commit 167c52aeb6c8e45cdcf6a4a032da709f6ef468cb Author: HiepLM Date: Thu May 28 10:29:58 2026 +0700 git commit -m "first commit" diff --git a/.gitignore b/.gitignore new file mode 100755 index 0000000..8c2b884 --- /dev/null +++ b/.gitignore @@ -0,0 +1,14 @@ +# ---> VisualStudioCode +.vscode/* +!.vscode/settings.json +!.vscode/tasks.json +!.vscode/launch.json +!.vscode/extensions.json +!.vscode/*.code-snippets + +# Local History for Visual Studio Code +.history/ + +# Built Visual Studio Code Extensions +*.vsix + diff --git a/.gitmodules b/.gitmodules new file mode 100755 index 0000000..958eb4b --- /dev/null +++ b/.gitmodules @@ -0,0 +1,3 @@ +# [submodule "costmap_2d"] +# path = navigations/costmap_2d +# url = http://git.pnkx/HiepLM/costmap_2d.git \ No newline at end of file diff --git a/.vscode/settings.json b/.vscode/settings.json new file mode 100755 index 0000000..f42346b --- /dev/null +++ b/.vscode/settings.json @@ -0,0 +1,9 @@ +{ + "ros.distro": "noetic", + "python.autoComplete.extraPaths": [ + "/opt/ros/noetic/lib/python3/dist-packages" + ], + "python.analysis.extraPaths": [ + "/opt/ros/noetic/lib/python3/dist-packages" + ] +} \ No newline at end of file diff --git a/CMakeLists.txt b/CMakeLists.txt new file mode 100644 index 0000000..744c4b2 --- /dev/null +++ b/CMakeLists.txt @@ -0,0 +1,69 @@ +# toplevel CMakeLists.txt for a catkin workspace +# catkin/cmake/toplevel.cmake + +cmake_minimum_required(VERSION 3.0.2) + +project(Project) + +set(CATKIN_TOPLEVEL TRUE) + +# search for catkin within the workspace +set(_cmd "catkin_find_pkg" "catkin" "${CMAKE_SOURCE_DIR}") +execute_process(COMMAND ${_cmd} + RESULT_VARIABLE _res + OUTPUT_VARIABLE _out + ERROR_VARIABLE _err + OUTPUT_STRIP_TRAILING_WHITESPACE + ERROR_STRIP_TRAILING_WHITESPACE +) +if(NOT _res EQUAL 0 AND NOT _res EQUAL 2) + # searching for catkin resulted in an error + string(REPLACE ";" " " _cmd_str "${_cmd}") + message(FATAL_ERROR "Search for 'catkin' in workspace failed (${_cmd_str}): ${_err}") +endif() + +# include catkin from workspace or via find_package() +if(_res EQUAL 0) + set(catkin_EXTRAS_DIR "${CMAKE_SOURCE_DIR}/${_out}/cmake") + # include all.cmake without add_subdirectory to let it operate in same scope + include(${catkin_EXTRAS_DIR}/all.cmake NO_POLICY_SCOPE) + add_subdirectory("${_out}") + +else() + # use either CMAKE_PREFIX_PATH explicitly passed to CMake as a command line argument + # or CMAKE_PREFIX_PATH from the environment + if(NOT DEFINED CMAKE_PREFIX_PATH) + if(NOT "$ENV{CMAKE_PREFIX_PATH}" STREQUAL "") + if(NOT WIN32) + string(REPLACE ":" ";" CMAKE_PREFIX_PATH $ENV{CMAKE_PREFIX_PATH}) + else() + set(CMAKE_PREFIX_PATH $ENV{CMAKE_PREFIX_PATH}) + endif() + endif() + endif() + + # list of catkin workspaces + set(catkin_search_path "") + foreach(path ${CMAKE_PREFIX_PATH}) + if(EXISTS "${path}/.catkin") + list(FIND catkin_search_path ${path} _index) + if(_index EQUAL -1) + list(APPEND catkin_search_path ${path}) + endif() + endif() + endforeach() + + # search for catkin in all workspaces + set(CATKIN_TOPLEVEL_FIND_PACKAGE TRUE) + find_package(catkin QUIET + NO_POLICY_SCOPE + PATHS ${catkin_search_path} + NO_DEFAULT_PATH NO_CMAKE_FIND_ROOT_PATH) + unset(CATKIN_TOPLEVEL_FIND_PACKAGE) + + if(NOT catkin_FOUND) + message(FATAL_ERROR "find_package(catkin) failed. catkin was neither found in the workspace nor in the CMAKE_PREFIX_PATH. One reason may be that no ROS setup.sh was sourced before.") + endif() +endif() + +catkin_workspace() diff --git a/README.md b/README.md new file mode 100755 index 0000000..6e3109c --- /dev/null +++ b/README.md @@ -0,0 +1,125 @@ +# Example dynamic_logistics_warehouse +----------------------------------------------- +* Terminal 1 : + +```bash + +roslaunch mir_gazebo mir_empty_world.launch \ +world_name:=$(rospack find dynamic_logistics_warehouse)/worlds/warehouse.world robot_x:=9.0 robot_y:=25.0 2> >(grep -v TF_REPEATED_DATA buffer_core) + +``` + +* Terminal 2 : +```bash +### mapping: +roslaunch mir_navigation hector_mapping.launch +``` + +```bash +### localization: +roslaunch mir_navigation amcl.launch initial_pose_x:=0.00 initial_pose_y:=0.00 \ initial_pose_a:=0.0 2> >(grep -v TF_REPEATED_DATA buffer_core) + +``` +* Terminal 3 : + +```bash + +rviz -d $(rospack find mir_navigation)/rviz/navigation.rviz 2> >(grep -v TF_REPEATED_DATA buffer_core) + +``` +* Terminal 4 : + +```bash +# navigation: +roslaunch mir_navigation start_planner.launch \ +map_file:=$(rospack find dynamic_logistics_warehouse)/maps/warehouse/warehouse.yaml \ +empty_file:=$(rospack find dynamic_logistics_warehouse)/maps/warehouse/map_empty.yaml \ +virtual_walls_map_file:=$(rospack find dynamic_logistics_warehouse)/maps/warehouse/virtual_walls.yaml \ +with_virtual_walls:=true \ +preferred_zones_map_file:=$(rospack find dynamic_logistics_warehouse)/maps/warehouse/preferred_zones.yaml \ +with_preferred_zones:=true \ +unpreferred_zones_map_file:=$(rospack find dynamic_logistics_warehouse)/maps/warehouse/unpreferred_zones.yaml \ +with_unpreferred_zones:=true \ +critical_zones_map_file:=$(rospack find dynamic_logistics_warehouse)/maps/warehouse/critical_zones.yaml \ +with_critical_zones:=true \ +direction_zones_map_file:=$(rospack find dynamic_logistics_warehouse)/maps/warehouse/direction_zones.yaml \ +with_direction_zones:=true 2> >(grep -v TF_REPEATED_DATA buffer_core) +``` +```bash +roslaunch mir_navigation move_base.xml with_virtual_walls:=false +``` + +# Default + +```bash +### gazebo: +roslaunch mir_gazebo mir_maze_world.launch 2> >(grep -v TF_REPEATED_DATA buffer_core) +rosservice call /gazebo/unpause_physics # or click the "start" button in the Gazebo GUI + +### localization: +roslaunch mir_navigation amcl.launch initial_pose_x:=10.0 initial_pose_y:=10.0 2> >(grep -v TF_REPEATED_DATA buffer_core) +# or alternatively: roslaunch mir_gazebo fake_localization.launch delta_x:=-10.0 delta_y:=-10.0 + +# navigation: +roslaunch mir_navigation start_planner.launch \ + map_file:=$(rospack find mir_gazebo)/maps/maze.yaml + +roslaunch mir_navigation start_planner.launch \ +map_file:=$(rospack find mir_gazebo)/maps/warehouse/maze.yaml \ +virtual_walls_map_file:=$(rospack find mir_gazebo)/maps/warehouse/virtual_walls.yaml \ +with_virtual_walls:=true \ +preferred_zones_map_file:=$(rospack find mir_gazebo)/maps/warehouse/preferred_zones.yaml \ +with_preferred_zones:=true \ +unpreferred_zones_map_file:=$(rospack find mir_gazebo)/maps/warehouse/unpreferred_zones.yaml \ +with_unpreferred_zones:=true \ +critical_zones_map_file:=$(rospack find mir_gazebo)/maps/warehouse/critical_zones.yaml \ +with_critical_zones:=true \ +direction_zones_map_file:=$(rospack find mir_gazebo)/maps/warehouse/direction_zones.yaml \ +with_direction_zones:=true 2> >(grep -v TF_REPEATED_DATA buffer_core) + +# rviz +rviz -d $(rospack find mir_navigation)/rviz/navigation.rviz 2> >(grep -v TF_REPEATED_DATA buffer_core) +``` + +# Multilpe mir +# start Gazebo + first MiR +roslaunch mir_gazebo mir_maze_world.launch tf_prefix:=mir + +# first MiR: start localization, navigation + rviz +roslaunch mir_navigation amcl.launch initial_pose_x:=10.0 initial_pose_y:=10.0 tf_prefix:=mir + +roslaunch mir_navigation start_planner.launch \ +map_file:=$(rospack find mir_gazebo)/maps/warehouse/maze.yaml \ +virtual_walls_map_file:=$(rospack find mir_gazebo)/maps/warehouse/virtual_walls.yaml \ +with_virtual_walls:=true \ +preferred_zones_map_file:=$(rospack find mir_gazebo)/maps/warehouse/preferred_zones.yaml \ +with_preferred_zones:=true \ +unpreferred_zones_map_file:=$(rospack find mir_gazebo)/maps/warehouse/unpreferred_zones.yaml \ +with_unpreferred_zones:=true \ +critical_zones_map_file:=$(rospack find mir_gazebo)/maps/warehouse/critical_zones.yaml \ +with_critical_zones:=true \ +direction_zones_map_file:=$(rospack find mir_gazebo)/maps/warehouse/direction_zones.yaml \ +with_direction_zones:=true prefix:=mir/ 2> >(grep -v TF_REPEATED_DATA buffer_core) + +ROS_NAMESPACE=mir rviz -d $(rospack find mir_navigation)/rviz/navigation.rviz 2> >(grep -v TF_REPEATED_DATA buffer_core) + +# spawn second MiR into Gazebo +roslaunch mir_gazebo mir_gazebo_common.launch robot_x:=-2 robot_y:=-2 tf_prefix:=mir2 model_name:=mir2 __ns:=mir2 + +# second MiR: start localization, navigation + rviz +roslaunch mir_navigation amcl.launch initial_pose_x:=8.0 initial_pose_y:=8.0 tf_prefix:=mir2 + +roslaunch mir_navigation start_planner.launch \ +map_file:=$(rospack find mir_gazebo)/maps/warehouse/maze.yaml \ +virtual_walls_map_file:=$(rospack find mir_gazebo)/maps/warehouse/virtual_walls.yaml \ +with_virtual_walls:=true \ +preferred_zones_map_file:=$(rospack find mir_gazebo)/maps/warehouse/preferred_zones.yaml \ +with_preferred_zones:=true \ +unpreferred_zones_map_file:=$(rospack find mir_gazebo)/maps/warehouse/unpreferred_zones.yaml \ +with_unpreferred_zones:=true \ +critical_zones_map_file:=$(rospack find mir_gazebo)/maps/warehouse/critical_zones.yaml \ +with_critical_zones:=true \ +direction_zones_map_file:=$(rospack find mir_gazebo)/maps/warehouse/direction_zones.yaml \ +with_direction_zones:=true prefix:=mir2/ 2> >(grep -v TF_REPEATED_DATA buffer_core) + +ROS_NAMESPACE=mir2 rviz -d $(rospack find mir_navigation)/rviz/navigation.rviz 2> >(grep -v TF_REPEATED_DATA buffer_core) \ No newline at end of file diff --git a/Setup.txt b/Setup.txt new file mode 100755 index 0000000..1623fff --- /dev/null +++ b/Setup.txt @@ -0,0 +1,17 @@ +sudo apt install libsuitesparse-dev +sudo apt install libspdlog-dev + +git clone https://github.com/gabime/spdlog.git -b master +mkdir build +cd build +cmake .. -DSPDLOG_BUILD_SHARED=OFF -DSPDLOG_BUILD_STATIC=ON -DCMAKE_CXX_FLAGS=-fPIC +make +sudo rm /usr/local/lib/libspdlog.a +sudo cp /path/to/spdlog/source/build/libspdlog.a /usr/local/lib/ + +git clone https://github.com/RainerKuemmerle/g2o.git -b master +mkdir build +cd build +cmake ../ +make +sudo make install \ No newline at end of file diff --git a/mir_robot/.dockerfilelintrc b/mir_robot/.dockerfilelintrc new file mode 100755 index 0000000..7957788 --- /dev/null +++ b/mir_robot/.dockerfilelintrc @@ -0,0 +1,2 @@ +rules: + apt-get-update_require_install: off diff --git a/mir_robot/.flake8 b/mir_robot/.flake8 new file mode 100755 index 0000000..cdffbdc --- /dev/null +++ b/mir_robot/.flake8 @@ -0,0 +1,10 @@ +[flake8] +# The line length here has to match the black config in pyproject.toml +max-line-length = 120 +exclude = + .git, + __pycache__ +extend-ignore = + # See https://github.com/PyCQA/pycodestyle/issues/373 + E203, + E741, diff --git a/mir_robot/.github/workflows/github-actions.yml b/mir_robot/.github/workflows/github-actions.yml new file mode 100755 index 0000000..e72a113 --- /dev/null +++ b/mir_robot/.github/workflows/github-actions.yml @@ -0,0 +1,42 @@ +name: Build and run ROS tests +on: [push, pull_request] +jobs: + build: + strategy: + matrix: + rosdistro: [noetic] + runs-on: ubuntu-latest + container: + image: ros:${{ matrix.rosdistro }}-ros-core + steps: + - name: Install apt dependencies + run: | + sudo apt-get update + sudo apt-get install -y build-essential clang-format-10 file git python3-catkin-lint python3-catkin-tools python3-pip python3-rosdep + - name: Install pip dependencies + run: pip install pre-commit + - name: Checkout repository + uses: actions/checkout@v3 + with: + path: src/mir_robot + - name: Use rosdep to install remaining dependencies + run: | + sudo rosdep init + rosdep update + rosdep install --from-paths src -i -y --rosdistro ${{ matrix.rosdistro }} + - name: Build + run: | + . /opt/ros/${{ matrix.rosdistro }}/setup.sh + catkin init + catkin config -j 1 -p 1 + catkin build --limit-status-rate 0.1 --no-notify + catkin build --limit-status-rate 0.1 --no-notify --make-args tests + - name: Run tests + run: | + . devel/setup.sh + catkin run_tests + catkin_test_results + - name: Run pre-commit hooks + run: | + cd src/mir_robot + pre-commit run -a diff --git a/mir_robot/.gitignore b/mir_robot/.gitignore new file mode 100755 index 0000000..0d20b64 --- /dev/null +++ b/mir_robot/.gitignore @@ -0,0 +1 @@ +*.pyc diff --git a/mir_robot/.mdl_style.rb b/mir_robot/.mdl_style.rb new file mode 100755 index 0000000..1d4dc49 --- /dev/null +++ b/mir_robot/.mdl_style.rb @@ -0,0 +1,25 @@ +# Style file for markdownlint + +all + +exclude_rule 'fenced-code-language' # Fenced code blocks should have a language specified +exclude_rule 'first-line-h1' # First line in file should be a top level header + +exclude_rule 'ul-style' + +exclude_rule 'no-multiple-blanks' + +exclude_rule 'header-style' + +exclude_rule 'no-bare-urls' # we need to use a bare URL in the README for the video to properly show on GitHub + +# Line lenght +rule 'MD013', :line_length => 120, :code_blocks => false, :tables => false + +# Unordered list indentation +rule 'MD007', :indent => 2 + +# Ordered list item prefix +rule 'MD029', :style => 'ordered' + +rule 'no-duplicate-header', :allow_different_nesting => true diff --git a/mir_robot/.mdlrc b/mir_robot/.mdlrc new file mode 100755 index 0000000..71eadf9 --- /dev/null +++ b/mir_robot/.mdlrc @@ -0,0 +1,2 @@ +git_recurse true +style ".mdl_style.rb" diff --git a/mir_robot/.pre-commit-config.yaml b/mir_robot/.pre-commit-config.yaml new file mode 100755 index 0000000..cae31a3 --- /dev/null +++ b/mir_robot/.pre-commit-config.yaml @@ -0,0 +1,116 @@ +# To use: +# +# pre-commit run -a +# +# Or: +# +# pre-commit install # (runs every time you commit in git) +# +# To update this file: +# +# pre-commit autoupdate +# +# See https://github.com/pre-commit/pre-commit + +repos: + # Standard hooks + - repo: https://github.com/pre-commit/pre-commit-hooks + rev: v4.1.0 + hooks: + - id: check-added-large-files + - id: check-case-conflict + - id: check-executables-have-shebangs + - id: check-docstring-first + - id: check-merge-conflict + - id: check-shebang-scripts-are-executable + - id: check-symlinks + - id: check-vcs-permalinks + - id: check-xml + - id: check-yaml + exclude: mobipick_description/config/joint_limits.yaml + - id: debug-statements + - id: end-of-file-fixer + exclude: &excludes | + (?x)^( + .*\.blend| + .*\.dae| + .*\.mtl| + .*\.obj| + .*\.pgm| + .*\.step| + .*\.stl + )$ + - id: fix-byte-order-marker + - id: mixed-line-ending + exclude: *excludes + - id: trailing-whitespace + exclude: *excludes + + - repo: https://github.com/psf/black + rev: 22.3.0 + hooks: + - id: black + + - repo: https://github.com/PyCQA/flake8.git + rev: 5.0.4 + hooks: + - id: flake8 + + - repo: https://github.com/detailyang/pre-commit-shell.git + rev: v1.0.6 + hooks: + - id: shell-lint + args: [--external-sources] + + - repo: https://github.com/markdownlint/markdownlint + rev: v0.11.0 + hooks: + - id: markdownlint + + - repo: https://github.com/pryorda/dockerfilelint-precommit-hooks + rev: v0.1.0 + hooks: + - id: dockerfilelint + + - repo: https://github.com/Lucas-C/pre-commit-hooks + rev: v1.3.1 + hooks: + - id: insert-license + files: \.py$ + exclude: | + (?x)^( + .*setup\.py| + .*__init__\.py| + .*test_copyright\.py| + .*test_pep257\.py| + mir_driver/nodes/tf_remove_child_frames\.py| + mir_navigation/mprim/genmprim_unicycle_highcost_5cm\.py + )$ + args: + - --license-filepath + - LICENSE + + - repo: https://github.com/pycqa/pydocstyle + rev: 6.1.1 + hooks: + - id: pydocstyle + args: + - --ignore=D100,D101,D102,D103,D104,D105,D106,D107,D203,D212,D404 # same as https://github.com/ament/ament_lint/blob/bbdaa17224f3b8dfece53662b65d7d18b7404b6a/ament_pep257/ament_pep257/main.py#L43-L55 + + - repo: local + hooks: + - id: clang-format + name: clang-format + description: Format files with ClangFormat. + entry: clang-format-10 + language: system + files: \.(c|cc|cxx|cpp|frag|glsl|h|hpp|hxx|ih|ispc|ipp|java|js|m|proto|vert)$ + args: [ "-fallback-style=none", "-i" ] + - id: catkin_lint + name: catkin_lint + description: Check package.xml and cmake files + entry: catkin_lint . + language: system + always_run: true + pass_filenames: false + args: [ "--strict", "--skip-pkg", "mobipick_moveit_config" ] # have to skip this package because of the missing warehouse_ros_mongo dependency diff --git a/mir_robot/Dockerfile-noetic b/mir_robot/Dockerfile-noetic new file mode 100755 index 0000000..2dccaff --- /dev/null +++ b/mir_robot/Dockerfile-noetic @@ -0,0 +1,34 @@ +FROM ros:noetic-ros-core + +RUN apt-get update \ + && apt-get install -y --no-install-recommends build-essential python3-rosdep python3-catkin-lint python3-catkin-tools \ + && rm -rf /var/lib/apt/lists/* /tmp/* /var/tmp/* + +# Install pre-commit hooks to /root/.cache/pre-commit/ +RUN apt-get update -qq \ + && apt-get install -y -qq --no-install-recommends git python3-pip ruby shellcheck clang-format-10 python3-catkin-lint \ + && rm -rf /var/lib/apt/lists/* +RUN pip3 install pre-commit +RUN mkdir -p /tmp/pre-commit +COPY .pre-commit-config.yaml /tmp/pre-commit/ +RUN cd /tmp/pre-commit \ + && git init \ + && pre-commit install-hooks \ + && rm -rf /tmp/pre-commit + +# Create ROS workspace +COPY . /ws/src/mir_robot +WORKDIR /ws + +# Use rosdep to install all dependencies (including ROS itself) +RUN rosdep init \ + && rosdep update \ + && apt-get update \ + && DEBIAN_FRONTEND=noninteractive rosdep install --from-paths src -i -y --rosdistro noetic \ + && rm -rf /var/lib/apt/lists/* /tmp/* /var/tmp/* + +RUN /bin/bash -c "source /opt/ros/noetic/setup.bash && \ + catkin init && \ + catkin config --install -j 1 -p 1 && \ + catkin build --limit-status-rate 0.1 --no-notify && \ + catkin build --limit-status-rate 0.1 --no-notify --make-args tests" diff --git a/mir_robot/LICENSE b/mir_robot/LICENSE new file mode 100755 index 0000000..74dc9f4 --- /dev/null +++ b/mir_robot/LICENSE @@ -0,0 +1,27 @@ +Copyright (c) 2018-2022, Martin Günther (DFKI GmbH) and contributors + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + + * Redistributions of source code must retain the above copyright + notice, this list of conditions and the following disclaimer. + + * Redistributions in binary form must reproduce the above copyright + notice, this list of conditions and the following disclaimer in the + documentation and/or other materials provided with the distribution. + + * Neither the name of the the copyright holder nor the names of its + contributors may be used to endorse or promote products derived from + this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE +LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +POSSIBILITY OF SUCH DAMAGE. diff --git a/mir_robot/README.md b/mir_robot/README.md new file mode 100755 index 0000000..f278b45 --- /dev/null +++ b/mir_robot/README.md @@ -0,0 +1,388 @@ +mir_robot +========= + +This repo contains a ROS driver and ROS configuration files (URDF description, +Gazebo launch files, move_base config, bringup launch files, message and action +descriptions) for the [MiR robots](http://www.mobile-industrial-robots.com/). +This is a community project created by us ([DFKI](https://www.dfki.de/), the +German Research Center for Artificial Intelligence) to use the MiR Robots with +ROS. We are not affiliated with Mobile Industrial Robots. If you find a bug or +missing feature in this software, please report it on the +[issue tracker](https://github.com/DFKI-NI/mir_robot/issues). + +Supported MiR robots and software versions +------------------------------------------ + +This repo has been confirmed to work with the following robots: + +* MiR 100 +* MiR 200 +* MiR 500 + +It probably also works with the MiR250 and MiR1000. If you can test it on one +of those, please let us know if it works. + +This repo has been tested with the following MiR software versions: + +* 2.8.3.1 +* 2.13.4.1 + +You can try if it works with other versions, but these are the ones that are +known to work. + + +Package overview +---------------- + +* `mir_actions`: Action definitions for the MiR robot +* `mir_description`: URDF description of the MiR robot +* `mir_dwb_critics`: Plugins for the dwb_local_planner used in Gazebo +* `mir_driver`: A reverse ROS bridge for the MiR robot +* `mir_gazebo`: Simulation specific launch and configuration files for the MiR robot +* `mir_msgs`: Message definitions for the MiR robot +* `mir_navigation`: move_base launch and configuration files + + +Installation +------------ + +You can chose between binary and source install below. If you don't want to +modify the source, the binary install is preferred (if `mir_robot` binary +packages are available for your ROS distro). The instructions below use the ROS +distro `noetic` as an example; if you use a different distro (e.g. `melodic`), +replace all occurrences of the string `noetic` by your distro name in the +instructions. + +### Preliminaries + +If you haven't already installed ROS on your PC, you need to add the ROS apt +repository. This step is necessary for either binary or source install. + +``` +sudo sh -c 'echo "deb http://packages.ros.org/ros/ubuntu $(lsb_release -sc) main" > /etc/apt/sources.list.d/ros-latest.list' +wget http://packages.ros.org/ros.key -O - | sudo apt-key add - +sudo apt-get update -qq +``` + +### Binary install + +For a binary install, it suffices to run this command: + +```bash +sudo apt install ros-noetic-mir-robot +``` + +See the tables at the end of this README for a list of ROS distros for which +binary packages are available. + +### Source install + +For a source install, run the commands below instead of the command from the +"binary install" section. + +```bash +# create a catkin workspace +mkdir -p ~/catkin_ws/src +cd ~/catkin_ws/src/ + +# clone mir_robot into the catkin workspace +git clone -b noetic https://github.com/DFKI-NI/mir_robot.git + +# use rosdep to install all dependencies (including ROS itself) +sudo apt-get update -qq +sudo apt-get install -qq -y python-rosdep +sudo rosdep init +rosdep update +rosdep install --from-paths ./ -i -y --rosdistro noetic + +# build all packages in the catkin workspace +source /opt/ros/noetic/setup.bash +catkin_init_workspace +cd ~/catkin_ws +catkin_make -DCMAKE_BUILD_TYPE=RelWithDebugInfo +``` + +In case you encounter problems, please compare the commands above to the build +step in [`.github/workflows/github-actions.yml`](.github/workflows/github-actions.yml); that should always have the most +recent list of commands. + +You should add the following line to the end of your `~/.bashrc`, and then +close and reopen all terminals: + +```bash +source ~/catkin_ws/devel/setup.bash +``` + +Gazebo demo (existing map) +-------------------------- + +https://user-images.githubusercontent.com/320188/145610491-2afeb46c-3729-4106-ab9c-6681b5dd9d2e.mp4 + +```bash +### gazebo: +roslaunch mir_gazebo mir_maze_world.launch +rosservice call /gazebo/unpause_physics # or click the "start" button in the Gazebo GUI + +### localization: +roslaunch mir_navigation amcl.launch initial_pose_x:=10.0 initial_pose_y:=10.0 +# or alternatively: roslaunch mir_gazebo fake_localization.launch delta_x:=-10.0 delta_y:=-10.0 + +# navigation: +roslaunch mir_navigation start_planner.launch \ + map_file:=$(rospack find mir_gazebo)/maps/maze.yaml \ + virtual_walls_map_file:=$(rospack find mir_gazebo)/maps/maze_virtual_walls.yaml +rviz -d $(rospack find mir_navigation)/rviz/navigation.rviz +``` + +Now, you can use the "2D Nav Goal" tool in RViz to set a navigation goal for move_base. + + +Gazebo demo (mapping) +--------------------- + +```bash +### gazebo: +roslaunch mir_gazebo mir_maze_world.launch +rosservice call /gazebo/unpause_physics # or click the "start" button in the Gazebo GUI + +### mapping: +roslaunch mir_navigation hector_mapping.launch + +# navigation: +roslaunch mir_navigation move_base.xml with_virtual_walls:=false +rviz -d $(rospack find mir_navigation)/rviz/navigation.rviz +``` + +Gazebo demo (MiR 250 in warehouse Gazebo world) +----------------------------------------------- + +https://user-images.githubusercontent.com/320188/171613044-639f3ab2-fe84-4839-acfc-d0642f8869b3.mp4 + +This repo contains URDF descriptions for the MiR 100 (default) and the MiR 250. +You can switch to the MiR 250 by adding **`mir_type:=mir_250`** to the gazebo +roslaunch command. You can also select another Gazebo world using the +**`world_name`** argument. For example, the video above was generated using the +following commands: + +```bash +cd +git clone -b ros1 https://github.com/aws-robotics/aws-robomaker-small-warehouse-world.git +catkin build + +roslaunch mir_gazebo mir_empty_world.launch \ + world_name:=$(rospack find aws_robomaker_small_warehouse_world)/worlds/no_roof_small_warehouse.world \ + mir_type:=mir_250 +``` + +... and then running the remaining commands from the "mapping" section above. + + +Gazebo demo (multiple robots) +----------------------------- + +If you want to spawn multiple robots into Gazebo, you unfortunately have to +hard-code the name of the second robot into the `mir_empty_world.launch` file, +like this: + +```diff +diff --git i/mir_gazebo/launch/mir_empty_world.launch w/mir_gazebo/launch/mir_empty_world.launch +index 27b9159..7773fae 100644 +--- i/mir_gazebo/launch/mir_empty_world.launch ++++ w/mir_gazebo/launch/mir_empty_world.launch +@@ -17,6 +17,10 @@ + + + ++ ++ ++ ++ + + + +``` + +Then you can run the simulation like this: + +```bash +# start Gazebo + first MiR +roslaunch mir_gazebo mir_maze_world.launch tf_prefix:=mir + +# first MiR: start localization, navigation + rviz +roslaunch mir_navigation amcl.launch initial_pose_x:=10.0 initial_pose_y:=10.0 tf_prefix:=mir# +roslaunch mir_navigation start_planner.launch \ + map_file:=$(rospack find mir_gazebo)/maps/maze.yaml \ + virtual_walls_map_file:=$(rospack find mir_gazebo)/maps/maze_virtual_walls.yaml prefix:=mir/ +ROS_NAMESPACE=mir rviz -d $(rospack find mir_navigation)/rviz/navigation.rviz + +# spawn second MiR into Gazebo +roslaunch mir_gazebo mir_gazebo_common.launch robot_x:=-2 robot_y:=-2 tf_prefix:=mir2 model_name:=mir2 __ns:=mir2 + +# second MiR: start localization, navigation + rviz +roslaunch mir_navigation amcl.launch initial_pose_x:=8.0 initial_pose_y:=8.0 tf_prefix:=mir2 +roslaunch mir_navigation start_planner.launch \ + map_file:=$(rospack find mir_gazebo)/maps/maze.yaml \ + virtual_walls_map_file:=$(rospack find mir_gazebo)/maps/maze_virtual_walls.yaml prefix:=mir2/ +ROS_NAMESPACE=mir2 rviz -d $(rospack find mir_navigation)/rviz/navigation.rviz +``` + + +Running the driver on the real robot +------------------------------------ + +### Start up the robot + +* switch on MiR base + + +### Connect to the MiR web interface + +* connect to MiR_R??? wifi (password "mirex4you"), for example from your Android phone/tablet +* disable other network connections (mobile data / LAN / etc.) +* open mir.com (192.168.12.20) in Chrome (!) +* log in (admin/mir4you) + + +### Synchronize system time + +The internal robot PC's is not synchronized (for example via NTP), so it tends +to get out of sync quickly (about 1 second per day!). This causes TF transforms +timing out etc. and can be seen using `tf_monitor` (the "Max Delay" is about +3.3 seconds, but should be less than 0.1 seconds): + +``` +$ rosrun tf tf_monitor +Frames: +Frame: /back_laser_link published by unknown_publisher Average Delay: 3.22686 Max Delay: 3.34766 +Frame: /base_footprint published by unknown_publisher Average Delay: 3.34273 Max Delay: 3.38062 +Frame: /base_link published by unknown_publisher Average Delay: 3.22751 Max Delay: 3.34844 +Frame: /front_laser_link published by unknown_publisher Average Delay: 3.22661 Max Delay: 3.34159 +Frame: /imu_link published by unknown_publisher Average Delay: 3.22739 Max Delay: 3.34738 +Frame: /odom published by unknown_publisher Average Delay: 3.16493 Max Delay: 3.28667 +[...] + +All Broadcasters: +Node: unknown_publisher 418.344 Hz, Average Delay: 0.827575 Max Delay: 3.35237 +Node: unknown_publisher(static) 465.362 Hz, Average Delay: 0 Max Delay: 0 +``` + +To fix this: + +* go to "Service" -> "Configuration" -> "System settings" -> "Time settings" -> "Set device time on robot" + +Afterwards, the ROS software on the robot will restart, so you'll have to start `move_base` again (see below). + +If you have an external PC on the MiR platform, you can use `chrony` to automatically synchronize system time (see below). + + +### Start `move_base` on the robot + +* go to "Service" -> "Configuration" -> "Launch menu", start "Planner"; this starts `move_base` and `amcl` on the robot + + +### Teleoperate the robot (optional) + +* go to "Manual", press yellow button (LEDs change from yellow to blue); now the robot can be teleoperated + + +### Relocalize robot (optional) + +If the robot's localization is lost: + +* go to "Service" -> "Command view" -> "Set start position" and click + drag to current position of robot in the map +* click "Adjust" + + +### Start the ROS driver + +```bash +roslaunch mir_driver mir.launch +``` + +Advanced +-------- + +### Installing chrony to synchronize system time automatically + +If you have an external PC integrated into your robot that is on the same wired +network as the MiR PC, you can use `chrony` to automatically synchronize the +MiR's system time. Unfortunately, this method is not easy to install. + +Let's call the external PC `external-pc`. That PC's clock is our reference +clock. It is synced to an NTP clock whenever the `external-pc` has access to +the internet. To implement this synchronization solution, install `chrony` on +both the `external-pc` and the internal PC of the MiR, and set up the +`external-pc` as the chrony server and the internal MiR PC as the chrony +client. This way, the clocks on these systems always stay in sync without any +manual interaction. + +To install things on the internal MiR PC: + +* connect a monitor and keyboard to the ports that are exposed on one corner of the MiR +* boot into a live USB linux system +* `chroot` into the MiR PC +* download `chrony_2.1.1-1ubuntu0.1_amd64.deb`, + `libtomcrypt0_1.17-7ubuntu0.1_amd64.deb`, `libtommath0_0.42.0-1.2_amd64.deb` + and `timelimit_1.8-1_amd64.deb` from a PC that has internet and install them + in the `chroot` environment onto the MiR PC using `dpkg -i` +* set up `/etc/chrony/chrony.conf` + + +Troubleshooting +--------------- + +### Got a result when we were already in the DONE state + +Sometimes the move_base action will print the warning "Got a result when we +were already in the DONE state". This is caused by a race condition between the +`/move_base/result` and `/move_base/status` topics. When a status message with +status `SUCCEEDED` arrives before the corresponding result message, this +warning will be printed. It can be safely ignored. + + +### Gazebo prints errors: "No p gain specified for pid." + +These errors are expected and can be ignored. + +Unfortunately, we cannot set the PID gains (to silence the error) due to the +following behavior of Gazebo: + +1. When using the `PositionJointInterface`, you *must* set the PID values for the + joints using that interface, otherwise you will run into + [this bug](https://github.com/ros-simulation/gazebo_ros_pkgs/issues/612). +2. When using the `VelocityJointInterface`, if you omit the PID values, Gazebo + just perfectly follows the commanded velocities. If you specify PID values, + Gazebo will use a PID controller to approximate following the commanded + velocities, so you have to tune the PID controllers. + +Since we just want Gazebo to follow our commanded velocities, we cannot set the +PID values for joints using the VelocityJointInterface, so the errors get +printed (but can be ignored). + + +GitHub Actions - Continuous Integration +--------------------------------------- + +| Noetic | +|--------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------| +| [![Build Status](https://github.com/DFKI-NI/mir_robot/actions/workflows/github-actions.yml/badge.svg)](https://github.com/DFKI-NI/mir_robot/actions/workflows/github-actions.yml/) | + + +ROS Buildfarm +------------- + +| | Melodic source deb | Melodic binary deb | Noetic source deb | Noetic binary deb | +|--------------------------------------------------------|-----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------|---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------|---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------|-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------| +| [mir_actions](http://wiki.ros.org/mir_actions) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Msrc_uB__mir_actions__ubuntu_bionic__source)](http://build.ros.org/job/Msrc_uB__mir_actions__ubuntu_bionic__source/) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Mbin_uB64__mir_actions__ubuntu_bionic_amd64__binary)](http://build.ros.org/job/Mbin_uB64__mir_actions__ubuntu_bionic_amd64__binary/) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Nsrc_uF__mir_actions__ubuntu_focal__source)](http://build.ros.org/job/Nsrc_uF__mir_actions__ubuntu_focal__source/) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Nbin_uF64__mir_actions__ubuntu_focal_amd64__binary)](http://build.ros.org/job/Nbin_uF64__mir_actions__ubuntu_focal_amd64__binary/) | +| [mir_description](http://wiki.ros.org/mir_description) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Msrc_uB__mir_description__ubuntu_bionic__source)](http://build.ros.org/job/Msrc_uB__mir_description__ubuntu_bionic__source/) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Mbin_uB64__mir_description__ubuntu_bionic_amd64__binary)](http://build.ros.org/job/Mbin_uB64__mir_description__ubuntu_bionic_amd64__binary/) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Nsrc_uF__mir_description__ubuntu_focal__source)](http://build.ros.org/job/Nsrc_uF__mir_description__ubuntu_focal__source/) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Nbin_uF64__mir_description__ubuntu_focal_amd64__binary)](http://build.ros.org/job/Nbin_uF64__mir_description__ubuntu_focal_amd64__binary/) | +| [mir_driver](http://wiki.ros.org/mir_driver) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Msrc_uB__mir_driver__ubuntu_bionic__source)](http://build.ros.org/job/Msrc_uB__mir_driver__ubuntu_bionic__source/) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Mbin_uB64__mir_driver__ubuntu_bionic_amd64__binary)](http://build.ros.org/job/Mbin_uB64__mir_driver__ubuntu_bionic_amd64__binary/) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Nsrc_uF__mir_driver__ubuntu_focal__source)](http://build.ros.org/job/Nsrc_uF__mir_driver__ubuntu_focal__source/) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Nbin_uF64__mir_driver__ubuntu_focal_amd64__binary)](http://build.ros.org/job/Nbin_uF64__mir_driver__ubuntu_focal_amd64__binary/) | +| [mir_dwb_critics](http://wiki.ros.org/mir_dwb_critics) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Msrc_uB__mir_dwb_critics__ubuntu_bionic__source)](http://build.ros.org/job/Msrc_uB__mir_dwb_critics__ubuntu_bionic__source/) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Mbin_uB64__mir_dwb_critics__ubuntu_bionic_amd64__binary)](http://build.ros.org/job/Mbin_uB64__mir_dwb_critics__ubuntu_bionic_amd64__binary/) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Nsrc_uF__mir_dwb_critics__ubuntu_focal__source)](http://build.ros.org/job/Nsrc_uF__mir_dwb_critics__ubuntu_focal__source/) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Nbin_uF64__mir_dwb_critics__ubuntu_focal_amd64__binary)](http://build.ros.org/job/Nbin_uF64__mir_dwb_critics__ubuntu_focal_amd64__binary/) | +| [mir_gazebo](http://wiki.ros.org/mir_gazebo) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Msrc_uB__mir_gazebo__ubuntu_bionic__source)](http://build.ros.org/job/Msrc_uB__mir_gazebo__ubuntu_bionic__source/) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Mbin_uB64__mir_gazebo__ubuntu_bionic_amd64__binary)](http://build.ros.org/job/Mbin_uB64__mir_gazebo__ubuntu_bionic_amd64__binary/) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Nsrc_uF__mir_gazebo__ubuntu_focal__source)](http://build.ros.org/job/Nsrc_uF__mir_gazebo__ubuntu_focal__source/) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Nbin_uF64__mir_gazebo__ubuntu_focal_amd64__binary)](http://build.ros.org/job/Nbin_uF64__mir_gazebo__ubuntu_focal_amd64__binary/) | +| [mir_msgs](http://wiki.ros.org/mir_msgs) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Msrc_uB__mir_msgs__ubuntu_bionic__source)](http://build.ros.org/job/Msrc_uB__mir_msgs__ubuntu_bionic__source/) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Mbin_uB64__mir_msgs__ubuntu_bionic_amd64__binary)](http://build.ros.org/job/Mbin_uB64__mir_msgs__ubuntu_bionic_amd64__binary/) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Nsrc_uF__mir_msgs__ubuntu_focal__source)](http://build.ros.org/job/Nsrc_uF__mir_msgs__ubuntu_focal__source/) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Nbin_uF64__mir_msgs__ubuntu_focal_amd64__binary)](http://build.ros.org/job/Nbin_uF64__mir_msgs__ubuntu_focal_amd64__binary/) | +| [mir_navigation](http://wiki.ros.org/mir_navigation) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Msrc_uB__mir_navigation__ubuntu_bionic__source)](http://build.ros.org/job/Msrc_uB__mir_navigation__ubuntu_bionic__source/) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Mbin_uB64__mir_navigation__ubuntu_bionic_amd64__binary)](http://build.ros.org/job/Mbin_uB64__mir_navigation__ubuntu_bionic_amd64__binary/) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Nsrc_uF__mir_navigation__ubuntu_focal__source)](http://build.ros.org/job/Nsrc_uF__mir_navigation__ubuntu_focal__source/) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Nbin_uF64__mir_navigation__ubuntu_focal_amd64__binary)](http://build.ros.org/job/Nbin_uF64__mir_navigation__ubuntu_focal_amd64__binary/) | +| [mir_robot](http://wiki.ros.org/mir_robot) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Msrc_uB__mir_robot__ubuntu_bionic__source)](http://build.ros.org/job/Msrc_uB__mir_robot__ubuntu_bionic__source/) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Mbin_uB64__mir_robot__ubuntu_bionic_amd64__binary)](http://build.ros.org/job/Mbin_uB64__mir_robot__ubuntu_bionic_amd64__binary/) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Nsrc_uF__mir_robot__ubuntu_focal__source)](http://build.ros.org/job/Nsrc_uF__mir_robot__ubuntu_focal__source/) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Nbin_uF64__mir_robot__ubuntu_focal_amd64__binary)](http://build.ros.org/job/Nbin_uF64__mir_robot__ubuntu_focal_amd64__binary/) | +| [sdc21x0](http://wiki.ros.org/sdc21x0) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Msrc_uB__sdc21x0__ubuntu_bionic__source)](http://build.ros.org/job/Msrc_uB__sdc21x0__ubuntu_bionic__source/) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Mbin_uB64__sdc21x0__ubuntu_bionic_amd64__binary)](http://build.ros.org/job/Mbin_uB64__sdc21x0__ubuntu_bionic_amd64__binary/) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Nsrc_uF__sdc21x0__ubuntu_focal__source)](http://build.ros.org/job/Nsrc_uF__sdc21x0__ubuntu_focal__source/) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Nbin_uF64__sdc21x0__ubuntu_focal_amd64__binary)](http://build.ros.org/job/Nbin_uF64__sdc21x0__ubuntu_focal_amd64__binary/) | + +| | Melodic devel | Melodic doc | Noetic devel | Noetic doc | +|--------------------------------------------|------------------------------------------------------------------------------------------------------------------------------------------------------------------|------------------------------------------------------------------------------------------------------------------------------------------------------------------|----------------------------------------------------------------------------------------------------------------------------------------------------------------|----------------------------------------------------------------------------------------------------------------------------------------------------------------| +| [mir_robot](http://wiki.ros.org/mir_robot) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Mdev__mir_robot__ubuntu_bionic_amd64)](http://build.ros.org/job/Mdev__mir_robot__ubuntu_bionic_amd64) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Mdoc__mir_robot__ubuntu_bionic_amd64)](http://build.ros.org/job/Mdoc__mir_robot__ubuntu_bionic_amd64) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Ndev__mir_robot__ubuntu_focal_amd64)](http://build.ros.org/job/Ndev__mir_robot__ubuntu_focal_amd64) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Ndoc__mir_robot__ubuntu_focal_amd64)](http://build.ros.org/job/Ndoc__mir_robot__ubuntu_focal_amd64) | diff --git a/mir_robot/diff_drive_controller/CHANGELOG.rst b/mir_robot/diff_drive_controller/CHANGELOG.rst new file mode 100755 index 0000000..35f3563 --- /dev/null +++ b/mir_robot/diff_drive_controller/CHANGELOG.rst @@ -0,0 +1,237 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package diff_drive_controller +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +0.21.2 (2023-09-03) +------------------- + +0.21.1 (2023-01-31) +------------------- +* Don't hardcode plugin library path +* Contributors: Jochen Sprickerhof + +0.21.0 (2022-10-21) +------------------- +* std::bind and placeholders instead of boost +* use boost::placeholders::_1/_2 in remaining instances, include boost/bind/bind.hpp instead of boost/bind.hpp, eliminated unnecessary bind.hpp include +* Contributors: Lucas Walter + +0.20.0 (2022-05-06) +------------------- +* Drop old C++ standard +* Use new boost bind placeholders +* Add to every .launch and .test file +* Contributors: Jochen Sprickerhof, Lucas Walter + +0.19.0 (2021-06-13) +------------------- +* fix NaN bug +* fix test to expose NaN bug +* Wait long enough for accumulator to be cleared +* Add test for `#532 `_ + Close `#540 `_ +* Contributors: Caio Amaral, Matt Reynolds, Melvin Wang + +0.18.1 (2020-12-03) +------------------- +* Fix null pointer checks in diff_drive_controller +* Use version-agnostic FindBoost for headers +* Contributors: David V. Lu, Matt Reynolds + +0.18.0 (2020-10-11) +------------------- +* Fix dependency on Boost +* Apply consistent format to CMakeLists.txt +* Update package.xml to format 3 +* Clean dependencies of diff_drive_controller package +* Apply waitForController method to all diff_drive_controller tests +* Move odom_pub setup to the end to allow consistent isControllerAlive check +* Contributors: Mateus Amarante + +0.17.0 (2020-05-12) +------------------- + +0.16.1 (2020-04-27) +------------------- + +0.16.0 (2020-04-16) +------------------- +* Fix warning dynamic_reconfigure +* Bump CMake version to prevent CMP0048 +* Add missing header guards +* Replace header guard with #pragma once +* Prefix every xacro tag with 'xacro:' +* Modernize xacro + - Remove '--inorder' + - Use 'xacro' over 'xacro.py' +* switch implementation of read and write methods of Diffbot class +* Refactor nan test + EXPECT_NE(x, bool) -> EXPECT_TRUE/FALSE(x) + EXPECT_EQ(x, double) -> EXPECT_DOUBLE_EQ(x, double) + + clang default reformat +* Check for nan cmd_vel +* Contributors: Anas Abou Allaban, Bence Magyar, Franz, Matt Reynolds, Raffaello Bonghi + +0.15.1 (2020-03-09) +------------------- +* Use nullptr +* add missing pluginlib deps. +* Update null link pointer error message +* Revert cmake include catkin_INCLUDE_DIRS as system +* Use C++11 `std::this_thread::sleep_for`. +* Contributors: Bence Magyar, Enrique Fernandez Perdomo, Matt Reynolds, Sean Yen + +0.15.0 (2019-03-26) +------------------- +* Default all controller builds to C++14 +* boost::chrono -> std::chrono +* boost::assign -> C++ initializer list +* boost::shared_ptr -> std::shared_ptr +* Using left/right multiplies for desired vel +* diff-drive publish joint trajectory controller state +* fix install destination for libraries (`#403 `_) +* Contributors: Bence Magyar, Gennaro Raiola, James Xu, Jeremie Deray, Jordan Palacios + +0.14.3 (2019-02-09) +------------------- +* use operators instead of aliases +* Fix typo descripion -> description +* Contributors: Daniel Ingram, James Xu + +0.14.2 (2018-10-23) +------------------- + +0.14.1 (2018-06-26) +------------------- +* Added 'multiplier' in DynamicParams ostream and changed boolean printing to 'enabled/disabled' +* isPublishngCmdVelOut to check getNumPublisheres until timeout +* Contributors: Kei Okada, Martin Ganeff + +0.14.0 (2018-04-27) +------------------- +* add dynamic_reconf to diff_drive_controller +* migrate to new pluginlib headers +* per wheel radius multiplier +* fix xacro macro warning +* [DiffDrive] Fix time-sensitive tests of diff_drive_controller +* separate include_directories as SYSTEM to avoid unrelated compilation warnings +* Contributors: Jeremie Deray, Mathias Lüdtke + +0.13.2 (2017-12-23) +------------------- + +0.13.1 (2017-11-06) +------------------- + +0.13.0 (2017-08-10) +------------------- +* Add test for allow_multiple_cmd_vel_publishers param +* add check for multiple publishers on cmd_vel +* Added tests for the odom_frame_id parameter. +* Parameterized diff_drive_controller's odom_frame_id +* Publish executed velocity if publish_cmd +* refactor to remove code duplication +* fixup pointer type for new convention +* Allow diff_drive_controller to use spheres as well as cylinders for wheel collision geometry. Cylinders are not well behaved on Gazebo/ODE heightfields, using spheres works around the issue. +* Contributors: Bence Magyar, Eric Tappan, Jeremie Deray, Karsten Knese, Tully Foote, mallanmba, tappan-at-git + +0.12.3 (2017-04-23) +------------------- + +0.12.2 (2017-04-21) +------------------- + +0.12.1 (2017-03-08) +------------------- +* Add exporting include dirs +* Contributors: Bence Magyar + +0.12.0 (2017-02-15) +------------------- +* Fix most catkin lint issues +* Change for format2 +* Add Enrique and Bence to maintainers +* Add urdf compatibility header +* Add --inorder to xacro calls +* Add missing xacro tags +* Use xacro instead of xacro.py +* Disable angular jerk limit test +* Replace boost::shared_ptr with urdf::XYConstSharedPtr when exists +* Contributors: Bence Magyar + +0.11.2 (2016-08-16) +------------------- + +0.11.1 (2016-05-23) +------------------- + +0.11.0 (2016-05-03) +------------------- + +0.10.0 (2015-11-20) +------------------- +* Address -Wunused-parameter warnings +* Limit jerk +* Add param velocity_rolling_window_size +* Minor fixes + 1. Coding style + 2. Tolerance to fall-back to Runge-Kutta 2 integration + 3. Remove unused variables +* Fix the following bugs in the testForward test: + 1. Check traveled distance in XY plane + 2. Use expected speed variable on test check +* Add test for NaN +* Add test for bad URDF +* Contributors: Adolfo Rodriguez Tsouroukdissian, Enrique Fernandez, Paul Mathieu + +0.9.2 (2015-05-04) +------------------ +* Allow the wheel separation and radius to be set from different sources + i.e. one can be set from the URDF, the other from the parameter server. + If wheel separation and wheel diameter is specified in the parameter server, don't look them up from urdf +* Contributors: Bence Magyar, Nils Berg + +0.9.1 (2014-11-03) +------------------ + +0.9.0 (2014-10-31) +------------------ +* Add support for multiple wheels per side +* Odometry computation: + - New option to compute in open loop fashion + - New option to skip publishing odom frame to tf +* Remove dependency on angles package +* Buildsystem fixes +* Contributors: Bence Magyar, Lukas Bulwahn, efernandez + +0.8.1 (2014-07-11) +------------------ + +0.8.0 (2014-05-12) +------------------ +* Add base_frame_id param (defaults to base_link) + The nav_msgs/Odometry message specifies the child_frame_id field, + which was previously not set. + This commit creates a parameter to replace the previously hard-coded + value of the child_frame_id of the published tf frame, and uses it + in the odom message as well. +* Contributors: enriquefernandez + +0.7.2 (2014-04-01) +------------------ + +0.7.1 (2014-03-31) +------------------ +* Changed test-depend to build-depend for release jobs. +* Contributors: Bence Magyar + +0.7.0 (2014-03-28) +------------------ +* diff_drive_controller: New controller for differential drive wheel systems. +* Control is in the form of a velocity command, that is split then sent on the two wheels of a differential drive +wheel base. +* Odometry is published to tf and to a dedicated nav__msgs/Odometry topic. +* Realtime-safe implementation. +* Implements task-space velocity and acceleration limits. +* Automatic stop after command time-out. +* Contributors: Bence Magyar, Paul Mathieu, Enrique Fernandez. diff --git a/mir_robot/diff_drive_controller/CMakeLists.txt b/mir_robot/diff_drive_controller/CMakeLists.txt new file mode 100755 index 0000000..93a7d95 --- /dev/null +++ b/mir_robot/diff_drive_controller/CMakeLists.txt @@ -0,0 +1,216 @@ +cmake_minimum_required(VERSION 3.0.2) +project(diff_drive_controller) + +# Load catkin and all dependencies required for this package +find_package(catkin REQUIRED COMPONENTS + controller_interface + control_msgs + dynamic_reconfigure + geometry_msgs + hardware_interface + nav_msgs + pluginlib + realtime_tools + tf + urdf +) + +find_package(Boost REQUIRED) + +# Declare a catkin package +generate_dynamic_reconfigure_options(cfg/DiffDriveController.cfg) + +catkin_package( + INCLUDE_DIRS include + CATKIN_DEPENDS + controller_interface + control_msgs + dynamic_reconfigure + geometry_msgs + hardware_interface + nav_msgs + realtime_tools + tf + LIBRARIES ${PROJECT_NAME} + DEPENDS Boost +) + + +########### +## Build ## +########### + +# Specify header include paths +include_directories( + include ${catkin_INCLUDE_DIRS} + include ${Boost_INCLUDE_DIRS} +) + +add_library(${PROJECT_NAME} + src/diff_drive_controller.cpp + src/odometry.cpp + src/speed_limiter.cpp +) +target_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES}) +add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${PROJECT_NAME}_gencfg) + + +############# +## Testing ## +############# + +if (CATKIN_ENABLE_TESTING) + find_package(controller_manager REQUIRED) + find_package(rosgraph_msgs REQUIRED) + find_package(std_srvs REQUIRED) + find_package(rostest REQUIRED) + + include_directories( + ${controller_manager_INCLUDE_DIRS} + ${rosgraph_msgs_INCLUDE_DIRS} + ${std_srvs_INCLUDE_DIRS} + ) + + set(test_LIBRARIES + ${controller_manager_LIBRARIES} + ${rosgraph_msgs_LIBRARIES} + ${std_srvs_LIBRARIES} + ) + + add_executable(diffbot test/diffbot.cpp) + target_link_libraries(diffbot ${catkin_LIBRARIES} ${test_LIBRARIES}) + + add_executable(skidsteerbot test/skidsteerbot.cpp) + target_link_libraries(skidsteerbot ${catkin_LIBRARIES} ${test_LIBRARIES}) + + add_dependencies(tests diffbot skidsteerbot) + + add_rostest_gtest(diff_drive_test + test/diff_drive_controller.test + test/diff_drive_test.cpp + ) + target_link_libraries(diff_drive_test ${catkin_LIBRARIES} ${test_LIBRARIES}) + + add_rostest_gtest(diff_drive_nan_test + test/diff_drive_controller_nan.test + test/diff_drive_nan_test.cpp + ) + target_link_libraries(diff_drive_nan_test ${catkin_LIBRARIES} ${test_LIBRARIES}) + + add_rostest_gtest(diff_drive_limits_test + test/diff_drive_controller_limits.test + test/diff_drive_limits_test.cpp + ) + target_link_libraries(diff_drive_limits_test ${catkin_LIBRARIES} ${test_LIBRARIES}) + + add_rostest_gtest(diff_drive_timeout_test + test/diff_drive_timeout.test + test/diff_drive_timeout_test.cpp + ) + target_link_libraries(diff_drive_timeout_test ${catkin_LIBRARIES} ${test_LIBRARIES}) + + add_rostest(test/diff_drive_multipliers.test) + + add_rostest(test/diff_drive_left_right_multipliers.test) + + add_rostest_gtest(diff_drive_fail_test + test/diff_drive_wrong.test + test/diff_drive_fail_test.cpp + ) + target_link_libraries(diff_drive_fail_test ${catkin_LIBRARIES} ${test_LIBRARIES}) + + add_rostest_gtest(diff_drive_odom_tf_test + test/diff_drive_odom_tf.test + test/diff_drive_odom_tf_test.cpp + ) + target_link_libraries(diff_drive_odom_tf_test ${catkin_LIBRARIES} ${test_LIBRARIES}) + + add_rostest_gtest(diff_drive_default_cmd_vel_out_test + test/diff_drive_default_cmd_vel_out.test + test/diff_drive_default_cmd_vel_out_test.cpp + ) + target_link_libraries(diff_drive_default_cmd_vel_out_test ${catkin_LIBRARIES} ${test_LIBRARIES}) + + add_rostest_gtest(diff_drive_pub_cmd_vel_out_test + test/diff_drive_pub_cmd_vel_out.test + test/diff_drive_pub_cmd_vel_out_test.cpp + ) + target_link_libraries(diff_drive_pub_cmd_vel_out_test ${catkin_LIBRARIES} ${test_LIBRARIES}) + + add_rostest_gtest(diff_drive_default_wheel_joint_controller_state_test + test/diff_drive_default_wheel_joint_controller_state.test + test/diff_drive_default_wheel_joint_controller_state_test.cpp + ) + target_link_libraries(diff_drive_default_wheel_joint_controller_state_test ${catkin_LIBRARIES} ${test_LIBRARIES}) + + add_rostest_gtest(diff_drive_publish_wheel_joint_controller_state_test + test/diff_drive_publish_wheel_joint_controller_state.test + test/diff_drive_publish_wheel_joint_controller_state_test.cpp + ) + target_link_libraries(diff_drive_publish_wheel_joint_controller_state_test ${catkin_LIBRARIES} ${test_LIBRARIES}) + + add_rostest_gtest(diff_drive_default_odom_frame_test + test/diff_drive_default_odom_frame.test + test/diff_drive_default_odom_frame_test.cpp + ) + target_link_libraries(diff_drive_default_odom_frame_test ${catkin_LIBRARIES} ${test_LIBRARIES}) + + add_rostest_gtest(diff_drive_odom_frame_test + test/diff_drive_odom_frame.test + test/diff_drive_odom_frame_test.cpp + ) + target_link_libraries(diff_drive_odom_frame_test ${catkin_LIBRARIES} ${test_LIBRARIES}) + + add_rostest_gtest(diff_drive_multiple_cmd_vel_publishers_test + test/diff_drive_multiple_cmd_vel_publishers.test + test/diff_drive_multiple_cmd_vel_publishers_test.cpp + ) + target_link_libraries(diff_drive_multiple_cmd_vel_publishers_test ${catkin_LIBRARIES} ${test_LIBRARIES}) + + add_rostest(test/diff_drive_open_loop.test) + + add_rostest(test/skid_steer_controller.test) + + add_rostest(test/skid_steer_no_wheels.test) + + add_rostest(test/diff_drive_radius_sphere.test) + + add_rostest(test/diff_drive_radius_param.test) + + add_rostest(test/diff_drive_radius_param_fail.test) + + add_rostest(test/diff_drive_separation_param.test) + + add_rostest(test/diff_drive_bad_urdf.test) + + add_rostest(test/diff_drive_get_wheel_radius_fail.test) + + add_rostest_gtest(diff_drive_dyn_reconf_test + test/diff_drive_dyn_reconf.test + test/diff_drive_dyn_reconf_test.cpp + ) + target_link_libraries(diff_drive_dyn_reconf_test ${catkin_LIBRARIES} ${test_LIBRARIES}) + +endif() + + +############# +## Install ## +############# + +# Install headers +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} +) + +# Install library +install(TARGETS ${PROJECT_NAME} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} +) + +# Install plugins +install(FILES diff_drive_controller_plugins.xml + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) diff --git a/mir_robot/diff_drive_controller/README.md b/mir_robot/diff_drive_controller/README.md new file mode 100755 index 0000000..371baed --- /dev/null +++ b/mir_robot/diff_drive_controller/README.md @@ -0,0 +1,5 @@ +## Diff Drive Controller ## + +Controller for a differential drive mobile base. + +Detailed user documentation can be found in the controller's [ROS wiki page](http://wiki.ros.org/diff_drive_controller). diff --git a/mir_robot/diff_drive_controller/cfg/DiffDriveController.cfg b/mir_robot/diff_drive_controller/cfg/DiffDriveController.cfg new file mode 100755 index 0000000..31a1668 --- /dev/null +++ b/mir_robot/diff_drive_controller/cfg/DiffDriveController.cfg @@ -0,0 +1,18 @@ +#!/usr/bin/env python + +PACKAGE = 'diff_drive_controller' + +from dynamic_reconfigure.parameter_generator_catkin import ParameterGenerator, bool_t, double_t + +gen = ParameterGenerator() + +# Kinematic parameters related +gen.add("left_wheel_radius_multiplier", double_t, 0, "Left wheel radius multiplier.", 1.0, 0.5, 1.5) +gen.add("right_wheel_radius_multiplier", double_t, 0, "Right wheel radius multiplier.", 1.0, 0.5, 1.5) +gen.add("wheel_separation_multiplier", double_t, 0, "Wheel separation multiplier.", 1.0, 0.5, 1.5) + +# Publication related +gen.add("publish_rate", double_t, 0, "Publish rate of odom.", 50.0, 0.0, 2000.0) +gen.add("enable_odom_tf", bool_t, 0, "Publish odom frame to tf.", True) + +exit(gen.generate(PACKAGE, "diff_drive_controller", "DiffDriveController")) diff --git a/mir_robot/diff_drive_controller/diff_drive_controller_plugins.xml b/mir_robot/diff_drive_controller/diff_drive_controller_plugins.xml new file mode 100755 index 0000000..a1c1d05 --- /dev/null +++ b/mir_robot/diff_drive_controller/diff_drive_controller_plugins.xml @@ -0,0 +1,9 @@ + + + + + The DiffDriveController tracks velocity commands. It expects 2 VelocityJointInterface type of hardware interfaces. + + + + diff --git a/mir_robot/diff_drive_controller/include/diff_drive_controller/diff_drive_controller.h b/mir_robot/diff_drive_controller/include/diff_drive_controller/diff_drive_controller.h new file mode 100755 index 0000000..798e6fa --- /dev/null +++ b/mir_robot/diff_drive_controller/include/diff_drive_controller/diff_drive_controller.h @@ -0,0 +1,312 @@ +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2013, PAL Robotics, S.L. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the PAL Robotics nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *********************************************************************/ + +/* + * Author: Bence Magyar, Enrique Fernández + */ + +#pragma once + + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +namespace diff_drive_controller{ + + /** + * This class makes some assumptions on the model of the robot: + * - the rotation axes of wheels are collinear + * - the wheels are identical in radius + * Additional assumptions to not duplicate information readily available in the URDF: + * - the wheels have the same parent frame + * - a wheel collision geometry is a cylinder or sphere in the urdf + * - a wheel joint frame center's vertical projection on the floor must lie within the contact patch + */ + class DiffDriveController + : public controller_interface::Controller + { + public: + DiffDriveController(); + + /** + * \brief Initialize controller + * \param hw Velocity joint interface for the wheels + * \param root_nh Node handle at root namespace + * \param controller_nh Node handle inside the controller namespace + */ + bool init(hardware_interface::VelocityJointInterface* hw, + ros::NodeHandle& root_nh, + ros::NodeHandle &controller_nh); + + /** + * \brief Updates controller, i.e. computes the odometry and sets the new velocity commands + * \param time Current time + * \param period Time since the last called to update + */ + void update(const ros::Time& time, const ros::Duration& period); + + /** + * \brief Starts controller + * \param time Current time + */ + void starting(const ros::Time& time); + + /** + * \brief Stops controller + * \param time Current time + */ + void stopping(const ros::Time& /*time*/); + + private: + std::string name_; + + /// Odometry related: + ros::Duration publish_period_; + ros::Time last_state_publish_time_; + bool open_loop_; + + /// Hardware handles: + std::vector left_wheel_joints_; + std::vector right_wheel_joints_; + + // Previous time + ros::Time time_previous_; + + /// Previous velocities from the encoders: + std::vector vel_left_previous_; + std::vector vel_right_previous_; + + /// Previous velocities from the encoders: + double vel_left_desired_previous_; + double vel_right_desired_previous_; + + /// Velocity command related: + struct Commands + { + double lin; + double ang; + ros::Time stamp; + + Commands() : lin(0.0), ang(0.0), stamp(0.0) {} + }; + realtime_tools::RealtimeBuffer command_; + Commands command_struct_; + ros::Subscriber sub_command_; + + /// Publish executed commands + std::shared_ptr > cmd_vel_pub_; + + /// Odometry related: + std::shared_ptr > odom_pub_; + std::shared_ptr > tf_odom_pub_; + Odometry odometry_; + + /// Controller state publisher + std::shared_ptr > controller_state_pub_; + + /// Wheel separation, wrt the midpoint of the wheel width: + double wheel_separation_; + + /// Wheel radius (assuming it's the same for the left and right wheels): + double wheel_radius_; + + /// Wheel separation and radius calibration multipliers: + double wheel_separation_multiplier_; + double left_wheel_radius_multiplier_; + double right_wheel_radius_multiplier_; + + /// Timeout to consider cmd_vel commands old: + double cmd_vel_timeout_; + + /// Whether to allow multiple publishers on cmd_vel topic or not: + bool allow_multiple_cmd_vel_publishers_; + + /// Frame to use for the robot base: + std::string base_frame_id_; + + /// Frame to use for odometry and odom tf: + std::string odom_frame_id_; + + /// Whether to publish odometry to tf or not: + bool enable_odom_tf_; + + /// Number of wheel joints: + size_t wheel_joints_size_; + + /// Speed limiters: + Commands last1_cmd_; + Commands last0_cmd_; + SpeedLimiter limiter_lin_; + SpeedLimiter limiter_ang_; + + /// Publish limited velocity: + bool publish_cmd_; + + /// Publish wheel data: + bool publish_wheel_joint_controller_state_; + + // A struct to hold dynamic parameters + // set from dynamic_reconfigure server + struct DynamicParams + { + bool update; + + double left_wheel_radius_multiplier; + double right_wheel_radius_multiplier; + double wheel_separation_multiplier; + + bool publish_cmd; + + double publish_rate; + bool enable_odom_tf; + + DynamicParams() + : left_wheel_radius_multiplier(1.0) + , right_wheel_radius_multiplier(1.0) + , wheel_separation_multiplier(1.0) + , publish_cmd(false) + , publish_rate(50) + , enable_odom_tf(true) + {} + + friend std::ostream& operator<<(std::ostream& os, const DynamicParams& params) + { + os << "DynamicParams:\n" + // + << "\tOdometry parameters:\n" + << "\t\tleft wheel radius multiplier: " << params.left_wheel_radius_multiplier << "\n" + << "\t\tright wheel radius multiplier: " << params.right_wheel_radius_multiplier << "\n" + << "\t\twheel separation multiplier: " << params.wheel_separation_multiplier << "\n" + // + << "\tPublication parameters:\n" + << "\t\tPublish executed velocity command: " << (params.publish_cmd?"enabled":"disabled") << "\n" + << "\t\tPublication rate: " << params.publish_rate << "\n" + << "\t\tPublish frame odom on tf: " << (params.enable_odom_tf?"enabled":"disabled"); + + return os; + } + }; + + realtime_tools::RealtimeBuffer dynamic_params_; + + /// Dynamic Reconfigure server + typedef dynamic_reconfigure::Server ReconfigureServer; + std::shared_ptr dyn_reconf_server_; + boost::recursive_mutex dyn_reconf_server_mutex_; + + private: + /** + * \brief Brakes the wheels, i.e. sets the velocity to 0 + */ + void brake(); + + /** + * \brief Velocity command callback + * \param command Velocity command message (twist) + */ + void cmdVelCallback(const geometry_msgs::Twist& command); + + /** + * \brief Get the wheel names from a wheel param + * \param [in] controller_nh Controller node handler + * \param [in] wheel_param Param name + * \param [out] wheel_names Vector with the whel names + * \return true if the wheel_param is available and the wheel_names are + * retrieved successfully from the param server; false otherwise + */ + bool getWheelNames(ros::NodeHandle& controller_nh, + const std::string& wheel_param, + std::vector& wheel_names); + + /** + * \brief Sets odometry parameters from the URDF, i.e. the wheel radius and separation + * \param root_nh Root node handle + * \param left_wheel_name Name of the left wheel joint + * \param right_wheel_name Name of the right wheel joint + */ + bool setOdomParamsFromUrdf(ros::NodeHandle& root_nh, + const std::string& left_wheel_name, + const std::string& right_wheel_name, + bool lookup_wheel_separation, + bool lookup_wheel_radius); + + /** + * \brief Sets the odometry publishing fields + * \param root_nh Root node handle + * \param controller_nh Node handle inside the controller namespace + */ + void setOdomPubFields(ros::NodeHandle& root_nh, ros::NodeHandle& controller_nh); + + /** + * \brief Callback for dynamic_reconfigure server + * \param config The config set from dynamic_reconfigure server + * \param level not used at this time. + * \see dyn_reconf_server_ + */ + void reconfCallback(DiffDriveControllerConfig& config, uint32_t /*level*/); + + /** + * \brief Update the dynamic parameters in the RT loop + */ + void updateDynamicParams(); + + /** + * \brief + * \param time Current time + * \param period Time since the last called to update + * \param curr_cmd Current velocity command + * \param wheel_separation wheel separation with multiplier + * \param left_wheel_radius left wheel radius with multiplier + * \param right_wheel_radius right wheel radius with multiplier + */ + void publishWheelData(const ros::Time& time, + const ros::Duration& period, + Commands& curr_cmd, + double wheel_separation, + double left_wheel_radius, + double right_wheel_radius); + }; + +} // namespace diff_drive_controller diff --git a/mir_robot/diff_drive_controller/include/diff_drive_controller/odometry.h b/mir_robot/diff_drive_controller/include/diff_drive_controller/odometry.h new file mode 100755 index 0000000..39a5eb8 --- /dev/null +++ b/mir_robot/diff_drive_controller/include/diff_drive_controller/odometry.h @@ -0,0 +1,210 @@ +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2013, PAL Robotics, S.L. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the PAL Robotics nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *********************************************************************/ + +/* + * Author: Luca Marchionni + * Author: Bence Magyar + * Author: Enrique Fernández + * Author: Paul Mathieu + */ + +#pragma once + + +#include +#include +#include +#include +#include + +namespace diff_drive_controller +{ + namespace bacc = boost::accumulators; + + /** + * \brief The Odometry class handles odometry readings + * (2D pose and velocity with related timestamp) + */ + class Odometry + { + public: + + /// Integration function, used to integrate the odometry: + typedef boost::function IntegrationFunction; + + /** + * \brief Constructor + * Timestamp will get the current time value + * Value will be set to zero + * \param velocity_rolling_window_size Rolling window size used to compute the velocity mean + */ + Odometry(size_t velocity_rolling_window_size = 10); + + /** + * \brief Initialize the odometry + * \param time Current time + */ + void init(const ros::Time &time); + + /** + * \brief Updates the odometry class with latest wheels position + * \param left_pos Left wheel position [rad] + * \param right_pos Right wheel position [rad] + * \param time Current time + * \return true if the odometry is actually updated + */ + bool update(double left_pos, double right_pos, const ros::Time &time); + + /** + * \brief Updates the odometry class with latest velocity command + * \param linear Linear velocity [m/s] + * \param angular Angular velocity [rad/s] + * \param time Current time + */ + void updateOpenLoop(double linear, double angular, const ros::Time &time); + + /** + * \brief heading getter + * \return heading [rad] + */ + double getHeading() const + { + return heading_; + } + + /** + * \brief x position getter + * \return x position [m] + */ + double getX() const + { + return x_; + } + + /** + * \brief y position getter + * \return y position [m] + */ + double getY() const + { + return y_; + } + + /** + * \brief linear velocity getter + * \return linear velocity [m/s] + */ + double getLinear() const + { + return linear_; + } + + /** + * \brief angular velocity getter + * \return angular velocity [rad/s] + */ + double getAngular() const + { + return angular_; + } + + /** + * \brief Sets the wheel parameters: radius and separation + * \param wheel_separation Separation between left and right wheels [m] + * \param left_wheel_radius Left wheel radius [m] + * \param right_wheel_radius Right wheel radius [m] + */ + void setWheelParams(double wheel_separation, double left_wheel_radius, double right_wheel_radius); + + /** + * \brief Velocity rolling window size setter + * \param velocity_rolling_window_size Velocity rolling window size + */ + void setVelocityRollingWindowSize(size_t velocity_rolling_window_size); + + private: + + /// Rolling mean accumulator and window: + typedef bacc::accumulator_set > RollingMeanAcc; + typedef bacc::tag::rolling_window RollingWindow; + + /** + * \brief Integrates the velocities (linear and angular) using 2nd order Runge-Kutta + * \param linear Linear velocity [m] (linear displacement, i.e. m/s * dt) computed by encoders + * \param angular Angular velocity [rad] (angular displacement, i.e. m/s * dt) computed by encoders + */ + void integrateRungeKutta2(double linear, double angular); + + /** + * \brief Integrates the velocities (linear and angular) using exact method + * \param linear Linear velocity [m] (linear displacement, i.e. m/s * dt) computed by encoders + * \param angular Angular velocity [rad] (angular displacement, i.e. m/s * dt) computed by encoders + */ + void integrateExact(double linear, double angular); + + /** + * \brief Reset linear and angular accumulators + */ + void resetAccumulators(); + + /// Current timestamp: + ros::Time timestamp_; + + /// Current pose: + double x_; // [m] + double y_; // [m] + double heading_; // [rad] + + /// Current velocity: + double linear_; // [m/s] + double angular_; // [rad/s] + + /// Wheel kinematic parameters [m]: + double wheel_separation_; + double left_wheel_radius_; + double right_wheel_radius_; + + /// Previou wheel position/state [rad]: + double left_wheel_old_pos_; + double right_wheel_old_pos_; + + /// Rolling mean accumulators for the linar and angular velocities: + size_t velocity_rolling_window_size_; + RollingMeanAcc linear_acc_; + RollingMeanAcc angular_acc_; + + /// Integration funcion, used to integrate the odometry: + IntegrationFunction integrate_fun_; + }; +} diff --git a/mir_robot/diff_drive_controller/include/diff_drive_controller/speed_limiter.h b/mir_robot/diff_drive_controller/include/diff_drive_controller/speed_limiter.h new file mode 100755 index 0000000..32f6c4b --- /dev/null +++ b/mir_robot/diff_drive_controller/include/diff_drive_controller/speed_limiter.h @@ -0,0 +1,129 @@ +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2013, PAL Robotics, S.L. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the PAL Robotics nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *********************************************************************/ + +/* + * Author: Enrique Fernández + */ + +#pragma once + + +namespace diff_drive_controller +{ + + class SpeedLimiter + { + public: + + /** + * \brief Constructor + * \param [in] has_velocity_limits if true, applies velocity limits + * \param [in] has_acceleration_limits if true, applies acceleration limits + * \param [in] has_jerk_limits if true, applies jerk limits + * \param [in] min_velocity Minimum velocity [m/s], usually <= 0 + * \param [in] max_velocity Maximum velocity [m/s], usually >= 0 + * \param [in] min_acceleration Minimum acceleration [m/s^2], usually <= 0 + * \param [in] max_acceleration Maximum acceleration [m/s^2], usually >= 0 + * \param [in] min_jerk Minimum jerk [m/s^3], usually <= 0 + * \param [in] max_jerk Maximum jerk [m/s^3], usually >= 0 + */ + SpeedLimiter( + bool has_velocity_limits = false, + bool has_acceleration_limits = false, + bool has_jerk_limits = false, + double min_velocity = 0.0, + double max_velocity = 0.0, + double min_acceleration = 0.0, + double max_acceleration = 0.0, + double min_jerk = 0.0, + double max_jerk = 0.0 + ); + + /** + * \brief Limit the velocity and acceleration + * \param [in, out] v Velocity [m/s] + * \param [in] v0 Previous velocity to v [m/s] + * \param [in] v1 Previous velocity to v0 [m/s] + * \param [in] dt Time step [s] + * \return Limiting factor (1.0 if none) + */ + double limit(double& v, double v0, double v1, double dt); + + /** + * \brief Limit the velocity + * \param [in, out] v Velocity [m/s] + * \return Limiting factor (1.0 if none) + */ + double limit_velocity(double& v); + + /** + * \brief Limit the acceleration + * \param [in, out] v Velocity [m/s] + * \param [in] v0 Previous velocity [m/s] + * \param [in] dt Time step [s] + * \return Limiting factor (1.0 if none) + */ + double limit_acceleration(double& v, double v0, double dt); + + /** + * \brief Limit the jerk + * \param [in, out] v Velocity [m/s] + * \param [in] v0 Previous velocity to v [m/s] + * \param [in] v1 Previous velocity to v0 [m/s] + * \param [in] dt Time step [s] + * \return Limiting factor (1.0 if none) + * \see http://en.wikipedia.org/wiki/Jerk_%28physics%29#Motion_control + */ + double limit_jerk(double& v, double v0, double v1, double dt); + + public: + // Enable/Disable velocity/acceleration/jerk limits: + bool has_velocity_limits; + bool has_acceleration_limits; + bool has_jerk_limits; + + // Velocity limits: + double min_velocity; + double max_velocity; + + // Acceleration limits: + double min_acceleration; + double max_acceleration; + + // Jerk limits: + double min_jerk; + double max_jerk; + }; + +} // namespace diff_drive_controller diff --git a/mir_robot/diff_drive_controller/package.xml b/mir_robot/diff_drive_controller/package.xml new file mode 100755 index 0000000..1dc2794 --- /dev/null +++ b/mir_robot/diff_drive_controller/package.xml @@ -0,0 +1,51 @@ + + + + diff_drive_controller + 0.21.2 + Controller for a differential drive mobile base. + + Bence Magyar + Enrique Fernandez + + BSD + + https://github.com/ros-controls/ros_controllers/wiki + https://github.com/ros-controls/ros_controllers/issues + https://github.com/ros-controls/ros_controllers + + Bence Magyar + + catkin + + controller_interface + control_msgs + dynamic_reconfigure + geometry_msgs + hardware_interface + nav_msgs + realtime_tools + tf + + boost + pluginlib + urdf + + boost + + pluginlib + urdf + + controller_manager + rosgraph_msgs + rostest + rostopic + std_srvs + xacro + + + + + diff --git a/mir_robot/diff_drive_controller/src/diff_drive_controller.cpp b/mir_robot/diff_drive_controller/src/diff_drive_controller.cpp new file mode 100755 index 0000000..4d9045a --- /dev/null +++ b/mir_robot/diff_drive_controller/src/diff_drive_controller.cpp @@ -0,0 +1,837 @@ +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2013, PAL Robotics, S.L. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the PAL Robotics nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *********************************************************************/ + +/* + * Author: Bence Magyar, Enrique Fernández + */ + +#include +#include +#include +#include +#include +#include + +static double euclideanOfVectors(const urdf::Vector3& vec1, const urdf::Vector3& vec2) +{ + return std::sqrt(std::pow(vec1.x-vec2.x,2) + + std::pow(vec1.y-vec2.y,2) + + std::pow(vec1.z-vec2.z,2)); +} + +/* +* \brief Check that a link exists and has a geometry collision. +* \param link The link +* \return true if the link has a collision element with geometry +*/ +static bool hasCollisionGeometry(const urdf::LinkConstSharedPtr& link) +{ + if (!link) + { + ROS_ERROR("Link pointer is null."); + return false; + } + + if (!link->collision) + { + ROS_ERROR_STREAM("Link " << link->name << " does not have collision description. Add collision description for link to urdf."); + return false; + } + + if (!link->collision->geometry) + { + ROS_ERROR_STREAM("Link " << link->name << " does not have collision geometry description. Add collision geometry description for link to urdf."); + return false; + } + return true; +} + +/* + * \brief Check if the link is modeled as a cylinder + * \param link Link + * \return true if the link is modeled as a Cylinder; false otherwise + */ +static bool isCylinder(const urdf::LinkConstSharedPtr& link) +{ + if (!hasCollisionGeometry(link)) + { + return false; + } + + if (link->collision->geometry->type != urdf::Geometry::CYLINDER) + { + ROS_DEBUG_STREAM("Link " << link->name << " does not have cylinder geometry"); + return false; + } + + return true; +} + +/* + * \brief Check if the link is modeled as a sphere + * \param link Link + * \return true if the link is modeled as a Sphere; false otherwise + */ +static bool isSphere(const urdf::LinkConstSharedPtr& link) +{ + if (!hasCollisionGeometry(link)) + { + return false; + } + + if (link->collision->geometry->type != urdf::Geometry::SPHERE) + { + ROS_DEBUG_STREAM("Link " << link->name << " does not have sphere geometry"); + return false; + } + + return true; +} + +/* + * \brief Get the wheel radius + * \param [in] wheel_link Wheel link + * \param [out] wheel_radius Wheel radius [m] + * \return true if the wheel radius was found; false otherwise + */ +static bool getWheelRadius(const urdf::LinkConstSharedPtr& wheel_link, double& wheel_radius) +{ + if (isCylinder(wheel_link)) + { + wheel_radius = (static_cast(wheel_link->collision->geometry.get()))->radius; + return true; + } + else if (isSphere(wheel_link)) + { + wheel_radius = (static_cast(wheel_link->collision->geometry.get()))->radius; + return true; + } + + ROS_ERROR_STREAM("Wheel link " << wheel_link->name << " is NOT modeled as a cylinder or sphere!"); + return false; +} + +namespace diff_drive_controller{ + + DiffDriveController::DiffDriveController() + : open_loop_(false) + , command_struct_() + , wheel_separation_(0.0) + , wheel_radius_(0.0) + , wheel_separation_multiplier_(1.0) + , left_wheel_radius_multiplier_(1.0) + , right_wheel_radius_multiplier_(1.0) + , cmd_vel_timeout_(0.5) + , allow_multiple_cmd_vel_publishers_(true) + , base_frame_id_("base_link") + , odom_frame_id_("odom") + , enable_odom_tf_(true) + , wheel_joints_size_(0) + , publish_cmd_(false) + , publish_wheel_joint_controller_state_(false) + { + } + + bool DiffDriveController::init(hardware_interface::VelocityJointInterface* hw, + ros::NodeHandle& root_nh, + ros::NodeHandle &controller_nh) + { + const std::string complete_ns = controller_nh.getNamespace(); + std::size_t id = complete_ns.find_last_of("/"); + name_ = complete_ns.substr(id + 1); + + // Get joint names from the parameter server + std::vector left_wheel_names, right_wheel_names; + if (!getWheelNames(controller_nh, "left_wheel", left_wheel_names) || + !getWheelNames(controller_nh, "right_wheel", right_wheel_names)) + { + return false; + } + + if (left_wheel_names.size() != right_wheel_names.size()) + { + ROS_ERROR_STREAM_NAMED(name_, + "#left wheels (" << left_wheel_names.size() << ") != " << + "#right wheels (" << right_wheel_names.size() << ")."); + return false; + } + else + { + wheel_joints_size_ = left_wheel_names.size(); + + left_wheel_joints_.resize(wheel_joints_size_); + right_wheel_joints_.resize(wheel_joints_size_); + } + + // Odometry related: + double publish_rate; + controller_nh.param("publish_rate", publish_rate, 50.0); + ROS_INFO_STREAM_NAMED(name_, "Controller state will be published at " + << publish_rate << "Hz."); + publish_period_ = ros::Duration(1.0 / publish_rate); + + controller_nh.param("open_loop", open_loop_, open_loop_); + + controller_nh.param("wheel_separation_multiplier", wheel_separation_multiplier_, wheel_separation_multiplier_); + ROS_INFO_STREAM_NAMED(name_, "Wheel separation will be multiplied by " + << wheel_separation_multiplier_ << "."); + + if (controller_nh.hasParam("wheel_radius_multiplier")) + { + double wheel_radius_multiplier; + controller_nh.getParam("wheel_radius_multiplier", wheel_radius_multiplier); + + left_wheel_radius_multiplier_ = wheel_radius_multiplier; + right_wheel_radius_multiplier_ = wheel_radius_multiplier; + } + else + { + controller_nh.param("left_wheel_radius_multiplier", left_wheel_radius_multiplier_, left_wheel_radius_multiplier_); + controller_nh.param("right_wheel_radius_multiplier", right_wheel_radius_multiplier_, right_wheel_radius_multiplier_); + } + + ROS_INFO_STREAM_NAMED(name_, "Left wheel radius will be multiplied by " + << left_wheel_radius_multiplier_ << "."); + ROS_INFO_STREAM_NAMED(name_, "Right wheel radius will be multiplied by " + << right_wheel_radius_multiplier_ << "."); + + int velocity_rolling_window_size = 10; + controller_nh.param("velocity_rolling_window_size", velocity_rolling_window_size, velocity_rolling_window_size); + ROS_INFO_STREAM_NAMED(name_, "Velocity rolling window size of " + << velocity_rolling_window_size << "."); + + odometry_.setVelocityRollingWindowSize(velocity_rolling_window_size); + + // Twist command related: + controller_nh.param("cmd_vel_timeout", cmd_vel_timeout_, cmd_vel_timeout_); + ROS_INFO_STREAM_NAMED(name_, "Velocity commands will be considered old if they are older than " + << cmd_vel_timeout_ << "s."); + + controller_nh.param("allow_multiple_cmd_vel_publishers", allow_multiple_cmd_vel_publishers_, allow_multiple_cmd_vel_publishers_); + ROS_INFO_STREAM_NAMED(name_, "Allow mutiple cmd_vel publishers is " + << (allow_multiple_cmd_vel_publishers_?"enabled":"disabled")); + + controller_nh.param("base_frame_id", base_frame_id_, base_frame_id_); + ROS_INFO_STREAM_NAMED(name_, "Base frame_id set to " << base_frame_id_); + + controller_nh.param("odom_frame_id", odom_frame_id_, odom_frame_id_); + ROS_INFO_STREAM_NAMED(name_, "Odometry frame_id set to " << odom_frame_id_); + + controller_nh.param("enable_odom_tf", enable_odom_tf_, enable_odom_tf_); + ROS_INFO_STREAM_NAMED(name_, "Publishing to tf is " << (enable_odom_tf_?"enabled":"disabled")); + + // Velocity and acceleration limits: + controller_nh.param("linear/x/has_velocity_limits" , limiter_lin_.has_velocity_limits , limiter_lin_.has_velocity_limits ); + controller_nh.param("linear/x/has_acceleration_limits", limiter_lin_.has_acceleration_limits, limiter_lin_.has_acceleration_limits); + controller_nh.param("linear/x/has_jerk_limits" , limiter_lin_.has_jerk_limits , limiter_lin_.has_jerk_limits ); + controller_nh.param("linear/x/max_velocity" , limiter_lin_.max_velocity , limiter_lin_.max_velocity ); + controller_nh.param("linear/x/min_velocity" , limiter_lin_.min_velocity , -limiter_lin_.max_velocity ); + controller_nh.param("linear/x/max_acceleration" , limiter_lin_.max_acceleration , limiter_lin_.max_acceleration ); + controller_nh.param("linear/x/min_acceleration" , limiter_lin_.min_acceleration , -limiter_lin_.max_acceleration ); + controller_nh.param("linear/x/max_jerk" , limiter_lin_.max_jerk , limiter_lin_.max_jerk ); + controller_nh.param("linear/x/min_jerk" , limiter_lin_.min_jerk , -limiter_lin_.max_jerk ); + + controller_nh.param("angular/z/has_velocity_limits" , limiter_ang_.has_velocity_limits , limiter_ang_.has_velocity_limits ); + controller_nh.param("angular/z/has_acceleration_limits", limiter_ang_.has_acceleration_limits, limiter_ang_.has_acceleration_limits); + controller_nh.param("angular/z/has_jerk_limits" , limiter_ang_.has_jerk_limits , limiter_ang_.has_jerk_limits ); + controller_nh.param("angular/z/max_velocity" , limiter_ang_.max_velocity , limiter_ang_.max_velocity ); + controller_nh.param("angular/z/min_velocity" , limiter_ang_.min_velocity , -limiter_ang_.max_velocity ); + controller_nh.param("angular/z/max_acceleration" , limiter_ang_.max_acceleration , limiter_ang_.max_acceleration ); + controller_nh.param("angular/z/min_acceleration" , limiter_ang_.min_acceleration , -limiter_ang_.max_acceleration ); + controller_nh.param("angular/z/max_jerk" , limiter_ang_.max_jerk , limiter_ang_.max_jerk ); + controller_nh.param("angular/z/min_jerk" , limiter_ang_.min_jerk , -limiter_ang_.max_jerk ); + + // Publish limited velocity: + controller_nh.param("publish_cmd", publish_cmd_, publish_cmd_); + + // Publish wheel data: + controller_nh.param("publish_wheel_joint_controller_state", publish_wheel_joint_controller_state_, publish_wheel_joint_controller_state_); + + // If either parameter is not available, we need to look up the value in the URDF + bool lookup_wheel_separation = !controller_nh.getParam("wheel_separation", wheel_separation_); + bool lookup_wheel_radius = !controller_nh.getParam("wheel_radius", wheel_radius_); + + if (!setOdomParamsFromUrdf(root_nh, + left_wheel_names[0], + right_wheel_names[0], + lookup_wheel_separation, + lookup_wheel_radius)) + { + return false; + } + + // Regardless of how we got the separation and radius, use them + // to set the odometry parameters + const double ws = wheel_separation_multiplier_ * wheel_separation_; + const double lwr = left_wheel_radius_multiplier_ * wheel_radius_; + const double rwr = right_wheel_radius_multiplier_ * wheel_radius_; + odometry_.setWheelParams(ws, lwr, rwr); + ROS_INFO_STREAM_NAMED(name_, + "Odometry params : wheel separation " << ws + << ", left wheel radius " << lwr + << ", right wheel radius " << rwr); + + if (publish_cmd_) + { + cmd_vel_pub_.reset(new realtime_tools::RealtimePublisher(controller_nh, "cmd_vel_out", 100)); + } + + // Wheel joint controller state: + if (publish_wheel_joint_controller_state_) + { + controller_state_pub_.reset(new realtime_tools::RealtimePublisher(controller_nh, "wheel_joint_controller_state", 100)); + + const size_t num_wheels = wheel_joints_size_ * 2; + + controller_state_pub_->msg_.joint_names.resize(num_wheels); + + controller_state_pub_->msg_.desired.positions.resize(num_wheels); + controller_state_pub_->msg_.desired.velocities.resize(num_wheels); + controller_state_pub_->msg_.desired.accelerations.resize(num_wheels); + controller_state_pub_->msg_.desired.effort.resize(num_wheels); + + controller_state_pub_->msg_.actual.positions.resize(num_wheels); + controller_state_pub_->msg_.actual.velocities.resize(num_wheels); + controller_state_pub_->msg_.actual.accelerations.resize(num_wheels); + controller_state_pub_->msg_.actual.effort.resize(num_wheels); + + controller_state_pub_->msg_.error.positions.resize(num_wheels); + controller_state_pub_->msg_.error.velocities.resize(num_wheels); + controller_state_pub_->msg_.error.accelerations.resize(num_wheels); + controller_state_pub_->msg_.error.effort.resize(num_wheels); + + for (size_t i = 0; i < wheel_joints_size_; ++i) + { + controller_state_pub_->msg_.joint_names[i] = left_wheel_names[i]; + controller_state_pub_->msg_.joint_names[i + wheel_joints_size_] = right_wheel_names[i]; + } + + vel_left_previous_.resize(wheel_joints_size_, 0.0); + vel_right_previous_.resize(wheel_joints_size_, 0.0); + } + + setOdomPubFields(root_nh, controller_nh); + + // Get the joint object to use in the realtime loop + for (size_t i = 0; i < wheel_joints_size_; ++i) + { + ROS_INFO_STREAM_NAMED(name_, + "Adding left wheel with joint name: " << left_wheel_names[i] + << " and right wheel with joint name: " << right_wheel_names[i]); + left_wheel_joints_[i] = hw->getHandle(left_wheel_names[i]); // throws on failure + right_wheel_joints_[i] = hw->getHandle(right_wheel_names[i]); // throws on failure + } + + sub_command_ = controller_nh.subscribe("cmd_vel", 1, &DiffDriveController::cmdVelCallback, this); + + // Initialize dynamic parameters + DynamicParams dynamic_params; + dynamic_params.left_wheel_radius_multiplier = left_wheel_radius_multiplier_; + dynamic_params.right_wheel_radius_multiplier = right_wheel_radius_multiplier_; + dynamic_params.wheel_separation_multiplier = wheel_separation_multiplier_; + + dynamic_params.publish_rate = publish_rate; + dynamic_params.enable_odom_tf = enable_odom_tf_; + + dynamic_params_.writeFromNonRT(dynamic_params); + + // Initialize dynamic_reconfigure server + DiffDriveControllerConfig config; + config.left_wheel_radius_multiplier = left_wheel_radius_multiplier_; + config.right_wheel_radius_multiplier = right_wheel_radius_multiplier_; + config.wheel_separation_multiplier = wheel_separation_multiplier_; + + config.publish_rate = publish_rate; + config.enable_odom_tf = enable_odom_tf_; + + dyn_reconf_server_ = std::make_shared(dyn_reconf_server_mutex_, controller_nh); + + // Update parameters + dyn_reconf_server_mutex_.lock(); + dyn_reconf_server_->updateConfig(config); + dyn_reconf_server_mutex_.unlock(); + + dyn_reconf_server_->setCallback( + std::bind(&DiffDriveController::reconfCallback, this, std::placeholders::_1, std::placeholders::_2)); + return true; + } + + void DiffDriveController::update(const ros::Time& time, const ros::Duration& period) + { + // update parameter from dynamic reconf + updateDynamicParams(); + + // Apply (possibly new) multipliers: + const double ws = wheel_separation_multiplier_ * wheel_separation_; + const double lwr = left_wheel_radius_multiplier_ * wheel_radius_; + const double rwr = right_wheel_radius_multiplier_ * wheel_radius_; + + odometry_.setWheelParams(ws, lwr, rwr); + + // COMPUTE AND PUBLISH ODOMETRY + if (open_loop_) + { + odometry_.updateOpenLoop(last0_cmd_.lin, last0_cmd_.ang, time); + } + else + { + double left_pos = 0.0; + double right_pos = 0.0; + for (size_t i = 0; i < wheel_joints_size_; ++i) + { + const double lp = left_wheel_joints_[i].getPosition(); + const double rp = right_wheel_joints_[i].getPosition(); + if (std::isnan(lp) || std::isnan(rp)) + return; + + left_pos += lp; + right_pos += rp; + } + left_pos /= wheel_joints_size_; + right_pos /= wheel_joints_size_; + + // Estimate linear and angular velocity using joint information + odometry_.update(left_pos, right_pos, time); + } + + // Publish odometry message + if (last_state_publish_time_ + publish_period_ < time) + { + last_state_publish_time_ += publish_period_; + // Compute and store orientation info + const geometry_msgs::Quaternion orientation( + tf::createQuaternionMsgFromYaw(odometry_.getHeading())); + + // Populate odom message and publish + if (odom_pub_->trylock()) + { + odom_pub_->msg_.header.stamp = time; + odom_pub_->msg_.pose.pose.position.x = odometry_.getX(); + odom_pub_->msg_.pose.pose.position.y = odometry_.getY(); + odom_pub_->msg_.pose.pose.orientation = orientation; + odom_pub_->msg_.twist.twist.linear.x = odometry_.getLinear(); + odom_pub_->msg_.twist.twist.angular.z = odometry_.getAngular(); + odom_pub_->unlockAndPublish(); + } + + // Publish tf /odom frame + if (enable_odom_tf_ && tf_odom_pub_->trylock()) + { + geometry_msgs::TransformStamped& odom_frame = tf_odom_pub_->msg_.transforms[0]; + odom_frame.header.stamp = time; + odom_frame.transform.translation.x = odometry_.getX(); + odom_frame.transform.translation.y = odometry_.getY(); + odom_frame.transform.rotation = orientation; + tf_odom_pub_->unlockAndPublish(); + } + } + + // MOVE ROBOT + // Retreive current velocity command and time step: + Commands curr_cmd = *(command_.readFromRT()); + const double dt = (time - curr_cmd.stamp).toSec(); + + // Brake if cmd_vel has timeout: + if (dt > cmd_vel_timeout_) + { + curr_cmd.lin = 0.0; + curr_cmd.ang = 0.0; + } + + // Limit velocities and accelerations: + const double cmd_dt(period.toSec()); + + limiter_lin_.limit(curr_cmd.lin, last0_cmd_.lin, last1_cmd_.lin, cmd_dt); + limiter_ang_.limit(curr_cmd.ang, last0_cmd_.ang, last1_cmd_.ang, cmd_dt); + + last1_cmd_ = last0_cmd_; + last0_cmd_ = curr_cmd; + + // Publish limited velocity: + if (publish_cmd_ && cmd_vel_pub_ && cmd_vel_pub_->trylock()) + { + cmd_vel_pub_->msg_.header.stamp = time; + cmd_vel_pub_->msg_.twist.linear.x = curr_cmd.lin; + cmd_vel_pub_->msg_.twist.angular.z = curr_cmd.ang; + cmd_vel_pub_->unlockAndPublish(); + } + + // Compute wheels velocities: + const double vel_left = (curr_cmd.lin - curr_cmd.ang * ws / 2.0)/lwr; + const double vel_right = (curr_cmd.lin + curr_cmd.ang * ws / 2.0)/rwr; + + // Set wheels velocities: + for (size_t i = 0; i < wheel_joints_size_; ++i) + { + left_wheel_joints_[i].setCommand(vel_left); + right_wheel_joints_[i].setCommand(vel_right); + } + + publishWheelData(time, period, curr_cmd, ws, lwr, rwr); + time_previous_ = time; + } + + void DiffDriveController::starting(const ros::Time& time) + { + brake(); + + // Register starting time used to keep fixed rate + last_state_publish_time_ = time; + time_previous_ = time; + + odometry_.init(time); + } + + void DiffDriveController::stopping(const ros::Time& /*time*/) + { + brake(); + } + + void DiffDriveController::brake() + { + const double vel = 0.0; + for (size_t i = 0; i < wheel_joints_size_; ++i) + { + left_wheel_joints_[i].setCommand(vel); + right_wheel_joints_[i].setCommand(vel); + } + } + + void DiffDriveController::cmdVelCallback(const geometry_msgs::Twist& command) + { + if (isRunning()) + { + // check that we don't have multiple publishers on the command topic + if (!allow_multiple_cmd_vel_publishers_ && sub_command_.getNumPublishers() > 1) + { + ROS_ERROR_STREAM_THROTTLE_NAMED(1.0, name_, "Detected " << sub_command_.getNumPublishers() + << " publishers. Only 1 publisher is allowed. Going to brake."); + brake(); + return; + } + + if(!std::isfinite(command.angular.z) || !std::isfinite(command.linear.x)) + { + ROS_WARN_THROTTLE(1.0, "Received NaN in velocity command. Ignoring."); + return; + } + + command_struct_.ang = command.angular.z; + command_struct_.lin = command.linear.x; + command_struct_.stamp = ros::Time::now(); + command_.writeFromNonRT (command_struct_); + ROS_DEBUG_STREAM_NAMED(name_, + "Added values to command. " + << "Ang: " << command_struct_.ang << ", " + << "Lin: " << command_struct_.lin << ", " + << "Stamp: " << command_struct_.stamp); + } + else + { + ROS_ERROR_NAMED(name_, "Can't accept new commands. Controller is not running."); + } + } + + bool DiffDriveController::getWheelNames(ros::NodeHandle& controller_nh, + const std::string& wheel_param, + std::vector& wheel_names) + { + XmlRpc::XmlRpcValue wheel_list; + if (!controller_nh.getParam(wheel_param, wheel_list)) + { + ROS_ERROR_STREAM_NAMED(name_, + "Couldn't retrieve wheel param '" << wheel_param << "'."); + return false; + } + + if (wheel_list.getType() == XmlRpc::XmlRpcValue::TypeArray) + { + if (wheel_list.size() == 0) + { + ROS_ERROR_STREAM_NAMED(name_, + "Wheel param '" << wheel_param << "' is an empty list"); + return false; + } + + for (int i = 0; i < wheel_list.size(); ++i) + { + if (wheel_list[i].getType() != XmlRpc::XmlRpcValue::TypeString) + { + ROS_ERROR_STREAM_NAMED(name_, + "Wheel param '" << wheel_param << "' #" << i << + " isn't a string."); + return false; + } + } + + wheel_names.resize(wheel_list.size()); + for (int i = 0; i < wheel_list.size(); ++i) + { + wheel_names[i] = static_cast(wheel_list[i]); + } + } + else if (wheel_list.getType() == XmlRpc::XmlRpcValue::TypeString) + { + wheel_names.push_back(wheel_list); + } + else + { + ROS_ERROR_STREAM_NAMED(name_, + "Wheel param '" << wheel_param << + "' is neither a list of strings nor a string."); + return false; + } + + return true; + } + + bool DiffDriveController::setOdomParamsFromUrdf(ros::NodeHandle& root_nh, + const std::string& left_wheel_name, + const std::string& right_wheel_name, + bool lookup_wheel_separation, + bool lookup_wheel_radius) + { + if (!(lookup_wheel_separation || lookup_wheel_radius)) + { + // Short-circuit in case we don't need to look up anything, so we don't have to parse the URDF + return true; + } + + // Parse robot description + const std::string model_param_name = "robot_description"; + bool res = root_nh.hasParam(model_param_name); + std::string robot_model_str=""; + if (!res || !root_nh.getParam(model_param_name,robot_model_str)) + { + ROS_ERROR_NAMED(name_, "Robot description couldn't be retrieved from param server."); + return false; + } + + urdf::ModelInterfaceSharedPtr model(urdf::parseURDF(robot_model_str)); + + urdf::JointConstSharedPtr left_wheel_joint(model->getJoint(left_wheel_name)); + urdf::JointConstSharedPtr right_wheel_joint(model->getJoint(right_wheel_name)); + + if (!left_wheel_joint) + { + ROS_ERROR_STREAM_NAMED(name_, left_wheel_name + << " couldn't be retrieved from model description"); + return false; + } + + if (!right_wheel_joint) + { + ROS_ERROR_STREAM_NAMED(name_, right_wheel_name + << " couldn't be retrieved from model description"); + return false; + } + + if (lookup_wheel_separation) + { + // Get wheel separation + ROS_INFO_STREAM("left wheel to origin: " << left_wheel_joint->parent_to_joint_origin_transform.position.x << "," + << left_wheel_joint->parent_to_joint_origin_transform.position.y << ", " + << left_wheel_joint->parent_to_joint_origin_transform.position.z); + ROS_INFO_STREAM("right wheel to origin: " << right_wheel_joint->parent_to_joint_origin_transform.position.x << "," + << right_wheel_joint->parent_to_joint_origin_transform.position.y << ", " + << right_wheel_joint->parent_to_joint_origin_transform.position.z); + + wheel_separation_ = euclideanOfVectors(left_wheel_joint->parent_to_joint_origin_transform.position, + right_wheel_joint->parent_to_joint_origin_transform.position); + + } + + if (lookup_wheel_radius) + { + // Get wheel radius + if (!getWheelRadius(model->getLink(left_wheel_joint->child_link_name), wheel_radius_)) + { + ROS_ERROR_STREAM_NAMED(name_, "Couldn't retrieve " << left_wheel_name << " wheel radius"); + return false; + } + } + + return true; + } + + void DiffDriveController::setOdomPubFields(ros::NodeHandle& root_nh, ros::NodeHandle& controller_nh) + { + // Get and check params for covariances + XmlRpc::XmlRpcValue pose_cov_list; + controller_nh.getParam("pose_covariance_diagonal", pose_cov_list); + ROS_ASSERT(pose_cov_list.getType() == XmlRpc::XmlRpcValue::TypeArray); + ROS_ASSERT(pose_cov_list.size() == 6); + for (int i = 0; i < pose_cov_list.size(); ++i) + ROS_ASSERT(pose_cov_list[i].getType() == XmlRpc::XmlRpcValue::TypeDouble); + + XmlRpc::XmlRpcValue twist_cov_list; + controller_nh.getParam("twist_covariance_diagonal", twist_cov_list); + ROS_ASSERT(twist_cov_list.getType() == XmlRpc::XmlRpcValue::TypeArray); + ROS_ASSERT(twist_cov_list.size() == 6); + for (int i = 0; i < twist_cov_list.size(); ++i) + ROS_ASSERT(twist_cov_list[i].getType() == XmlRpc::XmlRpcValue::TypeDouble); + + // Setup odometry realtime publisher + odom message constant fields + odom_pub_.reset(new realtime_tools::RealtimePublisher(controller_nh, "odom", 100)); + odom_pub_->msg_.header.frame_id = odom_frame_id_; + odom_pub_->msg_.child_frame_id = base_frame_id_; + odom_pub_->msg_.pose.pose.position.z = 0; + odom_pub_->msg_.pose.covariance = { + static_cast(pose_cov_list[0]), 0., 0., 0., 0., 0., + 0., static_cast(pose_cov_list[1]), 0., 0., 0., 0., + 0., 0., static_cast(pose_cov_list[2]), 0., 0., 0., + 0., 0., 0., static_cast(pose_cov_list[3]), 0., 0., + 0., 0., 0., 0., static_cast(pose_cov_list[4]), 0., + 0., 0., 0., 0., 0., static_cast(pose_cov_list[5]) }; + odom_pub_->msg_.twist.twist.linear.y = 0; + odom_pub_->msg_.twist.twist.linear.z = 0; + odom_pub_->msg_.twist.twist.angular.x = 0; + odom_pub_->msg_.twist.twist.angular.y = 0; + odom_pub_->msg_.twist.covariance = { + static_cast(twist_cov_list[0]), 0., 0., 0., 0., 0., + 0., static_cast(twist_cov_list[1]), 0., 0., 0., 0., + 0., 0., static_cast(twist_cov_list[2]), 0., 0., 0., + 0., 0., 0., static_cast(twist_cov_list[3]), 0., 0., + 0., 0., 0., 0., static_cast(twist_cov_list[4]), 0., + 0., 0., 0., 0., 0., static_cast(twist_cov_list[5]) }; + tf_odom_pub_.reset(new realtime_tools::RealtimePublisher(root_nh, "/tf", 100)); + tf_odom_pub_->msg_.transforms.resize(1); + tf_odom_pub_->msg_.transforms[0].transform.translation.z = 0.0; + tf_odom_pub_->msg_.transforms[0].child_frame_id = base_frame_id_; + tf_odom_pub_->msg_.transforms[0].header.frame_id = odom_frame_id_; + } + + void DiffDriveController::reconfCallback(DiffDriveControllerConfig& config, uint32_t /*level*/) + { + DynamicParams dynamic_params; + dynamic_params.left_wheel_radius_multiplier = config.left_wheel_radius_multiplier; + dynamic_params.right_wheel_radius_multiplier = config.right_wheel_radius_multiplier; + dynamic_params.wheel_separation_multiplier = config.wheel_separation_multiplier; + + dynamic_params.publish_rate = config.publish_rate; + + dynamic_params.enable_odom_tf = config.enable_odom_tf; + + dynamic_params_.writeFromNonRT(dynamic_params); + + ROS_INFO_STREAM_NAMED(name_, "Dynamic Reconfigure:\n" << dynamic_params); + } + + void DiffDriveController::updateDynamicParams() + { + // Retreive dynamic params: + const DynamicParams dynamic_params = *(dynamic_params_.readFromRT()); + + left_wheel_radius_multiplier_ = dynamic_params.left_wheel_radius_multiplier; + right_wheel_radius_multiplier_ = dynamic_params.right_wheel_radius_multiplier; + wheel_separation_multiplier_ = dynamic_params.wheel_separation_multiplier; + + publish_period_ = ros::Duration(1.0 / dynamic_params.publish_rate); + enable_odom_tf_ = dynamic_params.enable_odom_tf; + } + + void DiffDriveController::publishWheelData(const ros::Time& time, const ros::Duration& period, Commands& curr_cmd, + double wheel_separation, double left_wheel_radius, double right_wheel_radius) + { + if (publish_wheel_joint_controller_state_ && controller_state_pub_->trylock()) + { + const double cmd_dt(period.toSec()); + + // Compute desired wheels velocities, that is before applying limits: + const double vel_left_desired = (curr_cmd.lin - curr_cmd.ang * wheel_separation / 2.0) / left_wheel_radius; + const double vel_right_desired = (curr_cmd.lin + curr_cmd.ang * wheel_separation / 2.0) / right_wheel_radius; + controller_state_pub_->msg_.header.stamp = time; + + for (size_t i = 0; i < wheel_joints_size_; ++i) + { + const double control_duration = (time - time_previous_).toSec(); + + const double left_wheel_acc = (left_wheel_joints_[i].getVelocity() - vel_left_previous_[i]) / control_duration; + const double right_wheel_acc = (right_wheel_joints_[i].getVelocity() - vel_right_previous_[i]) / control_duration; + + // Actual + controller_state_pub_->msg_.actual.positions[i] = left_wheel_joints_[i].getPosition(); + controller_state_pub_->msg_.actual.velocities[i] = left_wheel_joints_[i].getVelocity(); + controller_state_pub_->msg_.actual.accelerations[i] = left_wheel_acc; + controller_state_pub_->msg_.actual.effort[i] = left_wheel_joints_[i].getEffort(); + + controller_state_pub_->msg_.actual.positions[i + wheel_joints_size_] = right_wheel_joints_[i].getPosition(); + controller_state_pub_->msg_.actual.velocities[i + wheel_joints_size_] = right_wheel_joints_[i].getVelocity(); + controller_state_pub_->msg_.actual.accelerations[i + wheel_joints_size_] = right_wheel_acc; + controller_state_pub_->msg_.actual.effort[i+ wheel_joints_size_] = right_wheel_joints_[i].getEffort(); + + // Desired + controller_state_pub_->msg_.desired.positions[i] += vel_left_desired * cmd_dt; + controller_state_pub_->msg_.desired.velocities[i] = vel_left_desired; + controller_state_pub_->msg_.desired.accelerations[i] = (vel_left_desired - vel_left_desired_previous_) * cmd_dt; + controller_state_pub_->msg_.desired.effort[i] = std::numeric_limits::quiet_NaN(); + + controller_state_pub_->msg_.desired.positions[i + wheel_joints_size_] += vel_right_desired * cmd_dt; + controller_state_pub_->msg_.desired.velocities[i + wheel_joints_size_] = vel_right_desired; + controller_state_pub_->msg_.desired.accelerations[i + wheel_joints_size_] = (vel_right_desired - vel_right_desired_previous_) * cmd_dt; + controller_state_pub_->msg_.desired.effort[i+ wheel_joints_size_] = std::numeric_limits::quiet_NaN(); + + // Error + controller_state_pub_->msg_.error.positions[i] = controller_state_pub_->msg_.desired.positions[i] - + controller_state_pub_->msg_.actual.positions[i]; + controller_state_pub_->msg_.error.velocities[i] = controller_state_pub_->msg_.desired.velocities[i] - + controller_state_pub_->msg_.actual.velocities[i]; + controller_state_pub_->msg_.error.accelerations[i] = controller_state_pub_->msg_.desired.accelerations[i] - + controller_state_pub_->msg_.actual.accelerations[i]; + controller_state_pub_->msg_.error.effort[i] = controller_state_pub_->msg_.desired.effort[i] - + controller_state_pub_->msg_.actual.effort[i]; + + controller_state_pub_->msg_.error.positions[i + wheel_joints_size_] = controller_state_pub_->msg_.desired.positions[i + wheel_joints_size_] - + controller_state_pub_->msg_.actual.positions[i + wheel_joints_size_]; + controller_state_pub_->msg_.error.velocities[i + wheel_joints_size_] = controller_state_pub_->msg_.desired.velocities[i + wheel_joints_size_] - + controller_state_pub_->msg_.actual.velocities[i + wheel_joints_size_]; + controller_state_pub_->msg_.error.accelerations[i + wheel_joints_size_] = controller_state_pub_->msg_.desired.accelerations[i + wheel_joints_size_] - + controller_state_pub_->msg_.actual.accelerations[i + wheel_joints_size_]; + controller_state_pub_->msg_.error.effort[i+ wheel_joints_size_] = controller_state_pub_->msg_.desired.effort[i + wheel_joints_size_] - + controller_state_pub_->msg_.actual.effort[i + wheel_joints_size_]; + + // Save previous velocities to compute acceleration + vel_left_previous_[i] = left_wheel_joints_[i].getVelocity(); + vel_right_previous_[i] = right_wheel_joints_[i].getVelocity(); + vel_left_desired_previous_ = vel_left_desired; + vel_right_desired_previous_ = vel_right_desired; + } + + controller_state_pub_->unlockAndPublish(); + } + } + +} // namespace diff_drive_controller + +PLUGINLIB_EXPORT_CLASS(diff_drive_controller::DiffDriveController, controller_interface::ControllerBase); diff --git a/mir_robot/diff_drive_controller/src/odometry.cpp b/mir_robot/diff_drive_controller/src/odometry.cpp new file mode 100755 index 0000000..fafbb74 --- /dev/null +++ b/mir_robot/diff_drive_controller/src/odometry.cpp @@ -0,0 +1,174 @@ +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2013, PAL Robotics, S.L. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the PAL Robotics nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *********************************************************************/ + +/* + * Author: Luca Marchionni + * Author: Bence Magyar + * Author: Enrique Fernández + * Author: Paul Mathieu + */ + +#include + +namespace diff_drive_controller +{ + namespace bacc = boost::accumulators; + + Odometry::Odometry(size_t velocity_rolling_window_size) + : timestamp_(0.0) + , x_(0.0) + , y_(0.0) + , heading_(0.0) + , linear_(0.0) + , angular_(0.0) + , wheel_separation_(0.0) + , left_wheel_radius_(0.0) + , right_wheel_radius_(0.0) + , left_wheel_old_pos_(0.0) + , right_wheel_old_pos_(0.0) + , velocity_rolling_window_size_(velocity_rolling_window_size) + , linear_acc_(RollingWindow::window_size = velocity_rolling_window_size) + , angular_acc_(RollingWindow::window_size = velocity_rolling_window_size) + , integrate_fun_(std::bind(&Odometry::integrateExact, this, std::placeholders::_1, std::placeholders::_2)) + { + } + + void Odometry::init(const ros::Time& time) + { + // Reset accumulators and timestamp: + resetAccumulators(); + timestamp_ = time; + } + + bool Odometry::update(double left_pos, double right_pos, const ros::Time &time) + { + /// Get current wheel joint positions: + const double left_wheel_cur_pos = left_pos * left_wheel_radius_; + const double right_wheel_cur_pos = right_pos * right_wheel_radius_; + + /// Estimate velocity of wheels using old and current position: + const double left_wheel_est_vel = left_wheel_cur_pos - left_wheel_old_pos_; + const double right_wheel_est_vel = right_wheel_cur_pos - right_wheel_old_pos_; + + /// Update old position with current: + left_wheel_old_pos_ = left_wheel_cur_pos; + right_wheel_old_pos_ = right_wheel_cur_pos; + + /// Compute linear and angular diff: + const double linear = (right_wheel_est_vel + left_wheel_est_vel) * 0.5 ; + const double angular = (right_wheel_est_vel - left_wheel_est_vel) / wheel_separation_; + + /// Integrate odometry: + integrate_fun_(linear, angular); + + /// We cannot estimate the speed with very small time intervals: + const double dt = (time - timestamp_).toSec(); + if (dt < 0.0001) + return false; // Interval too small to integrate with + + timestamp_ = time; + + /// Estimate speeds using a rolling mean to filter them out: + linear_acc_(linear/dt); + angular_acc_(angular/dt); + + linear_ = bacc::rolling_mean(linear_acc_); + angular_ = bacc::rolling_mean(angular_acc_); + + return true; + } + + void Odometry::updateOpenLoop(double linear, double angular, const ros::Time &time) + { + /// Save last linear and angular velocity: + linear_ = linear; + angular_ = angular; + + /// Integrate odometry: + const double dt = (time - timestamp_).toSec(); + timestamp_ = time; + integrate_fun_(linear * dt, angular * dt); + } + + void Odometry::setWheelParams(double wheel_separation, double left_wheel_radius, double right_wheel_radius) + { + wheel_separation_ = wheel_separation; + left_wheel_radius_ = left_wheel_radius; + right_wheel_radius_ = right_wheel_radius; + } + + void Odometry::setVelocityRollingWindowSize(size_t velocity_rolling_window_size) + { + velocity_rolling_window_size_ = velocity_rolling_window_size; + + resetAccumulators(); + } + + void Odometry::integrateRungeKutta2(double linear, double angular) + { + const double direction = heading_ + angular * 0.5; + + /// Runge-Kutta 2nd order integration: + x_ += linear * cos(direction); + y_ += linear * sin(direction); + heading_ += angular; + } + + /** + * \brief Other possible integration method provided by the class + * \param linear + * \param angular + */ + void Odometry::integrateExact(double linear, double angular) + { + if (fabs(angular) < 1e-6) + integrateRungeKutta2(linear, angular); + else + { + /// Exact integration (should solve problems when angular is zero): + const double heading_old = heading_; + const double r = linear/angular; + heading_ += angular; + x_ += r * (sin(heading_) - sin(heading_old)); + y_ += -r * (cos(heading_) - cos(heading_old)); + } + } + + void Odometry::resetAccumulators() + { + linear_acc_ = RollingMeanAcc(RollingWindow::window_size = velocity_rolling_window_size_); + angular_acc_ = RollingMeanAcc(RollingWindow::window_size = velocity_rolling_window_size_); + } + +} // namespace diff_drive_controller diff --git a/mir_robot/diff_drive_controller/src/speed_limiter.cpp b/mir_robot/diff_drive_controller/src/speed_limiter.cpp new file mode 100755 index 0000000..630ec82 --- /dev/null +++ b/mir_robot/diff_drive_controller/src/speed_limiter.cpp @@ -0,0 +1,137 @@ +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2013, PAL Robotics, S.L. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the PAL Robotics nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *********************************************************************/ + +/* + * Author: Enrique Fernández + */ + +#include + +#include + +template +T clamp(T x, T min, T max) +{ + return std::min(std::max(min, x), max); +} + +namespace diff_drive_controller +{ + + SpeedLimiter::SpeedLimiter( + bool has_velocity_limits, + bool has_acceleration_limits, + bool has_jerk_limits, + double min_velocity, + double max_velocity, + double min_acceleration, + double max_acceleration, + double min_jerk, + double max_jerk + ) + : has_velocity_limits(has_velocity_limits) + , has_acceleration_limits(has_acceleration_limits) + , has_jerk_limits(has_jerk_limits) + , min_velocity(min_velocity) + , max_velocity(max_velocity) + , min_acceleration(min_acceleration) + , max_acceleration(max_acceleration) + , min_jerk(min_jerk) + , max_jerk(max_jerk) + { + } + + double SpeedLimiter::limit(double& v, double v0, double v1, double dt) + { + const double tmp = v; + + limit_jerk(v, v0, v1, dt); + limit_acceleration(v, v0, dt); + limit_velocity(v); + + return tmp != 0.0 ? v / tmp : 1.0; + } + + double SpeedLimiter::limit_velocity(double& v) + { + const double tmp = v; + + if (has_velocity_limits) + { + v = clamp(v, min_velocity, max_velocity); + } + + return tmp != 0.0 ? v / tmp : 1.0; + } + + double SpeedLimiter::limit_acceleration(double& v, double v0, double dt) + { + const double tmp = v; + + if (has_acceleration_limits) + { + const double dv_min = min_acceleration * dt; + const double dv_max = max_acceleration * dt; + + const double dv = clamp(v - v0, dv_min, dv_max); + + v = v0 + dv; + } + + return tmp != 0.0 ? v / tmp : 1.0; + } + + double SpeedLimiter::limit_jerk(double& v, double v0, double v1, double dt) + { + const double tmp = v; + + if (has_jerk_limits) + { + const double dv = v - v0; + const double dv0 = v0 - v1; + + const double dt2 = 2. * dt * dt; + + const double da_min = min_jerk * dt2; + const double da_max = max_jerk * dt2; + + const double da = clamp(dv - dv0, da_min, da_max); + + v = v0 + dv0 + da; + } + + return tmp != 0.0 ? v / tmp : 1.0; + } + +} // namespace diff_drive_controller diff --git a/mir_robot/diff_drive_controller/test/diff_drive_bad_urdf.test b/mir_robot/diff_drive_controller/test/diff_drive_bad_urdf.test new file mode 100755 index 0000000..a5f44f2 --- /dev/null +++ b/mir_robot/diff_drive_controller/test/diff_drive_bad_urdf.test @@ -0,0 +1,18 @@ + + + + + + + + + + + + + + diff --git a/mir_robot/diff_drive_controller/test/diff_drive_common.launch b/mir_robot/diff_drive_controller/test/diff_drive_common.launch new file mode 100755 index 0000000..94bbabc --- /dev/null +++ b/mir_robot/diff_drive_controller/test/diff_drive_common.launch @@ -0,0 +1,35 @@ + + + + True + + + + + + + + + + + + + + + + diff --git a/mir_robot/diff_drive_controller/test/diff_drive_controller.test b/mir_robot/diff_drive_controller/test/diff_drive_controller.test new file mode 100755 index 0000000..3542517 --- /dev/null +++ b/mir_robot/diff_drive_controller/test/diff_drive_controller.test @@ -0,0 +1,14 @@ + + + + + + + + + + + diff --git a/mir_robot/diff_drive_controller/test/diff_drive_controller_limits.test b/mir_robot/diff_drive_controller/test/diff_drive_controller_limits.test new file mode 100755 index 0000000..949ad82 --- /dev/null +++ b/mir_robot/diff_drive_controller/test/diff_drive_controller_limits.test @@ -0,0 +1,17 @@ + + + + + + + + + + + + + + diff --git a/mir_robot/diff_drive_controller/test/diff_drive_controller_nan.test b/mir_robot/diff_drive_controller/test/diff_drive_controller_nan.test new file mode 100755 index 0000000..fb6f9dd --- /dev/null +++ b/mir_robot/diff_drive_controller/test/diff_drive_controller_nan.test @@ -0,0 +1,20 @@ + + + + + + + diffbot_controller: + publish_cmd: True + + + + + + + + + diff --git a/mir_robot/diff_drive_controller/test/diff_drive_default_cmd_vel_out.test b/mir_robot/diff_drive_controller/test/diff_drive_default_cmd_vel_out.test new file mode 100755 index 0000000..0f9c5ef --- /dev/null +++ b/mir_robot/diff_drive_controller/test/diff_drive_default_cmd_vel_out.test @@ -0,0 +1,21 @@ + + + + + + + + + + + + + + + diff --git a/mir_robot/diff_drive_controller/test/diff_drive_default_cmd_vel_out_test.cpp b/mir_robot/diff_drive_controller/test/diff_drive_default_cmd_vel_out_test.cpp new file mode 100755 index 0000000..907187b --- /dev/null +++ b/mir_robot/diff_drive_controller/test/diff_drive_default_cmd_vel_out_test.cpp @@ -0,0 +1,69 @@ +/////////////////////////////////////////////////////////////////////////////// +// Copyright (C) 2017, PAL Robotics. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of PAL Robotics, Inc. nor the names of its +// contributors may be used to endorse or promote products derived from +// this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +// POSSIBILITY OF SUCH DAMAGE. +////////////////////////////////////////////////////////////////////////////// + +/// \author Jeremie Deray + +#include "test_common.h" + +// TEST CASES +TEST_F(DiffDriveControllerTest, testDefaultCmdVelOutTopic) +{ + // wait for ROS + waitForController(); + // msgs are published in the same loop + // thus if odom is published cmd_vel_out + // should be as well (if enabled) + waitForOdomMsgs(); + + EXPECT_FALSE(isPublishingCmdVelOut()); + + // zero everything before test + geometry_msgs::Twist cmd_vel; + cmd_vel.linear.x = 0.0; + cmd_vel.angular.z = 0.0; + publish(cmd_vel); + ros::Duration(0.1).sleep(); + + cmd_vel.linear.x = 0.1; + publish(cmd_vel); + ros::Duration(0.1).sleep(); + + EXPECT_FALSE(isPublishingCmdVelOut()); +} + +int main(int argc, char** argv) +{ + testing::InitGoogleTest(&argc, argv); + ros::init(argc, argv, "diff_drive_default_cmd_vel_out_topic_test"); + + ros::AsyncSpinner spinner(1); + spinner.start(); + int ret = RUN_ALL_TESTS(); + spinner.stop(); + ros::shutdown(); + return ret; +} diff --git a/mir_robot/diff_drive_controller/test/diff_drive_default_odom_frame.test b/mir_robot/diff_drive_controller/test/diff_drive_default_odom_frame.test new file mode 100755 index 0000000..e6c1738 --- /dev/null +++ b/mir_robot/diff_drive_controller/test/diff_drive_default_odom_frame.test @@ -0,0 +1,20 @@ + + + + + + + + + + + + + + diff --git a/mir_robot/diff_drive_controller/test/diff_drive_default_odom_frame_test.cpp b/mir_robot/diff_drive_controller/test/diff_drive_default_odom_frame_test.cpp new file mode 100755 index 0000000..c06fcc0 --- /dev/null +++ b/mir_robot/diff_drive_controller/test/diff_drive_default_odom_frame_test.cpp @@ -0,0 +1,69 @@ +/////////////////////////////////////////////////////////////////////////////// +// Copyright (C) 2015, Locus Robotics Corp. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of PAL Robotics, Inc. nor the names of its +// contributors may be used to endorse or promote products derived from +// this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +// POSSIBILITY OF SUCH DAMAGE. +////////////////////////////////////////////////////////////////////////////// + +/// \author Eric Tappan + +#include "test_common.h" +#include + +// TEST CASES +TEST_F(DiffDriveControllerTest, testOdomFrame) +{ + // wait for ROS + waitForController(); + + // set up tf listener + tf::TransformListener listener; + ros::Duration(2.0).sleep(); + // check the original odom frame doesn't exist + EXPECT_TRUE(listener.frameExists("odom")); +} + +TEST_F(DiffDriveControllerTest, testOdomTopic) +{ + // wait for ROS + waitForController(); + waitForOdomMsgs(); + + // get an odom message + nav_msgs::Odometry odom_msg = getLastOdom(); + // check its frame_id + ASSERT_STREQ(odom_msg.header.frame_id.c_str(), "odom"); +} + +int main(int argc, char** argv) +{ + testing::InitGoogleTest(&argc, argv); + ros::init(argc, argv, "diff_drive_default_odom_frame_test"); + + ros::AsyncSpinner spinner(1); + spinner.start(); + int ret = RUN_ALL_TESTS(); + spinner.stop(); + ros::shutdown(); + return ret; +} diff --git a/mir_robot/diff_drive_controller/test/diff_drive_default_wheel_joint_controller_state.test b/mir_robot/diff_drive_controller/test/diff_drive_default_wheel_joint_controller_state.test new file mode 100755 index 0000000..4b17188 --- /dev/null +++ b/mir_robot/diff_drive_controller/test/diff_drive_default_wheel_joint_controller_state.test @@ -0,0 +1,21 @@ + + + + + + + + + + + + + + + diff --git a/mir_robot/diff_drive_controller/test/diff_drive_default_wheel_joint_controller_state_test.cpp b/mir_robot/diff_drive_controller/test/diff_drive_default_wheel_joint_controller_state_test.cpp new file mode 100755 index 0000000..cb29465 --- /dev/null +++ b/mir_robot/diff_drive_controller/test/diff_drive_default_wheel_joint_controller_state_test.cpp @@ -0,0 +1,65 @@ +/////////////////////////////////////////////////////////////////////////////// +// Copyright (C) 2018, PAL Robotics. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of PAL Robotics, Inc. nor the names of its +// contributors may be used to endorse or promote products derived from +// this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +// POSSIBILITY OF SUCH DAMAGE. +////////////////////////////////////////////////////////////////////////////// + +/// \author Jeremie Deray + +#include "test_common.h" + +// TEST CASES +TEST_F(DiffDriveControllerTest, testDefaultJointTrajectoryControllerStateTopic) +{ + // wait for ROS + waitForController(); + + EXPECT_FALSE(isPublishingJointTrajectoryControllerState()); + + // zero everything before test + geometry_msgs::Twist cmd_vel; + cmd_vel.linear.x = 0.0; + cmd_vel.angular.z = 0.0; + publish(cmd_vel); + ros::Duration(0.1).sleep(); + + cmd_vel.linear.x = 0.1; + publish(cmd_vel); + ros::Duration(0.1).sleep(); + + EXPECT_FALSE(isPublishingJointTrajectoryControllerState()); +} + +int main(int argc, char** argv) +{ + testing::InitGoogleTest(&argc, argv); + ros::init(argc, argv, "diff_drive_default_wheel_joint_controller_state_topic_test"); + + ros::AsyncSpinner spinner(1); + spinner.start(); + int ret = RUN_ALL_TESTS(); + spinner.stop(); + ros::shutdown(); + return ret; +} diff --git a/mir_robot/diff_drive_controller/test/diff_drive_dyn_reconf.test b/mir_robot/diff_drive_controller/test/diff_drive_dyn_reconf.test new file mode 100755 index 0000000..bb670ed --- /dev/null +++ b/mir_robot/diff_drive_controller/test/diff_drive_dyn_reconf.test @@ -0,0 +1,20 @@ + + + + + + + + diffbot_controller: + enable_odom_tf: False + + + + + + + + diff --git a/mir_robot/diff_drive_controller/test/diff_drive_dyn_reconf_test.cpp b/mir_robot/diff_drive_controller/test/diff_drive_dyn_reconf_test.cpp new file mode 100755 index 0000000..94842cd --- /dev/null +++ b/mir_robot/diff_drive_controller/test/diff_drive_dyn_reconf_test.cpp @@ -0,0 +1,176 @@ +/////////////////////////////////////////////////////////////////////////////// +// Copyright (C) 2018, PAL Robotics S.L. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of PAL Robotics, Inc. nor the names of its +// contributors may be used to endorse or promote products derived from +// this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +// POSSIBILITY OF SUCH DAMAGE. +////////////////////////////////////////////////////////////////////////////// + +/// \author Jeremie Deray + +#include "test_common.h" +#include + +#include + +// TEST CASES +TEST_F(DiffDriveControllerTest, testDynReconfServerAlive) +{ + // wait for ROS + waitForController(); + + // Expect server is alive + EXPECT_TRUE(ros::service::exists("diffbot_controller/set_parameters", true)); + + dynamic_reconfigure::ReconfigureRequest srv_req; + dynamic_reconfigure::ReconfigureResponse srv_resp; + + // Expect server is callable (get-fashion) + EXPECT_TRUE(ros::service::call("diffbot_controller/set_parameters", srv_req, srv_resp)); + + EXPECT_EQ(1, srv_resp.config.bools.size()); + + if (!srv_resp.config.bools.empty()) + { + EXPECT_EQ("enable_odom_tf", srv_resp.config.bools[0].name); + // expect false since it is set to false in the .test + EXPECT_EQ(false, srv_resp.config.bools[0].value); + } + + EXPECT_EQ(4, srv_resp.config.doubles.size()); + + if (srv_resp.config.doubles.size() >= 4) + { + EXPECT_EQ("left_wheel_radius_multiplier", srv_resp.config.doubles[0].name); + EXPECT_EQ(1, srv_resp.config.doubles[0].value); + + EXPECT_EQ("right_wheel_radius_multiplier", srv_resp.config.doubles[1].name); + EXPECT_EQ(1, srv_resp.config.doubles[1].value); + + EXPECT_EQ("wheel_separation_multiplier", srv_resp.config.doubles[2].name); + EXPECT_EQ(1, srv_resp.config.doubles[2].value); + + EXPECT_EQ("publish_rate", srv_resp.config.doubles[3].name); + EXPECT_EQ(50, srv_resp.config.doubles[3].value); + } + + dynamic_reconfigure::DoubleParameter double_param; + double_param.name = "left_wheel_radius_multiplier"; + double_param.value = 0.95; + + srv_req.config.doubles.push_back(double_param); + + double_param.name = "right_wheel_radius_multiplier"; + double_param.value = 0.95; + + srv_req.config.doubles.push_back(double_param); + + double_param.name = "wheel_separation_multiplier"; + double_param.value = 0.95; + + srv_req.config.doubles.push_back(double_param); + + double_param.name = "publish_rate"; + double_param.value = 150; + + srv_req.config.doubles.push_back(double_param); + + dynamic_reconfigure::BoolParameter bool_param; + bool_param.name = "enable_odom_tf"; + bool_param.value = false; + + srv_req.config.bools.push_back(bool_param); + + // Expect server is callable (set-fashion) + EXPECT_TRUE(ros::service::call("diffbot_controller/set_parameters", srv_req, srv_resp)); + + EXPECT_EQ(1, srv_resp.config.bools.size()); + + if (!srv_resp.config.bools.empty()) + { + EXPECT_EQ("enable_odom_tf", srv_resp.config.bools[0].name); + EXPECT_EQ(false, srv_resp.config.bools[0].value); + } + + EXPECT_EQ(4, srv_resp.config.doubles.size()); + + if (srv_resp.config.doubles.size() >= 4) + { + EXPECT_EQ("left_wheel_radius_multiplier", srv_resp.config.doubles[0].name); + EXPECT_EQ(0.95, srv_resp.config.doubles[0].value); + + EXPECT_EQ("right_wheel_radius_multiplier", srv_resp.config.doubles[1].name); + EXPECT_EQ(0.95, srv_resp.config.doubles[1].value); + + EXPECT_EQ("wheel_separation_multiplier", srv_resp.config.doubles[2].name); + EXPECT_EQ(0.95, srv_resp.config.doubles[2].value); + + EXPECT_EQ("publish_rate", srv_resp.config.doubles[3].name); + EXPECT_EQ(150, srv_resp.config.doubles[3].value); + } +} + +// TEST CASES +TEST_F(DiffDriveControllerTest, testDynReconfEnableTf) +{ + // wait for ROS + while(!isControllerAlive() && ros::ok()) + { + ros::Duration(0.1).sleep(); + } + if (!ros::ok()) + FAIL() << "Something went wrong while executing test"; + + // set up tf listener + tf::TransformListener listener; + ros::Duration(2.0).sleep(); + // check the odom frame doesn't exist + EXPECT_FALSE(listener.frameExists("odom")); + + dynamic_reconfigure::ReconfigureRequest srv_req; + dynamic_reconfigure::ReconfigureResponse srv_resp; + + dynamic_reconfigure::BoolParameter bool_param; + bool_param.name = "enable_odom_tf"; + bool_param.value = true; + + srv_req.config.bools.push_back(bool_param); + + EXPECT_TRUE(ros::service::call("diffbot_controller/set_parameters", srv_req, srv_resp)); + + ros::Duration(2.0).sleep(); + // check the odom frame doesn't exist + EXPECT_TRUE(listener.frameExists("odom")); +} + +int main(int argc, char** argv) +{ + testing::InitGoogleTest(&argc, argv); + ros::init(argc, argv, "diff_drive_dyn_reconf_test"); + + ros::AsyncSpinner spinner(1); + spinner.start(); + int ret = RUN_ALL_TESTS(); + spinner.stop(); + ros::shutdown(); + return ret; +} diff --git a/mir_robot/diff_drive_controller/test/diff_drive_fail_test.cpp b/mir_robot/diff_drive_controller/test/diff_drive_fail_test.cpp new file mode 100755 index 0000000..bb1ee6c --- /dev/null +++ b/mir_robot/diff_drive_controller/test/diff_drive_fail_test.cpp @@ -0,0 +1,60 @@ +/////////////////////////////////////////////////////////////////////////////// +// Copyright (C) 2013, PAL Robotics S.L. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of PAL Robotics, Inc. nor the names of its +// contributors may be used to endorse or promote products derived from +// this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +// POSSIBILITY OF SUCH DAMAGE. +////////////////////////////////////////////////////////////////////////////// + +/// \author Paul Mathieu + +#include "test_common.h" + +// TEST CASES +TEST_F(DiffDriveControllerTest, testWrongJointName) +{ + // the controller should never be alive + int secs = 0; + while(!isControllerAlive() && ros::ok() && secs < 5) + { + ros::Duration(1.0).sleep(); + secs++; + } + if (!ros::ok()) + FAIL() << "Something went wrong while executing test."; + + // give up and assume controller load failure after 5 seconds + EXPECT_GE(secs, 5); +} + +int main(int argc, char** argv) +{ + testing::InitGoogleTest(&argc, argv); + ros::init(argc, argv, "diff_drive_fail_test"); + + ros::AsyncSpinner spinner(1); + spinner.start(); + int ret = RUN_ALL_TESTS(); + spinner.stop(); + ros::shutdown(); + return ret; +} diff --git a/mir_robot/diff_drive_controller/test/diff_drive_get_wheel_radius_fail.test b/mir_robot/diff_drive_controller/test/diff_drive_get_wheel_radius_fail.test new file mode 100755 index 0000000..fae7a83 --- /dev/null +++ b/mir_robot/diff_drive_controller/test/diff_drive_get_wheel_radius_fail.test @@ -0,0 +1,19 @@ + + + + + + + + + + + + + + + + diff --git a/mir_robot/diff_drive_controller/test/diff_drive_left_right_multipliers.test b/mir_robot/diff_drive_controller/test/diff_drive_left_right_multipliers.test new file mode 100755 index 0000000..f1432fb --- /dev/null +++ b/mir_robot/diff_drive_controller/test/diff_drive_left_right_multipliers.test @@ -0,0 +1,17 @@ + + + + + + + + + + + + + + diff --git a/mir_robot/diff_drive_controller/test/diff_drive_limits_test.cpp b/mir_robot/diff_drive_controller/test/diff_drive_limits_test.cpp new file mode 100755 index 0000000..5215075 --- /dev/null +++ b/mir_robot/diff_drive_controller/test/diff_drive_limits_test.cpp @@ -0,0 +1,231 @@ +/////////////////////////////////////////////////////////////////////////////// +// Copyright (C) 2013, PAL Robotics S.L. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of PAL Robotics, Inc. nor the names of its +// contributors may be used to endorse or promote products derived from +// this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +// POSSIBILITY OF SUCH DAMAGE. +////////////////////////////////////////////////////////////////////////////// + +/// \author Paul Mathieu + +#include "test_common.h" + +// TEST CASES +TEST_F(DiffDriveControllerTest, testLinearJerkLimits) +{ + // wait for ROS + waitForController(); + + // zero everything before test + geometry_msgs::Twist cmd_vel; + cmd_vel.linear.x = 0.0; + cmd_vel.angular.z = 0.0; + publish(cmd_vel); + ros::Duration(2.0).sleep(); + // get initial odom + nav_msgs::Odometry old_odom = getLastOdom(); + // send a big command + cmd_vel.linear.x = 10.0; + publish(cmd_vel); + // wait for a while + ros::Duration(0.5).sleep(); + + nav_msgs::Odometry new_odom = getLastOdom(); + + // check if the robot speed is now 0.37m.s-1 + EXPECT_NEAR(new_odom.twist.twist.linear.x, 0.37, JERK_LINEAR_VELOCITY_TOLERANCE); + EXPECT_LT(fabs(new_odom.twist.twist.angular.z - old_odom.twist.twist.angular.z), EPS); + + cmd_vel.linear.x = 0.0; + publish(cmd_vel); +} + +TEST_F(DiffDriveControllerTest, testLinearAccelerationLimits) +{ + // wait for ROS + while(!isControllerAlive()) + { + ros::Duration(0.1).sleep(); + } + // zero everything before test + geometry_msgs::Twist cmd_vel; + cmd_vel.linear.x = 0.0; + cmd_vel.angular.z = 0.0; + publish(cmd_vel); + ros::Duration(2.0).sleep(); + // get initial odom + nav_msgs::Odometry old_odom = getLastOdom(); + // send a big command + cmd_vel.linear.x = 10.0; + publish(cmd_vel); + // wait for a while + ros::Duration(0.5).sleep(); + + nav_msgs::Odometry new_odom = getLastOdom(); + + // check if the robot speed is now 0.5 m.s-1, which is 1.0m.s-2 * 0.5s + EXPECT_LT(fabs(new_odom.twist.twist.linear.x - old_odom.twist.twist.linear.x), 0.5 + VELOCITY_TOLERANCE); + EXPECT_LT(fabs(new_odom.twist.twist.angular.z - old_odom.twist.twist.angular.z), EPS); + + cmd_vel.linear.x = 0.0; + publish(cmd_vel); +} + +TEST_F(DiffDriveControllerTest, testLinearVelocityLimits) +{ + // wait for ROS + while(!isControllerAlive()) + { + ros::Duration(0.1).sleep(); + } + // zero everything before test + geometry_msgs::Twist cmd_vel; + cmd_vel.linear.x = 0.0; + cmd_vel.angular.z = 0.0; + publish(cmd_vel); + ros::Duration(2.0).sleep(); + // get initial odom + nav_msgs::Odometry old_odom = getLastOdom(); + // send a big command + cmd_vel.linear.x = 10.0; + publish(cmd_vel); + // wait for a while + ros::Duration(5.0).sleep(); + + nav_msgs::Odometry new_odom = getLastOdom(); + + // check if the robot speed is now 1.0 m.s-1, the limit + EXPECT_LT(fabs(new_odom.twist.twist.linear.x - old_odom.twist.twist.linear.x), 1.0 + VELOCITY_TOLERANCE); + EXPECT_LT(fabs(new_odom.twist.twist.angular.z - old_odom.twist.twist.angular.z), EPS); + + cmd_vel.linear.x = 0.0; + publish(cmd_vel); +} + +/* This test has been failing on Travis for a long time due to timing issues however it works well when ran manually +TEST_F(DiffDriveControllerTest, testAngularJerkLimits) +{ + // wait for ROS + while(!isControllerAlive()) + { + ros::Duration(0.1).sleep(); + } + // zero everything before test + geometry_msgs::Twist cmd_vel; + cmd_vel.linear.x = 0.0; + cmd_vel.angular.z = 0.0; + publish(cmd_vel); + ros::Duration(2.0).sleep(); + // get initial odom + nav_msgs::Odometry old_odom = getLastOdom(); + // send a big command + cmd_vel.angular.z = 10.0; + publish(cmd_vel); + // wait for a while + ros::Duration(0.5).sleep(); + + nav_msgs::Odometry new_odom = getLastOdom(); + + // check if the robot speed is now 0.7rad.s-1 + EXPECT_NEAR(new_odom.twist.twist.angular.z, 0.7, JERK_ANGULAR_VELOCITY_TOLERANCE); + EXPECT_LT(fabs(new_odom.twist.twist.linear.x - old_odom.twist.twist.linear.x), EPS); + + cmd_vel.angular.z = 0.0; + publish(cmd_vel); +} +*/ + +TEST_F(DiffDriveControllerTest, testAngularAccelerationLimits) +{ + // wait for ROS + while(!isControllerAlive()) + { + ros::Duration(0.1).sleep(); + } + // zero everything before test + geometry_msgs::Twist cmd_vel; + cmd_vel.linear.x = 0.0; + cmd_vel.angular.z = 0.0; + publish(cmd_vel); + ros::Duration(2.0).sleep(); + // get initial odom + nav_msgs::Odometry old_odom = getLastOdom(); + // send a big command + cmd_vel.angular.z = 10.0; + publish(cmd_vel); + // wait for a while + ros::Duration(0.5).sleep(); + + nav_msgs::Odometry new_odom = getLastOdom(); + + // check if the robot speed is now 1.0rad.s-1, which is 2.0rad.s-2 * 0.5s + EXPECT_LT(fabs(new_odom.twist.twist.angular.z - old_odom.twist.twist.angular.z), 1.0 + VELOCITY_TOLERANCE); + EXPECT_LT(fabs(new_odom.twist.twist.linear.x - old_odom.twist.twist.linear.x), EPS); + + cmd_vel.angular.z = 0.0; + publish(cmd_vel); +} + +TEST_F(DiffDriveControllerTest, testAngularVelocityLimits) +{ + // wait for ROS + while(!isControllerAlive()) + { + ros::Duration(0.1).sleep(); + } + // zero everything before test + geometry_msgs::Twist cmd_vel; + cmd_vel.linear.x = 0.0; + cmd_vel.angular.z = 0.0; + publish(cmd_vel); + ros::Duration(2.0).sleep(); + // get initial odom + nav_msgs::Odometry old_odom = getLastOdom(); + // send a big command + cmd_vel.angular.z = 10.0; + publish(cmd_vel); + // wait for a while + ros::Duration(5.0).sleep(); + + nav_msgs::Odometry new_odom = getLastOdom(); + + // check if the robot speed is now 2.0rad.s-1, the limit + EXPECT_LT(fabs(new_odom.twist.twist.angular.z - old_odom.twist.twist.angular.z), 2.0 + VELOCITY_TOLERANCE); + EXPECT_LT(fabs(new_odom.twist.twist.linear.x - old_odom.twist.twist.linear.x), EPS); + + cmd_vel.angular.z = 0.0; + publish(cmd_vel); +} + +int main(int argc, char** argv) +{ + testing::InitGoogleTest(&argc, argv); + ros::init(argc, argv, "diff_drive_limits_test"); + + ros::AsyncSpinner spinner(1); + spinner.start(); + //ros::Duration(0.5).sleep(); + int ret = RUN_ALL_TESTS(); + spinner.stop(); + ros::shutdown(); + return ret; +} diff --git a/mir_robot/diff_drive_controller/test/diff_drive_multiple_cmd_vel_publishers.test b/mir_robot/diff_drive_controller/test/diff_drive_multiple_cmd_vel_publishers.test new file mode 100755 index 0000000..6681cce --- /dev/null +++ b/mir_robot/diff_drive_controller/test/diff_drive_multiple_cmd_vel_publishers.test @@ -0,0 +1,24 @@ + + + + + + + + + + + + + + + + + + + + diff --git a/mir_robot/diff_drive_controller/test/diff_drive_multiple_cmd_vel_publishers_test.cpp b/mir_robot/diff_drive_controller/test/diff_drive_multiple_cmd_vel_publishers_test.cpp new file mode 100755 index 0000000..929abd1 --- /dev/null +++ b/mir_robot/diff_drive_controller/test/diff_drive_multiple_cmd_vel_publishers_test.cpp @@ -0,0 +1,72 @@ +/////////////////////////////////////////////////////////////////////////////// +// Copyright (C) 2014, PAL Robotics S.L. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of PAL Robotics, Inc. nor the names of its +// contributors may be used to endorse or promote products derived from +// this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +// POSSIBILITY OF SUCH DAMAGE. +////////////////////////////////////////////////////////////////////////////// + +/// \author Bence Magyar + +#include "test_common.h" + +// TEST CASES +TEST_F(DiffDriveControllerTest, breakWithMultiplePublishers) +{ + // wait for ROS + waitForController(); + waitForOdomMsgs(); + + nav_msgs::Odometry old_odom = getLastOdom(); + //TODO: we should be programatically publish from 2 different nodes + // not the current hacky solution with the launch files + ros::Duration(1.0).sleep(); + nav_msgs::Odometry new_odom = getLastOdom(); + + const double dx = new_odom.pose.pose.position.x - old_odom.pose.pose.position.x; + const double dy = new_odom.pose.pose.position.y - old_odom.pose.pose.position.y; + const double dz = new_odom.pose.pose.position.z - old_odom.pose.pose.position.z; + EXPECT_NEAR(sqrt(dx*dx + dy*dy), 0.0, POSITION_TOLERANCE); + EXPECT_LT(fabs(dz), EPS); + + // convert to rpy and test that way + double roll_old, pitch_old, yaw_old; + double roll_new, pitch_new, yaw_new; + tf::Matrix3x3(tfQuatFromGeomQuat(old_odom.pose.pose.orientation)).getRPY(roll_old, pitch_old, yaw_old); + tf::Matrix3x3(tfQuatFromGeomQuat(new_odom.pose.pose.orientation)).getRPY(roll_new, pitch_new, yaw_new); + EXPECT_LT(fabs(roll_new - roll_old), EPS); + EXPECT_LT(fabs(pitch_new - pitch_old), EPS); + EXPECT_LT(fabs(yaw_new - yaw_old), EPS); +} + +int main(int argc, char** argv) +{ + testing::InitGoogleTest(&argc, argv); + ros::init(argc, argv, "diff_drive_multiple_publishers_test"); + + ros::AsyncSpinner spinner(1); + spinner.start(); + int ret = RUN_ALL_TESTS(); + spinner.stop(); + ros::shutdown(); + return ret; +} diff --git a/mir_robot/diff_drive_controller/test/diff_drive_multipliers.test b/mir_robot/diff_drive_controller/test/diff_drive_multipliers.test new file mode 100755 index 0000000..e6d9f9e --- /dev/null +++ b/mir_robot/diff_drive_controller/test/diff_drive_multipliers.test @@ -0,0 +1,17 @@ + + + + + + + + + + + + + + diff --git a/mir_robot/diff_drive_controller/test/diff_drive_nan_test.cpp b/mir_robot/diff_drive_controller/test/diff_drive_nan_test.cpp new file mode 100755 index 0000000..769b42d --- /dev/null +++ b/mir_robot/diff_drive_controller/test/diff_drive_nan_test.cpp @@ -0,0 +1,131 @@ +/////////////////////////////////////////////////////////////////////////////// +// Copyright (C) 2014, PAL Robotics S.L. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of PAL Robotics, Inc. nor the names of its +// contributors may be used to endorse or promote products derived from +// this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +// POSSIBILITY OF SUCH DAMAGE. +////////////////////////////////////////////////////////////////////////////// + +/// \author Enrique Fernandez + +#include "test_common.h" + +// NaN +#include + +// TEST CASES +TEST_F(DiffDriveControllerTest, testNaN) { + // wait for ROS + waitForController(); + + // zero everything before test + geometry_msgs::Twist cmd_vel; + cmd_vel.linear.x = 0.0; + cmd_vel.angular.z = 0.0; + publish(cmd_vel); + ros::Duration(2.0).sleep(); + + // send a command + cmd_vel.linear.x = 0.1; + ros::Duration(2.0).sleep(); + + // stop robot (will generate NaN) + stop(); + ros::Duration(2.0).sleep(); + + nav_msgs::Odometry odom = getLastOdom(); + + EXPECT_FALSE(std::isnan(odom.twist.twist.linear.x)); + EXPECT_FALSE(std::isnan(odom.twist.twist.angular.z)); + EXPECT_FALSE(std::isnan(odom.pose.pose.position.x)); + EXPECT_FALSE(std::isnan(odom.pose.pose.position.y)); + EXPECT_FALSE(std::isnan(odom.pose.pose.orientation.z)); + EXPECT_FALSE(std::isnan(odom.pose.pose.orientation.w)); + + // start robot + start(); + ros::Duration(2.0).sleep(); + + odom = getLastOdom(); + + EXPECT_FALSE(std::isnan(odom.twist.twist.linear.x)); + EXPECT_FALSE(std::isnan(odom.twist.twist.angular.z)); + EXPECT_FALSE(std::isnan(odom.pose.pose.position.x)); + EXPECT_FALSE(std::isnan(odom.pose.pose.position.y)); + EXPECT_FALSE(std::isnan(odom.pose.pose.orientation.z)); + EXPECT_FALSE(std::isnan(odom.pose.pose.orientation.w)); +} + +TEST_F(DiffDriveControllerTest, testNaNCmd) { + // wait for ROS + while (!isControllerAlive()) { + ros::Duration(0.1).sleep(); + } + // zero everything before test + geometry_msgs::Twist cmd_vel; + cmd_vel.linear.x = 0.0; + cmd_vel.angular.z = 0.0; + publish(cmd_vel); + ros::Duration(0.1).sleep(); + + // send NaN + for (int i = 0; i < 10; ++i) { + geometry_msgs::Twist cmd_vel; + cmd_vel.linear.x = NAN; + cmd_vel.angular.z = 0.0; + publish(cmd_vel); + geometry_msgs::TwistStamped odom_msg = getLastCmdVelOut(); + EXPECT_FALSE(std::isnan(odom_msg.twist.linear.x)); + EXPECT_FALSE(std::isnan(odom_msg.twist.angular.z)); + ros::Duration(0.1).sleep(); + } + for (int i = 0; i < 10; ++i) { + geometry_msgs::Twist cmd_vel; + cmd_vel.linear.x = 0.0; + cmd_vel.angular.z = NAN; + publish(cmd_vel); + geometry_msgs::TwistStamped odom_msg = getLastCmdVelOut(); + EXPECT_FALSE(std::isnan(odom_msg.twist.linear.x)); + EXPECT_FALSE(std::isnan(odom_msg.twist.angular.z)); + ros::Duration(0.1).sleep(); + } + + nav_msgs::Odometry odom = getLastOdom(); + EXPECT_DOUBLE_EQ(odom.twist.twist.linear.x, 0.0); + EXPECT_DOUBLE_EQ(odom.pose.pose.position.x, 0.0); + EXPECT_DOUBLE_EQ(odom.pose.pose.position.y, 0.0); + + geometry_msgs::TwistStamped odom_msg = getLastCmdVelOut(); + EXPECT_DOUBLE_EQ(odom_msg.twist.linear.x, 0.0); +} + +int main(int argc, char **argv) { + testing::InitGoogleTest(&argc, argv); + ros::init(argc, argv, "diff_drive_nan_test"); + + ros::AsyncSpinner spinner(1); + spinner.start(); + int ret = RUN_ALL_TESTS(); + spinner.stop(); + ros::shutdown(); + return ret; +} diff --git a/mir_robot/diff_drive_controller/test/diff_drive_odom_frame.test b/mir_robot/diff_drive_controller/test/diff_drive_odom_frame.test new file mode 100755 index 0000000..7ac4072 --- /dev/null +++ b/mir_robot/diff_drive_controller/test/diff_drive_odom_frame.test @@ -0,0 +1,20 @@ + + + + + + + + diffbot_controller: + odom_frame_id: new_odom + + + + + + + + diff --git a/mir_robot/diff_drive_controller/test/diff_drive_odom_frame_test.cpp b/mir_robot/diff_drive_controller/test/diff_drive_odom_frame_test.cpp new file mode 100755 index 0000000..ea86e40 --- /dev/null +++ b/mir_robot/diff_drive_controller/test/diff_drive_odom_frame_test.cpp @@ -0,0 +1,83 @@ +/////////////////////////////////////////////////////////////////////////////// +// Copyright (C) 2015, Locus Robotics Corp. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of PAL Robotics, Inc. nor the names of its +// contributors may be used to endorse or promote products derived from +// this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +// POSSIBILITY OF SUCH DAMAGE. +////////////////////////////////////////////////////////////////////////////// + +/// \author Eric Tappan + +#include "test_common.h" +#include + +// TEST CASES +TEST_F(DiffDriveControllerTest, testNoOdomFrame) +{ + // wait for ROS + waitForController(); + + // set up tf listener + tf::TransformListener listener; + ros::Duration(2.0).sleep(); + // check the original odom frame doesn't exist + EXPECT_FALSE(listener.frameExists("odom")); +} + +TEST_F(DiffDriveControllerTest, testNewOdomFrame) +{ + // wait for ROS + waitForController(); + + // set up tf listener + tf::TransformListener listener; + ros::Duration(2.0).sleep(); + // check the new_odom frame does exist + EXPECT_TRUE(listener.frameExists("new_odom")); +} + +TEST_F(DiffDriveControllerTest, testOdomTopic) +{ + // wait for ROS + waitForController(); + + // wait until we received first odom msg + waitForOdomMsgs(); + + // get an odom message + nav_msgs::Odometry odom_msg = getLastOdom(); + // check its frame_id + ASSERT_STREQ(odom_msg.header.frame_id.c_str(), "new_odom"); +} + +int main(int argc, char** argv) +{ + testing::InitGoogleTest(&argc, argv); + ros::init(argc, argv, "diff_drive_odom_frame_test"); + + ros::AsyncSpinner spinner(1); + spinner.start(); + int ret = RUN_ALL_TESTS(); + spinner.stop(); + ros::shutdown(); + return ret; +} diff --git a/mir_robot/diff_drive_controller/test/diff_drive_odom_tf.test b/mir_robot/diff_drive_controller/test/diff_drive_odom_tf.test new file mode 100755 index 0000000..117a630 --- /dev/null +++ b/mir_robot/diff_drive_controller/test/diff_drive_odom_tf.test @@ -0,0 +1,20 @@ + + + + + + + + diffbot_controller: + enable_odom_tf: False + + + + + + + + diff --git a/mir_robot/diff_drive_controller/test/diff_drive_odom_tf_test.cpp b/mir_robot/diff_drive_controller/test/diff_drive_odom_tf_test.cpp new file mode 100755 index 0000000..fef3096 --- /dev/null +++ b/mir_robot/diff_drive_controller/test/diff_drive_odom_tf_test.cpp @@ -0,0 +1,57 @@ +/////////////////////////////////////////////////////////////////////////////// +// Copyright (C) 2014, PAL Robotics S.L. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of PAL Robotics, Inc. nor the names of its +// contributors may be used to endorse or promote products derived from +// this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +// POSSIBILITY OF SUCH DAMAGE. +////////////////////////////////////////////////////////////////////////////// + +/// \author Bence Magyar + +#include "test_common.h" +#include + +// TEST CASES +TEST_F(DiffDriveControllerTest, testNoOdomFrame) +{ + // wait for ROS + waitForController(); + + // set up tf listener + tf::TransformListener listener; + ros::Duration(2.0).sleep(); + // check the odom frame doesn't exist + EXPECT_FALSE(listener.frameExists("odom")); +} + +int main(int argc, char** argv) +{ + testing::InitGoogleTest(&argc, argv); + ros::init(argc, argv, "diff_drive_odom_tf_test"); + + ros::AsyncSpinner spinner(1); + spinner.start(); + int ret = RUN_ALL_TESTS(); + spinner.stop(); + ros::shutdown(); + return ret; +} diff --git a/mir_robot/diff_drive_controller/test/diff_drive_open_loop.test b/mir_robot/diff_drive_controller/test/diff_drive_open_loop.test new file mode 100755 index 0000000..c6484b3 --- /dev/null +++ b/mir_robot/diff_drive_controller/test/diff_drive_open_loop.test @@ -0,0 +1,17 @@ + + + + + + + + + + + + + + diff --git a/mir_robot/diff_drive_controller/test/diff_drive_pub_cmd_vel_out.test b/mir_robot/diff_drive_controller/test/diff_drive_pub_cmd_vel_out.test new file mode 100755 index 0000000..3734c37 --- /dev/null +++ b/mir_robot/diff_drive_controller/test/diff_drive_pub_cmd_vel_out.test @@ -0,0 +1,20 @@ + + + + + + + diffbot_controller: + publish_cmd: True + + + + + + + + + diff --git a/mir_robot/diff_drive_controller/test/diff_drive_pub_cmd_vel_out_test.cpp b/mir_robot/diff_drive_controller/test/diff_drive_pub_cmd_vel_out_test.cpp new file mode 100755 index 0000000..88c4e11 --- /dev/null +++ b/mir_robot/diff_drive_controller/test/diff_drive_pub_cmd_vel_out_test.cpp @@ -0,0 +1,74 @@ +/////////////////////////////////////////////////////////////////////////////// +// Copyright (C) 2017, PAL Robotics. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of PAL Robotics, Inc. nor the names of its +// contributors may be used to endorse or promote products derived from +// this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +// POSSIBILITY OF SUCH DAMAGE. +////////////////////////////////////////////////////////////////////////////// + +/// \author Jeremie Deray + +#include "test_common.h" + +// TEST CASES +TEST_F(DiffDriveControllerTest, testCmdVelOutTopic) +{ + // wait for ROS + waitForController(); + // msgs are published in the same loop + // thus if odom is published cmd_vel_out + // should be as well (if enabled) + waitForOdomMsgs(); + + EXPECT_TRUE(isPublishingCmdVelOut()); + + // zero everything before test + geometry_msgs::Twist cmd_vel; + cmd_vel.linear.x = 0.0; + cmd_vel.angular.z = 0.0; + publish(cmd_vel); + ros::Duration(0.1).sleep(); + + cmd_vel.linear.x = 0.1; + publish(cmd_vel); + ros::Duration(0.1).sleep(); + + EXPECT_TRUE(isPublishingCmdVelOut()); + + // get a twist message + geometry_msgs::TwistStamped odom_msg = getLastCmdVelOut(); + + EXPECT_GT(fabs(odom_msg.twist.linear.x), 0); +} + +int main(int argc, char** argv) +{ + testing::InitGoogleTest(&argc, argv); + ros::init(argc, argv, "diff_drive_pub_cmd_vel_out_topic_test"); + + ros::AsyncSpinner spinner(1); + spinner.start(); + int ret = RUN_ALL_TESTS(); + spinner.stop(); + ros::shutdown(); + return ret; +} diff --git a/mir_robot/diff_drive_controller/test/diff_drive_publish_wheel_joint_controller_state.test b/mir_robot/diff_drive_controller/test/diff_drive_publish_wheel_joint_controller_state.test new file mode 100755 index 0000000..d4f9fff --- /dev/null +++ b/mir_robot/diff_drive_controller/test/diff_drive_publish_wheel_joint_controller_state.test @@ -0,0 +1,21 @@ + + + + + + + + diffbot_controller: + publish_wheel_joint_controller_state: True + + + + + + + + + diff --git a/mir_robot/diff_drive_controller/test/diff_drive_publish_wheel_joint_controller_state_test.cpp b/mir_robot/diff_drive_controller/test/diff_drive_publish_wheel_joint_controller_state_test.cpp new file mode 100755 index 0000000..300353d --- /dev/null +++ b/mir_robot/diff_drive_controller/test/diff_drive_publish_wheel_joint_controller_state_test.cpp @@ -0,0 +1,65 @@ +/////////////////////////////////////////////////////////////////////////////// +// Copyright (C) 2018, PAL Robotics. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of PAL Robotics, Inc. nor the names of its +// contributors may be used to endorse or promote products derived from +// this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +// POSSIBILITY OF SUCH DAMAGE. +////////////////////////////////////////////////////////////////////////////// + +/// \author Jeremie Deray + +#include "test_common.h" + +// TEST CASES +TEST_F(DiffDriveControllerTest, testPublishJointTrajectoryControllerStateTopic) +{ + // wait for ROS + waitForController(); + + EXPECT_TRUE(isPublishingJointTrajectoryControllerState()); + + // zero everything before test + geometry_msgs::Twist cmd_vel; + cmd_vel.linear.x = 0.0; + cmd_vel.angular.z = 0.0; + publish(cmd_vel); + ros::Duration(0.1).sleep(); + + cmd_vel.linear.x = 0.1; + publish(cmd_vel); + ros::Duration(0.1).sleep(); + + EXPECT_TRUE(isPublishingJointTrajectoryControllerState()); +} + +int main(int argc, char** argv) +{ + testing::InitGoogleTest(&argc, argv); + ros::init(argc, argv, "diff_drive_publish_wheel_joint_controller_state_topic_test"); + + ros::AsyncSpinner spinner(1); + spinner.start(); + int ret = RUN_ALL_TESTS(); + spinner.stop(); + ros::shutdown(); + return ret; +} diff --git a/mir_robot/diff_drive_controller/test/diff_drive_radius_param.test b/mir_robot/diff_drive_controller/test/diff_drive_radius_param.test new file mode 100755 index 0000000..3baa691 --- /dev/null +++ b/mir_robot/diff_drive_controller/test/diff_drive_radius_param.test @@ -0,0 +1,20 @@ + + + + + + + + + + + + + + + + diff --git a/mir_robot/diff_drive_controller/test/diff_drive_radius_param_fail.test b/mir_robot/diff_drive_controller/test/diff_drive_radius_param_fail.test new file mode 100755 index 0000000..9fb9ac7 --- /dev/null +++ b/mir_robot/diff_drive_controller/test/diff_drive_radius_param_fail.test @@ -0,0 +1,20 @@ + + + + + + + + + + + + + + + + diff --git a/mir_robot/diff_drive_controller/test/diff_drive_radius_sphere.test b/mir_robot/diff_drive_controller/test/diff_drive_radius_sphere.test new file mode 100755 index 0000000..24e1b75 --- /dev/null +++ b/mir_robot/diff_drive_controller/test/diff_drive_radius_sphere.test @@ -0,0 +1,20 @@ + + + + + + + + + + + + + + + + diff --git a/mir_robot/diff_drive_controller/test/diff_drive_separation_param.test b/mir_robot/diff_drive_controller/test/diff_drive_separation_param.test new file mode 100755 index 0000000..07c7afb --- /dev/null +++ b/mir_robot/diff_drive_controller/test/diff_drive_separation_param.test @@ -0,0 +1,22 @@ + + + + + + + + + + + + + + + + + + diff --git a/mir_robot/diff_drive_controller/test/diff_drive_test.cpp b/mir_robot/diff_drive_controller/test/diff_drive_test.cpp new file mode 100755 index 0000000..d89fde9 --- /dev/null +++ b/mir_robot/diff_drive_controller/test/diff_drive_test.cpp @@ -0,0 +1,154 @@ +/////////////////////////////////////////////////////////////////////////////// +// Copyright (C) 2013, PAL Robotics S.L. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of PAL Robotics, Inc. nor the names of its +// contributors may be used to endorse or promote products derived from +// this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +// POSSIBILITY OF SUCH DAMAGE. +////////////////////////////////////////////////////////////////////////////// + +/// \author Bence Magyar + +#include "test_common.h" +#include + +// TEST CASES +TEST_F(DiffDriveControllerTest, testForward) +{ + // wait for ROS + waitForController(); + + // zero everything before test + geometry_msgs::Twist cmd_vel; + cmd_vel.linear.x = 0.0; + cmd_vel.angular.z = 0.0; + publish(cmd_vel); + ros::Duration(2.0).sleep(); + // get initial odom + nav_msgs::Odometry old_odom = getLastOdom(); + // send a velocity command of 0.1 m/s + cmd_vel.linear.x = 0.1; + publish(cmd_vel); + // wait for 10s + ros::Duration(10.0).sleep(); + + nav_msgs::Odometry new_odom = getLastOdom(); + + const ros::Duration actual_elapsed_time = new_odom.header.stamp - old_odom.header.stamp; + + const double expected_distance = cmd_vel.linear.x * actual_elapsed_time.toSec(); + + // check if the robot traveled 1 meter in XY plane, changes in z should be ~~0 + const double dx = new_odom.pose.pose.position.x - old_odom.pose.pose.position.x; + const double dy = new_odom.pose.pose.position.y - old_odom.pose.pose.position.y; + const double dz = new_odom.pose.pose.position.z - old_odom.pose.pose.position.z; + EXPECT_NEAR(sqrt(dx*dx + dy*dy), expected_distance, POSITION_TOLERANCE); + EXPECT_LT(fabs(dz), EPS); + + // convert to rpy and test that way + double roll_old, pitch_old, yaw_old; + double roll_new, pitch_new, yaw_new; + tf::Matrix3x3(tfQuatFromGeomQuat(old_odom.pose.pose.orientation)).getRPY(roll_old, pitch_old, yaw_old); + tf::Matrix3x3(tfQuatFromGeomQuat(new_odom.pose.pose.orientation)).getRPY(roll_new, pitch_new, yaw_new); + EXPECT_LT(fabs(roll_new - roll_old), EPS); + EXPECT_LT(fabs(pitch_new - pitch_old), EPS); + EXPECT_LT(fabs(yaw_new - yaw_old), EPS); + EXPECT_NEAR(fabs(new_odom.twist.twist.linear.x), cmd_vel.linear.x, EPS); + EXPECT_LT(fabs(new_odom.twist.twist.linear.y), EPS); + EXPECT_LT(fabs(new_odom.twist.twist.linear.z), EPS); + + EXPECT_LT(fabs(new_odom.twist.twist.angular.x), EPS); + EXPECT_LT(fabs(new_odom.twist.twist.angular.y), EPS); + EXPECT_LT(fabs(new_odom.twist.twist.angular.z), EPS); +} + +TEST_F(DiffDriveControllerTest, testTurn) +{ + // wait for ROS + waitForController(); + + // zero everything before test + geometry_msgs::Twist cmd_vel; + cmd_vel.linear.x = 0.0; + cmd_vel.angular.z = 0.0; + publish(cmd_vel); + ros::Duration(2.0).sleep(); + // get initial odom + nav_msgs::Odometry old_odom = getLastOdom(); + // send a velocity command + cmd_vel.angular.z = M_PI/10.0; + publish(cmd_vel); + // wait for 10s + ros::Duration(10.0).sleep(); + + nav_msgs::Odometry new_odom = getLastOdom(); + + // check if the robot rotated PI around z, changes in the other fields should be ~~0 + EXPECT_LT(fabs(new_odom.pose.pose.position.x - old_odom.pose.pose.position.x), EPS); + EXPECT_LT(fabs(new_odom.pose.pose.position.y - old_odom.pose.pose.position.y), EPS); + EXPECT_LT(fabs(new_odom.pose.pose.position.z - old_odom.pose.pose.position.z), EPS); + + const ros::Duration actual_elapsed_time = new_odom.header.stamp - old_odom.header.stamp; + const double expected_rotation = cmd_vel.angular.z * actual_elapsed_time.toSec(); + + // convert to rpy and test that way + double roll_old, pitch_old, yaw_old; + double roll_new, pitch_new, yaw_new; + tf::Matrix3x3(tfQuatFromGeomQuat(old_odom.pose.pose.orientation)).getRPY(roll_old, pitch_old, yaw_old); + tf::Matrix3x3(tfQuatFromGeomQuat(new_odom.pose.pose.orientation)).getRPY(roll_new, pitch_new, yaw_new); + EXPECT_LT(fabs(roll_new - roll_old), EPS); + EXPECT_LT(fabs(pitch_new - pitch_old), EPS); + EXPECT_NEAR(fabs(yaw_new - yaw_old), expected_rotation, ORIENTATION_TOLERANCE); + + EXPECT_LT(fabs(new_odom.twist.twist.linear.x), EPS); + EXPECT_LT(fabs(new_odom.twist.twist.linear.y), EPS); + EXPECT_LT(fabs(new_odom.twist.twist.linear.z), EPS); + + EXPECT_LT(fabs(new_odom.twist.twist.angular.x), EPS); + EXPECT_LT(fabs(new_odom.twist.twist.angular.y), EPS); + EXPECT_NEAR(fabs(new_odom.twist.twist.angular.z), expected_rotation/actual_elapsed_time.toSec(), EPS); +} + +TEST_F(DiffDriveControllerTest, testOdomFrame) +{ + // wait for ROS + waitForController(); + + // set up tf listener + tf::TransformListener listener; + ros::Duration(2.0).sleep(); + // check the odom frame exist + EXPECT_TRUE(listener.frameExists("odom")); +} + +int main(int argc, char** argv) +{ + testing::InitGoogleTest(&argc, argv); + ros::init(argc, argv, "diff_drive_test"); + + ros::AsyncSpinner spinner(1); + spinner.start(); + //ros::Duration(0.5).sleep(); + int ret = RUN_ALL_TESTS(); + spinner.stop(); + ros::shutdown(); + return ret; +} diff --git a/mir_robot/diff_drive_controller/test/diff_drive_timeout.test b/mir_robot/diff_drive_controller/test/diff_drive_timeout.test new file mode 100755 index 0000000..b55a16f --- /dev/null +++ b/mir_robot/diff_drive_controller/test/diff_drive_timeout.test @@ -0,0 +1,17 @@ + + + + + + + + + + + + + + diff --git a/mir_robot/diff_drive_controller/test/diff_drive_timeout_test.cpp b/mir_robot/diff_drive_controller/test/diff_drive_timeout_test.cpp new file mode 100755 index 0000000..1f822ce --- /dev/null +++ b/mir_robot/diff_drive_controller/test/diff_drive_timeout_test.cpp @@ -0,0 +1,70 @@ +/////////////////////////////////////////////////////////////////////////////// +// Copyright (C) 2013, PAL Robotics S.L. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of PAL Robotics, Inc. nor the names of its +// contributors may be used to endorse or promote products derived from +// this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +// POSSIBILITY OF SUCH DAMAGE. +////////////////////////////////////////////////////////////////////////////// + +/// \author Paul Mathieu + +#include "test_common.h" + +// TEST CASES +TEST_F(DiffDriveControllerTest, testTimeout) +{ + // wait for ROS + waitForController(); + + // zero everything before test + geometry_msgs::Twist cmd_vel; + cmd_vel.linear.x = 0.0; + cmd_vel.angular.z = 0.0; + publish(cmd_vel); + // give some time to the controller to react to the command + ros::Duration(0.1).sleep(); + // get initial odom + nav_msgs::Odometry old_odom = getLastOdom(); + // send a velocity command of 1 m/s + cmd_vel.linear.x = 1.0; + publish(cmd_vel); + // wait a bit + ros::Duration(3.0).sleep(); + + nav_msgs::Odometry new_odom = getLastOdom(); + + // check if the robot has stopped after 0.5s, thus covering less than 0.5s*1.0m.s-1 + some (big) tolerance + EXPECT_LT(fabs(new_odom.pose.pose.position.x - old_odom.pose.pose.position.x), 0.8); +} + +int main(int argc, char** argv) +{ + testing::InitGoogleTest(&argc, argv); + ros::init(argc, argv, "diff_drive_test"); + + ros::AsyncSpinner spinner(1); + spinner.start(); + int ret = RUN_ALL_TESTS(); + spinner.stop(); + ros::shutdown(); + return ret; +} diff --git a/mir_robot/diff_drive_controller/test/diff_drive_wrong.test b/mir_robot/diff_drive_controller/test/diff_drive_wrong.test new file mode 100755 index 0000000..6efbf73 --- /dev/null +++ b/mir_robot/diff_drive_controller/test/diff_drive_wrong.test @@ -0,0 +1,17 @@ + + + + + + + + + + + + + + diff --git a/mir_robot/diff_drive_controller/test/diffbot.cpp b/mir_robot/diff_drive_controller/test/diffbot.cpp new file mode 100755 index 0000000..0b69273 --- /dev/null +++ b/mir_robot/diff_drive_controller/test/diffbot.cpp @@ -0,0 +1,93 @@ +/////////////////////////////////////////////////////////////////////////////// +// Copyright (C) 2013, PAL Robotics S.L. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of PAL Robotics, Inc. nor the names of its +// contributors may be used to endorse or promote products derived from +// this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +// POSSIBILITY OF SUCH DAMAGE. +////////////////////////////////////////////////////////////////////////////// + +// NOTE: The contents of this file have been taken largely from the ros_control wiki tutorials + +#include "diffbot.h" +#include +#include +#include +#include +#include + +int main(int argc, char **argv) +{ + ros::init(argc, argv, "diffbot"); + ros::NodeHandle nh; + + // This should be set in launch files as well + nh.setParam("/use_sim_time", true); + + Diffbot<> robot; + ROS_WARN_STREAM("period: " << robot.getPeriod().toSec()); + controller_manager::ControllerManager cm(&robot, nh); + + ros::Publisher clock_publisher = nh.advertise("/clock", 1); + + ros::AsyncSpinner spinner(1); + spinner.start(); + + std::chrono::system_clock::time_point begin = std::chrono::system_clock::now(); + std::chrono::system_clock::time_point end = std::chrono::system_clock::now(); + + ros::Time internal_time(0); + const ros::Duration dt = robot.getPeriod(); + double elapsed_secs = 0; + + while(ros::ok()) + { + begin = std::chrono::system_clock::now(); + + robot.read(); + cm.update(internal_time, dt); + + robot.write(); + + end = std::chrono::system_clock::now(); + + elapsed_secs = std::chrono::duration_cast >((end - begin)).count(); + + if (dt.toSec() - elapsed_secs < 0.0) + { + ROS_WARN_STREAM_THROTTLE( + 0.1, "Control cycle is taking to much time, elapsed: " << elapsed_secs); + } + else + { + ROS_DEBUG_STREAM_THROTTLE(1.0, "Control cycle is, elapsed: " << elapsed_secs); + std::this_thread::sleep_for(std::chrono::duration(dt.toSec() - elapsed_secs)); + } + + rosgraph_msgs::Clock clock; + clock.clock = ros::Time(internal_time); + clock_publisher.publish(clock); + internal_time += dt; + } + spinner.stop(); + + return 0; +} diff --git a/mir_robot/diff_drive_controller/test/diffbot.h b/mir_robot/diff_drive_controller/test/diffbot.h new file mode 100755 index 0000000..6c8b9cd --- /dev/null +++ b/mir_robot/diff_drive_controller/test/diffbot.h @@ -0,0 +1,143 @@ +/////////////////////////////////////////////////////////////////////////////// +// Copyright (C) 2013, PAL Robotics S.L. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of PAL Robotics, Inc. nor the names of its +// contributors may be used to endorse or promote products derived from +// this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +// POSSIBILITY OF SUCH DAMAGE. +////////////////////////////////////////////////////////////////////////////// + +// NOTE: The contents of this file have been taken largely from the ros_control wiki tutorials + +#pragma once + + +// ROS +#include +#include + +// ros_control +#include +#include +#include +#include +#include + +// NaN +#include + +// ostringstream +#include + +template +class Diffbot : public hardware_interface::RobotHW +{ +public: + Diffbot() + : running_(true) + , start_srv_(nh_.advertiseService("start", &Diffbot::start_callback, this)) + , stop_srv_(nh_.advertiseService("stop", &Diffbot::stop_callback, this)) + { + // Intialize raw data + std::fill_n(pos_, NUM_JOINTS, 0.0); + std::fill_n(vel_, NUM_JOINTS, 0.0); + std::fill_n(eff_, NUM_JOINTS, 0.0); + std::fill_n(cmd_, NUM_JOINTS, 0.0); + + // Connect and register the joint state and velocity interface + for (unsigned int i = 0; i < NUM_JOINTS; ++i) + { + std::ostringstream os; + os << "wheel_" << i << "_joint"; + + hardware_interface::JointStateHandle state_handle(os.str(), &pos_[i], &vel_[i], &eff_[i]); + jnt_state_interface_.registerHandle(state_handle); + + hardware_interface::JointHandle vel_handle(jnt_state_interface_.getHandle(os.str()), &cmd_[i]); + jnt_vel_interface_.registerHandle(vel_handle); + } + + registerInterface(&jnt_state_interface_); + registerInterface(&jnt_vel_interface_); + } + + ros::Time getTime() const {return ros::Time::now();} + ros::Duration getPeriod() const {return ros::Duration(0.01);} + + void read() + { + // Read the joint state of the robot into the hardware interface + if (running_) + { + for (unsigned int i = 0; i < NUM_JOINTS; ++i) + { + // Note that pos_[i] will be NaN for one more cycle after we start(), + // but that is consistent with the knowledge we have about the state + // of the robot. + pos_[i] += vel_[i]*getPeriod().toSec(); // update position + vel_[i] = cmd_[i]; // might add smoothing here later + } + } + else + { + std::fill_n(pos_, NUM_JOINTS, std::numeric_limits::quiet_NaN()); + std::fill_n(vel_, NUM_JOINTS, std::numeric_limits::quiet_NaN()); + } + } + + void write() + { + // Write the commands to the joints + std::ostringstream os; + for (unsigned int i = 0; i < NUM_JOINTS - 1; ++i) + { + os << cmd_[i] << ", "; + } + os << cmd_[NUM_JOINTS - 1]; + + ROS_INFO_STREAM("Commands for joints: " << os.str()); + } + + bool start_callback(std_srvs::Empty::Request& /*req*/, std_srvs::Empty::Response& /*res*/) + { + running_ = true; + return true; + } + + bool stop_callback(std_srvs::Empty::Request& /*req*/, std_srvs::Empty::Response& /*res*/) + { + running_ = false; + return true; + } + +private: + hardware_interface::JointStateInterface jnt_state_interface_; + hardware_interface::VelocityJointInterface jnt_vel_interface_; + double cmd_[NUM_JOINTS]; + double pos_[NUM_JOINTS]; + double vel_[NUM_JOINTS]; + double eff_[NUM_JOINTS]; + bool running_; + + ros::NodeHandle nh_; + ros::ServiceServer start_srv_; + ros::ServiceServer stop_srv_; +}; diff --git a/mir_robot/diff_drive_controller/test/diffbot.xacro b/mir_robot/diff_drive_controller/test/diffbot.xacro new file mode 100755 index 0000000..c9b96c2 --- /dev/null +++ b/mir_robot/diff_drive_controller/test/diffbot.xacro @@ -0,0 +1,77 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Gazebo/Green + + + + Gazebo/Purple + + + diff --git a/mir_robot/diff_drive_controller/test/diffbot_bad.xacro b/mir_robot/diff_drive_controller/test/diffbot_bad.xacro new file mode 100755 index 0000000..ec88c38 --- /dev/null +++ b/mir_robot/diff_drive_controller/test/diffbot_bad.xacro @@ -0,0 +1,142 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 1 + 1 + + + + + + 1 + 1 + + + + + Gazebo/Green + + + + Gazebo/Red + + + + Gazebo/Blue + + + + Gazebo/Purple + + + diff --git a/mir_robot/diff_drive_controller/test/diffbot_controllers.yaml b/mir_robot/diff_drive_controller/test/diffbot_controllers.yaml new file mode 100755 index 0000000..f89c38c --- /dev/null +++ b/mir_robot/diff_drive_controller/test/diffbot_controllers.yaml @@ -0,0 +1,8 @@ +diffbot_controller: + type: "diff_drive_controller/DiffDriveController" + left_wheel: 'wheel_0_joint' + right_wheel: 'wheel_1_joint' + publish_rate: 50.0 # defaults to 50 + pose_covariance_diagonal: [0.001, 0.001, 1000000.0, 1000000.0, 1000000.0, 1000.0] + twist_covariance_diagonal: [0.001, 0.001, 1000000.0, 1000000.0, 1000000.0, 1000.0] + cmd_vel_timeout: 20.0 # we test this separately, give plenty for the other tests diff --git a/mir_robot/diff_drive_controller/test/diffbot_left_right_multipliers.yaml b/mir_robot/diff_drive_controller/test/diffbot_left_right_multipliers.yaml new file mode 100755 index 0000000..26b21eb --- /dev/null +++ b/mir_robot/diff_drive_controller/test/diffbot_left_right_multipliers.yaml @@ -0,0 +1,4 @@ +diffbot_controller: + wheel_separation_multiplier: 2.3 + left_wheel_radius_multiplier: 1.4 + right_wheel_radius_multiplier: 1.4 diff --git a/mir_robot/diff_drive_controller/test/diffbot_limits.yaml b/mir_robot/diff_drive_controller/test/diffbot_limits.yaml new file mode 100755 index 0000000..78f0bf9 --- /dev/null +++ b/mir_robot/diff_drive_controller/test/diffbot_limits.yaml @@ -0,0 +1,19 @@ +diffbot_controller: + linear: + x: + has_velocity_limits: true + min_velocity: -0.5 + max_velocity: 1.0 + has_acceleration_limits: true + min_acceleration: -0.5 + max_acceleration: 1.0 + has_jerk_limits: true + max_jerk: 5.0 + angular: + z: + has_velocity_limits: true + max_velocity: 2.0 + has_acceleration_limits: true + max_acceleration: 2.0 + has_jerk_limits: true + max_jerk: 10.0 diff --git a/mir_robot/diff_drive_controller/test/diffbot_multipliers.yaml b/mir_robot/diff_drive_controller/test/diffbot_multipliers.yaml new file mode 100755 index 0000000..d2ef5d5 --- /dev/null +++ b/mir_robot/diff_drive_controller/test/diffbot_multipliers.yaml @@ -0,0 +1,3 @@ +diffbot_controller: + wheel_separation_multiplier: 2.3 + wheel_radius_multiplier: 1.4 diff --git a/mir_robot/diff_drive_controller/test/diffbot_open_loop.yaml b/mir_robot/diff_drive_controller/test/diffbot_open_loop.yaml new file mode 100755 index 0000000..19224f3 --- /dev/null +++ b/mir_robot/diff_drive_controller/test/diffbot_open_loop.yaml @@ -0,0 +1,2 @@ +diffbot_controller: + open_loop: true diff --git a/mir_robot/diff_drive_controller/test/diffbot_sphere_wheels.xacro b/mir_robot/diff_drive_controller/test/diffbot_sphere_wheels.xacro new file mode 100755 index 0000000..90b2962 --- /dev/null +++ b/mir_robot/diff_drive_controller/test/diffbot_sphere_wheels.xacro @@ -0,0 +1,75 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Gazebo/Green + + + + Gazebo/Purple + + + diff --git a/mir_robot/diff_drive_controller/test/diffbot_square_wheels.xacro b/mir_robot/diff_drive_controller/test/diffbot_square_wheels.xacro new file mode 100755 index 0000000..a87ef57 --- /dev/null +++ b/mir_robot/diff_drive_controller/test/diffbot_square_wheels.xacro @@ -0,0 +1,75 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Gazebo/Green + + + + Gazebo/Purple + + + diff --git a/mir_robot/diff_drive_controller/test/diffbot_timeout.yaml b/mir_robot/diff_drive_controller/test/diffbot_timeout.yaml new file mode 100755 index 0000000..4ecfa18 --- /dev/null +++ b/mir_robot/diff_drive_controller/test/diffbot_timeout.yaml @@ -0,0 +1,2 @@ +diffbot_controller: + cmd_vel_timeout: 0.5 diff --git a/mir_robot/diff_drive_controller/test/diffbot_wrong.yaml b/mir_robot/diff_drive_controller/test/diffbot_wrong.yaml new file mode 100755 index 0000000..516fd75 --- /dev/null +++ b/mir_robot/diff_drive_controller/test/diffbot_wrong.yaml @@ -0,0 +1,8 @@ +diffbot_controller: + type: "diff_drive_controller/DiffDriveController" + left_wheel: 'this_joint_does_not_exist' + right_wheel: 'right_wheel_joint' + publish_rate: 50.0 # defaults to 50 + pose_covariance_diagonal: [0.001, 0.001, 1000000.0, 1000000.0, 1000000.0, 1000.0] + twist_covariance_diagonal: [0.001, 0.001, 1000000.0, 1000000.0, 1000000.0, 1000.0] + cmd_vel_timeout: 20.0 # we test this separately, give plenty for the other tests diff --git a/mir_robot/diff_drive_controller/test/skid_steer_common.launch b/mir_robot/diff_drive_controller/test/skid_steer_common.launch new file mode 100755 index 0000000..378ccdb --- /dev/null +++ b/mir_robot/diff_drive_controller/test/skid_steer_common.launch @@ -0,0 +1,35 @@ + + + + True + + + + + + + + + + + + + + + + diff --git a/mir_robot/diff_drive_controller/test/skid_steer_controller.test b/mir_robot/diff_drive_controller/test/skid_steer_controller.test new file mode 100755 index 0000000..1c47937 --- /dev/null +++ b/mir_robot/diff_drive_controller/test/skid_steer_controller.test @@ -0,0 +1,14 @@ + + + + + + + + + + + diff --git a/mir_robot/diff_drive_controller/test/skid_steer_no_wheels.test b/mir_robot/diff_drive_controller/test/skid_steer_no_wheels.test new file mode 100755 index 0000000..bb0d9bc --- /dev/null +++ b/mir_robot/diff_drive_controller/test/skid_steer_no_wheels.test @@ -0,0 +1,17 @@ + + + + + + + + + + + + + + diff --git a/mir_robot/diff_drive_controller/test/skidsteerbot.cpp b/mir_robot/diff_drive_controller/test/skidsteerbot.cpp new file mode 100755 index 0000000..05852f3 --- /dev/null +++ b/mir_robot/diff_drive_controller/test/skidsteerbot.cpp @@ -0,0 +1,93 @@ +/////////////////////////////////////////////////////////////////////////////// +// Copyright (C) 2013, PAL Robotics S.L. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of PAL Robotics, Inc. nor the names of its +// contributors may be used to endorse or promote products derived from +// this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +// POSSIBILITY OF SUCH DAMAGE. +////////////////////////////////////////////////////////////////////////////// + +// NOTE: The contents of this file have been taken largely from the ros_control wiki tutorials + +#include "diffbot.h" +#include +#include +#include +#include +#include + +int main(int argc, char **argv) +{ + ros::init(argc, argv, "skidsteerbot"); + ros::NodeHandle nh; + + // This should be set in launch files as well + nh.setParam("/use_sim_time", true); + + Diffbot<6> robot; + ROS_WARN_STREAM("period: " << robot.getPeriod().toSec()); + controller_manager::ControllerManager cm(&robot, nh); + + ros::Publisher clock_publisher = nh.advertise("/clock", 1); + + //ros::Rate rate(1.0 / robot.getPeriod().toSec()); + ros::AsyncSpinner spinner(1); + spinner.start(); + + std::chrono::system_clock::time_point begin = std::chrono::system_clock::now(); + std::chrono::system_clock::time_point end = std::chrono::system_clock::now(); + + ros::Time internal_time(0); + const ros::Duration dt = robot.getPeriod(); + double elapsed_secs = 0; + + while(ros::ok()) + { + begin = std::chrono::system_clock::now(); + + robot.read(); + cm.update(internal_time, dt); + robot.write(); + + end = std::chrono::system_clock::now(); + + elapsed_secs = std::chrono::duration_cast >((end - begin)).count(); + + if (dt.toSec() - elapsed_secs < 0.0) + { + ROS_WARN_STREAM_THROTTLE( + 0.1, "Control cycle is taking to much time, elapsed: " << elapsed_secs); + } + else + { + ROS_DEBUG_STREAM_THROTTLE(1.0, "Control cycle is, elapsed: " << elapsed_secs); + std::this_thread::sleep_for(std::chrono::duration(dt.toSec() - elapsed_secs)); + } + + rosgraph_msgs::Clock clock; + clock.clock = ros::Time(internal_time); + clock_publisher.publish(clock); + internal_time += dt; + } + spinner.stop(); + + return 0; +} diff --git a/mir_robot/diff_drive_controller/test/skidsteerbot.xacro b/mir_robot/diff_drive_controller/test/skidsteerbot.xacro new file mode 100755 index 0000000..f2b36ef --- /dev/null +++ b/mir_robot/diff_drive_controller/test/skidsteerbot.xacro @@ -0,0 +1,90 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Gazebo/Green + + + + Gazebo/Purple + + + diff --git a/mir_robot/diff_drive_controller/test/skidsteerbot_controllers.yaml b/mir_robot/diff_drive_controller/test/skidsteerbot_controllers.yaml new file mode 100755 index 0000000..ab49424 --- /dev/null +++ b/mir_robot/diff_drive_controller/test/skidsteerbot_controllers.yaml @@ -0,0 +1,8 @@ +skidsteerbot_controller: + type: "diff_drive_controller/DiffDriveController" + left_wheel: ['wheel_0_joint', 'wheel_1_joint', 'wheel_2_joint'] + right_wheel: ['wheel_3_joint', 'wheel_4_joint', 'wheel_5_joint'] + publish_rate: 50.0 # defaults to 50 + pose_covariance_diagonal: [0.001, 0.001, 1000000.0, 1000000.0, 1000000.0, 1000.0] + twist_covariance_diagonal: [0.001, 0.001, 1000000.0, 1000000.0, 1000000.0, 1000.0] + cmd_vel_timeout: 20.0 # we test this separately, give plenty for the other tests diff --git a/mir_robot/diff_drive_controller/test/skidsteerbot_no_wheels.yaml b/mir_robot/diff_drive_controller/test/skidsteerbot_no_wheels.yaml new file mode 100755 index 0000000..37f0d99 --- /dev/null +++ b/mir_robot/diff_drive_controller/test/skidsteerbot_no_wheels.yaml @@ -0,0 +1,8 @@ +skidsteerbot_controller: + type: "diff_drive_controller/DiffDriveController" + left_wheel: [] + right_wheel: ['wheel_3_joint', 'wheel_4_joint', 'wheel_5_joint'] + publish_rate: 50.0 # defaults to 50 + pose_covariance_diagonal: [0.001, 0.001, 1000000.0, 1000000.0, 1000000.0, 1000.0] + twist_covariance_diagonal: [0.001, 0.001, 1000000.0, 1000000.0, 1000000.0, 1000.0] + cmd_vel_timeout: 20.0 # we test this separately, give plenty for the other tests diff --git a/mir_robot/diff_drive_controller/test/sphere_wheel.xacro b/mir_robot/diff_drive_controller/test/sphere_wheel.xacro new file mode 100755 index 0000000..bd8dd47 --- /dev/null +++ b/mir_robot/diff_drive_controller/test/sphere_wheel.xacro @@ -0,0 +1,43 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 1 + 1 + + + + Gazebo/Red + + + diff --git a/mir_robot/diff_drive_controller/test/square_wheel.xacro b/mir_robot/diff_drive_controller/test/square_wheel.xacro new file mode 100755 index 0000000..56680a0 --- /dev/null +++ b/mir_robot/diff_drive_controller/test/square_wheel.xacro @@ -0,0 +1,44 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 1 + 1 + + + + Gazebo/Red + + + diff --git a/mir_robot/diff_drive_controller/test/test_common.h b/mir_robot/diff_drive_controller/test/test_common.h new file mode 100755 index 0000000..a726d75 --- /dev/null +++ b/mir_robot/diff_drive_controller/test/test_common.h @@ -0,0 +1,162 @@ +/////////////////////////////////////////////////////////////////////////////// +// Copyright (C) 2013, PAL Robotics S.L. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of PAL Robotics, Inc. nor the names of its +// contributors may be used to endorse or promote products derived from +// this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +// POSSIBILITY OF SUCH DAMAGE. +////////////////////////////////////////////////////////////////////////////// + +/// \author Bence Magyar + +#pragma once + + +#include + +#include + +#include + +#include +#include +#include +#include + +#include + +// Floating-point value comparison threshold +const double EPS = 0.01; +const double POSITION_TOLERANCE = 0.01; // 1 cm-s precision +const double VELOCITY_TOLERANCE = 0.02; // 2 cm-s-1 precision +const double JERK_LINEAR_VELOCITY_TOLERANCE = 0.10; // 10 cm-s-1 precision +const double JERK_ANGULAR_VELOCITY_TOLERANCE = 0.05; // 3 deg-s-1 precision +const double ORIENTATION_TOLERANCE = 0.03; // 0.57 degree precision + +class DiffDriveControllerTest : public ::testing::Test +{ +public: + + DiffDriveControllerTest() + : received_first_odom(false) + , cmd_pub(nh.advertise("cmd_vel", 100)) + , odom_sub(nh.subscribe("odom", 100, &DiffDriveControllerTest::odomCallback, this)) + , vel_out_sub(nh.subscribe("cmd_vel_out", 100, &DiffDriveControllerTest::cmdVelOutCallback, this)) + , joint_traj_controller_state_sub(nh.subscribe("wheel_joint_controller_state", 100, &DiffDriveControllerTest::jointTrajectoryControllerStateCallback, this)) + , start_srv(nh.serviceClient("start")) + , stop_srv(nh.serviceClient("stop")) + { + } + + ~DiffDriveControllerTest() + { + odom_sub.shutdown(); + joint_traj_controller_state_sub.shutdown(); + } + + nav_msgs::Odometry getLastOdom(){ return last_odom; } + geometry_msgs::TwistStamped getLastCmdVelOut(){ return last_cmd_vel_out; } + control_msgs::JointTrajectoryControllerState getLastJointTrajectoryControllerState(){ return last_joint_traj_controller_state; } + void publish(geometry_msgs::Twist cmd_vel){ cmd_pub.publish(cmd_vel); } + bool isControllerAlive()const{ return (odom_sub.getNumPublishers() > 0); } + bool isPublishingCmdVelOut(const ros::Duration &timeout=ros::Duration(1)) const + { + ros::Time start = ros::Time::now(); + int get_num_publishers = vel_out_sub.getNumPublishers(); + while ( (get_num_publishers == 0) && (ros::Time::now() < start + timeout) ) { + ros::Duration(0.1).sleep(); + get_num_publishers = vel_out_sub.getNumPublishers(); + } + return (get_num_publishers > 0); + } + bool isPublishingJointTrajectoryControllerState(){ return (joint_traj_controller_state_sub.getNumPublishers() > 0); } + bool hasReceivedFirstOdom()const{ return received_first_odom; } + + void start(){ std_srvs::Empty srv; start_srv.call(srv); } + void stop(){ std_srvs::Empty srv; stop_srv.call(srv); } + + void waitForController() const + { + while(!isControllerAlive() && ros::ok()) + { + ROS_DEBUG_STREAM_THROTTLE(0.5, "Waiting for controller."); + ros::Duration(0.1).sleep(); + } + if (!ros::ok()) + FAIL() << "Something went wrong while executing test."; + } + + void waitForOdomMsgs() const + { + while(!hasReceivedFirstOdom() && ros::ok()) + { + ROS_DEBUG_STREAM_THROTTLE(0.5, "Waiting for odom messages to be published."); + ros::Duration(0.01).sleep(); + } + if (!ros::ok()) + FAIL() << "Something went wrong while executing test."; + } + +private: + bool received_first_odom; + ros::NodeHandle nh; + ros::Publisher cmd_pub; + ros::Subscriber odom_sub; + ros::Subscriber vel_out_sub; + nav_msgs::Odometry last_odom; + geometry_msgs::TwistStamped last_cmd_vel_out; + ros::Subscriber joint_traj_controller_state_sub; + control_msgs::JointTrajectoryControllerState last_joint_traj_controller_state; + + ros::ServiceClient start_srv; + ros::ServiceClient stop_srv; + + void odomCallback(const nav_msgs::Odometry& odom) + { + ROS_INFO_STREAM("Callback received: pos.x: " << odom.pose.pose.position.x + << ", orient.z: " << odom.pose.pose.orientation.z + << ", lin_est: " << odom.twist.twist.linear.x + << ", ang_est: " << odom.twist.twist.angular.z); + last_odom = odom; + received_first_odom = true; + } + + void jointTrajectoryControllerStateCallback(const control_msgs::JointTrajectoryControllerState& joint_traj_controller_state) + { + ROS_INFO_STREAM("Joint trajectory controller state callback."); + ROS_DEBUG_STREAM("Joint trajectory controller state callback received:\n" << + joint_traj_controller_state); + + last_joint_traj_controller_state = joint_traj_controller_state; + } + + void cmdVelOutCallback(const geometry_msgs::TwistStamped& cmd_vel_out) + { + ROS_INFO_STREAM("Callback received: lin: " << cmd_vel_out.twist.linear.x + << ", ang: " << cmd_vel_out.twist.angular.z); + last_cmd_vel_out = cmd_vel_out; + } +}; + +inline tf::Quaternion tfQuatFromGeomQuat(const geometry_msgs::Quaternion& quat) +{ + return tf::Quaternion(quat.x, quat.y, quat.z, quat.w); +} diff --git a/mir_robot/diff_drive_controller/test/view_diffbot.launch b/mir_robot/diff_drive_controller/test/view_diffbot.launch new file mode 100755 index 0000000..212993f --- /dev/null +++ b/mir_robot/diff_drive_controller/test/view_diffbot.launch @@ -0,0 +1,26 @@ + + + + + + + + + + + + + + + + + + + + + diff --git a/mir_robot/diff_drive_controller/test/view_skidsteerbot.launch b/mir_robot/diff_drive_controller/test/view_skidsteerbot.launch new file mode 100755 index 0000000..4460cee --- /dev/null +++ b/mir_robot/diff_drive_controller/test/view_skidsteerbot.launch @@ -0,0 +1,26 @@ + + + + + + + + + + + + + + + + + + + + + diff --git a/mir_robot/diff_drive_controller/test/wheel.xacro b/mir_robot/diff_drive_controller/test/wheel.xacro new file mode 100755 index 0000000..1e8dd89 --- /dev/null +++ b/mir_robot/diff_drive_controller/test/wheel.xacro @@ -0,0 +1,43 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 1 + 1 + + + + Gazebo/Red + + + diff --git a/mir_robot/mir_actions/CHANGELOG.rst b/mir_robot/mir_actions/CHANGELOG.rst new file mode 100755 index 0000000..73e3752 --- /dev/null +++ b/mir_robot/mir_actions/CHANGELOG.rst @@ -0,0 +1,70 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package mir_actions +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +1.1.7 (2023-01-20) +------------------ +* Update MirMoveBase action to 2.10.3.1 +* Don't set cmake_policy CMP0048 +* Contributors: Martin Günther + +1.1.6 (2022-06-02) +------------------ +* Rename mir_100 -> mir + This is in preparation of mir_250 support. +* Contributors: Martin Günther + +1.1.5 (2022-02-11) +------------------ + +1.1.4 (2021-12-10) +------------------ + +1.1.3 (2021-06-11) +------------------ +* Merge branch 'melodic-2.8' into noetic +* Remove RelativeMove action + It was removed in MiR software 2.4.0. +* Update mir_actions to MiR 2.8.3 +* Adjust to changed MirMoveBase action (MiR >= 2.4.0) + See `#45 `_. +* Contributors: Martin Günther + +1.1.2 (2021-05-12) +------------------ + +1.1.1 (2021-02-11) +------------------ +* Contributors: Martin Günther + +1.1.0 (2020-06-30) +------------------ +* Initial release into noetic +* Contributors: Martin Günther + +1.0.6 (2020-06-30) +------------------ +* Set cmake_policy CMP0048 to fix warning +* Contributors: Martin Günther + +1.0.5 (2020-05-01) +------------------ + +1.0.4 (2019-05-06) +------------------ +* Update mir_msgs and mir_actions to MiR 2.3.1 +* Contributors: Martin Günther + +1.0.3 (2019-03-04) +------------------ + +1.0.2 (2018-07-30) +------------------ + +1.0.1 (2018-07-17) +------------------ + +1.0.0 (2018-07-12) +------------------ +* Initial release +* Contributors: Martin Günther diff --git a/mir_robot/mir_actions/CMakeLists.txt b/mir_robot/mir_actions/CMakeLists.txt new file mode 100755 index 0000000..551eed4 --- /dev/null +++ b/mir_robot/mir_actions/CMakeLists.txt @@ -0,0 +1,40 @@ +cmake_minimum_required(VERSION 3.5.1) +project(mir_actions) + +find_package(catkin REQUIRED COMPONENTS + actionlib + geometry_msgs + message_generation + mir_msgs + nav_msgs +) + +################################################ +## Declare ROS messages, services and actions ## +################################################ + +# Generate actions in the 'action' folder +add_action_files( + FILES + MirMoveBase.action +) + +# Generate added messages and services with any dependencies listed here +generate_messages( + DEPENDENCIES + geometry_msgs + mir_msgs + nav_msgs +) + +################################### +## catkin specific configuration ## +################################### +catkin_package( + CATKIN_DEPENDS + actionlib + geometry_msgs + message_runtime + mir_msgs + nav_msgs +) diff --git a/mir_robot/mir_actions/action/MirMoveBase.action b/mir_robot/mir_actions/action/MirMoveBase.action new file mode 100755 index 0000000..ef9d472 --- /dev/null +++ b/mir_robot/mir_actions/action/MirMoveBase.action @@ -0,0 +1,130 @@ +#goal definition +#move type +int16 BASE_MOVE = 0 +int16 GLOBAL_MOVE = 1 +int16 RELATIVE_MOVE = 2 +int16 RELATIVE_MARKER_MOVE = 3 +int16 DOCKING_MOVE = 4 +int16 DOCKING_GLOBAL_MOVE = 5 +int16 PATH_TYPE = 6 +int16 move_task + +#shared parameters +geometry_msgs/PoseStamped target_pose +string target_guid + +#global move parameters +float64 goal_dist_threshold +float64 goal_orientation_threshold +nav_msgs/Path path +float32 max_plan_time +bool clear_costmaps +bool pause_command +bool continue_command + +#relative move parameters +float64 yaw +bool collision_detection +bool collision_avoidance +float64 disable_collision_check_dist +float64 max_linear_speed +float64 max_rotational_speed +float64 pid_dist_offset +float64 target_offset +bool only_collision_detection +float64 timeout + +#docking move parameters +int32 pattern_type +int32 pattern_value +bool only_track +bool same_goal +string pose_frame +geometry_msgs/Pose2D pose +geometry_msgs/Pose2D offset +float64 bar_length +float64 bar_distance +float64 shelf_leg_asymmetry_x +float64 tolerance + +#Path type +mir_msgs/MirLocalPlannerPathTypes path_type +geometry_msgs/PoseStamped start_pose +# float64 timeout + + +--- +#result definition + +#shared states +int16 UNDEFINED = 0 +int16 GOAL_REACHED = 1 +int16 FAILED = -1 + +#global move states +int16 MARKER_VISIBLE = 2 +int16 FAILED_NO_PATH = -2 +int16 FAILED_GOAL_IN_STATIC_OBSTACLE = -3 +int16 FAILED_GOAL_IN_FORBIDDEN_AREA = -4 +int16 FAILED_GOAL_IN_DYNAMIC_OBSTACLE = -5 +int16 FAILED_ROBOT_IN_COLLISION = -6 +int16 FAILED_ROBOT_IN_FORBIDDEN_AREA = -7 +int16 FAILED_UNKNOWN_TRAILER = -8 +int16 FAILED_TO_PASS_GLOBAL_PLAN = -9 +int16 FAILED_NO_VALID_RECOVERY_CONTROL = -10 +int16 FAILED_UNKNOWN_PLANNER_ERROR = -11 +int16 FAILED_ROBOT_OSCILLATING = -12 +int16 FAILED_SOFTWARE_ERROR = -13 + +#relative move states +int16 FAILED_TIMEOUT = -14 +int16 FAILED_COLLISION = -15 +int16 INVALID_GOAL = -16 + +#docking move states +int16 FAILED_MARKER_TRACKING_ERROR = -17 + +#shared results +int16 end_state +geometry_msgs/PoseStamped end_pose + +#docking results +geometry_msgs/Pose2D pose + +#feedback for UI +string message + +--- +#feedback +#shared +int8 NOT_READY = -1 +int8 UNKNOWN = -2 +int8 WAITING_FOR_FLEET = -3 +int8 COLLISION = -4 + +#global move states +int8 PLANNING = 0 +int8 CONTROLLING = 1 +int8 CLEARING = 2 + +#relative move states +int8 DOCKING = 3 + +#shared feedback +int8 state + +#global move feedback +geometry_msgs/PoseStamped base_position + +#relative move feedback +geometry_msgs/PoseStamped current_goal +geometry_msgs/PoseStamped dist_to_goal + +#docking move feedback +geometry_msgs/Pose2D pose +bool marker_inversion + +#path_types + #reverse_trolly +int8 MOVING_FORWARD = 10 +int8 MOVING_BACKWARD = 11 diff --git a/mir_robot/mir_actions/package.xml b/mir_robot/mir_actions/package.xml new file mode 100755 index 0000000..77f6533 --- /dev/null +++ b/mir_robot/mir_actions/package.xml @@ -0,0 +1,25 @@ + + + mir_actions + 1.1.7 + Action definitions for the MiR robot + + Martin Günther + Martin Günther + + BSD + + https://github.com/DFKI-NI/mir_robot + https://github.com/DFKI-NI/mir_robot + https://github.com/DFKI-NI/mir_robot/issues + + catkin + + actionlib + geometry_msgs + mir_msgs + nav_msgs + + message_generation + message_runtime + diff --git a/mir_robot/mir_description/CHANGELOG.rst b/mir_robot/mir_description/CHANGELOG.rst new file mode 100755 index 0000000..5402ae9 --- /dev/null +++ b/mir_robot/mir_description/CHANGELOG.rst @@ -0,0 +1,133 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package mir_description +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +1.1.7 (2023-01-20) +------------------ +* Don't set cmake_policy CMP0048 +* Contributors: Martin Günther + +1.1.6 (2022-06-02) +------------------ +* URDF: Downsize inertia box, move to lower back +* URDF: Pull out inertia properties +* URDF: Update masses according to data sheet +* URDF: Add mir_250 +* Add arg mir_type to launch files and urdfs +* Add mir_250 meshes +* URDF: Make wheels black +* Add mir_100_v1.urdf.xacro for backwards compatibility +* Rename mir_100 -> mir +* Refactor URDF to prepare for MiR250 support +* Gazebo: Don't manually specify wheel params for diffdrive controller +* Simplify mir_100 collision mesh further +* Contributors: Martin Günther + +1.1.5 (2022-02-11) +------------------ +* Remove xacro comment to work around xacro bug + Since xacro 1.14.11, xacro now also evaluates expressions in comments + and throws an error if the substition argument is undefined. In xacro + 1.14.12, this error was changed to a warning. + This commit removes that warning. + Workaround for https://github.com/ros/xacro/issues/309 . +* xacro: drop --inorder option + In-order processing became default in ROS Melodic. +* Add gazebo_plugins to dependency list (`#103 `_) + This is needed for the ground truth pose via p3d plugin. +* Contributors: Martin Günther, moooeeeep + +1.1.4 (2021-12-10) +------------------ +* Replace gazebo_plugins IMU with hector_gazebo_plugins +* Use cylinders instead of STLs for wheel collision geometries + Fixes `#99 `_. +* mir_debug_urdf.launch: Fix GUI display +* Contributors: Martin Günther + +1.1.3 (2021-06-11) +------------------ +* Merge branch 'melodic-2.8' into noetic +* Rename tf frame and topic 'odom_comb' -> 'odom' + This is how they are called on the real MiR since MiR software 2.0. +* Contributors: Martin Günther + +1.1.2 (2021-05-12) +------------------ +* Fix laser scan frame_id with gazebo_plugins 2.9.2 +* Contributors: Martin Günther + +1.1.1 (2021-02-11) +------------------ +* Add prepend_prefix_to_laser_frame to URDF and launch files + Fixes `#65 `_. +* Add tf_prefix to URDF and launch files +* Fix typo in robot_namespace +* Add missing 'xacro:' xml namespace prefixes + Macro calls without 'xacro:' prefix are deprecated in Melodic and will + be forbidden in Noetic. +* Contributors: Martin Günther + +1.1.0 (2020-06-30) +------------------ +* Initial release into noetic +* Contributors: Martin Günther + +1.0.6 (2020-06-30) +------------------ +* Update to non-deprecated robot_state_publisher node +* Set cmake_policy CMP0048 to fix warning +* Contributors: Martin Günther + +1.0.5 (2020-05-01) +------------------ +* Switch from Gazebo GPU laser to normal laser plugin + The GPU laser plugin has caused multiple people problems before, because + it is not compatible with all GPUS: `#1 `_ + `#32 `_ + `#46 `_ + `#52 `_ + The normal laser plugin directly uses the physics engine, so it doesn't + depend on any specific GPU. Also, it doesn't slow down the simulation + noticeably (maybe 1-2%). +* Contributors: Martin Günther + +1.0.4 (2019-05-06) +------------------ +* Add legacyModeNS param to gazebo_ros_control plugin + This enables the new behavior of the plugin (pid_gains parameter are now + in the proper namespace). +* re-added gazebo friction parameters for the wheels (`#19 `_) +* Contributors: Martin Günther, niniemann + +1.0.3 (2019-03-04) +------------------ +* Merge pull request `#16 `_ from niniemann/add-prefix-argument-to-configs + Add prefix argument to configs +* removed prefix from plugin frameName in sick urdf + The gazebo plugins automatically use tf_prefix, even if none is set + (in that case it defaults to the robot namespace). That's why we can + remove the prefix from the plugins configuration, assuming that the + robot namespace will be equal to the prefix. +* adds $(arg prefix) to a lot of configs + This is an important step to be able to re-parameterize move base, + the diffdrive controller, ekf, amcl and the costmaps for adding a + tf prefix to the robots links +* workaround eval in xacro for indigo support +* adds tf_prefix argument to imu.gazebo.urdf.xacro +* Add TFs for ultrasound sensors +* Contributors: Martin Günther, Nils Niemann + +1.0.2 (2018-07-30) +------------------ + +1.0.1 (2018-07-17) +------------------ +* gazebo: Remove leading slashes in TF frames + TF2 doesn't like it (e.g., robot_localization). +* Contributors: Martin Günther + +1.0.0 (2018-07-12) +------------------ +* Initial release +* Contributors: Martin Günther diff --git a/mir_robot/mir_description/CMakeLists.txt b/mir_robot/mir_description/CMakeLists.txt new file mode 100755 index 0000000..1437510 --- /dev/null +++ b/mir_robot/mir_description/CMakeLists.txt @@ -0,0 +1,31 @@ +cmake_minimum_required(VERSION 3.5.1) +project(mir_description) + +find_package(catkin REQUIRED COMPONENTS + roslaunch +) + +################################### +## catkin specific configuration ## +################################### +catkin_package() + +############# +## Install ## +############# + +# Mark other files for installation (e.g. launch and bag files, etc.) +install(DIRECTORY + config + launch + meshes + rviz + urdf + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) + +############# +## Testing ## +############# + +roslaunch_add_file_check(launch) diff --git a/mir_robot/mir_description/config/diffdrive_controller.yaml b/mir_robot/mir_description/config/diffdrive_controller.yaml new file mode 100755 index 0000000..161b63a --- /dev/null +++ b/mir_robot/mir_description/config/diffdrive_controller.yaml @@ -0,0 +1,44 @@ +# ----------------------------------- +mobile_base_controller: + type : "diff_drive_controller/DiffDriveController" + left_wheel : '$(arg prefix)left_wheel_joint' + right_wheel : '$(arg prefix)right_wheel_joint' + publish_rate: 41.2 # this is what the real MiR platform publishes (default: 50) + # These covariances are exactly what the real MiR platform publishes + pose_covariance_diagonal : [0.00001, 0.00001, 1000000.0, 1000000.0, 1000000.0, 1000.0] + twist_covariance_diagonal: [0.1, 0.1, 1000000.0, 1000000.0, 1000000.0, 1000.0] + enable_odom_tf: false + + # Wheel separation and diameter. These are both optional. + # diff_drive_controller will attempt to read either one or both from the + # URDF if not specified as a parameter. + # We don't set the value here because it's different for each MiR type (100, 250, ...), and + # the plugin figures out the correct values. + #wheel_separation : 0.445208 + #wheel_radius : 0.0625 + + # Wheel separation and radius multipliers + wheel_separation_multiplier: 1.0 # default: 1.0 + wheel_radius_multiplier : 1.0 # default: 1.0 + + # Velocity commands timeout [s], default 0.5 + cmd_vel_timeout: 0.5 + + # frame_ids (same as real MiR platform) + base_frame_id: $(arg prefix)base_footprint # default: base_link + odom_frame_id: $(arg prefix)odom # default: odom + + # Velocity and acceleration limits + # Whenever a min_* is unspecified, default to -max_* + linear: + x: + has_velocity_limits : false + max_velocity : 2.0 # m/s; move_base max_vel_x: 0.8 + has_acceleration_limits: true + max_acceleration : 3.0 # m/s^2; move_base acc_lim_x: 1.5 + angular: + z: + has_velocity_limits : false + max_velocity : 2.0 # rad/s; move_base max_rot_vel: 1.0 + has_acceleration_limits: true + max_acceleration : 2.0 # rad/s^2; move_base acc_lim_th: 2.0 diff --git a/mir_robot/mir_description/config/joint_state_controller.yaml b/mir_robot/mir_description/config/joint_state_controller.yaml new file mode 100755 index 0000000..2487d71 --- /dev/null +++ b/mir_robot/mir_description/config/joint_state_controller.yaml @@ -0,0 +1,4 @@ +# Publish all joint states ----------------------------------- +joint_state_controller: + type: joint_state_controller/JointStateController + publish_rate: 50 diff --git a/mir_robot/mir_description/launch/mir_debug_urdf.launch b/mir_robot/mir_description/launch/mir_debug_urdf.launch new file mode 100755 index 0000000..e2a698c --- /dev/null +++ b/mir_robot/mir_description/launch/mir_debug_urdf.launch @@ -0,0 +1,18 @@ + + + + + + + + + + + + + + + + + + diff --git a/mir_robot/mir_description/launch/upload_mir_urdf.launch b/mir_robot/mir_description/launch/upload_mir_urdf.launch new file mode 100755 index 0000000..7f6a559 --- /dev/null +++ b/mir_robot/mir_description/launch/upload_mir_urdf.launch @@ -0,0 +1,7 @@ + + + + + + + diff --git a/mir_robot/mir_description/meshes/collision/caster_wheel_base.stl b/mir_robot/mir_description/meshes/collision/caster_wheel_base.stl new file mode 100755 index 0000000..365f113 Binary files /dev/null and b/mir_robot/mir_description/meshes/collision/caster_wheel_base.stl differ diff --git a/mir_robot/mir_description/meshes/collision/mir_100_base.stl b/mir_robot/mir_description/meshes/collision/mir_100_base.stl new file mode 100755 index 0000000..a49e167 Binary files /dev/null and b/mir_robot/mir_description/meshes/collision/mir_100_base.stl differ diff --git a/mir_robot/mir_description/meshes/collision/mir_250_base.stl b/mir_robot/mir_description/meshes/collision/mir_250_base.stl new file mode 100755 index 0000000..9c20e60 Binary files /dev/null and b/mir_robot/mir_description/meshes/collision/mir_250_base.stl differ diff --git a/mir_robot/mir_description/meshes/visual/caster_wheel_base.stl b/mir_robot/mir_description/meshes/visual/caster_wheel_base.stl new file mode 100755 index 0000000..cc79f23 Binary files /dev/null and b/mir_robot/mir_description/meshes/visual/caster_wheel_base.stl differ diff --git a/mir_robot/mir_description/meshes/visual/mir_100_base.stl b/mir_robot/mir_description/meshes/visual/mir_100_base.stl new file mode 100755 index 0000000..7dbeb44 Binary files /dev/null and b/mir_robot/mir_description/meshes/visual/mir_100_base.stl differ diff --git a/mir_robot/mir_description/meshes/visual/mir_250_base.stl b/mir_robot/mir_description/meshes/visual/mir_250_base.stl new file mode 100755 index 0000000..d06f993 Binary files /dev/null and b/mir_robot/mir_description/meshes/visual/mir_250_base.stl differ diff --git a/mir_robot/mir_description/meshes/visual/sick_lms-100.stl b/mir_robot/mir_description/meshes/visual/sick_lms-100.stl new file mode 100755 index 0000000..9cd840a Binary files /dev/null and b/mir_robot/mir_description/meshes/visual/sick_lms-100.stl differ diff --git a/mir_robot/mir_description/meshes/visual/wheel.stl b/mir_robot/mir_description/meshes/visual/wheel.stl new file mode 100755 index 0000000..104a847 Binary files /dev/null and b/mir_robot/mir_description/meshes/visual/wheel.stl differ diff --git a/mir_robot/mir_description/package.xml b/mir_robot/mir_description/package.xml new file mode 100755 index 0000000..2b45785 --- /dev/null +++ b/mir_robot/mir_description/package.xml @@ -0,0 +1,34 @@ + + + mir_description + 1.1.7 + URDF description of the MiR robot + + Martin Günther + Martin Günther + + BSD + + https://github.com/DFKI-NI/mir_robot + https://github.com/DFKI-NI/mir_robot + https://github.com/DFKI-NI/mir_robot/issues + + catkin + + roslaunch + + diff_drive_controller + diff_drive_controller + + gazebo_plugins + gazebo_ros_control + hector_gazebo_plugins + joint_state_controller + joint_state_publisher + joint_state_publisher_gui + position_controllers + robot_state_publisher + rviz + urdf + xacro + diff --git a/mir_robot/mir_description/rviz/mir_description.rviz b/mir_robot/mir_description/rviz/mir_description.rviz new file mode 100755 index 0000000..c17b041 --- /dev/null +++ b/mir_robot/mir_description/rviz/mir_description.rviz @@ -0,0 +1,210 @@ +Panels: + - Class: rviz/Displays + Help Height: 81 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /Status1 + Splitter Ratio: 0.5 + Tree Height: 535 + - Class: rviz/Selection + Name: Selection + - Class: rviz/Tool Properties + Expanded: + - /2D Pose Estimate1 + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.588679016 + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: "" +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.0299999993 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Alpha: 1 + Class: rviz/RobotModel + Collision Enabled: false + Enabled: true + Links: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + Link Tree Style: Links in Alphabetic Order + back_laser_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + base_footprint: + Alpha: 1 + Show Axes: false + Show Trail: false + base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + bl_caster_rotation_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + bl_caster_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + br_caster_rotation_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + br_caster_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fl_caster_rotation_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fl_caster_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fr_caster_rotation_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fr_caster_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + front_laser_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + imu_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + imu_link: + Alpha: 1 + Show Axes: false + Show Trail: false + left_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + right_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + surface: + Alpha: 1 + Show Axes: false + Show Trail: false + Name: RobotModel + Robot Description: robot_description + TF Prefix: "" + Update Interval: 0 + Value: true + Visual Enabled: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Default Light: true + Fixed Frame: base_footprint + Frame Rate: 30 + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + - Class: rviz/FocusCamera + - Class: rviz/Measure + - Class: rviz/SetInitialPose + Topic: /initialpose + - Class: rviz/SetGoal + Topic: /move_base_simple/goal + - Class: rviz/PublishPoint + Single click: true + Topic: /clicked_point + Value: true + Views: + Current: + Class: rviz/Orbit + Distance: 2.20704937 + Enable Stereo Rendering: + Stereo Eye Separation: 0.0599999987 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: 0.023150593 + Y: -0.0341755934 + Z: -2.6775524e-09 + Focal Shape Fixed Size: false + Focal Shape Size: 0.0500000007 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.00999999978 + Pitch: 0.515398085 + Target Frame: + Value: Orbit (rviz) + Yaw: 0.490397513 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 846 + Hide Left Dock: false + Hide Right Dock: false + QMainWindow State: 000000ff00000000fd00000004000000000000016a000002a9fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006700fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c0061007900730100000043000002a9000000e300fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002a9fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a005600690065007700730100000043000002a9000000b300fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004b00000003efc0100000002fb0000000800540069006d00650100000000000004b00000022300fffffffb0000000800540069006d006501000000000000045000000000000000000000022b000002a900000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 1200 + X: 59 + Y: 29 diff --git a/mir_robot/mir_description/urdf/include/common.gazebo.xacro b/mir_robot/mir_description/urdf/include/common.gazebo.xacro new file mode 100755 index 0000000..87a1390 --- /dev/null +++ b/mir_robot/mir_description/urdf/include/common.gazebo.xacro @@ -0,0 +1,15 @@ + + + + + + + + ${robot_namespace} + + 0.001 + false + + + + diff --git a/mir_robot/mir_description/urdf/include/common_properties.urdf.xacro b/mir_robot/mir_description/urdf/include/common_properties.urdf.xacro new file mode 100755 index 0000000..3c1a28d --- /dev/null +++ b/mir_robot/mir_description/urdf/include/common_properties.urdf.xacro @@ -0,0 +1,84 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/mir_robot/mir_description/urdf/include/imu.gazebo.urdf.xacro b/mir_robot/mir_description/urdf/include/imu.gazebo.urdf.xacro new file mode 100755 index 0000000..abd6cec --- /dev/null +++ b/mir_robot/mir_description/urdf/include/imu.gazebo.urdf.xacro @@ -0,0 +1,31 @@ + + + + + + + + + + + + + + + + + + ${update_rate} + ${link} + ${imu_frame} + ${imu_topic} + 0.0 0.0 0.0 + ${sqrt(5e-05)} ${sqrt(0.0001)} ${sqrt(0.00013)} + 0.0 0.0 0.0 + ${sqrt(8e-06)} ${sqrt(8e-06)} ${sqrt(3e-07)} + 0.0 + ${sqrt(0.1)} + + + + diff --git a/mir_robot/mir_description/urdf/include/mir.gazebo.xacro b/mir_robot/mir_description/urdf/include/mir.gazebo.xacro new file mode 100755 index 0000000..5293163 --- /dev/null +++ b/mir_robot/mir_description/urdf/include/mir.gazebo.xacro @@ -0,0 +1,62 @@ + + + + + + + false + true + 1000.0 + ${left_wheel_joint} + ${right_wheel_joint} + ${wheel_separation} + ${2*wheel_radius} + 10 + 1 + map + mobile_base_controller/cmd_vel + mobile_base_controller/odom + base_footprint + 2.8 + true + false + world + Debug + + + + + + + + + + + 0.01 + + + + + + + + + + + + + + + + true + 50.0 + ${prefix}base_footprint + base_pose_ground_truth + 0.01 + map + 0 0 0 + 0 0 0 + + + + diff --git a/mir_robot/mir_description/urdf/include/mir.transmission.xacro b/mir_robot/mir_description/urdf/include/mir.transmission.xacro new file mode 100755 index 0000000..0fe6ae0 --- /dev/null +++ b/mir_robot/mir_description/urdf/include/mir.transmission.xacro @@ -0,0 +1,22 @@ + + + + + + transmission_interface/SimpleTransmission + + hardware_interface/VelocityJointInterface + + + hardware_interface/VelocityJointInterface + 1 + + + + + + + + + + diff --git a/mir_robot/mir_description/urdf/include/mir_100_v1.urdf.xacro b/mir_robot/mir_description/urdf/include/mir_100_v1.urdf.xacro new file mode 100755 index 0000000..a7cb30f --- /dev/null +++ b/mir_robot/mir_description/urdf/include/mir_100_v1.urdf.xacro @@ -0,0 +1,12 @@ + + + + + + + + + + + diff --git a/mir_robot/mir_description/urdf/include/mir_v1.urdf.xacro b/mir_robot/mir_description/urdf/include/mir_v1.urdf.xacro new file mode 100755 index 0000000..98804e6 --- /dev/null +++ b/mir_robot/mir_description/urdf/include/mir_v1.urdf.xacro @@ -0,0 +1,308 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Gazebo/FlatBlack + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Gazebo/Grey + + + Gazebo/FlatBlack + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Gazebo/FlatBlack + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Gazebo/White + + + Gazebo/DarkGrey + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/mir_robot/mir_description/urdf/include/sick_s300.urdf.xacro b/mir_robot/mir_description/urdf/include/sick_s300.urdf.xacro new file mode 100755 index 0000000..be37319 --- /dev/null +++ b/mir_robot/mir_description/urdf/include/sick_s300.urdf.xacro @@ -0,0 +1,72 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 0 0 0 0 0 0 + false + 12.5 + + + + 541 + 1 + + -2.094395102 + 2.181661565 + + + + 0.05 + 29.0 + 0.01 + + + gaussian + + 0.0 + 0.01 + + + + ${prefix}${link} + ${topic} + + + + + diff --git a/mir_robot/mir_description/urdf/mir.urdf.xacro b/mir_robot/mir_description/urdf/mir.urdf.xacro new file mode 100755 index 0000000..17c0cb2 --- /dev/null +++ b/mir_robot/mir_description/urdf/mir.urdf.xacro @@ -0,0 +1,28 @@ + + + + + + + + + + + + + + + + + + + + + + + diff --git a/mir_robot/mir_driver/CHANGELOG.rst b/mir_robot/mir_driver/CHANGELOG.rst new file mode 100755 index 0000000..5aad22d --- /dev/null +++ b/mir_robot/mir_driver/CHANGELOG.rst @@ -0,0 +1,137 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package mir_driver +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +1.1.7 (2023-01-20) +------------------ +* Don't set cmake_policy CMP0048 +* Fix pydocstyle errors +* Add license headers +* Fix flake8 warnings +* Contributors: Martin Günther + +1.1.6 (2022-06-02) +------------------ +* Add arg mir_type to launch files and urdfs +* Rename mir_100 -> mir + This is in preparation of mir_250 support. +* Contributors: Martin Günther + +1.1.5 (2022-02-11) +------------------ + +1.1.4 (2021-12-10) +------------------ + +1.1.3 (2021-06-11) +------------------ +* Merge branch 'melodic-2.8' into noetic +* Subscribe to move_base_simple/goal in relative namespace +* Use absolute topics for /tf, /tf_static, /map etc. +* Rename tf frame and topic 'odom_comb' -> 'odom' + This is how they are called on the real MiR since MiR software 2.0. +* Fix handling of tf_static topic + This does two things: + 1. Make the tf_static topic latched. + 2. Cache all transforms, publish as one message. +* Increase queue_size for publishers + subscribers to 10 + One case where this was a problem was the tf_static topic: Since + multiple messages are being published at once, the subscriber often + missed one. The tf_static topic will be fixed anyway in the next commit, + but let's increase the queue_size anyway to avoid such bugs in the + future. +* Update topic list to 2.8.3.1 +* Reformat python code using black +* Remove outdated topics + These topics don't exist on MiR software 2.8.3 any more (most of them + have been removed a long time ago). + Fixes `#37 `_. +* Remove MirStatus + This message was removed in MiR software 2.0 (Renamed to RobotStatus). +* Use same MirMoveBase params as real MiR (2.8.3) + This shouldn't make a difference (it used to work before). Just removing + one more potential source of error. +* Fix: Converts move_base_simple/goal into a move_base action. (`#62 `_) + At least MIR software version 2.8 does not react properly to move_base_simple/goal messages. This implements a workaround. + Closes `#60 `_. +* Fix: Adds subscription to "tf_static". (`#58 `_) + Some transformations are published on this topic and are needed to + obtain a full tf tree. E.g. "base_footprint" to "base_link" +* Minor: Removes /particlecloud from the list of published topics. (`#57 `_) +* Fix: Add missing dict_filter keyword argument for cmd_vel msgs (`#56 `_) +* Remove relative_move_action (MiR => 2.4.0) + This action was merged into the generic MirMoveBaseAction in MiR + software 2.4.0. +* Adjust to changed MirMoveBase action (MiR >= 2.4.0) + See `#45 `_. +* Adjust cmd_vel topic to TwistStamped (MiR >= 2.7) + See `#45 `_. +* Contributors: Martin Günther, matthias-mayr + +1.1.2 (2021-05-12) +------------------ + +1.1.1 (2021-02-11) +------------------ +* Fix subscribing twice to same topic (TF etc) + There was a flaw in the subscriber logic that caused the mir_bridge to + subscribe multiple times to the same topic from the MiR, especially for + latched topics. This can be seen by repeated lines in the output: + starting to stream messages on topic 'tf' + starting to stream messages on topic 'tf' + starting to stream messages on topic 'tf' + Probably related to `#64 `_. +* Contributors: Martin Günther + +1.1.0 (2020-06-30) +------------------ +* Initial release into noetic +* Adapt to changes in websocket-client >= 0.49 + Ubuntu 16.04 has python-websocket 0.18 + Ubuntu 20.04 has python3-websocket 0.53 +* Update scripts to Python3 (Noetic) +* Contributors: Martin Günther + +1.0.6 (2020-06-30) +------------------ +* Set cmake_policy CMP0048 to fix warning +* Contributors: Martin Günther + +1.0.5 (2020-05-01) +------------------ +* Add optional prefix parameter to fake_mir_joint_publisher (`#47 `_) +* tf_remove_child_frames: Don't publish empty TFs +* Add sdc21x0 package, MC/currents topic +* Contributors: Martin Günther, Nils Niemann + +1.0.4 (2019-05-06) +------------------ +* Remove garbage file +* Contributors: Martin Günther + +1.0.3 (2019-03-04) +------------------ +* Make disable_map work with MiR software 2.0 + See `#5 `_. +* mir_driver: Optionally disable the map topic + TF frame (`#6 `_) + This is useful when running one's own SLAM / localization nodes. + Fixes `#5 `_. +* Split scan_rep117 topic into two separate topics + This fixes the problem that the back laser scanner was ignored in the + navigation costmap in Gazebo (probably because in Gazebo, both laser + scanners have the exact same timestamp). +* Contributors: Martin Günther + +1.0.2 (2018-07-30) +------------------ + +1.0.1 (2018-07-17) +------------------ +* mir_driver: Remove leading slashes in TF frames +* mir_driver: Install launch directory +* Contributors: Martin Günther + +1.0.0 (2018-07-12) +------------------ +* Initial release +* Contributors: Martin Günther diff --git a/mir_robot/mir_driver/CMakeLists.txt b/mir_robot/mir_driver/CMakeLists.txt new file mode 100755 index 0000000..c1d06fc --- /dev/null +++ b/mir_robot/mir_driver/CMakeLists.txt @@ -0,0 +1,67 @@ +cmake_minimum_required(VERSION 3.5.1) +project(mir_driver) + +find_package(catkin REQUIRED COMPONENTS + actionlib_msgs + diagnostic_msgs + dynamic_reconfigure + geometry_msgs + mir_actions + mir_msgs + move_base_msgs + nav_msgs + rosgraph_msgs + roslaunch + rospy + rospy_message_converter + sensor_msgs + std_msgs + tf + visualization_msgs +) + +catkin_python_setup() + +################################### +## catkin specific configuration ## +################################### +catkin_package( + CATKIN_DEPENDS + actionlib_msgs + diagnostic_msgs + dynamic_reconfigure + geometry_msgs + mir_actions + mir_msgs + move_base_msgs + nav_msgs + rosgraph_msgs + rospy_message_converter + sensor_msgs + std_msgs + tf + visualization_msgs +) + +############# +## Install ## +############# + +catkin_install_python(PROGRAMS + nodes/fake_mir_joint_publisher.py + nodes/mir_bridge.py + nodes/rep117_filter.py + nodes/tf_remove_child_frames.py + DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) + +# Mark other files for installation (e.g. launch and bag files, etc.) +install(DIRECTORY + launch + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) + +############# +## Testing ## +############# + +roslaunch_add_file_check(launch) diff --git a/mir_robot/mir_driver/launch/mir.launch b/mir_robot/mir_driver/launch/mir.launch new file mode 100755 index 0000000..144b4b9 --- /dev/null +++ b/mir_robot/mir_driver/launch/mir.launch @@ -0,0 +1,85 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - base_link + - front_laser_link + - back_laser_link + - camera_top_link + - camera_top_depth_optical_frame + - camera_floor_link + - camera_floor_depth_optical_frame + - imu_link + + + + + + + + + + + + + + + + + + + + + - odom + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/mir_robot/mir_driver/nodes/fake_mir_joint_publisher.py b/mir_robot/mir_driver/nodes/fake_mir_joint_publisher.py new file mode 100755 index 0000000..2ad4830 --- /dev/null +++ b/mir_robot/mir_driver/nodes/fake_mir_joint_publisher.py @@ -0,0 +1,67 @@ +#!/usr/bin/env python3 +# Copyright (c) 2018-2022, Martin Günther (DFKI GmbH) and contributors +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# +# * Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in the +# documentation and/or other materials provided with the distribution. +# +# * Neither the name of the the copyright holder nor the names of its +# contributors may be used to endorse or promote products derived from +# this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE +# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +# Author: Martin Günther + +import rospy +from sensor_msgs.msg import JointState + + +def fake_mir_joint_publisher(): + rospy.init_node('fake_mir_joint_publisher') + prefix = rospy.get_param('~prefix', '') + pub = rospy.Publisher('joint_states', JointState, queue_size=10) + r = rospy.Rate(50.0) + while not rospy.is_shutdown(): + js = JointState() + js.header.stamp = rospy.Time.now() + js.name = [ + prefix + 'left_wheel_joint', + prefix + 'right_wheel_joint', + prefix + 'fl_caster_rotation_joint', + prefix + 'fl_caster_wheel_joint', + prefix + 'fr_caster_rotation_joint', + prefix + 'fr_caster_wheel_joint', + prefix + 'bl_caster_rotation_joint', + prefix + 'bl_caster_wheel_joint', + prefix + 'br_caster_rotation_joint', + prefix + 'br_caster_wheel_joint', + ] + js.position = [0.0 for _ in js.name] + js.velocity = [0.0 for _ in js.name] + js.effort = [0.0 for _ in js.name] + pub.publish(js) + r.sleep() + + +if __name__ == '__main__': + try: + fake_mir_joint_publisher() + except rospy.ROSInterruptException: + pass diff --git a/mir_robot/mir_driver/nodes/mir_bridge.py b/mir_robot/mir_driver/nodes/mir_bridge.py new file mode 100755 index 0000000..0c61a63 --- /dev/null +++ b/mir_robot/mir_driver/nodes/mir_bridge.py @@ -0,0 +1,529 @@ +#!/usr/bin/env python3 +# Copyright (c) 2018-2022, Martin Günther (DFKI GmbH) and contributors +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# +# * Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in the +# documentation and/or other materials provided with the distribution. +# +# * Neither the name of the the copyright holder nor the names of its +# contributors may be used to endorse or promote products derived from +# this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE +# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +# Author: Martin Günther + +import rospy + +import copy +import sys +from collections.abc import Iterable + +from mir_driver import rosbridge +from rospy_message_converter import message_converter + +from actionlib import SimpleActionClient +import actionlib_msgs.msg +import diagnostic_msgs.msg +import dynamic_reconfigure.msg +import geometry_msgs.msg +import mir_actions.msg +import mir_msgs.msg +import move_base_msgs.msg +import nav_msgs.msg +import rosgraph_msgs.msg +import sdc21x0.msg +import sensor_msgs.msg +import std_msgs.msg +import tf2_msgs.msg +import visualization_msgs.msg + +from collections import OrderedDict + +tf_prefix = '' +static_transforms = OrderedDict() + + +class TopicConfig(object): + def __init__(self, topic, topic_type, latch=False, dict_filter=None): + self.topic = topic + self.topic_type = topic_type + self.latch = latch + self.dict_filter = dict_filter + + +# remap mir_actions/MirMoveBaseAction => move_base_msgs/MoveBaseAction +def _move_base_goal_dict_filter(msg_dict): + filtered_msg_dict = copy.deepcopy(msg_dict) + filtered_msg_dict['goal']['move_task'] = mir_actions.msg.MirMoveBaseGoal.GLOBAL_MOVE + filtered_msg_dict['goal']['goal_dist_threshold'] = 0.25 + filtered_msg_dict['goal']['clear_costmaps'] = True + return filtered_msg_dict + + +def _move_base_feedback_dict_filter(msg_dict): + # filter out slots from the dict that are not in our message definition + # e.g., MiRMoveBaseFeedback has the field "state", which MoveBaseFeedback doesn't + filtered_msg_dict = copy.deepcopy(msg_dict) + filtered_msg_dict['feedback'] = { + key: msg_dict['feedback'][key] for key in move_base_msgs.msg.MoveBaseFeedback.__slots__ + } + return filtered_msg_dict + + +def _move_base_result_dict_filter(msg_dict): + filtered_msg_dict = copy.deepcopy(msg_dict) + filtered_msg_dict['result'] = {key: msg_dict['result'][key] for key in move_base_msgs.msg.MoveBaseResult.__slots__} + return filtered_msg_dict + + +def _cmd_vel_dict_filter(msg_dict): + """ + Convert Twist to TwistStamped. + + Convert a geometry_msgs/Twist message dict (as sent from the ROS side) to + a geometry_msgs/TwistStamped message dict (as expected by the MiR on + software version >=2.7). + """ + header = std_msgs.msg.Header(frame_id='', stamp=rospy.Time.now()) + filtered_msg_dict = { + 'header': message_converter.convert_ros_message_to_dictionary(header), + 'twist': copy.deepcopy(msg_dict), + } + return filtered_msg_dict + + +def _tf_dict_filter(msg_dict): + filtered_msg_dict = copy.deepcopy(msg_dict) + for transform in filtered_msg_dict['transforms']: + transform['child_frame_id'] = tf_prefix + '/' + transform['child_frame_id'].strip('/') + return filtered_msg_dict + + +def _tf_static_dict_filter(msg_dict): + """ + Cache tf_static messages (simulate latching). + + The tf_static topic needs special handling. Publishers on tf_static are *latched*, which means that the ROS master + caches the last message that was sent by each publisher on that topic, and will forward it to new subscribers. + However, since the mir_driver node appears to the ROS master as a single node with a single publisher on tf_static, + and there are multiple actual publishers hiding behind it on the MiR side, only one of those messages will be + cached. Therefore, we need to implement the caching ourselves and make sure that we always publish the full set of + transforms as a single message. + """ + global static_transforms + + # prepend tf_prefix + filtered_msg_dict = _tf_dict_filter(msg_dict) + + # The following code was copied + modified from https://github.com/tradr-project/static_transform_mux . + + # Process the incoming transforms, merge them with our cache. + for transform in filtered_msg_dict['transforms']: + key = transform['child_frame_id'] + rospy.loginfo( + "[%s] tf_static: updated transform %s->%s.", + rospy.get_name(), + transform['header']['frame_id'], + transform['child_frame_id'], + ) + static_transforms[key] = transform + + # Return the cached messages. + filtered_msg_dict['transforms'] = static_transforms.values() + rospy.loginfo( + "[%s] tf_static: sent %i transforms: %s", + rospy.get_name(), + len(static_transforms), + str(static_transforms.keys()), + ) + return filtered_msg_dict + + +def _prepend_tf_prefix_dict_filter(msg_dict): + # filtered_msg_dict = copy.deepcopy(msg_dict) + if not isinstance(msg_dict, dict): # can happen during recursion + return + for (key, value) in msg_dict.items(): + if key == 'header': + try: + # prepend frame_id + frame_id = value['frame_id'].strip('/') + if frame_id != 'map': + # prepend tf_prefix, then remove leading '/' (e.g., when tf_prefix is empty) + value['frame_id'] = (tf_prefix + '/' + frame_id).strip('/') + else: + value['frame_id'] = frame_id + + except TypeError: + pass # value is not a dict + except KeyError: + pass # value doesn't have key 'frame_id' + elif isinstance(value, dict): + _prepend_tf_prefix_dict_filter(value) + elif isinstance(value, Iterable): # an Iterable other than dict (e.g., a list) + for item in value: + _prepend_tf_prefix_dict_filter(item) + return msg_dict + + +def _remove_tf_prefix_dict_filter(msg_dict): + # filtered_msg_dict = copy.deepcopy(msg_dict) + if not isinstance(msg_dict, dict): # can happen during recursion + return + for (key, value) in msg_dict.items(): + if key == 'header': + try: + # remove frame_id + s = value['frame_id'].strip('/') + if s.find(tf_prefix) == 0: + value['frame_id'] = (s[len(tf_prefix) :]).strip('/') # strip off tf_prefix, then strip leading '/' + except TypeError: + pass # value is not a dict + except KeyError: + pass # value doesn't have key 'frame_id' + elif isinstance(value, dict): + _remove_tf_prefix_dict_filter(value) + elif isinstance(value, Iterable): # an Iterable other than dict (e.g., a list) + for item in value: + _remove_tf_prefix_dict_filter(item) + return msg_dict + + +# topics we want to publish to ROS (and subscribe to from the MiR) +PUB_TOPICS = [ + # TopicConfig('LightCtrl/bms_data', mir_msgs.msg.BMSData), + # TopicConfig('LightCtrl/charging_state', mir_msgs.msg.ChargingState), + TopicConfig('LightCtrl/us_list', sensor_msgs.msg.Range), + # TopicConfig('MC/battery_currents', mir_msgs.msg.BatteryCurrents), + # TopicConfig('MC/battery_voltage', std_msgs.msg.Float64), + TopicConfig('MC/currents', sdc21x0.msg.MotorCurrents), + # TopicConfig('MC/encoders', sdc21x0.msg.StampedEncoders), + TopicConfig('MissionController/CheckArea/visualization_marker', visualization_msgs.msg.Marker), + # TopicConfig('MissionController/goal_position_guid', std_msgs.msg.String), + # TopicConfig('MissionController/prompt_user', mir_msgs.msg.UserPrompt), + TopicConfig('SickPLC/parameter_descriptions', dynamic_reconfigure.msg.ConfigDescription), + TopicConfig('SickPLC/parameter_updates', dynamic_reconfigure.msg.Config), + # TopicConfig('active_mapping_guid', std_msgs.msg.String), + TopicConfig('amcl_pose', geometry_msgs.msg.PoseWithCovarianceStamped), + TopicConfig('b_raw_scan', sensor_msgs.msg.LaserScan), + TopicConfig('b_scan', sensor_msgs.msg.LaserScan), + TopicConfig('camera_floor/background', sensor_msgs.msg.PointCloud2), + TopicConfig('camera_floor/depth/parameter_descriptions', dynamic_reconfigure.msg.ConfigDescription), + TopicConfig('camera_floor/depth/parameter_updates', dynamic_reconfigure.msg.Config), + TopicConfig('camera_floor/depth/points', sensor_msgs.msg.PointCloud2), + TopicConfig('camera_floor/filter/visualization_marker', visualization_msgs.msg.Marker), + TopicConfig('camera_floor/floor', sensor_msgs.msg.PointCloud2), + TopicConfig('camera_floor/obstacles', sensor_msgs.msg.PointCloud2), + TopicConfig('check_area/polygon', geometry_msgs.msg.PolygonStamped), + # TopicConfig('check_pose_area/polygon', geometry_msgs.msg.PolygonStamped), + # TopicConfig('data_events/area_events', mir_data_msgs.msg.AreaEventEvent), + # TopicConfig('data_events/maps', mir_data_msgs.msg.MapEvent), + # TopicConfig('data_events/positions', mir_data_msgs.msg.PositionEvent), + # TopicConfig('data_events/registers', mir_data_msgs.msg.PLCRegisterEvent), + # TopicConfig('data_events/sounds', mir_data_msgs.msg.SoundEvent), + TopicConfig('diagnostics', diagnostic_msgs.msg.DiagnosticArray), + TopicConfig('diagnostics_agg', diagnostic_msgs.msg.DiagnosticArray), + TopicConfig('diagnostics_toplevel_state', diagnostic_msgs.msg.DiagnosticStatus), + TopicConfig('f_raw_scan', sensor_msgs.msg.LaserScan), + TopicConfig('f_scan', sensor_msgs.msg.LaserScan), + TopicConfig('imu_data', sensor_msgs.msg.Imu), + TopicConfig('laser_back/driver/parameter_descriptions', dynamic_reconfigure.msg.ConfigDescription), + TopicConfig('laser_back/driver/parameter_updates', dynamic_reconfigure.msg.Config), + TopicConfig('laser_front/driver/parameter_descriptions', dynamic_reconfigure.msg.ConfigDescription), + TopicConfig('laser_front/driver/parameter_updates', dynamic_reconfigure.msg.Config), + # TopicConfig('localization_score', std_msgs.msg.Float64), + TopicConfig('/map', nav_msgs.msg.OccupancyGrid, latch=True), + TopicConfig('/map_metadata', nav_msgs.msg.MapMetaData), + # TopicConfig('marker_tracking_node/feedback', mir_marker_tracking.msg.MarkerTrackingActionFeedback), + # TopicConfig( + # 'marker_tracking_node/laser_line_extract/parameter_descriptions', dynamic_reconfigure.msg.ConfigDescription + # ), + # TopicConfig('marker_tracking_node/laser_line_extract/parameter_updates', dynamic_reconfigure.msg.Config), + # TopicConfig('marker_tracking_node/laser_line_extract/visualization_marker', visualization_msgs.msg.Marker), + # TopicConfig('marker_tracking_node/result', mir_marker_tracking.msg.MarkerTrackingActionResult), + # TopicConfig('marker_tracking_node/status', actionlib_msgs.msg.GoalStatusArray), + # TopicConfig('mirEventTrigger/events', mir_msgs.msg.Events), + TopicConfig('mir_amcl/parameter_descriptions', dynamic_reconfigure.msg.ConfigDescription), + TopicConfig('mir_amcl/parameter_updates', dynamic_reconfigure.msg.Config), + TopicConfig('mir_amcl/selected_points', sensor_msgs.msg.PointCloud2), + TopicConfig('mir_log', rosgraph_msgs.msg.Log), + # TopicConfig('mir_sound/sound_event', mir_msgs.msg.SoundEvent), + TopicConfig('mir_status_msg', std_msgs.msg.String), + # TopicConfig('mirspawn/node_events', mirSpawn.msg.LaunchItem), + TopicConfig('mirwebapp/grid_map_metadata', mir_msgs.msg.LocalMapStat), + TopicConfig('mirwebapp/laser_map_metadata', mir_msgs.msg.LocalMapStat), + # TopicConfig('mirwebapp/web_path', mir_msgs.msg.WebPath), + # really mir_actions/MirMoveBaseActionFeedback: + TopicConfig( + 'move_base/feedback', move_base_msgs.msg.MoveBaseActionFeedback, dict_filter=_move_base_feedback_dict_filter + ), + # really mir_actions/MirMoveBaseActionResult: + TopicConfig('move_base/result', move_base_msgs.msg.MoveBaseActionResult, dict_filter=_move_base_result_dict_filter), + TopicConfig('move_base/status', actionlib_msgs.msg.GoalStatusArray), + # TopicConfig('move_base_node/MIRPlannerROS/cost_cloud', sensor_msgs.msg.PointCloud2), + # TopicConfig('move_base_node/MIRPlannerROS/global_plan', nav_msgs.msg.Path), + # TopicConfig('move_base_node/MIRPlannerROS/len_to_goal', std_msgs.msg.Float64), + TopicConfig('move_base_node/MIRPlannerROS/local_plan', nav_msgs.msg.Path), + # TopicConfig('move_base_node/MIRPlannerROS/parameter_descriptions', dynamic_reconfigure.msg.ConfigDescription), + # TopicConfig('move_base_node/MIRPlannerROS/parameter_updates', dynamic_reconfigure.msg.Config), + TopicConfig('move_base_node/MIRPlannerROS/updated_global_plan', mir_msgs.msg.PlanSegments), + # TopicConfig('move_base_node/MIRPlannerROS/visualization_marker', visualization_msgs.msg.MarkerArray), + TopicConfig('move_base_node/SBPLLatticePlanner/plan', nav_msgs.msg.Path), + # TopicConfig( + # 'move_base_node/SBPLLatticePlanner/sbpl_lattice_planner_stats', sbpl_lattice_planner.msg.SBPLLatticePlannerStats + # ), + # TopicConfig('move_base_node/SBPLLatticePlanner/visualization_marker', visualization_msgs.msg.MarkerArray), + TopicConfig('move_base_node/current_goal', geometry_msgs.msg.PoseStamped), + # TopicConfig('move_base_node/global_costmap/inflated_obstacles', nav_msgs.msg.GridCells), + # TopicConfig('move_base_node/global_costmap/obstacles', nav_msgs.msg.GridCells), + # TopicConfig('move_base_node/global_costmap/parameter_descriptions', dynamic_reconfigure.msg.ConfigDescription), + # TopicConfig('move_base_node/global_costmap/parameter_updates', dynamic_reconfigure.msg.Config), + # TopicConfig('move_base_node/global_costmap/robot_footprint', geometry_msgs.msg.PolygonStamped), + # TopicConfig('move_base_node/global_costmap/unknown_space', nav_msgs.msg.GridCells), + # TopicConfig('move_base_node/global_plan', nav_msgs.msg.Path), + TopicConfig('move_base_node/local_costmap/inflated_obstacles', nav_msgs.msg.GridCells), + TopicConfig('move_base_node/local_costmap/obstacles', nav_msgs.msg.GridCells), + # TopicConfig('move_base_node/local_costmap/parameter_descriptions', dynamic_reconfigure.msg.ConfigDescription), + # TopicConfig('move_base_node/local_costmap/parameter_updates', dynamic_reconfigure.msg.Config), + TopicConfig('move_base_node/local_costmap/robot_footprint', geometry_msgs.msg.PolygonStamped), + # TopicConfig('move_base_node/local_costmap/safety_zone', geometry_msgs.msg.PolygonStamped), + # TopicConfig('move_base_node/local_costmap/unknown_space', nav_msgs.msg.GridCells), + # TopicConfig('move_base_node/mir_escape_recovery/visualization_marker', visualization_msgs.msg.Marker), + # TopicConfig('move_base_node/parameter_descriptions', dynamic_reconfigure.msg.ConfigDescription), + # TopicConfig('move_base_node/parameter_updates', dynamic_reconfigure.msg.Config), + TopicConfig('move_base_node/time_to_coll', std_msgs.msg.Float64), + TopicConfig('move_base_node/traffic_costmap/inflated_obstacles', nav_msgs.msg.GridCells), + TopicConfig('move_base_node/traffic_costmap/obstacles', nav_msgs.msg.GridCells), + TopicConfig('move_base_node/traffic_costmap/parameter_descriptions', dynamic_reconfigure.msg.ConfigDescription), + TopicConfig('move_base_node/traffic_costmap/parameter_updates', dynamic_reconfigure.msg.Config), + TopicConfig('move_base_node/traffic_costmap/robot_footprint', geometry_msgs.msg.PolygonStamped), + TopicConfig('move_base_node/traffic_costmap/unknown_space', nav_msgs.msg.GridCells), + TopicConfig('move_base_node/visualization_marker', visualization_msgs.msg.Marker), + TopicConfig('move_base_simple/visualization_marker', visualization_msgs.msg.Marker), + TopicConfig('odom', nav_msgs.msg.Odometry), + TopicConfig('odom_enc', nav_msgs.msg.Odometry), + # TopicConfig('one_way_map', nav_msgs.msg.OccupancyGrid), + # TopicConfig('param_update', std_msgs.msg.String), + # TopicConfig('particlevizmarker', visualization_msgs.msg.MarkerArray), + # TopicConfig('resource_tracker/needed_resources', mir_msgs.msg.ResourcesState), + TopicConfig('robot_mode', mir_msgs.msg.RobotMode), + TopicConfig('robot_pose', geometry_msgs.msg.Pose), + TopicConfig('robot_state', mir_msgs.msg.RobotState), + # TopicConfig('robot_status', mir_msgs.msg.RobotStatus), + TopicConfig('/rosout', rosgraph_msgs.msg.Log), + TopicConfig('/rosout_agg', rosgraph_msgs.msg.Log), + TopicConfig('scan', sensor_msgs.msg.LaserScan), + # TopicConfig('scan_filter/parameter_descriptions', dynamic_reconfigure.msg.ConfigDescription), + # TopicConfig('scan_filter/parameter_updates', dynamic_reconfigure.msg.Config), + TopicConfig('scan_filter/visualization_marker', visualization_msgs.msg.Marker), + # TopicConfig('session_importer_node/info', mirSessionImporter.msg.SessionImportInfo), + # TopicConfig('set_mc_PID', std_msgs.msg.Float64MultiArray), + TopicConfig('/tf', tf2_msgs.msg.TFMessage, dict_filter=_tf_dict_filter), + TopicConfig('/tf_static', tf2_msgs.msg.TFMessage, dict_filter=_tf_static_dict_filter, latch=True), + # TopicConfig('traffic_map', nav_msgs.msg.OccupancyGrid), + # TopicConfig('wifi_diagnostics', diagnostic_msgs.msg.DiagnosticArray), + # TopicConfig('wifi_diagnostics/cur_ap', mir_wifi_msgs.msg.APInfo), + # TopicConfig('wifi_diagnostics/roam_events', mir_wifi_msgs.msg.WifiRoamEvent), + # TopicConfig('wifi_diagnostics/wifi_ap_interface_stats', mir_wifi_msgs.msg.WifiInterfaceStats), + # TopicConfig('wifi_diagnostics/wifi_ap_rssi', mir_wifi_msgs.msg.APRssiStats), + # TopicConfig('wifi_diagnostics/wifi_ap_time_stats', mir_wifi_msgs.msg.APTimeStats), + # TopicConfig('wifi_watchdog/ping', mir_wifi_msgs.msg.APPingStats), +] + +# topics we want to subscribe to from ROS (and publish to the MiR) +SUB_TOPICS = [ + # really geometry_msgs.msg.TwistStamped: + TopicConfig('cmd_vel', geometry_msgs.msg.Twist, dict_filter=_cmd_vel_dict_filter), + TopicConfig('initialpose', geometry_msgs.msg.PoseWithCovarianceStamped), + TopicConfig('light_cmd', std_msgs.msg.String), + TopicConfig('mir_cmd', std_msgs.msg.String), + TopicConfig('move_base/cancel', actionlib_msgs.msg.GoalID), + # really mir_actions/MirMoveBaseActionGoal: + TopicConfig('move_base/goal', move_base_msgs.msg.MoveBaseActionGoal, dict_filter=_move_base_goal_dict_filter), +] + + +class PublisherWrapper(rospy.SubscribeListener): + def __init__(self, topic_config, robot): + self.topic_config = topic_config + self.robot = robot + self.connected = False + # Use topic_config.topic directly here. If it does not have a leading slash, it will use the private namespace. + self.pub = rospy.Publisher( + name=topic_config.topic, + data_class=topic_config.topic_type, + subscriber_listener=self, + latch=topic_config.latch, + queue_size=10, + ) + rospy.loginfo( + "[%s] publishing topic '%s' [%s]", rospy.get_name(), topic_config.topic, topic_config.topic_type._type + ) + # latched topics must be subscribed immediately + if topic_config.latch: + self.peer_subscribe("", None, None) + + def peer_subscribe(self, topic_name, topic_publish, peer_publish): + if not self.connected: + self.connected = True + rospy.loginfo("[%s] starting to stream messages on topic '%s'", rospy.get_name(), self.topic_config.topic) + absolute_topic = '/' + self.topic_config.topic.lstrip('/') # ensure exactly 1 leading slash for MiR comm + self.robot.subscribe(topic=absolute_topic, callback=self.callback) + + def peer_unsubscribe(self, topic_name, num_peers): + pass + # doesn't work: once ubsubscribed, robot doesn't let us subscribe again + # if self.connected and self.pub.get_num_connections() == 0 and not self.topic_config.latch: + # self.connected = False + # rospy.loginfo("[%s] stopping to stream messages on topic '%s'", rospy.get_name(), self.topic_config.topic) + # absolute_topic = '/' + self.topic_config.topic.lstrip('/') # ensure exactly 1 leading slash for MiR comm + # self.robot.unsubscribe(topic=absolute_topic) + + def callback(self, msg_dict): + msg_dict = _prepend_tf_prefix_dict_filter(msg_dict) + if self.topic_config.dict_filter is not None: + msg_dict = self.topic_config.dict_filter(msg_dict) + msg = message_converter.convert_dictionary_to_ros_message(self.topic_config.topic_type._type, msg_dict) + self.pub.publish(msg) + + +class SubscriberWrapper(object): + def __init__(self, topic_config, robot): + self.topic_config = topic_config + self.robot = robot + # Use topic_config.topic directly here. If it does not have a leading slash, it will use the private namespace. + self.sub = rospy.Subscriber( + name=topic_config.topic, data_class=topic_config.topic_type, callback=self.callback, queue_size=10 + ) + rospy.loginfo( + "[%s] subscribing to topic '%s' [%s]", rospy.get_name(), topic_config.topic, topic_config.topic_type._type + ) + + def callback(self, msg): + msg_dict = message_converter.convert_ros_message_to_dictionary(msg) + msg_dict = _remove_tf_prefix_dict_filter(msg_dict) + if self.topic_config.dict_filter is not None: + msg_dict = self.topic_config.dict_filter(msg_dict) + absolute_topic = '/' + self.topic_config.topic.lstrip('/') # ensure exactly 1 leading slash for MiR comm + self.robot.publish(absolute_topic, msg_dict) + + +class MiRBridge(object): + def __init__(self): + try: + hostname = rospy.get_param('~hostname') + except KeyError: + rospy.logfatal('[%s] parameter "hostname" is not set!', rospy.get_name()) + sys.exit(-1) + port = rospy.get_param('~port', 9090) + + global tf_prefix + tf_prefix = rospy.get_param('~tf_prefix', '').strip('/') + + rospy.loginfo('[%s] trying to connect to %s:%i...', rospy.get_name(), hostname, port) + self.robot = rosbridge.RosbridgeSetup(hostname, port) + + r = rospy.Rate(10) + i = 1 + while not self.robot.is_connected(): + if rospy.is_shutdown(): + sys.exit(0) + if self.robot.is_errored(): + rospy.logfatal('[%s] connection error to %s:%i, giving up!', rospy.get_name(), hostname, port) + sys.exit(-1) + if i % 10 == 0: + rospy.logwarn('[%s] still waiting for connection to %s:%i...', rospy.get_name(), hostname, port) + i += 1 + r.sleep() + + rospy.loginfo('[%s] ... connected.', rospy.get_name()) + + topics = self.get_topics() + published_topics = [topic_name for (topic_name, _, has_publishers, _) in topics if has_publishers] + subscribed_topics = [topic_name for (topic_name, _, _, has_subscribers) in topics if has_subscribers] + + for pub_topic in PUB_TOPICS: + PublisherWrapper(pub_topic, self.robot) + absolute_topic = '/' + pub_topic.topic.lstrip('/') # ensure exactly 1 leading slash for MiR comm + if absolute_topic not in published_topics: + rospy.logwarn("[%s] topic '%s' is not published by the MiR!", rospy.get_name(), pub_topic.topic) + + for sub_topic in SUB_TOPICS: + SubscriberWrapper(sub_topic, self.robot) + absolute_topic = '/' + sub_topic.topic.lstrip('/') # ensure exactly 1 leading slash for MiR comm + if absolute_topic not in subscribed_topics: + rospy.logwarn("[%s] topic '%s' is not yet subscribed to by the MiR!", rospy.get_name(), sub_topic.topic) + + # At least with software version 2.8 there were issues when forwarding a simple goal to the robot + # This workaround converts it into an action. Check https://github.com/DFKI-NI/mir_robot/issues/60 for details. + self._move_base_client = SimpleActionClient('move_base', move_base_msgs.msg.MoveBaseAction) + rospy.Subscriber("move_base_simple/goal", geometry_msgs.msg.PoseStamped, self._move_base_simple_goal_callback) + + def get_topics(self): + srv_response = self.robot.callService('/rosapi/topics', msg={}) + topic_names = sorted(srv_response['topics']) + topics = [] + + for topic_name in topic_names: + srv_response = self.robot.callService("/rosapi/topic_type", msg={'topic': topic_name}) + topic_type = srv_response['type'] + + srv_response = self.robot.callService("/rosapi/publishers", msg={'topic': topic_name}) + has_publishers = True if len(srv_response['publishers']) > 0 else False + + srv_response = self.robot.callService("/rosapi/subscribers", msg={'topic': topic_name}) + has_subscribers = True if len(srv_response['subscribers']) > 0 else False + + topics.append([topic_name, topic_type, has_publishers, has_subscribers]) + + print('Publishers:') + for (topic_name, topic_type, has_publishers, has_subscribers) in topics: + if has_publishers: + print((' * %s [%s]' % (topic_name, topic_type))) + + print('\nSubscribers:') + for (topic_name, topic_type, has_publishers, has_subscribers) in topics: + if has_subscribers: + print((' * %s [%s]' % (topic_name, topic_type))) + + return topics + + def _move_base_simple_goal_callback(self, msg): + if not self._move_base_client.wait_for_server(rospy.Duration(2)): + rospy.logwarn("Could not connect to 'move_base' server after two seconds. Dropping goal.") + rospy.logwarn("Did you activate 'planner' in the MIR web interface?") + return + goal = move_base_msgs.msg.MoveBaseGoal() + goal.target_pose.header = copy.deepcopy(msg.header) + goal.target_pose.pose = copy.deepcopy(msg.pose) + self._move_base_client.send_goal(goal) + + +def main(): + rospy.init_node('mir_bridge') + MiRBridge() + rospy.spin() + + +if __name__ == '__main__': + try: + main() + except rospy.ROSInterruptException: + pass diff --git a/mir_robot/mir_driver/nodes/rep117_filter.py b/mir_robot/mir_driver/nodes/rep117_filter.py new file mode 100755 index 0000000..d8d66f8 --- /dev/null +++ b/mir_robot/mir_driver/nodes/rep117_filter.py @@ -0,0 +1,76 @@ +#!/usr/bin/env python3 + +# Copyright (c) 2018-2022, Martin Günther (DFKI GmbH) and contributors +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# +# * Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in the +# documentation and/or other materials provided with the distribution. +# +# * Neither the name of the the copyright holder nor the names of its +# contributors may be used to endorse or promote products derived from +# this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE +# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +# Author: Martin Günther + +import rospy +from sensor_msgs.msg import LaserScan + +pub = None + + +def callback(msg): + """ + Convert laser scans to REP 117 standard. + + See http://www.ros.org/reps/rep-0117.html + """ + ranges_out = [] + for dist in msg.ranges: + if dist < msg.range_min: + # assume "reading too close to measure", + # although it could also be "reading invalid" (nan) + ranges_out.append(float("-inf")) + + elif dist > msg.range_max: + # assume "reading of no return (outside sensor range)", + # although it could also be "reading invalid" (nan) + ranges_out.append(float("inf")) + else: + ranges_out.append(dist) + + msg.ranges = ranges_out + pub.publish(msg) + + +def main(): + global pub + rospy.init_node('rep117_filter') + + pub = rospy.Publisher('scan_filtered', LaserScan, queue_size=10) + rospy.Subscriber('scan', LaserScan, callback) + rospy.spin() + + +if __name__ == '__main__': + try: + main() + except rospy.ROSInterruptException: + pass diff --git a/mir_robot/mir_driver/nodes/tf_remove_child_frames.py b/mir_robot/mir_driver/nodes/tf_remove_child_frames.py new file mode 100755 index 0000000..26dcfe1 --- /dev/null +++ b/mir_robot/mir_driver/nodes/tf_remove_child_frames.py @@ -0,0 +1,51 @@ +#!/usr/bin/env python3 +# -*- coding: utf-8 -*- + +# Copyright 2016 The Cartographer Authors +# Copyright 2018 DFKI GmbH +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import rospy +from tf.msg import tfMessage + + +def main(): + rospy.init_node('tf_remove_child_frames') + remove_frames = rospy.get_param('~remove_frames', []) + + # filter tf_in topic + tf_pub = rospy.Publisher('tf_out', tfMessage, queue_size=1) + + def tf_cb(msg): + msg.transforms = [t for t in msg.transforms if t.child_frame_id.lstrip('/') not in remove_frames] + if len(msg.transforms) > 0: + tf_pub.publish(msg) + + rospy.Subscriber('tf_in', tfMessage, tf_cb) + + # filter tf_static_in topic + tf_static_pub = rospy.Publisher('tf_static_out', tfMessage, queue_size=1, latch=True) + + def tf_static_cb(msg): + msg.transforms = [t for t in msg.transforms if t.child_frame_id.lstrip('/') not in remove_frames] + if len(msg.transforms) > 0: + tf_static_pub.publish(msg) + + rospy.Subscriber('tf_static_in', tfMessage, tf_static_cb) + + rospy.spin() + + +if __name__ == '__main__': + main() diff --git a/mir_robot/mir_driver/package.xml b/mir_robot/mir_driver/package.xml new file mode 100755 index 0000000..134dcf0 --- /dev/null +++ b/mir_robot/mir_driver/package.xml @@ -0,0 +1,40 @@ + + + mir_driver + 1.1.7 + A reverse ROS bridge for the MiR robot + + Martin Günther + Martin Günther + + BSD + Apache 2.0 + + https://github.com/DFKI-NI/mir_robot + https://github.com/DFKI-NI/mir_robot + https://github.com/DFKI-NI/mir_robot/issues + + catkin + + roslaunch + + actionlib_msgs + diagnostic_msgs + dynamic_reconfigure + geometry_msgs + mir_actions + mir_msgs + move_base_msgs + nav_msgs + python3-websocket + rosgraph_msgs + rospy + rospy_message_converter + sensor_msgs + std_msgs + tf + visualization_msgs + + mir_description + robot_state_publisher + diff --git a/mir_robot/mir_driver/setup.py b/mir_robot/mir_driver/setup.py new file mode 100755 index 0000000..6f789db --- /dev/null +++ b/mir_robot/mir_driver/setup.py @@ -0,0 +1,9 @@ +# ! DO NOT MANUALLY INVOKE THIS setup.py, USE CATKIN INSTEAD + +from distutils.core import setup +from catkin_pkg.python_setup import generate_distutils_setup + +# fetch values from package.xml +setup_args = generate_distutils_setup(packages=['mir_driver'], package_dir={'': 'src'}) + +setup(**setup_args) diff --git a/mir_robot/mir_driver/src/mir_driver/__init__.py b/mir_robot/mir_driver/src/mir_driver/__init__.py new file mode 100755 index 0000000..e69de29 diff --git a/mir_robot/mir_driver/src/mir_driver/rosbridge.py b/mir_robot/mir_driver/src/mir_driver/rosbridge.py new file mode 100755 index 0000000..e96fb94 --- /dev/null +++ b/mir_robot/mir_driver/src/mir_driver/rosbridge.py @@ -0,0 +1,214 @@ +# Copyright (c) 2018-2022, Martin Günther (DFKI GmbH) and contributors +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# +# * Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in the +# documentation and/or other materials provided with the distribution. +# +# * Neither the name of the the copyright holder nor the names of its +# contributors may be used to endorse or promote products derived from +# this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE +# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. + +import websocket +import threading + +import json +import traceback +import time + +import string +import random + + +class RosbridgeSetup: + def __init__(self, host, port): + self.callbacks = {} + self.service_callbacks = {} + self.resp = None + self.connection = RosbridgeWSConnection(host, port) + self.connection.registerCallback(self.onMessageReceived) + + def publish(self, topic, obj): + pub = {"op": "publish", "topic": topic, "msg": obj} + self.send(pub) + + def subscribe(self, topic, callback, throttle_rate=-1): + if self.addCallback(topic, callback): + sub = {"op": "subscribe", "topic": topic} + if throttle_rate > 0: + sub['throttle_rate'] = throttle_rate + + self.send(sub) + + def unhook(self, callback): + keys_for_deletion = [] + for key, values in self.callbacks.items(): + for value in values: + if callback == value: + print("Found!") + values.remove(value) + if len(values) == 0: + keys_for_deletion.append(key) + + for key in keys_for_deletion: + self.unsubscribe(key) + self.callbacks.pop(key) + + def unsubscribe(self, topic): + unsub = {"op": "unsubscribe", "topic": topic} + self.send(unsub) + + def callService(self, serviceName, callback=None, msg=None): + id = self.generate_id() + call = {"op": "call_service", "id": id, "service": serviceName} + if msg is not None: + call['args'] = msg + + if callback is None: + self.resp = None + + def internalCB(msg): + self.resp = msg + return None + + self.addServiceCallback(id, internalCB) + self.send(call) + + while self.resp is None: + time.sleep(0.01) + + return self.resp + + self.addServiceCallback(id, callback) + self.send(call) + return None + + def send(self, obj): + try: + self.connection.sendString(json.dumps(obj)) + except Exception: + traceback.print_exc() + raise + + def generate_id(self, chars=16): + return ''.join(random.SystemRandom().choice(string.ascii_letters + string.digits) for _ in range(chars)) + + def addServiceCallback(self, id, callback): + self.service_callbacks[id] = callback + + def addCallback(self, topic, callback): + if topic in self.callbacks: + self.callbacks[topic].append(callback) + return False + + self.callbacks[topic] = [callback] + return True + + def is_connected(self): + return self.connection.connected + + def is_errored(self): + return self.connection.errored + + def onMessageReceived(self, message): + try: + # Load the string into a JSON object + obj = json.loads(message) + # print "Received: ", obj + + if 'op' in obj: + option = obj['op'] + if option == "publish": # A message from a topic we have subscribed to.. + topic = obj["topic"] + msg = obj["msg"] + if topic in self.callbacks: + for callback in self.callbacks[topic]: + try: + callback(msg) + except Exception: + print("exception on callback", callback, "from", topic) + traceback.print_exc() + raise + elif option == "service_response": + if "id" in obj: + id = obj["id"] + values = obj["values"] + if id in self.service_callbacks: + try: + # print 'id:', id, 'func:', self.service_callbacks[id] + self.service_callbacks[id](values) + except Exception: + print("exception on callback ID:", id) + traceback.print_exc() + raise + else: + print("Missing ID!") + else: + print("Recieved unknown option - it was: ", option) + else: + print("No OP key!") + except Exception: + print("exception in onMessageReceived") + print("message", message) + traceback.print_exc() + raise + + +class RosbridgeWSConnection: + def __init__(self, host, port): + self.ws = websocket.WebSocketApp( + ("ws://%s:%d/" % (host, port)), on_message=self.on_message, on_error=self.on_error, on_close=self.on_close + ) + self.ws.on_open = self.on_open + self.run_thread = threading.Thread(target=self.run) + self.run_thread.start() + self.connected = False + self.errored = False + self.callbacks = [] + + def on_open(self): + print("### ROS bridge connected ###") + self.connected = True + + def sendString(self, message): + if not self.connected: + print("Error: not connected, could not send message") + # TODO: throw exception + else: + self.ws.send(message) + + def on_error(self, error): + self.errored = True + print("Error: %s" % error) + + def on_close(self): + self.connected = False + print("### ROS bridge closed ###") + + def run(self, *args): + self.ws.run_forever() + + def on_message(self, message): + # Call the handlers + for callback in self.callbacks: + callback(message) + + def registerCallback(self, callback): + self.callbacks.append(callback) diff --git a/mir_robot/mir_dwb_critics/CHANGELOG.rst b/mir_robot/mir_dwb_critics/CHANGELOG.rst new file mode 100755 index 0000000..4351079 --- /dev/null +++ b/mir_robot/mir_dwb_critics/CHANGELOG.rst @@ -0,0 +1,78 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package mir_dwb_critics +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +1.1.7 (2023-01-20) +------------------ +* Don't set cmake_policy CMP0048 +* Drop old C++ compiler flags +* Add license headers +* Contributors: Martin Günther + +1.1.6 (2022-06-02) +------------------ + +1.1.5 (2022-02-11) +------------------ + +1.1.4 (2021-12-10) +------------------ + +1.1.3 (2021-06-11) +------------------ +* Merge branch 'melodic-2.8' into noetic +* Reformat python code using black +* Contributors: Martin Günther + +1.1.2 (2021-05-12) +------------------ + +1.1.1 (2021-02-11) +------------------ +* Fix bug in path_dist_pruned + With some paths, the previous code crashed with "terminate called after throwing an instance + of 'std::bad_alloc'". +* Contributors: Martin Günther + +1.1.0 (2020-06-30) +------------------ +* Initial release into noetic +* Update scripts to Python3 (Noetic) +* Contributors: Martin Günther + +1.0.6 (2020-06-30) +------------------ +* Add missing matplotlib dependency +* Fix some catkin_lint warnings +* Set cmake_policy CMP0048 to fix warning +* Contributors: Martin Günther + +1.0.5 (2020-05-01) +------------------ +* mir_dwb_critics: Add plot_dwb_scores.py +* mir_dwb_critics: Improve print_dwb_scores output +* added PathDistPrunedCritic for dwb (`#42 `_) + which works exactly like the original PathDistCritic, except that it + searches for a local minimum in the distance from the global path to the robots + current position. It then prunes the global_path from the start up to + this point, therefore approximately cutting of a segment of the path + that the robot already followed. +* Contributors: Martin Günther, Nils Niemann + +1.0.4 (2019-05-06) +------------------ + +1.0.3 (2019-03-04) +------------------ +* PathProgressCritic: Add heading score +* Add package: mir_dwb_critics +* Contributors: Martin Günther + +1.0.2 (2018-07-30) +------------------ + +1.0.1 (2018-07-17) +------------------ + +1.0.0 (2018-07-12) +------------------ diff --git a/mir_robot/mir_dwb_critics/CMakeLists.txt b/mir_robot/mir_dwb_critics/CMakeLists.txt new file mode 100755 index 0000000..89e5c9c --- /dev/null +++ b/mir_robot/mir_dwb_critics/CMakeLists.txt @@ -0,0 +1,55 @@ +cmake_minimum_required(VERSION 3.5.1) +project(mir_dwb_critics) + +set_directory_properties(PROPERTIES COMPILE_OPTIONS "-Wall;-Werror") + +find_package(catkin REQUIRED COMPONENTS + angles + costmap_queue + dwb_critics + dwb_local_planner + geometry_msgs + nav_2d_msgs + nav_2d_utils + nav_core2 + nav_grid_iterators + pluginlib + roscpp + sensor_msgs +) + +catkin_package( + INCLUDE_DIRS include + LIBRARIES ${PROJECT_NAME} + CATKIN_DEPENDS angles costmap_queue dwb_critics dwb_local_planner geometry_msgs nav_2d_msgs nav_2d_utils nav_core2 nav_grid_iterators pluginlib roscpp sensor_msgs +) + +include_directories( + include + ${catkin_INCLUDE_DIRS} +) + +add_library(${PROJECT_NAME} + src/path_angle.cpp + src/path_progress.cpp + src/path_dist_pruned.cpp +) +add_dependencies(${PROJECT_NAME} ${catkin_EXPORTED_TARGETS}) +target_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES}) + +install(PROGRAMS + nodes/print_dwb_scores.py + nodes/plot_dwb_scores.py + DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) +install(TARGETS ${PROJECT_NAME} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} +) +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} +) +install(FILES default_critics.xml + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) diff --git a/mir_robot/mir_dwb_critics/default_critics.xml b/mir_robot/mir_dwb_critics/default_critics.xml new file mode 100755 index 0000000..8c056bf --- /dev/null +++ b/mir_robot/mir_dwb_critics/default_critics.xml @@ -0,0 +1,13 @@ + + + + Scores trajectories based on how far along the global path they end up. + + + TODO + + + Scores trajectories based on the distance to the global path, only taking the parts into account that are still ahead of the robot. + + + diff --git a/mir_robot/mir_dwb_critics/include/mir_dwb_critics/path_angle.h b/mir_robot/mir_dwb_critics/include/mir_dwb_critics/path_angle.h new file mode 100755 index 0000000..0c70097 --- /dev/null +++ b/mir_robot/mir_dwb_critics/include/mir_dwb_critics/path_angle.h @@ -0,0 +1,71 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2019, DFKI GmbH + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ +#ifndef MIR_DWB_CRITICS_PATH_ANGLE_H_ +#define MIR_DWB_CRITICS_PATH_ANGLE_H_ + +#include +#include + +namespace mir_dwb_critics +{ +/** + * @class PathAngleCritic + * @brief Scores trajectories based on the difference between the path's current angle and the trajectory's angle + * + * This trajectory critic helps to ensure that the robot is roughly aligned with the path (i.e., + * if the path specifies a forward motion, the robot should point forward along the path and vice versa). + * This critic is not a replacement for the PathAlignCritic: The PathAlignCritic tries to point the robot + * towards a point on the path that is in front of the trajectory's end point, so it helps guiding the + * robot back towards the path. The PathAngleCritic on the other hand uses the path point that is closest + * to the robot's current position (not the trajectory end point, or even a point in front of that) as a + * reference, so it always lags behind. Also, it tries to keep the robot parallel to the path, not towards + * it. For these reasons, the error is squared, so that the PathAngleCritic really only affects the final + * score if the error is large. The PathAlignCritic doesn't take the path orientation into account though, + * so that's why the PathAngleCritic is a useful addition. + */ +class PathAngleCritic: public dwb_local_planner::TrajectoryCritic +{ +public: + virtual bool prepare(const geometry_msgs::Pose2D& pose, const nav_2d_msgs::Twist2D& vel, + const geometry_msgs::Pose2D& goal, + const nav_2d_msgs::Path2D& global_plan) override; + + virtual double scoreTrajectory(const dwb_msgs::Trajectory2D& traj) override; + +protected: + double desired_angle_; +}; + +} // namespace mir_dwb_critics +#endif // MIR_DWB_CRITICS_PATH_ANGLE_H_ diff --git a/mir_robot/mir_dwb_critics/include/mir_dwb_critics/path_dist_pruned.h b/mir_robot/mir_dwb_critics/include/mir_dwb_critics/path_dist_pruned.h new file mode 100755 index 0000000..81e5738 --- /dev/null +++ b/mir_robot/mir_dwb_critics/include/mir_dwb_critics/path_dist_pruned.h @@ -0,0 +1,56 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2019, DFKI GmbH + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ +#ifndef MIR_DWB_CRITICS_PATH_DISTANCE_PRUNED_H_ +#define MIR_DWB_CRITICS_PATH_DISTANCE_PRUNED_H_ + +#include +#include + +namespace mir_dwb_critics +{ +/** + * @class PathDistPrunedCritic + * @brief Scores trajectories based on how far from the global path they end up, + * where the global path is pruned to only include waypoints ahead of the + * robot. + */ +class PathDistPrunedCritic : public dwb_critics::PathDistCritic { +public: + virtual bool prepare(const geometry_msgs::Pose2D& pose, const nav_2d_msgs::Twist2D& vel, + const geometry_msgs::Pose2D& goal, + const nav_2d_msgs::Path2D& global_plan) override; +}; + +} // namespace mir_dwb_critics +#endif // MIR_DWB_CRITICS_DISTANCE_PRUNED_H_ diff --git a/mir_robot/mir_dwb_critics/include/mir_dwb_critics/path_progress.h b/mir_robot/mir_dwb_critics/include/mir_dwb_critics/path_progress.h new file mode 100755 index 0000000..a5942df --- /dev/null +++ b/mir_robot/mir_dwb_critics/include/mir_dwb_critics/path_progress.h @@ -0,0 +1,86 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2019, DFKI GmbH + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ +#ifndef MIR_DWB_CRITICS_PATH_PROGRESS_H_ +#define MIR_DWB_CRITICS_PATH_PROGRESS_H_ + +#include +#include +#include +#include +#include + +namespace mir_dwb_critics { +/** + * @class PathProgressCritic + * @brief Calculates an intermediate goal along the global path and scores trajectories on the distance to that goal. + * + * This trajectory critic helps ensure progress along the global path. It + * calculates an intermediate goal that is as far as possible along the global + * path as long as the path continues to move in one direction (+/- + * angle_threshold). + */ +class PathProgressCritic : public dwb_critics::MapGridCritic { + public: + bool prepare(const geometry_msgs::Pose2D &pose, + const nav_2d_msgs::Twist2D &vel, + const geometry_msgs::Pose2D &goal, + const nav_2d_msgs::Path2D &global_plan) override; + + void onInit() override; + void reset() override; + double scoreTrajectory(const dwb_msgs::Trajectory2D& traj) override; + + protected: + bool getGoalPose(const geometry_msgs::Pose2D &robot_pose, + const nav_2d_msgs::Path2D &global_plan, + unsigned int &x, + unsigned int &y, + double &desired_angle); + + unsigned int getGoalIndex(const geometry_msgs::Pose2D &robot_pose, + const std::vector &plan, + unsigned int start_index, + unsigned int last_valid_index) const; + + double xy_local_goal_tolerance_; + double angle_threshold_; + double heading_scale_; + + std::vector reached_intermediate_goals_; + double desired_angle_; + ros::Publisher reached_intermediate_goals_pub_, current_goal_pub_, closet_robot_goal_pub_; +}; + +} // namespace mir_dwb_critics +#endif // MIR_DWB_CRITICS_PATH_PROGRESS_H_ diff --git a/mir_robot/mir_dwb_critics/include/mir_dwb_critics/path_progress_default.h b/mir_robot/mir_dwb_critics/include/mir_dwb_critics/path_progress_default.h new file mode 100755 index 0000000..b6f9ffa --- /dev/null +++ b/mir_robot/mir_dwb_critics/include/mir_dwb_critics/path_progress_default.h @@ -0,0 +1,81 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2019, DFKI GmbH + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ +#ifndef MIR_DWB_CRITICS_PATH_PROGRESS_H_ +#define MIR_DWB_CRITICS_PATH_PROGRESS_H_ + +#include +#include + +namespace mir_dwb_critics { +/** + * @class PathProgressCritic + * @brief Calculates an intermediate goal along the global path and scores trajectories on the distance to that goal. + * + * This trajectory critic helps ensure progress along the global path. It + * calculates an intermediate goal that is as far as possible along the global + * path as long as the path continues to move in one direction (+/- + * angle_threshold). + */ +class PathProgressCritic : public dwb_critics::MapGridCritic { + public: + bool prepare(const geometry_msgs::Pose2D &pose, + const nav_2d_msgs::Twist2D &vel, + const geometry_msgs::Pose2D &goal, + const nav_2d_msgs::Path2D &global_plan) override; + + void onInit() override; + void reset() override; + double scoreTrajectory(const dwb_msgs::Trajectory2D& traj) override; + + protected: + bool getGoalPose(const geometry_msgs::Pose2D &robot_pose, + const nav_2d_msgs::Path2D &global_plan, + unsigned int &x, + unsigned int &y, + double &desired_angle); + + unsigned int getGoalIndex(const std::vector &plan, + unsigned int start_index, + unsigned int last_valid_index) const; + + double xy_local_goal_tolerance_; + double angle_threshold_; + double heading_scale_; + + std::vector reached_intermediate_goals_; + double desired_angle_; +}; + +} // namespace mir_dwb_critics +#endif // MIR_DWB_CRITICS_PATH_PROGRESS_H_ \ No newline at end of file diff --git a/mir_robot/mir_dwb_critics/nodes/plot_dwb_scores.py b/mir_robot/mir_dwb_critics/nodes/plot_dwb_scores.py new file mode 100755 index 0000000..840558f --- /dev/null +++ b/mir_robot/mir_dwb_critics/nodes/plot_dwb_scores.py @@ -0,0 +1,94 @@ +#!/usr/bin/env python3 +# Copyright (c) 2018-2022, Martin Günther (DFKI GmbH) and contributors +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# +# * Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in the +# documentation and/or other materials provided with the distribution. +# +# * Neither the name of the the copyright holder nor the names of its +# contributors may be used to endorse or promote products derived from +# this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE +# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +# Author: Martin Günther + +import os +import tkinter +import matplotlib.pyplot as plt +import numpy as np + +import rospy +from dwb_msgs.msg import LocalPlanEvaluation + +fig = None +rects = None +max_score = 0.0 + + +def eval_cb(msg): + global fig, rects, max_score + labels = [s.name for s in msg.twists[msg.best_index].scores] + scaled_scores = [s.scale * s.raw_score for s in msg.twists[msg.best_index].scores] + + # reverse labels + scaled_scores to show the critics in the correct order top to bottom + labels.reverse() + scaled_scores.reverse() + + if not fig: + # init + y = np.arange(len(labels)) # the label locations + height = 0.35 # the height of the bars + + fig, ax = plt.subplots() + rects = ax.barh(y - height / 2, scaled_scores, height, label='scaled score') + + ax.set_ylabel('DWB Critics') + ax.set_title('Scaled scores') + ax.set_yticks(y) + ax.set_yticklabels(labels) + + fig.tight_layout() + fig.canvas.set_window_title('DWB Scores') + + # update axis limit + if max_score < max(scaled_scores): + max_score = max(scaled_scores) + plt.xlim(0.0, max_score) + + for rect, h in zip(rects, scaled_scores): + rect.set_width(h) + try: + fig.canvas.draw() + fig.canvas.flush_events() + except tkinter.TclError: + rospy.loginfo('Window was closed, exiting.') + os._exit(0) + + +def main(): + rospy.init_node('plot_dwb_scores') + rospy.Subscriber('move_base_node/DWBLocalPlanner/evaluation', LocalPlanEvaluation, eval_cb) + rospy.loginfo('plot_dwb_scores ready.') + plt.ion() + rospy.spin() + + +if __name__ == '__main__': + main() diff --git a/mir_robot/mir_dwb_critics/nodes/print_dwb_scores.py b/mir_robot/mir_dwb_critics/nodes/print_dwb_scores.py new file mode 100755 index 0000000..94bbb86 --- /dev/null +++ b/mir_robot/mir_dwb_critics/nodes/print_dwb_scores.py @@ -0,0 +1,57 @@ +#!/usr/bin/env python3 +# Copyright (c) 2018-2022, Martin Günther (DFKI GmbH) and contributors +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# +# * Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in the +# documentation and/or other materials provided with the distribution. +# +# * Neither the name of the the copyright holder nor the names of its +# contributors may be used to endorse or promote products derived from +# this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE +# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +# Author: Martin Günther + +import rospy + +from dwb_msgs.msg import LocalPlanEvaluation + + +def eval_cb(msg): + print('\n\n=========================================================\n\n') + for heading, i in zip(['best trajectory', 'worst trajectory'], [msg.best_index, msg.worst_index]): + print('### {}\n'.format(heading)) + print('Name | Raw | Scale | Scaled Score') + print('---------------------|-----------|---------|-------------') + for s in msg.twists[i].scores: + print('{:20} | {:9.4f} | {:7.4f} | {:12.4f}'.format(s.name, s.raw_score, s.scale, s.raw_score * s.scale)) + print('---------------------------------------- total: {:9.4f}'.format(msg.twists[i].total)) + print() + + +def main(): + rospy.init_node('print_dwb_scores', anonymous=True) + rospy.Subscriber('move_base_node/DWBLocalPlanner/evaluation', LocalPlanEvaluation, eval_cb) + rospy.loginfo('print_dwb_scores ready.') + rospy.spin() + + +if __name__ == '__main__': + main() diff --git a/mir_robot/mir_dwb_critics/package.xml b/mir_robot/mir_dwb_critics/package.xml new file mode 100755 index 0000000..652df8a --- /dev/null +++ b/mir_robot/mir_dwb_critics/package.xml @@ -0,0 +1,38 @@ + + + mir_dwb_critics + 1.1.7 + + Trajectory critics for the dwb_local_planner that work well together with the SBPL global planner on the MiR robot + + + Martin Günther + Martin Günther + + BSD + + https://github.com/DFKI-NI/mir_robot + https://github.com/DFKI-NI/mir_robot + https://github.com/DFKI-NI/mir_robot/issues + + catkin + + angles + costmap_queue + dwb_critics + dwb_local_planner + geometry_msgs + nav_2d_msgs + nav_2d_utils + nav_core2 + nav_grid_iterators + pluginlib + roscpp + sensor_msgs + + python3-matplotlib + + + + + diff --git a/mir_robot/mir_dwb_critics/src/path_angle.cpp b/mir_robot/mir_dwb_critics/src/path_angle.cpp new file mode 100755 index 0000000..f4d9e26 --- /dev/null +++ b/mir_robot/mir_dwb_critics/src/path_angle.cpp @@ -0,0 +1,93 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2019, DFKI GmbH + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include +#include +#include +#include + +namespace mir_dwb_critics { + +bool PathAngleCritic::prepare(const geometry_msgs::Pose2D &pose, const nav_2d_msgs::Twist2D &vel, + const geometry_msgs::Pose2D &goal, const nav_2d_msgs::Path2D &global_plan) { + const nav_core2::Costmap &costmap = *costmap_; + const nav_grid::NavGridInfo &info = costmap.getInfo(); + nav_2d_msgs::Path2D adjusted_global_plan = nav_2d_utils::adjustPlanResolution(global_plan, info.resolution); + + if (global_plan.poses.empty()) { + ROS_ERROR_NAMED("PathAngleCritic", "The global plan was empty."); + return false; + } + + // find the angle of the plan at the pose on the plan closest to the robot + double distance_min = std::numeric_limits::infinity(); + bool started_path = false; + for (unsigned int i = 0; i < adjusted_global_plan.poses.size(); i++) { + double g_x = adjusted_global_plan.poses[i].x; + double g_y = adjusted_global_plan.poses[i].y; + unsigned int map_x, map_y; + if (worldToGridBounded(info, g_x, g_y, map_x, map_y) && costmap(map_x, map_y) != costmap.NO_INFORMATION) { + double distance = nav_2d_utils::poseDistance(adjusted_global_plan.poses[i], pose); + if (distance_min > distance) { + // still getting closer + desired_angle_ = adjusted_global_plan.poses[i].theta; + distance_min = distance; + started_path = true; + } else { + // plan is going away from the robot again + break; + } + } else if (started_path) { + // Off the costmap after being on the costmap. + break; + } + // else, we have not yet found a point on the costmap, so we just continue + } + + if (!started_path) { + ROS_ERROR_NAMED("PathAngleCritic", "None of the points of the global plan were in the local costmap."); + return false; + } + return true; +} + +double PathAngleCritic::scoreTrajectory(const dwb_msgs::Trajectory2D &traj) { + double diff = fabs(remainder(traj.poses.back().theta - desired_angle_, 2 * M_PI)); + return diff * diff; +} + +} // namespace mir_dwb_critics + +PLUGINLIB_EXPORT_CLASS(mir_dwb_critics::PathAngleCritic, dwb_local_planner::TrajectoryCritic) diff --git a/mir_robot/mir_dwb_critics/src/path_dist_pruned.cpp b/mir_robot/mir_dwb_critics/src/path_dist_pruned.cpp new file mode 100755 index 0000000..d0ccc16 --- /dev/null +++ b/mir_robot/mir_dwb_critics/src/path_dist_pruned.cpp @@ -0,0 +1,101 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2019, DFKI GmbH + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ +#include +#include + +#include "mir_dwb_critics/path_dist_pruned.h" + +namespace mir_dwb_critics { + +bool PathDistPrunedCritic::prepare( + const geometry_msgs::Pose2D &pose, + const nav_2d_msgs::Twist2D &vel, + const geometry_msgs::Pose2D &goal, + const nav_2d_msgs::Path2D &global_plan) { + + const nav_core2::Costmap &costmap = *costmap_; + const nav_grid::NavGridInfo &info = costmap.getInfo(); + + auto plan = nav_2d_utils::adjustPlanResolution(global_plan, info.resolution).poses; + + + // --- stolen from PathProgressCritic::getGoalPose --- + // find the "start pose", i.e. the pose on the plan closest to the robot that is also on the local map + unsigned int start_index = 0; + double distance_to_start = std::numeric_limits::infinity(); + bool started_path = false; + for (unsigned int i = 0; i < plan.size(); i++) { + double g_x = plan[i].x; + double g_y = plan[i].y; + unsigned int map_x, map_y; + if (worldToGridBounded(info, g_x, g_y, map_x, map_y) + && costmap(map_x, map_y) != nav_core2::Costmap::NO_INFORMATION) { + // Still on the costmap. Continue. + double distance = nav_2d_utils::poseDistance(plan[i], pose); + if (distance_to_start > distance) { + start_index = i; + distance_to_start = distance; + started_path = true; + } else { + // Plan is going away from the robot again. It's possible that it comes back and we would find a pose that's + // even closer to the robot, but then we would skip over parts of the plan. + break; + } + } else if (started_path) { + // Off the costmap after being on the costmap. + break; + } + // else, we have not yet found a point on the costmap, so we just continue + } + + if (!started_path) { + ROS_ERROR_NAMED("PathDistPrunedCritic", "None of the points of the global plan were in the local costmap."); + return false; + } + // --------------------------------------------------- + + // remove the first part of the path, everything before start_index, to + // disregard that part in the PathDistCritic implementation. + nav_2d_msgs::Path2D global_plan_pruned; + global_plan_pruned.header = global_plan.header; + global_plan_pruned.poses = std::vector( + plan.begin() + start_index, + plan.end()); + + return dwb_critics::PathDistCritic::prepare(pose, vel, goal, global_plan_pruned); +} + +} // namespace mir_dwb_critics + +PLUGINLIB_EXPORT_CLASS(mir_dwb_critics::PathDistPrunedCritic, dwb_local_planner::TrajectoryCritic) diff --git a/mir_robot/mir_dwb_critics/src/path_progress.cpp b/mir_robot/mir_dwb_critics/src/path_progress.cpp new file mode 100755 index 0000000..2e4b28f --- /dev/null +++ b/mir_robot/mir_dwb_critics/src/path_progress.cpp @@ -0,0 +1,302 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2019, DFKI GmbH + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ +#include +#include +#include +#include +#include + +namespace mir_dwb_critics +{ + bool PathProgressCritic::prepare(const geometry_msgs::Pose2D &pose, const nav_2d_msgs::Twist2D &vel, + const geometry_msgs::Pose2D &goal, + const nav_2d_msgs::Path2D &global_plan) + { + dwb_critics::MapGridCritic::reset(); + + unsigned int local_goal_x, local_goal_y; + if (!getGoalPose(pose, global_plan, local_goal_x, local_goal_y, desired_angle_)) + { + return false; + } + // Enqueue just the last pose + cell_values_.setValue(local_goal_x, local_goal_y, 0.0); + queue_->enqueueCell(local_goal_x, local_goal_y); + + // MapGridCritic::propogateManhattanDistances + propogateManhattanDistances(); + + return true; + } + + void PathProgressCritic::onInit() + { + dwb_critics::MapGridCritic::onInit(); + critic_nh_.param("xy_local_goal_tolerance", xy_local_goal_tolerance_, 0.20); + critic_nh_.param("angle_threshold", angle_threshold_, M_PI_4); + critic_nh_.param("heading_scale", heading_scale_, 1.0); + reached_intermediate_goals_pub_ = critic_nh_.advertise("reached_intermediate_goals", 1); + current_goal_pub_ = critic_nh_.advertise("current_goal", 1); + closet_robot_goal_pub_ = critic_nh_.advertise("closet_robot_goal", 1); + // divide heading scale by position scale because the sum will be multiplied by scale again + heading_scale_ /= getScale(); + } + + void PathProgressCritic::reset() + { + reached_intermediate_goals_.clear(); + } + + double PathProgressCritic::scoreTrajectory(const dwb_msgs::Trajectory2D &traj) + { + double position_score = MapGridCritic::scoreTrajectory(traj); + double heading_diff = fabs(remainder(traj.poses.back().theta - desired_angle_, 2 * M_PI)); + double heading_score = heading_diff * heading_diff; + return position_score + heading_scale_ * heading_score; + } + + bool PathProgressCritic::getGoalPose(const geometry_msgs::Pose2D &robot_pose, const nav_2d_msgs::Path2D &global_plan, + unsigned int &x, unsigned int &y, double &desired_angle) + { + const nav_core2::Costmap &costmap = *costmap_; + const nav_grid::NavGridInfo &info = costmap.getInfo(); + + if (global_plan.poses.empty()) + { + ROS_ERROR_NAMED("PathProgressCritic", "The global plan was empty."); + return false; + } + // Chuyển đổi dữ liệu kế hoạch đường đi 'nav_2d_msgs::Path2D' sang 'std::vector' + std::vector plan = nav_2d_utils::adjustPlanResolution(global_plan, info.resolution).poses; + + // find the "start pose", i.e. the pose on the plan closest to the robot that is also on the local map + // Tìm điểm pose bắt đầu trên kế hoạch đường đi gần nhất với robot đồng thời có tồn tại trong local map + unsigned int start_index = 0; // số vị trí pose trong kế hoạch đường đi + double distance_to_start = std::numeric_limits::infinity(); // Xét giá trị là vô cùng oo + bool started_path = false; + for (unsigned int i = 0; i < plan.size(); i++) + { + double g_x = plan[i].x; + double g_y = plan[i].y; + unsigned int map_x, map_y; + if (worldToGridBounded(info, g_x, g_y, map_x, map_y) // chuyển tọa độ từ đơn vị mét sang pixel + && costmap(map_x, map_y) != nav_core2::Costmap::NO_INFORMATION) + { // chi phí phải khác -1 + // Still on the costmap. Continue. + double distance = nav_2d_utils::poseDistance(plan[i], robot_pose); // Tính khoảng cách từ vị trí của robot đến pose đang xét + if (distance_to_start > distance) + { + start_index = i; + distance_to_start = distance; + started_path = true; + } + // else + // { + // // Plan is going away from the robot again. It's possible that it comes back and we would find a pose that's + // // even closer to the robot, but then we would skip over parts of the plan. + // ss <<" index_max_ " << index_max_; + // break; + // } + } + else if (started_path) + { + // Off the costmap after being on the costmap. + break; + } + // else, we have not yet found a point on the costmap, so we just continue + } + + geometry_msgs::PoseStamped pose; + pose.header.stamp = ros::Time::now(); + pose.header.frame_id = global_plan.header.frame_id; + pose.pose.position.x = plan[start_index].x; + pose.pose.position.y = plan[start_index].y; + tf2::Quaternion temp; + temp.setRPY(0, 0, plan[start_index].theta); + pose.pose.orientation.x = temp.getX(); + pose.pose.orientation.y = temp.getY(); + pose.pose.orientation.z = temp.getZ(); + pose.pose.orientation.w = temp.getW(); + + closet_robot_goal_pub_.publish(pose); + + // Nếu khồng tìm được điểm gần với robot nhất thì trả về false + if (!started_path) + { + ROS_ERROR_NAMED("PathProgressCritic", "None of the points of the global plan were in the local costmap."); + return false; + } + // current_index_ = start_index; + // find the "last valid pose", i.e. the last pose on the plan after the start pose that is still on the local map + // Tìm điểm pose cuôi cùng sau điểm pose bắt đầu và có tồn tại trong local map + unsigned int last_valid_index = start_index; + for (unsigned int i = start_index + 1; i < plan.size(); i++) + { + double g_x = plan[i].x; + double g_y = plan[i].y; + unsigned int map_x, map_y; + if (worldToGridBounded(info, g_x, g_y, map_x, map_y) && costmap(map_x, map_y) != nav_core2::Costmap::NO_INFORMATION) + { + // Still on the costmap. Continue. + last_valid_index = i; + } + else + { + // Off the costmap after being on the costmap. + break; + } + } + // find the "goal pose" by walking along the plan as long as each step leads far enough away from the starting point, + // i.e. is within angle_threshold_ of the starting direction. + // Tìm điểm mục tiêu chạy từ điểm start pose đến last valid pose dọc thep plan + unsigned int goal_index = start_index; + + while (goal_index < last_valid_index && critic_nh_.ok()) + { + // Tìm kiếm vị trí điểm mục tiêu phù hợp + goal_index = getGoalIndex(robot_pose, plan, start_index, last_valid_index); + + // check if goal already reached + bool goal_already_reached = false; + + geometry_msgs::PoseArray poseArrayMsg; + poseArrayMsg.header.stamp = ros::Time::now(); + poseArrayMsg.header.frame_id = global_plan.header.frame_id; + for (const auto &pose2D : reached_intermediate_goals_) + { + geometry_msgs::Pose pose; + pose.position.x = pose2D.x; + pose.position.y = pose2D.y; + tf2::Quaternion temp; + temp.setRPY(0, 0, pose2D.theta); + pose.orientation.x = temp.getX(); + pose.orientation.y = temp.getY(); + pose.orientation.z = temp.getZ(); + pose.orientation.w = temp.getW(); + poseArrayMsg.poses.push_back(pose); + } + reached_intermediate_goals_pub_.publish(poseArrayMsg); + + for (auto &reached_intermediate_goal : reached_intermediate_goals_) + { + double distance = nav_2d_utils::poseDistance(reached_intermediate_goal, plan[goal_index]); + if (distance < xy_local_goal_tolerance_) + { + goal_already_reached = true; + // choose a new start_index by walking along the plan until we're outside xy_local_goal_tolerance_ and try again + // (start_index is now > goal_index) + for (start_index = goal_index; start_index <= last_valid_index; ++start_index) + { + distance = nav_2d_utils::poseDistance(reached_intermediate_goal, plan[start_index]); + if (distance >= xy_local_goal_tolerance_) + { + break; + } + } + break; + } + } + + pose.header.stamp = ros::Time::now(); + pose.header.frame_id = global_plan.header.frame_id; + pose.pose.position.x = plan[goal_index].x; + pose.pose.position.y = plan[goal_index].y; + tf2::Quaternion temp; + temp.setRPY(0, 0, plan[goal_index].theta); + pose.pose.orientation.x = temp.getX(); + pose.pose.orientation.y = temp.getY(); + pose.pose.orientation.z = temp.getZ(); + pose.pose.orientation.w = temp.getW(); + + current_goal_pub_.publish(pose); + + if (!goal_already_reached) + { + // new goal not in reached_intermediate_goals_ + double distance = nav_2d_utils::poseDistance(plan[goal_index], robot_pose); + if (distance < xy_local_goal_tolerance_) + { + // the robot has currently reached the goal + reached_intermediate_goals_.push_back(plan[goal_index]); + ROS_DEBUG_NAMED("PathProgressCritic", "Number of reached_intermediate goals: %zu", reached_intermediate_goals_.size()); + } + else + { + // we've found a new goal! + break; + } + } + } + + if (start_index > goal_index) + start_index = goal_index; + ROS_ASSERT(goal_index <= last_valid_index); + + // save goal in x, y + worldToGridBounded(info, plan[goal_index].x, plan[goal_index].y, x, y); + desired_angle = plan[start_index].theta; + return true; + } + + unsigned int PathProgressCritic::getGoalIndex(const geometry_msgs::Pose2D &robot_pose, + const std::vector &plan, + unsigned int start_index, + unsigned int last_valid_index) const + { + if (start_index >= last_valid_index) + return last_valid_index; + + unsigned int goal_index = start_index; + + for (unsigned int i = start_index + 1; i <= last_valid_index; ++i) + { + const double current_direction_x = plan[i].x - plan[i - 1].x; + const double current_direction_y = plan[i].y - plan[i - 1].y; + if (fabs(current_direction_x) > 1e-9 || fabs(current_direction_y) > 1e-9) + { + double current_angle = atan2(current_direction_y, current_direction_x); + if (fabs(remainder(robot_pose.theta - current_angle, 2 * M_PI)) > angle_threshold_) + break; + + goal_index = i; + } + } + if (nav_2d_utils::poseDistance(plan[goal_index], plan[last_valid_index]) <= xy_local_goal_tolerance_) + goal_index = last_valid_index; + return goal_index; + } + +} // namespace mir_dwb_critics + +PLUGINLIB_EXPORT_CLASS(mir_dwb_critics::PathProgressCritic, dwb_local_planner::TrajectoryCritic) diff --git a/mir_robot/mir_dwb_critics/src/path_progress_default.cpp b/mir_robot/mir_dwb_critics/src/path_progress_default.cpp new file mode 100755 index 0000000..a64b583 --- /dev/null +++ b/mir_robot/mir_dwb_critics/src/path_progress_default.cpp @@ -0,0 +1,221 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2019, DFKI GmbH + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ +#include +#include +#include +#include +#include + +namespace mir_dwb_critics { +bool PathProgressCritic::prepare(const geometry_msgs::Pose2D &pose, const nav_2d_msgs::Twist2D &vel, + const geometry_msgs::Pose2D &goal, + const nav_2d_msgs::Path2D &global_plan) { + dwb_critics::MapGridCritic::reset(); + + unsigned int local_goal_x, local_goal_y; + if (!getGoalPose(pose, global_plan, local_goal_x, local_goal_y, desired_angle_)) { + return false; + } + + // Enqueue just the last pose + cell_values_.setValue(local_goal_x, local_goal_y, 0.0); + queue_->enqueueCell(local_goal_x, local_goal_y); + + propogateManhattanDistances(); + + return true; +} + +void PathProgressCritic::onInit() { + dwb_critics::MapGridCritic::onInit(); + critic_nh_.param("xy_local_goal_tolerance", xy_local_goal_tolerance_, 0.20); + critic_nh_.param("angle_threshold", angle_threshold_, M_PI_4); + critic_nh_.param("heading_scale", heading_scale_, 1.0); + + // divide heading scale by position scale because the sum will be multiplied by scale again + heading_scale_ /= getScale(); +} + +void PathProgressCritic::reset() { + reached_intermediate_goals_.clear(); +} + +double PathProgressCritic::scoreTrajectory(const dwb_msgs::Trajectory2D &traj) { + double position_score = MapGridCritic::scoreTrajectory(traj); + double heading_diff = fabs(remainder(traj.poses.back().theta - desired_angle_, 2 * M_PI)); + double heading_score = heading_diff * heading_diff; + + return position_score + heading_scale_ * heading_score; +} + +bool PathProgressCritic::getGoalPose(const geometry_msgs::Pose2D &robot_pose, const nav_2d_msgs::Path2D &global_plan, + unsigned int &x, unsigned int &y, double &desired_angle) { + const nav_core2::Costmap &costmap = *costmap_; + const nav_grid::NavGridInfo &info = costmap.getInfo(); + + if (global_plan.poses.empty()) { + ROS_ERROR_NAMED("PathProgressCritic", "The global plan was empty."); + return false; + } + + std::vector plan = nav_2d_utils::adjustPlanResolution(global_plan, info.resolution).poses; + + // find the "start pose", i.e. the pose on the plan closest to the robot that is also on the local map + unsigned int start_index = 0; + double distance_to_start = std::numeric_limits::infinity(); + bool started_path = false; + for (unsigned int i = 0; i < plan.size(); i++) { + double g_x = plan[i].x; + double g_y = plan[i].y; + unsigned int map_x, map_y; + if (worldToGridBounded(info, g_x, g_y, map_x, map_y) + && costmap(map_x, map_y) != nav_core2::Costmap::NO_INFORMATION) { + // Still on the costmap. Continue. + double distance = nav_2d_utils::poseDistance(plan[i], robot_pose); + if (distance_to_start > distance) { + start_index = i; + distance_to_start = distance; + started_path = true; + } else { + // Plan is going away from the robot again. It's possible that it comes back and we would find a pose that's + // even closer to the robot, but then we would skip over parts of the plan. + break; + } + } else if (started_path) { + // Off the costmap after being on the costmap. + break; + } + // else, we have not yet found a point on the costmap, so we just continue + } + + if (!started_path) { + ROS_ERROR_NAMED("PathProgressCritic", "None of the points of the global plan were in the local costmap."); + return false; + } + + // find the "last valid pose", i.e. the last pose on the plan after the start pose that is still on the local map + unsigned int last_valid_index = start_index; + for (unsigned int i = start_index + 1; i < plan.size(); i++) { + double g_x = plan[i].x; + double g_y = plan[i].y; + unsigned int map_x, map_y; + if (worldToGridBounded(info, g_x, g_y, map_x, map_y) + && costmap(map_x, map_y) != nav_core2::Costmap::NO_INFORMATION) { + // Still on the costmap. Continue. + last_valid_index = i; + } else { + // Off the costmap after being on the costmap. + break; + } + } + + // find the "goal pose" by walking along the plan as long as each step leads far enough away from the starting point, + // i.e. is within angle_threshold_ of the starting direction. + unsigned int goal_index = start_index; + + while (goal_index < last_valid_index) { + goal_index = getGoalIndex(plan, start_index, last_valid_index); + + // check if goal already reached + bool goal_already_reached = false; + for (auto &reached_intermediate_goal : reached_intermediate_goals_) { + double distance = nav_2d_utils::poseDistance(reached_intermediate_goal, plan[goal_index]); + if (distance < xy_local_goal_tolerance_) { + goal_already_reached = true; + // choose a new start_index by walking along the plan until we're outside xy_local_goal_tolerance_ and try again + // (start_index is now > goal_index) + for (start_index = goal_index; start_index <= last_valid_index; ++start_index) { + distance = nav_2d_utils::poseDistance(reached_intermediate_goal, plan[start_index]); + if (distance >= xy_local_goal_tolerance_) { + break; + } + } + break; + } + } + if (!goal_already_reached) { + // new goal not in reached_intermediate_goals_ + double distance = nav_2d_utils::poseDistance(plan[goal_index], robot_pose); + if (distance < xy_local_goal_tolerance_) { + // the robot has currently reached the goal + reached_intermediate_goals_.push_back(plan[goal_index]); + ROS_DEBUG_NAMED("PathProgressCritic", "Number of reached_intermediate goals: %zu", reached_intermediate_goals_.size()); + } else { + // we've found a new goal! + break; + } + } + } + if (start_index > goal_index) + start_index = goal_index; + ROS_ASSERT(goal_index <= last_valid_index); + + // save goal in x, y + worldToGridBounded(info, plan[goal_index].x, plan[goal_index].y, x, y); + desired_angle = plan[start_index].theta; + return true; +} + +unsigned int PathProgressCritic::getGoalIndex(const std::vector &plan, + unsigned int start_index, + unsigned int last_valid_index) const { + if (start_index >= last_valid_index) + return last_valid_index; + + unsigned int goal_index = start_index; + const double start_direction_x = plan[start_index + 1].x - plan[start_index].x; + const double start_direction_y = plan[start_index + 1].y - plan[start_index].y; + if (fabs(start_direction_x) > 1e-9 || fabs(start_direction_y) > 1e-9) { // make sure that atan2 is defined + double start_angle = atan2(start_direction_y, start_direction_x); + + for (unsigned int i = start_index + 1; i <= last_valid_index; ++i) { + const double current_direction_x = plan[i].x - plan[i - 1].x; + const double current_direction_y = plan[i].y - plan[i - 1].y; + if (fabs(current_direction_x) > 1e-9 || fabs(current_direction_y) > 1e-9) { + double current_angle = atan2(current_direction_y, current_direction_x); + + // goal pose is found if plan doesn't point far enough away from the starting point + if (fabs(remainder(start_angle - current_angle, 2 * M_PI)) > angle_threshold_) + break; + + goal_index = i; + } + } + } + return goal_index; +} + +} // namespace mir_dwb_critics + +PLUGINLIB_EXPORT_CLASS(mir_dwb_critics::PathProgressCritic, dwb_local_planner::TrajectoryCritic) \ No newline at end of file diff --git a/mir_robot/mir_gazebo/CHANGELOG.rst b/mir_robot/mir_gazebo/CHANGELOG.rst new file mode 100755 index 0000000..84ed916 --- /dev/null +++ b/mir_robot/mir_gazebo/CHANGELOG.rst @@ -0,0 +1,104 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package mir_gazebo +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +1.1.7 (2023-01-20) +------------------ +* Don't set cmake_policy CMP0048 +* Contributors: Martin Günther + +1.1.6 (2022-06-02) +------------------ +* Add arg mir_type to launch files and urdfs +* Rename mir_100 -> mir + This is in preparation of mir_250 support. +* Contributors: Martin Günther + +1.1.5 (2022-02-11) +------------------ + +1.1.4 (2021-12-10) +------------------ +* Remove outdated comment +* Contributors: Martin Günther + +1.1.3 (2021-06-11) +------------------ +* Merge branch 'melodic-2.8' into noetic +* Rename tf frame and topic 'odom_comb' -> 'odom' + This is how they are called on the real MiR since MiR software 2.0. +* Contributors: Martin Günther + +1.1.2 (2021-05-12) +------------------ +* Fix laser scan frame_id with gazebo_plugins 2.9.2 +* Contributors: Martin Günther + +1.1.1 (2021-02-11) +------------------ +* mir_gazebo: Add model_name arg +* Move joint_state_publisher to mir_gazebo_common.launch +* Add optional namespace to launch files +* Add prepend_prefix_to_laser_frame to URDF and launch files + Fixes `#65 `_. +* Add tf_prefix to URDF and launch files +* Contributors: Martin Günther + +1.1.0 (2020-06-30) +------------------ +* Initial release into noetic +* Contributors: Martin Günther + +1.0.6 (2020-06-30) +------------------ +* Set cmake_policy CMP0048 to fix warning +* Contributors: Martin Günther + +1.0.5 (2020-05-01) +------------------ + +1.0.4 (2019-05-06) +------------------ +* Fix gazebo launch file + Before this commit, the mobile base plugin couldn't initialize, because + subst_value didn't work. +* Contributors: Martin Günther + +1.0.3 (2019-03-04) +------------------ +* Add hector_mapping +* fake_localization.launch: Add frame id args +* Merge pull request `#16 `_ from niniemann/add-prefix-argument-to-configs + Add prefix argument to configs +* adds $(arg prefix) to a lot of configs + This is an important step to be able to re-parameterize move base, + the diffdrive controller, ekf, amcl and the costmaps for adding a + tf prefix to the robots links +* Fix translation error in odom_comb (`#12 `_) + Previously, the ekf localization only computed a correct orientation, but the translation still followed the pure odometry data. This led to strange errors where the robot would move sideways (despite only having a diff drive). + This PR changes the ekf configuration to not use any position information from the odometry, but to integrate the velocities, which fixes this problem. +* Split scan_rep117 topic into two separate topics + This fixes the problem that the back laser scanner was ignored in the + navigation costmap in Gazebo (probably because in Gazebo, both laser + scanners have the exact same timestamp). +* Contributors: Martin Günther, Nils Niemann + +1.0.2 (2018-07-30) +------------------ +* mir_gazebo: Install config directory +* Contributors: Martin Günther + +1.0.1 (2018-07-17) +------------------ +* gazebo: Replace robot_pose_ekf with robot_localization + robot_pose_ekf is deprecated, and has been removed from the navigation + stack starting in melodic. +* gazebo: Adjust ekf.yaml +* gazebo: Copy robot_localization/ekf_template.yaml + ... for modification. +* Contributors: Martin Günther + +1.0.0 (2018-07-12) +------------------ +* Initial release +* Contributors: Martin Günther diff --git a/mir_robot/mir_gazebo/CMakeLists.txt b/mir_robot/mir_gazebo/CMakeLists.txt new file mode 100755 index 0000000..d8e5ac0 --- /dev/null +++ b/mir_robot/mir_gazebo/CMakeLists.txt @@ -0,0 +1,30 @@ +cmake_minimum_required(VERSION 3.5.1) +project(mir_gazebo) + +find_package(catkin REQUIRED COMPONENTS + roslaunch +) + +################################### +## catkin specific configuration ## +################################### +catkin_package() + +############# +## Install ## +############# + +# Mark other files for installation (e.g. launch and bag files, etc.) +install(DIRECTORY + config + launch + maps + sdf + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) + +############# +## Testing ## +############# + +roslaunch_add_file_check(launch) diff --git a/mir_robot/mir_gazebo/config/ekf.yaml b/mir_robot/mir_gazebo/config/ekf.yaml new file mode 100755 index 0000000..6c2c1a6 --- /dev/null +++ b/mir_robot/mir_gazebo/config/ekf.yaml @@ -0,0 +1,217 @@ +# The frequency, in Hz, at which the filter will output a position estimate. Note that the filter will not begin +# computation until it receives at least one message from one of the inputs. It will then run continuously at the +# frequency specified here, regardless of whether it receives more measurements. Defaults to 30 if unspecified. +frequency: 40 + +# The period, in seconds, after which we consider a sensor to have timed out. In this event, we carry out a predict +# cycle on the EKF without correcting it. This parameter can be thought of as the minimum frequency with which the +# filter will generate new output. Defaults to 1 / frequency if not specified. +sensor_timeout: 0.1 + +# ekf_localization_node and ukf_localization_node both use a 3D omnidirectional motion model. If this parameter is +# set to true, no 3D information will be used in your state estimate. Use this if you are operating in a planar +# environment and want to ignore the effect of small variations in the ground plane that might otherwise be detected +# by, for example, an IMU. Defaults to false if unspecified. +two_d_mode: true + +# Use this parameter to provide an offset to the transform generated by ekf_localization_node. This can be used for +# future dating the transform, which is required for interaction with some other packages. Defaults to 0.0 if +# unspecified. +transform_time_offset: 0.0 + +# Use this parameter to specify how long the tf listener should wait for a transform to become available. +# Defaults to 0.0 if unspecified. +transform_timeout: 0.0 + +# If you're having trouble, try setting this to true, and then echo the /diagnostics_agg topic to see if the node is +# unhappy with any settings or data. +print_diagnostics: true + +# Debug settings. Not for the faint of heart. Outputs a ludicrous amount of information to the file specified by +# debug_out_file. I hope you like matrices! Please note that setting this to true will have strongly deleterious +# effects on the performance of the node. Defaults to false if unspecified. +debug: false + +# Defaults to "robot_localization_debug.txt" if unspecified. Please specify the full path. +debug_out_file: /path/to/debug/file.txt + +# Whether to broadcast the transformation over the /tf topic. Defaults to true if unspecified. +publish_tf: true + +# Whether to publish the acceleration state. Defaults to false if unspecified. +publish_acceleration: false + +# REP-105 (http://www.ros.org/reps/rep-0105.html) specifies four principal coordinate frames: base_link, odom, map, and +# earth. base_link is the coordinate frame that is affixed to the robot. Both odom and map are world-fixed frames. +# The robot's position in the odom frame will drift over time, but is accurate in the short term and should be +# continuous. The odom frame is therefore the best frame for executing local motion plans. The map frame, like the odom +# frame, is a world-fixed coordinate frame, and while it contains the most globally accurate position estimate for your +# robot, it is subject to discrete jumps, e.g., due to the fusion of GPS data or a correction from a map-based +# localization node. The earth frame is used to relate multiple map frames by giving them a common reference frame. +# ekf_localization_node and ukf_localization_node are not concerned with the earth frame. +# Here is how to use the following settings: +# 1. Set the map_frame, odom_frame, and base_link frames to the appropriate frame names for your system. +# 1a. If your system does not have a map_frame, just remove it, and make sure "world_frame" is set to the value of +# odom_frame. +# 2. If you are fusing continuous position data such as wheel encoder odometry, visual odometry, or IMU data, set +# "world_frame" to your odom_frame value. This is the default behavior for robot_localization's state estimation nodes. +# 3. If you are fusing global absolute position data that is subject to discrete jumps (e.g., GPS or position updates +# from landmark observations) then: +# 3a. Set your "world_frame" to your map_frame value +# 3b. MAKE SURE something else is generating the odom->base_link transform. Note that this can even be another state +# estimation node from robot_localization! However, that instance should *not* fuse the global data. +map_frame: map # Defaults to "map" if unspecified +odom_frame: $(arg tf_prefix)odom # Defaults to "odom" if unspecified +base_link_frame: $(arg tf_prefix)base_footprint # Defaults to "base_link" if unspecified +world_frame: $(arg tf_prefix)odom # Defaults to the value of odom_frame if unspecified + +# The filter accepts an arbitrary number of inputs from each input message type (nav_msgs/Odometry, +# geometry_msgs/PoseWithCovarianceStamped, geometry_msgs/TwistWithCovarianceStamped, +# sensor_msgs/Imu). To add an input, simply append the next number in the sequence to its "base" name, e.g., odom0, +# odom1, twist0, twist1, imu0, imu1, imu2, etc. The value should be the topic name. These parameters obviously have no +# default values, and must be specified. +odom0: odom + +# Each sensor reading updates some or all of the filter's state. These options give you greater control over which +# values from each measurement are fed to the filter. For example, if you have an odometry message as input, but only +# want to use its Z position value, then set the entire vector to false, except for the third entry. The order of the +# values is x, y, z, roll, pitch, yaw, vx, vy, vz, vroll, vpitch, vyaw, ax, ay, az. Note that not some message types +# do not provide some of the state variables estimated by the filter. For example, a TwistWithCovarianceStamped message +# has no pose information, so the first six values would be meaningless in that case. Each vector defaults to all false +# if unspecified, effectively making this parameter required for each sensor. +# see http://docs.ros.org/melodic/api/robot_localization/html/configuring_robot_localization.html +odom0_config: [false, false, false, # x y z + false, false, false, # roll pitch yaw + true, true, false, # vx vy vz + false, false, true, # vroll vpitch vyaw + false, false, false] # ax ay az + +# If you have high-frequency data or are running with a low frequency parameter value, then you may want to increase +# the size of the subscription queue so that more measurements are fused. +odom0_queue_size: 10 + +# [ADVANCED] Large messages in ROS can exhibit strange behavior when they arrive at a high frequency. This is a result +# of Nagle's algorithm. This option tells the ROS subscriber to use the tcpNoDelay option, which disables Nagle's +# algorithm. +odom0_nodelay: false + +# [ADVANCED] When measuring one pose variable with two sensors, a situation can arise in which both sensors under- +# report their covariances. This can lead to the filter rapidly jumping back and forth between each measurement as they +# arrive. In these cases, it often makes sense to (a) correct the measurement covariances, or (b) if velocity is also +# measured by one of the sensors, let one sensor measure pose, and the other velocity. However, doing (a) or (b) isn't +# always feasible, and so we expose the differential parameter. When differential mode is enabled, all absolute pose +# data is converted to velocity data by differentiating the absolute pose measurements. These velocities are then +# integrated as usual. NOTE: this only applies to sensors that provide pose measurements; setting differential to true +# for twist measurements has no effect. +odom0_differential: false + +# [ADVANCED] When the node starts, if this parameter is true, then the first measurement is treated as a "zero point" +# for all future measurements. While you can achieve the same effect with the differential paremeter, the key +# difference is that the relative parameter doesn't cause the measurement to be converted to a velocity before +# integrating it. If you simply want your measurements to start at 0 for a given sensor, set this to true. +odom0_relative: false + +# [ADVANCED] If your data is subject to outliers, use these threshold settings, expressed as Mahalanobis distances, to +# control how far away from the current vehicle state a sensor measurement is permitted to be. Each defaults to +# numeric_limits::max() if unspecified. It is strongly recommended that these parameters be removed if not +# required. Data is specified at the level of pose and twist variables, rather than for each variable in isolation. +# For messages that have both pose and twist data, the parameter specifies to which part of the message we are applying +# the thresholds. +#odom0_pose_rejection_threshold: 5 +#odom0_twist_rejection_threshold: 1 + +# Further input parameter examples +# see http://docs.ros.org/melodic/api/robot_localization/html/configuring_robot_localization.html +imu0: imu_data +imu0_config: [false, false, false, # x y z + false, false, true, # roll pitch yaw + false, false, false, # vx vy vz + false, false, true, # vroll vpitch vyaw + true, false, false] # ax ay az +imu0_nodelay: false +imu0_differential: false +imu0_relative: true +imu0_queue_size: 10 +#imu0_pose_rejection_threshold: 0.8 # Note the difference in parameter names +#imu0_twist_rejection_threshold: 0.8 # +#imu0_linear_acceleration_rejection_threshold: 0.8 # + +# [ADVANCED] Some IMUs automatically remove acceleration due to gravity, and others don't. If yours doesn't, please set +# this to true, and *make sure* your data conforms to REP-103, specifically, that the data is in ENU frame. +imu0_remove_gravitational_acceleration: false + +# [ADVANCED] The EKF and UKF models follow a standard predict/correct cycle. During prediction, if there is no +# acceleration reference, the velocity at time t+1 is simply predicted to be the same as the velocity at time t. During +# correction, this predicted value is fused with the measured value to produce the new velocity estimate. This can be +# problematic, as the final velocity will effectively be a weighted average of the old velocity and the new one. When +# this velocity is the integrated into a new pose, the result can be sluggish covergence. This effect is especially +# noticeable with LIDAR data during rotations. To get around it, users can try inflating the process_noise_covariance +# for the velocity variable in question, or decrease the variance of the variable in question in the measurement +# itself. In addition, users can also take advantage of the control command being issued to the robot at the time we +# make the prediction. If control is used, it will get converted into an acceleration term, which will be used during +# predicition. Note that if an acceleration measurement for the variable in question is available from one of the +# inputs, the control term will be ignored. +# Whether or not we use the control input during predicition. Defaults to false. +use_control: false +# Whether the input (assumed to be cmd_vel) is a geometry_msgs/Twist or geometry_msgs/TwistStamped message. Defaults to +# false. +stamped_control: false +# The last issued control command will be used in prediction for this period. Defaults to 0.2. +control_timeout: 0.2 +# Which velocities are being controlled. Order is vx, vy, vz, vroll, vpitch, vyaw. +control_config: [true, false, false, false, false, true] +# Places limits on how large the acceleration term will be. Should match your robot's kinematics. +acceleration_limits: [1.3, 0.0, 0.0, 0.0, 0.0, 3.4] +# Acceleration and deceleration limits are not always the same for robots. +deceleration_limits: [1.3, 0.0, 0.0, 0.0, 0.0, 4.5] +# If your robot cannot instantaneously reach its acceleration limit, the permitted change can be controlled with these +# gains +acceleration_gains: [0.8, 0.0, 0.0, 0.0, 0.0, 0.9] +# If your robot cannot instantaneously reach its deceleration limit, the permitted change can be controlled with these +# gains +deceleration_gains: [1.0, 0.0, 0.0, 0.0, 0.0, 1.0] + +# [ADVANCED] The process noise covariance matrix can be difficult to tune, and can vary for each application, so it is +# exposed as a configuration parameter. This matrix represents the noise we add to the total error after each +# prediction step. The better the omnidirectional motion model matches your system, the smaller these values can be. +# However, if users find that a given variable is slow to converge, one approach is to increase the +# process_noise_covariance diagonal value for the variable in question, which will cause the filter's predicted error +# to be larger, which will cause the filter to trust the incoming measurement more during correction. The values are +# ordered as x, y, z, roll, pitch, yaw, vx, vy, vz, vroll, vpitch, vyaw, ax, ay, az. Defaults to the matrix below if +# unspecified. +process_noise_covariance: [0.05, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0.05, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0.06, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0.03, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0.03, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0.06, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0.025, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0.025, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0.04, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.02, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.015] + +# [ADVANCED] This represents the initial value for the state estimate error covariance matrix. Setting a diagonal +# value (variance) to a large value will result in rapid convergence for initial measurements of the variable in +# question. Users should take care not to use large values for variables that will not be measured directly. The values +# are ordered as x, y, z, roll, pitch, yaw, vx, vy, vz, vroll, vpitch, vyaw, ax, ay, az. Defaults to the matrix below +#if unspecified. +initial_estimate_covariance: [100.0,0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 100.0,0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 1.0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1.0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 10.0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 10.0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9] diff --git a/mir_robot/mir_gazebo/launch/fake_localization.launch b/mir_robot/mir_gazebo/launch/fake_localization.launch new file mode 100755 index 0000000..3bbbfe1 --- /dev/null +++ b/mir_robot/mir_gazebo/launch/fake_localization.launch @@ -0,0 +1,17 @@ + + + + + + + + + + + + + + + + + diff --git a/mir_robot/mir_gazebo/launch/includes/ekf.launch.xml b/mir_robot/mir_gazebo/launch/includes/ekf.launch.xml new file mode 100755 index 0000000..bcf3362 --- /dev/null +++ b/mir_robot/mir_gazebo/launch/includes/ekf.launch.xml @@ -0,0 +1,7 @@ + + + + + + + diff --git a/mir_robot/mir_gazebo/launch/includes/spawn_maze.launch.xml b/mir_robot/mir_gazebo/launch/includes/spawn_maze.launch.xml new file mode 100755 index 0000000..604f501 --- /dev/null +++ b/mir_robot/mir_gazebo/launch/includes/spawn_maze.launch.xml @@ -0,0 +1,5 @@ + + + + diff --git a/mir_robot/mir_gazebo/launch/mir_empty_world.launch b/mir_robot/mir_gazebo/launch/mir_empty_world.launch new file mode 100755 index 0000000..cc6e640 --- /dev/null +++ b/mir_robot/mir_gazebo/launch/mir_empty_world.launch @@ -0,0 +1,69 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/mir_robot/mir_gazebo/launch/mir_gazebo_common.launch b/mir_robot/mir_gazebo/launch/mir_gazebo_common.launch new file mode 100755 index 0000000..60559b5 --- /dev/null +++ b/mir_robot/mir_gazebo/launch/mir_gazebo_common.launch @@ -0,0 +1,71 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [mir/joint_states] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/mir_robot/mir_gazebo/launch/mir_maze_world.launch b/mir_robot/mir_gazebo/launch/mir_maze_world.launch new file mode 100755 index 0000000..4758715 --- /dev/null +++ b/mir_robot/mir_gazebo/launch/mir_maze_world.launch @@ -0,0 +1,14 @@ + + + + + + + + + + + + + + diff --git a/mir_robot/mir_gazebo/maps/maps_new/Direction_Zones_0.png b/mir_robot/mir_gazebo/maps/maps_new/Direction_Zones_0.png new file mode 100755 index 0000000..b7d235d Binary files /dev/null and b/mir_robot/mir_gazebo/maps/maps_new/Direction_Zones_0.png differ diff --git a/mir_robot/mir_gazebo/maps/maps_new/Driection_Zones_180.png b/mir_robot/mir_gazebo/maps/maps_new/Driection_Zones_180.png new file mode 100755 index 0000000..9e2763b Binary files /dev/null and b/mir_robot/mir_gazebo/maps/maps_new/Driection_Zones_180.png differ diff --git a/mir_robot/mir_gazebo/maps/maps_new/Driection_Zones_270.png b/mir_robot/mir_gazebo/maps/maps_new/Driection_Zones_270.png new file mode 100755 index 0000000..c2c0b9b Binary files /dev/null and b/mir_robot/mir_gazebo/maps/maps_new/Driection_Zones_270.png differ diff --git a/mir_robot/mir_gazebo/maps/maps_new/Driection_Zones_90.png b/mir_robot/mir_gazebo/maps/maps_new/Driection_Zones_90.png new file mode 100755 index 0000000..1bfce3f Binary files /dev/null and b/mir_robot/mir_gazebo/maps/maps_new/Driection_Zones_90.png differ diff --git a/mir_robot/mir_gazebo/maps/maps_new/critical_zones.png b/mir_robot/mir_gazebo/maps/maps_new/critical_zones.png new file mode 100755 index 0000000..1f51952 Binary files /dev/null and b/mir_robot/mir_gazebo/maps/maps_new/critical_zones.png differ diff --git a/mir_robot/mir_gazebo/maps/maps_new/maze.png b/mir_robot/mir_gazebo/maps/maps_new/maze.png new file mode 100755 index 0000000..41d6fa1 Binary files /dev/null and b/mir_robot/mir_gazebo/maps/maps_new/maze.png differ diff --git a/mir_robot/mir_gazebo/maps/maps_new/maze.psd b/mir_robot/mir_gazebo/maps/maps_new/maze.psd new file mode 100755 index 0000000..9c02fea Binary files /dev/null and b/mir_robot/mir_gazebo/maps/maps_new/maze.psd differ diff --git a/mir_robot/mir_gazebo/maps/maps_new/maze.yaml b/mir_robot/mir_gazebo/maps/maps_new/maze.yaml new file mode 100755 index 0000000..79220e7 --- /dev/null +++ b/mir_robot/mir_gazebo/maps/maps_new/maze.yaml @@ -0,0 +1,6 @@ +image: maze.png +resolution: 0.05 +origin: [0.0, 0.0, 0.0] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 diff --git a/mir_robot/mir_gazebo/maps/maps_new/maze_virtual_walls.png b/mir_robot/mir_gazebo/maps/maps_new/maze_virtual_walls.png new file mode 100755 index 0000000..e5dd8bb Binary files /dev/null and b/mir_robot/mir_gazebo/maps/maps_new/maze_virtual_walls.png differ diff --git a/mir_robot/mir_gazebo/maps/maps_new/maze_virtual_walls.yaml b/mir_robot/mir_gazebo/maps/maps_new/maze_virtual_walls.yaml new file mode 100755 index 0000000..89320ac --- /dev/null +++ b/mir_robot/mir_gazebo/maps/maps_new/maze_virtual_walls.yaml @@ -0,0 +1,6 @@ +image: maze_virtual_walls.png +resolution: 0.05 +origin: [0.0, 0.0, 0.0] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 diff --git a/mir_robot/mir_gazebo/maps/maps_new/maze_with_samp.png b/mir_robot/mir_gazebo/maps/maps_new/maze_with_samp.png new file mode 100755 index 0000000..cdfba6e Binary files /dev/null and b/mir_robot/mir_gazebo/maps/maps_new/maze_with_samp.png differ diff --git a/mir_robot/mir_gazebo/maps/maps_new/preferred_zones.png b/mir_robot/mir_gazebo/maps/maps_new/preferred_zones.png new file mode 100755 index 0000000..b71b21c Binary files /dev/null and b/mir_robot/mir_gazebo/maps/maps_new/preferred_zones.png differ diff --git a/mir_robot/mir_gazebo/maps/maps_new/unpreferred_zones.png b/mir_robot/mir_gazebo/maps/maps_new/unpreferred_zones.png new file mode 100755 index 0000000..b71b21c Binary files /dev/null and b/mir_robot/mir_gazebo/maps/maps_new/unpreferred_zones.png differ diff --git a/mir_robot/mir_gazebo/maps/maps_new/virtual_walls.png b/mir_robot/mir_gazebo/maps/maps_new/virtual_walls.png new file mode 100755 index 0000000..6bed1a4 Binary files /dev/null and b/mir_robot/mir_gazebo/maps/maps_new/virtual_walls.png differ diff --git a/mir_robot/mir_gazebo/maps/maze.png b/mir_robot/mir_gazebo/maps/maze.png new file mode 100755 index 0000000..41d6fa1 Binary files /dev/null and b/mir_robot/mir_gazebo/maps/maze.png differ diff --git a/mir_robot/mir_gazebo/maps/maze.yaml b/mir_robot/mir_gazebo/maps/maze.yaml new file mode 100755 index 0000000..79220e7 --- /dev/null +++ b/mir_robot/mir_gazebo/maps/maze.yaml @@ -0,0 +1,6 @@ +image: maze.png +resolution: 0.05 +origin: [0.0, 0.0, 0.0] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 diff --git a/mir_robot/mir_gazebo/maps/maze_virtual_walls.png b/mir_robot/mir_gazebo/maps/maze_virtual_walls.png new file mode 100755 index 0000000..e5dd8bb Binary files /dev/null and b/mir_robot/mir_gazebo/maps/maze_virtual_walls.png differ diff --git a/mir_robot/mir_gazebo/maps/maze_virtual_walls.yaml b/mir_robot/mir_gazebo/maps/maze_virtual_walls.yaml new file mode 100755 index 0000000..89320ac --- /dev/null +++ b/mir_robot/mir_gazebo/maps/maze_virtual_walls.yaml @@ -0,0 +1,6 @@ +image: maze_virtual_walls.png +resolution: 0.05 +origin: [0.0, 0.0, 0.0] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 diff --git a/mir_robot/mir_gazebo/maps/warehouse/critical_zones.png b/mir_robot/mir_gazebo/maps/warehouse/critical_zones.png new file mode 100755 index 0000000..1f51952 Binary files /dev/null and b/mir_robot/mir_gazebo/maps/warehouse/critical_zones.png differ diff --git a/mir_robot/mir_gazebo/maps/warehouse/critical_zones.yaml b/mir_robot/mir_gazebo/maps/warehouse/critical_zones.yaml new file mode 100755 index 0000000..7e08db5 --- /dev/null +++ b/mir_robot/mir_gazebo/maps/warehouse/critical_zones.yaml @@ -0,0 +1,6 @@ +image: critical_zones.png +resolution: 0.05 +origin: [0.0, 0.0, 0.0] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 diff --git a/mir_robot/mir_gazebo/maps/warehouse/direction_zones.png b/mir_robot/mir_gazebo/maps/warehouse/direction_zones.png new file mode 100755 index 0000000..33c0ea0 Binary files /dev/null and b/mir_robot/mir_gazebo/maps/warehouse/direction_zones.png differ diff --git a/mir_robot/mir_gazebo/maps/warehouse/direction_zones.yaml b/mir_robot/mir_gazebo/maps/warehouse/direction_zones.yaml new file mode 100755 index 0000000..26b9fdf --- /dev/null +++ b/mir_robot/mir_gazebo/maps/warehouse/direction_zones.yaml @@ -0,0 +1,6 @@ +image: direction_zones.png +resolution: 0.05 +origin: [0.0, 0.0, 0.0] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 diff --git a/mir_robot/mir_gazebo/maps/warehouse/map_empty.png b/mir_robot/mir_gazebo/maps/warehouse/map_empty.png new file mode 100755 index 0000000..5ca33cc Binary files /dev/null and b/mir_robot/mir_gazebo/maps/warehouse/map_empty.png differ diff --git a/mir_robot/mir_gazebo/maps/warehouse/map_empty.yaml b/mir_robot/mir_gazebo/maps/warehouse/map_empty.yaml new file mode 100755 index 0000000..95f5242 --- /dev/null +++ b/mir_robot/mir_gazebo/maps/warehouse/map_empty.yaml @@ -0,0 +1,6 @@ +image: map_empty.png +resolution: 0.05 +origin: [0.0, 0.0, 0.0] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 diff --git a/mir_robot/mir_gazebo/maps/warehouse/maze.png b/mir_robot/mir_gazebo/maps/warehouse/maze.png new file mode 100755 index 0000000..41d6fa1 Binary files /dev/null and b/mir_robot/mir_gazebo/maps/warehouse/maze.png differ diff --git a/mir_robot/mir_gazebo/maps/warehouse/maze.psd b/mir_robot/mir_gazebo/maps/warehouse/maze.psd new file mode 100755 index 0000000..8572a03 Binary files /dev/null and b/mir_robot/mir_gazebo/maps/warehouse/maze.psd differ diff --git a/mir_robot/mir_gazebo/maps/warehouse/maze.yaml b/mir_robot/mir_gazebo/maps/warehouse/maze.yaml new file mode 100755 index 0000000..79220e7 --- /dev/null +++ b/mir_robot/mir_gazebo/maps/warehouse/maze.yaml @@ -0,0 +1,6 @@ +image: maze.png +resolution: 0.05 +origin: [0.0, 0.0, 0.0] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 diff --git a/mir_robot/mir_gazebo/maps/warehouse/maze_with_samp.png b/mir_robot/mir_gazebo/maps/warehouse/maze_with_samp.png new file mode 100755 index 0000000..cdfba6e Binary files /dev/null and b/mir_robot/mir_gazebo/maps/warehouse/maze_with_samp.png differ diff --git a/mir_robot/mir_gazebo/maps/warehouse/preferred_zones.png b/mir_robot/mir_gazebo/maps/warehouse/preferred_zones.png new file mode 100755 index 0000000..5ca33cc Binary files /dev/null and b/mir_robot/mir_gazebo/maps/warehouse/preferred_zones.png differ diff --git a/mir_robot/mir_gazebo/maps/warehouse/preferred_zones.yaml b/mir_robot/mir_gazebo/maps/warehouse/preferred_zones.yaml new file mode 100755 index 0000000..18e426b --- /dev/null +++ b/mir_robot/mir_gazebo/maps/warehouse/preferred_zones.yaml @@ -0,0 +1,6 @@ +image: preferred_zones.png +resolution: 0.05 +origin: [0.0, 0.0, 0.0] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 diff --git a/mir_robot/mir_gazebo/maps/warehouse/unpreferred_zones.png b/mir_robot/mir_gazebo/maps/warehouse/unpreferred_zones.png new file mode 100755 index 0000000..b71b21c Binary files /dev/null and b/mir_robot/mir_gazebo/maps/warehouse/unpreferred_zones.png differ diff --git a/mir_robot/mir_gazebo/maps/warehouse/unpreferred_zones.yaml b/mir_robot/mir_gazebo/maps/warehouse/unpreferred_zones.yaml new file mode 100755 index 0000000..b8d48e5 --- /dev/null +++ b/mir_robot/mir_gazebo/maps/warehouse/unpreferred_zones.yaml @@ -0,0 +1,6 @@ +image: unpreferred_zones.png +resolution: 0.05 +origin: [0.0, 0.0, 0.0] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 diff --git a/mir_robot/mir_gazebo/maps/warehouse/virtual_walls.png b/mir_robot/mir_gazebo/maps/warehouse/virtual_walls.png new file mode 100755 index 0000000..aaa1786 Binary files /dev/null and b/mir_robot/mir_gazebo/maps/warehouse/virtual_walls.png differ diff --git a/mir_robot/mir_gazebo/maps/warehouse/virtual_walls.yaml b/mir_robot/mir_gazebo/maps/warehouse/virtual_walls.yaml new file mode 100755 index 0000000..7ad4500 --- /dev/null +++ b/mir_robot/mir_gazebo/maps/warehouse/virtual_walls.yaml @@ -0,0 +1,6 @@ +image: virtual_walls.png +resolution: 0.05 +origin: [0.0, 0.0, 0.0] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 diff --git a/mir_robot/mir_gazebo/package.xml b/mir_robot/mir_gazebo/package.xml new file mode 100755 index 0000000..255e358 --- /dev/null +++ b/mir_robot/mir_gazebo/package.xml @@ -0,0 +1,31 @@ + + + mir_gazebo + 1.1.7 + Simulation specific launch and configuration files for the MiR robot. + + Martin Günther + Martin Günther + + BSD + + https://github.com/DFKI-NI/mir_robot + https://github.com/DFKI-NI/mir_robot + https://github.com/DFKI-NI/mir_robot/issues + + catkin + + roslaunch + + controller_manager + fake_localization + gazebo_ros + joint_state_publisher + mir_description + mir_driver + robot_localization + robot_state_publisher + rostopic + rqt_robot_steering + topic_tools + diff --git a/mir_robot/mir_gazebo/sdf/maze/model.config b/mir_robot/mir_gazebo/sdf/maze/model.config new file mode 100755 index 0000000..9a00866 --- /dev/null +++ b/mir_robot/mir_gazebo/sdf/maze/model.config @@ -0,0 +1,11 @@ + + + maze + 1.0 + model.sdf + + Martin Günther + martin.guenther@dfki.de + + + diff --git a/mir_robot/mir_gazebo/sdf/maze/model.sdf b/mir_robot/mir_gazebo/sdf/maze/model.sdf new file mode 100755 index 0000000..b31cc0b --- /dev/null +++ b/mir_robot/mir_gazebo/sdf/maze/model.sdf @@ -0,0 +1,345 @@ + + + + -0.078283 0.098984 0 0 -0 0 + + + + + 20 0.15 2.5 + + + 0 0 1.25 0 -0 0 + + + 0 0 1.25 0 -0 0 + + + 20 0.15 2.5 + + + + + 1 1 1 1 + + + 0.030536 9.925 0 0 -0 0 + + + + + + 20 0.15 2.5 + + + 0 0 1.25 0 -0 0 + + + 0 0 1.25 0 -0 0 + + + 20 0.15 2.5 + + + + + 1 1 1 1 + + + 9.95554 0 0 0 0 -1.5708 + + + + + + 20 0.15 2.5 + + + 0 0 1.25 0 -0 0 + + + 0 0 1.25 0 -0 0 + + + 20 0.15 2.5 + + + + + 1 1 1 1 + + + 0.030536 -9.925 0 0 -0 3.14159 + + + + + + 1.5 0.15 2.5 + + + 0 0 1.25 0 -0 0 + + + 0 0 1.25 0 -0 0 + + + 1.5 0.15 2.5 + + + + + 1 1 1 1 + + + 5.35089 3.21906 0 0 -0 3.14159 + + + + + + 5.25 0.15 2.5 + + + 0 0 1.25 0 -0 0 + + + 0 0 1.25 0 -0 0 + + + 5.25 0.15 2.5 + + + + + 1 1 1 1 + + + 4.67589 5.76906 0 0 -0 1.5708 + + + + + + 5.5 0.15 2.5 + + + 0 0 1.25 0 -0 0 + + + 0 0 1.25 0 -0 0 + + + 5.5 0.15 2.5 + + + + + 1 1 1 1 + + + 7.10914 4.73454 0 0 0 -1.5708 + + + + + + 3 0.15 2.5 + + + 0 0 1.25 0 -0 0 + + + 0 0 1.25 0 -0 0 + + + 3 0.15 2.5 + + + + + 1 1 1 1 + + + 8.53414 2.05954 0 0 -0 0 + + + + + + 20 0.15 2.5 + + + 0 0 1.25 0 -0 0 + + + 0 0 1.25 0 -0 0 + + + 20 0.15 2.5 + + + + + 1 1 1 1 + + + -9.89446 0 0 0 -0 1.5708 + + + + + + 5.5 0.15 2.5 + + + 0 0 1.25 0 -0 0 + + + 0 0 1.25 0 -0 0 + + + 5.5 0.15 2.5 + + + + + 1 1 1 1 + + + -4.35914 -2.82889 0 0 0 -1.5708 + + + + + + 5.75 0.15 2.5 + + + 0 0 1.25 0 -0 0 + + + 0 0 1.25 0 -0 0 + + + 5.75 0.15 2.5 + + + + + 1 1 1 1 + + + -7.15914 -5.50389 0 0 -0 3.14159 + + + + + + 16 0.15 2.5 + + + 0 0 1.25 0 -0 0 + + + 0 0 1.25 0 -0 0 + + + 16 0.15 2.5 + + + + + 1 1 1 1 + + + -1.89911 1.86906 0 0 -0 0 + + + + + + 1.5 0.15 2.5 + + + 0 0 1.25 0 -0 0 + + + 0 0 1.25 0 -0 0 + + + 1.5 0.15 2.5 + + + + + 1 1 1 1 + + + 6.02589 2.54406 0 0 -0 1.5708 + + + + + + 0.15 0.15 2.5 + + + 0 0 1.25 0 -0 0 + + + 0 0 1.25 0 -0 0 + + + 0.15 0.15 2.5 + + + + + 1 1 1 1 + + + 6.02589 3.21906 0 0 -0 0 + + 1 + + diff --git a/mir_robot/mir_msgs/CHANGELOG.rst b/mir_robot/mir_msgs/CHANGELOG.rst new file mode 100755 index 0000000..e48c07d --- /dev/null +++ b/mir_robot/mir_msgs/CHANGELOG.rst @@ -0,0 +1,101 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package mir_msgs +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +1.1.7 (2023-01-20) +------------------ +* Build new msgs (`#117 `_) + Need to build new msg files. The files were added in a previous commit, but not added here for build and installation. +* Update MirMoveBase action to 2.10.3.1 +* Update BMSData.msg to MiR software 2.13.2 + This is an "unsafe" change (it breaks compatibility with MiR versions <= + 2.13.2), but since BMSData is not published by the mir_driver currently, + it should be ok. +* Add new messages added in MiR software 2.13.4.1 + This does not break compatibility with earlier versions (like 2.8.3.1), + because these messages did not exist before. + Actually, these messages were added in 2.10.3.1 (all other messages) and + 2.13.0.4 (ServiceResponseHeader.msg). +* Update Brake, Gripper + Height State msg to 2.13.4.1 + These are "unsafe" message changes (fields have been removed), but it + should be ok because these are only used in HookExtendedStatus, and that + message isn't forwarded by the mir_driver. +* Partially update messages to MiR software 2.13.4.1 + This only contains the "safe" changes, where fields were added. Also, it + doesn't include the move of some messages to mir_hook_shared_interface, + but keeps them here. +* Don't set cmake_policy CMP0048 +* Contributors: Martin Günther, moooeeeep + +1.1.6 (2022-06-02) +------------------ +* Rename mir_100 -> mir + This is in preparation of mir_250 support. +* Contributors: Martin Günther + +1.1.5 (2022-02-11) +------------------ + +1.1.4 (2021-12-10) +------------------ +* mir_msgs: Build all messages (`#98 `_) +* Contributors: Martin Günther + +1.1.3 (2021-06-11) +------------------ +* Merge branch 'melodic-2.8' into noetic +* Update BMSData msg to MiR software 2.8.3.1 +* Remove MirStatus + This message was removed in MiR software 2.0 (Renamed to RobotStatus). +* Update mir_msgs to 2.8.2.2 +* Contributors: Felix, Martin Günther + +1.1.2 (2021-05-12) +------------------ + +1.1.1 (2021-02-11) +------------------ +* Contributors: Martin Günther + +1.1.0 (2020-06-30) +------------------ +* Initial release into noetic +* Contributors: Martin Günther + +1.0.6 (2020-06-30) +------------------ +* Fix some catkin_lint warnings +* Set cmake_policy CMP0048 to fix warning +* Contributors: Martin Günther + +1.0.5 (2020-05-01) +------------------ + +1.0.4 (2019-05-06) +------------------ +* Update mir_msgs and mir_actions to MiR 2.3.1 + The following changes were made to the actual mir_msgs: + * rename mirMsgs -> mir_msgs + * rename proximity -> Proximity + * rename serial -> Serial + * keep MirStatus msg (was replaced by RobotStatus in MiR software 2.0) +* Contributors: Martin Günther + +1.0.3 (2019-03-04) +------------------ +* mir_msgs: Compile new msgs + rename mirMsgs -> mir_msgs +* mir_msgs: Add geometry_msgs dependency + Now that we have an actual msg package dependency, we don't need the std_msgs placeholder any more. +* mir_msgs: Add new messages on kinetic +* Contributors: Martin Günther + +1.0.2 (2018-07-30) +------------------ + +1.0.1 (2018-07-17) +------------------ + +1.0.0 (2018-07-12) +------------------ +* Initial release +* Contributors: Martin Günther diff --git a/mir_robot/mir_msgs/CMakeLists.txt b/mir_robot/mir_msgs/CMakeLists.txt new file mode 100755 index 0000000..1ffbb0e --- /dev/null +++ b/mir_robot/mir_msgs/CMakeLists.txt @@ -0,0 +1,88 @@ +cmake_minimum_required(VERSION 3.5.1) +project(mir_msgs) + +find_package(catkin REQUIRED COMPONENTS + geometry_msgs + message_generation +) + +################################################ +## Declare ROS messages, services and actions ## +################################################ + +# Generate messages in the 'msg' folder +add_message_files( + FILES + AngleMeasurment.msg + BMSData.msg + BatteryCurrents.msg + BrakeState.msg + ChargingState.msg + Device.msg + Devices.msg + EncoderTestEntry.msg + Encoders.msg + Error.msg + Event.msg + Events.msg + ExternalRobot.msg + ExternalRobots.msg + Gpio.msg + GripperState.msg + HeightState.msg + HookData.msg + HookExtendedStatus.msg + HookStatus.msg + IOs.msg + JoystickVel.msg + LocalMapStat.msg + MirExtra.msg + MirLocalPlannerPathTypes.msg + MissionCtrlCommand.msg + MissionCtrlState.msg + MovingState.msg + PalletLifterStatus.msg + Path.msg + Pendant.msg + PlanSegment.msg + PlanSegments.msg + Pose2D.msg + PowerBoardMotorStatus.msg + PrecisionDockingStatus.msg + Proximity.msg + ResourceState.msg + ResourcesAcquisition.msg + ResourcesState.msg + RobotMode.msg + RobotState.msg + RobotStatus.msg + SafetyStatus.msg + Serial.msg + ServiceResponseHeader.msg + SkidDetectionDiff.msg + SkidDetectionStampedFloat.msg + SoundEvent.msg + StampedEncoders.msg + TimeDebug.msg + Trolley.msg + Twist2D.msg + UserPrompt.msg + WebPath.msg + WorldMap.msg + WorldModel.msg +) + +# Generate added messages and services with any dependencies listed here +generate_messages( + DEPENDENCIES + geometry_msgs +) + +################################### +## catkin specific configuration ## +################################### +catkin_package( + CATKIN_DEPENDS + geometry_msgs + message_runtime +) diff --git a/mir_robot/mir_msgs/msg/AngleMeasurment.msg b/mir_robot/mir_msgs/msg/AngleMeasurment.msg new file mode 100755 index 0000000..0d80882 --- /dev/null +++ b/mir_robot/mir_msgs/msg/AngleMeasurment.msg @@ -0,0 +1,2 @@ +float64 angle #radians +time timestamp diff --git a/mir_robot/mir_msgs/msg/BMSData.msg b/mir_robot/mir_msgs/msg/BMSData.msg new file mode 100755 index 0000000..fea7a63 --- /dev/null +++ b/mir_robot/mir_msgs/msg/BMSData.msg @@ -0,0 +1,134 @@ +float64 pack_voltage +float64 charge_current +float64 discharge_current +float64 state_of_charge +float64 remaining_time_to_full_charge +int32 remaining_capacity +int32 state_of_health +int32 DISCHARGING=1 #bit 0 +int32 CHARGING=2 #bit 1 +int32 OV=4 #bit 2 Over voltage +int32 UV=8 #bit 3 Under voltage +int32 COC=16 #bit 4 Charge over current +int32 DOC=32 #bit 5 Discharge over current +int32 DOT=64 #bit 6 Discharge over temperature +int32 DUT=128 #bit 7 Discharge under temperature +int32 SC=512 #bit 9 +int32 COT=1024 #bit 10 Charge over temperature +int32 CUT=2048 #bit 11 Charge under temperature +int32 FW_STATUS_MSK=2031616 # to get Battery_Firmware_Status do the following: +int32 FW_STATUS_SHIFT=16 # batt_fw_stat=(status_flags & FW_STATUS_MSK)>>FW_STATUS_SHIFT +int32 FW_UPD_OK=0 #Battery firmware update finished OK. +int32 FW_UPD_RUNNING=1 #Battery firmware update running. +int32 FW_UPD_FAILED_BOOT=2 #Battery firmware update failed in Bootloader (Robot must not drive) +int32 FW_UPD_FAILED_APP=3 #Battery firmware update failed updating the application (Robot can drive with old FW) +int32 FW_UPD_FAILED_PARAM=4 #Battery firmware update failed uploading parameters (Robot can drive with old fw and parameters.) +int32 FW_STATUS_LOW_BATT=5 #Battery firmware update skipped battery too low or high (Robot can drive with old parameters.) +int32 FW_STATUS_FILE_CORRUPTED=6 #Battery firmware file corrupted (Robot can drive with old parameters.) +int32 FW_STATUS_CURRENT_TO_HIGH=7 #Battery firmware file corrupted (Robot can drive with old parameters.) +int32 FW_STATUS_NO_CAN=8 #Battery firmware update skipped no CAN communication (Robot can drive with old fw and parameters.) +int32 FW_BATTERY_IMBALANCE_HIGH=9 #Battery firmware update is enforced and the battery will be shut off by the new firmware +int32 status_flags +int32 temperature +uint32[] cell_voltage # In Mk2 robots and above the BMS provides data for 8 battery cells. 2Gen robots have BMS for 13 battery cells +uint32 cell_voltage_diff + +string WST_serial + +# Exteded diagnosticts for BMZ battery +uint32 bmz_flag # Flag for enabling extended diagnosticts +uint32 battery_type +uint32 BATT_TYPE_UNKNOWN=0 #type is unknown / no communucation +uint32 BATT_TYPE_BMZ=1 #BMZ battery +uint32 BATT_TYPE_WST=2 #WST battery +uint32 BATT_TYPE_SBS=3 #SBS battery +uint32 BATT_TYPE_SBS_SLIDE=4 #SBS SLIDE battery +uint32 BATT_TYPE_NO_BMS=255 #WST No BMS battery +float64 full_voltage +int32 full_capacity +int32 temperature2 +int32 temperature_pcb +int32 cycle_count +int32 dsg_overcurrent_counter +int32 chg_overcurrent_counter +int32 hw_major +int32 hw_minor +int32 fw_major +int32 fw_minor +int32 fw_patch +int32 fw_parameters_ok +int32 rec_fw_major +int32 rec_fw_minor +int32 rec_fw_patch +int32 bl_major +int32 bl_minor +uint32 status_enabled +uint32 status_current_limitation +uint32 status_switch_off_warn1 +uint32 status_switch_off_warn2 +uint32 status_fully_discharged +uint32 status_nearly_discharged +uint32 status_chargefet_on +uint32 status_dischargefet_on +uint32 status_discharging +uint32 status_fully_charged +uint32 status_charging +uint32 status_temp_charging_err +uint32 status_cell_over_voltage +uint32 status_cell_under_voltage +uint32 status_charge_over_current +uint32 status_shortcircuit +uint32 status_discharge_over_current +float64 status_chargefet_voltage +float64 status_dischargefet_voltage +uint32 status_temp_discharging_err +uint32 status_charger_detected +uint32 mnfct_bms_revision +uint32 mnfct_asn_revision +uint32 mnfct_year +uint32 mnfct_week +uint32 mnfct_model +uint32 mnfct_serial +uint32 afe_i2c_error_count +uint32 app_error_count +uint32 fet_disable_state + +float64 last_battery_msg_time + +# SBS battery states +uint32 SBS_battery_status +uint32 SBS_battery_status_raw +uint32 SBS_InitState1=1 +uint32 SBS_InitState2=2 +uint32 SBS_InitState3=3 +uint32 SBS_InitState4=4 +uint32 SBS_Idle=5 +uint32 SBS_Discharge=6 +uint32 SBS_Charge=7 +uint32 SBS_Fault=10 +uint32 SBS_CriticalError=11 +uint32 SBS_PrepareDeepsleep=99 +uint32 SBS_Deepsleep=100 + +string SBS_serial_1 +string SBS_serial_2 + +uint32 SBS_arti_nr_1 +uint32 SBS_arti_nr_2 +uint32 SBS_arti_nr_3 + +uint32 SBS_curr_flow_passive_state + +# Overcurrent counters +uint8 CHG_OC1_Count +uint8 CHG_OC2_Count +uint8 DSG_OC1_Count +uint8 DSG_OC2_Count +uint8 DSG_OC3_Count +uint8 AFE_OC1_Count +uint8 AFE_OC2_Count +uint8 CHG_LatchClear_Count +uint8 DSG_LatchClear_Count + +uint8 chg_oc_warning +uint8 dsg_oc_warning diff --git a/mir_robot/mir_msgs/msg/BatteryCurrents.msg b/mir_robot/mir_msgs/msg/BatteryCurrents.msg new file mode 100755 index 0000000..d81b7dd --- /dev/null +++ b/mir_robot/mir_msgs/msg/BatteryCurrents.msg @@ -0,0 +1,2 @@ +float64 battery1_current +float64 battery2_current diff --git a/mir_robot/mir_msgs/msg/BrakeState.msg b/mir_robot/mir_msgs/msg/BrakeState.msg new file mode 100755 index 0000000..3c22250 --- /dev/null +++ b/mir_robot/mir_msgs/msg/BrakeState.msg @@ -0,0 +1,10 @@ +uint8 UNKNOWN = 0 +uint8 INITIALIZING = 1 +uint8 HOMING = 2 +uint8 ACTIVE = 3 +uint8 INACTIVE = 4 +uint8 ACTIVATING = 5 +uint8 DEACTIVATING = 6 +uint8 ERROR = 7 + +uint8 state diff --git a/mir_robot/mir_msgs/msg/ChargingState.msg b/mir_robot/mir_msgs/msg/ChargingState.msg new file mode 100755 index 0000000..c2b50be --- /dev/null +++ b/mir_robot/mir_msgs/msg/ChargingState.msg @@ -0,0 +1,9 @@ +bool charging_relay +float64 charging_current +uint32 charging_current_raw +float64 last_time_current + +float64 charging_voltage +uint32 charging_voltage_raw +bool is_voltage_low +float64 last_time_voltage diff --git a/mir_robot/mir_msgs/msg/Device.msg b/mir_robot/mir_msgs/msg/Device.msg new file mode 100755 index 0000000..f3eefc0 --- /dev/null +++ b/mir_robot/mir_msgs/msg/Device.msg @@ -0,0 +1,2 @@ +string name +string serial diff --git a/mir_robot/mir_msgs/msg/Devices.msg b/mir_robot/mir_msgs/msg/Devices.msg new file mode 100755 index 0000000..77d98e8 --- /dev/null +++ b/mir_robot/mir_msgs/msg/Devices.msg @@ -0,0 +1 @@ +mir_msgs/Device[] devices diff --git a/mir_robot/mir_msgs/msg/EncoderTestEntry.msg b/mir_robot/mir_msgs/msg/EncoderTestEntry.msg new file mode 100755 index 0000000..e8e8ba2 --- /dev/null +++ b/mir_robot/mir_msgs/msg/EncoderTestEntry.msg @@ -0,0 +1,6 @@ +float64 command_velocity +float64 command_distance +float64 left_dist +float64 right_dist +string suggested_direction +string user_direction diff --git a/mir_robot/mir_msgs/msg/Encoders.msg b/mir_robot/mir_msgs/msg/Encoders.msg new file mode 100755 index 0000000..9fff122 --- /dev/null +++ b/mir_robot/mir_msgs/msg/Encoders.msg @@ -0,0 +1,3 @@ +float32 time_delta # Time since last encoder update. +int32 left_wheel # Encoder counts (absolute or relative) +int32 right_wheel # Encoder counts (absolute or relative) diff --git a/mir_robot/mir_msgs/msg/Error.msg b/mir_robot/mir_msgs/msg/Error.msg new file mode 100755 index 0000000..aa32383 --- /dev/null +++ b/mir_robot/mir_msgs/msg/Error.msg @@ -0,0 +1,34 @@ +# Definition of offsets indicating what type an error is +int32 HARDWARE_ERROR = 0 +int32 CPU_LOAD_ERROR = 100 +int32 MEMORY_ERROR = 200 +int32 ETHERNET_ERROR = 300 +int32 HDD_ERROR = 400 +int32 BATTERY_ERROR = 500 +int32 IMU_ERROR = 600 +int32 MOTOR_ERROR = 700 +int32 LASER_ERROR = 800 +int32 CAMERA_ERROR = 900 +int32 SAFETY_SYSTEM_ERROR = 1000 +int32 POWERBOARD_ERROR = 2000 +int32 POWERSUPPLY_ERROR = 2100 +int32 CANBUS_ERROR = 2200 +int32 HOOK_ERROR = 5000 +int32 HOOK_CAMERA_ERROR = 5100 +int32 HOOK_ACTUATOR_ERROR = 5200 +int32 HOOK_BRAKE_ERROR = 5300 +int32 HOOK_ENCODER_ERROR = 5400 +int32 MISSING_ERROR = 9000 +int32 SOFTWARE_ERROR = 10000 +int32 MISSION_ERROR = 10100 +int32 LOCALIZATION_ERROR = 10200 +int32 MAPPING_ERROR = 10300 +int32 ODOM_FUSION_ERROR = 10400 +int32 EVACUATION_ERROR = 12000 + + +time timestamp # Timestamp for when the error occurred +int32 code # Error code +string description # Error description +string module # Module in which the error occurred +bool nolog # Do not trigger an error log if set to true diff --git a/mir_robot/mir_msgs/msg/Event.msg b/mir_robot/mir_msgs/msg/Event.msg new file mode 100755 index 0000000..a183c83 --- /dev/null +++ b/mir_robot/mir_msgs/msg/Event.msg @@ -0,0 +1,13 @@ +uint32 EV_SPEED=1 +uint32 EV_BLINK=2 +uint32 EV_SOUND=3 +uint32 EV_DOOR=4 +uint32 EV_AMCLOFF=5 +uint32 EV_FWDDIST=6 +uint32 EV_IO=7 +uint32 EV_FLEETLCK=8 # Fleet +uint32 EV_EMERGENCY=9 # Fleet +uint32 eventType # The area event type +string area_guid # The area unique identifier +string area_name # The name of the area +geometry_msgs/Point[] polygon # An array of corner points that define the edges of the area diff --git a/mir_robot/mir_msgs/msg/Events.msg b/mir_robot/mir_msgs/msg/Events.msg new file mode 100755 index 0000000..770319d --- /dev/null +++ b/mir_robot/mir_msgs/msg/Events.msg @@ -0,0 +1,2 @@ +Header header +Event[] events diff --git a/mir_robot/mir_msgs/msg/ExternalRobot.msg b/mir_robot/mir_msgs/msg/ExternalRobot.msg new file mode 100755 index 0000000..8997d71 --- /dev/null +++ b/mir_robot/mir_msgs/msg/ExternalRobot.msg @@ -0,0 +1,15 @@ +Header header +uint32 id +uint32 MIR100=1 +uint32 MIR500=3 +uint32 type_id +string name +float64 robot_length +float64 robot_width +string footprint +string ip +uint32 map_id +int32 priority +geometry_msgs/Pose pose +geometry_msgs/Pose extrapolated_pose +geometry_msgs/Twist twist diff --git a/mir_robot/mir_msgs/msg/ExternalRobots.msg b/mir_robot/mir_msgs/msg/ExternalRobots.msg new file mode 100755 index 0000000..a04f3f5 --- /dev/null +++ b/mir_robot/mir_msgs/msg/ExternalRobots.msg @@ -0,0 +1,2 @@ +Header header +mir_msgs/ExternalRobot[] robots diff --git a/mir_robot/mir_msgs/msg/Gpio.msg b/mir_robot/mir_msgs/msg/Gpio.msg new file mode 100755 index 0000000..5fdb189 --- /dev/null +++ b/mir_robot/mir_msgs/msg/Gpio.msg @@ -0,0 +1,9 @@ +uint8 POWERBOARD_GPIO = 0 +uint8 POWERBOARD_RESET_SWITCH_LED = 1 +uint8 PENDANT_INPUT = 5 +uint8 AUTO_MODE_SWITCH = 10 +uint8 MANUAL_MODE_SWITCH = 11 +uint8 STOP_BUTTON = 12 + +uint8 ioport +uint8 dat diff --git a/mir_robot/mir_msgs/msg/GripperState.msg b/mir_robot/mir_msgs/msg/GripperState.msg new file mode 100755 index 0000000..ee86c12 --- /dev/null +++ b/mir_robot/mir_msgs/msg/GripperState.msg @@ -0,0 +1,9 @@ +uint8 LOCK_UNKNOWN = 0 +uint8 LOCK_HOMING = 1 +uint8 LOCK_OPEN = 2 +uint8 LOCK_OPENING = 3 +uint8 LOCK_CLOSED = 4 +uint8 LOCK_CLOSING = 6 +uint8 LOCK_ERROR = 9 + +uint8 state diff --git a/mir_robot/mir_msgs/msg/HeightState.msg b/mir_robot/mir_msgs/msg/HeightState.msg new file mode 100755 index 0000000..a882157 --- /dev/null +++ b/mir_robot/mir_msgs/msg/HeightState.msg @@ -0,0 +1,7 @@ +uint8 HEIGHT_UNKNOWN = 0 +uint8 HEIGHT_HOMING = 1 +uint8 HEIGHT_IDLE = 2 +uint8 HEIGHT_CHANGING = 3 +uint8 HEIGHT_ERROR = 4 + +uint8 state diff --git a/mir_robot/mir_msgs/msg/HookData.msg b/mir_robot/mir_msgs/msg/HookData.msg new file mode 100755 index 0000000..46a1578 --- /dev/null +++ b/mir_robot/mir_msgs/msg/HookData.msg @@ -0,0 +1,6 @@ +AngleMeasurment angle +float64 height +float64 length +uint8 brake_state +uint8 gripper_state +uint8 height_state diff --git a/mir_robot/mir_msgs/msg/HookExtendedStatus.msg b/mir_robot/mir_msgs/msg/HookExtendedStatus.msg new file mode 100755 index 0000000..86d121a --- /dev/null +++ b/mir_robot/mir_msgs/msg/HookExtendedStatus.msg @@ -0,0 +1,11 @@ +bool available + +BrakeState brake + +GripperState gripper + +HeightState height + +float32 angle + +string qr_marker_name diff --git a/mir_robot/mir_msgs/msg/HookStatus.msg b/mir_robot/mir_msgs/msg/HookStatus.msg new file mode 100755 index 0000000..7e1aad4 --- /dev/null +++ b/mir_robot/mir_msgs/msg/HookStatus.msg @@ -0,0 +1,8 @@ +bool available +float32 length +float32 height +float32 angle +bool braked + +bool trolley_attached +Trolley trolley diff --git a/mir_robot/mir_msgs/msg/IOs.msg b/mir_robot/mir_msgs/msg/IOs.msg new file mode 100755 index 0000000..5ef8fe5 --- /dev/null +++ b/mir_robot/mir_msgs/msg/IOs.msg @@ -0,0 +1,12 @@ +string module_guid +bool connected +uint8 DONE=0 +uint8 STARTED=1 +uint8 ERROR=3 +uint8 status +int8 num_inputs +bool[] input_state +int8 num_outputs +bool[] output_state +string ip +string error diff --git a/mir_robot/mir_msgs/msg/JoystickVel.msg b/mir_robot/mir_msgs/msg/JoystickVel.msg new file mode 100755 index 0000000..f905658 --- /dev/null +++ b/mir_robot/mir_msgs/msg/JoystickVel.msg @@ -0,0 +1,2 @@ +string joystick_token +geometry_msgs/Twist speed_command diff --git a/mir_robot/mir_msgs/msg/LocalMapStat.msg b/mir_robot/mir_msgs/msg/LocalMapStat.msg new file mode 100755 index 0000000..4d216c0 --- /dev/null +++ b/mir_robot/mir_msgs/msg/LocalMapStat.msg @@ -0,0 +1,3 @@ +int32 idx +int32 x +int32 y diff --git a/mir_robot/mir_msgs/msg/MirExtra.msg b/mir_robot/mir_msgs/msg/MirExtra.msg new file mode 100755 index 0000000..dc25e37 --- /dev/null +++ b/mir_robot/mir_msgs/msg/MirExtra.msg @@ -0,0 +1,7 @@ +# MirExtra - to publish data on a topic +Header header +float32 time_delta # Time since last encoder update. +float32 r_rpm # rmp speed from right encoder +float32 l_rpm # rmp speed from left encoder +float32 vel # calc velocity +float32 ang # calculated angle speed diff --git a/mir_robot/mir_msgs/msg/MirLocalPlannerPathTypes.msg b/mir_robot/mir_msgs/msg/MirLocalPlannerPathTypes.msg new file mode 100755 index 0000000..3425728 --- /dev/null +++ b/mir_robot/mir_msgs/msg/MirLocalPlannerPathTypes.msg @@ -0,0 +1,6 @@ +uint8 REVERSE_TROLLEY_STANDARD=1 +uint8 REVERSE_TROLLEY_FAST=2 +uint8 REVERSE_TROLLEY_COMPACT=3 + + +uint8 path_type diff --git a/mir_robot/mir_msgs/msg/MissionCtrlCommand.msg b/mir_robot/mir_msgs/msg/MissionCtrlCommand.msg new file mode 100755 index 0000000..9af9214 --- /dev/null +++ b/mir_robot/mir_msgs/msg/MissionCtrlCommand.msg @@ -0,0 +1,9 @@ +uint8 CMD_GET_STATUS = 0 +uint8 CMD_WAIT_POS_LOCK = 1 +uint8 CMD_WAIT_AREA_LOCK = 2 +uint8 CMD_CONTINUE = 3 +uint8 CMD_LOAD_MISSION = 4 + +string description +int32 cmd +int32 mission_id diff --git a/mir_robot/mir_msgs/msg/MissionCtrlState.msg b/mir_robot/mir_msgs/msg/MissionCtrlState.msg new file mode 100755 index 0000000..972f936 --- /dev/null +++ b/mir_robot/mir_msgs/msg/MissionCtrlState.msg @@ -0,0 +1,11 @@ +uint8 STATE_IDLE = 0 +uint8 STATE_WAIT_POS_LOCK = 1 +uint8 STATE_WAIT_AREA_LOCK = 2 +uint8 STATE_WAIT_MAP_TRANSITION = 10 +uint8 STATE_WAIT_LIFT_START_FLOOR = 11 +uint8 STATE_WAIT_LIFT_END_FLOOR = 12 +uint8 STATE_WAIT_LIFT_END_FLOOR_CONTINUE = 13 + + +int32 state +int32 pos_id diff --git a/mir_robot/mir_msgs/msg/MovingState.msg b/mir_robot/mir_msgs/msg/MovingState.msg new file mode 100755 index 0000000..6e495e5 --- /dev/null +++ b/mir_robot/mir_msgs/msg/MovingState.msg @@ -0,0 +1,6 @@ +uint8 UNKNOWN=0 +uint8 MOVING=1 +uint8 STOPPED=2 +uint8 STANDING_STILL=3 + +uint8 moving_state # Current robot moving state diff --git a/mir_robot/mir_msgs/msg/PalletLifterStatus.msg b/mir_robot/mir_msgs/msg/PalletLifterStatus.msg new file mode 100755 index 0000000..46acbab --- /dev/null +++ b/mir_robot/mir_msgs/msg/PalletLifterStatus.msg @@ -0,0 +1,7 @@ +uint8 PALLET_LIFT_STATE_DISABLED = 0 +uint8 PALLET_LIFT_STATE_MOVING = 1 +uint8 PALLET_LIFT_STATE_DOWN = 2 +uint8 PALLET_LIFT_STATE_UP = 3 + +bool is_enabled +uint8 state diff --git a/mir_robot/mir_msgs/msg/Path.msg b/mir_robot/mir_msgs/msg/Path.msg new file mode 100755 index 0000000..390bd76 --- /dev/null +++ b/mir_robot/mir_msgs/msg/Path.msg @@ -0,0 +1,2 @@ +Header header +mir_msgs/Pose2D[] poses diff --git a/mir_robot/mir_msgs/msg/Pendant.msg b/mir_robot/mir_msgs/msg/Pendant.msg new file mode 100755 index 0000000..47dae77 --- /dev/null +++ b/mir_robot/mir_msgs/msg/Pendant.msg @@ -0,0 +1,3 @@ +float32 x +float32 y +uint8 gpio_bits diff --git a/mir_robot/mir_msgs/msg/PlanSegment.msg b/mir_robot/mir_msgs/msg/PlanSegment.msg new file mode 100755 index 0000000..675fdb5 --- /dev/null +++ b/mir_robot/mir_msgs/msg/PlanSegment.msg @@ -0,0 +1,5 @@ +bool forward_motion +int32 start_idx +float64 length +float64 remaining_length +geometry_msgs/PoseStamped[] path diff --git a/mir_robot/mir_msgs/msg/PlanSegments.msg b/mir_robot/mir_msgs/msg/PlanSegments.msg new file mode 100755 index 0000000..73e62c9 --- /dev/null +++ b/mir_robot/mir_msgs/msg/PlanSegments.msg @@ -0,0 +1 @@ +mir_msgs/PlanSegment[] p_segments diff --git a/mir_robot/mir_msgs/msg/Pose2D.msg b/mir_robot/mir_msgs/msg/Pose2D.msg new file mode 100755 index 0000000..b8285c2 --- /dev/null +++ b/mir_robot/mir_msgs/msg/Pose2D.msg @@ -0,0 +1,3 @@ +float32 x +float32 y +float32 orientation diff --git a/mir_robot/mir_msgs/msg/PowerBoardMotorStatus.msg b/mir_robot/mir_msgs/msg/PowerBoardMotorStatus.msg new file mode 100755 index 0000000..e78aab8 --- /dev/null +++ b/mir_robot/mir_msgs/msg/PowerBoardMotorStatus.msg @@ -0,0 +1,32 @@ +uint16 LeftMotor_CtrlWord +int32 LeftMotor_Speed +int32 LeftMotor_Encoder +uint16 LeftMotor_Status +uint8 LeftMotor_Error +uint32 LeftMotor_ErrorHist1 +uint32 LeftMotor_ErrorHist2 +int32 LeftMotor_Current +uint16 LeftMotor_I2t_Motor +uint16 LeftMotor_I2t_Controller +int16 LeftMotor_Temperature +uint16 RightMotor_CtrlWord +int32 RightMotor_Speed +int32 RightMotor_Encoder +uint16 RightMotor_Status +uint8 RightMotor_Error +uint32 RightMotor_ErrorHist1 +uint32 RightMotor_ErrorHist2 +int32 RightMotor_Current +uint16 RightMotor_I2t_Motor +uint16 RightMotor_I2t_Controller +int16 RightMotor_Temperature +#Status bits for brake feedback. +uint8 BRAKE_STATUS_BRAKED_BIT=1 # is "1" if brake is supposed to be braked +uint8 BRAKE_STATUS_FB_BIT=4 # is "1" if brake feedback sensor is activated (brake is released) +uint8 BRAKE_STATUS_TRANSITION_BIT=128 +# So error combinations are - (Any combination with the TRANSITION bit set are valid) +# BRAKED FB TRANSITION STATUSWORD +# 0 0 0 0x00 Brake is suppused to be released, but FB indicate braked. We are not in transition. +# 1 1 0 0x05 Brake is suppused to be braked, but FB indicate released. We are not in transition. +uint8 Brake_LeftStatus +uint8 Brake_RightStatus diff --git a/mir_robot/mir_msgs/msg/PrecisionDockingStatus.msg b/mir_robot/mir_msgs/msg/PrecisionDockingStatus.msg new file mode 100755 index 0000000..db614f8 --- /dev/null +++ b/mir_robot/mir_msgs/msg/PrecisionDockingStatus.msg @@ -0,0 +1,5 @@ +bool connected +bool motor_forward +bool motor_back +bool left_docking +bool right_docking diff --git a/mir_robot/mir_msgs/msg/Proximity.msg b/mir_robot/mir_msgs/msg/Proximity.msg new file mode 100755 index 0000000..d78ba80 --- /dev/null +++ b/mir_robot/mir_msgs/msg/Proximity.msg @@ -0,0 +1,2 @@ +Header header +uint16[] ranges diff --git a/mir_robot/mir_msgs/msg/ResourceState.msg b/mir_robot/mir_msgs/msg/ResourceState.msg new file mode 100755 index 0000000..f93f208 --- /dev/null +++ b/mir_robot/mir_msgs/msg/ResourceState.msg @@ -0,0 +1,15 @@ +string[] assigned # A list of IPs of all assigned robots (Areas can have more than one robot assigned at a time) +uint32 ROBOT_POSITION=0 +uint32 STAGING_POSITION=1 +uint32 CHARGING_STATION=2 +uint32 AREA=3 +uint32 ELEVATOR_ENTRY_POSITION=26 +uint32 ELEVATOR_POSITION=25 +uint32 type # The resource type +uint32 path_idx # The index from the global path in which the robot gets into the position +float32 distance # The distance from the robot to the resource +geometry_msgs/Point collision_point # The collision point with the resource +geometry_msgs/Point[] resource_geometry # The resource_geometry +string[] queue # The queue for a resource. It's a list of robots ips. +string name # The name of the resource +string guid # The guid of the resource diff --git a/mir_robot/mir_msgs/msg/ResourcesAcquisition.msg b/mir_robot/mir_msgs/msg/ResourcesAcquisition.msg new file mode 100755 index 0000000..783d172 --- /dev/null +++ b/mir_robot/mir_msgs/msg/ResourcesAcquisition.msg @@ -0,0 +1,4 @@ +Header header +geometry_msgs/PoseStamped[] path +string position_guid +string token diff --git a/mir_robot/mir_msgs/msg/ResourcesState.msg b/mir_robot/mir_msgs/msg/ResourcesState.msg new file mode 100755 index 0000000..0fa2508 --- /dev/null +++ b/mir_robot/mir_msgs/msg/ResourcesState.msg @@ -0,0 +1,3 @@ +Header header +ResourceState[] resources +string token diff --git a/mir_robot/mir_msgs/msg/RobotMode.msg b/mir_robot/mir_msgs/msg/RobotMode.msg new file mode 100755 index 0000000..34cbb3a --- /dev/null +++ b/mir_robot/mir_msgs/msg/RobotMode.msg @@ -0,0 +1,9 @@ +# The robot operates in different mode +uint8 ROBOT_MODE_NONE = 0 # start mode +uint8 ROBOT_MODE_MAPPING = 3 # in mapping a new map is made +uint8 ROBOT_MODE_MAPPING_FINALIZING = 4 # in mapping the recorded map is being finalised +uint8 ROBOT_MODE_MISSION = 7 # primary mode when executing a mission (action list) +uint8 ROBOT_MODE_CHANGING = 255 # a transition mode - to say that a transition is in progress + +uint8 robotMode +string robotModeString diff --git a/mir_robot/mir_msgs/msg/RobotState.msg b/mir_robot/mir_msgs/msg/RobotState.msg new file mode 100755 index 0000000..f78c555 --- /dev/null +++ b/mir_robot/mir_msgs/msg/RobotState.msg @@ -0,0 +1,17 @@ +# The robot has to be in a predefined state +uint8 ROBOT_STATE_NONE = 0 +uint8 ROBOT_STATE_STARTING = 1 +uint8 ROBOT_STATE_SHUTTINGDOWN = 2 +uint8 ROBOT_STATE_READY = 3 # ready to execute +uint8 ROBOT_STATE_PAUSE = 4 # pause from executing +uint8 ROBOT_STATE_EXECUTING = 5 # when running in mission/taxa/bus +uint8 ROBOT_STATE_ABORTED = 6 +uint8 ROBOT_STATE_COMPLETED = 7 # done executing +uint8 ROBOT_STATE_DOCKED = 8 # in the dock and charging the batteries +uint8 ROBOT_STATE_DOCKING = 9 +uint8 ROBOT_STATE_EMERGENCYSTOP = 10 # the robot has emg-stop activated +uint8 ROBOT_STATE_MANUALCONTROL = 11 # a pause state, where the robot can move +uint8 ROBOT_STATE_ERROR = 12 # a general error state, requires a error handle + +uint8 robotState +string robotStateString diff --git a/mir_robot/mir_msgs/msg/RobotStatus.msg b/mir_robot/mir_msgs/msg/RobotStatus.msg new file mode 100755 index 0000000..b2d8b04 --- /dev/null +++ b/mir_robot/mir_msgs/msg/RobotStatus.msg @@ -0,0 +1,29 @@ +Header header +float32 battery_percentage +int32 battery_time_remaining +float32 battery_voltage +float32 distance_to_next_target +Error[] errors +string footprint +HookStatus hook_status +HookData hook_data +string map_id +bool unloaded_map_changes +int32 mission_queue_id +string mission_text +int32 mode_id +string mode_text +float64 moved +Pose2D position +string robot_name +string session_id +string software_version +uint8 state_id +string state_text +int32 uptime +Twist2D velocity +mir_msgs/UserPrompt user_prompt +bool safety_system_muted +bool joystick_low_speed_mode_enabled +string joystick_web_session_id +string mode_key_state diff --git a/mir_robot/mir_msgs/msg/SafetyStatus.msg b/mir_robot/mir_msgs/msg/SafetyStatus.msg new file mode 100755 index 0000000..1595194 --- /dev/null +++ b/mir_robot/mir_msgs/msg/SafetyStatus.msg @@ -0,0 +1,40 @@ +bool is_connected + +bool is_firmware_ok +int32 firmware_version + +bool in_protective_stop +bool in_emergency_stop +bool sto_feedback +bool is_restart_required + +bool is_safety_muted +float64 max_lin_speed +float64 max_rot_speed + +# Defines for filling out the mute_mask +uint8 MUTE_FRONT_RIGHT = 1 +uint8 MUTE_FRONT_CENTER = 2 +uint8 MUTE_FRONT_LEFT = 4 +uint8 MUTE_LEFT_CENTER = 8 +uint8 MUTE_REAR_LEFT = 16 +uint8 MUTE_REAR_CENTER = 32 +uint8 MUTE_REAR_RIGHT = 64 +uint8 MUTE_RIGHT_CENTER = 128 + +uint8 MUTE_FRONT = 7 +uint8 MUTE_LEFT = 28 +uint8 MUTE_REAR = 112 +uint8 MUTE_RIGHT = 193 +uint8 MUTE_SIDES = 221 +uint8 MUTE_ALL = 255 + +uint8 mute_mask +uint8 partial_mute_mask + +bool is_limited_speed_active +bool is_lifter_down +bool in_sleep_mode + +bool in_manual_mode +bool is_manual_mode_restart_required diff --git a/mir_robot/mir_msgs/msg/Serial.msg b/mir_robot/mir_msgs/msg/Serial.msg new file mode 100755 index 0000000..9741bda --- /dev/null +++ b/mir_robot/mir_msgs/msg/Serial.msg @@ -0,0 +1,2 @@ +Header header +string data diff --git a/mir_robot/mir_msgs/msg/ServiceResponseHeader.msg b/mir_robot/mir_msgs/msg/ServiceResponseHeader.msg new file mode 100755 index 0000000..2369083 --- /dev/null +++ b/mir_robot/mir_msgs/msg/ServiceResponseHeader.msg @@ -0,0 +1,2 @@ +bool success +string error diff --git a/mir_robot/mir_msgs/msg/SkidDetectionDiff.msg b/mir_robot/mir_msgs/msg/SkidDetectionDiff.msg new file mode 100755 index 0000000..6168b08 --- /dev/null +++ b/mir_robot/mir_msgs/msg/SkidDetectionDiff.msg @@ -0,0 +1,14 @@ +time time_stamp +float64 enc_acc_x +float64 enc_acc_y +float64 enc_rot_th + + +float64 imu_acc_x +float64 imu_acc_y +float64 imu_rot_th + + +float64 diff_acc_x +float64 diff_acc_y +float64 diff_rot_th diff --git a/mir_robot/mir_msgs/msg/SkidDetectionStampedFloat.msg b/mir_robot/mir_msgs/msg/SkidDetectionStampedFloat.msg new file mode 100755 index 0000000..e02869c --- /dev/null +++ b/mir_robot/mir_msgs/msg/SkidDetectionStampedFloat.msg @@ -0,0 +1,2 @@ +time time_stamp +float64 value diff --git a/mir_robot/mir_msgs/msg/SoundEvent.msg b/mir_robot/mir_msgs/msg/SoundEvent.msg new file mode 100755 index 0000000..73b21ef --- /dev/null +++ b/mir_robot/mir_msgs/msg/SoundEvent.msg @@ -0,0 +1,16 @@ +time time_stamp +string sound_guid +string message + +uint8 START=0 +uint8 STOP =1 +uint8 MUTE=2 +uint8 UNMUTE=3 +uint8 PAUSE=4 +uint8 UNPAUSE=5 +uint8 FINISH=6 +uint8 MUTEABLE=7 +uint8 REQ_PLAY=10 + + +uint8 event diff --git a/mir_robot/mir_msgs/msg/StampedEncoders.msg b/mir_robot/mir_msgs/msg/StampedEncoders.msg new file mode 100755 index 0000000..ff8193c --- /dev/null +++ b/mir_robot/mir_msgs/msg/StampedEncoders.msg @@ -0,0 +1,2 @@ +Header header +Encoders encoders diff --git a/mir_robot/mir_msgs/msg/TimeDebug.msg b/mir_robot/mir_msgs/msg/TimeDebug.msg new file mode 100755 index 0000000..4384e6b --- /dev/null +++ b/mir_robot/mir_msgs/msg/TimeDebug.msg @@ -0,0 +1,2 @@ +string[] description +float64[] time_elapsed diff --git a/mir_robot/mir_msgs/msg/Trolley.msg b/mir_robot/mir_msgs/msg/Trolley.msg new file mode 100755 index 0000000..03d00a1 --- /dev/null +++ b/mir_robot/mir_msgs/msg/Trolley.msg @@ -0,0 +1,5 @@ +int32 id +float32 length +float32 width +float32 height +float32 offset_locked_wheels diff --git a/mir_robot/mir_msgs/msg/Twist2D.msg b/mir_robot/mir_msgs/msg/Twist2D.msg new file mode 100755 index 0000000..2be144e --- /dev/null +++ b/mir_robot/mir_msgs/msg/Twist2D.msg @@ -0,0 +1,2 @@ +float32 linear +float32 angular diff --git a/mir_robot/mir_msgs/msg/UserPrompt.msg b/mir_robot/mir_msgs/msg/UserPrompt.msg new file mode 100755 index 0000000..b3e2c45 --- /dev/null +++ b/mir_robot/mir_msgs/msg/UserPrompt.msg @@ -0,0 +1,6 @@ +bool has_request +string guid +string user_group +string question +string[] options +duration timeout diff --git a/mir_robot/mir_msgs/msg/WebPath.msg b/mir_robot/mir_msgs/msg/WebPath.msg new file mode 100755 index 0000000..9a3fd5a --- /dev/null +++ b/mir_robot/mir_msgs/msg/WebPath.msg @@ -0,0 +1,3 @@ +int32 seq +float32[] x +float32[] y diff --git a/mir_robot/mir_msgs/msg/WorldMap.msg b/mir_robot/mir_msgs/msg/WorldMap.msg new file mode 100755 index 0000000..2716ccb --- /dev/null +++ b/mir_robot/mir_msgs/msg/WorldMap.msg @@ -0,0 +1,4 @@ +mir_msgs/ResourcesState positions +mir_msgs/ResourcesState areas +mir_msgs/ExternalRobots robots +int32 map_id diff --git a/mir_robot/mir_msgs/msg/WorldModel.msg b/mir_robot/mir_msgs/msg/WorldModel.msg new file mode 100755 index 0000000..762c470 --- /dev/null +++ b/mir_robot/mir_msgs/msg/WorldModel.msg @@ -0,0 +1,3 @@ +Header header +mir_msgs/WorldMap[] world_map # world model for a particular map +bool enable_resource_tracking diff --git a/mir_robot/mir_msgs/package.xml b/mir_robot/mir_msgs/package.xml new file mode 100755 index 0000000..c1c67e4 --- /dev/null +++ b/mir_robot/mir_msgs/package.xml @@ -0,0 +1,22 @@ + + + mir_msgs + 1.1.7 + Message definitions for the MiR robot + + Martin Günther + Martin Günther + + BSD + + https://github.com/DFKI-NI/mir_robot + https://github.com/DFKI-NI/mir_robot + https://github.com/DFKI-NI/mir_robot/issues + + catkin + + geometry_msgs + + message_generation + message_runtime + diff --git a/mir_robot/mir_navigation/CHANGELOG.rst b/mir_robot/mir_navigation/CHANGELOG.rst new file mode 100755 index 0000000..79e1011 --- /dev/null +++ b/mir_robot/mir_navigation/CHANGELOG.rst @@ -0,0 +1,182 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package mir_navigation +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +1.1.7 (2023-01-20) +------------------ +* Don't set cmake_policy CMP0048 +* Add license headers +* Fix flake8 warnings +* Contributors: Martin Günther + +1.1.6 (2022-06-02) +------------------ +* navigation: Reduce footprint to actual size + This reduces the footprint: + * 18 mm in front + * 42 mm in the back + * 27 mm at the sides + Now the footprint exactly matches the bounding box of the mesh, with no + padding. This should make navigation in tight spaces easier; let's hope + it doesn't lead to collisions. +* navigation: Move footprint_padding to proper namespace + The footprint_padding parameter in the upper namespace was ignored, + needed to be moved into local_costmap/global_costmap to take effect. +* genmprim: Remove obsolete plt.hold() + This fixes the following error: + AttributeError: module 'matplotlib.pyplot' has no attribute 'hold' +* mir_navigation: Remove static_map parameter + This fixes the following warning: + [ WARN] local_costmap: Pre-Hydro parameter "static_map" unused since "plugins" is provided +* Contributors: Martin Günther + +1.1.5 (2022-02-11) +------------------ + +1.1.4 (2021-12-10) +------------------ + +1.1.3 (2021-06-11) +------------------ +* Merge branch 'melodic-2.8' into noetic +* Rename tf frame and topic 'odom_comb' -> 'odom' + This is how they are called on the real MiR since MiR software 2.0. +* Reformat python code using black +* Contributors: Martin Günther + +1.1.2 (2021-05-12) +------------------ +* Uncomment available dependencies in noetic (`#79 `_) +* Contributors: Oscar Lima + +1.1.1 (2021-02-11) +------------------ +* Add optional namespace to launch files +* Add prefix to start_planner.launch (`#67 `_) +* Update scripts to Python3 (Noetic) +* Contributors: Martin Günther + +1.1.0 (2020-06-30) +------------------ +* Initial release into noetic +* Remove hector_mapping dependency (not released in noetic) +* Update scripts to Python3 (Noetic) +* Contributors: Martin Günther + +1.0.6 (2020-06-30) +------------------ +* Add missing matplotlib dependency +* plot_mprim: Fix color display +* Fix bug in genmprim_unicycle_highcost_5cm + In Python3, np.arange doesn't accept floats. +* Fix some catkin_lint warnings +* Set cmake_policy CMP0048 to fix warning +* Contributors: Martin Günther + +1.0.5 (2020-05-01) +------------------ +* Rename hector_mapping.launch, add dependency +* genmprim.py: Improve plotting +* genmprim.py: Make executable +* SBPL: Reduce allocated_time + initial_epsilon params + This leads to shorter planning times, but will perhaps fail on larger + maps. +* Update mprim file to mir-software 2.0.17 + This was updated in 2.0.17 and hasn't changed through 2.6 at least. +* Add genmprim_unicycle matlab + python script, fix mprim file +* Adjust dwb params: split_path, finer trajectories (`#43 `_) + - use split_path option to enforce following complex paths + - more trajectory samples over a smaller simulated time. This fixes a + problem where the robot would stop too far away from the goal, as all + possible trajectories either overshot the goal, or were too short to + reach into the next gridcell of the critics. + - remove Oscillation critic (never helped) +* added PathDistPrunedCritic for dwb (`#42 `_) + which works exactly like the original PathDistCritic, except that it + searches for a local minimum in the distance from the global path to the robots + current position. It then prunes the global_path from the start up to + this point, therefore approximately cutting of a segment of the path + that the robot already followed. +* Add default local_planner to move_base launch file + This makes the hector_mapping Gazebo demo work with the instructions + from the README (see `#32 `_). +* Contributors: Martin Günther, Nils Niemann + +1.0.4 (2019-05-06) +------------------ +* Rviz config: Add planned paths + costmap from real MiR +* Contributors: Martin Günther + +1.0.3 (2019-03-04) +------------------ +* fix frame_id for melodic (`#18 `_) +* Tune dwb parameters +* PathProgressCritic: Add heading score +* Use dwb_local_planner in move_base config +* Move footprint param to move_base root namespace + This allows other move_base plugins, such as dwb_local_planner, to + access this parameter. +* Add hector_mapping +* amcl.launch: Change default, remap service + This is required if amcl.launch is started within a namespace. +* teb_local_planner: Fix odom topic name +* Merge pull request `#16 `_ from niniemann/add-prefix-argument-to-configs + Add prefix argument to configs +* adds $(arg prefix) to a lot of configs + This is an important step to be able to re-parameterize move base, + the diffdrive controller, ekf, amcl and the costmaps for adding a + tf prefix to the robots links +* mir_navigation: Adjust helper node topics +* Add amcl launchfile (`#11 `_) + * added amcl.launch + * changed amcl params to default mir amcl parameters +* Merge pull request `#13 `_ from niniemann/fix-virtual-walls + The previous configuration of the local costmap didn't work for me -- obstacles seen in the laser scans were not added, or were overridden by the virtual\_walls\_map layer. Reordering the layers and loading the virtual walls before the obstacles fixes this for me. + Also, I added a `with_virtual_walls` parameter to `start_maps.launch` and `start_planner.launch`. +* added with_virtual_walls parameter to start_maps and start_planner +* reorder local costmap plugins +* Revert "mir_navigation: Disable virtual walls if no map file set" + This reverts commit 0cfda301b2bb1e8b3458e698efd24a7901e5d132. + The reason is that the `eval` keyword was introduced in kinetic, so it + doesn't work in indigo. +* mir_navigation: Update rviz config +* mir_navigation: Disable virtual walls if no map file set +* mir_navigation: Rename virtual_walls args + files +* mir_navigation: Remove parameter first_map_only + This parameter must be set to false (the default) when running SLAM + (otherwise the map updates won't be received), and when running a static + map_server it doesn't matter; even then, it should be false to allow + restarting the map_server with a different map. Therefore this commit + removes it altogether and leaves it at the default of "false". +* split parameter files between mapping/planning (`#10 `_) + The differences are simple: When mapping, first_map_only must be + set to false, and the virtual walls plugin must not be loaded + (else move_base will wait for a topic that is not going to be + published). +* Document move_base params, add max_planning_retries + Setting max_planning_retries to 10 makes the planner fail faster if the + planning problem is infeasible. By default, there's an infinite number + of retries, so we had to wait until the planner_patience ran out (5 s). +* Update rviz config + Make topics relative, so that ROS_NAMESPACE=... works. +* Switch to binary sbpl_lattice_planner dependency + ... instead of compiling from source. +* Split scan_rep117 topic into two separate topics + This fixes the problem that the back laser scanner was ignored in the + navigation costmap in Gazebo (probably because in Gazebo, both laser + scanners have the exact same timestamp). +* mir_navigation: Add clear_params to move_base launch +* mir_navigation: marking + clearing were switched + Other than misleading names, this had no effect. +* Contributors: Martin Günther, Nils Niemann, Noël Martignoni + +1.0.2 (2018-07-30) +------------------ + +1.0.1 (2018-07-17) +------------------ + +1.0.0 (2018-07-12) +------------------ +* Initial release +* Contributors: Martin Günther diff --git a/mir_robot/mir_navigation/CMakeLists.txt b/mir_robot/mir_navigation/CMakeLists.txt new file mode 100755 index 0000000..f1ce57f --- /dev/null +++ b/mir_robot/mir_navigation/CMakeLists.txt @@ -0,0 +1,76 @@ +cmake_minimum_required(VERSION 3.5.1) +project(mir_navigation) + +find_package(catkin REQUIRED COMPONENTS + roslaunch + move_base + amcl + nav_core_adapter + base_local_planner + dwb_local_planner + dwb_plugins + dwb_critics + sbpl_lattice_planner + teb_local_planner + map_server +) + +################################### +## catkin specific configuration ## +################################### +catkin_package() + +############# +## Install ## +############# + +# all install targets should use catkin DESTINATION variables +# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html + +# Mark executable scripts (Python etc.) for installation +# in contrast to setup.py, you can choose the destination +install(PROGRAMS + mprim/genmprim_unicycle_highcost_5cm.py + nodes/acc_finder.py + nodes/min_max_finder.py + scripts/plot_mprim.py + DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) + +## Mark executables and/or libraries for installation +# install(TARGETS mir_navigation mir_navigation_node +# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + +## Mark cpp header files for installation +# install(DIRECTORY include/${PROJECT_NAME}/ +# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} +# FILES_MATCHING PATTERN "*.h" +# PATTERN ".svn" EXCLUDE +# ) + +# Mark other files for installation (e.g. launch and bag files, etc.) +install(DIRECTORY + config + launch + mprim + rviz + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) + +############# +## Testing ## +############# + +## Add gtest based cpp test target and link libraries +# catkin_add_gtest(${PROJECT_NAME}-test test/test_mir_navigation.cpp) +# if(TARGET ${PROJECT_NAME}-test) +# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME}) +# endif() + +## Add folders to be run by python nosetests +# catkin_add_nosetests(test) + +roslaunch_add_file_check(launch) diff --git a/mir_robot/mir_navigation/config/base_local_planner_params.yaml b/mir_robot/mir_navigation/config/base_local_planner_params.yaml new file mode 100755 index 0000000..2f0f44e --- /dev/null +++ b/mir_robot/mir_navigation/config/base_local_planner_params.yaml @@ -0,0 +1,44 @@ +base_local_planner: base_local_planner/TrajectoryPlannerROS +TrajectoryPlannerROS: + # Robot configuration + acc_lim_x: 1.5 + acc_lim_y: 0 + acc_lim_theta: 2.0 + max_vel_x: 0.8 + min_vel_x: 0.1 + max_vel_theta: 1.0 + min_vel_theta: -1.0 + min_in_place_vel_theta: 0.2 + escape_vel: -0.1 + holonomic_robot: false + + # Goal tolerance + yaw_goal_tolerance: 0.03 + xy_goal_tolerance: 0.08 + latch_xy_goal_tolerance: true + + # Forward simulaton parameters + sim_time: 1.2 + sim_granularity: 0.025 + angular_sim_granularity: 0.04 + vx_samples: 15 + vtheta_samples: 20 + controller_frequency: 10 + + # Trajectory scoring parameters + meter_scoring: true + pdist_scale: 2.2 #0.6 + gdist_scale: 0.8 #0.8 + occdist_scale: 0.1 + heading_lookahead: 0.325 + heading_scoring: true + heading_scoring_timestep: 0.8 + dwa: true + publish_cost_grid: false + global_frame_id: map + + # Oscillation prevention parameter + oscillation_reset_dist: 0.05 + + # Global plan parameters + prune_plan: true diff --git a/mir_robot/mir_navigation/config/costmap_common_params.yaml b/mir_robot/mir_navigation/config/costmap_common_params.yaml new file mode 100755 index 0000000..f1fc59f --- /dev/null +++ b/mir_robot/mir_navigation/config/costmap_common_params.yaml @@ -0,0 +1,65 @@ +robot_base_frame: $(arg prefix)base_footprint +transform_tolerance: 0.2 +obstacle_range: 3.0 +#mark_threshold: 1 +publish_voxel_map: true +footprint_padding: 0.0 +navigation_map: + map_topic: /map +virtual_walls_map: + map_topic: /virtual_walls/map + use_maximum: true + lethal_cost_threshold: 100 +preferred_zones_map: + map_topic: /preferred_zones/map + lethal_cost_threshold: 100 + use_maximum: true +unpreferred_zones_map: + map_topic: /unpreferred_zones/map + lethal_cost_threshold: 100 + use_maximum: true +critical_zones_map: + map_topic: /critical_zones/map + lethal_cost_threshold: 100 + use_maximum: true + # subscribe_to_updates: true +direction_zones_map: + map_topic: /direction_zones/map + base_frame_id: $(arg prefix)base_footprint + lethal_cost_threshold: 100 + use_maximum: true + # subscribe_to_updates: true +obstacles: + observation_sources: b_scan_marking b_scan_clearing f_scan_marking f_scan_clearing + b_scan_marking: + topic: b_scan_rep117 + data_type: LaserScan + clearing: false + marking: true + inf_is_valid: false + min_obstacle_height: 0.13 + max_obstacle_height: 0.25 + b_scan_clearing: + topic: b_scan_rep117 + data_type: LaserScan + clearing: true + marking: false + inf_is_valid: false + min_obstacle_height: 0.13 + max_obstacle_height: 0.25 + f_scan_marking: + topic: f_scan_rep117 + data_type: LaserScan + clearing: false + marking: true + inf_is_valid: false + min_obstacle_height: 0.13 + max_obstacle_height: 0.25 + f_scan_clearing: + topic: f_scan_rep117 + data_type: LaserScan + clearing: true + marking: false + inf_is_valid: false + min_obstacle_height: 0.13 + max_obstacle_height: 0.25 diff --git a/mir_robot/mir_navigation/config/costmap_global_params.yaml b/mir_robot/mir_navigation/config/costmap_global_params.yaml new file mode 100755 index 0000000..2e39cbb --- /dev/null +++ b/mir_robot/mir_navigation/config/costmap_global_params.yaml @@ -0,0 +1,14 @@ +global_costmap: + global_frame: map + update_frequency: 1.0 + publish_frequency: 1.0 + raytrace_range: 2.0 + resolution: 0.05 + z_resolution: 0.2 + rolling_window: false + z_voxels: 10 + inflation: + cost_scaling_factor: 4.0 # Exponential rate at which the obstacle cost drops off (default: 10). Must be chosen so that the cost value is > 0 at robot's circumscribed radius. + inflation_radius: 0.8 # Max. distance from an obstacle at which costs are incurred for planning paths. Must be > robot's circumscribed radius. + + # plugins are loaded via costmap_global_params_plugins_[mapping|planning].yaml diff --git a/mir_robot/mir_navigation/config/costmap_global_params_plugins.yaml b/mir_robot/mir_navigation/config/costmap_global_params_plugins.yaml new file mode 100755 index 0000000..d5765b0 --- /dev/null +++ b/mir_robot/mir_navigation/config/costmap_global_params_plugins.yaml @@ -0,0 +1,13 @@ +global_costmap: + frame_id: map + plugins: + - {name: navigation_map, type: "costmap_2d::StaticLayer" } + - {name: virtual_walls_map, type: "costmap_2d::StaticLayer" } + - {name: obstacles, type: "costmap_2d::VoxelLayer" } + - {name: preferred_zones_map, type: "costmap_2d::PreferredLayer" } + - {name: unpreferred_zones_map, type: "costmap_2d::UnPreferredLayer" } + - {name: direction_zones_map, type: "costmap_2d::DirectionalLayer" } + - {name: inflation, type: "costmap_2d::InflationLayer" } + - {name: critical_zones_map, type: "costmap_2d::CriticalLayer" } + # obstacles: + # track_unknown_space: true \ No newline at end of file diff --git a/mir_robot/mir_navigation/config/costmap_local_params.yaml b/mir_robot/mir_navigation/config/costmap_local_params.yaml new file mode 100755 index 0000000..1d3dfd4 --- /dev/null +++ b/mir_robot/mir_navigation/config/costmap_local_params.yaml @@ -0,0 +1,18 @@ +local_costmap: + global_frame: $(arg prefix)odom + update_frequency: 5.0 + publish_frequency: 5.0 + rolling_window: true + raytrace_range: 2.0 + resolution: 0.05 + z_resolution: 0.15 + z_voxels: 8 + inflation: + cost_scaling_factor: 5.0 # Exponential rate at which the obstacle cost drops off (default: 10). Must be chosen so that the cost value is > 0 at robot's circumscribed radius. + inflation_radius: 0.8 # Max. distance from an obstacle at which costs are incurred for planning paths. Must be > robot's circumscribed radius. + width: 10.0 + height: 10.0 + origin_x: 0.0 + origin_y: 0.0 + + # plugins are loaded via costmap_local_params_plugins_[mapping|planning].yaml diff --git a/mir_robot/mir_navigation/config/costmap_local_params_plugins.yaml b/mir_robot/mir_navigation/config/costmap_local_params_plugins.yaml new file mode 100755 index 0000000..f25e579 --- /dev/null +++ b/mir_robot/mir_navigation/config/costmap_local_params_plugins.yaml @@ -0,0 +1,7 @@ +local_costmap: + frame_id: odom + plugins: + - {name: virtual_walls_map, type: "costmap_2d::StaticLayer" } # các ô chi phí xung quanh "tường ảo" sẽ được tăng lên giá trị cao hơn, tạo ra một vùng an toàn xung quanh các vật cản. + - {name: obstacles, type: "costmap_2d::VoxelLayer" } # các ô chi phí xung quanh các "vật cản" sẽ được tăng lên giá trị cao hơn, tạo ra một vùng an toàn xung quanh các vật cản. + - {name: inflation, type: "costmap_2d::InflationLayer" } # các ô chi phí xung quanh các "vật cản" sẽ được tăng lên giá trị cao hơn, tạo ra một vùng an toàn xung quanh các vật cản. + # - {name: critical_zones_map, type: "costmap_2d::CriticalLayer" } \ No newline at end of file diff --git a/mir_robot/mir_navigation/config/dwa_local_planner_params.yaml b/mir_robot/mir_navigation/config/dwa_local_planner_params.yaml new file mode 100755 index 0000000..b8d766a --- /dev/null +++ b/mir_robot/mir_navigation/config/dwa_local_planner_params.yaml @@ -0,0 +1,55 @@ +base_local_planner: dwa_local_planner/DWAPlannerROS +DWAPlannerROS: + # Robot configuration + max_vel_x: 0.8 + min_vel_x: -0.2 + + max_vel_y: 0.0 # diff drive robot + min_vel_y: 0.0 # diff drive robot + + max_trans_vel: 0.8 # choose slightly less than the base's capability + min_trans_vel: 0.1 # this is the min trans velocity when there is negligible rotational velocity + trans_stopped_vel: 0.03 + + # Warning! + # do not set min_trans_vel to 0.0 otherwise dwa will always think translational velocities + # are non-negligible and small in place rotational velocities will be created. + + max_rot_vel: 1.0 # choose slightly less than the base's capability + min_rot_vel: 0.1 # this is the min angular velocity when there is negligible translational velocity + rot_stopped_vel: 0.1 + + acc_lim_x: 1.5 + acc_lim_y: 0.0 # diff drive robot + acc_limit_trans: 1.5 + acc_lim_theta: 2.0 + + # Goal tolerance + yaw_goal_tolerance: 0.03 # yaw_goal_tolerance > (sim_time * min_rot_vel) / 2 (from Navigation Tuning Guide) + xy_goal_tolerance: 0.08 # xy_goal_tolerance > (sim_time * min_vel_x) / 2 + latch_xy_goal_tolerance: true + + # Forward simulation + sim_time: 1.2 + vx_samples: 15 + vy_samples: 1 # diff drive robot, there is only one sample + vtheta_samples: 20 + + # Trajectory scoring + path_distance_bias: 64.0 # default: 32.0 mir: 32.0 - weighting for how much it should stick to the global path plan + goal_distance_bias: 12.0 # default: 24.0 mir: 48.0 - weighting for how much it should attempt to reach its goal + occdist_scale: 0.5 # default: 0.01 mir: 0.01 - weighting for how much the controller should avoid obstacles + forward_point_distance: 0.325 # default: 0.325 mir: 0.325 - how far along to place an additional scoring point + stop_time_buffer: 0.2 # default: 0.2 mir: 0.2 - amount of time a robot must stop before colliding for a valid traj. + scaling_speed: 0.25 # default: 0.25 mir: 0.25 - absolute velocity at which to start scaling the robot's footprint + max_scaling_factor: 0.2 # default: 0.2 mir: 0.2 - how much to scale the robot's footprint when at speed. + prune_plan: true + + # Oscillation prevention + oscillation_reset_dist: 0.05 # 0.05 - how far to travel before resetting oscillation flags, in m + oscillation_reset_angle: 0.2 # 0.2 - the angle the robot must turn before resetting Oscillation flags, in rad + + # Debugging + publish_traj_pc : true + publish_cost_grid_pc: true + global_frame_id: /odom # or /odom diff --git a/mir_robot/mir_navigation/config/dwb_local_planner_params.yaml b/mir_robot/mir_navigation/config/dwb_local_planner_params.yaml new file mode 100755 index 0000000..99c0ad8 --- /dev/null +++ b/mir_robot/mir_navigation/config/dwb_local_planner_params.yaml @@ -0,0 +1,102 @@ +base_local_planner: nav_core_adapter::LocalPlannerAdapter +LocalPlannerAdapter: + planner_name: dwb_local_planner::DWBLocalPlanner +DWBLocalPlanner: + # Robot configuration + max_vel_x: 1.5 + min_vel_x: -0.3 + + max_vel_y: 0.0 # diff drive robot + min_vel_y: 0.0 # diff drive robot + + max_speed_xy: 2.0 # max_trans_vel: 0.8 # choose slightly less than the base's capability + min_speed_xy: 0.1 # min_trans_vel: 0.1 # this is the min trans velocity when there is negligible rotational velocity + + max_vel_theta: 1.0 # max_rot_vel: 1.0 # choose slightly less than the base's capability + min_speed_theta: 0.1 # min_rot_vel: 0.1 default: 0.4 # this is the min angular velocity when there is negligible translational velocity + + acc_lim_x: 0.4 + acc_lim_y: 0.0 # diff drive robot + acc_lim_theta: 1.0 + decel_lim_x: -1.0 + decel_lim_y: -0.0 + decel_lim_theta: -1.0 + + # Goal tolerance + yaw_goal_tolerance: 0.03 # yaw_goal_tolerance > (sim_time * min_rot_vel) / 2 (from Navigation Tuning Guide) + xy_goal_tolerance: 0.05 # xy_goal_tolerance > (sim_time * min_vel_x) / 2 + # latch_xy_goal_tolerance: true + + # Whether to split the path into segments or not + # Requires https://github.com/locusrobotics/robot_navigation/pull/50 + split_path: true + + # Forward simulation (trajectory generation) + trajectory_generator_name: dwb_plugins::StandardTrajectoryGenerator # or dwb_plugins::LimitedAccelGenerator + sim_time: 1.2 + vx_samples: 12 + vy_samples: 1 # diff drive robot, there is only one sample + vtheta_samples: 12 + discretize_by_time: true + angular_granularity: 0.05 + linear_granularity: 0.1 + # sim_period + include_last_point: true + + # Goal checking + goal_checker_name: dwb_plugins::SimpleGoalChecker + # stateful: true + + # Critics (trajectory scoring) + # default_critic_namespaces: [dwb_critics, mir_dwb_critics] + critics: [RotateToGoal, ObstacleFootprint, PathAlign, PathDistPruned, PathProgress] + # critics: [MetratronikTechnik] + # MetratronikTechnik: + # scale: 0.01 + # sq_window: 1.0 + # xy_goal_tolerance: 0.02 + # trans_stopped_velocity: 0.3 + # slowing_factor: 1.0 + # angle_threshold: 0.436332313 + # Lm: 0.25 + RotateToGoal: + scale: 100.0 + trans_stopped_velocity: 0.25 + lookahead_time: -1.0 + slowing_factor: 10.0 + ObstacleFootprint: + scale: 0.01 # default: 0.01 mir: 0.01 - weighting for how much the controller should avoid obstacles + max_scaling_factor: 0.5 # default: 0.2 mir: 0.2 - how much to scale the robot's footprint when at speed. + scaling_speed: 0.25 # default: 0.25 mir: 0.25 - absolute velocity at which to start scaling the robot's footprint + sum_scores: false # if true, return sum of scores of all trajectory points instead of only last one + PathAlign: + scale: 16.0 + forward_point_distance: 0.325 # default: 0.325 mir: 0.325 - how far along to place an additional scoring point + PathDistPruned: + scale: 0.01 # default: 32.0 mir: 32.0 - weighting for how much it should stick to the global path plan + class: 'mir_dwb_critics::PathDistPruned' + PathProgress: + scale: 24.0 # default: 24.0 mir: 48.0 - weighting for how much it should attempt to reach its goal + heading_scale: 0.01 + class: 'mir_dwb_critics::PathProgress' + xy_local_goal_tolerance: 0.5 + angle_threshold: 0.523598776 # 30 degrees + # angle_threshold: 0.785398163 # 45 degrees + + # Prune already passed poses from plan + prune_plan: true + prune_distance: 1.0 # Old poses farther away than prune_distance (in m) will be pruned. + # If the robot ever gets away further than this distance from the plan, + # the error "Resulting plan has 0 poses in it" will be thrown and + # replanning will be triggered. + + # Debugging + publish_cost_grid_pc: true + debug_trajectory_details: false + publish_evaluation: true + publish_global_plan: true + publish_input_params: true + publish_local_plan: true + publish_trajectories: true + publish_transformed_plan: true + marker_lifetime: 0.5 \ No newline at end of file diff --git a/mir_robot/mir_navigation/config/eband_local_planner_params.yaml b/mir_robot/mir_navigation/config/eband_local_planner_params.yaml new file mode 100755 index 0000000..148af01 --- /dev/null +++ b/mir_robot/mir_navigation/config/eband_local_planner_params.yaml @@ -0,0 +1,44 @@ +base_local_planner: eband_local_planner/EBandPlannerROS +EBandPlannerROS: + # Robot configuration + max_vel_lin: 0.8 # choose slightly less than the base's capability + min_vel_lin: 0.1 # this is the min trans velocity when there is negligible rotational velocity + trans_stopped_vel: 0.03 + + max_vel_th: 1.0 # choose slightly less than the base's capability + min_vel_th: 0.1 # this is the min angular velocity when there is negligible translational velocity + rot_stopped_vel: 0.1 + + min_in_place_vel_th: 0.1 # Minimum in-place angular velocity + in_place_trans_vel: 0.0 # Minimum in place linear velocity + + max_acceleration: 1.5 # Maximum allowable acceleration + max_translational_acceleration: 1.5 # Maximum linear acceleration + max_rotational_acceleration: 2.0 # Maximum angular acceleration + + # Goal tolerance + yaw_goal_tolerance: 0.03 # yaw_goal_tolerance > (sim_time * min_rot_vel) / 2 (from Navigation Tuning Guide) + xy_goal_tolerance: 0.08 # xy_goal_tolerance > (sim_time * min_vel_x) / 2 + + # Elastic Band Parameters + eband_min_relative_overlap: 0.7 # Min distance that denotes connectivity between consecutive bubbles + eband_tiny_bubble_distance: 0.01 # Bubble geometric bound regarding tiny bubble distance + eband_tiny_bubble_expansion: 0.01 # Bubble geometric bound regarding tiny bubble expansion + eband_internal_force_gain: 1.0 # Force gain of forces between consecutive bubbles that tend to stretch the elastic band + eband_external_force_gain: 2.0 # Force gain of forces that tend to move the bubbles away from obstacles + num_iterations_eband_optimization: 3 # Number of iterations for eband optimization + eband_equilibrium_approx_max_recursion_depth: 4 # Number of iterations for reaching the equilibrium between internal and external forces + eband_equilibrium_relative_overshoot: 0.75 # Maximum relative equlibrium overshoot + eband_significant_force_lower_bound: 0.15 # Minimum magnitude of force that is considered significant and used in the calculations + costmap_weight: 10.0 # Costmap weight factor used in the calculation of distance to obstacles + + # Trajectory Controller Parameters + k_prop: 4.0 # Proportional gain of the PID controller + k_damp: 3.5 # Damping gain of the PID controller + Ctrl_Rate: 10.0 # Control rate + virtual_mass: 0.75 # Virtual mass + rotation_correction_threshold: 0.5 # Rotation correction threshold + differential_drive: True # Denotes whether to use the differential drive mode + bubble_velocity_multiplier: 2.0 # Multiplier of bubble radius + rotation_threshold_multiplier: 1.0 # Multiplier of rotation threshold + disallow_hysteresis: False # Determines whether to try getting closer to the goal, in case of going past the tolerance diff --git a/mir_robot/mir_navigation/config/mir_local_planner_params.yaml b/mir_robot/mir_navigation/config/mir_local_planner_params.yaml new file mode 100755 index 0000000..ba7f82d --- /dev/null +++ b/mir_robot/mir_navigation/config/mir_local_planner_params.yaml @@ -0,0 +1,81 @@ +base_local_planner: mirLocalPlanner/MIRPlannerROS +MIRPlannerROS: + # Robot configuration + max_vel_x: 0.8 + min_vel_x: -0.2 + + min_trans_vel: 0.1 # this is the min trans velocity when there is negligible rotational velocity + + # Warning! + # do not set min_trans_vel to 0.0 otherwise dwa will always think translational velocities + # are non-negligible and small in place rotational velocities will be created. + + max_rot_vel: 1.0 # choose slightly less than the base's capability + min_rot_vel: 0.1 # this is the min angular velocity when there is negligible translational velocity + + acc_lim_x: 1.5 + acc_lim_y: 0.0 # diff drive robot + acc_lim_th: 2.0 + min_inplace_rot: 0.15 + max_inplace_rot: 0.6 + min_in_place_rotational_vel: 0.2 + escape_vel: -0.1 + holonomic_robot: false + + # Goal tolerance + yaw_goal_tolerance: 0.03 # yaw_goal_tolerance > (sim_time * min_rot_vel) / 2 (from Navigation Tuning Guide) + xy_goal_tolerance: 0.08 # xy_goal_tolerance > (sim_time * min_vel_x) / 2 + + # Forward simulaton + sim_time: 1.2 + sim_granularity: 0.025 + vx_samples: 15 + vth_samples: 20 + vtheta_samples: 20 + + # Trajectory scoring + path_distance_bias: 0.4 # weighting for how much it should stick to the global path plan + goal_distance_bias: 0.6 # weighting for how much it should attempt to reach its goal + occdist_scale: 0.01 # weighting for how much the controller should avoid obstacles + forward_point_distance: 0.325 # how far along to place an additional scoring point + stop_time_buffer: 0.2 # amount of time a robot must stop before colliding for a valid traj. + scaling_speed: 0.25 # absolute velocity at which to start scaling the robot's footprint + max_scaling_factor: 0.2 # how much to scale the robot's footprint when at speed. + heading_lookahead: 0.325 + dwa: true + + # Oscillation prevention + oscillation_reset_dist: 0.05 # how far to travel before resetting oscillation flags, in m + + + # Debugging + publish_visualization: false + publish_cost_grid_pc: false + global_frame_id: odom + + # MiR specific parameters + tau_p: 5.0 # The proportional value in the CTE PID tracking + tau_i: 0.1 # The integral value in the CTE PID tracking + tau_d: 0.5 # The differential value in the CTE PID tracking + tau_w: 9.0 # The proportional angle value in the CTE tracking + + k_rho: 1.0 # The proportional value to goal in Goal tracking + k_alfa: 8.0 # The diff angle between the robot and the goal in the Goal tracking + k_beta: -2.5 # The angle to the goal from the robot in the Goal tracking + + blocked_path_dist: 3.0 # At what distance should the planner react when the path is blocked + blocked_path_dev: 60.0 # How far can we move from the planned path when it is blocked + blocked_path_action: new_plan # Which action to take, when path is blocked + occ_path_dist: 3.0 # At what distance should the planner react when the path is near obstacle + occ_path_dev: 15.0 # How far can we move from the planned path when the path is near a obstacle + occ_path_level: 120.0 # Threshold level for a obstacle + + cte_look_ahead: 0.2 # The max/min distance to add for the CTE tracking + + penalize_negative_x: true # Whether to penalize trajectories that have negative x velocities. + + # non-dynamic parameters + dist_towards_obstacles: 1.5 + dist_towards_obstacles_trolley: 1.75 + goal_seek_tolerance: 2.0 + goal_seek_tolerance_trolley: 0.25 diff --git a/mir_robot/mir_navigation/config/move_base_common_params.yaml b/mir_robot/mir_navigation/config/move_base_common_params.yaml new file mode 100755 index 0000000..e8df96c --- /dev/null +++ b/mir_robot/mir_navigation/config/move_base_common_params.yaml @@ -0,0 +1,46 @@ +### footprint +# footprint: [[0.488,-0.293],[0.488,0.293],[-0.412,0.293],[-0.412,-0.293]] # mir 100 +footprint: [[0.405,-0.293],[0.405,0.293],[-0.412,0.293],[-0.412,-0.293]] # mir 250 +# footprint: [[0.394,-0.385],[0.394,0.385],[-0.363,0.385],[-0.363,-0.385]] + +### replanning +controller_frequency: 15.0 # run controller at 5.0 Hz +controller_patience: 2.0 # if the controller failed, clear obstacles and retry; after 15.0 s, abort and replan +planner_frequency: 0.0 # don't continually replan (only when controller failed) +planner_patience: 5.0 # if the first planning attempt failed, abort planning retries after 5.0 s... +max_planning_retries: 5 # ... or after 10 attempts (whichever happens first) +oscillation_timeout: 30.0 # abort controller and trigger recovery behaviors after 30.0 s +oscillation_distance: 0.3 +### recovery behaviors +recovery_behavior_enabled: true +recovery_behaviors: [ + {name: aggressive_reset, type: clear_costmap_recovery/ClearCostmapRecovery}, + {name: conservative_reset, type: clear_costmap_recovery/ClearCostmapRecovery}, + # {name: particular, type: twist_recovery/TwistRecovery}, + # {name: by_pass, type: direction_zones_recovery/DirectionZonesRecovery}, + ] + +conservative_reset: + reset_distance: 3.0 # clear obstacles farther away than 3.0 m + force_updating: true + # invert_area_to_clear: true + +aggressive_reset: + reset_distance: 3.0 + force_updating: true + +particular: + linear_x: -0.3 + linear_y: 0.0 + angular_z: 0.0 + duration: 1.5 + +# advoicedance: +# use_local_frame: false +# plan_topic: /move_base_node/SBPLLatticePlanner/plan +# planning_distance: 4.0 + +by_pass: + reset_distance: 8.0 + force_updating: true + affected_maps: global diff --git a/mir_robot/mir_navigation/config/pose_local_planner_params.yaml b/mir_robot/mir_navigation/config/pose_local_planner_params.yaml new file mode 100755 index 0000000..238e113 --- /dev/null +++ b/mir_robot/mir_navigation/config/pose_local_planner_params.yaml @@ -0,0 +1,46 @@ +base_local_planner: pose_follower/PoseFollower +PoseFollower: + k_trans: 2.0 + k_rot: 1.0 + + # within this distance to the goal, finally rotate to the goal heading (also, we've reached our goal only if we're within this dist) + tolerance_trans: 0.3 + + # we've reached our goal only if we're within this angular distance + tolerance_rot: 0.3 + + # we've reached our goal only if we're within range for this long and stopped + tolerance_timeout: 0.5 + + # set this to true if you're using a holonomic robot + holonomic: false + + # number of samples (scaling factors of our current desired twist) to check the validity of + samples: 10 + + # go no faster than this + max_vel_lin: 0.3 + max_vel_th: 0.5 + + # minimum velocities to keep from getting stuck + min_vel_lin: 0.03 + min_vel_th: 0.1 + + # if we're rotating in place, go at least this fast to avoid getting stuck + min_in_place_vel_th: 0.1 + + # when we're near the end and would be trying to go no faster than this translationally, just rotate in place instead + in_place_trans_vel: 0.1 + + # we're "stopped" if we're going slower than these velocities + trans_stopped_velocity: 0.03 + rot_stopped_velocity: 0.1 + + # if this is true, we don't care whether we go backwards or forwards + allow_backwards: true + + # if this is true, turn in place to face the new goal instead of arcing toward it + turn_in_place_first: true + + # if turn_in_place_first is true, turn in place if our heading is more than this far from facing the goal location + max_heading_diff_before_moving: 0.2 diff --git a/mir_robot/mir_navigation/config/sbpl_global_params.yaml b/mir_robot/mir_navigation/config/sbpl_global_params.yaml new file mode 100755 index 0000000..a7c6da7 --- /dev/null +++ b/mir_robot/mir_navigation/config/sbpl_global_params.yaml @@ -0,0 +1,10 @@ +base_global_planner: SBPLLatticePlanner +SBPLLatticePlanner: + environment_type: XYThetaLattice + planner_type: ARAPlanner + allocated_time: 10.0 + initial_epsilon: 1.0 + force_scratch_limit: 10000 + forward_search: true + nominalvel_mpersecs: 0.3 + timetoturn45degsinplace_secs: 1.31 # = 0.6 rad/s diff --git a/mir_robot/mir_navigation/config/teb_local_planner_params.yaml b/mir_robot/mir_navigation/config/teb_local_planner_params.yaml new file mode 100755 index 0000000..5e395af --- /dev/null +++ b/mir_robot/mir_navigation/config/teb_local_planner_params.yaml @@ -0,0 +1,105 @@ +# NOTE: When using the teb_local_planner, make sure to set the local costmap +# resolution high (for example 0.1 m), otherwise the optimization will take +# forever (around 10 minutes for each iteration). +base_local_planner: teb_local_planner/TebLocalPlannerROS +TebLocalPlannerROS: + # Trajectory + teb_autosize: true # Enable the automatic resizing of the trajectory during optimization (based on the temporal resolution of the trajectory, recommended) + dt_ref: 0.3 # Temporal resolution of the planned trajectory (usually it is set to the magnitude of the 1/control_rate) + dt_hysteresis: 0.1 # Hysteresis that is utilized for automatic resizing depending on the current temporal resolution (dt): usually 10% of dt_ref + global_plan_overwrite_orientation: false # Some global planners are not considering the orientation at local subgoals between start and global goal, therefore determine it automatically + allow_init_with_backwards_motion: false # If true, the underlying trajectories might be initialized with backwards motions in case the goal is behind the start within the local costmap (this is only recommended if the robot is equipped with rear sensors) + max_global_plan_lookahead_dist: 3.0 # Specify maximum length (cumulative Euclidean distances) of the subset of the global plan taken into account for optimization [if 0 or negative: disabled; the length is also bounded by the local costmap size] + force_reinit_new_goal_dist: 1.0 # Force the planner to reinitialize the trajectory if a previous goal is updated with a seperation of more than the specified value in meters (skip hot-starting) + feasibility_check_no_poses: 5 # Specify up to which pose on the predicted plan the feasibility should be checked each sampling interval + global_plan_viapoint_sep: -0.1 # Min. separation between each two consecutive via-points extracted from the global plan [if negative: disabled] + via_points_ordered: false # If true, the planner adheres to the order of via-points in the storage container + exact_arc_length: false # If true, the planner uses the exact arc length in velocity, acceleration and turning rate computations [-> increased cpu time], otherwise the euclidean approximation is used. + publish_feedback: false # Publish planner feedback containing the full trajectory and a list of active obstacles (should be enabled only for evaluation or debugging purposes) + + # Robot + max_vel_x: 0.8 # Maximum translational velocity of the robot + max_vel_x_backwards: 0.2 # Maximum translational velocity of the robot for driving backwards + max_vel_y: 0.0 # Maximum strafing velocity of the robot (should be zero for non-holonomic robots!) + max_vel_theta: 1.0 # Maximum angular velocity of the robot + acc_lim_x: 1.5 # Maximum translational acceleration of the robot + acc_lim_y: 0.0 # Maximum strafing acceleration of the robot + acc_lim_theta: 2.0 # Maximum angular acceleration of the robot + min_turning_radius: 0.0 # Minimum turning radius of a carlike robot (diff-drive robot: zero) + wheelbase: 1.0 # The distance between the drive shaft and steering axle (only required for a carlike robot with 'cmd_angle_instead_rotvel' enabled); The value might be negative for back-wheeled robots! + cmd_angle_instead_rotvel: false # Substitute the rotational velocity in the commanded velocity message by the corresponding steering angle (check 'axles_distance') + is_footprint_dynamic: false # If true, update the footprint before checking trajectory feasibility + footprint_model: + type: "polygon" + vertices: [[0.506,-0.32],[0.506,0.32],[-0.454,0.32],[-0.454,-0.32]] + + # Goal tolerance + xy_goal_tolerance: 0.03 # Allowed final euclidean distance to the goal position + yaw_goal_tolerance: 0.08 # Allowed final orientation error to the goal orientation + free_goal_vel: false # Allow the robot's velocity to be nonzero for planning purposes (the robot can arrive at the goal with max speed) + + # Obstacles + min_obstacle_dist: 0.4 # Minimum desired separation from obstacles + inflation_dist: 0.1 # Buffer zone around obstacles with non-zero penalty costs (should be larger than min_obstacle_dist in order to take effect) + dynamic_obstacle_inflation_dist: 0.6 # Buffer zone around predicted locations of dynamic obstacles with non-zero penalty costs (should be larger than min_obstacle_dist in order to take effect) + include_dynamic_obstacles: false # Specify whether the movement of dynamic obstacles should be predicted by a constant velocity model (this also changes the homotopy class search). If false, all obstacles are considered to be static. + include_costmap_obstacles: true # Specify whether the obstacles in the costmap should be taken into account directly (this is necessary if no seperate clustering and detection is implemented) + legacy_obstacle_association: false # If true, the old association strategy is used (for each obstacle, find the nearest TEB pose), otherwise the new one (for each teb pose, find only 'relevant' obstacles). + obstacle_association_force_inclusion_factor: 1.5 # The non-legacy obstacle association technique tries to connect only relevant obstacles with the discretized trajectory during optimization, all obstacles within a specifed distance are forced to be included (as a multiple of min_obstacle_dist), e.g. choose 2.0 in order to consider obstacles within a radius of 2.0*min_obstacle_dist. + obstacle_association_cutoff_factor: 5.0 # See obstacle_association_force_inclusion_factor, but beyond a multiple of [value]*min_obstacle_dist all obstacles are ignored during optimization. obstacle_association_force_inclusion_factor is processed first. + costmap_obstacles_behind_robot_dist: 1.5 # Limit the occupied local costmap obstacles taken into account for planning behind the robot (specify distance in meters) + obstacle_poses_affected: 10 # The obstacle position is attached to the closest pose on the trajectory to reduce computational effort, but take a number of neighbors into account as well + #costmap_converter_plugin: "" # + #costmap_converter_spin_thread: true # + #costmap_converter_rate: 5 # + + # Optimization + no_inner_iterations: 5 # Number of solver iterations called in each outerloop iteration + no_outer_iterations: 4 # Each outerloop iteration automatically resizes the trajectory and invokes the internal optimizer with no_inner_iterations + optimization_activate: true # Activate the optimization + optimization_verbose: false # Print verbose information + penalty_epsilon: 0.1 # Add a small safty margin to penalty functions for hard-constraint approximations + weight_max_vel_x: 2.0 # Optimization weight for satisfying the maximum allowed translational velocity + weight_max_vel_y: 2.0 # Optimization weight for satisfying the maximum allowed strafing velocity (in use only for holonomic robots) + weight_max_vel_theta: 1.0 # Optimization weight for satisfying the maximum allowed angular velocity + weight_acc_lim_x: 1.0 # Optimization weight for satisfying the maximum allowed translational acceleration + weight_acc_lim_y: 1.0 # Optimization weight for satisfying the maximum allowed strafing acceleration (in use only for holonomic robots) + weight_acc_lim_theta: 1.0 # Optimization weight for satisfying the maximum allowed angular acceleration + weight_kinematics_nh: 1000.0 # Optimization weight for satisfying the non-holonomic kinematics + weight_kinematics_forward_drive: 1.0 # Optimization weight for forcing the robot to choose only forward directions (positive transl. velocities, only diffdrive robot) + weight_kinematics_turning_radius: 1.0 # Optimization weight for enforcing a minimum turning radius (carlike robots) + weight_optimaltime: 1.0 # Optimization weight for contracting the trajectory w.r.t transition time + weight_obstacle: 50.0 # Optimization weight for satisfying a minimum seperation from obstacles + weight_inflation: 0.1 # Optimization weight for the inflation penalty (should be small) + weight_dynamic_obstacle: 50.0 # Optimization weight for satisfying a minimum seperation from dynamic obstacles + weight_dynamic_obstacle_inflation: 0.1 # Optimization weight for the inflation penalty of dynamic obstacles (should be small) + weight_viapoint: 1.0 # Optimization weight for minimizing the distance to via-points + weight_adapt_factor: 2.0 # Some special weights (currently 'weight_obstacle') are repeatedly scaled by this factor in each outer TEB iteration (weight_new: weight_old * factor); Increasing weights iteratively instead of setting a huge value a-priori leads to better numerical conditions of the underlying optimization problem. + + # Homotopy Class Planner +# enable_homotopy_class_planning: true # + enable_multithreading: true # Activate multiple threading for planning multiple trajectories in parallel +# simple_exploration: false # + max_number_classes: 2 # Specify the maximum number of allowed alternative homotopy classes (limits computational effort) + selection_cost_hysteresis: 1.0 # Specify how much trajectory cost must a new candidate have w.r.t. a previously selected trajectory in order to be selected (selection if new_cost < old_cost*factor) + selection_prefer_initial_plan: 0.95 # Specify a cost reduction in the interval (0,1) for the trajectory in the equivalence class of the initial plan.) + selection_obst_cost_scale: 100.0 # Extra scaling of obstacle cost terms just for selecting the 'best' candidate (new_obst_cost: obst_cost*factor) + selection_viapoint_cost_scale: 1.0 # Extra scaling of via-point cost terms just for selecting the 'best' candidate. (new_viapt_cost: viapt_cost*factor) + selection_alternative_time_cost: false # If true, time cost is replaced by the total transition time. + roadmap_graph_no_samples: 15 # Specify the number of samples generated for creating the roadmap graph, if simple_exploration is turend off + roadmap_graph_area_width: 5.0 # Specify the width of the area in which sampled will be generated between start and goal [m] (the height equals the start-goal distance) + roadmap_graph_area_length_scale: 1.0 # The length of the rectangular region is determined by the distance between start and goal. This parameter further scales the distance such that the geometric center remains equal!) + h_signature_prescaler: 1.0 # Scale number of obstacle value in order to allow huge number of obstacles. Do not choose it extremly low, otherwise obstacles cannot be distinguished from each other (0.2 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/mir_robot/mir_navigation/launch/hector_mapping.launch b/mir_robot/mir_navigation/launch/hector_mapping.launch new file mode 100755 index 0000000..ea5c4b8 --- /dev/null +++ b/mir_robot/mir_navigation/launch/hector_mapping.launch @@ -0,0 +1,68 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/mir_robot/mir_navigation/launch/move_base.xml b/mir_robot/mir_navigation/launch/move_base.xml new file mode 100755 index 0000000..a04a764 --- /dev/null +++ b/mir_robot/mir_navigation/launch/move_base.xml @@ -0,0 +1,29 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/mir_robot/mir_navigation/launch/start_maps.launch b/mir_robot/mir_navigation/launch/start_maps.launch new file mode 100755 index 0000000..ea954c0 --- /dev/null +++ b/mir_robot/mir_navigation/launch/start_maps.launch @@ -0,0 +1,44 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/mir_robot/mir_navigation/launch/start_planner.launch b/mir_robot/mir_navigation/launch/start_planner.launch new file mode 100755 index 0000000..863b88b --- /dev/null +++ b/mir_robot/mir_navigation/launch/start_planner.launch @@ -0,0 +1,89 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/mir_robot/mir_navigation/mprim/genmprim_unicycle_highcost_5cm.m b/mir_robot/mir_navigation/mprim/genmprim_unicycle_highcost_5cm.m new file mode 100755 index 0000000..2810593 --- /dev/null +++ b/mir_robot/mir_navigation/mprim/genmprim_unicycle_highcost_5cm.m @@ -0,0 +1,280 @@ +% /* +% * Copyright (c) 2008, Maxim Likhachev +% * All rights reserved. +% * +% * Redistribution and use in source and binary forms, with or without +% * modification, are permitted provided that the following conditions are met: +% * +% * * Redistributions of source code must retain the above copyright +% * notice, this list of conditions and the following disclaimer. +% * * Redistributions in binary form must reproduce the above copyright +% * notice, this list of conditions and the following disclaimer in the +% * documentation and/or other materials provided with the distribution. +% * * Neither the name of the Carnegie Mellon University nor the names of its +% * contributors may be used to endorse or promote products derived from +% * this software without specific prior written permission. +% * +% * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +% * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +% * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +% * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +% * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +% * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +% * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +% * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +% * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +% * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +% * POSSIBILITY OF SUCH DAMAGE. +% */ + +function[] = genmprim_unicycle_highcost_5cm(outfilename) + +% +%generates motion primitives and saves them into file +% +%written by Maxim Likhachev +%--------------------------------------------------- +% + +%defines + +UNICYCLE_MPRIM_16DEGS = 1; + + +if UNICYCLE_MPRIM_16DEGS == 1 + resolution = 0.05; + numberofangles = 16; %preferably a power of 2, definitely multiple of 8 + numberofprimsperangle = 7; + + %multipliers (multiplier is used as costmult*cost) + forwardcostmult = 1; + backwardcostmult = 40; + forwardandturncostmult = 2; + sidestepcostmult = 10; + turninplacecostmult = 20; + + %note, what is shown x,y,theta changes (not absolute numbers) + + %0 degreees + basemprimendpts0_c = zeros(numberofprimsperangle, 4); %x,y,theta,costmult + %x aligned with the heading of the robot, angles are positive + %counterclockwise + %0 theta change + basemprimendpts0_c(1,:) = [1 0 0 forwardcostmult]; + basemprimendpts0_c(2,:) = [8 0 0 forwardcostmult]; + basemprimendpts0_c(3,:) = [-1 0 0 backwardcostmult]; + %1/16 theta change + basemprimendpts0_c(4,:) = [8 1 1 forwardandturncostmult]; + basemprimendpts0_c(5,:) = [8 -1 -1 forwardandturncostmult]; + %turn in place + basemprimendpts0_c(6,:) = [0 0 1 turninplacecostmult]; + basemprimendpts0_c(7,:) = [0 0 -1 turninplacecostmult]; + + %45 degrees + basemprimendpts45_c = zeros(numberofprimsperangle, 4); %x,y,theta,costmult (multiplier is used as costmult*cost) + %x aligned with the heading of the robot, angles are positive + %counterclockwise + %0 theta change + basemprimendpts45_c(1,:) = [1 1 0 forwardcostmult]; + basemprimendpts45_c(2,:) = [6 6 0 forwardcostmult]; + basemprimendpts45_c(3,:) = [-1 -1 0 backwardcostmult]; + %1/16 theta change + basemprimendpts45_c(4,:) = [5 7 1 forwardandturncostmult]; + basemprimendpts45_c(5,:) = [7 5 -1 forwardandturncostmult]; + %turn in place + basemprimendpts45_c(6,:) = [0 0 1 turninplacecostmult]; + basemprimendpts45_c(7,:) = [0 0 -1 turninplacecostmult]; + + %22.5 degrees + basemprimendpts22p5_c = zeros(numberofprimsperangle, 4); %x,y,theta,costmult (multiplier is used as costmult*cost) + %x aligned with the heading of the robot, angles are positive + %counterclockwise + %0 theta change + basemprimendpts22p5_c(1,:) = [2 1 0 forwardcostmult]; + basemprimendpts22p5_c(2,:) = [6 3 0 forwardcostmult]; + basemprimendpts22p5_c(3,:) = [-2 -1 0 backwardcostmult]; + %1/16 theta change + basemprimendpts22p5_c(4,:) = [5 4 1 forwardandturncostmult]; + basemprimendpts22p5_c(5,:) = [7 2 -1 forwardandturncostmult]; + %turn in place + basemprimendpts22p5_c(6,:) = [0 0 1 turninplacecostmult]; + basemprimendpts22p5_c(7,:) = [0 0 -1 turninplacecostmult]; + +else + fprintf(1, 'ERROR: undefined mprims type\n'); + return; +end; + + +fout = fopen(outfilename, 'w'); + + +%write the header +fprintf(fout, 'resolution_m: %f\n', resolution); +fprintf(fout, 'numberofangles: %d\n', numberofangles); +fprintf(fout, 'totalnumberofprimitives: %d\n', numberofprimsperangle*numberofangles); + +%iterate over angles +for angleind = 1:numberofangles + + figure(1); + hold off; + + text(0, 0, int2str(angleind)); + + %iterate over primitives + for primind = 1:numberofprimsperangle + fprintf(fout, 'primID: %d\n', primind-1); + fprintf(fout, 'startangle_c: %d\n', angleind-1); + + %current angle + currentangle = (angleind-1)*2*pi/numberofangles; + currentangle_36000int = round((angleind-1)*36000/numberofangles); + + %compute which template to use + if (rem(currentangle_36000int, 9000) == 0) + basemprimendpts_c = basemprimendpts0_c(primind,:); + angle = currentangle; + elseif (rem(currentangle_36000int, 4500) == 0) + basemprimendpts_c = basemprimendpts45_c(primind,:); + angle = currentangle - 45*pi/180; + elseif (rem(currentangle_36000int-7875, 9000) == 0) + basemprimendpts_c = basemprimendpts33p75_c(primind,:); + basemprimendpts_c(1) = basemprimendpts33p75_c(primind, 2); %reverse x and y + basemprimendpts_c(2) = basemprimendpts33p75_c(primind, 1); + basemprimendpts_c(3) = -basemprimendpts33p75_c(primind, 3); %reverse the angle as well + angle = currentangle - 78.75*pi/180; + fprintf(1, '78p75\n'); + elseif (rem(currentangle_36000int-6750, 9000) == 0) + basemprimendpts_c = basemprimendpts22p5_c(primind,:); + basemprimendpts_c(1) = basemprimendpts22p5_c(primind, 2); %reverse x and y + basemprimendpts_c(2) = basemprimendpts22p5_c(primind, 1); + basemprimendpts_c(3) = -basemprimendpts22p5_c(primind, 3); %reverse the angle as well + %fprintf(1, '%d %d %d onto %d %d %d\n', basemprimendpts22p5_c(1), basemprimendpts22p5_c(2), basemprimendpts22p5_c(3), ... + % basemprimendpts_c(1), basemprimendpts_c(2), basemprimendpts_c(3)); + angle = currentangle - 67.5*pi/180; + fprintf(1, '67p5\n'); + elseif (rem(currentangle_36000int-5625, 9000) == 0) + basemprimendpts_c = basemprimendpts11p25_c(primind,:); + basemprimendpts_c(1) = basemprimendpts11p25_c(primind, 2); %reverse x and y + basemprimendpts_c(2) = basemprimendpts11p25_c(primind, 1); + basemprimendpts_c(3) = -basemprimendpts11p25_c(primind, 3); %reverse the angle as well + angle = currentangle - 56.25*pi/180; + fprintf(1, '56p25\n'); + elseif (rem(currentangle_36000int-3375, 9000) == 0) + basemprimendpts_c = basemprimendpts33p75_c(primind,:); + angle = currentangle - 33.75*pi/180; + fprintf(1, '33p75\n'); + elseif (rem(currentangle_36000int-2250, 9000) == 0) + basemprimendpts_c = basemprimendpts22p5_c(primind,:); + angle = currentangle - 22.5*pi/180; + fprintf(1, '22p5\n'); + elseif (rem(currentangle_36000int-1125, 9000) == 0) + basemprimendpts_c = basemprimendpts11p25_c(primind,:); + angle = currentangle - 11.25*pi/180; + fprintf(1, '11p25\n'); + else + fprintf(1, 'ERROR: invalid angular resolution. angle = %d\n', currentangle_36000int); + return; + end; + + %now figure out what action will be + baseendpose_c = basemprimendpts_c(1:3); + additionalactioncostmult = basemprimendpts_c(4); + endx_c = round(baseendpose_c(1)*cos(angle) - baseendpose_c(2)*sin(angle)); + endy_c = round(baseendpose_c(1)*sin(angle) + baseendpose_c(2)*cos(angle)); + endtheta_c = rem(angleind - 1 + baseendpose_c(3), numberofangles); + endpose_c = [endx_c endy_c endtheta_c]; + + fprintf(1, 'rotation angle=%f\n', angle*180/pi); + + if baseendpose_c(2) == 0 & baseendpose_c(3) == 0 + %fprintf(1, 'endpose=%d %d %d\n', endpose_c(1), endpose_c(2), endpose_c(3)); + end; + + %generate intermediate poses (remember they are w.r.t 0,0 (and not + %centers of the cells) + numofsamples = 10; + intermcells_m = zeros(numofsamples,3); + if UNICYCLE_MPRIM_16DEGS == 1 + startpt = [0 0 currentangle]; + endpt = [endpose_c(1)*resolution endpose_c(2)*resolution ... + rem(angleind - 1 + baseendpose_c(3), numberofangles)*2*pi/numberofangles]; + intermcells_m = zeros(numofsamples,3); + if ((endx_c == 0 & endy_c == 0) | baseendpose_c(3) == 0) %turn in place or move forward + for iind = 1:numofsamples + intermcells_m(iind,:) = [startpt(1) + (endpt(1) - startpt(1))*(iind-1)/(numofsamples-1) ... + startpt(2) + (endpt(2) - startpt(2))*(iind-1)/(numofsamples-1) ... + 0]; + rotation_angle = (baseendpose_c(3) ) * (2*pi/numberofangles); + intermcells_m(iind,3) = rem(startpt(3) + (rotation_angle)*(iind-1)/(numofsamples-1), 2*pi); + + end; + else %unicycle-based move forward or backward + R = [cos(startpt(3)) sin(endpt(3)) - sin(startpt(3)); + sin(startpt(3)) -(cos(endpt(3)) - cos(startpt(3)))]; + S = pinv(R)*[endpt(1) - startpt(1); endpt(2) - startpt(2)]; + l = S(1); + tvoverrv = S(2); + rv = (baseendpose_c(3)*2*pi/numberofangles + l/tvoverrv); + tv = tvoverrv*rv; + + if l < 0 + fprintf(1, 'WARNING: l = %d < 0 -> bad action start/end points\n', l); + l = 0; + end; + %compute rv + %rv = baseendpose_c(3)*2*pi/numberofangles; + %compute tv + %tvx = (endpt(1) - startpt(1))*rv/(sin(endpt(3)) - sin(startpt(3))) + %tvy = -(endpt(2) - startpt(2))*rv/(cos(endpt(3)) - cos(startpt(3))) + %tv = (tvx + tvy)/2.0; + %generate samples + for iind = 1:numofsamples + dt = (iind-1)/(numofsamples-1); + + %dtheta = rv*dt + startpt(3); + %intermcells_m(iind,:) = [startpt(1) + tv/rv*(sin(dtheta) - sin(startpt(3))) ... + % startpt(2) - tv/rv*(cos(dtheta) - cos(startpt(3))) ... + % dtheta]; + + if(dt*tv < l) + intermcells_m(iind,:) = [startpt(1) + dt*tv*cos(startpt(3)) ... + startpt(2) + dt*tv*sin(startpt(3)) ... + startpt(3)]; + else + dtheta = rv*(dt - l/tv) + startpt(3); + intermcells_m(iind,:) = [startpt(1) + l*cos(startpt(3)) + tvoverrv*(sin(dtheta) - sin(startpt(3))) ... + startpt(2) + l*sin(startpt(3)) - tvoverrv*(cos(dtheta) - cos(startpt(3))) ... + dtheta]; + end; + end; + %correct + errorxy = [endpt(1) - intermcells_m(numofsamples,1) ... + endpt(2) - intermcells_m(numofsamples,2)]; + fprintf(1, 'l=%f errx=%f erry=%f\n', l, errorxy(1), errorxy(2)); + interpfactor = [0:1/(numofsamples-1):1]; + intermcells_m(:,1) = intermcells_m(:,1) + errorxy(1)*interpfactor'; + intermcells_m(:,2) = intermcells_m(:,2) + errorxy(2)*interpfactor'; + end; + end; + + %write out + fprintf(fout, 'endpose_c: %d %d %d\n', endpose_c(1), endpose_c(2), endpose_c(3)); + fprintf(fout, 'additionalactioncostmult: %d\n', additionalactioncostmult); + fprintf(fout, 'intermediateposes: %d\n', size(intermcells_m,1)); + for interind = 1:size(intermcells_m, 1) + fprintf(fout, '%.4f %.4f %.4f\n', intermcells_m(interind,1), intermcells_m(interind,2), intermcells_m(interind,3)); + end; + + plot(intermcells_m(:,1), intermcells_m(:,2)); + axis([-0.3 0.3 -0.3 0.3]); + text(intermcells_m(numofsamples,1), intermcells_m(numofsamples,2), int2str(endpose_c(3))); + hold on; + + end; + grid; + pause; +end; + +fclose('all'); diff --git a/mir_robot/mir_navigation/mprim/genmprim_unicycle_highcost_5cm.py b/mir_robot/mir_navigation/mprim/genmprim_unicycle_highcost_5cm.py new file mode 100755 index 0000000..a77f83c --- /dev/null +++ b/mir_robot/mir_navigation/mprim/genmprim_unicycle_highcost_5cm.py @@ -0,0 +1,416 @@ +#!/usr/bin/env python3 +# +# Copyright (c) 2016, David Conner (Christopher Newport University) +# Based on genmprim_unicycle.m +# Copyright (c) 2008, Maxim Likhachev +# All rights reserved. +# converted by libermate utility (https://github.com/awesomebytes/libermate) +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# * Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in the +# documentation and/or other materials provided with the distribution. +# * Neither the name of the Carnegie Mellon University nor the names of its +# contributors may be used to endorse or promote products derived from +# this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. + +import numpy as np +import rospkg + +# if available import pylab (from matlibplot) +matplotlib_found = False +try: + import matplotlib.pylab as plt + + matplotlib_found = True +except ImportError: + pass + + +def matrix_size(mat, elem=None): + if not elem: + return mat.shape + else: + return mat.shape[int(elem) - 1] + + +def genmprim_unicycle(outfilename, visualize=False, separate_plots=False): + visualize = matplotlib_found and visualize # Plot the primitives + + # Local Variables: basemprimendpts22p5_c, endtheta_c, endx_c, + # baseendpose_c, additionalactioncostmult, fout, numofsamples, + # basemprimendpts45_c, primind, basemprimendpts0_c, rv, angle, outfilename, + # numberofangles, startpt, UNICYCLE_MPRIM_16DEGS, sidestepcostmult, + # rotation_angle, basemprimendpts_c, forwardandturncostmult, + # forwardcostmult, turninplacecostmult, endpose_c, backwardcostmult, + # interpfactor, S, R, tvoverrv, dtheta, intermcells_m, tv, dt, + # currentangle, numberofprimsperangle, resolution, currentangle_36000int, + # l, iind, errorxy, interind, endy_c, angleind, endpt + # Function calls: plot, cos, pi, grid, figure, genmprim_unicycle, text, + # int2str, pause, axis, sin, pinv, fprintf, fclose, rem, zeros, fopen, + # round, size + # % + # %generates motion primitives and saves them into file + # % + # %written by Maxim Likhachev + # %--------------------------------------------------- + # % + # %defines + UNICYCLE_MPRIM_16DEGS = 1.0 + if UNICYCLE_MPRIM_16DEGS == 1.0: + resolution = 0.05 + numberofangles = 16 + # %preferably a power of 2, definitely multiple of 8 + numberofprimsperangle = 7 + # %multipliers (multiplier is used as costmult*cost) + forwardcostmult = 1.0 + backwardcostmult = 40.0 + forwardandturncostmult = 2.0 + # sidestepcostmult = 10.0 + turninplacecostmult = 20.0 + # %note, what is shown x,y,theta changes (not absolute numbers) + # %0 degreees + basemprimendpts0_c = np.zeros((numberofprimsperangle, 4)) + # %x,y,theta,costmult + # %x aligned with the heading of the robot, angles are positive + # %counterclockwise + # %0 theta change + basemprimendpts0_c[0, :] = np.array(np.hstack((1.0, 0.0, 0.0, forwardcostmult))) + basemprimendpts0_c[1, :] = np.array(np.hstack((8.0, 0.0, 0.0, forwardcostmult))) + basemprimendpts0_c[2, :] = np.array(np.hstack((-1.0, 0.0, 0.0, backwardcostmult))) + # %1/16 theta change + basemprimendpts0_c[3, :] = np.array(np.hstack((8.0, 1.0, 1.0, forwardandturncostmult))) + basemprimendpts0_c[4, :] = np.array(np.hstack((8.0, -1.0, -1.0, forwardandturncostmult))) + # %turn in place + basemprimendpts0_c[5, :] = np.array(np.hstack((0.0, 0.0, 1.0, turninplacecostmult))) + basemprimendpts0_c[6, :] = np.array(np.hstack((0.0, 0.0, -1.0, turninplacecostmult))) + # %45 degrees + basemprimendpts45_c = np.zeros((numberofprimsperangle, 4)) + # %x,y,theta,costmult (multiplier is used as costmult*cost) + # %x aligned with the heading of the robot, angles are positive + # %counterclockwise + # %0 theta change + basemprimendpts45_c[0, :] = np.array(np.hstack((1.0, 1.0, 0.0, forwardcostmult))) + basemprimendpts45_c[1, :] = np.array(np.hstack((6.0, 6.0, 0.0, forwardcostmult))) + basemprimendpts45_c[2, :] = np.array(np.hstack((-1.0, -1.0, 0.0, backwardcostmult))) + # %1/16 theta change + basemprimendpts45_c[3, :] = np.array(np.hstack((5.0, 7.0, 1.0, forwardandturncostmult))) + basemprimendpts45_c[4, :] = np.array(np.hstack((7.0, 5.0, -1.0, forwardandturncostmult))) + # %turn in place + basemprimendpts45_c[5, :] = np.array(np.hstack((0.0, 0.0, 1.0, turninplacecostmult))) + basemprimendpts45_c[6, :] = np.array(np.hstack((0.0, 0.0, -1.0, turninplacecostmult))) + # %22.5 degrees + basemprimendpts22p5_c = np.zeros((numberofprimsperangle, 4)) + # %x,y,theta,costmult (multiplier is used as costmult*cost) + # %x aligned with the heading of the robot, angles are positive + # %counterclockwise + # %0 theta change + basemprimendpts22p5_c[0, :] = np.array(np.hstack((2.0, 1.0, 0.0, forwardcostmult))) + basemprimendpts22p5_c[1, :] = np.array(np.hstack((6.0, 3.0, 0.0, forwardcostmult))) + basemprimendpts22p5_c[2, :] = np.array(np.hstack((-2.0, -1.0, 0.0, backwardcostmult))) + # %1/16 theta change + basemprimendpts22p5_c[3, :] = np.array(np.hstack((5.0, 4.0, 1.0, forwardandturncostmult))) + basemprimendpts22p5_c[4, :] = np.array(np.hstack((7.0, 2.0, -1.0, forwardandturncostmult))) + # %turn in place + basemprimendpts22p5_c[5, :] = np.array(np.hstack((0.0, 0.0, 1.0, turninplacecostmult))) + basemprimendpts22p5_c[6, :] = np.array(np.hstack((0.0, 0.0, -1.0, turninplacecostmult))) + else: + print('ERROR: undefined mprims type\n') + return [] + + fout = open(outfilename, 'w') + # %write the header + fout.write('resolution_m: %f\n' % (resolution)) + fout.write('numberofangles: %d\n' % (numberofangles)) + fout.write('totalnumberofprimitives: %d\n' % (numberofprimsperangle * numberofangles)) + # %iterate over angles + for angleind in np.arange(1.0, (numberofangles) + 1): + currentangle = ((angleind - 1) * 2.0 * np.pi) / numberofangles + currentangle_36000int = np.round((angleind - 1) * 36000.0 / numberofangles) + if visualize: + if separate_plots: + fig = plt.figure(angleind) + plt.title('angle {:2.0f} (= {:3.1f} degrees)'.format(angleind - 1, currentangle_36000int / 100.0)) + else: + fig = plt.figure(1) + + plt.axis('equal') + plt.axis([-10 * resolution, 10 * resolution, -10 * resolution, 10 * resolution]) + ax = fig.add_subplot(1, 1, 1) + major_ticks = np.arange(-8 * resolution, 9 * resolution, 4 * resolution) + minor_ticks = np.arange(-8 * resolution, 9 * resolution, resolution) + ax.set_xticks(major_ticks) + ax.set_xticks(minor_ticks, minor=True) + ax.set_yticks(major_ticks) + ax.set_yticks(minor_ticks, minor=True) + ax.grid(which='minor', alpha=0.5) + ax.grid(which='major', alpha=0.9) + + # %iterate over primitives + for primind in np.arange(1.0, (numberofprimsperangle) + 1): + fout.write('primID: %d\n' % (primind - 1)) + fout.write('startangle_c: %d\n' % (angleind - 1)) + # %current angle + # %compute which template to use + if (currentangle_36000int % 9000) == 0: + basemprimendpts_c = basemprimendpts0_c[int(primind) - 1, :] + angle = currentangle + elif (currentangle_36000int % 4500) == 0: + basemprimendpts_c = basemprimendpts45_c[int(primind) - 1, :] + angle = currentangle - 45.0 * np.pi / 180.0 + + # commented out because basemprimendpts33p75_c is undefined + # elif ((currentangle_36000int - 7875) % 9000) == 0: + # basemprimendpts_c = ( + # 1 * basemprimendpts33p75_c[primind, :] + # ) # 1* to force deep copy to avoid reference update below + # basemprimendpts_c[0] = basemprimendpts33p75_c[primind, 1] + # # %reverse x and y + # basemprimendpts_c[1] = basemprimendpts33p75_c[primind, 0] + # basemprimendpts_c[2] = -basemprimendpts33p75_c[primind, 2] + # # %reverse the angle as well + # angle = currentangle - (78.75 * np.pi) / 180.0 + # print('78p75\n') + + elif ((currentangle_36000int - 6750) % 9000) == 0: + basemprimendpts_c = ( + 1 * basemprimendpts22p5_c[int(primind) - 1, :] + ) # 1* to force deep copy to avoid reference update below + basemprimendpts_c[0] = basemprimendpts22p5_c[int(primind) - 1, 1] + # %reverse x and y + basemprimendpts_c[1] = basemprimendpts22p5_c[int(primind) - 1, 0] + basemprimendpts_c[2] = -basemprimendpts22p5_c[int(primind) - 1, 2] + # %reverse the angle as well + # print( + # '%d : %d %d %d onto %d %d %d\n' + # % ( + # primind - 1, + # basemprimendpts22p5_c[int(primind) - 1, 0], + # basemprimendpts22p5_c[int(primind) - 1, 1], + # basemprimendpts22p5_c[int(primind) - 1, 2], + # basemprimendpts_c[0], + # basemprimendpts_c[1], + # basemprimendpts_c[2], + # ) + # ) + angle = currentangle - (67.5 * np.pi) / 180.0 + print('67p5\n') + + # commented out because basemprimendpts11p25_c is undefined + # elif ((currentangle_36000int - 5625) % 9000) == 0: + # basemprimendpts_c = ( + # 1 * basemprimendpts11p25_c[primind, :] + # ) # 1* to force deep copy to avoid reference update below + # basemprimendpts_c[0] = basemprimendpts11p25_c[primind, 1] + # # %reverse x and y + # basemprimendpts_c[1] = basemprimendpts11p25_c[primind, 0] + # basemprimendpts_c[2] = -basemprimendpts11p25_c[primind, 2] + # # %reverse the angle as well + # angle = currentangle - (56.25 * np.pi) / 180.0 + # print('56p25\n') + + # commented out because basemprimendpts33p75_c is undefined + # elif ((currentangle_36000int - 3375) % 9000) == 0: + # basemprimendpts_c = basemprimendpts33p75_c[int(primind), :] + # angle = currentangle - (33.75 * np.pi) / 180.0 + # print('33p75\n') + + elif ((currentangle_36000int - 2250) % 9000) == 0: + basemprimendpts_c = basemprimendpts22p5_c[int(primind) - 1, :] + angle = currentangle - (22.5 * np.pi) / 180.0 + print('22p5\n') + + # commented out because basemprimendpts11p25_c is undefined + # elif ((currentangle_36000int - 1125) % 9000) == 0: + # basemprimendpts_c = basemprimendpts11p25_c[int(primind), :] + # angle = currentangle - (11.25 * np.pi) / 180.0 + # print('11p25\n') + + else: + print('ERROR: invalid angular resolution. angle = %d\n' % currentangle_36000int) + return [] + + # %now figure out what action will be + baseendpose_c = basemprimendpts_c[0:3] + additionalactioncostmult = basemprimendpts_c[3] + endx_c = np.round((baseendpose_c[0] * np.cos(angle)) - (baseendpose_c[1] * np.sin(angle))) + endy_c = np.round((baseendpose_c[0] * np.sin(angle)) + (baseendpose_c[1] * np.cos(angle))) + endtheta_c = np.fmod(angleind - 1 + baseendpose_c[2], numberofangles) + endpose_c = np.array(np.hstack((endx_c, endy_c, endtheta_c))) + print("endpose_c=", endpose_c) + print(('rotation angle=%f\n' % (angle * 180.0 / np.pi))) + # if np.logical_and(baseendpose_c[1] == 0., baseendpose_c[2] == 0.): + # %fprintf(1, 'endpose=%d %d %d\n', endpose_c(1), endpose_c(2), endpose_c(3)); + + # %generate intermediate poses (remember they are w.r.t 0,0 (and not + # %centers of the cells) + numofsamples = 10 + intermcells_m = np.zeros((numofsamples, 3)) + if UNICYCLE_MPRIM_16DEGS == 1.0: + startpt = np.array(np.hstack((0.0, 0.0, currentangle))) + endpt = np.array( + np.hstack( + ( + (endpose_c[0] * resolution), + (endpose_c[1] * resolution), + ( + ((np.fmod(angleind - 1 + baseendpose_c[2], numberofangles)) * 2.0 * np.pi) + / numberofangles + ), + ) + ) + ) + + print("startpt =", startpt) + print("endpt =", endpt) + intermcells_m = np.zeros((numofsamples, 3)) + if np.logical_or(np.logical_and(endx_c == 0.0, endy_c == 0.0), baseendpose_c[2] == 0.0): + # %turn in place or move forward + for iind in np.arange(1.0, (numofsamples) + 1): + fraction = float(iind - 1) / (numofsamples - 1) + intermcells_m[int(iind) - 1, :] = np.array( + ( + startpt[0] + (endpt[0] - startpt[0]) * fraction, + startpt[1] + (endpt[1] - startpt[1]) * fraction, + 0, + ) + ) + rotation_angle = baseendpose_c[2] * (2.0 * np.pi / numberofangles) + intermcells_m[int(iind) - 1, 2] = np.fmod(startpt[2] + rotation_angle * fraction, (2.0 * np.pi)) + # print " ",iind," of ",numofsamples," fraction=",fraction," rotation=",rotation_angle + + else: + # %unicycle-based move forward or backward (http://sbpl.net/node/53) + R = np.array( + np.vstack( + ( + np.hstack((np.cos(startpt[2]), np.sin(endpt[2]) - np.sin(startpt[2]))), + np.hstack((np.sin(startpt[2]), -np.cos(endpt[2]) + np.cos(startpt[2]))), + ) + ) + ) + + S = np.dot(np.linalg.pinv(R), np.array(np.vstack((endpt[0] - startpt[0], endpt[1] - startpt[1])))) + l = S[0] + tvoverrv = S[1] + rv = (baseendpose_c[2] * 2.0 * np.pi / numberofangles) + l / tvoverrv + tv = tvoverrv * rv + + # print "R=\n",R + # print "Rpi=\n",np.linalg.pinv(R) + # print "S=\n",S + # print "l=",l + # print "tvoverrv=",tvoverrv + # print "rv=",rv + # print "tv=",tv + + if l < 0.0: + print(('WARNING: l = %f < 0 -> bad action start/end points\n' % (l))) + l = 0.0 + + # %compute rv + # %rv = baseendpose_c(3)*2*pi/numberofangles; + # %compute tv + # %tvx = (endpt(1) - startpt(1))*rv/(sin(endpt(3)) - sin(startpt(3))) + # %tvy = -(endpt(2) - startpt(2))*rv/(cos(endpt(3)) - cos(startpt(3))) + # %tv = (tvx + tvy)/2.0; + # %generate samples + for iind in np.arange(1, numofsamples + 1): + dt = (iind - 1) / (numofsamples - 1) + # %dtheta = rv*dt + startpt(3); + # %intermcells_m(iind,:) = [startpt(1) + tv/rv*(sin(dtheta) - sin(startpt(3))) ... + # % startpt(2) - tv/rv*(cos(dtheta) - cos(startpt(3))) ... + # % dtheta]; + if (dt * tv) < l: + intermcells_m[int(iind) - 1, :] = np.array( + np.hstack( + ( + startpt[0] + dt * tv * np.cos(startpt[2]), + startpt[1] + dt * tv * np.sin(startpt[2]), + startpt[2], + ) + ) + ) + else: + dtheta = rv * (dt - l / tv) + startpt[2] + intermcells_m[int(iind) - 1, :] = np.array( + np.hstack( + ( + startpt[0] + + l * np.cos(startpt[2]) + + tvoverrv * (np.sin(dtheta) - np.sin(startpt[2])), + startpt[1] + + l * np.sin(startpt[2]) + - tvoverrv * (np.cos(dtheta) - np.cos(startpt[2])), + dtheta, + ) + ) + ) + + # %correct + errorxy = np.array( + np.hstack( + ( + endpt[0] - intermcells_m[int(numofsamples) - 1, 0], + endpt[1] - intermcells_m[int(numofsamples) - 1, 1], + ) + ) + ) + # print('l=%f errx=%f erry=%f\n'%(l, errorxy[0], errorxy[1])) + interpfactor = np.array( + np.hstack((np.arange(0.0, 1.0 + (1.0 / (numofsamples)), 1.0 / (numofsamples - 1)))) + ) + + # print "intermcells_m=",intermcells_m + # print "interp'=",interpfactor.conj().T + + intermcells_m[:, 0] = intermcells_m[:, 0] + errorxy[0] * interpfactor.conj().T + intermcells_m[:, 1] = intermcells_m[:, 1] + errorxy[1] * interpfactor.conj().T + + # %write out + fout.write('endpose_c: %d %d %d\n' % (endpose_c[0], endpose_c[1], endpose_c[2])) + fout.write('additionalactioncostmult: %d\n' % (additionalactioncostmult)) + fout.write('intermediateposes: %d\n' % (matrix_size(intermcells_m, 1.0))) + for interind in np.arange(1.0, (matrix_size(intermcells_m, 1.0)) + 1): + fout.write( + '%.4f %.4f %.4f\n' + % ( + intermcells_m[int(interind) - 1, 0], + intermcells_m[int(interind) - 1, 1], + intermcells_m[int(interind) - 1, 2], + ) + ) + + if visualize: + plt.plot(intermcells_m[:, 0], intermcells_m[:, 1], linestyle="-", marker="o") + plt.text(endpt[0], endpt[1], '{:2.0f}'.format(endpose_c[2])) + # if (visualize): + # plt.waitforbuttonpress() # uncomment to plot each primitive set one at a time + + fout.close() + if visualize: + # plt.waitforbuttonpress() # hold until buttom pressed + plt.show() # Keep windows open until the program is terminated + return [] + + +if __name__ == "__main__": + rospack = rospkg.RosPack() + outfilename = rospack.get_path('mir_navigation') + '/mprim/unicycle_5cm.mprim' + genmprim_unicycle(outfilename, visualize=True, separate_plots= False) diff --git a/mir_robot/mir_navigation/mprim/unicycle_5cm.mprim b/mir_robot/mir_navigation/mprim/unicycle_5cm.mprim new file mode 100755 index 0000000..cb56cd0 --- /dev/null +++ b/mir_robot/mir_navigation/mprim/unicycle_5cm.mprim @@ -0,0 +1,1203 @@ +resolution_m: 0.050000 +numberofangles: 16 +totalnumberofprimitives: 80 +primID: 0 +startangle_c: 0 +endpose_c: 1 0 0 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0056 0.0000 0.0000 +0.0111 0.0000 0.0000 +0.0167 0.0000 0.0000 +0.0222 0.0000 0.0000 +0.0278 0.0000 0.0000 +0.0333 0.0000 0.0000 +0.0389 0.0000 0.0000 +0.0444 0.0000 0.0000 +0.0500 0.0000 0.0000 +primID: 1 +startangle_c: 0 +endpose_c: 8 0 0 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0444 0.0000 0.0000 +0.0889 0.0000 0.0000 +0.1333 0.0000 0.0000 +0.1778 0.0000 0.0000 +0.2222 0.0000 0.0000 +0.2667 0.0000 0.0000 +0.3111 0.0000 0.0000 +0.3556 0.0000 0.0000 +0.4000 0.0000 0.0000 +primID: 2 +startangle_c: 0 +endpose_c: -1 0 0 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 0.0000 +-0.0056 0.0000 0.0000 +-0.0111 0.0000 0.0000 +-0.0167 0.0000 0.0000 +-0.0222 0.0000 0.0000 +-0.0278 0.0000 0.0000 +-0.0333 0.0000 0.0000 +-0.0389 0.0000 0.0000 +-0.0444 0.0000 0.0000 +-0.0500 0.0000 0.0000 +primID: 3 +startangle_c: 0 +endpose_c: 8 1 1 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0452 -0.0000 0.0000 +0.0904 -0.0000 0.0000 +0.1355 -0.0000 0.0000 +0.1807 0.0008 0.0488 +0.2257 0.0045 0.1176 +0.2703 0.0114 0.1864 +0.3144 0.0213 0.2551 +0.3577 0.0342 0.3239 +0.4000 0.0500 0.3927 +primID: 4 +startangle_c: 0 +endpose_c: 8 -1 -1 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0452 0.0000 0.0000 +0.0904 0.0000 0.0000 +0.1355 0.0000 0.0000 +0.1807 -0.0008 -0.0488 +0.2257 -0.0045 -0.1176 +0.2703 -0.0114 -0.1864 +0.3144 -0.0213 -0.2551 +0.3577 -0.0342 -0.3239 +0.4000 -0.0500 -0.3927 +primID: 0 +startangle_c: 1 +endpose_c: 2 1 1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0111 0.0056 0.3927 +0.0222 0.0111 0.3927 +0.0333 0.0167 0.3927 +0.0444 0.0222 0.3927 +0.0556 0.0278 0.3927 +0.0667 0.0333 0.3927 +0.0778 0.0389 0.3927 +0.0889 0.0444 0.3927 +0.1000 0.0500 0.3927 +primID: 1 +startangle_c: 1 +endpose_c: 6 3 1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0333 0.0167 0.3927 +0.0667 0.0333 0.3927 +0.1000 0.0500 0.3927 +0.1333 0.0667 0.3927 +0.1667 0.0833 0.3927 +0.2000 0.1000 0.3927 +0.2333 0.1167 0.3927 +0.2667 0.1333 0.3927 +0.3000 0.1500 0.3927 +primID: 2 +startangle_c: 1 +endpose_c: -2 -1 1 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 0.3927 +-0.0111 -0.0056 0.3927 +-0.0222 -0.0111 0.3927 +-0.0333 -0.0167 0.3927 +-0.0444 -0.0222 0.3927 +-0.0556 -0.0278 0.3927 +-0.0667 -0.0333 0.3927 +-0.0778 -0.0389 0.3927 +-0.0889 -0.0444 0.3927 +-0.1000 -0.0500 0.3927 +primID: 3 +startangle_c: 1 +endpose_c: 5 4 2 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0298 0.0184 0.4230 +0.0592 0.0379 0.4533 +0.0881 0.0583 0.4836 +0.1165 0.0796 0.5139 +0.1444 0.1019 0.5442 +0.1717 0.1251 0.5745 +0.1984 0.1492 0.6048 +0.2245 0.1742 0.6351 +0.2500 0.2000 0.6654 +primID: 4 +startangle_c: 1 +endpose_c: 7 2 0 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0377 0.0156 0.3927 +0.0754 0.0312 0.3927 +0.1131 0.0468 0.3927 +0.1508 0.0623 0.3736 +0.1893 0.0758 0.2989 +0.2287 0.0863 0.2242 +0.2687 0.0939 0.1494 +0.3092 0.0985 0.0747 +0.3500 0.1000 0.0000 +primID: 0 +startangle_c: 2 +endpose_c: 1 1 2 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0056 0.0056 0.7854 +0.0111 0.0111 0.7854 +0.0167 0.0167 0.7854 +0.0222 0.0222 0.7854 +0.0278 0.0278 0.7854 +0.0333 0.0333 0.7854 +0.0389 0.0389 0.7854 +0.0444 0.0444 0.7854 +0.0500 0.0500 0.7854 +primID: 1 +startangle_c: 2 +endpose_c: 6 6 2 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0333 0.0333 0.7854 +0.0667 0.0667 0.7854 +0.1000 0.1000 0.7854 +0.1333 0.1333 0.7854 +0.1667 0.1667 0.7854 +0.2000 0.2000 0.7854 +0.2333 0.2333 0.7854 +0.2667 0.2667 0.7854 +0.3000 0.3000 0.7854 +primID: 2 +startangle_c: 2 +endpose_c: -1 -1 2 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 0.7854 +-0.0056 -0.0056 0.7854 +-0.0111 -0.0111 0.7854 +-0.0167 -0.0167 0.7854 +-0.0222 -0.0222 0.7854 +-0.0278 -0.0278 0.7854 +-0.0333 -0.0333 0.7854 +-0.0389 -0.0389 0.7854 +-0.0444 -0.0444 0.7854 +-0.0500 -0.0500 0.7854 +primID: 3 +startangle_c: 2 +endpose_c: 5 7 3 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0341 0.0341 0.7854 +0.0678 0.0684 0.8151 +0.1000 0.1043 0.8669 +0.1302 0.1418 0.9188 +0.1584 0.1809 0.9707 +0.1846 0.2213 1.0225 +0.2086 0.2631 1.0744 +0.2304 0.3060 1.1262 +0.2500 0.3500 1.1781 +primID: 4 +startangle_c: 2 +endpose_c: 7 5 1 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0341 0.0341 0.7854 +0.0684 0.0678 0.7557 +0.1043 0.1000 0.7039 +0.1418 0.1302 0.6520 +0.1809 0.1584 0.6001 +0.2213 0.1846 0.5483 +0.2631 0.2086 0.4964 +0.3060 0.2304 0.4446 +0.3500 0.2500 0.3927 +primID: 0 +startangle_c: 3 +endpose_c: 1 2 3 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0056 0.0111 1.1781 +0.0111 0.0222 1.1781 +0.0167 0.0333 1.1781 +0.0222 0.0444 1.1781 +0.0278 0.0556 1.1781 +0.0333 0.0667 1.1781 +0.0389 0.0778 1.1781 +0.0444 0.0889 1.1781 +0.0500 0.1000 1.1781 +primID: 1 +startangle_c: 3 +endpose_c: 3 6 3 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0167 0.0333 1.1781 +0.0333 0.0667 1.1781 +0.0500 0.1000 1.1781 +0.0667 0.1333 1.1781 +0.0833 0.1667 1.1781 +0.1000 0.2000 1.1781 +0.1167 0.2333 1.1781 +0.1333 0.2667 1.1781 +0.1500 0.3000 1.1781 +primID: 2 +startangle_c: 3 +endpose_c: -1 -2 3 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 1.1781 +-0.0056 -0.0111 1.1781 +-0.0111 -0.0222 1.1781 +-0.0167 -0.0333 1.1781 +-0.0222 -0.0444 1.1781 +-0.0278 -0.0556 1.1781 +-0.0333 -0.0667 1.1781 +-0.0389 -0.0778 1.1781 +-0.0444 -0.0889 1.1781 +-0.0500 -0.1000 1.1781 +primID: 3 +startangle_c: 3 +endpose_c: 4 5 2 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0184 0.0298 1.1478 +0.0379 0.0592 1.1175 +0.0583 0.0881 1.0872 +0.0796 0.1165 1.0569 +0.1019 0.1444 1.0266 +0.1251 0.1717 0.9963 +0.1492 0.1984 0.9660 +0.1742 0.2245 0.9357 +0.2000 0.2500 0.9054 +primID: 4 +startangle_c: 3 +endpose_c: 2 7 4 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0156 0.0377 1.1781 +0.0312 0.0754 1.1781 +0.0468 0.1131 1.1781 +0.0623 0.1508 1.1972 +0.0758 0.1893 1.2719 +0.0863 0.2287 1.3466 +0.0939 0.2687 1.4214 +0.0985 0.3092 1.4961 +0.1000 0.3500 1.5708 +primID: 0 +startangle_c: 4 +endpose_c: 0 1 4 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0056 1.5708 +0.0000 0.0111 1.5708 +0.0000 0.0167 1.5708 +0.0000 0.0222 1.5708 +0.0000 0.0278 1.5708 +0.0000 0.0333 1.5708 +0.0000 0.0389 1.5708 +0.0000 0.0444 1.5708 +0.0000 0.0500 1.5708 +primID: 1 +startangle_c: 4 +endpose_c: 0 8 4 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0444 1.5708 +0.0000 0.0889 1.5708 +0.0000 0.1333 1.5708 +0.0000 0.1778 1.5708 +0.0000 0.2222 1.5708 +0.0000 0.2667 1.5708 +0.0000 0.3111 1.5708 +0.0000 0.3556 1.5708 +0.0000 0.4000 1.5708 +primID: 2 +startangle_c: 4 +endpose_c: 0 -1 4 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 -0.0056 1.5708 +0.0000 -0.0111 1.5708 +0.0000 -0.0167 1.5708 +0.0000 -0.0222 1.5708 +0.0000 -0.0278 1.5708 +0.0000 -0.0333 1.5708 +0.0000 -0.0389 1.5708 +0.0000 -0.0444 1.5708 +0.0000 -0.0500 1.5708 +primID: 3 +startangle_c: 4 +endpose_c: -1 8 5 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0452 1.5708 +0.0000 0.0904 1.5708 +0.0000 0.1355 1.5708 +-0.0008 0.1807 1.6196 +-0.0045 0.2257 1.6884 +-0.0114 0.2703 1.7572 +-0.0213 0.3144 1.8259 +-0.0342 0.3577 1.8947 +-0.0500 0.4000 1.9635 +primID: 4 +startangle_c: 4 +endpose_c: 1 8 3 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.5708 +-0.0000 0.0452 1.5708 +-0.0000 0.0904 1.5708 +-0.0000 0.1355 1.5708 +0.0008 0.1807 1.5220 +0.0045 0.2257 1.4532 +0.0114 0.2703 1.3844 +0.0213 0.3144 1.3156 +0.0342 0.3577 1.2469 +0.0500 0.4000 1.1781 +primID: 0 +startangle_c: 5 +endpose_c: -1 2 5 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0056 0.0111 1.9635 +-0.0111 0.0222 1.9635 +-0.0167 0.0333 1.9635 +-0.0222 0.0444 1.9635 +-0.0278 0.0556 1.9635 +-0.0333 0.0667 1.9635 +-0.0389 0.0778 1.9635 +-0.0444 0.0889 1.9635 +-0.0500 0.1000 1.9635 +primID: 1 +startangle_c: 5 +endpose_c: -3 6 5 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0167 0.0333 1.9635 +-0.0333 0.0667 1.9635 +-0.0500 0.1000 1.9635 +-0.0667 0.1333 1.9635 +-0.0833 0.1667 1.9635 +-0.1000 0.2000 1.9635 +-0.1167 0.2333 1.9635 +-0.1333 0.2667 1.9635 +-0.1500 0.3000 1.9635 +primID: 2 +startangle_c: 5 +endpose_c: 1 -2 5 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0056 -0.0111 1.9635 +0.0111 -0.0222 1.9635 +0.0167 -0.0333 1.9635 +0.0222 -0.0444 1.9635 +0.0278 -0.0556 1.9635 +0.0333 -0.0667 1.9635 +0.0389 -0.0778 1.9635 +0.0444 -0.0889 1.9635 +0.0500 -0.1000 1.9635 +primID: 3 +startangle_c: 5 +endpose_c: -4 5 6 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0184 0.0298 1.9938 +-0.0379 0.0592 2.0241 +-0.0583 0.0881 2.0544 +-0.0796 0.1165 2.0847 +-0.1019 0.1444 2.1150 +-0.1251 0.1717 2.1453 +-0.1492 0.1984 2.1756 +-0.1742 0.2245 2.2059 +-0.2000 0.2500 2.2362 +primID: 4 +startangle_c: 5 +endpose_c: -2 7 4 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0156 0.0377 1.9635 +-0.0312 0.0754 1.9635 +-0.0468 0.1131 1.9635 +-0.0623 0.1508 1.9444 +-0.0758 0.1893 1.8697 +-0.0863 0.2287 1.7950 +-0.0939 0.2687 1.7202 +-0.0985 0.3092 1.6455 +-0.1000 0.3500 1.5708 +primID: 0 +startangle_c: 6 +endpose_c: -1 1 6 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0056 0.0056 2.3562 +-0.0111 0.0111 2.3562 +-0.0167 0.0167 2.3562 +-0.0222 0.0222 2.3562 +-0.0278 0.0278 2.3562 +-0.0333 0.0333 2.3562 +-0.0389 0.0389 2.3562 +-0.0444 0.0444 2.3562 +-0.0500 0.0500 2.3562 +primID: 1 +startangle_c: 6 +endpose_c: -6 6 6 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0333 0.0333 2.3562 +-0.0667 0.0667 2.3562 +-0.1000 0.1000 2.3562 +-0.1333 0.1333 2.3562 +-0.1667 0.1667 2.3562 +-0.2000 0.2000 2.3562 +-0.2333 0.2333 2.3562 +-0.2667 0.2667 2.3562 +-0.3000 0.3000 2.3562 +primID: 2 +startangle_c: 6 +endpose_c: 1 -1 6 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0056 -0.0056 2.3562 +0.0111 -0.0111 2.3562 +0.0167 -0.0167 2.3562 +0.0222 -0.0222 2.3562 +0.0278 -0.0278 2.3562 +0.0333 -0.0333 2.3562 +0.0389 -0.0389 2.3562 +0.0444 -0.0444 2.3562 +0.0500 -0.0500 2.3562 +primID: 3 +startangle_c: 6 +endpose_c: -7 5 7 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0341 0.0341 2.3562 +-0.0684 0.0678 2.3859 +-0.1043 0.1000 2.4377 +-0.1418 0.1302 2.4896 +-0.1809 0.1584 2.5415 +-0.2213 0.1846 2.5933 +-0.2631 0.2086 2.6452 +-0.3060 0.2304 2.6970 +-0.3500 0.2500 2.7489 +primID: 4 +startangle_c: 6 +endpose_c: -5 7 5 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0341 0.0341 2.3562 +-0.0678 0.0684 2.3265 +-0.1000 0.1043 2.2747 +-0.1302 0.1418 2.2228 +-0.1584 0.1809 2.1709 +-0.1846 0.2213 2.1191 +-0.2086 0.2631 2.0672 +-0.2304 0.3060 2.0154 +-0.2500 0.3500 1.9635 +primID: 0 +startangle_c: 7 +endpose_c: -2 1 7 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0111 0.0056 2.7489 +-0.0222 0.0111 2.7489 +-0.0333 0.0167 2.7489 +-0.0444 0.0222 2.7489 +-0.0556 0.0278 2.7489 +-0.0667 0.0333 2.7489 +-0.0778 0.0389 2.7489 +-0.0889 0.0444 2.7489 +-0.1000 0.0500 2.7489 +primID: 1 +startangle_c: 7 +endpose_c: -6 3 7 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0333 0.0167 2.7489 +-0.0667 0.0333 2.7489 +-0.1000 0.0500 2.7489 +-0.1333 0.0667 2.7489 +-0.1667 0.0833 2.7489 +-0.2000 0.1000 2.7489 +-0.2333 0.1167 2.7489 +-0.2667 0.1333 2.7489 +-0.3000 0.1500 2.7489 +primID: 2 +startangle_c: 7 +endpose_c: 2 -1 7 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0111 -0.0056 2.7489 +0.0222 -0.0111 2.7489 +0.0333 -0.0167 2.7489 +0.0444 -0.0222 2.7489 +0.0556 -0.0278 2.7489 +0.0667 -0.0333 2.7489 +0.0778 -0.0389 2.7489 +0.0889 -0.0444 2.7489 +0.1000 -0.0500 2.7489 +primID: 3 +startangle_c: 7 +endpose_c: -5 4 6 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0298 0.0184 2.7186 +-0.0592 0.0379 2.6883 +-0.0881 0.0583 2.6580 +-0.1165 0.0796 2.6277 +-0.1444 0.1019 2.5974 +-0.1717 0.1251 2.5671 +-0.1984 0.1492 2.5368 +-0.2245 0.1742 2.5065 +-0.2500 0.2000 2.4762 +primID: 4 +startangle_c: 7 +endpose_c: -7 2 8 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0377 0.0156 2.7489 +-0.0754 0.0312 2.7489 +-0.1131 0.0468 2.7489 +-0.1508 0.0623 2.7680 +-0.1893 0.0758 2.8427 +-0.2287 0.0863 2.9174 +-0.2687 0.0939 2.9921 +-0.3092 0.0985 3.0669 +-0.3500 0.1000 3.1416 +primID: 0 +startangle_c: 8 +endpose_c: -1 0 8 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0056 0.0000 3.1416 +-0.0111 0.0000 3.1416 +-0.0167 0.0000 3.1416 +-0.0222 0.0000 3.1416 +-0.0278 0.0000 3.1416 +-0.0333 0.0000 3.1416 +-0.0389 0.0000 3.1416 +-0.0444 0.0000 3.1416 +-0.0500 0.0000 3.1416 +primID: 1 +startangle_c: 8 +endpose_c: -8 0 8 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0444 0.0000 3.1416 +-0.0889 0.0000 3.1416 +-0.1333 0.0000 3.1416 +-0.1778 0.0000 3.1416 +-0.2222 0.0000 3.1416 +-0.2667 0.0000 3.1416 +-0.3111 0.0000 3.1416 +-0.3556 0.0000 3.1416 +-0.4000 0.0000 3.1416 +primID: 2 +startangle_c: 8 +endpose_c: 1 0 8 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0056 0.0000 3.1416 +0.0111 0.0000 3.1416 +0.0167 0.0000 3.1416 +0.0222 0.0000 3.1416 +0.0278 0.0000 3.1416 +0.0333 0.0000 3.1416 +0.0389 0.0000 3.1416 +0.0444 0.0000 3.1416 +0.0500 0.0000 3.1416 +primID: 3 +startangle_c: 8 +endpose_c: -8 -1 9 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0452 0.0000 3.1416 +-0.0904 0.0000 3.1416 +-0.1355 0.0000 3.1416 +-0.1807 -0.0008 3.1904 +-0.2257 -0.0045 3.2592 +-0.2703 -0.0114 3.3280 +-0.3144 -0.0213 3.3967 +-0.3577 -0.0342 3.4655 +-0.4000 -0.0500 3.5343 +primID: 4 +startangle_c: 8 +endpose_c: -8 1 7 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0452 0.0000 3.1416 +-0.0904 0.0000 3.1416 +-0.1355 0.0000 3.1416 +-0.1807 0.0008 3.0928 +-0.2257 0.0045 3.0240 +-0.2703 0.0114 2.9552 +-0.3144 0.0213 2.8864 +-0.3577 0.0342 2.8177 +-0.4000 0.0500 2.7489 +primID: 0 +startangle_c: 9 +endpose_c: -2 -1 9 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0111 -0.0056 3.5343 +-0.0222 -0.0111 3.5343 +-0.0333 -0.0167 3.5343 +-0.0444 -0.0222 3.5343 +-0.0556 -0.0278 3.5343 +-0.0667 -0.0333 3.5343 +-0.0778 -0.0389 3.5343 +-0.0889 -0.0444 3.5343 +-0.1000 -0.0500 3.5343 +primID: 1 +startangle_c: 9 +endpose_c: -6 -3 9 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0333 -0.0167 3.5343 +-0.0667 -0.0333 3.5343 +-0.1000 -0.0500 3.5343 +-0.1333 -0.0667 3.5343 +-0.1667 -0.0833 3.5343 +-0.2000 -0.1000 3.5343 +-0.2333 -0.1167 3.5343 +-0.2667 -0.1333 3.5343 +-0.3000 -0.1500 3.5343 +primID: 2 +startangle_c: 9 +endpose_c: 2 1 9 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0111 0.0056 3.5343 +0.0222 0.0111 3.5343 +0.0333 0.0167 3.5343 +0.0444 0.0222 3.5343 +0.0556 0.0278 3.5343 +0.0667 0.0333 3.5343 +0.0778 0.0389 3.5343 +0.0889 0.0444 3.5343 +0.1000 0.0500 3.5343 +primID: 3 +startangle_c: 9 +endpose_c: -5 -4 10 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0298 -0.0184 3.5646 +-0.0592 -0.0379 3.5949 +-0.0881 -0.0583 3.6252 +-0.1165 -0.0796 3.6555 +-0.1444 -0.1019 3.6858 +-0.1717 -0.1251 3.7161 +-0.1984 -0.1492 3.7464 +-0.2245 -0.1742 3.7767 +-0.2500 -0.2000 3.8070 +primID: 4 +startangle_c: 9 +endpose_c: -7 -2 8 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0377 -0.0156 3.5343 +-0.0754 -0.0312 3.5343 +-0.1131 -0.0468 3.5343 +-0.1508 -0.0623 3.5152 +-0.1893 -0.0758 3.4405 +-0.2287 -0.0863 3.3658 +-0.2687 -0.0939 3.2910 +-0.3092 -0.0985 3.2163 +-0.3500 -0.1000 3.1416 +primID: 0 +startangle_c: 10 +endpose_c: -1 -1 10 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0056 -0.0056 3.9270 +-0.0111 -0.0111 3.9270 +-0.0167 -0.0167 3.9270 +-0.0222 -0.0222 3.9270 +-0.0278 -0.0278 3.9270 +-0.0333 -0.0333 3.9270 +-0.0389 -0.0389 3.9270 +-0.0444 -0.0444 3.9270 +-0.0500 -0.0500 3.9270 +primID: 1 +startangle_c: 10 +endpose_c: -6 -6 10 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0333 -0.0333 3.9270 +-0.0667 -0.0667 3.9270 +-0.1000 -0.1000 3.9270 +-0.1333 -0.1333 3.9270 +-0.1667 -0.1667 3.9270 +-0.2000 -0.2000 3.9270 +-0.2333 -0.2333 3.9270 +-0.2667 -0.2667 3.9270 +-0.3000 -0.3000 3.9270 +primID: 2 +startangle_c: 10 +endpose_c: 1 1 10 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0056 0.0056 3.9270 +0.0111 0.0111 3.9270 +0.0167 0.0167 3.9270 +0.0222 0.0222 3.9270 +0.0278 0.0278 3.9270 +0.0333 0.0333 3.9270 +0.0389 0.0389 3.9270 +0.0444 0.0444 3.9270 +0.0500 0.0500 3.9270 +primID: 3 +startangle_c: 10 +endpose_c: -5 -7 11 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0341 -0.0341 3.9270 +-0.0678 -0.0684 3.9567 +-0.1000 -0.1043 4.0085 +-0.1302 -0.1418 4.0604 +-0.1584 -0.1809 4.1123 +-0.1846 -0.2213 4.1641 +-0.2086 -0.2631 4.2160 +-0.2304 -0.3060 4.2678 +-0.2500 -0.3500 4.3197 +primID: 4 +startangle_c: 10 +endpose_c: -7 -5 9 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0341 -0.0341 3.9270 +-0.0684 -0.0678 3.8973 +-0.1043 -0.1000 3.8455 +-0.1418 -0.1302 3.7936 +-0.1809 -0.1584 3.7417 +-0.2213 -0.1846 3.6899 +-0.2631 -0.2086 3.6380 +-0.3060 -0.2304 3.5862 +-0.3500 -0.2500 3.5343 +primID: 0 +startangle_c: 11 +endpose_c: -1 -2 11 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0056 -0.0111 4.3197 +-0.0111 -0.0222 4.3197 +-0.0167 -0.0333 4.3197 +-0.0222 -0.0444 4.3197 +-0.0278 -0.0556 4.3197 +-0.0333 -0.0667 4.3197 +-0.0389 -0.0778 4.3197 +-0.0444 -0.0889 4.3197 +-0.0500 -0.1000 4.3197 +primID: 1 +startangle_c: 11 +endpose_c: -3 -6 11 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0167 -0.0333 4.3197 +-0.0333 -0.0667 4.3197 +-0.0500 -0.1000 4.3197 +-0.0667 -0.1333 4.3197 +-0.0833 -0.1667 4.3197 +-0.1000 -0.2000 4.3197 +-0.1167 -0.2333 4.3197 +-0.1333 -0.2667 4.3197 +-0.1500 -0.3000 4.3197 +primID: 2 +startangle_c: 11 +endpose_c: 1 2 11 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0056 0.0111 4.3197 +0.0111 0.0222 4.3197 +0.0167 0.0333 4.3197 +0.0222 0.0444 4.3197 +0.0278 0.0556 4.3197 +0.0333 0.0667 4.3197 +0.0389 0.0778 4.3197 +0.0444 0.0889 4.3197 +0.0500 0.1000 4.3197 +primID: 3 +startangle_c: 11 +endpose_c: -4 -5 10 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0184 -0.0298 4.2894 +-0.0379 -0.0592 4.2591 +-0.0583 -0.0881 4.2288 +-0.0796 -0.1165 4.1985 +-0.1019 -0.1444 4.1682 +-0.1251 -0.1717 4.1379 +-0.1492 -0.1984 4.1076 +-0.1742 -0.2245 4.0773 +-0.2000 -0.2500 4.0470 +primID: 4 +startangle_c: 11 +endpose_c: -2 -7 12 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0156 -0.0377 4.3197 +-0.0312 -0.0754 4.3197 +-0.0468 -0.1131 4.3197 +-0.0623 -0.1508 4.3388 +-0.0758 -0.1893 4.4135 +-0.0863 -0.2287 4.4882 +-0.0939 -0.2687 4.5629 +-0.0985 -0.3092 4.6377 +-0.1000 -0.3500 4.7124 +primID: 0 +startangle_c: 12 +endpose_c: 0 -1 12 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0056 4.7124 +0.0000 -0.0111 4.7124 +0.0000 -0.0167 4.7124 +0.0000 -0.0222 4.7124 +0.0000 -0.0278 4.7124 +0.0000 -0.0333 4.7124 +0.0000 -0.0389 4.7124 +0.0000 -0.0444 4.7124 +0.0000 -0.0500 4.7124 +primID: 1 +startangle_c: 12 +endpose_c: 0 -8 12 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0444 4.7124 +0.0000 -0.0889 4.7124 +0.0000 -0.1333 4.7124 +0.0000 -0.1778 4.7124 +0.0000 -0.2222 4.7124 +0.0000 -0.2667 4.7124 +0.0000 -0.3111 4.7124 +0.0000 -0.3556 4.7124 +0.0000 -0.4000 4.7124 +primID: 2 +startangle_c: 12 +endpose_c: 0 1 12 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0056 4.7124 +0.0000 0.0111 4.7124 +0.0000 0.0167 4.7124 +0.0000 0.0222 4.7124 +0.0000 0.0278 4.7124 +0.0000 0.0333 4.7124 +0.0000 0.0389 4.7124 +0.0000 0.0444 4.7124 +0.0000 0.0500 4.7124 +primID: 3 +startangle_c: 12 +endpose_c: 1 -8 13 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 4.7124 +-0.0000 -0.0452 4.7124 +-0.0000 -0.0904 4.7124 +-0.0000 -0.1355 4.7124 +0.0008 -0.1807 4.7612 +0.0045 -0.2257 4.8300 +0.0114 -0.2703 4.8988 +0.0213 -0.3144 4.9675 +0.0342 -0.3577 5.0363 +0.0500 -0.4000 5.1051 +primID: 4 +startangle_c: 12 +endpose_c: -1 -8 11 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 4.7124 +-0.0000 -0.0452 4.7124 +-0.0000 -0.0904 4.7124 +-0.0000 -0.1355 4.7124 +-0.0008 -0.1807 4.6636 +-0.0045 -0.2257 4.5948 +-0.0114 -0.2703 4.5260 +-0.0213 -0.3144 4.4572 +-0.0342 -0.3577 4.3885 +-0.0500 -0.4000 4.3197 +primID: 0 +startangle_c: 13 +endpose_c: 1 -2 13 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0056 -0.0111 5.1051 +0.0111 -0.0222 5.1051 +0.0167 -0.0333 5.1051 +0.0222 -0.0444 5.1051 +0.0278 -0.0556 5.1051 +0.0333 -0.0667 5.1051 +0.0389 -0.0778 5.1051 +0.0444 -0.0889 5.1051 +0.0500 -0.1000 5.1051 +primID: 1 +startangle_c: 13 +endpose_c: 3 -6 13 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0167 -0.0333 5.1051 +0.0333 -0.0667 5.1051 +0.0500 -0.1000 5.1051 +0.0667 -0.1333 5.1051 +0.0833 -0.1667 5.1051 +0.1000 -0.2000 5.1051 +0.1167 -0.2333 5.1051 +0.1333 -0.2667 5.1051 +0.1500 -0.3000 5.1051 +primID: 2 +startangle_c: 13 +endpose_c: -1 2 13 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 5.1051 +-0.0056 0.0111 5.1051 +-0.0111 0.0222 5.1051 +-0.0167 0.0333 5.1051 +-0.0222 0.0444 5.1051 +-0.0278 0.0556 5.1051 +-0.0333 0.0667 5.1051 +-0.0389 0.0778 5.1051 +-0.0444 0.0889 5.1051 +-0.0500 0.1000 5.1051 +primID: 3 +startangle_c: 13 +endpose_c: 4 -5 14 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0184 -0.0298 5.1354 +0.0379 -0.0592 5.1657 +0.0583 -0.0881 5.1960 +0.0796 -0.1165 5.2263 +0.1019 -0.1444 5.2566 +0.1251 -0.1717 5.2869 +0.1492 -0.1984 5.3172 +0.1742 -0.2245 5.3475 +0.2000 -0.2500 5.3778 +primID: 4 +startangle_c: 13 +endpose_c: 2 -7 12 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0156 -0.0377 5.1051 +0.0312 -0.0754 5.1051 +0.0468 -0.1131 5.1051 +0.0623 -0.1508 5.0860 +0.0758 -0.1893 5.0113 +0.0863 -0.2287 4.9366 +0.0939 -0.2687 4.8618 +0.0985 -0.3092 4.7871 +0.1000 -0.3500 4.7124 +primID: 0 +startangle_c: 14 +endpose_c: 1 -1 14 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0056 -0.0056 5.4978 +0.0111 -0.0111 5.4978 +0.0167 -0.0167 5.4978 +0.0222 -0.0222 5.4978 +0.0278 -0.0278 5.4978 +0.0333 -0.0333 5.4978 +0.0389 -0.0389 5.4978 +0.0444 -0.0444 5.4978 +0.0500 -0.0500 5.4978 +primID: 1 +startangle_c: 14 +endpose_c: 6 -6 14 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0333 -0.0333 5.4978 +0.0667 -0.0667 5.4978 +0.1000 -0.1000 5.4978 +0.1333 -0.1333 5.4978 +0.1667 -0.1667 5.4978 +0.2000 -0.2000 5.4978 +0.2333 -0.2333 5.4978 +0.2667 -0.2667 5.4978 +0.3000 -0.3000 5.4978 +primID: 2 +startangle_c: 14 +endpose_c: -1 1 14 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 5.4978 +-0.0056 0.0056 5.4978 +-0.0111 0.0111 5.4978 +-0.0167 0.0167 5.4978 +-0.0222 0.0222 5.4978 +-0.0278 0.0278 5.4978 +-0.0333 0.0333 5.4978 +-0.0389 0.0389 5.4978 +-0.0444 0.0444 5.4978 +-0.0500 0.0500 5.4978 +primID: 3 +startangle_c: 14 +endpose_c: 7 -5 15 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0341 -0.0341 5.4978 +0.0684 -0.0678 5.5275 +0.1043 -0.1000 5.5793 +0.1418 -0.1302 5.6312 +0.1809 -0.1584 5.6830 +0.2213 -0.1846 5.7349 +0.2631 -0.2086 5.7868 +0.3060 -0.2304 5.8386 +0.3500 -0.2500 5.8905 +primID: 4 +startangle_c: 14 +endpose_c: 5 -7 13 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0341 -0.0341 5.4978 +0.0678 -0.0684 5.4681 +0.1000 -0.1043 5.4162 +0.1302 -0.1418 5.3644 +0.1584 -0.1809 5.3125 +0.1846 -0.2213 5.2607 +0.2086 -0.2631 5.2088 +0.2304 -0.3060 5.1569 +0.2500 -0.3500 5.1051 +primID: 0 +startangle_c: 15 +endpose_c: 2 -1 15 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0111 -0.0056 5.8905 +0.0222 -0.0111 5.8905 +0.0333 -0.0167 5.8905 +0.0444 -0.0222 5.8905 +0.0556 -0.0278 5.8905 +0.0667 -0.0333 5.8905 +0.0778 -0.0389 5.8905 +0.0889 -0.0444 5.8905 +0.1000 -0.0500 5.8905 +primID: 1 +startangle_c: 15 +endpose_c: 6 -3 15 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0333 -0.0167 5.8905 +0.0667 -0.0333 5.8905 +0.1000 -0.0500 5.8905 +0.1333 -0.0667 5.8905 +0.1667 -0.0833 5.8905 +0.2000 -0.1000 5.8905 +0.2333 -0.1167 5.8905 +0.2667 -0.1333 5.8905 +0.3000 -0.1500 5.8905 +primID: 2 +startangle_c: 15 +endpose_c: -2 1 15 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 5.8905 +-0.0111 0.0056 5.8905 +-0.0222 0.0111 5.8905 +-0.0333 0.0167 5.8905 +-0.0444 0.0222 5.8905 +-0.0556 0.0278 5.8905 +-0.0667 0.0333 5.8905 +-0.0778 0.0389 5.8905 +-0.0889 0.0444 5.8905 +-0.1000 0.0500 5.8905 +primID: 3 +startangle_c: 15 +endpose_c: 5 -4 14 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0298 -0.0184 5.8602 +0.0592 -0.0379 5.8299 +0.0881 -0.0583 5.7996 +0.1165 -0.0796 5.7693 +0.1444 -0.1019 5.7390 +0.1717 -0.1251 5.7087 +0.1984 -0.1492 5.6784 +0.2245 -0.1742 5.6481 +0.2500 -0.2000 5.6178 +primID: 4 +startangle_c: 15 +endpose_c: 7 -2 0 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0377 -0.0156 5.8905 +0.0754 -0.0312 5.8905 +0.1131 -0.0468 5.8905 +0.1508 -0.0623 5.9096 +0.1893 -0.0758 5.9843 +0.2287 -0.0863 6.0590 +0.2687 -0.0939 6.1337 +0.3092 -0.0985 6.2085 +0.3500 -0.1000 6.2832 diff --git a/mir_robot/mir_navigation/mprim/unicycle_5cm_expensive_turn_in_place.mprim b/mir_robot/mir_navigation/mprim/unicycle_5cm_expensive_turn_in_place.mprim new file mode 100755 index 0000000..f27907b --- /dev/null +++ b/mir_robot/mir_navigation/mprim/unicycle_5cm_expensive_turn_in_place.mprim @@ -0,0 +1,1683 @@ +resolution_m: 0.050000 +numberofangles: 16 +totalnumberofprimitives: 112 +primID: 0 +startangle_c: 0 +endpose_c: 1 0 0 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0056 0.0000 0.0000 +0.0111 0.0000 0.0000 +0.0167 0.0000 0.0000 +0.0222 0.0000 0.0000 +0.0278 0.0000 0.0000 +0.0333 0.0000 0.0000 +0.0389 0.0000 0.0000 +0.0444 0.0000 0.0000 +0.0500 0.0000 0.0000 +primID: 1 +startangle_c: 0 +endpose_c: 8 0 0 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0444 0.0000 0.0000 +0.0889 0.0000 0.0000 +0.1333 0.0000 0.0000 +0.1778 0.0000 0.0000 +0.2222 0.0000 0.0000 +0.2667 0.0000 0.0000 +0.3111 0.0000 0.0000 +0.3556 0.0000 0.0000 +0.4000 0.0000 0.0000 +primID: 2 +startangle_c: 0 +endpose_c: -1 0 0 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 0.0000 +-0.0056 0.0000 0.0000 +-0.0111 0.0000 0.0000 +-0.0167 0.0000 0.0000 +-0.0222 0.0000 0.0000 +-0.0278 0.0000 0.0000 +-0.0333 0.0000 0.0000 +-0.0389 0.0000 0.0000 +-0.0444 0.0000 0.0000 +-0.0500 0.0000 0.0000 +primID: 3 +startangle_c: 0 +endpose_c: 8 1 1 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0452 -0.0000 0.0000 +0.0904 -0.0000 0.0000 +0.1355 -0.0000 0.0000 +0.1807 0.0008 0.0488 +0.2257 0.0045 0.1176 +0.2703 0.0114 0.1864 +0.3144 0.0213 0.2551 +0.3577 0.0342 0.3239 +0.4000 0.0500 0.3927 +primID: 4 +startangle_c: 0 +endpose_c: 8 -1 -1 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0452 0.0000 0.0000 +0.0904 0.0000 0.0000 +0.1355 0.0000 0.0000 +0.1807 -0.0008 -0.0488 +0.2257 -0.0045 -0.1176 +0.2703 -0.0114 -0.1864 +0.3144 -0.0213 -0.2551 +0.3577 -0.0342 -0.3239 +0.4000 -0.0500 -0.3927 +primID: 5 +startangle_c: 0 +endpose_c: 0 0 1 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0000 0.0000 0.0436 +0.0000 0.0000 0.0873 +0.0000 0.0000 0.1309 +0.0000 0.0000 0.1745 +0.0000 0.0000 0.2182 +0.0000 0.0000 0.2618 +0.0000 0.0000 0.3054 +0.0000 0.0000 0.3491 +0.0000 0.0000 0.3927 +primID: 6 +startangle_c: 0 +endpose_c: 0 0 -1 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0000 0.0000 -0.0436 +0.0000 0.0000 -0.0873 +0.0000 0.0000 -0.1309 +0.0000 0.0000 -0.1745 +0.0000 0.0000 -0.2182 +0.0000 0.0000 -0.2618 +0.0000 0.0000 -0.3054 +0.0000 0.0000 -0.3491 +0.0000 0.0000 -0.3927 +primID: 0 +startangle_c: 1 +endpose_c: 2 1 1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0111 0.0056 0.3927 +0.0222 0.0111 0.3927 +0.0333 0.0167 0.3927 +0.0444 0.0222 0.3927 +0.0556 0.0278 0.3927 +0.0667 0.0333 0.3927 +0.0778 0.0389 0.3927 +0.0889 0.0444 0.3927 +0.1000 0.0500 0.3927 +primID: 1 +startangle_c: 1 +endpose_c: 6 3 1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0333 0.0167 0.3927 +0.0667 0.0333 0.3927 +0.1000 0.0500 0.3927 +0.1333 0.0667 0.3927 +0.1667 0.0833 0.3927 +0.2000 0.1000 0.3927 +0.2333 0.1167 0.3927 +0.2667 0.1333 0.3927 +0.3000 0.1500 0.3927 +primID: 2 +startangle_c: 1 +endpose_c: -2 -1 1 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 0.3927 +-0.0111 -0.0056 0.3927 +-0.0222 -0.0111 0.3927 +-0.0333 -0.0167 0.3927 +-0.0444 -0.0222 0.3927 +-0.0556 -0.0278 0.3927 +-0.0667 -0.0333 0.3927 +-0.0778 -0.0389 0.3927 +-0.0889 -0.0444 0.3927 +-0.1000 -0.0500 0.3927 +primID: 3 +startangle_c: 1 +endpose_c: 5 4 2 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0298 0.0184 0.4230 +0.0592 0.0379 0.4533 +0.0881 0.0583 0.4836 +0.1165 0.0796 0.5139 +0.1444 0.1019 0.5442 +0.1717 0.1251 0.5745 +0.1984 0.1492 0.6048 +0.2245 0.1742 0.6351 +0.2500 0.2000 0.6654 +primID: 4 +startangle_c: 1 +endpose_c: 7 2 0 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0377 0.0156 0.3927 +0.0754 0.0312 0.3927 +0.1131 0.0468 0.3927 +0.1508 0.0623 0.3736 +0.1893 0.0758 0.2989 +0.2287 0.0863 0.2242 +0.2687 0.0939 0.1494 +0.3092 0.0985 0.0747 +0.3500 0.1000 -0.0000 +primID: 5 +startangle_c: 1 +endpose_c: 0 0 2 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0000 0.0000 0.4363 +0.0000 0.0000 0.4800 +0.0000 0.0000 0.5236 +0.0000 0.0000 0.5672 +0.0000 0.0000 0.6109 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.6981 +0.0000 0.0000 0.7418 +0.0000 0.0000 0.7854 +primID: 6 +startangle_c: 1 +endpose_c: 0 0 0 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0000 0.0000 0.3491 +0.0000 0.0000 0.3054 +0.0000 0.0000 0.2618 +0.0000 0.0000 0.2182 +0.0000 0.0000 0.1745 +0.0000 0.0000 0.1309 +0.0000 0.0000 0.0873 +0.0000 0.0000 0.0436 +0.0000 0.0000 0.0000 +primID: 0 +startangle_c: 2 +endpose_c: 1 1 2 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0056 0.0056 0.7854 +0.0111 0.0111 0.7854 +0.0167 0.0167 0.7854 +0.0222 0.0222 0.7854 +0.0278 0.0278 0.7854 +0.0333 0.0333 0.7854 +0.0389 0.0389 0.7854 +0.0444 0.0444 0.7854 +0.0500 0.0500 0.7854 +primID: 1 +startangle_c: 2 +endpose_c: 6 6 2 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0333 0.0333 0.7854 +0.0667 0.0667 0.7854 +0.1000 0.1000 0.7854 +0.1333 0.1333 0.7854 +0.1667 0.1667 0.7854 +0.2000 0.2000 0.7854 +0.2333 0.2333 0.7854 +0.2667 0.2667 0.7854 +0.3000 0.3000 0.7854 +primID: 2 +startangle_c: 2 +endpose_c: -1 -1 2 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 0.7854 +-0.0056 -0.0056 0.7854 +-0.0111 -0.0111 0.7854 +-0.0167 -0.0167 0.7854 +-0.0222 -0.0222 0.7854 +-0.0278 -0.0278 0.7854 +-0.0333 -0.0333 0.7854 +-0.0389 -0.0389 0.7854 +-0.0444 -0.0444 0.7854 +-0.0500 -0.0500 0.7854 +primID: 3 +startangle_c: 2 +endpose_c: 5 7 3 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0341 0.0341 0.7854 +0.0678 0.0684 0.8151 +0.1000 0.1043 0.8669 +0.1302 0.1418 0.9188 +0.1584 0.1809 0.9707 +0.1846 0.2213 1.0225 +0.2086 0.2631 1.0744 +0.2304 0.3060 1.1262 +0.2500 0.3500 1.1781 +primID: 4 +startangle_c: 2 +endpose_c: 7 5 1 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0341 0.0341 0.7854 +0.0684 0.0678 0.7557 +0.1043 0.1000 0.7039 +0.1418 0.1302 0.6520 +0.1809 0.1584 0.6001 +0.2213 0.1846 0.5483 +0.2631 0.2086 0.4964 +0.3060 0.2304 0.4446 +0.3500 0.2500 0.3927 +primID: 5 +startangle_c: 2 +endpose_c: 0 0 3 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0000 0.0000 0.8290 +0.0000 0.0000 0.8727 +0.0000 0.0000 0.9163 +0.0000 0.0000 0.9599 +0.0000 0.0000 1.0036 +0.0000 0.0000 1.0472 +0.0000 0.0000 1.0908 +0.0000 0.0000 1.1345 +0.0000 0.0000 1.1781 +primID: 6 +startangle_c: 2 +endpose_c: 0 0 1 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0000 0.0000 0.7418 +0.0000 0.0000 0.6981 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.6109 +0.0000 0.0000 0.5672 +0.0000 0.0000 0.5236 +0.0000 0.0000 0.4800 +0.0000 0.0000 0.4363 +0.0000 0.0000 0.3927 +primID: 0 +startangle_c: 3 +endpose_c: 1 2 3 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0056 0.0111 1.1781 +0.0111 0.0222 1.1781 +0.0167 0.0333 1.1781 +0.0222 0.0444 1.1781 +0.0278 0.0556 1.1781 +0.0333 0.0667 1.1781 +0.0389 0.0778 1.1781 +0.0444 0.0889 1.1781 +0.0500 0.1000 1.1781 +primID: 1 +startangle_c: 3 +endpose_c: 3 6 3 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0167 0.0333 1.1781 +0.0333 0.0667 1.1781 +0.0500 0.1000 1.1781 +0.0667 0.1333 1.1781 +0.0833 0.1667 1.1781 +0.1000 0.2000 1.1781 +0.1167 0.2333 1.1781 +0.1333 0.2667 1.1781 +0.1500 0.3000 1.1781 +primID: 2 +startangle_c: 3 +endpose_c: -1 -2 3 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 1.1781 +-0.0056 -0.0111 1.1781 +-0.0111 -0.0222 1.1781 +-0.0167 -0.0333 1.1781 +-0.0222 -0.0444 1.1781 +-0.0278 -0.0556 1.1781 +-0.0333 -0.0667 1.1781 +-0.0389 -0.0778 1.1781 +-0.0444 -0.0889 1.1781 +-0.0500 -0.1000 1.1781 +primID: 3 +startangle_c: 3 +endpose_c: 4 5 2 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0184 0.0298 1.1478 +0.0379 0.0592 1.1175 +0.0583 0.0881 1.0872 +0.0796 0.1165 1.0569 +0.1019 0.1444 1.0266 +0.1251 0.1717 0.9963 +0.1492 0.1984 0.9660 +0.1742 0.2245 0.9357 +0.2000 0.2500 0.9054 +primID: 4 +startangle_c: 3 +endpose_c: 2 7 4 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0156 0.0377 1.1781 +0.0312 0.0754 1.1781 +0.0468 0.1131 1.1781 +0.0623 0.1508 1.1972 +0.0758 0.1893 1.2719 +0.0863 0.2287 1.3466 +0.0939 0.2687 1.4214 +0.0985 0.3092 1.4961 +0.1000 0.3500 1.5708 +primID: 5 +startangle_c: 3 +endpose_c: 0 0 2 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0000 0.0000 1.1345 +0.0000 0.0000 1.0908 +0.0000 0.0000 1.0472 +0.0000 0.0000 1.0036 +0.0000 0.0000 0.9599 +0.0000 0.0000 0.9163 +0.0000 0.0000 0.8727 +0.0000 0.0000 0.8290 +0.0000 0.0000 0.7854 +primID: 6 +startangle_c: 3 +endpose_c: 0 0 4 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0000 0.0000 1.2217 +0.0000 0.0000 1.2654 +0.0000 0.0000 1.3090 +0.0000 0.0000 1.3526 +0.0000 0.0000 1.3963 +0.0000 0.0000 1.4399 +0.0000 0.0000 1.4835 +0.0000 0.0000 1.5272 +0.0000 0.0000 1.5708 +primID: 0 +startangle_c: 4 +endpose_c: 0 1 4 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0056 1.5708 +0.0000 0.0111 1.5708 +0.0000 0.0167 1.5708 +0.0000 0.0222 1.5708 +0.0000 0.0278 1.5708 +0.0000 0.0333 1.5708 +0.0000 0.0389 1.5708 +0.0000 0.0444 1.5708 +0.0000 0.0500 1.5708 +primID: 1 +startangle_c: 4 +endpose_c: 0 8 4 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0444 1.5708 +0.0000 0.0889 1.5708 +0.0000 0.1333 1.5708 +0.0000 0.1778 1.5708 +0.0000 0.2222 1.5708 +0.0000 0.2667 1.5708 +0.0000 0.3111 1.5708 +0.0000 0.3556 1.5708 +0.0000 0.4000 1.5708 +primID: 2 +startangle_c: 4 +endpose_c: 0 -1 4 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 -0.0056 1.5708 +0.0000 -0.0111 1.5708 +0.0000 -0.0167 1.5708 +0.0000 -0.0222 1.5708 +0.0000 -0.0278 1.5708 +0.0000 -0.0333 1.5708 +0.0000 -0.0389 1.5708 +0.0000 -0.0444 1.5708 +0.0000 -0.0500 1.5708 +primID: 3 +startangle_c: 4 +endpose_c: -1 8 5 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0452 1.5708 +0.0000 0.0904 1.5708 +0.0000 0.1355 1.5708 +-0.0008 0.1807 1.6196 +-0.0045 0.2257 1.6884 +-0.0114 0.2703 1.7572 +-0.0213 0.3144 1.8259 +-0.0342 0.3577 1.8947 +-0.0500 0.4000 1.9635 +primID: 4 +startangle_c: 4 +endpose_c: 1 8 3 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0452 1.5708 +0.0000 0.0904 1.5708 +0.0000 0.1355 1.5708 +0.0008 0.1807 1.5220 +0.0045 0.2257 1.4532 +0.0114 0.2703 1.3844 +0.0213 0.3144 1.3156 +0.0342 0.3577 1.2469 +0.0500 0.4000 1.1781 +primID: 5 +startangle_c: 4 +endpose_c: 0 0 5 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0000 1.6144 +0.0000 0.0000 1.6581 +0.0000 0.0000 1.7017 +0.0000 0.0000 1.7453 +0.0000 0.0000 1.7890 +0.0000 0.0000 1.8326 +0.0000 0.0000 1.8762 +0.0000 0.0000 1.9199 +0.0000 0.0000 1.9635 +primID: 6 +startangle_c: 4 +endpose_c: 0 0 3 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0000 1.5272 +0.0000 0.0000 1.4835 +0.0000 0.0000 1.4399 +0.0000 0.0000 1.3963 +0.0000 0.0000 1.3526 +0.0000 0.0000 1.3090 +0.0000 0.0000 1.2654 +0.0000 0.0000 1.2217 +0.0000 0.0000 1.1781 +primID: 0 +startangle_c: 5 +endpose_c: -1 2 5 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0056 0.0111 1.9635 +-0.0111 0.0222 1.9635 +-0.0167 0.0333 1.9635 +-0.0222 0.0444 1.9635 +-0.0278 0.0556 1.9635 +-0.0333 0.0667 1.9635 +-0.0389 0.0778 1.9635 +-0.0444 0.0889 1.9635 +-0.0500 0.1000 1.9635 +primID: 1 +startangle_c: 5 +endpose_c: -3 6 5 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0167 0.0333 1.9635 +-0.0333 0.0667 1.9635 +-0.0500 0.1000 1.9635 +-0.0667 0.1333 1.9635 +-0.0833 0.1667 1.9635 +-0.1000 0.2000 1.9635 +-0.1167 0.2333 1.9635 +-0.1333 0.2667 1.9635 +-0.1500 0.3000 1.9635 +primID: 2 +startangle_c: 5 +endpose_c: 1 -2 5 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0056 -0.0111 1.9635 +0.0111 -0.0222 1.9635 +0.0167 -0.0333 1.9635 +0.0222 -0.0444 1.9635 +0.0278 -0.0556 1.9635 +0.0333 -0.0667 1.9635 +0.0389 -0.0778 1.9635 +0.0444 -0.0889 1.9635 +0.0500 -0.1000 1.9635 +primID: 3 +startangle_c: 5 +endpose_c: -4 5 6 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0184 0.0298 1.9938 +-0.0379 0.0592 2.0241 +-0.0583 0.0881 2.0544 +-0.0796 0.1165 2.0847 +-0.1019 0.1444 2.1150 +-0.1251 0.1717 2.1453 +-0.1492 0.1984 2.1756 +-0.1742 0.2245 2.2059 +-0.2000 0.2500 2.2362 +primID: 4 +startangle_c: 5 +endpose_c: -2 7 4 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0156 0.0377 1.9635 +-0.0312 0.0754 1.9635 +-0.0468 0.1131 1.9635 +-0.0623 0.1508 1.9444 +-0.0758 0.1893 1.8697 +-0.0863 0.2287 1.7950 +-0.0939 0.2687 1.7202 +-0.0985 0.3092 1.6455 +-0.1000 0.3500 1.5708 +primID: 5 +startangle_c: 5 +endpose_c: 0 0 6 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0000 0.0000 2.0071 +0.0000 0.0000 2.0508 +0.0000 0.0000 2.0944 +0.0000 0.0000 2.1380 +0.0000 0.0000 2.1817 +0.0000 0.0000 2.2253 +0.0000 0.0000 2.2689 +0.0000 0.0000 2.3126 +0.0000 0.0000 2.3562 +primID: 6 +startangle_c: 5 +endpose_c: 0 0 4 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0000 0.0000 1.9199 +0.0000 0.0000 1.8762 +0.0000 0.0000 1.8326 +0.0000 0.0000 1.7890 +0.0000 0.0000 1.7453 +0.0000 0.0000 1.7017 +0.0000 0.0000 1.6581 +0.0000 0.0000 1.6144 +0.0000 0.0000 1.5708 +primID: 0 +startangle_c: 6 +endpose_c: -1 1 6 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0056 0.0056 2.3562 +-0.0111 0.0111 2.3562 +-0.0167 0.0167 2.3562 +-0.0222 0.0222 2.3562 +-0.0278 0.0278 2.3562 +-0.0333 0.0333 2.3562 +-0.0389 0.0389 2.3562 +-0.0444 0.0444 2.3562 +-0.0500 0.0500 2.3562 +primID: 1 +startangle_c: 6 +endpose_c: -6 6 6 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0333 0.0333 2.3562 +-0.0667 0.0667 2.3562 +-0.1000 0.1000 2.3562 +-0.1333 0.1333 2.3562 +-0.1667 0.1667 2.3562 +-0.2000 0.2000 2.3562 +-0.2333 0.2333 2.3562 +-0.2667 0.2667 2.3562 +-0.3000 0.3000 2.3562 +primID: 2 +startangle_c: 6 +endpose_c: 1 -1 6 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0056 -0.0056 2.3562 +0.0111 -0.0111 2.3562 +0.0167 -0.0167 2.3562 +0.0222 -0.0222 2.3562 +0.0278 -0.0278 2.3562 +0.0333 -0.0333 2.3562 +0.0389 -0.0389 2.3562 +0.0444 -0.0444 2.3562 +0.0500 -0.0500 2.3562 +primID: 3 +startangle_c: 6 +endpose_c: -7 5 7 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0341 0.0341 2.3562 +-0.0684 0.0678 2.3859 +-0.1043 0.1000 2.4377 +-0.1418 0.1302 2.4896 +-0.1809 0.1584 2.5415 +-0.2213 0.1846 2.5933 +-0.2631 0.2086 2.6452 +-0.3060 0.2304 2.6970 +-0.3500 0.2500 2.7489 +primID: 4 +startangle_c: 6 +endpose_c: -5 7 5 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0341 0.0341 2.3562 +-0.0678 0.0684 2.3265 +-0.1000 0.1043 2.2747 +-0.1302 0.1418 2.2228 +-0.1584 0.1809 2.1709 +-0.1846 0.2213 2.1191 +-0.2086 0.2631 2.0672 +-0.2304 0.3060 2.0154 +-0.2500 0.3500 1.9635 +primID: 5 +startangle_c: 6 +endpose_c: 0 0 7 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0000 0.0000 2.3998 +0.0000 0.0000 2.4435 +0.0000 0.0000 2.4871 +0.0000 0.0000 2.5307 +0.0000 0.0000 2.5744 +0.0000 0.0000 2.6180 +0.0000 0.0000 2.6616 +0.0000 0.0000 2.7053 +0.0000 0.0000 2.7489 +primID: 6 +startangle_c: 6 +endpose_c: 0 0 5 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0000 0.0000 2.3126 +0.0000 0.0000 2.2689 +0.0000 0.0000 2.2253 +0.0000 0.0000 2.1817 +0.0000 0.0000 2.1380 +0.0000 0.0000 2.0944 +0.0000 0.0000 2.0508 +0.0000 0.0000 2.0071 +0.0000 0.0000 1.9635 +primID: 0 +startangle_c: 7 +endpose_c: -2 1 7 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0111 0.0056 2.7489 +-0.0222 0.0111 2.7489 +-0.0333 0.0167 2.7489 +-0.0444 0.0222 2.7489 +-0.0556 0.0278 2.7489 +-0.0667 0.0333 2.7489 +-0.0778 0.0389 2.7489 +-0.0889 0.0444 2.7489 +-0.1000 0.0500 2.7489 +primID: 1 +startangle_c: 7 +endpose_c: -6 3 7 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0333 0.0167 2.7489 +-0.0667 0.0333 2.7489 +-0.1000 0.0500 2.7489 +-0.1333 0.0667 2.7489 +-0.1667 0.0833 2.7489 +-0.2000 0.1000 2.7489 +-0.2333 0.1167 2.7489 +-0.2667 0.1333 2.7489 +-0.3000 0.1500 2.7489 +primID: 2 +startangle_c: 7 +endpose_c: 2 -1 7 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0111 -0.0056 2.7489 +0.0222 -0.0111 2.7489 +0.0333 -0.0167 2.7489 +0.0444 -0.0222 2.7489 +0.0556 -0.0278 2.7489 +0.0667 -0.0333 2.7489 +0.0778 -0.0389 2.7489 +0.0889 -0.0444 2.7489 +0.1000 -0.0500 2.7489 +primID: 3 +startangle_c: 7 +endpose_c: -5 4 6 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0298 0.0184 2.7186 +-0.0592 0.0379 2.6883 +-0.0881 0.0583 2.6580 +-0.1165 0.0796 2.6277 +-0.1444 0.1019 2.5974 +-0.1717 0.1251 2.5671 +-0.1984 0.1492 2.5368 +-0.2245 0.1742 2.5065 +-0.2500 0.2000 2.4762 +primID: 4 +startangle_c: 7 +endpose_c: -7 2 8 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0377 0.0156 2.7489 +-0.0754 0.0312 2.7489 +-0.1131 0.0468 2.7489 +-0.1508 0.0623 2.7680 +-0.1893 0.0758 2.8427 +-0.2287 0.0863 2.9174 +-0.2687 0.0939 2.9921 +-0.3092 0.0985 3.0669 +-0.3500 0.1000 3.1416 +primID: 5 +startangle_c: 7 +endpose_c: 0 0 6 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0000 0.0000 2.7053 +0.0000 0.0000 2.6616 +0.0000 0.0000 2.6180 +0.0000 0.0000 2.5744 +0.0000 0.0000 2.5307 +0.0000 0.0000 2.4871 +0.0000 0.0000 2.4435 +0.0000 0.0000 2.3998 +0.0000 0.0000 2.3562 +primID: 6 +startangle_c: 7 +endpose_c: 0 0 8 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0000 0.0000 2.7925 +0.0000 0.0000 2.8362 +0.0000 0.0000 2.8798 +0.0000 0.0000 2.9234 +0.0000 0.0000 2.9671 +0.0000 0.0000 3.0107 +0.0000 0.0000 3.0543 +0.0000 0.0000 3.0980 +0.0000 0.0000 3.1416 +primID: 0 +startangle_c: 8 +endpose_c: -1 0 8 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0056 0.0000 3.1416 +-0.0111 0.0000 3.1416 +-0.0167 0.0000 3.1416 +-0.0222 0.0000 3.1416 +-0.0278 0.0000 3.1416 +-0.0333 0.0000 3.1416 +-0.0389 0.0000 3.1416 +-0.0444 0.0000 3.1416 +-0.0500 0.0000 3.1416 +primID: 1 +startangle_c: 8 +endpose_c: -8 0 8 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0444 0.0000 3.1416 +-0.0889 0.0000 3.1416 +-0.1333 0.0000 3.1416 +-0.1778 0.0000 3.1416 +-0.2222 0.0000 3.1416 +-0.2667 0.0000 3.1416 +-0.3111 0.0000 3.1416 +-0.3556 0.0000 3.1416 +-0.4000 0.0000 3.1416 +primID: 2 +startangle_c: 8 +endpose_c: 1 0 8 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0056 0.0000 3.1416 +0.0111 0.0000 3.1416 +0.0167 0.0000 3.1416 +0.0222 0.0000 3.1416 +0.0278 0.0000 3.1416 +0.0333 0.0000 3.1416 +0.0389 0.0000 3.1416 +0.0444 0.0000 3.1416 +0.0500 0.0000 3.1416 +primID: 3 +startangle_c: 8 +endpose_c: -8 -1 9 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0452 0.0000 3.1416 +-0.0904 0.0000 3.1416 +-0.1355 0.0000 3.1416 +-0.1807 -0.0008 3.1904 +-0.2257 -0.0045 3.2592 +-0.2703 -0.0114 3.3280 +-0.3144 -0.0213 3.3967 +-0.3577 -0.0342 3.4655 +-0.4000 -0.0500 3.5343 +primID: 4 +startangle_c: 8 +endpose_c: -8 1 7 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0452 0.0000 3.1416 +-0.0904 0.0000 3.1416 +-0.1355 0.0000 3.1416 +-0.1807 0.0008 3.0928 +-0.2257 0.0045 3.0240 +-0.2703 0.0114 2.9552 +-0.3144 0.0213 2.8864 +-0.3577 0.0342 2.8177 +-0.4000 0.0500 2.7489 +primID: 5 +startangle_c: 8 +endpose_c: 0 0 9 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0000 0.0000 3.1852 +0.0000 0.0000 3.2289 +0.0000 0.0000 3.2725 +0.0000 0.0000 3.3161 +0.0000 0.0000 3.3598 +0.0000 0.0000 3.4034 +0.0000 0.0000 3.4470 +0.0000 0.0000 3.4907 +0.0000 0.0000 3.5343 +primID: 6 +startangle_c: 8 +endpose_c: 0 0 7 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0000 0.0000 3.0980 +0.0000 0.0000 3.0543 +0.0000 0.0000 3.0107 +0.0000 0.0000 2.9671 +0.0000 0.0000 2.9234 +0.0000 0.0000 2.8798 +0.0000 0.0000 2.8362 +0.0000 0.0000 2.7925 +0.0000 0.0000 2.7489 +primID: 0 +startangle_c: 9 +endpose_c: -2 -1 9 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0111 -0.0056 3.5343 +-0.0222 -0.0111 3.5343 +-0.0333 -0.0167 3.5343 +-0.0444 -0.0222 3.5343 +-0.0556 -0.0278 3.5343 +-0.0667 -0.0333 3.5343 +-0.0778 -0.0389 3.5343 +-0.0889 -0.0444 3.5343 +-0.1000 -0.0500 3.5343 +primID: 1 +startangle_c: 9 +endpose_c: -6 -3 9 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0333 -0.0167 3.5343 +-0.0667 -0.0333 3.5343 +-0.1000 -0.0500 3.5343 +-0.1333 -0.0667 3.5343 +-0.1667 -0.0833 3.5343 +-0.2000 -0.1000 3.5343 +-0.2333 -0.1167 3.5343 +-0.2667 -0.1333 3.5343 +-0.3000 -0.1500 3.5343 +primID: 2 +startangle_c: 9 +endpose_c: 2 1 9 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0111 0.0056 3.5343 +0.0222 0.0111 3.5343 +0.0333 0.0167 3.5343 +0.0444 0.0222 3.5343 +0.0556 0.0278 3.5343 +0.0667 0.0333 3.5343 +0.0778 0.0389 3.5343 +0.0889 0.0444 3.5343 +0.1000 0.0500 3.5343 +primID: 3 +startangle_c: 9 +endpose_c: -5 -4 10 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0298 -0.0184 3.5646 +-0.0592 -0.0379 3.5949 +-0.0881 -0.0583 3.6252 +-0.1165 -0.0796 3.6555 +-0.1444 -0.1019 3.6858 +-0.1717 -0.1251 3.7161 +-0.1984 -0.1492 3.7464 +-0.2245 -0.1742 3.7767 +-0.2500 -0.2000 3.8070 +primID: 4 +startangle_c: 9 +endpose_c: -7 -2 8 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0377 -0.0156 3.5343 +-0.0754 -0.0312 3.5343 +-0.1131 -0.0468 3.5343 +-0.1508 -0.0623 3.5152 +-0.1893 -0.0758 3.4405 +-0.2287 -0.0863 3.3658 +-0.2687 -0.0939 3.2910 +-0.3092 -0.0985 3.2163 +-0.3500 -0.1000 3.1416 +primID: 5 +startangle_c: 9 +endpose_c: 0 0 10 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0000 0.0000 3.5779 +0.0000 0.0000 3.6216 +0.0000 0.0000 3.6652 +0.0000 0.0000 3.7088 +0.0000 0.0000 3.7525 +0.0000 0.0000 3.7961 +0.0000 0.0000 3.8397 +0.0000 0.0000 3.8834 +0.0000 0.0000 3.9270 +primID: 6 +startangle_c: 9 +endpose_c: 0 0 8 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0000 0.0000 3.4907 +0.0000 0.0000 3.4470 +0.0000 0.0000 3.4034 +0.0000 0.0000 3.3598 +0.0000 0.0000 3.3161 +0.0000 0.0000 3.2725 +0.0000 0.0000 3.2289 +0.0000 0.0000 3.1852 +0.0000 0.0000 3.1416 +primID: 0 +startangle_c: 10 +endpose_c: -1 -1 10 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0056 -0.0056 3.9270 +-0.0111 -0.0111 3.9270 +-0.0167 -0.0167 3.9270 +-0.0222 -0.0222 3.9270 +-0.0278 -0.0278 3.9270 +-0.0333 -0.0333 3.9270 +-0.0389 -0.0389 3.9270 +-0.0444 -0.0444 3.9270 +-0.0500 -0.0500 3.9270 +primID: 1 +startangle_c: 10 +endpose_c: -6 -6 10 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0333 -0.0333 3.9270 +-0.0667 -0.0667 3.9270 +-0.1000 -0.1000 3.9270 +-0.1333 -0.1333 3.9270 +-0.1667 -0.1667 3.9270 +-0.2000 -0.2000 3.9270 +-0.2333 -0.2333 3.9270 +-0.2667 -0.2667 3.9270 +-0.3000 -0.3000 3.9270 +primID: 2 +startangle_c: 10 +endpose_c: 1 1 10 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0056 0.0056 3.9270 +0.0111 0.0111 3.9270 +0.0167 0.0167 3.9270 +0.0222 0.0222 3.9270 +0.0278 0.0278 3.9270 +0.0333 0.0333 3.9270 +0.0389 0.0389 3.9270 +0.0444 0.0444 3.9270 +0.0500 0.0500 3.9270 +primID: 3 +startangle_c: 10 +endpose_c: -5 -7 11 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0341 -0.0341 3.9270 +-0.0678 -0.0684 3.9567 +-0.1000 -0.1043 4.0085 +-0.1302 -0.1418 4.0604 +-0.1584 -0.1809 4.1123 +-0.1846 -0.2213 4.1641 +-0.2086 -0.2631 4.2160 +-0.2304 -0.3060 4.2678 +-0.2500 -0.3500 4.3197 +primID: 4 +startangle_c: 10 +endpose_c: -7 -5 9 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0341 -0.0341 3.9270 +-0.0684 -0.0678 3.8973 +-0.1043 -0.1000 3.8455 +-0.1418 -0.1302 3.7936 +-0.1809 -0.1584 3.7417 +-0.2213 -0.1846 3.6899 +-0.2631 -0.2086 3.6380 +-0.3060 -0.2304 3.5862 +-0.3500 -0.2500 3.5343 +primID: 5 +startangle_c: 10 +endpose_c: 0 0 11 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.9706 +0.0000 0.0000 4.0143 +0.0000 0.0000 4.0579 +0.0000 0.0000 4.1015 +0.0000 0.0000 4.1452 +0.0000 0.0000 4.1888 +0.0000 0.0000 4.2324 +0.0000 0.0000 4.2761 +0.0000 0.0000 4.3197 +primID: 6 +startangle_c: 10 +endpose_c: 0 0 9 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.8834 +0.0000 0.0000 3.8397 +0.0000 0.0000 3.7961 +0.0000 0.0000 3.7525 +0.0000 0.0000 3.7088 +0.0000 0.0000 3.6652 +0.0000 0.0000 3.6216 +0.0000 0.0000 3.5779 +0.0000 0.0000 3.5343 +primID: 0 +startangle_c: 11 +endpose_c: -1 -2 11 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0056 -0.0111 4.3197 +-0.0111 -0.0222 4.3197 +-0.0167 -0.0333 4.3197 +-0.0222 -0.0444 4.3197 +-0.0278 -0.0556 4.3197 +-0.0333 -0.0667 4.3197 +-0.0389 -0.0778 4.3197 +-0.0444 -0.0889 4.3197 +-0.0500 -0.1000 4.3197 +primID: 1 +startangle_c: 11 +endpose_c: -3 -6 11 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0167 -0.0333 4.3197 +-0.0333 -0.0667 4.3197 +-0.0500 -0.1000 4.3197 +-0.0667 -0.1333 4.3197 +-0.0833 -0.1667 4.3197 +-0.1000 -0.2000 4.3197 +-0.1167 -0.2333 4.3197 +-0.1333 -0.2667 4.3197 +-0.1500 -0.3000 4.3197 +primID: 2 +startangle_c: 11 +endpose_c: 1 2 11 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0056 0.0111 4.3197 +0.0111 0.0222 4.3197 +0.0167 0.0333 4.3197 +0.0222 0.0444 4.3197 +0.0278 0.0556 4.3197 +0.0333 0.0667 4.3197 +0.0389 0.0778 4.3197 +0.0444 0.0889 4.3197 +0.0500 0.1000 4.3197 +primID: 3 +startangle_c: 11 +endpose_c: -4 -5 10 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0184 -0.0298 4.2894 +-0.0379 -0.0592 4.2591 +-0.0583 -0.0881 4.2288 +-0.0796 -0.1165 4.1985 +-0.1019 -0.1444 4.1682 +-0.1251 -0.1717 4.1379 +-0.1492 -0.1984 4.1076 +-0.1742 -0.2245 4.0773 +-0.2000 -0.2500 4.0470 +primID: 4 +startangle_c: 11 +endpose_c: -2 -7 12 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0156 -0.0377 4.3197 +-0.0312 -0.0754 4.3197 +-0.0468 -0.1131 4.3197 +-0.0623 -0.1508 4.3388 +-0.0758 -0.1893 4.4135 +-0.0863 -0.2287 4.4882 +-0.0939 -0.2687 4.5629 +-0.0985 -0.3092 4.6377 +-0.1000 -0.3500 4.7124 +primID: 5 +startangle_c: 11 +endpose_c: 0 0 10 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0000 0.0000 4.2761 +0.0000 0.0000 4.2324 +0.0000 0.0000 4.1888 +0.0000 0.0000 4.1452 +0.0000 0.0000 4.1015 +0.0000 0.0000 4.0579 +0.0000 0.0000 4.0143 +0.0000 0.0000 3.9706 +0.0000 0.0000 3.9270 +primID: 6 +startangle_c: 11 +endpose_c: 0 0 12 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0000 0.0000 4.3633 +0.0000 0.0000 4.4070 +0.0000 0.0000 4.4506 +0.0000 0.0000 4.4942 +0.0000 0.0000 4.5379 +0.0000 0.0000 4.5815 +0.0000 0.0000 4.6251 +0.0000 0.0000 4.6688 +0.0000 0.0000 4.7124 +primID: 0 +startangle_c: 12 +endpose_c: 0 -1 12 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0056 4.7124 +0.0000 -0.0111 4.7124 +0.0000 -0.0167 4.7124 +0.0000 -0.0222 4.7124 +0.0000 -0.0278 4.7124 +0.0000 -0.0333 4.7124 +0.0000 -0.0389 4.7124 +0.0000 -0.0444 4.7124 +0.0000 -0.0500 4.7124 +primID: 1 +startangle_c: 12 +endpose_c: 0 -8 12 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0444 4.7124 +0.0000 -0.0889 4.7124 +0.0000 -0.1333 4.7124 +0.0000 -0.1778 4.7124 +0.0000 -0.2222 4.7124 +0.0000 -0.2667 4.7124 +0.0000 -0.3111 4.7124 +0.0000 -0.3556 4.7124 +0.0000 -0.4000 4.7124 +primID: 2 +startangle_c: 12 +endpose_c: 0 1 12 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0056 4.7124 +0.0000 0.0111 4.7124 +0.0000 0.0167 4.7124 +0.0000 0.0222 4.7124 +0.0000 0.0278 4.7124 +0.0000 0.0333 4.7124 +0.0000 0.0389 4.7124 +0.0000 0.0444 4.7124 +0.0000 0.0500 4.7124 +primID: 3 +startangle_c: 12 +endpose_c: 1 -8 13 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0452 4.7124 +0.0000 -0.0904 4.7124 +0.0000 -0.1355 4.7124 +0.0008 -0.1807 4.7612 +0.0045 -0.2257 4.8300 +0.0114 -0.2703 4.8988 +0.0213 -0.3144 4.9675 +0.0342 -0.3577 5.0363 +0.0500 -0.4000 5.1051 +primID: 4 +startangle_c: 12 +endpose_c: -1 -8 11 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 4.7124 +-0.0000 -0.0452 4.7124 +-0.0000 -0.0904 4.7124 +-0.0000 -0.1355 4.7124 +-0.0008 -0.1807 4.6636 +-0.0045 -0.2257 4.5948 +-0.0114 -0.2703 4.5260 +-0.0213 -0.3144 4.4572 +-0.0342 -0.3577 4.3885 +-0.0500 -0.4000 4.3197 +primID: 5 +startangle_c: 12 +endpose_c: 0 0 13 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0000 4.7560 +0.0000 0.0000 4.7997 +0.0000 0.0000 4.8433 +0.0000 0.0000 4.8869 +0.0000 0.0000 4.9306 +0.0000 0.0000 4.9742 +0.0000 0.0000 5.0178 +0.0000 0.0000 5.0615 +0.0000 0.0000 5.1051 +primID: 6 +startangle_c: 12 +endpose_c: 0 0 11 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0000 4.6688 +0.0000 0.0000 4.6251 +0.0000 0.0000 4.5815 +0.0000 0.0000 4.5379 +0.0000 0.0000 4.4942 +0.0000 0.0000 4.4506 +0.0000 0.0000 4.4070 +0.0000 0.0000 4.3633 +0.0000 0.0000 4.3197 +primID: 0 +startangle_c: 13 +endpose_c: 1 -2 13 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0056 -0.0111 5.1051 +0.0111 -0.0222 5.1051 +0.0167 -0.0333 5.1051 +0.0222 -0.0444 5.1051 +0.0278 -0.0556 5.1051 +0.0333 -0.0667 5.1051 +0.0389 -0.0778 5.1051 +0.0444 -0.0889 5.1051 +0.0500 -0.1000 5.1051 +primID: 1 +startangle_c: 13 +endpose_c: 3 -6 13 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0167 -0.0333 5.1051 +0.0333 -0.0667 5.1051 +0.0500 -0.1000 5.1051 +0.0667 -0.1333 5.1051 +0.0833 -0.1667 5.1051 +0.1000 -0.2000 5.1051 +0.1167 -0.2333 5.1051 +0.1333 -0.2667 5.1051 +0.1500 -0.3000 5.1051 +primID: 2 +startangle_c: 13 +endpose_c: -1 2 13 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 5.1051 +-0.0056 0.0111 5.1051 +-0.0111 0.0222 5.1051 +-0.0167 0.0333 5.1051 +-0.0222 0.0444 5.1051 +-0.0278 0.0556 5.1051 +-0.0333 0.0667 5.1051 +-0.0389 0.0778 5.1051 +-0.0444 0.0889 5.1051 +-0.0500 0.1000 5.1051 +primID: 3 +startangle_c: 13 +endpose_c: 4 -5 14 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0184 -0.0298 5.1354 +0.0379 -0.0592 5.1657 +0.0583 -0.0881 5.1960 +0.0796 -0.1165 5.2263 +0.1019 -0.1444 5.2566 +0.1251 -0.1717 5.2869 +0.1492 -0.1984 5.3172 +0.1742 -0.2245 5.3475 +0.2000 -0.2500 5.3778 +primID: 4 +startangle_c: 13 +endpose_c: 2 -7 12 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0156 -0.0377 5.1051 +0.0312 -0.0754 5.1051 +0.0468 -0.1131 5.1051 +0.0623 -0.1508 5.0860 +0.0758 -0.1893 5.0113 +0.0863 -0.2287 4.9366 +0.0939 -0.2687 4.8618 +0.0985 -0.3092 4.7871 +0.1000 -0.3500 4.7124 +primID: 5 +startangle_c: 13 +endpose_c: 0 0 14 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0000 0.0000 5.1487 +0.0000 0.0000 5.1924 +0.0000 0.0000 5.2360 +0.0000 0.0000 5.2796 +0.0000 0.0000 5.3233 +0.0000 0.0000 5.3669 +0.0000 0.0000 5.4105 +0.0000 0.0000 5.4542 +0.0000 0.0000 5.4978 +primID: 6 +startangle_c: 13 +endpose_c: 0 0 12 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0000 0.0000 5.0615 +0.0000 0.0000 5.0178 +0.0000 0.0000 4.9742 +0.0000 0.0000 4.9306 +0.0000 0.0000 4.8869 +0.0000 0.0000 4.8433 +0.0000 0.0000 4.7997 +0.0000 0.0000 4.7560 +0.0000 0.0000 4.7124 +primID: 0 +startangle_c: 14 +endpose_c: 1 -1 14 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0056 -0.0056 5.4978 +0.0111 -0.0111 5.4978 +0.0167 -0.0167 5.4978 +0.0222 -0.0222 5.4978 +0.0278 -0.0278 5.4978 +0.0333 -0.0333 5.4978 +0.0389 -0.0389 5.4978 +0.0444 -0.0444 5.4978 +0.0500 -0.0500 5.4978 +primID: 1 +startangle_c: 14 +endpose_c: 6 -6 14 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0333 -0.0333 5.4978 +0.0667 -0.0667 5.4978 +0.1000 -0.1000 5.4978 +0.1333 -0.1333 5.4978 +0.1667 -0.1667 5.4978 +0.2000 -0.2000 5.4978 +0.2333 -0.2333 5.4978 +0.2667 -0.2667 5.4978 +0.3000 -0.3000 5.4978 +primID: 2 +startangle_c: 14 +endpose_c: -1 1 14 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 5.4978 +-0.0056 0.0056 5.4978 +-0.0111 0.0111 5.4978 +-0.0167 0.0167 5.4978 +-0.0222 0.0222 5.4978 +-0.0278 0.0278 5.4978 +-0.0333 0.0333 5.4978 +-0.0389 0.0389 5.4978 +-0.0444 0.0444 5.4978 +-0.0500 0.0500 5.4978 +primID: 3 +startangle_c: 14 +endpose_c: 7 -5 15 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0341 -0.0341 5.4978 +0.0684 -0.0678 5.5275 +0.1043 -0.1000 5.5793 +0.1418 -0.1302 5.6312 +0.1809 -0.1584 5.6830 +0.2213 -0.1846 5.7349 +0.2631 -0.2086 5.7868 +0.3060 -0.2304 5.8386 +0.3500 -0.2500 5.8905 +primID: 4 +startangle_c: 14 +endpose_c: 5 -7 13 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0341 -0.0341 5.4978 +0.0678 -0.0684 5.4681 +0.1000 -0.1043 5.4162 +0.1302 -0.1418 5.3644 +0.1584 -0.1809 5.3125 +0.1846 -0.2213 5.2607 +0.2086 -0.2631 5.2088 +0.2304 -0.3060 5.1569 +0.2500 -0.3500 5.1051 +primID: 5 +startangle_c: 14 +endpose_c: 0 0 15 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0000 0.0000 5.5414 +0.0000 0.0000 5.5851 +0.0000 0.0000 5.6287 +0.0000 0.0000 5.6723 +0.0000 0.0000 5.7160 +0.0000 0.0000 5.7596 +0.0000 0.0000 5.8032 +0.0000 0.0000 5.8469 +0.0000 0.0000 5.8905 +primID: 6 +startangle_c: 14 +endpose_c: 0 0 13 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0000 0.0000 5.4542 +0.0000 0.0000 5.4105 +0.0000 0.0000 5.3669 +0.0000 0.0000 5.3233 +0.0000 0.0000 5.2796 +0.0000 0.0000 5.2360 +0.0000 0.0000 5.1924 +0.0000 0.0000 5.1487 +0.0000 0.0000 5.1051 +primID: 0 +startangle_c: 15 +endpose_c: 2 -1 15 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0111 -0.0056 5.8905 +0.0222 -0.0111 5.8905 +0.0333 -0.0167 5.8905 +0.0444 -0.0222 5.8905 +0.0556 -0.0278 5.8905 +0.0667 -0.0333 5.8905 +0.0778 -0.0389 5.8905 +0.0889 -0.0444 5.8905 +0.1000 -0.0500 5.8905 +primID: 1 +startangle_c: 15 +endpose_c: 6 -3 15 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0333 -0.0167 5.8905 +0.0667 -0.0333 5.8905 +0.1000 -0.0500 5.8905 +0.1333 -0.0667 5.8905 +0.1667 -0.0833 5.8905 +0.2000 -0.1000 5.8905 +0.2333 -0.1167 5.8905 +0.2667 -0.1333 5.8905 +0.3000 -0.1500 5.8905 +primID: 2 +startangle_c: 15 +endpose_c: -2 1 15 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 5.8905 +-0.0111 0.0056 5.8905 +-0.0222 0.0111 5.8905 +-0.0333 0.0167 5.8905 +-0.0444 0.0222 5.8905 +-0.0556 0.0278 5.8905 +-0.0667 0.0333 5.8905 +-0.0778 0.0389 5.8905 +-0.0889 0.0444 5.8905 +-0.1000 0.0500 5.8905 +primID: 3 +startangle_c: 15 +endpose_c: 5 -4 14 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0298 -0.0184 5.8602 +0.0592 -0.0379 5.8299 +0.0881 -0.0583 5.7996 +0.1165 -0.0796 5.7693 +0.1444 -0.1019 5.7390 +0.1717 -0.1251 5.7087 +0.1984 -0.1492 5.6784 +0.2245 -0.1742 5.6481 +0.2500 -0.2000 5.6178 +primID: 4 +startangle_c: 15 +endpose_c: 7 -2 0 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0377 -0.0156 5.8905 +0.0754 -0.0312 5.8905 +0.1131 -0.0468 5.8905 +0.1508 -0.0623 5.9096 +0.1893 -0.0758 5.9843 +0.2287 -0.0863 6.0590 +0.2687 -0.0939 6.1337 +0.3092 -0.0985 6.2085 +0.3500 -0.1000 6.2832 +primID: 5 +startangle_c: 15 +endpose_c: 0 0 14 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0000 0.0000 5.8469 +0.0000 0.0000 5.8032 +0.0000 0.0000 5.7596 +0.0000 0.0000 5.7160 +0.0000 0.0000 5.6723 +0.0000 0.0000 5.6287 +0.0000 0.0000 5.5851 +0.0000 0.0000 5.5414 +0.0000 0.0000 5.4978 +primID: 6 +startangle_c: 15 +endpose_c: 0 0 0 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0000 0.0000 5.2360 +0.0000 0.0000 4.5815 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.2725 +0.0000 0.0000 2.6180 +0.0000 0.0000 1.9635 +0.0000 0.0000 1.3090 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.0000 diff --git a/mir_robot/mir_navigation/mprim/unicycle_5cm_expensive_turn_in_place_highcost.mprim b/mir_robot/mir_navigation/mprim/unicycle_5cm_expensive_turn_in_place_highcost.mprim new file mode 100755 index 0000000..0f11e5d --- /dev/null +++ b/mir_robot/mir_navigation/mprim/unicycle_5cm_expensive_turn_in_place_highcost.mprim @@ -0,0 +1,1683 @@ +resolution_m: 0.050000 +numberofangles: 16 +totalnumberofprimitives: 112 +primID: 0 +startangle_c: 0 +endpose_c: 1 0 0 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0056 0.0000 0.0000 +0.0111 0.0000 0.0000 +0.0167 0.0000 0.0000 +0.0222 0.0000 0.0000 +0.0278 0.0000 0.0000 +0.0333 0.0000 0.0000 +0.0389 0.0000 0.0000 +0.0444 0.0000 0.0000 +0.0500 0.0000 0.0000 +primID: 1 +startangle_c: 0 +endpose_c: 8 0 0 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0444 0.0000 0.0000 +0.0889 0.0000 0.0000 +0.1333 0.0000 0.0000 +0.1778 0.0000 0.0000 +0.2222 0.0000 0.0000 +0.2667 0.0000 0.0000 +0.3111 0.0000 0.0000 +0.3556 0.0000 0.0000 +0.4000 0.0000 0.0000 +primID: 2 +startangle_c: 0 +endpose_c: -1 0 0 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.0000 +-0.0056 0.0000 0.0000 +-0.0111 0.0000 0.0000 +-0.0167 0.0000 0.0000 +-0.0222 0.0000 0.0000 +-0.0278 0.0000 0.0000 +-0.0333 0.0000 0.0000 +-0.0389 0.0000 0.0000 +-0.0444 0.0000 0.0000 +-0.0500 0.0000 0.0000 +primID: 3 +startangle_c: 0 +endpose_c: 8 1 1 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0452 -0.0000 0.0000 +0.0904 -0.0000 0.0000 +0.1355 -0.0000 0.0000 +0.1807 0.0008 0.0488 +0.2257 0.0045 0.1176 +0.2703 0.0114 0.1864 +0.3144 0.0213 0.2551 +0.3577 0.0342 0.3239 +0.4000 0.0500 0.3927 +primID: 4 +startangle_c: 0 +endpose_c: 8 -1 -1 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0452 0.0000 0.0000 +0.0904 0.0000 0.0000 +0.1355 0.0000 0.0000 +0.1807 -0.0008 -0.0488 +0.2257 -0.0045 -0.1176 +0.2703 -0.0114 -0.1864 +0.3144 -0.0213 -0.2551 +0.3577 -0.0342 -0.3239 +0.4000 -0.0500 -0.3927 +primID: 5 +startangle_c: 0 +endpose_c: 0 0 1 +additionalactioncostmult: 200 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0000 0.0000 0.0436 +0.0000 0.0000 0.0873 +0.0000 0.0000 0.1309 +0.0000 0.0000 0.1745 +0.0000 0.0000 0.2182 +0.0000 0.0000 0.2618 +0.0000 0.0000 0.3054 +0.0000 0.0000 0.3491 +0.0000 0.0000 0.3927 +primID: 6 +startangle_c: 0 +endpose_c: 0 0 -1 +additionalactioncostmult: 200 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0000 0.0000 -0.0436 +0.0000 0.0000 -0.0873 +0.0000 0.0000 -0.1309 +0.0000 0.0000 -0.1745 +0.0000 0.0000 -0.2182 +0.0000 0.0000 -0.2618 +0.0000 0.0000 -0.3054 +0.0000 0.0000 -0.3491 +0.0000 0.0000 -0.3927 +primID: 0 +startangle_c: 1 +endpose_c: 2 1 1 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0111 0.0056 0.3927 +0.0222 0.0111 0.3927 +0.0333 0.0167 0.3927 +0.0444 0.0222 0.3927 +0.0556 0.0278 0.3927 +0.0667 0.0333 0.3927 +0.0778 0.0389 0.3927 +0.0889 0.0444 0.3927 +0.1000 0.0500 0.3927 +primID: 1 +startangle_c: 1 +endpose_c: 6 3 1 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0333 0.0167 0.3927 +0.0667 0.0333 0.3927 +0.1000 0.0500 0.3927 +0.1333 0.0667 0.3927 +0.1667 0.0833 0.3927 +0.2000 0.1000 0.3927 +0.2333 0.1167 0.3927 +0.2667 0.1333 0.3927 +0.3000 0.1500 0.3927 +primID: 2 +startangle_c: 1 +endpose_c: -2 -1 1 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.3927 +-0.0111 -0.0056 0.3927 +-0.0222 -0.0111 0.3927 +-0.0333 -0.0167 0.3927 +-0.0444 -0.0222 0.3927 +-0.0556 -0.0278 0.3927 +-0.0667 -0.0333 0.3927 +-0.0778 -0.0389 0.3927 +-0.0889 -0.0444 0.3927 +-0.1000 -0.0500 0.3927 +primID: 3 +startangle_c: 1 +endpose_c: 5 4 2 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0298 0.0184 0.4230 +0.0592 0.0379 0.4533 +0.0881 0.0583 0.4836 +0.1165 0.0796 0.5139 +0.1444 0.1019 0.5442 +0.1717 0.1251 0.5745 +0.1984 0.1492 0.6048 +0.2245 0.1742 0.6351 +0.2500 0.2000 0.6654 +primID: 4 +startangle_c: 1 +endpose_c: 7 2 0 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0377 0.0156 0.3927 +0.0754 0.0312 0.3927 +0.1131 0.0468 0.3927 +0.1508 0.0623 0.3736 +0.1893 0.0758 0.2989 +0.2287 0.0863 0.2242 +0.2687 0.0939 0.1494 +0.3092 0.0985 0.0747 +0.3500 0.1000 -0.0000 +primID: 5 +startangle_c: 1 +endpose_c: 0 0 2 +additionalactioncostmult: 200 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0000 0.0000 0.4363 +0.0000 0.0000 0.4800 +0.0000 0.0000 0.5236 +0.0000 0.0000 0.5672 +0.0000 0.0000 0.6109 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.6981 +0.0000 0.0000 0.7418 +0.0000 0.0000 0.7854 +primID: 6 +startangle_c: 1 +endpose_c: 0 0 0 +additionalactioncostmult: 200 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0000 0.0000 0.3491 +0.0000 0.0000 0.3054 +0.0000 0.0000 0.2618 +0.0000 0.0000 0.2182 +0.0000 0.0000 0.1745 +0.0000 0.0000 0.1309 +0.0000 0.0000 0.0873 +0.0000 0.0000 0.0436 +0.0000 0.0000 0.0000 +primID: 0 +startangle_c: 2 +endpose_c: 1 1 2 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0056 0.0056 0.7854 +0.0111 0.0111 0.7854 +0.0167 0.0167 0.7854 +0.0222 0.0222 0.7854 +0.0278 0.0278 0.7854 +0.0333 0.0333 0.7854 +0.0389 0.0389 0.7854 +0.0444 0.0444 0.7854 +0.0500 0.0500 0.7854 +primID: 1 +startangle_c: 2 +endpose_c: 6 6 2 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0333 0.0333 0.7854 +0.0667 0.0667 0.7854 +0.1000 0.1000 0.7854 +0.1333 0.1333 0.7854 +0.1667 0.1667 0.7854 +0.2000 0.2000 0.7854 +0.2333 0.2333 0.7854 +0.2667 0.2667 0.7854 +0.3000 0.3000 0.7854 +primID: 2 +startangle_c: 2 +endpose_c: -1 -1 2 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.7854 +-0.0056 -0.0056 0.7854 +-0.0111 -0.0111 0.7854 +-0.0167 -0.0167 0.7854 +-0.0222 -0.0222 0.7854 +-0.0278 -0.0278 0.7854 +-0.0333 -0.0333 0.7854 +-0.0389 -0.0389 0.7854 +-0.0444 -0.0444 0.7854 +-0.0500 -0.0500 0.7854 +primID: 3 +startangle_c: 2 +endpose_c: 5 7 3 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0341 0.0341 0.7854 +0.0678 0.0684 0.8151 +0.1000 0.1043 0.8669 +0.1302 0.1418 0.9188 +0.1584 0.1809 0.9707 +0.1846 0.2213 1.0225 +0.2086 0.2631 1.0744 +0.2304 0.3060 1.1262 +0.2500 0.3500 1.1781 +primID: 4 +startangle_c: 2 +endpose_c: 7 5 1 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0341 0.0341 0.7854 +0.0684 0.0678 0.7557 +0.1043 0.1000 0.7039 +0.1418 0.1302 0.6520 +0.1809 0.1584 0.6001 +0.2213 0.1846 0.5483 +0.2631 0.2086 0.4964 +0.3060 0.2304 0.4446 +0.3500 0.2500 0.3927 +primID: 5 +startangle_c: 2 +endpose_c: 0 0 3 +additionalactioncostmult: 200 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0000 0.0000 0.8290 +0.0000 0.0000 0.8727 +0.0000 0.0000 0.9163 +0.0000 0.0000 0.9599 +0.0000 0.0000 1.0036 +0.0000 0.0000 1.0472 +0.0000 0.0000 1.0908 +0.0000 0.0000 1.1345 +0.0000 0.0000 1.1781 +primID: 6 +startangle_c: 2 +endpose_c: 0 0 1 +additionalactioncostmult: 200 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0000 0.0000 0.7418 +0.0000 0.0000 0.6981 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.6109 +0.0000 0.0000 0.5672 +0.0000 0.0000 0.5236 +0.0000 0.0000 0.4800 +0.0000 0.0000 0.4363 +0.0000 0.0000 0.3927 +primID: 0 +startangle_c: 3 +endpose_c: 1 2 3 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0056 0.0111 1.1781 +0.0111 0.0222 1.1781 +0.0167 0.0333 1.1781 +0.0222 0.0444 1.1781 +0.0278 0.0556 1.1781 +0.0333 0.0667 1.1781 +0.0389 0.0778 1.1781 +0.0444 0.0889 1.1781 +0.0500 0.1000 1.1781 +primID: 1 +startangle_c: 3 +endpose_c: 3 6 3 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0167 0.0333 1.1781 +0.0333 0.0667 1.1781 +0.0500 0.1000 1.1781 +0.0667 0.1333 1.1781 +0.0833 0.1667 1.1781 +0.1000 0.2000 1.1781 +0.1167 0.2333 1.1781 +0.1333 0.2667 1.1781 +0.1500 0.3000 1.1781 +primID: 2 +startangle_c: 3 +endpose_c: -1 -2 3 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.1781 +-0.0056 -0.0111 1.1781 +-0.0111 -0.0222 1.1781 +-0.0167 -0.0333 1.1781 +-0.0222 -0.0444 1.1781 +-0.0278 -0.0556 1.1781 +-0.0333 -0.0667 1.1781 +-0.0389 -0.0778 1.1781 +-0.0444 -0.0889 1.1781 +-0.0500 -0.1000 1.1781 +primID: 3 +startangle_c: 3 +endpose_c: 4 5 2 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0184 0.0298 1.1478 +0.0379 0.0592 1.1175 +0.0583 0.0881 1.0872 +0.0796 0.1165 1.0569 +0.1019 0.1444 1.0266 +0.1251 0.1717 0.9963 +0.1492 0.1984 0.9660 +0.1742 0.2245 0.9357 +0.2000 0.2500 0.9054 +primID: 4 +startangle_c: 3 +endpose_c: 2 7 4 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0156 0.0377 1.1781 +0.0312 0.0754 1.1781 +0.0468 0.1131 1.1781 +0.0623 0.1508 1.1972 +0.0758 0.1893 1.2719 +0.0863 0.2287 1.3466 +0.0939 0.2687 1.4214 +0.0985 0.3092 1.4961 +0.1000 0.3500 1.5708 +primID: 5 +startangle_c: 3 +endpose_c: 0 0 2 +additionalactioncostmult: 200 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0000 0.0000 1.1345 +0.0000 0.0000 1.0908 +0.0000 0.0000 1.0472 +0.0000 0.0000 1.0036 +0.0000 0.0000 0.9599 +0.0000 0.0000 0.9163 +0.0000 0.0000 0.8727 +0.0000 0.0000 0.8290 +0.0000 0.0000 0.7854 +primID: 6 +startangle_c: 3 +endpose_c: 0 0 4 +additionalactioncostmult: 200 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0000 0.0000 1.2217 +0.0000 0.0000 1.2654 +0.0000 0.0000 1.3090 +0.0000 0.0000 1.3526 +0.0000 0.0000 1.3963 +0.0000 0.0000 1.4399 +0.0000 0.0000 1.4835 +0.0000 0.0000 1.5272 +0.0000 0.0000 1.5708 +primID: 0 +startangle_c: 4 +endpose_c: 0 1 4 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0056 1.5708 +0.0000 0.0111 1.5708 +0.0000 0.0167 1.5708 +0.0000 0.0222 1.5708 +0.0000 0.0278 1.5708 +0.0000 0.0333 1.5708 +0.0000 0.0389 1.5708 +0.0000 0.0444 1.5708 +0.0000 0.0500 1.5708 +primID: 1 +startangle_c: 4 +endpose_c: 0 8 4 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0444 1.5708 +0.0000 0.0889 1.5708 +0.0000 0.1333 1.5708 +0.0000 0.1778 1.5708 +0.0000 0.2222 1.5708 +0.0000 0.2667 1.5708 +0.0000 0.3111 1.5708 +0.0000 0.3556 1.5708 +0.0000 0.4000 1.5708 +primID: 2 +startangle_c: 4 +endpose_c: 0 -1 4 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 -0.0056 1.5708 +0.0000 -0.0111 1.5708 +0.0000 -0.0167 1.5708 +0.0000 -0.0222 1.5708 +0.0000 -0.0278 1.5708 +0.0000 -0.0333 1.5708 +0.0000 -0.0389 1.5708 +0.0000 -0.0444 1.5708 +0.0000 -0.0500 1.5708 +primID: 3 +startangle_c: 4 +endpose_c: -1 8 5 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0452 1.5708 +0.0000 0.0904 1.5708 +0.0000 0.1355 1.5708 +-0.0008 0.1807 1.6196 +-0.0045 0.2257 1.6884 +-0.0114 0.2703 1.7572 +-0.0213 0.3144 1.8259 +-0.0342 0.3577 1.8947 +-0.0500 0.4000 1.9635 +primID: 4 +startangle_c: 4 +endpose_c: 1 8 3 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0452 1.5708 +0.0000 0.0904 1.5708 +0.0000 0.1355 1.5708 +0.0008 0.1807 1.5220 +0.0045 0.2257 1.4532 +0.0114 0.2703 1.3844 +0.0213 0.3144 1.3156 +0.0342 0.3577 1.2469 +0.0500 0.4000 1.1781 +primID: 5 +startangle_c: 4 +endpose_c: 0 0 5 +additionalactioncostmult: 200 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0000 1.6144 +0.0000 0.0000 1.6581 +0.0000 0.0000 1.7017 +0.0000 0.0000 1.7453 +0.0000 0.0000 1.7890 +0.0000 0.0000 1.8326 +0.0000 0.0000 1.8762 +0.0000 0.0000 1.9199 +0.0000 0.0000 1.9635 +primID: 6 +startangle_c: 4 +endpose_c: 0 0 3 +additionalactioncostmult: 200 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0000 1.5272 +0.0000 0.0000 1.4835 +0.0000 0.0000 1.4399 +0.0000 0.0000 1.3963 +0.0000 0.0000 1.3526 +0.0000 0.0000 1.3090 +0.0000 0.0000 1.2654 +0.0000 0.0000 1.2217 +0.0000 0.0000 1.1781 +primID: 0 +startangle_c: 5 +endpose_c: -1 2 5 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0056 0.0111 1.9635 +-0.0111 0.0222 1.9635 +-0.0167 0.0333 1.9635 +-0.0222 0.0444 1.9635 +-0.0278 0.0556 1.9635 +-0.0333 0.0667 1.9635 +-0.0389 0.0778 1.9635 +-0.0444 0.0889 1.9635 +-0.0500 0.1000 1.9635 +primID: 1 +startangle_c: 5 +endpose_c: -3 6 5 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0167 0.0333 1.9635 +-0.0333 0.0667 1.9635 +-0.0500 0.1000 1.9635 +-0.0667 0.1333 1.9635 +-0.0833 0.1667 1.9635 +-0.1000 0.2000 1.9635 +-0.1167 0.2333 1.9635 +-0.1333 0.2667 1.9635 +-0.1500 0.3000 1.9635 +primID: 2 +startangle_c: 5 +endpose_c: 1 -2 5 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0056 -0.0111 1.9635 +0.0111 -0.0222 1.9635 +0.0167 -0.0333 1.9635 +0.0222 -0.0444 1.9635 +0.0278 -0.0556 1.9635 +0.0333 -0.0667 1.9635 +0.0389 -0.0778 1.9635 +0.0444 -0.0889 1.9635 +0.0500 -0.1000 1.9635 +primID: 3 +startangle_c: 5 +endpose_c: -4 5 6 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0184 0.0298 1.9938 +-0.0379 0.0592 2.0241 +-0.0583 0.0881 2.0544 +-0.0796 0.1165 2.0847 +-0.1019 0.1444 2.1150 +-0.1251 0.1717 2.1453 +-0.1492 0.1984 2.1756 +-0.1742 0.2245 2.2059 +-0.2000 0.2500 2.2362 +primID: 4 +startangle_c: 5 +endpose_c: -2 7 4 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0156 0.0377 1.9635 +-0.0312 0.0754 1.9635 +-0.0468 0.1131 1.9635 +-0.0623 0.1508 1.9444 +-0.0758 0.1893 1.8697 +-0.0863 0.2287 1.7950 +-0.0939 0.2687 1.7202 +-0.0985 0.3092 1.6455 +-0.1000 0.3500 1.5708 +primID: 5 +startangle_c: 5 +endpose_c: 0 0 6 +additionalactioncostmult: 200 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0000 0.0000 2.0071 +0.0000 0.0000 2.0508 +0.0000 0.0000 2.0944 +0.0000 0.0000 2.1380 +0.0000 0.0000 2.1817 +0.0000 0.0000 2.2253 +0.0000 0.0000 2.2689 +0.0000 0.0000 2.3126 +0.0000 0.0000 2.3562 +primID: 6 +startangle_c: 5 +endpose_c: 0 0 4 +additionalactioncostmult: 200 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0000 0.0000 1.9199 +0.0000 0.0000 1.8762 +0.0000 0.0000 1.8326 +0.0000 0.0000 1.7890 +0.0000 0.0000 1.7453 +0.0000 0.0000 1.7017 +0.0000 0.0000 1.6581 +0.0000 0.0000 1.6144 +0.0000 0.0000 1.5708 +primID: 0 +startangle_c: 6 +endpose_c: -1 1 6 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0056 0.0056 2.3562 +-0.0111 0.0111 2.3562 +-0.0167 0.0167 2.3562 +-0.0222 0.0222 2.3562 +-0.0278 0.0278 2.3562 +-0.0333 0.0333 2.3562 +-0.0389 0.0389 2.3562 +-0.0444 0.0444 2.3562 +-0.0500 0.0500 2.3562 +primID: 1 +startangle_c: 6 +endpose_c: -6 6 6 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0333 0.0333 2.3562 +-0.0667 0.0667 2.3562 +-0.1000 0.1000 2.3562 +-0.1333 0.1333 2.3562 +-0.1667 0.1667 2.3562 +-0.2000 0.2000 2.3562 +-0.2333 0.2333 2.3562 +-0.2667 0.2667 2.3562 +-0.3000 0.3000 2.3562 +primID: 2 +startangle_c: 6 +endpose_c: 1 -1 6 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0056 -0.0056 2.3562 +0.0111 -0.0111 2.3562 +0.0167 -0.0167 2.3562 +0.0222 -0.0222 2.3562 +0.0278 -0.0278 2.3562 +0.0333 -0.0333 2.3562 +0.0389 -0.0389 2.3562 +0.0444 -0.0444 2.3562 +0.0500 -0.0500 2.3562 +primID: 3 +startangle_c: 6 +endpose_c: -7 5 7 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0341 0.0341 2.3562 +-0.0684 0.0678 2.3859 +-0.1043 0.1000 2.4377 +-0.1418 0.1302 2.4896 +-0.1809 0.1584 2.5415 +-0.2213 0.1846 2.5933 +-0.2631 0.2086 2.6452 +-0.3060 0.2304 2.6970 +-0.3500 0.2500 2.7489 +primID: 4 +startangle_c: 6 +endpose_c: -5 7 5 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0341 0.0341 2.3562 +-0.0678 0.0684 2.3265 +-0.1000 0.1043 2.2747 +-0.1302 0.1418 2.2228 +-0.1584 0.1809 2.1709 +-0.1846 0.2213 2.1191 +-0.2086 0.2631 2.0672 +-0.2304 0.3060 2.0154 +-0.2500 0.3500 1.9635 +primID: 5 +startangle_c: 6 +endpose_c: 0 0 7 +additionalactioncostmult: 200 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0000 0.0000 2.3998 +0.0000 0.0000 2.4435 +0.0000 0.0000 2.4871 +0.0000 0.0000 2.5307 +0.0000 0.0000 2.5744 +0.0000 0.0000 2.6180 +0.0000 0.0000 2.6616 +0.0000 0.0000 2.7053 +0.0000 0.0000 2.7489 +primID: 6 +startangle_c: 6 +endpose_c: 0 0 5 +additionalactioncostmult: 200 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0000 0.0000 2.3126 +0.0000 0.0000 2.2689 +0.0000 0.0000 2.2253 +0.0000 0.0000 2.1817 +0.0000 0.0000 2.1380 +0.0000 0.0000 2.0944 +0.0000 0.0000 2.0508 +0.0000 0.0000 2.0071 +0.0000 0.0000 1.9635 +primID: 0 +startangle_c: 7 +endpose_c: -2 1 7 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0111 0.0056 2.7489 +-0.0222 0.0111 2.7489 +-0.0333 0.0167 2.7489 +-0.0444 0.0222 2.7489 +-0.0556 0.0278 2.7489 +-0.0667 0.0333 2.7489 +-0.0778 0.0389 2.7489 +-0.0889 0.0444 2.7489 +-0.1000 0.0500 2.7489 +primID: 1 +startangle_c: 7 +endpose_c: -6 3 7 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0333 0.0167 2.7489 +-0.0667 0.0333 2.7489 +-0.1000 0.0500 2.7489 +-0.1333 0.0667 2.7489 +-0.1667 0.0833 2.7489 +-0.2000 0.1000 2.7489 +-0.2333 0.1167 2.7489 +-0.2667 0.1333 2.7489 +-0.3000 0.1500 2.7489 +primID: 2 +startangle_c: 7 +endpose_c: 2 -1 7 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0111 -0.0056 2.7489 +0.0222 -0.0111 2.7489 +0.0333 -0.0167 2.7489 +0.0444 -0.0222 2.7489 +0.0556 -0.0278 2.7489 +0.0667 -0.0333 2.7489 +0.0778 -0.0389 2.7489 +0.0889 -0.0444 2.7489 +0.1000 -0.0500 2.7489 +primID: 3 +startangle_c: 7 +endpose_c: -5 4 6 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0298 0.0184 2.7186 +-0.0592 0.0379 2.6883 +-0.0881 0.0583 2.6580 +-0.1165 0.0796 2.6277 +-0.1444 0.1019 2.5974 +-0.1717 0.1251 2.5671 +-0.1984 0.1492 2.5368 +-0.2245 0.1742 2.5065 +-0.2500 0.2000 2.4762 +primID: 4 +startangle_c: 7 +endpose_c: -7 2 8 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0377 0.0156 2.7489 +-0.0754 0.0312 2.7489 +-0.1131 0.0468 2.7489 +-0.1508 0.0623 2.7680 +-0.1893 0.0758 2.8427 +-0.2287 0.0863 2.9174 +-0.2687 0.0939 2.9921 +-0.3092 0.0985 3.0669 +-0.3500 0.1000 3.1416 +primID: 5 +startangle_c: 7 +endpose_c: 0 0 6 +additionalactioncostmult: 200 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0000 0.0000 2.7053 +0.0000 0.0000 2.6616 +0.0000 0.0000 2.6180 +0.0000 0.0000 2.5744 +0.0000 0.0000 2.5307 +0.0000 0.0000 2.4871 +0.0000 0.0000 2.4435 +0.0000 0.0000 2.3998 +0.0000 0.0000 2.3562 +primID: 6 +startangle_c: 7 +endpose_c: 0 0 8 +additionalactioncostmult: 200 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0000 0.0000 2.7925 +0.0000 0.0000 2.8362 +0.0000 0.0000 2.8798 +0.0000 0.0000 2.9234 +0.0000 0.0000 2.9671 +0.0000 0.0000 3.0107 +0.0000 0.0000 3.0543 +0.0000 0.0000 3.0980 +0.0000 0.0000 3.1416 +primID: 0 +startangle_c: 8 +endpose_c: -1 0 8 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0056 0.0000 3.1416 +-0.0111 0.0000 3.1416 +-0.0167 0.0000 3.1416 +-0.0222 0.0000 3.1416 +-0.0278 0.0000 3.1416 +-0.0333 0.0000 3.1416 +-0.0389 0.0000 3.1416 +-0.0444 0.0000 3.1416 +-0.0500 0.0000 3.1416 +primID: 1 +startangle_c: 8 +endpose_c: -8 0 8 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0444 0.0000 3.1416 +-0.0889 0.0000 3.1416 +-0.1333 0.0000 3.1416 +-0.1778 0.0000 3.1416 +-0.2222 0.0000 3.1416 +-0.2667 0.0000 3.1416 +-0.3111 0.0000 3.1416 +-0.3556 0.0000 3.1416 +-0.4000 0.0000 3.1416 +primID: 2 +startangle_c: 8 +endpose_c: 1 0 8 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0056 0.0000 3.1416 +0.0111 0.0000 3.1416 +0.0167 0.0000 3.1416 +0.0222 0.0000 3.1416 +0.0278 0.0000 3.1416 +0.0333 0.0000 3.1416 +0.0389 0.0000 3.1416 +0.0444 0.0000 3.1416 +0.0500 0.0000 3.1416 +primID: 3 +startangle_c: 8 +endpose_c: -8 -1 9 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0452 0.0000 3.1416 +-0.0904 0.0000 3.1416 +-0.1355 0.0000 3.1416 +-0.1807 -0.0008 3.1904 +-0.2257 -0.0045 3.2592 +-0.2703 -0.0114 3.3280 +-0.3144 -0.0213 3.3967 +-0.3577 -0.0342 3.4655 +-0.4000 -0.0500 3.5343 +primID: 4 +startangle_c: 8 +endpose_c: -8 1 7 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0452 0.0000 3.1416 +-0.0904 0.0000 3.1416 +-0.1355 0.0000 3.1416 +-0.1807 0.0008 3.0928 +-0.2257 0.0045 3.0240 +-0.2703 0.0114 2.9552 +-0.3144 0.0213 2.8864 +-0.3577 0.0342 2.8177 +-0.4000 0.0500 2.7489 +primID: 5 +startangle_c: 8 +endpose_c: 0 0 9 +additionalactioncostmult: 200 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0000 0.0000 3.1852 +0.0000 0.0000 3.2289 +0.0000 0.0000 3.2725 +0.0000 0.0000 3.3161 +0.0000 0.0000 3.3598 +0.0000 0.0000 3.4034 +0.0000 0.0000 3.4470 +0.0000 0.0000 3.4907 +0.0000 0.0000 3.5343 +primID: 6 +startangle_c: 8 +endpose_c: 0 0 7 +additionalactioncostmult: 200 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0000 0.0000 3.0980 +0.0000 0.0000 3.0543 +0.0000 0.0000 3.0107 +0.0000 0.0000 2.9671 +0.0000 0.0000 2.9234 +0.0000 0.0000 2.8798 +0.0000 0.0000 2.8362 +0.0000 0.0000 2.7925 +0.0000 0.0000 2.7489 +primID: 0 +startangle_c: 9 +endpose_c: -2 -1 9 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0111 -0.0056 3.5343 +-0.0222 -0.0111 3.5343 +-0.0333 -0.0167 3.5343 +-0.0444 -0.0222 3.5343 +-0.0556 -0.0278 3.5343 +-0.0667 -0.0333 3.5343 +-0.0778 -0.0389 3.5343 +-0.0889 -0.0444 3.5343 +-0.1000 -0.0500 3.5343 +primID: 1 +startangle_c: 9 +endpose_c: -6 -3 9 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0333 -0.0167 3.5343 +-0.0667 -0.0333 3.5343 +-0.1000 -0.0500 3.5343 +-0.1333 -0.0667 3.5343 +-0.1667 -0.0833 3.5343 +-0.2000 -0.1000 3.5343 +-0.2333 -0.1167 3.5343 +-0.2667 -0.1333 3.5343 +-0.3000 -0.1500 3.5343 +primID: 2 +startangle_c: 9 +endpose_c: 2 1 9 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0111 0.0056 3.5343 +0.0222 0.0111 3.5343 +0.0333 0.0167 3.5343 +0.0444 0.0222 3.5343 +0.0556 0.0278 3.5343 +0.0667 0.0333 3.5343 +0.0778 0.0389 3.5343 +0.0889 0.0444 3.5343 +0.1000 0.0500 3.5343 +primID: 3 +startangle_c: 9 +endpose_c: -5 -4 10 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0298 -0.0184 3.5646 +-0.0592 -0.0379 3.5949 +-0.0881 -0.0583 3.6252 +-0.1165 -0.0796 3.6555 +-0.1444 -0.1019 3.6858 +-0.1717 -0.1251 3.7161 +-0.1984 -0.1492 3.7464 +-0.2245 -0.1742 3.7767 +-0.2500 -0.2000 3.8070 +primID: 4 +startangle_c: 9 +endpose_c: -7 -2 8 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0377 -0.0156 3.5343 +-0.0754 -0.0312 3.5343 +-0.1131 -0.0468 3.5343 +-0.1508 -0.0623 3.5152 +-0.1893 -0.0758 3.4405 +-0.2287 -0.0863 3.3658 +-0.2687 -0.0939 3.2910 +-0.3092 -0.0985 3.2163 +-0.3500 -0.1000 3.1416 +primID: 5 +startangle_c: 9 +endpose_c: 0 0 10 +additionalactioncostmult: 200 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0000 0.0000 3.5779 +0.0000 0.0000 3.6216 +0.0000 0.0000 3.6652 +0.0000 0.0000 3.7088 +0.0000 0.0000 3.7525 +0.0000 0.0000 3.7961 +0.0000 0.0000 3.8397 +0.0000 0.0000 3.8834 +0.0000 0.0000 3.9270 +primID: 6 +startangle_c: 9 +endpose_c: 0 0 8 +additionalactioncostmult: 200 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0000 0.0000 3.4907 +0.0000 0.0000 3.4470 +0.0000 0.0000 3.4034 +0.0000 0.0000 3.3598 +0.0000 0.0000 3.3161 +0.0000 0.0000 3.2725 +0.0000 0.0000 3.2289 +0.0000 0.0000 3.1852 +0.0000 0.0000 3.1416 +primID: 0 +startangle_c: 10 +endpose_c: -1 -1 10 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0056 -0.0056 3.9270 +-0.0111 -0.0111 3.9270 +-0.0167 -0.0167 3.9270 +-0.0222 -0.0222 3.9270 +-0.0278 -0.0278 3.9270 +-0.0333 -0.0333 3.9270 +-0.0389 -0.0389 3.9270 +-0.0444 -0.0444 3.9270 +-0.0500 -0.0500 3.9270 +primID: 1 +startangle_c: 10 +endpose_c: -6 -6 10 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0333 -0.0333 3.9270 +-0.0667 -0.0667 3.9270 +-0.1000 -0.1000 3.9270 +-0.1333 -0.1333 3.9270 +-0.1667 -0.1667 3.9270 +-0.2000 -0.2000 3.9270 +-0.2333 -0.2333 3.9270 +-0.2667 -0.2667 3.9270 +-0.3000 -0.3000 3.9270 +primID: 2 +startangle_c: 10 +endpose_c: 1 1 10 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0056 0.0056 3.9270 +0.0111 0.0111 3.9270 +0.0167 0.0167 3.9270 +0.0222 0.0222 3.9270 +0.0278 0.0278 3.9270 +0.0333 0.0333 3.9270 +0.0389 0.0389 3.9270 +0.0444 0.0444 3.9270 +0.0500 0.0500 3.9270 +primID: 3 +startangle_c: 10 +endpose_c: -5 -7 11 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0341 -0.0341 3.9270 +-0.0678 -0.0684 3.9567 +-0.1000 -0.1043 4.0085 +-0.1302 -0.1418 4.0604 +-0.1584 -0.1809 4.1123 +-0.1846 -0.2213 4.1641 +-0.2086 -0.2631 4.2160 +-0.2304 -0.3060 4.2678 +-0.2500 -0.3500 4.3197 +primID: 4 +startangle_c: 10 +endpose_c: -7 -5 9 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0341 -0.0341 3.9270 +-0.0684 -0.0678 3.8973 +-0.1043 -0.1000 3.8455 +-0.1418 -0.1302 3.7936 +-0.1809 -0.1584 3.7417 +-0.2213 -0.1846 3.6899 +-0.2631 -0.2086 3.6380 +-0.3060 -0.2304 3.5862 +-0.3500 -0.2500 3.5343 +primID: 5 +startangle_c: 10 +endpose_c: 0 0 11 +additionalactioncostmult: 200 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.9706 +0.0000 0.0000 4.0143 +0.0000 0.0000 4.0579 +0.0000 0.0000 4.1015 +0.0000 0.0000 4.1452 +0.0000 0.0000 4.1888 +0.0000 0.0000 4.2324 +0.0000 0.0000 4.2761 +0.0000 0.0000 4.3197 +primID: 6 +startangle_c: 10 +endpose_c: 0 0 9 +additionalactioncostmult: 200 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.8834 +0.0000 0.0000 3.8397 +0.0000 0.0000 3.7961 +0.0000 0.0000 3.7525 +0.0000 0.0000 3.7088 +0.0000 0.0000 3.6652 +0.0000 0.0000 3.6216 +0.0000 0.0000 3.5779 +0.0000 0.0000 3.5343 +primID: 0 +startangle_c: 11 +endpose_c: -1 -2 11 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0056 -0.0111 4.3197 +-0.0111 -0.0222 4.3197 +-0.0167 -0.0333 4.3197 +-0.0222 -0.0444 4.3197 +-0.0278 -0.0556 4.3197 +-0.0333 -0.0667 4.3197 +-0.0389 -0.0778 4.3197 +-0.0444 -0.0889 4.3197 +-0.0500 -0.1000 4.3197 +primID: 1 +startangle_c: 11 +endpose_c: -3 -6 11 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0167 -0.0333 4.3197 +-0.0333 -0.0667 4.3197 +-0.0500 -0.1000 4.3197 +-0.0667 -0.1333 4.3197 +-0.0833 -0.1667 4.3197 +-0.1000 -0.2000 4.3197 +-0.1167 -0.2333 4.3197 +-0.1333 -0.2667 4.3197 +-0.1500 -0.3000 4.3197 +primID: 2 +startangle_c: 11 +endpose_c: 1 2 11 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0056 0.0111 4.3197 +0.0111 0.0222 4.3197 +0.0167 0.0333 4.3197 +0.0222 0.0444 4.3197 +0.0278 0.0556 4.3197 +0.0333 0.0667 4.3197 +0.0389 0.0778 4.3197 +0.0444 0.0889 4.3197 +0.0500 0.1000 4.3197 +primID: 3 +startangle_c: 11 +endpose_c: -4 -5 10 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0184 -0.0298 4.2894 +-0.0379 -0.0592 4.2591 +-0.0583 -0.0881 4.2288 +-0.0796 -0.1165 4.1985 +-0.1019 -0.1444 4.1682 +-0.1251 -0.1717 4.1379 +-0.1492 -0.1984 4.1076 +-0.1742 -0.2245 4.0773 +-0.2000 -0.2500 4.0470 +primID: 4 +startangle_c: 11 +endpose_c: -2 -7 12 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0156 -0.0377 4.3197 +-0.0312 -0.0754 4.3197 +-0.0468 -0.1131 4.3197 +-0.0623 -0.1508 4.3388 +-0.0758 -0.1893 4.4135 +-0.0863 -0.2287 4.4882 +-0.0939 -0.2687 4.5629 +-0.0985 -0.3092 4.6377 +-0.1000 -0.3500 4.7124 +primID: 5 +startangle_c: 11 +endpose_c: 0 0 10 +additionalactioncostmult: 200 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0000 0.0000 4.2761 +0.0000 0.0000 4.2324 +0.0000 0.0000 4.1888 +0.0000 0.0000 4.1452 +0.0000 0.0000 4.1015 +0.0000 0.0000 4.0579 +0.0000 0.0000 4.0143 +0.0000 0.0000 3.9706 +0.0000 0.0000 3.9270 +primID: 6 +startangle_c: 11 +endpose_c: 0 0 12 +additionalactioncostmult: 200 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0000 0.0000 4.3633 +0.0000 0.0000 4.4070 +0.0000 0.0000 4.4506 +0.0000 0.0000 4.4942 +0.0000 0.0000 4.5379 +0.0000 0.0000 4.5815 +0.0000 0.0000 4.6251 +0.0000 0.0000 4.6688 +0.0000 0.0000 4.7124 +primID: 0 +startangle_c: 12 +endpose_c: 0 -1 12 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0056 4.7124 +0.0000 -0.0111 4.7124 +0.0000 -0.0167 4.7124 +0.0000 -0.0222 4.7124 +0.0000 -0.0278 4.7124 +0.0000 -0.0333 4.7124 +0.0000 -0.0389 4.7124 +0.0000 -0.0444 4.7124 +0.0000 -0.0500 4.7124 +primID: 1 +startangle_c: 12 +endpose_c: 0 -8 12 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0444 4.7124 +0.0000 -0.0889 4.7124 +0.0000 -0.1333 4.7124 +0.0000 -0.1778 4.7124 +0.0000 -0.2222 4.7124 +0.0000 -0.2667 4.7124 +0.0000 -0.3111 4.7124 +0.0000 -0.3556 4.7124 +0.0000 -0.4000 4.7124 +primID: 2 +startangle_c: 12 +endpose_c: 0 1 12 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0056 4.7124 +0.0000 0.0111 4.7124 +0.0000 0.0167 4.7124 +0.0000 0.0222 4.7124 +0.0000 0.0278 4.7124 +0.0000 0.0333 4.7124 +0.0000 0.0389 4.7124 +0.0000 0.0444 4.7124 +0.0000 0.0500 4.7124 +primID: 3 +startangle_c: 12 +endpose_c: 1 -8 13 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0452 4.7124 +0.0000 -0.0904 4.7124 +0.0000 -0.1355 4.7124 +0.0008 -0.1807 4.7612 +0.0045 -0.2257 4.8300 +0.0114 -0.2703 4.8988 +0.0213 -0.3144 4.9675 +0.0342 -0.3577 5.0363 +0.0500 -0.4000 5.1051 +primID: 4 +startangle_c: 12 +endpose_c: -1 -8 11 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.7124 +-0.0000 -0.0452 4.7124 +-0.0000 -0.0904 4.7124 +-0.0000 -0.1355 4.7124 +-0.0008 -0.1807 4.6636 +-0.0045 -0.2257 4.5948 +-0.0114 -0.2703 4.5260 +-0.0213 -0.3144 4.4572 +-0.0342 -0.3577 4.3885 +-0.0500 -0.4000 4.3197 +primID: 5 +startangle_c: 12 +endpose_c: 0 0 13 +additionalactioncostmult: 200 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0000 4.7560 +0.0000 0.0000 4.7997 +0.0000 0.0000 4.8433 +0.0000 0.0000 4.8869 +0.0000 0.0000 4.9306 +0.0000 0.0000 4.9742 +0.0000 0.0000 5.0178 +0.0000 0.0000 5.0615 +0.0000 0.0000 5.1051 +primID: 6 +startangle_c: 12 +endpose_c: 0 0 11 +additionalactioncostmult: 200 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0000 4.6688 +0.0000 0.0000 4.6251 +0.0000 0.0000 4.5815 +0.0000 0.0000 4.5379 +0.0000 0.0000 4.4942 +0.0000 0.0000 4.4506 +0.0000 0.0000 4.4070 +0.0000 0.0000 4.3633 +0.0000 0.0000 4.3197 +primID: 0 +startangle_c: 13 +endpose_c: 1 -2 13 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0056 -0.0111 5.1051 +0.0111 -0.0222 5.1051 +0.0167 -0.0333 5.1051 +0.0222 -0.0444 5.1051 +0.0278 -0.0556 5.1051 +0.0333 -0.0667 5.1051 +0.0389 -0.0778 5.1051 +0.0444 -0.0889 5.1051 +0.0500 -0.1000 5.1051 +primID: 1 +startangle_c: 13 +endpose_c: 3 -6 13 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0167 -0.0333 5.1051 +0.0333 -0.0667 5.1051 +0.0500 -0.1000 5.1051 +0.0667 -0.1333 5.1051 +0.0833 -0.1667 5.1051 +0.1000 -0.2000 5.1051 +0.1167 -0.2333 5.1051 +0.1333 -0.2667 5.1051 +0.1500 -0.3000 5.1051 +primID: 2 +startangle_c: 13 +endpose_c: -1 2 13 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.1051 +-0.0056 0.0111 5.1051 +-0.0111 0.0222 5.1051 +-0.0167 0.0333 5.1051 +-0.0222 0.0444 5.1051 +-0.0278 0.0556 5.1051 +-0.0333 0.0667 5.1051 +-0.0389 0.0778 5.1051 +-0.0444 0.0889 5.1051 +-0.0500 0.1000 5.1051 +primID: 3 +startangle_c: 13 +endpose_c: 4 -5 14 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0184 -0.0298 5.1354 +0.0379 -0.0592 5.1657 +0.0583 -0.0881 5.1960 +0.0796 -0.1165 5.2263 +0.1019 -0.1444 5.2566 +0.1251 -0.1717 5.2869 +0.1492 -0.1984 5.3172 +0.1742 -0.2245 5.3475 +0.2000 -0.2500 5.3778 +primID: 4 +startangle_c: 13 +endpose_c: 2 -7 12 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0156 -0.0377 5.1051 +0.0312 -0.0754 5.1051 +0.0468 -0.1131 5.1051 +0.0623 -0.1508 5.0860 +0.0758 -0.1893 5.0113 +0.0863 -0.2287 4.9366 +0.0939 -0.2687 4.8618 +0.0985 -0.3092 4.7871 +0.1000 -0.3500 4.7124 +primID: 5 +startangle_c: 13 +endpose_c: 0 0 14 +additionalactioncostmult: 200 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0000 0.0000 5.1487 +0.0000 0.0000 5.1924 +0.0000 0.0000 5.2360 +0.0000 0.0000 5.2796 +0.0000 0.0000 5.3233 +0.0000 0.0000 5.3669 +0.0000 0.0000 5.4105 +0.0000 0.0000 5.4542 +0.0000 0.0000 5.4978 +primID: 6 +startangle_c: 13 +endpose_c: 0 0 12 +additionalactioncostmult: 200 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0000 0.0000 5.0615 +0.0000 0.0000 5.0178 +0.0000 0.0000 4.9742 +0.0000 0.0000 4.9306 +0.0000 0.0000 4.8869 +0.0000 0.0000 4.8433 +0.0000 0.0000 4.7997 +0.0000 0.0000 4.7560 +0.0000 0.0000 4.7124 +primID: 0 +startangle_c: 14 +endpose_c: 1 -1 14 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0056 -0.0056 5.4978 +0.0111 -0.0111 5.4978 +0.0167 -0.0167 5.4978 +0.0222 -0.0222 5.4978 +0.0278 -0.0278 5.4978 +0.0333 -0.0333 5.4978 +0.0389 -0.0389 5.4978 +0.0444 -0.0444 5.4978 +0.0500 -0.0500 5.4978 +primID: 1 +startangle_c: 14 +endpose_c: 6 -6 14 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0333 -0.0333 5.4978 +0.0667 -0.0667 5.4978 +0.1000 -0.1000 5.4978 +0.1333 -0.1333 5.4978 +0.1667 -0.1667 5.4978 +0.2000 -0.2000 5.4978 +0.2333 -0.2333 5.4978 +0.2667 -0.2667 5.4978 +0.3000 -0.3000 5.4978 +primID: 2 +startangle_c: 14 +endpose_c: -1 1 14 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.4978 +-0.0056 0.0056 5.4978 +-0.0111 0.0111 5.4978 +-0.0167 0.0167 5.4978 +-0.0222 0.0222 5.4978 +-0.0278 0.0278 5.4978 +-0.0333 0.0333 5.4978 +-0.0389 0.0389 5.4978 +-0.0444 0.0444 5.4978 +-0.0500 0.0500 5.4978 +primID: 3 +startangle_c: 14 +endpose_c: 7 -5 15 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0341 -0.0341 5.4978 +0.0684 -0.0678 5.5275 +0.1043 -0.1000 5.5793 +0.1418 -0.1302 5.6312 +0.1809 -0.1584 5.6830 +0.2213 -0.1846 5.7349 +0.2631 -0.2086 5.7868 +0.3060 -0.2304 5.8386 +0.3500 -0.2500 5.8905 +primID: 4 +startangle_c: 14 +endpose_c: 5 -7 13 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0341 -0.0341 5.4978 +0.0678 -0.0684 5.4681 +0.1000 -0.1043 5.4162 +0.1302 -0.1418 5.3644 +0.1584 -0.1809 5.3125 +0.1846 -0.2213 5.2607 +0.2086 -0.2631 5.2088 +0.2304 -0.3060 5.1569 +0.2500 -0.3500 5.1051 +primID: 5 +startangle_c: 14 +endpose_c: 0 0 15 +additionalactioncostmult: 200 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0000 0.0000 5.5414 +0.0000 0.0000 5.5851 +0.0000 0.0000 5.6287 +0.0000 0.0000 5.6723 +0.0000 0.0000 5.7160 +0.0000 0.0000 5.7596 +0.0000 0.0000 5.8032 +0.0000 0.0000 5.8469 +0.0000 0.0000 5.8905 +primID: 6 +startangle_c: 14 +endpose_c: 0 0 13 +additionalactioncostmult: 200 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0000 0.0000 5.4542 +0.0000 0.0000 5.4105 +0.0000 0.0000 5.3669 +0.0000 0.0000 5.3233 +0.0000 0.0000 5.2796 +0.0000 0.0000 5.2360 +0.0000 0.0000 5.1924 +0.0000 0.0000 5.1487 +0.0000 0.0000 5.1051 +primID: 0 +startangle_c: 15 +endpose_c: 2 -1 15 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0111 -0.0056 5.8905 +0.0222 -0.0111 5.8905 +0.0333 -0.0167 5.8905 +0.0444 -0.0222 5.8905 +0.0556 -0.0278 5.8905 +0.0667 -0.0333 5.8905 +0.0778 -0.0389 5.8905 +0.0889 -0.0444 5.8905 +0.1000 -0.0500 5.8905 +primID: 1 +startangle_c: 15 +endpose_c: 6 -3 15 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0333 -0.0167 5.8905 +0.0667 -0.0333 5.8905 +0.1000 -0.0500 5.8905 +0.1333 -0.0667 5.8905 +0.1667 -0.0833 5.8905 +0.2000 -0.1000 5.8905 +0.2333 -0.1167 5.8905 +0.2667 -0.1333 5.8905 +0.3000 -0.1500 5.8905 +primID: 2 +startangle_c: 15 +endpose_c: -2 1 15 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.8905 +-0.0111 0.0056 5.8905 +-0.0222 0.0111 5.8905 +-0.0333 0.0167 5.8905 +-0.0444 0.0222 5.8905 +-0.0556 0.0278 5.8905 +-0.0667 0.0333 5.8905 +-0.0778 0.0389 5.8905 +-0.0889 0.0444 5.8905 +-0.1000 0.0500 5.8905 +primID: 3 +startangle_c: 15 +endpose_c: 5 -4 14 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0298 -0.0184 5.8602 +0.0592 -0.0379 5.8299 +0.0881 -0.0583 5.7996 +0.1165 -0.0796 5.7693 +0.1444 -0.1019 5.7390 +0.1717 -0.1251 5.7087 +0.1984 -0.1492 5.6784 +0.2245 -0.1742 5.6481 +0.2500 -0.2000 5.6178 +primID: 4 +startangle_c: 15 +endpose_c: 7 -2 0 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0377 -0.0156 5.8905 +0.0754 -0.0312 5.8905 +0.1131 -0.0468 5.8905 +0.1508 -0.0623 5.9096 +0.1893 -0.0758 5.9843 +0.2287 -0.0863 6.0590 +0.2687 -0.0939 6.1337 +0.3092 -0.0985 6.2085 +0.3500 -0.1000 6.2832 +primID: 5 +startangle_c: 15 +endpose_c: 0 0 14 +additionalactioncostmult: 200 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0000 0.0000 5.8469 +0.0000 0.0000 5.8032 +0.0000 0.0000 5.7596 +0.0000 0.0000 5.7160 +0.0000 0.0000 5.6723 +0.0000 0.0000 5.6287 +0.0000 0.0000 5.5851 +0.0000 0.0000 5.5414 +0.0000 0.0000 5.4978 +primID: 6 +startangle_c: 15 +endpose_c: 0 0 0 +additionalactioncostmult: 200 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0000 0.0000 5.2360 +0.0000 0.0000 4.5815 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.2725 +0.0000 0.0000 2.6180 +0.0000 0.0000 1.9635 +0.0000 0.0000 1.3090 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.0000 diff --git a/mir_robot/mir_navigation/mprim/unicycle_5cm_noreverse_trolley.mprim b/mir_robot/mir_navigation/mprim/unicycle_5cm_noreverse_trolley.mprim new file mode 100755 index 0000000..596f5c5 --- /dev/null +++ b/mir_robot/mir_navigation/mprim/unicycle_5cm_noreverse_trolley.mprim @@ -0,0 +1,2403 @@ +resolution_m: 0.050000 +numberofangles: 16 +totalnumberofprimitives: 160 +primID: 0 +startangle_c: 0 +endpose_c: 1 0 0 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0056 0.0000 0.0000 +0.0111 0.0000 0.0000 +0.0167 0.0000 0.0000 +0.0222 0.0000 0.0000 +0.0278 0.0000 0.0000 +0.0333 0.0000 0.0000 +0.0389 0.0000 0.0000 +0.0444 0.0000 0.0000 +0.0500 0.0000 0.0000 +primID: 1 +startangle_c: 0 +endpose_c: 8 0 0 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0444 0.0000 0.0000 +0.0889 0.0000 0.0000 +0.1333 0.0000 0.0000 +0.1778 0.0000 0.0000 +0.2222 0.0000 0.0000 +0.2667 0.0000 0.0000 +0.3111 0.0000 0.0000 +0.3556 0.0000 0.0000 +0.4000 0.0000 0.0000 +primID: 2 +startangle_c: 0 +endpose_c: 16 4 1 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0904 0.0095 0.0349 +0.1806 0.0222 0.0699 +0.2707 0.0381 0.1048 +0.3604 0.0572 0.1398 +0.4496 0.0795 0.1747 +0.5383 0.1050 0.2097 +0.6264 0.1335 0.2446 +0.7136 0.1652 0.2796 +0.8000 0.2000 0.3145 +primID: 3 +startangle_c: 0 +endpose_c: 16 -4 -1 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0904 -0.0095 -0.0349 +0.1806 -0.0222 -0.0699 +0.2707 -0.0381 -0.1048 +0.3604 -0.0572 -0.1398 +0.4496 -0.0795 -0.1747 +0.5383 -0.1050 -0.2097 +0.6264 -0.1335 -0.2446 +0.7136 -0.1652 -0.2796 +0.8000 -0.2000 -0.3145 +primID: 4 +startangle_c: 0 +endpose_c: 5 2 1 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0280 0.0085 0.0223 +0.0559 0.0177 0.0445 +0.0839 0.0275 0.0668 +0.1117 0.0380 0.0890 +0.1396 0.0491 0.1113 +0.1673 0.0609 0.1335 +0.1950 0.0733 0.1558 +0.2225 0.0863 0.1781 +0.2500 0.1000 0.2003 +primID: 5 +startangle_c: 0 +endpose_c: 5 -2 -1 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0280 -0.0085 -0.0223 +0.0559 -0.0177 -0.0445 +0.0839 -0.0275 -0.0668 +0.1117 -0.0380 -0.0890 +0.1396 -0.0491 -0.1113 +0.1673 -0.0609 -0.1335 +0.1950 -0.0733 -0.1558 +0.2225 -0.0863 -0.1781 +0.2500 -0.1000 -0.2003 +primID: 6 +startangle_c: 0 +endpose_c: 0 0 1 +additionalactioncostmult: 1000 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0000 0.0000 0.0436 +0.0000 0.0000 0.0873 +0.0000 0.0000 0.1309 +0.0000 0.0000 0.1745 +0.0000 0.0000 0.2182 +0.0000 0.0000 0.2618 +0.0000 0.0000 0.3054 +0.0000 0.0000 0.3491 +0.0000 0.0000 0.3927 +primID: 7 +startangle_c: 0 +endpose_c: 0 0 -1 +additionalactioncostmult: 1000 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0000 0.0000 -0.0436 +0.0000 0.0000 -0.0873 +0.0000 0.0000 -0.1309 +0.0000 0.0000 -0.1745 +0.0000 0.0000 -0.2182 +0.0000 0.0000 -0.2618 +0.0000 0.0000 -0.3054 +0.0000 0.0000 -0.3491 +0.0000 0.0000 -0.3927 +primID: 8 +startangle_c: 0 +endpose_c: 8 1 0 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0444 0.0056 0.0000 +0.0889 0.0111 0.0000 +0.1333 0.0167 0.0000 +0.1778 0.0222 0.0000 +0.2222 0.0278 0.0000 +0.2667 0.0333 0.0000 +0.3111 0.0389 0.0000 +0.3556 0.0444 0.0000 +0.4000 0.0500 0.0000 +primID: 9 +startangle_c: 0 +endpose_c: 8 -1 0 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0444 -0.0056 0.0000 +0.0889 -0.0111 0.0000 +0.1333 -0.0167 0.0000 +0.1778 -0.0222 0.0000 +0.2222 -0.0278 0.0000 +0.2667 -0.0333 0.0000 +0.3111 -0.0389 0.0000 +0.3556 -0.0444 0.0000 +0.4000 -0.0500 0.0000 +primID: 0 +startangle_c: 1 +endpose_c: 2 1 1 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0111 0.0056 0.3927 +0.0222 0.0111 0.3927 +0.0333 0.0167 0.3927 +0.0444 0.0222 0.3927 +0.0556 0.0278 0.3927 +0.0667 0.0333 0.3927 +0.0778 0.0389 0.3927 +0.0889 0.0444 0.3927 +0.1000 0.0500 0.3927 +primID: 1 +startangle_c: 1 +endpose_c: 6 3 1 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0333 0.0167 0.3927 +0.0667 0.0333 0.3927 +0.1000 0.0500 0.3927 +0.1333 0.0667 0.3927 +0.1667 0.0833 0.3927 +0.2000 0.1000 0.3927 +0.2333 0.1167 0.3927 +0.2667 0.1333 0.3927 +0.3000 0.1500 0.3927 +primID: 2 +startangle_c: 1 +endpose_c: 13 9 2 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0793 0.0378 0.4329 +0.1572 0.0787 0.4732 +0.2334 0.1229 0.5134 +0.3079 0.1701 0.5537 +0.3805 0.2204 0.5939 +0.4512 0.2736 0.6342 +0.5197 0.3296 0.6744 +0.5860 0.3885 0.7147 +0.6500 0.4500 0.7549 +primID: 3 +startangle_c: 1 +endpose_c: 14 3 0 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0741 0.0305 0.3774 +0.1493 0.0582 0.3302 +0.2256 0.0824 0.2830 +0.3031 0.1030 0.2359 +0.3814 0.1199 0.1887 +0.4604 0.1330 0.1415 +0.5400 0.1424 0.0943 +0.6199 0.1481 0.0472 +0.7000 0.1500 -0.0000 +primID: 4 +startangle_c: 1 +endpose_c: 5 4 2 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0298 0.0184 0.4230 +0.0592 0.0379 0.4533 +0.0881 0.0583 0.4836 +0.1165 0.0796 0.5139 +0.1444 0.1019 0.5442 +0.1717 0.1251 0.5745 +0.1984 0.1492 0.6048 +0.2245 0.1742 0.6351 +0.2500 0.2000 0.6654 +primID: 5 +startangle_c: 1 +endpose_c: 6 1 0 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0320 0.0105 0.3551 +0.0644 0.0197 0.3174 +0.0973 0.0278 0.2798 +0.1304 0.0346 0.2421 +0.1639 0.0402 0.2045 +0.1977 0.0446 0.1669 +0.2316 0.0476 0.1292 +0.2658 0.0495 0.0916 +0.3000 0.0500 0.0540 +primID: 6 +startangle_c: 1 +endpose_c: 0 0 2 +additionalactioncostmult: 1000 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0000 0.0000 0.4363 +0.0000 0.0000 0.4800 +0.0000 0.0000 0.5236 +0.0000 0.0000 0.5672 +0.0000 0.0000 0.6109 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.6981 +0.0000 0.0000 0.7418 +0.0000 0.0000 0.7854 +primID: 7 +startangle_c: 1 +endpose_c: 0 0 0 +additionalactioncostmult: 1000 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0000 0.0000 0.3491 +0.0000 0.0000 0.3054 +0.0000 0.0000 0.2618 +0.0000 0.0000 0.2182 +0.0000 0.0000 0.1745 +0.0000 0.0000 0.1309 +0.0000 0.0000 0.0873 +0.0000 0.0000 0.0436 +0.0000 0.0000 0.0000 +primID: 8 +startangle_c: 1 +endpose_c: 7 2 1 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0389 0.0111 0.3927 +0.0778 0.0222 0.3927 +0.1167 0.0333 0.3927 +0.1556 0.0444 0.3927 +0.1944 0.0556 0.3927 +0.2333 0.0667 0.3927 +0.2722 0.0778 0.3927 +0.3111 0.0889 0.3927 +0.3500 0.1000 0.3927 +primID: 9 +startangle_c: 1 +endpose_c: 5 4 1 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0278 0.0222 0.3927 +0.0556 0.0444 0.3927 +0.0833 0.0667 0.3927 +0.1111 0.0889 0.3927 +0.1389 0.1111 0.3927 +0.1667 0.1333 0.3927 +0.1944 0.1556 0.3927 +0.2222 0.1778 0.3927 +0.2500 0.2000 0.3927 +primID: 0 +startangle_c: 2 +endpose_c: 1 1 2 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0056 0.0056 0.7854 +0.0111 0.0111 0.7854 +0.0167 0.0167 0.7854 +0.0222 0.0222 0.7854 +0.0278 0.0278 0.7854 +0.0333 0.0333 0.7854 +0.0389 0.0389 0.7854 +0.0444 0.0444 0.7854 +0.0500 0.0500 0.7854 +primID: 1 +startangle_c: 2 +endpose_c: 6 6 2 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0333 0.0333 0.7854 +0.0667 0.0667 0.7854 +0.1000 0.1000 0.7854 +0.1333 0.1333 0.7854 +0.1667 0.1667 0.7854 +0.2000 0.2000 0.7854 +0.2333 0.2333 0.7854 +0.2667 0.2667 0.7854 +0.3000 0.3000 0.7854 +primID: 2 +startangle_c: 2 +endpose_c: 11 14 3 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0705 0.0705 0.7854 +0.1411 0.1411 0.7854 +0.2116 0.2116 0.7854 +0.2816 0.2828 0.8201 +0.3469 0.3581 0.8917 +0.4068 0.4379 0.9633 +0.4607 0.5218 1.0349 +0.5086 0.6093 1.1065 +0.5500 0.7000 1.1781 +primID: 3 +startangle_c: 2 +endpose_c: 14 11 1 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0705 0.0705 0.7854 +0.1411 0.1411 0.7854 +0.2116 0.2116 0.7854 +0.2828 0.2816 0.7507 +0.3581 0.3469 0.6791 +0.4379 0.4068 0.6075 +0.5218 0.4607 0.5359 +0.6093 0.5086 0.4643 +0.7000 0.5500 0.3927 +primID: 4 +startangle_c: 2 +endpose_c: 4 6 3 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0278 0.0292 0.8288 +0.0543 0.0595 0.8722 +0.0795 0.0910 0.9156 +0.1033 0.1235 0.9590 +0.1257 0.1571 1.0024 +0.1466 0.1916 1.0458 +0.1659 0.2269 1.0892 +0.1838 0.2631 1.1326 +0.2000 0.3000 1.1760 +primID: 5 +startangle_c: 2 +endpose_c: 6 4 1 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0292 0.0278 0.7420 +0.0595 0.0543 0.6986 +0.0910 0.0795 0.6552 +0.1235 0.1033 0.6118 +0.1571 0.1257 0.5684 +0.1916 0.1466 0.5250 +0.2269 0.1659 0.4816 +0.2631 0.1838 0.4382 +0.3000 0.2000 0.3948 +primID: 6 +startangle_c: 2 +endpose_c: 0 0 3 +additionalactioncostmult: 1000 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0000 0.0000 0.8290 +0.0000 0.0000 0.8727 +0.0000 0.0000 0.9163 +0.0000 0.0000 0.9599 +0.0000 0.0000 1.0036 +0.0000 0.0000 1.0472 +0.0000 0.0000 1.0908 +0.0000 0.0000 1.1345 +0.0000 0.0000 1.1781 +primID: 7 +startangle_c: 2 +endpose_c: 0 0 1 +additionalactioncostmult: 1000 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0000 0.0000 0.7418 +0.0000 0.0000 0.6981 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.6109 +0.0000 0.0000 0.5672 +0.0000 0.0000 0.5236 +0.0000 0.0000 0.4800 +0.0000 0.0000 0.4363 +0.0000 0.0000 0.3927 +primID: 8 +startangle_c: 2 +endpose_c: 6 7 2 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0333 0.0389 0.7854 +0.0667 0.0778 0.7854 +0.1000 0.1167 0.7854 +0.1333 0.1556 0.7854 +0.1667 0.1944 0.7854 +0.2000 0.2333 0.7854 +0.2333 0.2722 0.7854 +0.2667 0.3111 0.7854 +0.3000 0.3500 0.7854 +primID: 9 +startangle_c: 2 +endpose_c: 7 6 2 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0389 0.0333 0.7854 +0.0778 0.0667 0.7854 +0.1167 0.1000 0.7854 +0.1556 0.1333 0.7854 +0.1944 0.1667 0.7854 +0.2333 0.2000 0.7854 +0.2722 0.2333 0.7854 +0.3111 0.2667 0.7854 +0.3500 0.3000 0.7854 +primID: 0 +startangle_c: 3 +endpose_c: 1 2 3 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0056 0.0111 1.1781 +0.0111 0.0222 1.1781 +0.0167 0.0333 1.1781 +0.0222 0.0444 1.1781 +0.0278 0.0556 1.1781 +0.0333 0.0667 1.1781 +0.0389 0.0778 1.1781 +0.0444 0.0889 1.1781 +0.0500 0.1000 1.1781 +primID: 1 +startangle_c: 3 +endpose_c: 3 6 3 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0167 0.0333 1.1781 +0.0333 0.0667 1.1781 +0.0500 0.1000 1.1781 +0.0667 0.1333 1.1781 +0.0833 0.1667 1.1781 +0.1000 0.2000 1.1781 +0.1167 0.2333 1.1781 +0.1333 0.2667 1.1781 +0.1500 0.3000 1.1781 +primID: 2 +startangle_c: 3 +endpose_c: 9 13 2 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0378 0.0793 1.1378 +0.0787 0.1572 1.0976 +0.1229 0.2334 1.0574 +0.1701 0.3079 1.0171 +0.2204 0.3805 0.9769 +0.2736 0.4512 0.9366 +0.3296 0.5197 0.8964 +0.3885 0.5860 0.8561 +0.4500 0.6500 0.8159 +primID: 3 +startangle_c: 3 +endpose_c: 3 14 4 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0305 0.0741 1.1934 +0.0582 0.1493 1.2406 +0.0824 0.2256 1.2878 +0.1030 0.3031 1.3349 +0.1199 0.3814 1.3821 +0.1330 0.4604 1.4293 +0.1424 0.5400 1.4765 +0.1481 0.6199 1.5236 +0.1500 0.7000 1.5708 +primID: 4 +startangle_c: 3 +endpose_c: 4 5 2 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0184 0.0298 1.1478 +0.0379 0.0592 1.1175 +0.0583 0.0881 1.0872 +0.0796 0.1165 1.0569 +0.1019 0.1444 1.0266 +0.1251 0.1717 0.9963 +0.1492 0.1984 0.9660 +0.1742 0.2245 0.9357 +0.2000 0.2500 0.9054 +primID: 5 +startangle_c: 3 +endpose_c: 1 6 4 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0105 0.0320 1.2157 +0.0197 0.0644 1.2534 +0.0278 0.0973 1.2910 +0.0346 0.1304 1.3286 +0.0402 0.1639 1.3663 +0.0446 0.1977 1.4039 +0.0476 0.2316 1.4416 +0.0495 0.2658 1.4792 +0.0500 0.3000 1.5168 +primID: 6 +startangle_c: 3 +endpose_c: 0 0 2 +additionalactioncostmult: 1000 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0000 0.0000 1.1345 +0.0000 0.0000 1.0908 +0.0000 0.0000 1.0472 +0.0000 0.0000 1.0036 +0.0000 0.0000 0.9599 +0.0000 0.0000 0.9163 +0.0000 0.0000 0.8727 +0.0000 0.0000 0.8290 +0.0000 0.0000 0.7854 +primID: 7 +startangle_c: 3 +endpose_c: 0 0 4 +additionalactioncostmult: 1000 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0000 0.0000 1.2217 +0.0000 0.0000 1.2654 +0.0000 0.0000 1.3090 +0.0000 0.0000 1.3526 +0.0000 0.0000 1.3963 +0.0000 0.0000 1.4399 +0.0000 0.0000 1.4835 +0.0000 0.0000 1.5272 +0.0000 0.0000 1.5708 +primID: 8 +startangle_c: 3 +endpose_c: 2 7 3 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0111 0.0389 1.1781 +0.0222 0.0778 1.1781 +0.0333 0.1167 1.1781 +0.0444 0.1556 1.1781 +0.0556 0.1944 1.1781 +0.0667 0.2333 1.1781 +0.0778 0.2722 1.1781 +0.0889 0.3111 1.1781 +0.1000 0.3500 1.1781 +primID: 9 +startangle_c: 3 +endpose_c: 4 5 3 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0222 0.0278 1.1781 +0.0444 0.0556 1.1781 +0.0667 0.0833 1.1781 +0.0889 0.1111 1.1781 +0.1111 0.1389 1.1781 +0.1333 0.1667 1.1781 +0.1556 0.1944 1.1781 +0.1778 0.2222 1.1781 +0.2000 0.2500 1.1781 +primID: 0 +startangle_c: 4 +endpose_c: 0 1 4 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0056 1.5708 +0.0000 0.0111 1.5708 +0.0000 0.0167 1.5708 +0.0000 0.0222 1.5708 +0.0000 0.0278 1.5708 +0.0000 0.0333 1.5708 +0.0000 0.0389 1.5708 +0.0000 0.0444 1.5708 +0.0000 0.0500 1.5708 +primID: 1 +startangle_c: 4 +endpose_c: 0 8 4 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0444 1.5708 +0.0000 0.0889 1.5708 +0.0000 0.1333 1.5708 +0.0000 0.1778 1.5708 +0.0000 0.2222 1.5708 +0.0000 0.2667 1.5708 +0.0000 0.3111 1.5708 +0.0000 0.3556 1.5708 +0.0000 0.4000 1.5708 +primID: 2 +startangle_c: 4 +endpose_c: -4 16 5 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.5708 +-0.0095 0.0904 1.6057 +-0.0222 0.1806 1.6407 +-0.0381 0.2707 1.6756 +-0.0572 0.3604 1.7106 +-0.0795 0.4496 1.7455 +-0.1050 0.5383 1.7805 +-0.1335 0.6264 1.8154 +-0.1652 0.7136 1.8503 +-0.2000 0.8000 1.8853 +primID: 3 +startangle_c: 4 +endpose_c: 4 16 3 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0095 0.0904 1.5359 +0.0222 0.1806 1.5009 +0.0381 0.2707 1.4660 +0.0572 0.3604 1.4310 +0.0795 0.4496 1.3961 +0.1050 0.5383 1.3611 +0.1335 0.6264 1.3262 +0.1652 0.7136 1.2912 +0.2000 0.8000 1.2563 +primID: 4 +startangle_c: 4 +endpose_c: -2 5 5 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.5708 +-0.0085 0.0280 1.5931 +-0.0177 0.0559 1.6153 +-0.0275 0.0839 1.6376 +-0.0380 0.1117 1.6598 +-0.0491 0.1396 1.6821 +-0.0609 0.1673 1.7043 +-0.0733 0.1950 1.7266 +-0.0863 0.2225 1.7489 +-0.1000 0.2500 1.7711 +primID: 5 +startangle_c: 4 +endpose_c: 2 5 3 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0085 0.0280 1.5485 +0.0177 0.0559 1.5263 +0.0275 0.0839 1.5040 +0.0380 0.1117 1.4818 +0.0491 0.1396 1.4595 +0.0609 0.1673 1.4373 +0.0733 0.1950 1.4150 +0.0863 0.2225 1.3927 +0.1000 0.2500 1.3705 +primID: 6 +startangle_c: 4 +endpose_c: 0 0 5 +additionalactioncostmult: 1000 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0000 1.6144 +0.0000 0.0000 1.6581 +0.0000 0.0000 1.7017 +0.0000 0.0000 1.7453 +0.0000 0.0000 1.7890 +0.0000 0.0000 1.8326 +0.0000 0.0000 1.8762 +0.0000 0.0000 1.9199 +0.0000 0.0000 1.9635 +primID: 7 +startangle_c: 4 +endpose_c: 0 0 3 +additionalactioncostmult: 1000 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0000 1.5272 +0.0000 0.0000 1.4835 +0.0000 0.0000 1.4399 +0.0000 0.0000 1.3963 +0.0000 0.0000 1.3526 +0.0000 0.0000 1.3090 +0.0000 0.0000 1.2654 +0.0000 0.0000 1.2217 +0.0000 0.0000 1.1781 +primID: 8 +startangle_c: 4 +endpose_c: -1 8 4 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 1.5708 +-0.0056 0.0444 1.5708 +-0.0111 0.0889 1.5708 +-0.0167 0.1333 1.5708 +-0.0222 0.1778 1.5708 +-0.0278 0.2222 1.5708 +-0.0333 0.2667 1.5708 +-0.0389 0.3111 1.5708 +-0.0444 0.3556 1.5708 +-0.0500 0.4000 1.5708 +primID: 9 +startangle_c: 4 +endpose_c: 1 8 4 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0056 0.0444 1.5708 +0.0111 0.0889 1.5708 +0.0167 0.1333 1.5708 +0.0222 0.1778 1.5708 +0.0278 0.2222 1.5708 +0.0333 0.2667 1.5708 +0.0389 0.3111 1.5708 +0.0444 0.3556 1.5708 +0.0500 0.4000 1.5708 +primID: 0 +startangle_c: 5 +endpose_c: -1 2 5 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0056 0.0111 1.9635 +-0.0111 0.0222 1.9635 +-0.0167 0.0333 1.9635 +-0.0222 0.0444 1.9635 +-0.0278 0.0556 1.9635 +-0.0333 0.0667 1.9635 +-0.0389 0.0778 1.9635 +-0.0444 0.0889 1.9635 +-0.0500 0.1000 1.9635 +primID: 1 +startangle_c: 5 +endpose_c: -3 6 5 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0167 0.0333 1.9635 +-0.0333 0.0667 1.9635 +-0.0500 0.1000 1.9635 +-0.0667 0.1333 1.9635 +-0.0833 0.1667 1.9635 +-0.1000 0.2000 1.9635 +-0.1167 0.2333 1.9635 +-0.1333 0.2667 1.9635 +-0.1500 0.3000 1.9635 +primID: 2 +startangle_c: 5 +endpose_c: -9 13 6 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0378 0.0793 2.0037 +-0.0787 0.1572 2.0440 +-0.1229 0.2334 2.0842 +-0.1701 0.3079 2.1245 +-0.2204 0.3805 2.1647 +-0.2736 0.4512 2.2050 +-0.3296 0.5197 2.2452 +-0.3885 0.5860 2.2855 +-0.4500 0.6500 2.3257 +primID: 3 +startangle_c: 5 +endpose_c: -3 14 4 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0305 0.0741 1.9482 +-0.0582 0.1493 1.9010 +-0.0824 0.2256 1.8538 +-0.1030 0.3031 1.8067 +-0.1199 0.3814 1.7595 +-0.1330 0.4604 1.7123 +-0.1424 0.5400 1.6651 +-0.1481 0.6199 1.6180 +-0.1500 0.7000 1.5708 +primID: 4 +startangle_c: 5 +endpose_c: -4 5 6 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0184 0.0298 1.9938 +-0.0379 0.0592 2.0241 +-0.0583 0.0881 2.0544 +-0.0796 0.1165 2.0847 +-0.1019 0.1444 2.1150 +-0.1251 0.1717 2.1453 +-0.1492 0.1984 2.1756 +-0.1742 0.2245 2.2059 +-0.2000 0.2500 2.2362 +primID: 5 +startangle_c: 5 +endpose_c: -1 6 4 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0105 0.0320 1.9259 +-0.0197 0.0644 1.8882 +-0.0278 0.0973 1.8506 +-0.0346 0.1304 1.8129 +-0.0402 0.1639 1.7753 +-0.0446 0.1977 1.7377 +-0.0476 0.2316 1.7000 +-0.0495 0.2658 1.6624 +-0.0500 0.3000 1.6248 +primID: 6 +startangle_c: 5 +endpose_c: 0 0 6 +additionalactioncostmult: 1000 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0000 0.0000 2.0071 +0.0000 0.0000 2.0508 +0.0000 0.0000 2.0944 +0.0000 0.0000 2.1380 +0.0000 0.0000 2.1817 +0.0000 0.0000 2.2253 +0.0000 0.0000 2.2689 +0.0000 0.0000 2.3126 +0.0000 0.0000 2.3562 +primID: 7 +startangle_c: 5 +endpose_c: 0 0 4 +additionalactioncostmult: 1000 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0000 0.0000 1.9199 +0.0000 0.0000 1.8762 +0.0000 0.0000 1.8326 +0.0000 0.0000 1.7890 +0.0000 0.0000 1.7453 +0.0000 0.0000 1.7017 +0.0000 0.0000 1.6581 +0.0000 0.0000 1.6144 +0.0000 0.0000 1.5708 +primID: 8 +startangle_c: 5 +endpose_c: -2 7 5 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0111 0.0389 1.9635 +-0.0222 0.0778 1.9635 +-0.0333 0.1167 1.9635 +-0.0444 0.1556 1.9635 +-0.0556 0.1944 1.9635 +-0.0667 0.2333 1.9635 +-0.0778 0.2722 1.9635 +-0.0889 0.3111 1.9635 +-0.1000 0.3500 1.9635 +primID: 9 +startangle_c: 5 +endpose_c: -4 5 5 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0222 0.0278 1.9635 +-0.0444 0.0556 1.9635 +-0.0667 0.0833 1.9635 +-0.0889 0.1111 1.9635 +-0.1111 0.1389 1.9635 +-0.1333 0.1667 1.9635 +-0.1556 0.1944 1.9635 +-0.1778 0.2222 1.9635 +-0.2000 0.2500 1.9635 +primID: 0 +startangle_c: 6 +endpose_c: -1 1 6 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0056 0.0056 2.3562 +-0.0111 0.0111 2.3562 +-0.0167 0.0167 2.3562 +-0.0222 0.0222 2.3562 +-0.0278 0.0278 2.3562 +-0.0333 0.0333 2.3562 +-0.0389 0.0389 2.3562 +-0.0444 0.0444 2.3562 +-0.0500 0.0500 2.3562 +primID: 1 +startangle_c: 6 +endpose_c: -6 6 6 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0333 0.0333 2.3562 +-0.0667 0.0667 2.3562 +-0.1000 0.1000 2.3562 +-0.1333 0.1333 2.3562 +-0.1667 0.1667 2.3562 +-0.2000 0.2000 2.3562 +-0.2333 0.2333 2.3562 +-0.2667 0.2667 2.3562 +-0.3000 0.3000 2.3562 +primID: 2 +startangle_c: 6 +endpose_c: -14 11 7 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0705 0.0705 2.3562 +-0.1411 0.1411 2.3562 +-0.2116 0.2116 2.3562 +-0.2828 0.2816 2.3909 +-0.3581 0.3469 2.4625 +-0.4379 0.4068 2.5341 +-0.5218 0.4607 2.6057 +-0.6093 0.5086 2.6773 +-0.7000 0.5500 2.7489 +primID: 3 +startangle_c: 6 +endpose_c: -11 14 5 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0705 0.0705 2.3562 +-0.1411 0.1411 2.3562 +-0.2116 0.2116 2.3562 +-0.2816 0.2828 2.3215 +-0.3469 0.3581 2.2499 +-0.4068 0.4379 2.1783 +-0.4607 0.5218 2.1067 +-0.5086 0.6093 2.0351 +-0.5500 0.7000 1.9635 +primID: 4 +startangle_c: 6 +endpose_c: -6 4 7 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0292 0.0278 2.3996 +-0.0595 0.0543 2.4430 +-0.0910 0.0795 2.4864 +-0.1235 0.1033 2.5298 +-0.1571 0.1257 2.5732 +-0.1916 0.1466 2.6166 +-0.2269 0.1659 2.6600 +-0.2631 0.1838 2.7034 +-0.3000 0.2000 2.7468 +primID: 5 +startangle_c: 6 +endpose_c: -4 6 5 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0278 0.0292 2.3128 +-0.0543 0.0595 2.2694 +-0.0795 0.0910 2.2260 +-0.1033 0.1235 2.1826 +-0.1257 0.1571 2.1392 +-0.1466 0.1916 2.0958 +-0.1659 0.2269 2.0524 +-0.1838 0.2631 2.0090 +-0.2000 0.3000 1.9656 +primID: 6 +startangle_c: 6 +endpose_c: 0 0 7 +additionalactioncostmult: 1000 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0000 0.0000 2.3998 +0.0000 0.0000 2.4435 +0.0000 0.0000 2.4871 +0.0000 0.0000 2.5307 +0.0000 0.0000 2.5744 +0.0000 0.0000 2.6180 +0.0000 0.0000 2.6616 +0.0000 0.0000 2.7053 +0.0000 0.0000 2.7489 +primID: 7 +startangle_c: 6 +endpose_c: 0 0 5 +additionalactioncostmult: 1000 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0000 0.0000 2.3126 +0.0000 0.0000 2.2689 +0.0000 0.0000 2.2253 +0.0000 0.0000 2.1817 +0.0000 0.0000 2.1380 +0.0000 0.0000 2.0944 +0.0000 0.0000 2.0508 +0.0000 0.0000 2.0071 +0.0000 0.0000 1.9635 +primID: 8 +startangle_c: 6 +endpose_c: -7 6 6 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0389 0.0333 2.3562 +-0.0778 0.0667 2.3562 +-0.1167 0.1000 2.3562 +-0.1556 0.1333 2.3562 +-0.1944 0.1667 2.3562 +-0.2333 0.2000 2.3562 +-0.2722 0.2333 2.3562 +-0.3111 0.2667 2.3562 +-0.3500 0.3000 2.3562 +primID: 9 +startangle_c: 6 +endpose_c: -6 7 6 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0333 0.0389 2.3562 +-0.0667 0.0778 2.3562 +-0.1000 0.1167 2.3562 +-0.1333 0.1556 2.3562 +-0.1667 0.1944 2.3562 +-0.2000 0.2333 2.3562 +-0.2333 0.2722 2.3562 +-0.2667 0.3111 2.3562 +-0.3000 0.3500 2.3562 +primID: 0 +startangle_c: 7 +endpose_c: -2 1 7 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0111 0.0056 2.7489 +-0.0222 0.0111 2.7489 +-0.0333 0.0167 2.7489 +-0.0444 0.0222 2.7489 +-0.0556 0.0278 2.7489 +-0.0667 0.0333 2.7489 +-0.0778 0.0389 2.7489 +-0.0889 0.0444 2.7489 +-0.1000 0.0500 2.7489 +primID: 1 +startangle_c: 7 +endpose_c: -6 3 7 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0333 0.0167 2.7489 +-0.0667 0.0333 2.7489 +-0.1000 0.0500 2.7489 +-0.1333 0.0667 2.7489 +-0.1667 0.0833 2.7489 +-0.2000 0.1000 2.7489 +-0.2333 0.1167 2.7489 +-0.2667 0.1333 2.7489 +-0.3000 0.1500 2.7489 +primID: 2 +startangle_c: 7 +endpose_c: -13 9 6 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0793 0.0378 2.7086 +-0.1572 0.0787 2.6684 +-0.2334 0.1229 2.6281 +-0.3079 0.1701 2.5879 +-0.3805 0.2204 2.5477 +-0.4512 0.2736 2.5074 +-0.5197 0.3296 2.4672 +-0.5860 0.3885 2.4269 +-0.6500 0.4500 2.3867 +primID: 3 +startangle_c: 7 +endpose_c: -14 3 8 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0741 0.0305 2.7642 +-0.1493 0.0582 2.8114 +-0.2256 0.0824 2.8586 +-0.3031 0.1030 2.9057 +-0.3814 0.1199 2.9529 +-0.4604 0.1330 3.0001 +-0.5400 0.1424 3.0472 +-0.6199 0.1481 3.0944 +-0.7000 0.1500 3.1416 +primID: 4 +startangle_c: 7 +endpose_c: -5 4 6 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0298 0.0184 2.7186 +-0.0592 0.0379 2.6883 +-0.0881 0.0583 2.6580 +-0.1165 0.0796 2.6277 +-0.1444 0.1019 2.5974 +-0.1717 0.1251 2.5671 +-0.1984 0.1492 2.5368 +-0.2245 0.1742 2.5065 +-0.2500 0.2000 2.4762 +primID: 5 +startangle_c: 7 +endpose_c: -6 1 8 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0320 0.0105 2.7865 +-0.0644 0.0197 2.8242 +-0.0973 0.0278 2.8618 +-0.1304 0.0346 2.8994 +-0.1639 0.0402 2.9371 +-0.1977 0.0446 2.9747 +-0.2316 0.0476 3.0124 +-0.2658 0.0495 3.0500 +-0.3000 0.0500 3.0876 +primID: 6 +startangle_c: 7 +endpose_c: 0 0 6 +additionalactioncostmult: 1000 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0000 0.0000 2.7053 +0.0000 0.0000 2.6616 +0.0000 0.0000 2.6180 +0.0000 0.0000 2.5744 +0.0000 0.0000 2.5307 +0.0000 0.0000 2.4871 +0.0000 0.0000 2.4435 +0.0000 0.0000 2.3998 +0.0000 0.0000 2.3562 +primID: 7 +startangle_c: 7 +endpose_c: 0 0 8 +additionalactioncostmult: 1000 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0000 0.0000 2.7925 +0.0000 0.0000 2.8362 +0.0000 0.0000 2.8798 +0.0000 0.0000 2.9234 +0.0000 0.0000 2.9671 +0.0000 0.0000 3.0107 +0.0000 0.0000 3.0543 +0.0000 0.0000 3.0980 +0.0000 0.0000 3.1416 +primID: 8 +startangle_c: 7 +endpose_c: -7 2 7 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0389 0.0111 2.7489 +-0.0778 0.0222 2.7489 +-0.1167 0.0333 2.7489 +-0.1556 0.0444 2.7489 +-0.1944 0.0556 2.7489 +-0.2333 0.0667 2.7489 +-0.2722 0.0778 2.7489 +-0.3111 0.0889 2.7489 +-0.3500 0.1000 2.7489 +primID: 9 +startangle_c: 7 +endpose_c: -5 4 7 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0278 0.0222 2.7489 +-0.0556 0.0444 2.7489 +-0.0833 0.0667 2.7489 +-0.1111 0.0889 2.7489 +-0.1389 0.1111 2.7489 +-0.1667 0.1333 2.7489 +-0.1944 0.1556 2.7489 +-0.2222 0.1778 2.7489 +-0.2500 0.2000 2.7489 +primID: 0 +startangle_c: 8 +endpose_c: -1 0 8 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0056 0.0000 3.1416 +-0.0111 0.0000 3.1416 +-0.0167 0.0000 3.1416 +-0.0222 0.0000 3.1416 +-0.0278 0.0000 3.1416 +-0.0333 0.0000 3.1416 +-0.0389 0.0000 3.1416 +-0.0444 0.0000 3.1416 +-0.0500 0.0000 3.1416 +primID: 1 +startangle_c: 8 +endpose_c: -8 0 8 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0444 0.0000 3.1416 +-0.0889 0.0000 3.1416 +-0.1333 0.0000 3.1416 +-0.1778 0.0000 3.1416 +-0.2222 0.0000 3.1416 +-0.2667 0.0000 3.1416 +-0.3111 0.0000 3.1416 +-0.3556 0.0000 3.1416 +-0.4000 0.0000 3.1416 +primID: 2 +startangle_c: 8 +endpose_c: -16 -4 9 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0904 -0.0095 3.1765 +-0.1806 -0.0222 3.2115 +-0.2707 -0.0381 3.2464 +-0.3604 -0.0572 3.2814 +-0.4496 -0.0795 3.3163 +-0.5383 -0.1050 3.3513 +-0.6264 -0.1335 3.3862 +-0.7136 -0.1652 3.4211 +-0.8000 -0.2000 3.4561 +primID: 3 +startangle_c: 8 +endpose_c: -16 4 7 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0904 0.0095 3.1066 +-0.1806 0.0222 3.0717 +-0.2707 0.0381 3.0368 +-0.3604 0.0572 3.0018 +-0.4496 0.0795 2.9669 +-0.5383 0.1050 2.9319 +-0.6264 0.1335 2.8970 +-0.7136 0.1652 2.8620 +-0.8000 0.2000 2.8271 +primID: 4 +startangle_c: 8 +endpose_c: -5 -2 9 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0280 -0.0085 3.1639 +-0.0559 -0.0177 3.1861 +-0.0839 -0.0275 3.2084 +-0.1117 -0.0380 3.2306 +-0.1396 -0.0491 3.2529 +-0.1673 -0.0609 3.2751 +-0.1950 -0.0733 3.2974 +-0.2225 -0.0863 3.3197 +-0.2500 -0.1000 3.3419 +primID: 5 +startangle_c: 8 +endpose_c: -5 2 7 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0280 0.0085 3.1193 +-0.0559 0.0177 3.0971 +-0.0839 0.0275 3.0748 +-0.1117 0.0380 3.0526 +-0.1396 0.0491 3.0303 +-0.1673 0.0609 3.0080 +-0.1950 0.0733 2.9858 +-0.2225 0.0863 2.9635 +-0.2500 0.1000 2.9413 +primID: 6 +startangle_c: 8 +endpose_c: 0 0 9 +additionalactioncostmult: 1000 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0000 0.0000 3.1852 +0.0000 0.0000 3.2289 +0.0000 0.0000 3.2725 +0.0000 0.0000 3.3161 +0.0000 0.0000 3.3598 +0.0000 0.0000 3.4034 +0.0000 0.0000 3.4470 +0.0000 0.0000 3.4907 +0.0000 0.0000 3.5343 +primID: 7 +startangle_c: 8 +endpose_c: 0 0 7 +additionalactioncostmult: 1000 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0000 0.0000 3.0980 +0.0000 0.0000 3.0543 +0.0000 0.0000 3.0107 +0.0000 0.0000 2.9671 +0.0000 0.0000 2.9234 +0.0000 0.0000 2.8798 +0.0000 0.0000 2.8362 +0.0000 0.0000 2.7925 +0.0000 0.0000 2.7489 +primID: 8 +startangle_c: 8 +endpose_c: -8 -1 8 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0444 -0.0056 3.1416 +-0.0889 -0.0111 3.1416 +-0.1333 -0.0167 3.1416 +-0.1778 -0.0222 3.1416 +-0.2222 -0.0278 3.1416 +-0.2667 -0.0333 3.1416 +-0.3111 -0.0389 3.1416 +-0.3556 -0.0444 3.1416 +-0.4000 -0.0500 3.1416 +primID: 9 +startangle_c: 8 +endpose_c: -8 1 8 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0444 0.0056 3.1416 +-0.0889 0.0111 3.1416 +-0.1333 0.0167 3.1416 +-0.1778 0.0222 3.1416 +-0.2222 0.0278 3.1416 +-0.2667 0.0333 3.1416 +-0.3111 0.0389 3.1416 +-0.3556 0.0444 3.1416 +-0.4000 0.0500 3.1416 +primID: 0 +startangle_c: 9 +endpose_c: -2 -1 9 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0111 -0.0056 3.5343 +-0.0222 -0.0111 3.5343 +-0.0333 -0.0167 3.5343 +-0.0444 -0.0222 3.5343 +-0.0556 -0.0278 3.5343 +-0.0667 -0.0333 3.5343 +-0.0778 -0.0389 3.5343 +-0.0889 -0.0444 3.5343 +-0.1000 -0.0500 3.5343 +primID: 1 +startangle_c: 9 +endpose_c: -6 -3 9 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0333 -0.0167 3.5343 +-0.0667 -0.0333 3.5343 +-0.1000 -0.0500 3.5343 +-0.1333 -0.0667 3.5343 +-0.1667 -0.0833 3.5343 +-0.2000 -0.1000 3.5343 +-0.2333 -0.1167 3.5343 +-0.2667 -0.1333 3.5343 +-0.3000 -0.1500 3.5343 +primID: 2 +startangle_c: 9 +endpose_c: -13 -9 10 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0793 -0.0378 3.5745 +-0.1572 -0.0787 3.6148 +-0.2334 -0.1229 3.6550 +-0.3079 -0.1701 3.6953 +-0.3805 -0.2204 3.7355 +-0.4512 -0.2736 3.7758 +-0.5197 -0.3296 3.8160 +-0.5860 -0.3885 3.8563 +-0.6500 -0.4500 3.8965 +primID: 3 +startangle_c: 9 +endpose_c: -14 -3 8 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0741 -0.0305 3.5190 +-0.1493 -0.0582 3.4718 +-0.2256 -0.0824 3.4246 +-0.3031 -0.1030 3.3775 +-0.3814 -0.1199 3.3303 +-0.4604 -0.1330 3.2831 +-0.5400 -0.1424 3.2359 +-0.6199 -0.1481 3.1888 +-0.7000 -0.1500 3.1416 +primID: 4 +startangle_c: 9 +endpose_c: -5 -4 10 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0298 -0.0184 3.5646 +-0.0592 -0.0379 3.5949 +-0.0881 -0.0583 3.6252 +-0.1165 -0.0796 3.6555 +-0.1444 -0.1019 3.6858 +-0.1717 -0.1251 3.7161 +-0.1984 -0.1492 3.7464 +-0.2245 -0.1742 3.7767 +-0.2500 -0.2000 3.8070 +primID: 5 +startangle_c: 9 +endpose_c: -6 -1 8 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0320 -0.0105 3.4967 +-0.0644 -0.0197 3.4590 +-0.0973 -0.0278 3.4214 +-0.1304 -0.0346 3.3837 +-0.1639 -0.0402 3.3461 +-0.1977 -0.0446 3.3085 +-0.2316 -0.0476 3.2708 +-0.2658 -0.0495 3.2332 +-0.3000 -0.0500 3.1955 +primID: 6 +startangle_c: 9 +endpose_c: 0 0 10 +additionalactioncostmult: 1000 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0000 0.0000 3.5779 +0.0000 0.0000 3.6216 +0.0000 0.0000 3.6652 +0.0000 0.0000 3.7088 +0.0000 0.0000 3.7525 +0.0000 0.0000 3.7961 +0.0000 0.0000 3.8397 +0.0000 0.0000 3.8834 +0.0000 0.0000 3.9270 +primID: 7 +startangle_c: 9 +endpose_c: 0 0 8 +additionalactioncostmult: 1000 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0000 0.0000 3.4907 +0.0000 0.0000 3.4470 +0.0000 0.0000 3.4034 +0.0000 0.0000 3.3598 +0.0000 0.0000 3.3161 +0.0000 0.0000 3.2725 +0.0000 0.0000 3.2289 +0.0000 0.0000 3.1852 +0.0000 0.0000 3.1416 +primID: 8 +startangle_c: 9 +endpose_c: -7 -2 9 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0389 -0.0111 3.5343 +-0.0778 -0.0222 3.5343 +-0.1167 -0.0333 3.5343 +-0.1556 -0.0444 3.5343 +-0.1944 -0.0556 3.5343 +-0.2333 -0.0667 3.5343 +-0.2722 -0.0778 3.5343 +-0.3111 -0.0889 3.5343 +-0.3500 -0.1000 3.5343 +primID: 9 +startangle_c: 9 +endpose_c: -5 -4 9 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0278 -0.0222 3.5343 +-0.0556 -0.0444 3.5343 +-0.0833 -0.0667 3.5343 +-0.1111 -0.0889 3.5343 +-0.1389 -0.1111 3.5343 +-0.1667 -0.1333 3.5343 +-0.1944 -0.1556 3.5343 +-0.2222 -0.1778 3.5343 +-0.2500 -0.2000 3.5343 +primID: 0 +startangle_c: 10 +endpose_c: -1 -1 10 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0056 -0.0056 3.9270 +-0.0111 -0.0111 3.9270 +-0.0167 -0.0167 3.9270 +-0.0222 -0.0222 3.9270 +-0.0278 -0.0278 3.9270 +-0.0333 -0.0333 3.9270 +-0.0389 -0.0389 3.9270 +-0.0444 -0.0444 3.9270 +-0.0500 -0.0500 3.9270 +primID: 1 +startangle_c: 10 +endpose_c: -6 -6 10 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0333 -0.0333 3.9270 +-0.0667 -0.0667 3.9270 +-0.1000 -0.1000 3.9270 +-0.1333 -0.1333 3.9270 +-0.1667 -0.1667 3.9270 +-0.2000 -0.2000 3.9270 +-0.2333 -0.2333 3.9270 +-0.2667 -0.2667 3.9270 +-0.3000 -0.3000 3.9270 +primID: 2 +startangle_c: 10 +endpose_c: -11 -14 11 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0705 -0.0705 3.9270 +-0.1411 -0.1411 3.9270 +-0.2116 -0.2116 3.9270 +-0.2816 -0.2828 3.9617 +-0.3469 -0.3581 4.0333 +-0.4068 -0.4379 4.1049 +-0.4607 -0.5218 4.1765 +-0.5086 -0.6093 4.2481 +-0.5500 -0.7000 4.3197 +primID: 3 +startangle_c: 10 +endpose_c: -14 -11 9 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0705 -0.0705 3.9270 +-0.1411 -0.1411 3.9270 +-0.2116 -0.2116 3.9270 +-0.2828 -0.2816 3.8923 +-0.3581 -0.3469 3.8207 +-0.4379 -0.4068 3.7491 +-0.5218 -0.4607 3.6775 +-0.6093 -0.5086 3.6059 +-0.7000 -0.5500 3.5343 +primID: 4 +startangle_c: 10 +endpose_c: -4 -6 11 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0278 -0.0292 3.9704 +-0.0543 -0.0595 4.0138 +-0.0795 -0.0910 4.0572 +-0.1033 -0.1235 4.1006 +-0.1257 -0.1571 4.1440 +-0.1466 -0.1916 4.1874 +-0.1659 -0.2269 4.2308 +-0.1838 -0.2631 4.2742 +-0.2000 -0.3000 4.3176 +primID: 5 +startangle_c: 10 +endpose_c: -6 -4 9 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0292 -0.0278 3.8836 +-0.0595 -0.0543 3.8402 +-0.0910 -0.0795 3.7968 +-0.1235 -0.1033 3.7534 +-0.1571 -0.1257 3.7100 +-0.1916 -0.1466 3.6666 +-0.2269 -0.1659 3.6232 +-0.2631 -0.1838 3.5798 +-0.3000 -0.2000 3.5364 +primID: 6 +startangle_c: 10 +endpose_c: 0 0 11 +additionalactioncostmult: 1000 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.9706 +0.0000 0.0000 4.0143 +0.0000 0.0000 4.0579 +0.0000 0.0000 4.1015 +0.0000 0.0000 4.1452 +0.0000 0.0000 4.1888 +0.0000 0.0000 4.2324 +0.0000 0.0000 4.2761 +0.0000 0.0000 4.3197 +primID: 7 +startangle_c: 10 +endpose_c: 0 0 9 +additionalactioncostmult: 1000 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.8834 +0.0000 0.0000 3.8397 +0.0000 0.0000 3.7961 +0.0000 0.0000 3.7525 +0.0000 0.0000 3.7088 +0.0000 0.0000 3.6652 +0.0000 0.0000 3.6216 +0.0000 0.0000 3.5779 +0.0000 0.0000 3.5343 +primID: 8 +startangle_c: 10 +endpose_c: -6 -7 10 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0333 -0.0389 3.9270 +-0.0667 -0.0778 3.9270 +-0.1000 -0.1167 3.9270 +-0.1333 -0.1556 3.9270 +-0.1667 -0.1944 3.9270 +-0.2000 -0.2333 3.9270 +-0.2333 -0.2722 3.9270 +-0.2667 -0.3111 3.9270 +-0.3000 -0.3500 3.9270 +primID: 9 +startangle_c: 10 +endpose_c: -7 -6 10 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0389 -0.0333 3.9270 +-0.0778 -0.0667 3.9270 +-0.1167 -0.1000 3.9270 +-0.1556 -0.1333 3.9270 +-0.1944 -0.1667 3.9270 +-0.2333 -0.2000 3.9270 +-0.2722 -0.2333 3.9270 +-0.3111 -0.2667 3.9270 +-0.3500 -0.3000 3.9270 +primID: 0 +startangle_c: 11 +endpose_c: -1 -2 11 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0056 -0.0111 4.3197 +-0.0111 -0.0222 4.3197 +-0.0167 -0.0333 4.3197 +-0.0222 -0.0444 4.3197 +-0.0278 -0.0556 4.3197 +-0.0333 -0.0667 4.3197 +-0.0389 -0.0778 4.3197 +-0.0444 -0.0889 4.3197 +-0.0500 -0.1000 4.3197 +primID: 1 +startangle_c: 11 +endpose_c: -3 -6 11 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0167 -0.0333 4.3197 +-0.0333 -0.0667 4.3197 +-0.0500 -0.1000 4.3197 +-0.0667 -0.1333 4.3197 +-0.0833 -0.1667 4.3197 +-0.1000 -0.2000 4.3197 +-0.1167 -0.2333 4.3197 +-0.1333 -0.2667 4.3197 +-0.1500 -0.3000 4.3197 +primID: 2 +startangle_c: 11 +endpose_c: -9 -13 10 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0378 -0.0793 4.2794 +-0.0787 -0.1572 4.2392 +-0.1229 -0.2334 4.1989 +-0.1701 -0.3079 4.1587 +-0.2204 -0.3805 4.1185 +-0.2736 -0.4512 4.0782 +-0.3296 -0.5197 4.0380 +-0.3885 -0.5860 3.9977 +-0.4500 -0.6500 3.9575 +primID: 3 +startangle_c: 11 +endpose_c: -3 -14 12 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0305 -0.0741 4.3350 +-0.0582 -0.1493 4.3822 +-0.0824 -0.2256 4.4294 +-0.1030 -0.3031 4.4765 +-0.1199 -0.3814 4.5237 +-0.1330 -0.4604 4.5709 +-0.1424 -0.5400 4.6180 +-0.1481 -0.6199 4.6652 +-0.1500 -0.7000 4.7124 +primID: 4 +startangle_c: 11 +endpose_c: -4 -5 10 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0184 -0.0298 4.2894 +-0.0379 -0.0592 4.2591 +-0.0583 -0.0881 4.2288 +-0.0796 -0.1165 4.1985 +-0.1019 -0.1444 4.1682 +-0.1251 -0.1717 4.1379 +-0.1492 -0.1984 4.1076 +-0.1742 -0.2245 4.0773 +-0.2000 -0.2500 4.0470 +primID: 5 +startangle_c: 11 +endpose_c: -1 -6 12 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0105 -0.0320 4.3573 +-0.0197 -0.0644 4.3950 +-0.0278 -0.0973 4.4326 +-0.0346 -0.1304 4.4702 +-0.0402 -0.1639 4.5079 +-0.0446 -0.1977 4.5455 +-0.0476 -0.2316 4.5832 +-0.0495 -0.2658 4.6208 +-0.0500 -0.3000 4.6584 +primID: 6 +startangle_c: 11 +endpose_c: 0 0 10 +additionalactioncostmult: 1000 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0000 0.0000 4.2761 +0.0000 0.0000 4.2324 +0.0000 0.0000 4.1888 +0.0000 0.0000 4.1452 +0.0000 0.0000 4.1015 +0.0000 0.0000 4.0579 +0.0000 0.0000 4.0143 +0.0000 0.0000 3.9706 +0.0000 0.0000 3.9270 +primID: 7 +startangle_c: 11 +endpose_c: 0 0 12 +additionalactioncostmult: 1000 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0000 0.0000 4.3633 +0.0000 0.0000 4.4070 +0.0000 0.0000 4.4506 +0.0000 0.0000 4.4942 +0.0000 0.0000 4.5379 +0.0000 0.0000 4.5815 +0.0000 0.0000 4.6251 +0.0000 0.0000 4.6688 +0.0000 0.0000 4.7124 +primID: 8 +startangle_c: 11 +endpose_c: -2 -7 11 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0111 -0.0389 4.3197 +-0.0222 -0.0778 4.3197 +-0.0333 -0.1167 4.3197 +-0.0444 -0.1556 4.3197 +-0.0556 -0.1944 4.3197 +-0.0667 -0.2333 4.3197 +-0.0778 -0.2722 4.3197 +-0.0889 -0.3111 4.3197 +-0.1000 -0.3500 4.3197 +primID: 9 +startangle_c: 11 +endpose_c: -4 -5 11 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0222 -0.0278 4.3197 +-0.0444 -0.0556 4.3197 +-0.0667 -0.0833 4.3197 +-0.0889 -0.1111 4.3197 +-0.1111 -0.1389 4.3197 +-0.1333 -0.1667 4.3197 +-0.1556 -0.1944 4.3197 +-0.1778 -0.2222 4.3197 +-0.2000 -0.2500 4.3197 +primID: 0 +startangle_c: 12 +endpose_c: 0 -1 12 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0056 4.7124 +0.0000 -0.0111 4.7124 +0.0000 -0.0167 4.7124 +0.0000 -0.0222 4.7124 +0.0000 -0.0278 4.7124 +0.0000 -0.0333 4.7124 +0.0000 -0.0389 4.7124 +0.0000 -0.0444 4.7124 +0.0000 -0.0500 4.7124 +primID: 1 +startangle_c: 12 +endpose_c: 0 -8 12 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0444 4.7124 +0.0000 -0.0889 4.7124 +0.0000 -0.1333 4.7124 +0.0000 -0.1778 4.7124 +0.0000 -0.2222 4.7124 +0.0000 -0.2667 4.7124 +0.0000 -0.3111 4.7124 +0.0000 -0.3556 4.7124 +0.0000 -0.4000 4.7124 +primID: 2 +startangle_c: 12 +endpose_c: 4 -16 13 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0095 -0.0904 4.7473 +0.0222 -0.1806 4.7823 +0.0381 -0.2707 4.8172 +0.0572 -0.3604 4.8522 +0.0795 -0.4496 4.8871 +0.1050 -0.5383 4.9221 +0.1335 -0.6264 4.9570 +0.1652 -0.7136 4.9919 +0.2000 -0.8000 5.0269 +primID: 3 +startangle_c: 12 +endpose_c: -4 -16 11 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.7124 +-0.0095 -0.0904 4.6774 +-0.0222 -0.1806 4.6425 +-0.0381 -0.2707 4.6076 +-0.0572 -0.3604 4.5726 +-0.0795 -0.4496 4.5377 +-0.1050 -0.5383 4.5027 +-0.1335 -0.6264 4.4678 +-0.1652 -0.7136 4.4328 +-0.2000 -0.8000 4.3979 +primID: 4 +startangle_c: 12 +endpose_c: 2 -5 13 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0085 -0.0280 4.7346 +0.0177 -0.0559 4.7569 +0.0275 -0.0839 4.7792 +0.0380 -0.1117 4.8014 +0.0491 -0.1396 4.8237 +0.0609 -0.1673 4.8459 +0.0733 -0.1950 4.8682 +0.0863 -0.2225 4.8904 +0.1000 -0.2500 4.9127 +primID: 5 +startangle_c: 12 +endpose_c: -2 -5 11 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 4.7124 +-0.0085 -0.0280 4.6901 +-0.0177 -0.0559 4.6679 +-0.0275 -0.0839 4.6456 +-0.0380 -0.1117 4.6234 +-0.0491 -0.1396 4.6011 +-0.0609 -0.1673 4.5788 +-0.0733 -0.1950 4.5566 +-0.0863 -0.2225 4.5343 +-0.1000 -0.2500 4.5121 +primID: 6 +startangle_c: 12 +endpose_c: 0 0 13 +additionalactioncostmult: 1000 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0000 4.7560 +0.0000 0.0000 4.7997 +0.0000 0.0000 4.8433 +0.0000 0.0000 4.8869 +0.0000 0.0000 4.9306 +0.0000 0.0000 4.9742 +0.0000 0.0000 5.0178 +0.0000 0.0000 5.0615 +0.0000 0.0000 5.1051 +primID: 7 +startangle_c: 12 +endpose_c: 0 0 11 +additionalactioncostmult: 1000 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0000 4.6688 +0.0000 0.0000 4.6251 +0.0000 0.0000 4.5815 +0.0000 0.0000 4.5379 +0.0000 0.0000 4.4942 +0.0000 0.0000 4.4506 +0.0000 0.0000 4.4070 +0.0000 0.0000 4.3633 +0.0000 0.0000 4.3197 +primID: 8 +startangle_c: 12 +endpose_c: 1 -8 12 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0056 -0.0444 4.7124 +0.0111 -0.0889 4.7124 +0.0167 -0.1333 4.7124 +0.0222 -0.1778 4.7124 +0.0278 -0.2222 4.7124 +0.0333 -0.2667 4.7124 +0.0389 -0.3111 4.7124 +0.0444 -0.3556 4.7124 +0.0500 -0.4000 4.7124 +primID: 9 +startangle_c: 12 +endpose_c: -1 -8 12 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 4.7124 +-0.0056 -0.0444 4.7124 +-0.0111 -0.0889 4.7124 +-0.0167 -0.1333 4.7124 +-0.0222 -0.1778 4.7124 +-0.0278 -0.2222 4.7124 +-0.0333 -0.2667 4.7124 +-0.0389 -0.3111 4.7124 +-0.0444 -0.3556 4.7124 +-0.0500 -0.4000 4.7124 +primID: 0 +startangle_c: 13 +endpose_c: 1 -2 13 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0056 -0.0111 5.1051 +0.0111 -0.0222 5.1051 +0.0167 -0.0333 5.1051 +0.0222 -0.0444 5.1051 +0.0278 -0.0556 5.1051 +0.0333 -0.0667 5.1051 +0.0389 -0.0778 5.1051 +0.0444 -0.0889 5.1051 +0.0500 -0.1000 5.1051 +primID: 1 +startangle_c: 13 +endpose_c: 3 -6 13 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0167 -0.0333 5.1051 +0.0333 -0.0667 5.1051 +0.0500 -0.1000 5.1051 +0.0667 -0.1333 5.1051 +0.0833 -0.1667 5.1051 +0.1000 -0.2000 5.1051 +0.1167 -0.2333 5.1051 +0.1333 -0.2667 5.1051 +0.1500 -0.3000 5.1051 +primID: 2 +startangle_c: 13 +endpose_c: 9 -13 14 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0378 -0.0793 5.1453 +0.0787 -0.1572 5.1856 +0.1229 -0.2334 5.2258 +0.1701 -0.3079 5.2661 +0.2204 -0.3805 5.3063 +0.2736 -0.4512 5.3466 +0.3296 -0.5197 5.3868 +0.3885 -0.5860 5.4271 +0.4500 -0.6500 5.4673 +primID: 3 +startangle_c: 13 +endpose_c: 3 -14 12 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0305 -0.0741 5.0898 +0.0582 -0.1493 5.0426 +0.0824 -0.2256 4.9954 +0.1030 -0.3031 4.9482 +0.1199 -0.3814 4.9011 +0.1330 -0.4604 4.8539 +0.1424 -0.5400 4.8067 +0.1481 -0.6199 4.7596 +0.1500 -0.7000 4.7124 +primID: 4 +startangle_c: 13 +endpose_c: 4 -5 14 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0184 -0.0298 5.1354 +0.0379 -0.0592 5.1657 +0.0583 -0.0881 5.1960 +0.0796 -0.1165 5.2263 +0.1019 -0.1444 5.2566 +0.1251 -0.1717 5.2869 +0.1492 -0.1984 5.3172 +0.1742 -0.2245 5.3475 +0.2000 -0.2500 5.3778 +primID: 5 +startangle_c: 13 +endpose_c: 1 -6 12 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0105 -0.0320 5.0674 +0.0197 -0.0644 5.0298 +0.0278 -0.0973 4.9922 +0.0346 -0.1304 4.9545 +0.0402 -0.1639 4.9169 +0.0446 -0.1977 4.8793 +0.0476 -0.2316 4.8416 +0.0495 -0.2658 4.8040 +0.0500 -0.3000 4.7663 +primID: 6 +startangle_c: 13 +endpose_c: 0 0 14 +additionalactioncostmult: 1000 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0000 0.0000 5.1487 +0.0000 0.0000 5.1924 +0.0000 0.0000 5.2360 +0.0000 0.0000 5.2796 +0.0000 0.0000 5.3233 +0.0000 0.0000 5.3669 +0.0000 0.0000 5.4105 +0.0000 0.0000 5.4542 +0.0000 0.0000 5.4978 +primID: 7 +startangle_c: 13 +endpose_c: 0 0 12 +additionalactioncostmult: 1000 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0000 0.0000 5.0615 +0.0000 0.0000 5.0178 +0.0000 0.0000 4.9742 +0.0000 0.0000 4.9306 +0.0000 0.0000 4.8869 +0.0000 0.0000 4.8433 +0.0000 0.0000 4.7997 +0.0000 0.0000 4.7560 +0.0000 0.0000 4.7124 +primID: 8 +startangle_c: 13 +endpose_c: 2 -7 13 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0111 -0.0389 5.1051 +0.0222 -0.0778 5.1051 +0.0333 -0.1167 5.1051 +0.0444 -0.1556 5.1051 +0.0556 -0.1944 5.1051 +0.0667 -0.2333 5.1051 +0.0778 -0.2722 5.1051 +0.0889 -0.3111 5.1051 +0.1000 -0.3500 5.1051 +primID: 9 +startangle_c: 13 +endpose_c: 4 -5 13 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0222 -0.0278 5.1051 +0.0444 -0.0556 5.1051 +0.0667 -0.0833 5.1051 +0.0889 -0.1111 5.1051 +0.1111 -0.1389 5.1051 +0.1333 -0.1667 5.1051 +0.1556 -0.1944 5.1051 +0.1778 -0.2222 5.1051 +0.2000 -0.2500 5.1051 +primID: 0 +startangle_c: 14 +endpose_c: 1 -1 14 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0056 -0.0056 5.4978 +0.0111 -0.0111 5.4978 +0.0167 -0.0167 5.4978 +0.0222 -0.0222 5.4978 +0.0278 -0.0278 5.4978 +0.0333 -0.0333 5.4978 +0.0389 -0.0389 5.4978 +0.0444 -0.0444 5.4978 +0.0500 -0.0500 5.4978 +primID: 1 +startangle_c: 14 +endpose_c: 6 -6 14 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0333 -0.0333 5.4978 +0.0667 -0.0667 5.4978 +0.1000 -0.1000 5.4978 +0.1333 -0.1333 5.4978 +0.1667 -0.1667 5.4978 +0.2000 -0.2000 5.4978 +0.2333 -0.2333 5.4978 +0.2667 -0.2667 5.4978 +0.3000 -0.3000 5.4978 +primID: 2 +startangle_c: 14 +endpose_c: 14 -11 15 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0705 -0.0705 5.4978 +0.1411 -0.1411 5.4978 +0.2116 -0.2116 5.4978 +0.2828 -0.2816 5.5325 +0.3581 -0.3469 5.6041 +0.4379 -0.4068 5.6757 +0.5218 -0.4607 5.7473 +0.6093 -0.5086 5.8189 +0.7000 -0.5500 5.8905 +primID: 3 +startangle_c: 14 +endpose_c: 11 -14 13 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0705 -0.0705 5.4978 +0.1411 -0.1411 5.4978 +0.2116 -0.2116 5.4978 +0.2816 -0.2828 5.4631 +0.3469 -0.3581 5.3915 +0.4068 -0.4379 5.3199 +0.4607 -0.5218 5.2483 +0.5086 -0.6093 5.1767 +0.5500 -0.7000 5.1051 +primID: 4 +startangle_c: 14 +endpose_c: 6 -4 15 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0292 -0.0278 5.5412 +0.0595 -0.0543 5.5846 +0.0910 -0.0795 5.6280 +0.1235 -0.1033 5.6714 +0.1571 -0.1257 5.7148 +0.1916 -0.1466 5.7582 +0.2269 -0.1659 5.8016 +0.2631 -0.1838 5.8450 +0.3000 -0.2000 5.8884 +primID: 5 +startangle_c: 14 +endpose_c: 4 -6 13 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0278 -0.0292 5.4544 +0.0543 -0.0595 5.4110 +0.0795 -0.0910 5.3676 +0.1033 -0.1235 5.3242 +0.1257 -0.1571 5.2808 +0.1466 -0.1916 5.2374 +0.1659 -0.2269 5.1940 +0.1838 -0.2631 5.1506 +0.2000 -0.3000 5.1072 +primID: 6 +startangle_c: 14 +endpose_c: 0 0 15 +additionalactioncostmult: 1000 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0000 0.0000 5.5414 +0.0000 0.0000 5.5851 +0.0000 0.0000 5.6287 +0.0000 0.0000 5.6723 +0.0000 0.0000 5.7160 +0.0000 0.0000 5.7596 +0.0000 0.0000 5.8032 +0.0000 0.0000 5.8469 +0.0000 0.0000 5.8905 +primID: 7 +startangle_c: 14 +endpose_c: 0 0 13 +additionalactioncostmult: 1000 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0000 0.0000 5.4542 +0.0000 0.0000 5.4105 +0.0000 0.0000 5.3669 +0.0000 0.0000 5.3233 +0.0000 0.0000 5.2796 +0.0000 0.0000 5.2360 +0.0000 0.0000 5.1924 +0.0000 0.0000 5.1487 +0.0000 0.0000 5.1051 +primID: 8 +startangle_c: 14 +endpose_c: 7 -6 14 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0389 -0.0333 5.4978 +0.0778 -0.0667 5.4978 +0.1167 -0.1000 5.4978 +0.1556 -0.1333 5.4978 +0.1944 -0.1667 5.4978 +0.2333 -0.2000 5.4978 +0.2722 -0.2333 5.4978 +0.3111 -0.2667 5.4978 +0.3500 -0.3000 5.4978 +primID: 9 +startangle_c: 14 +endpose_c: 6 -7 14 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0333 -0.0389 5.4978 +0.0667 -0.0778 5.4978 +0.1000 -0.1167 5.4978 +0.1333 -0.1556 5.4978 +0.1667 -0.1944 5.4978 +0.2000 -0.2333 5.4978 +0.2333 -0.2722 5.4978 +0.2667 -0.3111 5.4978 +0.3000 -0.3500 5.4978 +primID: 0 +startangle_c: 15 +endpose_c: 2 -1 15 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0111 -0.0056 5.8905 +0.0222 -0.0111 5.8905 +0.0333 -0.0167 5.8905 +0.0444 -0.0222 5.8905 +0.0556 -0.0278 5.8905 +0.0667 -0.0333 5.8905 +0.0778 -0.0389 5.8905 +0.0889 -0.0444 5.8905 +0.1000 -0.0500 5.8905 +primID: 1 +startangle_c: 15 +endpose_c: 6 -3 15 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0333 -0.0167 5.8905 +0.0667 -0.0333 5.8905 +0.1000 -0.0500 5.8905 +0.1333 -0.0667 5.8905 +0.1667 -0.0833 5.8905 +0.2000 -0.1000 5.8905 +0.2333 -0.1167 5.8905 +0.2667 -0.1333 5.8905 +0.3000 -0.1500 5.8905 +primID: 2 +startangle_c: 15 +endpose_c: 13 -9 14 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0793 -0.0378 5.8502 +0.1572 -0.0787 5.8100 +0.2334 -0.1229 5.7697 +0.3079 -0.1701 5.7295 +0.3805 -0.2204 5.6892 +0.4512 -0.2736 5.6490 +0.5197 -0.3296 5.6088 +0.5860 -0.3885 5.5685 +0.6500 -0.4500 5.5283 +primID: 3 +startangle_c: 15 +endpose_c: 14 -3 0 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0741 -0.0305 5.9058 +0.1493 -0.0582 5.9530 +0.2256 -0.0824 6.0002 +0.3031 -0.1030 6.0473 +0.3814 -0.1199 6.0945 +0.4604 -0.1330 6.1417 +0.5400 -0.1424 6.1888 +0.6199 -0.1481 6.2360 +0.7000 -0.1500 6.2832 +primID: 4 +startangle_c: 15 +endpose_c: 5 -4 14 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0298 -0.0184 5.8602 +0.0592 -0.0379 5.8299 +0.0881 -0.0583 5.7996 +0.1165 -0.0796 5.7693 +0.1444 -0.1019 5.7390 +0.1717 -0.1251 5.7087 +0.1984 -0.1492 5.6784 +0.2245 -0.1742 5.6481 +0.2500 -0.2000 5.6178 +primID: 5 +startangle_c: 15 +endpose_c: 6 -1 0 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0320 -0.0105 5.9281 +0.0644 -0.0197 5.9658 +0.0973 -0.0278 6.0034 +0.1304 -0.0346 6.0410 +0.1639 -0.0402 6.0787 +0.1977 -0.0446 6.1163 +0.2316 -0.0476 6.1540 +0.2658 -0.0495 6.1916 +0.3000 -0.0500 6.2292 +primID: 6 +startangle_c: 15 +endpose_c: 0 0 14 +additionalactioncostmult: 1000 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0000 0.0000 5.8469 +0.0000 0.0000 5.8032 +0.0000 0.0000 5.7596 +0.0000 0.0000 5.7160 +0.0000 0.0000 5.6723 +0.0000 0.0000 5.6287 +0.0000 0.0000 5.5851 +0.0000 0.0000 5.5414 +0.0000 0.0000 5.4978 +primID: 7 +startangle_c: 15 +endpose_c: 0 0 0 +additionalactioncostmult: 1000 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0000 0.0000 5.2360 +0.0000 0.0000 4.5815 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.2725 +0.0000 0.0000 2.6180 +0.0000 0.0000 1.9635 +0.0000 0.0000 1.3090 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.0000 +primID: 8 +startangle_c: 15 +endpose_c: 7 -2 15 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0389 -0.0111 5.8905 +0.0778 -0.0222 5.8905 +0.1167 -0.0333 5.8905 +0.1556 -0.0444 5.8905 +0.1944 -0.0556 5.8905 +0.2333 -0.0667 5.8905 +0.2722 -0.0778 5.8905 +0.3111 -0.0889 5.8905 +0.3500 -0.1000 5.8905 +primID: 9 +startangle_c: 15 +endpose_c: 5 -4 15 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0278 -0.0222 5.8905 +0.0556 -0.0444 5.8905 +0.0833 -0.0667 5.8905 +0.1111 -0.0889 5.8905 +0.1389 -0.1111 5.8905 +0.1667 -0.1333 5.8905 +0.1944 -0.1556 5.8905 +0.2222 -0.1778 5.8905 +0.2500 -0.2000 5.8905 diff --git a/mir_robot/mir_navigation/mprim/unicycle_highcost_10cm.mprim b/mir_robot/mir_navigation/mprim/unicycle_highcost_10cm.mprim new file mode 100755 index 0000000..de16976 --- /dev/null +++ b/mir_robot/mir_navigation/mprim/unicycle_highcost_10cm.mprim @@ -0,0 +1,1683 @@ +resolution_m: 0.100000 +numberofangles: 16 +totalnumberofprimitives: 112 +primID: 0 +startangle_c: 0 +endpose_c: 1 0 0 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0111 0.0000 0.0000 +0.0222 0.0000 0.0000 +0.0333 0.0000 0.0000 +0.0444 0.0000 0.0000 +0.0556 0.0000 0.0000 +0.0667 0.0000 0.0000 +0.0778 0.0000 0.0000 +0.0889 0.0000 0.0000 +0.1000 0.0000 0.0000 +primID: 1 +startangle_c: 0 +endpose_c: 4 0 0 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0444 0.0000 0.0000 +0.0889 0.0000 0.0000 +0.1333 0.0000 0.0000 +0.1778 0.0000 0.0000 +0.2222 0.0000 0.0000 +0.2667 0.0000 0.0000 +0.3111 0.0000 0.0000 +0.3556 0.0000 0.0000 +0.4000 0.0000 0.0000 +primID: 2 +startangle_c: 0 +endpose_c: -1 0 0 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.0000 +-0.0111 0.0000 0.0000 +-0.0222 0.0000 0.0000 +-0.0333 0.0000 0.0000 +-0.0444 0.0000 0.0000 +-0.0556 0.0000 0.0000 +-0.0667 0.0000 0.0000 +-0.0778 0.0000 0.0000 +-0.0889 0.0000 0.0000 +-0.1000 0.0000 0.0000 +primID: 3 +startangle_c: 0 +endpose_c: 4 1 1 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0452 0.0048 0.0349 +0.0903 0.0111 0.0699 +0.1353 0.0191 0.1048 +0.1802 0.0286 0.1398 +0.2248 0.0398 0.1747 +0.2692 0.0525 0.2097 +0.3132 0.0668 0.2446 +0.3568 0.0826 0.2796 +0.4000 0.1000 0.3145 +primID: 4 +startangle_c: 0 +endpose_c: 4 -1 -1 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0452 -0.0048 -0.0349 +0.0903 -0.0111 -0.0699 +0.1353 -0.0191 -0.1048 +0.1802 -0.0286 -0.1398 +0.2248 -0.0398 -0.1747 +0.2692 -0.0525 -0.2097 +0.3132 -0.0668 -0.2446 +0.3568 -0.0826 -0.2796 +0.4000 -0.1000 -0.3145 +primID: 5 +startangle_c: 0 +endpose_c: 0 0 1 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0000 0.0000 0.0436 +0.0000 0.0000 0.0873 +0.0000 0.0000 0.1309 +0.0000 0.0000 0.1745 +0.0000 0.0000 0.2182 +0.0000 0.0000 0.2618 +0.0000 0.0000 0.3054 +0.0000 0.0000 0.3491 +0.0000 0.0000 0.3927 +primID: 6 +startangle_c: 0 +endpose_c: 0 0 -1 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0000 0.0000 -0.0436 +0.0000 0.0000 -0.0873 +0.0000 0.0000 -0.1309 +0.0000 0.0000 -0.1745 +0.0000 0.0000 -0.2182 +0.0000 0.0000 -0.2618 +0.0000 0.0000 -0.3054 +0.0000 0.0000 -0.3491 +0.0000 0.0000 -0.3927 +primID: 0 +startangle_c: 1 +endpose_c: 2 1 1 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0222 0.0111 0.3927 +0.0444 0.0222 0.3927 +0.0667 0.0333 0.3927 +0.0889 0.0444 0.3927 +0.1111 0.0556 0.3927 +0.1333 0.0667 0.3927 +0.1556 0.0778 0.3927 +0.1778 0.0889 0.3927 +0.2000 0.1000 0.3927 +primID: 1 +startangle_c: 1 +endpose_c: 6 3 1 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0667 0.0333 0.3927 +0.1333 0.0667 0.3927 +0.2000 0.1000 0.3927 +0.2667 0.1333 0.3927 +0.3333 0.1667 0.3927 +0.4000 0.2000 0.3927 +0.4667 0.2333 0.3927 +0.5333 0.2667 0.3927 +0.6000 0.3000 0.3927 +primID: 2 +startangle_c: 1 +endpose_c: -2 -1 1 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.3927 +-0.0222 -0.0111 0.3927 +-0.0444 -0.0222 0.3927 +-0.0667 -0.0333 0.3927 +-0.0889 -0.0444 0.3927 +-0.1111 -0.0556 0.3927 +-0.1333 -0.0667 0.3927 +-0.1556 -0.0778 0.3927 +-0.1778 -0.0889 0.3927 +-0.2000 -0.1000 0.3927 +primID: 3 +startangle_c: 1 +endpose_c: 3 2 2 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0369 0.0162 0.4345 +0.0731 0.0339 0.4783 +0.1085 0.0533 0.5222 +0.1430 0.0741 0.5661 +0.1766 0.0965 0.6099 +0.2091 0.1203 0.6538 +0.2405 0.1455 0.6977 +0.2709 0.1721 0.7415 +0.3000 0.2000 0.7854 +primID: 4 +startangle_c: 1 +endpose_c: 4 1 0 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0427 0.0177 0.3927 +0.0854 0.0354 0.3927 +0.1283 0.0523 0.3477 +0.1722 0.0668 0.2898 +0.2168 0.0787 0.2318 +0.2621 0.0880 0.1739 +0.3078 0.0947 0.1159 +0.3538 0.0987 0.0580 +0.4000 0.1000 0.0000 +primID: 5 +startangle_c: 1 +endpose_c: 0 0 2 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0000 0.0000 0.4363 +0.0000 0.0000 0.4800 +0.0000 0.0000 0.5236 +0.0000 0.0000 0.5672 +0.0000 0.0000 0.6109 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.6981 +0.0000 0.0000 0.7418 +0.0000 0.0000 0.7854 +primID: 6 +startangle_c: 1 +endpose_c: 0 0 0 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0000 0.0000 0.3491 +0.0000 0.0000 0.3054 +0.0000 0.0000 0.2618 +0.0000 0.0000 0.2182 +0.0000 0.0000 0.1745 +0.0000 0.0000 0.1309 +0.0000 0.0000 0.0873 +0.0000 0.0000 0.0436 +0.0000 0.0000 0.0000 +primID: 0 +startangle_c: 2 +endpose_c: 1 1 2 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0111 0.0111 0.7854 +0.0222 0.0222 0.7854 +0.0333 0.0333 0.7854 +0.0444 0.0444 0.7854 +0.0556 0.0556 0.7854 +0.0667 0.0667 0.7854 +0.0778 0.0778 0.7854 +0.0889 0.0889 0.7854 +0.1000 0.1000 0.7854 +primID: 1 +startangle_c: 2 +endpose_c: 3 3 2 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0333 0.0333 0.7854 +0.0667 0.0667 0.7854 +0.1000 0.1000 0.7854 +0.1333 0.1333 0.7854 +0.1667 0.1667 0.7854 +0.2000 0.2000 0.7854 +0.2333 0.2333 0.7854 +0.2667 0.2667 0.7854 +0.3000 0.3000 0.7854 +primID: 2 +startangle_c: 2 +endpose_c: -1 -1 2 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.7854 +-0.0111 -0.0111 0.7854 +-0.0222 -0.0222 0.7854 +-0.0333 -0.0333 0.7854 +-0.0444 -0.0444 0.7854 +-0.0556 -0.0556 0.7854 +-0.0667 -0.0667 0.7854 +-0.0778 -0.0778 0.7854 +-0.0889 -0.0889 0.7854 +-0.1000 -0.1000 0.7854 +primID: 3 +startangle_c: 2 +endpose_c: 2 4 3 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0262 0.0411 0.8119 +0.0515 0.0831 0.8384 +0.0758 0.1260 0.8649 +0.0991 0.1697 0.8913 +0.1214 0.2142 0.9178 +0.1426 0.2595 0.9443 +0.1628 0.3056 0.9708 +0.1820 0.3525 0.9973 +0.2000 0.4000 1.0238 +primID: 4 +startangle_c: 2 +endpose_c: 4 2 1 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0411 0.0262 0.7589 +0.0831 0.0515 0.7324 +0.1260 0.0758 0.7059 +0.1697 0.0991 0.6795 +0.2142 0.1214 0.6530 +0.2595 0.1426 0.6265 +0.3056 0.1628 0.6000 +0.3525 0.1820 0.5735 +0.4000 0.2000 0.5470 +primID: 5 +startangle_c: 2 +endpose_c: 0 0 3 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0000 0.0000 0.8290 +0.0000 0.0000 0.8727 +0.0000 0.0000 0.9163 +0.0000 0.0000 0.9599 +0.0000 0.0000 1.0036 +0.0000 0.0000 1.0472 +0.0000 0.0000 1.0908 +0.0000 0.0000 1.1345 +0.0000 0.0000 1.1781 +primID: 6 +startangle_c: 2 +endpose_c: 0 0 1 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0000 0.0000 0.7418 +0.0000 0.0000 0.6981 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.6109 +0.0000 0.0000 0.5672 +0.0000 0.0000 0.5236 +0.0000 0.0000 0.4800 +0.0000 0.0000 0.4363 +0.0000 0.0000 0.3927 +primID: 0 +startangle_c: 3 +endpose_c: 1 2 3 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0111 0.0222 1.1781 +0.0222 0.0444 1.1781 +0.0333 0.0667 1.1781 +0.0444 0.0889 1.1781 +0.0556 0.1111 1.1781 +0.0667 0.1333 1.1781 +0.0778 0.1556 1.1781 +0.0889 0.1778 1.1781 +0.1000 0.2000 1.1781 +primID: 1 +startangle_c: 3 +endpose_c: 3 6 3 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0333 0.0667 1.1781 +0.0667 0.1333 1.1781 +0.1000 0.2000 1.1781 +0.1333 0.2667 1.1781 +0.1667 0.3333 1.1781 +0.2000 0.4000 1.1781 +0.2333 0.4667 1.1781 +0.2667 0.5333 1.1781 +0.3000 0.6000 1.1781 +primID: 2 +startangle_c: 3 +endpose_c: -1 -2 3 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.1781 +-0.0111 -0.0222 1.1781 +-0.0222 -0.0444 1.1781 +-0.0333 -0.0667 1.1781 +-0.0444 -0.0889 1.1781 +-0.0556 -0.1111 1.1781 +-0.0667 -0.1333 1.1781 +-0.0778 -0.1556 1.1781 +-0.0889 -0.1778 1.1781 +-0.1000 -0.2000 1.1781 +primID: 3 +startangle_c: 3 +endpose_c: 2 3 2 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0162 0.0369 1.1363 +0.0339 0.0731 1.0925 +0.0533 0.1085 1.0486 +0.0741 0.1430 1.0047 +0.0965 0.1766 0.9609 +0.1203 0.2091 0.9170 +0.1455 0.2405 0.8731 +0.1721 0.2709 0.8293 +0.2000 0.3000 0.7854 +primID: 4 +startangle_c: 3 +endpose_c: 1 4 4 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0177 0.0427 1.1781 +0.0354 0.0854 1.1781 +0.0523 0.1283 1.2231 +0.0668 0.1722 1.2810 +0.0787 0.2168 1.3390 +0.0880 0.2621 1.3969 +0.0947 0.3078 1.4549 +0.0987 0.3538 1.5128 +0.1000 0.4000 1.5708 +primID: 5 +startangle_c: 3 +endpose_c: 0 0 2 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0000 0.0000 1.1345 +0.0000 0.0000 1.0908 +0.0000 0.0000 1.0472 +0.0000 0.0000 1.0036 +0.0000 0.0000 0.9599 +0.0000 0.0000 0.9163 +0.0000 0.0000 0.8727 +0.0000 0.0000 0.8290 +0.0000 0.0000 0.7854 +primID: 6 +startangle_c: 3 +endpose_c: 0 0 4 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0000 0.0000 1.2217 +0.0000 0.0000 1.2654 +0.0000 0.0000 1.3090 +0.0000 0.0000 1.3526 +0.0000 0.0000 1.3963 +0.0000 0.0000 1.4399 +0.0000 0.0000 1.4835 +0.0000 0.0000 1.5272 +0.0000 0.0000 1.5708 +primID: 0 +startangle_c: 4 +endpose_c: 0 1 4 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0111 1.5708 +0.0000 0.0222 1.5708 +0.0000 0.0333 1.5708 +0.0000 0.0444 1.5708 +0.0000 0.0556 1.5708 +0.0000 0.0667 1.5708 +0.0000 0.0778 1.5708 +0.0000 0.0889 1.5708 +0.0000 0.1000 1.5708 +primID: 1 +startangle_c: 4 +endpose_c: 0 4 4 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0444 1.5708 +0.0000 0.0889 1.5708 +0.0000 0.1333 1.5708 +0.0000 0.1778 1.5708 +0.0000 0.2222 1.5708 +0.0000 0.2667 1.5708 +0.0000 0.3111 1.5708 +0.0000 0.3556 1.5708 +0.0000 0.4000 1.5708 +primID: 2 +startangle_c: 4 +endpose_c: 0 -1 4 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 -0.0111 1.5708 +0.0000 -0.0222 1.5708 +0.0000 -0.0333 1.5708 +0.0000 -0.0444 1.5708 +0.0000 -0.0556 1.5708 +0.0000 -0.0667 1.5708 +0.0000 -0.0778 1.5708 +0.0000 -0.0889 1.5708 +0.0000 -0.1000 1.5708 +primID: 3 +startangle_c: 4 +endpose_c: -1 4 5 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.5708 +-0.0048 0.0452 1.6057 +-0.0111 0.0903 1.6407 +-0.0191 0.1353 1.6756 +-0.0286 0.1802 1.7106 +-0.0398 0.2248 1.7455 +-0.0525 0.2692 1.7805 +-0.0668 0.3132 1.8154 +-0.0826 0.3568 1.8503 +-0.1000 0.4000 1.8853 +primID: 4 +startangle_c: 4 +endpose_c: 1 4 3 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0048 0.0452 1.5359 +0.0111 0.0903 1.5009 +0.0191 0.1353 1.4660 +0.0286 0.1802 1.4310 +0.0398 0.2248 1.3961 +0.0525 0.2692 1.3611 +0.0668 0.3132 1.3262 +0.0826 0.3568 1.2912 +0.1000 0.4000 1.2563 +primID: 5 +startangle_c: 4 +endpose_c: 0 0 5 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0000 1.6144 +0.0000 0.0000 1.6581 +0.0000 0.0000 1.7017 +0.0000 0.0000 1.7453 +0.0000 0.0000 1.7890 +0.0000 0.0000 1.8326 +0.0000 0.0000 1.8762 +0.0000 0.0000 1.9199 +0.0000 0.0000 1.9635 +primID: 6 +startangle_c: 4 +endpose_c: 0 0 3 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0000 1.5272 +0.0000 0.0000 1.4835 +0.0000 0.0000 1.4399 +0.0000 0.0000 1.3963 +0.0000 0.0000 1.3526 +0.0000 0.0000 1.3090 +0.0000 0.0000 1.2654 +0.0000 0.0000 1.2217 +0.0000 0.0000 1.1781 +primID: 0 +startangle_c: 5 +endpose_c: -1 2 5 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0111 0.0222 1.9635 +-0.0222 0.0444 1.9635 +-0.0333 0.0667 1.9635 +-0.0444 0.0889 1.9635 +-0.0556 0.1111 1.9635 +-0.0667 0.1333 1.9635 +-0.0778 0.1556 1.9635 +-0.0889 0.1778 1.9635 +-0.1000 0.2000 1.9635 +primID: 1 +startangle_c: 5 +endpose_c: -3 6 5 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0333 0.0667 1.9635 +-0.0667 0.1333 1.9635 +-0.1000 0.2000 1.9635 +-0.1333 0.2667 1.9635 +-0.1667 0.3333 1.9635 +-0.2000 0.4000 1.9635 +-0.2333 0.4667 1.9635 +-0.2667 0.5333 1.9635 +-0.3000 0.6000 1.9635 +primID: 2 +startangle_c: 5 +endpose_c: 1 -2 5 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0111 -0.0222 1.9635 +0.0222 -0.0444 1.9635 +0.0333 -0.0667 1.9635 +0.0444 -0.0889 1.9635 +0.0556 -0.1111 1.9635 +0.0667 -0.1333 1.9635 +0.0778 -0.1556 1.9635 +0.0889 -0.1778 1.9635 +0.1000 -0.2000 1.9635 +primID: 3 +startangle_c: 5 +endpose_c: -2 3 6 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0162 0.0369 2.0053 +-0.0339 0.0731 2.0491 +-0.0533 0.1085 2.0930 +-0.0741 0.1430 2.1369 +-0.0965 0.1766 2.1807 +-0.1203 0.2091 2.2246 +-0.1455 0.2405 2.2685 +-0.1721 0.2709 2.3123 +-0.2000 0.3000 2.3562 +primID: 4 +startangle_c: 5 +endpose_c: -1 4 4 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0177 0.0427 1.9635 +-0.0354 0.0854 1.9635 +-0.0523 0.1283 1.9185 +-0.0668 0.1722 1.8606 +-0.0787 0.2168 1.8026 +-0.0880 0.2621 1.7447 +-0.0947 0.3078 1.6867 +-0.0987 0.3538 1.6287 +-0.1000 0.4000 1.5708 +primID: 5 +startangle_c: 5 +endpose_c: 0 0 6 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0000 0.0000 2.0071 +0.0000 0.0000 2.0508 +0.0000 0.0000 2.0944 +0.0000 0.0000 2.1380 +0.0000 0.0000 2.1817 +0.0000 0.0000 2.2253 +0.0000 0.0000 2.2689 +0.0000 0.0000 2.3126 +0.0000 0.0000 2.3562 +primID: 6 +startangle_c: 5 +endpose_c: 0 0 4 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0000 0.0000 1.9199 +0.0000 0.0000 1.8762 +0.0000 0.0000 1.8326 +0.0000 0.0000 1.7890 +0.0000 0.0000 1.7453 +0.0000 0.0000 1.7017 +0.0000 0.0000 1.6581 +0.0000 0.0000 1.6144 +0.0000 0.0000 1.5708 +primID: 0 +startangle_c: 6 +endpose_c: -1 1 6 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0111 0.0111 2.3562 +-0.0222 0.0222 2.3562 +-0.0333 0.0333 2.3562 +-0.0444 0.0444 2.3562 +-0.0556 0.0556 2.3562 +-0.0667 0.0667 2.3562 +-0.0778 0.0778 2.3562 +-0.0889 0.0889 2.3562 +-0.1000 0.1000 2.3562 +primID: 1 +startangle_c: 6 +endpose_c: -3 3 6 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0333 0.0333 2.3562 +-0.0667 0.0667 2.3562 +-0.1000 0.1000 2.3562 +-0.1333 0.1333 2.3562 +-0.1667 0.1667 2.3562 +-0.2000 0.2000 2.3562 +-0.2333 0.2333 2.3562 +-0.2667 0.2667 2.3562 +-0.3000 0.3000 2.3562 +primID: 2 +startangle_c: 6 +endpose_c: 1 -1 6 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0111 -0.0111 2.3562 +0.0222 -0.0222 2.3562 +0.0333 -0.0333 2.3562 +0.0444 -0.0444 2.3562 +0.0556 -0.0556 2.3562 +0.0667 -0.0667 2.3562 +0.0778 -0.0778 2.3562 +0.0889 -0.0889 2.3562 +0.1000 -0.1000 2.3562 +primID: 3 +startangle_c: 6 +endpose_c: -4 2 7 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0411 0.0262 2.3827 +-0.0831 0.0515 2.4092 +-0.1260 0.0758 2.4357 +-0.1697 0.0991 2.4621 +-0.2142 0.1214 2.4886 +-0.2595 0.1426 2.5151 +-0.3056 0.1628 2.5416 +-0.3525 0.1820 2.5681 +-0.4000 0.2000 2.5946 +primID: 4 +startangle_c: 6 +endpose_c: -2 4 5 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0262 0.0411 2.3297 +-0.0515 0.0831 2.3032 +-0.0758 0.1260 2.2767 +-0.0991 0.1697 2.2502 +-0.1214 0.2142 2.2238 +-0.1426 0.2595 2.1973 +-0.1628 0.3056 2.1708 +-0.1820 0.3525 2.1443 +-0.2000 0.4000 2.1178 +primID: 5 +startangle_c: 6 +endpose_c: 0 0 7 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0000 0.0000 2.3998 +0.0000 0.0000 2.4435 +0.0000 0.0000 2.4871 +0.0000 0.0000 2.5307 +0.0000 0.0000 2.5744 +0.0000 0.0000 2.6180 +0.0000 0.0000 2.6616 +0.0000 0.0000 2.7053 +0.0000 0.0000 2.7489 +primID: 6 +startangle_c: 6 +endpose_c: 0 0 5 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0000 0.0000 2.3126 +0.0000 0.0000 2.2689 +0.0000 0.0000 2.2253 +0.0000 0.0000 2.1817 +0.0000 0.0000 2.1380 +0.0000 0.0000 2.0944 +0.0000 0.0000 2.0508 +0.0000 0.0000 2.0071 +0.0000 0.0000 1.9635 +primID: 0 +startangle_c: 7 +endpose_c: -2 1 7 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0222 0.0111 2.7489 +-0.0444 0.0222 2.7489 +-0.0667 0.0333 2.7489 +-0.0889 0.0444 2.7489 +-0.1111 0.0556 2.7489 +-0.1333 0.0667 2.7489 +-0.1556 0.0778 2.7489 +-0.1778 0.0889 2.7489 +-0.2000 0.1000 2.7489 +primID: 1 +startangle_c: 7 +endpose_c: -6 3 7 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0667 0.0333 2.7489 +-0.1333 0.0667 2.7489 +-0.2000 0.1000 2.7489 +-0.2667 0.1333 2.7489 +-0.3333 0.1667 2.7489 +-0.4000 0.2000 2.7489 +-0.4667 0.2333 2.7489 +-0.5333 0.2667 2.7489 +-0.6000 0.3000 2.7489 +primID: 2 +startangle_c: 7 +endpose_c: 2 -1 7 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0222 -0.0111 2.7489 +0.0444 -0.0222 2.7489 +0.0667 -0.0333 2.7489 +0.0889 -0.0444 2.7489 +0.1111 -0.0556 2.7489 +0.1333 -0.0667 2.7489 +0.1556 -0.0778 2.7489 +0.1778 -0.0889 2.7489 +0.2000 -0.1000 2.7489 +primID: 3 +startangle_c: 7 +endpose_c: -3 2 6 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0369 0.0162 2.7071 +-0.0731 0.0339 2.6633 +-0.1085 0.0533 2.6194 +-0.1430 0.0741 2.5755 +-0.1766 0.0965 2.5317 +-0.2091 0.1203 2.4878 +-0.2405 0.1455 2.4439 +-0.2709 0.1721 2.4001 +-0.3000 0.2000 2.3562 +primID: 4 +startangle_c: 7 +endpose_c: -4 1 8 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0427 0.0177 2.7489 +-0.0854 0.0354 2.7489 +-0.1283 0.0523 2.7939 +-0.1722 0.0668 2.8518 +-0.2168 0.0787 2.9098 +-0.2621 0.0880 2.9677 +-0.3078 0.0947 3.0257 +-0.3538 0.0987 3.0836 +-0.4000 0.1000 3.1416 +primID: 5 +startangle_c: 7 +endpose_c: 0 0 6 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0000 0.0000 2.7053 +0.0000 0.0000 2.6616 +0.0000 0.0000 2.6180 +0.0000 0.0000 2.5744 +0.0000 0.0000 2.5307 +0.0000 0.0000 2.4871 +0.0000 0.0000 2.4435 +0.0000 0.0000 2.3998 +0.0000 0.0000 2.3562 +primID: 6 +startangle_c: 7 +endpose_c: 0 0 8 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0000 0.0000 2.7925 +0.0000 0.0000 2.8362 +0.0000 0.0000 2.8798 +0.0000 0.0000 2.9234 +0.0000 0.0000 2.9671 +0.0000 0.0000 3.0107 +0.0000 0.0000 3.0543 +0.0000 0.0000 3.0980 +0.0000 0.0000 3.1416 +primID: 0 +startangle_c: 8 +endpose_c: -1 0 8 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0111 0.0000 3.1416 +-0.0222 0.0000 3.1416 +-0.0333 0.0000 3.1416 +-0.0444 0.0000 3.1416 +-0.0556 0.0000 3.1416 +-0.0667 0.0000 3.1416 +-0.0778 0.0000 3.1416 +-0.0889 0.0000 3.1416 +-0.1000 0.0000 3.1416 +primID: 1 +startangle_c: 8 +endpose_c: -4 0 8 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0444 0.0000 3.1416 +-0.0889 0.0000 3.1416 +-0.1333 0.0000 3.1416 +-0.1778 0.0000 3.1416 +-0.2222 0.0000 3.1416 +-0.2667 0.0000 3.1416 +-0.3111 0.0000 3.1416 +-0.3556 0.0000 3.1416 +-0.4000 0.0000 3.1416 +primID: 2 +startangle_c: 8 +endpose_c: 1 0 8 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0111 0.0000 3.1416 +0.0222 0.0000 3.1416 +0.0333 0.0000 3.1416 +0.0444 0.0000 3.1416 +0.0556 0.0000 3.1416 +0.0667 0.0000 3.1416 +0.0778 0.0000 3.1416 +0.0889 0.0000 3.1416 +0.1000 0.0000 3.1416 +primID: 3 +startangle_c: 8 +endpose_c: -4 -1 9 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0452 -0.0048 3.1765 +-0.0903 -0.0111 3.2115 +-0.1353 -0.0191 3.2464 +-0.1802 -0.0286 3.2814 +-0.2248 -0.0398 3.3163 +-0.2692 -0.0525 3.3513 +-0.3132 -0.0668 3.3862 +-0.3568 -0.0826 3.4211 +-0.4000 -0.1000 3.4561 +primID: 4 +startangle_c: 8 +endpose_c: -4 1 7 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0452 0.0048 3.1066 +-0.0903 0.0111 3.0717 +-0.1353 0.0191 3.0368 +-0.1802 0.0286 3.0018 +-0.2248 0.0398 2.9669 +-0.2692 0.0525 2.9319 +-0.3132 0.0668 2.8970 +-0.3568 0.0826 2.8620 +-0.4000 0.1000 2.8271 +primID: 5 +startangle_c: 8 +endpose_c: 0 0 9 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0000 0.0000 3.1852 +0.0000 0.0000 3.2289 +0.0000 0.0000 3.2725 +0.0000 0.0000 3.3161 +0.0000 0.0000 3.3598 +0.0000 0.0000 3.4034 +0.0000 0.0000 3.4470 +0.0000 0.0000 3.4907 +0.0000 0.0000 3.5343 +primID: 6 +startangle_c: 8 +endpose_c: 0 0 7 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0000 0.0000 3.0980 +0.0000 0.0000 3.0543 +0.0000 0.0000 3.0107 +0.0000 0.0000 2.9671 +0.0000 0.0000 2.9234 +0.0000 0.0000 2.8798 +0.0000 0.0000 2.8362 +0.0000 0.0000 2.7925 +0.0000 0.0000 2.7489 +primID: 0 +startangle_c: 9 +endpose_c: -2 -1 9 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0222 -0.0111 3.5343 +-0.0444 -0.0222 3.5343 +-0.0667 -0.0333 3.5343 +-0.0889 -0.0444 3.5343 +-0.1111 -0.0556 3.5343 +-0.1333 -0.0667 3.5343 +-0.1556 -0.0778 3.5343 +-0.1778 -0.0889 3.5343 +-0.2000 -0.1000 3.5343 +primID: 1 +startangle_c: 9 +endpose_c: -6 -3 9 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0667 -0.0333 3.5343 +-0.1333 -0.0667 3.5343 +-0.2000 -0.1000 3.5343 +-0.2667 -0.1333 3.5343 +-0.3333 -0.1667 3.5343 +-0.4000 -0.2000 3.5343 +-0.4667 -0.2333 3.5343 +-0.5333 -0.2667 3.5343 +-0.6000 -0.3000 3.5343 +primID: 2 +startangle_c: 9 +endpose_c: 2 1 9 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0222 0.0111 3.5343 +0.0444 0.0222 3.5343 +0.0667 0.0333 3.5343 +0.0889 0.0444 3.5343 +0.1111 0.0556 3.5343 +0.1333 0.0667 3.5343 +0.1556 0.0778 3.5343 +0.1778 0.0889 3.5343 +0.2000 0.1000 3.5343 +primID: 3 +startangle_c: 9 +endpose_c: -3 -2 10 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0369 -0.0162 3.5761 +-0.0731 -0.0339 3.6199 +-0.1085 -0.0533 3.6638 +-0.1430 -0.0741 3.7077 +-0.1766 -0.0965 3.7515 +-0.2091 -0.1203 3.7954 +-0.2405 -0.1455 3.8393 +-0.2709 -0.1721 3.8831 +-0.3000 -0.2000 3.9270 +primID: 4 +startangle_c: 9 +endpose_c: -4 -1 8 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0427 -0.0177 3.5343 +-0.0854 -0.0354 3.5343 +-0.1283 -0.0523 3.4893 +-0.1722 -0.0668 3.4313 +-0.2168 -0.0787 3.3734 +-0.2621 -0.0880 3.3154 +-0.3078 -0.0947 3.2575 +-0.3538 -0.0987 3.1995 +-0.4000 -0.1000 3.1416 +primID: 5 +startangle_c: 9 +endpose_c: 0 0 10 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0000 0.0000 3.5779 +0.0000 0.0000 3.6216 +0.0000 0.0000 3.6652 +0.0000 0.0000 3.7088 +0.0000 0.0000 3.7525 +0.0000 0.0000 3.7961 +0.0000 0.0000 3.8397 +0.0000 0.0000 3.8834 +0.0000 0.0000 3.9270 +primID: 6 +startangle_c: 9 +endpose_c: 0 0 8 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0000 0.0000 3.4907 +0.0000 0.0000 3.4470 +0.0000 0.0000 3.4034 +0.0000 0.0000 3.3598 +0.0000 0.0000 3.3161 +0.0000 0.0000 3.2725 +0.0000 0.0000 3.2289 +0.0000 0.0000 3.1852 +0.0000 0.0000 3.1416 +primID: 0 +startangle_c: 10 +endpose_c: -1 -1 10 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0111 -0.0111 3.9270 +-0.0222 -0.0222 3.9270 +-0.0333 -0.0333 3.9270 +-0.0444 -0.0444 3.9270 +-0.0556 -0.0556 3.9270 +-0.0667 -0.0667 3.9270 +-0.0778 -0.0778 3.9270 +-0.0889 -0.0889 3.9270 +-0.1000 -0.1000 3.9270 +primID: 1 +startangle_c: 10 +endpose_c: -3 -3 10 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0333 -0.0333 3.9270 +-0.0667 -0.0667 3.9270 +-0.1000 -0.1000 3.9270 +-0.1333 -0.1333 3.9270 +-0.1667 -0.1667 3.9270 +-0.2000 -0.2000 3.9270 +-0.2333 -0.2333 3.9270 +-0.2667 -0.2667 3.9270 +-0.3000 -0.3000 3.9270 +primID: 2 +startangle_c: 10 +endpose_c: 1 1 10 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0111 0.0111 3.9270 +0.0222 0.0222 3.9270 +0.0333 0.0333 3.9270 +0.0444 0.0444 3.9270 +0.0556 0.0556 3.9270 +0.0667 0.0667 3.9270 +0.0778 0.0778 3.9270 +0.0889 0.0889 3.9270 +0.1000 0.1000 3.9270 +primID: 3 +startangle_c: 10 +endpose_c: -2 -4 11 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0262 -0.0411 3.9535 +-0.0515 -0.0831 3.9800 +-0.0758 -0.1260 4.0064 +-0.0991 -0.1697 4.0329 +-0.1214 -0.2142 4.0594 +-0.1426 -0.2595 4.0859 +-0.1628 -0.3056 4.1124 +-0.1820 -0.3525 4.1389 +-0.2000 -0.4000 4.1654 +primID: 4 +startangle_c: 10 +endpose_c: -4 -2 9 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0411 -0.0262 3.9005 +-0.0831 -0.0515 3.8740 +-0.1260 -0.0758 3.8475 +-0.1697 -0.0991 3.8210 +-0.2142 -0.1214 3.7946 +-0.2595 -0.1426 3.7681 +-0.3056 -0.1628 3.7416 +-0.3525 -0.1820 3.7151 +-0.4000 -0.2000 3.6886 +primID: 5 +startangle_c: 10 +endpose_c: 0 0 11 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.9706 +0.0000 0.0000 4.0143 +0.0000 0.0000 4.0579 +0.0000 0.0000 4.1015 +0.0000 0.0000 4.1452 +0.0000 0.0000 4.1888 +0.0000 0.0000 4.2324 +0.0000 0.0000 4.2761 +0.0000 0.0000 4.3197 +primID: 6 +startangle_c: 10 +endpose_c: 0 0 9 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.8834 +0.0000 0.0000 3.8397 +0.0000 0.0000 3.7961 +0.0000 0.0000 3.7525 +0.0000 0.0000 3.7088 +0.0000 0.0000 3.6652 +0.0000 0.0000 3.6216 +0.0000 0.0000 3.5779 +0.0000 0.0000 3.5343 +primID: 0 +startangle_c: 11 +endpose_c: -1 -2 11 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0111 -0.0222 4.3197 +-0.0222 -0.0444 4.3197 +-0.0333 -0.0667 4.3197 +-0.0444 -0.0889 4.3197 +-0.0556 -0.1111 4.3197 +-0.0667 -0.1333 4.3197 +-0.0778 -0.1556 4.3197 +-0.0889 -0.1778 4.3197 +-0.1000 -0.2000 4.3197 +primID: 1 +startangle_c: 11 +endpose_c: -3 -6 11 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0333 -0.0667 4.3197 +-0.0667 -0.1333 4.3197 +-0.1000 -0.2000 4.3197 +-0.1333 -0.2667 4.3197 +-0.1667 -0.3333 4.3197 +-0.2000 -0.4000 4.3197 +-0.2333 -0.4667 4.3197 +-0.2667 -0.5333 4.3197 +-0.3000 -0.6000 4.3197 +primID: 2 +startangle_c: 11 +endpose_c: 1 2 11 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0111 0.0222 4.3197 +0.0222 0.0444 4.3197 +0.0333 0.0667 4.3197 +0.0444 0.0889 4.3197 +0.0556 0.1111 4.3197 +0.0667 0.1333 4.3197 +0.0778 0.1556 4.3197 +0.0889 0.1778 4.3197 +0.1000 0.2000 4.3197 +primID: 3 +startangle_c: 11 +endpose_c: -2 -3 10 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0162 -0.0369 4.2779 +-0.0339 -0.0731 4.2341 +-0.0533 -0.1085 4.1902 +-0.0741 -0.1430 4.1463 +-0.0965 -0.1766 4.1025 +-0.1203 -0.2091 4.0586 +-0.1455 -0.2405 4.0147 +-0.1721 -0.2709 3.9709 +-0.2000 -0.3000 3.9270 +primID: 4 +startangle_c: 11 +endpose_c: -1 -4 12 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0177 -0.0427 4.3197 +-0.0354 -0.0854 4.3197 +-0.0523 -0.1283 4.3647 +-0.0668 -0.1722 4.4226 +-0.0787 -0.2168 4.4806 +-0.0880 -0.2621 4.5385 +-0.0947 -0.3078 4.5965 +-0.0987 -0.3538 4.6544 +-0.1000 -0.4000 4.7124 +primID: 5 +startangle_c: 11 +endpose_c: 0 0 10 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0000 0.0000 4.2761 +0.0000 0.0000 4.2324 +0.0000 0.0000 4.1888 +0.0000 0.0000 4.1452 +0.0000 0.0000 4.1015 +0.0000 0.0000 4.0579 +0.0000 0.0000 4.0143 +0.0000 0.0000 3.9706 +0.0000 0.0000 3.9270 +primID: 6 +startangle_c: 11 +endpose_c: 0 0 12 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0000 0.0000 4.3633 +0.0000 0.0000 4.4070 +0.0000 0.0000 4.4506 +0.0000 0.0000 4.4942 +0.0000 0.0000 4.5379 +0.0000 0.0000 4.5815 +0.0000 0.0000 4.6251 +0.0000 0.0000 4.6688 +0.0000 0.0000 4.7124 +primID: 0 +startangle_c: 12 +endpose_c: 0 -1 12 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0111 4.7124 +0.0000 -0.0222 4.7124 +0.0000 -0.0333 4.7124 +0.0000 -0.0444 4.7124 +0.0000 -0.0556 4.7124 +0.0000 -0.0667 4.7124 +0.0000 -0.0778 4.7124 +0.0000 -0.0889 4.7124 +0.0000 -0.1000 4.7124 +primID: 1 +startangle_c: 12 +endpose_c: 0 -4 12 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0444 4.7124 +0.0000 -0.0889 4.7124 +0.0000 -0.1333 4.7124 +0.0000 -0.1778 4.7124 +0.0000 -0.2222 4.7124 +0.0000 -0.2667 4.7124 +0.0000 -0.3111 4.7124 +0.0000 -0.3556 4.7124 +0.0000 -0.4000 4.7124 +primID: 2 +startangle_c: 12 +endpose_c: 0 1 12 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0111 4.7124 +0.0000 0.0222 4.7124 +0.0000 0.0333 4.7124 +0.0000 0.0444 4.7124 +0.0000 0.0556 4.7124 +0.0000 0.0667 4.7124 +0.0000 0.0778 4.7124 +0.0000 0.0889 4.7124 +0.0000 0.1000 4.7124 +primID: 3 +startangle_c: 12 +endpose_c: 1 -4 13 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0048 -0.0452 4.7473 +0.0111 -0.0903 4.7823 +0.0191 -0.1353 4.8172 +0.0286 -0.1802 4.8522 +0.0398 -0.2248 4.8871 +0.0525 -0.2692 4.9221 +0.0668 -0.3132 4.9570 +0.0826 -0.3568 4.9919 +0.1000 -0.4000 5.0269 +primID: 4 +startangle_c: 12 +endpose_c: -1 -4 11 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.7124 +-0.0048 -0.0452 4.6774 +-0.0111 -0.0903 4.6425 +-0.0191 -0.1353 4.6076 +-0.0286 -0.1802 4.5726 +-0.0398 -0.2248 4.5377 +-0.0525 -0.2692 4.5027 +-0.0668 -0.3132 4.4678 +-0.0826 -0.3568 4.4328 +-0.1000 -0.4000 4.3979 +primID: 5 +startangle_c: 12 +endpose_c: 0 0 13 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0000 4.7560 +0.0000 0.0000 4.7997 +0.0000 0.0000 4.8433 +0.0000 0.0000 4.8869 +0.0000 0.0000 4.9306 +0.0000 0.0000 4.9742 +0.0000 0.0000 5.0178 +0.0000 0.0000 5.0615 +0.0000 0.0000 5.1051 +primID: 6 +startangle_c: 12 +endpose_c: 0 0 11 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0000 4.6688 +0.0000 0.0000 4.6251 +0.0000 0.0000 4.5815 +0.0000 0.0000 4.5379 +0.0000 0.0000 4.4942 +0.0000 0.0000 4.4506 +0.0000 0.0000 4.4070 +0.0000 0.0000 4.3633 +0.0000 0.0000 4.3197 +primID: 0 +startangle_c: 13 +endpose_c: 1 -2 13 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0111 -0.0222 5.1051 +0.0222 -0.0444 5.1051 +0.0333 -0.0667 5.1051 +0.0444 -0.0889 5.1051 +0.0556 -0.1111 5.1051 +0.0667 -0.1333 5.1051 +0.0778 -0.1556 5.1051 +0.0889 -0.1778 5.1051 +0.1000 -0.2000 5.1051 +primID: 1 +startangle_c: 13 +endpose_c: 3 -6 13 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0333 -0.0667 5.1051 +0.0667 -0.1333 5.1051 +0.1000 -0.2000 5.1051 +0.1333 -0.2667 5.1051 +0.1667 -0.3333 5.1051 +0.2000 -0.4000 5.1051 +0.2333 -0.4667 5.1051 +0.2667 -0.5333 5.1051 +0.3000 -0.6000 5.1051 +primID: 2 +startangle_c: 13 +endpose_c: -1 2 13 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.1051 +-0.0111 0.0222 5.1051 +-0.0222 0.0444 5.1051 +-0.0333 0.0667 5.1051 +-0.0444 0.0889 5.1051 +-0.0556 0.1111 5.1051 +-0.0667 0.1333 5.1051 +-0.0778 0.1556 5.1051 +-0.0889 0.1778 5.1051 +-0.1000 0.2000 5.1051 +primID: 3 +startangle_c: 13 +endpose_c: 2 -3 14 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0162 -0.0369 5.1469 +0.0339 -0.0731 5.1907 +0.0533 -0.1085 5.2346 +0.0741 -0.1430 5.2785 +0.0965 -0.1766 5.3223 +0.1203 -0.2091 5.3662 +0.1455 -0.2405 5.4101 +0.1721 -0.2709 5.4539 +0.2000 -0.3000 5.4978 +primID: 4 +startangle_c: 13 +endpose_c: 1 -4 12 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0177 -0.0427 5.1051 +0.0354 -0.0854 5.1051 +0.0523 -0.1283 5.0601 +0.0668 -0.1722 5.0021 +0.0787 -0.2168 4.9442 +0.0880 -0.2621 4.8862 +0.0947 -0.3078 4.8283 +0.0987 -0.3538 4.7703 +0.1000 -0.4000 4.7124 +primID: 5 +startangle_c: 13 +endpose_c: 0 0 14 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0000 0.0000 5.1487 +0.0000 0.0000 5.1924 +0.0000 0.0000 5.2360 +0.0000 0.0000 5.2796 +0.0000 0.0000 5.3233 +0.0000 0.0000 5.3669 +0.0000 0.0000 5.4105 +0.0000 0.0000 5.4542 +0.0000 0.0000 5.4978 +primID: 6 +startangle_c: 13 +endpose_c: 0 0 12 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0000 0.0000 5.0615 +0.0000 0.0000 5.0178 +0.0000 0.0000 4.9742 +0.0000 0.0000 4.9306 +0.0000 0.0000 4.8869 +0.0000 0.0000 4.8433 +0.0000 0.0000 4.7997 +0.0000 0.0000 4.7560 +0.0000 0.0000 4.7124 +primID: 0 +startangle_c: 14 +endpose_c: 1 -1 14 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0111 -0.0111 5.4978 +0.0222 -0.0222 5.4978 +0.0333 -0.0333 5.4978 +0.0444 -0.0444 5.4978 +0.0556 -0.0556 5.4978 +0.0667 -0.0667 5.4978 +0.0778 -0.0778 5.4978 +0.0889 -0.0889 5.4978 +0.1000 -0.1000 5.4978 +primID: 1 +startangle_c: 14 +endpose_c: 3 -3 14 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0333 -0.0333 5.4978 +0.0667 -0.0667 5.4978 +0.1000 -0.1000 5.4978 +0.1333 -0.1333 5.4978 +0.1667 -0.1667 5.4978 +0.2000 -0.2000 5.4978 +0.2333 -0.2333 5.4978 +0.2667 -0.2667 5.4978 +0.3000 -0.3000 5.4978 +primID: 2 +startangle_c: 14 +endpose_c: -1 1 14 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.4978 +-0.0111 0.0111 5.4978 +-0.0222 0.0222 5.4978 +-0.0333 0.0333 5.4978 +-0.0444 0.0444 5.4978 +-0.0556 0.0556 5.4978 +-0.0667 0.0667 5.4978 +-0.0778 0.0778 5.4978 +-0.0889 0.0889 5.4978 +-0.1000 0.1000 5.4978 +primID: 3 +startangle_c: 14 +endpose_c: 4 -2 15 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0411 -0.0262 5.5243 +0.0831 -0.0515 5.5508 +0.1260 -0.0758 5.5772 +0.1697 -0.0991 5.6037 +0.2142 -0.1214 5.6302 +0.2595 -0.1426 5.6567 +0.3056 -0.1628 5.6832 +0.3525 -0.1820 5.7097 +0.4000 -0.2000 5.7362 +primID: 4 +startangle_c: 14 +endpose_c: 2 -4 13 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0262 -0.0411 5.4713 +0.0515 -0.0831 5.4448 +0.0758 -0.1260 5.4183 +0.0991 -0.1697 5.3918 +0.1214 -0.2142 5.3654 +0.1426 -0.2595 5.3389 +0.1628 -0.3056 5.3124 +0.1820 -0.3525 5.2859 +0.2000 -0.4000 5.2594 +primID: 5 +startangle_c: 14 +endpose_c: 0 0 15 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0000 0.0000 5.5414 +0.0000 0.0000 5.5851 +0.0000 0.0000 5.6287 +0.0000 0.0000 5.6723 +0.0000 0.0000 5.7160 +0.0000 0.0000 5.7596 +0.0000 0.0000 5.8032 +0.0000 0.0000 5.8469 +0.0000 0.0000 5.8905 +primID: 6 +startangle_c: 14 +endpose_c: 0 0 13 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0000 0.0000 5.4542 +0.0000 0.0000 5.4105 +0.0000 0.0000 5.3669 +0.0000 0.0000 5.3233 +0.0000 0.0000 5.2796 +0.0000 0.0000 5.2360 +0.0000 0.0000 5.1924 +0.0000 0.0000 5.1487 +0.0000 0.0000 5.1051 +primID: 0 +startangle_c: 15 +endpose_c: 2 -1 15 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0222 -0.0111 5.8905 +0.0444 -0.0222 5.8905 +0.0667 -0.0333 5.8905 +0.0889 -0.0444 5.8905 +0.1111 -0.0556 5.8905 +0.1333 -0.0667 5.8905 +0.1556 -0.0778 5.8905 +0.1778 -0.0889 5.8905 +0.2000 -0.1000 5.8905 +primID: 1 +startangle_c: 15 +endpose_c: 6 -3 15 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0667 -0.0333 5.8905 +0.1333 -0.0667 5.8905 +0.2000 -0.1000 5.8905 +0.2667 -0.1333 5.8905 +0.3333 -0.1667 5.8905 +0.4000 -0.2000 5.8905 +0.4667 -0.2333 5.8905 +0.5333 -0.2667 5.8905 +0.6000 -0.3000 5.8905 +primID: 2 +startangle_c: 15 +endpose_c: -2 1 15 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.8905 +-0.0222 0.0111 5.8905 +-0.0444 0.0222 5.8905 +-0.0667 0.0333 5.8905 +-0.0889 0.0444 5.8905 +-0.1111 0.0556 5.8905 +-0.1333 0.0667 5.8905 +-0.1556 0.0778 5.8905 +-0.1778 0.0889 5.8905 +-0.2000 0.1000 5.8905 +primID: 3 +startangle_c: 15 +endpose_c: 3 -2 14 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0369 -0.0162 5.8487 +0.0731 -0.0339 5.8049 +0.1085 -0.0533 5.7610 +0.1430 -0.0741 5.7171 +0.1766 -0.0965 5.6733 +0.2091 -0.1203 5.6294 +0.2405 -0.1455 5.5855 +0.2709 -0.1721 5.5417 +0.3000 -0.2000 5.4978 +primID: 4 +startangle_c: 15 +endpose_c: 4 -1 0 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0427 -0.0177 5.8905 +0.0854 -0.0354 5.8905 +0.1283 -0.0523 5.9355 +0.1722 -0.0668 5.9934 +0.2168 -0.0787 6.0514 +0.2621 -0.0880 6.1093 +0.3078 -0.0947 6.1673 +0.3538 -0.0987 6.2252 +0.4000 -0.1000 6.2832 +primID: 5 +startangle_c: 15 +endpose_c: 0 0 14 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0000 0.0000 5.8469 +0.0000 0.0000 5.8032 +0.0000 0.0000 5.7596 +0.0000 0.0000 5.7160 +0.0000 0.0000 5.6723 +0.0000 0.0000 5.6287 +0.0000 0.0000 5.5851 +0.0000 0.0000 5.5414 +0.0000 0.0000 5.4978 +primID: 6 +startangle_c: 15 +endpose_c: 0 0 0 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0000 0.0000 5.2360 +0.0000 0.0000 4.5815 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.2725 +0.0000 0.0000 2.6180 +0.0000 0.0000 1.9635 +0.0000 0.0000 1.3090 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.0000 diff --git a/mir_robot/mir_navigation/mprim/unicycle_highcost_1cm.mprim b/mir_robot/mir_navigation/mprim/unicycle_highcost_1cm.mprim new file mode 100755 index 0000000..aa9670d --- /dev/null +++ b/mir_robot/mir_navigation/mprim/unicycle_highcost_1cm.mprim @@ -0,0 +1,1683 @@ +resolution_m: 0.010000 +numberofangles: 16 +totalnumberofprimitives: 112 +primID: 0 +startangle_c: 0 +endpose_c: 1 0 0 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0011 0.0000 0.0000 +0.0022 0.0000 0.0000 +0.0033 0.0000 0.0000 +0.0044 0.0000 0.0000 +0.0056 0.0000 0.0000 +0.0067 0.0000 0.0000 +0.0078 0.0000 0.0000 +0.0089 0.0000 0.0000 +0.0100 0.0000 0.0000 +primID: 1 +startangle_c: 0 +endpose_c: 20 0 0 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0222 0.0000 0.0000 +0.0444 0.0000 0.0000 +0.0667 0.0000 0.0000 +0.0889 0.0000 0.0000 +0.1111 0.0000 0.0000 +0.1333 0.0000 0.0000 +0.1556 0.0000 0.0000 +0.1778 0.0000 0.0000 +0.2000 0.0000 0.0000 +primID: 2 +startangle_c: 0 +endpose_c: -1 0 0 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.0000 +-0.0011 0.0000 0.0000 +-0.0022 0.0000 0.0000 +-0.0033 0.0000 0.0000 +-0.0044 0.0000 0.0000 +-0.0056 0.0000 0.0000 +-0.0067 0.0000 0.0000 +-0.0078 0.0000 0.0000 +-0.0089 0.0000 0.0000 +-0.0100 0.0000 0.0000 +primID: 3 +startangle_c: 0 +endpose_c: 40 5 1 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0452 -0.0000 0.0000 +0.0904 -0.0000 0.0000 +0.1355 -0.0000 0.0000 +0.1807 0.0008 0.0488 +0.2257 0.0045 0.1176 +0.2703 0.0114 0.1864 +0.3144 0.0213 0.2551 +0.3577 0.0342 0.3239 +0.4000 0.0500 0.3927 +primID: 4 +startangle_c: 0 +endpose_c: 40 -5 -1 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0452 0.0000 0.0000 +0.0904 0.0000 0.0000 +0.1355 0.0000 0.0000 +0.1807 -0.0008 -0.0488 +0.2257 -0.0045 -0.1176 +0.2703 -0.0114 -0.1864 +0.3144 -0.0213 -0.2551 +0.3577 -0.0342 -0.3239 +0.4000 -0.0500 -0.3927 +primID: 5 +startangle_c: 0 +endpose_c: 0 0 1 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0000 0.0000 0.0436 +0.0000 0.0000 0.0873 +0.0000 0.0000 0.1309 +0.0000 0.0000 0.1745 +0.0000 0.0000 0.2182 +0.0000 0.0000 0.2618 +0.0000 0.0000 0.3054 +0.0000 0.0000 0.3491 +0.0000 0.0000 0.3927 +primID: 6 +startangle_c: 0 +endpose_c: 0 0 -1 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0000 0.0000 -0.0436 +0.0000 0.0000 -0.0873 +0.0000 0.0000 -0.1309 +0.0000 0.0000 -0.1745 +0.0000 0.0000 -0.2182 +0.0000 0.0000 -0.2618 +0.0000 0.0000 -0.3054 +0.0000 0.0000 -0.3491 +0.0000 0.0000 -0.3927 +primID: 0 +startangle_c: 1 +endpose_c: 2 1 1 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0022 0.0011 0.3927 +0.0044 0.0022 0.3927 +0.0067 0.0033 0.3927 +0.0089 0.0044 0.3927 +0.0111 0.0056 0.3927 +0.0133 0.0067 0.3927 +0.0156 0.0078 0.3927 +0.0178 0.0089 0.3927 +0.0200 0.0100 0.3927 +primID: 1 +startangle_c: 1 +endpose_c: 20 10 1 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0222 0.0111 0.3927 +0.0444 0.0222 0.3927 +0.0667 0.0333 0.3927 +0.0889 0.0444 0.3927 +0.1111 0.0556 0.3927 +0.1333 0.0667 0.3927 +0.1556 0.0778 0.3927 +0.1778 0.0889 0.3927 +0.2000 0.1000 0.3927 +primID: 2 +startangle_c: 1 +endpose_c: -2 -1 1 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.3927 +-0.0022 -0.0011 0.3927 +-0.0044 -0.0022 0.3927 +-0.0067 -0.0033 0.3927 +-0.0089 -0.0044 0.3927 +-0.0111 -0.0056 0.3927 +-0.0133 -0.0067 0.3927 +-0.0156 -0.0078 0.3927 +-0.0178 -0.0089 0.3927 +-0.0200 -0.0100 0.3927 +primID: 3 +startangle_c: 1 +endpose_c: 25 20 2 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0298 0.0184 0.4230 +0.0592 0.0379 0.4533 +0.0881 0.0583 0.4836 +0.1165 0.0796 0.5139 +0.1444 0.1019 0.5442 +0.1717 0.1251 0.5745 +0.1984 0.1492 0.6048 +0.2245 0.1742 0.6351 +0.2500 0.2000 0.6654 +primID: 4 +startangle_c: 1 +endpose_c: 35 10 0 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0377 0.0156 0.3927 +0.0754 0.0312 0.3927 +0.1131 0.0468 0.3927 +0.1508 0.0623 0.3736 +0.1893 0.0758 0.2989 +0.2287 0.0863 0.2242 +0.2687 0.0939 0.1494 +0.3092 0.0985 0.0747 +0.3500 0.1000 -0.0000 +primID: 5 +startangle_c: 1 +endpose_c: 0 0 2 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0000 0.0000 0.4363 +0.0000 0.0000 0.4800 +0.0000 0.0000 0.5236 +0.0000 0.0000 0.5672 +0.0000 0.0000 0.6109 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.6981 +0.0000 0.0000 0.7418 +0.0000 0.0000 0.7854 +primID: 6 +startangle_c: 1 +endpose_c: 0 0 0 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0000 0.0000 0.3491 +0.0000 0.0000 0.3054 +0.0000 0.0000 0.2618 +0.0000 0.0000 0.2182 +0.0000 0.0000 0.1745 +0.0000 0.0000 0.1309 +0.0000 0.0000 0.0873 +0.0000 0.0000 0.0436 +0.0000 0.0000 0.0000 +primID: 0 +startangle_c: 2 +endpose_c: 1 1 2 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0011 0.0011 0.7854 +0.0022 0.0022 0.7854 +0.0033 0.0033 0.7854 +0.0044 0.0044 0.7854 +0.0056 0.0056 0.7854 +0.0067 0.0067 0.7854 +0.0078 0.0078 0.7854 +0.0089 0.0089 0.7854 +0.0100 0.0100 0.7854 +primID: 1 +startangle_c: 2 +endpose_c: 10 10 2 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0111 0.0111 0.7854 +0.0222 0.0222 0.7854 +0.0333 0.0333 0.7854 +0.0444 0.0444 0.7854 +0.0556 0.0556 0.7854 +0.0667 0.0667 0.7854 +0.0778 0.0778 0.7854 +0.0889 0.0889 0.7854 +0.1000 0.1000 0.7854 +primID: 2 +startangle_c: 2 +endpose_c: -1 -1 2 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.7854 +-0.0011 -0.0011 0.7854 +-0.0022 -0.0022 0.7854 +-0.0033 -0.0033 0.7854 +-0.0044 -0.0044 0.7854 +-0.0056 -0.0056 0.7854 +-0.0067 -0.0067 0.7854 +-0.0078 -0.0078 0.7854 +-0.0089 -0.0089 0.7854 +-0.0100 -0.0100 0.7854 +primID: 3 +startangle_c: 2 +endpose_c: 25 35 3 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0341 0.0341 0.7854 +0.0678 0.0684 0.8151 +0.1000 0.1043 0.8669 +0.1302 0.1418 0.9188 +0.1584 0.1809 0.9707 +0.1846 0.2213 1.0225 +0.2086 0.2631 1.0744 +0.2304 0.3060 1.1262 +0.2500 0.3500 1.1781 +primID: 4 +startangle_c: 2 +endpose_c: 35 25 1 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0341 0.0341 0.7854 +0.0684 0.0678 0.7557 +0.1043 0.1000 0.7039 +0.1418 0.1302 0.6520 +0.1809 0.1584 0.6001 +0.2213 0.1846 0.5483 +0.2631 0.2086 0.4964 +0.3060 0.2304 0.4446 +0.3500 0.2500 0.3927 +primID: 5 +startangle_c: 2 +endpose_c: 0 0 3 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0000 0.0000 0.8290 +0.0000 0.0000 0.8727 +0.0000 0.0000 0.9163 +0.0000 0.0000 0.9599 +0.0000 0.0000 1.0036 +0.0000 0.0000 1.0472 +0.0000 0.0000 1.0908 +0.0000 0.0000 1.1345 +0.0000 0.0000 1.1781 +primID: 6 +startangle_c: 2 +endpose_c: 0 0 1 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0000 0.0000 0.7418 +0.0000 0.0000 0.6981 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.6109 +0.0000 0.0000 0.5672 +0.0000 0.0000 0.5236 +0.0000 0.0000 0.4800 +0.0000 0.0000 0.4363 +0.0000 0.0000 0.3927 +primID: 0 +startangle_c: 3 +endpose_c: 1 2 3 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0011 0.0022 1.1781 +0.0022 0.0044 1.1781 +0.0033 0.0067 1.1781 +0.0044 0.0089 1.1781 +0.0056 0.0111 1.1781 +0.0067 0.0133 1.1781 +0.0078 0.0156 1.1781 +0.0089 0.0178 1.1781 +0.0100 0.0200 1.1781 +primID: 1 +startangle_c: 3 +endpose_c: 10 20 3 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0111 0.0222 1.1781 +0.0222 0.0444 1.1781 +0.0333 0.0667 1.1781 +0.0444 0.0889 1.1781 +0.0556 0.1111 1.1781 +0.0667 0.1333 1.1781 +0.0778 0.1556 1.1781 +0.0889 0.1778 1.1781 +0.1000 0.2000 1.1781 +primID: 2 +startangle_c: 3 +endpose_c: -1 -2 3 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.1781 +-0.0011 -0.0022 1.1781 +-0.0022 -0.0044 1.1781 +-0.0033 -0.0067 1.1781 +-0.0044 -0.0089 1.1781 +-0.0056 -0.0111 1.1781 +-0.0067 -0.0133 1.1781 +-0.0078 -0.0156 1.1781 +-0.0089 -0.0178 1.1781 +-0.0100 -0.0200 1.1781 +primID: 3 +startangle_c: 3 +endpose_c: 20 25 2 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0184 0.0298 1.1478 +0.0379 0.0592 1.1175 +0.0583 0.0881 1.0872 +0.0796 0.1165 1.0569 +0.1019 0.1444 1.0266 +0.1251 0.1717 0.9963 +0.1492 0.1984 0.9660 +0.1742 0.2245 0.9357 +0.2000 0.2500 0.9054 +primID: 4 +startangle_c: 3 +endpose_c: 10 35 4 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0156 0.0377 1.1781 +0.0312 0.0754 1.1781 +0.0468 0.1131 1.1781 +0.0623 0.1508 1.1972 +0.0758 0.1893 1.2719 +0.0863 0.2287 1.3466 +0.0939 0.2687 1.4214 +0.0985 0.3092 1.4961 +0.1000 0.3500 1.5708 +primID: 5 +startangle_c: 3 +endpose_c: 0 0 2 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0000 0.0000 1.1345 +0.0000 0.0000 1.0908 +0.0000 0.0000 1.0472 +0.0000 0.0000 1.0036 +0.0000 0.0000 0.9599 +0.0000 0.0000 0.9163 +0.0000 0.0000 0.8727 +0.0000 0.0000 0.8290 +0.0000 0.0000 0.7854 +primID: 6 +startangle_c: 3 +endpose_c: 0 0 4 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0000 0.0000 1.2217 +0.0000 0.0000 1.2654 +0.0000 0.0000 1.3090 +0.0000 0.0000 1.3526 +0.0000 0.0000 1.3963 +0.0000 0.0000 1.4399 +0.0000 0.0000 1.4835 +0.0000 0.0000 1.5272 +0.0000 0.0000 1.5708 +primID: 0 +startangle_c: 4 +endpose_c: 0 1 4 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0011 1.5708 +0.0000 0.0022 1.5708 +0.0000 0.0033 1.5708 +0.0000 0.0044 1.5708 +0.0000 0.0056 1.5708 +0.0000 0.0067 1.5708 +0.0000 0.0078 1.5708 +0.0000 0.0089 1.5708 +0.0000 0.0100 1.5708 +primID: 1 +startangle_c: 4 +endpose_c: 0 20 4 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0222 1.5708 +0.0000 0.0444 1.5708 +0.0000 0.0667 1.5708 +0.0000 0.0889 1.5708 +0.0000 0.1111 1.5708 +0.0000 0.1333 1.5708 +0.0000 0.1556 1.5708 +0.0000 0.1778 1.5708 +0.0000 0.2000 1.5708 +primID: 2 +startangle_c: 4 +endpose_c: 0 -1 4 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 -0.0011 1.5708 +0.0000 -0.0022 1.5708 +0.0000 -0.0033 1.5708 +0.0000 -0.0044 1.5708 +0.0000 -0.0056 1.5708 +0.0000 -0.0067 1.5708 +0.0000 -0.0078 1.5708 +0.0000 -0.0089 1.5708 +0.0000 -0.0100 1.5708 +primID: 3 +startangle_c: 4 +endpose_c: -5 40 5 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0452 1.5708 +0.0000 0.0904 1.5708 +0.0000 0.1355 1.5708 +-0.0008 0.1807 1.6196 +-0.0045 0.2257 1.6884 +-0.0114 0.2703 1.7572 +-0.0213 0.3144 1.8259 +-0.0342 0.3577 1.8947 +-0.0500 0.4000 1.9635 +primID: 4 +startangle_c: 4 +endpose_c: 5 40 3 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0452 1.5708 +0.0000 0.0904 1.5708 +0.0000 0.1355 1.5708 +0.0008 0.1807 1.5220 +0.0045 0.2257 1.4532 +0.0114 0.2703 1.3844 +0.0213 0.3144 1.3156 +0.0342 0.3577 1.2469 +0.0500 0.4000 1.1781 +primID: 5 +startangle_c: 4 +endpose_c: 0 0 5 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0000 1.6144 +0.0000 0.0000 1.6581 +0.0000 0.0000 1.7017 +0.0000 0.0000 1.7453 +0.0000 0.0000 1.7890 +0.0000 0.0000 1.8326 +0.0000 0.0000 1.8762 +0.0000 0.0000 1.9199 +0.0000 0.0000 1.9635 +primID: 6 +startangle_c: 4 +endpose_c: 0 0 3 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0000 1.5272 +0.0000 0.0000 1.4835 +0.0000 0.0000 1.4399 +0.0000 0.0000 1.3963 +0.0000 0.0000 1.3526 +0.0000 0.0000 1.3090 +0.0000 0.0000 1.2654 +0.0000 0.0000 1.2217 +0.0000 0.0000 1.1781 +primID: 0 +startangle_c: 5 +endpose_c: -1 2 5 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0011 0.0022 1.9635 +-0.0022 0.0044 1.9635 +-0.0033 0.0067 1.9635 +-0.0044 0.0089 1.9635 +-0.0056 0.0111 1.9635 +-0.0067 0.0133 1.9635 +-0.0078 0.0156 1.9635 +-0.0089 0.0178 1.9635 +-0.0100 0.0200 1.9635 +primID: 1 +startangle_c: 5 +endpose_c: -10 20 5 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0111 0.0222 1.9635 +-0.0222 0.0444 1.9635 +-0.0333 0.0667 1.9635 +-0.0444 0.0889 1.9635 +-0.0556 0.1111 1.9635 +-0.0667 0.1333 1.9635 +-0.0778 0.1556 1.9635 +-0.0889 0.1778 1.9635 +-0.1000 0.2000 1.9635 +primID: 2 +startangle_c: 5 +endpose_c: 1 -2 5 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0011 -0.0022 1.9635 +0.0022 -0.0044 1.9635 +0.0033 -0.0067 1.9635 +0.0044 -0.0089 1.9635 +0.0056 -0.0111 1.9635 +0.0067 -0.0133 1.9635 +0.0078 -0.0156 1.9635 +0.0089 -0.0178 1.9635 +0.0100 -0.0200 1.9635 +primID: 3 +startangle_c: 5 +endpose_c: -20 25 6 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0184 0.0298 1.9938 +-0.0379 0.0592 2.0241 +-0.0583 0.0881 2.0544 +-0.0796 0.1165 2.0847 +-0.1019 0.1444 2.1150 +-0.1251 0.1717 2.1453 +-0.1492 0.1984 2.1756 +-0.1742 0.2245 2.2059 +-0.2000 0.2500 2.2362 +primID: 4 +startangle_c: 5 +endpose_c: -10 35 4 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0156 0.0377 1.9635 +-0.0312 0.0754 1.9635 +-0.0468 0.1131 1.9635 +-0.0623 0.1508 1.9444 +-0.0758 0.1893 1.8697 +-0.0863 0.2287 1.7950 +-0.0939 0.2687 1.7202 +-0.0985 0.3092 1.6455 +-0.1000 0.3500 1.5708 +primID: 5 +startangle_c: 5 +endpose_c: 0 0 6 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0000 0.0000 2.0071 +0.0000 0.0000 2.0508 +0.0000 0.0000 2.0944 +0.0000 0.0000 2.1380 +0.0000 0.0000 2.1817 +0.0000 0.0000 2.2253 +0.0000 0.0000 2.2689 +0.0000 0.0000 2.3126 +0.0000 0.0000 2.3562 +primID: 6 +startangle_c: 5 +endpose_c: 0 0 4 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0000 0.0000 1.9199 +0.0000 0.0000 1.8762 +0.0000 0.0000 1.8326 +0.0000 0.0000 1.7890 +0.0000 0.0000 1.7453 +0.0000 0.0000 1.7017 +0.0000 0.0000 1.6581 +0.0000 0.0000 1.6144 +0.0000 0.0000 1.5708 +primID: 0 +startangle_c: 6 +endpose_c: -1 1 6 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0011 0.0011 2.3562 +-0.0022 0.0022 2.3562 +-0.0033 0.0033 2.3562 +-0.0044 0.0044 2.3562 +-0.0056 0.0056 2.3562 +-0.0067 0.0067 2.3562 +-0.0078 0.0078 2.3562 +-0.0089 0.0089 2.3562 +-0.0100 0.0100 2.3562 +primID: 1 +startangle_c: 6 +endpose_c: -10 10 6 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0111 0.0111 2.3562 +-0.0222 0.0222 2.3562 +-0.0333 0.0333 2.3562 +-0.0444 0.0444 2.3562 +-0.0556 0.0556 2.3562 +-0.0667 0.0667 2.3562 +-0.0778 0.0778 2.3562 +-0.0889 0.0889 2.3562 +-0.1000 0.1000 2.3562 +primID: 2 +startangle_c: 6 +endpose_c: 1 -1 6 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0011 -0.0011 2.3562 +0.0022 -0.0022 2.3562 +0.0033 -0.0033 2.3562 +0.0044 -0.0044 2.3562 +0.0056 -0.0056 2.3562 +0.0067 -0.0067 2.3562 +0.0078 -0.0078 2.3562 +0.0089 -0.0089 2.3562 +0.0100 -0.0100 2.3562 +primID: 3 +startangle_c: 6 +endpose_c: -35 25 7 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0341 0.0341 2.3562 +-0.0684 0.0678 2.3859 +-0.1043 0.1000 2.4377 +-0.1418 0.1302 2.4896 +-0.1809 0.1584 2.5415 +-0.2213 0.1846 2.5933 +-0.2631 0.2086 2.6452 +-0.3060 0.2304 2.6970 +-0.3500 0.2500 2.7489 +primID: 4 +startangle_c: 6 +endpose_c: -25 35 5 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0341 0.0341 2.3562 +-0.0678 0.0684 2.3265 +-0.1000 0.1043 2.2747 +-0.1302 0.1418 2.2228 +-0.1584 0.1809 2.1709 +-0.1846 0.2213 2.1191 +-0.2086 0.2631 2.0672 +-0.2304 0.3060 2.0154 +-0.2500 0.3500 1.9635 +primID: 5 +startangle_c: 6 +endpose_c: 0 0 7 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0000 0.0000 2.3998 +0.0000 0.0000 2.4435 +0.0000 0.0000 2.4871 +0.0000 0.0000 2.5307 +0.0000 0.0000 2.5744 +0.0000 0.0000 2.6180 +0.0000 0.0000 2.6616 +0.0000 0.0000 2.7053 +0.0000 0.0000 2.7489 +primID: 6 +startangle_c: 6 +endpose_c: 0 0 5 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0000 0.0000 2.3126 +0.0000 0.0000 2.2689 +0.0000 0.0000 2.2253 +0.0000 0.0000 2.1817 +0.0000 0.0000 2.1380 +0.0000 0.0000 2.0944 +0.0000 0.0000 2.0508 +0.0000 0.0000 2.0071 +0.0000 0.0000 1.9635 +primID: 0 +startangle_c: 7 +endpose_c: -2 1 7 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0022 0.0011 2.7489 +-0.0044 0.0022 2.7489 +-0.0067 0.0033 2.7489 +-0.0089 0.0044 2.7489 +-0.0111 0.0056 2.7489 +-0.0133 0.0067 2.7489 +-0.0156 0.0078 2.7489 +-0.0178 0.0089 2.7489 +-0.0200 0.0100 2.7489 +primID: 1 +startangle_c: 7 +endpose_c: -20 10 7 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0222 0.0111 2.7489 +-0.0444 0.0222 2.7489 +-0.0667 0.0333 2.7489 +-0.0889 0.0444 2.7489 +-0.1111 0.0556 2.7489 +-0.1333 0.0667 2.7489 +-0.1556 0.0778 2.7489 +-0.1778 0.0889 2.7489 +-0.2000 0.1000 2.7489 +primID: 2 +startangle_c: 7 +endpose_c: 2 -1 7 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0022 -0.0011 2.7489 +0.0044 -0.0022 2.7489 +0.0067 -0.0033 2.7489 +0.0089 -0.0044 2.7489 +0.0111 -0.0056 2.7489 +0.0133 -0.0067 2.7489 +0.0156 -0.0078 2.7489 +0.0178 -0.0089 2.7489 +0.0200 -0.0100 2.7489 +primID: 3 +startangle_c: 7 +endpose_c: -25 20 6 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0298 0.0184 2.7186 +-0.0592 0.0379 2.6883 +-0.0881 0.0583 2.6580 +-0.1165 0.0796 2.6277 +-0.1444 0.1019 2.5974 +-0.1717 0.1251 2.5671 +-0.1984 0.1492 2.5368 +-0.2245 0.1742 2.5065 +-0.2500 0.2000 2.4762 +primID: 4 +startangle_c: 7 +endpose_c: -35 10 8 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0377 0.0156 2.7489 +-0.0754 0.0312 2.7489 +-0.1131 0.0468 2.7489 +-0.1508 0.0623 2.7680 +-0.1893 0.0758 2.8427 +-0.2287 0.0863 2.9174 +-0.2687 0.0939 2.9921 +-0.3092 0.0985 3.0669 +-0.3500 0.1000 3.1416 +primID: 5 +startangle_c: 7 +endpose_c: 0 0 6 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0000 0.0000 2.7053 +0.0000 0.0000 2.6616 +0.0000 0.0000 2.6180 +0.0000 0.0000 2.5744 +0.0000 0.0000 2.5307 +0.0000 0.0000 2.4871 +0.0000 0.0000 2.4435 +0.0000 0.0000 2.3998 +0.0000 0.0000 2.3562 +primID: 6 +startangle_c: 7 +endpose_c: 0 0 8 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0000 0.0000 2.7925 +0.0000 0.0000 2.8362 +0.0000 0.0000 2.8798 +0.0000 0.0000 2.9234 +0.0000 0.0000 2.9671 +0.0000 0.0000 3.0107 +0.0000 0.0000 3.0543 +0.0000 0.0000 3.0980 +0.0000 0.0000 3.1416 +primID: 0 +startangle_c: 8 +endpose_c: -1 0 8 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0011 0.0000 3.1416 +-0.0022 0.0000 3.1416 +-0.0033 0.0000 3.1416 +-0.0044 0.0000 3.1416 +-0.0056 0.0000 3.1416 +-0.0067 0.0000 3.1416 +-0.0078 0.0000 3.1416 +-0.0089 0.0000 3.1416 +-0.0100 0.0000 3.1416 +primID: 1 +startangle_c: 8 +endpose_c: -20 0 8 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0222 0.0000 3.1416 +-0.0444 0.0000 3.1416 +-0.0667 0.0000 3.1416 +-0.0889 0.0000 3.1416 +-0.1111 0.0000 3.1416 +-0.1333 0.0000 3.1416 +-0.1556 0.0000 3.1416 +-0.1778 0.0000 3.1416 +-0.2000 0.0000 3.1416 +primID: 2 +startangle_c: 8 +endpose_c: 1 0 8 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0011 0.0000 3.1416 +0.0022 0.0000 3.1416 +0.0033 0.0000 3.1416 +0.0044 0.0000 3.1416 +0.0056 0.0000 3.1416 +0.0067 0.0000 3.1416 +0.0078 0.0000 3.1416 +0.0089 0.0000 3.1416 +0.0100 0.0000 3.1416 +primID: 3 +startangle_c: 8 +endpose_c: -40 -5 9 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0452 0.0000 3.1416 +-0.0904 0.0000 3.1416 +-0.1355 0.0000 3.1416 +-0.1807 -0.0008 3.1904 +-0.2257 -0.0045 3.2592 +-0.2703 -0.0114 3.3280 +-0.3144 -0.0213 3.3967 +-0.3577 -0.0342 3.4655 +-0.4000 -0.0500 3.5343 +primID: 4 +startangle_c: 8 +endpose_c: -40 5 7 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0452 0.0000 3.1416 +-0.0904 0.0000 3.1416 +-0.1355 0.0000 3.1416 +-0.1807 0.0008 3.0928 +-0.2257 0.0045 3.0240 +-0.2703 0.0114 2.9552 +-0.3144 0.0213 2.8864 +-0.3577 0.0342 2.8177 +-0.4000 0.0500 2.7489 +primID: 5 +startangle_c: 8 +endpose_c: 0 0 9 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0000 0.0000 3.1852 +0.0000 0.0000 3.2289 +0.0000 0.0000 3.2725 +0.0000 0.0000 3.3161 +0.0000 0.0000 3.3598 +0.0000 0.0000 3.4034 +0.0000 0.0000 3.4470 +0.0000 0.0000 3.4907 +0.0000 0.0000 3.5343 +primID: 6 +startangle_c: 8 +endpose_c: 0 0 7 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0000 0.0000 3.0980 +0.0000 0.0000 3.0543 +0.0000 0.0000 3.0107 +0.0000 0.0000 2.9671 +0.0000 0.0000 2.9234 +0.0000 0.0000 2.8798 +0.0000 0.0000 2.8362 +0.0000 0.0000 2.7925 +0.0000 0.0000 2.7489 +primID: 0 +startangle_c: 9 +endpose_c: -2 -1 9 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0022 -0.0011 3.5343 +-0.0044 -0.0022 3.5343 +-0.0067 -0.0033 3.5343 +-0.0089 -0.0044 3.5343 +-0.0111 -0.0056 3.5343 +-0.0133 -0.0067 3.5343 +-0.0156 -0.0078 3.5343 +-0.0178 -0.0089 3.5343 +-0.0200 -0.0100 3.5343 +primID: 1 +startangle_c: 9 +endpose_c: -20 -10 9 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0222 -0.0111 3.5343 +-0.0444 -0.0222 3.5343 +-0.0667 -0.0333 3.5343 +-0.0889 -0.0444 3.5343 +-0.1111 -0.0556 3.5343 +-0.1333 -0.0667 3.5343 +-0.1556 -0.0778 3.5343 +-0.1778 -0.0889 3.5343 +-0.2000 -0.1000 3.5343 +primID: 2 +startangle_c: 9 +endpose_c: 2 1 9 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0022 0.0011 3.5343 +0.0044 0.0022 3.5343 +0.0067 0.0033 3.5343 +0.0089 0.0044 3.5343 +0.0111 0.0056 3.5343 +0.0133 0.0067 3.5343 +0.0156 0.0078 3.5343 +0.0178 0.0089 3.5343 +0.0200 0.0100 3.5343 +primID: 3 +startangle_c: 9 +endpose_c: -25 -20 10 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0298 -0.0184 3.5646 +-0.0592 -0.0379 3.5949 +-0.0881 -0.0583 3.6252 +-0.1165 -0.0796 3.6555 +-0.1444 -0.1019 3.6858 +-0.1717 -0.1251 3.7161 +-0.1984 -0.1492 3.7464 +-0.2245 -0.1742 3.7767 +-0.2500 -0.2000 3.8070 +primID: 4 +startangle_c: 9 +endpose_c: -35 -10 8 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0377 -0.0156 3.5343 +-0.0754 -0.0312 3.5343 +-0.1131 -0.0468 3.5343 +-0.1508 -0.0623 3.5152 +-0.1893 -0.0758 3.4405 +-0.2287 -0.0863 3.3658 +-0.2687 -0.0939 3.2910 +-0.3092 -0.0985 3.2163 +-0.3500 -0.1000 3.1416 +primID: 5 +startangle_c: 9 +endpose_c: 0 0 10 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0000 0.0000 3.5779 +0.0000 0.0000 3.6216 +0.0000 0.0000 3.6652 +0.0000 0.0000 3.7088 +0.0000 0.0000 3.7525 +0.0000 0.0000 3.7961 +0.0000 0.0000 3.8397 +0.0000 0.0000 3.8834 +0.0000 0.0000 3.9270 +primID: 6 +startangle_c: 9 +endpose_c: 0 0 8 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0000 0.0000 3.4907 +0.0000 0.0000 3.4470 +0.0000 0.0000 3.4034 +0.0000 0.0000 3.3598 +0.0000 0.0000 3.3161 +0.0000 0.0000 3.2725 +0.0000 0.0000 3.2289 +0.0000 0.0000 3.1852 +0.0000 0.0000 3.1416 +primID: 0 +startangle_c: 10 +endpose_c: -1 -1 10 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0011 -0.0011 3.9270 +-0.0022 -0.0022 3.9270 +-0.0033 -0.0033 3.9270 +-0.0044 -0.0044 3.9270 +-0.0056 -0.0056 3.9270 +-0.0067 -0.0067 3.9270 +-0.0078 -0.0078 3.9270 +-0.0089 -0.0089 3.9270 +-0.0100 -0.0100 3.9270 +primID: 1 +startangle_c: 10 +endpose_c: -10 -10 10 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0111 -0.0111 3.9270 +-0.0222 -0.0222 3.9270 +-0.0333 -0.0333 3.9270 +-0.0444 -0.0444 3.9270 +-0.0556 -0.0556 3.9270 +-0.0667 -0.0667 3.9270 +-0.0778 -0.0778 3.9270 +-0.0889 -0.0889 3.9270 +-0.1000 -0.1000 3.9270 +primID: 2 +startangle_c: 10 +endpose_c: 1 1 10 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0011 0.0011 3.9270 +0.0022 0.0022 3.9270 +0.0033 0.0033 3.9270 +0.0044 0.0044 3.9270 +0.0056 0.0056 3.9270 +0.0067 0.0067 3.9270 +0.0078 0.0078 3.9270 +0.0089 0.0089 3.9270 +0.0100 0.0100 3.9270 +primID: 3 +startangle_c: 10 +endpose_c: -25 -35 11 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0341 -0.0341 3.9270 +-0.0678 -0.0684 3.9567 +-0.1000 -0.1043 4.0085 +-0.1302 -0.1418 4.0604 +-0.1584 -0.1809 4.1123 +-0.1846 -0.2213 4.1641 +-0.2086 -0.2631 4.2160 +-0.2304 -0.3060 4.2678 +-0.2500 -0.3500 4.3197 +primID: 4 +startangle_c: 10 +endpose_c: -35 -25 9 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0341 -0.0341 3.9270 +-0.0684 -0.0678 3.8973 +-0.1043 -0.1000 3.8455 +-0.1418 -0.1302 3.7936 +-0.1809 -0.1584 3.7417 +-0.2213 -0.1846 3.6899 +-0.2631 -0.2086 3.6380 +-0.3060 -0.2304 3.5862 +-0.3500 -0.2500 3.5343 +primID: 5 +startangle_c: 10 +endpose_c: 0 0 11 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.9706 +0.0000 0.0000 4.0143 +0.0000 0.0000 4.0579 +0.0000 0.0000 4.1015 +0.0000 0.0000 4.1452 +0.0000 0.0000 4.1888 +0.0000 0.0000 4.2324 +0.0000 0.0000 4.2761 +0.0000 0.0000 4.3197 +primID: 6 +startangle_c: 10 +endpose_c: 0 0 9 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.8834 +0.0000 0.0000 3.8397 +0.0000 0.0000 3.7961 +0.0000 0.0000 3.7525 +0.0000 0.0000 3.7088 +0.0000 0.0000 3.6652 +0.0000 0.0000 3.6216 +0.0000 0.0000 3.5779 +0.0000 0.0000 3.5343 +primID: 0 +startangle_c: 11 +endpose_c: -1 -2 11 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0011 -0.0022 4.3197 +-0.0022 -0.0044 4.3197 +-0.0033 -0.0067 4.3197 +-0.0044 -0.0089 4.3197 +-0.0056 -0.0111 4.3197 +-0.0067 -0.0133 4.3197 +-0.0078 -0.0156 4.3197 +-0.0089 -0.0178 4.3197 +-0.0100 -0.0200 4.3197 +primID: 1 +startangle_c: 11 +endpose_c: -10 -20 11 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0111 -0.0222 4.3197 +-0.0222 -0.0444 4.3197 +-0.0333 -0.0667 4.3197 +-0.0444 -0.0889 4.3197 +-0.0556 -0.1111 4.3197 +-0.0667 -0.1333 4.3197 +-0.0778 -0.1556 4.3197 +-0.0889 -0.1778 4.3197 +-0.1000 -0.2000 4.3197 +primID: 2 +startangle_c: 11 +endpose_c: 1 2 11 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0011 0.0022 4.3197 +0.0022 0.0044 4.3197 +0.0033 0.0067 4.3197 +0.0044 0.0089 4.3197 +0.0056 0.0111 4.3197 +0.0067 0.0133 4.3197 +0.0078 0.0156 4.3197 +0.0089 0.0178 4.3197 +0.0100 0.0200 4.3197 +primID: 3 +startangle_c: 11 +endpose_c: -20 -25 10 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0184 -0.0298 4.2894 +-0.0379 -0.0592 4.2591 +-0.0583 -0.0881 4.2288 +-0.0796 -0.1165 4.1985 +-0.1019 -0.1444 4.1682 +-0.1251 -0.1717 4.1379 +-0.1492 -0.1984 4.1076 +-0.1742 -0.2245 4.0773 +-0.2000 -0.2500 4.0470 +primID: 4 +startangle_c: 11 +endpose_c: -10 -35 12 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0156 -0.0377 4.3197 +-0.0312 -0.0754 4.3197 +-0.0468 -0.1131 4.3197 +-0.0623 -0.1508 4.3388 +-0.0758 -0.1893 4.4135 +-0.0863 -0.2287 4.4882 +-0.0939 -0.2687 4.5629 +-0.0985 -0.3092 4.6377 +-0.1000 -0.3500 4.7124 +primID: 5 +startangle_c: 11 +endpose_c: 0 0 10 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0000 0.0000 4.2761 +0.0000 0.0000 4.2324 +0.0000 0.0000 4.1888 +0.0000 0.0000 4.1452 +0.0000 0.0000 4.1015 +0.0000 0.0000 4.0579 +0.0000 0.0000 4.0143 +0.0000 0.0000 3.9706 +0.0000 0.0000 3.9270 +primID: 6 +startangle_c: 11 +endpose_c: 0 0 12 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0000 0.0000 4.3633 +0.0000 0.0000 4.4070 +0.0000 0.0000 4.4506 +0.0000 0.0000 4.4942 +0.0000 0.0000 4.5379 +0.0000 0.0000 4.5815 +0.0000 0.0000 4.6251 +0.0000 0.0000 4.6688 +0.0000 0.0000 4.7124 +primID: 0 +startangle_c: 12 +endpose_c: 0 -1 12 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0011 4.7124 +0.0000 -0.0022 4.7124 +0.0000 -0.0033 4.7124 +0.0000 -0.0044 4.7124 +0.0000 -0.0056 4.7124 +0.0000 -0.0067 4.7124 +0.0000 -0.0078 4.7124 +0.0000 -0.0089 4.7124 +0.0000 -0.0100 4.7124 +primID: 1 +startangle_c: 12 +endpose_c: 0 -20 12 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0222 4.7124 +0.0000 -0.0444 4.7124 +0.0000 -0.0667 4.7124 +0.0000 -0.0889 4.7124 +0.0000 -0.1111 4.7124 +0.0000 -0.1333 4.7124 +0.0000 -0.1556 4.7124 +0.0000 -0.1778 4.7124 +0.0000 -0.2000 4.7124 +primID: 2 +startangle_c: 12 +endpose_c: 0 1 12 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0011 4.7124 +0.0000 0.0022 4.7124 +0.0000 0.0033 4.7124 +0.0000 0.0044 4.7124 +0.0000 0.0056 4.7124 +0.0000 0.0067 4.7124 +0.0000 0.0078 4.7124 +0.0000 0.0089 4.7124 +0.0000 0.0100 4.7124 +primID: 3 +startangle_c: 12 +endpose_c: 5 -40 13 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0452 4.7124 +0.0000 -0.0904 4.7124 +0.0000 -0.1355 4.7124 +0.0008 -0.1807 4.7612 +0.0045 -0.2257 4.8300 +0.0114 -0.2703 4.8988 +0.0213 -0.3144 4.9675 +0.0342 -0.3577 5.0363 +0.0500 -0.4000 5.1051 +primID: 4 +startangle_c: 12 +endpose_c: -5 -40 11 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.7124 +-0.0000 -0.0452 4.7124 +-0.0000 -0.0904 4.7124 +-0.0000 -0.1355 4.7124 +-0.0008 -0.1807 4.6636 +-0.0045 -0.2257 4.5948 +-0.0114 -0.2703 4.5260 +-0.0213 -0.3144 4.4572 +-0.0342 -0.3577 4.3885 +-0.0500 -0.4000 4.3197 +primID: 5 +startangle_c: 12 +endpose_c: 0 0 13 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0000 4.7560 +0.0000 0.0000 4.7997 +0.0000 0.0000 4.8433 +0.0000 0.0000 4.8869 +0.0000 0.0000 4.9306 +0.0000 0.0000 4.9742 +0.0000 0.0000 5.0178 +0.0000 0.0000 5.0615 +0.0000 0.0000 5.1051 +primID: 6 +startangle_c: 12 +endpose_c: 0 0 11 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0000 4.6688 +0.0000 0.0000 4.6251 +0.0000 0.0000 4.5815 +0.0000 0.0000 4.5379 +0.0000 0.0000 4.4942 +0.0000 0.0000 4.4506 +0.0000 0.0000 4.4070 +0.0000 0.0000 4.3633 +0.0000 0.0000 4.3197 +primID: 0 +startangle_c: 13 +endpose_c: 1 -2 13 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0011 -0.0022 5.1051 +0.0022 -0.0044 5.1051 +0.0033 -0.0067 5.1051 +0.0044 -0.0089 5.1051 +0.0056 -0.0111 5.1051 +0.0067 -0.0133 5.1051 +0.0078 -0.0156 5.1051 +0.0089 -0.0178 5.1051 +0.0100 -0.0200 5.1051 +primID: 1 +startangle_c: 13 +endpose_c: 10 -20 13 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0111 -0.0222 5.1051 +0.0222 -0.0444 5.1051 +0.0333 -0.0667 5.1051 +0.0444 -0.0889 5.1051 +0.0556 -0.1111 5.1051 +0.0667 -0.1333 5.1051 +0.0778 -0.1556 5.1051 +0.0889 -0.1778 5.1051 +0.1000 -0.2000 5.1051 +primID: 2 +startangle_c: 13 +endpose_c: -1 2 13 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.1051 +-0.0011 0.0022 5.1051 +-0.0022 0.0044 5.1051 +-0.0033 0.0067 5.1051 +-0.0044 0.0089 5.1051 +-0.0056 0.0111 5.1051 +-0.0067 0.0133 5.1051 +-0.0078 0.0156 5.1051 +-0.0089 0.0178 5.1051 +-0.0100 0.0200 5.1051 +primID: 3 +startangle_c: 13 +endpose_c: 20 -25 14 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0184 -0.0298 5.1354 +0.0379 -0.0592 5.1657 +0.0583 -0.0881 5.1960 +0.0796 -0.1165 5.2263 +0.1019 -0.1444 5.2566 +0.1251 -0.1717 5.2869 +0.1492 -0.1984 5.3172 +0.1742 -0.2245 5.3475 +0.2000 -0.2500 5.3778 +primID: 4 +startangle_c: 13 +endpose_c: 10 -35 12 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0156 -0.0377 5.1051 +0.0312 -0.0754 5.1051 +0.0468 -0.1131 5.1051 +0.0623 -0.1508 5.0860 +0.0758 -0.1893 5.0113 +0.0863 -0.2287 4.9366 +0.0939 -0.2687 4.8618 +0.0985 -0.3092 4.7871 +0.1000 -0.3500 4.7124 +primID: 5 +startangle_c: 13 +endpose_c: 0 0 14 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0000 0.0000 5.1487 +0.0000 0.0000 5.1924 +0.0000 0.0000 5.2360 +0.0000 0.0000 5.2796 +0.0000 0.0000 5.3233 +0.0000 0.0000 5.3669 +0.0000 0.0000 5.4105 +0.0000 0.0000 5.4542 +0.0000 0.0000 5.4978 +primID: 6 +startangle_c: 13 +endpose_c: 0 0 12 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0000 0.0000 5.0615 +0.0000 0.0000 5.0178 +0.0000 0.0000 4.9742 +0.0000 0.0000 4.9306 +0.0000 0.0000 4.8869 +0.0000 0.0000 4.8433 +0.0000 0.0000 4.7997 +0.0000 0.0000 4.7560 +0.0000 0.0000 4.7124 +primID: 0 +startangle_c: 14 +endpose_c: 1 -1 14 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0011 -0.0011 5.4978 +0.0022 -0.0022 5.4978 +0.0033 -0.0033 5.4978 +0.0044 -0.0044 5.4978 +0.0056 -0.0056 5.4978 +0.0067 -0.0067 5.4978 +0.0078 -0.0078 5.4978 +0.0089 -0.0089 5.4978 +0.0100 -0.0100 5.4978 +primID: 1 +startangle_c: 14 +endpose_c: 10 -10 14 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0111 -0.0111 5.4978 +0.0222 -0.0222 5.4978 +0.0333 -0.0333 5.4978 +0.0444 -0.0444 5.4978 +0.0556 -0.0556 5.4978 +0.0667 -0.0667 5.4978 +0.0778 -0.0778 5.4978 +0.0889 -0.0889 5.4978 +0.1000 -0.1000 5.4978 +primID: 2 +startangle_c: 14 +endpose_c: -1 1 14 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.4978 +-0.0011 0.0011 5.4978 +-0.0022 0.0022 5.4978 +-0.0033 0.0033 5.4978 +-0.0044 0.0044 5.4978 +-0.0056 0.0056 5.4978 +-0.0067 0.0067 5.4978 +-0.0078 0.0078 5.4978 +-0.0089 0.0089 5.4978 +-0.0100 0.0100 5.4978 +primID: 3 +startangle_c: 14 +endpose_c: 35 -25 15 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0341 -0.0341 5.4978 +0.0684 -0.0678 5.5275 +0.1043 -0.1000 5.5793 +0.1418 -0.1302 5.6312 +0.1809 -0.1584 5.6830 +0.2213 -0.1846 5.7349 +0.2631 -0.2086 5.7868 +0.3060 -0.2304 5.8386 +0.3500 -0.2500 5.8905 +primID: 4 +startangle_c: 14 +endpose_c: 25 -35 13 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0341 -0.0341 5.4978 +0.0678 -0.0684 5.4681 +0.1000 -0.1043 5.4162 +0.1302 -0.1418 5.3644 +0.1584 -0.1809 5.3125 +0.1846 -0.2213 5.2607 +0.2086 -0.2631 5.2088 +0.2304 -0.3060 5.1569 +0.2500 -0.3500 5.1051 +primID: 5 +startangle_c: 14 +endpose_c: 0 0 15 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0000 0.0000 5.5414 +0.0000 0.0000 5.5851 +0.0000 0.0000 5.6287 +0.0000 0.0000 5.6723 +0.0000 0.0000 5.7160 +0.0000 0.0000 5.7596 +0.0000 0.0000 5.8032 +0.0000 0.0000 5.8469 +0.0000 0.0000 5.8905 +primID: 6 +startangle_c: 14 +endpose_c: 0 0 13 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0000 0.0000 5.4542 +0.0000 0.0000 5.4105 +0.0000 0.0000 5.3669 +0.0000 0.0000 5.3233 +0.0000 0.0000 5.2796 +0.0000 0.0000 5.2360 +0.0000 0.0000 5.1924 +0.0000 0.0000 5.1487 +0.0000 0.0000 5.1051 +primID: 0 +startangle_c: 15 +endpose_c: 2 -1 15 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0022 -0.0011 5.8905 +0.0044 -0.0022 5.8905 +0.0067 -0.0033 5.8905 +0.0089 -0.0044 5.8905 +0.0111 -0.0056 5.8905 +0.0133 -0.0067 5.8905 +0.0156 -0.0078 5.8905 +0.0178 -0.0089 5.8905 +0.0200 -0.0100 5.8905 +primID: 1 +startangle_c: 15 +endpose_c: 20 -10 15 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0222 -0.0111 5.8905 +0.0444 -0.0222 5.8905 +0.0667 -0.0333 5.8905 +0.0889 -0.0444 5.8905 +0.1111 -0.0556 5.8905 +0.1333 -0.0667 5.8905 +0.1556 -0.0778 5.8905 +0.1778 -0.0889 5.8905 +0.2000 -0.1000 5.8905 +primID: 2 +startangle_c: 15 +endpose_c: -2 1 15 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.8905 +-0.0022 0.0011 5.8905 +-0.0044 0.0022 5.8905 +-0.0067 0.0033 5.8905 +-0.0089 0.0044 5.8905 +-0.0111 0.0056 5.8905 +-0.0133 0.0067 5.8905 +-0.0156 0.0078 5.8905 +-0.0178 0.0089 5.8905 +-0.0200 0.0100 5.8905 +primID: 3 +startangle_c: 15 +endpose_c: 25 -20 14 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0298 -0.0184 5.8602 +0.0592 -0.0379 5.8299 +0.0881 -0.0583 5.7996 +0.1165 -0.0796 5.7693 +0.1444 -0.1019 5.7390 +0.1717 -0.1251 5.7087 +0.1984 -0.1492 5.6784 +0.2245 -0.1742 5.6481 +0.2500 -0.2000 5.6178 +primID: 4 +startangle_c: 15 +endpose_c: 35 -10 0 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0377 -0.0156 5.8905 +0.0754 -0.0312 5.8905 +0.1131 -0.0468 5.8905 +0.1508 -0.0623 5.9096 +0.1893 -0.0758 5.9843 +0.2287 -0.0863 6.0590 +0.2687 -0.0939 6.1337 +0.3092 -0.0985 6.2085 +0.3500 -0.1000 6.2832 +primID: 5 +startangle_c: 15 +endpose_c: 0 0 14 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0000 0.0000 5.8469 +0.0000 0.0000 5.8032 +0.0000 0.0000 5.7596 +0.0000 0.0000 5.7160 +0.0000 0.0000 5.6723 +0.0000 0.0000 5.6287 +0.0000 0.0000 5.5851 +0.0000 0.0000 5.5414 +0.0000 0.0000 5.4978 +primID: 6 +startangle_c: 15 +endpose_c: 0 0 0 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0000 0.0000 5.2360 +0.0000 0.0000 4.5815 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.2725 +0.0000 0.0000 2.6180 +0.0000 0.0000 1.9635 +0.0000 0.0000 1.3090 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.0000 diff --git a/mir_robot/mir_navigation/mprim/unicycle_highcost_2_5cm.mprim b/mir_robot/mir_navigation/mprim/unicycle_highcost_2_5cm.mprim new file mode 100755 index 0000000..6bf962e --- /dev/null +++ b/mir_robot/mir_navigation/mprim/unicycle_highcost_2_5cm.mprim @@ -0,0 +1,1683 @@ +resolution_m: 0.025000 +numberofangles: 16 +totalnumberofprimitives: 112 +primID: 0 +startangle_c: 0 +endpose_c: 1 0 0 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0028 0.0000 0.0000 +0.0056 0.0000 0.0000 +0.0083 0.0000 0.0000 +0.0111 0.0000 0.0000 +0.0139 0.0000 0.0000 +0.0167 0.0000 0.0000 +0.0194 0.0000 0.0000 +0.0222 0.0000 0.0000 +0.0250 0.0000 0.0000 +primID: 1 +startangle_c: 0 +endpose_c: 12 0 0 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0333 0.0000 0.0000 +0.0667 0.0000 0.0000 +0.1000 0.0000 0.0000 +0.1333 0.0000 0.0000 +0.1667 0.0000 0.0000 +0.2000 0.0000 0.0000 +0.2333 0.0000 0.0000 +0.2667 0.0000 0.0000 +0.3000 0.0000 0.0000 +primID: 2 +startangle_c: 0 +endpose_c: -1 0 0 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.0000 +-0.0028 0.0000 0.0000 +-0.0056 0.0000 0.0000 +-0.0083 0.0000 0.0000 +-0.0111 0.0000 0.0000 +-0.0139 0.0000 0.0000 +-0.0167 0.0000 0.0000 +-0.0194 0.0000 0.0000 +-0.0222 0.0000 0.0000 +-0.0250 0.0000 0.0000 +primID: 3 +startangle_c: 0 +endpose_c: 16 2 1 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0452 -0.0000 0.0000 +0.0904 -0.0000 0.0000 +0.1355 -0.0000 0.0000 +0.1807 0.0008 0.0488 +0.2257 0.0045 0.1176 +0.2703 0.0114 0.1864 +0.3144 0.0213 0.2551 +0.3577 0.0342 0.3239 +0.4000 0.0500 0.3927 +primID: 4 +startangle_c: 0 +endpose_c: 16 -2 -1 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0452 0.0000 0.0000 +0.0904 0.0000 0.0000 +0.1355 0.0000 0.0000 +0.1807 -0.0008 -0.0488 +0.2257 -0.0045 -0.1176 +0.2703 -0.0114 -0.1864 +0.3144 -0.0213 -0.2551 +0.3577 -0.0342 -0.3239 +0.4000 -0.0500 -0.3927 +primID: 5 +startangle_c: 0 +endpose_c: 0 0 1 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0000 0.0000 0.0436 +0.0000 0.0000 0.0873 +0.0000 0.0000 0.1309 +0.0000 0.0000 0.1745 +0.0000 0.0000 0.2182 +0.0000 0.0000 0.2618 +0.0000 0.0000 0.3054 +0.0000 0.0000 0.3491 +0.0000 0.0000 0.3927 +primID: 6 +startangle_c: 0 +endpose_c: 0 0 -1 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0000 0.0000 -0.0436 +0.0000 0.0000 -0.0873 +0.0000 0.0000 -0.1309 +0.0000 0.0000 -0.1745 +0.0000 0.0000 -0.2182 +0.0000 0.0000 -0.2618 +0.0000 0.0000 -0.3054 +0.0000 0.0000 -0.3491 +0.0000 0.0000 -0.3927 +primID: 0 +startangle_c: 1 +endpose_c: 2 1 1 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0056 0.0028 0.3927 +0.0111 0.0056 0.3927 +0.0167 0.0083 0.3927 +0.0222 0.0111 0.3927 +0.0278 0.0139 0.3927 +0.0333 0.0167 0.3927 +0.0389 0.0194 0.3927 +0.0444 0.0222 0.3927 +0.0500 0.0250 0.3927 +primID: 1 +startangle_c: 1 +endpose_c: 12 6 1 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0333 0.0167 0.3927 +0.0667 0.0333 0.3927 +0.1000 0.0500 0.3927 +0.1333 0.0667 0.3927 +0.1667 0.0833 0.3927 +0.2000 0.1000 0.3927 +0.2333 0.1167 0.3927 +0.2667 0.1333 0.3927 +0.3000 0.1500 0.3927 +primID: 2 +startangle_c: 1 +endpose_c: -2 -1 1 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.3927 +-0.0056 -0.0028 0.3927 +-0.0111 -0.0056 0.3927 +-0.0167 -0.0083 0.3927 +-0.0222 -0.0111 0.3927 +-0.0278 -0.0139 0.3927 +-0.0333 -0.0167 0.3927 +-0.0389 -0.0194 0.3927 +-0.0444 -0.0222 0.3927 +-0.0500 -0.0250 0.3927 +primID: 3 +startangle_c: 1 +endpose_c: 10 8 2 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0298 0.0184 0.4230 +0.0592 0.0379 0.4533 +0.0881 0.0583 0.4836 +0.1165 0.0796 0.5139 +0.1444 0.1019 0.5442 +0.1717 0.1251 0.5745 +0.1984 0.1492 0.6048 +0.2245 0.1742 0.6351 +0.2500 0.2000 0.6654 +primID: 4 +startangle_c: 1 +endpose_c: 14 4 0 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0377 0.0156 0.3927 +0.0754 0.0312 0.3927 +0.1131 0.0468 0.3927 +0.1508 0.0623 0.3736 +0.1893 0.0758 0.2989 +0.2287 0.0863 0.2242 +0.2687 0.0939 0.1494 +0.3092 0.0985 0.0747 +0.3500 0.1000 -0.0000 +primID: 5 +startangle_c: 1 +endpose_c: 0 0 2 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0000 0.0000 0.4363 +0.0000 0.0000 0.4800 +0.0000 0.0000 0.5236 +0.0000 0.0000 0.5672 +0.0000 0.0000 0.6109 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.6981 +0.0000 0.0000 0.7418 +0.0000 0.0000 0.7854 +primID: 6 +startangle_c: 1 +endpose_c: 0 0 0 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0000 0.0000 0.3491 +0.0000 0.0000 0.3054 +0.0000 0.0000 0.2618 +0.0000 0.0000 0.2182 +0.0000 0.0000 0.1745 +0.0000 0.0000 0.1309 +0.0000 0.0000 0.0873 +0.0000 0.0000 0.0436 +0.0000 0.0000 0.0000 +primID: 0 +startangle_c: 2 +endpose_c: 1 1 2 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0028 0.0028 0.7854 +0.0056 0.0056 0.7854 +0.0083 0.0083 0.7854 +0.0111 0.0111 0.7854 +0.0139 0.0139 0.7854 +0.0167 0.0167 0.7854 +0.0194 0.0194 0.7854 +0.0222 0.0222 0.7854 +0.0250 0.0250 0.7854 +primID: 1 +startangle_c: 2 +endpose_c: 12 12 2 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0333 0.0333 0.7854 +0.0667 0.0667 0.7854 +0.1000 0.1000 0.7854 +0.1333 0.1333 0.7854 +0.1667 0.1667 0.7854 +0.2000 0.2000 0.7854 +0.2333 0.2333 0.7854 +0.2667 0.2667 0.7854 +0.3000 0.3000 0.7854 +primID: 2 +startangle_c: 2 +endpose_c: -1 -1 2 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.7854 +-0.0028 -0.0028 0.7854 +-0.0056 -0.0056 0.7854 +-0.0083 -0.0083 0.7854 +-0.0111 -0.0111 0.7854 +-0.0139 -0.0139 0.7854 +-0.0167 -0.0167 0.7854 +-0.0194 -0.0194 0.7854 +-0.0222 -0.0222 0.7854 +-0.0250 -0.0250 0.7854 +primID: 3 +startangle_c: 2 +endpose_c: 10 14 3 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0341 0.0341 0.7854 +0.0678 0.0684 0.8151 +0.1000 0.1043 0.8669 +0.1302 0.1418 0.9188 +0.1584 0.1809 0.9707 +0.1846 0.2213 1.0225 +0.2086 0.2631 1.0744 +0.2304 0.3060 1.1262 +0.2500 0.3500 1.1781 +primID: 4 +startangle_c: 2 +endpose_c: 14 10 1 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0341 0.0341 0.7854 +0.0684 0.0678 0.7557 +0.1043 0.1000 0.7039 +0.1418 0.1302 0.6520 +0.1809 0.1584 0.6001 +0.2213 0.1846 0.5483 +0.2631 0.2086 0.4964 +0.3060 0.2304 0.4446 +0.3500 0.2500 0.3927 +primID: 5 +startangle_c: 2 +endpose_c: 0 0 3 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0000 0.0000 0.8290 +0.0000 0.0000 0.8727 +0.0000 0.0000 0.9163 +0.0000 0.0000 0.9599 +0.0000 0.0000 1.0036 +0.0000 0.0000 1.0472 +0.0000 0.0000 1.0908 +0.0000 0.0000 1.1345 +0.0000 0.0000 1.1781 +primID: 6 +startangle_c: 2 +endpose_c: 0 0 1 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0000 0.0000 0.7418 +0.0000 0.0000 0.6981 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.6109 +0.0000 0.0000 0.5672 +0.0000 0.0000 0.5236 +0.0000 0.0000 0.4800 +0.0000 0.0000 0.4363 +0.0000 0.0000 0.3927 +primID: 0 +startangle_c: 3 +endpose_c: 1 2 3 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0028 0.0056 1.1781 +0.0056 0.0111 1.1781 +0.0083 0.0167 1.1781 +0.0111 0.0222 1.1781 +0.0139 0.0278 1.1781 +0.0167 0.0333 1.1781 +0.0194 0.0389 1.1781 +0.0222 0.0444 1.1781 +0.0250 0.0500 1.1781 +primID: 1 +startangle_c: 3 +endpose_c: 6 12 3 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0167 0.0333 1.1781 +0.0333 0.0667 1.1781 +0.0500 0.1000 1.1781 +0.0667 0.1333 1.1781 +0.0833 0.1667 1.1781 +0.1000 0.2000 1.1781 +0.1167 0.2333 1.1781 +0.1333 0.2667 1.1781 +0.1500 0.3000 1.1781 +primID: 2 +startangle_c: 3 +endpose_c: -1 -2 3 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.1781 +-0.0028 -0.0056 1.1781 +-0.0056 -0.0111 1.1781 +-0.0083 -0.0167 1.1781 +-0.0111 -0.0222 1.1781 +-0.0139 -0.0278 1.1781 +-0.0167 -0.0333 1.1781 +-0.0194 -0.0389 1.1781 +-0.0222 -0.0444 1.1781 +-0.0250 -0.0500 1.1781 +primID: 3 +startangle_c: 3 +endpose_c: 8 10 2 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0184 0.0298 1.1478 +0.0379 0.0592 1.1175 +0.0583 0.0881 1.0872 +0.0796 0.1165 1.0569 +0.1019 0.1444 1.0266 +0.1251 0.1717 0.9963 +0.1492 0.1984 0.9660 +0.1742 0.2245 0.9357 +0.2000 0.2500 0.9054 +primID: 4 +startangle_c: 3 +endpose_c: 4 14 4 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0156 0.0377 1.1781 +0.0312 0.0754 1.1781 +0.0468 0.1131 1.1781 +0.0623 0.1508 1.1972 +0.0758 0.1893 1.2719 +0.0863 0.2287 1.3466 +0.0939 0.2687 1.4214 +0.0985 0.3092 1.4961 +0.1000 0.3500 1.5708 +primID: 5 +startangle_c: 3 +endpose_c: 0 0 2 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0000 0.0000 1.1345 +0.0000 0.0000 1.0908 +0.0000 0.0000 1.0472 +0.0000 0.0000 1.0036 +0.0000 0.0000 0.9599 +0.0000 0.0000 0.9163 +0.0000 0.0000 0.8727 +0.0000 0.0000 0.8290 +0.0000 0.0000 0.7854 +primID: 6 +startangle_c: 3 +endpose_c: 0 0 4 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0000 0.0000 1.2217 +0.0000 0.0000 1.2654 +0.0000 0.0000 1.3090 +0.0000 0.0000 1.3526 +0.0000 0.0000 1.3963 +0.0000 0.0000 1.4399 +0.0000 0.0000 1.4835 +0.0000 0.0000 1.5272 +0.0000 0.0000 1.5708 +primID: 0 +startangle_c: 4 +endpose_c: 0 1 4 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0028 1.5708 +0.0000 0.0056 1.5708 +0.0000 0.0083 1.5708 +0.0000 0.0111 1.5708 +0.0000 0.0139 1.5708 +0.0000 0.0167 1.5708 +0.0000 0.0194 1.5708 +0.0000 0.0222 1.5708 +0.0000 0.0250 1.5708 +primID: 1 +startangle_c: 4 +endpose_c: 0 12 4 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0333 1.5708 +0.0000 0.0667 1.5708 +0.0000 0.1000 1.5708 +0.0000 0.1333 1.5708 +0.0000 0.1667 1.5708 +0.0000 0.2000 1.5708 +0.0000 0.2333 1.5708 +0.0000 0.2667 1.5708 +0.0000 0.3000 1.5708 +primID: 2 +startangle_c: 4 +endpose_c: 0 -1 4 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 -0.0028 1.5708 +0.0000 -0.0056 1.5708 +0.0000 -0.0083 1.5708 +0.0000 -0.0111 1.5708 +0.0000 -0.0139 1.5708 +0.0000 -0.0167 1.5708 +0.0000 -0.0194 1.5708 +0.0000 -0.0222 1.5708 +0.0000 -0.0250 1.5708 +primID: 3 +startangle_c: 4 +endpose_c: -2 16 5 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0452 1.5708 +0.0000 0.0904 1.5708 +0.0000 0.1355 1.5708 +-0.0008 0.1807 1.6196 +-0.0045 0.2257 1.6884 +-0.0114 0.2703 1.7572 +-0.0213 0.3144 1.8259 +-0.0342 0.3577 1.8947 +-0.0500 0.4000 1.9635 +primID: 4 +startangle_c: 4 +endpose_c: 2 16 3 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0452 1.5708 +0.0000 0.0904 1.5708 +0.0000 0.1355 1.5708 +0.0008 0.1807 1.5220 +0.0045 0.2257 1.4532 +0.0114 0.2703 1.3844 +0.0213 0.3144 1.3156 +0.0342 0.3577 1.2469 +0.0500 0.4000 1.1781 +primID: 5 +startangle_c: 4 +endpose_c: 0 0 5 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0000 1.6144 +0.0000 0.0000 1.6581 +0.0000 0.0000 1.7017 +0.0000 0.0000 1.7453 +0.0000 0.0000 1.7890 +0.0000 0.0000 1.8326 +0.0000 0.0000 1.8762 +0.0000 0.0000 1.9199 +0.0000 0.0000 1.9635 +primID: 6 +startangle_c: 4 +endpose_c: 0 0 3 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0000 1.5272 +0.0000 0.0000 1.4835 +0.0000 0.0000 1.4399 +0.0000 0.0000 1.3963 +0.0000 0.0000 1.3526 +0.0000 0.0000 1.3090 +0.0000 0.0000 1.2654 +0.0000 0.0000 1.2217 +0.0000 0.0000 1.1781 +primID: 0 +startangle_c: 5 +endpose_c: -1 2 5 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0028 0.0056 1.9635 +-0.0056 0.0111 1.9635 +-0.0083 0.0167 1.9635 +-0.0111 0.0222 1.9635 +-0.0139 0.0278 1.9635 +-0.0167 0.0333 1.9635 +-0.0194 0.0389 1.9635 +-0.0222 0.0444 1.9635 +-0.0250 0.0500 1.9635 +primID: 1 +startangle_c: 5 +endpose_c: -6 12 5 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0167 0.0333 1.9635 +-0.0333 0.0667 1.9635 +-0.0500 0.1000 1.9635 +-0.0667 0.1333 1.9635 +-0.0833 0.1667 1.9635 +-0.1000 0.2000 1.9635 +-0.1167 0.2333 1.9635 +-0.1333 0.2667 1.9635 +-0.1500 0.3000 1.9635 +primID: 2 +startangle_c: 5 +endpose_c: 1 -2 5 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0028 -0.0056 1.9635 +0.0056 -0.0111 1.9635 +0.0083 -0.0167 1.9635 +0.0111 -0.0222 1.9635 +0.0139 -0.0278 1.9635 +0.0167 -0.0333 1.9635 +0.0194 -0.0389 1.9635 +0.0222 -0.0444 1.9635 +0.0250 -0.0500 1.9635 +primID: 3 +startangle_c: 5 +endpose_c: -8 10 6 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0184 0.0298 1.9938 +-0.0379 0.0592 2.0241 +-0.0583 0.0881 2.0544 +-0.0796 0.1165 2.0847 +-0.1019 0.1444 2.1150 +-0.1251 0.1717 2.1453 +-0.1492 0.1984 2.1756 +-0.1742 0.2245 2.2059 +-0.2000 0.2500 2.2362 +primID: 4 +startangle_c: 5 +endpose_c: -4 14 4 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0156 0.0377 1.9635 +-0.0312 0.0754 1.9635 +-0.0468 0.1131 1.9635 +-0.0623 0.1508 1.9444 +-0.0758 0.1893 1.8697 +-0.0863 0.2287 1.7950 +-0.0939 0.2687 1.7202 +-0.0985 0.3092 1.6455 +-0.1000 0.3500 1.5708 +primID: 5 +startangle_c: 5 +endpose_c: 0 0 6 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0000 0.0000 2.0071 +0.0000 0.0000 2.0508 +0.0000 0.0000 2.0944 +0.0000 0.0000 2.1380 +0.0000 0.0000 2.1817 +0.0000 0.0000 2.2253 +0.0000 0.0000 2.2689 +0.0000 0.0000 2.3126 +0.0000 0.0000 2.3562 +primID: 6 +startangle_c: 5 +endpose_c: 0 0 4 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0000 0.0000 1.9199 +0.0000 0.0000 1.8762 +0.0000 0.0000 1.8326 +0.0000 0.0000 1.7890 +0.0000 0.0000 1.7453 +0.0000 0.0000 1.7017 +0.0000 0.0000 1.6581 +0.0000 0.0000 1.6144 +0.0000 0.0000 1.5708 +primID: 0 +startangle_c: 6 +endpose_c: -1 1 6 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0028 0.0028 2.3562 +-0.0056 0.0056 2.3562 +-0.0083 0.0083 2.3562 +-0.0111 0.0111 2.3562 +-0.0139 0.0139 2.3562 +-0.0167 0.0167 2.3562 +-0.0194 0.0194 2.3562 +-0.0222 0.0222 2.3562 +-0.0250 0.0250 2.3562 +primID: 1 +startangle_c: 6 +endpose_c: -12 12 6 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0333 0.0333 2.3562 +-0.0667 0.0667 2.3562 +-0.1000 0.1000 2.3562 +-0.1333 0.1333 2.3562 +-0.1667 0.1667 2.3562 +-0.2000 0.2000 2.3562 +-0.2333 0.2333 2.3562 +-0.2667 0.2667 2.3562 +-0.3000 0.3000 2.3562 +primID: 2 +startangle_c: 6 +endpose_c: 1 -1 6 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0028 -0.0028 2.3562 +0.0056 -0.0056 2.3562 +0.0083 -0.0083 2.3562 +0.0111 -0.0111 2.3562 +0.0139 -0.0139 2.3562 +0.0167 -0.0167 2.3562 +0.0194 -0.0194 2.3562 +0.0222 -0.0222 2.3562 +0.0250 -0.0250 2.3562 +primID: 3 +startangle_c: 6 +endpose_c: -14 10 7 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0341 0.0341 2.3562 +-0.0684 0.0678 2.3859 +-0.1043 0.1000 2.4377 +-0.1418 0.1302 2.4896 +-0.1809 0.1584 2.5415 +-0.2213 0.1846 2.5933 +-0.2631 0.2086 2.6452 +-0.3060 0.2304 2.6970 +-0.3500 0.2500 2.7489 +primID: 4 +startangle_c: 6 +endpose_c: -10 14 5 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0341 0.0341 2.3562 +-0.0678 0.0684 2.3265 +-0.1000 0.1043 2.2747 +-0.1302 0.1418 2.2228 +-0.1584 0.1809 2.1709 +-0.1846 0.2213 2.1191 +-0.2086 0.2631 2.0672 +-0.2304 0.3060 2.0154 +-0.2500 0.3500 1.9635 +primID: 5 +startangle_c: 6 +endpose_c: 0 0 7 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0000 0.0000 2.3998 +0.0000 0.0000 2.4435 +0.0000 0.0000 2.4871 +0.0000 0.0000 2.5307 +0.0000 0.0000 2.5744 +0.0000 0.0000 2.6180 +0.0000 0.0000 2.6616 +0.0000 0.0000 2.7053 +0.0000 0.0000 2.7489 +primID: 6 +startangle_c: 6 +endpose_c: 0 0 5 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0000 0.0000 2.3126 +0.0000 0.0000 2.2689 +0.0000 0.0000 2.2253 +0.0000 0.0000 2.1817 +0.0000 0.0000 2.1380 +0.0000 0.0000 2.0944 +0.0000 0.0000 2.0508 +0.0000 0.0000 2.0071 +0.0000 0.0000 1.9635 +primID: 0 +startangle_c: 7 +endpose_c: -2 1 7 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0056 0.0028 2.7489 +-0.0111 0.0056 2.7489 +-0.0167 0.0083 2.7489 +-0.0222 0.0111 2.7489 +-0.0278 0.0139 2.7489 +-0.0333 0.0167 2.7489 +-0.0389 0.0194 2.7489 +-0.0444 0.0222 2.7489 +-0.0500 0.0250 2.7489 +primID: 1 +startangle_c: 7 +endpose_c: -12 6 7 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0333 0.0167 2.7489 +-0.0667 0.0333 2.7489 +-0.1000 0.0500 2.7489 +-0.1333 0.0667 2.7489 +-0.1667 0.0833 2.7489 +-0.2000 0.1000 2.7489 +-0.2333 0.1167 2.7489 +-0.2667 0.1333 2.7489 +-0.3000 0.1500 2.7489 +primID: 2 +startangle_c: 7 +endpose_c: 2 -1 7 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0056 -0.0028 2.7489 +0.0111 -0.0056 2.7489 +0.0167 -0.0083 2.7489 +0.0222 -0.0111 2.7489 +0.0278 -0.0139 2.7489 +0.0333 -0.0167 2.7489 +0.0389 -0.0194 2.7489 +0.0444 -0.0222 2.7489 +0.0500 -0.0250 2.7489 +primID: 3 +startangle_c: 7 +endpose_c: -10 8 6 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0298 0.0184 2.7186 +-0.0592 0.0379 2.6883 +-0.0881 0.0583 2.6580 +-0.1165 0.0796 2.6277 +-0.1444 0.1019 2.5974 +-0.1717 0.1251 2.5671 +-0.1984 0.1492 2.5368 +-0.2245 0.1742 2.5065 +-0.2500 0.2000 2.4762 +primID: 4 +startangle_c: 7 +endpose_c: -14 4 8 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0377 0.0156 2.7489 +-0.0754 0.0312 2.7489 +-0.1131 0.0468 2.7489 +-0.1508 0.0623 2.7680 +-0.1893 0.0758 2.8427 +-0.2287 0.0863 2.9174 +-0.2687 0.0939 2.9921 +-0.3092 0.0985 3.0669 +-0.3500 0.1000 3.1416 +primID: 5 +startangle_c: 7 +endpose_c: 0 0 6 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0000 0.0000 2.7053 +0.0000 0.0000 2.6616 +0.0000 0.0000 2.6180 +0.0000 0.0000 2.5744 +0.0000 0.0000 2.5307 +0.0000 0.0000 2.4871 +0.0000 0.0000 2.4435 +0.0000 0.0000 2.3998 +0.0000 0.0000 2.3562 +primID: 6 +startangle_c: 7 +endpose_c: 0 0 8 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0000 0.0000 2.7925 +0.0000 0.0000 2.8362 +0.0000 0.0000 2.8798 +0.0000 0.0000 2.9234 +0.0000 0.0000 2.9671 +0.0000 0.0000 3.0107 +0.0000 0.0000 3.0543 +0.0000 0.0000 3.0980 +0.0000 0.0000 3.1416 +primID: 0 +startangle_c: 8 +endpose_c: -1 0 8 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0028 0.0000 3.1416 +-0.0056 0.0000 3.1416 +-0.0083 0.0000 3.1416 +-0.0111 0.0000 3.1416 +-0.0139 0.0000 3.1416 +-0.0167 0.0000 3.1416 +-0.0194 0.0000 3.1416 +-0.0222 0.0000 3.1416 +-0.0250 0.0000 3.1416 +primID: 1 +startangle_c: 8 +endpose_c: -12 0 8 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0333 0.0000 3.1416 +-0.0667 0.0000 3.1416 +-0.1000 0.0000 3.1416 +-0.1333 0.0000 3.1416 +-0.1667 0.0000 3.1416 +-0.2000 0.0000 3.1416 +-0.2333 0.0000 3.1416 +-0.2667 0.0000 3.1416 +-0.3000 0.0000 3.1416 +primID: 2 +startangle_c: 8 +endpose_c: 1 0 8 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0028 0.0000 3.1416 +0.0056 0.0000 3.1416 +0.0083 0.0000 3.1416 +0.0111 0.0000 3.1416 +0.0139 0.0000 3.1416 +0.0167 0.0000 3.1416 +0.0194 0.0000 3.1416 +0.0222 0.0000 3.1416 +0.0250 0.0000 3.1416 +primID: 3 +startangle_c: 8 +endpose_c: -16 -2 9 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0452 0.0000 3.1416 +-0.0904 0.0000 3.1416 +-0.1355 0.0000 3.1416 +-0.1807 -0.0008 3.1904 +-0.2257 -0.0045 3.2592 +-0.2703 -0.0114 3.3280 +-0.3144 -0.0213 3.3967 +-0.3577 -0.0342 3.4655 +-0.4000 -0.0500 3.5343 +primID: 4 +startangle_c: 8 +endpose_c: -16 2 7 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0452 0.0000 3.1416 +-0.0904 0.0000 3.1416 +-0.1355 0.0000 3.1416 +-0.1807 0.0008 3.0928 +-0.2257 0.0045 3.0240 +-0.2703 0.0114 2.9552 +-0.3144 0.0213 2.8864 +-0.3577 0.0342 2.8177 +-0.4000 0.0500 2.7489 +primID: 5 +startangle_c: 8 +endpose_c: 0 0 9 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0000 0.0000 3.1852 +0.0000 0.0000 3.2289 +0.0000 0.0000 3.2725 +0.0000 0.0000 3.3161 +0.0000 0.0000 3.3598 +0.0000 0.0000 3.4034 +0.0000 0.0000 3.4470 +0.0000 0.0000 3.4907 +0.0000 0.0000 3.5343 +primID: 6 +startangle_c: 8 +endpose_c: 0 0 7 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0000 0.0000 3.0980 +0.0000 0.0000 3.0543 +0.0000 0.0000 3.0107 +0.0000 0.0000 2.9671 +0.0000 0.0000 2.9234 +0.0000 0.0000 2.8798 +0.0000 0.0000 2.8362 +0.0000 0.0000 2.7925 +0.0000 0.0000 2.7489 +primID: 0 +startangle_c: 9 +endpose_c: -2 -1 9 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0056 -0.0028 3.5343 +-0.0111 -0.0056 3.5343 +-0.0167 -0.0083 3.5343 +-0.0222 -0.0111 3.5343 +-0.0278 -0.0139 3.5343 +-0.0333 -0.0167 3.5343 +-0.0389 -0.0194 3.5343 +-0.0444 -0.0222 3.5343 +-0.0500 -0.0250 3.5343 +primID: 1 +startangle_c: 9 +endpose_c: -12 -6 9 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0333 -0.0167 3.5343 +-0.0667 -0.0333 3.5343 +-0.1000 -0.0500 3.5343 +-0.1333 -0.0667 3.5343 +-0.1667 -0.0833 3.5343 +-0.2000 -0.1000 3.5343 +-0.2333 -0.1167 3.5343 +-0.2667 -0.1333 3.5343 +-0.3000 -0.1500 3.5343 +primID: 2 +startangle_c: 9 +endpose_c: 2 1 9 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0056 0.0028 3.5343 +0.0111 0.0056 3.5343 +0.0167 0.0083 3.5343 +0.0222 0.0111 3.5343 +0.0278 0.0139 3.5343 +0.0333 0.0167 3.5343 +0.0389 0.0194 3.5343 +0.0444 0.0222 3.5343 +0.0500 0.0250 3.5343 +primID: 3 +startangle_c: 9 +endpose_c: -10 -8 10 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0298 -0.0184 3.5646 +-0.0592 -0.0379 3.5949 +-0.0881 -0.0583 3.6252 +-0.1165 -0.0796 3.6555 +-0.1444 -0.1019 3.6858 +-0.1717 -0.1251 3.7161 +-0.1984 -0.1492 3.7464 +-0.2245 -0.1742 3.7767 +-0.2500 -0.2000 3.8070 +primID: 4 +startangle_c: 9 +endpose_c: -14 -4 8 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0377 -0.0156 3.5343 +-0.0754 -0.0312 3.5343 +-0.1131 -0.0468 3.5343 +-0.1508 -0.0623 3.5152 +-0.1893 -0.0758 3.4405 +-0.2287 -0.0863 3.3658 +-0.2687 -0.0939 3.2910 +-0.3092 -0.0985 3.2163 +-0.3500 -0.1000 3.1416 +primID: 5 +startangle_c: 9 +endpose_c: 0 0 10 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0000 0.0000 3.5779 +0.0000 0.0000 3.6216 +0.0000 0.0000 3.6652 +0.0000 0.0000 3.7088 +0.0000 0.0000 3.7525 +0.0000 0.0000 3.7961 +0.0000 0.0000 3.8397 +0.0000 0.0000 3.8834 +0.0000 0.0000 3.9270 +primID: 6 +startangle_c: 9 +endpose_c: 0 0 8 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0000 0.0000 3.4907 +0.0000 0.0000 3.4470 +0.0000 0.0000 3.4034 +0.0000 0.0000 3.3598 +0.0000 0.0000 3.3161 +0.0000 0.0000 3.2725 +0.0000 0.0000 3.2289 +0.0000 0.0000 3.1852 +0.0000 0.0000 3.1416 +primID: 0 +startangle_c: 10 +endpose_c: -1 -1 10 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0028 -0.0028 3.9270 +-0.0056 -0.0056 3.9270 +-0.0083 -0.0083 3.9270 +-0.0111 -0.0111 3.9270 +-0.0139 -0.0139 3.9270 +-0.0167 -0.0167 3.9270 +-0.0194 -0.0194 3.9270 +-0.0222 -0.0222 3.9270 +-0.0250 -0.0250 3.9270 +primID: 1 +startangle_c: 10 +endpose_c: -12 -12 10 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0333 -0.0333 3.9270 +-0.0667 -0.0667 3.9270 +-0.1000 -0.1000 3.9270 +-0.1333 -0.1333 3.9270 +-0.1667 -0.1667 3.9270 +-0.2000 -0.2000 3.9270 +-0.2333 -0.2333 3.9270 +-0.2667 -0.2667 3.9270 +-0.3000 -0.3000 3.9270 +primID: 2 +startangle_c: 10 +endpose_c: 1 1 10 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0028 0.0028 3.9270 +0.0056 0.0056 3.9270 +0.0083 0.0083 3.9270 +0.0111 0.0111 3.9270 +0.0139 0.0139 3.9270 +0.0167 0.0167 3.9270 +0.0194 0.0194 3.9270 +0.0222 0.0222 3.9270 +0.0250 0.0250 3.9270 +primID: 3 +startangle_c: 10 +endpose_c: -10 -14 11 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0341 -0.0341 3.9270 +-0.0678 -0.0684 3.9567 +-0.1000 -0.1043 4.0085 +-0.1302 -0.1418 4.0604 +-0.1584 -0.1809 4.1123 +-0.1846 -0.2213 4.1641 +-0.2086 -0.2631 4.2160 +-0.2304 -0.3060 4.2678 +-0.2500 -0.3500 4.3197 +primID: 4 +startangle_c: 10 +endpose_c: -14 -10 9 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0341 -0.0341 3.9270 +-0.0684 -0.0678 3.8973 +-0.1043 -0.1000 3.8455 +-0.1418 -0.1302 3.7936 +-0.1809 -0.1584 3.7417 +-0.2213 -0.1846 3.6899 +-0.2631 -0.2086 3.6380 +-0.3060 -0.2304 3.5862 +-0.3500 -0.2500 3.5343 +primID: 5 +startangle_c: 10 +endpose_c: 0 0 11 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.9706 +0.0000 0.0000 4.0143 +0.0000 0.0000 4.0579 +0.0000 0.0000 4.1015 +0.0000 0.0000 4.1452 +0.0000 0.0000 4.1888 +0.0000 0.0000 4.2324 +0.0000 0.0000 4.2761 +0.0000 0.0000 4.3197 +primID: 6 +startangle_c: 10 +endpose_c: 0 0 9 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.8834 +0.0000 0.0000 3.8397 +0.0000 0.0000 3.7961 +0.0000 0.0000 3.7525 +0.0000 0.0000 3.7088 +0.0000 0.0000 3.6652 +0.0000 0.0000 3.6216 +0.0000 0.0000 3.5779 +0.0000 0.0000 3.5343 +primID: 0 +startangle_c: 11 +endpose_c: -1 -2 11 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0028 -0.0056 4.3197 +-0.0056 -0.0111 4.3197 +-0.0083 -0.0167 4.3197 +-0.0111 -0.0222 4.3197 +-0.0139 -0.0278 4.3197 +-0.0167 -0.0333 4.3197 +-0.0194 -0.0389 4.3197 +-0.0222 -0.0444 4.3197 +-0.0250 -0.0500 4.3197 +primID: 1 +startangle_c: 11 +endpose_c: -6 -12 11 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0167 -0.0333 4.3197 +-0.0333 -0.0667 4.3197 +-0.0500 -0.1000 4.3197 +-0.0667 -0.1333 4.3197 +-0.0833 -0.1667 4.3197 +-0.1000 -0.2000 4.3197 +-0.1167 -0.2333 4.3197 +-0.1333 -0.2667 4.3197 +-0.1500 -0.3000 4.3197 +primID: 2 +startangle_c: 11 +endpose_c: 1 2 11 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0028 0.0056 4.3197 +0.0056 0.0111 4.3197 +0.0083 0.0167 4.3197 +0.0111 0.0222 4.3197 +0.0139 0.0278 4.3197 +0.0167 0.0333 4.3197 +0.0194 0.0389 4.3197 +0.0222 0.0444 4.3197 +0.0250 0.0500 4.3197 +primID: 3 +startangle_c: 11 +endpose_c: -8 -10 10 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0184 -0.0298 4.2894 +-0.0379 -0.0592 4.2591 +-0.0583 -0.0881 4.2288 +-0.0796 -0.1165 4.1985 +-0.1019 -0.1444 4.1682 +-0.1251 -0.1717 4.1379 +-0.1492 -0.1984 4.1076 +-0.1742 -0.2245 4.0773 +-0.2000 -0.2500 4.0470 +primID: 4 +startangle_c: 11 +endpose_c: -4 -14 12 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0156 -0.0377 4.3197 +-0.0312 -0.0754 4.3197 +-0.0468 -0.1131 4.3197 +-0.0623 -0.1508 4.3388 +-0.0758 -0.1893 4.4135 +-0.0863 -0.2287 4.4882 +-0.0939 -0.2687 4.5629 +-0.0985 -0.3092 4.6377 +-0.1000 -0.3500 4.7124 +primID: 5 +startangle_c: 11 +endpose_c: 0 0 10 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0000 0.0000 4.2761 +0.0000 0.0000 4.2324 +0.0000 0.0000 4.1888 +0.0000 0.0000 4.1452 +0.0000 0.0000 4.1015 +0.0000 0.0000 4.0579 +0.0000 0.0000 4.0143 +0.0000 0.0000 3.9706 +0.0000 0.0000 3.9270 +primID: 6 +startangle_c: 11 +endpose_c: 0 0 12 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0000 0.0000 4.3633 +0.0000 0.0000 4.4070 +0.0000 0.0000 4.4506 +0.0000 0.0000 4.4942 +0.0000 0.0000 4.5379 +0.0000 0.0000 4.5815 +0.0000 0.0000 4.6251 +0.0000 0.0000 4.6688 +0.0000 0.0000 4.7124 +primID: 0 +startangle_c: 12 +endpose_c: 0 -1 12 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0028 4.7124 +0.0000 -0.0056 4.7124 +0.0000 -0.0083 4.7124 +0.0000 -0.0111 4.7124 +0.0000 -0.0139 4.7124 +0.0000 -0.0167 4.7124 +0.0000 -0.0194 4.7124 +0.0000 -0.0222 4.7124 +0.0000 -0.0250 4.7124 +primID: 1 +startangle_c: 12 +endpose_c: 0 -12 12 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0333 4.7124 +0.0000 -0.0667 4.7124 +0.0000 -0.1000 4.7124 +0.0000 -0.1333 4.7124 +0.0000 -0.1667 4.7124 +0.0000 -0.2000 4.7124 +0.0000 -0.2333 4.7124 +0.0000 -0.2667 4.7124 +0.0000 -0.3000 4.7124 +primID: 2 +startangle_c: 12 +endpose_c: 0 1 12 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0028 4.7124 +0.0000 0.0056 4.7124 +0.0000 0.0083 4.7124 +0.0000 0.0111 4.7124 +0.0000 0.0139 4.7124 +0.0000 0.0167 4.7124 +0.0000 0.0194 4.7124 +0.0000 0.0222 4.7124 +0.0000 0.0250 4.7124 +primID: 3 +startangle_c: 12 +endpose_c: 2 -16 13 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0452 4.7124 +0.0000 -0.0904 4.7124 +0.0000 -0.1355 4.7124 +0.0008 -0.1807 4.7612 +0.0045 -0.2257 4.8300 +0.0114 -0.2703 4.8988 +0.0213 -0.3144 4.9675 +0.0342 -0.3577 5.0363 +0.0500 -0.4000 5.1051 +primID: 4 +startangle_c: 12 +endpose_c: -2 -16 11 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.7124 +-0.0000 -0.0452 4.7124 +-0.0000 -0.0904 4.7124 +-0.0000 -0.1355 4.7124 +-0.0008 -0.1807 4.6636 +-0.0045 -0.2257 4.5948 +-0.0114 -0.2703 4.5260 +-0.0213 -0.3144 4.4572 +-0.0342 -0.3577 4.3885 +-0.0500 -0.4000 4.3197 +primID: 5 +startangle_c: 12 +endpose_c: 0 0 13 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0000 4.7560 +0.0000 0.0000 4.7997 +0.0000 0.0000 4.8433 +0.0000 0.0000 4.8869 +0.0000 0.0000 4.9306 +0.0000 0.0000 4.9742 +0.0000 0.0000 5.0178 +0.0000 0.0000 5.0615 +0.0000 0.0000 5.1051 +primID: 6 +startangle_c: 12 +endpose_c: 0 0 11 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0000 4.6688 +0.0000 0.0000 4.6251 +0.0000 0.0000 4.5815 +0.0000 0.0000 4.5379 +0.0000 0.0000 4.4942 +0.0000 0.0000 4.4506 +0.0000 0.0000 4.4070 +0.0000 0.0000 4.3633 +0.0000 0.0000 4.3197 +primID: 0 +startangle_c: 13 +endpose_c: 1 -2 13 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0028 -0.0056 5.1051 +0.0056 -0.0111 5.1051 +0.0083 -0.0167 5.1051 +0.0111 -0.0222 5.1051 +0.0139 -0.0278 5.1051 +0.0167 -0.0333 5.1051 +0.0194 -0.0389 5.1051 +0.0222 -0.0444 5.1051 +0.0250 -0.0500 5.1051 +primID: 1 +startangle_c: 13 +endpose_c: 6 -12 13 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0167 -0.0333 5.1051 +0.0333 -0.0667 5.1051 +0.0500 -0.1000 5.1051 +0.0667 -0.1333 5.1051 +0.0833 -0.1667 5.1051 +0.1000 -0.2000 5.1051 +0.1167 -0.2333 5.1051 +0.1333 -0.2667 5.1051 +0.1500 -0.3000 5.1051 +primID: 2 +startangle_c: 13 +endpose_c: -1 2 13 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.1051 +-0.0028 0.0056 5.1051 +-0.0056 0.0111 5.1051 +-0.0083 0.0167 5.1051 +-0.0111 0.0222 5.1051 +-0.0139 0.0278 5.1051 +-0.0167 0.0333 5.1051 +-0.0194 0.0389 5.1051 +-0.0222 0.0444 5.1051 +-0.0250 0.0500 5.1051 +primID: 3 +startangle_c: 13 +endpose_c: 8 -10 14 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0184 -0.0298 5.1354 +0.0379 -0.0592 5.1657 +0.0583 -0.0881 5.1960 +0.0796 -0.1165 5.2263 +0.1019 -0.1444 5.2566 +0.1251 -0.1717 5.2869 +0.1492 -0.1984 5.3172 +0.1742 -0.2245 5.3475 +0.2000 -0.2500 5.3778 +primID: 4 +startangle_c: 13 +endpose_c: 4 -14 12 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0156 -0.0377 5.1051 +0.0312 -0.0754 5.1051 +0.0468 -0.1131 5.1051 +0.0623 -0.1508 5.0860 +0.0758 -0.1893 5.0113 +0.0863 -0.2287 4.9366 +0.0939 -0.2687 4.8618 +0.0985 -0.3092 4.7871 +0.1000 -0.3500 4.7124 +primID: 5 +startangle_c: 13 +endpose_c: 0 0 14 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0000 0.0000 5.1487 +0.0000 0.0000 5.1924 +0.0000 0.0000 5.2360 +0.0000 0.0000 5.2796 +0.0000 0.0000 5.3233 +0.0000 0.0000 5.3669 +0.0000 0.0000 5.4105 +0.0000 0.0000 5.4542 +0.0000 0.0000 5.4978 +primID: 6 +startangle_c: 13 +endpose_c: 0 0 12 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0000 0.0000 5.0615 +0.0000 0.0000 5.0178 +0.0000 0.0000 4.9742 +0.0000 0.0000 4.9306 +0.0000 0.0000 4.8869 +0.0000 0.0000 4.8433 +0.0000 0.0000 4.7997 +0.0000 0.0000 4.7560 +0.0000 0.0000 4.7124 +primID: 0 +startangle_c: 14 +endpose_c: 1 -1 14 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0028 -0.0028 5.4978 +0.0056 -0.0056 5.4978 +0.0083 -0.0083 5.4978 +0.0111 -0.0111 5.4978 +0.0139 -0.0139 5.4978 +0.0167 -0.0167 5.4978 +0.0194 -0.0194 5.4978 +0.0222 -0.0222 5.4978 +0.0250 -0.0250 5.4978 +primID: 1 +startangle_c: 14 +endpose_c: 12 -12 14 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0333 -0.0333 5.4978 +0.0667 -0.0667 5.4978 +0.1000 -0.1000 5.4978 +0.1333 -0.1333 5.4978 +0.1667 -0.1667 5.4978 +0.2000 -0.2000 5.4978 +0.2333 -0.2333 5.4978 +0.2667 -0.2667 5.4978 +0.3000 -0.3000 5.4978 +primID: 2 +startangle_c: 14 +endpose_c: -1 1 14 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.4978 +-0.0028 0.0028 5.4978 +-0.0056 0.0056 5.4978 +-0.0083 0.0083 5.4978 +-0.0111 0.0111 5.4978 +-0.0139 0.0139 5.4978 +-0.0167 0.0167 5.4978 +-0.0194 0.0194 5.4978 +-0.0222 0.0222 5.4978 +-0.0250 0.0250 5.4978 +primID: 3 +startangle_c: 14 +endpose_c: 14 -10 15 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0341 -0.0341 5.4978 +0.0684 -0.0678 5.5275 +0.1043 -0.1000 5.5793 +0.1418 -0.1302 5.6312 +0.1809 -0.1584 5.6830 +0.2213 -0.1846 5.7349 +0.2631 -0.2086 5.7868 +0.3060 -0.2304 5.8386 +0.3500 -0.2500 5.8905 +primID: 4 +startangle_c: 14 +endpose_c: 10 -14 13 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0341 -0.0341 5.4978 +0.0678 -0.0684 5.4681 +0.1000 -0.1043 5.4162 +0.1302 -0.1418 5.3644 +0.1584 -0.1809 5.3125 +0.1846 -0.2213 5.2607 +0.2086 -0.2631 5.2088 +0.2304 -0.3060 5.1569 +0.2500 -0.3500 5.1051 +primID: 5 +startangle_c: 14 +endpose_c: 0 0 15 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0000 0.0000 5.5414 +0.0000 0.0000 5.5851 +0.0000 0.0000 5.6287 +0.0000 0.0000 5.6723 +0.0000 0.0000 5.7160 +0.0000 0.0000 5.7596 +0.0000 0.0000 5.8032 +0.0000 0.0000 5.8469 +0.0000 0.0000 5.8905 +primID: 6 +startangle_c: 14 +endpose_c: 0 0 13 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0000 0.0000 5.4542 +0.0000 0.0000 5.4105 +0.0000 0.0000 5.3669 +0.0000 0.0000 5.3233 +0.0000 0.0000 5.2796 +0.0000 0.0000 5.2360 +0.0000 0.0000 5.1924 +0.0000 0.0000 5.1487 +0.0000 0.0000 5.1051 +primID: 0 +startangle_c: 15 +endpose_c: 2 -1 15 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0056 -0.0028 5.8905 +0.0111 -0.0056 5.8905 +0.0167 -0.0083 5.8905 +0.0222 -0.0111 5.8905 +0.0278 -0.0139 5.8905 +0.0333 -0.0167 5.8905 +0.0389 -0.0194 5.8905 +0.0444 -0.0222 5.8905 +0.0500 -0.0250 5.8905 +primID: 1 +startangle_c: 15 +endpose_c: 12 -6 15 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0333 -0.0167 5.8905 +0.0667 -0.0333 5.8905 +0.1000 -0.0500 5.8905 +0.1333 -0.0667 5.8905 +0.1667 -0.0833 5.8905 +0.2000 -0.1000 5.8905 +0.2333 -0.1167 5.8905 +0.2667 -0.1333 5.8905 +0.3000 -0.1500 5.8905 +primID: 2 +startangle_c: 15 +endpose_c: -2 1 15 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.8905 +-0.0056 0.0028 5.8905 +-0.0111 0.0056 5.8905 +-0.0167 0.0083 5.8905 +-0.0222 0.0111 5.8905 +-0.0278 0.0139 5.8905 +-0.0333 0.0167 5.8905 +-0.0389 0.0194 5.8905 +-0.0444 0.0222 5.8905 +-0.0500 0.0250 5.8905 +primID: 3 +startangle_c: 15 +endpose_c: 10 -8 14 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0298 -0.0184 5.8602 +0.0592 -0.0379 5.8299 +0.0881 -0.0583 5.7996 +0.1165 -0.0796 5.7693 +0.1444 -0.1019 5.7390 +0.1717 -0.1251 5.7087 +0.1984 -0.1492 5.6784 +0.2245 -0.1742 5.6481 +0.2500 -0.2000 5.6178 +primID: 4 +startangle_c: 15 +endpose_c: 14 -4 0 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0377 -0.0156 5.8905 +0.0754 -0.0312 5.8905 +0.1131 -0.0468 5.8905 +0.1508 -0.0623 5.9096 +0.1893 -0.0758 5.9843 +0.2287 -0.0863 6.0590 +0.2687 -0.0939 6.1337 +0.3092 -0.0985 6.2085 +0.3500 -0.1000 6.2832 +primID: 5 +startangle_c: 15 +endpose_c: 0 0 14 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0000 0.0000 5.8469 +0.0000 0.0000 5.8032 +0.0000 0.0000 5.7596 +0.0000 0.0000 5.7160 +0.0000 0.0000 5.6723 +0.0000 0.0000 5.6287 +0.0000 0.0000 5.5851 +0.0000 0.0000 5.5414 +0.0000 0.0000 5.4978 +primID: 6 +startangle_c: 15 +endpose_c: 0 0 0 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0000 0.0000 5.2360 +0.0000 0.0000 4.5815 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.2725 +0.0000 0.0000 2.6180 +0.0000 0.0000 1.9635 +0.0000 0.0000 1.3090 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.0000 diff --git a/mir_robot/mir_navigation/mprim/unicycle_highcost_2cm.mprim b/mir_robot/mir_navigation/mprim/unicycle_highcost_2cm.mprim new file mode 100755 index 0000000..b87c310 --- /dev/null +++ b/mir_robot/mir_navigation/mprim/unicycle_highcost_2cm.mprim @@ -0,0 +1,1683 @@ +resolution_m: 0.020000 +numberofangles: 16 +totalnumberofprimitives: 112 +primID: 0 +startangle_c: 0 +endpose_c: 1 0 0 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0022 0.0000 0.0000 +0.0044 0.0000 0.0000 +0.0067 0.0000 0.0000 +0.0089 0.0000 0.0000 +0.0111 0.0000 0.0000 +0.0133 0.0000 0.0000 +0.0156 0.0000 0.0000 +0.0178 0.0000 0.0000 +0.0200 0.0000 0.0000 +primID: 1 +startangle_c: 0 +endpose_c: 20 0 0 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0444 0.0000 0.0000 +0.0889 0.0000 0.0000 +0.1333 0.0000 0.0000 +0.1778 0.0000 0.0000 +0.2222 0.0000 0.0000 +0.2667 0.0000 0.0000 +0.3111 0.0000 0.0000 +0.3556 0.0000 0.0000 +0.4000 0.0000 0.0000 +primID: 2 +startangle_c: 0 +endpose_c: -1 0 0 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.0000 +-0.0022 0.0000 0.0000 +-0.0044 0.0000 0.0000 +-0.0067 0.0000 0.0000 +-0.0089 0.0000 0.0000 +-0.0111 0.0000 0.0000 +-0.0133 0.0000 0.0000 +-0.0156 0.0000 0.0000 +-0.0178 0.0000 0.0000 +-0.0200 0.0000 0.0000 +primID: 3 +startangle_c: 0 +endpose_c: 15 3 1 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0342 0.0008 0.0434 +0.0683 0.0031 0.0868 +0.1023 0.0069 0.1302 +0.1361 0.0121 0.1736 +0.1696 0.0188 0.2170 +0.2029 0.0270 0.2604 +0.2357 0.0366 0.3038 +0.2681 0.0476 0.3472 +0.3000 0.0600 0.3906 +primID: 4 +startangle_c: 0 +endpose_c: 15 -3 -1 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0342 -0.0008 -0.0434 +0.0683 -0.0031 -0.0868 +0.1023 -0.0069 -0.1302 +0.1361 -0.0121 -0.1736 +0.1696 -0.0188 -0.2170 +0.2029 -0.0270 -0.2604 +0.2357 -0.0366 -0.3038 +0.2681 -0.0476 -0.3472 +0.3000 -0.0600 -0.3906 +primID: 5 +startangle_c: 0 +endpose_c: 0 0 1 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0000 0.0000 0.0436 +0.0000 0.0000 0.0873 +0.0000 0.0000 0.1309 +0.0000 0.0000 0.1745 +0.0000 0.0000 0.2182 +0.0000 0.0000 0.2618 +0.0000 0.0000 0.3054 +0.0000 0.0000 0.3491 +0.0000 0.0000 0.3927 +primID: 6 +startangle_c: 0 +endpose_c: 0 0 -1 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0000 0.0000 -0.0436 +0.0000 0.0000 -0.0873 +0.0000 0.0000 -0.1309 +0.0000 0.0000 -0.1745 +0.0000 0.0000 -0.2182 +0.0000 0.0000 -0.2618 +0.0000 0.0000 -0.3054 +0.0000 0.0000 -0.3491 +0.0000 0.0000 -0.3927 +primID: 0 +startangle_c: 1 +endpose_c: 2 1 1 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0044 0.0022 0.3927 +0.0089 0.0044 0.3927 +0.0133 0.0067 0.3927 +0.0178 0.0089 0.3927 +0.0222 0.0111 0.3927 +0.0267 0.0133 0.3927 +0.0311 0.0156 0.3927 +0.0356 0.0178 0.3927 +0.0400 0.0200 0.3927 +primID: 1 +startangle_c: 1 +endpose_c: 15 8 1 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0333 0.0178 0.3927 +0.0667 0.0356 0.3927 +0.1000 0.0533 0.3927 +0.1333 0.0711 0.3927 +0.1667 0.0889 0.3927 +0.2000 0.1067 0.3927 +0.2333 0.1244 0.3927 +0.2667 0.1422 0.3927 +0.3000 0.1600 0.3927 +primID: 2 +startangle_c: 1 +endpose_c: -2 -1 1 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.3927 +-0.0044 -0.0022 0.3927 +-0.0089 -0.0044 0.3927 +-0.0133 -0.0067 0.3927 +-0.0178 -0.0089 0.3927 +-0.0222 -0.0111 0.3927 +-0.0267 -0.0133 0.3927 +-0.0311 -0.0156 0.3927 +-0.0356 -0.0178 0.3927 +-0.0400 -0.0200 0.3927 +primID: 3 +startangle_c: 1 +endpose_c: 12 10 2 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0285 0.0188 0.4210 +0.0566 0.0385 0.4492 +0.0842 0.0590 0.4775 +0.1115 0.0804 0.5057 +0.1382 0.1027 0.5340 +0.1645 0.1258 0.5623 +0.1902 0.1497 0.5905 +0.2154 0.1745 0.6188 +0.2400 0.2000 0.6470 +primID: 4 +startangle_c: 1 +endpose_c: 18 5 0 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0387 0.0160 0.3927 +0.0774 0.0320 0.3927 +0.1161 0.0481 0.3927 +0.1549 0.0636 0.3512 +0.1947 0.0766 0.2809 +0.2353 0.0868 0.2107 +0.2765 0.0941 0.1405 +0.3182 0.0985 0.0702 +0.3600 0.1000 0.0000 +primID: 5 +startangle_c: 1 +endpose_c: 0 0 2 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0000 0.0000 0.4363 +0.0000 0.0000 0.4800 +0.0000 0.0000 0.5236 +0.0000 0.0000 0.5672 +0.0000 0.0000 0.6109 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.6981 +0.0000 0.0000 0.7418 +0.0000 0.0000 0.7854 +primID: 6 +startangle_c: 1 +endpose_c: 0 0 0 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0000 0.0000 0.3491 +0.0000 0.0000 0.3054 +0.0000 0.0000 0.2618 +0.0000 0.0000 0.2182 +0.0000 0.0000 0.1745 +0.0000 0.0000 0.1309 +0.0000 0.0000 0.0873 +0.0000 0.0000 0.0436 +0.0000 0.0000 0.0000 +primID: 0 +startangle_c: 2 +endpose_c: 1 1 2 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0022 0.0022 0.7854 +0.0044 0.0044 0.7854 +0.0067 0.0067 0.7854 +0.0089 0.0089 0.7854 +0.0111 0.0111 0.7854 +0.0133 0.0133 0.7854 +0.0156 0.0156 0.7854 +0.0178 0.0178 0.7854 +0.0200 0.0200 0.7854 +primID: 1 +startangle_c: 2 +endpose_c: 15 15 2 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0333 0.0333 0.7854 +0.0667 0.0667 0.7854 +0.1000 0.1000 0.7854 +0.1333 0.1333 0.7854 +0.1667 0.1667 0.7854 +0.2000 0.2000 0.7854 +0.2333 0.2333 0.7854 +0.2667 0.2667 0.7854 +0.3000 0.3000 0.7854 +primID: 2 +startangle_c: 2 +endpose_c: -1 -1 2 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.7854 +-0.0022 -0.0022 0.7854 +-0.0044 -0.0044 0.7854 +-0.0067 -0.0067 0.7854 +-0.0089 -0.0089 0.7854 +-0.0111 -0.0111 0.7854 +-0.0133 -0.0133 0.7854 +-0.0156 -0.0156 0.7854 +-0.0178 -0.0178 0.7854 +-0.0200 -0.0200 0.7854 +primID: 3 +startangle_c: 2 +endpose_c: 12 18 3 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0334 0.0350 0.8288 +0.0652 0.0714 0.8722 +0.0954 0.1092 0.9156 +0.1240 0.1482 0.9590 +0.1508 0.1885 1.0024 +0.1759 0.2299 1.0458 +0.1991 0.2723 1.0892 +0.2205 0.3157 1.1326 +0.2400 0.3600 1.1760 +primID: 4 +startangle_c: 2 +endpose_c: 18 12 1 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0350 0.0334 0.7420 +0.0714 0.0652 0.6986 +0.1092 0.0954 0.6552 +0.1482 0.1240 0.6118 +0.1885 0.1508 0.5684 +0.2299 0.1759 0.5250 +0.2723 0.1991 0.4816 +0.3157 0.2205 0.4382 +0.3600 0.2400 0.3948 +primID: 5 +startangle_c: 2 +endpose_c: 0 0 3 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0000 0.0000 0.8290 +0.0000 0.0000 0.8727 +0.0000 0.0000 0.9163 +0.0000 0.0000 0.9599 +0.0000 0.0000 1.0036 +0.0000 0.0000 1.0472 +0.0000 0.0000 1.0908 +0.0000 0.0000 1.1345 +0.0000 0.0000 1.1781 +primID: 6 +startangle_c: 2 +endpose_c: 0 0 1 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0000 0.0000 0.7418 +0.0000 0.0000 0.6981 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.6109 +0.0000 0.0000 0.5672 +0.0000 0.0000 0.5236 +0.0000 0.0000 0.4800 +0.0000 0.0000 0.4363 +0.0000 0.0000 0.3927 +primID: 0 +startangle_c: 3 +endpose_c: 1 2 3 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0022 0.0044 1.1781 +0.0044 0.0089 1.1781 +0.0067 0.0133 1.1781 +0.0089 0.0178 1.1781 +0.0111 0.0222 1.1781 +0.0133 0.0267 1.1781 +0.0156 0.0311 1.1781 +0.0178 0.0356 1.1781 +0.0200 0.0400 1.1781 +primID: 1 +startangle_c: 3 +endpose_c: 8 15 3 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0178 0.0333 1.1781 +0.0356 0.0667 1.1781 +0.0533 0.1000 1.1781 +0.0711 0.1333 1.1781 +0.0889 0.1667 1.1781 +0.1067 0.2000 1.1781 +0.1244 0.2333 1.1781 +0.1422 0.2667 1.1781 +0.1600 0.3000 1.1781 +primID: 2 +startangle_c: 3 +endpose_c: -1 -2 3 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.1781 +-0.0022 -0.0044 1.1781 +-0.0044 -0.0089 1.1781 +-0.0067 -0.0133 1.1781 +-0.0089 -0.0178 1.1781 +-0.0111 -0.0222 1.1781 +-0.0133 -0.0267 1.1781 +-0.0156 -0.0311 1.1781 +-0.0178 -0.0356 1.1781 +-0.0200 -0.0400 1.1781 +primID: 3 +startangle_c: 3 +endpose_c: 10 12 2 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0188 0.0285 1.1498 +0.0385 0.0566 1.1216 +0.0590 0.0842 1.0933 +0.0804 0.1115 1.0651 +0.1027 0.1382 1.0368 +0.1258 0.1645 1.0085 +0.1497 0.1902 0.9803 +0.1745 0.2154 0.9520 +0.2000 0.2400 0.9238 +primID: 4 +startangle_c: 3 +endpose_c: 5 18 4 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0160 0.0387 1.1781 +0.0320 0.0774 1.1781 +0.0481 0.1161 1.1781 +0.0636 0.1549 1.2196 +0.0766 0.1947 1.2898 +0.0868 0.2353 1.3601 +0.0941 0.2765 1.4303 +0.0985 0.3182 1.5006 +0.1000 0.3600 1.5708 +primID: 5 +startangle_c: 3 +endpose_c: 0 0 2 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0000 0.0000 1.1345 +0.0000 0.0000 1.0908 +0.0000 0.0000 1.0472 +0.0000 0.0000 1.0036 +0.0000 0.0000 0.9599 +0.0000 0.0000 0.9163 +0.0000 0.0000 0.8727 +0.0000 0.0000 0.8290 +0.0000 0.0000 0.7854 +primID: 6 +startangle_c: 3 +endpose_c: 0 0 4 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0000 0.0000 1.2217 +0.0000 0.0000 1.2654 +0.0000 0.0000 1.3090 +0.0000 0.0000 1.3526 +0.0000 0.0000 1.3963 +0.0000 0.0000 1.4399 +0.0000 0.0000 1.4835 +0.0000 0.0000 1.5272 +0.0000 0.0000 1.5708 +primID: 0 +startangle_c: 4 +endpose_c: 0 1 4 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0022 1.5708 +0.0000 0.0044 1.5708 +0.0000 0.0067 1.5708 +0.0000 0.0089 1.5708 +0.0000 0.0111 1.5708 +0.0000 0.0133 1.5708 +0.0000 0.0156 1.5708 +0.0000 0.0178 1.5708 +0.0000 0.0200 1.5708 +primID: 1 +startangle_c: 4 +endpose_c: 0 20 4 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0444 1.5708 +0.0000 0.0889 1.5708 +0.0000 0.1333 1.5708 +0.0000 0.1778 1.5708 +0.0000 0.2222 1.5708 +0.0000 0.2667 1.5708 +0.0000 0.3111 1.5708 +0.0000 0.3556 1.5708 +0.0000 0.4000 1.5708 +primID: 2 +startangle_c: 4 +endpose_c: 0 -1 4 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 -0.0022 1.5708 +0.0000 -0.0044 1.5708 +0.0000 -0.0067 1.5708 +0.0000 -0.0089 1.5708 +0.0000 -0.0111 1.5708 +0.0000 -0.0133 1.5708 +0.0000 -0.0156 1.5708 +0.0000 -0.0178 1.5708 +0.0000 -0.0200 1.5708 +primID: 3 +startangle_c: 4 +endpose_c: -3 15 5 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.5708 +-0.0008 0.0342 1.6142 +-0.0031 0.0683 1.6576 +-0.0069 0.1023 1.7010 +-0.0121 0.1361 1.7444 +-0.0188 0.1696 1.7878 +-0.0270 0.2029 1.8312 +-0.0366 0.2357 1.8746 +-0.0476 0.2681 1.9180 +-0.0600 0.3000 1.9614 +primID: 4 +startangle_c: 4 +endpose_c: 3 15 3 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0008 0.0342 1.5274 +0.0031 0.0683 1.4840 +0.0069 0.1023 1.4406 +0.0121 0.1361 1.3972 +0.0188 0.1696 1.3538 +0.0270 0.2029 1.3104 +0.0366 0.2357 1.2670 +0.0476 0.2681 1.2236 +0.0600 0.3000 1.1802 +primID: 5 +startangle_c: 4 +endpose_c: 0 0 5 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0000 1.6144 +0.0000 0.0000 1.6581 +0.0000 0.0000 1.7017 +0.0000 0.0000 1.7453 +0.0000 0.0000 1.7890 +0.0000 0.0000 1.8326 +0.0000 0.0000 1.8762 +0.0000 0.0000 1.9199 +0.0000 0.0000 1.9635 +primID: 6 +startangle_c: 4 +endpose_c: 0 0 3 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0000 1.5272 +0.0000 0.0000 1.4835 +0.0000 0.0000 1.4399 +0.0000 0.0000 1.3963 +0.0000 0.0000 1.3526 +0.0000 0.0000 1.3090 +0.0000 0.0000 1.2654 +0.0000 0.0000 1.2217 +0.0000 0.0000 1.1781 +primID: 0 +startangle_c: 5 +endpose_c: -1 2 5 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0022 0.0044 1.9635 +-0.0044 0.0089 1.9635 +-0.0067 0.0133 1.9635 +-0.0089 0.0178 1.9635 +-0.0111 0.0222 1.9635 +-0.0133 0.0267 1.9635 +-0.0156 0.0311 1.9635 +-0.0178 0.0356 1.9635 +-0.0200 0.0400 1.9635 +primID: 1 +startangle_c: 5 +endpose_c: -8 15 5 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0178 0.0333 1.9635 +-0.0356 0.0667 1.9635 +-0.0533 0.1000 1.9635 +-0.0711 0.1333 1.9635 +-0.0889 0.1667 1.9635 +-0.1067 0.2000 1.9635 +-0.1244 0.2333 1.9635 +-0.1422 0.2667 1.9635 +-0.1600 0.3000 1.9635 +primID: 2 +startangle_c: 5 +endpose_c: 1 -2 5 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0022 -0.0044 1.9635 +0.0044 -0.0089 1.9635 +0.0067 -0.0133 1.9635 +0.0089 -0.0178 1.9635 +0.0111 -0.0222 1.9635 +0.0133 -0.0267 1.9635 +0.0156 -0.0311 1.9635 +0.0178 -0.0356 1.9635 +0.0200 -0.0400 1.9635 +primID: 3 +startangle_c: 5 +endpose_c: -10 12 6 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0188 0.0285 1.9918 +-0.0385 0.0566 2.0200 +-0.0590 0.0842 2.0483 +-0.0804 0.1115 2.0765 +-0.1027 0.1382 2.1048 +-0.1258 0.1645 2.1330 +-0.1497 0.1902 2.1613 +-0.1745 0.2154 2.1896 +-0.2000 0.2400 2.2178 +primID: 4 +startangle_c: 5 +endpose_c: -5 18 4 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0160 0.0387 1.9635 +-0.0320 0.0774 1.9635 +-0.0481 0.1161 1.9635 +-0.0636 0.1549 1.9220 +-0.0766 0.1947 1.8517 +-0.0868 0.2353 1.7815 +-0.0941 0.2765 1.7113 +-0.0985 0.3182 1.6410 +-0.1000 0.3600 1.5708 +primID: 5 +startangle_c: 5 +endpose_c: 0 0 6 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0000 0.0000 2.0071 +0.0000 0.0000 2.0508 +0.0000 0.0000 2.0944 +0.0000 0.0000 2.1380 +0.0000 0.0000 2.1817 +0.0000 0.0000 2.2253 +0.0000 0.0000 2.2689 +0.0000 0.0000 2.3126 +0.0000 0.0000 2.3562 +primID: 6 +startangle_c: 5 +endpose_c: 0 0 4 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0000 0.0000 1.9199 +0.0000 0.0000 1.8762 +0.0000 0.0000 1.8326 +0.0000 0.0000 1.7890 +0.0000 0.0000 1.7453 +0.0000 0.0000 1.7017 +0.0000 0.0000 1.6581 +0.0000 0.0000 1.6144 +0.0000 0.0000 1.5708 +primID: 0 +startangle_c: 6 +endpose_c: -1 1 6 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0022 0.0022 2.3562 +-0.0044 0.0044 2.3562 +-0.0067 0.0067 2.3562 +-0.0089 0.0089 2.3562 +-0.0111 0.0111 2.3562 +-0.0133 0.0133 2.3562 +-0.0156 0.0156 2.3562 +-0.0178 0.0178 2.3562 +-0.0200 0.0200 2.3562 +primID: 1 +startangle_c: 6 +endpose_c: -15 15 6 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0333 0.0333 2.3562 +-0.0667 0.0667 2.3562 +-0.1000 0.1000 2.3562 +-0.1333 0.1333 2.3562 +-0.1667 0.1667 2.3562 +-0.2000 0.2000 2.3562 +-0.2333 0.2333 2.3562 +-0.2667 0.2667 2.3562 +-0.3000 0.3000 2.3562 +primID: 2 +startangle_c: 6 +endpose_c: 1 -1 6 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0022 -0.0022 2.3562 +0.0044 -0.0044 2.3562 +0.0067 -0.0067 2.3562 +0.0089 -0.0089 2.3562 +0.0111 -0.0111 2.3562 +0.0133 -0.0133 2.3562 +0.0156 -0.0156 2.3562 +0.0178 -0.0178 2.3562 +0.0200 -0.0200 2.3562 +primID: 3 +startangle_c: 6 +endpose_c: -18 12 7 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0350 0.0334 2.3996 +-0.0714 0.0652 2.4430 +-0.1092 0.0954 2.4864 +-0.1482 0.1240 2.5298 +-0.1885 0.1508 2.5732 +-0.2299 0.1759 2.6166 +-0.2723 0.1991 2.6600 +-0.3157 0.2205 2.7034 +-0.3600 0.2400 2.7468 +primID: 4 +startangle_c: 6 +endpose_c: -12 18 5 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0334 0.0350 2.3128 +-0.0652 0.0714 2.2694 +-0.0954 0.1092 2.2260 +-0.1240 0.1482 2.1826 +-0.1508 0.1885 2.1392 +-0.1759 0.2299 2.0958 +-0.1991 0.2723 2.0524 +-0.2205 0.3157 2.0090 +-0.2400 0.3600 1.9656 +primID: 5 +startangle_c: 6 +endpose_c: 0 0 7 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0000 0.0000 2.3998 +0.0000 0.0000 2.4435 +0.0000 0.0000 2.4871 +0.0000 0.0000 2.5307 +0.0000 0.0000 2.5744 +0.0000 0.0000 2.6180 +0.0000 0.0000 2.6616 +0.0000 0.0000 2.7053 +0.0000 0.0000 2.7489 +primID: 6 +startangle_c: 6 +endpose_c: 0 0 5 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0000 0.0000 2.3126 +0.0000 0.0000 2.2689 +0.0000 0.0000 2.2253 +0.0000 0.0000 2.1817 +0.0000 0.0000 2.1380 +0.0000 0.0000 2.0944 +0.0000 0.0000 2.0508 +0.0000 0.0000 2.0071 +0.0000 0.0000 1.9635 +primID: 0 +startangle_c: 7 +endpose_c: -2 1 7 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0044 0.0022 2.7489 +-0.0089 0.0044 2.7489 +-0.0133 0.0067 2.7489 +-0.0178 0.0089 2.7489 +-0.0222 0.0111 2.7489 +-0.0267 0.0133 2.7489 +-0.0311 0.0156 2.7489 +-0.0356 0.0178 2.7489 +-0.0400 0.0200 2.7489 +primID: 1 +startangle_c: 7 +endpose_c: -15 8 7 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0333 0.0178 2.7489 +-0.0667 0.0356 2.7489 +-0.1000 0.0533 2.7489 +-0.1333 0.0711 2.7489 +-0.1667 0.0889 2.7489 +-0.2000 0.1067 2.7489 +-0.2333 0.1244 2.7489 +-0.2667 0.1422 2.7489 +-0.3000 0.1600 2.7489 +primID: 2 +startangle_c: 7 +endpose_c: 2 -1 7 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0044 -0.0022 2.7489 +0.0089 -0.0044 2.7489 +0.0133 -0.0067 2.7489 +0.0178 -0.0089 2.7489 +0.0222 -0.0111 2.7489 +0.0267 -0.0133 2.7489 +0.0311 -0.0156 2.7489 +0.0356 -0.0178 2.7489 +0.0400 -0.0200 2.7489 +primID: 3 +startangle_c: 7 +endpose_c: -12 10 6 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0285 0.0188 2.7206 +-0.0566 0.0385 2.6924 +-0.0842 0.0590 2.6641 +-0.1115 0.0804 2.6359 +-0.1382 0.1027 2.6076 +-0.1645 0.1258 2.5793 +-0.1902 0.1497 2.5511 +-0.2154 0.1745 2.5228 +-0.2400 0.2000 2.4946 +primID: 4 +startangle_c: 7 +endpose_c: -18 5 8 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0387 0.0160 2.7489 +-0.0774 0.0320 2.7489 +-0.1161 0.0481 2.7489 +-0.1549 0.0636 2.7904 +-0.1947 0.0766 2.8606 +-0.2353 0.0868 2.9309 +-0.2765 0.0941 3.0011 +-0.3182 0.0985 3.0714 +-0.3600 0.1000 3.1416 +primID: 5 +startangle_c: 7 +endpose_c: 0 0 6 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0000 0.0000 2.7053 +0.0000 0.0000 2.6616 +0.0000 0.0000 2.6180 +0.0000 0.0000 2.5744 +0.0000 0.0000 2.5307 +0.0000 0.0000 2.4871 +0.0000 0.0000 2.4435 +0.0000 0.0000 2.3998 +0.0000 0.0000 2.3562 +primID: 6 +startangle_c: 7 +endpose_c: 0 0 8 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0000 0.0000 2.7925 +0.0000 0.0000 2.8362 +0.0000 0.0000 2.8798 +0.0000 0.0000 2.9234 +0.0000 0.0000 2.9671 +0.0000 0.0000 3.0107 +0.0000 0.0000 3.0543 +0.0000 0.0000 3.0980 +0.0000 0.0000 3.1416 +primID: 0 +startangle_c: 8 +endpose_c: -1 0 8 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0022 0.0000 3.1416 +-0.0044 0.0000 3.1416 +-0.0067 0.0000 3.1416 +-0.0089 0.0000 3.1416 +-0.0111 0.0000 3.1416 +-0.0133 0.0000 3.1416 +-0.0156 0.0000 3.1416 +-0.0178 0.0000 3.1416 +-0.0200 0.0000 3.1416 +primID: 1 +startangle_c: 8 +endpose_c: -20 0 8 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0444 0.0000 3.1416 +-0.0889 0.0000 3.1416 +-0.1333 0.0000 3.1416 +-0.1778 0.0000 3.1416 +-0.2222 0.0000 3.1416 +-0.2667 0.0000 3.1416 +-0.3111 0.0000 3.1416 +-0.3556 0.0000 3.1416 +-0.4000 0.0000 3.1416 +primID: 2 +startangle_c: 8 +endpose_c: 1 0 8 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0022 0.0000 3.1416 +0.0044 0.0000 3.1416 +0.0067 0.0000 3.1416 +0.0089 0.0000 3.1416 +0.0111 0.0000 3.1416 +0.0133 0.0000 3.1416 +0.0156 0.0000 3.1416 +0.0178 0.0000 3.1416 +0.0200 0.0000 3.1416 +primID: 3 +startangle_c: 8 +endpose_c: -15 -3 9 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0342 -0.0008 3.1850 +-0.0683 -0.0031 3.2284 +-0.1023 -0.0069 3.2718 +-0.1361 -0.0121 3.3152 +-0.1696 -0.0188 3.3586 +-0.2029 -0.0270 3.4020 +-0.2357 -0.0366 3.4454 +-0.2681 -0.0476 3.4888 +-0.3000 -0.0600 3.5322 +primID: 4 +startangle_c: 8 +endpose_c: -15 3 7 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0342 0.0008 3.0982 +-0.0683 0.0031 3.0548 +-0.1023 0.0069 3.0114 +-0.1361 0.0121 2.9680 +-0.1696 0.0188 2.9246 +-0.2029 0.0270 2.8812 +-0.2357 0.0366 2.8378 +-0.2681 0.0476 2.7944 +-0.3000 0.0600 2.7510 +primID: 5 +startangle_c: 8 +endpose_c: 0 0 9 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0000 0.0000 3.1852 +0.0000 0.0000 3.2289 +0.0000 0.0000 3.2725 +0.0000 0.0000 3.3161 +0.0000 0.0000 3.3598 +0.0000 0.0000 3.4034 +0.0000 0.0000 3.4470 +0.0000 0.0000 3.4907 +0.0000 0.0000 3.5343 +primID: 6 +startangle_c: 8 +endpose_c: 0 0 7 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0000 0.0000 3.0980 +0.0000 0.0000 3.0543 +0.0000 0.0000 3.0107 +0.0000 0.0000 2.9671 +0.0000 0.0000 2.9234 +0.0000 0.0000 2.8798 +0.0000 0.0000 2.8362 +0.0000 0.0000 2.7925 +0.0000 0.0000 2.7489 +primID: 0 +startangle_c: 9 +endpose_c: -2 -1 9 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0044 -0.0022 3.5343 +-0.0089 -0.0044 3.5343 +-0.0133 -0.0067 3.5343 +-0.0178 -0.0089 3.5343 +-0.0222 -0.0111 3.5343 +-0.0267 -0.0133 3.5343 +-0.0311 -0.0156 3.5343 +-0.0356 -0.0178 3.5343 +-0.0400 -0.0200 3.5343 +primID: 1 +startangle_c: 9 +endpose_c: -15 -8 9 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0333 -0.0178 3.5343 +-0.0667 -0.0356 3.5343 +-0.1000 -0.0533 3.5343 +-0.1333 -0.0711 3.5343 +-0.1667 -0.0889 3.5343 +-0.2000 -0.1067 3.5343 +-0.2333 -0.1244 3.5343 +-0.2667 -0.1422 3.5343 +-0.3000 -0.1600 3.5343 +primID: 2 +startangle_c: 9 +endpose_c: 2 1 9 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0044 0.0022 3.5343 +0.0089 0.0044 3.5343 +0.0133 0.0067 3.5343 +0.0178 0.0089 3.5343 +0.0222 0.0111 3.5343 +0.0267 0.0133 3.5343 +0.0311 0.0156 3.5343 +0.0356 0.0178 3.5343 +0.0400 0.0200 3.5343 +primID: 3 +startangle_c: 9 +endpose_c: -12 -10 10 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0285 -0.0188 3.5626 +-0.0566 -0.0385 3.5908 +-0.0842 -0.0590 3.6191 +-0.1115 -0.0804 3.6473 +-0.1382 -0.1027 3.6756 +-0.1645 -0.1258 3.7038 +-0.1902 -0.1497 3.7321 +-0.2154 -0.1745 3.7604 +-0.2400 -0.2000 3.7886 +primID: 4 +startangle_c: 9 +endpose_c: -18 -5 8 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0387 -0.0160 3.5343 +-0.0774 -0.0320 3.5343 +-0.1161 -0.0481 3.5343 +-0.1549 -0.0636 3.4928 +-0.1947 -0.0766 3.4225 +-0.2353 -0.0868 3.3523 +-0.2765 -0.0941 3.2821 +-0.3182 -0.0985 3.2118 +-0.3600 -0.1000 3.1416 +primID: 5 +startangle_c: 9 +endpose_c: 0 0 10 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0000 0.0000 3.5779 +0.0000 0.0000 3.6216 +0.0000 0.0000 3.6652 +0.0000 0.0000 3.7088 +0.0000 0.0000 3.7525 +0.0000 0.0000 3.7961 +0.0000 0.0000 3.8397 +0.0000 0.0000 3.8834 +0.0000 0.0000 3.9270 +primID: 6 +startangle_c: 9 +endpose_c: 0 0 8 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0000 0.0000 3.4907 +0.0000 0.0000 3.4470 +0.0000 0.0000 3.4034 +0.0000 0.0000 3.3598 +0.0000 0.0000 3.3161 +0.0000 0.0000 3.2725 +0.0000 0.0000 3.2289 +0.0000 0.0000 3.1852 +0.0000 0.0000 3.1416 +primID: 0 +startangle_c: 10 +endpose_c: -1 -1 10 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0022 -0.0022 3.9270 +-0.0044 -0.0044 3.9270 +-0.0067 -0.0067 3.9270 +-0.0089 -0.0089 3.9270 +-0.0111 -0.0111 3.9270 +-0.0133 -0.0133 3.9270 +-0.0156 -0.0156 3.9270 +-0.0178 -0.0178 3.9270 +-0.0200 -0.0200 3.9270 +primID: 1 +startangle_c: 10 +endpose_c: -15 -15 10 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0333 -0.0333 3.9270 +-0.0667 -0.0667 3.9270 +-0.1000 -0.1000 3.9270 +-0.1333 -0.1333 3.9270 +-0.1667 -0.1667 3.9270 +-0.2000 -0.2000 3.9270 +-0.2333 -0.2333 3.9270 +-0.2667 -0.2667 3.9270 +-0.3000 -0.3000 3.9270 +primID: 2 +startangle_c: 10 +endpose_c: 1 1 10 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0022 0.0022 3.9270 +0.0044 0.0044 3.9270 +0.0067 0.0067 3.9270 +0.0089 0.0089 3.9270 +0.0111 0.0111 3.9270 +0.0133 0.0133 3.9270 +0.0156 0.0156 3.9270 +0.0178 0.0178 3.9270 +0.0200 0.0200 3.9270 +primID: 3 +startangle_c: 10 +endpose_c: -12 -18 11 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0334 -0.0350 3.9704 +-0.0652 -0.0714 4.0138 +-0.0954 -0.1092 4.0572 +-0.1240 -0.1482 4.1006 +-0.1508 -0.1885 4.1440 +-0.1759 -0.2299 4.1874 +-0.1991 -0.2723 4.2308 +-0.2205 -0.3157 4.2742 +-0.2400 -0.3600 4.3176 +primID: 4 +startangle_c: 10 +endpose_c: -18 -12 9 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0350 -0.0334 3.8836 +-0.0714 -0.0652 3.8402 +-0.1092 -0.0954 3.7968 +-0.1482 -0.1240 3.7534 +-0.1885 -0.1508 3.7100 +-0.2299 -0.1759 3.6666 +-0.2723 -0.1991 3.6232 +-0.3157 -0.2205 3.5798 +-0.3600 -0.2400 3.5364 +primID: 5 +startangle_c: 10 +endpose_c: 0 0 11 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.9706 +0.0000 0.0000 4.0143 +0.0000 0.0000 4.0579 +0.0000 0.0000 4.1015 +0.0000 0.0000 4.1452 +0.0000 0.0000 4.1888 +0.0000 0.0000 4.2324 +0.0000 0.0000 4.2761 +0.0000 0.0000 4.3197 +primID: 6 +startangle_c: 10 +endpose_c: 0 0 9 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.8834 +0.0000 0.0000 3.8397 +0.0000 0.0000 3.7961 +0.0000 0.0000 3.7525 +0.0000 0.0000 3.7088 +0.0000 0.0000 3.6652 +0.0000 0.0000 3.6216 +0.0000 0.0000 3.5779 +0.0000 0.0000 3.5343 +primID: 0 +startangle_c: 11 +endpose_c: -1 -2 11 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0022 -0.0044 4.3197 +-0.0044 -0.0089 4.3197 +-0.0067 -0.0133 4.3197 +-0.0089 -0.0178 4.3197 +-0.0111 -0.0222 4.3197 +-0.0133 -0.0267 4.3197 +-0.0156 -0.0311 4.3197 +-0.0178 -0.0356 4.3197 +-0.0200 -0.0400 4.3197 +primID: 1 +startangle_c: 11 +endpose_c: -8 -15 11 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0178 -0.0333 4.3197 +-0.0356 -0.0667 4.3197 +-0.0533 -0.1000 4.3197 +-0.0711 -0.1333 4.3197 +-0.0889 -0.1667 4.3197 +-0.1067 -0.2000 4.3197 +-0.1244 -0.2333 4.3197 +-0.1422 -0.2667 4.3197 +-0.1600 -0.3000 4.3197 +primID: 2 +startangle_c: 11 +endpose_c: 1 2 11 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0022 0.0044 4.3197 +0.0044 0.0089 4.3197 +0.0067 0.0133 4.3197 +0.0089 0.0178 4.3197 +0.0111 0.0222 4.3197 +0.0133 0.0267 4.3197 +0.0156 0.0311 4.3197 +0.0178 0.0356 4.3197 +0.0200 0.0400 4.3197 +primID: 3 +startangle_c: 11 +endpose_c: -10 -12 10 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0188 -0.0285 4.2914 +-0.0385 -0.0566 4.2632 +-0.0590 -0.0842 4.2349 +-0.0804 -0.1115 4.2067 +-0.1027 -0.1382 4.1784 +-0.1258 -0.1645 4.1501 +-0.1497 -0.1902 4.1219 +-0.1745 -0.2154 4.0936 +-0.2000 -0.2400 4.0654 +primID: 4 +startangle_c: 11 +endpose_c: -5 -18 12 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0160 -0.0387 4.3197 +-0.0320 -0.0774 4.3197 +-0.0481 -0.1161 4.3197 +-0.0636 -0.1549 4.3612 +-0.0766 -0.1947 4.4314 +-0.0868 -0.2353 4.5017 +-0.0941 -0.2765 4.5719 +-0.0985 -0.3182 4.6422 +-0.1000 -0.3600 4.7124 +primID: 5 +startangle_c: 11 +endpose_c: 0 0 10 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0000 0.0000 4.2761 +0.0000 0.0000 4.2324 +0.0000 0.0000 4.1888 +0.0000 0.0000 4.1452 +0.0000 0.0000 4.1015 +0.0000 0.0000 4.0579 +0.0000 0.0000 4.0143 +0.0000 0.0000 3.9706 +0.0000 0.0000 3.9270 +primID: 6 +startangle_c: 11 +endpose_c: 0 0 12 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0000 0.0000 4.3633 +0.0000 0.0000 4.4070 +0.0000 0.0000 4.4506 +0.0000 0.0000 4.4942 +0.0000 0.0000 4.5379 +0.0000 0.0000 4.5815 +0.0000 0.0000 4.6251 +0.0000 0.0000 4.6688 +0.0000 0.0000 4.7124 +primID: 0 +startangle_c: 12 +endpose_c: 0 -1 12 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0022 4.7124 +0.0000 -0.0044 4.7124 +0.0000 -0.0067 4.7124 +0.0000 -0.0089 4.7124 +0.0000 -0.0111 4.7124 +0.0000 -0.0133 4.7124 +0.0000 -0.0156 4.7124 +0.0000 -0.0178 4.7124 +0.0000 -0.0200 4.7124 +primID: 1 +startangle_c: 12 +endpose_c: 0 -20 12 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0444 4.7124 +0.0000 -0.0889 4.7124 +0.0000 -0.1333 4.7124 +0.0000 -0.1778 4.7124 +0.0000 -0.2222 4.7124 +0.0000 -0.2667 4.7124 +0.0000 -0.3111 4.7124 +0.0000 -0.3556 4.7124 +0.0000 -0.4000 4.7124 +primID: 2 +startangle_c: 12 +endpose_c: 0 1 12 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0022 4.7124 +0.0000 0.0044 4.7124 +0.0000 0.0067 4.7124 +0.0000 0.0089 4.7124 +0.0000 0.0111 4.7124 +0.0000 0.0133 4.7124 +0.0000 0.0156 4.7124 +0.0000 0.0178 4.7124 +0.0000 0.0200 4.7124 +primID: 3 +startangle_c: 12 +endpose_c: 3 -15 13 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0008 -0.0342 4.7558 +0.0031 -0.0683 4.7992 +0.0069 -0.1023 4.8426 +0.0121 -0.1361 4.8860 +0.0188 -0.1696 4.9294 +0.0270 -0.2029 4.9728 +0.0366 -0.2357 5.0162 +0.0476 -0.2681 5.0596 +0.0600 -0.3000 5.1030 +primID: 4 +startangle_c: 12 +endpose_c: -3 -15 11 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.7124 +-0.0008 -0.0342 4.6690 +-0.0031 -0.0683 4.6256 +-0.0069 -0.1023 4.5822 +-0.0121 -0.1361 4.5388 +-0.0188 -0.1696 4.4954 +-0.0270 -0.2029 4.4520 +-0.0366 -0.2357 4.4086 +-0.0476 -0.2681 4.3652 +-0.0600 -0.3000 4.3218 +primID: 5 +startangle_c: 12 +endpose_c: 0 0 13 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0000 4.7560 +0.0000 0.0000 4.7997 +0.0000 0.0000 4.8433 +0.0000 0.0000 4.8869 +0.0000 0.0000 4.9306 +0.0000 0.0000 4.9742 +0.0000 0.0000 5.0178 +0.0000 0.0000 5.0615 +0.0000 0.0000 5.1051 +primID: 6 +startangle_c: 12 +endpose_c: 0 0 11 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0000 4.6688 +0.0000 0.0000 4.6251 +0.0000 0.0000 4.5815 +0.0000 0.0000 4.5379 +0.0000 0.0000 4.4942 +0.0000 0.0000 4.4506 +0.0000 0.0000 4.4070 +0.0000 0.0000 4.3633 +0.0000 0.0000 4.3197 +primID: 0 +startangle_c: 13 +endpose_c: 1 -2 13 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0022 -0.0044 5.1051 +0.0044 -0.0089 5.1051 +0.0067 -0.0133 5.1051 +0.0089 -0.0178 5.1051 +0.0111 -0.0222 5.1051 +0.0133 -0.0267 5.1051 +0.0156 -0.0311 5.1051 +0.0178 -0.0356 5.1051 +0.0200 -0.0400 5.1051 +primID: 1 +startangle_c: 13 +endpose_c: 8 -15 13 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0178 -0.0333 5.1051 +0.0356 -0.0667 5.1051 +0.0533 -0.1000 5.1051 +0.0711 -0.1333 5.1051 +0.0889 -0.1667 5.1051 +0.1067 -0.2000 5.1051 +0.1244 -0.2333 5.1051 +0.1422 -0.2667 5.1051 +0.1600 -0.3000 5.1051 +primID: 2 +startangle_c: 13 +endpose_c: -1 2 13 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.1051 +-0.0022 0.0044 5.1051 +-0.0044 0.0089 5.1051 +-0.0067 0.0133 5.1051 +-0.0089 0.0178 5.1051 +-0.0111 0.0222 5.1051 +-0.0133 0.0267 5.1051 +-0.0156 0.0311 5.1051 +-0.0178 0.0356 5.1051 +-0.0200 0.0400 5.1051 +primID: 3 +startangle_c: 13 +endpose_c: 10 -12 14 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0188 -0.0285 5.1333 +0.0385 -0.0566 5.1616 +0.0590 -0.0842 5.1899 +0.0804 -0.1115 5.2181 +0.1027 -0.1382 5.2464 +0.1258 -0.1645 5.2746 +0.1497 -0.1902 5.3029 +0.1745 -0.2154 5.3312 +0.2000 -0.2400 5.3594 +primID: 4 +startangle_c: 13 +endpose_c: 5 -18 12 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0160 -0.0387 5.1051 +0.0320 -0.0774 5.1051 +0.0481 -0.1161 5.1051 +0.0636 -0.1549 5.0636 +0.0766 -0.1947 4.9933 +0.0868 -0.2353 4.9231 +0.0941 -0.2765 4.8529 +0.0985 -0.3182 4.7826 +0.1000 -0.3600 4.7124 +primID: 5 +startangle_c: 13 +endpose_c: 0 0 14 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0000 0.0000 5.1487 +0.0000 0.0000 5.1924 +0.0000 0.0000 5.2360 +0.0000 0.0000 5.2796 +0.0000 0.0000 5.3233 +0.0000 0.0000 5.3669 +0.0000 0.0000 5.4105 +0.0000 0.0000 5.4542 +0.0000 0.0000 5.4978 +primID: 6 +startangle_c: 13 +endpose_c: 0 0 12 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0000 0.0000 5.0615 +0.0000 0.0000 5.0178 +0.0000 0.0000 4.9742 +0.0000 0.0000 4.9306 +0.0000 0.0000 4.8869 +0.0000 0.0000 4.8433 +0.0000 0.0000 4.7997 +0.0000 0.0000 4.7560 +0.0000 0.0000 4.7124 +primID: 0 +startangle_c: 14 +endpose_c: 1 -1 14 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0022 -0.0022 5.4978 +0.0044 -0.0044 5.4978 +0.0067 -0.0067 5.4978 +0.0089 -0.0089 5.4978 +0.0111 -0.0111 5.4978 +0.0133 -0.0133 5.4978 +0.0156 -0.0156 5.4978 +0.0178 -0.0178 5.4978 +0.0200 -0.0200 5.4978 +primID: 1 +startangle_c: 14 +endpose_c: 15 -15 14 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0333 -0.0333 5.4978 +0.0667 -0.0667 5.4978 +0.1000 -0.1000 5.4978 +0.1333 -0.1333 5.4978 +0.1667 -0.1667 5.4978 +0.2000 -0.2000 5.4978 +0.2333 -0.2333 5.4978 +0.2667 -0.2667 5.4978 +0.3000 -0.3000 5.4978 +primID: 2 +startangle_c: 14 +endpose_c: -1 1 14 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.4978 +-0.0022 0.0022 5.4978 +-0.0044 0.0044 5.4978 +-0.0067 0.0067 5.4978 +-0.0089 0.0089 5.4978 +-0.0111 0.0111 5.4978 +-0.0133 0.0133 5.4978 +-0.0156 0.0156 5.4978 +-0.0178 0.0178 5.4978 +-0.0200 0.0200 5.4978 +primID: 3 +startangle_c: 14 +endpose_c: 18 -12 15 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0350 -0.0334 5.5412 +0.0714 -0.0652 5.5846 +0.1092 -0.0954 5.6280 +0.1482 -0.1240 5.6714 +0.1885 -0.1508 5.7148 +0.2299 -0.1759 5.7582 +0.2723 -0.1991 5.8016 +0.3157 -0.2205 5.8450 +0.3600 -0.2400 5.8884 +primID: 4 +startangle_c: 14 +endpose_c: 12 -18 13 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0334 -0.0350 5.4544 +0.0652 -0.0714 5.4110 +0.0954 -0.1092 5.3676 +0.1240 -0.1482 5.3242 +0.1508 -0.1885 5.2808 +0.1759 -0.2299 5.2374 +0.1991 -0.2723 5.1940 +0.2205 -0.3157 5.1506 +0.2400 -0.3600 5.1072 +primID: 5 +startangle_c: 14 +endpose_c: 0 0 15 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0000 0.0000 5.5414 +0.0000 0.0000 5.5851 +0.0000 0.0000 5.6287 +0.0000 0.0000 5.6723 +0.0000 0.0000 5.7160 +0.0000 0.0000 5.7596 +0.0000 0.0000 5.8032 +0.0000 0.0000 5.8469 +0.0000 0.0000 5.8905 +primID: 6 +startangle_c: 14 +endpose_c: 0 0 13 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0000 0.0000 5.4542 +0.0000 0.0000 5.4105 +0.0000 0.0000 5.3669 +0.0000 0.0000 5.3233 +0.0000 0.0000 5.2796 +0.0000 0.0000 5.2360 +0.0000 0.0000 5.1924 +0.0000 0.0000 5.1487 +0.0000 0.0000 5.1051 +primID: 0 +startangle_c: 15 +endpose_c: 2 -1 15 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0044 -0.0022 5.8905 +0.0089 -0.0044 5.8905 +0.0133 -0.0067 5.8905 +0.0178 -0.0089 5.8905 +0.0222 -0.0111 5.8905 +0.0267 -0.0133 5.8905 +0.0311 -0.0156 5.8905 +0.0356 -0.0178 5.8905 +0.0400 -0.0200 5.8905 +primID: 1 +startangle_c: 15 +endpose_c: 15 -8 15 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0333 -0.0178 5.8905 +0.0667 -0.0356 5.8905 +0.1000 -0.0533 5.8905 +0.1333 -0.0711 5.8905 +0.1667 -0.0889 5.8905 +0.2000 -0.1067 5.8905 +0.2333 -0.1244 5.8905 +0.2667 -0.1422 5.8905 +0.3000 -0.1600 5.8905 +primID: 2 +startangle_c: 15 +endpose_c: -2 1 15 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.8905 +-0.0044 0.0022 5.8905 +-0.0089 0.0044 5.8905 +-0.0133 0.0067 5.8905 +-0.0178 0.0089 5.8905 +-0.0222 0.0111 5.8905 +-0.0267 0.0133 5.8905 +-0.0311 0.0156 5.8905 +-0.0356 0.0178 5.8905 +-0.0400 0.0200 5.8905 +primID: 3 +startangle_c: 15 +endpose_c: 12 -10 14 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0285 -0.0188 5.8622 +0.0566 -0.0385 5.8340 +0.0842 -0.0590 5.8057 +0.1115 -0.0804 5.7775 +0.1382 -0.1027 5.7492 +0.1645 -0.1258 5.7209 +0.1902 -0.1497 5.6927 +0.2154 -0.1745 5.6644 +0.2400 -0.2000 5.6362 +primID: 4 +startangle_c: 15 +endpose_c: 18 -5 0 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0387 -0.0160 5.8905 +0.0774 -0.0320 5.8905 +0.1161 -0.0481 5.8905 +0.1549 -0.0636 5.9320 +0.1947 -0.0766 6.0022 +0.2353 -0.0868 6.0725 +0.2765 -0.0941 6.1427 +0.3182 -0.0985 6.2129 +0.3600 -0.1000 6.2832 +primID: 5 +startangle_c: 15 +endpose_c: 0 0 14 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0000 0.0000 5.8469 +0.0000 0.0000 5.8032 +0.0000 0.0000 5.7596 +0.0000 0.0000 5.7160 +0.0000 0.0000 5.6723 +0.0000 0.0000 5.6287 +0.0000 0.0000 5.5851 +0.0000 0.0000 5.5414 +0.0000 0.0000 5.4978 +primID: 6 +startangle_c: 15 +endpose_c: 0 0 0 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0000 0.0000 5.2360 +0.0000 0.0000 4.5815 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.2725 +0.0000 0.0000 2.6180 +0.0000 0.0000 1.9635 +0.0000 0.0000 1.3090 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.0000 diff --git a/mir_robot/mir_navigation/mprim/unicycle_highcost_5cm.mprim b/mir_robot/mir_navigation/mprim/unicycle_highcost_5cm.mprim new file mode 100755 index 0000000..bff2688 --- /dev/null +++ b/mir_robot/mir_navigation/mprim/unicycle_highcost_5cm.mprim @@ -0,0 +1,1683 @@ +resolution_m: 0.050000 +numberofangles: 16 +totalnumberofprimitives: 112 +primID: 0 +startangle_c: 0 +endpose_c: 1 0 0 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0056 0.0000 0.0000 +0.0111 0.0000 0.0000 +0.0167 0.0000 0.0000 +0.0222 0.0000 0.0000 +0.0278 0.0000 0.0000 +0.0333 0.0000 0.0000 +0.0389 0.0000 0.0000 +0.0444 0.0000 0.0000 +0.0500 0.0000 0.0000 +primID: 1 +startangle_c: 0 +endpose_c: 8 0 0 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0444 0.0000 0.0000 +0.0889 0.0000 0.0000 +0.1333 0.0000 0.0000 +0.1778 0.0000 0.0000 +0.2222 0.0000 0.0000 +0.2667 0.0000 0.0000 +0.3111 0.0000 0.0000 +0.3556 0.0000 0.0000 +0.4000 0.0000 0.0000 +primID: 2 +startangle_c: 0 +endpose_c: -1 0 0 +additionalactioncostmult: 40 +intermediateposes: 10 +0.0000 0.0000 0.0000 +-0.0056 0.0000 0.0000 +-0.0111 0.0000 0.0000 +-0.0167 0.0000 0.0000 +-0.0222 0.0000 0.0000 +-0.0278 0.0000 0.0000 +-0.0333 0.0000 0.0000 +-0.0389 0.0000 0.0000 +-0.0444 0.0000 0.0000 +-0.0500 0.0000 0.0000 +primID: 3 +startangle_c: 0 +endpose_c: 8 1 1 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0452 -0.0000 0.0000 +0.0904 -0.0000 0.0000 +0.1355 -0.0000 0.0000 +0.1807 0.0008 0.0488 +0.2257 0.0045 0.1176 +0.2703 0.0114 0.1864 +0.3144 0.0213 0.2551 +0.3577 0.0342 0.3239 +0.4000 0.0500 0.3927 +primID: 4 +startangle_c: 0 +endpose_c: 8 -1 -1 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0452 0.0000 0.0000 +0.0904 0.0000 0.0000 +0.1355 0.0000 0.0000 +0.1807 -0.0008 -0.0488 +0.2257 -0.0045 -0.1176 +0.2703 -0.0114 -0.1864 +0.3144 -0.0213 -0.2551 +0.3577 -0.0342 -0.3239 +0.4000 -0.0500 -0.3927 +primID: 5 +startangle_c: 0 +endpose_c: 0 0 1 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0000 0.0000 0.0436 +0.0000 0.0000 0.0873 +0.0000 0.0000 0.1309 +0.0000 0.0000 0.1745 +0.0000 0.0000 0.2182 +0.0000 0.0000 0.2618 +0.0000 0.0000 0.3054 +0.0000 0.0000 0.3491 +0.0000 0.0000 0.3927 +primID: 6 +startangle_c: 0 +endpose_c: 0 0 -1 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0000 0.0000 -0.0436 +0.0000 0.0000 -0.0873 +0.0000 0.0000 -0.1309 +0.0000 0.0000 -0.1745 +0.0000 0.0000 -0.2182 +0.0000 0.0000 -0.2618 +0.0000 0.0000 -0.3054 +0.0000 0.0000 -0.3491 +0.0000 0.0000 -0.3927 +primID: 0 +startangle_c: 1 +endpose_c: 2 1 1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0111 0.0056 0.3927 +0.0222 0.0111 0.3927 +0.0333 0.0167 0.3927 +0.0444 0.0222 0.3927 +0.0556 0.0278 0.3927 +0.0667 0.0333 0.3927 +0.0778 0.0389 0.3927 +0.0889 0.0444 0.3927 +0.1000 0.0500 0.3927 +primID: 1 +startangle_c: 1 +endpose_c: 6 3 1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0333 0.0167 0.3927 +0.0667 0.0333 0.3927 +0.1000 0.0500 0.3927 +0.1333 0.0667 0.3927 +0.1667 0.0833 0.3927 +0.2000 0.1000 0.3927 +0.2333 0.1167 0.3927 +0.2667 0.1333 0.3927 +0.3000 0.1500 0.3927 +primID: 2 +startangle_c: 1 +endpose_c: -2 -1 1 +additionalactioncostmult: 40 +intermediateposes: 10 +0.0000 0.0000 0.3927 +-0.0111 -0.0056 0.3927 +-0.0222 -0.0111 0.3927 +-0.0333 -0.0167 0.3927 +-0.0444 -0.0222 0.3927 +-0.0556 -0.0278 0.3927 +-0.0667 -0.0333 0.3927 +-0.0778 -0.0389 0.3927 +-0.0889 -0.0444 0.3927 +-0.1000 -0.0500 0.3927 +primID: 3 +startangle_c: 1 +endpose_c: 5 4 2 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0298 0.0184 0.4230 +0.0592 0.0379 0.4533 +0.0881 0.0583 0.4836 +0.1165 0.0796 0.5139 +0.1444 0.1019 0.5442 +0.1717 0.1251 0.5745 +0.1984 0.1492 0.6048 +0.2245 0.1742 0.6351 +0.2500 0.2000 0.6654 +primID: 4 +startangle_c: 1 +endpose_c: 7 2 0 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0377 0.0156 0.3927 +0.0754 0.0312 0.3927 +0.1131 0.0468 0.3927 +0.1508 0.0623 0.3736 +0.1893 0.0758 0.2989 +0.2287 0.0863 0.2242 +0.2687 0.0939 0.1494 +0.3092 0.0985 0.0747 +0.3500 0.1000 -0.0000 +primID: 5 +startangle_c: 1 +endpose_c: 0 0 2 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0000 0.0000 0.4363 +0.0000 0.0000 0.4800 +0.0000 0.0000 0.5236 +0.0000 0.0000 0.5672 +0.0000 0.0000 0.6109 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.6981 +0.0000 0.0000 0.7418 +0.0000 0.0000 0.7854 +primID: 6 +startangle_c: 1 +endpose_c: 0 0 0 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0000 0.0000 0.3491 +0.0000 0.0000 0.3054 +0.0000 0.0000 0.2618 +0.0000 0.0000 0.2182 +0.0000 0.0000 0.1745 +0.0000 0.0000 0.1309 +0.0000 0.0000 0.0873 +0.0000 0.0000 0.0436 +0.0000 0.0000 0.0000 +primID: 0 +startangle_c: 2 +endpose_c: 1 1 2 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0056 0.0056 0.7854 +0.0111 0.0111 0.7854 +0.0167 0.0167 0.7854 +0.0222 0.0222 0.7854 +0.0278 0.0278 0.7854 +0.0333 0.0333 0.7854 +0.0389 0.0389 0.7854 +0.0444 0.0444 0.7854 +0.0500 0.0500 0.7854 +primID: 1 +startangle_c: 2 +endpose_c: 6 6 2 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0333 0.0333 0.7854 +0.0667 0.0667 0.7854 +0.1000 0.1000 0.7854 +0.1333 0.1333 0.7854 +0.1667 0.1667 0.7854 +0.2000 0.2000 0.7854 +0.2333 0.2333 0.7854 +0.2667 0.2667 0.7854 +0.3000 0.3000 0.7854 +primID: 2 +startangle_c: 2 +endpose_c: -1 -1 2 +additionalactioncostmult: 40 +intermediateposes: 10 +0.0000 0.0000 0.7854 +-0.0056 -0.0056 0.7854 +-0.0111 -0.0111 0.7854 +-0.0167 -0.0167 0.7854 +-0.0222 -0.0222 0.7854 +-0.0278 -0.0278 0.7854 +-0.0333 -0.0333 0.7854 +-0.0389 -0.0389 0.7854 +-0.0444 -0.0444 0.7854 +-0.0500 -0.0500 0.7854 +primID: 3 +startangle_c: 2 +endpose_c: 5 7 3 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0341 0.0341 0.7854 +0.0678 0.0684 0.8151 +0.1000 0.1043 0.8669 +0.1302 0.1418 0.9188 +0.1584 0.1809 0.9707 +0.1846 0.2213 1.0225 +0.2086 0.2631 1.0744 +0.2304 0.3060 1.1262 +0.2500 0.3500 1.1781 +primID: 4 +startangle_c: 2 +endpose_c: 7 5 1 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0341 0.0341 0.7854 +0.0684 0.0678 0.7557 +0.1043 0.1000 0.7039 +0.1418 0.1302 0.6520 +0.1809 0.1584 0.6001 +0.2213 0.1846 0.5483 +0.2631 0.2086 0.4964 +0.3060 0.2304 0.4446 +0.3500 0.2500 0.3927 +primID: 5 +startangle_c: 2 +endpose_c: 0 0 3 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0000 0.0000 0.8290 +0.0000 0.0000 0.8727 +0.0000 0.0000 0.9163 +0.0000 0.0000 0.9599 +0.0000 0.0000 1.0036 +0.0000 0.0000 1.0472 +0.0000 0.0000 1.0908 +0.0000 0.0000 1.1345 +0.0000 0.0000 1.1781 +primID: 6 +startangle_c: 2 +endpose_c: 0 0 1 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0000 0.0000 0.7418 +0.0000 0.0000 0.6981 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.6109 +0.0000 0.0000 0.5672 +0.0000 0.0000 0.5236 +0.0000 0.0000 0.4800 +0.0000 0.0000 0.4363 +0.0000 0.0000 0.3927 +primID: 0 +startangle_c: 3 +endpose_c: 1 2 3 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0056 0.0111 1.1781 +0.0111 0.0222 1.1781 +0.0167 0.0333 1.1781 +0.0222 0.0444 1.1781 +0.0278 0.0556 1.1781 +0.0333 0.0667 1.1781 +0.0389 0.0778 1.1781 +0.0444 0.0889 1.1781 +0.0500 0.1000 1.1781 +primID: 1 +startangle_c: 3 +endpose_c: 3 6 3 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0167 0.0333 1.1781 +0.0333 0.0667 1.1781 +0.0500 0.1000 1.1781 +0.0667 0.1333 1.1781 +0.0833 0.1667 1.1781 +0.1000 0.2000 1.1781 +0.1167 0.2333 1.1781 +0.1333 0.2667 1.1781 +0.1500 0.3000 1.1781 +primID: 2 +startangle_c: 3 +endpose_c: -1 -2 3 +additionalactioncostmult: 40 +intermediateposes: 10 +0.0000 0.0000 1.1781 +-0.0056 -0.0111 1.1781 +-0.0111 -0.0222 1.1781 +-0.0167 -0.0333 1.1781 +-0.0222 -0.0444 1.1781 +-0.0278 -0.0556 1.1781 +-0.0333 -0.0667 1.1781 +-0.0389 -0.0778 1.1781 +-0.0444 -0.0889 1.1781 +-0.0500 -0.1000 1.1781 +primID: 3 +startangle_c: 3 +endpose_c: 4 5 2 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0184 0.0298 1.1478 +0.0379 0.0592 1.1175 +0.0583 0.0881 1.0872 +0.0796 0.1165 1.0569 +0.1019 0.1444 1.0266 +0.1251 0.1717 0.9963 +0.1492 0.1984 0.9660 +0.1742 0.2245 0.9357 +0.2000 0.2500 0.9054 +primID: 4 +startangle_c: 3 +endpose_c: 2 7 4 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0156 0.0377 1.1781 +0.0312 0.0754 1.1781 +0.0468 0.1131 1.1781 +0.0623 0.1508 1.1972 +0.0758 0.1893 1.2719 +0.0863 0.2287 1.3466 +0.0939 0.2687 1.4214 +0.0985 0.3092 1.4961 +0.1000 0.3500 1.5708 +primID: 5 +startangle_c: 3 +endpose_c: 0 0 2 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0000 0.0000 1.1345 +0.0000 0.0000 1.0908 +0.0000 0.0000 1.0472 +0.0000 0.0000 1.0036 +0.0000 0.0000 0.9599 +0.0000 0.0000 0.9163 +0.0000 0.0000 0.8727 +0.0000 0.0000 0.8290 +0.0000 0.0000 0.7854 +primID: 6 +startangle_c: 3 +endpose_c: 0 0 4 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0000 0.0000 1.2217 +0.0000 0.0000 1.2654 +0.0000 0.0000 1.3090 +0.0000 0.0000 1.3526 +0.0000 0.0000 1.3963 +0.0000 0.0000 1.4399 +0.0000 0.0000 1.4835 +0.0000 0.0000 1.5272 +0.0000 0.0000 1.5708 +primID: 0 +startangle_c: 4 +endpose_c: 0 1 4 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0056 1.5708 +0.0000 0.0111 1.5708 +0.0000 0.0167 1.5708 +0.0000 0.0222 1.5708 +0.0000 0.0278 1.5708 +0.0000 0.0333 1.5708 +0.0000 0.0389 1.5708 +0.0000 0.0444 1.5708 +0.0000 0.0500 1.5708 +primID: 1 +startangle_c: 4 +endpose_c: 0 8 4 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0444 1.5708 +0.0000 0.0889 1.5708 +0.0000 0.1333 1.5708 +0.0000 0.1778 1.5708 +0.0000 0.2222 1.5708 +0.0000 0.2667 1.5708 +0.0000 0.3111 1.5708 +0.0000 0.3556 1.5708 +0.0000 0.4000 1.5708 +primID: 2 +startangle_c: 4 +endpose_c: 0 -1 4 +additionalactioncostmult: 40 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 -0.0056 1.5708 +0.0000 -0.0111 1.5708 +0.0000 -0.0167 1.5708 +0.0000 -0.0222 1.5708 +0.0000 -0.0278 1.5708 +0.0000 -0.0333 1.5708 +0.0000 -0.0389 1.5708 +0.0000 -0.0444 1.5708 +0.0000 -0.0500 1.5708 +primID: 3 +startangle_c: 4 +endpose_c: -1 8 5 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0452 1.5708 +0.0000 0.0904 1.5708 +0.0000 0.1355 1.5708 +-0.0008 0.1807 1.6196 +-0.0045 0.2257 1.6884 +-0.0114 0.2703 1.7572 +-0.0213 0.3144 1.8259 +-0.0342 0.3577 1.8947 +-0.0500 0.4000 1.9635 +primID: 4 +startangle_c: 4 +endpose_c: 1 8 3 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0452 1.5708 +0.0000 0.0904 1.5708 +0.0000 0.1355 1.5708 +0.0008 0.1807 1.5220 +0.0045 0.2257 1.4532 +0.0114 0.2703 1.3844 +0.0213 0.3144 1.3156 +0.0342 0.3577 1.2469 +0.0500 0.4000 1.1781 +primID: 5 +startangle_c: 4 +endpose_c: 0 0 5 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0000 1.6144 +0.0000 0.0000 1.6581 +0.0000 0.0000 1.7017 +0.0000 0.0000 1.7453 +0.0000 0.0000 1.7890 +0.0000 0.0000 1.8326 +0.0000 0.0000 1.8762 +0.0000 0.0000 1.9199 +0.0000 0.0000 1.9635 +primID: 6 +startangle_c: 4 +endpose_c: 0 0 3 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0000 1.5272 +0.0000 0.0000 1.4835 +0.0000 0.0000 1.4399 +0.0000 0.0000 1.3963 +0.0000 0.0000 1.3526 +0.0000 0.0000 1.3090 +0.0000 0.0000 1.2654 +0.0000 0.0000 1.2217 +0.0000 0.0000 1.1781 +primID: 0 +startangle_c: 5 +endpose_c: -1 2 5 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0056 0.0111 1.9635 +-0.0111 0.0222 1.9635 +-0.0167 0.0333 1.9635 +-0.0222 0.0444 1.9635 +-0.0278 0.0556 1.9635 +-0.0333 0.0667 1.9635 +-0.0389 0.0778 1.9635 +-0.0444 0.0889 1.9635 +-0.0500 0.1000 1.9635 +primID: 1 +startangle_c: 5 +endpose_c: -3 6 5 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0167 0.0333 1.9635 +-0.0333 0.0667 1.9635 +-0.0500 0.1000 1.9635 +-0.0667 0.1333 1.9635 +-0.0833 0.1667 1.9635 +-0.1000 0.2000 1.9635 +-0.1167 0.2333 1.9635 +-0.1333 0.2667 1.9635 +-0.1500 0.3000 1.9635 +primID: 2 +startangle_c: 5 +endpose_c: 1 -2 5 +additionalactioncostmult: 40 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0056 -0.0111 1.9635 +0.0111 -0.0222 1.9635 +0.0167 -0.0333 1.9635 +0.0222 -0.0444 1.9635 +0.0278 -0.0556 1.9635 +0.0333 -0.0667 1.9635 +0.0389 -0.0778 1.9635 +0.0444 -0.0889 1.9635 +0.0500 -0.1000 1.9635 +primID: 3 +startangle_c: 5 +endpose_c: -4 5 6 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0184 0.0298 1.9938 +-0.0379 0.0592 2.0241 +-0.0583 0.0881 2.0544 +-0.0796 0.1165 2.0847 +-0.1019 0.1444 2.1150 +-0.1251 0.1717 2.1453 +-0.1492 0.1984 2.1756 +-0.1742 0.2245 2.2059 +-0.2000 0.2500 2.2362 +primID: 4 +startangle_c: 5 +endpose_c: -2 7 4 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0156 0.0377 1.9635 +-0.0312 0.0754 1.9635 +-0.0468 0.1131 1.9635 +-0.0623 0.1508 1.9444 +-0.0758 0.1893 1.8697 +-0.0863 0.2287 1.7950 +-0.0939 0.2687 1.7202 +-0.0985 0.3092 1.6455 +-0.1000 0.3500 1.5708 +primID: 5 +startangle_c: 5 +endpose_c: 0 0 6 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0000 0.0000 2.0071 +0.0000 0.0000 2.0508 +0.0000 0.0000 2.0944 +0.0000 0.0000 2.1380 +0.0000 0.0000 2.1817 +0.0000 0.0000 2.2253 +0.0000 0.0000 2.2689 +0.0000 0.0000 2.3126 +0.0000 0.0000 2.3562 +primID: 6 +startangle_c: 5 +endpose_c: 0 0 4 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0000 0.0000 1.9199 +0.0000 0.0000 1.8762 +0.0000 0.0000 1.8326 +0.0000 0.0000 1.7890 +0.0000 0.0000 1.7453 +0.0000 0.0000 1.7017 +0.0000 0.0000 1.6581 +0.0000 0.0000 1.6144 +0.0000 0.0000 1.5708 +primID: 0 +startangle_c: 6 +endpose_c: -1 1 6 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0056 0.0056 2.3562 +-0.0111 0.0111 2.3562 +-0.0167 0.0167 2.3562 +-0.0222 0.0222 2.3562 +-0.0278 0.0278 2.3562 +-0.0333 0.0333 2.3562 +-0.0389 0.0389 2.3562 +-0.0444 0.0444 2.3562 +-0.0500 0.0500 2.3562 +primID: 1 +startangle_c: 6 +endpose_c: -6 6 6 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0333 0.0333 2.3562 +-0.0667 0.0667 2.3562 +-0.1000 0.1000 2.3562 +-0.1333 0.1333 2.3562 +-0.1667 0.1667 2.3562 +-0.2000 0.2000 2.3562 +-0.2333 0.2333 2.3562 +-0.2667 0.2667 2.3562 +-0.3000 0.3000 2.3562 +primID: 2 +startangle_c: 6 +endpose_c: 1 -1 6 +additionalactioncostmult: 40 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0056 -0.0056 2.3562 +0.0111 -0.0111 2.3562 +0.0167 -0.0167 2.3562 +0.0222 -0.0222 2.3562 +0.0278 -0.0278 2.3562 +0.0333 -0.0333 2.3562 +0.0389 -0.0389 2.3562 +0.0444 -0.0444 2.3562 +0.0500 -0.0500 2.3562 +primID: 3 +startangle_c: 6 +endpose_c: -7 5 7 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0341 0.0341 2.3562 +-0.0684 0.0678 2.3859 +-0.1043 0.1000 2.4377 +-0.1418 0.1302 2.4896 +-0.1809 0.1584 2.5415 +-0.2213 0.1846 2.5933 +-0.2631 0.2086 2.6452 +-0.3060 0.2304 2.6970 +-0.3500 0.2500 2.7489 +primID: 4 +startangle_c: 6 +endpose_c: -5 7 5 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0341 0.0341 2.3562 +-0.0678 0.0684 2.3265 +-0.1000 0.1043 2.2747 +-0.1302 0.1418 2.2228 +-0.1584 0.1809 2.1709 +-0.1846 0.2213 2.1191 +-0.2086 0.2631 2.0672 +-0.2304 0.3060 2.0154 +-0.2500 0.3500 1.9635 +primID: 5 +startangle_c: 6 +endpose_c: 0 0 7 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0000 0.0000 2.3998 +0.0000 0.0000 2.4435 +0.0000 0.0000 2.4871 +0.0000 0.0000 2.5307 +0.0000 0.0000 2.5744 +0.0000 0.0000 2.6180 +0.0000 0.0000 2.6616 +0.0000 0.0000 2.7053 +0.0000 0.0000 2.7489 +primID: 6 +startangle_c: 6 +endpose_c: 0 0 5 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0000 0.0000 2.3126 +0.0000 0.0000 2.2689 +0.0000 0.0000 2.2253 +0.0000 0.0000 2.1817 +0.0000 0.0000 2.1380 +0.0000 0.0000 2.0944 +0.0000 0.0000 2.0508 +0.0000 0.0000 2.0071 +0.0000 0.0000 1.9635 +primID: 0 +startangle_c: 7 +endpose_c: -2 1 7 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0111 0.0056 2.7489 +-0.0222 0.0111 2.7489 +-0.0333 0.0167 2.7489 +-0.0444 0.0222 2.7489 +-0.0556 0.0278 2.7489 +-0.0667 0.0333 2.7489 +-0.0778 0.0389 2.7489 +-0.0889 0.0444 2.7489 +-0.1000 0.0500 2.7489 +primID: 1 +startangle_c: 7 +endpose_c: -6 3 7 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0333 0.0167 2.7489 +-0.0667 0.0333 2.7489 +-0.1000 0.0500 2.7489 +-0.1333 0.0667 2.7489 +-0.1667 0.0833 2.7489 +-0.2000 0.1000 2.7489 +-0.2333 0.1167 2.7489 +-0.2667 0.1333 2.7489 +-0.3000 0.1500 2.7489 +primID: 2 +startangle_c: 7 +endpose_c: 2 -1 7 +additionalactioncostmult: 40 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0111 -0.0056 2.7489 +0.0222 -0.0111 2.7489 +0.0333 -0.0167 2.7489 +0.0444 -0.0222 2.7489 +0.0556 -0.0278 2.7489 +0.0667 -0.0333 2.7489 +0.0778 -0.0389 2.7489 +0.0889 -0.0444 2.7489 +0.1000 -0.0500 2.7489 +primID: 3 +startangle_c: 7 +endpose_c: -5 4 6 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0298 0.0184 2.7186 +-0.0592 0.0379 2.6883 +-0.0881 0.0583 2.6580 +-0.1165 0.0796 2.6277 +-0.1444 0.1019 2.5974 +-0.1717 0.1251 2.5671 +-0.1984 0.1492 2.5368 +-0.2245 0.1742 2.5065 +-0.2500 0.2000 2.4762 +primID: 4 +startangle_c: 7 +endpose_c: -7 2 8 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0377 0.0156 2.7489 +-0.0754 0.0312 2.7489 +-0.1131 0.0468 2.7489 +-0.1508 0.0623 2.7680 +-0.1893 0.0758 2.8427 +-0.2287 0.0863 2.9174 +-0.2687 0.0939 2.9921 +-0.3092 0.0985 3.0669 +-0.3500 0.1000 3.1416 +primID: 5 +startangle_c: 7 +endpose_c: 0 0 6 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0000 0.0000 2.7053 +0.0000 0.0000 2.6616 +0.0000 0.0000 2.6180 +0.0000 0.0000 2.5744 +0.0000 0.0000 2.5307 +0.0000 0.0000 2.4871 +0.0000 0.0000 2.4435 +0.0000 0.0000 2.3998 +0.0000 0.0000 2.3562 +primID: 6 +startangle_c: 7 +endpose_c: 0 0 8 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0000 0.0000 2.7925 +0.0000 0.0000 2.8362 +0.0000 0.0000 2.8798 +0.0000 0.0000 2.9234 +0.0000 0.0000 2.9671 +0.0000 0.0000 3.0107 +0.0000 0.0000 3.0543 +0.0000 0.0000 3.0980 +0.0000 0.0000 3.1416 +primID: 0 +startangle_c: 8 +endpose_c: -1 0 8 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0056 0.0000 3.1416 +-0.0111 0.0000 3.1416 +-0.0167 0.0000 3.1416 +-0.0222 0.0000 3.1416 +-0.0278 0.0000 3.1416 +-0.0333 0.0000 3.1416 +-0.0389 0.0000 3.1416 +-0.0444 0.0000 3.1416 +-0.0500 0.0000 3.1416 +primID: 1 +startangle_c: 8 +endpose_c: -8 0 8 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0444 0.0000 3.1416 +-0.0889 0.0000 3.1416 +-0.1333 0.0000 3.1416 +-0.1778 0.0000 3.1416 +-0.2222 0.0000 3.1416 +-0.2667 0.0000 3.1416 +-0.3111 0.0000 3.1416 +-0.3556 0.0000 3.1416 +-0.4000 0.0000 3.1416 +primID: 2 +startangle_c: 8 +endpose_c: 1 0 8 +additionalactioncostmult: 40 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0056 0.0000 3.1416 +0.0111 0.0000 3.1416 +0.0167 0.0000 3.1416 +0.0222 0.0000 3.1416 +0.0278 0.0000 3.1416 +0.0333 0.0000 3.1416 +0.0389 0.0000 3.1416 +0.0444 0.0000 3.1416 +0.0500 0.0000 3.1416 +primID: 3 +startangle_c: 8 +endpose_c: -8 -1 9 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0452 0.0000 3.1416 +-0.0904 0.0000 3.1416 +-0.1355 0.0000 3.1416 +-0.1807 -0.0008 3.1904 +-0.2257 -0.0045 3.2592 +-0.2703 -0.0114 3.3280 +-0.3144 -0.0213 3.3967 +-0.3577 -0.0342 3.4655 +-0.4000 -0.0500 3.5343 +primID: 4 +startangle_c: 8 +endpose_c: -8 1 7 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0452 0.0000 3.1416 +-0.0904 0.0000 3.1416 +-0.1355 0.0000 3.1416 +-0.1807 0.0008 3.0928 +-0.2257 0.0045 3.0240 +-0.2703 0.0114 2.9552 +-0.3144 0.0213 2.8864 +-0.3577 0.0342 2.8177 +-0.4000 0.0500 2.7489 +primID: 5 +startangle_c: 8 +endpose_c: 0 0 9 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0000 0.0000 3.1852 +0.0000 0.0000 3.2289 +0.0000 0.0000 3.2725 +0.0000 0.0000 3.3161 +0.0000 0.0000 3.3598 +0.0000 0.0000 3.4034 +0.0000 0.0000 3.4470 +0.0000 0.0000 3.4907 +0.0000 0.0000 3.5343 +primID: 6 +startangle_c: 8 +endpose_c: 0 0 7 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0000 0.0000 3.0980 +0.0000 0.0000 3.0543 +0.0000 0.0000 3.0107 +0.0000 0.0000 2.9671 +0.0000 0.0000 2.9234 +0.0000 0.0000 2.8798 +0.0000 0.0000 2.8362 +0.0000 0.0000 2.7925 +0.0000 0.0000 2.7489 +primID: 0 +startangle_c: 9 +endpose_c: -2 -1 9 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0111 -0.0056 3.5343 +-0.0222 -0.0111 3.5343 +-0.0333 -0.0167 3.5343 +-0.0444 -0.0222 3.5343 +-0.0556 -0.0278 3.5343 +-0.0667 -0.0333 3.5343 +-0.0778 -0.0389 3.5343 +-0.0889 -0.0444 3.5343 +-0.1000 -0.0500 3.5343 +primID: 1 +startangle_c: 9 +endpose_c: -6 -3 9 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0333 -0.0167 3.5343 +-0.0667 -0.0333 3.5343 +-0.1000 -0.0500 3.5343 +-0.1333 -0.0667 3.5343 +-0.1667 -0.0833 3.5343 +-0.2000 -0.1000 3.5343 +-0.2333 -0.1167 3.5343 +-0.2667 -0.1333 3.5343 +-0.3000 -0.1500 3.5343 +primID: 2 +startangle_c: 9 +endpose_c: 2 1 9 +additionalactioncostmult: 40 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0111 0.0056 3.5343 +0.0222 0.0111 3.5343 +0.0333 0.0167 3.5343 +0.0444 0.0222 3.5343 +0.0556 0.0278 3.5343 +0.0667 0.0333 3.5343 +0.0778 0.0389 3.5343 +0.0889 0.0444 3.5343 +0.1000 0.0500 3.5343 +primID: 3 +startangle_c: 9 +endpose_c: -5 -4 10 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0298 -0.0184 3.5646 +-0.0592 -0.0379 3.5949 +-0.0881 -0.0583 3.6252 +-0.1165 -0.0796 3.6555 +-0.1444 -0.1019 3.6858 +-0.1717 -0.1251 3.7161 +-0.1984 -0.1492 3.7464 +-0.2245 -0.1742 3.7767 +-0.2500 -0.2000 3.8070 +primID: 4 +startangle_c: 9 +endpose_c: -7 -2 8 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0377 -0.0156 3.5343 +-0.0754 -0.0312 3.5343 +-0.1131 -0.0468 3.5343 +-0.1508 -0.0623 3.5152 +-0.1893 -0.0758 3.4405 +-0.2287 -0.0863 3.3658 +-0.2687 -0.0939 3.2910 +-0.3092 -0.0985 3.2163 +-0.3500 -0.1000 3.1416 +primID: 5 +startangle_c: 9 +endpose_c: 0 0 10 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0000 0.0000 3.5779 +0.0000 0.0000 3.6216 +0.0000 0.0000 3.6652 +0.0000 0.0000 3.7088 +0.0000 0.0000 3.7525 +0.0000 0.0000 3.7961 +0.0000 0.0000 3.8397 +0.0000 0.0000 3.8834 +0.0000 0.0000 3.9270 +primID: 6 +startangle_c: 9 +endpose_c: 0 0 8 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0000 0.0000 3.4907 +0.0000 0.0000 3.4470 +0.0000 0.0000 3.4034 +0.0000 0.0000 3.3598 +0.0000 0.0000 3.3161 +0.0000 0.0000 3.2725 +0.0000 0.0000 3.2289 +0.0000 0.0000 3.1852 +0.0000 0.0000 3.1416 +primID: 0 +startangle_c: 10 +endpose_c: -1 -1 10 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0056 -0.0056 3.9270 +-0.0111 -0.0111 3.9270 +-0.0167 -0.0167 3.9270 +-0.0222 -0.0222 3.9270 +-0.0278 -0.0278 3.9270 +-0.0333 -0.0333 3.9270 +-0.0389 -0.0389 3.9270 +-0.0444 -0.0444 3.9270 +-0.0500 -0.0500 3.9270 +primID: 1 +startangle_c: 10 +endpose_c: -6 -6 10 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0333 -0.0333 3.9270 +-0.0667 -0.0667 3.9270 +-0.1000 -0.1000 3.9270 +-0.1333 -0.1333 3.9270 +-0.1667 -0.1667 3.9270 +-0.2000 -0.2000 3.9270 +-0.2333 -0.2333 3.9270 +-0.2667 -0.2667 3.9270 +-0.3000 -0.3000 3.9270 +primID: 2 +startangle_c: 10 +endpose_c: 1 1 10 +additionalactioncostmult: 40 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0056 0.0056 3.9270 +0.0111 0.0111 3.9270 +0.0167 0.0167 3.9270 +0.0222 0.0222 3.9270 +0.0278 0.0278 3.9270 +0.0333 0.0333 3.9270 +0.0389 0.0389 3.9270 +0.0444 0.0444 3.9270 +0.0500 0.0500 3.9270 +primID: 3 +startangle_c: 10 +endpose_c: -5 -7 11 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0341 -0.0341 3.9270 +-0.0678 -0.0684 3.9567 +-0.1000 -0.1043 4.0085 +-0.1302 -0.1418 4.0604 +-0.1584 -0.1809 4.1123 +-0.1846 -0.2213 4.1641 +-0.2086 -0.2631 4.2160 +-0.2304 -0.3060 4.2678 +-0.2500 -0.3500 4.3197 +primID: 4 +startangle_c: 10 +endpose_c: -7 -5 9 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0341 -0.0341 3.9270 +-0.0684 -0.0678 3.8973 +-0.1043 -0.1000 3.8455 +-0.1418 -0.1302 3.7936 +-0.1809 -0.1584 3.7417 +-0.2213 -0.1846 3.6899 +-0.2631 -0.2086 3.6380 +-0.3060 -0.2304 3.5862 +-0.3500 -0.2500 3.5343 +primID: 5 +startangle_c: 10 +endpose_c: 0 0 11 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.9706 +0.0000 0.0000 4.0143 +0.0000 0.0000 4.0579 +0.0000 0.0000 4.1015 +0.0000 0.0000 4.1452 +0.0000 0.0000 4.1888 +0.0000 0.0000 4.2324 +0.0000 0.0000 4.2761 +0.0000 0.0000 4.3197 +primID: 6 +startangle_c: 10 +endpose_c: 0 0 9 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.8834 +0.0000 0.0000 3.8397 +0.0000 0.0000 3.7961 +0.0000 0.0000 3.7525 +0.0000 0.0000 3.7088 +0.0000 0.0000 3.6652 +0.0000 0.0000 3.6216 +0.0000 0.0000 3.5779 +0.0000 0.0000 3.5343 +primID: 0 +startangle_c: 11 +endpose_c: -1 -2 11 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0056 -0.0111 4.3197 +-0.0111 -0.0222 4.3197 +-0.0167 -0.0333 4.3197 +-0.0222 -0.0444 4.3197 +-0.0278 -0.0556 4.3197 +-0.0333 -0.0667 4.3197 +-0.0389 -0.0778 4.3197 +-0.0444 -0.0889 4.3197 +-0.0500 -0.1000 4.3197 +primID: 1 +startangle_c: 11 +endpose_c: -3 -6 11 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0167 -0.0333 4.3197 +-0.0333 -0.0667 4.3197 +-0.0500 -0.1000 4.3197 +-0.0667 -0.1333 4.3197 +-0.0833 -0.1667 4.3197 +-0.1000 -0.2000 4.3197 +-0.1167 -0.2333 4.3197 +-0.1333 -0.2667 4.3197 +-0.1500 -0.3000 4.3197 +primID: 2 +startangle_c: 11 +endpose_c: 1 2 11 +additionalactioncostmult: 40 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0056 0.0111 4.3197 +0.0111 0.0222 4.3197 +0.0167 0.0333 4.3197 +0.0222 0.0444 4.3197 +0.0278 0.0556 4.3197 +0.0333 0.0667 4.3197 +0.0389 0.0778 4.3197 +0.0444 0.0889 4.3197 +0.0500 0.1000 4.3197 +primID: 3 +startangle_c: 11 +endpose_c: -4 -5 10 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0184 -0.0298 4.2894 +-0.0379 -0.0592 4.2591 +-0.0583 -0.0881 4.2288 +-0.0796 -0.1165 4.1985 +-0.1019 -0.1444 4.1682 +-0.1251 -0.1717 4.1379 +-0.1492 -0.1984 4.1076 +-0.1742 -0.2245 4.0773 +-0.2000 -0.2500 4.0470 +primID: 4 +startangle_c: 11 +endpose_c: -2 -7 12 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0156 -0.0377 4.3197 +-0.0312 -0.0754 4.3197 +-0.0468 -0.1131 4.3197 +-0.0623 -0.1508 4.3388 +-0.0758 -0.1893 4.4135 +-0.0863 -0.2287 4.4882 +-0.0939 -0.2687 4.5629 +-0.0985 -0.3092 4.6377 +-0.1000 -0.3500 4.7124 +primID: 5 +startangle_c: 11 +endpose_c: 0 0 10 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0000 0.0000 4.2761 +0.0000 0.0000 4.2324 +0.0000 0.0000 4.1888 +0.0000 0.0000 4.1452 +0.0000 0.0000 4.1015 +0.0000 0.0000 4.0579 +0.0000 0.0000 4.0143 +0.0000 0.0000 3.9706 +0.0000 0.0000 3.9270 +primID: 6 +startangle_c: 11 +endpose_c: 0 0 12 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0000 0.0000 4.3633 +0.0000 0.0000 4.4070 +0.0000 0.0000 4.4506 +0.0000 0.0000 4.4942 +0.0000 0.0000 4.5379 +0.0000 0.0000 4.5815 +0.0000 0.0000 4.6251 +0.0000 0.0000 4.6688 +0.0000 0.0000 4.7124 +primID: 0 +startangle_c: 12 +endpose_c: 0 -1 12 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0056 4.7124 +0.0000 -0.0111 4.7124 +0.0000 -0.0167 4.7124 +0.0000 -0.0222 4.7124 +0.0000 -0.0278 4.7124 +0.0000 -0.0333 4.7124 +0.0000 -0.0389 4.7124 +0.0000 -0.0444 4.7124 +0.0000 -0.0500 4.7124 +primID: 1 +startangle_c: 12 +endpose_c: 0 -8 12 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0444 4.7124 +0.0000 -0.0889 4.7124 +0.0000 -0.1333 4.7124 +0.0000 -0.1778 4.7124 +0.0000 -0.2222 4.7124 +0.0000 -0.2667 4.7124 +0.0000 -0.3111 4.7124 +0.0000 -0.3556 4.7124 +0.0000 -0.4000 4.7124 +primID: 2 +startangle_c: 12 +endpose_c: 0 1 12 +additionalactioncostmult: 40 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0056 4.7124 +0.0000 0.0111 4.7124 +0.0000 0.0167 4.7124 +0.0000 0.0222 4.7124 +0.0000 0.0278 4.7124 +0.0000 0.0333 4.7124 +0.0000 0.0389 4.7124 +0.0000 0.0444 4.7124 +0.0000 0.0500 4.7124 +primID: 3 +startangle_c: 12 +endpose_c: 1 -8 13 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0452 4.7124 +0.0000 -0.0904 4.7124 +0.0000 -0.1355 4.7124 +0.0008 -0.1807 4.7612 +0.0045 -0.2257 4.8300 +0.0114 -0.2703 4.8988 +0.0213 -0.3144 4.9675 +0.0342 -0.3577 5.0363 +0.0500 -0.4000 5.1051 +primID: 4 +startangle_c: 12 +endpose_c: -1 -8 11 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 4.7124 +-0.0000 -0.0452 4.7124 +-0.0000 -0.0904 4.7124 +-0.0000 -0.1355 4.7124 +-0.0008 -0.1807 4.6636 +-0.0045 -0.2257 4.5948 +-0.0114 -0.2703 4.5260 +-0.0213 -0.3144 4.4572 +-0.0342 -0.3577 4.3885 +-0.0500 -0.4000 4.3197 +primID: 5 +startangle_c: 12 +endpose_c: 0 0 13 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0000 4.7560 +0.0000 0.0000 4.7997 +0.0000 0.0000 4.8433 +0.0000 0.0000 4.8869 +0.0000 0.0000 4.9306 +0.0000 0.0000 4.9742 +0.0000 0.0000 5.0178 +0.0000 0.0000 5.0615 +0.0000 0.0000 5.1051 +primID: 6 +startangle_c: 12 +endpose_c: 0 0 11 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0000 4.6688 +0.0000 0.0000 4.6251 +0.0000 0.0000 4.5815 +0.0000 0.0000 4.5379 +0.0000 0.0000 4.4942 +0.0000 0.0000 4.4506 +0.0000 0.0000 4.4070 +0.0000 0.0000 4.3633 +0.0000 0.0000 4.3197 +primID: 0 +startangle_c: 13 +endpose_c: 1 -2 13 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0056 -0.0111 5.1051 +0.0111 -0.0222 5.1051 +0.0167 -0.0333 5.1051 +0.0222 -0.0444 5.1051 +0.0278 -0.0556 5.1051 +0.0333 -0.0667 5.1051 +0.0389 -0.0778 5.1051 +0.0444 -0.0889 5.1051 +0.0500 -0.1000 5.1051 +primID: 1 +startangle_c: 13 +endpose_c: 3 -6 13 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0167 -0.0333 5.1051 +0.0333 -0.0667 5.1051 +0.0500 -0.1000 5.1051 +0.0667 -0.1333 5.1051 +0.0833 -0.1667 5.1051 +0.1000 -0.2000 5.1051 +0.1167 -0.2333 5.1051 +0.1333 -0.2667 5.1051 +0.1500 -0.3000 5.1051 +primID: 2 +startangle_c: 13 +endpose_c: -1 2 13 +additionalactioncostmult: 40 +intermediateposes: 10 +0.0000 0.0000 5.1051 +-0.0056 0.0111 5.1051 +-0.0111 0.0222 5.1051 +-0.0167 0.0333 5.1051 +-0.0222 0.0444 5.1051 +-0.0278 0.0556 5.1051 +-0.0333 0.0667 5.1051 +-0.0389 0.0778 5.1051 +-0.0444 0.0889 5.1051 +-0.0500 0.1000 5.1051 +primID: 3 +startangle_c: 13 +endpose_c: 4 -5 14 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0184 -0.0298 5.1354 +0.0379 -0.0592 5.1657 +0.0583 -0.0881 5.1960 +0.0796 -0.1165 5.2263 +0.1019 -0.1444 5.2566 +0.1251 -0.1717 5.2869 +0.1492 -0.1984 5.3172 +0.1742 -0.2245 5.3475 +0.2000 -0.2500 5.3778 +primID: 4 +startangle_c: 13 +endpose_c: 2 -7 12 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0156 -0.0377 5.1051 +0.0312 -0.0754 5.1051 +0.0468 -0.1131 5.1051 +0.0623 -0.1508 5.0860 +0.0758 -0.1893 5.0113 +0.0863 -0.2287 4.9366 +0.0939 -0.2687 4.8618 +0.0985 -0.3092 4.7871 +0.1000 -0.3500 4.7124 +primID: 5 +startangle_c: 13 +endpose_c: 0 0 14 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0000 0.0000 5.1487 +0.0000 0.0000 5.1924 +0.0000 0.0000 5.2360 +0.0000 0.0000 5.2796 +0.0000 0.0000 5.3233 +0.0000 0.0000 5.3669 +0.0000 0.0000 5.4105 +0.0000 0.0000 5.4542 +0.0000 0.0000 5.4978 +primID: 6 +startangle_c: 13 +endpose_c: 0 0 12 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0000 0.0000 5.0615 +0.0000 0.0000 5.0178 +0.0000 0.0000 4.9742 +0.0000 0.0000 4.9306 +0.0000 0.0000 4.8869 +0.0000 0.0000 4.8433 +0.0000 0.0000 4.7997 +0.0000 0.0000 4.7560 +0.0000 0.0000 4.7124 +primID: 0 +startangle_c: 14 +endpose_c: 1 -1 14 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0056 -0.0056 5.4978 +0.0111 -0.0111 5.4978 +0.0167 -0.0167 5.4978 +0.0222 -0.0222 5.4978 +0.0278 -0.0278 5.4978 +0.0333 -0.0333 5.4978 +0.0389 -0.0389 5.4978 +0.0444 -0.0444 5.4978 +0.0500 -0.0500 5.4978 +primID: 1 +startangle_c: 14 +endpose_c: 6 -6 14 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0333 -0.0333 5.4978 +0.0667 -0.0667 5.4978 +0.1000 -0.1000 5.4978 +0.1333 -0.1333 5.4978 +0.1667 -0.1667 5.4978 +0.2000 -0.2000 5.4978 +0.2333 -0.2333 5.4978 +0.2667 -0.2667 5.4978 +0.3000 -0.3000 5.4978 +primID: 2 +startangle_c: 14 +endpose_c: -1 1 14 +additionalactioncostmult: 40 +intermediateposes: 10 +0.0000 0.0000 5.4978 +-0.0056 0.0056 5.4978 +-0.0111 0.0111 5.4978 +-0.0167 0.0167 5.4978 +-0.0222 0.0222 5.4978 +-0.0278 0.0278 5.4978 +-0.0333 0.0333 5.4978 +-0.0389 0.0389 5.4978 +-0.0444 0.0444 5.4978 +-0.0500 0.0500 5.4978 +primID: 3 +startangle_c: 14 +endpose_c: 7 -5 15 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0341 -0.0341 5.4978 +0.0684 -0.0678 5.5275 +0.1043 -0.1000 5.5793 +0.1418 -0.1302 5.6312 +0.1809 -0.1584 5.6830 +0.2213 -0.1846 5.7349 +0.2631 -0.2086 5.7868 +0.3060 -0.2304 5.8386 +0.3500 -0.2500 5.8905 +primID: 4 +startangle_c: 14 +endpose_c: 5 -7 13 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0341 -0.0341 5.4978 +0.0678 -0.0684 5.4681 +0.1000 -0.1043 5.4162 +0.1302 -0.1418 5.3644 +0.1584 -0.1809 5.3125 +0.1846 -0.2213 5.2607 +0.2086 -0.2631 5.2088 +0.2304 -0.3060 5.1569 +0.2500 -0.3500 5.1051 +primID: 5 +startangle_c: 14 +endpose_c: 0 0 15 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0000 0.0000 5.5414 +0.0000 0.0000 5.5851 +0.0000 0.0000 5.6287 +0.0000 0.0000 5.6723 +0.0000 0.0000 5.7160 +0.0000 0.0000 5.7596 +0.0000 0.0000 5.8032 +0.0000 0.0000 5.8469 +0.0000 0.0000 5.8905 +primID: 6 +startangle_c: 14 +endpose_c: 0 0 13 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0000 0.0000 5.4542 +0.0000 0.0000 5.4105 +0.0000 0.0000 5.3669 +0.0000 0.0000 5.3233 +0.0000 0.0000 5.2796 +0.0000 0.0000 5.2360 +0.0000 0.0000 5.1924 +0.0000 0.0000 5.1487 +0.0000 0.0000 5.1051 +primID: 0 +startangle_c: 15 +endpose_c: 2 -1 15 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0111 -0.0056 5.8905 +0.0222 -0.0111 5.8905 +0.0333 -0.0167 5.8905 +0.0444 -0.0222 5.8905 +0.0556 -0.0278 5.8905 +0.0667 -0.0333 5.8905 +0.0778 -0.0389 5.8905 +0.0889 -0.0444 5.8905 +0.1000 -0.0500 5.8905 +primID: 1 +startangle_c: 15 +endpose_c: 6 -3 15 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0333 -0.0167 5.8905 +0.0667 -0.0333 5.8905 +0.1000 -0.0500 5.8905 +0.1333 -0.0667 5.8905 +0.1667 -0.0833 5.8905 +0.2000 -0.1000 5.8905 +0.2333 -0.1167 5.8905 +0.2667 -0.1333 5.8905 +0.3000 -0.1500 5.8905 +primID: 2 +startangle_c: 15 +endpose_c: -2 1 15 +additionalactioncostmult: 40 +intermediateposes: 10 +0.0000 0.0000 5.8905 +-0.0111 0.0056 5.8905 +-0.0222 0.0111 5.8905 +-0.0333 0.0167 5.8905 +-0.0444 0.0222 5.8905 +-0.0556 0.0278 5.8905 +-0.0667 0.0333 5.8905 +-0.0778 0.0389 5.8905 +-0.0889 0.0444 5.8905 +-0.1000 0.0500 5.8905 +primID: 3 +startangle_c: 15 +endpose_c: 5 -4 14 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0298 -0.0184 5.8602 +0.0592 -0.0379 5.8299 +0.0881 -0.0583 5.7996 +0.1165 -0.0796 5.7693 +0.1444 -0.1019 5.7390 +0.1717 -0.1251 5.7087 +0.1984 -0.1492 5.6784 +0.2245 -0.1742 5.6481 +0.2500 -0.2000 5.6178 +primID: 4 +startangle_c: 15 +endpose_c: 7 -2 0 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0377 -0.0156 5.8905 +0.0754 -0.0312 5.8905 +0.1131 -0.0468 5.8905 +0.1508 -0.0623 5.9096 +0.1893 -0.0758 5.9843 +0.2287 -0.0863 6.0590 +0.2687 -0.0939 6.1337 +0.3092 -0.0985 6.2085 +0.3500 -0.1000 6.2832 +primID: 5 +startangle_c: 15 +endpose_c: 0 0 14 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0000 0.0000 5.8469 +0.0000 0.0000 5.8032 +0.0000 0.0000 5.7596 +0.0000 0.0000 5.7160 +0.0000 0.0000 5.6723 +0.0000 0.0000 5.6287 +0.0000 0.0000 5.5851 +0.0000 0.0000 5.5414 +0.0000 0.0000 5.4978 +primID: 6 +startangle_c: 15 +endpose_c: 0 0 0 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0000 0.0000 5.9341 +0.0000 0.0000 5.9778 +0.0000 0.0000 6.0214 +0.0000 0.0000 6.0650 +0.0000 0.0000 6.1087 +0.0000 0.0000 6.1523 +0.0000 0.0000 6.1959 +0.0000 0.0000 6.2396 +0.0000 0.0000 0.0000 diff --git a/mir_robot/mir_navigation/nodes/acc_finder.py b/mir_robot/mir_navigation/nodes/acc_finder.py new file mode 100755 index 0000000..6295112 --- /dev/null +++ b/mir_robot/mir_navigation/nodes/acc_finder.py @@ -0,0 +1,104 @@ +#!/usr/bin/env python3 +# Copyright (c) 2018-2022, Martin Günther (DFKI GmbH) and contributors +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# +# * Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in the +# documentation and/or other materials provided with the distribution. +# +# * Neither the name of the the copyright holder nor the names of its +# contributors may be used to endorse or promote products derived from +# this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE +# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +# Author: Martin Günther + +import rospy + +from geometry_msgs.msg import Twist +from nav_msgs.msg import Odometry + +LIN_MAX = 1.0 +ANG_MAX = 1.5 # adjust this value to the rough maximum angular velocity + +state = 'stopped' +start = rospy.Time(0) + + +def odom_cb(msg): + global state + + twist = msg.twist.twist + t = (rospy.Time.now() - start).to_sec() + + if state == 'wait_for_stop': + if -0.05 < twist.linear.x < 0.05 and -0.1 < twist.angular.z < 0.1: + state = 'stopped' + rospy.loginfo('state transition --> %s', state) + return + + if state == 'backward' and twist.linear.x < -0.9 * LIN_MAX: + rospy.loginfo('backward from 0 to %f m/s in %f sec', twist.linear.x, t) + elif state == 'forward' and twist.linear.x > 0.9 * LIN_MAX: + rospy.loginfo('forward from 0 to %f m/s in %f sec', twist.linear.x, t) + elif state == 'turning_clockwise' and twist.angular.z < -0.9 * ANG_MAX: + rospy.loginfo('turning_clockwise from 0 to %f rad/s in %f sec', twist.angular.z, t) + elif state == 'turning_counter_clockwise' and twist.angular.z > 0.9 * ANG_MAX: + rospy.loginfo('turning_counter_clockwise from 0 to %f rad/s in %f sec', twist.angular.z, t) + else: + return + + state = 'wait_for_stop' + rospy.loginfo('state transition --> %s', state) + + +def cmd_vel_cb(msg): + global state, start + + if state != 'stopped': + return + + if msg.linear.x <= -LIN_MAX: + start = rospy.Time.now() + state = 'backward' + elif msg.linear.x >= LIN_MAX: + start = rospy.Time.now() + state = 'forward' + elif msg.angular.z <= -ANG_MAX: + start = rospy.Time.now() + state = 'turning_clockwise' + elif msg.angular.z >= ANG_MAX: + start = rospy.Time.now() + state = 'turning_counter_clockwise' + else: + return + + rospy.loginfo('state transition --> %s', state) + + +def main(): + rospy.init_node('acc_finder', anonymous=True) + rospy.Subscriber('odom', Odometry, odom_cb) + rospy.Subscriber('cmd_vel', Twist, cmd_vel_cb) + rospy.loginfo('acc_finder node ready and listening. now use teleop to move your robot to the limits!') + rospy.spin() + + +if __name__ == '__main__': + main() diff --git a/mir_robot/mir_navigation/nodes/min_max_finder.py b/mir_robot/mir_navigation/nodes/min_max_finder.py new file mode 100755 index 0000000..7124463 --- /dev/null +++ b/mir_robot/mir_navigation/nodes/min_max_finder.py @@ -0,0 +1,64 @@ +#!/usr/bin/env python3 +# Copyright (c) 2018-2022, Martin Günther (DFKI GmbH) and contributors +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# +# * Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in the +# documentation and/or other materials provided with the distribution. +# +# * Neither the name of the the copyright holder nor the names of its +# contributors may be used to endorse or promote products derived from +# this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE +# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +# Author: Martin Günther + +import rospy + +from nav_msgs.msg import Odometry + +lin_min = 0.0 +lin_max = 0.0 +ang_min = 0.0 +ang_max = 0.0 + + +def odom_cb(msg): + global lin_min, lin_max, ang_min, ang_max + if lin_min > msg.twist.twist.linear.x: + lin_min = msg.twist.twist.linear.x + if lin_max < msg.twist.twist.linear.x: + lin_max = msg.twist.twist.linear.x + if ang_min > msg.twist.twist.angular.z: + ang_min = msg.twist.twist.angular.z + if ang_max < msg.twist.twist.angular.z: + ang_max = msg.twist.twist.angular.z + + rospy.loginfo('linear: [%f, %f] angular: [%f, %f]', lin_min, lin_max, ang_min, ang_max) + + +def main(): + rospy.init_node('min_max_finder', anonymous=True) + rospy.Subscriber('odom', Odometry, odom_cb) + rospy.loginfo('min_max_finde node ready and listening. now use teleop to move your robot to the limits!') + rospy.spin() + + +if __name__ == '__main__': + main() diff --git a/mir_robot/mir_navigation/package.xml b/mir_robot/mir_navigation/package.xml new file mode 100755 index 0000000..261e238 --- /dev/null +++ b/mir_robot/mir_navigation/package.xml @@ -0,0 +1,61 @@ + + + mir_navigation + 1.1.7 + Launch and configuration files for move_base, localization etc. on the MiR robot. + + Martin Günther + Martin Günther + + BSD + + https://github.com/DFKI-NI/mir_robot + https://github.com/DFKI-NI/mir_robot + https://github.com/DFKI-NI/mir_robot/issues + + catkin + + roslaunch + amcl + amcl + + base_local_planner + base_local_planner + + dwa_local_planner + + dwb_critics + dwb_critics + + dwb_local_planner + dwb_local_planner + + dwb_plugins + dwb_plugins + + + hector_mapping + + map_server + map_server + + mir_driver + mir_driver + + mir_dwb_critics + mir_gazebo + + move_base + move_base + + nav_core_adapter + nav_core_adapter + + python3-matplotlib + + sbpl_lattice_planner + sbpl_lattice_planner + + teb_local_planner + teb_local_planner + diff --git a/mir_robot/mir_navigation/rviz/navigation.rviz b/mir_robot/mir_navigation/rviz/navigation.rviz new file mode 100755 index 0000000..223d7de --- /dev/null +++ b/mir_robot/mir_navigation/rviz/navigation.rviz @@ -0,0 +1,784 @@ +Panels: + - Class: rviz/Displays + Help Height: 81 + Name: Displays + Property Tree Widget: + Expanded: + - /Grid1/Offset1 + - /TF1/Frames1 + - /TF1/Tree1 + - /Global Map1 + - /Global Map1/Costmap1 + - /Global Map1/Full Plan1 + - /Local Map1 + - /Local Map1/DWB Markers1/Namespaces1 + Splitter Ratio: 0.42881646752357483 + Tree Height: 641 + - Class: rviz/Selection + Name: Selection + - Class: rviz/Tool Properties + Expanded: + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz/Time + Name: Time + SyncMode: 0 + SyncSource: LaserScan +Preferences: + PromptSaveOnExit: true +Toolbars: + toolButtonStyle: 2 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 50 + Reference Frame: + Value: true + - Alpha: 1 + Class: rviz/RobotModel + Collision Enabled: false + Enabled: true + Links: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + Link Tree Style: Links in Alphabetic Order + back_laser_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + base_footprint: + Alpha: 1 + Show Axes: false + Show Trail: false + base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + bl_caster_rotation_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + bl_caster_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + br_caster_rotation_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + br_caster_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fl_caster_rotation_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fl_caster_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fr_caster_rotation_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fr_caster_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + front_laser_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + imu_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + imu_link: + Alpha: 1 + Show Axes: false + Show Trail: false + left_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + right_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + surface: + Alpha: 1 + Show Axes: false + Show Trail: false + us_1_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + us_2_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + Name: RobotModel + Robot Description: robot_description + TF Prefix: "" + Update Interval: 0 + Value: true + Visual Enabled: true + - Class: rviz/TF + Enabled: true + Filter (blacklist): "" + Filter (whitelist): "" + Frame Timeout: 15 + Frames: + All Enabled: false + back_laser_link: + Value: true + base_footprint: + Value: true + base_link: + Value: true + bl_caster_rotation_link: + Value: true + bl_caster_wheel_link: + Value: true + br_caster_rotation_link: + Value: true + br_caster_wheel_link: + Value: true + fl_caster_rotation_link: + Value: true + fl_caster_wheel_link: + Value: true + fr_caster_rotation_link: + Value: true + fr_caster_wheel_link: + Value: true + front_laser_link: + Value: true + imu_frame: + Value: true + imu_link: + Value: true + left_wheel_link: + Value: true + map: + Value: true + odom: + Value: true + right_wheel_link: + Value: true + surface: + Value: true + us_1_frame: + Value: true + us_2_frame: + Value: true + Marker Alpha: 1 + Marker Scale: 1 + Name: TF + Show Arrows: true + Show Axes: true + Show Names: false + Tree: + map: + odom: + base_footprint: + base_link: + back_laser_link: + {} + bl_caster_rotation_link: + bl_caster_wheel_link: + {} + br_caster_rotation_link: + br_caster_wheel_link: + {} + fl_caster_rotation_link: + fl_caster_wheel_link: + {} + fr_caster_rotation_link: + fr_caster_wheel_link: + {} + front_laser_link: + {} + imu_link: + imu_frame: + {} + left_wheel_link: + {} + right_wheel_link: + {} + surface: + {} + us_1_frame: + {} + us_2_frame: + {} + Update Interval: 0 + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/LaserScan + Color: 239; 41; 41 + Color Transformer: FlatColor + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Min Color: 0; 0; 0 + Name: LaserScan + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 5 + Size (m): 0.20000000298023224 + Style: Points + Topic: scan + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/PointCloud2 + Color: 255; 0; 0 + Color Transformer: FlatColor + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Min Color: 0; 0; 0 + Name: Bumper Hit + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.07999999821186066 + Style: Spheres + Topic: mobile_base/sensors/bumper_pointcloud + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true + - Class: rviz/Group + Displays: + - Alpha: 0.699999988079071 + Class: rviz/Map + Color Scheme: costmap + Draw Behind: true + Enabled: true + Name: Costmap + Topic: /move_base_node/global_costmap/costmap + Unreliable: false + Use Timestamp: false + Value: true + - Alpha: 1 + Buffer Length: 1 + Class: rviz/Path + Color: 252; 175; 62 + Enabled: false + Head Diameter: 0.30000001192092896 + Head Length: 0.20000000298023224 + Length: 0.30000001192092896 + Line Style: Billboards + Line Width: 0.029999999329447746 + Name: Global Plan (DWB) + Offset: + X: 0 + Y: 0 + Z: 0 + Pose Color: 255; 85; 255 + Pose Style: None + Queue Size: 10 + Radius: 0.029999999329447746 + Shaft Diameter: 0.10000000149011612 + Shaft Length: 0.10000000149011612 + Topic: /move_base_node/DWBLocalPlanner/global_plan + Unreliable: false + Value: false + - Alpha: 1 + Buffer Length: 1 + Class: rviz/Path + Color: 239; 41; 41 + Enabled: true + Head Diameter: 0.30000001192092896 + Head Length: 0.20000000298023224 + Length: 0.30000001192092896 + Line Style: Billboards + Line Width: 0.029999999329447746 + Name: Full Plan + Offset: + X: 0 + Y: 0 + Z: 0 + Pose Color: 255; 85; 255 + Pose Style: Axes + Queue Size: 10 + Radius: 0.029999999329447746 + Shaft Diameter: 0.10000000149011612 + Shaft Length: 0.10000000149011612 + Topic: /move_base_node/SBPLLatticePlanner/plan + Unreliable: true + Value: true + - Alpha: 1 + Class: rviz/Polygon + Color: 0; 12; 255 + Enabled: false + Name: Footprint + Queue Size: 10 + Topic: move_base_node/global_costmap/footprint + Unreliable: true + Value: false + - Class: rviz/Marker + Enabled: false + Marker Topic: /move_base_node/SBPLLatticePlanner/footprint_markers + Name: Marker + Namespaces: + {} + Queue Size: 100 + Value: false + Enabled: true + Name: Global Map + - Class: rviz/Group + Displays: + - Alpha: 0.699999988079071 + Class: rviz/Map + Color Scheme: costmap + Draw Behind: false + Enabled: true + Name: Costmap + Topic: move_base_node/local_costmap/costmap + Unreliable: false + Use Timestamp: false + Value: true + - Alpha: 1 + Class: rviz/GridCells + Color: 25; 255; 0 + Enabled: false + Name: Costmap (MiR) + Queue Size: 10 + Topic: move_base_node/local_costmap/obstacles + Unreliable: false + Value: false + - Alpha: 1 + Buffer Length: 1 + Class: rviz/Path + Color: 0; 12; 255 + Enabled: true + Head Diameter: 0.30000001192092896 + Head Length: 0.20000000298023224 + Length: 0.20000000298023224 + Line Style: Lines + Line Width: 0.05000000074505806 + Name: Local Plan (DWB) + Offset: + X: 0 + Y: 0 + Z: 0 + Pose Color: 255; 85; 255 + Pose Style: Axes + Queue Size: 10 + Radius: 0.019999999552965164 + Shaft Diameter: 0.10000000149011612 + Shaft Length: 0.10000000149011612 + Topic: move_base_node/DWBLocalPlanner/local_plan + Unreliable: false + Value: true + - Alpha: 1 + Buffer Length: 1 + Class: rviz/Path + Color: 255; 25; 0 + Enabled: false + Head Diameter: 0.30000001192092896 + Head Length: 0.20000000298023224 + Length: 0.30000001192092896 + Line Style: Billboards + Line Width: 0.029999999329447746 + Name: TransformedToLocalPath + Offset: + X: 0 + Y: 0 + Z: 0 + Pose Color: 255; 85; 255 + Pose Style: None + Queue Size: 10 + Radius: 0.029999999329447746 + Shaft Diameter: 0.10000000149011612 + Shaft Length: 0.10000000149011612 + Topic: /move_base_node/DWBLocalPlanner/transformed_global_plan + Unreliable: false + Value: false + - Alpha: 1 + Class: rviz/Polygon + Color: 204; 0; 0 + Enabled: true + Name: Footprint + Queue Size: 10 + Topic: move_base_node/local_costmap/footprint + Unreliable: false + Value: true + - Alpha: 0.30000001192092896 + Autocompute Intensity Bounds: false + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: total_cost + Class: rviz/PointCloud2 + Color: 255; 255; 255 + Color Transformer: Intensity + Decay Time: 0 + Enabled: false + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 40 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: Cost Cloud + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.03999999910593033 + Style: Flat Squares + Topic: move_base_node/DWBLocalPlanner/cost_cloud + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: false + - Class: rviz/MarkerArray + Enabled: true + Marker Topic: move_base_node/DWBLocalPlanner/markers + Name: DWB Markers + Namespaces: + {} + Queue Size: 100 + Value: true + Enabled: true + Name: Local Map + - Alpha: 1 + Arrow Length: 0.20000000298023224 + Axes Length: 0.30000001192092896 + Axes Radius: 0.009999999776482582 + Class: rviz/PoseArray + Color: 0; 192; 0 + Enabled: false + Head Length: 0.07000000029802322 + Head Radius: 0.029999999329447746 + Name: Amcl Particle Swarm + Queue Size: 10 + Shaft Length: 0.23000000417232513 + Shaft Radius: 0.009999999776482582 + Shape: Arrow (Flat) + Topic: particlecloud + Unreliable: false + Value: false + - Class: rviz/MarkerArray + Enabled: false + Marker Topic: /move_base_node/WaypointsSBPLPlanner/waypoints + Name: Waypoints + Namespaces: + {} + Queue Size: 100 + Value: false + - Alpha: 1 + Arrow Length: 2 + Axes Length: 0.20000000298023224 + Axes Radius: 0.019999999552965164 + Class: rviz/PoseArray + Color: 255; 25; 0 + Enabled: false + Head Length: 0.10000000149011612 + Head Radius: 0.029999999329447746 + Name: waypoints + Queue Size: 6 + Shaft Length: 0.33000001311302185 + Shaft Radius: 0.019999999552965164 + Shape: Axes + Topic: /move_base_node/DWBLocalPlanner/PathProgress/reached_intermediate_goals + Unreliable: false + Value: false + - Alpha: 1 + Axes Length: 0.30000001192092896 + Axes Radius: 0.019999999552965164 + Class: rviz/Pose + Color: 114; 159; 207 + Enabled: true + Head Length: 0.30000001192092896 + Head Radius: 0.10000000149011612 + Name: Pose_closet + Queue Size: 10 + Shaft Length: 1 + Shaft Radius: 0.05000000074505806 + Shape: Axes + Topic: /move_base_node/DWBLocalPlanner/PathProgress/closet_robot_goal + Unreliable: false + Value: true + - Alpha: 1 + Axes Length: 0.30000001192092896 + Axes Radius: 0.019999999552965164 + Class: rviz/Pose + Color: 46; 52; 54 + Enabled: true + Head Length: 0.10000000149011612 + Head Radius: 0.10000000149011612 + Name: Pose + Queue Size: 10 + Shaft Length: 1 + Shaft Radius: 0.05000000074505806 + Shape: Axes + Topic: /move_base_simple/goal + Unreliable: true + Value: true + - Alpha: 0.699999988079071 + Class: rviz/Map + Color Scheme: map + Draw Behind: false + Enabled: true + Name: Map + Topic: /map + Unreliable: false + Use Timestamp: false + Value: true + - Alpha: 0.699999988079071 + Class: rviz/Map + Color Scheme: map + Draw Behind: false + Enabled: false + Name: Directional zones + Topic: /direction_zones/map + Unreliable: false + Use Timestamp: false + Value: false + - Alpha: 0.699999988079071 + Class: rviz/Map + Color Scheme: map + Draw Behind: false + Enabled: false + Name: Forbidden zones + Topic: /virtual_walls/map + Unreliable: false + Use Timestamp: false + Value: false + - Alpha: 0.699999988079071 + Class: rviz/Map + Color Scheme: map + Draw Behind: false + Enabled: false + Name: Critical zones + Topic: /critical_zones/map + Unreliable: false + Use Timestamp: false + Value: false + - Alpha: 0.699999988079071 + Class: rviz/Map + Color Scheme: map + Draw Behind: false + Enabled: false + Name: Preferred zones + Topic: /preferred_zones/map + Unreliable: false + Use Timestamp: false + Value: false + - Alpha: 0.699999988079071 + Class: rviz/Map + Color Scheme: map + Draw Behind: false + Enabled: false + Name: Unpreferred zones + Topic: /unpreferred_zones/map + Unreliable: false + Use Timestamp: false + Value: false + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Default Light: true + Fixed Frame: map + Frame Rate: 30 + Name: root + Tools: + - Class: rviz/MoveCamera + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/Select + - Class: rviz/SetInitialPose + Theta std deviation: 0.2617993950843811 + Topic: initialpose + X std deviation: 0.5 + Y std deviation: 0.5 + - Class: rviz/SetGoal + Topic: move_base_simple/goal + - Class: rviz/Measure + - Class: rviz/PublishPoint + Single click: false + Topic: clicked_point + Value: true + Views: + Current: + Angle: -3.145003080368042 + Class: rviz/TopDownOrtho + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Scale: -52.603572845458984 + Target Frame: + X: 8.760619163513184 + Y: 10.58740234375 + Saved: + - Angle: -0.004999996162950993 + Class: rviz/TopDownOrtho + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Invert Z Axis: false + Name: TopDownOrtho + Near Clip Distance: 0.009999999776482582 + Scale: 23.103717803955078 + Target Frame: + X: 17.860042572021484 + Y: 15.485589981079102 + - Angle: -0.004999996162950993 + Class: rviz/TopDownOrtho + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Invert Z Axis: false + Name: TopDownOrtho + Near Clip Distance: 0.009999999776482582 + Scale: 23.103717803955078 + Target Frame: + X: 17.860042572021484 + Y: 15.485589981079102 + - Angle: -0.004999996162950993 + Class: rviz/TopDownOrtho + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Invert Z Axis: false + Name: TopDownOrtho + Near Clip Distance: 0.009999999776482582 + Scale: 23.103717803955078 + Target Frame: + X: 17.860042572021484 + Y: 15.485589981079102 + - Angle: -0.004999996162950993 + Class: rviz/TopDownOrtho + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Invert Z Axis: false + Name: TopDownOrtho + Near Clip Distance: 0.009999999776482582 + Scale: 23.103717803955078 + Target Frame: + X: 17.860042572021484 + Y: 15.485589981079102 + - Angle: -0.004999995231628418 + Class: rviz/TopDownOrtho + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Invert Z Axis: false + Name: TopDownOrtho + Near Clip Distance: 0.009999999776482582 + Scale: 52.42099380493164 + Target Frame: + X: 0.5443607568740845 + Y: -0.26071029901504517 + - Angle: -1.5799980163574219 + Class: rviz/TopDownOrtho + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Invert Z Axis: false + Name: TopDownOrtho + Near Clip Distance: 0.009999999776482582 + Scale: 131.970703125 + Target Frame: + X: -1.8128122091293335 + Y: -5.972503662109375 +Window Geometry: + Displays: + collapsed: false + Height: 1016 + Hide Left Dock: false + Hide Right Dock: false + QMainWindow State: 000000ff00000000fd0000000400000000000001560000039efc0200000004fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afc0000003d0000039e0000000000fffffffaffffffff0100000002fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730000000000ffffffff0000009d00fffffffb000000100044006900730070006c0061007900730300000431000000830000043800000311000000010000010f00000374fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003d00000374000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004a00000003efc0100000002fb0000000800540069006d00650000000000000004a00000041800fffffffb0000000800540069006d00650100000000000004500000000000000000000004350000039e00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 1077 + X: 0 + Y: 27 diff --git a/mir_robot/mir_navigation/scripts/plot_mprim.py b/mir_robot/mir_navigation/scripts/plot_mprim.py new file mode 100755 index 0000000..0537302 --- /dev/null +++ b/mir_robot/mir_navigation/scripts/plot_mprim.py @@ -0,0 +1,92 @@ +#!/usr/bin/env python3 +# Copyright (c) 2018-2022, Martin Günther (DFKI GmbH) and contributors +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# +# * Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in the +# documentation and/or other materials provided with the distribution. +# +# * Neither the name of the the copyright holder nor the names of its +# contributors may be used to endorse or promote products derived from +# this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE +# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +# Author: Martin Günther + +import matplotlib.pyplot as plt +import numpy as np +import sys + + +def get_value(strline, name): + if strline.find(name) < 0: + raise Exception("File format not matching the parser expectation", name) + + return strline.replace(name, "", 1) + + +def get_pose(line): + ss = line.split() + return np.array([float(ss[0]), float(ss[1]), float(ss[2])]) + + +class MPrim: + def __init__(self, f): + self.primID = int(get_value(f.readline(), "primID:")) + self.startAngle = int(get_value(f.readline(), "startangle_c:")) + self.endPose = get_pose(get_value(f.readline(), "endpose_c:")) + self.cost = float(get_value(f.readline(), "additionalactioncostmult:")) + self.nrPoses = int(get_value(f.readline(), "intermediateposes:")) + poses = [] + for _ in range(self.nrPoses): + poses.append(f.readline()) + self.poses = np.loadtxt(poses, delimiter=" ") + self.cmap = plt.get_cmap("nipy_spectral") + + def plot(self, nr_angles): + plt.plot(self.poses[:, 0], self.poses[:, 1], c=self.cmap(float(self.startAngle) / nr_angles)) + + +class MPrims: + def __init__(self, filename): + f = open(filename, "r") + + self.resolution = float(get_value(f.readline(), "resolution_m:")) + self.nrAngles = int(get_value(f.readline(), "numberofangles:")) + self.nrPrims = int(get_value(f.readline(), "totalnumberofprimitives:")) + + self.prims = [] + for _ in range(self.nrPrims): + self.prims.append(MPrim(f)) + + f.close() + + def plot(self): + fig = plt.figure() + ax = fig.add_subplot(111) + ax.set_xticks(np.arange(-1, 1, self.resolution)) + ax.set_yticks(np.arange(-1, 1, self.resolution)) + for prim in self.prims: + prim.plot(self.nrAngles) + plt.grid() + plt.show() + + +prims = MPrims(sys.argv[1]) +prims.plot() diff --git a/mir_robot/mir_robot/CHANGELOG.rst b/mir_robot/mir_robot/CHANGELOG.rst new file mode 100755 index 0000000..0795532 --- /dev/null +++ b/mir_robot/mir_robot/CHANGELOG.rst @@ -0,0 +1,61 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package mir_robot +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +1.1.7 (2023-01-20) +------------------ + +1.1.6 (2022-06-02) +------------------ +* Rename mir_100 -> mir + This is in preparation of mir_250 support. +* Contributors: Martin Günther + +1.1.5 (2022-02-11) +------------------ + +1.1.4 (2021-12-10) +------------------ + +1.1.3 (2021-06-11) +------------------ + +1.1.2 (2021-05-12) +------------------ + +1.1.1 (2021-02-11) +------------------ +* Contributors: Martin Günther + +1.1.0 (2020-06-30) +------------------ +* Initial release into noetic +* Contributors: Martin Günther + +1.0.6 (2020-06-30) +------------------ +* Set cmake_policy CMP0048 to fix warning +* Add sdc21x0 dependency to mir_robot meta package +* Contributors: Martin Günther + +1.0.5 (2020-05-01) +------------------ + +1.0.4 (2019-05-06) +------------------ + +1.0.3 (2019-03-04) +------------------ +* Add package: mir_dwb_critics +* Contributors: Martin Günther + +1.0.2 (2018-07-30) +------------------ +* Add metapackage +* Contributors: Martin Günther + +1.0.1 (2018-07-17) +------------------ + +1.0.0 (2018-07-12) +------------------ diff --git a/mir_robot/mir_robot/CMakeLists.txt b/mir_robot/mir_robot/CMakeLists.txt new file mode 100755 index 0000000..559abf9 --- /dev/null +++ b/mir_robot/mir_robot/CMakeLists.txt @@ -0,0 +1,4 @@ +cmake_minimum_required(VERSION 3.5.1) +project(mir_robot) +find_package(catkin REQUIRED) +catkin_metapackage() diff --git a/mir_robot/mir_robot/package.xml b/mir_robot/mir_robot/package.xml new file mode 100755 index 0000000..2d0d5cd --- /dev/null +++ b/mir_robot/mir_robot/package.xml @@ -0,0 +1,32 @@ + + + mir_robot + 1.1.7 + + URDF description, Gazebo simulation, navigation, bringup launch files, message and action descriptions for the MiR robot. + + + Martin Günther + Martin Günther + + BSD + + https://github.com/DFKI-NI/mir_robot + https://github.com/DFKI-NI/mir_robot + https://github.com/DFKI-NI/mir_robot/issues + + catkin + + mir_actions + mir_description + mir_driver + mir_dwb_critics + mir_gazebo + mir_msgs + mir_navigation + sdc21x0 + + + + + diff --git a/mir_robot/pyproject.toml b/mir_robot/pyproject.toml new file mode 100755 index 0000000..d374d61 --- /dev/null +++ b/mir_robot/pyproject.toml @@ -0,0 +1,4 @@ +[tool.black] +line-length = 120 +target-version = ['py38'] +skip-string-normalization = true diff --git a/mir_robot/sdc21x0/CHANGELOG.rst b/mir_robot/sdc21x0/CHANGELOG.rst new file mode 100755 index 0000000..99c80fd --- /dev/null +++ b/mir_robot/sdc21x0/CHANGELOG.rst @@ -0,0 +1,60 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package sdc21x0 +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +1.1.7 (2023-01-20) +------------------ +* Don't set cmake_policy CMP0048 +* Contributors: Martin Günther + +1.1.6 (2022-06-02) +------------------ + +1.1.5 (2022-02-11) +------------------ + +1.1.4 (2021-12-10) +------------------ + +1.1.3 (2021-06-11) +------------------ + +1.1.2 (2021-05-12) +------------------ + +1.1.1 (2021-02-11) +------------------ +* Contributors: Martin Günther + +1.1.0 (2020-06-30) +------------------ +* Initial release into noetic +* Contributors: Martin Günther + +1.0.6 (2020-06-30) +------------------ +* Set cmake_policy CMP0048 to fix warning +* Contributors: Martin Günther + +1.0.5 (2020-05-01) +------------------ +* Add sdc21x0 package, MC/currents topic +* Contributors: Martin Günther + +* Add sdc21x0 package, MC/currents topic +* Contributors: Martin Günther + +1.0.4 (2019-05-06) +------------------ + +1.0.3 (2019-03-04) +------------------ + +1.0.2 (2018-07-30) +------------------ + +1.0.1 (2018-07-17) +------------------ + +1.0.0 (2018-07-12) +------------------ diff --git a/mir_robot/sdc21x0/CMakeLists.txt b/mir_robot/sdc21x0/CMakeLists.txt new file mode 100755 index 0000000..7b5353c --- /dev/null +++ b/mir_robot/sdc21x0/CMakeLists.txt @@ -0,0 +1,40 @@ +cmake_minimum_required(VERSION 3.5.1) +project(sdc21x0) + +find_package(catkin REQUIRED COMPONENTS + message_generation + std_msgs +) + +################################################ +## Declare ROS messages, services and actions ## +################################################ + +# Generate messages in the 'msg' folder +add_message_files( + FILES + Encoders.msg + MotorCurrents.msg + StampedEncoders.msg +) + +# Generate services in the 'srv' folder +add_service_files( + FILES + Flags.srv +) + +# Generate added messages and services with any dependencies listed here +generate_messages( + DEPENDENCIES + std_msgs +) + +################################### +## catkin specific configuration ## +################################### +catkin_package( + CATKIN_DEPENDS + message_runtime + std_msgs +) diff --git a/mir_robot/sdc21x0/msg/Encoders.msg b/mir_robot/sdc21x0/msg/Encoders.msg new file mode 100755 index 0000000..9fff122 --- /dev/null +++ b/mir_robot/sdc21x0/msg/Encoders.msg @@ -0,0 +1,3 @@ +float32 time_delta # Time since last encoder update. +int32 left_wheel # Encoder counts (absolute or relative) +int32 right_wheel # Encoder counts (absolute or relative) diff --git a/mir_robot/sdc21x0/msg/MotorCurrents.msg b/mir_robot/sdc21x0/msg/MotorCurrents.msg new file mode 100755 index 0000000..233a16b --- /dev/null +++ b/mir_robot/sdc21x0/msg/MotorCurrents.msg @@ -0,0 +1,2 @@ +float32 left_motor +float32 right_motor diff --git a/mir_robot/sdc21x0/msg/StampedEncoders.msg b/mir_robot/sdc21x0/msg/StampedEncoders.msg new file mode 100755 index 0000000..ff8193c --- /dev/null +++ b/mir_robot/sdc21x0/msg/StampedEncoders.msg @@ -0,0 +1,2 @@ +Header header +Encoders encoders diff --git a/mir_robot/sdc21x0/package.xml b/mir_robot/sdc21x0/package.xml new file mode 100755 index 0000000..632ab86 --- /dev/null +++ b/mir_robot/sdc21x0/package.xml @@ -0,0 +1,22 @@ + + + sdc21x0 + 1.1.7 + Message definitions for the sdc21x0 motor controller + + Martin Günther + Martin Günther + + BSD + + https://github.com/DFKI-NI/mir_robot + https://github.com/DFKI-NI/mir_robot + https://github.com/DFKI-NI/mir_robot/issues + + catkin + + std_msgs + + message_generation + message_runtime + diff --git a/mir_robot/sdc21x0/srv/Flags.srv b/mir_robot/sdc21x0/srv/Flags.srv new file mode 100755 index 0000000..576a737 --- /dev/null +++ b/mir_robot/sdc21x0/srv/Flags.srv @@ -0,0 +1,3 @@ +int32 digitalPort +--- +bool response diff --git a/move_base.png b/move_base.png new file mode 100755 index 0000000..75ad018 Binary files /dev/null and b/move_base.png differ diff --git a/navigations/.vscode/settings.json b/navigations/.vscode/settings.json new file mode 100755 index 0000000..87e1fc2 --- /dev/null +++ b/navigations/.vscode/settings.json @@ -0,0 +1,20 @@ +{ + "files.associations": { + "iterator": "cpp", + "cmath": "cpp", + "complex": "cpp", + "*.ipp": "cpp", + "array": "cpp", + "string_view": "cpp", + "unordered_map": "cpp", + "unordered_set": "cpp", + "random": "cpp", + "typeindex": "cpp", + "typeinfo": "cpp", + "functional": "cpp", + "bitset": "cpp", + "initializer_list": "cpp", + "utility": "cpp", + "list": "cpp" + } +} \ No newline at end of file diff --git a/navigations/amcl/CHANGELOG.rst b/navigations/amcl/CHANGELOG.rst new file mode 100755 index 0000000..2faef83 --- /dev/null +++ b/navigations/amcl/CHANGELOG.rst @@ -0,0 +1,258 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package amcl +^^^^^^^^^^^^^^^^^^^^^^^^^^ + +1.17.3 (2023-01-10) +------------------- +* [AMCL] Add option to force nomotion update after initialpose (`#1226 `_) + * Adds a new boolean parameter force_update_after_initialpose. When set to true, an update is forced on the next laser scan callback, such as when the /request_nomotion_update service is called. This often results in an improved robot pose after a manual (not very precise) re-localization - without a need for the robot to move. + * Fixes a bunch of compiler warnings (unused variable now, catching exceptions by value), normalizes how tf exceptions are caught +* [ROS-O] various patches (`#1225 `_) + * do not specify obsolete c++11 standard + this breaks with current versions of log4cxx. + * update pluginlib include paths + the non-hpp headers have been deprecated since kinetic + * use lambdas in favor of boost::bind + Using boost's _1 as a global system is deprecated since C++11. + The ROS packages in Debian removed the implicit support for the global symbols, + so this code fails to compile there without the patch. +* Contributors: Michael Görner, Stephan + +1.17.2 (2022-06-20) +------------------- +* Update pf.c (`#1161 `_) + `#1160 `_ AMCL miscalculates orientation covariance for clusters +* Improved Overall readablity (`#1177 `_) +* fix crashes in AMCL (`#1152 `_) + * fix: catch runtime_error from roscore + * ignore malformed message from laser, otherwise it will crash +* Fixes `#1117 `_ (`#1118 `_) +* Fixed the risk of divide by zero. (`#1099 `_) +* (AMCL) add missing test dep on tf2_py (`#1091 `_) +* (AMCL)(Noetic) use robot pose in tests (`#1087 `_) +* (amcl) fix missing '#if NEW_UNIFORM_SAMPLING' (`#1079 `_) +* Contributors: David V. Lu!!, Matthijs van der Burgh, Noriaki Ando, Supernovae, christofschroeter, easylyou + +1.17.1 (2020-08-27) +------------------- +* (AMCL) add resample limit cache [Noetic] (`#1014 `_) +* Contributors: Matthijs van der Burgh + +1.17.0 (2020-04-02) +------------------- +* Merge pull request `#982 `_ from ros-planning/noetic_prep + Noetic Migration +* map is not subscriptable in python3 +* fix python3 errors in basic_localization.py +* use upstream pykdl +* Contributors: Michael Ferguson + +1.16.6 (2020-03-18) +------------------- + +1.16.5 (2020-03-15) +------------------- +* [melodic] updated install for better portability. (`#973 `_) +* Contributors: Sean Yen + +1.16.4 (2020-03-04) +------------------- +* Implement selective resampling (`#921 `_) (`#971 `_) + Co-authored-by: Adi Vardi +* Add CLI option to trigger global localization before processing a bagfile (`#816 `_) (`#970 `_) + Co-authored-by: alain-m +* Fix some reconfigure parameters not being applied [amcl]. (`#952 `_) +* amcl: include missing CMake functions to fix build (`#946 `_) +* Set proper limits for the z-weights [amcl]. (`#953 `_) +* Merge pull request `#965 `_ from nlimpert/nlimpert/fix_missing_cmake_include + Add missing CMake include(CheckSymbolExists) for CMake >= 3.15 +* amcl: add missing CMake include(CheckSymbolExists) + Starting with CMake 3.15 an explicit include(CheckSymbolExists) + is required to use the check_symbol_exists macro. +* Contributors: Ben Wolsieffer, Michael Ferguson, Nicolas Limpert, Patrick Chin + +1.16.3 (2019-11-15) +------------------- +* Merge branch 'melodic-devel' into layer_clear_area-melodic +* Fix typo in amcl_laser model header (`#918 `_) +* Merge pull request `#849 `_ from seanyen/amcl_windows_fix + [Windows][melodic] AMCL Windows build bring up. +* revert unrelated changes. +* AMCL windows build bring up. + * Add HAVE_UNISTD and HAVE_DRAND48 and portable_utils.hpp for better cross compiling. + * Variable length array is not supported in MSVC, conditionally disable it. + * Fix install location for shared lib and executables on Windows. + * Use isfinite for better cross compiling. +* feat: AMCL Diagnostics (`#807 `_) + Diagnostic task that monitors the estimated standard deviation of the filter. + By: reinzor +* fix typo for parameter beam_skip_error_threshold but bandaged for other users in AMCL (`#790 `_) + * fix typo but bandage for other users +* Merge pull request `#785 `_ from mintar/amcl_c++11 + amcl: Add compile option C++11 +* amcl: Set C++ standard 11 if not set + This is required to build the melodic-devel branch of the navigation + stack on kinetic. Melodic sets CMAKE_CXX_STANDARD=14, but kinetic + doesn't set that variable at all. +* Contributors: Hadi Tabatabaee, Martin Günther, Michael Ferguson, Rein Appeldoorn, Sean Yen, Steven Macenski + +1.16.2 (2018-07-31) +------------------- +* Merge pull request `#773 `_ from ros-planning/packaging_fixes + packaging fixes +* update amcl to have proper depends + * add geometry_msgs + * add tf2_msgs + * fix alphabetical order +* Contributors: Michael Ferguson + +1.16.1 (2018-07-28) +------------------- +* Merge pull request `#770 `_ from ros-planning/fix_debians + Fix debian builds (closes `#769 `_) +* make AMCL depend on sensor_msgs + previously, amcl depended on TF, which depended on + sensor_msgs. +* Contributors: Michael Ferguson + +1.16.0 (2018-07-25) +------------------- +* Switch to TF2 `#755 `_ +* Merge pull request `#734 `_ from ros-planning/melodic_731 + AMCL dynamic reconfigure: Extend parameter range (Forward port `#731 `_) +* Merge pull request `#728 `_ from ros-planning/melodic_tf2_conversion + switch AMCL to use TF2 +* fix swapped odom1/4 in omni model, fixes `#499 `_ +* Merge pull request `#730 `_ from Glowcloud/melodic-devel + Fix for Potential Memory Leak in AmclNode::reconfigureCB `#729 `_ +* Fix for Potential Memory Leak in AmclNode::reconfigureCB +* switch AMCL to use TF2 +* Merge pull request `#727 `_ from ros-planning/melodic_668 + Update laser_model_type enum on AMCL.cfg (Melodic port of `#668 `_) +* Update laser_model_type enum on AMCL.cfg + Adding likelihood_field_prob laser model option on AMCL.cfg to be able to control dynamic parameters with this laser sensor model. +* Merge pull request `#723 `_ from moriarty/melodic-buildfarm-errors + Melodic buildfarm errors +* include for std::shared_ptr +* Merge pull request `#718 `_ from moriarty/tf2-buffer-ptr + [melodic] tf2_buffer\_ -> tf2_buffer_ptr\_ +* [melodic] tf2_buffer\_ -> tf2_buffer_ptr\_ + Change required due to changes in upstream dependencies: + `ros/geometry#163 `_: "Maintain & expose tf2 Buffer in shared_ptr for tf" + fixes `ros-planning/navigation#717 `_ (for compile errors at least.) +* Contributors: Alexander Moriarty, Glowcloud, Martin Ganeff, Michael Ferguson, Miguel Cordero, Vincent Rabaud, maracuya-robotics + +1.15.2 (2018-03-22) +------------------- +* Fix minor typo (`#682 `_) + This typo caused some confusion because we were searching for a semicolon in our configuration. +* Merge pull request `#677 `_ from ros-planning/lunar_634 + removing recomputation of cluster stats causing assertion error (`#634 `_) +* Merge pull request `#673 `_ from ros-planning/email_update_lunar + update maintainer email (lunar) +* Remove Dead Code [Lunar] (`#646 `_) + * Clean up navfn + * Cleanup amcl +* Merge pull request `#649 `_ from aaronhoy/lunar_add_ahoy + Add myself as a maintainer. +* Contributors: Aaron Hoy, David V. Lu!!, Michael Ferguson, stevemacenski + +1.15.1 (2017-08-14) +------------------- + +1.15.0 (2017-08-07) +------------------- +* Reference Issue `#592 `_ Added warning to AMCL when map is published on ... (`#604 `_) +* rebase fixups +* convert packages to format2 +* recompute cluster stat when force_publication +* Fix CMakeLists + package.xmls (`#548 `_) +* amcl: fix compilation with gcc v7 +* Added deps to amcl costmap_2d move_base (`#512 `_) +* fix order of parameters (closes `#553 `_) +* Fix potential string overflow and resource leak +* Contributors: Dmitry Rozhkov, Laurent GEORGE, Martin Günther, Michael Ferguson, Mikael Arguedas, Peter Harliman Liem, mryellow, vik748 + +1.14.0 (2016-05-20) +------------------- +* Allow AMCL to run from bag file to allow very fast testing. +* Fixes interpretation of a delayed initialpose message (see `#424 `_). + The tf lookup as it was before this change was very likely to fail as + ros::Time::now() was used to look up a tf without waiting on the tf's + availability. Additionally, the computation of the "new pose" by + multiplying the delta that the robot moved from the initialpose's + timestamp to ros::Time::now() was wrong. That delta has to by multiplied + from the right to the "old pose". + This commit also changes the reference frame to look up this delta to be + the odom frame as this one is supposed to be smooth and therefore the + best reference to get relative robot motion in the robot (base link) frame. +* New unit test for proper interpretation of a delayed initialpose message. + Modifies the set_pose.py script to be able to send an initial pose with + a user defined time stamp at a user defined time. Adds a rostest to + exercise this new option. + This reveals the issues mentioned in `#424 `_ (the new test fails). +* Contributors: Derek King, Stephan Wirth + +1.13.1 (2015-10-29) +------------------- +* adds the set_map service to amcl +* fix pthread_mutex_lock on shutdown +* Contributors: Michael Ferguson, Stephan Wirth + +1.13.0 (2015-03-17) +------------------- +* amcl_node will now save latest pose on shutdown +* Contributors: Ian Danforth + +1.12.0 (2015-02-04) +------------------- +* update maintainer email +* Contributors: Michael Ferguson + +1.11.15 (2015-02-03) +-------------------- + +1.11.14 (2014-12-05) +-------------------- + +1.11.13 (2014-10-02) +-------------------- + +1.11.12 (2014-10-01) +-------------------- +* Bug fix to remove particle weights being reset when motion model is updated +* Integrated new sensor model which calculates the observation likelihood in a probabilistic manner + Also includes the option to do beam-skipping (to better handle observations from dynamic obstacles) +* Pose pulled from parameter server when new map received +* Contributors: Steven Kordell, hes3pal + +1.11.11 (2014-07-23) +-------------------- + +1.11.10 (2014-06-25) +-------------------- + +1.11.9 (2014-06-10) +------------------- + +1.11.8 (2014-05-21) +------------------- + +1.11.7 (2014-05-21) +------------------- +* removes useless this->z_max = z_max assignment +* Fix warning string. +* Contributors: Jeremiah Via, enriquefernandez + +1.11.5 (2014-01-30) +------------------- +* Fix for `#160 `_ +* Download test data from download.ros.org instead of willow +* Change maintainer from Hersh to Lu + +1.11.4 (2013-09-27) +------------------- +* Package URL Updates +* amcl_pose and particle cloud are now published latched +* Fixed or commented out failing amcl tests. + diff --git a/navigations/amcl/CMakeLists.txt b/navigations/amcl/CMakeLists.txt new file mode 100755 index 0000000..6307119 --- /dev/null +++ b/navigations/amcl/CMakeLists.txt @@ -0,0 +1,168 @@ +cmake_minimum_required(VERSION 3.1) +project(amcl) + +include(CheckIncludeFile) +include(CheckSymbolExists) + +find_package(catkin REQUIRED + COMPONENTS + diagnostic_updater + dynamic_reconfigure + geometry_msgs + message_filters + nav_msgs + rosbag + roscpp + sensor_msgs + std_srvs + tf2 + tf2_geometry_msgs + tf2_msgs + tf2_ros +) + +find_package(Boost REQUIRED) + +# dynamic reconfigure +generate_dynamic_reconfigure_options( + cfg/AMCL.cfg +) + +catkin_package( + CATKIN_DEPENDS + diagnostic_updater + dynamic_reconfigure + geometry_msgs + nav_msgs + rosbag + roscpp + sensor_msgs + std_srvs + tf2 + tf2_msgs + tf2_ros + INCLUDE_DIRS include + LIBRARIES amcl_sensors amcl_map amcl_pf +) + +include_directories(include) +include_directories(${catkin_INCLUDE_DIRS} ${Boost_INCLUDE_DIRS}) +include_directories(src/include) + +check_include_file(unistd.h HAVE_UNISTD_H) +if (HAVE_UNISTD_H) + add_definitions(-DHAVE_UNISTD_H) +endif (HAVE_UNISTD_H) + +check_symbol_exists(drand48 stdlib.h HAVE_DRAND48) +if (HAVE_DRAND48) + add_definitions(-DHAVE_DRAND48) +endif (HAVE_DRAND48) + +add_library(amcl_pf + src/amcl/pf/pf.c + src/amcl/pf/pf_kdtree.c + src/amcl/pf/pf_pdf.c + src/amcl/pf/pf_vector.c + src/amcl/pf/eig3.c + src/amcl/pf/pf_draw.c) + +add_library(amcl_map + src/amcl/map/map.c + src/amcl/map/map_cspace.cpp + src/amcl/map/map_range.c + src/amcl/map/map_store.c + src/amcl/map/map_draw.c) + +add_library(amcl_sensors + src/amcl/sensors/amcl_sensor.cpp + src/amcl/sensors/amcl_odom.cpp + src/amcl/sensors/amcl_laser.cpp) +target_link_libraries(amcl_sensors amcl_map amcl_pf) + + +add_executable(amcl + src/amcl_node.cpp) +add_dependencies(amcl ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) + +target_link_libraries(amcl + amcl_sensors amcl_map amcl_pf + ${Boost_LIBRARIES} + ${catkin_LIBRARIES} +) + +install(TARGETS + amcl + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) + +install(TARGETS + amcl_sensors amcl_map amcl_pf + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} +) + +install(DIRECTORY include/amcl/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} +) + +install(DIRECTORY examples/ + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/examples +) + +## Configure Tests +if(CATKIN_ENABLE_TESTING) + find_package(rostest REQUIRED) + + # Bags + catkin_download_test_data(${PROJECT_NAME}_basic_localization_stage_indexed.bag + http://download.ros.org/data/amcl/basic_localization_stage_indexed.bag + DESTINATION ${CATKIN_DEVEL_PREFIX}/${CATKIN_PACKAGE_SHARE_DESTINATION}/test + MD5 41fe43af189ec71e5e48eb9ed661a655) + catkin_download_test_data(${PROJECT_NAME}_global_localization_stage_indexed.bag + http://download.ros.org/data/amcl/global_localization_stage_indexed.bag + DESTINATION ${CATKIN_DEVEL_PREFIX}/${CATKIN_PACKAGE_SHARE_DESTINATION}/test + MD5 752f711cf4f6e8d1d660675e2da096b0) + catkin_download_test_data(${PROJECT_NAME}_small_loop_prf_indexed.bag + http://download.ros.org/data/amcl/small_loop_prf_indexed.bag + DESTINATION ${CATKIN_DEVEL_PREFIX}/${CATKIN_PACKAGE_SHARE_DESTINATION}/test + MD5 e4ef0fc006872b43f12ed8a7ce7dcd81) + catkin_download_test_data(${PROJECT_NAME}_small_loop_crazy_driving_prg_indexed.bag + http://download.ros.org/data/amcl/small_loop_crazy_driving_prg_indexed.bag + DESTINATION ${CATKIN_DEVEL_PREFIX}/${CATKIN_PACKAGE_SHARE_DESTINATION}/test + MD5 4a58d1a7962914009d99000d06e5939c) + catkin_download_test_data(${PROJECT_NAME}_texas_greenroom_loop_indexed.bag + http://download.ros.org/data/amcl/texas_greenroom_loop_indexed.bag + DESTINATION ${CATKIN_DEVEL_PREFIX}/${CATKIN_PACKAGE_SHARE_DESTINATION}/test + MD5 6e3432115cccdca1247f6c807038e13d) + catkin_download_test_data(${PROJECT_NAME}_texas_willow_hallway_loop_indexed.bag + http://download.ros.org/data/amcl/texas_willow_hallway_loop_indexed.bag + DESTINATION ${CATKIN_DEVEL_PREFIX}/${CATKIN_PACKAGE_SHARE_DESTINATION}/test + MD5 27deb742fdcd3af44cf446f39f2688a8) + catkin_download_test_data(${PROJECT_NAME}_rosie_localization_stage.bag + http://download.ros.org/data/amcl/rosie_localization_stage.bag + DESTINATION ${CATKIN_DEVEL_PREFIX}/${CATKIN_PACKAGE_SHARE_DESTINATION}/test + MD5 3347bf3835724cfa45e958c5c1846066) + + # Maps + catkin_download_test_data(${PROJECT_NAME}_willow-full.pgm + http://download.ros.org/data/amcl/willow-full.pgm + DESTINATION ${CATKIN_DEVEL_PREFIX}/${CATKIN_PACKAGE_SHARE_DESTINATION}/test + MD5 b84465cdbbfe3e2fb9eb4579e0bcaf0e) + catkin_download_test_data(${PROJECT_NAME}_willow-full-0.05.pgm + http://download.ros.org/data/amcl/willow-full-0.05.pgm + DESTINATION ${CATKIN_DEVEL_PREFIX}/${CATKIN_PACKAGE_SHARE_DESTINATION}/test + MD5 b61694296e08965096c5e78611fd9765) + + # Tests + add_rostest(test/set_initial_pose.xml) + add_rostest(test/set_initial_pose_delayed.xml) + add_rostest(test/basic_localization_stage.xml) + add_rostest(test/global_localization_stage.xml) + add_rostest(test/small_loop_prf.xml) + add_rostest(test/small_loop_crazy_driving_prg.xml) + add_rostest(test/texas_greenroom_loop.xml) + add_rostest(test/rosie_multilaser.xml) + add_rostest(test/texas_willow_hallway_loop.xml) +endif() diff --git a/navigations/amcl/cfg/AMCL.cfg b/navigations/amcl/cfg/AMCL.cfg new file mode 100755 index 0000000..4695df7 --- /dev/null +++ b/navigations/amcl/cfg/AMCL.cfg @@ -0,0 +1,77 @@ +#!/usr/bin/env python + +PACKAGE = 'amcl' + +from math import pi +from dynamic_reconfigure.parameter_generator_catkin import ParameterGenerator, int_t, double_t, str_t, bool_t + +gen = ParameterGenerator() + +gen.add("min_particles", int_t, 0, "Minimum allowed number of particles.", 100, 0, 1000) +gen.add("max_particles", int_t, 0, "Mamimum allowed number of particles.", 5000, 0, 10000) + +gen.add("kld_err", double_t, 0, "Maximum error between the true distribution and the estimated distribution.", .01, 0, 1) +gen.add("kld_z", double_t, 0, "Upper standard normal quantile for (1 - p), where p is the probability that the error on the estimated distribution will be less than kld_err.", .99, 0, 1) + +gen.add("update_min_d", double_t, 0, "Translational movement required before performing a filter update.", .2, 0, 5) +gen.add("update_min_a", double_t, 0, "Rotational movement required before performing a filter update.", pi/6, 0, 2*pi) + +gen.add("resample_interval", int_t, 0, "Number of filter updates required before resampling.", 2, 0, 20) + +gen.add("transform_tolerance", double_t, 0, "Time with which to post-date the transform that is published, to indicate that this transform is valid into the future.", .1, 0, 2) + +gen.add("recovery_alpha_slow", double_t, 0, "Exponential decay rate for the slow average weight filter, used in deciding when to recover by adding random poses. A good value might be 0.001.", 0, 0, .5) +gen.add("recovery_alpha_fast", double_t, 0, "Exponential decay rate for the fast average weight filter, used in deciding when to recover by adding random poses. A good value might be 0.1.", 0, 0, 1) + +gen.add("do_beamskip", bool_t, 0, "When true skips laser scans when a scan doesnt work for a majority of particles", False) +gen.add("beam_skip_distance", double_t, 0, "Distance from a valid map point before scan is considered invalid", 0.5, 0, 2) +gen.add("beam_skip_threshold", double_t, 0, "Ratio of samples for which the scans are valid to consider as valid scan", 0.3, 0, 1) + +gen.add("tf_broadcast", bool_t, 0, "When true (the default), publish results via TF. When false, do not.", True) +gen.add("force_update_after_initialpose", bool_t, 0, "When true, force a pose update after a new /initialpose is received.", False) +gen.add("force_update_after_set_map", bool_t, 0, "When true, force a pose update after a new map (and pose) has been set via the /set_map service.", False) +gen.add("gui_publish_rate", double_t, 0, "Maximum rate (Hz) at which scans and paths are published for visualization, -1.0 to disable.", -1, -1, 100) +gen.add("save_pose_rate", double_t, 0, "Maximum rate (Hz) at which to store the last estimated pose and covariance to the parameter server, in the variables ~initial_pose_* and ~initial_cov_*. This saved pose will be used on subsequent runs to initialize the filter. -1.0 to disable.", .5, -1, 10) + +gen.add("use_map_topic", bool_t, 0, "When set to true, AMCL will subscribe to the map topic rather than making a service call to receive its map.", False) +gen.add("first_map_only", bool_t, 0, "When set to true, AMCL will only use the first map it subscribes to, rather than updating each time a new one is received.", False) + +# Laser Model Parameters +gen.add("laser_min_range", double_t, 0, "Minimum scan range to be considered; -1.0 will cause the laser's reported minimum range to be used.", -1, -1, 1000) +gen.add("laser_max_range", double_t, 0, "Maximum scan range to be considered; -1.0 will cause the laser's reported maximum range to be used.", -1, -1, 1000) + +gen.add("laser_max_beams", int_t, 0, "How many evenly-spaced beams in each scan to be used when updating the filter.", 30, 0, 250) + +gen.add("laser_z_hit", double_t, 0, "Mixture weight for the z_hit part of the model.", .95, 0, 1) +gen.add("laser_z_short", double_t, 0, "Mixture weight for the z_short part of the model.", .1, 0, 1) +gen.add("laser_z_max", double_t, 0, "Mixture weight for the z_max part of the model.", .05, 0, 1) +gen.add("laser_z_rand", double_t, 0, "Mixture weight for the z_rand part of the model.", .05, 0, 1) + +gen.add("laser_sigma_hit", double_t, 0, "Standard deviation for Gaussian model used in z_hit part of the model.", .2, 0, 10) +gen.add("laser_lambda_short", double_t, 0, "Exponential decay parameter for z_short part of model.", .1, 0, 10) +gen.add("laser_likelihood_max_dist", double_t, 0, "Maximum distance to do obstacle inflation on map, for use in likelihood_field model.", 2, 0, 20) + +lmt = gen.enum([gen.const("beam_const", str_t, "beam", "Use beam laser model"), gen.const("likelihood_field_const", str_t, "likelihood_field", "Use likelihood_field laser model"), gen.const("likelihood_field_prob", str_t, "likelihood_field_prob", "Use likelihood_field_prob laser model")], "Laser Models") +gen.add("laser_model_type", str_t, 0, "Which model to use, either beam, likelihood_field or likelihood_field_prob.", "likelihood_field", edit_method=lmt) + +# Odometry Model Parameters +odt = gen.enum([gen.const("diff_const", str_t, "diff", "Use diff odom model"), + gen.const("omni_const", str_t, "omni", "Use omni odom model"), + gen.const("diff_corrected_const", str_t, "diff-corrected", "Use corrected diff odom model"), + gen.const("omni_corrected_const", str_t, "omni-corrected", "Use corrected omni odom model")], + "Odom Models") +gen.add("odom_model_type", str_t, 0, "Which model to use, diff, omni, diff-corrected, or omni-corrected", "diff", edit_method=odt) + +gen.add("odom_alpha1", double_t, 0, "Specifies the expected noise in odometry's rotation estimate from the rotational component of the robot's motion.", .2, 0, 10) +gen.add("odom_alpha2", double_t, 0, "Specifies the expected noise in odometry's rotation estimate from the translational component of the robot's motion.", .2, 0, 10) +gen.add("odom_alpha3", double_t, 0, "Specifies the expected noise in odometry's translation estimate from the translational component of the robot's motion.", .2, 0, 10) +gen.add("odom_alpha4", double_t, 0, "Specifies the expected noise in odometry's translation estimate from the rotational component of the robot's motion.", .2, 0, 10) +gen.add("odom_alpha5", double_t, 0, "Translation-related noise parameter (only used if model is omni).", .2, 0, 10) + +gen.add("odom_frame_id", str_t, 0, "Which frame to use for odometry.", "odom") +gen.add("base_frame_id", str_t, 0, "Which frame to use for the robot base.", "base_link") +gen.add("global_frame_id", str_t, 0, "The name of the coordinate frame published by the localization system.", "map") + +gen.add("restore_defaults", bool_t, 0, "Retsore the default configuration", False) + +exit(gen.generate(PACKAGE, "amcl_node", "AMCL")) diff --git a/navigations/amcl/examples/amcl_diff.launch b/navigations/amcl/examples/amcl_diff.launch new file mode 100755 index 0000000..6e23ebd --- /dev/null +++ b/navigations/amcl/examples/amcl_diff.launch @@ -0,0 +1,34 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/navigations/amcl/examples/amcl_omni.launch b/navigations/amcl/examples/amcl_omni.launch new file mode 100755 index 0000000..a9137b2 --- /dev/null +++ b/navigations/amcl/examples/amcl_omni.launch @@ -0,0 +1,34 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/navigations/amcl/include/amcl/map/map.h b/navigations/amcl/include/amcl/map/map.h new file mode 100755 index 0000000..17aabf9 --- /dev/null +++ b/navigations/amcl/include/amcl/map/map.h @@ -0,0 +1,150 @@ +/* + * Player - One Hell of a Robot Server + * Copyright (C) 2000 Brian Gerkey & Kasper Stoy + * gerkey@usc.edu kaspers@robotics.usc.edu + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + * + */ +/************************************************************************** + * Desc: Global map (grid-based) + * Author: Andrew Howard + * Date: 6 Feb 2003 + * CVS: $Id: map.h 1713 2003-08-23 04:03:43Z inspectorg $ + **************************************************************************/ + +#ifndef MAP_H +#define MAP_H + +#include + +#ifdef __cplusplus +extern "C" { +#endif + +// Forward declarations +struct _rtk_fig_t; + + +// Limits +#define MAP_WIFI_MAX_LEVELS 8 + + +// Description for a single map cell. +typedef struct +{ + // Occupancy state (-1 = free, 0 = unknown, +1 = occ) + int occ_state; + + // Distance to the nearest occupied cell + double occ_dist; + + // Wifi levels + //int wifi_levels[MAP_WIFI_MAX_LEVELS]; + +} map_cell_t; + + +// Description for a map +typedef struct +{ + // Map origin; the map is a viewport onto a conceptual larger map. + double origin_x, origin_y; + + // Map scale (m/cell) + double scale; + + // Map dimensions (number of cells) + int size_x, size_y; + + // The map data, stored as a grid + map_cell_t *cells; + + // Max distance at which we care about obstacles, for constructing + // likelihood field + double max_occ_dist; + +} map_t; + + + +/************************************************************************** + * Basic map functions + **************************************************************************/ + +// Create a new (empty) map +map_t *map_alloc(void); + +// Destroy a map +void map_free(map_t *map); + +// Get the cell at the given point +map_cell_t *map_get_cell(map_t *map, double ox, double oy, double oa); + +// Load an occupancy map +int map_load_occ(map_t *map, const char *filename, double scale, int negate); + +// Load a wifi signal strength map +//int map_load_wifi(map_t *map, const char *filename, int index); + +// Update the cspace distances +void map_update_cspace(map_t *map, double max_occ_dist); + + +/************************************************************************** + * Range functions + **************************************************************************/ + +// Extract a single range reading from the map +double map_calc_range(map_t *map, double ox, double oy, double oa, double max_range); + + +/************************************************************************** + * GUI/diagnostic functions + **************************************************************************/ + +// Draw the occupancy grid +void map_draw_occ(map_t *map, struct _rtk_fig_t *fig); + +// Draw the cspace map +void map_draw_cspace(map_t *map, struct _rtk_fig_t *fig); + +// Draw a wifi map +void map_draw_wifi(map_t *map, struct _rtk_fig_t *fig, int index); + + +/************************************************************************** + * Map manipulation macros + **************************************************************************/ + +// Convert from map index to world coords +#define MAP_WXGX(map, i) (map->origin_x + ((i) - map->size_x / 2) * map->scale) +#define MAP_WYGY(map, j) (map->origin_y + ((j) - map->size_y / 2) * map->scale) + +// Convert from world coords to map coords +#define MAP_GXWX(map, x) (floor((x - map->origin_x) / map->scale + 0.5) + map->size_x / 2) +#define MAP_GYWY(map, y) (floor((y - map->origin_y) / map->scale + 0.5) + map->size_y / 2) + +// Test to see if the given map coords lie within the absolute map bounds. +#define MAP_VALID(map, i, j) ((i >= 0) && (i < map->size_x) && (j >= 0) && (j < map->size_y)) + +// Compute the cell index for the given map coords. +#define MAP_INDEX(map, i, j) ((i) + (j) * map->size_x) + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/navigations/amcl/include/amcl/pf/eig3.h b/navigations/amcl/include/amcl/pf/eig3.h new file mode 100755 index 0000000..b708cb1 --- /dev/null +++ b/navigations/amcl/include/amcl/pf/eig3.h @@ -0,0 +1,11 @@ + +/* Eigen-decomposition for symmetric 3x3 real matrices. + Public domain, copied from the public domain Java library JAMA. */ + +#ifndef _eig_h + +/* Symmetric matrix A => eigenvectors in columns of V, corresponding + eigenvalues in d. */ +void eigen_decomposition(double A[3][3], double V[3][3], double d[3]); + +#endif diff --git a/navigations/amcl/include/amcl/pf/pf.h b/navigations/amcl/include/amcl/pf/pf.h new file mode 100755 index 0000000..ba778d1 --- /dev/null +++ b/navigations/amcl/include/amcl/pf/pf.h @@ -0,0 +1,210 @@ +/* + * Player - One Hell of a Robot Server + * Copyright (C) 2000 Brian Gerkey & Kasper Stoy + * gerkey@usc.edu kaspers@robotics.usc.edu + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + * + */ +/************************************************************************** + * Desc: Simple particle filter for localization. + * Author: Andrew Howard + * Date: 10 Dec 2002 + * CVS: $Id: pf.h 3293 2005-11-19 08:37:45Z gerkey $ + *************************************************************************/ + +#ifndef PF_H +#define PF_H + +#include "pf_vector.h" +#include "pf_kdtree.h" + +#ifdef __cplusplus +extern "C" { +#endif + +// Forward declarations +struct _pf_t; +struct _rtk_fig_t; +struct _pf_sample_set_t; + +// Function prototype for the initialization model; generates a sample pose from +// an appropriate distribution. +typedef pf_vector_t (*pf_init_model_fn_t) (void *init_data); + +// Function prototype for the action model; generates a sample pose from +// an appropriate distribution +typedef void (*pf_action_model_fn_t) (void *action_data, + struct _pf_sample_set_t* set); + +// Function prototype for the sensor model; determines the probability +// for the given set of sample poses. +typedef double (*pf_sensor_model_fn_t) (void *sensor_data, + struct _pf_sample_set_t* set); + + +// Information for a single sample +typedef struct +{ + // Pose represented by this sample + pf_vector_t pose; + + // Weight for this pose + double weight; + +} pf_sample_t; + + +// Information for a cluster of samples +typedef struct +{ + // Number of samples + int count; + + // Total weight of samples in this cluster + double weight; + + // Cluster statistics + pf_vector_t mean; + pf_matrix_t cov; + + // Workspace + double m[4], c[2][2]; + +} pf_cluster_t; + + +// Information for a set of samples +typedef struct _pf_sample_set_t +{ + // The samples + int sample_count; + pf_sample_t *samples; + + // A kdtree encoding the histogram + pf_kdtree_t *kdtree; + + // Clusters + int cluster_count, cluster_max_count; + pf_cluster_t *clusters; + + // Filter statistics + pf_vector_t mean; + pf_matrix_t cov; + int converged; + double n_effective; +} pf_sample_set_t; + + +// Information for an entire filter +typedef struct _pf_t +{ + // This min and max number of samples + int min_samples, max_samples; + + // Population size parameters + double pop_err, pop_z; + + // Resample limit cache + int *limit_cache; + + // The sample sets. We keep two sets and use [current_set] + // to identify the active set. + int current_set; + pf_sample_set_t sets[2]; + + // Running averages, slow and fast, of likelihood + double w_slow, w_fast; + + // Decay rates for running averages + double alpha_slow, alpha_fast; + + // Function used to draw random pose samples + pf_init_model_fn_t random_pose_fn; + void *random_pose_data; + + double dist_threshold; //distance threshold in each axis over which the pf is considered to not be converged + int converged; + + // boolean parameter to enamble/diable selective resampling + int selective_resampling; +} pf_t; + + +// Create a new filter +pf_t *pf_alloc(int min_samples, int max_samples, + double alpha_slow, double alpha_fast, + pf_init_model_fn_t random_pose_fn, void *random_pose_data); + +// Free an existing filter +void pf_free(pf_t *pf); + +// Initialize the filter using a guassian +void pf_init(pf_t *pf, pf_vector_t mean, pf_matrix_t cov); + +// Initialize the filter using some model +void pf_init_model(pf_t *pf, pf_init_model_fn_t init_fn, void *init_data); + +// Update the filter with some new action +void pf_update_action(pf_t *pf, pf_action_model_fn_t action_fn, void *action_data); + +// Update the filter with some new sensor observation +void pf_update_sensor(pf_t *pf, pf_sensor_model_fn_t sensor_fn, void *sensor_data); + +// Resample the distribution +void pf_update_resample(pf_t *pf); + +// set selective resampling parameter +void pf_set_selective_resampling(pf_t *pf, int selective_resampling); + +// Compute the CEP statistics (mean and variance). +void pf_get_cep_stats(pf_t *pf, pf_vector_t *mean, double *var); + +// Compute the statistics for a particular cluster. Returns 0 if +// there is no such cluster. +int pf_get_cluster_stats(pf_t *pf, int cluster, double *weight, + pf_vector_t *mean, pf_matrix_t *cov); + +// Re-compute the cluster statistics for a sample set +void pf_cluster_stats(pf_t *pf, pf_sample_set_t *set); + + +// Display the sample set +void pf_draw_samples(pf_t *pf, struct _rtk_fig_t *fig, int max_samples); + +// Draw the histogram (kdtree) +void pf_draw_hist(pf_t *pf, struct _rtk_fig_t *fig); + +// Draw the CEP statistics +void pf_draw_cep_stats(pf_t *pf, struct _rtk_fig_t *fig); + +// Draw the cluster statistics +void pf_draw_cluster_stats(pf_t *pf, struct _rtk_fig_t *fig); + +//calculate if the particle filter has converged - +//and sets the converged flag in the current set and the pf +int pf_update_converged(pf_t *pf); + +//sets the current set and pf converged values to zero +void pf_init_converged(pf_t *pf); + +void pf_copy_set(pf_sample_set_t* set_a, pf_sample_set_t* set_b); + +#ifdef __cplusplus +} +#endif + + +#endif diff --git a/navigations/amcl/include/amcl/pf/pf_kdtree.h b/navigations/amcl/include/amcl/pf/pf_kdtree.h new file mode 100755 index 0000000..2368fa3 --- /dev/null +++ b/navigations/amcl/include/amcl/pf/pf_kdtree.h @@ -0,0 +1,109 @@ +/* + * Player - One Hell of a Robot Server + * Copyright (C) 2000 Brian Gerkey & Kasper Stoy + * gerkey@usc.edu kaspers@robotics.usc.edu + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + * + */ +/************************************************************************** + * Desc: KD tree functions + * Author: Andrew Howard + * Date: 18 Dec 2002 + * CVS: $Id: pf_kdtree.h 6532 2008-06-11 02:45:56Z gbiggs $ + *************************************************************************/ + +#ifndef PF_KDTREE_H +#define PF_KDTREE_H + +#ifdef INCLUDE_RTKGUI +#include "rtk.h" +#endif + + +// Info for a node in the tree +typedef struct pf_kdtree_node +{ + // Depth in the tree + int leaf, depth; + + // Pivot dimension and value + int pivot_dim; + double pivot_value; + + // The key for this node + int key[3]; + + // The value for this node + double value; + + // The cluster label (leaf nodes) + int cluster; + + // Child nodes + struct pf_kdtree_node *children[2]; + +} pf_kdtree_node_t; + + +// A kd tree +typedef struct +{ + // Cell size + double size[3]; + + // The root node of the tree + pf_kdtree_node_t *root; + + // The number of nodes in the tree + int node_count, node_max_count; + pf_kdtree_node_t *nodes; + + // The number of leaf nodes in the tree + int leaf_count; + +} pf_kdtree_t; + + +// Create a tree +extern pf_kdtree_t *pf_kdtree_alloc(int max_size); + +// Destroy a tree +extern void pf_kdtree_free(pf_kdtree_t *self); + +// Clear all entries from the tree +extern void pf_kdtree_clear(pf_kdtree_t *self); + +// Insert a pose into the tree +extern void pf_kdtree_insert(pf_kdtree_t *self, pf_vector_t pose, double value); + +// Cluster the leaves in the tree +extern void pf_kdtree_cluster(pf_kdtree_t *self); + +// Determine the probability estimate for the given pose +extern double pf_kdtree_get_prob(pf_kdtree_t *self, pf_vector_t pose); + +// Determine the cluster label for the given pose +extern int pf_kdtree_get_cluster(pf_kdtree_t *self, pf_vector_t pose); + + +#ifdef INCLUDE_RTKGUI + +// Draw the tree +extern void pf_kdtree_draw(pf_kdtree_t *self, rtk_fig_t *fig); + +#endif + +#endif diff --git a/navigations/amcl/include/amcl/pf/pf_pdf.h b/navigations/amcl/include/amcl/pf/pf_pdf.h new file mode 100755 index 0000000..2f2ad87 --- /dev/null +++ b/navigations/amcl/include/amcl/pf/pf_pdf.h @@ -0,0 +1,85 @@ +/* + * Player - One Hell of a Robot Server + * Copyright (C) 2000 Brian Gerkey & Kasper Stoy + * gerkey@usc.edu kaspers@robotics.usc.edu + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + * + */ +/************************************************************************** + * Desc: Useful pdf functions + * Author: Andrew Howard + * Date: 10 Dec 2002 + * CVS: $Id: pf_pdf.h 6345 2008-04-17 01:36:39Z gerkey $ + *************************************************************************/ + +#ifndef PF_PDF_H +#define PF_PDF_H + +#include "pf_vector.h" + +//#include +//#include + +#ifdef __cplusplus +extern "C" { +#endif + +/************************************************************************** + * Gaussian + *************************************************************************/ + +// Gaussian PDF info +typedef struct +{ + // Mean, covariance and inverse covariance + pf_vector_t x; + pf_matrix_t cx; + //pf_matrix_t cxi; + double cxdet; + + // Decomposed covariance matrix (rotation * diagonal) + pf_matrix_t cr; + pf_vector_t cd; + + // A random number generator + //gsl_rng *rng; + +} pf_pdf_gaussian_t; + + +// Create a gaussian pdf +pf_pdf_gaussian_t *pf_pdf_gaussian_alloc(pf_vector_t x, pf_matrix_t cx); + +// Destroy the pdf +void pf_pdf_gaussian_free(pf_pdf_gaussian_t *pdf); + +// Compute the value of the pdf at some point [z]. +//double pf_pdf_gaussian_value(pf_pdf_gaussian_t *pdf, pf_vector_t z); + +// Draw randomly from a zero-mean Gaussian distribution, with standard +// deviation sigma. +// We use the polar form of the Box-Muller transformation, explained here: +// http://www.taygeta.com/random/gaussian.html +double pf_ran_gaussian(double sigma); + +// Generate a sample from the pdf. +pf_vector_t pf_pdf_gaussian_sample(pf_pdf_gaussian_t *pdf); + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/navigations/amcl/include/amcl/pf/pf_vector.h b/navigations/amcl/include/amcl/pf/pf_vector.h new file mode 100755 index 0000000..6162ba3 --- /dev/null +++ b/navigations/amcl/include/amcl/pf/pf_vector.h @@ -0,0 +1,94 @@ +/* + * Player - One Hell of a Robot Server + * Copyright (C) 2000 Brian Gerkey & Kasper Stoy + * gerkey@usc.edu kaspers@robotics.usc.edu + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + * + */ +/************************************************************************** + * Desc: Vector functions + * Author: Andrew Howard + * Date: 10 Dec 2002 + * CVS: $Id: pf_vector.h 6345 2008-04-17 01:36:39Z gerkey $ + *************************************************************************/ + +#ifndef PF_VECTOR_H +#define PF_VECTOR_H + +#ifdef __cplusplus +extern "C" { +#endif + +#include + +// The basic vector +typedef struct +{ + double v[3]; +} pf_vector_t; + + +// The basic matrix +typedef struct +{ + double m[3][3]; +} pf_matrix_t; + + +// Return a zero vector +pf_vector_t pf_vector_zero(); + +// Check for NAN or INF in any component +int pf_vector_finite(pf_vector_t a); + +// Print a vector +void pf_vector_fprintf(pf_vector_t s, FILE *file, const char *fmt); + +// Simple vector addition +pf_vector_t pf_vector_add(pf_vector_t a, pf_vector_t b); + +// Simple vector subtraction +pf_vector_t pf_vector_sub(pf_vector_t a, pf_vector_t b); + +// Transform from local to global coords (a + b) +pf_vector_t pf_vector_coord_add(pf_vector_t a, pf_vector_t b); + +// Transform from global to local coords (a - b) +pf_vector_t pf_vector_coord_sub(pf_vector_t a, pf_vector_t b); + + +// Return a zero matrix +pf_matrix_t pf_matrix_zero(); + +// Check for NAN or INF in any component +int pf_matrix_finite(pf_matrix_t a); + +// Print a matrix +void pf_matrix_fprintf(pf_matrix_t s, FILE *file, const char *fmt); + +// Compute the matrix inverse. Will also return the determinant, +// which should be checked for underflow (indicated singular matrix). +//pf_matrix_t pf_matrix_inverse(pf_matrix_t a, double *det); + +// Decompose a covariance matrix [a] into a rotation matrix [r] and a +// diagonal matrix [d] such that a = r * d * r^T. +void pf_matrix_unitary(pf_matrix_t *r, pf_matrix_t *d, pf_matrix_t a); + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/navigations/amcl/include/amcl/sensors/amcl_laser.h b/navigations/amcl/include/amcl/sensors/amcl_laser.h new file mode 100755 index 0000000..391c921 --- /dev/null +++ b/navigations/amcl/include/amcl/sensors/amcl_laser.h @@ -0,0 +1,156 @@ +/* + * Player - One Hell of a Robot Server + * Copyright (C) 2000 Brian Gerkey et al. + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + * + */ +/////////////////////////////////////////////////////////////////////////// +// +// Desc: LASER sensor model for AMCL +// Author: Andrew Howard +// Date: 17 Aug 2003 +// CVS: $Id: amcl_laser.h 6443 2008-05-15 19:46:11Z gerkey $ +// +/////////////////////////////////////////////////////////////////////////// + +#ifndef AMCL_LASER_H +#define AMCL_LASER_H + +#include "amcl_sensor.h" +#include "../map/map.h" + +namespace amcl +{ + +typedef enum +{ + LASER_MODEL_BEAM, + LASER_MODEL_LIKELIHOOD_FIELD, + LASER_MODEL_LIKELIHOOD_FIELD_PROB +} laser_model_t; + +// Laser sensor data +class AMCLLaserData : public AMCLSensorData +{ + public: + AMCLLaserData () {ranges=NULL;}; + virtual ~AMCLLaserData() {delete [] ranges;}; + // Laser range data (range, bearing tuples) + public: int range_count; + public: double range_max; + public: double (*ranges)[2]; +}; + + +// Laseretric sensor model +class AMCLLaser : public AMCLSensor +{ + // Default constructor + public: AMCLLaser(size_t max_beams, map_t* map); + + public: virtual ~AMCLLaser(); + + public: void SetModelBeam(double z_hit, + double z_short, + double z_max, + double z_rand, + double sigma_hit, + double lambda_short, + double chi_outlier); + + public: void SetModelLikelihoodField(double z_hit, + double z_rand, + double sigma_hit, + double max_occ_dist); + + //a more probabilistically correct model - also with the option to do beam skipping + public: void SetModelLikelihoodFieldProb(double z_hit, + double z_rand, + double sigma_hit, + double max_occ_dist, + bool do_beamskip, + double beam_skip_distance, + double beam_skip_threshold, + double beam_skip_error_threshold); + + // Update the filter based on the sensor model. Returns true if the + // filter has been updated. + public: virtual bool UpdateSensor(pf_t *pf, AMCLSensorData *data); + + // Set the laser's pose after construction + public: void SetLaserPose(pf_vector_t& laser_pose) + {this->laser_pose = laser_pose;} + + // Determine the probability for the given pose + private: static double BeamModel(AMCLLaserData *data, + pf_sample_set_t* set); + // Determine the probability for the given pose + private: static double LikelihoodFieldModel(AMCLLaserData *data, + pf_sample_set_t* set); + + // Determine the probability for the given pose - more probablistic model + private: static double LikelihoodFieldModelProb(AMCLLaserData *data, + pf_sample_set_t* set); + + private: void reallocTempData(int max_samples, int max_obs); + + private: laser_model_t model_type; + + // Current data timestamp + private: double time; + + // The laser map + private: map_t *map; + + // Laser offset relative to robot + private: pf_vector_t laser_pose; + + // Max beams to consider + private: int max_beams; + + // Beam skipping parameters (used by LikelihoodFieldModelProb model) + private: bool do_beamskip; + private: double beam_skip_distance; + private: double beam_skip_threshold; + //threshold for the ratio of invalid beams - at which all beams are integrated to the likelihoods + //this would be an error condition + private: double beam_skip_error_threshold; + + //temp data that is kept before observations are integrated to each particle (requried for beam skipping) + private: int max_samples; + private: int max_obs; + private: double **temp_obs; + + // Laser model params + // + // Mixture params for the components of the model; must sum to 1 + private: double z_hit; + private: double z_short; + private: double z_max; + private: double z_rand; + // + // Stddev of Gaussian model for laser hits. + private: double sigma_hit; + // Decay rate of exponential model for short readings. + private: double lambda_short; + // Threshold for outlier rejection (unused) + private: double chi_outlier; +}; + + +} + +#endif diff --git a/navigations/amcl/include/amcl/sensors/amcl_laser.puml b/navigations/amcl/include/amcl/sensors/amcl_laser.puml new file mode 100755 index 0000000..3c161b9 --- /dev/null +++ b/navigations/amcl/include/amcl/sensors/amcl_laser.puml @@ -0,0 +1,54 @@ +@startuml + +class Player { + + Player() +} + +class AMCLLaserData { + + AMCLLaserData() + + ~AMCLLaserData() + # range_count: int + # range_max: double + # ranges: double[][] + +} + +class AMCLLaser { + - model_type: laser_model_t + - time: double + - map: map_t + - laser_pose: pf_vector_t + - max_beams: int + - do_beamskip: bool + - beam_skip_distance: double + - beam_skip_threshold: double + - beam_skip_error_threshold: double + - max_samples: int + - max_obs: int + - temp_obs: double[][] + - z_hit: double + - z_short: double + - z_max: double + - z_rand: double + - sigma_hit: double + - lambda_short: double + - chi_outlier: double + + + AMCLLaser(max_beams: size_t, map: map_t) + + ~AMCLLaser() + + SetModelBeam(z_hit: double, z_short: double, z_max: double, z_rand: double, sigma_hit: double, lambda_short: double, chi_outlier: double) + + SetModelLikelihoodField(z_hit: double, z_rand: double, sigma_hit: double, max_occ_dist: double) + + SetModelLikelihoodFieldProb(z_hit: double, z_rand: double, sigma_hit: double, max_occ_dist: double, do_beamskip: bool, beam_skip_distance: double, beam_skip_threshold: double, beam_skip_error_threshold: double) + + UpdateSensor(pf: pf_t, data: AMCLSensorData): bool + + SetLaserPose(laser_pose: pf_vector_t) + + BeamModel(data: AMCLLaserData, set: pf_sample_set_t): double + + LikelihoodFieldModel(data: AMCLLaserData, set: pf_sample_set_t): double + + LikelihoodFieldModelProb(data: AMCLLaserData, set: pf_sample_set_t): double + + reallocTempData(max_samples: int, max_obs: int) +} + +Player --|> AMCLSensor + +AMCLLaserData --|> AMCLSensorData + +@enduml \ No newline at end of file diff --git a/navigations/amcl/include/amcl/sensors/amcl_odom.h b/navigations/amcl/include/amcl/sensors/amcl_odom.h new file mode 100755 index 0000000..d50244a --- /dev/null +++ b/navigations/amcl/include/amcl/sensors/amcl_odom.h @@ -0,0 +1,98 @@ +/* + * Player - One Hell of a Robot Server + * Copyright (C) 2000 Brian Gerkey et al. + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + * + */ +/////////////////////////////////////////////////////////////////////////// +// +// Desc: Odometry sensor model for AMCL +// Author: Andrew Howard +// Date: 17 Aug 2003 +// CVS: $Id: amcl_odom.h 4135 2007-08-23 19:58:48Z gerkey $ +// +/////////////////////////////////////////////////////////////////////////// + +#ifndef AMCL_ODOM_H +#define AMCL_ODOM_H + +#include "amcl_sensor.h" +#include "../pf/pf_pdf.h" + +namespace amcl +{ + +typedef enum +{ + ODOM_MODEL_DIFF, + ODOM_MODEL_OMNI, + ODOM_MODEL_DIFF_CORRECTED, + ODOM_MODEL_OMNI_CORRECTED +} odom_model_t; + +// Odometric sensor data +class AMCLOdomData : public AMCLSensorData +{ + // Odometric pose + public: pf_vector_t pose; + + // Change in odometric pose + public: pf_vector_t delta; +}; + + +// Odometric sensor model +class AMCLOdom : public AMCLSensor +{ + // Default constructor + public: AMCLOdom(); + + public: void SetModelDiff(double alpha1, + double alpha2, + double alpha3, + double alpha4); + + public: void SetModelOmni(double alpha1, + double alpha2, + double alpha3, + double alpha4, + double alpha5); + + public: void SetModel( odom_model_t type, + double alpha1, + double alpha2, + double alpha3, + double alpha4, + double alpha5 = 0 ); + + // Update the filter based on the action model. Returns true if the filter + // has been updated. + public: virtual bool UpdateAction(pf_t *pf, AMCLSensorData *data); + + // Current data timestamp + private: double time; + + // Model type + private: odom_model_t model_type; + + // Drift parameters + private: double alpha1, alpha2, alpha3, alpha4, alpha5; +}; + + +} + +#endif diff --git a/navigations/amcl/include/amcl/sensors/amcl_odom.puml b/navigations/amcl/include/amcl/sensors/amcl_odom.puml new file mode 100755 index 0000000..8991b0f --- /dev/null +++ b/navigations/amcl/include/amcl/sensors/amcl_odom.puml @@ -0,0 +1,54 @@ +@startuml + +class Player { + + Player() +} + +class AMCLSensor { + - is_action: bool + - pose: pf_vector_t + + + AMCLSensor() + + ~AMCLSensor() + + UpdateAction(pf: pf_t, data: AMCLSensorData): bool + + InitSensor(pf: pf_t, data: AMCLSensorData): bool + + UpdateSensor(pf: pf_t, data: AMCLSensorData): bool +} + +class AMCLSensorData { + - sensor: AMCLSensor + + + AMCLSensorData() + + ~AMCLSensorData() +} + +class AMCLOdomData { + - pose: pf_vector_t + - delta: pf_vector_t + + + AMCLOdomData() +} + +class AMCLOdom { + - time: double + - model_type: odom_model_t + - alpha1: double + - alpha2: double + - alpha3: double + - alpha4: double + - alpha5: double + + + AMCLOdom() + + SetModelDiff(alpha1: double, alpha2: double, alpha3: double, alpha4: double) + + SetModelOmni(alpha1: double, alpha2: double, alpha3: double, alpha4: double, alpha5: double) + + SetModel(type: odom_model_t, alpha1: double, alpha2: double, alpha3: double, alpha4: double, alpha5: double = 0) + + UpdateAction(pf: pf_t, data: AMCLSensorData): bool +} + +Player --|> AMCLSensor + +AMCLSensorData --|> AMCLSensor +AMCLOdomData --|> AMCLSensorData +AMCLOdom --|> AMCLSensor + +@enduml diff --git a/navigations/amcl/include/amcl/sensors/amcl_sensor.h b/navigations/amcl/include/amcl/sensors/amcl_sensor.h new file mode 100755 index 0000000..fe0875a --- /dev/null +++ b/navigations/amcl/include/amcl/sensors/amcl_sensor.h @@ -0,0 +1,97 @@ +/* + * Player - One Hell of a Robot Server + * Copyright (C) 2000 Brian Gerkey et al. + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +/////////////////////////////////////////////////////////////////////////// +// +// Desc: Adaptive Monte-Carlo localization +// Author: Andrew Howard +// Date: 6 Feb 2003 +// CVS: $Id: amcl_sensor.h 6443 2008-05-15 19:46:11Z gerkey $ +// +/////////////////////////////////////////////////////////////////////////// + +#ifndef AMCL_SENSOR_H +#define AMCL_SENSOR_H + +#include "../pf/pf.h" + +namespace amcl +{ + +// Forward declarations +class AMCLSensorData; + + +// Base class for all AMCL sensors +class AMCLSensor +{ + // Default constructor + public: AMCLSensor(); + + // Default destructor + public: virtual ~AMCLSensor(); + + // Update the filter based on the action model. Returns true if the filter + // has been updated. + public: virtual bool UpdateAction(pf_t *pf, AMCLSensorData *data); + + // Initialize the filter based on the sensor model. Returns true if the + // filter has been initialized. + public: virtual bool InitSensor(pf_t *pf, AMCLSensorData *data); + + // Update the filter based on the sensor model. Returns true if the + // filter has been updated. + public: virtual bool UpdateSensor(pf_t *pf, AMCLSensorData *data); + + // Flag is true if this is the action sensor + public: bool is_action; + + // Action pose (action sensors only) + public: pf_vector_t pose; + + // AMCL Base + //protected: AdaptiveMCL & AMCL; + +#ifdef INCLUDE_RTKGUI + // Setup the GUI + public: virtual void SetupGUI(rtk_canvas_t *canvas, rtk_fig_t *robot_fig); + + // Finalize the GUI + public: virtual void ShutdownGUI(rtk_canvas_t *canvas, rtk_fig_t *robot_fig); + + // Draw sensor data + public: virtual void UpdateGUI(rtk_canvas_t *canvas, rtk_fig_t *robot_fig, AMCLSensorData *data); +#endif +}; + + + +// Base class for all AMCL sensor measurements +class AMCLSensorData +{ + // Pointer to sensor that generated the data + public: AMCLSensor *sensor; + virtual ~AMCLSensorData() {} + + // Data timestamp + public: double time; +}; + +} + +#endif diff --git a/navigations/amcl/include/amcl/sensors/amcl_sensor.puml b/navigations/amcl/include/amcl/sensors/amcl_sensor.puml new file mode 100755 index 0000000..7197de0 --- /dev/null +++ b/navigations/amcl/include/amcl/sensors/amcl_sensor.puml @@ -0,0 +1,29 @@ +@startuml + +class Player { + + Player() +} + +class AMCLSensor { + - is_action: bool + - pose: pf_vector_t + + + AMCLSensor() + + ~AMCLSensor() + + UpdateAction(pf: pf_t, data: AMCLSensorData): bool + + InitSensor(pf: pf_t, data: AMCLSensorData): bool + + UpdateSensor(pf: pf_t, data: AMCLSensorData): bool +} + +class AMCLSensorData { + - sensor: AMCLSensor + + + AMCLSensorData() + + ~AMCLSensorData() +} + +Player --|> AMCLSensor + +AMCLSensorData --|> AMCLSensor + +@enduml \ No newline at end of file diff --git a/navigations/amcl/package.xml b/navigations/amcl/package.xml new file mode 100755 index 0000000..8bed780 --- /dev/null +++ b/navigations/amcl/package.xml @@ -0,0 +1,47 @@ + + + + amcl + 1.17.3 + +

+ amcl is a probabilistic localization system for a robot moving in + 2D. It implements the adaptive (or KLD-sampling) Monte Carlo + localization approach (as described by Dieter Fox), which uses a + particle filter to track the pose of a robot against a known map. +

+

+ This node is derived, with thanks, from Andrew Howard's excellent + 'amcl' Player driver. +

+
+ http://wiki.ros.org/amcl + Brian P. Gerkey + contradict@gmail.com + David V. Lu!! + Michael Ferguson + Aaron Hoy + LGPL + + catkin + + message_filters + tf2_geometry_msgs + + diagnostic_updater + dynamic_reconfigure + geometry_msgs + nav_msgs + rosbag + roscpp + sensor_msgs + std_srvs + tf2 + tf2_msgs + tf2_ros + + map_server + rostest + python3-pykdl + tf2_py +
diff --git a/navigations/amcl/src/amcl/map/map.c b/navigations/amcl/src/amcl/map/map.c new file mode 100755 index 0000000..23c9662 --- /dev/null +++ b/navigations/amcl/src/amcl/map/map.c @@ -0,0 +1,84 @@ +/* + * Player - One Hell of a Robot Server + * Copyright (C) 2000 Brian Gerkey & Kasper Stoy + * gerkey@usc.edu kaspers@robotics.usc.edu + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + * + */ +/************************************************************************** + * Desc: Global map (grid-based) + * Author: Andrew Howard + * Date: 6 Feb 2003 + * CVS: $Id: map.c 1713 2003-08-23 04:03:43Z inspectorg $ +**************************************************************************/ + +#include +#include +#include +#include +#include + +#include "amcl/map/map.h" + + +// Create a new map +map_t *map_alloc(void) +{ + map_t *map; + + map = (map_t*) malloc(sizeof(map_t)); + + // Assume we start at (0, 0) + map->origin_x = 0; + map->origin_y = 0; + + // Make the size odd + map->size_x = 0; + map->size_y = 0; + map->scale = 0; + + // Allocate storage for main map + map->cells = (map_cell_t*) NULL; + + return map; +} + + +// Destroy a map +void map_free(map_t *map) +{ + free(map->cells); + free(map); + return; +} + + +// Get the cell at the given point +map_cell_t *map_get_cell(map_t *map, double ox, double oy, double oa) +{ + int i, j; + map_cell_t *cell; + + i = MAP_GXWX(map, ox); + j = MAP_GYWY(map, oy); + + if (!MAP_VALID(map, i, j)) + return NULL; + + cell = map->cells + MAP_INDEX(map, i, j); + return cell; +} + diff --git a/navigations/amcl/src/amcl/map/map_cspace.cpp b/navigations/amcl/src/amcl/map/map_cspace.cpp new file mode 100755 index 0000000..3eafd9d --- /dev/null +++ b/navigations/amcl/src/amcl/map/map_cspace.cpp @@ -0,0 +1,176 @@ +/* + * Player - One Hell of a Robot Server + * Copyright (C) 2000 Brian Gerkey & Kasper Stoy + * gerkey@usc.edu kaspers@robotics.usc.edu + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + * + */ + +#include +#include +#include +#include +#include "amcl/map/map.h" + +class CellData +{ + public: + map_t* map_; + unsigned int i_, j_; + unsigned int src_i_, src_j_; +}; + +class CachedDistanceMap +{ + public: + CachedDistanceMap(double scale, double max_dist) : + distances_(NULL), scale_(scale), max_dist_(max_dist) + { + cell_radius_ = max_dist / scale; + distances_ = new double *[cell_radius_+2]; + for(int i=0; i<=cell_radius_+1; i++) + { + distances_[i] = new double[cell_radius_+2]; + for(int j=0; j<=cell_radius_+1; j++) + { + distances_[i][j] = sqrt(i*i + j*j); + } + } + } + ~CachedDistanceMap() + { + if(distances_) + { + for(int i=0; i<=cell_radius_+1; i++) + delete[] distances_[i]; + delete[] distances_; + } + } + double** distances_; + double scale_; + double max_dist_; + int cell_radius_; +}; + + +bool operator<(const CellData& a, const CellData& b) +{ + return a.map_->cells[MAP_INDEX(a.map_, a.i_, a.j_)].occ_dist > a.map_->cells[MAP_INDEX(b.map_, b.i_, b.j_)].occ_dist; +} + +CachedDistanceMap* +get_distance_map(double scale, double max_dist) +{ + static CachedDistanceMap* cdm = NULL; + + if(!cdm || (cdm->scale_ != scale) || (cdm->max_dist_ != max_dist)) + { + if(cdm) + delete cdm; + cdm = new CachedDistanceMap(scale, max_dist); + } + + return cdm; +} + +void enqueue(map_t* map, int i, int j, + int src_i, int src_j, + std::priority_queue& Q, + CachedDistanceMap* cdm, + unsigned char* marked) +{ + if(marked[MAP_INDEX(map, i, j)]) + return; + + int di = abs(i - src_i); + int dj = abs(j - src_j); + double distance = cdm->distances_[di][dj]; + + if(distance > cdm->cell_radius_) + return; + + map->cells[MAP_INDEX(map, i, j)].occ_dist = distance * map->scale; + + CellData cell; + cell.map_ = map; + cell.i_ = i; + cell.j_ = j; + cell.src_i_ = src_i; + cell.src_j_ = src_j; + + Q.push(cell); + + marked[MAP_INDEX(map, i, j)] = 1; +} + +// Update the cspace distance values +void map_update_cspace(map_t *map, double max_occ_dist) +{ + unsigned char* marked; + std::priority_queue Q; + + marked = new unsigned char[map->size_x*map->size_y]; + memset(marked, 0, sizeof(unsigned char) * map->size_x*map->size_y); + + map->max_occ_dist = max_occ_dist; + + CachedDistanceMap* cdm = get_distance_map(map->scale, map->max_occ_dist); + + // Enqueue all the obstacle cells + CellData cell; + cell.map_ = map; + for(int i=0; isize_x; i++) + { + cell.src_i_ = cell.i_ = i; + for(int j=0; jsize_y; j++) + { + if(map->cells[MAP_INDEX(map, i, j)].occ_state == +1) + { + map->cells[MAP_INDEX(map, i, j)].occ_dist = 0.0; + cell.src_j_ = cell.j_ = j; + marked[MAP_INDEX(map, i, j)] = 1; + Q.push(cell); + } + else + map->cells[MAP_INDEX(map, i, j)].occ_dist = max_occ_dist; + } + } + + while(!Q.empty()) + { + CellData current_cell = Q.top(); + if(current_cell.i_ > 0) + enqueue(map, current_cell.i_-1, current_cell.j_, + current_cell.src_i_, current_cell.src_j_, + Q, cdm, marked); + if(current_cell.j_ > 0) + enqueue(map, current_cell.i_, current_cell.j_-1, + current_cell.src_i_, current_cell.src_j_, + Q, cdm, marked); + if((int)current_cell.i_ < map->size_x - 1) + enqueue(map, current_cell.i_+1, current_cell.j_, + current_cell.src_i_, current_cell.src_j_, + Q, cdm, marked); + if((int)current_cell.j_ < map->size_y - 1) + enqueue(map, current_cell.i_, current_cell.j_+1, + current_cell.src_i_, current_cell.src_j_, + Q, cdm, marked); + + Q.pop(); + } + + delete[] marked; +} diff --git a/navigations/amcl/src/amcl/map/map_draw.c b/navigations/amcl/src/amcl/map/map_draw.c new file mode 100755 index 0000000..b1201fd --- /dev/null +++ b/navigations/amcl/src/amcl/map/map_draw.c @@ -0,0 +1,158 @@ +/* + * Player - One Hell of a Robot Server + * Copyright (C) 2000 Brian Gerkey & Kasper Stoy + * gerkey@usc.edu kaspers@robotics.usc.edu + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + * + */ +/************************************************************************** + * Desc: Local map GUI functions + * Author: Andrew Howard + * Date: 18 Jan 2003 + * CVS: $Id: map_draw.c 7057 2008-10-02 00:44:06Z gbiggs $ +**************************************************************************/ + +#ifdef INCLUDE_RTKGUI + +#include +#include +#include +#include + +#include +#include "amcl/map/map.h" + + +//////////////////////////////////////////////////////////////////////////// +// Draw the occupancy map +void map_draw_occ(map_t *map, rtk_fig_t *fig) +{ + int i, j; + int col; + map_cell_t *cell; + uint16_t *image; + uint16_t *pixel; + + image = malloc(map->size_x * map->size_y * sizeof(image[0])); + + // Draw occupancy + for (j = 0; j < map->size_y; j++) + { + for (i = 0; i < map->size_x; i++) + { + cell = map->cells + MAP_INDEX(map, i, j); + pixel = image + (j * map->size_x + i); + + col = 127 - 127 * cell->occ_state; + *pixel = RTK_RGB16(col, col, col); + } + } + + // Draw the entire occupancy map as an image + rtk_fig_image(fig, map->origin_x, map->origin_y, 0, + map->scale, map->size_x, map->size_y, 16, image, NULL); + + free(image); + + return; +} + + +//////////////////////////////////////////////////////////////////////////// +// Draw the cspace map +void map_draw_cspace(map_t *map, rtk_fig_t *fig) +{ + int i, j; + int col; + map_cell_t *cell; + uint16_t *image; + uint16_t *pixel; + + image = malloc(map->size_x * map->size_y * sizeof(image[0])); + + // Draw occupancy + for (j = 0; j < map->size_y; j++) + { + for (i = 0; i < map->size_x; i++) + { + cell = map->cells + MAP_INDEX(map, i, j); + pixel = image + (j * map->size_x + i); + + col = 255 * cell->occ_dist / map->max_occ_dist; + + *pixel = RTK_RGB16(col, col, col); + } + } + + // Draw the entire occupancy map as an image + rtk_fig_image(fig, map->origin_x, map->origin_y, 0, + map->scale, map->size_x, map->size_y, 16, image, NULL); + + free(image); + + return; +} + + +//////////////////////////////////////////////////////////////////////////// +// Draw a wifi map +void map_draw_wifi(map_t *map, rtk_fig_t *fig, int index) +{ + int i, j; + int level, col; + map_cell_t *cell; + uint16_t *image, *mask; + uint16_t *ipix, *mpix; + + image = malloc(map->size_x * map->size_y * sizeof(image[0])); + mask = malloc(map->size_x * map->size_y * sizeof(mask[0])); + + // Draw wifi levels + for (j = 0; j < map->size_y; j++) + { + for (i = 0; i < map->size_x; i++) + { + cell = map->cells + MAP_INDEX(map, i, j); + ipix = image + (j * map->size_x + i); + mpix = mask + (j * map->size_x + i); + + level = cell->wifi_levels[index]; + + if (cell->occ_state == -1 && level != 0) + { + col = 255 * (100 + level) / 100; + *ipix = RTK_RGB16(col, col, col); + *mpix = 1; + } + else + { + *mpix = 0; + } + } + } + + // Draw the entire occupancy map as an image + rtk_fig_image(fig, map->origin_x, map->origin_y, 0, + map->scale, map->size_x, map->size_y, 16, image, mask); + + free(mask); + free(image); + + return; +} + + +#endif diff --git a/navigations/amcl/src/amcl/map/map_range.c b/navigations/amcl/src/amcl/map/map_range.c new file mode 100755 index 0000000..658619f --- /dev/null +++ b/navigations/amcl/src/amcl/map/map_range.c @@ -0,0 +1,120 @@ +/* + * Player - One Hell of a Robot Server + * Copyright (C) 2000 Brian Gerkey & Kasper Stoy + * gerkey@usc.edu kaspers@robotics.usc.edu + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + * + */ +/************************************************************************** + * Desc: Range routines + * Author: Andrew Howard + * Date: 18 Jan 2003 + * CVS: $Id: map_range.c 1347 2003-05-05 06:24:33Z inspectorg $ +**************************************************************************/ + +#include +#include +#include +#include + +#include "amcl/map/map.h" + +// Extract a single range reading from the map. Unknown cells and/or +// out-of-bound cells are treated as occupied, which makes it easy to +// use Stage bitmap files. +double map_calc_range(map_t *map, double ox, double oy, double oa, double max_range) +{ + // Bresenham raytracing + int x0,x1,y0,y1; + int x,y; + int xstep, ystep; + char steep; + int tmp; + int deltax, deltay, error, deltaerr; + + x0 = MAP_GXWX(map,ox); + y0 = MAP_GYWY(map,oy); + + x1 = MAP_GXWX(map,ox + max_range * cos(oa)); + y1 = MAP_GYWY(map,oy + max_range * sin(oa)); + + if(abs(y1-y0) > abs(x1-x0)) + steep = 1; + else + steep = 0; + + if(steep) + { + tmp = x0; + x0 = y0; + y0 = tmp; + + tmp = x1; + x1 = y1; + y1 = tmp; + } + + deltax = abs(x1-x0); + deltay = abs(y1-y0); + error = 0; + deltaerr = deltay; + + x = x0; + y = y0; + + if(x0 < x1) + xstep = 1; + else + xstep = -1; + if(y0 < y1) + ystep = 1; + else + ystep = -1; + + if(steep) + { + if(!MAP_VALID(map,y,x) || map->cells[MAP_INDEX(map,y,x)].occ_state > -1) + return sqrt((x-x0)*(x-x0) + (y-y0)*(y-y0)) * map->scale; + } + else + { + if(!MAP_VALID(map,x,y) || map->cells[MAP_INDEX(map,x,y)].occ_state > -1) + return sqrt((x-x0)*(x-x0) + (y-y0)*(y-y0)) * map->scale; + } + + while(x != (x1 + xstep * 1)) + { + x += xstep; + error += deltaerr; + if(2*error >= deltax) + { + y += ystep; + error -= deltax; + } + + if(steep) + { + if(!MAP_VALID(map,y,x) || map->cells[MAP_INDEX(map,y,x)].occ_state > -1) + return sqrt((x-x0)*(x-x0) + (y-y0)*(y-y0)) * map->scale; + } + else + { + if(!MAP_VALID(map,x,y) || map->cells[MAP_INDEX(map,x,y)].occ_state > -1) + return sqrt((x-x0)*(x-x0) + (y-y0)*(y-y0)) * map->scale; + } + } + return max_range; +} diff --git a/navigations/amcl/src/amcl/map/map_store.c b/navigations/amcl/src/amcl/map/map_store.c new file mode 100755 index 0000000..b6d6ddb --- /dev/null +++ b/navigations/amcl/src/amcl/map/map_store.c @@ -0,0 +1,215 @@ +/* + * Player - One Hell of a Robot Server + * Copyright (C) 2000 Brian Gerkey & Kasper Stoy + * gerkey@usc.edu kaspers@robotics.usc.edu + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + * + */ +/************************************************************************** + * Desc: Global map storage functions + * Author: Andrew Howard + * Date: 6 Feb 2003 + * CVS: $Id: map_store.c 2951 2005-08-19 00:48:20Z gerkey $ +**************************************************************************/ + +#include +#include +#include +#include +#include + +#include "amcl/map/map.h" + + +//////////////////////////////////////////////////////////////////////////// +// Load an occupancy grid +int map_load_occ(map_t *map, const char *filename, double scale, int negate) +{ + FILE *file; + char magic[3]; + int i, j; + int ch, occ; + int width, height, depth; + map_cell_t *cell; + + // Open file + file = fopen(filename, "r"); + if (file == NULL) + { + fprintf(stderr, "%s: %s\n", strerror(errno), filename); + return -1; + } + + // Read ppm header + + if ((fscanf(file, "%2s \n", magic) != 1) || (strcmp(magic, "P5") != 0)) + { + fprintf(stderr, "incorrect image format; must be PGM/binary"); + fclose(file); + return -1; + } + + // Ignore comments + while ((ch = fgetc(file)) == '#') + while (fgetc(file) != '\n'); + ungetc(ch, file); + + // Read image dimensions + if(fscanf(file, " %d %d \n %d \n", &width, &height, &depth) != 3) + { + fprintf(stderr, "Failed ot read image dimensions"); + return -1; + } + + // Allocate space in the map + if (map->cells == NULL) + { + map->scale = scale; + map->size_x = width; + map->size_y = height; + map->cells = calloc(width * height, sizeof(map->cells[0])); + } + else + { + if (width != map->size_x || height != map->size_y) + { + //PLAYER_ERROR("map dimensions are inconsistent with prior map dimensions"); + return -1; + } + } + + // Read in the image + for (j = height - 1; j >= 0; j--) + { + for (i = 0; i < width; i++) + { + ch = fgetc(file); + + // Black-on-white images + if (!negate) + { + if (ch < depth / 4) + occ = +1; + else if (ch > 3 * depth / 4) + occ = -1; + else + occ = 0; + } + + // White-on-black images + else + { + if (ch < depth / 4) + occ = -1; + else if (ch > 3 * depth / 4) + occ = +1; + else + occ = 0; + } + + if (!MAP_VALID(map, i, j)) + continue; + cell = map->cells + MAP_INDEX(map, i, j); + cell->occ_state = occ; + } + } + + fclose(file); + + return 0; +} + + +//////////////////////////////////////////////////////////////////////////// +// Load a wifi signal strength map +/* +int map_load_wifi(map_t *map, const char *filename, int index) +{ + FILE *file; + char magic[3]; + int i, j; + int ch, level; + int width, height, depth; + map_cell_t *cell; + + // Open file + file = fopen(filename, "r"); + if (file == NULL) + { + fprintf(stderr, "%s: %s\n", strerror(errno), filename); + return -1; + } + + // Read ppm header + fscanf(file, "%10s \n", magic); + if (strcmp(magic, "P5") != 0) + { + fprintf(stderr, "incorrect image format; must be PGM/binary"); + return -1; + } + + // Ignore comments + while ((ch = fgetc(file)) == '#') + while (fgetc(file) != '\n'); + ungetc(ch, file); + + // Read image dimensions + fscanf(file, " %d %d \n %d \n", &width, &height, &depth); + + // Allocate space in the map + if (map->cells == NULL) + { + map->size_x = width; + map->size_y = height; + map->cells = calloc(width * height, sizeof(map->cells[0])); + } + else + { + if (width != map->size_x || height != map->size_y) + { + //PLAYER_ERROR("map dimensions are inconsistent with prior map dimensions"); + return -1; + } + } + + // Read in the image + for (j = height - 1; j >= 0; j--) + { + for (i = 0; i < width; i++) + { + ch = fgetc(file); + + if (!MAP_VALID(map, i, j)) + continue; + + if (ch == 0) + level = 0; + else + level = ch * 100 / 255 - 100; + + cell = map->cells + MAP_INDEX(map, i, j); + cell->wifi_levels[index] = level; + } + } + + fclose(file); + + return 0; +} +*/ + + + diff --git a/navigations/amcl/src/amcl/pf/eig3.c b/navigations/amcl/src/amcl/pf/eig3.c new file mode 100755 index 0000000..3e8aee6 --- /dev/null +++ b/navigations/amcl/src/amcl/pf/eig3.c @@ -0,0 +1,274 @@ + +/* Eigen decomposition code for symmetric 3x3 matrices, copied from the public + domain Java Matrix library JAMA. */ + +#include + +#ifndef MAX +#define MAX(a, b) ((a)>(b)?(a):(b)) +#endif + +#ifdef _MSC_VER +#define n 3 +#else +static int n = 3; +#endif + +static double hypot2(double x, double y) { + return sqrt(x*x+y*y); +} + +// Symmetric Householder reduction to tridiagonal form. + +static void tred2(double V[n][n], double d[n], double e[n]) { + +// This is derived from the Algol procedures tred2 by +// Bowdler, Martin, Reinsch, and Wilkinson, Handbook for +// Auto. Comp., Vol.ii-Linear Algebra, and the corresponding +// Fortran subroutine in EISPACK. + + int i,j,k; + double f,g,h,hh; + for (j = 0; j < n; j++) { + d[j] = V[n-1][j]; + } + + // Householder reduction to tridiagonal form. + + for (i = n-1; i > 0; i--) { + + // Scale to avoid under/overflow. + + double scale = 0.0; + double h = 0.0; + for (k = 0; k < i; k++) { + scale = scale + fabs(d[k]); + } + if (scale == 0.0) { + e[i] = d[i-1]; + for (j = 0; j < i; j++) { + d[j] = V[i-1][j]; + V[i][j] = 0.0; + V[j][i] = 0.0; + } + } else { + + // Generate Householder vector. + + for (k = 0; k < i; k++) { + d[k] /= scale; + h += d[k] * d[k]; + } + f = d[i-1]; + g = sqrt(h); + if (f > 0) { + g = -g; + } + e[i] = scale * g; + h = h - f * g; + d[i-1] = f - g; + for (j = 0; j < i; j++) { + e[j] = 0.0; + } + + // Apply similarity transformation to remaining columns. + + for (j = 0; j < i; j++) { + f = d[j]; + V[j][i] = f; + g = e[j] + V[j][j] * f; + for (k = j+1; k <= i-1; k++) { + g += V[k][j] * d[k]; + e[k] += V[k][j] * f; + } + e[j] = g; + } + f = 0.0; + for (j = 0; j < i; j++) { + e[j] /= h; + f += e[j] * d[j]; + } + hh = f / (h + h); + for (j = 0; j < i; j++) { + e[j] -= hh * d[j]; + } + for (j = 0; j < i; j++) { + f = d[j]; + g = e[j]; + for (k = j; k <= i-1; k++) { + V[k][j] -= (f * e[k] + g * d[k]); + } + d[j] = V[i-1][j]; + V[i][j] = 0.0; + } + } + d[i] = h; + } + + // Accumulate transformations. + + for (i = 0; i < n-1; i++) { + V[n-1][i] = V[i][i]; + V[i][i] = 1.0; + h = d[i+1]; + if (h != 0.0) { + for (k = 0; k <= i; k++) { + d[k] = V[k][i+1] / h; + } + for (j = 0; j <= i; j++) { + g = 0.0; + for (k = 0; k <= i; k++) { + g += V[k][i+1] * V[k][j]; + } + for (k = 0; k <= i; k++) { + V[k][j] -= g * d[k]; + } + } + } + for (k = 0; k <= i; k++) { + V[k][i+1] = 0.0; + } + } + for (j = 0; j < n; j++) { + d[j] = V[n-1][j]; + V[n-1][j] = 0.0; + } + V[n-1][n-1] = 1.0; + e[0] = 0.0; +} + +// Symmetric tridiagonal QL algorithm. + +static void tql2(double V[n][n], double d[n], double e[n]) { + +// This is derived from the Algol procedures tql2, by +// Bowdler, Martin, Reinsch, and Wilkinson, Handbook for +// Auto. Comp., Vol.ii-Linear Algebra, and the corresponding +// Fortran subroutine in EISPACK. + + int i,j,m,l,k; + double g,p,r,dl1,h,f,tst1,eps; + double c,c2,c3,el1,s,s2; + + for (i = 1; i < n; i++) { + e[i-1] = e[i]; + } + e[n-1] = 0.0; + + f = 0.0; + tst1 = 0.0; + eps = pow(2.0,-52.0); + for (l = 0; l < n; l++) { + + // Find small subdiagonal element + + tst1 = MAX(tst1,fabs(d[l]) + fabs(e[l])); + m = l; + while (m < n) { + if (fabs(e[m]) <= eps*tst1) { + break; + } + m++; + } + + // If m == l, d[l] is an eigenvalue, + // otherwise, iterate. + + if (m > l) { + int iter = 0; + do { + iter = iter + 1; // (Could check iteration count here.) + + // Compute implicit shift + + g = d[l]; + p = (d[l+1] - g) / (2.0 * e[l]); + r = hypot2(p,1.0); + if (p < 0) { + r = -r; + } + d[l] = e[l] / (p + r); + d[l+1] = e[l] * (p + r); + dl1 = d[l+1]; + h = g - d[l]; + for (i = l+2; i < n; i++) { + d[i] -= h; + } + f = f + h; + + // Implicit QL transformation. + + p = d[m]; + c = 1.0; + c2 = c; + c3 = c; + el1 = e[l+1]; + s = 0.0; + s2 = 0.0; + for (i = m-1; i >= l; i--) { + c3 = c2; + c2 = c; + s2 = s; + g = c * e[i]; + h = c * p; + r = hypot2(p,e[i]); + e[i+1] = s * r; + s = e[i] / r; + c = p / r; + p = c * d[i] - s * g; + d[i+1] = h + s * (c * g + s * d[i]); + + // Accumulate transformation. + + for (k = 0; k < n; k++) { + h = V[k][i+1]; + V[k][i+1] = s * V[k][i] + c * h; + V[k][i] = c * V[k][i] - s * h; + } + } + p = -s * s2 * c3 * el1 * e[l] / dl1; + e[l] = s * p; + d[l] = c * p; + + // Check for convergence. + + } while (fabs(e[l]) > eps*tst1); + } + d[l] = d[l] + f; + e[l] = 0.0; + } + + // Sort eigenvalues and corresponding vectors. + + for (i = 0; i < n-1; i++) { + k = i; + p = d[i]; + for (j = i+1; j < n; j++) { + if (d[j] < p) { + k = j; + p = d[j]; + } + } + if (k != i) { + d[k] = d[i]; + d[i] = p; + for (j = 0; j < n; j++) { + p = V[j][i]; + V[j][i] = V[j][k]; + V[j][k] = p; + } + } + } +} + +void eigen_decomposition(double A[n][n], double V[n][n], double d[n]) { + int i,j; + double e[n]; + for (i = 0; i < n; i++) { + for (j = 0; j < n; j++) { + V[i][j] = A[i][j]; + } + } + tred2(V, d, e); + tql2(V, d, e); +} diff --git a/navigations/amcl/src/amcl/pf/pf.c b/navigations/amcl/src/amcl/pf/pf.c new file mode 100755 index 0000000..2e0b44b --- /dev/null +++ b/navigations/amcl/src/amcl/pf/pf.c @@ -0,0 +1,763 @@ +/* + * Player - One Hell of a Robot Server + * Copyright (C) 2000 Brian Gerkey & Kasper Stoy + * gerkey@usc.edu kaspers@robotics.usc.edu + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + * + */ +/************************************************************************** + * Desc: Simple particle filter for localization. + * Author: Andrew Howard + * Date: 10 Dec 2002 + * CVS: $Id: pf.c 6345 2008-04-17 01:36:39Z gerkey $ + *************************************************************************/ + +#include +#include +#include +#include + +#include "amcl/pf/pf.h" +#include "amcl/pf/pf_pdf.h" +#include "amcl/pf/pf_kdtree.h" +#include "portable_utils.hpp" + + +// Compute the required number of samples, given that there are k bins +// with samples in them. +static int pf_resample_limit(pf_t *pf, int k); + + + +// Create a new filter +pf_t *pf_alloc(int min_samples, int max_samples, + double alpha_slow, double alpha_fast, + pf_init_model_fn_t random_pose_fn, void *random_pose_data) +{ + int i, j; + pf_t *pf; + pf_sample_set_t *set; + pf_sample_t *sample; + + srand48(time(NULL)); + + pf = calloc(1, sizeof(pf_t)); + + pf->random_pose_fn = random_pose_fn; + pf->random_pose_data = random_pose_data; + + pf->min_samples = min_samples; + pf->max_samples = max_samples; + + // Control parameters for the population size calculation. [err] is + // the max error between the true distribution and the estimated + // distribution. [z] is the upper standard normal quantile for (1 - + // p), where p is the probability that the error on the estimated + // distrubition will be less than [err]. + pf->pop_err = 0.01; + pf->pop_z = 3; + pf->dist_threshold = 0.5; + + // Number of leaf nodes is never higher than the max number of samples + pf->limit_cache = calloc(max_samples, sizeof(int)); + + pf->current_set = 0; + for (j = 0; j < 2; j++) + { + set = pf->sets + j; + + set->sample_count = max_samples; + set->samples = calloc(max_samples, sizeof(pf_sample_t)); + + for (i = 0; i < set->sample_count; i++) + { + sample = set->samples + i; + sample->pose.v[0] = 0.0; + sample->pose.v[1] = 0.0; + sample->pose.v[2] = 0.0; + sample->weight = 1.0 / max_samples; + } + + // HACK: is 3 times max_samples enough? + set->kdtree = pf_kdtree_alloc(3 * max_samples); + + set->cluster_count = 0; + set->cluster_max_count = max_samples; + set->clusters = calloc(set->cluster_max_count, sizeof(pf_cluster_t)); + + set->mean = pf_vector_zero(); + set->cov = pf_matrix_zero(); + } + + pf->w_slow = 0.0; + pf->w_fast = 0.0; + + pf->alpha_slow = alpha_slow; + pf->alpha_fast = alpha_fast; + + //set converged to 0 + pf_init_converged(pf); + + return pf; +} + +// Free an existing filter +void pf_free(pf_t *pf) +{ + int i; + + free(pf->limit_cache); + + for (i = 0; i < 2; i++) + { + free(pf->sets[i].clusters); + pf_kdtree_free(pf->sets[i].kdtree); + free(pf->sets[i].samples); + } + free(pf); + + return; +} + +// Initialize the filter using a gaussian +void pf_init(pf_t *pf, pf_vector_t mean, pf_matrix_t cov) +{ + int i; + pf_sample_set_t *set; + pf_sample_t *sample; + pf_pdf_gaussian_t *pdf; + + set = pf->sets + pf->current_set; + + // Create the kd tree for adaptive sampling + pf_kdtree_clear(set->kdtree); + + set->sample_count = pf->max_samples; + + pdf = pf_pdf_gaussian_alloc(mean, cov); + + // Compute the new sample poses + for (i = 0; i < set->sample_count; i++) + { + sample = set->samples + i; + sample->weight = 1.0 / pf->max_samples; + sample->pose = pf_pdf_gaussian_sample(pdf); + + // Add sample to histogram + pf_kdtree_insert(set->kdtree, sample->pose, sample->weight); + } + + pf->w_slow = pf->w_fast = 0.0; + + pf_pdf_gaussian_free(pdf); + + // Re-compute cluster statistics + pf_cluster_stats(pf, set); + + //set converged to 0 + pf_init_converged(pf); + + return; +} + + +// Initialize the filter using some model +void pf_init_model(pf_t *pf, pf_init_model_fn_t init_fn, void *init_data) +{ + int i; + pf_sample_set_t *set; + pf_sample_t *sample; + + set = pf->sets + pf->current_set; + + // Create the kd tree for adaptive sampling + pf_kdtree_clear(set->kdtree); + + set->sample_count = pf->max_samples; + + // Compute the new sample poses + for (i = 0; i < set->sample_count; i++) + { + sample = set->samples + i; + sample->weight = 1.0 / pf->max_samples; + sample->pose = (*init_fn) (init_data); + + // Add sample to histogram + pf_kdtree_insert(set->kdtree, sample->pose, sample->weight); + } + + pf->w_slow = pf->w_fast = 0.0; + + // Re-compute cluster statistics + pf_cluster_stats(pf, set); + + //set converged to 0 + pf_init_converged(pf); + + return; +} + +void pf_init_converged(pf_t *pf){ + pf_sample_set_t *set; + set = pf->sets + pf->current_set; + set->converged = 0; + pf->converged = 0; +} + +int pf_update_converged(pf_t *pf) +{ + int i; + pf_sample_set_t *set; + pf_sample_t *sample; + double total; + + set = pf->sets + pf->current_set; + double mean_x = 0, mean_y = 0; + + for (i = 0; i < set->sample_count; i++){ + sample = set->samples + i; + + mean_x += sample->pose.v[0]; + mean_y += sample->pose.v[1]; + } + mean_x /= set->sample_count; + mean_y /= set->sample_count; + + for (i = 0; i < set->sample_count; i++){ + sample = set->samples + i; + if(fabs(sample->pose.v[0] - mean_x) > pf->dist_threshold || + fabs(sample->pose.v[1] - mean_y) > pf->dist_threshold){ + set->converged = 0; + pf->converged = 0; + return 0; + } + } + set->converged = 1; + pf->converged = 1; + return 1; +} + +// Update the filter with some new action +void pf_update_action(pf_t *pf, pf_action_model_fn_t action_fn, void *action_data) +{ + pf_sample_set_t *set; + + set = pf->sets + pf->current_set; + + (*action_fn) (action_data, set); + + return; +} + + +#include +// Update the filter with some new sensor observation +void pf_update_sensor(pf_t *pf, pf_sensor_model_fn_t sensor_fn, void *sensor_data) +{ + int i; + pf_sample_set_t *set; + pf_sample_t *sample; + double total; + + set = pf->sets + pf->current_set; + + // Compute the sample weights + total = (*sensor_fn) (sensor_data, set); + + set->n_effective = 0; + + if (total > 0.0) + { + // Normalize weights + double w_avg=0.0; + for (i = 0; i < set->sample_count; i++) + { + sample = set->samples + i; + w_avg += sample->weight; + sample->weight /= total; + set->n_effective += sample->weight*sample->weight; + } + // Update running averages of likelihood of samples (Prob Rob p258) + w_avg /= set->sample_count; + if(pf->w_slow == 0.0) + pf->w_slow = w_avg; + else + pf->w_slow += pf->alpha_slow * (w_avg - pf->w_slow); + if(pf->w_fast == 0.0) + pf->w_fast = w_avg; + else + pf->w_fast += pf->alpha_fast * (w_avg - pf->w_fast); + //printf("w_avg: %e slow: %e fast: %e\n", + //w_avg, pf->w_slow, pf->w_fast); + } + else + { + // Handle zero total + for (i = 0; i < set->sample_count; i++) + { + sample = set->samples + i; + sample->weight = 1.0 / set->sample_count; + } + } + + set->n_effective = 1.0/set->n_effective; + return; +} + +// copy set a to set b +void copy_set(pf_sample_set_t* set_a, pf_sample_set_t* set_b) +{ + int i; + double total; + pf_sample_t *sample_a, *sample_b; + + // Clean set b's kdtree + pf_kdtree_clear(set_b->kdtree); + + // Copy samples from set a to create set b + total = 0; + set_b->sample_count = 0; + + for(i = 0; i < set_a->sample_count; i++) + { + sample_b = set_b->samples + set_b->sample_count++; + + sample_a = set_a->samples + i; + + assert(sample_a->weight > 0); + + // Copy sample a to sample b + sample_b->pose = sample_a->pose; + sample_b->weight = sample_a->weight; + + total += sample_b->weight; + + // Add sample to histogram + pf_kdtree_insert(set_b->kdtree, sample_b->pose, sample_b->weight); + } + + // Normalize weights + for (i = 0; i < set_b->sample_count; i++) + { + sample_b = set_b->samples + i; + sample_b->weight /= total; + } + + set_b->converged = set_a->converged; +} + +// Resample the distribution +void pf_update_resample(pf_t *pf) +{ + int i; + double total; + pf_sample_set_t *set_a, *set_b; + pf_sample_t *sample_a, *sample_b; + + //double r,c,U; + //int m; + //double count_inv; + double* c; + + double w_diff; + + set_a = pf->sets + pf->current_set; + set_b = pf->sets + (pf->current_set + 1) % 2; + + if (pf->selective_resampling != 0) + { + if (set_a->n_effective > 0.5*(set_a->sample_count)) + { + // copy set a to b + copy_set(set_a,set_b); + + // Re-compute cluster statistics + pf_cluster_stats(pf, set_b); + + // Use the newly created sample set + pf->current_set = (pf->current_set + 1) % 2; + return; + } + } + + // Build up cumulative probability table for resampling. + // TODO: Replace this with a more efficient procedure + // (e.g., http://www.network-theory.co.uk/docs/gslref/GeneralDiscreteDistributions.html) + c = (double*)malloc(sizeof(double)*(set_a->sample_count+1)); + c[0] = 0.0; + for(i=0;isample_count;i++) + c[i+1] = c[i]+set_a->samples[i].weight; + + // Create the kd tree for adaptive sampling + pf_kdtree_clear(set_b->kdtree); + + // Draw samples from set a to create set b. + total = 0; + set_b->sample_count = 0; + + w_diff = 1.0 - pf->w_fast / pf->w_slow; + if(w_diff < 0.0) + w_diff = 0.0; + //printf("w_diff: %9.6f\n", w_diff); + + // Can't (easily) combine low-variance sampler with KLD adaptive + // sampling, so we'll take the more traditional route. + /* + // Low-variance resampler, taken from Probabilistic Robotics, p110 + count_inv = 1.0/set_a->sample_count; + r = drand48() * count_inv; + c = set_a->samples[0].weight; + i = 0; + m = 0; + */ + while(set_b->sample_count < pf->max_samples) + { + sample_b = set_b->samples + set_b->sample_count++; + + if(drand48() < w_diff) + sample_b->pose = (pf->random_pose_fn)(pf->random_pose_data); + else + { + // Can't (easily) combine low-variance sampler with KLD adaptive + // sampling, so we'll take the more traditional route. + /* + // Low-variance resampler, taken from Probabilistic Robotics, p110 + U = r + m * count_inv; + while(U>c) + { + i++; + // Handle wrap-around by resetting counters and picking a new random + // number + if(i >= set_a->sample_count) + { + r = drand48() * count_inv; + c = set_a->samples[0].weight; + i = 0; + m = 0; + U = r + m * count_inv; + continue; + } + c += set_a->samples[i].weight; + } + m++; + */ + + // Naive discrete event sampler + double r; + r = drand48(); + for(i=0;isample_count;i++) + { + if((c[i] <= r) && (r < c[i+1])) + break; + } + assert(isample_count); + + sample_a = set_a->samples + i; + + assert(sample_a->weight > 0); + + // Add sample to list + sample_b->pose = sample_a->pose; + } + + sample_b->weight = 1.0; + total += sample_b->weight; + + // Add sample to histogram + pf_kdtree_insert(set_b->kdtree, sample_b->pose, sample_b->weight); + + // See if we have enough samples yet + if (set_b->sample_count > pf_resample_limit(pf, set_b->kdtree->leaf_count)) + break; + } + + // Reset averages, to avoid spiraling off into complete randomness. + if(w_diff > 0.0) + pf->w_slow = pf->w_fast = 0.0; + + //fprintf(stderr, "\n\n"); + + // Normalize weights + for (i = 0; i < set_b->sample_count; i++) + { + sample_b = set_b->samples + i; + sample_b->weight /= total; + } + + // Re-compute cluster statistics + pf_cluster_stats(pf, set_b); + + // Use the newly created sample set + pf->current_set = (pf->current_set + 1) % 2; + + pf_update_converged(pf); + + free(c); + return; +} + + +// Compute the required number of samples, given that there are k bins +// with samples in them. This is taken directly from Fox et al. +int pf_resample_limit(pf_t *pf, int k) +{ + double a, b, c, x; + int n; + + // Return max_samples in case k is outside expected range, this shouldn't + // happen, but is added to prevent any runtime errors + if (k < 1 || k > pf->max_samples) + return pf->max_samples; + + // Return value if cache is valid, which means value is non-zero positive + if (pf->limit_cache[k-1] > 0) + return pf->limit_cache[k-1]; + + if (k == 1) + { + pf->limit_cache[k-1] = pf->max_samples; + return pf->max_samples; + } + + a = 1; + b = 2 / (9 * ((double) k - 1)); + c = sqrt(2 / (9 * ((double) k - 1))) * pf->pop_z; + x = a - b + c; + + n = (int) ceil((k - 1) / (2 * pf->pop_err) * x * x * x); + + if (n < pf->min_samples) + { + pf->limit_cache[k-1] = pf->min_samples; + return pf->min_samples; + } + if (n > pf->max_samples) + { + pf->limit_cache[k-1] = pf->max_samples; + return pf->max_samples; + } + + pf->limit_cache[k-1] = n; + return n; +} + + +// Re-compute the cluster statistics for a sample set +void pf_cluster_stats(pf_t *pf, pf_sample_set_t *set) +{ + int i, j, k, cidx; + pf_sample_t *sample; + pf_cluster_t *cluster; + + // Workspace + double m[4], c[2][2]; + size_t count; + double weight; + + // Cluster the samples + pf_kdtree_cluster(set->kdtree); + + // Initialize cluster stats + set->cluster_count = 0; + + for (i = 0; i < set->cluster_max_count; i++) + { + cluster = set->clusters + i; + cluster->count = 0; + cluster->weight = 0; + cluster->mean = pf_vector_zero(); + cluster->cov = pf_matrix_zero(); + + for (j = 0; j < 4; j++) + cluster->m[j] = 0.0; + for (j = 0; j < 2; j++) + for (k = 0; k < 2; k++) + cluster->c[j][k] = 0.0; + } + + // Initialize overall filter stats + count = 0; + weight = 0.0; + set->mean = pf_vector_zero(); + set->cov = pf_matrix_zero(); + for (j = 0; j < 4; j++) + m[j] = 0.0; + for (j = 0; j < 2; j++) + for (k = 0; k < 2; k++) + c[j][k] = 0.0; + + // Compute cluster stats + for (i = 0; i < set->sample_count; i++) + { + sample = set->samples + i; + + //printf("%d %f %f %f\n", i, sample->pose.v[0], sample->pose.v[1], sample->pose.v[2]); + + // Get the cluster label for this sample + cidx = pf_kdtree_get_cluster(set->kdtree, sample->pose); + assert(cidx >= 0); + if (cidx >= set->cluster_max_count) + continue; + if (cidx + 1 > set->cluster_count) + set->cluster_count = cidx + 1; + + cluster = set->clusters + cidx; + + cluster->count += 1; + cluster->weight += sample->weight; + + count += 1; + weight += sample->weight; + + // Compute mean + cluster->m[0] += sample->weight * sample->pose.v[0]; + cluster->m[1] += sample->weight * sample->pose.v[1]; + cluster->m[2] += sample->weight * cos(sample->pose.v[2]); + cluster->m[3] += sample->weight * sin(sample->pose.v[2]); + + m[0] += sample->weight * sample->pose.v[0]; + m[1] += sample->weight * sample->pose.v[1]; + m[2] += sample->weight * cos(sample->pose.v[2]); + m[3] += sample->weight * sin(sample->pose.v[2]); + + // Compute covariance in linear components + for (j = 0; j < 2; j++) + for (k = 0; k < 2; k++) + { + cluster->c[j][k] += sample->weight * sample->pose.v[j] * sample->pose.v[k]; + c[j][k] += sample->weight * sample->pose.v[j] * sample->pose.v[k]; + } + } + + // Normalize + for (i = 0; i < set->cluster_count; i++) + { + cluster = set->clusters + i; + + cluster->mean.v[0] = cluster->m[0] / cluster->weight; + cluster->mean.v[1] = cluster->m[1] / cluster->weight; + cluster->mean.v[2] = atan2(cluster->m[3], cluster->m[2]); + + cluster->cov = pf_matrix_zero(); + + // Covariance in linear components + for (j = 0; j < 2; j++) + for (k = 0; k < 2; k++) + cluster->cov.m[j][k] = cluster->c[j][k] / cluster->weight - + cluster->mean.v[j] * cluster->mean.v[k]; + + // Covariance in angular components; I think this is the correct + // formula for circular statistics. + cluster->cov.m[2][2] = -2 * log(sqrt(cluster->m[2] * cluster->m[2] + + cluster->m[3] * cluster->m[3]) / cluster->weight); + + //printf("cluster %d %d %f (%f %f %f)\n", i, cluster->count, cluster->weight, + //cluster->mean.v[0], cluster->mean.v[1], cluster->mean.v[2]); + //pf_matrix_fprintf(cluster->cov, stdout, "%e"); + } + + assert(fabs(weight) >= DBL_EPSILON); + if (fabs(weight) < DBL_EPSILON) + { + printf("ERROR : divide-by-zero exception : weight is zero\n"); + return; + } + // Compute overall filter stats + set->mean.v[0] = m[0] / weight; + set->mean.v[1] = m[1] / weight; + set->mean.v[2] = atan2(m[3], m[2]); + + // Covariance in linear components + for (j = 0; j < 2; j++) + for (k = 0; k < 2; k++) + set->cov.m[j][k] = c[j][k] / weight - set->mean.v[j] * set->mean.v[k]; + + // Covariance in angular components; I think this is the correct + // formula for circular statistics. + set->cov.m[2][2] = -2 * log(sqrt(m[2] * m[2] + m[3] * m[3])); + + return; +} + +void pf_set_selective_resampling(pf_t *pf, int selective_resampling) +{ + pf->selective_resampling = selective_resampling; +} + +// Compute the CEP statistics (mean and variance). +void pf_get_cep_stats(pf_t *pf, pf_vector_t *mean, double *var) +{ + int i; + double mn, mx, my, mrr; + pf_sample_set_t *set; + pf_sample_t *sample; + + set = pf->sets + pf->current_set; + + mn = 0.0; + mx = 0.0; + my = 0.0; + mrr = 0.0; + + for (i = 0; i < set->sample_count; i++) + { + sample = set->samples + i; + + mn += sample->weight; + mx += sample->weight * sample->pose.v[0]; + my += sample->weight * sample->pose.v[1]; + mrr += sample->weight * sample->pose.v[0] * sample->pose.v[0]; + mrr += sample->weight * sample->pose.v[1] * sample->pose.v[1]; + } + + assert(fabs(mn) >= DBL_EPSILON); + if (fabs(mn) < DBL_EPSILON) + { + printf("ERROR : divide-by-zero exception : mn is zero\n"); + return; + } + + mean->v[0] = mx / mn; + mean->v[1] = my / mn; + mean->v[2] = 0.0; + + *var = mrr / mn - (mx * mx / (mn * mn) + my * my / (mn * mn)); + + return; +} + + +// Get the statistics for a particular cluster. +int pf_get_cluster_stats(pf_t *pf, int clabel, double *weight, + pf_vector_t *mean, pf_matrix_t *cov) +{ + pf_sample_set_t *set; + pf_cluster_t *cluster; + + set = pf->sets + pf->current_set; + + if (clabel >= set->cluster_count) + return 0; + cluster = set->clusters + clabel; + + *weight = cluster->weight; + *mean = cluster->mean; + *cov = cluster->cov; + + return 1; +} + + diff --git a/navigations/amcl/src/amcl/pf/pf_draw.c b/navigations/amcl/src/amcl/pf/pf_draw.c new file mode 100755 index 0000000..0c445af --- /dev/null +++ b/navigations/amcl/src/amcl/pf/pf_draw.c @@ -0,0 +1,163 @@ +/* + * Player - One Hell of a Robot Server + * Copyright (C) 2000 Brian Gerkey & Kasper Stoy + * gerkey@usc.edu kaspers@robotics.usc.edu + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + * + */ +/************************************************************************** + * Desc: Particle filter; drawing routines + * Author: Andrew Howard + * Date: 10 Dec 2002 + * CVS: $Id: pf_draw.c 7057 2008-10-02 00:44:06Z gbiggs $ + *************************************************************************/ + +#ifdef INCLUDE_RTKGUI + +#include +#include +#include + + +#include "rtk.h" + +#include "pf.h" +#include "pf_pdf.h" +#include "pf_kdtree.h" + + +// Draw the statistics +void pf_draw_statistics(pf_t *pf, rtk_fig_t *fig); + + +// Draw the sample set +void pf_draw_samples(pf_t *pf, rtk_fig_t *fig, int max_samples) +{ + int i; + double px, py, pa; + pf_sample_set_t *set; + pf_sample_t *sample; + + set = pf->sets + pf->current_set; + max_samples = MIN(max_samples, set->sample_count); + + for (i = 0; i < max_samples; i++) + { + sample = set->samples + i; + + px = sample->pose.v[0]; + py = sample->pose.v[1]; + pa = sample->pose.v[2]; + + //printf("%f %f\n", px, py); + + rtk_fig_point(fig, px, py); + rtk_fig_arrow(fig, px, py, pa, 0.1, 0.02); + //rtk_fig_rectangle(fig, px, py, 0, 0.1, 0.1, 0); + } + + return; +} + + +// Draw the hitogram (kd tree) +void pf_draw_hist(pf_t *pf, rtk_fig_t *fig) +{ + pf_sample_set_t *set; + + set = pf->sets + pf->current_set; + + rtk_fig_color(fig, 0.0, 0.0, 1.0); + pf_kdtree_draw(set->kdtree, fig); + + return; +} + + +// Draw the CEP statistics +void pf_draw_cep_stats(pf_t *pf, rtk_fig_t *fig) +{ + pf_vector_t mean; + double var; + + pf_get_cep_stats(pf, &mean, &var); + var = sqrt(var); + + rtk_fig_color(fig, 0, 0, 1); + rtk_fig_ellipse(fig, mean.v[0], mean.v[1], mean.v[2], 3 * var, 3 * var, 0); + + return; +} + + +// Draw the cluster statistics +void pf_draw_cluster_stats(pf_t *pf, rtk_fig_t *fig) +{ + int i; + pf_cluster_t *cluster; + pf_sample_set_t *set; + pf_vector_t mean; + pf_matrix_t cov; + pf_matrix_t r, d; + double weight, o, d1, d2; + + set = pf->sets + pf->current_set; + + for (i = 0; i < set->cluster_count; i++) + { + cluster = set->clusters + i; + + weight = cluster->weight; + mean = cluster->mean; + cov = cluster->cov; + + // Compute unitary representation S = R D R^T + pf_matrix_unitary(&r, &d, cov); + + /* Debugging + printf("mean = \n"); + pf_vector_fprintf(mean, stdout, "%e"); + printf("cov = \n"); + pf_matrix_fprintf(cov, stdout, "%e"); + printf("r = \n"); + pf_matrix_fprintf(r, stdout, "%e"); + printf("d = \n"); + pf_matrix_fprintf(d, stdout, "%e"); + */ + + // Compute the orientation of the error ellipse (first eigenvector) + o = atan2(r.m[1][0], r.m[0][0]); + d1 = 6 * sqrt(d.m[0][0]); + d2 = 6 * sqrt(d.m[1][1]); + + if (d1 > 1e-3 && d2 > 1e-3) + { + // Draw the error ellipse + rtk_fig_ellipse(fig, mean.v[0], mean.v[1], o, d1, d2, 0); + rtk_fig_line_ex(fig, mean.v[0], mean.v[1], o, d1); + rtk_fig_line_ex(fig, mean.v[0], mean.v[1], o + M_PI / 2, d2); + } + + // Draw a direction indicator + rtk_fig_arrow(fig, mean.v[0], mean.v[1], mean.v[2], 0.50, 0.10); + rtk_fig_arrow(fig, mean.v[0], mean.v[1], mean.v[2] + 3 * sqrt(cov.m[2][2]), 0.50, 0.10); + rtk_fig_arrow(fig, mean.v[0], mean.v[1], mean.v[2] - 3 * sqrt(cov.m[2][2]), 0.50, 0.10); + } + + return; +} + +#endif diff --git a/navigations/amcl/src/amcl/pf/pf_kdtree.c b/navigations/amcl/src/amcl/pf/pf_kdtree.c new file mode 100755 index 0000000..b625b83 --- /dev/null +++ b/navigations/amcl/src/amcl/pf/pf_kdtree.c @@ -0,0 +1,486 @@ +/* + * Player - One Hell of a Robot Server + * Copyright (C) 2000 Brian Gerkey & Kasper Stoy + * gerkey@usc.edu kaspers@robotics.usc.edu + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + * + */ +/************************************************************************** + * Desc: kd-tree functions + * Author: Andrew Howard + * Date: 18 Dec 2002 + * CVS: $Id: pf_kdtree.c 7057 2008-10-02 00:44:06Z gbiggs $ + *************************************************************************/ + +#include +#include +#include +#include + + +#include "amcl/pf/pf_vector.h" +#include "amcl/pf/pf_kdtree.h" + + +// Compare keys to see if they are equal +static int pf_kdtree_equal(pf_kdtree_t *self, int key_a[], int key_b[]); + +// Insert a node into the tree +static pf_kdtree_node_t *pf_kdtree_insert_node(pf_kdtree_t *self, pf_kdtree_node_t *parent, + pf_kdtree_node_t *node, int key[], double value); + +// Recursive node search +static pf_kdtree_node_t *pf_kdtree_find_node(pf_kdtree_t *self, pf_kdtree_node_t *node, int key[]); + +// Recursively label nodes in this cluster +static void pf_kdtree_cluster_node(pf_kdtree_t *self, pf_kdtree_node_t *node, int depth); + +// Recursive node printing +//static void pf_kdtree_print_node(pf_kdtree_t *self, pf_kdtree_node_t *node); + + +#ifdef INCLUDE_RTKGUI + +// Recursively draw nodes +static void pf_kdtree_draw_node(pf_kdtree_t *self, pf_kdtree_node_t *node, rtk_fig_t *fig); + +#endif + + + +//////////////////////////////////////////////////////////////////////////////// +// Create a tree +pf_kdtree_t *pf_kdtree_alloc(int max_size) +{ + pf_kdtree_t *self; + + self = calloc(1, sizeof(pf_kdtree_t)); + + self->size[0] = 0.50; + self->size[1] = 0.50; + self->size[2] = (10 * M_PI / 180); + + self->root = NULL; + + self->node_count = 0; + self->node_max_count = max_size; + self->nodes = calloc(self->node_max_count, sizeof(pf_kdtree_node_t)); + + self->leaf_count = 0; + + return self; +} + + +//////////////////////////////////////////////////////////////////////////////// +// Destroy a tree +void pf_kdtree_free(pf_kdtree_t *self) +{ + free(self->nodes); + free(self); + return; +} + + +//////////////////////////////////////////////////////////////////////////////// +// Clear all entries from the tree +void pf_kdtree_clear(pf_kdtree_t *self) +{ + self->root = NULL; + self->leaf_count = 0; + self->node_count = 0; + + return; +} + + +//////////////////////////////////////////////////////////////////////////////// +// Insert a pose into the tree. +void pf_kdtree_insert(pf_kdtree_t *self, pf_vector_t pose, double value) +{ + int key[3]; + + key[0] = floor(pose.v[0] / self->size[0]); + key[1] = floor(pose.v[1] / self->size[1]); + key[2] = floor(pose.v[2] / self->size[2]); + + self->root = pf_kdtree_insert_node(self, NULL, self->root, key, value); + + // Test code + /* + printf("find %d %d %d\n", key[0], key[1], key[2]); + assert(pf_kdtree_find_node(self, self->root, key) != NULL); + + pf_kdtree_print_node(self, self->root); + + printf("\n"); + + for (i = 0; i < self->node_count; i++) + { + node = self->nodes + i; + if (node->leaf) + { + printf("find %d %d %d\n", node->key[0], node->key[1], node->key[2]); + assert(pf_kdtree_find_node(self, self->root, node->key) == node); + } + } + printf("\n\n"); + */ + + return; +} + + +//////////////////////////////////////////////////////////////////////////////// +// Determine the probability estimate for the given pose. TODO: this +// should do a kernel density estimate rather than a simple histogram. +double pf_kdtree_get_prob(pf_kdtree_t *self, pf_vector_t pose) +{ + int key[3]; + pf_kdtree_node_t *node; + + key[0] = floor(pose.v[0] / self->size[0]); + key[1] = floor(pose.v[1] / self->size[1]); + key[2] = floor(pose.v[2] / self->size[2]); + + node = pf_kdtree_find_node(self, self->root, key); + if (node == NULL) + return 0.0; + return node->value; +} + + +//////////////////////////////////////////////////////////////////////////////// +// Determine the cluster label for the given pose +int pf_kdtree_get_cluster(pf_kdtree_t *self, pf_vector_t pose) +{ + int key[3]; + pf_kdtree_node_t *node; + + key[0] = floor(pose.v[0] / self->size[0]); + key[1] = floor(pose.v[1] / self->size[1]); + key[2] = floor(pose.v[2] / self->size[2]); + + node = pf_kdtree_find_node(self, self->root, key); + if (node == NULL) + return -1; + return node->cluster; +} + + +//////////////////////////////////////////////////////////////////////////////// +// Compare keys to see if they are equal +int pf_kdtree_equal(pf_kdtree_t *self, int key_a[], int key_b[]) +{ + //double a, b; + + if (key_a[0] != key_b[0]) + return 0; + if (key_a[1] != key_b[1]) + return 0; + + if (key_a[2] != key_b[2]) + return 0; + + /* TODO: make this work (pivot selection needs fixing, too) + // Normalize angles + a = key_a[2] * self->size[2]; + a = atan2(sin(a), cos(a)) / self->size[2]; + b = key_b[2] * self->size[2]; + b = atan2(sin(b), cos(b)) / self->size[2]; + + if ((int) a != (int) b) + return 0; + */ + + return 1; +} + + +//////////////////////////////////////////////////////////////////////////////// +// Insert a node into the tree +pf_kdtree_node_t *pf_kdtree_insert_node(pf_kdtree_t *self, pf_kdtree_node_t *parent, + pf_kdtree_node_t *node, int key[], double value) +{ + int i; + int split, max_split; + + // If the node doesnt exist yet... + if (node == NULL) + { + assert(self->node_count < self->node_max_count); + node = self->nodes + self->node_count++; + memset(node, 0, sizeof(pf_kdtree_node_t)); + + node->leaf = 1; + + if (parent == NULL) + node->depth = 0; + else + node->depth = parent->depth + 1; + + for (i = 0; i < 3; i++) + node->key[i] = key[i]; + + node->value = value; + self->leaf_count += 1; + } + + // If the node exists, and it is a leaf node... + else if (node->leaf) + { + // If the keys are equal, increment the value + if (pf_kdtree_equal(self, key, node->key)) + { + node->value += value; + } + + // The keys are not equal, so split this node + else + { + // Find the dimension with the largest variance and do a mean + // split + max_split = 0; + node->pivot_dim = -1; + for (i = 0; i < 3; i++) + { + split = abs(key[i] - node->key[i]); + if (split > max_split) + { + max_split = split; + node->pivot_dim = i; + } + } + assert(node->pivot_dim >= 0); + + node->pivot_value = (key[node->pivot_dim] + node->key[node->pivot_dim]) / 2.0; + + if (key[node->pivot_dim] < node->pivot_value) + { + node->children[0] = pf_kdtree_insert_node(self, node, NULL, key, value); + node->children[1] = pf_kdtree_insert_node(self, node, NULL, node->key, node->value); + } + else + { + node->children[0] = pf_kdtree_insert_node(self, node, NULL, node->key, node->value); + node->children[1] = pf_kdtree_insert_node(self, node, NULL, key, value); + } + + node->leaf = 0; + self->leaf_count -= 1; + } + } + + // If the node exists, and it has children... + else + { + assert(node->children[0] != NULL); + assert(node->children[1] != NULL); + + if (key[node->pivot_dim] < node->pivot_value) + pf_kdtree_insert_node(self, node, node->children[0], key, value); + else + pf_kdtree_insert_node(self, node, node->children[1], key, value); + } + + return node; +} + + +//////////////////////////////////////////////////////////////////////////////// +// Recursive node search +pf_kdtree_node_t *pf_kdtree_find_node(pf_kdtree_t *self, pf_kdtree_node_t *node, int key[]) +{ + if (node->leaf) + { + //printf("find : leaf %p %d %d %d\n", node, node->key[0], node->key[1], node->key[2]); + + // If the keys are the same... + if (pf_kdtree_equal(self, key, node->key)) + return node; + else + return NULL; + } + else + { + //printf("find : brch %p %d %f\n", node, node->pivot_dim, node->pivot_value); + + assert(node->children[0] != NULL); + assert(node->children[1] != NULL); + + // If the keys are different... + if (key[node->pivot_dim] < node->pivot_value) + return pf_kdtree_find_node(self, node->children[0], key); + else + return pf_kdtree_find_node(self, node->children[1], key); + } + + return NULL; +} + + +//////////////////////////////////////////////////////////////////////////////// +// Recursive node printing +/* +void pf_kdtree_print_node(pf_kdtree_t *self, pf_kdtree_node_t *node) +{ + if (node->leaf) + { + printf("(%+02d %+02d %+02d)\n", node->key[0], node->key[1], node->key[2]); + printf("%*s", node->depth * 11, ""); + } + else + { + printf("(%+02d %+02d %+02d) ", node->key[0], node->key[1], node->key[2]); + pf_kdtree_print_node(self, node->children[0]); + pf_kdtree_print_node(self, node->children[1]); + } + return; +} +*/ + + +//////////////////////////////////////////////////////////////////////////////// +// Cluster the leaves in the tree +void pf_kdtree_cluster(pf_kdtree_t *self) +{ + int i; + int queue_count, cluster_count; + pf_kdtree_node_t **queue, *node; + + queue_count = 0; + queue = calloc(self->node_count, sizeof(queue[0])); + + // Put all the leaves in a queue + for (i = 0; i < self->node_count; i++) + { + node = self->nodes + i; + if (node->leaf) + { + node->cluster = -1; + assert(queue_count < self->node_count); + queue[queue_count++] = node; + + // TESTING; remove + assert(node == pf_kdtree_find_node(self, self->root, node->key)); + } + } + + cluster_count = 0; + + // Do connected components for each node + while (queue_count > 0) + { + node = queue[--queue_count]; + + // If this node has already been labelled, skip it + if (node->cluster >= 0) + continue; + + // Assign a label to this cluster + node->cluster = cluster_count++; + + // Recursively label nodes in this cluster + pf_kdtree_cluster_node(self, node, 0); + } + + free(queue); + return; +} + + +//////////////////////////////////////////////////////////////////////////////// +// Recursively label nodes in this cluster +void pf_kdtree_cluster_node(pf_kdtree_t *self, pf_kdtree_node_t *node, int depth) +{ + int i; + int nkey[3]; + pf_kdtree_node_t *nnode; + + for (i = 0; i < 3 * 3 * 3; i++) + { + nkey[0] = node->key[0] + (i / 9) - 1; + nkey[1] = node->key[1] + ((i % 9) / 3) - 1; + nkey[2] = node->key[2] + ((i % 9) % 3) - 1; + + nnode = pf_kdtree_find_node(self, self->root, nkey); + if (nnode == NULL) + continue; + + assert(nnode->leaf); + + // This node already has a label; skip it. The label should be + // consistent, however. + if (nnode->cluster >= 0) + { + assert(nnode->cluster == node->cluster); + continue; + } + + // Label this node and recurse + nnode->cluster = node->cluster; + + pf_kdtree_cluster_node(self, nnode, depth + 1); + } + return; +} + + + +#ifdef INCLUDE_RTKGUI + +//////////////////////////////////////////////////////////////////////////////// +// Draw the tree +void pf_kdtree_draw(pf_kdtree_t *self, rtk_fig_t *fig) +{ + if (self->root != NULL) + pf_kdtree_draw_node(self, self->root, fig); + return; +} + + +//////////////////////////////////////////////////////////////////////////////// +// Recursively draw nodes +void pf_kdtree_draw_node(pf_kdtree_t *self, pf_kdtree_node_t *node, rtk_fig_t *fig) +{ + double ox, oy; + char text[64]; + + if (node->leaf) + { + ox = (node->key[0] + 0.5) * self->size[0]; + oy = (node->key[1] + 0.5) * self->size[1]; + + rtk_fig_rectangle(fig, ox, oy, 0.0, self->size[0], self->size[1], 0); + + //snprintf(text, sizeof(text), "%0.3f", node->value); + //rtk_fig_text(fig, ox, oy, 0.0, text); + + snprintf(text, sizeof(text), "%d", node->cluster); + rtk_fig_text(fig, ox, oy, 0.0, text); + } + else + { + assert(node->children[0] != NULL); + assert(node->children[1] != NULL); + pf_kdtree_draw_node(self, node->children[0], fig); + pf_kdtree_draw_node(self, node->children[1], fig); + } + + return; +} + +#endif diff --git a/navigations/amcl/src/amcl/pf/pf_pdf.c b/navigations/amcl/src/amcl/pf/pf_pdf.c new file mode 100755 index 0000000..06310a5 --- /dev/null +++ b/navigations/amcl/src/amcl/pf/pf_pdf.c @@ -0,0 +1,147 @@ +/* + * Player - One Hell of a Robot Server + * Copyright (C) 2000 Brian Gerkey & Kasper Stoy + * gerkey@usc.edu kaspers@robotics.usc.edu + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + * + */ +/************************************************************************** + * Desc: Useful pdf functions + * Author: Andrew Howard + * Date: 10 Dec 2002 + * CVS: $Id: pf_pdf.c 6348 2008-04-17 02:53:17Z gerkey $ + *************************************************************************/ + +#include +#include +#include +#include +//#include +//#include + +#include "amcl/pf/pf_pdf.h" +#include "portable_utils.hpp" + +// Random number generator seed value +static unsigned int pf_pdf_seed; + + +/************************************************************************** + * Gaussian + *************************************************************************/ + +// Create a gaussian pdf +pf_pdf_gaussian_t *pf_pdf_gaussian_alloc(pf_vector_t x, pf_matrix_t cx) +{ + pf_matrix_t cd; + pf_pdf_gaussian_t *pdf; + + pdf = calloc(1, sizeof(pf_pdf_gaussian_t)); + + pdf->x = x; + pdf->cx = cx; + //pdf->cxi = pf_matrix_inverse(cx, &pdf->cxdet); + + // Decompose the convariance matrix into a rotation + // matrix and a diagonal matrix. + pf_matrix_unitary(&pdf->cr, &cd, pdf->cx); + pdf->cd.v[0] = sqrt(cd.m[0][0]); + pdf->cd.v[1] = sqrt(cd.m[1][1]); + pdf->cd.v[2] = sqrt(cd.m[2][2]); + + // Initialize the random number generator + //pdf->rng = gsl_rng_alloc(gsl_rng_taus); + //gsl_rng_set(pdf->rng, ++pf_pdf_seed); + srand48(++pf_pdf_seed); + + return pdf; +} + + +// Destroy the pdf +void pf_pdf_gaussian_free(pf_pdf_gaussian_t *pdf) +{ + //gsl_rng_free(pdf->rng); + free(pdf); + return; +} + + +/* +// Compute the value of the pdf at some point [x]. +double pf_pdf_gaussian_value(pf_pdf_gaussian_t *pdf, pf_vector_t x) +{ + int i, j; + pf_vector_t z; + double zz, p; + + z = pf_vector_sub(x, pdf->x); + + zz = 0; + for (i = 0; i < 3; i++) + for (j = 0; j < 3; j++) + zz += z.v[i] * pdf->cxi.m[i][j] * z.v[j]; + + p = 1 / (2 * M_PI * pdf->cxdet) * exp(-zz / 2); + + return p; +} +*/ + + +// Generate a sample from the pdf. +pf_vector_t pf_pdf_gaussian_sample(pf_pdf_gaussian_t *pdf) +{ + int i, j; + pf_vector_t r; + pf_vector_t x; + + // Generate a random vector + for (i = 0; i < 3; i++) + { + //r.v[i] = gsl_ran_gaussian(pdf->rng, pdf->cd.v[i]); + r.v[i] = pf_ran_gaussian(pdf->cd.v[i]); + } + + for (i = 0; i < 3; i++) + { + x.v[i] = pdf->x.v[i]; + for (j = 0; j < 3; j++) + x.v[i] += pdf->cr.m[i][j] * r.v[j]; + } + + return x; +} + +// Draw randomly from a zero-mean Gaussian distribution, with standard +// deviation sigma. +// We use the polar form of the Box-Muller transformation, explained here: +// http://www.taygeta.com/random/gaussian.html +double pf_ran_gaussian(double sigma) +{ + double x1, x2, w, r; + + do + { + do { r = drand48(); } while (r==0.0); + x1 = 2.0 * r - 1.0; + do { r = drand48(); } while (r==0.0); + x2 = 2.0 * r - 1.0; + w = x1*x1 + x2*x2; + } while(w > 1.0 || w==0.0); + + return(sigma * x2 * sqrt(-2.0*log(w)/w)); +} diff --git a/navigations/amcl/src/amcl/pf/pf_vector.c b/navigations/amcl/src/amcl/pf/pf_vector.c new file mode 100755 index 0000000..23d7ccb --- /dev/null +++ b/navigations/amcl/src/amcl/pf/pf_vector.c @@ -0,0 +1,276 @@ +/* + * Player - One Hell of a Robot Server + * Copyright (C) 2000 Brian Gerkey & Kasper Stoy + * gerkey@usc.edu kaspers@robotics.usc.edu + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + * + */ +/************************************************************************** + * Desc: Vector functions + * Author: Andrew Howard + * Date: 10 Dec 2002 + * CVS: $Id: pf_vector.c 6345 2008-04-17 01:36:39Z gerkey $ + *************************************************************************/ + +#include +//#include +//#include +//#include + +#include "amcl/pf/pf_vector.h" +#include "amcl/pf/eig3.h" + + +// Return a zero vector +pf_vector_t pf_vector_zero() +{ + pf_vector_t c; + + c.v[0] = 0.0; + c.v[1] = 0.0; + c.v[2] = 0.0; + + return c; +} + + +// Check for NAN or INF in any component +int pf_vector_finite(pf_vector_t a) +{ + int i; + + for (i = 0; i < 3; i++) + if (!isfinite(a.v[i])) + return 0; + + return 1; +} + + +// Print a vector +void pf_vector_fprintf(pf_vector_t a, FILE *file, const char *fmt) +{ + int i; + + for (i = 0; i < 3; i++) + { + fprintf(file, fmt, a.v[i]); + fprintf(file, " "); + } + fprintf(file, "\n"); + + return; +} + + +// Simple vector addition +pf_vector_t pf_vector_add(pf_vector_t a, pf_vector_t b) +{ + pf_vector_t c; + + c.v[0] = a.v[0] + b.v[0]; + c.v[1] = a.v[1] + b.v[1]; + c.v[2] = a.v[2] + b.v[2]; + + return c; +} + + +// Simple vector subtraction +pf_vector_t pf_vector_sub(pf_vector_t a, pf_vector_t b) +{ + pf_vector_t c; + + c.v[0] = a.v[0] - b.v[0]; + c.v[1] = a.v[1] - b.v[1]; + c.v[2] = a.v[2] - b.v[2]; + + return c; +} + + +// Transform from local to global coords (a + b) +pf_vector_t pf_vector_coord_add(pf_vector_t a, pf_vector_t b) +{ + pf_vector_t c; + + c.v[0] = b.v[0] + a.v[0] * cos(b.v[2]) - a.v[1] * sin(b.v[2]); + c.v[1] = b.v[1] + a.v[0] * sin(b.v[2]) + a.v[1] * cos(b.v[2]); + c.v[2] = b.v[2] + a.v[2]; + c.v[2] = atan2(sin(c.v[2]), cos(c.v[2])); + + return c; +} + + +// Transform from global to local coords (a - b) +pf_vector_t pf_vector_coord_sub(pf_vector_t a, pf_vector_t b) +{ + pf_vector_t c; + + c.v[0] = +(a.v[0] - b.v[0]) * cos(b.v[2]) + (a.v[1] - b.v[1]) * sin(b.v[2]); + c.v[1] = -(a.v[0] - b.v[0]) * sin(b.v[2]) + (a.v[1] - b.v[1]) * cos(b.v[2]); + c.v[2] = a.v[2] - b.v[2]; + c.v[2] = atan2(sin(c.v[2]), cos(c.v[2])); + + return c; +} + + +// Return a zero matrix +pf_matrix_t pf_matrix_zero() +{ + int i, j; + pf_matrix_t c; + + for (i = 0; i < 3; i++) + for (j = 0; j < 3; j++) + c.m[i][j] = 0.0; + + return c; +} + + +// Check for NAN or INF in any component +int pf_matrix_finite(pf_matrix_t a) +{ + int i, j; + + for (i = 0; i < 3; i++) + for (j = 0; j < 3; j++) + if (!isfinite(a.m[i][j])) + return 0; + + return 1; +} + + +// Print a matrix +void pf_matrix_fprintf(pf_matrix_t a, FILE *file, const char *fmt) +{ + int i, j; + + for (i = 0; i < 3; i++) + { + for (j = 0; j < 3; j++) + { + fprintf(file, fmt, a.m[i][j]); + fprintf(file, " "); + } + fprintf(file, "\n"); + } + return; +} + + +/* +// Compute the matrix inverse +pf_matrix_t pf_matrix_inverse(pf_matrix_t a, double *det) +{ + double lndet; + int signum; + gsl_permutation *p; + gsl_matrix_view A, Ai; + + pf_matrix_t ai; + + A = gsl_matrix_view_array((double*) a.m, 3, 3); + Ai = gsl_matrix_view_array((double*) ai.m, 3, 3); + + // Do LU decomposition + p = gsl_permutation_alloc(3); + gsl_linalg_LU_decomp(&A.matrix, p, &signum); + + // Check for underflow + lndet = gsl_linalg_LU_lndet(&A.matrix); + if (lndet < -1000) + { + //printf("underflow in matrix inverse lndet = %f", lndet); + gsl_matrix_set_zero(&Ai.matrix); + } + else + { + // Compute inverse + gsl_linalg_LU_invert(&A.matrix, p, &Ai.matrix); + } + + gsl_permutation_free(p); + + if (det) + *det = exp(lndet); + + return ai; +} +*/ + + +// Decompose a covariance matrix [a] into a rotation matrix [r] and a diagonal +// matrix [d] such that a = r d r^T. +void pf_matrix_unitary(pf_matrix_t *r, pf_matrix_t *d, pf_matrix_t a) +{ + int i, j; + /* + gsl_matrix *aa; + gsl_vector *eval; + gsl_matrix *evec; + gsl_eigen_symmv_workspace *w; + + aa = gsl_matrix_alloc(3, 3); + eval = gsl_vector_alloc(3); + evec = gsl_matrix_alloc(3, 3); + */ + + double aa[3][3]; + double eval[3]; + double evec[3][3]; + + for (i = 0; i < 3; i++) + { + for (j = 0; j < 3; j++) + { + //gsl_matrix_set(aa, i, j, a.m[i][j]); + aa[i][j] = a.m[i][j]; + } + } + + // Compute eigenvectors/values + /* + w = gsl_eigen_symmv_alloc(3); + gsl_eigen_symmv(aa, eval, evec, w); + gsl_eigen_symmv_free(w); + */ + + eigen_decomposition(aa,evec,eval); + + *d = pf_matrix_zero(); + for (i = 0; i < 3; i++) + { + //d->m[i][i] = gsl_vector_get(eval, i); + d->m[i][i] = eval[i]; + for (j = 0; j < 3; j++) + { + //r->m[i][j] = gsl_matrix_get(evec, i, j); + r->m[i][j] = evec[i][j]; + } + } + + //gsl_matrix_free(evec); + //gsl_vector_free(eval); + //gsl_matrix_free(aa); + + return; +} + diff --git a/navigations/amcl/src/amcl/sensors/amcl_laser.cpp b/navigations/amcl/src/amcl/sensors/amcl_laser.cpp new file mode 100755 index 0000000..f8aa35c --- /dev/null +++ b/navigations/amcl/src/amcl/sensors/amcl_laser.cpp @@ -0,0 +1,510 @@ +/* + * Player - One Hell of a Robot Server + * Copyright (C) 2000 Brian Gerkey & Kasper Stoy + * gerkey@usc.edu kaspers@robotics.usc.edu + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + * + */ +/////////////////////////////////////////////////////////////////////////// +// +// Desc: AMCL laser routines +// Author: Andrew Howard +// Date: 6 Feb 2003 +// CVS: $Id: amcl_laser.cc 7057 2008-10-02 00:44:06Z gbiggs $ +// +/////////////////////////////////////////////////////////////////////////// + +#include // required by Darwin +#include +#include +#include +#ifdef HAVE_UNISTD_H +#include +#endif + +#include "amcl/sensors/amcl_laser.h" + +using namespace amcl; + +//////////////////////////////////////////////////////////////////////////////// +// Default constructor +AMCLLaser::AMCLLaser(size_t max_beams, map_t* map) : AMCLSensor(), + max_samples(0), max_obs(0), + temp_obs(NULL) +{ + this->time = 0.0; + + this->max_beams = max_beams; + this->map = map; + + return; +} + +AMCLLaser::~AMCLLaser() +{ + if(temp_obs){ + for(int k=0; k < max_samples; k++){ + delete [] temp_obs[k]; + } + delete []temp_obs; + } +} + +void +AMCLLaser::SetModelBeam(double z_hit, + double z_short, + double z_max, + double z_rand, + double sigma_hit, + double lambda_short, + double chi_outlier) +{ + this->model_type = LASER_MODEL_BEAM; + this->z_hit = z_hit; + this->z_short = z_short; + this->z_max = z_max; + this->z_rand = z_rand; + this->sigma_hit = sigma_hit; + this->lambda_short = lambda_short; + this->chi_outlier = chi_outlier; +} + +void +AMCLLaser::SetModelLikelihoodField(double z_hit, + double z_rand, + double sigma_hit, + double max_occ_dist) +{ + this->model_type = LASER_MODEL_LIKELIHOOD_FIELD; + this->z_hit = z_hit; + this->z_rand = z_rand; + this->sigma_hit = sigma_hit; + + map_update_cspace(this->map, max_occ_dist); +} + +void +AMCLLaser::SetModelLikelihoodFieldProb(double z_hit, + double z_rand, + double sigma_hit, + double max_occ_dist, + bool do_beamskip, + double beam_skip_distance, + double beam_skip_threshold, + double beam_skip_error_threshold) +{ + this->model_type = LASER_MODEL_LIKELIHOOD_FIELD_PROB; + this->z_hit = z_hit; + this->z_rand = z_rand; + this->sigma_hit = sigma_hit; + this->do_beamskip = do_beamskip; + this->beam_skip_distance = beam_skip_distance; + this->beam_skip_threshold = beam_skip_threshold; + this->beam_skip_error_threshold = beam_skip_error_threshold; + map_update_cspace(this->map, max_occ_dist); +} + + +//////////////////////////////////////////////////////////////////////////////// +// Apply the laser sensor model +bool AMCLLaser::UpdateSensor(pf_t *pf, AMCLSensorData *data) +{ + if (this->max_beams < 2) + return false; + + // Apply the laser sensor model + if(this->model_type == LASER_MODEL_BEAM) + pf_update_sensor(pf, (pf_sensor_model_fn_t) BeamModel, data); + else if(this->model_type == LASER_MODEL_LIKELIHOOD_FIELD) + pf_update_sensor(pf, (pf_sensor_model_fn_t) LikelihoodFieldModel, data); + else if(this->model_type == LASER_MODEL_LIKELIHOOD_FIELD_PROB) + pf_update_sensor(pf, (pf_sensor_model_fn_t) LikelihoodFieldModelProb, data); + else + pf_update_sensor(pf, (pf_sensor_model_fn_t) BeamModel, data); + + return true; +} + + +//////////////////////////////////////////////////////////////////////////////// +// Determine the probability for the given pose +double AMCLLaser::BeamModel(AMCLLaserData *data, pf_sample_set_t* set) +{ + AMCLLaser *self; + int i, j, step; + double z, pz; + double p; + double map_range; + double obs_range, obs_bearing; + double total_weight; + pf_sample_t *sample; + pf_vector_t pose; + + self = (AMCLLaser*) data->sensor; + + total_weight = 0.0; + + // Compute the sample weights + for (j = 0; j < set->sample_count; j++) + { + sample = set->samples + j; + pose = sample->pose; + + // Take account of the laser pose relative to the robot + pose = pf_vector_coord_add(self->laser_pose, pose); + + p = 1.0; + + step = (data->range_count - 1) / (self->max_beams - 1); + for (i = 0; i < data->range_count; i += step) + { + obs_range = data->ranges[i][0]; + obs_bearing = data->ranges[i][1]; + + // Compute the range according to the map + map_range = map_calc_range(self->map, pose.v[0], pose.v[1], + pose.v[2] + obs_bearing, data->range_max); + pz = 0.0; + + // Part 1: good, but noisy, hit + z = obs_range - map_range; + pz += self->z_hit * exp(-(z * z) / (2 * self->sigma_hit * self->sigma_hit)); + + // Part 2: short reading from unexpected obstacle (e.g., a person) + if(z < 0) + pz += self->z_short * self->lambda_short * exp(-self->lambda_short*obs_range); + + // Part 3: Failure to detect obstacle, reported as max-range + if(obs_range == data->range_max) + pz += self->z_max * 1.0; + + // Part 4: Random measurements + if(obs_range < data->range_max) + pz += self->z_rand * 1.0/data->range_max; + + // TODO: outlier rejection for short readings + + assert(pz <= 1.0); + assert(pz >= 0.0); + // p *= pz; + // here we have an ad-hoc weighting scheme for combining beam probs + // works well, though... + p += pz*pz*pz; + } + + sample->weight *= p; + total_weight += sample->weight; + } + + return(total_weight); +} + +double AMCLLaser::LikelihoodFieldModel(AMCLLaserData *data, pf_sample_set_t* set) +{ + AMCLLaser *self; + int i, j, step; + double z, pz; + double p; + double obs_range, obs_bearing; + double total_weight; + pf_sample_t *sample; + pf_vector_t pose; + pf_vector_t hit; + + self = (AMCLLaser*) data->sensor; + + total_weight = 0.0; + + // Compute the sample weights + for (j = 0; j < set->sample_count; j++) + { + sample = set->samples + j; + pose = sample->pose; + + // Take account of the laser pose relative to the robot + pose = pf_vector_coord_add(self->laser_pose, pose); + + p = 1.0; + + // Pre-compute a couple of things + double z_hit_denom = 2 * self->sigma_hit * self->sigma_hit; + double z_rand_mult = 1.0/data->range_max; + + step = (data->range_count - 1) / (self->max_beams - 1); + + // Step size must be at least 1 + if(step < 1) + step = 1; + + for (i = 0; i < data->range_count; i += step) + { + obs_range = data->ranges[i][0]; + obs_bearing = data->ranges[i][1]; + + // This model ignores max range readings + if(obs_range >= data->range_max) + continue; + + // Check for NaN + if(obs_range != obs_range) + continue; + + pz = 0.0; + + // Compute the endpoint of the beam + hit.v[0] = pose.v[0] + obs_range * cos(pose.v[2] + obs_bearing); + hit.v[1] = pose.v[1] + obs_range * sin(pose.v[2] + obs_bearing); + + // Convert to map grid coords. + int mi, mj; + mi = MAP_GXWX(self->map, hit.v[0]); + mj = MAP_GYWY(self->map, hit.v[1]); + + // Part 1: Get distance from the hit to closest obstacle. + // Off-map penalized as max distance + if(!MAP_VALID(self->map, mi, mj)) + z = self->map->max_occ_dist; + else + z = self->map->cells[MAP_INDEX(self->map,mi,mj)].occ_dist; + // Gaussian model + // NOTE: this should have a normalization of 1/(sqrt(2pi)*sigma) + pz += self->z_hit * exp(-(z * z) / z_hit_denom); + // Part 2: random measurements + pz += self->z_rand * z_rand_mult; + + // TODO: outlier rejection for short readings + + assert(pz <= 1.0); + assert(pz >= 0.0); + // p *= pz; + // here we have an ad-hoc weighting scheme for combining beam probs + // works well, though... + p += pz*pz*pz; + } + + sample->weight *= p; + total_weight += sample->weight; + } + + return(total_weight); +} + +double AMCLLaser::LikelihoodFieldModelProb(AMCLLaserData *data, pf_sample_set_t* set) +{ + AMCLLaser *self; + int i, j, step; + double z, pz; + double log_p; + double obs_range, obs_bearing; + double total_weight; + pf_sample_t *sample; + pf_vector_t pose; + pf_vector_t hit; + + self = (AMCLLaser*) data->sensor; + + total_weight = 0.0; + + step = ceil((data->range_count) / static_cast(self->max_beams)); + + // Step size must be at least 1 + if(step < 1) + step = 1; + + // Pre-compute a couple of things + double z_hit_denom = 2 * self->sigma_hit * self->sigma_hit; + double z_rand_mult = 1.0/data->range_max; + + double max_dist_prob = exp(-(self->map->max_occ_dist * self->map->max_occ_dist) / z_hit_denom); + + //Beam skipping - ignores beams for which a majority of particles do not agree with the map + //prevents correct particles from getting down weighted because of unexpected obstacles + //such as humans + + bool do_beamskip = self->do_beamskip; + double beam_skip_distance = self->beam_skip_distance; + double beam_skip_threshold = self->beam_skip_threshold; + + //we only do beam skipping if the filter has converged + if(do_beamskip && !set->converged){ + do_beamskip = false; + } + + //we need a count the no of particles for which the beam agreed with the map + int *obs_count = new int[self->max_beams](); + + //we also need a mask of which observations to integrate (to decide which beams to integrate to all particles) + bool *obs_mask = new bool[self->max_beams](); + + int beam_ind = 0; + + //realloc indicates if we need to reallocate the temp data structure needed to do beamskipping + bool realloc = false; + + if(do_beamskip){ + if(self->max_obs < self->max_beams){ + realloc = true; + } + + if(self->max_samples < set->sample_count){ + realloc = true; + } + + if(realloc){ + self->reallocTempData(set->sample_count, self->max_beams); + fprintf(stderr, "Reallocing temp weights %d - %d\n", self->max_samples, self->max_obs); + } + } + + // Compute the sample weights + for (j = 0; j < set->sample_count; j++) + { + sample = set->samples + j; + pose = sample->pose; + + // Take account of the laser pose relative to the robot + pose = pf_vector_coord_add(self->laser_pose, pose); + + log_p = 0; + + beam_ind = 0; + + for (i = 0; i < data->range_count; i += step, beam_ind++) + { + obs_range = data->ranges[i][0]; + obs_bearing = data->ranges[i][1]; + + // This model ignores max range readings + if(obs_range >= data->range_max){ + continue; + } + + // Check for NaN + if(obs_range != obs_range){ + continue; + } + + pz = 0.0; + + // Compute the endpoint of the beam + hit.v[0] = pose.v[0] + obs_range * cos(pose.v[2] + obs_bearing); + hit.v[1] = pose.v[1] + obs_range * sin(pose.v[2] + obs_bearing); + + // Convert to map grid coords. + int mi, mj; + mi = MAP_GXWX(self->map, hit.v[0]); + mj = MAP_GYWY(self->map, hit.v[1]); + + // Part 1: Get distance from the hit to closest obstacle. + // Off-map penalized as max distance + + if(!MAP_VALID(self->map, mi, mj)){ + pz += self->z_hit * max_dist_prob; + } + else{ + z = self->map->cells[MAP_INDEX(self->map,mi,mj)].occ_dist; + if(z < beam_skip_distance){ + obs_count[beam_ind] += 1; + } + pz += self->z_hit * exp(-(z * z) / z_hit_denom); + } + + // Gaussian model + // NOTE: this should have a normalization of 1/(sqrt(2pi)*sigma) + + // Part 2: random measurements + pz += self->z_rand * z_rand_mult; + + assert(pz <= 1.0); + assert(pz >= 0.0); + + // TODO: outlier rejection for short readings + + if(!do_beamskip){ + log_p += log(pz); + } + else{ + self->temp_obs[j][beam_ind] = pz; + } + } + if(!do_beamskip){ + sample->weight *= exp(log_p); + total_weight += sample->weight; + } + } + + if(do_beamskip){ + int skipped_beam_count = 0; + for (beam_ind = 0; beam_ind < self->max_beams; beam_ind++){ + if((obs_count[beam_ind] / static_cast(set->sample_count)) > beam_skip_threshold){ + obs_mask[beam_ind] = true; + } + else{ + obs_mask[beam_ind] = false; + skipped_beam_count++; + } + } + + //we check if there is at least a critical number of beams that agreed with the map + //otherwise it probably indicates that the filter converged to a wrong solution + //if that's the case we integrate all the beams and hope the filter might converge to + //the right solution + bool error = false; + + if(skipped_beam_count >= (beam_ind * self->beam_skip_error_threshold)){ + fprintf(stderr, "Over %f%% of the observations were not in the map - pf may have converged to wrong pose - integrating all observations\n", (100 * self->beam_skip_error_threshold)); + error = true; + } + + for (j = 0; j < set->sample_count; j++) + { + sample = set->samples + j; + pose = sample->pose; + + log_p = 0; + + for (beam_ind = 0; beam_ind < self->max_beams; beam_ind++){ + if(error || obs_mask[beam_ind]){ + log_p += log(self->temp_obs[j][beam_ind]); + } + } + + sample->weight *= exp(log_p); + + total_weight += sample->weight; + } + } + + delete [] obs_count; + delete [] obs_mask; + return(total_weight); +} + +void AMCLLaser::reallocTempData(int new_max_samples, int new_max_obs){ + if(temp_obs){ + for(int k=0; k < max_samples; k++){ + delete [] temp_obs[k]; + } + delete []temp_obs; + } + max_obs = new_max_obs; + max_samples = fmax(max_samples, new_max_samples); + + temp_obs = new double*[max_samples](); + for(int k=0; k < max_samples; k++){ + temp_obs[k] = new double[max_obs](); + } +} diff --git a/navigations/amcl/src/amcl/sensors/amcl_odom.cpp b/navigations/amcl/src/amcl/sensors/amcl_odom.cpp new file mode 100755 index 0000000..5aa846f --- /dev/null +++ b/navigations/amcl/src/amcl/sensors/amcl_odom.cpp @@ -0,0 +1,310 @@ +/* + * Player - One Hell of a Robot Server + * Copyright (C) 2000 Brian Gerkey & Kasper Stoy + * gerkey@usc.edu kaspers@robotics.usc.edu + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + * + */ +/////////////////////////////////////////////////////////////////////////// +// +// Desc: AMCL odometry routines +// Author: Andrew Howard +// Date: 6 Feb 2003 +// CVS: $Id: amcl_odom.cc 7057 2008-10-02 00:44:06Z gbiggs $ +// +/////////////////////////////////////////////////////////////////////////// + +#include + +#include // required by Darwin +#include + +#include "amcl/sensors/amcl_odom.h" + +using namespace amcl; + +static double +normalize(double z) +{ + return atan2(sin(z),cos(z)); +} +static double +angle_diff(double a, double b) +{ + double d1, d2; + a = normalize(a); + b = normalize(b); + d1 = a-b; + d2 = 2*M_PI - fabs(d1); + if(d1 > 0) + d2 *= -1.0; + if(fabs(d1) < fabs(d2)) + return(d1); + else + return(d2); +} + +//////////////////////////////////////////////////////////////////////////////// +// Default constructor +AMCLOdom::AMCLOdom() : AMCLSensor() +{ + this->time = 0.0; +} + +void +AMCLOdom::SetModelDiff(double alpha1, + double alpha2, + double alpha3, + double alpha4) +{ + this->model_type = ODOM_MODEL_DIFF; + this->alpha1 = alpha1; + this->alpha2 = alpha2; + this->alpha3 = alpha3; + this->alpha4 = alpha4; +} + +void +AMCLOdom::SetModelOmni(double alpha1, + double alpha2, + double alpha3, + double alpha4, + double alpha5) +{ + this->model_type = ODOM_MODEL_OMNI; + this->alpha1 = alpha1; + this->alpha2 = alpha2; + this->alpha3 = alpha3; + this->alpha4 = alpha4; + this->alpha5 = alpha5; +} + +void +AMCLOdom::SetModel( odom_model_t type, + double alpha1, + double alpha2, + double alpha3, + double alpha4, + double alpha5 ) +{ + this->model_type = type; + this->alpha1 = alpha1; + this->alpha2 = alpha2; + this->alpha3 = alpha3; + this->alpha4 = alpha4; + this->alpha5 = alpha5; +} + +//////////////////////////////////////////////////////////////////////////////// +// Apply the action model +bool AMCLOdom::UpdateAction(pf_t *pf, AMCLSensorData *data) +{ + AMCLOdomData *ndata; + ndata = (AMCLOdomData*) data; + + // Compute the new sample poses + pf_sample_set_t *set; + + set = pf->sets + pf->current_set; + pf_vector_t old_pose = pf_vector_sub(ndata->pose, ndata->delta); + + switch( this->model_type ) + { + case ODOM_MODEL_OMNI: + { + double delta_trans, delta_rot, delta_bearing; + double delta_trans_hat, delta_rot_hat, delta_strafe_hat; + + delta_trans = sqrt(ndata->delta.v[0]*ndata->delta.v[0] + + ndata->delta.v[1]*ndata->delta.v[1]); + delta_rot = ndata->delta.v[2]; + + // Precompute a couple of things + double trans_hat_stddev = (alpha3 * (delta_trans*delta_trans) + + alpha1 * (delta_rot*delta_rot)); + double rot_hat_stddev = (alpha4 * (delta_rot*delta_rot) + + alpha2 * (delta_trans*delta_trans)); + double strafe_hat_stddev = (alpha1 * (delta_rot*delta_rot) + + alpha5 * (delta_trans*delta_trans)); + + for (int i = 0; i < set->sample_count; i++) + { + pf_sample_t* sample = set->samples + i; + + delta_bearing = angle_diff(atan2(ndata->delta.v[1], ndata->delta.v[0]), + old_pose.v[2]) + sample->pose.v[2]; + double cs_bearing = cos(delta_bearing); + double sn_bearing = sin(delta_bearing); + + // Sample pose differences + delta_trans_hat = delta_trans + pf_ran_gaussian(trans_hat_stddev); + delta_rot_hat = delta_rot + pf_ran_gaussian(rot_hat_stddev); + delta_strafe_hat = 0 + pf_ran_gaussian(strafe_hat_stddev); + // Apply sampled update to particle pose + sample->pose.v[0] += (delta_trans_hat * cs_bearing + + delta_strafe_hat * sn_bearing); + sample->pose.v[1] += (delta_trans_hat * sn_bearing - + delta_strafe_hat * cs_bearing); + sample->pose.v[2] += delta_rot_hat ; + } + } + break; + case ODOM_MODEL_DIFF: + { + // Implement sample_motion_odometry (Prob Rob p 136) + double delta_rot1, delta_trans, delta_rot2; + double delta_rot1_hat, delta_trans_hat, delta_rot2_hat; + double delta_rot1_noise, delta_rot2_noise; + + // Avoid computing a bearing from two poses that are extremely near each + // other (happens on in-place rotation). + if(sqrt(ndata->delta.v[1]*ndata->delta.v[1] + + ndata->delta.v[0]*ndata->delta.v[0]) < 0.01) + delta_rot1 = 0.0; + else + delta_rot1 = angle_diff(atan2(ndata->delta.v[1], ndata->delta.v[0]), + old_pose.v[2]); + delta_trans = sqrt(ndata->delta.v[0]*ndata->delta.v[0] + + ndata->delta.v[1]*ndata->delta.v[1]); + delta_rot2 = angle_diff(ndata->delta.v[2], delta_rot1); + + // We want to treat backward and forward motion symmetrically for the + // noise model to be applied below. The standard model seems to assume + // forward motion. + delta_rot1_noise = std::min(fabs(angle_diff(delta_rot1,0.0)), + fabs(angle_diff(delta_rot1,M_PI))); + delta_rot2_noise = std::min(fabs(angle_diff(delta_rot2,0.0)), + fabs(angle_diff(delta_rot2,M_PI))); + + for (int i = 0; i < set->sample_count; i++) + { + pf_sample_t* sample = set->samples + i; + + // Sample pose differences + delta_rot1_hat = angle_diff(delta_rot1, + pf_ran_gaussian(this->alpha1*delta_rot1_noise*delta_rot1_noise + + this->alpha2*delta_trans*delta_trans)); + delta_trans_hat = delta_trans - + pf_ran_gaussian(this->alpha3*delta_trans*delta_trans + + this->alpha4*delta_rot1_noise*delta_rot1_noise + + this->alpha4*delta_rot2_noise*delta_rot2_noise); + delta_rot2_hat = angle_diff(delta_rot2, + pf_ran_gaussian(this->alpha1*delta_rot2_noise*delta_rot2_noise + + this->alpha2*delta_trans*delta_trans)); + + // Apply sampled update to particle pose + sample->pose.v[0] += delta_trans_hat * + cos(sample->pose.v[2] + delta_rot1_hat); + sample->pose.v[1] += delta_trans_hat * + sin(sample->pose.v[2] + delta_rot1_hat); + sample->pose.v[2] += delta_rot1_hat + delta_rot2_hat; + } + } + break; + case ODOM_MODEL_OMNI_CORRECTED: + { + double delta_trans, delta_rot, delta_bearing; + double delta_trans_hat, delta_rot_hat, delta_strafe_hat; + + delta_trans = sqrt(ndata->delta.v[0]*ndata->delta.v[0] + + ndata->delta.v[1]*ndata->delta.v[1]); + delta_rot = ndata->delta.v[2]; + + // Precompute a couple of things + double trans_hat_stddev = sqrt( alpha3 * (delta_trans*delta_trans) + + alpha4 * (delta_rot*delta_rot) ); + double rot_hat_stddev = sqrt( alpha1 * (delta_rot*delta_rot) + + alpha2 * (delta_trans*delta_trans) ); + double strafe_hat_stddev = sqrt( alpha4 * (delta_rot*delta_rot) + + alpha5 * (delta_trans*delta_trans) ); + + for (int i = 0; i < set->sample_count; i++) + { + pf_sample_t* sample = set->samples + i; + + delta_bearing = angle_diff(atan2(ndata->delta.v[1], ndata->delta.v[0]), + old_pose.v[2]) + sample->pose.v[2]; + double cs_bearing = cos(delta_bearing); + double sn_bearing = sin(delta_bearing); + + // Sample pose differences + delta_trans_hat = delta_trans + pf_ran_gaussian(trans_hat_stddev); + delta_rot_hat = delta_rot + pf_ran_gaussian(rot_hat_stddev); + delta_strafe_hat = 0 + pf_ran_gaussian(strafe_hat_stddev); + // Apply sampled update to particle pose + sample->pose.v[0] += (delta_trans_hat * cs_bearing + + delta_strafe_hat * sn_bearing); + sample->pose.v[1] += (delta_trans_hat * sn_bearing - + delta_strafe_hat * cs_bearing); + sample->pose.v[2] += delta_rot_hat ; + } + } + break; + case ODOM_MODEL_DIFF_CORRECTED: + { + // Implement sample_motion_odometry (Prob Rob p 136) + double delta_rot1, delta_trans, delta_rot2; + double delta_rot1_hat, delta_trans_hat, delta_rot2_hat; + double delta_rot1_noise, delta_rot2_noise; + + // Avoid computing a bearing from two poses that are extremely near each + // other (happens on in-place rotation). + if(sqrt(ndata->delta.v[1]*ndata->delta.v[1] + + ndata->delta.v[0]*ndata->delta.v[0]) < 0.01) + delta_rot1 = 0.0; + else + delta_rot1 = angle_diff(atan2(ndata->delta.v[1], ndata->delta.v[0]), + old_pose.v[2]); + delta_trans = sqrt(ndata->delta.v[0]*ndata->delta.v[0] + + ndata->delta.v[1]*ndata->delta.v[1]); + delta_rot2 = angle_diff(ndata->delta.v[2], delta_rot1); + + // We want to treat backward and forward motion symmetrically for the + // noise model to be applied below. The standard model seems to assume + // forward motion. + delta_rot1_noise = std::min(fabs(angle_diff(delta_rot1,0.0)), + fabs(angle_diff(delta_rot1,M_PI))); + delta_rot2_noise = std::min(fabs(angle_diff(delta_rot2,0.0)), + fabs(angle_diff(delta_rot2,M_PI))); + + for (int i = 0; i < set->sample_count; i++) + { + pf_sample_t* sample = set->samples + i; + + // Sample pose differences + delta_rot1_hat = angle_diff(delta_rot1, + pf_ran_gaussian(sqrt(this->alpha1*delta_rot1_noise*delta_rot1_noise + + this->alpha2*delta_trans*delta_trans))); + delta_trans_hat = delta_trans - + pf_ran_gaussian(sqrt(this->alpha3*delta_trans*delta_trans + + this->alpha4*delta_rot1_noise*delta_rot1_noise + + this->alpha4*delta_rot2_noise*delta_rot2_noise)); + delta_rot2_hat = angle_diff(delta_rot2, + pf_ran_gaussian(sqrt(this->alpha1*delta_rot2_noise*delta_rot2_noise + + this->alpha2*delta_trans*delta_trans))); + + // Apply sampled update to particle pose + sample->pose.v[0] += delta_trans_hat * + cos(sample->pose.v[2] + delta_rot1_hat); + sample->pose.v[1] += delta_trans_hat * + sin(sample->pose.v[2] + delta_rot1_hat); + sample->pose.v[2] += delta_rot1_hat + delta_rot2_hat; + } + } + break; + } + return true; +} diff --git a/navigations/amcl/src/amcl/sensors/amcl_sensor.cpp b/navigations/amcl/src/amcl/sensors/amcl_sensor.cpp new file mode 100755 index 0000000..48e190d --- /dev/null +++ b/navigations/amcl/src/amcl/sensors/amcl_sensor.cpp @@ -0,0 +1,95 @@ +/* + * Player - One Hell of a Robot Server + * Copyright (C) 2000 Brian Gerkey & Kasper Stoy + * gerkey@usc.edu kaspers@robotics.usc.edu + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + * + */ +/////////////////////////////////////////////////////////////////////////// +// +// Desc: AMCL sensor +// Author: Andrew Howard +// Date: 6 Feb 2003 +// CVS: $Id: amcl_sensor.cc 7057 2008-10-02 00:44:06Z gbiggs $ +// +/////////////////////////////////////////////////////////////////////////// + + +#include "amcl/sensors/amcl_sensor.h" + +using namespace amcl; + +//////////////////////////////////////////////////////////////////////////////// +// Default constructor +AMCLSensor::AMCLSensor() +{ + return; +} + +AMCLSensor::~AMCLSensor() +{ +} + +//////////////////////////////////////////////////////////////////////////////// +// Apply the action model +bool AMCLSensor::UpdateAction(pf_t *pf, AMCLSensorData *data) +{ + return false; +} + + +//////////////////////////////////////////////////////////////////////////////// +// Initialize the filter +bool AMCLSensor::InitSensor(pf_t *pf, AMCLSensorData *data) +{ + return false; +} + + +//////////////////////////////////////////////////////////////////////////////// +// Apply the sensor model +bool AMCLSensor::UpdateSensor(pf_t *pf, AMCLSensorData *data) +{ + return false; +} + + +#ifdef INCLUDE_RTKGUI + +//////////////////////////////////////////////////////////////////////////////// +// Setup the GUI +void AMCLSensor::SetupGUI(rtk_canvas_t *canvas, rtk_fig_t *robot_fig) +{ + return; +} + + +//////////////////////////////////////////////////////////////////////////////// +// Shutdown the GUI +void AMCLSensor::ShutdownGUI(rtk_canvas_t *canvas, rtk_fig_t *robot_fig) +{ + return; +} + + +//////////////////////////////////////////////////////////////////////////////// +// Draw sensor data +void AMCLSensor::UpdateGUI(rtk_canvas_t *canvas, rtk_fig_t *robot_fig, AMCLSensorData *data) +{ + return; +} + +#endif diff --git a/navigations/amcl/src/amcl_node.cpp b/navigations/amcl/src/amcl_node.cpp new file mode 100755 index 0000000..b0e11d1 --- /dev/null +++ b/navigations/amcl/src/amcl_node.cpp @@ -0,0 +1,1656 @@ +/* + * Copyright (c) 2008, Willow Garage, Inc. + * All rights reserved. + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + * + */ + +/* Author: Brian Gerkey */ + +#include +#include +#include +#include +#include + +#include +#include + +// Signal handling +#include + +#include "amcl/map/map.h" +#include "amcl/pf/pf.h" +#include "amcl/sensors/amcl_odom.h" +#include "amcl/sensors/amcl_laser.h" +#include "portable_utils.hpp" + +#include "ros/assert.h" + +// roscpp +#include "ros/ros.h" + +// Messages that I need +#include "sensor_msgs/LaserScan.h" +#include "geometry_msgs/PoseWithCovarianceStamped.h" +#include "geometry_msgs/PoseArray.h" +#include "geometry_msgs/Pose.h" +#include "geometry_msgs/PoseStamped.h" +#include "nav_msgs/GetMap.h" +#include "nav_msgs/SetMap.h" +#include "std_srvs/Empty.h" + +// For transform support +#include "tf2/LinearMath/Transform.h" +#include "tf2/convert.h" +#include "tf2/utils.h" +#include "tf2_geometry_msgs/tf2_geometry_msgs.h" +#include "tf2_ros/buffer.h" +#include "tf2_ros/message_filter.h" +#include "tf2_ros/transform_broadcaster.h" +#include "tf2_ros/transform_listener.h" +#include "message_filters/subscriber.h" + +// Dynamic_reconfigure +#include "dynamic_reconfigure/server.h" +#include "amcl/AMCLConfig.h" + +// Allows AMCL to run from bag file +#include +#include +#include + +// For monitoring the estimator +#include + +#define NEW_UNIFORM_SAMPLING 1 + +using namespace amcl; + +// Pose hypothesis +typedef struct +{ + // Total weight (weights sum to 1) + double weight; + + // Mean of pose esimate + pf_vector_t pf_pose_mean; + + // Covariance of pose estimate + pf_matrix_t pf_pose_cov; + +} amcl_hyp_t; + +static double +normalize(double z) +{ + return atan2(sin(z),cos(z)); +} +static double +angle_diff(double a, double b) +{ + double d1, d2; + a = normalize(a); + b = normalize(b); + d1 = a-b; + d2 = 2*M_PI - fabs(d1); + if(d1 > 0) + d2 *= -1.0; + if(fabs(d1) < fabs(d2)) + return(d1); + else + return(d2); +} + +static const std::string scan_topic_ = "scan"; + +/* This function is only useful to have the whole code work + * with old rosbags that have trailing slashes for their frames + */ +inline +std::string stripSlash(const std::string& in) +{ + std::string out = in; + if ( ( !in.empty() ) && (in[0] == '/') ) + out.erase(0,1); + return out; +} + +class AmclNode +{ + public: + AmclNode(); + ~AmclNode(); + + /** + * @brief Uses TF and LaserScan messages from bag file to drive AMCL instead + * @param in_bag_fn input bagfile + * @param trigger_global_localization whether to trigger global localization + * before starting to process the bagfile + */ + void runFromBag(const std::string &in_bag_fn, bool trigger_global_localization = false); + + int process(); + void savePoseToServer(); + + private: + std::shared_ptr tfb_; + std::shared_ptr tfl_; + std::shared_ptr tf_; + + bool sent_first_transform_; + + tf2::Transform latest_tf_; + bool latest_tf_valid_; + + // Pose-generating function used to uniformly distribute particles over + // the map + static pf_vector_t uniformPoseGenerator(void* arg); +#if NEW_UNIFORM_SAMPLING + static std::vector > free_space_indices; +#endif + // Callbacks + bool globalLocalizationCallback(std_srvs::Empty::Request& req, + std_srvs::Empty::Response& res); + bool nomotionUpdateCallback(std_srvs::Empty::Request& req, + std_srvs::Empty::Response& res); + bool setMapCallback(nav_msgs::SetMap::Request& req, + nav_msgs::SetMap::Response& res); + + void laserReceived(const sensor_msgs::LaserScanConstPtr& laser_scan); + void initialPoseReceived(const geometry_msgs::PoseWithCovarianceStampedConstPtr& msg); + void handleInitialPoseMessage(const geometry_msgs::PoseWithCovarianceStamped& msg); + void mapReceived(const nav_msgs::OccupancyGridConstPtr& msg); + + void handleMapMessage(const nav_msgs::OccupancyGrid& msg); + void freeMapDependentMemory(); + map_t* convertMap( const nav_msgs::OccupancyGrid& map_msg ); + void updatePoseFromServer(); + void applyInitialPose(); + + //parameter for which odom to use + std::string odom_frame_id_; + + //paramater to store latest odom pose + geometry_msgs::PoseStamped latest_odom_pose_; + + //parameter for which base to use + std::string base_frame_id_; + std::string global_frame_id_; + + bool use_map_topic_; + bool first_map_only_; + + ros::Duration gui_publish_period; + ros::Time save_pose_last_time; + ros::Duration save_pose_period; + + geometry_msgs::PoseWithCovarianceStamped last_published_pose; + + map_t* map_; + char* mapdata; + int sx, sy; + double resolution; + + message_filters::Subscriber* laser_scan_sub_; + tf2_ros::MessageFilter* laser_scan_filter_; + ros::Subscriber initial_pose_sub_; + std::vector< AMCLLaser* > lasers_; + std::vector< bool > lasers_update_; + std::map< std::string, int > frame_to_laser_; + + // Particle filter + pf_t *pf_; + double pf_err_, pf_z_; + bool pf_init_; + pf_vector_t pf_odom_pose_; + double d_thresh_, a_thresh_; + int resample_interval_; + int resample_count_; + double laser_min_range_; + double laser_max_range_; + + //Nomotion update control + bool m_force_update; // used to temporarily let amcl update samples even when no motion occurs... + + AMCLOdom* odom_; + AMCLLaser* laser_; + + ros::Duration cloud_pub_interval; + ros::Time last_cloud_pub_time; + + // For slowing play-back when reading directly from a bag file + ros::WallDuration bag_scan_period_; + + void requestMap(); + + // Helper to get odometric pose from transform system + bool getOdomPose(geometry_msgs::PoseStamped& pose, + double& x, double& y, double& yaw, + const ros::Time& t, const std::string& f); + + //time for tolerance on the published transform, + //basically defines how long a map->odom transform is good for + ros::Duration transform_tolerance_; + + ros::NodeHandle nh_; + ros::NodeHandle private_nh_; + ros::Publisher pose_pub_; + ros::Publisher particlecloud_pub_; + ros::ServiceServer global_loc_srv_; + ros::ServiceServer nomotion_update_srv_; //to let amcl update samples without requiring motion + ros::ServiceServer set_map_srv_; + ros::Subscriber initial_pose_sub_old_; + ros::Subscriber map_sub_; + + diagnostic_updater::Updater diagnosic_updater_; + void standardDeviationDiagnostics(diagnostic_updater::DiagnosticStatusWrapper& diagnostic_status); + double std_warn_level_x_; + double std_warn_level_y_; + double std_warn_level_yaw_; + + amcl_hyp_t* initial_pose_hyp_; + bool first_map_received_; + bool first_reconfigure_call_; + + boost::recursive_mutex configuration_mutex_; + dynamic_reconfigure::Server *dsrv_; + amcl::AMCLConfig default_config_; + ros::Timer check_laser_timer_; + + int max_beams_, min_particles_, max_particles_; + double alpha1_, alpha2_, alpha3_, alpha4_, alpha5_; + double alpha_slow_, alpha_fast_; + double z_hit_, z_short_, z_max_, z_rand_, sigma_hit_, lambda_short_; + //beam skip related params + bool do_beamskip_; + double beam_skip_distance_, beam_skip_threshold_, beam_skip_error_threshold_; + double laser_likelihood_max_dist_; + odom_model_t odom_model_type_; + double init_pose_[3]; + double init_cov_[3]; + laser_model_t laser_model_type_; + bool tf_broadcast_; + bool force_update_after_initialpose_; + bool force_update_after_set_map_; + bool selective_resampling_; + + void reconfigureCB(amcl::AMCLConfig &config, uint32_t level); + + ros::Time last_laser_received_ts_; + ros::Duration laser_check_interval_; + void checkLaserReceived(const ros::TimerEvent& event); +}; + +#if NEW_UNIFORM_SAMPLING +std::vector > AmclNode::free_space_indices; +#endif + +#define USAGE "USAGE: amcl" + +boost::shared_ptr amcl_node_ptr; + +void sigintHandler(int sig) +{ + // Save latest pose as we're shutting down. + amcl_node_ptr->savePoseToServer(); + ros::shutdown(); +} + +int +main(int argc, char** argv) +{ + ros::init(argc, argv, "amcl"); + ros::NodeHandle nh; + + // Override default sigint handler + signal(SIGINT, sigintHandler); + + // Make our node available to sigintHandler + amcl_node_ptr.reset(new AmclNode()); + + if (argc == 1) + { + // run using ROS input + ros::spin(); + } + else if ((argc >= 3) && (std::string(argv[1]) == "--run-from-bag")) + { + if (argc == 3) + { + amcl_node_ptr->runFromBag(argv[2]); + } + else if ((argc == 4) && (std::string(argv[3]) == "--global-localization")) + { + amcl_node_ptr->runFromBag(argv[2], true); + } + } + + // Without this, our boost locks are not shut down nicely + amcl_node_ptr.reset(); + + // To quote Morgan, Hooray! + return(0); +} + +AmclNode::AmclNode() : + sent_first_transform_(false), + latest_tf_valid_(false), + map_(NULL), + pf_(NULL), + resample_count_(0), + odom_(NULL), + laser_(NULL), + private_nh_("~"), + initial_pose_hyp_(NULL), + first_map_received_(false), + first_reconfigure_call_(true) +{ + boost::recursive_mutex::scoped_lock l(configuration_mutex_); + + // Grab params off the param server + private_nh_.param("use_map_topic", use_map_topic_, false); + private_nh_.param("first_map_only", first_map_only_, false); + + double tmp; + private_nh_.param("gui_publish_rate", tmp, -1.0); + gui_publish_period = ros::Duration(1.0/tmp); + private_nh_.param("save_pose_rate", tmp, 0.5); + save_pose_period = ros::Duration(1.0/tmp); + + private_nh_.param("laser_min_range", laser_min_range_, -1.0); + private_nh_.param("laser_max_range", laser_max_range_, -1.0); + private_nh_.param("laser_max_beams", max_beams_, 30); + private_nh_.param("min_particles", min_particles_, 100); + private_nh_.param("max_particles", max_particles_, 5000); + private_nh_.param("kld_err", pf_err_, 0.01); + private_nh_.param("kld_z", pf_z_, 0.99); + private_nh_.param("odom_alpha1", alpha1_, 0.2); + private_nh_.param("odom_alpha2", alpha2_, 0.2); + private_nh_.param("odom_alpha3", alpha3_, 0.2); + private_nh_.param("odom_alpha4", alpha4_, 0.2); + private_nh_.param("odom_alpha5", alpha5_, 0.2); + + private_nh_.param("do_beamskip", do_beamskip_, false); + private_nh_.param("beam_skip_distance", beam_skip_distance_, 0.5); + private_nh_.param("beam_skip_threshold", beam_skip_threshold_, 0.3); + if (private_nh_.hasParam("beam_skip_error_threshold_")) + { + private_nh_.param("beam_skip_error_threshold_", beam_skip_error_threshold_); + } + else + { + private_nh_.param("beam_skip_error_threshold", beam_skip_error_threshold_, 0.9); + } + + private_nh_.param("laser_z_hit", z_hit_, 0.95); + private_nh_.param("laser_z_short", z_short_, 0.1); + private_nh_.param("laser_z_max", z_max_, 0.05); + private_nh_.param("laser_z_rand", z_rand_, 0.05); + private_nh_.param("laser_sigma_hit", sigma_hit_, 0.2); + private_nh_.param("laser_lambda_short", lambda_short_, 0.1); + private_nh_.param("laser_likelihood_max_dist", laser_likelihood_max_dist_, 2.0); + std::string tmp_model_type; + private_nh_.param("laser_model_type", tmp_model_type, std::string("likelihood_field")); + if(tmp_model_type == "beam") + laser_model_type_ = LASER_MODEL_BEAM; + else if(tmp_model_type == "likelihood_field") + laser_model_type_ = LASER_MODEL_LIKELIHOOD_FIELD; + else if(tmp_model_type == "likelihood_field_prob"){ + laser_model_type_ = LASER_MODEL_LIKELIHOOD_FIELD_PROB; + } + else + { + ROS_WARN("Unknown laser model type \"%s\"; defaulting to likelihood_field model", + tmp_model_type.c_str()); + laser_model_type_ = LASER_MODEL_LIKELIHOOD_FIELD; + } + + private_nh_.param("odom_model_type", tmp_model_type, std::string("diff")); + if(tmp_model_type == "diff") + odom_model_type_ = ODOM_MODEL_DIFF; + else if(tmp_model_type == "omni") + odom_model_type_ = ODOM_MODEL_OMNI; + else if(tmp_model_type == "diff-corrected") + odom_model_type_ = ODOM_MODEL_DIFF_CORRECTED; + else if(tmp_model_type == "omni-corrected") + odom_model_type_ = ODOM_MODEL_OMNI_CORRECTED; + else + { + ROS_WARN("Unknown odom model type \"%s\"; defaulting to diff model", + tmp_model_type.c_str()); + odom_model_type_ = ODOM_MODEL_DIFF; + } + + private_nh_.param("update_min_d", d_thresh_, 0.2); + private_nh_.param("update_min_a", a_thresh_, M_PI/6.0); + private_nh_.param("odom_frame_id", odom_frame_id_, std::string("odom")); + private_nh_.param("base_frame_id", base_frame_id_, std::string("base_link")); + private_nh_.param("global_frame_id", global_frame_id_, std::string("map")); + private_nh_.param("resample_interval", resample_interval_, 2); + private_nh_.param("selective_resampling", selective_resampling_, false); + double tmp_tol; + private_nh_.param("transform_tolerance", tmp_tol, 0.1); + private_nh_.param("recovery_alpha_slow", alpha_slow_, 0.001); + private_nh_.param("recovery_alpha_fast", alpha_fast_, 0.1); + private_nh_.param("tf_broadcast", tf_broadcast_, true); + private_nh_.param("force_update_after_initialpose", force_update_after_initialpose_, false); + private_nh_.param("force_update_after_set_map", force_update_after_set_map_, false); + + // For diagnostics + private_nh_.param("std_warn_level_x", std_warn_level_x_, 0.2); + private_nh_.param("std_warn_level_y", std_warn_level_y_, 0.2); + private_nh_.param("std_warn_level_yaw", std_warn_level_yaw_, 0.1); + + transform_tolerance_.fromSec(tmp_tol); + + { + double bag_scan_period; + private_nh_.param("bag_scan_period", bag_scan_period, -1.0); + bag_scan_period_.fromSec(bag_scan_period); + } + + odom_frame_id_ = stripSlash(odom_frame_id_); + base_frame_id_ = stripSlash(base_frame_id_); + global_frame_id_ = stripSlash(global_frame_id_); + + updatePoseFromServer(); + + cloud_pub_interval.fromSec(1.0); + tfb_.reset(new tf2_ros::TransformBroadcaster()); + tf_.reset(new tf2_ros::Buffer()); + tfl_.reset(new tf2_ros::TransformListener(*tf_)); + + pose_pub_ = nh_.advertise("amcl_pose", 2, true); + particlecloud_pub_ = nh_.advertise("particlecloud", 2, true); + global_loc_srv_ = nh_.advertiseService("global_localization", + &AmclNode::globalLocalizationCallback, + this); + nomotion_update_srv_= nh_.advertiseService("request_nomotion_update", &AmclNode::nomotionUpdateCallback, this); + set_map_srv_= nh_.advertiseService("set_map", &AmclNode::setMapCallback, this); + + laser_scan_sub_ = new message_filters::Subscriber(nh_, scan_topic_, 100); + laser_scan_filter_ = + new tf2_ros::MessageFilter(*laser_scan_sub_, + *tf_, + odom_frame_id_, + 100, + nh_); + laser_scan_filter_->registerCallback(boost::bind(&AmclNode::laserReceived, + this, _1)); + initial_pose_sub_ = nh_.subscribe("initialpose", 2, &AmclNode::initialPoseReceived, this); + + if(use_map_topic_) { + map_sub_ = nh_.subscribe("map", 1, &AmclNode::mapReceived, this); + ROS_INFO("Subscribed to map topic."); + } else { + requestMap(); + } + m_force_update = false; + + dsrv_ = new dynamic_reconfigure::Server(ros::NodeHandle("~")); + dynamic_reconfigure::Server::CallbackType cb = boost::bind(&AmclNode::reconfigureCB, this, _1, _2); + dsrv_->setCallback(cb); + + // 15s timer to warn on lack of receipt of laser scans, #5209 + laser_check_interval_ = ros::Duration(15.0); + check_laser_timer_ = nh_.createTimer(laser_check_interval_, + boost::bind(&AmclNode::checkLaserReceived, this, _1)); + + diagnosic_updater_.setHardwareID("None"); + diagnosic_updater_.add("Standard deviation", this, &AmclNode::standardDeviationDiagnostics); +} + +void AmclNode::reconfigureCB(AMCLConfig &config, uint32_t level) +{ + boost::recursive_mutex::scoped_lock cfl(configuration_mutex_); + + //we don't want to do anything on the first call + //which corresponds to startup + if(first_reconfigure_call_) + { + first_reconfigure_call_ = false; + default_config_ = config; + return; + } + + if(config.restore_defaults) { + config = default_config_; + //avoid looping + config.restore_defaults = false; + } + + d_thresh_ = config.update_min_d; + a_thresh_ = config.update_min_a; + + resample_interval_ = config.resample_interval; + + laser_min_range_ = config.laser_min_range; + laser_max_range_ = config.laser_max_range; + + gui_publish_period = ros::Duration(1.0/config.gui_publish_rate); + save_pose_period = ros::Duration(1.0/config.save_pose_rate); + + transform_tolerance_.fromSec(config.transform_tolerance); + + max_beams_ = config.laser_max_beams; + alpha1_ = config.odom_alpha1; + alpha2_ = config.odom_alpha2; + alpha3_ = config.odom_alpha3; + alpha4_ = config.odom_alpha4; + alpha5_ = config.odom_alpha5; + + z_hit_ = config.laser_z_hit; + z_short_ = config.laser_z_short; + z_max_ = config.laser_z_max; + z_rand_ = config.laser_z_rand; + sigma_hit_ = config.laser_sigma_hit; + lambda_short_ = config.laser_lambda_short; + laser_likelihood_max_dist_ = config.laser_likelihood_max_dist; + + if(config.laser_model_type == "beam") + laser_model_type_ = LASER_MODEL_BEAM; + else if(config.laser_model_type == "likelihood_field") + laser_model_type_ = LASER_MODEL_LIKELIHOOD_FIELD; + else if(config.laser_model_type == "likelihood_field_prob") + laser_model_type_ = LASER_MODEL_LIKELIHOOD_FIELD_PROB; + + if(config.odom_model_type == "diff") + odom_model_type_ = ODOM_MODEL_DIFF; + else if(config.odom_model_type == "omni") + odom_model_type_ = ODOM_MODEL_OMNI; + else if(config.odom_model_type == "diff-corrected") + odom_model_type_ = ODOM_MODEL_DIFF_CORRECTED; + else if(config.odom_model_type == "omni-corrected") + odom_model_type_ = ODOM_MODEL_OMNI_CORRECTED; + + if(config.min_particles > config.max_particles) + { + ROS_WARN("You've set min_particles to be greater than max particles, this isn't allowed so they'll be set to be equal."); + config.max_particles = config.min_particles; + } + + min_particles_ = config.min_particles; + max_particles_ = config.max_particles; + alpha_slow_ = config.recovery_alpha_slow; + alpha_fast_ = config.recovery_alpha_fast; + tf_broadcast_ = config.tf_broadcast; + force_update_after_initialpose_ = config.force_update_after_initialpose; + force_update_after_set_map_ = config.force_update_after_set_map; + + do_beamskip_= config.do_beamskip; + beam_skip_distance_ = config.beam_skip_distance; + beam_skip_threshold_ = config.beam_skip_threshold; + + // Clear queued laser objects so that their parameters get updated + lasers_.clear(); + lasers_update_.clear(); + frame_to_laser_.clear(); + + if( pf_ != NULL ) + { + pf_free( pf_ ); + pf_ = NULL; + } + pf_ = pf_alloc(min_particles_, max_particles_, + alpha_slow_, alpha_fast_, + (pf_init_model_fn_t)AmclNode::uniformPoseGenerator, + (void *)map_); + pf_set_selective_resampling(pf_, selective_resampling_); + pf_err_ = config.kld_err; + pf_z_ = config.kld_z; + pf_->pop_err = pf_err_; + pf_->pop_z = pf_z_; + + // Initialize the filter + pf_vector_t pf_init_pose_mean = pf_vector_zero(); + pf_init_pose_mean.v[0] = last_published_pose.pose.pose.position.x; + pf_init_pose_mean.v[1] = last_published_pose.pose.pose.position.y; + pf_init_pose_mean.v[2] = tf2::getYaw(last_published_pose.pose.pose.orientation); + pf_matrix_t pf_init_pose_cov = pf_matrix_zero(); + pf_init_pose_cov.m[0][0] = last_published_pose.pose.covariance[6*0+0]; + pf_init_pose_cov.m[1][1] = last_published_pose.pose.covariance[6*1+1]; + pf_init_pose_cov.m[2][2] = last_published_pose.pose.covariance[6*5+5]; + pf_init(pf_, pf_init_pose_mean, pf_init_pose_cov); + pf_init_ = false; + + // Instantiate the sensor objects + // Odometry + delete odom_; + odom_ = new AMCLOdom(); + ROS_ASSERT(odom_); + odom_->SetModel( odom_model_type_, alpha1_, alpha2_, alpha3_, alpha4_, alpha5_ ); + // Laser + delete laser_; + laser_ = new AMCLLaser(max_beams_, map_); + ROS_ASSERT(laser_); + if(laser_model_type_ == LASER_MODEL_BEAM) + laser_->SetModelBeam(z_hit_, z_short_, z_max_, z_rand_, + sigma_hit_, lambda_short_, 0.0); + else if(laser_model_type_ == LASER_MODEL_LIKELIHOOD_FIELD_PROB){ + ROS_INFO("Initializing likelihood field model; this can take some time on large maps..."); + laser_->SetModelLikelihoodFieldProb(z_hit_, z_rand_, sigma_hit_, + laser_likelihood_max_dist_, + do_beamskip_, beam_skip_distance_, + beam_skip_threshold_, beam_skip_error_threshold_); + ROS_INFO("Done initializing likelihood field model with probabilities."); + } + else if(laser_model_type_ == LASER_MODEL_LIKELIHOOD_FIELD){ + ROS_INFO("Initializing likelihood field model; this can take some time on large maps..."); + laser_->SetModelLikelihoodField(z_hit_, z_rand_, sigma_hit_, + laser_likelihood_max_dist_); + ROS_INFO("Done initializing likelihood field model."); + } + + odom_frame_id_ = stripSlash(config.odom_frame_id); + base_frame_id_ = stripSlash(config.base_frame_id); + global_frame_id_ = stripSlash(config.global_frame_id); + + delete laser_scan_filter_; + laser_scan_filter_ = + new tf2_ros::MessageFilter(*laser_scan_sub_, + *tf_, + odom_frame_id_, + 100, + nh_); + laser_scan_filter_->registerCallback(boost::bind(&AmclNode::laserReceived, + this, _1)); + + initial_pose_sub_ = nh_.subscribe("initialpose", 2, &AmclNode::initialPoseReceived, this); +} + + +void AmclNode::runFromBag(const std::string &in_bag_fn, bool trigger_global_localization) +{ + rosbag::Bag bag; + bag.open(in_bag_fn, rosbag::bagmode::Read); + std::vector topics; + topics.push_back(std::string("tf")); + std::string scan_topic_name = "base_scan"; // TODO determine what topic this actually is from ROS + topics.push_back(scan_topic_name); + rosbag::View view(bag, rosbag::TopicQuery(topics)); + + ros::Publisher laser_pub = nh_.advertise(scan_topic_name, 100); + ros::Publisher tf_pub = nh_.advertise("/tf", 100); + + // Sleep for a second to let all subscribers connect + ros::WallDuration(1.0).sleep(); + + ros::WallTime start(ros::WallTime::now()); + + // Wait for map + while (ros::ok()) + { + { + boost::recursive_mutex::scoped_lock cfl(configuration_mutex_); + if (map_) + { + ROS_INFO("Map is ready"); + break; + } + } + ROS_INFO("Waiting for the map..."); + ros::getGlobalCallbackQueue()->callAvailable(ros::WallDuration(1.0)); + } + + if (trigger_global_localization) + { + std_srvs::Empty empty_srv; + globalLocalizationCallback(empty_srv.request, empty_srv.response); + } + + BOOST_FOREACH(rosbag::MessageInstance const msg, view) + { + if (!ros::ok()) + { + break; + } + + // Process any ros messages or callbacks at this point + ros::getGlobalCallbackQueue()->callAvailable(ros::WallDuration()); + + tf2_msgs::TFMessage::ConstPtr tf_msg = msg.instantiate(); + if (tf_msg != NULL) + { + tf_pub.publish(msg); + for (size_t ii=0; iitransforms.size(); ++ii) + { + tf_->setTransform(tf_msg->transforms[ii], "rosbag_authority"); + } + continue; + } + + sensor_msgs::LaserScan::ConstPtr base_scan = msg.instantiate(); + if (base_scan != NULL) + { + laser_pub.publish(msg); + laser_scan_filter_->add(base_scan); + if (bag_scan_period_ > ros::WallDuration(0)) + { + bag_scan_period_.sleep(); + } + continue; + } + + ROS_WARN_STREAM("Unsupported message type" << msg.getTopic()); + } + + bag.close(); + + double runtime = (ros::WallTime::now() - start).toSec(); + ROS_INFO("Bag complete, took %.1f seconds to process, shutting down", runtime); + + const geometry_msgs::Quaternion & q(last_published_pose.pose.pose.orientation); + double yaw, pitch, roll; + tf2::Matrix3x3(tf2::Quaternion(q.x, q.y, q.z, q.w)).getEulerYPR(yaw,pitch,roll); + ROS_INFO("Final location %.3f, %.3f, %.3f with stamp=%f", + last_published_pose.pose.pose.position.x, + last_published_pose.pose.pose.position.y, + yaw, last_published_pose.header.stamp.toSec() + ); + + ros::shutdown(); +} + + +void AmclNode::savePoseToServer() +{ + // We need to apply the last transform to the latest odom pose to get + // the latest map pose to store. We'll take the covariance from + // last_published_pose. + tf2::Transform odom_pose_tf2; + tf2::convert(latest_odom_pose_.pose, odom_pose_tf2); + tf2::Transform map_pose = latest_tf_.inverse() * odom_pose_tf2; + + double yaw = tf2::getYaw(map_pose.getRotation()); + + ROS_DEBUG("Saving pose to server. x: %.3f, y: %.3f", map_pose.getOrigin().x(), map_pose.getOrigin().y() ); + + private_nh_.setParam("initial_pose_x", map_pose.getOrigin().x()); + private_nh_.setParam("initial_pose_y", map_pose.getOrigin().y()); + private_nh_.setParam("initial_pose_a", yaw); + private_nh_.setParam("initial_cov_xx", + last_published_pose.pose.covariance[6*0+0]); + private_nh_.setParam("initial_cov_yy", + last_published_pose.pose.covariance[6*1+1]); + private_nh_.setParam("initial_cov_aa", + last_published_pose.pose.covariance[6*5+5]); +} + +void AmclNode::updatePoseFromServer() +{ + init_pose_[0] = 0.0; + init_pose_[1] = 0.0; + init_pose_[2] = 0.0; + init_cov_[0] = 0.5 * 0.5; + init_cov_[1] = 0.5 * 0.5; + init_cov_[2] = (M_PI/12.0) * (M_PI/12.0); + // Check for NAN on input from param server, #5239 + double tmp_pos; + private_nh_.param("initial_pose_x", tmp_pos, init_pose_[0]); + if(!std::isnan(tmp_pos)) + init_pose_[0] = tmp_pos; + else + ROS_WARN("ignoring NAN in initial pose X position"); + private_nh_.param("initial_pose_y", tmp_pos, init_pose_[1]); + if(!std::isnan(tmp_pos)) + init_pose_[1] = tmp_pos; + else + ROS_WARN("ignoring NAN in initial pose Y position"); + private_nh_.param("initial_pose_a", tmp_pos, init_pose_[2]); + if(!std::isnan(tmp_pos)) + init_pose_[2] = tmp_pos; + else + ROS_WARN("ignoring NAN in initial pose Yaw"); + private_nh_.param("initial_cov_xx", tmp_pos, init_cov_[0]); + if(!std::isnan(tmp_pos)) + init_cov_[0] =tmp_pos; + else + ROS_WARN("ignoring NAN in initial covariance XX"); + private_nh_.param("initial_cov_yy", tmp_pos, init_cov_[1]); + if(!std::isnan(tmp_pos)) + init_cov_[1] = tmp_pos; + else + ROS_WARN("ignoring NAN in initial covariance YY"); + private_nh_.param("initial_cov_aa", tmp_pos, init_cov_[2]); + if(!std::isnan(tmp_pos)) + init_cov_[2] = tmp_pos; + else + ROS_WARN("ignoring NAN in initial covariance AA"); +} + +void +AmclNode::checkLaserReceived(const ros::TimerEvent& event) +{ + ros::Duration d = ros::Time::now() - last_laser_received_ts_; + if(d > laser_check_interval_) + { + ROS_WARN("No laser scan received (and thus no pose updates have been published) for %f seconds. Verify that data is being published on the %s topic.", + d.toSec(), + ros::names::resolve(scan_topic_).c_str()); + } +} + +void +AmclNode::requestMap() +{ + boost::recursive_mutex::scoped_lock ml(configuration_mutex_); + + // get map via RPC + nav_msgs::GetMap::Request req; + nav_msgs::GetMap::Response resp; + ROS_INFO("Requesting the map..."); + while(!ros::service::call("static_map", req, resp)) + { + ROS_WARN("Request for map failed; trying again..."); + ros::Duration d(0.5); + d.sleep(); + } + handleMapMessage( resp.map ); +} + +void +AmclNode::mapReceived(const nav_msgs::OccupancyGridConstPtr& msg) +{ + if( first_map_only_ && first_map_received_ ) { + return; + } + + handleMapMessage( *msg ); + + first_map_received_ = true; +} + +void +AmclNode::handleMapMessage(const nav_msgs::OccupancyGrid& msg) +{ + boost::recursive_mutex::scoped_lock cfl(configuration_mutex_); + + ROS_INFO("Received a %d X %d map @ %.3f m/pix\n", + msg.info.width, + msg.info.height, + msg.info.resolution); + + if(msg.header.frame_id != global_frame_id_) + ROS_WARN("Frame_id of map received:'%s' doesn't match global_frame_id:'%s'. This could cause issues with reading published topics", + msg.header.frame_id.c_str(), + global_frame_id_.c_str()); + + freeMapDependentMemory(); + // Clear queued laser objects because they hold pointers to the existing + // map, #5202. + lasers_.clear(); + lasers_update_.clear(); + frame_to_laser_.clear(); + + map_ = convertMap(msg); + +#if NEW_UNIFORM_SAMPLING + // Index of free space + free_space_indices.resize(0); + for(int i = 0; i < map_->size_x; i++) + for(int j = 0; j < map_->size_y; j++) + if(map_->cells[MAP_INDEX(map_,i,j)].occ_state == -1) + free_space_indices.push_back(std::make_pair(i,j)); +#endif + // Create the particle filter + pf_ = pf_alloc(min_particles_, max_particles_, + alpha_slow_, alpha_fast_, + (pf_init_model_fn_t)AmclNode::uniformPoseGenerator, + (void *)map_); + pf_set_selective_resampling(pf_, selective_resampling_); + pf_->pop_err = pf_err_; + pf_->pop_z = pf_z_; + + // Initialize the filter + updatePoseFromServer(); + pf_vector_t pf_init_pose_mean = pf_vector_zero(); + pf_init_pose_mean.v[0] = init_pose_[0]; + pf_init_pose_mean.v[1] = init_pose_[1]; + pf_init_pose_mean.v[2] = init_pose_[2]; + pf_matrix_t pf_init_pose_cov = pf_matrix_zero(); + pf_init_pose_cov.m[0][0] = init_cov_[0]; + pf_init_pose_cov.m[1][1] = init_cov_[1]; + pf_init_pose_cov.m[2][2] = init_cov_[2]; + pf_init(pf_, pf_init_pose_mean, pf_init_pose_cov); + pf_init_ = false; + + // Instantiate the sensor objects + // Odometry + delete odom_; + odom_ = new AMCLOdom(); + ROS_ASSERT(odom_); + odom_->SetModel( odom_model_type_, alpha1_, alpha2_, alpha3_, alpha4_, alpha5_ ); + // Laser + delete laser_; + laser_ = new AMCLLaser(max_beams_, map_); + ROS_ASSERT(laser_); + if(laser_model_type_ == LASER_MODEL_BEAM) + laser_->SetModelBeam(z_hit_, z_short_, z_max_, z_rand_, + sigma_hit_, lambda_short_, 0.0); + else if(laser_model_type_ == LASER_MODEL_LIKELIHOOD_FIELD_PROB){ + ROS_INFO("Initializing likelihood field model; this can take some time on large maps..."); + laser_->SetModelLikelihoodFieldProb(z_hit_, z_rand_, sigma_hit_, + laser_likelihood_max_dist_, + do_beamskip_, beam_skip_distance_, + beam_skip_threshold_, beam_skip_error_threshold_); + ROS_INFO("Done initializing likelihood field model."); + } + else + { + ROS_INFO("Initializing likelihood field model; this can take some time on large maps..."); + laser_->SetModelLikelihoodField(z_hit_, z_rand_, sigma_hit_, + laser_likelihood_max_dist_); + ROS_INFO("Done initializing likelihood field model."); + } + + // In case the initial pose message arrived before the first map, + // try to apply the initial pose now that the map has arrived. + applyInitialPose(); + +} + +void +AmclNode::freeMapDependentMemory() +{ + if( map_ != NULL ) { + map_free( map_ ); + map_ = NULL; + } + if( pf_ != NULL ) { + pf_free( pf_ ); + pf_ = NULL; + } + delete odom_; + odom_ = NULL; + delete laser_; + laser_ = NULL; +} + +/** + * Convert an OccupancyGrid map message into the internal + * representation. This allocates a map_t and returns it. + */ +map_t* +AmclNode::convertMap( const nav_msgs::OccupancyGrid& map_msg ) +{ + map_t* map = map_alloc(); + ROS_ASSERT(map); + + map->size_x = map_msg.info.width; + map->size_y = map_msg.info.height; + map->scale = map_msg.info.resolution; + map->origin_x = map_msg.info.origin.position.x + (map->size_x / 2) * map->scale; + map->origin_y = map_msg.info.origin.position.y + (map->size_y / 2) * map->scale; + // Convert to player format + map->cells = (map_cell_t*)malloc(sizeof(map_cell_t)*map->size_x*map->size_y); + ROS_ASSERT(map->cells); + for(int i=0;isize_x * map->size_y;i++) + { + if(map_msg.data[i] == 0) + map->cells[i].occ_state = -1; + else if(map_msg.data[i] == 100) + map->cells[i].occ_state = +1; + else + map->cells[i].occ_state = 0; + } + + return map; +} + +AmclNode::~AmclNode() +{ + delete dsrv_; + freeMapDependentMemory(); + delete laser_scan_filter_; + delete laser_scan_sub_; + // TODO: delete everything allocated in constructor +} + +bool +AmclNode::getOdomPose(geometry_msgs::PoseStamped& odom_pose, + double& x, double& y, double& yaw, + const ros::Time& t, const std::string& f) +{ + // Get the robot's pose + geometry_msgs::PoseStamped ident; + ident.header.frame_id = stripSlash(f); + ident.header.stamp = t; + tf2::toMsg(tf2::Transform::getIdentity(), ident.pose); + try + { + this->tf_->transform(ident, odom_pose, odom_frame_id_); + } + catch(const tf2::TransformException& e) + { + ROS_WARN("Failed to compute odom pose, skipping scan (%s)", e.what()); + return false; + } + x = odom_pose.pose.position.x; + y = odom_pose.pose.position.y; + yaw = tf2::getYaw(odom_pose.pose.orientation); + + return true; +} + + +pf_vector_t +AmclNode::uniformPoseGenerator(void* arg) +{ + map_t* map = (map_t*)arg; +#if NEW_UNIFORM_SAMPLING + unsigned int rand_index = drand48() * free_space_indices.size(); + std::pair free_point = free_space_indices[rand_index]; + pf_vector_t p; + p.v[0] = MAP_WXGX(map, free_point.first); + p.v[1] = MAP_WYGY(map, free_point.second); + p.v[2] = drand48() * 2 * M_PI - M_PI; +#else + double min_x, max_x, min_y, max_y; + + min_x = (map->size_x * map->scale)/2.0 - map->origin_x; + max_x = (map->size_x * map->scale)/2.0 + map->origin_x; + min_y = (map->size_y * map->scale)/2.0 - map->origin_y; + max_y = (map->size_y * map->scale)/2.0 + map->origin_y; + + pf_vector_t p; + + ROS_DEBUG("Generating new uniform sample"); + for(;;) + { + p.v[0] = min_x + drand48() * (max_x - min_x); + p.v[1] = min_y + drand48() * (max_y - min_y); + p.v[2] = drand48() * 2 * M_PI - M_PI; + // Check that it's a free cell + int i,j; + i = MAP_GXWX(map, p.v[0]); + j = MAP_GYWY(map, p.v[1]); + if(MAP_VALID(map,i,j) && (map->cells[MAP_INDEX(map,i,j)].occ_state == -1)) + break; + } +#endif + return p; +} + +bool +AmclNode::globalLocalizationCallback(std_srvs::Empty::Request& req, + std_srvs::Empty::Response& res) +{ + if( map_ == NULL ) { + return true; + } + boost::recursive_mutex::scoped_lock gl(configuration_mutex_); + ROS_INFO("Initializing with uniform distribution"); + pf_init_model(pf_, (pf_init_model_fn_t)AmclNode::uniformPoseGenerator, + (void *)map_); + ROS_INFO("Global initialisation done!"); + pf_init_ = false; + return true; +} + +// force nomotion updates (amcl updating without requiring motion) +bool +AmclNode::nomotionUpdateCallback(std_srvs::Empty::Request& req, + std_srvs::Empty::Response& res) +{ + m_force_update = true; + //ROS_INFO("Requesting no-motion update"); + return true; +} + +bool +AmclNode::setMapCallback(nav_msgs::SetMap::Request& req, + nav_msgs::SetMap::Response& res) +{ + handleMapMessage(req.map); + handleInitialPoseMessage(req.initial_pose); + if (force_update_after_set_map_) + { + m_force_update = true; + } + res.success = true; + return true; +} + +void +AmclNode::laserReceived(const sensor_msgs::LaserScanConstPtr& laser_scan) +{ + std::string laser_scan_frame_id = stripSlash(laser_scan->header.frame_id); + last_laser_received_ts_ = ros::Time::now(); + if( map_ == NULL ) { + return; + } + boost::recursive_mutex::scoped_lock lr(configuration_mutex_); + int laser_index = -1; + + // Do we have the base->base_laser Tx yet? + if(frame_to_laser_.find(laser_scan_frame_id) == frame_to_laser_.end()) + { + ROS_DEBUG("Setting up laser %d (frame_id=%s)\n", (int)frame_to_laser_.size(), laser_scan_frame_id.c_str()); + lasers_.push_back(new AMCLLaser(*laser_)); + lasers_update_.push_back(true); + laser_index = frame_to_laser_.size(); + + geometry_msgs::PoseStamped ident; + ident.header.frame_id = laser_scan_frame_id; + ident.header.stamp = ros::Time(); + tf2::toMsg(tf2::Transform::getIdentity(), ident.pose); + + geometry_msgs::PoseStamped laser_pose; + try + { + this->tf_->transform(ident, laser_pose, base_frame_id_); + } + catch(const tf2::TransformException& e) + { + ROS_ERROR("Couldn't transform from %s to %s, " + "even though the message notifier is in use", + laser_scan_frame_id.c_str(), + base_frame_id_.c_str()); + return; + } + + pf_vector_t laser_pose_v; + laser_pose_v.v[0] = laser_pose.pose.position.x; + laser_pose_v.v[1] = laser_pose.pose.position.y; + // laser mounting angle gets computed later -> set to 0 here! + laser_pose_v.v[2] = 0; + lasers_[laser_index]->SetLaserPose(laser_pose_v); + ROS_DEBUG("Received laser's pose wrt robot: %.3f %.3f %.3f", + laser_pose_v.v[0], + laser_pose_v.v[1], + laser_pose_v.v[2]); + + frame_to_laser_[laser_scan_frame_id] = laser_index; + } else { + // we have the laser pose, retrieve laser index + laser_index = frame_to_laser_[laser_scan_frame_id]; + } + + // Where was the robot when this scan was taken? + pf_vector_t pose; + if(!getOdomPose(latest_odom_pose_, pose.v[0], pose.v[1], pose.v[2], + laser_scan->header.stamp, base_frame_id_)) + { + ROS_ERROR("Couldn't determine robot's pose associated with laser scan"); + return; + } + + + pf_vector_t delta = pf_vector_zero(); + + if(pf_init_) + { + // Compute change in pose + //delta = pf_vector_coord_sub(pose, pf_odom_pose_); + delta.v[0] = pose.v[0] - pf_odom_pose_.v[0]; + delta.v[1] = pose.v[1] - pf_odom_pose_.v[1]; + delta.v[2] = angle_diff(pose.v[2], pf_odom_pose_.v[2]); + + // See if we should update the filter + bool update = fabs(delta.v[0]) > d_thresh_ || + fabs(delta.v[1]) > d_thresh_ || + fabs(delta.v[2]) > a_thresh_; + update = update || m_force_update; + m_force_update=false; + + // Set the laser update flags + if(update) + for(unsigned int i=0; i < lasers_update_.size(); i++) + lasers_update_[i] = true; + } + + bool force_publication = false; + if(!pf_init_) + { + // Pose at last filter update + pf_odom_pose_ = pose; + + // Filter is now initialized + pf_init_ = true; + + // Should update sensor data + for(unsigned int i=0; i < lasers_update_.size(); i++) + lasers_update_[i] = true; + + force_publication = true; + + resample_count_ = 0; + } + // If the robot has moved, update the filter + else if(pf_init_ && lasers_update_[laser_index]) + { + //printf("pose\n"); + //pf_vector_fprintf(pose, stdout, "%.3f"); + + AMCLOdomData odata; + odata.pose = pose; + // HACK + // Modify the delta in the action data so the filter gets + // updated correctly + odata.delta = delta; + + // Use the action data to update the filter + odom_->UpdateAction(pf_, (AMCLSensorData*)&odata); + + // Pose at last filter update + //this->pf_odom_pose = pose; + } + + bool resampled = false; + // If the robot has moved, update the filter + if(lasers_update_[laser_index]) + { + AMCLLaserData ldata; + ldata.sensor = lasers_[laser_index]; + ldata.range_count = laser_scan->ranges.size(); + + // To account for lasers that are mounted upside-down, we determine the + // min, max, and increment angles of the laser in the base frame. + // + // Construct min and max angles of laser, in the base_link frame. + tf2::Quaternion q; + q.setRPY(0.0, 0.0, laser_scan->angle_min); + geometry_msgs::QuaternionStamped min_q, inc_q; + min_q.header.stamp = laser_scan->header.stamp; + min_q.header.frame_id = stripSlash(laser_scan->header.frame_id); + tf2::convert(q, min_q.quaternion); + + q.setRPY(0.0, 0.0, laser_scan->angle_min + laser_scan->angle_increment); + inc_q.header = min_q.header; + tf2::convert(q, inc_q.quaternion); + try + { + tf_->transform(min_q, min_q, base_frame_id_); + tf_->transform(inc_q, inc_q, base_frame_id_); + } + catch(const tf2::TransformException& e) + { + ROS_WARN("Unable to transform min/max laser angles into base frame: %s", + e.what()); + return; + } + + double angle_min = tf2::getYaw(min_q.quaternion); + double angle_increment = tf2::getYaw(inc_q.quaternion) - angle_min; + + // wrapping angle to [-pi .. pi] + angle_increment = fmod(angle_increment + 5*M_PI, 2*M_PI) - M_PI; + + ROS_DEBUG("Laser %d angles in base frame: min: %.3f inc: %.3f", laser_index, angle_min, angle_increment); + + // Apply range min/max thresholds, if the user supplied them + if(laser_max_range_ > 0.0) + ldata.range_max = std::min(laser_scan->range_max, (float)laser_max_range_); + else + ldata.range_max = laser_scan->range_max; + double range_min; + if(laser_min_range_ > 0.0) + range_min = std::max(laser_scan->range_min, (float)laser_min_range_); + else + range_min = laser_scan->range_min; + + if(ldata.range_max <= 0.0 || range_min < 0.0) { + ROS_ERROR("range_max or range_min from laser is negative! ignore this message."); + return; // ignore this. + } + + // The AMCLLaserData destructor will free this memory + ldata.ranges = new double[ldata.range_count][2]; + ROS_ASSERT(ldata.ranges); + for(int i=0;iranges[i] <= range_min) + ldata.ranges[i][0] = ldata.range_max; + else if(laser_scan->ranges[i] > ldata.range_max) + ldata.ranges[i][0] = std::numeric_limits::max(); + else + ldata.ranges[i][0] = laser_scan->ranges[i]; + // Compute bearing + ldata.ranges[i][1] = angle_min + + (i * angle_increment); + } + + lasers_[laser_index]->UpdateSensor(pf_, (AMCLSensorData*)&ldata); + + lasers_update_[laser_index] = false; + + pf_odom_pose_ = pose; + + // Resample the particles + if(!(++resample_count_ % resample_interval_)) + { + pf_update_resample(pf_); + resampled = true; + } + + pf_sample_set_t* set = pf_->sets + pf_->current_set; + ROS_DEBUG("Num samples: %d\n", set->sample_count); + + // Publish the resulting cloud + // TODO: set maximum rate for publishing + if (!m_force_update) + { + geometry_msgs::PoseArray cloud_msg; + cloud_msg.header.stamp = ros::Time::now(); + cloud_msg.header.frame_id = global_frame_id_; + cloud_msg.poses.resize(set->sample_count); + for(int i=0;isample_count;i++) + { + cloud_msg.poses[i].position.x = set->samples[i].pose.v[0]; + cloud_msg.poses[i].position.y = set->samples[i].pose.v[1]; + cloud_msg.poses[i].position.z = 0; + tf2::Quaternion q; + q.setRPY(0, 0, set->samples[i].pose.v[2]); + tf2::convert(q, cloud_msg.poses[i].orientation); + } + particlecloud_pub_.publish(cloud_msg); + } + } + + if(resampled || force_publication) + { + // Read out the current hypotheses + double max_weight = 0.0; + int max_weight_hyp = -1; + std::vector hyps; + hyps.resize(pf_->sets[pf_->current_set].cluster_count); + for(int hyp_count = 0; + hyp_count < pf_->sets[pf_->current_set].cluster_count; hyp_count++) + { + double weight; + pf_vector_t pose_mean; + pf_matrix_t pose_cov; + if (!pf_get_cluster_stats(pf_, hyp_count, &weight, &pose_mean, &pose_cov)) + { + ROS_ERROR("Couldn't get stats on cluster %d", hyp_count); + break; + } + + hyps[hyp_count].weight = weight; + hyps[hyp_count].pf_pose_mean = pose_mean; + hyps[hyp_count].pf_pose_cov = pose_cov; + + if(hyps[hyp_count].weight > max_weight) + { + max_weight = hyps[hyp_count].weight; + max_weight_hyp = hyp_count; + } + } + + if(max_weight > 0.0) + { + ROS_DEBUG("Max weight pose: %.3f %.3f %.3f", + hyps[max_weight_hyp].pf_pose_mean.v[0], + hyps[max_weight_hyp].pf_pose_mean.v[1], + hyps[max_weight_hyp].pf_pose_mean.v[2]); + + /* + puts(""); + pf_matrix_fprintf(hyps[max_weight_hyp].pf_pose_cov, stdout, "%6.3f"); + puts(""); + */ + + geometry_msgs::PoseWithCovarianceStamped p; + // Fill in the header + p.header.frame_id = global_frame_id_; + p.header.stamp = laser_scan->header.stamp; + // Copy in the pose + p.pose.pose.position.x = hyps[max_weight_hyp].pf_pose_mean.v[0]; + p.pose.pose.position.y = hyps[max_weight_hyp].pf_pose_mean.v[1]; + + tf2::Quaternion q; + q.setRPY(0, 0, hyps[max_weight_hyp].pf_pose_mean.v[2]); + tf2::convert(q, p.pose.pose.orientation); + // Copy in the covariance, converting from 3-D to 6-D + pf_sample_set_t* set = pf_->sets + pf_->current_set; + for(int i=0; i<2; i++) + { + for(int j=0; j<2; j++) + { + // Report the overall filter covariance, rather than the + // covariance for the highest-weight cluster + //p.covariance[6*i+j] = hyps[max_weight_hyp].pf_pose_cov.m[i][j]; + p.pose.covariance[6*i+j] = set->cov.m[i][j]; + } + } + // Report the overall filter covariance, rather than the + // covariance for the highest-weight cluster + //p.covariance[6*5+5] = hyps[max_weight_hyp].pf_pose_cov.m[2][2]; + p.pose.covariance[6*5+5] = set->cov.m[2][2]; + + /* + printf("cov:\n"); + for(int i=0; i<6; i++) + { + for(int j=0; j<6; j++) + printf("%6.3f ", p.covariance[6*i+j]); + puts(""); + } + */ + + pose_pub_.publish(p); + last_published_pose = p; + + ROS_DEBUG("New pose: %6.3f %6.3f %6.3f", + hyps[max_weight_hyp].pf_pose_mean.v[0], + hyps[max_weight_hyp].pf_pose_mean.v[1], + hyps[max_weight_hyp].pf_pose_mean.v[2]); + + // subtracting base to odom from map to base and send map to odom instead + geometry_msgs::PoseStamped odom_to_map; + try + { + tf2::Quaternion q; + q.setRPY(0, 0, hyps[max_weight_hyp].pf_pose_mean.v[2]); + tf2::Transform tmp_tf(q, tf2::Vector3(hyps[max_weight_hyp].pf_pose_mean.v[0], + hyps[max_weight_hyp].pf_pose_mean.v[1], + 0.0)); + + geometry_msgs::PoseStamped tmp_tf_stamped; + tmp_tf_stamped.header.frame_id = base_frame_id_; + tmp_tf_stamped.header.stamp = laser_scan->header.stamp; + tf2::toMsg(tmp_tf.inverse(), tmp_tf_stamped.pose); + + this->tf_->transform(tmp_tf_stamped, odom_to_map, odom_frame_id_); + } + catch(const tf2::TransformException&) + { + ROS_DEBUG("Failed to subtract base to odom transform"); + return; + } + + tf2::convert(odom_to_map.pose, latest_tf_); + latest_tf_valid_ = true; + + if (tf_broadcast_ == true) + { + // We want to send a transform that is good up until a + // tolerance time so that odom can be used + ros::Time transform_expiration = (laser_scan->header.stamp + + transform_tolerance_); + geometry_msgs::TransformStamped tmp_tf_stamped; + tmp_tf_stamped.header.frame_id = global_frame_id_; + tmp_tf_stamped.header.stamp = transform_expiration; + tmp_tf_stamped.child_frame_id = odom_frame_id_; + tf2::convert(latest_tf_.inverse(), tmp_tf_stamped.transform); + + this->tfb_->sendTransform(tmp_tf_stamped); + sent_first_transform_ = true; + } + } + else + { + ROS_ERROR("No pose!"); + } + } + else if(latest_tf_valid_) + { + if (tf_broadcast_ == true) + { + // Nothing changed, so we'll just republish the last transform, to keep + // everybody happy. + ros::Time transform_expiration = (laser_scan->header.stamp + + transform_tolerance_); + geometry_msgs::TransformStamped tmp_tf_stamped; + tmp_tf_stamped.header.frame_id = global_frame_id_; + tmp_tf_stamped.header.stamp = transform_expiration; + tmp_tf_stamped.child_frame_id = odom_frame_id_; + tf2::convert(latest_tf_.inverse(), tmp_tf_stamped.transform); + this->tfb_->sendTransform(tmp_tf_stamped); + } + + // Is it time to save our last pose to the param server + ros::Time now = ros::Time::now(); + if((save_pose_period.toSec() > 0.0) && + (now - save_pose_last_time) >= save_pose_period) + { + this->savePoseToServer(); + save_pose_last_time = now; + } + } + + diagnosic_updater_.update(); +} + +void +AmclNode::initialPoseReceived(const geometry_msgs::PoseWithCovarianceStampedConstPtr& msg) +{ + handleInitialPoseMessage(*msg); + if (force_update_after_initialpose_) + { + m_force_update = true; + } +} + +void +AmclNode::handleInitialPoseMessage(const geometry_msgs::PoseWithCovarianceStamped& msg) +{ + boost::recursive_mutex::scoped_lock prl(configuration_mutex_); + if(msg.header.frame_id == "") + { + // This should be removed at some point + ROS_WARN("Received initial pose with empty frame_id. You should always supply a frame_id."); + } + // We only accept initial pose estimates in the global frame, #5148. + else if(stripSlash(msg.header.frame_id) != global_frame_id_) + { + ROS_WARN("Ignoring initial pose in frame \"%s\"; initial poses must be in the global frame, \"%s\"", + stripSlash(msg.header.frame_id).c_str(), + global_frame_id_.c_str()); + return; + } + + // In case the client sent us a pose estimate in the past, integrate the + // intervening odometric change. + geometry_msgs::TransformStamped tx_odom; + try + { + // wait a little for the latest tf to become available + tx_odom = tf_->lookupTransform(base_frame_id_, msg.header.stamp, + base_frame_id_, ros::Time::now(), + odom_frame_id_, ros::Duration(0.5)); + } + catch(const tf2::TransformException& e) + { + // If we've never sent a transform, then this is normal, because the + // global_frame_id_ frame doesn't exist. We only care about in-time + // transformation for on-the-move pose-setting, so ignoring this + // startup condition doesn't really cost us anything. + if(sent_first_transform_) + ROS_WARN("Failed to transform initial pose in time (%s)", e.what()); + tf2::convert(tf2::Transform::getIdentity(), tx_odom.transform); + } + + tf2::Transform tx_odom_tf2; + tf2::convert(tx_odom.transform, tx_odom_tf2); + tf2::Transform pose_old, pose_new; + tf2::convert(msg.pose.pose, pose_old); + pose_new = pose_old * tx_odom_tf2; + + // Transform into the global frame + + ROS_INFO("Setting pose (%.6f): %.3f %.3f %.3f", + ros::Time::now().toSec(), + pose_new.getOrigin().x(), + pose_new.getOrigin().y(), + tf2::getYaw(pose_new.getRotation())); + // Re-initialize the filter + pf_vector_t pf_init_pose_mean = pf_vector_zero(); + pf_init_pose_mean.v[0] = pose_new.getOrigin().x(); + pf_init_pose_mean.v[1] = pose_new.getOrigin().y(); + pf_init_pose_mean.v[2] = tf2::getYaw(pose_new.getRotation()); + pf_matrix_t pf_init_pose_cov = pf_matrix_zero(); + // Copy in the covariance, converting from 6-D to 3-D + for(int i=0; i<2; i++) + { + for(int j=0; j<2; j++) + { + pf_init_pose_cov.m[i][j] = msg.pose.covariance[6*i+j]; + } + } + pf_init_pose_cov.m[2][2] = msg.pose.covariance[6*5+5]; + + delete initial_pose_hyp_; + initial_pose_hyp_ = new amcl_hyp_t(); + initial_pose_hyp_->pf_pose_mean = pf_init_pose_mean; + initial_pose_hyp_->pf_pose_cov = pf_init_pose_cov; + applyInitialPose(); +} + +/** + * If initial_pose_hyp_ and map_ are both non-null, apply the initial + * pose to the particle filter state. initial_pose_hyp_ is deleted + * and set to NULL after it is used. + */ +void +AmclNode::applyInitialPose() +{ + boost::recursive_mutex::scoped_lock cfl(configuration_mutex_); + if( initial_pose_hyp_ != NULL && map_ != NULL ) { + pf_init(pf_, initial_pose_hyp_->pf_pose_mean, initial_pose_hyp_->pf_pose_cov); + pf_init_ = false; + + delete initial_pose_hyp_; + initial_pose_hyp_ = NULL; + } +} + +void +AmclNode::standardDeviationDiagnostics(diagnostic_updater::DiagnosticStatusWrapper& diagnostic_status) +{ + double std_x = sqrt(last_published_pose.pose.covariance[6*0+0]); + double std_y = sqrt(last_published_pose.pose.covariance[6*1+1]); + double std_yaw = sqrt(last_published_pose.pose.covariance[6*5+5]); + + diagnostic_status.add("std_x", std_x); + diagnostic_status.add("std_y", std_y); + diagnostic_status.add("std_yaw", std_yaw); + diagnostic_status.add("std_warn_level_x", std_warn_level_x_); + diagnostic_status.add("std_warn_level_y", std_warn_level_y_); + diagnostic_status.add("std_warn_level_yaw", std_warn_level_yaw_); + + if (std_x > std_warn_level_x_ || std_y > std_warn_level_y_ || std_yaw > std_warn_level_yaw_) + { + diagnostic_status.summary(diagnostic_msgs::DiagnosticStatus::WARN, "Too large"); + } + else + { + diagnostic_status.summary(diagnostic_msgs::DiagnosticStatus::OK, "OK"); + } +} diff --git a/navigations/amcl/src/include/portable_utils.hpp b/navigations/amcl/src/include/portable_utils.hpp new file mode 100755 index 0000000..8570393 --- /dev/null +++ b/navigations/amcl/src/include/portable_utils.hpp @@ -0,0 +1,28 @@ +#ifndef PORTABLE_UTILS_H +#define PORTABLE_UTILS_H + +#include + +#ifdef __cplusplus +extern "C" { +#endif + +#ifndef HAVE_DRAND48 +// Some system (e.g., Windows) doesn't come with drand48(), srand48(). +// Use rand, and srand for such system. +static double drand48(void) +{ + return ((double)rand())/RAND_MAX; +} + +static void srand48(long int seedval) +{ + srand(seedval); +} +#endif + +#ifdef __cplusplus +} +#endif + +#endif \ No newline at end of file diff --git a/navigations/amcl/test/basic_localization.py b/navigations/amcl/test/basic_localization.py new file mode 100755 index 0000000..4f5fa4a --- /dev/null +++ b/navigations/amcl/test/basic_localization.py @@ -0,0 +1,101 @@ +#!/usr/bin/env python + +from __future__ import print_function + +import sys +import time +from math import fmod, pi + +import unittest +import rospy +import rostest + +import tf2_py as tf2 +import tf2_ros +import PyKDL +from std_srvs.srv import Empty + + +class TestBasicLocalization(unittest.TestCase): + def setUp(self): + self.tf = None + self.target_x = None + self.target_y = None + self.target_a = None + self.tfBuffer = None + + def print_pose_diff(self): + a_curr = self.compute_angle() + a_diff = self.wrap_angle(a_curr - self.target_a) + print('Curr:\t %16.6f %16.6f %16.6f' % (self.tf.translation.x, self.tf.translation.y, a_curr)) + print('Target:\t %16.6f %16.6f %16.6f' % (self.target_x, self.target_y, self.target_a)) + print('Diff:\t %16.6f %16.6f %16.6f' % ( + abs(self.tf.translation.x - self.target_x), abs(self.tf.translation.y - self.target_y), a_diff)) + + def get_pose(self): + try: + tf_stamped = self.tfBuffer.lookup_transform("map", "base_link", rospy.Time()) + self.tf = tf_stamped.transform + self.print_pose_diff() + except (tf2.LookupException, tf2.ExtrapolationException): + pass + + @staticmethod + def wrap_angle(angle): + """ + Wrap angle to [-pi, pi) + :param angle: Angle to be wrapped + :return: wrapped angle + """ + angle += pi + while angle < 0: + angle += 2*pi + return fmod(angle, 2*pi) - pi + + def compute_angle(self): + rot = self.tf.rotation + a_curr = PyKDL.Rotation.Quaternion(rot.x, rot.y, rot.z, rot.w).GetRPY()[2] + a_diff = self.wrap_angle(a_curr - self.target_a) + return self.target_a + a_diff + + def test_basic_localization(self): + global_localization = int(sys.argv[1]) + self.target_x = float(sys.argv[2]) + self.target_y = float(sys.argv[3]) + self.target_a = self.wrap_angle(float(sys.argv[4])) + tolerance_d = float(sys.argv[5]) + tolerance_a = float(sys.argv[6]) + target_time = float(sys.argv[7]) + + rospy.init_node('test', anonymous=True) + while rospy.rostime.get_time() == 0.0: + print('Waiting for initial time publication') + time.sleep(0.1) + + if global_localization == 1: + print('Waiting for service global_localization') + rospy.wait_for_service('global_localization') + global_localization = rospy.ServiceProxy('global_localization', Empty) + global_localization() + + start_time = rospy.rostime.get_time() + self.tfBuffer = tf2_ros.Buffer() + listener = tf2_ros.TransformListener(self.tfBuffer) + + while (rospy.rostime.get_time() - start_time) < target_time: + print('Waiting for end time %.6f (current: %.6f)' % (target_time, (rospy.rostime.get_time() - start_time))) + self.get_pose() + time.sleep(0.1) + + print("Final pose:") + self.get_pose() + a_curr = self.compute_angle() + + self.assertNotEqual(self.tf, None) + self.assertAlmostEqual(self.tf.translation.x, self.target_x, delta=tolerance_d) + self.assertAlmostEqual(self.tf.translation.y, self.target_y, delta=tolerance_d) + self.assertAlmostEqual(a_curr, self.target_a, delta=tolerance_a) + + +if __name__ == '__main__': + rostest.run('amcl', 'amcl_localization', TestBasicLocalization, sys.argv) \ No newline at end of file diff --git a/navigations/amcl/test/basic_localization_stage.xml b/navigations/amcl/test/basic_localization_stage.xml new file mode 100755 index 0000000..3184121 --- /dev/null +++ b/navigations/amcl/test/basic_localization_stage.xml @@ -0,0 +1,51 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/navigations/amcl/test/global_localization_stage.xml b/navigations/amcl/test/global_localization_stage.xml new file mode 100755 index 0000000..8fca2ae --- /dev/null +++ b/navigations/amcl/test/global_localization_stage.xml @@ -0,0 +1,48 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/navigations/amcl/test/rosie_multilaser.xml b/navigations/amcl/test/rosie_multilaser.xml new file mode 100755 index 0000000..ade665a --- /dev/null +++ b/navigations/amcl/test/rosie_multilaser.xml @@ -0,0 +1,51 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/navigations/amcl/test/set_initial_pose.xml b/navigations/amcl/test/set_initial_pose.xml new file mode 100755 index 0000000..58d8432 --- /dev/null +++ b/navigations/amcl/test/set_initial_pose.xml @@ -0,0 +1,54 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/navigations/amcl/test/set_initial_pose_delayed.xml b/navigations/amcl/test/set_initial_pose_delayed.xml new file mode 100755 index 0000000..cae2ec3 --- /dev/null +++ b/navigations/amcl/test/set_initial_pose_delayed.xml @@ -0,0 +1,58 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/navigations/amcl/test/set_pose.py b/navigations/amcl/test/set_pose.py new file mode 100755 index 0000000..74592ed --- /dev/null +++ b/navigations/amcl/test/set_pose.py @@ -0,0 +1,46 @@ +#!/usr/bin/env python + +import rospy + +import math +import PyKDL +from geometry_msgs.msg import PoseWithCovarianceStamped + + +class PoseSetter(rospy.SubscribeListener): + def __init__(self, pose, stamp, publish_time): + self.pose = pose + self.stamp = stamp + self.publish_time = publish_time + + def peer_subscribe(self, topic_name, topic_publish, peer_publish): + p = PoseWithCovarianceStamped() + p.header.frame_id = "map" + p.header.stamp = self.stamp + p.pose.pose.position.x = self.pose[0] + p.pose.pose.position.y = self.pose[1] + (p.pose.pose.orientation.x, + p.pose.pose.orientation.y, + p.pose.pose.orientation.z, + p.pose.pose.orientation.w) = PyKDL.Rotation.RPY(0, 0, self.pose[2]).GetQuaternion() + p.pose.covariance[6*0+0] = 0.5 * 0.5 + p.pose.covariance[6*1+1] = 0.5 * 0.5 + p.pose.covariance[6*3+3] = math.pi/12.0 * math.pi/12.0 + # wait for the desired publish time + while rospy.get_rostime() < self.publish_time: + rospy.sleep(0.01) + peer_publish(p) + + +if __name__ == '__main__': + pose = list(map(float, rospy.myargv()[1:4])) + t_stamp = rospy.Time() + t_publish = rospy.Time() + if len(rospy.myargv()) > 4: + t_stamp = rospy.Time.from_sec(float(rospy.myargv()[4])) + if len(rospy.myargv()) > 5: + t_publish = rospy.Time.from_sec(float(rospy.myargv()[5])) + rospy.init_node('pose_setter', anonymous=True) + rospy.loginfo("Going to publish pose {} with stamp {} at {}".format(pose, t_stamp.to_sec(), t_publish.to_sec())) + pub = rospy.Publisher("initialpose", PoseWithCovarianceStamped, PoseSetter(pose, stamp=t_stamp, publish_time=t_publish), queue_size=1) + rospy.spin() diff --git a/navigations/amcl/test/small_loop_crazy_driving_prg.xml b/navigations/amcl/test/small_loop_crazy_driving_prg.xml new file mode 100755 index 0000000..7169c1c --- /dev/null +++ b/navigations/amcl/test/small_loop_crazy_driving_prg.xml @@ -0,0 +1,51 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/navigations/amcl/test/small_loop_crazy_driving_prg_corrected.xml b/navigations/amcl/test/small_loop_crazy_driving_prg_corrected.xml new file mode 100755 index 0000000..ce4f2d4 --- /dev/null +++ b/navigations/amcl/test/small_loop_crazy_driving_prg_corrected.xml @@ -0,0 +1,51 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/navigations/amcl/test/small_loop_prf.xml b/navigations/amcl/test/small_loop_prf.xml new file mode 100755 index 0000000..eadbd10 --- /dev/null +++ b/navigations/amcl/test/small_loop_prf.xml @@ -0,0 +1,48 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/navigations/amcl/test/texas_greenroom_loop.xml b/navigations/amcl/test/texas_greenroom_loop.xml new file mode 100755 index 0000000..7fea530 --- /dev/null +++ b/navigations/amcl/test/texas_greenroom_loop.xml @@ -0,0 +1,41 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/navigations/amcl/test/texas_greenroom_loop_corrected.xml b/navigations/amcl/test/texas_greenroom_loop_corrected.xml new file mode 100755 index 0000000..90ee389 --- /dev/null +++ b/navigations/amcl/test/texas_greenroom_loop_corrected.xml @@ -0,0 +1,41 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/navigations/amcl/test/texas_willow_hallway_loop.xml b/navigations/amcl/test/texas_willow_hallway_loop.xml new file mode 100755 index 0000000..c223308 --- /dev/null +++ b/navigations/amcl/test/texas_willow_hallway_loop.xml @@ -0,0 +1,41 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/navigations/amcl/test/texas_willow_hallway_loop_corrected.xml b/navigations/amcl/test/texas_willow_hallway_loop_corrected.xml new file mode 100755 index 0000000..bd01194 --- /dev/null +++ b/navigations/amcl/test/texas_willow_hallway_loop_corrected.xml @@ -0,0 +1,41 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/navigations/base_local_planner/CHANGELOG.rst b/navigations/base_local_planner/CHANGELOG.rst new file mode 100755 index 0000000..257807e --- /dev/null +++ b/navigations/base_local_planner/CHANGELOG.rst @@ -0,0 +1,214 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package base_local_planner +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +1.17.3 (2023-01-10) +------------------- +* [ROS-O] various patches (`#1225 `_) + * do not specify obsolete c++11 standard + this breaks with current versions of log4cxx. + * update pluginlib include paths + the non-hpp headers have been deprecated since kinetic + * use lambdas in favor of boost::bind + Using boost's _1 as a global system is deprecated since C++11. + The ROS packages in Debian removed the implicit support for the global symbols, + so this code fails to compile there without the patch. +* Contributors: Michael Görner + +1.17.2 (2022-06-20) +------------------- +* Commit 89a8593 removed footprint scaling. This brings it back. (`#886 `_) (`#1204 `_) + Co-authored-by: Frank Höller +* Contributors: Michael Ferguson + +1.17.1 (2020-08-27) +------------------- +* occdist_scale should not be scaled by the costmap resolution as it doesn't multiply a value that includes a distance. (`#1000 `_) +* Contributors: wjwagner + +1.17.0 (2020-04-02) +------------------- +* Merge pull request `#982 `_ from ros-planning/noetic_prep + Noetic Migration +* increase required cmake version +* Contributors: Michael Ferguson + +1.16.6 (2020-03-18) +------------------- +* Fix Unknown CMake command check_include_file (navfn & base_local_planner) (`#975 `_) +* Contributors: Sam Pfeiffer + +1.16.5 (2020-03-15) +------------------- +* [melodic] updated install for better portability. (`#973 `_) +* Contributors: Sean Yen + +1.16.4 (2020-03-04) +------------------- +* Fixes gdist- and pdist_scale node paramter names (`#936 `_) + Renames goal and path distance dynamic reconfigure parameter + names in the cfg file in order to actually make the parameters + used by the trajectory planner changeable. + Fixes `#935 `_ +* don't include a main() function in base_local_planner library (`#969 `_) +* [Windows][melodic] Navigation (except for map_server and amcl) Windows build bring up (`#851 `_) +* Contributors: David Leins, Sean Yen, ipa-fez + +1.16.3 (2019-11-15) +------------------- +* Merge branch 'melodic-devel' into layer_clear_area-melodic +* Provide different negative values for unknown and out-of-map costs (`#833 `_) +* Merge pull request `#857 `_ from jspricke/add_include + Add missing header +* Add missing header +* [kinetic] Fix for adjusting plan resolution (`#819 `_) + * Fix for adjusting plan resolution + * Simpler math expression +* Contributors: David V. Lu!!, Jochen Sprickerhof, Jorge Santos Simón, Michael Ferguson, Steven Macenski + +1.16.2 (2018-07-31) +------------------- +* Merge pull request `#773 `_ from ros-planning/packaging_fixes + packaging fixes +* add explicit sensor_msgs, tf2 depends for base_local_planner +* Contributors: Michael Ferguson + +1.16.1 (2018-07-28) +------------------- + +1.16.0 (2018-07-25) +------------------- +* Remove PCL `#765 `_ +* Switch to TF2 `#755 `_ +* Fix trajectory obstacle scoring in dwa_local_planner. +* Make trajectory scoring scales consistent. +* unify parameter names between base_local_planner and dwa_local_planner + addresses parts of `#90 `_ +* fix param to min_in_place_vel_theta, closes `#487 `_ +* add const to getLocalPlane, fixes `#709 `_ +* Merge pull request `#732 `_ from marting87/small_typo_fixes + Small typo fixes in ftrajectory_planner_ros and robot_pose_ekf +* Fixed typos for base_local_planner +* Contributors: Alexander Moriarty, David V. Lu, Martin Ganeff, Michael Ferguson, Pavlo Kolomiiets, Rein Appeldoorn, Vincent Rabaud, moriarty + +1.15.2 (2018-03-22) +------------------- +* Merge pull request `#673 `_ from ros-planning/email_update_lunar + update maintainer email (lunar) +* CostmapModel: Make lineCost and pointCost public (`#658 `_) + Make the methods `lineCost` and `pointCost` of the CostmapModel class + public so they can be used outside of the class. + Both methods are not changing the instance, so this should not cause any + problems. To emphasise their constness, add the actual `const` keyword. +* Merge pull request `#649 `_ from aaronhoy/lunar_add_ahoy + Add myself as a maintainer. +* Contributors: Aaron Hoy, Felix Widmaier, Michael Ferguson + +1.15.1 (2017-08-14) +------------------- + +1.15.0 (2017-08-07) +------------------- +* set message_generation build and runtime dependency +* convert packages to format2 +* cleaner logic, fixes `#156 `_ +* Merge pull request `#596 `_ from ros-planning/lunar_548 +* Add cost function to prevent unnecessary spinning +* Fix CMakeLists + package.xmls (`#548 `_) +* add missing deps on libpcl +* import only PCL common +* pcl proagate -lQt5::Widgets flag so we need to find_package Qt5Widgets (`#578 `_) +* make rostest in CMakeLists optional (`ros/rosdistro#3010 `_) +* remove GCC warnings +* Contributors: Lukas Bulwahn, Martin Günther, Michael Ferguson, Mikael Arguedas, Morgan Quigley, Vincent Rabaud, lengly + +1.14.0 (2016-05-20) +------------------- + +1.13.1 (2015-10-29) +------------------- +* base_local_planner: some fixes in goal_functions +* Merge pull request `#348 `_ from mikeferguson/trajectory_planner_fixes +* fix stuck_left/right calculation +* fix calculation of heading diff +* Contributors: Gael Ecorchard, Michael Ferguson + +1.13.0 (2015-03-17) +------------------- +* remove previously deprecated param +* Contributors: Michael Ferguson + +1.12.0 (2015-02-04) +------------------- +* update maintainer email +* Contributors: Michael Ferguson + +1.11.15 (2015-02-03) +-------------------- +* Add ARCHIVE_DESTINATION for static builds +* Contributors: Gary Servin + +1.11.14 (2014-12-05) +-------------------- +* Fixed setting child_frame_id in base_local_planner::OdometryHelperRos +* Contributors: Mani Monajjemi + +1.11.13 (2014-10-02) +-------------------- + +1.11.12 (2014-10-01) +-------------------- +* Bugfix uninitialised occ_cost variable usage + This fixes `#256 `_. +* base_local_planner: adds waitForTransform +* Fixed issue causing trajectory planner returning false to isGoalReach ed even when it's control thread finishes executing +* Contributors: Daniel Stonier, Marcus Liebhardt, hes3pal + +1.11.11 (2014-07-23) +-------------------- +* Minor code cleanup +* Contributors: Enrique Fernández Perdomo + +1.11.10 (2014-06-25) +-------------------- +* Remove unnecessary colons +* renames acc_lim_th to acc_lim_theta, add warning if using acc_lim_th +* uses odom child_frame_id to set robot_vel frame_id +* Contributors: David Lu!!, Michael Ferguson, Enrique Fernández Perdomo + +1.11.9 (2014-06-10) +------------------- +* uses ::hypot(x, y) instead of sqrt(x*x, y*y) +* No need to use `limits->` +* Contributors: Enrique Fernández Perdomo + +1.11.8 (2014-05-21) +------------------- + +1.11.7 (2014-05-21) +------------------- +* fixes latch_xy_goal_tolerance param not taken +* update build to find eigen using cmake_modules +* Trajectory: fix constness of getter methods +* Use hypot() instead of sqrt(x*x, y*y) +* Fix bug in distance calculation for trajectory rollout +* Some documentation fixes in SimpleTrajectoryGenerator +* Contributors: Michael Ferguson, Siegfried-A. Gevatter Pujals, enriquefernandez + +1.11.5 (2014-01-30) +------------------- +* Merge pull request `#152 `_ from KaijenHsiao/hydro-devel + uncommented trajectory_planner_ros from catkin_package LIBRARIES so other packages can find it +* Fix negative score bug, add ability to sum scores +* Ignore pyc files from running in devel +* Correct type of prefer_forward penalty member variable +* uncommented trajectory_planner_ros from catkin_package LIBRARIES so other packages can find it +* Better handling of frame param in MapGridVisualizer +* check for CATKIN_ENABLE_TESTING +* Change maintainer from Hersh to Lu + +1.11.4 (2013-09-27) +------------------- +* Package URL Updates +* Changed new Odom-Helper::initialize() function to setOdomTopic(). +* Converted to a pointcloud pointer in Observation in more places. diff --git a/navigations/base_local_planner/CMakeLists.txt b/navigations/base_local_planner/CMakeLists.txt new file mode 100755 index 0000000..b942aac --- /dev/null +++ b/navigations/base_local_planner/CMakeLists.txt @@ -0,0 +1,165 @@ +cmake_minimum_required(VERSION 3.0.2) +project(base_local_planner) + +include(CheckIncludeFile) + +find_package(catkin REQUIRED + COMPONENTS + angles + cmake_modules + costmap_2d + dynamic_reconfigure + geometry_msgs + message_generation + nav_core + nav_msgs + pluginlib + roscpp + rospy + sensor_msgs + std_msgs + tf2 + tf2_geometry_msgs + tf2_ros + voxel_grid + ) + +find_package(Boost REQUIRED + COMPONENTS + thread + ) + +find_package(Eigen3 REQUIRED) +remove_definitions(-DDISABLE_LIBUSB-1.0) +include_directories( + include + ${catkin_INCLUDE_DIRS} + ${EIGEN3_INCLUDE_DIRS} +) +add_definitions(${EIGEN3_DEFINITIONS}) + +catkin_python_setup() + +# messages +add_message_files( + DIRECTORY msg + FILES + Position2DInt.msg +) + +generate_messages( + DEPENDENCIES + std_msgs +) + +# dynamic reconfigure +generate_dynamic_reconfigure_options( + cfg/BaseLocalPlanner.cfg +) + +catkin_package( + INCLUDE_DIRS include + LIBRARIES + base_local_planner + trajectory_planner_ros + CATKIN_DEPENDS + angles + costmap_2d + dynamic_reconfigure + geometry_msgs + message_runtime + nav_core + nav_msgs + pluginlib + roscpp + sensor_msgs + std_msgs + tf2 + tf2_ros + voxel_grid +) + +check_include_file(sys/time.h HAVE_SYS_TIME_H) +if (HAVE_SYS_TIME_H) + add_definitions(-DHAVE_SYS_TIME_H) +endif (HAVE_SYS_TIME_H) + +#uncomment for profiling +#set(ROS_COMPILE_FLAGS "-g -pg" ${ROS_COMPILE_FLAGS}) +#set(ROS_LINK_FLAGS "-g -pg" ${ROS_LINK_FLAGS}) +#set(ROS_COMPILE_FLAGS "-g" ${ROS_COMPILE_FLAGS}) +#set(ROS_LINK_FLAGS "-g" ${ROS_LINK_FLAGS}) + +add_library(base_local_planner + src/footprint_helper.cpp + src/goal_functions.cpp + src/map_cell.cpp + src/map_grid.cpp + src/map_grid_visualizer.cpp + src/map_grid_cost_function.cpp + src/latched_stop_rotate_controller.cpp + src/local_planner_util.cpp + src/odometry_helper_ros.cpp + src/obstacle_cost_function.cpp + src/oscillation_cost_function.cpp + src/prefer_forward_cost_function.cpp + src/point_grid.cpp + src/costmap_model.cpp + src/simple_scored_sampling_planner.cpp + src/simple_trajectory_generator.cpp + src/trajectory.cpp + src/twirling_cost_function.cpp + src/voxel_grid_model.cpp) +add_dependencies(base_local_planner base_local_planner_gencfg) +add_dependencies(base_local_planner base_local_planner_generate_messages_cpp) +add_dependencies(base_local_planner nav_msgs_generate_messages_cpp) +target_link_libraries(base_local_planner + ${catkin_LIBRARIES} + ${Boost_LIBRARIES} + ${Eigen_LIBRARIES} + ) + +add_library(trajectory_planner_ros + src/trajectory_planner.cpp + src/trajectory_planner_ros.cpp) +add_dependencies(trajectory_planner_ros ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) +target_link_libraries(trajectory_planner_ros + base_local_planner) + +add_executable(point_grid src/point_grid_node.cpp) +add_dependencies(point_grid ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) +target_link_libraries(point_grid ${catkin_LIBRARIES} base_local_planner) + +install(TARGETS + base_local_planner + trajectory_planner_ros + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} + ) + +install(FILES blp_plugin.xml + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) + +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} + PATTERN ".svn" EXCLUDE +) + +if(CATKIN_ENABLE_TESTING) + find_package(rostest) + catkin_add_gtest(base_local_planner_utest + test/gtest_main.cpp + test/utest.cpp + test/velocity_iterator_test.cpp + test/footprint_helper_test.cpp + test/trajectory_generator_test.cpp + test/map_grid_test.cpp) + target_link_libraries(base_local_planner_utest + base_local_planner trajectory_planner_ros + ) + + catkin_add_gtest(line_iterator + test/line_iterator_test.cpp) +endif() diff --git a/navigations/base_local_planner/blp_plugin.xml b/navigations/base_local_planner/blp_plugin.xml new file mode 100755 index 0000000..ed0175a --- /dev/null +++ b/navigations/base_local_planner/blp_plugin.xml @@ -0,0 +1,7 @@ + + + + A implementation of a local planner using either a DWA or Trajectory Rollout approach based on configuration parameters. + + + diff --git a/navigations/base_local_planner/cfg/BaseLocalPlanner.cfg b/navigations/base_local_planner/cfg/BaseLocalPlanner.cfg new file mode 100755 index 0000000..fcb7b3d --- /dev/null +++ b/navigations/base_local_planner/cfg/BaseLocalPlanner.cfg @@ -0,0 +1,57 @@ +#!/usr/bin/env python + +PACKAGE = 'base_local_planner' + +from math import pi + +from dynamic_reconfigure.parameter_generator_catkin import ParameterGenerator, double_t, int_t, bool_t, str_t + +gen = ParameterGenerator() + +# gen.add("inscribed_radius", double_t, 0, "The radius of the inscribed circle of the robot", 1, 0) +# gen.add("circumscribed_radius", double_t, 0, "The radius of the circumscribed circle of the robot", 1, 0) + +gen.add("acc_lim_x", double_t, 0, "The acceleration limit of the robot in the x direction", 2.5, 0, 20.0) +gen.add("acc_lim_y", double_t, 0, "The acceleration limit of the robot in the y direction", 2.5, 0, 20.0) +gen.add("acc_lim_theta", double_t, 0, "The acceleration limit of the robot in the theta direction", 3.2, 0, 20.0) + +gen.add("max_vel_x", double_t, 0, "The maximum x velocity for the robot in m/s", 0.55, 0, 20.0) +gen.add("min_vel_x", double_t, 0, "The minimum x velocity for the robot in m/s", 0.0, 0, 20.0) + +gen.add("max_vel_theta", double_t, 0, "The absolute value of the maximum rotational velocity for the robot in rad/s", 1.0, 0, 20.0) +gen.add("min_vel_theta", double_t, 0, "The absolute value of the minimum rotational velocity for the robot in rad/s", -1.0, -20.0, 0.0) +gen.add("min_in_place_vel_theta", double_t, 0, "The absolute value of the minimum in-place rotational velocity the controller will explore", 0.4, 0, 20.0) + +gen.add("sim_time", double_t, 0, "The amount of time to roll trajectories out for in seconds", 1.7, 0, 10) +gen.add("sim_granularity", double_t, 0, "The granularity with which to check for collisions along each trajectory in meters", 0.025, 0, 5) +gen.add("angular_sim_granularity", double_t, 0, "The distance between simulation points for angular velocity should be small enough that the robot doesn't hit things", 0.025, 0, pi/2) + +gen.add("path_distance_bias", double_t, 0, "The weight for the path distance part of the cost function", 0.6, 0, 5) +gen.add("goal_distance_bias", double_t, 0, "The weight for the goal distance part of the cost function", 0.8, 0, 5) +gen.add("occdist_scale", double_t, 0, "The weight for the obstacle distance part of the cost function", 0.01, 0, 5) + +gen.add("oscillation_reset_dist", double_t, 0, "The distance the robot must travel before oscillation flags are reset, in meters", 0.05, 0, 5) +gen.add("escape_reset_dist", double_t, 0, "The distance the robot must travel before oscillation flags are reset, in meters", 0.10, 0, 5) +gen.add("escape_reset_theta", double_t, 0, "The distance the robot must travel before oscillation flags are reset, in meters", pi/2, 0, 5) + +gen.add("vx_samples", int_t, 0, "The number of samples to use when exploring the x velocity space", 20, 1, 300) +gen.add("vtheta_samples", int_t, 0, "The number of samples to use when exploring the theta velocity space", 20, 1, 300) + +gen.add("heading_lookahead", double_t, 0, "How far the robot should look ahead of itself when differentiating between different rotational velocities", 0.325, 0, 5) + +gen.add("holonomic_robot", bool_t, 0, "Set this to true if the robot being controlled can take y velocities and false otherwise", True) + +gen.add("escape_vel", double_t, 0, "The velocity to use while backing up", -0.1, -2, 2) + +gen.add("dwa", bool_t, 0, "Set this to true to use the Dynamic Window Approach, false to use acceleration limits", False) + +gen.add("heading_scoring", bool_t, 0, "Set this to true to use the Dynamic Window Approach, false to use acceleration limits", False) +gen.add("heading_scoring_timestep", double_t, 0, "How far to look ahead in time when we score heading based trajectories", 0.1, 0, 1) + +gen.add("simple_attractor", bool_t, 0, "Set this to true to allow simple attraction to a goal point instead of intelligent cost propagation", False) + +gen.add("y_vels", str_t, 0, "A comma delimited list of the y velocities the controller will explore", "-0.3,-0.1,0.1,-0.3") + +gen.add("restore_defaults", bool_t, 0, "Retore to the default configuration", False) + +exit(gen.generate(PACKAGE, "base_local_planner", "BaseLocalPlanner")) diff --git a/navigations/base_local_planner/cfg/LocalPlannerLimits.cfg b/navigations/base_local_planner/cfg/LocalPlannerLimits.cfg new file mode 100755 index 0000000..954982e --- /dev/null +++ b/navigations/base_local_planner/cfg/LocalPlannerLimits.cfg @@ -0,0 +1,10 @@ +#!/usr/bin/env python +# Generic Local Planner configuration + +# from dynamic_reconfigure.parameter_generator_catkin import * + + +# if __name__ == "__main__": +# gen = ParameterGenerator() +# add_generic_localplanner_params(gen) +# exit(gen.generate(PACKAGE, "base_local_planner", "LocalPlannerLimits")) diff --git a/navigations/base_local_planner/include/base_local_planner/costmap_model.h b/navigations/base_local_planner/include/base_local_planner/costmap_model.h new file mode 100755 index 0000000..21586b8 --- /dev/null +++ b/navigations/base_local_planner/include/base_local_planner/costmap_model.h @@ -0,0 +1,102 @@ +/********************************************************************* +* +* Software License Agreement (BSD License) +* +* Copyright (c) 2008, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of the Willow Garage nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* +* Author: Eitan Marder-Eppstein +*********************************************************************/ +#ifndef TRAJECTORY_ROLLOUT_COSTMAP_MODEL_ +#define TRAJECTORY_ROLLOUT_COSTMAP_MODEL_ + +#include +// For obstacle data access +#include + +namespace base_local_planner { + /** + * @class CostmapModel + * @brief A class that implements the WorldModel interface to provide grid + * based collision checks for the trajectory controller using the costmap. + */ + class CostmapModel : public WorldModel { + public: + /** + * @brief Constructor for the CostmapModel + * @param costmap The costmap that should be used + * @return + */ + CostmapModel(const costmap_2d::Costmap2D& costmap); + + /** + * @brief Destructor for the world model + */ + virtual ~CostmapModel(){} + using WorldModel::footprintCost; + + /** + * @brief Checks if any obstacles in the costmap lie inside a convex footprint that is rasterized into the grid + * @param position The position of the robot in world coordinates + * @param footprint The specification of the footprint of the robot in world coordinates + * @param inscribed_radius The radius of the inscribed circle of the robot + * @param circumscribed_radius The radius of the circumscribed circle of the robot + * @return Positive if all the points lie outside the footprint, negative otherwise: + * -1 if footprint covers at least a lethal obstacle cell, or + * -2 if footprint covers at least a no-information cell, or + * -3 if footprint is [partially] outside of the map + */ + virtual double footprintCost(const geometry_msgs::Point& position, const std::vector& footprint, + double inscribed_radius, double circumscribed_radius); + + /** + * @brief Rasterizes a line in the costmap grid and checks for collisions + * @param x0 The x position of the first cell in grid coordinates + * @param y0 The y position of the first cell in grid coordinates + * @param x1 The x position of the second cell in grid coordinates + * @param y1 The y position of the second cell in grid coordinates + * @return A positive cost for a legal line... negative otherwise + */ + double lineCost(int x0, int x1, int y0, int y1) const; + + /** + * @brief Checks the cost of a point in the costmap + * @param x The x position of the point in cell coordinates + * @param y The y position of the point in cell coordinates + * @return A positive cost for a legal point... negative otherwise + */ + double pointCost(int x, int y) const; + + private: + const costmap_2d::Costmap2D& costmap_; ///< @brief Allows access of costmap obstacle information + + }; +}; +#endif diff --git a/navigations/base_local_planner/include/base_local_planner/footprint_helper.h b/navigations/base_local_planner/include/base_local_planner/footprint_helper.h new file mode 100755 index 0000000..9f47ebc --- /dev/null +++ b/navigations/base_local_planner/include/base_local_planner/footprint_helper.h @@ -0,0 +1,87 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2008, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: TKruse + *********************************************************************/ + +#ifndef FOOTPRINT_HELPER_H_ +#define FOOTPRINT_HELPER_H_ + +#include + +#include +#include +#include +#include + +namespace base_local_planner { + +class FootprintHelper { +public: + FootprintHelper(); + virtual ~FootprintHelper(); + + /** + * @brief Used to get the cells that make up the footprint of the robot + * @param x_i The x position of the robot + * @param y_i The y position of the robot + * @param theta_i The orientation of the robot + * @param fill If true: returns all cells in the footprint of the robot. If false: returns only the cells that make up the outline of the footprint. + * @return The cells that make up either the outline or entire footprint of the robot depending on fill + */ + std::vector getFootprintCells( + Eigen::Vector3f pos, + std::vector footprint_spec, + const costmap_2d::Costmap2D&, + bool fill); + + /** + * @brief Use Bresenham's algorithm to trace a line between two points in a grid + * @param x0 The x coordinate of the first point + * @param x1 The x coordinate of the second point + * @param y0 The y coordinate of the first point + * @param y1 The y coordinate of the second point + * @param pts Will be filled with the cells that lie on the line in the grid + */ + void getLineCells(int x0, int x1, int y0, int y1, std::vector& pts); + + /** + * @brief Fill the outline of a polygon, in this case the robot footprint, in a grid + * @param footprint The list of cells making up the footprint in the grid, will be modified to include all cells inside the footprint + */ + void getFillCells(std::vector& footprint); +}; + +} /* namespace base_local_planner */ +#endif /* FOOTPRINT_HELPER_H_ */ diff --git a/navigations/base_local_planner/include/base_local_planner/goal_functions.h b/navigations/base_local_planner/include/base_local_planner/goal_functions.h new file mode 100755 index 0000000..c873555 --- /dev/null +++ b/navigations/base_local_planner/include/base_local_planner/goal_functions.h @@ -0,0 +1,153 @@ +/********************************************************************* +* +* Software License Agreement (BSD License) +* +* Copyright (c) 2009, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of Willow Garage, Inc. nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* +* Author: Eitan Marder-Eppstein +*********************************************************************/ +#ifndef BASE_LOCAL_PLANNER_GOAL_FUNCTIONS_H_ +#define BASE_LOCAL_PLANNER_GOAL_FUNCTIONS_H_ + +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +#include +#include + +namespace base_local_planner { + + /** + * @brief return squared distance to check if the goal position has been achieved + * @param global_pose The pose of the robot in the global frame + * @param goal_x The desired x value for the goal + * @param goal_y The desired y value for the goal + * @return distance to goal + */ + double getGoalPositionDistance(const geometry_msgs::PoseStamped& global_pose, double goal_x, double goal_y); + + /** + * @brief return angle difference to goal to check if the goal orientation has been achieved + * @param global_pose The pose of the robot in the global frame + * @param goal_x The desired x value for the goal + * @param goal_y The desired y value for the goal + * @return angular difference + */ + double getGoalOrientationAngleDifference(const geometry_msgs::PoseStamped& global_pose, double goal_th); + + /** + * @brief Publish a plan for visualization purposes + * @param path The plan to publish + * @param pub The published to use + * @param r,g,b,a The color and alpha value to use when publishing + */ + void publishPlan(const std::vector& path, const ros::Publisher& pub); + + /** + * @brief Trim off parts of the global plan that are far enough behind the robot + * @param global_pose The pose of the robot in the global frame + * @param plan The plan to be pruned + * @param global_plan The plan to be pruned in the frame of the planner + */ + void prunePlan(const geometry_msgs::PoseStamped& global_pose, std::vector& plan, std::vector& global_plan); + + /** + * @brief Transforms the global plan of the robot from the planner frame to the frame of the costmap, + * selects only the (first) part of the plan that is within the costmap area. + * @param tf A reference to a transform listener + * @param global_plan The plan to be transformed + * @param robot_pose The pose of the robot in the global frame (same as costmap) + * @param costmap A reference to the costmap being used so the window size for transforming can be computed + * @param global_frame The frame to transform the plan to + * @param transformed_plan Populated with the transformed plan + */ + bool transformGlobalPlan(const tf2_ros::Buffer& tf, + const std::vector& global_plan, + const geometry_msgs::PoseStamped& global_robot_pose, + const costmap_2d::Costmap2D& costmap, + const std::string& global_frame, + std::vector& transformed_plan); + + /** + * @brief Returns last pose in plan + * @param tf A reference to a transform listener + * @param global_plan The plan being followed + * @param global_frame The global frame of the local planner + * @param goal_pose the pose to copy into + * @return True if achieved, false otherwise + */ + bool getGoalPose(const tf2_ros::Buffer& tf, + const std::vector& global_plan, + const std::string& global_frame, + geometry_msgs::PoseStamped &goal_pose); + + /** + * @brief Check if the goal pose has been achieved + * @param tf A reference to a transform listener + * @param global_plan The plan being followed + * @param costmap_ros A reference to the costmap object being used by the planner + * @param global_frame The global frame of the local planner + * @param base_odom The current odometry information for the robot + * @param rot_stopped_vel The rotational velocity below which the robot is considered stopped + * @param trans_stopped_vel The translational velocity below which the robot is considered stopped + * @param xy_goal_tolerance The translational tolerance on reaching the goal + * @param yaw_goal_tolerance The rotational tolerance on reaching the goal + * @return True if achieved, false otherwise + */ + bool isGoalReached(const tf2_ros::Buffer& tf, + const std::vector& global_plan, + const costmap_2d::Costmap2D& costmap, + const std::string& global_frame, + geometry_msgs::PoseStamped& global_pose, + const nav_msgs::Odometry& base_odom, + double rot_stopped_vel, double trans_stopped_vel, + double xy_goal_tolerance, double yaw_goal_tolerance); + + /** + * @brief Check whether the robot is stopped or not + * @param base_odom The current odometry information for the robot + * @param rot_stopped_velocity The rotational velocity below which the robot is considered stopped + * @param trans_stopped_velocity The translational velocity below which the robot is considered stopped + * @return True if the robot is stopped, false otherwise + */ + bool stopped(const nav_msgs::Odometry& base_odom, + const double& rot_stopped_velocity, + const double& trans_stopped_velocity); +}; +#endif diff --git a/navigations/base_local_planner/include/base_local_planner/latched_stop_rotate_controller.h b/navigations/base_local_planner/include/base_local_planner/latched_stop_rotate_controller.h new file mode 100755 index 0000000..a396b94 --- /dev/null +++ b/navigations/base_local_planner/include/base_local_planner/latched_stop_rotate_controller.h @@ -0,0 +1,93 @@ +/* + * latched_stop_rotate_controller.h + * + * Created on: Apr 16, 2012 + * Author: tkruse + */ + +#ifndef LATCHED_STOP_ROTATE_CONTROLLER_H_ +#define LATCHED_STOP_ROTATE_CONTROLLER_H_ + +#include + +#include + +#include +#include + +namespace base_local_planner { + +class LatchedStopRotateController { +public: + LatchedStopRotateController(const std::string& name = ""); + virtual ~LatchedStopRotateController(); + + bool isPositionReached(LocalPlannerUtil* planner_util, + const geometry_msgs::PoseStamped& global_pose); + + bool isGoalReached(LocalPlannerUtil* planner_util, + OdometryHelperRos& odom_helper, + const geometry_msgs::PoseStamped& global_pose); + + void resetLatching() { + xy_tolerance_latch_ = false; + } + + /** + * @brief Stop the robot taking into account acceleration limits + * @param global_pose The pose of the robot in the global frame + * @param robot_vel The velocity of the robot + * @param cmd_vel The velocity commands to be filled + * @return True if a valid trajectory was found, false otherwise + */ + bool stopWithAccLimits(const geometry_msgs::PoseStamped& global_pose, + const geometry_msgs::PoseStamped& robot_vel, + geometry_msgs::Twist& cmd_vel, + Eigen::Vector3f acc_lim, + double sim_period, + boost::function obstacle_check); + + /** + * @brief Once a goal position is reached... rotate to the goal orientation + * @param global_pose The pose of the robot in the global frame + * @param robot_vel The velocity of the robot + * @param goal_th The desired th value for the goal + * @param cmd_vel The velocity commands to be filled + * @return True if a valid trajectory was found, false otherwise + */ + bool rotateToGoal(const geometry_msgs::PoseStamped& global_pose, + const geometry_msgs::PoseStamped& robot_vel, + double goal_th, + geometry_msgs::Twist& cmd_vel, + Eigen::Vector3f acc_lim, + double sim_period, + base_local_planner::LocalPlannerLimits& limits, + boost::function obstacle_check); + + bool computeVelocityCommandsStopRotate(geometry_msgs::Twist& cmd_vel, + Eigen::Vector3f acc_lim, + double sim_period, + LocalPlannerUtil* planner_util, + OdometryHelperRos& odom_helper, + const geometry_msgs::PoseStamped& global_pose, + boost::function obstacle_check); + +private: + inline double sign(double x){ + return x < 0.0 ? -1.0 : 1.0; + } + + + // whether to latch at all, and whether in this turn we have already been in goal area + bool latch_xy_goal_tolerance_, xy_tolerance_latch_; + bool rotating_to_goal_; +}; + +} /* namespace base_local_planner */ +#endif /* LATCHED_STOP_ROTATE_CONTROLLER_H_ */ diff --git a/navigations/base_local_planner/include/base_local_planner/line_iterator.h b/navigations/base_local_planner/include/base_local_planner/line_iterator.h new file mode 100755 index 0000000..c2f770e --- /dev/null +++ b/navigations/base_local_planner/include/base_local_planner/line_iterator.h @@ -0,0 +1,143 @@ +/* + * Copyright (c) 2012, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ +#ifndef LINE_ITERATOR_H +#define LINE_ITERATOR_H + +#include + +namespace base_local_planner +{ + +/** An iterator implementing Bresenham Ray-Tracing. */ +class LineIterator +{ +public: + LineIterator( int x0, int y0, int x1, int y1 ) + : x0_( x0 ) + , y0_( y0 ) + , x1_( x1 ) + , y1_( y1 ) + , x_( x0 ) // X and Y start of at first endpoint. + , y_( y0 ) + , deltax_( abs( x1 - x0 )) + , deltay_( abs( y1 - y0 )) + , curpixel_( 0 ) + { + if( x1_ >= x0_ ) // The x-values are increasing + { + xinc1_ = 1; + xinc2_ = 1; + } + else // The x-values are decreasing + { + xinc1_ = -1; + xinc2_ = -1; + } + + if( y1_ >= y0_) // The y-values are increasing + { + yinc1_ = 1; + yinc2_ = 1; + } + else // The y-values are decreasing + { + yinc1_ = -1; + yinc2_ = -1; + } + + if( deltax_ >= deltay_ ) // There is at least one x-value for every y-value + { + xinc1_ = 0; // Don't change the x when numerator >= denominator + yinc2_ = 0; // Don't change the y for every iteration + den_ = deltax_; + num_ = deltax_ / 2; + numadd_ = deltay_; + numpixels_ = deltax_; // There are more x-values than y-values + } + else // There is at least one y-value for every x-value + { + xinc2_ = 0; // Don't change the x for every iteration + yinc1_ = 0; // Don't change the y when numerator >= denominator + den_ = deltay_; + num_ = deltay_ / 2; + numadd_ = deltax_; + numpixels_ = deltay_; // There are more y-values than x-values + } + } + + bool isValid() const + { + return curpixel_ <= numpixels_; + } + + void advance() + { + num_ += numadd_; // Increase the numerator by the top of the fraction + if( num_ >= den_ ) // Check if numerator >= denominator + { + num_ -= den_; // Calculate the new numerator value + x_ += xinc1_; // Change the x as appropriate + y_ += yinc1_; // Change the y as appropriate + } + x_ += xinc2_; // Change the x as appropriate + y_ += yinc2_; // Change the y as appropriate + + curpixel_++; + } + + int getX() const { return x_; } + int getY() const { return y_; } + + int getX0() const { return x0_; } + int getY0() const { return y0_; } + + int getX1() const { return x1_; } + int getY1() const { return y1_; } + +private: + int x0_; ///< X coordinate of first end point. + int y0_; ///< Y coordinate of first end point. + int x1_; ///< X coordinate of second end point. + int y1_; ///< Y coordinate of second end point. + + int x_; ///< X coordinate of current point. + int y_; ///< Y coordinate of current point. + + int deltax_; ///< Difference between Xs of endpoints. + int deltay_; ///< Difference between Ys of endpoints. + + int curpixel_; ///< index of current point in line loop. + + int xinc1_, xinc2_, yinc1_, yinc2_; + int den_, num_, numadd_, numpixels_; +}; + +} // end namespace base_local_planner + +#endif // LINE_ITERATOR_H diff --git a/navigations/base_local_planner/include/base_local_planner/local_planner_limits.h b/navigations/base_local_planner/include/base_local_planner/local_planner_limits.h new file mode 100755 index 0000000..d94b87d --- /dev/null +++ b/navigations/base_local_planner/include/base_local_planner/local_planner_limits.h @@ -0,0 +1,121 @@ +/*********************************************************** + * Software License Agreement (BSD License) + * + * Copyright (c) 2008, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the Willow Garage nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + ***********************************************************/ + + +#ifndef __base_local_planner__LOCALPLANNERLIMITS_H__ +#define __base_local_planner__LOCALPLANNERLIMITS_H__ + +#include + +namespace base_local_planner +{ +class LocalPlannerLimits +{ +public: + + double max_vel_trans; + double min_vel_trans; + double max_vel_x; + double min_vel_x; + double max_vel_y; + double min_vel_y; + double max_vel_theta; + double min_vel_theta; + double acc_lim_x; + double acc_lim_y; + double acc_lim_theta; + double acc_lim_trans; + bool prune_plan; + double xy_goal_tolerance; + double yaw_goal_tolerance; + double trans_stopped_vel; + double theta_stopped_vel; + bool restore_defaults; + + LocalPlannerLimits() {} + + LocalPlannerLimits( + double nmax_vel_trans, + double nmin_vel_trans, + double nmax_vel_x, + double nmin_vel_x, + double nmax_vel_y, + double nmin_vel_y, + double nmax_vel_theta, + double nmin_vel_theta, + double nacc_lim_x, + double nacc_lim_y, + double nacc_lim_theta, + double nacc_lim_trans, + double nxy_goal_tolerance, + double nyaw_goal_tolerance, + bool nprune_plan = true, + double ntrans_stopped_vel = 0.1, + double ntheta_stopped_vel = 0.1): + max_vel_trans(nmax_vel_trans), + min_vel_trans(nmin_vel_trans), + max_vel_x(nmax_vel_x), + min_vel_x(nmin_vel_x), + max_vel_y(nmax_vel_y), + min_vel_y(nmin_vel_y), + max_vel_theta(nmax_vel_theta), + min_vel_theta(nmin_vel_theta), + acc_lim_x(nacc_lim_x), + acc_lim_y(nacc_lim_y), + acc_lim_theta(nacc_lim_theta), + acc_lim_trans(nacc_lim_trans), + prune_plan(nprune_plan), + xy_goal_tolerance(nxy_goal_tolerance), + yaw_goal_tolerance(nyaw_goal_tolerance), + trans_stopped_vel(ntrans_stopped_vel), + theta_stopped_vel(ntheta_stopped_vel) {} + + ~LocalPlannerLimits() {} + + /** + * @brief Get the acceleration limits of the robot + * @return The acceleration limits of the robot + */ + Eigen::Vector3f getAccLimits() { + Eigen::Vector3f acc_limits; + acc_limits[0] = acc_lim_x; + acc_limits[1] = acc_lim_y; + acc_limits[2] = acc_lim_theta; + return acc_limits; + } + +}; + +} +#endif // __LOCALPLANNERLIMITS_H__ diff --git a/navigations/base_local_planner/include/base_local_planner/local_planner_util.h b/navigations/base_local_planner/include/base_local_planner/local_planner_util.h new file mode 100755 index 0000000..a0dbb70 --- /dev/null +++ b/navigations/base_local_planner/include/base_local_planner/local_planner_util.h @@ -0,0 +1,111 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2008, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: Eitan Marder-Eppstein + *********************************************************************/ + +#ifndef ABSTRACT_LOCAL_PLANNER_ODOM_H_ +#define ABSTRACT_LOCAL_PLANNER_ODOM_H_ + +#include + +#include + +#include +#include + +#include + + +namespace base_local_planner { + +/** + * @class LocalPlannerUtil + * @brief Helper class implementing infrastructure code many local planner implementations may need. + */ +class LocalPlannerUtil { + +private: + // things we get from move_base + std::string name_; + std::string global_frame_; + + costmap_2d::Costmap2D* costmap_; + tf2_ros::Buffer* tf_; + + + std::vector global_plan_; + + + boost::mutex limits_configuration_mutex_; + bool setup_; + LocalPlannerLimits default_limits_; + LocalPlannerLimits limits_; + bool initialized_; + +public: + + /** + * @brief Callback to update the local planner's parameters + */ + void reconfigureCB(LocalPlannerLimits &config, bool restore_defaults); + + LocalPlannerUtil() : initialized_(false) {} + + ~LocalPlannerUtil() { + } + + void initialize(tf2_ros::Buffer* tf, + costmap_2d::Costmap2D* costmap, + std::string global_frame); + + bool getGoal(geometry_msgs::PoseStamped& goal_pose); + + bool setPlan(const std::vector& orig_global_plan); + + bool getLocalPlan(const geometry_msgs::PoseStamped& global_pose, std::vector& transformed_plan); + + costmap_2d::Costmap2D* getCostmap(); + + LocalPlannerLimits getCurrentLimits(); + + std::string getGlobalFrame(){ return global_frame_; } +}; + + + + +}; + +#endif /* ABSTRACT_LOCAL_PLANNER_ODOM_H_ */ diff --git a/navigations/base_local_planner/include/base_local_planner/map_cell.h b/navigations/base_local_planner/include/base_local_planner/map_cell.h new file mode 100755 index 0000000..6bb797b --- /dev/null +++ b/navigations/base_local_planner/include/base_local_planner/map_cell.h @@ -0,0 +1,67 @@ +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2008, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the Willow Garage nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *********************************************************************/ +#ifndef TRAJECTORY_ROLLOUT_MAP_CELL_H_ +#define TRAJECTORY_ROLLOUT_MAP_CELL_H_ + +#include + +namespace base_local_planner { + /** + * @class MapCell + * @brief Stores path distance and goal distance information used for scoring trajectories + */ + class MapCell{ + public: + /** + * @brief Default constructor + */ + MapCell(); + + /** + * @brief Copy constructor + * @param mc The MapCell to be copied + */ + MapCell(const MapCell& mc); + + unsigned int cx, cy; ///< @brief Cell index in the grid map + + double target_dist; ///< @brief Distance to planner's path + + bool target_mark; ///< @brief Marks for computing path/goal distances + + bool within_robot; ///< @brief Mark for cells within the robot footprint + }; +}; + +#endif diff --git a/navigations/base_local_planner/include/base_local_planner/map_grid.h b/navigations/base_local_planner/include/base_local_planner/map_grid.h new file mode 100755 index 0000000..05239b2 --- /dev/null +++ b/navigations/base_local_planner/include/base_local_planner/map_grid.h @@ -0,0 +1,200 @@ +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2008, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the Willow Garage nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *********************************************************************/ +#ifndef TRAJECTORY_ROLLOUT_MAP_GRID_H_ +#define TRAJECTORY_ROLLOUT_MAP_GRID_H_ + +#include +#include +#include +#include +#include + +#include +#include +#include + +namespace base_local_planner{ + /** + * @class MapGrid + * @brief A grid of MapCell cells that is used to propagate path and goal distances for the trajectory controller. + */ + class MapGrid{ + public: + /** + * @brief Creates a 0x0 map by default + */ + MapGrid(); + + /** + * @brief Creates a map of size_x by size_y + * @param size_x The width of the map + * @param size_y The height of the map + */ + MapGrid(unsigned int size_x, unsigned int size_y); + + + /** + * @brief Returns a map cell accessed by (col, row) + * @param x The x coordinate of the cell + * @param y The y coordinate of the cell + * @return A reference to the desired cell + */ + inline MapCell& operator() (unsigned int x, unsigned int y){ + return map_[size_x_ * y + x]; + } + + /** + * @brief Returns a map cell accessed by (col, row) + * @param x The x coordinate of the cell + * @param y The y coordinate of the cell + * @return A copy of the desired cell + */ + inline MapCell operator() (unsigned int x, unsigned int y) const { + return map_[size_x_ * y + x]; + } + + inline MapCell& getCell(unsigned int x, unsigned int y){ + return map_[size_x_ * y + x]; + } + + /** + * @brief Destructor for a MapGrid + */ + ~MapGrid(){} + + /** + * @brief Copy constructor for a MapGrid + * @param mg The MapGrid to copy + */ + MapGrid(const MapGrid& mg); + + /** + * @brief Assignment operator for a MapGrid + * @param mg The MapGrid to assign from + */ + MapGrid& operator= (const MapGrid& mg); + + /** + * @brief reset path distance fields for all cells + */ + void resetPathDist(); + + /** + * @brief check if we need to resize + * @param size_x The desired width + * @param size_y The desired height + */ + void sizeCheck(unsigned int size_x, unsigned int size_y); + + /** + * @brief Utility to share initialization code across constructors + */ + void commonInit(); + + /** + * @brief Returns a 1D index into the MapCell array for a 2D index + * @param x The desired x coordinate + * @param y The desired y coordinate + * @return The associated 1D index + */ + size_t getIndex(int x, int y); + + /** + * return a value that indicates cell is in obstacle + */ + inline double obstacleCosts() { + return map_.size(); + } + + /** + * returns a value indicating cell was not reached by wavefront + * propagation of set cells. (is behind walls, regarding the region covered by grid) + */ + inline double unreachableCellCosts() { + return map_.size() + 1; + } + + /** + * @brief Used to update the distance of a cell in path distance computation + * @param current_cell The cell we're currently in + * @param check_cell The cell to be updated + */ + inline bool updatePathCell(MapCell* current_cell, MapCell* check_cell, + const costmap_2d::Costmap2D& costmap); + + /** + * increase global plan resolution to match that of the costmap by adding points linearly between global plan points + * This is necessary where global planners produce plans with few points. + * @param global_plan_in input + * @param global_plan_output output + * @param resolution desired distance between waypoints + */ + static void adjustPlanResolution(const std::vector& global_plan_in, + std::vector& global_plan_out, double resolution); + + /** + * @brief Compute the distance from each cell in the local map grid to the planned path + * @param dist_queue A queue of the initial cells on the path + */ + void computeTargetDistance(std::queue& dist_queue, const costmap_2d::Costmap2D& costmap); + + /** + * @brief Compute the distance from each cell in the local map grid to the local goal point + * @param goal_queue A queue containing the local goal cell + */ + void computeGoalDistance(std::queue& dist_queue, const costmap_2d::Costmap2D& costmap); + + /** + * @brief Update what cells are considered path based on the global plan + */ + void setTargetCells(const costmap_2d::Costmap2D& costmap, const std::vector& global_plan); + + /** + * @brief Update what cell is considered the next local goal + */ + void setLocalGoal(const costmap_2d::Costmap2D& costmap, + const std::vector& global_plan); + + double goal_x_, goal_y_; /**< @brief The goal distance was last computed from */ + + unsigned int size_x_, size_y_; ///< @brief The dimensions of the grid + + private: + + std::vector map_; ///< @brief Storage for the MapCells + + }; +}; + +#endif diff --git a/navigations/base_local_planner/include/base_local_planner/map_grid_cost_function.h b/navigations/base_local_planner/include/base_local_planner/map_grid_cost_function.h new file mode 100755 index 0000000..421bd00 --- /dev/null +++ b/navigations/base_local_planner/include/base_local_planner/map_grid_cost_function.h @@ -0,0 +1,139 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2008, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: TKruse + *********************************************************************/ + +#ifndef MAP_GRID_COST_FUNCTION_H_ +#define MAP_GRID_COST_FUNCTION_H_ + +#include + +#include +#include + +namespace base_local_planner { + +/** + * when scoring a trajectory according to the values in mapgrid, we can take + *return the value of the last point (if no of the earlier points were in + * return collision), the sum for all points, or the product of all (non-zero) points + */ +enum CostAggregationType { Last, Sum, Product}; + +/** + * This class provides cost based on a map_grid of a small area of the world. + * The map_grid covers a the costmap, the costmap containing the information + * about sensed obstacles. The map_grid is used by setting + * certain cells to distance 0, and then propagating distances around them, + * filling up the area reachable around them. + * + * The approach using grid_maps is used for computational efficiency, allowing to + * score hundreds of trajectories very quickly. + * + * This can be used to favor trajectories which stay on a given path, or which + * approach a given goal. + * @param costmap_ros Reference to object giving updates of obstacles around robot + * @param xshift where the scoring point is with respect to robot center pose + * @param yshift where the scoring point is with respect to robot center pose + * @param is_local_goal_function, scores for local goal rather than whole path + * @param aggregationType how to combine costs along trajectory + */ +class MapGridCostFunction: public base_local_planner::TrajectoryCostFunction { +public: + MapGridCostFunction(costmap_2d::Costmap2D* costmap, + double xshift = 0.0, + double yshift = 0.0, + bool is_local_goal_function = false, + CostAggregationType aggregationType = Last); + + ~MapGridCostFunction() {} + + /** + * set line segments on the grid with distance 0, resets the grid + */ + void setTargetPoses(std::vector target_poses); + + void setXShift(double xshift) {xshift_ = xshift;} + void setYShift(double yshift) {yshift_ = yshift;} + + /** @brief If true, failures along the path cause the entire path to be rejected. + * + * Default is true. */ + void setStopOnFailure(bool stop_on_failure) {stop_on_failure_ = stop_on_failure;} + + /** + * propagate distances + */ + bool prepare(); + + double scoreTrajectory(Trajectory &traj); + + /** + * return a value that indicates cell is in obstacle + */ + double obstacleCosts() { + return map_.obstacleCosts(); + } + + /** + * returns a value indicating cell was not reached by wavefront + * propagation of set cells. (is behind walls, regarding the region covered by grid) + */ + double unreachableCellCosts() { + return map_.unreachableCellCosts(); + } + + // used for easier debugging + double getCellCosts(unsigned int cx, unsigned int cy); + +private: + std::vector target_poses_; + costmap_2d::Costmap2D* costmap_; + + base_local_planner::MapGrid map_; + CostAggregationType aggregationType_; + /// xshift and yshift allow scoring for different + // ooints of robots than center, like fron or back + // this can help with alignment or keeping specific + // wheels on tracks both default to 0 + double xshift_; + double yshift_; + // if true, we look for a suitable local goal on path, else we use the full path for costs + bool is_local_goal_function_; + bool stop_on_failure_; +}; + +} /* namespace base_local_planner */ +#endif /* MAP_GRID_COST_FUNCTION_H_ */ diff --git a/navigations/base_local_planner/include/base_local_planner/map_grid_visualizer.h b/navigations/base_local_planner/include/base_local_planner/map_grid_visualizer.h new file mode 100755 index 0000000..43d1bd0 --- /dev/null +++ b/navigations/base_local_planner/include/base_local_planner/map_grid_visualizer.h @@ -0,0 +1,71 @@ +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2010, Eric Perko + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Eric Perko nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *********************************************************************/ +#ifndef MAP_GRID_VISUALIZER_H_ +#define MAP_GRID_VISUALIZER_H_ + +#include +#include +#include + +namespace base_local_planner { + class MapGridVisualizer { + public: + /** + * @brief Default constructor + */ + MapGridVisualizer(); + + /** + * @brief Initializes the MapGridVisualizer + * @param name The name to be appended to ~/ in order to get the proper namespace for parameters + * @param costmap The costmap instance to use to get the size of the map to generate a point cloud for + * @param cost_function The function to use to compute the cost values to be inserted into each point in the output PointCloud as well as whether to include a given point or not + */ + void initialize(const std::string& name, std::string frame, boost::function cost_function); + + /** + * @brief Build and publish a PointCloud if the publish_cost_grid_pc parameter was true. Only include points for which the cost_function at (cx,cy) returns true. + */ + void publishCostCloud(const costmap_2d::Costmap2D* costmap_p_); + + private: + std::string name_; ///< @brief The name to get parameters relative to. + boost::function cost_function_; ///< @brief The function to be used to generate the cost components for the output PointCloud + ros::NodeHandle ns_nh_; + std::string frame_id_; + ros::Publisher pub_; + }; +}; + +#endif diff --git a/navigations/base_local_planner/include/base_local_planner/obstacle_cost_function.h b/navigations/base_local_planner/include/base_local_planner/obstacle_cost_function.h new file mode 100755 index 0000000..e5563df --- /dev/null +++ b/navigations/base_local_planner/include/base_local_planner/obstacle_cost_function.h @@ -0,0 +1,89 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2008, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: TKruse + *********************************************************************/ + +#ifndef OBSTACLE_COST_FUNCTION_H_ +#define OBSTACLE_COST_FUNCTION_H_ + +#include + +#include +#include + +namespace base_local_planner { + +/** + * class ObstacleCostFunction + * @brief Uses costmap 2d to assign negative costs if robot footprint + * is in obstacle on any point of the trajectory. + */ +class ObstacleCostFunction : public TrajectoryCostFunction { + +public: + ObstacleCostFunction(costmap_2d::Costmap2D* costmap); + ~ObstacleCostFunction(); + + bool prepare(); + double scoreTrajectory(Trajectory &traj); + + void setSumScores(bool score_sums){ sum_scores_=score_sums; } + + void setParams(double max_trans_vel, double max_scaling_factor, double scaling_speed); + void setFootprint(std::vector footprint_spec); + + // helper functions, made static for easy unit testing + static double getScalingFactor(Trajectory &traj, double scaling_speed, double max_trans_vel, double max_scaling_factor); + static double footprintCost( + const double& x, + const double& y, + const double& th, + double scale, + std::vector footprint_spec, + costmap_2d::Costmap2D* costmap, + base_local_planner::WorldModel* world_model); + +private: + costmap_2d::Costmap2D* costmap_; + std::vector footprint_spec_; + base_local_planner::WorldModel* world_model_; + double max_trans_vel_; + bool sum_scores_; + //footprint scaling with velocity; + double max_scaling_factor_, scaling_speed_; +}; + +} /* namespace base_local_planner */ +#endif /* OBSTACLE_COST_FUNCTION_H_ */ diff --git a/navigations/base_local_planner/include/base_local_planner/odometry_helper_ros.h b/navigations/base_local_planner/include/base_local_planner/odometry_helper_ros.h new file mode 100755 index 0000000..affce7a --- /dev/null +++ b/navigations/base_local_planner/include/base_local_planner/odometry_helper_ros.h @@ -0,0 +1,92 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2008, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: TKruse + *********************************************************************/ + +#ifndef ODOMETRY_HELPER_ROS2_H_ +#define ODOMETRY_HELPER_ROS2_H_ + +#include +#include +#include +#include + +namespace base_local_planner { + +class OdometryHelperRos { +public: + + /** @brief Constructor. + * @param odom_topic The topic on which to subscribe to Odometry + * messages. If the empty string is given (the default), no + * subscription is done. */ + OdometryHelperRos(std::string odom_topic = ""); + ~OdometryHelperRos() {} + + /** + * @brief Callback for receiving odometry data + * @param msg An Odometry message + */ + void odomCallback(const nav_msgs::Odometry::ConstPtr& msg); + + void getOdom(nav_msgs::Odometry& base_odom); + + void getRobotVel(geometry_msgs::PoseStamped& robot_vel); + + /** @brief Set the odometry topic. This overrides what was set in the constructor, if anything. + * + * This unsubscribes from the old topic (if any) and subscribes to the new one (if any). + * + * If odom_topic is the empty string, this just unsubscribes from the previous topic. */ + void setOdomTopic(std::string odom_topic); + + /** @brief Return the current odometry topic. */ + std::string getOdomTopic() const { return odom_topic_; } + +private: + //odom topic + std::string odom_topic_; + + // we listen on odometry on the odom topic + ros::Subscriber odom_sub_; + nav_msgs::Odometry base_odom_; + boost::mutex odom_mutex_; + // global tf frame id + std::string frame_id_; ///< The frame_id associated this data +}; + +} /* namespace base_local_planner */ +#define CHUNKY 1 +#endif /* ODOMETRY_HELPER_ROS2_H_ */ diff --git a/navigations/base_local_planner/include/base_local_planner/oscillation_cost_function.h b/navigations/base_local_planner/include/base_local_planner/oscillation_cost_function.h new file mode 100755 index 0000000..5a8f98a --- /dev/null +++ b/navigations/base_local_planner/include/base_local_planner/oscillation_cost_function.h @@ -0,0 +1,89 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2008, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: TKruse + *********************************************************************/ + +#ifndef OSCILLATION_COST_FUNCTION_H_ +#define OSCILLATION_COST_FUNCTION_H_ + +#include +#include + +namespace base_local_planner { + +class OscillationCostFunction: public base_local_planner::TrajectoryCostFunction { +public: + OscillationCostFunction(); + virtual ~OscillationCostFunction(); + + double scoreTrajectory(Trajectory &traj); + + bool prepare() {return true;}; + + /** + * @brief Reset the oscillation flags for the local planner + */ + void resetOscillationFlags(); + + + void updateOscillationFlags(Eigen::Vector3f pos, base_local_planner::Trajectory* traj, double min_vel_trans); + + void setOscillationResetDist(double dist, double angle); + +private: + + void resetOscillationFlagsIfPossible(const Eigen::Vector3f& pos, const Eigen::Vector3f& prev); + + /** + * @brief Given a trajectory that's selected, set flags if needed to + * prevent the robot from oscillating + * @param t The selected trajectory + * @return True if a flag was set, false otherwise + */ + bool setOscillationFlags(base_local_planner::Trajectory* t, double min_vel_trans); + + // flags + bool strafe_pos_only_, strafe_neg_only_, strafing_pos_, strafing_neg_; + bool rot_pos_only_, rot_neg_only_, rotating_pos_, rotating_neg_; + bool forward_pos_only_, forward_neg_only_, forward_pos_, forward_neg_; + + // param + double oscillation_reset_dist_, oscillation_reset_angle_; + + Eigen::Vector3f prev_stationary_pos_; +}; + +} /* namespace base_local_planner */ +#endif /* OSCILLATION_COST_FUNCTION_H_ */ diff --git a/navigations/base_local_planner/include/base_local_planner/planar_laser_scan.h b/navigations/base_local_planner/include/base_local_planner/planar_laser_scan.h new file mode 100755 index 0000000..ce99a70 --- /dev/null +++ b/navigations/base_local_planner/include/base_local_planner/planar_laser_scan.h @@ -0,0 +1,57 @@ +/********************************************************************* +* +* Software License Agreement (BSD License) +* +* Copyright (c) 2008, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of the Willow Garage nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* +* Author: Eitan Marder-Eppstein +*********************************************************************/ +#ifndef TRAJECTORY_ROLLOUT_PLANAR_LASER_SCAN_H_ +#define TRAJECTORY_ROLLOUT_PLANAR_LASER_SCAN_H_ + +#include +#include + +namespace base_local_planner { + /** + * @class PlanarLaserScan + * @brief Stores a scan from a planar laser that can be used to clear freespace + */ + class PlanarLaserScan { + public: + PlanarLaserScan() {} + geometry_msgs::Point32 origin; + sensor_msgs::PointCloud cloud; + double angle_min, angle_max, angle_increment; + }; +}; + +#endif diff --git a/navigations/base_local_planner/include/base_local_planner/point_grid.h b/navigations/base_local_planner/include/base_local_planner/point_grid.h new file mode 100755 index 0000000..2df7ea4 --- /dev/null +++ b/navigations/base_local_planner/include/base_local_planner/point_grid.h @@ -0,0 +1,326 @@ +/********************************************************************* +* +* Software License Agreement (BSD License) +* +* Copyright (c) 2008, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of the Willow Garage nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* +* Author: Eitan Marder-Eppstein +*********************************************************************/ +#ifndef POINT_GRID_H_ +#define POINT_GRID_H_ +#include +#include +#include +#include +#include +#include + +#include + +namespace base_local_planner { + /** + * @class PointGrid + * @brief A class that implements the WorldModel interface to provide + * free-space collision checks for the trajectory controller. This class + * stores points binned into a grid and performs point-in-polygon checks when + * necessary to determine the legality of a footprint at a given + * position/orientation. + */ + class PointGrid : public WorldModel { + public: + /** + * @brief Constuctor for a grid that stores points in the plane + * @param width The width in meters of the grid + * @param height The height in meters of the gird + * @param resolution The resolution of the grid in meters/cell + * @param origin The origin of the bottom left corner of the grid + * @param max_z The maximum height for an obstacle to be added to the grid + * @param obstacle_range The maximum distance for obstacles to be added to the grid + * @param min_separation The minimum distance between points in the grid + */ + PointGrid(double width, double height, double resolution, geometry_msgs::Point origin, + double max_z, double obstacle_range, double min_separation); + + /** + * @brief Destructor for a point grid + */ + virtual ~PointGrid(){} + + /** + * @brief Returns the points that lie within the cells contained in the specified range. Some of these points may be outside the range itself. + * @param lower_left The lower left corner of the range search + * @param upper_right The upper right corner of the range search + * @param points A vector of pointers to lists of the relevant points + */ + void getPointsInRange(const geometry_msgs::Point& lower_left, const geometry_msgs::Point& upper_right, std::vector< std::list* >& points); + + /** + * @brief Checks if any points in the grid lie inside a convex footprint + * @param position The position of the robot in world coordinates + * @param footprint The specification of the footprint of the robot in world coordinates + * @param inscribed_radius The radius of the inscribed circle of the robot + * @param circumscribed_radius The radius of the circumscribed circle of the robot + * @return Positive if all the points lie outside the footprint, negative otherwise + */ + virtual double footprintCost(const geometry_msgs::Point& position, const std::vector& footprint, + double inscribed_radius, double circumscribed_radius); + + using WorldModel::footprintCost; + + /** + * @brief Inserts observations from sensors into the point grid + * @param footprint The footprint of the robot in its current location + * @param observations The observations from various sensors + * @param laser_scans The laser scans used to clear freespace (the point grid only uses the first scan which is assumed to be the base laser) + */ + void updateWorld(const std::vector& footprint, + const std::vector& observations, const std::vector& laser_scans); + + /** + * @brief Convert from world coordinates to grid coordinates + * @param pt A point in world space + * @param gx The x coordinate of the corresponding grid cell to be set by the function + * @param gy The y coordinate of the corresponding grid cell to be set by the function + * @return True if the conversion was successful, false otherwise + */ + inline bool gridCoords(geometry_msgs::Point pt, unsigned int& gx, unsigned int& gy) const { + if(pt.x < origin_.x || pt.y < origin_.y){ + gx = 0; + gy = 0; + return false; + } + gx = (int) ((pt.x - origin_.x)/resolution_); + gy = (int) ((pt.y - origin_.y)/resolution_); + + if(gx >= width_ || gy >= height_){ + gx = 0; + gy = 0; + return false; + } + + return true; + } + + /** + * @brief Get the bounds in world coordinates of a cell in the point grid, assumes a legal cell when called + * @param gx The x coordinate of the grid cell + * @param gy The y coordinate of the grid cell + * @param lower_left The lower left bounds of the cell in world coordinates to be filled in + * @param upper_right The upper right bounds of the cell in world coordinates to be filled in + */ + inline void getCellBounds(unsigned int gx, unsigned int gy, geometry_msgs::Point& lower_left, geometry_msgs::Point& upper_right) const { + lower_left.x = gx * resolution_ + origin_.x; + lower_left.y = gy * resolution_ + origin_.y; + + upper_right.x = lower_left.x + resolution_; + upper_right.y = lower_left.y + resolution_; + } + + + /** + * @brief Compute the squared distance between two points + * @param pt1 The first point + * @param pt2 The second point + * @return The squared distance between the two points + */ + inline double sq_distance(const geometry_msgs::Point32& pt1, const geometry_msgs::Point32& pt2){ + return (pt1.x - pt2.x) * (pt1.x - pt2.x) + (pt1.y - pt2.y) * (pt1.y - pt2.y); + } + + /** + * @brief Convert from world coordinates to grid coordinates + * @param pt A point in world space + * @param gx The x coordinate of the corresponding grid cell to be set by the function + * @param gy The y coordinate of the corresponding grid cell to be set by the function + * @return True if the conversion was successful, false otherwise + */ + inline bool gridCoords(const geometry_msgs::Point32& pt, unsigned int& gx, unsigned int& gy) const { + if(pt.x < origin_.x || pt.y < origin_.y){ + gx = 0; + gy = 0; + return false; + } + gx = (int) ((pt.x - origin_.x)/resolution_); + gy = (int) ((pt.y - origin_.y)/resolution_); + + if(gx >= width_ || gy >= height_){ + gx = 0; + gy = 0; + return false; + } + + return true; + } + + /** + * @brief Converts cell coordinates to an index value that can be used to look up the correct grid cell + * @param gx The x coordinate of the cell + * @param gy The y coordinate of the cell + * @return The index of the cell in the stored cell list + */ + inline unsigned int gridIndex(unsigned int gx, unsigned int gy) const { + /* + * (0, 0) ---------------------- (width, 0) + * | | + * | | + * | | + * | | + * | | + * (0, height) ----------------- (width, height) + */ + return(gx + gy * width_); + } + + /** + * @brief Check the orientation of a pt c with respect to the vector a->b + * @param a The start point of the vector + * @param b The end point of the vector + * @param c The point to compute orientation for + * @return orient(a, b, c) < 0 ----> Right, orient(a, b, c) > 0 ----> Left + */ + inline double orient(const geometry_msgs::Point& a, const geometry_msgs::Point& b, const geometry_msgs::Point32& c){ + double acx = a.x - c.x; + double bcx = b.x - c.x; + double acy = a.y - c.y; + double bcy = b.y - c.y; + return acx * bcy - acy * bcx; + } + + /** + * @brief Check the orientation of a pt c with respect to the vector a->b + * @param a The start point of the vector + * @param b The end point of the vector + * @param c The point to compute orientation for + * @return orient(a, b, c) < 0 ----> Right, orient(a, b, c) > 0 ----> Left + */ + template + inline double orient(const T& a, const T& b, const T& c){ + double acx = a.x - c.x; + double bcx = b.x - c.x; + double acy = a.y - c.y; + double bcy = b.y - c.y; + return acx * bcy - acy * bcx; + } + + /** + * @brief Check if two line segmenst intersect + * @param v1 The first point of the first segment + * @param v2 The second point of the first segment + * @param u1 The first point of the second segment + * @param u2 The second point of the second segment + * @return True if the segments intersect, false otherwise + */ + inline bool segIntersect(const geometry_msgs::Point32& v1, const geometry_msgs::Point32& v2, + const geometry_msgs::Point32& u1, const geometry_msgs::Point32& u2){ + return (orient(v1, v2, u1) * orient(v1, v2, u2) < 0) && (orient(u1, u2, v1) * orient(u1, u2, v2) < 0); + } + + /** + * @brief Find the intersection point of two lines + * @param v1 The first point of the first segment + * @param v2 The second point of the first segment + * @param u1 The first point of the second segment + * @param u2 The second point of the second segment + * @param result The point to be filled in + */ + void intersectionPoint(const geometry_msgs::Point& v1, const geometry_msgs::Point& v2, + const geometry_msgs::Point& u1, const geometry_msgs::Point& u2, + geometry_msgs::Point& result); + + /** + * @brief Check if a point is in a polygon + * @param pt The point to be checked + * @param poly The polygon to check against + * @return True if the point is in the polygon, false otherwise + */ + bool ptInPolygon(const geometry_msgs::Point32& pt, const std::vector& poly); + + /** + * @brief Insert a point into the point grid + * @param pt The point to be inserted + */ + void insert(const geometry_msgs::Point32& pt); + + /** + * @brief Find the distance between a point and its nearest neighbor in the grid + * @param pt The point used for comparison + * @return The distance between the point passed in and its nearest neighbor in the point grid + */ + double nearestNeighborDistance(const geometry_msgs::Point32& pt); + + /** + * @brief Find the distance between a point and its nearest neighbor in a cell + * @param pt The point used for comparison + * @param gx The x coordinate of the cell + * @param gy The y coordinate of the cell + * @return The distance between the point passed in and its nearest neighbor in the cell + */ + double getNearestInCell(const geometry_msgs::Point32& pt, unsigned int gx, unsigned int gy); + + /** + * @brief Removes points from the grid that lie within the polygon + * @param poly A specification of the polygon to clear from the grid + */ + void removePointsInPolygon(const std::vector poly); + + /** + * @brief Removes points from the grid that lie within a laser scan + * @param laser_scan A specification of the laser scan to use for clearing + */ + void removePointsInScanBoundry(const PlanarLaserScan& laser_scan); + + /** + * @brief Checks to see if a point is within a laser scan specification + * @param pt The point to check + * @param laser_scan The specification of the scan to check against + * @return True if the point is contained within the scan, false otherwise + */ + bool ptInScan(const geometry_msgs::Point32& pt, const PlanarLaserScan& laser_scan); + + /** + * @brief Get the points in the point grid + * @param cloud The point cloud to insert the points into + */ + void getPoints(sensor_msgs::PointCloud2& cloud); + + private: + double resolution_; ///< @brief The resolution of the grid in meters/cell + geometry_msgs::Point origin_; ///< @brief The origin point of the grid + unsigned int width_; ///< @brief The width of the grid in cells + unsigned int height_; ///< @brief The height of the grid in cells + std::vector< std::list > cells_; ///< @brief Storage for the cells in the grid + double max_z_; ///< @brief The height cutoff for adding points as obstacles + double sq_obstacle_range_; ///< @brief The square distance at which we no longer add obstacles to the grid + double sq_min_separation_; ///< @brief The minimum square distance required between points in the grid + std::vector< std::list* > points_; ///< @brief The lists of points returned by a range search, made a member to save on memory allocation + }; +}; +#endif diff --git a/navigations/base_local_planner/include/base_local_planner/prefer_forward_cost_function.h b/navigations/base_local_planner/include/base_local_planner/prefer_forward_cost_function.h new file mode 100755 index 0000000..23ab6f1 --- /dev/null +++ b/navigations/base_local_planner/include/base_local_planner/prefer_forward_cost_function.h @@ -0,0 +1,64 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2008, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: TKruse + *********************************************************************/ + +#ifndef PREFER_FORWARD_COST_FUNCTION_H_ +#define PREFER_FORWARD_COST_FUNCTION_H_ + +#include + +namespace base_local_planner { + +class PreferForwardCostFunction: public base_local_planner::TrajectoryCostFunction { +public: + + PreferForwardCostFunction(double penalty) : penalty_(penalty) {} + ~PreferForwardCostFunction() {} + + double scoreTrajectory(Trajectory &traj); + + bool prepare() {return true;}; + + void setPenalty(double penalty) { + penalty_ = penalty; + } + +private: + double penalty_; +}; + +} /* namespace base_local_planner */ +#endif /* PREFER_FORWARD_COST_FUNCTION_H_ */ diff --git a/navigations/base_local_planner/include/base_local_planner/simple_scored_sampling_planner.h b/navigations/base_local_planner/include/base_local_planner/simple_scored_sampling_planner.h new file mode 100755 index 0000000..8e4aff7 --- /dev/null +++ b/navigations/base_local_planner/include/base_local_planner/simple_scored_sampling_planner.h @@ -0,0 +1,109 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2008, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: TKruse + *********************************************************************/ + +#ifndef SIMPLE_SCORED_SAMPLING_PLANNER_H_ +#define SIMPLE_SCORED_SAMPLING_PLANNER_H_ + +#include +#include +#include +#include +#include + +namespace base_local_planner { + +/** + * @class SimpleScoredSamplingPlanner + * @brief Generates a local plan using the given generator and cost functions. + * Assumes less cost are best, and negative costs indicate infinite costs + * + * This is supposed to be a simple and robust implementation of + * the TrajectorySearch interface. More efficient search may well be + * possible using search heuristics, parallel search, etc. + */ +class SimpleScoredSamplingPlanner : public base_local_planner::TrajectorySearch { +public: + + ~SimpleScoredSamplingPlanner() {} + + SimpleScoredSamplingPlanner() {} + + /** + * Takes a list of generators and critics. Critics return costs > 0, or negative costs for invalid trajectories. + * Generators other than the first are fallback generators, meaning they only get to generate if the previous + * generator did not find a valid trajectory. + * Will use every generator until it stops returning trajectories or count reaches max_samples. + * Then resets count and tries for the next in the list. + * passing max_samples = -1 (default): Each Sampling planner will continue to call + * generator until generator runs out of samples (or forever if that never happens) + */ + SimpleScoredSamplingPlanner(std::vector gen_list, std::vector& critics, int max_samples = -1); + + /** + * runs all scoring functions over the trajectory creating a weigthed sum + * of positive costs, aborting as soon as a negative cost are found or costs greater + * than positive best_traj_cost accumulated + */ + double scoreTrajectory(Trajectory& traj, double best_traj_cost); + + /** + * Calls generator until generator has no more samples or max_samples is reached. + * For each generated traj, calls critics in turn. If any critic returns negative + * value, that value is assumed as costs, else the costs are the sum of all critics + * result. Returns true and sets the traj parameter to the first trajectory with + * minimal non-negative costs if sampling yields trajectories with non-negative costs, + * else returns false. + * + * @param traj The container to write the result to + * @param all_explored pass NULL or a container to collect all trajectories for debugging (has a penalty) + */ + bool findBestTrajectory(Trajectory& traj, std::vector* all_explored = 0); + + +private: + std::vector gen_list_; + std::vector critics_; + + int max_samples_; +}; + + + + +} // namespace + +#endif /* SIMPLE_SCORED_SAMPLING_PLANNER_H_ */ diff --git a/navigations/base_local_planner/include/base_local_planner/simple_trajectory_generator.h b/navigations/base_local_planner/include/base_local_planner/simple_trajectory_generator.h new file mode 100755 index 0000000..18a6fd0 --- /dev/null +++ b/navigations/base_local_planner/include/base_local_planner/simple_trajectory_generator.h @@ -0,0 +1,160 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2008, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: TKruse + *********************************************************************/ + +#ifndef SIMPLE_TRAJECTORY_GENERATOR_H_ +#define SIMPLE_TRAJECTORY_GENERATOR_H_ + +#include +#include +#include + +namespace base_local_planner { + +/** + * generates trajectories based on equi-distant discretisation of the degrees of freedom. + * This is supposed to be a simple and robust implementation of the TrajectorySampleGenerator + * interface, more efficient implementations are thinkable. + * + * This can be used for both dwa and trajectory rollout approaches. + * As an example, assuming these values: + * sim_time = 1s, sim_period=200ms, dt = 200ms, + * vsamples_x=5, + * acc_limit_x = 1m/s^2, vel_x=0 (robot at rest, values just for easy calculations) + * dwa_planner will sample max-x-velocities from 0m/s to 0.2m/s. + * trajectory rollout approach will sample max-x-velocities 0m/s up to 1m/s + * trajectory rollout approach does so respecting the acceleration limit, so it gradually increases velocity + */ +class SimpleTrajectoryGenerator: public base_local_planner::TrajectorySampleGenerator { +public: + + SimpleTrajectoryGenerator() { + limits_ = NULL; + } + + ~SimpleTrajectoryGenerator() {} + + /** + * @param pos current robot position + * @param vel current robot velocity + * @param limits Current velocity limits + * @param vsamples: in how many samples to divide the given dimension + * @param use_acceleration_limits: if true use physical model, else idealized robot model + * @param additional_samples (deprecated): Additional velocity samples to generate individual trajectories from. + * @param discretize_by_time if true, the trajectory is split according in chunks of the same duration, else of same length + */ + void initialise( + const Eigen::Vector3f& pos, + const Eigen::Vector3f& vel, + const Eigen::Vector3f& goal, + base_local_planner::LocalPlannerLimits* limits, + const Eigen::Vector3f& vsamples, + std::vector additional_samples, + bool discretize_by_time = false); + + /** + * @param pos current robot position + * @param vel current robot velocity + * @param limits Current velocity limits + * @param vsamples: in how many samples to divide the given dimension + * @param use_acceleration_limits: if true use physical model, else idealized robot model + * @param discretize_by_time if true, the trajectory is split according in chunks of the same duration, else of same length + */ + void initialise( + const Eigen::Vector3f& pos, + const Eigen::Vector3f& vel, + const Eigen::Vector3f& goal, + base_local_planner::LocalPlannerLimits* limits, + const Eigen::Vector3f& vsamples, + bool discretize_by_time = false); + + /** + * This function is to be called only when parameters change + * + * @param sim_granularity granularity of collision detection + * @param angular_sim_granularity angular granularity of collision detection + * @param use_dwa whether to use DWA or trajectory rollout + * @param sim_period distance between points in one trajectory + */ + void setParameters(double sim_time, + double sim_granularity, + double angular_sim_granularity, + bool use_dwa = false, + double sim_period = 0.0); + + /** + * Whether this generator can create more trajectories + */ + bool hasMoreTrajectories(); + + /** + * Whether this generator can create more trajectories + */ + bool nextTrajectory(Trajectory &traj); + + + static Eigen::Vector3f computeNewPositions(const Eigen::Vector3f& pos, + const Eigen::Vector3f& vel, double dt); + + static Eigen::Vector3f computeNewVelocities(const Eigen::Vector3f& sample_target_vel, + const Eigen::Vector3f& vel, Eigen::Vector3f acclimits, double dt); + + bool generateTrajectory( + Eigen::Vector3f pos, + Eigen::Vector3f vel, + Eigen::Vector3f sample_target_vel, + base_local_planner::Trajectory& traj); + +protected: + + unsigned int next_sample_index_; + // to store sample params of each sample between init and generation + std::vector sample_params_; + base_local_planner::LocalPlannerLimits* limits_; + Eigen::Vector3f pos_; + Eigen::Vector3f vel_; + + // whether velocity of trajectory changes over time or not + bool continued_acceleration_; + bool discretize_by_time_; + + double sim_time_, sim_granularity_, angular_sim_granularity_; + bool use_dwa_; + double sim_period_; // only for dwa +}; + +} /* namespace base_local_planner */ +#endif /* SIMPLE_TRAJECTORY_GENERATOR_H_ */ diff --git a/navigations/base_local_planner/include/base_local_planner/trajectory.h b/navigations/base_local_planner/include/base_local_planner/trajectory.h new file mode 100755 index 0000000..da0223d --- /dev/null +++ b/navigations/base_local_planner/include/base_local_planner/trajectory.h @@ -0,0 +1,118 @@ +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2008, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the Willow Garage nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *********************************************************************/ +#ifndef TRAJECTORY_ROLLOUT_TRAJECTORY_H_ +#define TRAJECTORY_ROLLOUT_TRAJECTORY_H_ + +#include + +namespace base_local_planner { + /** + * @class Trajectory + * @brief Holds a trajectory generated by considering an x, y, and theta velocity + */ + class Trajectory { + public: + /** + * @brief Default constructor + */ + Trajectory(); + + /** + * @brief Constructs a trajectory + * @param xv The x velocity used to seed the trajectory + * @param yv The y velocity used to seed the trajectory + * @param thetav The theta velocity used to seed the trajectory + * @param num_pts The expected number of points for a trajectory + */ + Trajectory(double xv, double yv, double thetav, double time_delta, unsigned int num_pts); + + double xv_, yv_, thetav_; ///< @brief The x, y, and theta velocities of the trajectory + + double cost_; ///< @brief The cost/score of the trajectory + + double time_delta_; ///< @brief The time gap between points + + /** + * @brief Get a point within the trajectory + * @param index The index of the point to get + * @param x Will be set to the x position of the point + * @param y Will be set to the y position of the point + * @param th Will be set to the theta position of the point + */ + void getPoint(unsigned int index, double& x, double& y, double& th) const; + + /** + * @brief Set a point within the trajectory + * @param index The index of the point to set + * @param x The x position + * @param y The y position + * @param th The theta position + */ + void setPoint(unsigned int index, double x, double y, double th); + + /** + * @brief Add a point to the end of a trajectory + * @param x The x position + * @param y The y position + * @param th The theta position + */ + void addPoint(double x, double y, double th); + + /** + * @brief Get the last point of the trajectory + * @param x Will be set to the x position of the point + * @param y Will be set to the y position of the point + * @param th Will be set to the theta position of the point + */ + void getEndpoint(double& x, double& y, double& th) const; + + /** + * @brief Clear the trajectory's points + */ + void resetPoints(); + + /** + * @brief Return the number of points in the trajectory + * @return The number of points in the trajectory + */ + unsigned int getPointsSize() const; + + private: + std::vector x_pts_; ///< @brief The x points in the trajectory + std::vector y_pts_; ///< @brief The y points in the trajectory + std::vector th_pts_; ///< @brief The theta points in the trajectory + + }; +}; +#endif diff --git a/navigations/base_local_planner/include/base_local_planner/trajectory_cost_function.h b/navigations/base_local_planner/include/base_local_planner/trajectory_cost_function.h new file mode 100755 index 0000000..17e71a3 --- /dev/null +++ b/navigations/base_local_planner/include/base_local_planner/trajectory_cost_function.h @@ -0,0 +1,86 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2008, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: TKruse + *********************************************************************/ + +#ifndef TRAJECTORYCOSTFUNCTION_H_ +#define TRAJECTORYCOSTFUNCTION_H_ + +#include + +namespace base_local_planner { + +/** + * @class TrajectoryCostFunction + * @brief Provides an interface for critics of trajectories + * During each sampling run, a batch of many trajectories will be scored using such a cost function. + * The prepare method is called before each batch run, and then for each + * trajectory of the sampling set, score_trajectory may be called. + */ +class TrajectoryCostFunction { +public: + + /** + * + * General updating of context values if required. + * Subclasses may overwrite. Return false in case there is any error. + */ + virtual bool prepare() = 0; + + /** + * return a score for trajectory traj + */ + virtual double scoreTrajectory(Trajectory &traj) = 0; + + double getScale() { + return scale_; + } + + void setScale(double scale) { + scale_ = scale; + } + + virtual ~TrajectoryCostFunction() {} + +protected: + TrajectoryCostFunction(double scale = 1.0): scale_(scale) {} + +private: + double scale_; +}; + +} + +#endif /* TRAJECTORYCOSTFUNCTION_H_ */ diff --git a/navigations/base_local_planner/include/base_local_planner/trajectory_inc.h b/navigations/base_local_planner/include/base_local_planner/trajectory_inc.h new file mode 100755 index 0000000..4d121b5 --- /dev/null +++ b/navigations/base_local_planner/include/base_local_planner/trajectory_inc.h @@ -0,0 +1,47 @@ +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2008, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the Willow Garage nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *********************************************************************/ +#ifndef TRAJECTORY_INC_H_ +#define TRAJECTORY_INC_H_ + +#include + +#ifndef DBL_MAX /* Max decimal value of a double */ +#define DBL_MAX std::numeric_limits::max() // 1.7976931348623157e+308 +#endif + +#ifndef DBL_MIN //Min decimal value of a double +#define DBL_MIN std::numeric_limits::min() // 2.2250738585072014e-308 +#endif + +#endif diff --git a/navigations/base_local_planner/include/base_local_planner/trajectory_planner.h b/navigations/base_local_planner/include/base_local_planner/trajectory_planner.h new file mode 100755 index 0000000..19785d9 --- /dev/null +++ b/navigations/base_local_planner/include/base_local_planner/trajectory_planner.h @@ -0,0 +1,385 @@ +/********************************************************************* +* +* Software License Agreement (BSD License) +* +* Copyright (c) 2008, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of the Willow Garage nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* +* Author: Eitan Marder-Eppstein +*********************************************************************/ +#ifndef TRAJECTORY_ROLLOUT_TRAJECTORY_PLANNER_H_ +#define TRAJECTORY_ROLLOUT_TRAJECTORY_PLANNER_H_ + +#include +#include + +//for obstacle data access +#include +#include +#include + +#include +#include +#include +#include + +//we'll take in a path as a vector of poses +#include +#include + +//for creating a local cost grid +#include +#include + +namespace base_local_planner { + /** + * @class TrajectoryPlanner + * @brief Computes control velocities for a robot given a costmap, a plan, and the robot's position in the world. + */ + class TrajectoryPlanner{ + friend class TrajectoryPlannerTest; //Need this for gtest to work + public: + /** + * @brief Constructs a trajectory controller + * @param world_model The WorldModel the trajectory controller uses to check for collisions + * @param costmap A reference to the Costmap the controller should use + * @param footprint_spec A polygon representing the footprint of the robot. (Must be convex) + * @param inscribed_radius The radius of the inscribed circle of the robot + * @param circumscribed_radius The radius of the circumscribed circle of the robot + * @param acc_lim_x The acceleration limit of the robot in the x direction + * @param acc_lim_y The acceleration limit of the robot in the y direction + * @param acc_lim_theta The acceleration limit of the robot in the theta direction + * @param sim_time The number of seconds to "roll-out" each trajectory + * @param sim_granularity The distance between simulation points should be small enough that the robot doesn't hit things + * @param vx_samples The number of trajectories to sample in the x dimension + * @param vtheta_samples The number of trajectories to sample in the theta dimension + * @param path_distance_bias A scaling factor for how close the robot should stay to the path + * @param goal_distance_bias A scaling factor for how aggresively the robot should pursue a local goal + * @param occdist_scale A scaling factor for how much the robot should prefer to stay away from obstacles + * @param heading_lookahead How far the robot should look ahead of itself when differentiating between different rotational velocities + * @param oscillation_reset_dist The distance the robot must travel before it can explore rotational velocities that were unsuccessful in the past + * @param escape_reset_dist The distance the robot must travel before it can exit escape mode + * @param escape_reset_theta The distance the robot must rotate before it can exit escape mode + * @param holonomic_robot Set this to true if the robot being controlled can take y velocities and false otherwise + * @param max_vel_x The maximum x velocity the controller will explore + * @param min_vel_x The minimum x velocity the controller will explore + * @param max_vel_th The maximum rotational velocity the controller will explore + * @param min_vel_th The minimum rotational velocity the controller will explore + * @param min_in_place_vel_th The absolute value of the minimum in-place rotational velocity the controller will explore + * @param backup_vel The velocity to use while backing up + * @param dwa Set this to true to use the Dynamic Window Approach, false to use acceleration limits + * @param heading_scoring Set this to true to score trajectories based on the robot's heading after 1 timestep + * @param heading_scoring_timestep How far to look ahead in time when we score heading based trajectories + * @param meter_scoring adapt parameters to costmap resolution + * @param simple_attractor Set this to true to allow simple attraction to a goal point instead of intelligent cost propagation + * @param y_vels A vector of the y velocities the controller will explore + * @param angular_sim_granularity The distance between simulation points for angular velocity should be small enough that the robot doesn't hit things + */ + TrajectoryPlanner(WorldModel& world_model, + const costmap_2d::Costmap2D& costmap, + std::vector footprint_spec, + double acc_lim_x = 1.0, double acc_lim_y = 1.0, double acc_lim_theta = 1.0, + double sim_time = 1.0, double sim_granularity = 0.025, + int vx_samples = 20, int vtheta_samples = 20, + double path_distance_bias = 0.6, double goal_distance_bias = 0.8, double occdist_scale = 0.2, + double heading_lookahead = 0.325, double oscillation_reset_dist = 0.05, + double escape_reset_dist = 0.10, double escape_reset_theta = M_PI_2, + bool holonomic_robot = true, + double max_vel_x = 0.5, double min_vel_x = 0.1, + double max_vel_th = 1.0, double min_vel_th = -1.0, double min_in_place_vel_th = 0.4, + double backup_vel = -0.1, + bool dwa = false, bool heading_scoring = false, double heading_scoring_timestep = 0.1, + bool meter_scoring = true, + bool simple_attractor = false, + std::vector y_vels = std::vector(0), + double stop_time_buffer = 0.2, + double sim_period = 0.1, double angular_sim_granularity = 0.025); + + /** + * @brief Destructs a trajectory controller + */ + ~TrajectoryPlanner(); + + /** + * @brief Reconfigures the trajectory planner + */ + void reconfigure(BaseLocalPlannerConfig &cfg); + + /** + * @brief Given the current position, orientation, and velocity of the robot, return a trajectory to follow + * @param global_pose The current pose of the robot in world space + * @param global_vel The current velocity of the robot in world space + * @param drive_velocities Will be set to velocities to send to the robot base + * @return The selected path or trajectory + */ + Trajectory findBestPath(const geometry_msgs::PoseStamped& global_pose, + geometry_msgs::PoseStamped& global_vel, geometry_msgs::PoseStamped& drive_velocities); + + /** + * @brief Update the plan that the controller is following + * @param new_plan A new plan for the controller to follow + * @param compute_dists Wheter or not to compute path/goal distances when a plan is updated + */ + void updatePlan(const std::vector& new_plan, bool compute_dists = false); + + /** + * @brief Accessor for the goal the robot is currently pursuing in world corrdinates + * @param x Will be set to the x position of the local goal + * @param y Will be set to the y position of the local goal + */ + void getLocalGoal(double& x, double& y); + + /** + * @brief Generate and score a single trajectory + * @param x The x position of the robot + * @param y The y position of the robot + * @param theta The orientation of the robot + * @param vx The x velocity of the robot + * @param vy The y velocity of the robot + * @param vtheta The theta velocity of the robot + * @param vx_samp The x velocity used to seed the trajectory + * @param vy_samp The y velocity used to seed the trajectory + * @param vtheta_samp The theta velocity used to seed the trajectory + * @return True if the trajectory is legal, false otherwise + */ + bool checkTrajectory(double x, double y, double theta, double vx, double vy, + double vtheta, double vx_samp, double vy_samp, double vtheta_samp); + + /** + * @brief Generate and score a single trajectory + * @param x The x position of the robot + * @param y The y position of the robot + * @param theta The orientation of the robot + * @param vx The x velocity of the robot + * @param vy The y velocity of the robot + * @param vtheta The theta velocity of the robot + * @param vx_samp The x velocity used to seed the trajectory + * @param vy_samp The y velocity used to seed the trajectory + * @param vtheta_samp The theta velocity used to seed the trajectory + * @return The score (as double) + */ + double scoreTrajectory(double x, double y, double theta, double vx, double vy, + double vtheta, double vx_samp, double vy_samp, double vtheta_samp); + + /** + * @brief Compute the components and total cost for a map grid cell + * @param cx The x coordinate of the cell in the map grid + * @param cy The y coordinate of the cell in the map grid + * @param path_cost Will be set to the path distance component of the cost function + * @param goal_cost Will be set to the goal distance component of the cost function + * @param occ_cost Will be set to the costmap value of the cell + * @param total_cost Will be set to the value of the overall cost function, taking into account the scaling parameters + * @return True if the cell is traversible and therefore a legal location for the robot to move to + */ + bool getCellCosts(int cx, int cy, float &path_cost, float &goal_cost, float &occ_cost, float &total_cost); + + /** @brief Set the footprint specification of the robot. */ + void setFootprint( std::vector footprint ) { footprint_spec_ = footprint; } + + /** @brief Return the footprint specification of the robot. */ + geometry_msgs::Polygon getFootprintPolygon() const { return costmap_2d::toPolygon(footprint_spec_); } + std::vector getFootprint() const { return footprint_spec_; } + + private: + /** + * @brief Create the trajectories we wish to explore, score them, and return the best option + * @param x The x position of the robot + * @param y The y position of the robot + * @param theta The orientation of the robot + * @param vx The x velocity of the robot + * @param vy The y velocity of the robot + * @param vtheta The theta velocity of the robot + * @param acc_x The x acceleration limit of the robot + * @param acc_y The y acceleration limit of the robot + * @param acc_theta The theta acceleration limit of the robot + * @return + */ + Trajectory createTrajectories(double x, double y, double theta, double vx, double vy, double vtheta, + double acc_x, double acc_y, double acc_theta); + + /** + * @brief Generate and score a single trajectory + * @param x The x position of the robot + * @param y The y position of the robot + * @param theta The orientation of the robot + * @param vx The x velocity of the robot + * @param vy The y velocity of the robot + * @param vtheta The theta velocity of the robot + * @param vx_samp The x velocity used to seed the trajectory + * @param vy_samp The y velocity used to seed the trajectory + * @param vtheta_samp The theta velocity used to seed the trajectory + * @param acc_x The x acceleration limit of the robot + * @param acc_y The y acceleration limit of the robot + * @param acc_theta The theta acceleration limit of the robot + * @param impossible_cost The cost value of a cell in the local map grid that is considered impassable + * @param traj Will be set to the generated trajectory with its associated score + */ + void generateTrajectory(double x, double y, double theta, double vx, double vy, + double vtheta, double vx_samp, double vy_samp, double vtheta_samp, double acc_x, double acc_y, + double acc_theta, double impossible_cost, Trajectory& traj); + + /** + * @brief Checks the legality of the robot footprint at a position and orientation using the world model + * @param x_i The x position of the robot + * @param y_i The y position of the robot + * @param theta_i The orientation of the robot + * @return + */ + double footprintCost(double x_i, double y_i, double theta_i); + + base_local_planner::FootprintHelper footprint_helper_; + + MapGrid path_map_; ///< @brief The local map grid where we propagate path distance + MapGrid goal_map_; ///< @brief The local map grid where we propagate goal distance + const costmap_2d::Costmap2D& costmap_; ///< @brief Provides access to cost map information + WorldModel& world_model_; ///< @brief The world model that the controller uses for collision detection + + std::vector footprint_spec_; ///< @brief The footprint specification of the robot + + std::vector global_plan_; ///< @brief The global path for the robot to follow + + bool stuck_left, stuck_right; ///< @brief Booleans to keep the robot from oscillating during rotation + bool rotating_left, rotating_right; ///< @brief Booleans to keep track of the direction of rotation for the robot + + bool stuck_left_strafe, stuck_right_strafe; ///< @brief Booleans to keep the robot from oscillating during strafing + bool strafe_right, strafe_left; ///< @brief Booleans to keep track of strafe direction for the robot + + bool escaping_; ///< @brief Boolean to keep track of whether we're in escape mode + bool meter_scoring_; + + double goal_x_,goal_y_; ///< @brief Storage for the local goal the robot is pursuing + + double final_goal_x_, final_goal_y_; ///< @brief The end position of the plan. + bool final_goal_position_valid_; ///< @brief True if final_goal_x_ and final_goal_y_ have valid data. Only false if an empty path is sent. + + double sim_time_; ///< @brief The number of seconds each trajectory is "rolled-out" + double sim_granularity_; ///< @brief The distance between simulation points + double angular_sim_granularity_; ///< @brief The distance between angular simulation points + + int vx_samples_; ///< @brief The number of samples we'll take in the x dimenstion of the control space + int vtheta_samples_; ///< @brief The number of samples we'll take in the theta dimension of the control space + + double path_distance_bias_, goal_distance_bias_, occdist_scale_; ///< @brief Scaling factors for the controller's cost function + double acc_lim_x_, acc_lim_y_, acc_lim_theta_; ///< @brief The acceleration limits of the robot + + double prev_x_, prev_y_; ///< @brief Used to calculate the distance the robot has traveled before reseting oscillation booleans + double escape_x_, escape_y_, escape_theta_; ///< @brief Used to calculate the distance the robot has traveled before reseting escape booleans + + Trajectory traj_one, traj_two; ///< @brief Used for scoring trajectories + + double heading_lookahead_; ///< @brief How far the robot should look ahead of itself when differentiating between different rotational velocities + double oscillation_reset_dist_; ///< @brief The distance the robot must travel before it can explore rotational velocities that were unsuccessful in the past + double escape_reset_dist_, escape_reset_theta_; ///< @brief The distance the robot must travel before it can leave escape mode + bool holonomic_robot_; ///< @brief Is the robot holonomic or not? + + double max_vel_x_, min_vel_x_, max_vel_th_, min_vel_th_, min_in_place_vel_th_; ///< @brief Velocity limits for the controller + + double backup_vel_; ///< @brief The velocity to use while backing up + + bool dwa_; ///< @brief Should we use the dynamic window approach? + bool heading_scoring_; ///< @brief Should we score based on the rollout approach or the heading approach + double heading_scoring_timestep_; ///< @brief How far to look ahead in time when we score a heading + bool simple_attractor_; ///< @brief Enables simple attraction to a goal point + + std::vector y_vels_; ///< @brief Y velocities to explore + + double stop_time_buffer_; ///< @brief How long before hitting something we're going to enforce that the robot stop + double sim_period_; ///< @brief The number of seconds to use to compute max/min vels for dwa + + double inscribed_radius_, circumscribed_radius_; + + boost::mutex configuration_mutex_; + + /** + * @brief Compute x position based on velocity + * @param xi The current x position + * @param vx The current x velocity + * @param vy The current y velocity + * @param theta The current orientation + * @param dt The timestep to take + * @return The new x position + */ + inline double computeNewXPosition(double xi, double vx, double vy, double theta, double dt){ + return xi + (vx * cos(theta) + vy * cos(M_PI_2 + theta)) * dt; + } + + /** + * @brief Compute y position based on velocity + * @param yi The current y position + * @param vx The current x velocity + * @param vy The current y velocity + * @param theta The current orientation + * @param dt The timestep to take + * @return The new y position + */ + inline double computeNewYPosition(double yi, double vx, double vy, double theta, double dt){ + return yi + (vx * sin(theta) + vy * sin(M_PI_2 + theta)) * dt; + } + + /** + * @brief Compute orientation based on velocity + * @param thetai The current orientation + * @param vth The current theta velocity + * @param dt The timestep to take + * @return The new orientation + */ + inline double computeNewThetaPosition(double thetai, double vth, double dt){ + return thetai + vth * dt; + } + + //compute velocity based on acceleration + /** + * @brief Compute velocity based on acceleration + * @param vg The desired velocity, what we're accelerating up to + * @param vi The current velocity + * @param a_max An acceleration limit + * @param dt The timestep to take + * @return The new velocity + */ + inline double computeNewVelocity(double vg, double vi, double a_max, double dt){ + if((vg - vi) >= 0) { + return std::min(vg, vi + a_max * dt); + } + return std::max(vg, vi - a_max * dt); + } + + void getMaxSpeedToStopInTime(double time, double& vx, double& vy, double& vth){ + vx = acc_lim_x_ * std::max(time, 0.0); + vy = acc_lim_y_ * std::max(time, 0.0); + vth = acc_lim_theta_ * std::max(time, 0.0); + } + + double lineCost(int x0, int x1, int y0, int y1); + double pointCost(int x, int y); + double headingDiff(int cell_x, int cell_y, double x, double y, double heading); + }; +}; + +#endif diff --git a/navigations/base_local_planner/include/base_local_planner/trajectory_planner_ros.h b/navigations/base_local_planner/include/base_local_planner/trajectory_planner_ros.h new file mode 100755 index 0000000..0394945 --- /dev/null +++ b/navigations/base_local_planner/include/base_local_planner/trajectory_planner_ros.h @@ -0,0 +1,231 @@ +/********************************************************************* +* +* Software License Agreement (BSD License) +* +* Copyright (c) 2008, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of the Willow Garage nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* +* Author: Eitan Marder-Eppstein +*********************************************************************/ +#ifndef TRAJECTORY_ROLLOUT_TRAJECTORY_PLANNER_ROS_H_ +#define TRAJECTORY_ROLLOUT_TRAJECTORY_PLANNER_ROS_H_ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include + +#include +#include +#include +#include + +#include + +#include + +#include + +#include + +#include + +#include +#include + +#include + +namespace base_local_planner { + /** + * @class TrajectoryPlannerROS + * @brief A ROS wrapper for the trajectory controller that queries the param server to construct a controller + */ + class TrajectoryPlannerROS : public nav_core::BaseLocalPlanner { + public: + /** + * @brief Default constructor for the ros wrapper + */ + TrajectoryPlannerROS(); + + /** + * @brief Constructs the ros wrapper + * @param name The name to give this instance of the trajectory planner + * @param tf A pointer to a transform listener + * @param costmap The cost map to use for assigning costs to trajectories + */ + TrajectoryPlannerROS(std::string name, + tf2_ros::Buffer* tf, + costmap_2d::Costmap2DROS* costmap_ros); + + /** + * @brief Constructs the ros wrapper + * @param name The name to give this instance of the trajectory planner + * @param tf A pointer to a transform listener + * @param costmap The cost map to use for assigning costs to trajectories + */ + void initialize(std::string name, tf2_ros::Buffer* tf, + costmap_2d::Costmap2DROS* costmap_ros); + + /** + * @brief Destructor for the wrapper + */ + ~TrajectoryPlannerROS(); + + /** + * @brief Given the current position, orientation, and velocity of the robot, + * compute velocity commands to send to the base + * @param cmd_vel Will be filled with the velocity command to be passed to the robot base + * @return True if a valid trajectory was found, false otherwise + */ + bool computeVelocityCommands(geometry_msgs::Twist& cmd_vel); + + /** + * @brief Set the plan that the controller is following + * @param orig_global_plan The plan to pass to the controller + * @return True if the plan was updated successfully, false otherwise + */ + bool setPlan(const std::vector& orig_global_plan); + + /** + * @brief Check if the goal pose has been achieved + * @return True if achieved, false otherwise + */ + bool isGoalReached(); + + /** + * @brief Generate and score a single trajectory + * @param vx_samp The x velocity used to seed the trajectory + * @param vy_samp The y velocity used to seed the trajectory + * @param vtheta_samp The theta velocity used to seed the trajectory + * @param update_map Whether or not to update the map for the planner + * when computing the legality of the trajectory, this is useful to set + * to false if you're going to be doing a lot of trajectory checking over + * a short period of time + * @return True if the trajectory is legal, false otherwise + */ + bool checkTrajectory(double vx_samp, double vy_samp, double vtheta_samp, bool update_map = true); + + /** + * @brief Generate and score a single trajectory + * @param vx_samp The x velocity used to seed the trajectory + * @param vy_samp The y velocity used to seed the trajectory + * @param vtheta_samp The theta velocity used to seed the trajectory + * @param update_map Whether or not to update the map for the planner + * when computing the legality of the trajectory, this is useful to set + * to false if you're going to be doing a lot of trajectory checking over + * a short period of time + * @return score of trajectory (double) + */ + double scoreTrajectory(double vx_samp, double vy_samp, double vtheta_samp, bool update_map = true); + + bool isInitialized() { + return initialized_; + } + + /** @brief Return the inner TrajectoryPlanner object. Only valid after initialize(). */ + TrajectoryPlanner* getPlanner() const { return tc_; } + + private: + /** + * @brief Callback to update the local planner's parameters based on dynamic reconfigure + */ + void reconfigureCB(BaseLocalPlannerConfig &config, uint32_t level); + + /** + * @brief Once a goal position is reached... rotate to the goal orientation + * @param global_pose The pose of the robot in the global frame + * @param robot_vel The velocity of the robot + * @param goal_th The desired th value for the goal + * @param cmd_vel The velocity commands to be filled + * @return True if a valid trajectory was found, false otherwise + */ + bool rotateToGoal(const geometry_msgs::PoseStamped& global_pose, const geometry_msgs::PoseStamped& robot_vel, double goal_th, geometry_msgs::Twist& cmd_vel); + + /** + * @brief Stop the robot taking into account acceleration limits + * @param global_pose The pose of the robot in the global frame + * @param robot_vel The velocity of the robot + * @param cmd_vel The velocity commands to be filled + * @return True if a valid trajectory was found, false otherwise + */ + bool stopWithAccLimits(const geometry_msgs::PoseStamped& global_pose, const geometry_msgs::PoseStamped& robot_vel, geometry_msgs::Twist& cmd_vel); + + std::vector loadYVels(ros::NodeHandle node); + + double sign(double x){ + return x < 0.0 ? -1.0 : 1.0; + } + + WorldModel* world_model_; ///< @brief The world model that the controller will use + TrajectoryPlanner* tc_; ///< @brief The trajectory controller + + costmap_2d::Costmap2DROS* costmap_ros_; ///< @brief The ROS wrapper for the costmap the controller will use + costmap_2d::Costmap2D* costmap_; ///< @brief The costmap the controller will use + MapGridVisualizer map_viz_; ///< @brief The map grid visualizer for outputting the potential field generated by the cost function + tf2_ros::Buffer* tf_; ///< @brief Used for transforming point clouds + std::string global_frame_; ///< @brief The frame in which the controller will run + double max_sensor_range_; ///< @brief Keep track of the effective maximum range of our sensors + nav_msgs::Odometry base_odom_; ///< @brief Used to get the velocity of the robot + std::string robot_base_frame_; ///< @brief Used as the base frame id of the robot + double rot_stopped_velocity_, trans_stopped_velocity_; + double xy_goal_tolerance_, yaw_goal_tolerance_, min_in_place_vel_th_; + std::vector global_plan_; + bool prune_plan_; + boost::recursive_mutex odom_lock_; + + double max_vel_th_, min_vel_th_; + double acc_lim_x_, acc_lim_y_, acc_lim_theta_; + double sim_period_; + bool rotating_to_goal_; + bool reached_goal_; + bool latch_xy_goal_tolerance_, xy_tolerance_latch_; + + ros::Publisher g_plan_pub_, l_plan_pub_; + + dynamic_reconfigure::Server *dsrv_; + base_local_planner::BaseLocalPlannerConfig default_config_; + bool setup_; + + + bool initialized_; + base_local_planner::OdometryHelperRos odom_helper_; + + std::vector footprint_spec_; + }; +}; +#endif diff --git a/navigations/base_local_planner/include/base_local_planner/trajectory_sample_generator.h b/navigations/base_local_planner/include/base_local_planner/trajectory_sample_generator.h new file mode 100755 index 0000000..b67a0f1 --- /dev/null +++ b/navigations/base_local_planner/include/base_local_planner/trajectory_sample_generator.h @@ -0,0 +1,74 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2008, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: TKruse + *********************************************************************/ + +#ifndef TRAJECTORY_SAMPLE_GENERATOR_H_ +#define TRAJECTORY_SAMPLE_GENERATOR_H_ + +#include + +namespace base_local_planner { + +/** + * @class TrajectorySampleGenerator + * @brief Provides an interface for navigation trajectory generators + */ +class TrajectorySampleGenerator { +public: + + /** + * Whether this generator can create more trajectories + */ + virtual bool hasMoreTrajectories() = 0; + + /** + * Whether this generator can create more trajectories + */ + virtual bool nextTrajectory(Trajectory &traj) = 0; + + /** + * @brief Virtual destructor for the interface + */ + virtual ~TrajectorySampleGenerator() {} + +protected: + TrajectorySampleGenerator() {} + +}; + +} // end namespace + +#endif /* TRAJECTORY_SAMPLE_GENERATOR_H_ */ diff --git a/navigations/base_local_planner/include/base_local_planner/trajectory_search.h b/navigations/base_local_planner/include/base_local_planner/trajectory_search.h new file mode 100755 index 0000000..a473cd3 --- /dev/null +++ b/navigations/base_local_planner/include/base_local_planner/trajectory_search.h @@ -0,0 +1,71 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2008, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: TKruse + *********************************************************************/ + +#ifndef TRAJECTORY_SEARCH_H_ +#define TRAJECTORY_SEARCH_H_ + +#include + +namespace base_local_planner { + +/** + * @class TrajectorySearch + * @brief Interface for modules finding a trajectory to use for navigation commands next + */ +class TrajectorySearch { +public: + /** + * searches the space of allowed trajectory and + * returns one considered the optimal given the + * constraints of the particular search. + * + * @param traj The container to write the result to + * @param all_explored pass NULL or a container to collect all trajectories for debugging (has a penalty) + */ + virtual bool findBestTrajectory(Trajectory& traj, std::vector* all_explored) = 0; + + virtual ~TrajectorySearch() {} + +protected: + TrajectorySearch() {} + +}; + + +} + +#endif /* TRAJECTORY_SEARCH_H_ */ diff --git a/navigations/base_local_planner/include/base_local_planner/twirling_cost_function.h b/navigations/base_local_planner/include/base_local_planner/twirling_cost_function.h new file mode 100755 index 0000000..5ce02e1 --- /dev/null +++ b/navigations/base_local_planner/include/base_local_planner/twirling_cost_function.h @@ -0,0 +1,64 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Open Source Robotics Foundation, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: Morgan Quigley + *********************************************************************/ + +#ifndef TWIRLING_COST_FUNCTION_H +#define TWIRLING_COST_FUNCTION_H + +#include + +namespace base_local_planner { + +/** + * This class provides a cost based on how much a robot "twirls" on its + * way to the goal. With differential-drive robots, there isn't a choice, + * but with holonomic or near-holonomic robots, sometimes a robot spins + * more than you'd like on its way to a goal. This class provides a way + * to assign a penalty purely to rotational velocities. + */ +class TwirlingCostFunction: public base_local_planner::TrajectoryCostFunction { +public: + + TwirlingCostFunction() {} + ~TwirlingCostFunction() {} + + double scoreTrajectory(Trajectory &traj); + + bool prepare() {return true;}; +}; + +} /* namespace base_local_planner */ +#endif /* TWIRLING_COST_FUNCTION_H_ */ diff --git a/navigations/base_local_planner/include/base_local_planner/velocity_iterator.h b/navigations/base_local_planner/include/base_local_planner/velocity_iterator.h new file mode 100755 index 0000000..f4fc490 --- /dev/null +++ b/navigations/base_local_planner/include/base_local_planner/velocity_iterator.h @@ -0,0 +1,99 @@ +/********************************************************************* +* +* Software License Agreement (BSD License) +* +* Copyright (c) 2009, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of Willow Garage, Inc. nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* +* Author: Eitan Marder-Eppstein +*********************************************************************/ +#ifndef DWA_LOCAL_PLANNER_VELOCITY_ITERATOR_H_ +#define DWA_LOCAL_PLANNER_VELOCITY_ITERATOR_H_ +#include +#include +#include + +namespace base_local_planner { + + /** + * We use the class to get even sized samples between min and max, inluding zero if it is not included (and range goes from negative to positive + */ + class VelocityIterator { + public: + VelocityIterator(double min, double max, int num_samples): + current_index(0) + { + if (min == max) { + samples_.push_back(min); + } else { + num_samples = std::max(2, num_samples); + + // e.g. for 4 samples, split distance in 3 even parts + double step_size = (max - min) / double(std::max(1, (num_samples - 1))); + + // we make sure to avoid rounding errors around min and max. + double current; + double next = min; + for (int j = 0; j < num_samples - 1; ++j) { + current = next; + next += step_size; + samples_.push_back(current); + // if 0 is among samples, this is never true. Else it inserts a 0 between the positive and negative samples + if ((current < 0) && (next > 0)) { + samples_.push_back(0.0); + } + } + samples_.push_back(max); + } + } + + double getVelocity(){ + return samples_.at(current_index); + } + + VelocityIterator& operator++(int){ + current_index++; + return *this; + } + + void reset(){ + current_index = 0; + } + + bool isFinished(){ + return current_index >= samples_.size(); + } + + private: + std::vector samples_; + unsigned int current_index; + }; +}; +#endif diff --git a/navigations/base_local_planner/include/base_local_planner/voxel_grid_model.h b/navigations/base_local_planner/include/base_local_planner/voxel_grid_model.h new file mode 100755 index 0000000..4ecb288 --- /dev/null +++ b/navigations/base_local_planner/include/base_local_planner/voxel_grid_model.h @@ -0,0 +1,179 @@ +/********************************************************************* +* +* Software License Agreement (BSD License) +* +* Copyright (c) 2008, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of the Willow Garage nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* +* Author: Eitan Marder-Eppstein +*********************************************************************/ +#ifndef TRAJECTORY_ROLLOUT_VOXEL_WORLD_MODEL_H_ +#define TRAJECTORY_ROLLOUT_VOXEL_WORLD_MODEL_H_ +#include +#include +#include +#include +#include +#include + +//voxel grid stuff +#include + +namespace base_local_planner { + /** + * @class VoxelGridModel + * @brief A class that implements the WorldModel interface to provide grid + * based collision checks for the trajectory controller using a 3D voxel grid. + */ + class VoxelGridModel : public WorldModel { + public: + /** + * @brief Constructor for the VoxelGridModel + * @param size_x The x size of the map + * @param size_y The y size of the map + * @param size_z The z size of the map... up to 32 cells + * @param xy_resolution The horizontal resolution of the map in meters/cell + * @param z_resolution The vertical resolution of the map in meters/cell + * @param origin_x The x value of the origin of the map + * @param origin_y The y value of the origin of the map + * @param origin_z The z value of the origin of the map + * @param max_z The maximum height for an obstacle to be added to the grid + * @param obstacle_range The maximum distance for obstacles to be added to the grid + */ + VoxelGridModel(double size_x, double size_y, double size_z, double xy_resolution, double z_resolution, + double origin_x, double origin_y, double origin_z, double max_z, double obstacle_range); + + /** + * @brief Destructor for the world model + */ + virtual ~VoxelGridModel(){} + + /** + * @brief Checks if any obstacles in the voxel grid lie inside a convex footprint that is rasterized into the grid + * @param position The position of the robot in world coordinates + * @param footprint The specification of the footprint of the robot in world coordinates + * @param inscribed_radius The radius of the inscribed circle of the robot + * @param circumscribed_radius The radius of the circumscribed circle of the robot + * @return Positive if all the points lie outside the footprint, negative otherwise + */ + virtual double footprintCost(const geometry_msgs::Point& position, const std::vector& footprint, + double inscribed_radius, double circumscribed_radius); + + using WorldModel::footprintCost; + + /** + * @brief The costmap already keeps track of world observations, so for this world model this method does nothing + * @param footprint The footprint of the robot in its current location + * @param observations The observations from various sensors + * @param laser_scan The scans used to clear freespace + */ + void updateWorld(const std::vector& footprint, + const std::vector& observations, const std::vector& laser_scans); + + /** + * @brief Function copying the Voxel points into a point cloud + * @param cloud the point cloud to copy data to. It has the usual x,y,z channels + */ + void getPoints(sensor_msgs::PointCloud2& cloud); + + private: + /** + * @brief Rasterizes a line in the costmap grid and checks for collisions + * @param x0 The x position of the first cell in grid coordinates + * @param y0 The y position of the first cell in grid coordinates + * @param x1 The x position of the second cell in grid coordinates + * @param y1 The y position of the second cell in grid coordinates + * @return A positive cost for a legal line... negative otherwise + */ + double lineCost(int x0, int x1, int y0, int y1); + + /** + * @brief Checks the cost of a point in the costmap + * @param x The x position of the point in cell coordinates + * @param y The y position of the point in cell coordinates + * @return A positive cost for a legal point... negative otherwise + */ + double pointCost(int x, int y); + + void removePointsInScanBoundry(const PlanarLaserScan& laser_scan, double raytrace_range); + + inline bool worldToMap3D(double wx, double wy, double wz, unsigned int& mx, unsigned int& my, unsigned int& mz){ + if(wx < origin_x_ || wy < origin_y_ || wz < origin_z_) + return false; + mx = (int) ((wx - origin_x_) / xy_resolution_); + my = (int) ((wy - origin_y_) / xy_resolution_); + mz = (int) ((wz - origin_z_) / z_resolution_); + return true; + } + + inline bool worldToMap2D(double wx, double wy, unsigned int& mx, unsigned int& my){ + if(wx < origin_x_ || wy < origin_y_) + return false; + mx = (int) ((wx - origin_x_) / xy_resolution_); + my = (int) ((wy - origin_y_) / xy_resolution_); + return true; + } + + inline void mapToWorld3D(unsigned int mx, unsigned int my, unsigned int mz, double& wx, double& wy, double& wz){ + //returns the center point of the cell + wx = origin_x_ + (mx + 0.5) * xy_resolution_; + wy = origin_y_ + (my + 0.5) * xy_resolution_; + wz = origin_z_ + (mz + 0.5) * z_resolution_; + } + + inline void mapToWorld2D(unsigned int mx, unsigned int my, double& wx, double& wy){ + //returns the center point of the cell + wx = origin_x_ + (mx + 0.5) * xy_resolution_; + wy = origin_y_ + (my + 0.5) * xy_resolution_; + } + + inline double dist(double x0, double y0, double z0, double x1, double y1, double z1){ + return sqrt((x1 - x0) * (x1 - x0) + (y1 - y0) * (y1 - y0) + (z1 - z0) * (z1 - z0)); + } + + inline void insert(const geometry_msgs::Point32& pt){ + unsigned int cell_x, cell_y, cell_z; + if(!worldToMap3D(pt.x, pt.y, pt.z, cell_x, cell_y, cell_z)) + return; + obstacle_grid_.markVoxel(cell_x, cell_y, cell_z); + } + + voxel_grid::VoxelGrid obstacle_grid_; + double xy_resolution_; + double z_resolution_; + double origin_x_; + double origin_y_; + double origin_z_; + double max_z_; ///< @brief The height cutoff for adding points as obstacles + double sq_obstacle_range_; ///< @brief The square distance at which we no longer add obstacles to the grid + + }; +}; +#endif diff --git a/navigations/base_local_planner/include/base_local_planner/world_model.h b/navigations/base_local_planner/include/base_local_planner/world_model.h new file mode 100755 index 0000000..b4ca3bb --- /dev/null +++ b/navigations/base_local_planner/include/base_local_planner/world_model.h @@ -0,0 +1,114 @@ +/********************************************************************* +* +* Software License Agreement (BSD License) +* +* Copyright (c) 2008, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of the Willow Garage nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* +* Author: Eitan Marder-Eppstein +*********************************************************************/ +#ifndef TRAJECTORY_ROLLOUT_WORLD_MODEL_H_ +#define TRAJECTORY_ROLLOUT_WORLD_MODEL_H_ + +#include +#include +#include +#include +#include + +namespace base_local_planner { + /** + * @class WorldModel + * @brief An interface the trajectory controller uses to interact with the + * world regardless of the underlying world model. + */ + class WorldModel{ + public: + /** + * @brief Subclass will implement this method to check a footprint at a given position and orientation for legality in the world + * @param position The position of the robot in world coordinates + * @param footprint The specification of the footprint of the robot in world coordinates + * @param inscribed_radius The radius of the inscribed circle of the robot + * @param circumscribed_radius The radius of the circumscribed circle of the robot + * @return Positive if all the points lie outside the footprint, negative otherwise: + * -1 if footprint covers at least a lethal obstacle cell, or + * -2 if footprint covers at least a no-information cell, or + * -3 if footprint is partially or totally outside of the map + */ + virtual double footprintCost(const geometry_msgs::Point& position, const std::vector& footprint, + double inscribed_radius, double circumscribed_radius) = 0; + + double footprintCost(double x, double y, double theta, const std::vector& footprint_spec, double inscribed_radius = 0.0, double circumscribed_radius=0.0){ + + double cos_th = cos(theta); + double sin_th = sin(theta); + std::vector oriented_footprint; + for(unsigned int i = 0; i < footprint_spec.size(); ++i){ + geometry_msgs::Point new_pt; + new_pt.x = x + (footprint_spec[i].x * cos_th - footprint_spec[i].y * sin_th); + new_pt.y = y + (footprint_spec[i].x * sin_th + footprint_spec[i].y * cos_th); + oriented_footprint.push_back(new_pt); + } + + geometry_msgs::Point robot_position; + robot_position.x = x; + robot_position.y = y; + + if(inscribed_radius==0.0){ + costmap_2d::calculateMinAndMaxDistances(footprint_spec, inscribed_radius, circumscribed_radius); + } + + return footprintCost(robot_position, oriented_footprint, inscribed_radius, circumscribed_radius); + } + + /** + * @brief Checks if any obstacles in the costmap lie inside a convex footprint that is rasterized into the grid + * @param position The position of the robot in world coordinates + * @param footprint The specification of the footprint of the robot in world coordinates + * @param inscribed_radius The radius of the inscribed circle of the robot + * @param circumscribed_radius The radius of the circumscribed circle of the robot + * @return Positive if all the points lie outside the footprint, negative otherwise + */ + double footprintCost(const geometry_msgs::Point& position, const std::vector& footprint, + double inscribed_radius, double circumscribed_radius, double extra) { + return footprintCost(position, footprint, inscribed_radius, circumscribed_radius); + } + + /** + * @brief Subclass will implement a destructor + */ + virtual ~WorldModel(){} + + protected: + WorldModel(){} + }; + +}; +#endif diff --git a/navigations/base_local_planner/msg/Position2DInt.msg b/navigations/base_local_planner/msg/Position2DInt.msg new file mode 100755 index 0000000..7d5c799 --- /dev/null +++ b/navigations/base_local_planner/msg/Position2DInt.msg @@ -0,0 +1,2 @@ +int64 x +int64 y \ No newline at end of file diff --git a/navigations/base_local_planner/package.xml b/navigations/base_local_planner/package.xml new file mode 100755 index 0000000..78b7126 --- /dev/null +++ b/navigations/base_local_planner/package.xml @@ -0,0 +1,52 @@ + + + + base_local_planner + 1.17.3 + + + This package provides implementations of the Trajectory Rollout and Dynamic Window approaches to local robot navigation on a plane. Given a plan to follow and a costmap, the controller produces velocity commands to send to a mobile base. This package supports both holonomic and non-holonomic robots, any robot footprint that can be represented as a convex polygon or circle, and exposes its configuration as ROS parameters that can be set in a launch file. This package's ROS wrapper adheres to the BaseLocalPlanner interface specified in the nav_core package. + + + Eitan Marder-Eppstein + Eric Perko + contradict@gmail.com + Michael Ferguson + David V. Lu!! + Aaron Hoy + BSD + http://wiki.ros.org/base_local_planner + + catkin + python-setuptools + python3-setuptools + + cmake_modules + message_generation + tf2_geometry_msgs + + angles + costmap_2d + dynamic_reconfigure + eigen + geometry_msgs + nav_core + nav_msgs + pluginlib + sensor_msgs + std_msgs + rosconsole + roscpp + rospy + tf2 + tf2_ros + visualization_msgs + voxel_grid + + message_runtime + + rosunit + + + + diff --git a/navigations/base_local_planner/setup.py b/navigations/base_local_planner/setup.py new file mode 100755 index 0000000..d175406 --- /dev/null +++ b/navigations/base_local_planner/setup.py @@ -0,0 +1,10 @@ +#!/usr/bin/env python +from setuptools import setup +from catkin_pkg.python_setup import generate_distutils_setup + +d = generate_distutils_setup( + packages = ['local_planner_limits'], + package_dir = {'': 'src'}, + ) + +setup(**d) diff --git a/navigations/base_local_planner/src/costmap_model.cpp b/navigations/base_local_planner/src/costmap_model.cpp new file mode 100755 index 0000000..2f7896f --- /dev/null +++ b/navigations/base_local_planner/src/costmap_model.cpp @@ -0,0 +1,145 @@ +/********************************************************************* +* +* Software License Agreement (BSD License) +* +* Copyright (c) 2008, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of the Willow Garage nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* +* Author: Eitan Marder-Eppstein +*********************************************************************/ +#include +#include +#include + +using namespace std; +using namespace costmap_2d; + +namespace base_local_planner { + CostmapModel::CostmapModel(const Costmap2D& ma) : costmap_(ma) {} + + double CostmapModel::footprintCost(const geometry_msgs::Point& position, const std::vector& footprint, + double inscribed_radius, double circumscribed_radius){ + // returns: + // -1 if footprint covers at least a lethal obstacle cell, or + // -2 if footprint covers at least a no-information cell, or + // -3 if footprint is [partially] outside of the map, or + // a positive value for traversable space + + //used to put things into grid coordinates + unsigned int cell_x, cell_y; + + //get the cell coord of the center point of the robot + if(!costmap_.worldToMap(position.x, position.y, cell_x, cell_y)) + return -3.0; + + //if number of points in the footprint is less than 3, we'll just assume a circular robot + if(footprint.size() < 3){ + unsigned char cost = costmap_.getCost(cell_x, cell_y); + if(cost == NO_INFORMATION) + return -2.0; + if(cost == LETHAL_OBSTACLE || cost == INSCRIBED_INFLATED_OBSTACLE) + return -1.0; + return cost; + } + + //now we really have to lay down the footprint in the costmap grid + unsigned int x0, x1, y0, y1; + double line_cost = 0.0; + double footprint_cost = 0.0; + + //we need to rasterize each line in the footprint + for(unsigned int i = 0; i < footprint.size() - 1; ++i){ + //get the cell coord of the first point + if(!costmap_.worldToMap(footprint[i].x, footprint[i].y, x0, y0)) + return -3.0; + + //get the cell coord of the second point + if(!costmap_.worldToMap(footprint[i + 1].x, footprint[i + 1].y, x1, y1)) + return -3.0; + + line_cost = lineCost(x0, x1, y0, y1); + footprint_cost = std::max(line_cost, footprint_cost); + + //if there is an obstacle that hits the line... we know that we can return false right away + if(line_cost < 0) + return line_cost; + } + + //we also need to connect the first point in the footprint to the last point + //get the cell coord of the last point + if(!costmap_.worldToMap(footprint.back().x, footprint.back().y, x0, y0)) + return -3.0; + + //get the cell coord of the first point + if(!costmap_.worldToMap(footprint.front().x, footprint.front().y, x1, y1)) + return -3.0; + + line_cost = lineCost(x0, x1, y0, y1); + footprint_cost = std::max(line_cost, footprint_cost); + + if(line_cost < 0) + return line_cost; + + //if all line costs are legal... then we can return that the footprint is legal + return footprint_cost; + + } + + //calculate the cost of a ray-traced line + double CostmapModel::lineCost(int x0, int x1, int y0, int y1) const { + double line_cost = 0.0; + double point_cost = -1.0; + + for( LineIterator line( x0, y0, x1, y1 ); line.isValid(); line.advance() ) + { + point_cost = pointCost( line.getX(), line.getY() ); //Score the current point + + if(point_cost < 0) + return point_cost; + + if(line_cost < point_cost) + line_cost = point_cost; + } + + return line_cost; + } + + double CostmapModel::pointCost(int x, int y) const { + unsigned char cost = costmap_.getCost(x, y); + //if the cell is in an obstacle the path is invalid + if(cost == NO_INFORMATION) + return -2; + if(cost == LETHAL_OBSTACLE) + return -1; + + return cost; + } + +}; diff --git a/navigations/base_local_planner/src/footprint_helper.cpp b/navigations/base_local_planner/src/footprint_helper.cpp new file mode 100755 index 0000000..d94da1c --- /dev/null +++ b/navigations/base_local_planner/src/footprint_helper.cpp @@ -0,0 +1,248 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2008, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: TKruse + *********************************************************************/ + +#include + +namespace base_local_planner { + +FootprintHelper::FootprintHelper() { + // TODO Auto-generated constructor stub + +} + +FootprintHelper::~FootprintHelper() { + // TODO Auto-generated destructor stub +} + +void FootprintHelper::getLineCells(int x0, int x1, int y0, int y1, std::vector& pts) { + //Bresenham Ray-Tracing + int deltax = abs(x1 - x0); // The difference between the x's + int deltay = abs(y1 - y0); // The difference between the y's + int x = x0; // Start x off at the first pixel + int y = y0; // Start y off at the first pixel + + int xinc1, xinc2, yinc1, yinc2; + int den, num, numadd, numpixels; + + base_local_planner::Position2DInt pt; + + if (x1 >= x0) // The x-values are increasing + { + xinc1 = 1; + xinc2 = 1; + } + else // The x-values are decreasing + { + xinc1 = -1; + xinc2 = -1; + } + + if (y1 >= y0) // The y-values are increasing + { + yinc1 = 1; + yinc2 = 1; + } + else // The y-values are decreasing + { + yinc1 = -1; + yinc2 = -1; + } + + if (deltax >= deltay) // There is at least one x-value for every y-value + { + xinc1 = 0; // Don't change the x when numerator >= denominator + yinc2 = 0; // Don't change the y for every iteration + den = deltax; + num = deltax / 2; + numadd = deltay; + numpixels = deltax; // There are more x-values than y-values + } + else // There is at least one y-value for every x-value + { + xinc2 = 0; // Don't change the x for every iteration + yinc1 = 0; // Don't change the y when numerator >= denominator + den = deltay; + num = deltay / 2; + numadd = deltax; + numpixels = deltay; // There are more y-values than x-values + } + + for (int curpixel = 0; curpixel <= numpixels; curpixel++) + { + pt.x = x; //Draw the current pixel + pt.y = y; + pts.push_back(pt); + + num += numadd; // Increase the numerator by the top of the fraction + if (num >= den) // Check if numerator >= denominator + { + num -= den; // Calculate the new numerator value + x += xinc1; // Change the x as appropriate + y += yinc1; // Change the y as appropriate + } + x += xinc2; // Change the x as appropriate + y += yinc2; // Change the y as appropriate + } +} + + +void FootprintHelper::getFillCells(std::vector& footprint){ + //quick bubble sort to sort pts by x + base_local_planner::Position2DInt swap, pt; + unsigned int i = 0; + while (i < footprint.size() - 1) { + if (footprint[i].x > footprint[i + 1].x) { + swap = footprint[i]; + footprint[i] = footprint[i + 1]; + footprint[i + 1] = swap; + if(i > 0) { + --i; + } + } else { + ++i; + } + } + + i = 0; + base_local_planner::Position2DInt min_pt; + base_local_planner::Position2DInt max_pt; + unsigned int min_x = footprint[0].x; + unsigned int max_x = footprint[footprint.size() -1].x; + //walk through each column and mark cells inside the footprint + for (unsigned int x = min_x; x <= max_x; ++x) { + if (i >= footprint.size() - 1) { + break; + } + if (footprint[i].y < footprint[i + 1].y) { + min_pt = footprint[i]; + max_pt = footprint[i + 1]; + } else { + min_pt = footprint[i + 1]; + max_pt = footprint[i]; + } + + i += 2; + while (i < footprint.size() && footprint[i].x == x) { + if(footprint[i].y < min_pt.y) { + min_pt = footprint[i]; + } else if(footprint[i].y > max_pt.y) { + max_pt = footprint[i]; + } + ++i; + } + + //loop though cells in the column + for (unsigned int y = min_pt.y; y < max_pt.y; ++y) { + pt.x = x; + pt.y = y; + footprint.push_back(pt); + } + } +} + +/** + * get the cellsof a footprint at a given position + */ +std::vector FootprintHelper::getFootprintCells( + Eigen::Vector3f pos, + std::vector footprint_spec, + const costmap_2d::Costmap2D& costmap, + bool fill){ + double x_i = pos[0]; + double y_i = pos[1]; + double theta_i = pos[2]; + std::vector footprint_cells; + + //if we have no footprint... do nothing + if (footprint_spec.size() <= 1) { + unsigned int mx, my; + if (costmap.worldToMap(x_i, y_i, mx, my)) { + Position2DInt center; + center.x = mx; + center.y = my; + footprint_cells.push_back(center); + } + return footprint_cells; + } + + //pre-compute cos and sin values + double cos_th = cos(theta_i); + double sin_th = sin(theta_i); + double new_x, new_y; + unsigned int x0, y0, x1, y1; + unsigned int last_index = footprint_spec.size() - 1; + + for (unsigned int i = 0; i < last_index; ++i) { + //find the cell coordinates of the first segment point + new_x = x_i + (footprint_spec[i].x * cos_th - footprint_spec[i].y * sin_th); + new_y = y_i + (footprint_spec[i].x * sin_th + footprint_spec[i].y * cos_th); + if(!costmap.worldToMap(new_x, new_y, x0, y0)) { + return footprint_cells; + } + + //find the cell coordinates of the second segment point + new_x = x_i + (footprint_spec[i + 1].x * cos_th - footprint_spec[i + 1].y * sin_th); + new_y = y_i + (footprint_spec[i + 1].x * sin_th + footprint_spec[i + 1].y * cos_th); + if (!costmap.worldToMap(new_x, new_y, x1, y1)) { + return footprint_cells; + } + + getLineCells(x0, x1, y0, y1, footprint_cells); + } + + //we need to close the loop, so we also have to raytrace from the last pt to first pt + new_x = x_i + (footprint_spec[last_index].x * cos_th - footprint_spec[last_index].y * sin_th); + new_y = y_i + (footprint_spec[last_index].x * sin_th + footprint_spec[last_index].y * cos_th); + if (!costmap.worldToMap(new_x, new_y, x0, y0)) { + return footprint_cells; + } + new_x = x_i + (footprint_spec[0].x * cos_th - footprint_spec[0].y * sin_th); + new_y = y_i + (footprint_spec[0].x * sin_th + footprint_spec[0].y * cos_th); + if(!costmap.worldToMap(new_x, new_y, x1, y1)) { + return footprint_cells; + } + + getLineCells(x0, x1, y0, y1, footprint_cells); + + if(fill) { + getFillCells(footprint_cells); + } + + return footprint_cells; +} + +} /* namespace base_local_planner */ diff --git a/navigations/base_local_planner/src/goal_functions.cpp b/navigations/base_local_planner/src/goal_functions.cpp new file mode 100755 index 0000000..ca705a7 --- /dev/null +++ b/navigations/base_local_planner/src/goal_functions.cpp @@ -0,0 +1,245 @@ +/********************************************************************* +* +* Software License Agreement (BSD License) +* +* Copyright (c) 2009, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of Willow Garage, Inc. nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* +* Author: Eitan Marder-Eppstein +*********************************************************************/ +#include +#include +#include +#include +#ifdef _MSC_VER +#define GOAL_ATTRIBUTE_UNUSED +#else +#define GOAL_ATTRIBUTE_UNUSED __attribute__ ((unused)) +#endif + +namespace base_local_planner { + + double getGoalPositionDistance(const geometry_msgs::PoseStamped& global_pose, double goal_x, double goal_y) { + return hypot(goal_x - global_pose.pose.position.x, goal_y - global_pose.pose.position.y); + } + + double getGoalOrientationAngleDifference(const geometry_msgs::PoseStamped& global_pose, double goal_th) { + double yaw = tf2::getYaw(global_pose.pose.orientation); + return angles::shortest_angular_distance(yaw, goal_th); + } + + void publishPlan(const std::vector& path, const ros::Publisher& pub) { + //given an empty path we won't do anything + if(path.empty()) + return; + + //create a path message + nav_msgs::Path gui_path; + gui_path.poses.resize(path.size()); + gui_path.header.frame_id = path[0].header.frame_id; + gui_path.header.stamp = path[0].header.stamp; + + // Extract the plan in world co-ordinates, we assume the path is all in the same frame + for(unsigned int i=0; i < path.size(); i++){ + gui_path.poses[i] = path[i]; + } + + pub.publish(gui_path); + } + + void prunePlan(const geometry_msgs::PoseStamped& global_pose, std::vector& plan, std::vector& global_plan){ + ROS_ASSERT(global_plan.size() >= plan.size()); + std::vector::iterator it = plan.begin(); + std::vector::iterator global_it = global_plan.begin(); + while(it != plan.end()){ + const geometry_msgs::PoseStamped& w = *it; + // Fixed error bound of 2 meters for now. Can reduce to a portion of the map size or based on the resolution + double x_diff = global_pose.pose.position.x - w.pose.position.x; + double y_diff = global_pose.pose.position.y - w.pose.position.y; + double distance_sq = x_diff * x_diff + y_diff * y_diff; + if(distance_sq < 1){ + ROS_DEBUG("Nearest waypoint to <%f, %f> is <%f, %f>\n", global_pose.pose.position.x, global_pose.pose.position.y, w.pose.position.x, w.pose.position.y); + break; + } + it = plan.erase(it); + global_it = global_plan.erase(global_it); + } + } + + bool transformGlobalPlan( + const tf2_ros::Buffer& tf, + const std::vector& global_plan, + const geometry_msgs::PoseStamped& global_pose, + const costmap_2d::Costmap2D& costmap, + const std::string& global_frame, + std::vector& transformed_plan){ + transformed_plan.clear(); + + if (global_plan.empty()) { + ROS_ERROR("Received plan with zero length"); + return false; + } + + const geometry_msgs::PoseStamped& plan_pose = global_plan[0]; + try { + // get plan_to_global_transform from plan frame to global_frame + geometry_msgs::TransformStamped plan_to_global_transform = tf.lookupTransform(global_frame, ros::Time(), + plan_pose.header.frame_id, plan_pose.header.stamp, plan_pose.header.frame_id, ros::Duration(0.5)); + + //let's get the pose of the robot in the frame of the plan + geometry_msgs::PoseStamped robot_pose; + tf.transform(global_pose, robot_pose, plan_pose.header.frame_id); + + //we'll discard points on the plan that are outside the local costmap + double dist_threshold = std::max(costmap.getSizeInCellsX() * costmap.getResolution() / 2.0, + costmap.getSizeInCellsY() * costmap.getResolution() / 2.0); + + unsigned int i = 0; + double sq_dist_threshold = dist_threshold * dist_threshold; + double sq_dist = 0; + + //we need to loop to a point on the plan that is within a certain distance of the robot + while(i < (unsigned int)global_plan.size()) { + double x_diff = robot_pose.pose.position.x - global_plan[i].pose.position.x; + double y_diff = robot_pose.pose.position.y - global_plan[i].pose.position.y; + sq_dist = x_diff * x_diff + y_diff * y_diff; + if (sq_dist <= sq_dist_threshold) { + break; + } + ++i; + } + + geometry_msgs::PoseStamped newer_pose; + + //now we'll transform until points are outside of our distance threshold + while(i < (unsigned int)global_plan.size() && sq_dist <= sq_dist_threshold) { + const geometry_msgs::PoseStamped& pose = global_plan[i]; + tf2::doTransform(pose, newer_pose, plan_to_global_transform); + + transformed_plan.push_back(newer_pose); + + double x_diff = robot_pose.pose.position.x - global_plan[i].pose.position.x; + double y_diff = robot_pose.pose.position.y - global_plan[i].pose.position.y; + sq_dist = x_diff * x_diff + y_diff * y_diff; + + ++i; + } + } + catch(tf2::LookupException& ex) { + ROS_ERROR("No Transform available Error: %s\n", ex.what()); + return false; + } + catch(tf2::ConnectivityException& ex) { + ROS_ERROR("Connectivity Error: %s\n", ex.what()); + return false; + } + catch(tf2::ExtrapolationException& ex) { + ROS_ERROR("Extrapolation Error: %s\n", ex.what()); + if (!global_plan.empty()) + ROS_ERROR("Global Frame: %s Plan Frame size %d: %s\n", global_frame.c_str(), (unsigned int)global_plan.size(), global_plan[0].header.frame_id.c_str()); + + return false; + } + + return true; + } + + bool getGoalPose(const tf2_ros::Buffer& tf, + const std::vector& global_plan, + const std::string& global_frame, geometry_msgs::PoseStamped &goal_pose) { + if (global_plan.empty()) + { + ROS_ERROR("Received plan with zero length"); + return false; + } + + const geometry_msgs::PoseStamped& plan_goal_pose = global_plan.back(); + try{ + geometry_msgs::TransformStamped transform = tf.lookupTransform(global_frame, ros::Time(), + plan_goal_pose.header.frame_id, plan_goal_pose.header.stamp, + plan_goal_pose.header.frame_id, ros::Duration(0.5)); + + tf2::doTransform(plan_goal_pose, goal_pose, transform); + } + catch(tf2::LookupException& ex) { + ROS_ERROR("No Transform available Error: %s\n", ex.what()); + return false; + } + catch(tf2::ConnectivityException& ex) { + ROS_ERROR("Connectivity Error: %s\n", ex.what()); + return false; + } + catch(tf2::ExtrapolationException& ex) { + ROS_ERROR("Extrapolation Error: %s\n", ex.what()); + if (global_plan.size() > 0) + ROS_ERROR("Global Frame: %s Plan Frame size %d: %s\n", global_frame.c_str(), (unsigned int)global_plan.size(), global_plan[0].header.frame_id.c_str()); + + return false; + } + return true; + } + + bool isGoalReached(const tf2_ros::Buffer& tf, + const std::vector& global_plan, + const costmap_2d::Costmap2D& costmap GOAL_ATTRIBUTE_UNUSED, + const std::string& global_frame, + geometry_msgs::PoseStamped& global_pose, + const nav_msgs::Odometry& base_odom, + double rot_stopped_vel, double trans_stopped_vel, + double xy_goal_tolerance, double yaw_goal_tolerance){ + + //we assume the global goal is the last point in the global plan + geometry_msgs::PoseStamped goal_pose; + getGoalPose(tf, global_plan, global_frame, goal_pose); + + double goal_x = goal_pose.pose.position.x; + double goal_y = goal_pose.pose.position.y; + double goal_th = tf2::getYaw(goal_pose.pose.orientation); + + //check to see if we've reached the goal position + if(getGoalPositionDistance(global_pose, goal_x, goal_y) <= xy_goal_tolerance) { + //check to see if the goal orientation has been reached + if(fabs(getGoalOrientationAngleDifference(global_pose, goal_th)) <= yaw_goal_tolerance) { + //make sure that we're actually stopped before returning success + if(stopped(base_odom, rot_stopped_vel, trans_stopped_vel)) + return true; + } + } + + return false; + } + + bool stopped(const nav_msgs::Odometry& base_odom, + const double& rot_stopped_velocity, const double& trans_stopped_velocity){ + return fabs(base_odom.twist.twist.angular.z) <= rot_stopped_velocity + && fabs(base_odom.twist.twist.linear.x) <= trans_stopped_velocity + && fabs(base_odom.twist.twist.linear.y) <= trans_stopped_velocity; + } +}; diff --git a/navigations/base_local_planner/src/latched_stop_rotate_controller.cpp b/navigations/base_local_planner/src/latched_stop_rotate_controller.cpp new file mode 100755 index 0000000..9977a87 --- /dev/null +++ b/navigations/base_local_planner/src/latched_stop_rotate_controller.cpp @@ -0,0 +1,278 @@ +/* + * latched_stop_rotate_controller.cpp + * + * Created on: Apr 16, 2012 + * Author: tkruse + */ + +#include + +#include + +#include + +#include +#include + +#include +#include + +#include + +namespace base_local_planner { + +LatchedStopRotateController::LatchedStopRotateController(const std::string& name) { + ros::NodeHandle private_nh("~/" + name); + private_nh.param("latch_xy_goal_tolerance", latch_xy_goal_tolerance_, false); + + rotating_to_goal_ = false; +} + +LatchedStopRotateController::~LatchedStopRotateController() {} + + +/** + * returns true if we have passed the goal position. + * Meaning we might have overshot on the position beyond tolerance, yet still return true. + * Also goal orientation might not yet be true + */ +bool LatchedStopRotateController::isPositionReached(LocalPlannerUtil* planner_util, + const geometry_msgs::PoseStamped& global_pose) { + double xy_goal_tolerance = planner_util->getCurrentLimits().xy_goal_tolerance; + + //we assume the global goal is the last point in the global plan + geometry_msgs::PoseStamped goal_pose; + if ( ! planner_util->getGoal(goal_pose)) { + return false; + } + + double goal_x = goal_pose.pose.position.x; + double goal_y = goal_pose.pose.position.y; + + //check to see if we've reached the goal position + if ((latch_xy_goal_tolerance_ && xy_tolerance_latch_) || + base_local_planner::getGoalPositionDistance(global_pose, goal_x, goal_y) <= xy_goal_tolerance) { + xy_tolerance_latch_ = true; + return true; + } + return false; +} + + +/** + * returns true if we have passed the goal position and have reached goal orientation. + * Meaning we might have overshot on the position beyond tolerance, yet still return true. + */ +bool LatchedStopRotateController::isGoalReached(LocalPlannerUtil* planner_util, + OdometryHelperRos& odom_helper, + const geometry_msgs::PoseStamped& global_pose) { + double xy_goal_tolerance = planner_util->getCurrentLimits().xy_goal_tolerance; + double theta_stopped_vel = planner_util->getCurrentLimits().theta_stopped_vel; + double trans_stopped_vel = planner_util->getCurrentLimits().trans_stopped_vel; + + //copy over the odometry information + nav_msgs::Odometry base_odom; + odom_helper.getOdom(base_odom); + + //we assume the global goal is the last point in the global plan + geometry_msgs::PoseStamped goal_pose; + if ( ! planner_util->getGoal(goal_pose)) { + return false; + } + + double goal_x = goal_pose.pose.position.x; + double goal_y = goal_pose.pose.position.y; + + base_local_planner::LocalPlannerLimits limits = planner_util->getCurrentLimits(); + + //check to see if we've reached the goal position + if ((latch_xy_goal_tolerance_ && xy_tolerance_latch_) || + base_local_planner::getGoalPositionDistance(global_pose, goal_x, goal_y) <= xy_goal_tolerance) { + //if the user wants to latch goal tolerance, if we ever reach the goal location, we'll + //just rotate in place + if (latch_xy_goal_tolerance_ && ! xy_tolerance_latch_) { + ROS_DEBUG("Goal position reached (check), stopping and turning in place"); + xy_tolerance_latch_ = true; + } + double goal_th = tf2::getYaw(goal_pose.pose.orientation); + double angle = base_local_planner::getGoalOrientationAngleDifference(global_pose, goal_th); + //check to see if the goal orientation has been reached + if (fabs(angle) <= limits.yaw_goal_tolerance) { + //make sure that we're actually stopped before returning success + if (base_local_planner::stopped(base_odom, theta_stopped_vel, trans_stopped_vel)) { + return true; + } + } + } + return false; +} + +bool LatchedStopRotateController::stopWithAccLimits(const geometry_msgs::PoseStamped& global_pose, + const geometry_msgs::PoseStamped& robot_vel, + geometry_msgs::Twist& cmd_vel, + Eigen::Vector3f acc_lim, + double sim_period, + boost::function obstacle_check) { + + //slow down with the maximum possible acceleration... we should really use the frequency that we're running at to determine what is feasible + //but we'll use a tenth of a second to be consistent with the implementation of the local planner. + double vx = sign(robot_vel.pose.position.x) * std::max(0.0, (fabs(robot_vel.pose.position.x) - acc_lim[0] * sim_period)); + double vy = sign(robot_vel.pose.position.y) * std::max(0.0, (fabs(robot_vel.pose.position.y) - acc_lim[1] * sim_period)); + + double vel_yaw = tf2::getYaw(robot_vel.pose.orientation); + double vth = sign(vel_yaw) * std::max(0.0, (fabs(vel_yaw) - acc_lim[2] * sim_period)); + + //we do want to check whether or not the command is valid + double yaw = tf2::getYaw(global_pose.pose.orientation); + bool valid_cmd = obstacle_check(Eigen::Vector3f(global_pose.pose.position.x, global_pose.pose.position.y, yaw), + Eigen::Vector3f(robot_vel.pose.position.x, robot_vel.pose.position.y, vel_yaw), + Eigen::Vector3f(vx, vy, vth)); + + //if we have a valid command, we'll pass it on, otherwise we'll command all zeros + if(valid_cmd){ + ROS_DEBUG_NAMED("latched_stop_rotate", "Slowing down... using vx, vy, vth: %.2f, %.2f, %.2f", vx, vy, vth); + cmd_vel.linear.x = vx; + cmd_vel.linear.y = vy; + cmd_vel.angular.z = vth; + return true; + } + ROS_WARN("Stopping cmd in collision"); + cmd_vel.linear.x = 0.0; + cmd_vel.linear.y = 0.0; + cmd_vel.angular.z = 0.0; + return false; +} + +bool LatchedStopRotateController::rotateToGoal( + const geometry_msgs::PoseStamped& global_pose, + const geometry_msgs::PoseStamped& robot_vel, + double goal_th, + geometry_msgs::Twist& cmd_vel, + Eigen::Vector3f acc_lim, + double sim_period, + base_local_planner::LocalPlannerLimits& limits, + boost::function obstacle_check) { + double yaw = tf2::getYaw(global_pose.pose.orientation); + double vel_yaw = tf2::getYaw(robot_vel.pose.orientation); + cmd_vel.linear.x = 0; + cmd_vel.linear.y = 0; + double ang_diff = angles::shortest_angular_distance(yaw, goal_th); + + double v_theta_samp = std::min(limits.max_vel_theta, std::max(limits.min_vel_theta, fabs(ang_diff))); + + //take the acceleration limits of the robot into account + double max_acc_vel = fabs(vel_yaw) + acc_lim[2] * sim_period; + double min_acc_vel = fabs(vel_yaw) - acc_lim[2] * sim_period; + + v_theta_samp = std::min(std::max(fabs(v_theta_samp), min_acc_vel), max_acc_vel); + + //we also want to make sure to send a velocity that allows us to stop when we reach the goal given our acceleration limits + double max_speed_to_stop = sqrt(2 * acc_lim[2] * fabs(ang_diff)); + v_theta_samp = std::min(max_speed_to_stop, fabs(v_theta_samp)); + + v_theta_samp = std::min(limits.max_vel_theta, std::max(limits.min_vel_theta, v_theta_samp)); + + if (ang_diff < 0) { + v_theta_samp = - v_theta_samp; + } + + //we still want to lay down the footprint of the robot and check if the action is legal + bool valid_cmd = obstacle_check(Eigen::Vector3f(global_pose.pose.position.x, global_pose.pose.position.y, yaw), + Eigen::Vector3f(robot_vel.pose.position.x, robot_vel.pose.position.y, vel_yaw), + Eigen::Vector3f( 0.0, 0.0, v_theta_samp)); + + if (valid_cmd) { + ROS_DEBUG_NAMED("dwa_local_planner", "Moving to desired goal orientation, th cmd: %.2f, valid_cmd: %d", v_theta_samp, valid_cmd); + cmd_vel.angular.z = v_theta_samp; + return true; + } + ROS_WARN("Rotation cmd in collision"); + cmd_vel.angular.z = 0.0; + return false; + +} + +bool LatchedStopRotateController::computeVelocityCommandsStopRotate(geometry_msgs::Twist& cmd_vel, + Eigen::Vector3f acc_lim, + double sim_period, + LocalPlannerUtil* planner_util, + OdometryHelperRos& odom_helper_, + const geometry_msgs::PoseStamped& global_pose, + boost::function obstacle_check) { + //we assume the global goal is the last point in the global plan + geometry_msgs::PoseStamped goal_pose; + if ( ! planner_util->getGoal(goal_pose)) { + ROS_ERROR("Could not get goal pose"); + return false; + } + + base_local_planner::LocalPlannerLimits limits = planner_util->getCurrentLimits(); + + //if the user wants to latch goal tolerance, if we ever reach the goal location, we'll + //just rotate in place + if (latch_xy_goal_tolerance_ && ! xy_tolerance_latch_ ) { + ROS_INFO("Goal position reached, stopping and turning in place"); + xy_tolerance_latch_ = true; + } + //check to see if the goal orientation has been reached + double goal_th = tf2::getYaw(goal_pose.pose.orientation); + double angle = base_local_planner::getGoalOrientationAngleDifference(global_pose, goal_th); + if (fabs(angle) <= limits.yaw_goal_tolerance) { + //set the velocity command to zero + cmd_vel.linear.x = 0.0; + cmd_vel.linear.y = 0.0; + cmd_vel.angular.z = 0.0; + rotating_to_goal_ = false; + } else { + ROS_DEBUG("Angle: %f Tolerance: %f", angle, limits.yaw_goal_tolerance); + geometry_msgs::PoseStamped robot_vel; + odom_helper_.getRobotVel(robot_vel); + nav_msgs::Odometry base_odom; + odom_helper_.getOdom(base_odom); + + //if we're not stopped yet... we want to stop... taking into account the acceleration limits of the robot + if ( ! rotating_to_goal_ && !base_local_planner::stopped(base_odom, limits.theta_stopped_vel, limits.trans_stopped_vel)) { + if ( ! stopWithAccLimits( + global_pose, + robot_vel, + cmd_vel, + acc_lim, + sim_period, + obstacle_check)) { + ROS_INFO("Error when stopping."); + return false; + } + ROS_DEBUG("Stopping..."); + } + //if we're stopped... then we want to rotate to goal + else { + //set this so that we know its OK to be moving + rotating_to_goal_ = true; + if ( ! rotateToGoal( + global_pose, + robot_vel, + goal_th, + cmd_vel, + acc_lim, + sim_period, + limits, + obstacle_check)) { + ROS_INFO("Error when rotating."); + return false; + } + ROS_DEBUG("Rotating..."); + } + } + + return true; + +} + + +} /* namespace base_local_planner */ diff --git a/navigations/base_local_planner/src/local_planner_limits/.gitignore b/navigations/base_local_planner/src/local_planner_limits/.gitignore new file mode 100755 index 0000000..0d20b64 --- /dev/null +++ b/navigations/base_local_planner/src/local_planner_limits/.gitignore @@ -0,0 +1 @@ +*.pyc diff --git a/navigations/base_local_planner/src/local_planner_limits/__init__.py b/navigations/base_local_planner/src/local_planner_limits/__init__.py new file mode 100755 index 0000000..03fa1de --- /dev/null +++ b/navigations/base_local_planner/src/local_planner_limits/__init__.py @@ -0,0 +1,41 @@ +# Generic set of parameters to use with base local planners +# To use: +# +# from local_planner_limits import add_generic_localplanner_params +# gen = ParameterGenerator() +# add_generic_localplanner_params(gen) +# ... +# +# Using these standard parameters instead of your own allows easier switching of local planners + +# need this only for dataype declarations +from dynamic_reconfigure.parameter_generator_catkin import double_t, bool_t + + +def add_generic_localplanner_params(gen): + # velocities + gen.add("max_vel_trans", double_t, 0, "The absolute value of the maximum translational velocity for the robot in m/s", 0.55, 0) + gen.add("min_vel_trans", double_t, 0, "The absolute value of the minimum translational velocity for the robot in m/s", 0.1, 0) + + gen.add("max_vel_x", double_t, 0, "The maximum x velocity for the robot in m/s", 0.55) + gen.add("min_vel_x", double_t, 0, "The minimum x velocity for the robot in m/s", 0.0) + + gen.add("max_vel_y", double_t, 0, "The maximum y velocity for the robot in m/s", 0.1) + gen.add("min_vel_y", double_t, 0, "The minimum y velocity for the robot in m/s", -0.1) + + gen.add("max_vel_theta", double_t, 0, "The absolute value of the maximum rotational velocity for the robot in rad/s", 1.0, 0) + gen.add("min_vel_theta", double_t, 0, "The absolute value of the minimum rotational velocity for the robot in rad/s", 0.4, 0) + + # acceleration + gen.add("acc_lim_x", double_t, 0, "The acceleration limit of the robot in the x direction", 2.5, 0, 20.0) + gen.add("acc_lim_y", double_t, 0, "The acceleration limit of the robot in the y direction", 2.5, 0, 20.0) + gen.add("acc_lim_theta", double_t, 0, "The acceleration limit of the robot in the theta direction", 3.2, 0, 20.0) + gen.add("acc_lim_trans", double_t, 0, "The absolute value of the maximum translational acceleration for the robot in m/s^2", 0.1, 0) + + gen.add("prune_plan", bool_t, 0, "Start following closest point of global plan, not first point (if different).", False) + + gen.add("xy_goal_tolerance", double_t, 0, "Within what maximum distance we consider the robot to be in goal", 0.1) + gen.add("yaw_goal_tolerance", double_t, 0, "Within what maximum angle difference we consider the robot to face goal direction", 0.1) + + gen.add("trans_stopped_vel", double_t, 0, "Below what maximum velocity we consider the robot to be stopped in translation", 0.1) + gen.add("theta_stopped_vel", double_t, 0, "Below what maximum rotation velocity we consider the robot to be stopped in rotation", 0.1) diff --git a/navigations/base_local_planner/src/local_planner_util.cpp b/navigations/base_local_planner/src/local_planner_util.cpp new file mode 100755 index 0000000..fa4b1e2 --- /dev/null +++ b/navigations/base_local_planner/src/local_planner_util.cpp @@ -0,0 +1,128 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2008, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: Eitan Marder-Eppstein + *********************************************************************/ + +#include + +#include + +namespace base_local_planner { + +void LocalPlannerUtil::initialize( + tf2_ros::Buffer* tf, + costmap_2d::Costmap2D* costmap, + std::string global_frame) { + if(!initialized_) { + tf_ = tf; + costmap_ = costmap; + global_frame_ = global_frame; + initialized_ = true; + } + else{ + ROS_WARN("Planner utils have already been initialized, doing nothing."); + } +} + +void LocalPlannerUtil::reconfigureCB(LocalPlannerLimits &config, bool restore_defaults) +{ + if(setup_ && restore_defaults) { + config = default_limits_; + } + + if(!setup_) { + default_limits_ = config; + setup_ = true; + } + boost::mutex::scoped_lock l(limits_configuration_mutex_); + limits_ = LocalPlannerLimits(config); +} + +costmap_2d::Costmap2D* LocalPlannerUtil::getCostmap() { + return costmap_; +} + +LocalPlannerLimits LocalPlannerUtil::getCurrentLimits() { + boost::mutex::scoped_lock l(limits_configuration_mutex_); + return limits_; +} + + +bool LocalPlannerUtil::getGoal(geometry_msgs::PoseStamped& goal_pose) { + //we assume the global goal is the last point in the global plan + return base_local_planner::getGoalPose(*tf_, + global_plan_, + global_frame_, + goal_pose); +} + +bool LocalPlannerUtil::setPlan(const std::vector& orig_global_plan) { + if(!initialized_){ + ROS_ERROR("Planner utils have not been initialized, please call initialize() first"); + return false; + } + + //reset the global plan + global_plan_.clear(); + + global_plan_ = orig_global_plan; + + return true; +} + +bool LocalPlannerUtil::getLocalPlan(const geometry_msgs::PoseStamped& global_pose, std::vector& transformed_plan) { + //get the global plan in our frame + if(!base_local_planner::transformGlobalPlan( + *tf_, + global_plan_, + global_pose, + *costmap_, + global_frame_, + transformed_plan)) { + ROS_WARN("Could not transform the global plan to the frame of the controller"); + return false; + } + + //now we'll prune the plan based on the position of the robot + if(limits_.prune_plan) { + base_local_planner::prunePlan(global_pose, transformed_plan, global_plan_); + } + return true; +} + + + + +} // namespace diff --git a/navigations/base_local_planner/src/map_cell.cpp b/navigations/base_local_planner/src/map_cell.cpp new file mode 100755 index 0000000..13a35fc --- /dev/null +++ b/navigations/base_local_planner/src/map_cell.cpp @@ -0,0 +1,52 @@ +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2008, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the Willow Garage nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *********************************************************************/ + +#include + +namespace base_local_planner{ + + MapCell::MapCell() + : cx(0), cy(0), + target_dist(DBL_MAX), + target_mark(false), + within_robot(false) + {} + + MapCell::MapCell(const MapCell& mc) + : cx(mc.cx), cy(mc.cy), + target_dist(mc.target_dist), + target_mark(mc.target_mark), + within_robot(mc.within_robot) + {} +}; diff --git a/navigations/base_local_planner/src/map_grid.cpp b/navigations/base_local_planner/src/map_grid.cpp new file mode 100755 index 0000000..a100a8a --- /dev/null +++ b/navigations/base_local_planner/src/map_grid.cpp @@ -0,0 +1,309 @@ +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2008, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the Willow Garage nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *********************************************************************/ +#include +#include +using namespace std; + +namespace base_local_planner{ + + MapGrid::MapGrid() + : size_x_(0), size_y_(0) + { + } + + MapGrid::MapGrid(unsigned int size_x, unsigned int size_y) + : size_x_(size_x), size_y_(size_y) + { + commonInit(); + } + + MapGrid::MapGrid(const MapGrid& mg){ + size_y_ = mg.size_y_; + size_x_ = mg.size_x_; + map_ = mg.map_; + } + + void MapGrid::commonInit(){ + //don't allow construction of zero size grid + ROS_ASSERT(size_y_ != 0 && size_x_ != 0); + + map_.resize(size_y_ * size_x_); + + //make each cell aware of its location in the grid + for(unsigned int i = 0; i < size_y_; ++i){ + for(unsigned int j = 0; j < size_x_; ++j){ + unsigned int id = size_x_ * i + j; + map_[id].cx = j; + map_[id].cy = i; + } + } + } + + size_t MapGrid::getIndex(int x, int y){ + return size_x_ * y + x; + } + + MapGrid& MapGrid::operator= (const MapGrid& mg){ + size_y_ = mg.size_y_; + size_x_ = mg.size_x_; + map_ = mg.map_; + return *this; + } + + void MapGrid::sizeCheck(unsigned int size_x, unsigned int size_y){ + if(map_.size() != size_x * size_y) + map_.resize(size_x * size_y); + + if(size_x_ != size_x || size_y_ != size_y){ + size_x_ = size_x; + size_y_ = size_y; + + for(unsigned int i = 0; i < size_y_; ++i){ + for(unsigned int j = 0; j < size_x_; ++j){ + int index = size_x_ * i + j; + map_[index].cx = j; + map_[index].cy = i; + } + } + } + } + + + inline bool MapGrid::updatePathCell(MapCell* current_cell, MapCell* check_cell, + const costmap_2d::Costmap2D& costmap){ + + //if the cell is an obstacle set the max path distance + unsigned char cost = costmap.getCost(check_cell->cx, check_cell->cy); + if(! getCell(check_cell->cx, check_cell->cy).within_robot && + (cost == costmap_2d::LETHAL_OBSTACLE || + cost == costmap_2d::INSCRIBED_INFLATED_OBSTACLE || + cost == costmap_2d::NO_INFORMATION)){ + check_cell->target_dist = obstacleCosts(); + return false; + } + + double new_target_dist = current_cell->target_dist + 1; + if (new_target_dist < check_cell->target_dist) { + check_cell->target_dist = new_target_dist; + } + return true; + } + + + //reset the path_dist and goal_dist fields for all cells + void MapGrid::resetPathDist(){ + for(unsigned int i = 0; i < map_.size(); ++i) { + map_[i].target_dist = unreachableCellCosts(); + map_[i].target_mark = false; + map_[i].within_robot = false; + } + } + + void MapGrid::adjustPlanResolution(const std::vector& global_plan_in, + std::vector& global_plan_out, double resolution) { + if (global_plan_in.size() == 0) { + return; + } + double last_x = global_plan_in[0].pose.position.x; + double last_y = global_plan_in[0].pose.position.y; + global_plan_out.push_back(global_plan_in[0]); + + double min_sq_resolution = resolution * resolution; + + for (unsigned int i = 1; i < global_plan_in.size(); ++i) { + double loop_x = global_plan_in[i].pose.position.x; + double loop_y = global_plan_in[i].pose.position.y; + double sqdist = (loop_x - last_x) * (loop_x - last_x) + (loop_y - last_y) * (loop_y - last_y); + if (sqdist > min_sq_resolution) { + int steps = ceil((sqrt(sqdist)) / resolution); + // add a points in-between + double deltax = (loop_x - last_x) / steps; + double deltay = (loop_y - last_y) / steps; + // TODO: Interpolate orientation + for (int j = 1; j < steps; ++j) { + geometry_msgs::PoseStamped pose; + pose.pose.position.x = last_x + j * deltax; + pose.pose.position.y = last_y + j * deltay; + pose.pose.position.z = global_plan_in[i].pose.position.z; + pose.pose.orientation = global_plan_in[i].pose.orientation; + pose.header = global_plan_in[i].header; + global_plan_out.push_back(pose); + } + } + global_plan_out.push_back(global_plan_in[i]); + last_x = loop_x; + last_y = loop_y; + } + } + + //update what map cells are considered path based on the global_plan + void MapGrid::setTargetCells(const costmap_2d::Costmap2D& costmap, + const std::vector& global_plan) { + sizeCheck(costmap.getSizeInCellsX(), costmap.getSizeInCellsY()); + + bool started_path = false; + + queue path_dist_queue; + + std::vector adjusted_global_plan; + adjustPlanResolution(global_plan, adjusted_global_plan, costmap.getResolution()); + if (adjusted_global_plan.size() != global_plan.size()) { + ROS_DEBUG("Adjusted global plan resolution, added %zu points", adjusted_global_plan.size() - global_plan.size()); + } + unsigned int i; + // put global path points into local map until we reach the border of the local map + for (i = 0; i < adjusted_global_plan.size(); ++i) { + double g_x = adjusted_global_plan[i].pose.position.x; + double g_y = adjusted_global_plan[i].pose.position.y; + unsigned int map_x, map_y; + if (costmap.worldToMap(g_x, g_y, map_x, map_y) && costmap.getCost(map_x, map_y) != costmap_2d::NO_INFORMATION) { + MapCell& current = getCell(map_x, map_y); + current.target_dist = 0.0; + current.target_mark = true; + path_dist_queue.push(¤t); + started_path = true; + } else if (started_path) { + break; + } + } + if (!started_path) { + ROS_ERROR("None of the %d first of %zu (%zu) points of the global plan were in the local costmap and free", + i, adjusted_global_plan.size(), global_plan.size()); + return; + } + + computeTargetDistance(path_dist_queue, costmap); + } + + //mark the point of the costmap as local goal where global_plan first leaves the area (or its last point) + void MapGrid::setLocalGoal(const costmap_2d::Costmap2D& costmap, + const std::vector& global_plan) { + sizeCheck(costmap.getSizeInCellsX(), costmap.getSizeInCellsY()); + + int local_goal_x = -1; + int local_goal_y = -1; + bool started_path = false; + + std::vector adjusted_global_plan; + adjustPlanResolution(global_plan, adjusted_global_plan, costmap.getResolution()); + + // skip global path points until we reach the border of the local map + for (unsigned int i = 0; i < adjusted_global_plan.size(); ++i) { + double g_x = adjusted_global_plan[i].pose.position.x; + double g_y = adjusted_global_plan[i].pose.position.y; + unsigned int map_x, map_y; + if (costmap.worldToMap(g_x, g_y, map_x, map_y) && costmap.getCost(map_x, map_y) != costmap_2d::NO_INFORMATION) { + local_goal_x = map_x; + local_goal_y = map_y; + started_path = true; + } else { + if (started_path) { + break; + }// else we might have a non pruned path, so we just continue + } + } + if (!started_path) { + ROS_ERROR("None of the points of the global plan were in the local costmap, global plan points too far from robot"); + return; + } + + queue path_dist_queue; + if (local_goal_x >= 0 && local_goal_y >= 0) { + MapCell& current = getCell(local_goal_x, local_goal_y); + costmap.mapToWorld(local_goal_x, local_goal_y, goal_x_, goal_y_); + current.target_dist = 0.0; + current.target_mark = true; + path_dist_queue.push(¤t); + } + + computeTargetDistance(path_dist_queue, costmap); + } + + + + void MapGrid::computeTargetDistance(queue& dist_queue, const costmap_2d::Costmap2D& costmap){ + MapCell* current_cell; + MapCell* check_cell; + unsigned int last_col = size_x_ - 1; + unsigned int last_row = size_y_ - 1; + while(!dist_queue.empty()){ + current_cell = dist_queue.front(); + + + dist_queue.pop(); + + if(current_cell->cx > 0){ + check_cell = current_cell - 1; + if(!check_cell->target_mark){ + //mark the cell as visisted + check_cell->target_mark = true; + if(updatePathCell(current_cell, check_cell, costmap)) { + dist_queue.push(check_cell); + } + } + } + + if(current_cell->cx < last_col){ + check_cell = current_cell + 1; + if(!check_cell->target_mark){ + check_cell->target_mark = true; + if(updatePathCell(current_cell, check_cell, costmap)) { + dist_queue.push(check_cell); + } + } + } + + if(current_cell->cy > 0){ + check_cell = current_cell - size_x_; + if(!check_cell->target_mark){ + check_cell->target_mark = true; + if(updatePathCell(current_cell, check_cell, costmap)) { + dist_queue.push(check_cell); + } + } + } + + if(current_cell->cy < last_row){ + check_cell = current_cell + size_x_; + if(!check_cell->target_mark){ + check_cell->target_mark = true; + if(updatePathCell(current_cell, check_cell, costmap)) { + dist_queue.push(check_cell); + } + } + } + } + } + +}; diff --git a/navigations/base_local_planner/src/map_grid_cost_function.cpp b/navigations/base_local_planner/src/map_grid_cost_function.cpp new file mode 100755 index 0000000..bb35116 --- /dev/null +++ b/navigations/base_local_planner/src/map_grid_cost_function.cpp @@ -0,0 +1,131 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2008, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: TKruse + *********************************************************************/ + +#include + +namespace base_local_planner { + +MapGridCostFunction::MapGridCostFunction(costmap_2d::Costmap2D* costmap, + double xshift, + double yshift, + bool is_local_goal_function, + CostAggregationType aggregationType) : + costmap_(costmap), + map_(costmap->getSizeInCellsX(), costmap->getSizeInCellsY()), + aggregationType_(aggregationType), + xshift_(xshift), + yshift_(yshift), + is_local_goal_function_(is_local_goal_function), + stop_on_failure_(true) {} + +void MapGridCostFunction::setTargetPoses(std::vector target_poses) { + target_poses_ = target_poses; +} + +bool MapGridCostFunction::prepare() { + map_.resetPathDist(); + + if (is_local_goal_function_) { + map_.setLocalGoal(*costmap_, target_poses_); + } else { + map_.setTargetCells(*costmap_, target_poses_); + } + return true; +} + +double MapGridCostFunction::getCellCosts(unsigned int px, unsigned int py) { + double grid_dist = map_(px, py).target_dist; + return grid_dist; +} + +double MapGridCostFunction::scoreTrajectory(Trajectory &traj) { + double cost = 0.0; + if (aggregationType_ == Product) { + cost = 1.0; + } + double px, py, pth; + unsigned int cell_x, cell_y; + double grid_dist; + + for (unsigned int i = 0; i < traj.getPointsSize(); ++i) { + traj.getPoint(i, px, py, pth); + + // translate point forward if specified + if (xshift_ != 0.0) { + px = px + xshift_ * cos(pth); + py = py + xshift_ * sin(pth); + } + // translate point sideways if specified + if (yshift_ != 0.0) { + px = px + yshift_ * cos(pth + M_PI_2); + py = py + yshift_ * sin(pth + M_PI_2); + } + + //we won't allow trajectories that go off the map... shouldn't happen that often anyways + if ( ! costmap_->worldToMap(px, py, cell_x, cell_y)) { + //we're off the map + ROS_WARN("Off Map %f, %f", px, py); + return -4.0; + } + grid_dist = getCellCosts(cell_x, cell_y); + //if a point on this trajectory has no clear path to the goal... it may be invalid + if (stop_on_failure_) { + if (grid_dist == map_.obstacleCosts()) { + return -3.0; + } else if (grid_dist == map_.unreachableCellCosts()) { + return -2.0; + } + } + + switch( aggregationType_ ) { + case Last: + cost = grid_dist; + break; + case Sum: + cost += grid_dist; + break; + case Product: + if (cost > 0) { + cost *= grid_dist; + } + break; + } + } + return cost; +} + +} /* namespace base_local_planner */ diff --git a/navigations/base_local_planner/src/map_grid_visualizer.cpp b/navigations/base_local_planner/src/map_grid_visualizer.cpp new file mode 100755 index 0000000..5f865ec --- /dev/null +++ b/navigations/base_local_planner/src/map_grid_visualizer.cpp @@ -0,0 +1,95 @@ +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2010, Eric Perko + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Eric Perko nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *********************************************************************/ +#include +#include +#include + +#include +#include + +namespace base_local_planner { + MapGridVisualizer::MapGridVisualizer() {} + + + void MapGridVisualizer::initialize(const std::string& name, std::string frame_id, boost::function cost_function) { + name_ = name; + frame_id_ = frame_id; + cost_function_ = cost_function; + + ns_nh_ = ros::NodeHandle("~/" + name_); + pub_ = ns_nh_.advertise("cost_cloud", 1); + } + + void MapGridVisualizer::publishCostCloud(const costmap_2d::Costmap2D* costmap_p_) { + sensor_msgs::PointCloud2 cost_cloud; + cost_cloud.header.frame_id = frame_id_; + cost_cloud.header.stamp = ros::Time::now(); + + sensor_msgs::PointCloud2Modifier cloud_mod(cost_cloud); + cloud_mod.setPointCloud2Fields(7, "x", 1, sensor_msgs::PointField::FLOAT32, + "y", 1, sensor_msgs::PointField::FLOAT32, + "z", 1, sensor_msgs::PointField::FLOAT32, + "path_cost", 1, sensor_msgs::PointField::FLOAT32, + "goal_cost", 1, sensor_msgs::PointField::FLOAT32, + "occ_cost", 1, sensor_msgs::PointField::FLOAT32, + "total_cost", 1, sensor_msgs::PointField::FLOAT32); + + unsigned int x_size = costmap_p_->getSizeInCellsX(); + unsigned int y_size = costmap_p_->getSizeInCellsY(); + double z_coord = 0.0; + double x_coord, y_coord; + + cloud_mod.resize(x_size * y_size); + sensor_msgs::PointCloud2Iterator iter_x(cost_cloud, "x"); + + float path_cost, goal_cost, occ_cost, total_cost; + for (unsigned int cx = 0; cx < x_size; cx++) { + for (unsigned int cy = 0; cy < y_size; cy++) { + costmap_p_->mapToWorld(cx, cy, x_coord, y_coord); + if (cost_function_(cx, cy, path_cost, goal_cost, occ_cost, total_cost)) { + iter_x[0] = x_coord; + iter_x[1] = y_coord; + iter_x[2] = z_coord; + iter_x[3] = path_cost; + iter_x[4] = goal_cost; + iter_x[5] = occ_cost; + iter_x[6] = total_cost; + ++iter_x; + } + } + } + pub_.publish(cost_cloud); + ROS_DEBUG("Cost PointCloud published"); + } +}; diff --git a/navigations/base_local_planner/src/obstacle_cost_function.cpp b/navigations/base_local_planner/src/obstacle_cost_function.cpp new file mode 100755 index 0000000..c71716d --- /dev/null +++ b/navigations/base_local_planner/src/obstacle_cost_function.cpp @@ -0,0 +1,152 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2008, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: TKruse + *********************************************************************/ + +#include +#include +#include +#include + +namespace base_local_planner { + +ObstacleCostFunction::ObstacleCostFunction(costmap_2d::Costmap2D* costmap) + : costmap_(costmap), sum_scores_(false) { + if (costmap != NULL) { + world_model_ = new base_local_planner::CostmapModel(*costmap_); + } +} + +ObstacleCostFunction::~ObstacleCostFunction() { + if (world_model_ != NULL) { + delete world_model_; + } +} + + +void ObstacleCostFunction::setParams(double max_trans_vel, double max_scaling_factor, double scaling_speed) { + // TODO: move this to prepare if possible + max_trans_vel_ = max_trans_vel; + max_scaling_factor_ = max_scaling_factor; + scaling_speed_ = scaling_speed; +} + +void ObstacleCostFunction::setFootprint(std::vector footprint_spec) { + footprint_spec_ = footprint_spec; +} + +bool ObstacleCostFunction::prepare() { + return true; +} + +double ObstacleCostFunction::scoreTrajectory(Trajectory &traj) { + double cost = 0; + double scale = getScalingFactor(traj, scaling_speed_, max_trans_vel_, max_scaling_factor_); + double px, py, pth; + if (footprint_spec_.size() == 0) { + // Bug, should never happen + ROS_ERROR("Footprint spec is empty, maybe missing call to setFootprint?"); + return -9; + } + + for (unsigned int i = 0; i < traj.getPointsSize(); ++i) { + traj.getPoint(i, px, py, pth); + double f_cost = footprintCost(px, py, pth, + scale, footprint_spec_, + costmap_, world_model_); + + if(f_cost < 0){ + return f_cost; + } + + if(sum_scores_) + cost += f_cost; + else + cost = std::max(cost, f_cost); + } + return cost; +} + +double ObstacleCostFunction::getScalingFactor(Trajectory &traj, double scaling_speed, double max_trans_vel, double max_scaling_factor) { + double vmag = hypot(traj.xv_, traj.yv_); + + //if we're over a certain speed threshold, we'll scale the robot's + //footprint to make it either slow down or stay further from walls + double scale = 1.0; + if (vmag > scaling_speed) { + //scale up to the max scaling factor linearly... this could be changed later + double ratio = (vmag - scaling_speed) / (max_trans_vel - scaling_speed); + scale = max_scaling_factor * ratio + 1.0; + } + return scale; +} + +double ObstacleCostFunction::footprintCost ( + const double& x, + const double& y, + const double& th, + double scale, + std::vector footprint_spec, + costmap_2d::Costmap2D* costmap, + base_local_planner::WorldModel* world_model) { + + std::vector scaled_footprint; + for(unsigned int i = 0; i < footprint_spec.size(); ++i) { + geometry_msgs::Point new_pt; + new_pt.x = scale * footprint_spec[i].x; + new_pt.y = scale * footprint_spec[i].y; + scaled_footprint.push_back(new_pt); + } + + //check if the footprint is legal + // TODO: Cache inscribed radius + double footprint_cost = world_model->footprintCost(x, y, th, scaled_footprint); + + if (footprint_cost < 0) { + return -6.0; + } + unsigned int cell_x, cell_y; + + //we won't allow trajectories that go off the map... shouldn't happen that often anyways + if ( ! costmap->worldToMap(x, y, cell_x, cell_y)) { + return -7.0; + } + + double occ_cost = std::max(std::max(0.0, footprint_cost), double(costmap->getCost(cell_x, cell_y))); + + return occ_cost; +} + +} /* namespace base_local_planner */ diff --git a/navigations/base_local_planner/src/odometry_helper_ros.cpp b/navigations/base_local_planner/src/odometry_helper_ros.cpp new file mode 100755 index 0000000..cc497c4 --- /dev/null +++ b/navigations/base_local_planner/src/odometry_helper_ros.cpp @@ -0,0 +1,106 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2008, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: TKruse + *********************************************************************/ +#include +#include +#include +#include + +namespace base_local_planner { + +OdometryHelperRos::OdometryHelperRos(std::string odom_topic) { + setOdomTopic( odom_topic ); +} + +void OdometryHelperRos::odomCallback(const nav_msgs::Odometry::ConstPtr& msg) { + ROS_INFO_ONCE("odom received!"); + + //we assume that the odometry is published in the frame of the base + boost::mutex::scoped_lock lock(odom_mutex_); + base_odom_.twist.twist.linear.x = msg->twist.twist.linear.x; + base_odom_.twist.twist.linear.y = msg->twist.twist.linear.y; + base_odom_.twist.twist.angular.z = msg->twist.twist.angular.z; + base_odom_.child_frame_id = msg->child_frame_id; +// ROS_DEBUG_NAMED("dwa_local_planner", "In the odometry callback with velocity values: (%.2f, %.2f, %.2f)", +// base_odom_.twist.twist.linear.x, base_odom_.twist.twist.linear.y, base_odom_.twist.twist.angular.z); +} + +//copy over the odometry information +void OdometryHelperRos::getOdom(nav_msgs::Odometry& base_odom) { + boost::mutex::scoped_lock lock(odom_mutex_); + base_odom = base_odom_; +} + + +void OdometryHelperRos::getRobotVel(geometry_msgs::PoseStamped& robot_vel) { + // Set current velocities from odometry + geometry_msgs::Twist global_vel; + { + boost::mutex::scoped_lock lock(odom_mutex_); + global_vel.linear.x = base_odom_.twist.twist.linear.x; + global_vel.linear.y = base_odom_.twist.twist.linear.y; + global_vel.angular.z = base_odom_.twist.twist.angular.z; + + robot_vel.header.frame_id = base_odom_.child_frame_id; + } + robot_vel.pose.position.x = global_vel.linear.x; + robot_vel.pose.position.y = global_vel.linear.y; + robot_vel.pose.position.z = 0; + tf2::Quaternion q; + q.setRPY(0, 0, global_vel.angular.z); + tf2::convert(q, robot_vel.pose.orientation); + robot_vel.header.stamp = ros::Time(); +} + +void OdometryHelperRos::setOdomTopic(std::string odom_topic) +{ + if( odom_topic != odom_topic_ ) + { + odom_topic_ = odom_topic; + + if( odom_topic_ != "" ) + { + ros::NodeHandle gn; + odom_sub_ = gn.subscribe( odom_topic_, 1, [this](auto& msg){ odomCallback(msg); }); + } + else + { + odom_sub_.shutdown(); + } + } +} + +} /* namespace base_local_planner */ diff --git a/navigations/base_local_planner/src/oscillation_cost_function.cpp b/navigations/base_local_planner/src/oscillation_cost_function.cpp new file mode 100755 index 0000000..d24531d --- /dev/null +++ b/navigations/base_local_planner/src/oscillation_cost_function.cpp @@ -0,0 +1,178 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2008, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: TKruse + *********************************************************************/ + +#include + +#include + +namespace base_local_planner { + +OscillationCostFunction::OscillationCostFunction() { +} + +OscillationCostFunction::~OscillationCostFunction() { + prev_stationary_pos_ = Eigen::Vector3f::Zero(); +} + +void OscillationCostFunction::setOscillationResetDist(double dist, double angle) { + oscillation_reset_dist_ = dist; + oscillation_reset_angle_ = angle; +} + +void OscillationCostFunction::updateOscillationFlags(Eigen::Vector3f pos, base_local_planner::Trajectory* traj, double min_vel_trans) { + if (traj->cost_ >= 0) { + if (setOscillationFlags(traj, min_vel_trans)) { + prev_stationary_pos_ = pos; + } + //if we've got restrictions... check if we can reset any oscillation flags + if(forward_pos_only_ || forward_neg_only_ + || strafe_pos_only_ || strafe_neg_only_ + || rot_pos_only_ || rot_neg_only_){ + resetOscillationFlagsIfPossible(pos, prev_stationary_pos_); + } + } +} + +void OscillationCostFunction::resetOscillationFlagsIfPossible(const Eigen::Vector3f& pos, const Eigen::Vector3f& prev) { + double x_diff = pos[0] - prev[0]; + double y_diff = pos[1] - prev[1]; + double sq_dist = x_diff * x_diff + y_diff * y_diff; + + double th_diff = pos[2] - prev[2]; + + //if we've moved far enough... we can reset our flags + if (sq_dist > oscillation_reset_dist_ * oscillation_reset_dist_ || + fabs(th_diff) > oscillation_reset_angle_) { + resetOscillationFlags(); + } +} + +void OscillationCostFunction::resetOscillationFlags() { + strafe_pos_only_ = false; + strafe_neg_only_ = false; + strafing_pos_ = false; + strafing_neg_ = false; + + rot_pos_only_ = false; + rot_neg_only_ = false; + rotating_pos_ = false; + rotating_neg_ = false; + + forward_pos_only_ = false; + forward_neg_only_ = false; + forward_pos_ = false; + forward_neg_ = false; +} + +bool OscillationCostFunction::setOscillationFlags(base_local_planner::Trajectory* t, double min_vel_trans) { + bool flag_set = false; + //set oscillation flags for moving forward and backward + if (t->xv_ < 0.0) { + if (forward_pos_) { + forward_neg_only_ = true; + flag_set = true; + } + forward_pos_ = false; + forward_neg_ = true; + } + if (t->xv_ > 0.0) { + if (forward_neg_) { + forward_pos_only_ = true; + flag_set = true; + } + forward_neg_ = false; + forward_pos_ = true; + } + + //we'll only set flags for strafing and rotating when we're not moving forward at all + if (fabs(t->xv_) <= min_vel_trans) { + //check negative strafe + if (t->yv_ < 0) { + if (strafing_pos_) { + strafe_neg_only_ = true; + flag_set = true; + } + strafing_pos_ = false; + strafing_neg_ = true; + } + + //check positive strafe + if (t->yv_ > 0) { + if (strafing_neg_) { + strafe_pos_only_ = true; + flag_set = true; + } + strafing_neg_ = false; + strafing_pos_ = true; + } + + //check negative rotation + if (t->thetav_ < 0) { + if (rotating_pos_) { + rot_neg_only_ = true; + flag_set = true; + } + rotating_pos_ = false; + rotating_neg_ = true; + } + + //check positive rotation + if (t->thetav_ > 0) { + if (rotating_neg_) { + rot_pos_only_ = true; + flag_set = true; + } + rotating_neg_ = false; + rotating_pos_ = true; + } + } + return flag_set; +} + +double OscillationCostFunction::scoreTrajectory(Trajectory &traj) { + if ((forward_pos_only_ && traj.xv_ < 0.0) || + (forward_neg_only_ && traj.xv_ > 0.0) || + (strafe_pos_only_ && traj.yv_ < 0.0) || + (strafe_neg_only_ && traj.yv_ > 0.0) || + (rot_pos_only_ && traj.thetav_ < 0.0) || + (rot_neg_only_ && traj.thetav_ > 0.0)) { + return -5.0; + } + return 0.0; +} + +} /* namespace base_local_planner */ diff --git a/navigations/base_local_planner/src/point_grid.cpp b/navigations/base_local_planner/src/point_grid.cpp new file mode 100755 index 0000000..8fef01a --- /dev/null +++ b/navigations/base_local_planner/src/point_grid.cpp @@ -0,0 +1,556 @@ +/********************************************************************* +* +* Software License Agreement (BSD License) +* +* Copyright (c) 2008, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of the Willow Garage nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* +* Author: Eitan Marder-Eppstein +*********************************************************************/ + +#include +#include +#ifdef HAVE_SYS_TIME_H +#include +#endif + +#include +#include +#include + +using namespace std; +using namespace costmap_2d; + +namespace base_local_planner { + +PointGrid::PointGrid(double size_x, double size_y, double resolution, geometry_msgs::Point origin, double max_z, double obstacle_range, double min_seperation) : + resolution_(resolution), origin_(origin), max_z_(max_z), sq_obstacle_range_(obstacle_range * obstacle_range), sq_min_separation_(min_seperation * min_seperation) + { + width_ = (int) (size_x / resolution_); + height_ = (int) (size_y / resolution_); + cells_.resize(width_ * height_); + } + + double PointGrid::footprintCost(const geometry_msgs::Point& position, const std::vector& footprint, + double inscribed_radius, double circumscribed_radius){ + //the half-width of the circumscribed sqaure of the robot is equal to the circumscribed radius + double outer_square_radius = circumscribed_radius; + + //get all the points inside the circumscribed square of the robot footprint + geometry_msgs::Point c_lower_left, c_upper_right; + c_lower_left.x = position.x - outer_square_radius; + c_lower_left.y = position.y - outer_square_radius; + + c_upper_right.x = position.x + outer_square_radius; + c_upper_right.y = position.y + outer_square_radius; + + //This may return points that are still outside of the cirumscribed square because it returns the cells + //contained by the range + getPointsInRange(c_lower_left, c_upper_right, points_); + + //if there are no points in the circumscribed square... we don't have to check against the footprint + if(points_.empty()) + return 1.0; + + //compute the half-width of the inner square from the inscribed radius of the robot + double inner_square_radius = sqrt((inscribed_radius * inscribed_radius) / 2.0); + + //we'll also check against the inscribed square + geometry_msgs::Point i_lower_left, i_upper_right; + i_lower_left.x = position.x - inner_square_radius; + i_lower_left.y = position.y - inner_square_radius; + + i_upper_right.x = position.x + inner_square_radius; + i_upper_right.y = position.y + inner_square_radius; + + //if there are points, we have to do a more expensive check + for(unsigned int i = 0; i < points_.size(); ++i){ + list* cell_points = points_[i]; + if(cell_points != NULL){ + for(list::iterator it = cell_points->begin(); it != cell_points->end(); ++it){ + const geometry_msgs::Point32& pt = *it; + //first, we'll check to make sure we're in the outer square + //printf("(%.2f, %.2f) ... l(%.2f, %.2f) ... u(%.2f, %.2f)\n", pt.x, pt.y, c_lower_left.x, c_lower_left.y, c_upper_right.x, c_upper_right.y); + if(pt.x > c_lower_left.x && pt.x < c_upper_right.x && pt.y > c_lower_left.y && pt.y < c_upper_right.y){ + //do a quick check to see if the point lies in the inner square of the robot + if(pt.x > i_lower_left.x && pt.x < i_upper_right.x && pt.y > i_lower_left.y && pt.y < i_upper_right.y) + return -1.0; + + //now we really have to do a full footprint check on the point + if(ptInPolygon(pt, footprint)) + return -1.0; + } + } + } + } + + //if we get through all the points and none of them are in the footprint it's legal + return 1.0; + } + + bool PointGrid::ptInPolygon(const geometry_msgs::Point32& pt, const std::vector& poly){ + if(poly.size() < 3) + return false; + + //a point is in a polygon iff the orientation of the point + //with respect to sides of the polygon is the same for every + //side of the polygon + bool all_left = false; + bool all_right = false; + for(unsigned int i = 0; i < poly.size() - 1; ++i){ + //if pt left of a->b + if(orient(poly[i], poly[i + 1], pt) > 0){ + if(all_right) + return false; + all_left = true; + } + //if pt right of a->b + else{ + if(all_left) + return false; + all_right = true; + } + } + //also need to check the last point with the first point + if(orient(poly[poly.size() - 1], poly[0], pt) > 0){ + if(all_right) + return false; + } + else{ + if(all_left) + return false; + } + + return true; + } + + void PointGrid::getPointsInRange(const geometry_msgs::Point& lower_left, const geometry_msgs::Point& upper_right, + vector< list* >& points){ + points.clear(); + + //compute the other corners of the box so we can get cells indicies for them + geometry_msgs::Point upper_left, lower_right; + upper_left.x = lower_left.x; + upper_left.y = upper_right.y; + lower_right.x = upper_right.x; + lower_right.y = lower_left.y; + + //get the grid coordinates of the cells matching the corners of the range + unsigned int gx, gy; + + //if the grid coordinates are outside the bounds of the grid... return + if(!gridCoords(lower_left, gx, gy)) + return; + //get the associated index + unsigned int lower_left_index = gridIndex(gx, gy); + + if(!gridCoords(lower_right, gx, gy)) + return; + unsigned int lower_right_index = gridIndex(gx, gy); + + if(!gridCoords(upper_left, gx, gy)) + return; + unsigned int upper_left_index = gridIndex(gx, gy); + + //compute x_steps and y_steps + unsigned int x_steps = lower_right_index - lower_left_index + 1; + unsigned int y_steps = (upper_left_index - lower_left_index) / width_ + 1; + /* + * (0, 0) ---------------------- (width, 0) + * | | + * | | + * | | + * | | + * | | + * (0, height) ----------------- (width, height) + */ + //get an iterator + vector< list >::iterator cell_iterator = cells_.begin() + lower_left_index; + //printf("Index: %d, Width: %d, x_steps: %d, y_steps: %d\n", lower_left_index, width_, x_steps, y_steps); + for(unsigned int i = 0; i < y_steps; ++i){ + for(unsigned int j = 0; j < x_steps; ++j){ + list& cell = *cell_iterator; + //if the cell contains any points... we need to push them back to our list + if(!cell.empty()){ + points.push_back(&cell); + } + if(j < x_steps - 1) + cell_iterator++; //move a cell in the x direction + } + cell_iterator += width_ - (x_steps - 1); //move down a row + } + } + + void PointGrid::insert(const geometry_msgs::Point32& pt){ + //get the grid coordinates of the point + unsigned int gx, gy; + + //if the grid coordinates are outside the bounds of the grid... return + if(!gridCoords(pt, gx, gy)) + return; + + //if the point is too close to its nearest neighbor... return + if(nearestNeighborDistance(pt) < sq_min_separation_) + return; + + //get the associated index + unsigned int pt_index = gridIndex(gx, gy); + + //insert the point into the grid at the correct location + cells_[pt_index].push_back(pt); + //printf("Index: %d, size: %d\n", pt_index, cells_[pt_index].size()); + } + + double PointGrid::getNearestInCell(const geometry_msgs::Point32& pt, unsigned int gx, unsigned int gy){ + unsigned int index = gridIndex(gx, gy); + double min_sq_dist = DBL_MAX; + //loop through the points in the cell and find the minimum distance to the passed point + for(list::const_iterator it = cells_[index].begin(); it != cells_[index].end(); ++it){ + min_sq_dist = min(min_sq_dist, sq_distance(pt, *it)); + } + return min_sq_dist; + } + + + double PointGrid::nearestNeighborDistance(const geometry_msgs::Point32& pt){ + //get the grid coordinates of the point + unsigned int gx, gy; + + gridCoords(pt, gx, gy); + + //get the bounds of the grid cell in world coords + geometry_msgs::Point lower_left, upper_right; + getCellBounds(gx, gy, lower_left, upper_right); + + //now we need to check what cells could contain the nearest neighbor + geometry_msgs::Point32 check_point; + double sq_dist = DBL_MAX; + double neighbor_sq_dist = DBL_MAX; + + //left + if(gx > 0){ + check_point.x = lower_left.x; + check_point.y = pt.y; + sq_dist = sq_distance(pt, check_point); + if(sq_dist < sq_min_separation_) + neighbor_sq_dist = min(neighbor_sq_dist, getNearestInCell(pt, gx - 1, gy)); + } + + //upper left + if(gx > 0 && gy < height_ - 1){ + check_point.x = lower_left.x; + check_point.y = upper_right.y; + sq_dist = sq_distance(pt, check_point); + if(sq_dist < sq_min_separation_) + neighbor_sq_dist = min(neighbor_sq_dist, getNearestInCell(pt, gx - 1, gy + 1)); + } + + //top + if(gy < height_ - 1){ + check_point.x = pt.x; + check_point.y = upper_right.y; + sq_dist = sq_distance(pt, check_point); + if(sq_dist < sq_min_separation_) + neighbor_sq_dist = min(neighbor_sq_dist, getNearestInCell(pt, gx, gy + 1)); + } + + //upper right + if(gx < width_ - 1 && gy < height_ - 1){ + check_point.x = upper_right.x; + check_point.y = upper_right.y; + sq_dist = sq_distance(pt, check_point); + if(sq_dist < sq_min_separation_) + neighbor_sq_dist = min(neighbor_sq_dist, getNearestInCell(pt, gx + 1, gy + 1)); + } + + //right + if(gx < width_ - 1){ + check_point.x = upper_right.x; + check_point.y = pt.y; + sq_dist = sq_distance(pt, check_point); + if(sq_dist < sq_min_separation_) + neighbor_sq_dist = min(neighbor_sq_dist, getNearestInCell(pt, gx + 1, gy)); + } + + //lower right + if(gx < width_ - 1 && gy > 0){ + check_point.x = upper_right.x; + check_point.y = lower_left.y; + sq_dist = sq_distance(pt, check_point); + if(sq_dist < sq_min_separation_) + neighbor_sq_dist = min(neighbor_sq_dist, getNearestInCell(pt, gx + 1, gy - 1)); + } + + //bottom + if(gy > 0){ + check_point.x = pt.x; + check_point.y = lower_left.y; + sq_dist = sq_distance(pt, check_point); + if(sq_dist < sq_min_separation_) + neighbor_sq_dist = min(neighbor_sq_dist, getNearestInCell(pt, gx, gy - 1)); + } + + //lower left + if(gx > 0 && gy > 0){ + check_point.x = lower_left.x; + check_point.y = lower_left.y; + sq_dist = sq_distance(pt, check_point); + if(sq_dist < sq_min_separation_) + neighbor_sq_dist = min(neighbor_sq_dist, getNearestInCell(pt, gx - 1, gy - 1)); + } + + //we must also check within the cell we're in for a nearest neighbor + neighbor_sq_dist = min(neighbor_sq_dist, getNearestInCell(pt, gx, gy)); + + return neighbor_sq_dist; + } + + void PointGrid::updateWorld(const std::vector& footprint, + const vector& observations, const vector& laser_scans){ + //for our 2D point grid we only remove freespace based on the first laser scan + if(laser_scans.empty()) + return; + + removePointsInScanBoundry(laser_scans[0]); + + //iterate through all observations and update the grid + for(vector::const_iterator it = observations.begin(); it != observations.end(); ++it){ + const Observation& obs = *it; + const sensor_msgs::PointCloud2& cloud = *(obs.cloud_); + + sensor_msgs::PointCloud2ConstIterator iter_x(cloud, "x"); + sensor_msgs::PointCloud2ConstIterator iter_y(cloud, "y"); + sensor_msgs::PointCloud2ConstIterator iter_z(cloud, "z"); + + geometry_msgs::Point32 pt; + for(; iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z){ + //filter out points that are too high + if(*iter_z > max_z_) + continue; + + //compute the squared distance from the hitpoint to the pointcloud's origin + double sq_dist = (*iter_x - obs.origin_.x) * (*iter_x - obs.origin_.x) + + (*iter_y - obs.origin_.y) * (*iter_y - obs.origin_.y) + + (*iter_z - obs.origin_.z) * (*iter_z - obs.origin_.z); + + if(sq_dist >= sq_obstacle_range_) + continue; + + //insert the point + pt.x = *iter_x; + pt.y = *iter_y; + pt.z = *iter_z; + insert(pt); + } + } + + //remove the points that are in the footprint of the robot + removePointsInPolygon(footprint); + } + + void PointGrid::removePointsInScanBoundry(const PlanarLaserScan& laser_scan){ + if(laser_scan.cloud.points.size() == 0) + return; + + //compute the containing square of the scan + geometry_msgs::Point lower_left, upper_right; + lower_left.x = laser_scan.origin.x; + lower_left.y = laser_scan.origin.y; + upper_right.x = laser_scan.origin.x; + upper_right.y = laser_scan.origin.y; + + for(unsigned int i = 0; i < laser_scan.cloud.points.size(); ++i){ + lower_left.x = min((double)lower_left.x, (double)laser_scan.cloud.points[i].x); + lower_left.y = min((double)lower_left.y, (double)laser_scan.cloud.points[i].y); + upper_right.x = max((double)upper_right.x, (double)laser_scan.cloud.points[i].x); + upper_right.y = max((double)upper_right.y, (double)laser_scan.cloud.points[i].y); + } + + getPointsInRange(lower_left, upper_right, points_); + + //if there are no points in the containing square... we don't have to do anything + if(points_.empty()) + return; + + //if there are points, we have to check them against the scan explicitly to remove them + for(unsigned int i = 0; i < points_.size(); ++i){ + list* cell_points = points_[i]; + if(cell_points != NULL){ + list::iterator it = cell_points->begin(); + while(it != cell_points->end()){ + const geometry_msgs::Point32& pt = *it; + + //check if the point is in the polygon and if it is, erase it from the grid + if(ptInScan(pt, laser_scan)){ + it = cell_points->erase(it); + } + else + it++; + } + } + } + } + + bool PointGrid::ptInScan(const geometry_msgs::Point32& pt, const PlanarLaserScan& laser_scan){ + if(!laser_scan.cloud.points.empty()){ + //compute the angle of the point relative to that of the scan + double v1_x = laser_scan.cloud.points[0].x - laser_scan.origin.x; + double v1_y = laser_scan.cloud.points[0].y - laser_scan.origin.y; + double v2_x = pt.x - laser_scan.origin.x; + double v2_y = pt.y - laser_scan.origin.y; + + double perp_dot = v1_x * v2_y - v1_y * v2_x; + double dot = v1_x * v2_x + v1_y * v2_y; + + //get the signed angle + double vector_angle = atan2(perp_dot, dot); + + //we want all angles to be between 0 and 2PI + if(vector_angle < 0) + vector_angle = 2 * M_PI + vector_angle; + + double total_rads = laser_scan.angle_max - laser_scan.angle_min; + + //if this point lies outside of the scan field of view... it is not in the scan + if(vector_angle < 0 || vector_angle >= total_rads) + return false; + + //compute the index of the point in the scan + unsigned int index = (unsigned int) (vector_angle / laser_scan.angle_increment); + + //make sure we have a legal index... we always should at this point, but just in case + if(index >= laser_scan.cloud.points.size() - 1){ + return false; + } + + //if the point lies to the left of the line between the two scan points bounding it, it is within the scan + if(orient(laser_scan.cloud.points[index], laser_scan.cloud.points[index + 1], pt) > 0){ + return true; + } + + //otherwise it is not + return false; + } + else + return false; + } + + void PointGrid::getPoints(sensor_msgs::PointCloud2& cloud){ + sensor_msgs::PointCloud2Modifier modifier(cloud); + modifier.setPointCloud2FieldsByString(1, "xyz"); + + size_t n = 0; + for(unsigned int i = 0; i < cells_.size(); ++i){ + for(list::iterator it = cells_[i].begin(); it != cells_[i].end(); ++it){ + ++n; + } + } + modifier.resize(n); + + sensor_msgs::PointCloud2Iterator iter_x(cloud, "x"); + sensor_msgs::PointCloud2Iterator iter_y(cloud, "y"); + sensor_msgs::PointCloud2Iterator iter_z(cloud, "z"); + + for(unsigned int i = 0; i < cells_.size(); ++i){ + for(list::iterator it = cells_[i].begin(); it != cells_[i].end(); ++it, ++iter_x, ++iter_y, ++iter_z){ + *iter_x = it->x; + *iter_y = it->y; + *iter_z = it->z; + } + } + } + + void PointGrid::removePointsInPolygon(const std::vector poly){ + if(poly.size() == 0) + return; + + geometry_msgs::Point lower_left, upper_right; + lower_left.x = poly[0].x; + lower_left.y = poly[0].y; + upper_right.x = poly[0].x; + upper_right.y = poly[0].y; + + //compute the containing square of the polygon + for(unsigned int i = 1; i < poly.size(); ++i){ + lower_left.x = min(lower_left.x, poly[i].x); + lower_left.y = min(lower_left.y, poly[i].y); + upper_right.x = max(upper_right.x, poly[i].x); + upper_right.y = max(upper_right.y, poly[i].y); + } + + ROS_DEBUG("Lower: (%.2f, %.2f), Upper: (%.2f, %.2f)\n", lower_left.x, lower_left.y, upper_right.x, upper_right.y); + getPointsInRange(lower_left, upper_right, points_); + + //if there are no points in the containing square... we don't have to do anything + if(points_.empty()) + return; + + //if there are points, we have to check them against the polygon explicitly to remove them + for(unsigned int i = 0; i < points_.size(); ++i){ + list* cell_points = points_[i]; + if(cell_points != NULL){ + list::iterator it = cell_points->begin(); + while(it != cell_points->end()){ + const geometry_msgs::Point32& pt = *it; + + //check if the point is in the polygon and if it is, erase it from the grid + if(ptInPolygon(pt, poly)){ + it = cell_points->erase(it); + } + else + it++; + } + } + } + } + + void PointGrid::intersectionPoint(const geometry_msgs::Point& v1, const geometry_msgs::Point& v2, + const geometry_msgs::Point& u1, const geometry_msgs::Point& u2, geometry_msgs::Point& result){ + //generate the equation for line 1 + double a1 = v2.y - v1.y; + double b1 = v1.x - v2.x; + double c1 = a1 * v1.x + b1 * v1.y; + + //generate the equation for line 2 + double a2 = u2.y - u1.y; + double b2 = u1.x - u2.x; + double c2 = a2 * u1.x + b2 * u1.y; + + double det = a1 * b2 - a2 * b1; + + //the lines are parallel + if(det == 0) + return; + + result.x = (b2 * c1 - b1 * c2) / det; + result.y = (a1 * c2 - a2 * c1) / det; + } + +}; diff --git a/navigations/base_local_planner/src/point_grid_node.cpp b/navigations/base_local_planner/src/point_grid_node.cpp new file mode 100755 index 0000000..6534a35 --- /dev/null +++ b/navigations/base_local_planner/src/point_grid_node.cpp @@ -0,0 +1,221 @@ +/********************************************************************* +* +* Software License Agreement (BSD License) +* +* Copyright (c) 2008, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of the Willow Garage nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* +* Author: Eitan Marder-Eppstein +*********************************************************************/ + +#include +#include +#ifdef HAVE_SYS_TIME_H +#include +#endif + +#include +#include +#include + +using namespace std; +using namespace costmap_2d; + +void printPoint(const geometry_msgs::Point& pt){ + printf("(%.2f, %.2f, %.2f)", pt.x, pt.y, pt.z); +} + +void printPSHeader(){ + printf("%%!PS\n"); + printf("%%%%Creator: Eitan Marder-Eppstein (Willow Garage)\n"); + printf("%%%%EndComments\n"); +} + +void printPSFooter(){ + printf("showpage\n%%%%EOF\n"); +} + +void printPolygonPS(const std::vector& poly, double line_width){ + if(poly.size() < 2) + return; + + printf("%.2f setlinewidth\n", line_width); + printf("newpath\n"); + printf("%.4f\t%.4f\tmoveto\n", poly[0].x * 10, poly[0].y * 10); + for(unsigned int i = 1; i < poly.size(); ++i) + printf("%.4f\t%.4f\tlineto\n", poly[i].x * 10, poly[i].y * 10); + printf("%.4f\t%.4f\tlineto\n", poly[0].x * 10, poly[0].y * 10); + printf("closepath stroke\n"); + +} + +using namespace base_local_planner; + +int main(int argc, char** argv){ + geometry_msgs::Point origin; + origin.x = 0.0; + origin.y = 0.0; + PointGrid pg(50.0, 50.0, 0.2, origin, 2.0, 3.0, 0.0); + /* + double x = 10.0; + double y = 10.0; + for(int i = 0; i < 100; ++i){ + for(int j = 0; j < 100; ++j){ + pcl::PointXYZ pt; + pt.x = x; + pt.y = y; + pt.z = 1.0; + pg.insert(pt); + x += .03; + } + y += .03; + x = 10.0; + } + */ + std::vector footprint, footprint2, footprint3; + geometry_msgs::Point pt; + + pt.x = 1.0; + pt.y = 1.0; + footprint.push_back(pt); + + pt.x = 1.0; + pt.y = 1.65; + footprint.push_back(pt); + + pt.x = 1.325; + pt.y = 1.75; + footprint.push_back(pt); + + pt.x = 1.65; + pt.y = 1.65; + footprint.push_back(pt); + + pt.x = 1.65; + pt.y = 1.0; + footprint.push_back(pt); + + pt.x = 1.325; + pt.y = 1.00; + footprint2.push_back(pt); + + pt.x = 1.325; + pt.y = 1.75; + footprint2.push_back(pt); + + pt.x = 1.65; + pt.y = 1.75; + footprint2.push_back(pt); + + pt.x = 1.65; + pt.y = 1.00; + footprint2.push_back(pt); + + pt.x = 0.99; + pt.y = 0.99; + footprint3.push_back(pt); + + pt.x = 0.99; + pt.y = 1.66; + footprint3.push_back(pt); + + pt.x = 1.3255; + pt.y = 1.85; + footprint3.push_back(pt); + + pt.x = 1.66; + pt.y = 1.66; + footprint3.push_back(pt); + + pt.x = 1.66; + pt.y = 0.99; + footprint3.push_back(pt); + + pt.x = 1.325; + pt.y = 1.325; + + geometry_msgs::Point32 point; + point.x = 1.2; + point.y = 1.2; + point.z = 1.0; + +#ifdef HAVE_SYS_TIME_H + struct timeval start, end; + double start_t, end_t, t_diff; +#endif + + printPSHeader(); + +#ifdef HAVE_SYS_TIME_H + gettimeofday(&start, NULL); +#endif + + for(unsigned int i = 0; i < 2000; ++i){ + pg.insert(point); + } + +#ifdef HAVE_SYS_TIME_H + gettimeofday(&end, NULL); + start_t = start.tv_sec + double(start.tv_usec) / 1e6; + end_t = end.tv_sec + double(end.tv_usec) / 1e6; + t_diff = end_t - start_t; + printf("%%Insertion Time: %.9f \n", t_diff); +#endif + + vector obs; + vector scan; + +#ifdef HAVE_SYS_TIME_H + gettimeofday(&start, NULL); +#endif + pg.updateWorld(footprint, obs, scan); + + double legal = pg.footprintCost(pt, footprint, 0.0, .95); + pg.updateWorld(footprint, obs, scan); + double legal2 = pg.footprintCost(pt, footprint, 0.0, .95); + +#ifdef HAVE_SYS_TIME_H + gettimeofday(&end, NULL); + start_t = start.tv_sec + double(start.tv_usec) / 1e6; + end_t = end.tv_sec + double(end.tv_usec) / 1e6; + t_diff = end_t - start_t; + + printf("%%Footprint calc: %.9f \n", t_diff); +#endif + + if(legal >= 0.0) + printf("%%Legal footprint %.4f, %.4f\n", legal, legal2); + else + printf("%%Illegal footprint\n"); + + printPSFooter(); + + return 0; +} diff --git a/navigations/base_local_planner/src/prefer_forward_cost_function.cpp b/navigations/base_local_planner/src/prefer_forward_cost_function.cpp new file mode 100755 index 0000000..9329578 --- /dev/null +++ b/navigations/base_local_planner/src/prefer_forward_cost_function.cpp @@ -0,0 +1,28 @@ +/* + * prefer_forward_cost_function.cpp + * + * Created on: Apr 4, 2012 + * Author: tkruse + */ + +#include + +#include + +namespace base_local_planner { + + +double PreferForwardCostFunction::scoreTrajectory(Trajectory &traj) { + // backward motions bad on a robot without backward sensors + if (traj.xv_ < 0.0) { + return penalty_; + } + // strafing motions also bad on such a robot + if (traj.xv_ < 0.1 && fabs(traj.thetav_) < 0.2) { + return penalty_; + } + // the more we rotate, the less we progress forward + return fabs(traj.thetav_) * 10; +} + +} /* namespace base_local_planner */ diff --git a/navigations/base_local_planner/src/simple_scored_sampling_planner.cpp b/navigations/base_local_planner/src/simple_scored_sampling_planner.cpp new file mode 100755 index 0000000..61e191c --- /dev/null +++ b/navigations/base_local_planner/src/simple_scored_sampling_planner.cpp @@ -0,0 +1,145 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2008, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: TKruse + *********************************************************************/ + +#include + +#include + +namespace base_local_planner { + + SimpleScoredSamplingPlanner::SimpleScoredSamplingPlanner(std::vector gen_list, std::vector& critics, int max_samples) { + max_samples_ = max_samples; + gen_list_ = gen_list; + critics_ = critics; + } + + double SimpleScoredSamplingPlanner::scoreTrajectory(Trajectory& traj, double best_traj_cost) { + double traj_cost = 0; + int gen_id = 0; + for(std::vector::iterator score_function = critics_.begin(); score_function != critics_.end(); ++score_function) { + TrajectoryCostFunction* score_function_p = *score_function; + if (score_function_p->getScale() == 0) { + continue; + } + double cost = score_function_p->scoreTrajectory(traj); + if (cost < 0) { + ROS_DEBUG("Velocity %.3lf, %.3lf, %.3lf discarded by cost function %d with cost: %f", traj.xv_, traj.yv_, traj.thetav_, gen_id, cost); + traj_cost = cost; + break; + } + if (cost != 0) { + cost *= score_function_p->getScale(); + } + traj_cost += cost; + if (best_traj_cost > 0) { + // since we keep adding positives, once we are worse than the best, we will stay worse + if (traj_cost > best_traj_cost) { + break; + } + } + gen_id ++; + } + + + return traj_cost; + } + + bool SimpleScoredSamplingPlanner::findBestTrajectory(Trajectory& traj, std::vector* all_explored) { + Trajectory loop_traj; + Trajectory best_traj; + double loop_traj_cost, best_traj_cost = -1; + bool gen_success; + int count, count_valid; + for (std::vector::iterator loop_critic = critics_.begin(); loop_critic != critics_.end(); ++loop_critic) { + TrajectoryCostFunction* loop_critic_p = *loop_critic; + if (loop_critic_p->prepare() == false) { + ROS_WARN("A scoring function failed to prepare"); + return false; + } + } + + for (std::vector::iterator loop_gen = gen_list_.begin(); loop_gen != gen_list_.end(); ++loop_gen) { + count = 0; + count_valid = 0; + TrajectorySampleGenerator* gen_ = *loop_gen; + while (gen_->hasMoreTrajectories()) { + gen_success = gen_->nextTrajectory(loop_traj); + if (gen_success == false) { + // TODO use this for debugging + continue; + } + loop_traj_cost = scoreTrajectory(loop_traj, best_traj_cost); + if (all_explored != NULL) { + loop_traj.cost_ = loop_traj_cost; + all_explored->push_back(loop_traj); + } + + if (loop_traj_cost >= 0) { + count_valid++; + if (best_traj_cost < 0 || loop_traj_cost < best_traj_cost) { + best_traj_cost = loop_traj_cost; + best_traj = loop_traj; + } + } + count++; + if (max_samples_ > 0 && count >= max_samples_) { + break; + } + } + if (best_traj_cost >= 0) { + traj.xv_ = best_traj.xv_; + traj.yv_ = best_traj.yv_; + traj.thetav_ = best_traj.thetav_; + traj.cost_ = best_traj_cost; + traj.resetPoints(); + double px, py, pth; + for (unsigned int i = 0; i < best_traj.getPointsSize(); i++) { + best_traj.getPoint(i, px, py, pth); + traj.addPoint(px, py, pth); + } + } + ROS_DEBUG("Evaluated %d trajectories, found %d valid", count, count_valid); + if (best_traj_cost >= 0) { + // do not try fallback generators + break; + } + } + return best_traj_cost >= 0; + } + + +}// namespace diff --git a/navigations/base_local_planner/src/simple_trajectory_generator.cpp b/navigations/base_local_planner/src/simple_trajectory_generator.cpp new file mode 100755 index 0000000..2af290a --- /dev/null +++ b/navigations/base_local_planner/src/simple_trajectory_generator.cpp @@ -0,0 +1,282 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2008, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: TKruse + *********************************************************************/ + +#include + +#include + +#include + +namespace base_local_planner { + +void SimpleTrajectoryGenerator::initialise( + const Eigen::Vector3f& pos, + const Eigen::Vector3f& vel, + const Eigen::Vector3f& goal, + base_local_planner::LocalPlannerLimits* limits, + const Eigen::Vector3f& vsamples, + std::vector additional_samples, + bool discretize_by_time) { + initialise(pos, vel, goal, limits, vsamples, discretize_by_time); + // add static samples if any + sample_params_.insert(sample_params_.end(), additional_samples.begin(), additional_samples.end()); +} + + +void SimpleTrajectoryGenerator::initialise( + const Eigen::Vector3f& pos, + const Eigen::Vector3f& vel, + const Eigen::Vector3f& goal, + base_local_planner::LocalPlannerLimits* limits, + const Eigen::Vector3f& vsamples, + bool discretize_by_time) { + /* + * We actually generate all velocity sample vectors here, from which to generate trajectories later on + */ + double max_vel_th = limits->max_vel_theta; + double min_vel_th = -1.0 * max_vel_th; + discretize_by_time_ = discretize_by_time; + Eigen::Vector3f acc_lim = limits->getAccLimits(); + pos_ = pos; + vel_ = vel; + limits_ = limits; + next_sample_index_ = 0; + sample_params_.clear(); + + double min_vel_x = limits->min_vel_x; + double max_vel_x = limits->max_vel_x; + double min_vel_y = limits->min_vel_y; + double max_vel_y = limits->max_vel_y; + + // if sampling number is zero in any dimension, we don't generate samples generically + if (vsamples[0] * vsamples[1] * vsamples[2] > 0) { + //compute the feasible velocity space based on the rate at which we run + Eigen::Vector3f max_vel = Eigen::Vector3f::Zero(); + Eigen::Vector3f min_vel = Eigen::Vector3f::Zero(); + + if ( ! use_dwa_) { + // there is no point in overshooting the goal, and it also may break the + // robot behavior, so we limit the velocities to those that do not overshoot in sim_time + double dist = hypot(goal[0] - pos[0], goal[1] - pos[1]); + max_vel_x = std::max(std::min(max_vel_x, dist / sim_time_), min_vel_x); + max_vel_y = std::max(std::min(max_vel_y, dist / sim_time_), min_vel_y); + + // if we use continous acceleration, we can sample the max velocity we can reach in sim_time_ + max_vel[0] = std::min(max_vel_x, vel[0] + acc_lim[0] * sim_time_); + max_vel[1] = std::min(max_vel_y, vel[1] + acc_lim[1] * sim_time_); + max_vel[2] = std::min(max_vel_th, vel[2] + acc_lim[2] * sim_time_); + + min_vel[0] = std::max(min_vel_x, vel[0] - acc_lim[0] * sim_time_); + min_vel[1] = std::max(min_vel_y, vel[1] - acc_lim[1] * sim_time_); + min_vel[2] = std::max(min_vel_th, vel[2] - acc_lim[2] * sim_time_); + } else { + // with dwa do not accelerate beyond the first step, we only sample within velocities we reach in sim_period + max_vel[0] = std::min(max_vel_x, vel[0] + acc_lim[0] * sim_period_); + max_vel[1] = std::min(max_vel_y, vel[1] + acc_lim[1] * sim_period_); + max_vel[2] = std::min(max_vel_th, vel[2] + acc_lim[2] * sim_period_); + + min_vel[0] = std::max(min_vel_x, vel[0] - acc_lim[0] * sim_period_); + min_vel[1] = std::max(min_vel_y, vel[1] - acc_lim[1] * sim_period_); + min_vel[2] = std::max(min_vel_th, vel[2] - acc_lim[2] * sim_period_); + } + + Eigen::Vector3f vel_samp = Eigen::Vector3f::Zero(); + VelocityIterator x_it(min_vel[0], max_vel[0], vsamples[0]); + VelocityIterator y_it(min_vel[1], max_vel[1], vsamples[1]); + VelocityIterator th_it(min_vel[2], max_vel[2], vsamples[2]); + for(; !x_it.isFinished(); x_it++) { + vel_samp[0] = x_it.getVelocity(); + for(; !y_it.isFinished(); y_it++) { + vel_samp[1] = y_it.getVelocity(); + for(; !th_it.isFinished(); th_it++) { + vel_samp[2] = th_it.getVelocity(); + //ROS_DEBUG("Sample %f, %f, %f", vel_samp[0], vel_samp[1], vel_samp[2]); + sample_params_.push_back(vel_samp); + } + th_it.reset(); + } + y_it.reset(); + } + } +} + +void SimpleTrajectoryGenerator::setParameters( + double sim_time, + double sim_granularity, + double angular_sim_granularity, + bool use_dwa, + double sim_period) { + sim_time_ = sim_time; + sim_granularity_ = sim_granularity; + angular_sim_granularity_ = angular_sim_granularity; + use_dwa_ = use_dwa; + continued_acceleration_ = ! use_dwa_; + sim_period_ = sim_period; +} + +/** + * Whether this generator can create more trajectories + */ +bool SimpleTrajectoryGenerator::hasMoreTrajectories() { + return next_sample_index_ < sample_params_.size(); +} + +/** + * Create and return the next sample trajectory + */ +bool SimpleTrajectoryGenerator::nextTrajectory(Trajectory &comp_traj) { + bool result = false; + if (hasMoreTrajectories()) { + if (generateTrajectory( + pos_, + vel_, + sample_params_[next_sample_index_], + comp_traj)) { + result = true; + } + } + next_sample_index_++; + return result; +} + +/** + * @param pos current position of robot + * @param vel desired velocity for sampling + */ +bool SimpleTrajectoryGenerator::generateTrajectory( + Eigen::Vector3f pos, + Eigen::Vector3f vel, + Eigen::Vector3f sample_target_vel, + base_local_planner::Trajectory& traj) { + double vmag = hypot(sample_target_vel[0], sample_target_vel[1]); + double eps = 1e-4; + traj.cost_ = -1.0; // placed here in case we return early + //trajectory might be reused so we'll make sure to reset it + traj.resetPoints(); + + // make sure that the robot would at least be moving with one of + // the required minimum velocities for translation and rotation (if set) + if ((limits_->min_vel_trans >= 0 && vmag + eps < limits_->min_vel_trans) && + (limits_->min_vel_theta >= 0 && fabs(sample_target_vel[2]) + eps < limits_->min_vel_theta)) { + return false; + } + // make sure we do not exceed max diagonal (x+y) translational velocity (if set) + if (limits_->max_vel_trans >=0 && vmag - eps > limits_->max_vel_trans) { + return false; + } + + int num_steps; + if (discretize_by_time_) { + num_steps = ceil(sim_time_ / sim_granularity_); + } else { + //compute the number of steps we must take along this trajectory to be "safe" + double sim_time_distance = vmag * sim_time_; // the distance the robot would travel in sim_time if it did not change velocity + double sim_time_angle = fabs(sample_target_vel[2]) * sim_time_; // the angle the robot would rotate in sim_time + num_steps = + ceil(std::max(sim_time_distance / sim_granularity_, + sim_time_angle / angular_sim_granularity_)); + } + + if (num_steps == 0) { + return false; + } + + //compute a timestep + double dt = sim_time_ / num_steps; + traj.time_delta_ = dt; + + Eigen::Vector3f loop_vel; + if (continued_acceleration_) { + // assuming the velocity of the first cycle is the one we want to store in the trajectory object + loop_vel = computeNewVelocities(sample_target_vel, vel, limits_->getAccLimits(), dt); + traj.xv_ = loop_vel[0]; + traj.yv_ = loop_vel[1]; + traj.thetav_ = loop_vel[2]; + } else { + // assuming sample_vel is our target velocity within acc limits for one timestep + loop_vel = sample_target_vel; + traj.xv_ = sample_target_vel[0]; + traj.yv_ = sample_target_vel[1]; + traj.thetav_ = sample_target_vel[2]; + } + + //simulate the trajectory and check for collisions, updating costs along the way + for (int i = 0; i < num_steps; ++i) { + + //add the point to the trajectory so we can draw it later if we want + traj.addPoint(pos[0], pos[1], pos[2]); + + if (continued_acceleration_) { + //calculate velocities + loop_vel = computeNewVelocities(sample_target_vel, loop_vel, limits_->getAccLimits(), dt); + //ROS_WARN_NAMED("Generator", "Flag: %d, Loop_Vel %f, %f, %f", continued_acceleration_, loop_vel[0], loop_vel[1], loop_vel[2]); + } + + //update the position of the robot using the velocities passed in + pos = computeNewPositions(pos, loop_vel, dt); + + } // end for simulation steps + + return true; // trajectory has at least one point +} + +Eigen::Vector3f SimpleTrajectoryGenerator::computeNewPositions(const Eigen::Vector3f& pos, + const Eigen::Vector3f& vel, double dt) { + Eigen::Vector3f new_pos = Eigen::Vector3f::Zero(); + new_pos[0] = pos[0] + (vel[0] * cos(pos[2]) + vel[1] * cos(M_PI_2 + pos[2])) * dt; + new_pos[1] = pos[1] + (vel[0] * sin(pos[2]) + vel[1] * sin(M_PI_2 + pos[2])) * dt; + new_pos[2] = pos[2] + vel[2] * dt; + return new_pos; +} + +/** + * change vel using acceleration limits to converge towards sample_target-vel + */ +Eigen::Vector3f SimpleTrajectoryGenerator::computeNewVelocities(const Eigen::Vector3f& sample_target_vel, + const Eigen::Vector3f& vel, Eigen::Vector3f acclimits, double dt) { + Eigen::Vector3f new_vel = Eigen::Vector3f::Zero(); + for (int i = 0; i < 3; ++i) { + if (vel[i] < sample_target_vel[i]) { + new_vel[i] = std::min(double(sample_target_vel[i]), vel[i] + acclimits[i] * dt); + } else { + new_vel[i] = std::max(double(sample_target_vel[i]), vel[i] - acclimits[i] * dt); + } + } + return new_vel; +} + +} /* namespace base_local_planner */ diff --git a/navigations/base_local_planner/src/trajectory.cpp b/navigations/base_local_planner/src/trajectory.cpp new file mode 100755 index 0000000..4d395fb --- /dev/null +++ b/navigations/base_local_planner/src/trajectory.cpp @@ -0,0 +1,80 @@ +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2008, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the Willow Garage nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *********************************************************************/ +#include + +namespace base_local_planner { + Trajectory::Trajectory() + : xv_(0.0), yv_(0.0), thetav_(0.0), cost_(-1.0) + { + } + + Trajectory::Trajectory(double xv, double yv, double thetav, double time_delta, unsigned int num_pts) + : xv_(xv), yv_(yv), thetav_(thetav), cost_(-1.0), time_delta_(time_delta), x_pts_(num_pts), y_pts_(num_pts), th_pts_(num_pts) + { + } + + void Trajectory::getPoint(unsigned int index, double& x, double& y, double& th) const { + x = x_pts_[index]; + y = y_pts_[index]; + th = th_pts_[index]; + } + + void Trajectory::setPoint(unsigned int index, double x, double y, double th){ + x_pts_[index] = x; + y_pts_[index] = y; + th_pts_[index] = th; + } + + void Trajectory::addPoint(double x, double y, double th){ + x_pts_.push_back(x); + y_pts_.push_back(y); + th_pts_.push_back(th); + } + + void Trajectory::resetPoints(){ + x_pts_.clear(); + y_pts_.clear(); + th_pts_.clear(); + } + + void Trajectory::getEndpoint(double& x, double& y, double& th) const { + x = x_pts_.back(); + y = y_pts_.back(); + th = th_pts_.back(); + } + + unsigned int Trajectory::getPointsSize() const { + return x_pts_.size(); + } +}; diff --git a/navigations/base_local_planner/src/trajectory_planner.cpp b/navigations/base_local_planner/src/trajectory_planner.cpp new file mode 100755 index 0000000..69bad75 --- /dev/null +++ b/navigations/base_local_planner/src/trajectory_planner.cpp @@ -0,0 +1,1001 @@ +/********************************************************************* +* +* Software License Agreement (BSD License) +* +* Copyright (c) 2008, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of the Willow Garage nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* +* Author: Eitan Marder-Eppstein +*********************************************************************/ + +#include +#include +#include +#include +#include +#include + + + +#include + +#include + +//for computing path distance +#include +#include +#include + +using namespace std; +using namespace costmap_2d; + +namespace base_local_planner{ + + void TrajectoryPlanner::reconfigure(BaseLocalPlannerConfig &cfg) + { + BaseLocalPlannerConfig config(cfg); + + boost::mutex::scoped_lock l(configuration_mutex_); + + acc_lim_x_ = config.acc_lim_x; + acc_lim_y_ = config.acc_lim_y; + acc_lim_theta_ = config.acc_lim_theta; + + max_vel_x_ = config.max_vel_x; + min_vel_x_ = config.min_vel_x; + + max_vel_th_ = config.max_vel_theta; + min_vel_th_ = config.min_vel_theta; + min_in_place_vel_th_ = config.min_in_place_vel_theta; + + sim_time_ = config.sim_time; + sim_granularity_ = config.sim_granularity; + angular_sim_granularity_ = config.angular_sim_granularity; + + path_distance_bias_ = config.path_distance_bias; + goal_distance_bias_ = config.goal_distance_bias; + occdist_scale_ = config.occdist_scale; + + if (meter_scoring_) { + //if we use meter scoring, then we want to multiply the biases by the resolution of the costmap + double resolution = costmap_.getResolution(); + goal_distance_bias_ *= resolution; + path_distance_bias_ *= resolution; + } + + oscillation_reset_dist_ = config.oscillation_reset_dist; + escape_reset_dist_ = config.escape_reset_dist; + escape_reset_theta_ = config.escape_reset_theta; + + vx_samples_ = config.vx_samples; + vtheta_samples_ = config.vtheta_samples; + + if (vx_samples_ <= 0) { + config.vx_samples = 1; + vx_samples_ = config.vx_samples; + ROS_WARN("You've specified that you don't want any samples in the x dimension. We'll at least assume that you want to sample one value... so we're going to set vx_samples to 1 instead"); + } + if(vtheta_samples_ <= 0) { + config.vtheta_samples = 1; + vtheta_samples_ = config.vtheta_samples; + ROS_WARN("You've specified that you don't want any samples in the theta dimension. We'll at least assume that you want to sample one value... so we're going to set vtheta_samples to 1 instead"); + } + + heading_lookahead_ = config.heading_lookahead; + + holonomic_robot_ = config.holonomic_robot; + + backup_vel_ = config.escape_vel; + + dwa_ = config.dwa; + + heading_scoring_ = config.heading_scoring; + heading_scoring_timestep_ = config.heading_scoring_timestep; + + simple_attractor_ = config.simple_attractor; + + //y-vels + string y_string = config.y_vels; + vector y_strs; + boost::split(y_strs, y_string, boost::is_any_of(", "), boost::token_compress_on); + + vectory_vels; + for(vector::iterator it=y_strs.begin(); it != y_strs.end(); ++it) { + istringstream iss(*it); + double temp; + iss >> temp; + y_vels.push_back(temp); + //ROS_INFO("Adding y_vel: %e", temp); + } + + y_vels_ = y_vels; + + } + + TrajectoryPlanner::TrajectoryPlanner(WorldModel& world_model, + const Costmap2D& costmap, + std::vector footprint_spec, + double acc_lim_x, double acc_lim_y, double acc_lim_theta, + double sim_time, double sim_granularity, + int vx_samples, int vtheta_samples, + double path_distance_bias, double goal_distance_bias, double occdist_scale, + double heading_lookahead, double oscillation_reset_dist, + double escape_reset_dist, double escape_reset_theta, + bool holonomic_robot, + double max_vel_x, double min_vel_x, + double max_vel_th, double min_vel_th, double min_in_place_vel_th, + double backup_vel, + bool dwa, bool heading_scoring, double heading_scoring_timestep, bool meter_scoring, bool simple_attractor, + vector y_vels, double stop_time_buffer, double sim_period, double angular_sim_granularity) + : path_map_(costmap.getSizeInCellsX(), costmap.getSizeInCellsY()), + goal_map_(costmap.getSizeInCellsX(), costmap.getSizeInCellsY()), + costmap_(costmap), + world_model_(world_model), footprint_spec_(footprint_spec), + sim_time_(sim_time), sim_granularity_(sim_granularity), angular_sim_granularity_(angular_sim_granularity), + vx_samples_(vx_samples), vtheta_samples_(vtheta_samples), + path_distance_bias_(path_distance_bias), goal_distance_bias_(goal_distance_bias), occdist_scale_(occdist_scale), + acc_lim_x_(acc_lim_x), acc_lim_y_(acc_lim_y), acc_lim_theta_(acc_lim_theta), + prev_x_(0), prev_y_(0), escape_x_(0), escape_y_(0), escape_theta_(0), heading_lookahead_(heading_lookahead), + oscillation_reset_dist_(oscillation_reset_dist), escape_reset_dist_(escape_reset_dist), + escape_reset_theta_(escape_reset_theta), holonomic_robot_(holonomic_robot), + max_vel_x_(max_vel_x), min_vel_x_(min_vel_x), + max_vel_th_(max_vel_th), min_vel_th_(min_vel_th), min_in_place_vel_th_(min_in_place_vel_th), + backup_vel_(backup_vel), + dwa_(dwa), heading_scoring_(heading_scoring), heading_scoring_timestep_(heading_scoring_timestep), + simple_attractor_(simple_attractor), y_vels_(y_vels), stop_time_buffer_(stop_time_buffer), sim_period_(sim_period) + { + //the robot is not stuck to begin with + stuck_left = false; + stuck_right = false; + stuck_left_strafe = false; + stuck_right_strafe = false; + rotating_left = false; + rotating_right = false; + strafe_left = false; + strafe_right = false; + + escaping_ = false; + final_goal_position_valid_ = false; + + + costmap_2d::calculateMinAndMaxDistances(footprint_spec_, inscribed_radius_, circumscribed_radius_); + } + + TrajectoryPlanner::~TrajectoryPlanner(){} + + bool TrajectoryPlanner::getCellCosts(int cx, int cy, float &path_cost, float &goal_cost, float &occ_cost, float &total_cost) { + MapCell cell = path_map_(cx, cy); + MapCell goal_cell = goal_map_(cx, cy); + if (cell.within_robot) { + return false; + } + occ_cost = costmap_.getCost(cx, cy); + if (cell.target_dist == path_map_.obstacleCosts() || + cell.target_dist == path_map_.unreachableCellCosts() || + occ_cost >= costmap_2d::INSCRIBED_INFLATED_OBSTACLE) { + return false; + } + path_cost = cell.target_dist; + goal_cost = goal_cell.target_dist; + total_cost = path_distance_bias_ * path_cost + goal_distance_bias_ * goal_cost + occdist_scale_ * occ_cost; + return true; + } + + /** + * create and score a trajectory given the current pose of the robot and selected velocities + */ + void TrajectoryPlanner::generateTrajectory( + double x, double y, double theta, + double vx, double vy, double vtheta, + double vx_samp, double vy_samp, double vtheta_samp, + double acc_x, double acc_y, double acc_theta, + double impossible_cost, + Trajectory& traj) { + + // make sure the configuration doesn't change mid run + boost::mutex::scoped_lock l(configuration_mutex_); + + double x_i = x; + double y_i = y; + double theta_i = theta; + + double vx_i, vy_i, vtheta_i; + + vx_i = vx; + vy_i = vy; + vtheta_i = vtheta; + + //compute the magnitude of the velocities + double vmag = hypot(vx_samp, vy_samp); + + //compute the number of steps we must take along this trajectory to be "safe" + int num_steps; + if(!heading_scoring_) { + num_steps = int(max((vmag * sim_time_) / sim_granularity_, fabs(vtheta_samp) / angular_sim_granularity_) + 0.5); + } else { + num_steps = int(sim_time_ / sim_granularity_ + 0.5); + } + + //we at least want to take one step... even if we won't move, we want to score our current position + if(num_steps == 0) { + num_steps = 1; + } + + double dt = sim_time_ / num_steps; + double time = 0.0; + + //create a potential trajectory + traj.resetPoints(); + traj.xv_ = vx_samp; + traj.yv_ = vy_samp; + traj.thetav_ = vtheta_samp; + traj.cost_ = -1.0; + + //initialize the costs for the trajectory + double path_dist = 0.0; + double goal_dist = 0.0; + double occ_cost = 0.0; + double heading_diff = 0.0; + + for(int i = 0; i < num_steps; ++i){ + //get map coordinates of a point + unsigned int cell_x, cell_y; + + //we don't want a path that goes off the know map + if(!costmap_.worldToMap(x_i, y_i, cell_x, cell_y)){ + traj.cost_ = -1.0; + return; + } + + //check the point on the trajectory for legality + double footprint_cost = footprintCost(x_i, y_i, theta_i); + + //if the footprint hits an obstacle this trajectory is invalid + if(footprint_cost < 0){ + traj.cost_ = -1.0; + return; + //TODO: Really look at getMaxSpeedToStopInTime... dues to discretization errors and high acceleration limits, + //it can actually cause the robot to hit obstacles. There may be something to be done to fix, but I'll have to + //come back to it when I have time. Right now, pulling it out as it'll just make the robot a bit more conservative, + //but safe. + /* + double max_vel_x, max_vel_y, max_vel_th; + //we want to compute the max allowable speeds to be able to stop + //to be safe... we'll make sure we can stop some time before we actually hit + getMaxSpeedToStopInTime(time - stop_time_buffer_ - dt, max_vel_x, max_vel_y, max_vel_th); + + //check if we can stop in time + if(fabs(vx_samp) < max_vel_x && fabs(vy_samp) < max_vel_y && fabs(vtheta_samp) < max_vel_th){ + ROS_ERROR("v: (%.2f, %.2f, %.2f), m: (%.2f, %.2f, %.2f) t:%.2f, st: %.2f, dt: %.2f", vx_samp, vy_samp, vtheta_samp, max_vel_x, max_vel_y, max_vel_th, time, stop_time_buffer_, dt); + //if we can stop... we'll just break out of the loop here.. no point in checking future points + break; + } + else{ + traj.cost_ = -1.0; + return; + } + */ + } + + occ_cost = std::max(std::max(occ_cost, footprint_cost), double(costmap_.getCost(cell_x, cell_y))); + + //do we want to follow blindly + if (simple_attractor_) { + goal_dist = (x_i - global_plan_[global_plan_.size() -1].pose.position.x) * + (x_i - global_plan_[global_plan_.size() -1].pose.position.x) + + (y_i - global_plan_[global_plan_.size() -1].pose.position.y) * + (y_i - global_plan_[global_plan_.size() -1].pose.position.y); + } else { + + bool update_path_and_goal_distances = true; + + // with heading scoring, we take into account heading diff, and also only score + // path and goal distance for one point of the trajectory + if (heading_scoring_) { + if (time >= heading_scoring_timestep_ && time < heading_scoring_timestep_ + dt) { + heading_diff = headingDiff(cell_x, cell_y, x_i, y_i, theta_i); + } else { + update_path_and_goal_distances = false; + } + } + + if (update_path_and_goal_distances) { + //update path and goal distances + path_dist = path_map_(cell_x, cell_y).target_dist; + goal_dist = goal_map_(cell_x, cell_y).target_dist; + + //if a point on this trajectory has no clear path to goal it is invalid + if(impossible_cost <= goal_dist || impossible_cost <= path_dist){ +// ROS_DEBUG("No path to goal with goal distance = %f, path_distance = %f and max cost = %f", +// goal_dist, path_dist, impossible_cost); + traj.cost_ = -2.0; + return; + } + } + } + + + //the point is legal... add it to the trajectory + traj.addPoint(x_i, y_i, theta_i); + + //calculate velocities + vx_i = computeNewVelocity(vx_samp, vx_i, acc_x, dt); + vy_i = computeNewVelocity(vy_samp, vy_i, acc_y, dt); + vtheta_i = computeNewVelocity(vtheta_samp, vtheta_i, acc_theta, dt); + + //calculate positions + x_i = computeNewXPosition(x_i, vx_i, vy_i, theta_i, dt); + y_i = computeNewYPosition(y_i, vx_i, vy_i, theta_i, dt); + theta_i = computeNewThetaPosition(theta_i, vtheta_i, dt); + + //increment time + time += dt; + } // end for i < numsteps + + //ROS_INFO("OccCost: %f, vx: %.2f, vy: %.2f, vtheta: %.2f", occ_cost, vx_samp, vy_samp, vtheta_samp); + double cost = -1.0; + if (!heading_scoring_) { + cost = path_distance_bias_ * path_dist + goal_dist * goal_distance_bias_ + occdist_scale_ * occ_cost; + } else { + cost = occdist_scale_ * occ_cost + path_distance_bias_ * path_dist + 0.3 * heading_diff + goal_dist * goal_distance_bias_; + } + traj.cost_ = cost; + } + + double TrajectoryPlanner::headingDiff(int cell_x, int cell_y, double x, double y, double heading){ + unsigned int goal_cell_x, goal_cell_y; + + // find a clear line of sight from the robot's cell to a farthest point on the path + for (int i = global_plan_.size() - 1; i >=0; --i) { + if (costmap_.worldToMap(global_plan_[i].pose.position.x, global_plan_[i].pose.position.y, goal_cell_x, goal_cell_y)) { + if (lineCost(cell_x, goal_cell_x, cell_y, goal_cell_y) >= 0) { + double gx, gy; + costmap_.mapToWorld(goal_cell_x, goal_cell_y, gx, gy); + return fabs(angles::shortest_angular_distance(heading, atan2(gy - y, gx - x))); + } + } + } + return DBL_MAX; + } + + //calculate the cost of a ray-traced line + double TrajectoryPlanner::lineCost(int x0, int x1, + int y0, int y1){ + //Bresenham Ray-Tracing + int deltax = abs(x1 - x0); // The difference between the x's + int deltay = abs(y1 - y0); // The difference between the y's + int x = x0; // Start x off at the first pixel + int y = y0; // Start y off at the first pixel + + int xinc1, xinc2, yinc1, yinc2; + int den, num, numadd, numpixels; + + double line_cost = 0.0; + double point_cost = -1.0; + + if (x1 >= x0) // The x-values are increasing + { + xinc1 = 1; + xinc2 = 1; + } + else // The x-values are decreasing + { + xinc1 = -1; + xinc2 = -1; + } + + if (y1 >= y0) // The y-values are increasing + { + yinc1 = 1; + yinc2 = 1; + } + else // The y-values are decreasing + { + yinc1 = -1; + yinc2 = -1; + } + + if (deltax >= deltay) // There is at least one x-value for every y-value + { + xinc1 = 0; // Don't change the x when numerator >= denominator + yinc2 = 0; // Don't change the y for every iteration + den = deltax; + num = deltax / 2; + numadd = deltay; + numpixels = deltax; // There are more x-values than y-values + } else { // There is at least one y-value for every x-value + xinc2 = 0; // Don't change the x for every iteration + yinc1 = 0; // Don't change the y when numerator >= denominator + den = deltay; + num = deltay / 2; + numadd = deltax; + numpixels = deltay; // There are more y-values than x-values + } + + for (int curpixel = 0; curpixel <= numpixels; curpixel++) { + point_cost = pointCost(x, y); //Score the current point + + if (point_cost < 0) { + return -1; + } + + if (line_cost < point_cost) { + line_cost = point_cost; + } + + num += numadd; // Increase the numerator by the top of the fraction + if (num >= den) { // Check if numerator >= denominator + num -= den; // Calculate the new numerator value + x += xinc1; // Change the x as appropriate + y += yinc1; // Change the y as appropriate + } + x += xinc2; // Change the x as appropriate + y += yinc2; // Change the y as appropriate + } + + return line_cost; + } + + double TrajectoryPlanner::pointCost(int x, int y){ + unsigned char cost = costmap_.getCost(x, y); + //if the cell is in an obstacle the path is invalid + if(cost == LETHAL_OBSTACLE || cost == INSCRIBED_INFLATED_OBSTACLE || cost == NO_INFORMATION){ + return -1; + } + + return cost; + } + + void TrajectoryPlanner::updatePlan(const vector& new_plan, bool compute_dists){ + global_plan_.resize(new_plan.size()); + for(unsigned int i = 0; i < new_plan.size(); ++i){ + global_plan_[i] = new_plan[i]; + } + + if( global_plan_.size() > 0 ){ + geometry_msgs::PoseStamped& final_goal_pose = global_plan_[ global_plan_.size() - 1 ]; + final_goal_x_ = final_goal_pose.pose.position.x; + final_goal_y_ = final_goal_pose.pose.position.y; + final_goal_position_valid_ = true; + } else { + final_goal_position_valid_ = false; + } + + if (compute_dists) { + //reset the map for new operations + path_map_.resetPathDist(); + goal_map_.resetPathDist(); + + //make sure that we update our path based on the global plan and compute costs + path_map_.setTargetCells(costmap_, global_plan_); + goal_map_.setLocalGoal(costmap_, global_plan_); + ROS_DEBUG("Path/Goal distance computed"); + } + } + + bool TrajectoryPlanner::checkTrajectory(double x, double y, double theta, double vx, double vy, + double vtheta, double vx_samp, double vy_samp, double vtheta_samp){ + Trajectory t; + + double cost = scoreTrajectory(x, y, theta, vx, vy, vtheta, vx_samp, vy_samp, vtheta_samp); + + //if the trajectory is a legal one... the check passes + if(cost >= 0) { + return true; + } + ROS_WARN("Invalid Trajectory %f, %f, %f, cost: %f", vx_samp, vy_samp, vtheta_samp, cost); + + //otherwise the check fails + return false; + } + + double TrajectoryPlanner::scoreTrajectory(double x, double y, double theta, double vx, double vy, + double vtheta, double vx_samp, double vy_samp, double vtheta_samp) { + Trajectory t; + double impossible_cost = path_map_.obstacleCosts(); + generateTrajectory(x, y, theta, + vx, vy, vtheta, + vx_samp, vy_samp, vtheta_samp, + acc_lim_x_, acc_lim_y_, acc_lim_theta_, + impossible_cost, t); + + // return the cost. + return double( t.cost_ ); + } + + /* + * create the trajectories we wish to score + */ + Trajectory TrajectoryPlanner::createTrajectories(double x, double y, double theta, + double vx, double vy, double vtheta, + double acc_x, double acc_y, double acc_theta) { + //compute feasible velocity limits in robot space + double max_vel_x = max_vel_x_, max_vel_theta; + double min_vel_x, min_vel_theta; + + if( final_goal_position_valid_ ){ + double final_goal_dist = hypot( final_goal_x_ - x, final_goal_y_ - y ); + max_vel_x = min( max_vel_x, final_goal_dist / sim_time_ ); + } + + //should we use the dynamic window approach? + if (dwa_) { + max_vel_x = max(min(max_vel_x, vx + acc_x * sim_period_), min_vel_x_); + min_vel_x = max(min_vel_x_, vx - acc_x * sim_period_); + + max_vel_theta = min(max_vel_th_, vtheta + acc_theta * sim_period_); + min_vel_theta = max(min_vel_th_, vtheta - acc_theta * sim_period_); + } else { + max_vel_x = max(min(max_vel_x, vx + acc_x * sim_time_), min_vel_x_); + min_vel_x = max(min_vel_x_, vx - acc_x * sim_time_); + + max_vel_theta = min(max_vel_th_, vtheta + acc_theta * sim_time_); + min_vel_theta = max(min_vel_th_, vtheta - acc_theta * sim_time_); + } + + + //we want to sample the velocity space regularly + double dvx = (max_vel_x - min_vel_x) / (vx_samples_ - 1); + double dvtheta = (max_vel_theta - min_vel_theta) / (vtheta_samples_ - 1); + + double vx_samp = min_vel_x; + double vtheta_samp = min_vel_theta; + double vy_samp = 0.0; + + //keep track of the best trajectory seen so far + Trajectory* best_traj = &traj_one; + best_traj->cost_ = -1.0; + + Trajectory* comp_traj = &traj_two; + comp_traj->cost_ = -1.0; + + Trajectory* swap = NULL; + + //any cell with a cost greater than the size of the map is impossible + double impossible_cost = path_map_.obstacleCosts(); + + //if we're performing an escape we won't allow moving forward + if (!escaping_) { + //loop through all x velocities + for(int i = 0; i < vx_samples_; ++i) { + vtheta_samp = 0; + //first sample the straight trajectory + generateTrajectory(x, y, theta, vx, vy, vtheta, vx_samp, vy_samp, vtheta_samp, + acc_x, acc_y, acc_theta, impossible_cost, *comp_traj); + + //if the new trajectory is better... let's take it + if(comp_traj->cost_ >= 0 && (comp_traj->cost_ < best_traj->cost_ || best_traj->cost_ < 0)){ + swap = best_traj; + best_traj = comp_traj; + comp_traj = swap; + } + + vtheta_samp = min_vel_theta; + //next sample all theta trajectories + for(int j = 0; j < vtheta_samples_ - 1; ++j){ + generateTrajectory(x, y, theta, vx, vy, vtheta, vx_samp, vy_samp, vtheta_samp, + acc_x, acc_y, acc_theta, impossible_cost, *comp_traj); + + //if the new trajectory is better... let's take it + if(comp_traj->cost_ >= 0 && (comp_traj->cost_ < best_traj->cost_ || best_traj->cost_ < 0)){ + swap = best_traj; + best_traj = comp_traj; + comp_traj = swap; + } + vtheta_samp += dvtheta; + } + vx_samp += dvx; + } + + //only explore y velocities with holonomic robots + if (holonomic_robot_) { + //explore trajectories that move forward but also strafe slightly + vx_samp = 0.1; + vy_samp = 0.1; + vtheta_samp = 0.0; + generateTrajectory(x, y, theta, vx, vy, vtheta, vx_samp, vy_samp, vtheta_samp, + acc_x, acc_y, acc_theta, impossible_cost, *comp_traj); + + //if the new trajectory is better... let's take it + if(comp_traj->cost_ >= 0 && (comp_traj->cost_ < best_traj->cost_ || best_traj->cost_ < 0)){ + swap = best_traj; + best_traj = comp_traj; + comp_traj = swap; + } + + vx_samp = 0.1; + vy_samp = -0.1; + vtheta_samp = 0.0; + generateTrajectory(x, y, theta, vx, vy, vtheta, vx_samp, vy_samp, vtheta_samp, + acc_x, acc_y, acc_theta, impossible_cost, *comp_traj); + + //if the new trajectory is better... let's take it + if(comp_traj->cost_ >= 0 && (comp_traj->cost_ < best_traj->cost_ || best_traj->cost_ < 0)){ + swap = best_traj; + best_traj = comp_traj; + comp_traj = swap; + } + } + } // end if not escaping + + //next we want to generate trajectories for rotating in place + vtheta_samp = min_vel_theta; + vx_samp = 0.0; + vy_samp = 0.0; + + //let's try to rotate toward open space + double heading_dist = DBL_MAX; + + for(int i = 0; i < vtheta_samples_; ++i) { + //enforce a minimum rotational velocity because the base can't handle small in-place rotations + double vtheta_samp_limited = vtheta_samp > 0 ? max(vtheta_samp, min_in_place_vel_th_) + : min(vtheta_samp, -1.0 * min_in_place_vel_th_); + + generateTrajectory(x, y, theta, vx, vy, vtheta, vx_samp, vy_samp, vtheta_samp_limited, + acc_x, acc_y, acc_theta, impossible_cost, *comp_traj); + + //if the new trajectory is better... let's take it... + //note if we can legally rotate in place we prefer to do that rather than move with y velocity + if(comp_traj->cost_ >= 0 + && (comp_traj->cost_ <= best_traj->cost_ || best_traj->cost_ < 0 || best_traj->yv_ != 0.0) + && (vtheta_samp > dvtheta || vtheta_samp < -1 * dvtheta)){ + double x_r, y_r, th_r; + comp_traj->getEndpoint(x_r, y_r, th_r); + x_r += heading_lookahead_ * cos(th_r); + y_r += heading_lookahead_ * sin(th_r); + unsigned int cell_x, cell_y; + + //make sure that we'll be looking at a legal cell + if (costmap_.worldToMap(x_r, y_r, cell_x, cell_y)) { + double ahead_gdist = goal_map_(cell_x, cell_y).target_dist; + if (ahead_gdist < heading_dist) { + //if we haven't already tried rotating left since we've moved forward + if (vtheta_samp < 0 && !stuck_left) { + swap = best_traj; + best_traj = comp_traj; + comp_traj = swap; + heading_dist = ahead_gdist; + } + //if we haven't already tried rotating right since we've moved forward + else if(vtheta_samp > 0 && !stuck_right) { + swap = best_traj; + best_traj = comp_traj; + comp_traj = swap; + heading_dist = ahead_gdist; + } + } + } + } + + vtheta_samp += dvtheta; + } + + //do we have a legal trajectory + if (best_traj->cost_ >= 0) { + // avoid oscillations of in place rotation and in place strafing + if ( ! (best_traj->xv_ > 0)) { + if (best_traj->thetav_ < 0) { + if (rotating_right) { + stuck_right = true; + } + rotating_right = true; + } else if (best_traj->thetav_ > 0) { + if (rotating_left){ + stuck_left = true; + } + rotating_left = true; + } else if(best_traj->yv_ > 0) { + if (strafe_right) { + stuck_right_strafe = true; + } + strafe_right = true; + } else if(best_traj->yv_ < 0){ + if (strafe_left) { + stuck_left_strafe = true; + } + strafe_left = true; + } + + //set the position we must move a certain distance away from + prev_x_ = x; + prev_y_ = y; + } + + double dist = hypot(x - prev_x_, y - prev_y_); + if (dist > oscillation_reset_dist_) { + rotating_left = false; + rotating_right = false; + strafe_left = false; + strafe_right = false; + stuck_left = false; + stuck_right = false; + stuck_left_strafe = false; + stuck_right_strafe = false; + } + + dist = hypot(x - escape_x_, y - escape_y_); + if(dist > escape_reset_dist_ || + fabs(angles::shortest_angular_distance(escape_theta_, theta)) > escape_reset_theta_){ + escaping_ = false; + } + + return *best_traj; + } + + //only explore y velocities with holonomic robots + if (holonomic_robot_) { + //if we can't rotate in place or move forward... maybe we can move sideways and rotate + vtheta_samp = min_vel_theta; + vx_samp = 0.0; + + //loop through all y velocities + for(unsigned int i = 0; i < y_vels_.size(); ++i){ + vtheta_samp = 0; + vy_samp = y_vels_[i]; + //sample completely horizontal trajectories + generateTrajectory(x, y, theta, vx, vy, vtheta, vx_samp, vy_samp, vtheta_samp, + acc_x, acc_y, acc_theta, impossible_cost, *comp_traj); + + //if the new trajectory is better... let's take it + if(comp_traj->cost_ >= 0 && (comp_traj->cost_ <= best_traj->cost_ || best_traj->cost_ < 0)){ + double x_r, y_r, th_r; + comp_traj->getEndpoint(x_r, y_r, th_r); + x_r += heading_lookahead_ * cos(th_r); + y_r += heading_lookahead_ * sin(th_r); + unsigned int cell_x, cell_y; + + //make sure that we'll be looking at a legal cell + if(costmap_.worldToMap(x_r, y_r, cell_x, cell_y)) { + double ahead_gdist = goal_map_(cell_x, cell_y).target_dist; + if (ahead_gdist < heading_dist) { + //if we haven't already tried strafing left since we've moved forward + if (vy_samp > 0 && !stuck_left_strafe) { + swap = best_traj; + best_traj = comp_traj; + comp_traj = swap; + heading_dist = ahead_gdist; + } + //if we haven't already tried rotating right since we've moved forward + else if(vy_samp < 0 && !stuck_right_strafe) { + swap = best_traj; + best_traj = comp_traj; + comp_traj = swap; + heading_dist = ahead_gdist; + } + } + } + } + } + } + + //do we have a legal trajectory + if (best_traj->cost_ >= 0) { + if (!(best_traj->xv_ > 0)) { + if (best_traj->thetav_ < 0) { + if (rotating_right){ + stuck_right = true; + } + rotating_left = true; + } else if(best_traj->thetav_ > 0) { + if(rotating_left){ + stuck_left = true; + } + rotating_right = true; + } else if(best_traj->yv_ > 0) { + if(strafe_right){ + stuck_right_strafe = true; + } + strafe_left = true; + } else if(best_traj->yv_ < 0) { + if(strafe_left){ + stuck_left_strafe = true; + } + strafe_right = true; + } + + //set the position we must move a certain distance away from + prev_x_ = x; + prev_y_ = y; + + } + + double dist = hypot(x - prev_x_, y - prev_y_); + if(dist > oscillation_reset_dist_) { + rotating_left = false; + rotating_right = false; + strafe_left = false; + strafe_right = false; + stuck_left = false; + stuck_right = false; + stuck_left_strafe = false; + stuck_right_strafe = false; + } + + dist = hypot(x - escape_x_, y - escape_y_); + if(dist > escape_reset_dist_ || fabs(angles::shortest_angular_distance(escape_theta_, theta)) > escape_reset_theta_) { + escaping_ = false; + } + + return *best_traj; + } + + //and finally, if we can't do anything else, we want to generate trajectories that move backwards slowly + vtheta_samp = 0.0; + vx_samp = backup_vel_; + vy_samp = 0.0; + generateTrajectory(x, y, theta, vx, vy, vtheta, vx_samp, vy_samp, vtheta_samp, + acc_x, acc_y, acc_theta, impossible_cost, *comp_traj); + + //if the new trajectory is better... let's take it + /* + if(comp_traj->cost_ >= 0 && (comp_traj->cost_ < best_traj->cost_ || best_traj->cost_ < 0)){ + swap = best_traj; + best_traj = comp_traj; + comp_traj = swap; + } + */ + + //we'll allow moving backwards slowly even when the static map shows it as blocked + swap = best_traj; + best_traj = comp_traj; + comp_traj = swap; + + double dist = hypot(x - prev_x_, y - prev_y_); + if (dist > oscillation_reset_dist_) { + rotating_left = false; + rotating_right = false; + strafe_left = false; + strafe_right = false; + stuck_left = false; + stuck_right = false; + stuck_left_strafe = false; + stuck_right_strafe = false; + } + + //only enter escape mode when the planner has given a valid goal point + if (!escaping_ && best_traj->cost_ > -2.0) { + escape_x_ = x; + escape_y_ = y; + escape_theta_ = theta; + escaping_ = true; + } + + dist = hypot(x - escape_x_, y - escape_y_); + + if (dist > escape_reset_dist_ || + fabs(angles::shortest_angular_distance(escape_theta_, theta)) > escape_reset_theta_) { + escaping_ = false; + } + + + //if the trajectory failed because the footprint hits something, we're still going to back up + if(best_traj->cost_ == -1.0) + best_traj->cost_ = 1.0; + + return *best_traj; + + } + + //given the current state of the robot, find a good trajectory + Trajectory TrajectoryPlanner::findBestPath(const geometry_msgs::PoseStamped& global_pose, + geometry_msgs::PoseStamped& global_vel, geometry_msgs::PoseStamped& drive_velocities) { + + Eigen::Vector3f pos(global_pose.pose.position.x, global_pose.pose.position.y, tf2::getYaw(global_pose.pose.orientation)); + Eigen::Vector3f vel(global_vel.pose.position.x, global_vel.pose.position.y, tf2::getYaw(global_vel.pose.orientation)); + + //reset the map for new operations + path_map_.resetPathDist(); + goal_map_.resetPathDist(); + + //temporarily remove obstacles that are within the footprint of the robot + std::vector footprint_list = + footprint_helper_.getFootprintCells( + pos, + footprint_spec_, + costmap_, + true); + + //mark cells within the initial footprint of the robot + for (unsigned int i = 0; i < footprint_list.size(); ++i) { + path_map_(footprint_list[i].x, footprint_list[i].y).within_robot = true; + } + + //make sure that we update our path based on the global plan and compute costs + path_map_.setTargetCells(costmap_, global_plan_); + goal_map_.setLocalGoal(costmap_, global_plan_); + ROS_DEBUG("Path/Goal distance computed"); + + //rollout trajectories and find the minimum cost one + Trajectory best = createTrajectories(pos[0], pos[1], pos[2], + vel[0], vel[1], vel[2], + acc_lim_x_, acc_lim_y_, acc_lim_theta_); + ROS_DEBUG("Trajectories created"); + + /* + //If we want to print a ppm file to draw goal dist + char buf[4096]; + sprintf(buf, "base_local_planner.ppm"); + FILE *fp = fopen(buf, "w"); + if(fp){ + fprintf(fp, "P3\n"); + fprintf(fp, "%d %d\n", map_.size_x_, map_.size_y_); + fprintf(fp, "255\n"); + for(int j = map_.size_y_ - 1; j >= 0; --j){ + for(unsigned int i = 0; i < map_.size_x_; ++i){ + int g_dist = 255 - int(map_(i, j).goal_dist); + int p_dist = 255 - int(map_(i, j).path_dist); + if(g_dist < 0) + g_dist = 0; + if(p_dist < 0) + p_dist = 0; + fprintf(fp, "%d 0 %d ", g_dist, 0); + } + fprintf(fp, "\n"); + } + fclose(fp); + } + */ + + if(best.cost_ < 0){ + drive_velocities.pose.position.x = 0; + drive_velocities.pose.position.y = 0; + drive_velocities.pose.position.z = 0; + drive_velocities.pose.orientation.w = 1; + drive_velocities.pose.orientation.x = 0; + drive_velocities.pose.orientation.y = 0; + drive_velocities.pose.orientation.z = 0; + } + else{ + drive_velocities.pose.position.x = best.xv_; + drive_velocities.pose.position.y = best.yv_; + drive_velocities.pose.position.z = 0; + tf2::Quaternion q; + q.setRPY(0, 0, best.thetav_); + tf2::convert(q, drive_velocities.pose.orientation); + } + + return best; + } + + //we need to take the footprint of the robot into account when we calculate cost to obstacles + double TrajectoryPlanner::footprintCost(double x_i, double y_i, double theta_i){ + //check if the footprint is legal + return world_model_.footprintCost(x_i, y_i, theta_i, footprint_spec_, inscribed_radius_, circumscribed_radius_); + } + + + void TrajectoryPlanner::getLocalGoal(double& x, double& y){ + x = path_map_.goal_x_; + y = path_map_.goal_y_; + } + +}; + + diff --git a/navigations/base_local_planner/src/trajectory_planner_ros.cpp b/navigations/base_local_planner/src/trajectory_planner_ros.cpp new file mode 100755 index 0000000..e1ff245 --- /dev/null +++ b/navigations/base_local_planner/src/trajectory_planner_ros.cpp @@ -0,0 +1,621 @@ +/********************************************************************* +* +* Software License Agreement (BSD License) +* +* Copyright (c) 2008, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of the Willow Garage nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* +* Author: Eitan Marder-Eppstein +*********************************************************************/ + +#include + +#ifdef HAVE_SYS_TIME_H +#include +#endif + +#include + +#include +#include + +#include + +#include + +#include +#include + +#include +#include + +//register this planner as a BaseLocalPlanner plugin +PLUGINLIB_EXPORT_CLASS(base_local_planner::TrajectoryPlannerROS, nav_core::BaseLocalPlanner) + +namespace base_local_planner { + + void TrajectoryPlannerROS::reconfigureCB(BaseLocalPlannerConfig &config, uint32_t level) { + if (setup_ && config.restore_defaults) { + config = default_config_; + //Avoid looping + config.restore_defaults = false; + } + if ( ! setup_) { + default_config_ = config; + setup_ = true; + } + tc_->reconfigure(config); + reached_goal_ = false; + } + + TrajectoryPlannerROS::TrajectoryPlannerROS() : + world_model_(NULL), tc_(NULL), costmap_ros_(NULL), tf_(NULL), setup_(false), initialized_(false), odom_helper_("odom") {} + + TrajectoryPlannerROS::TrajectoryPlannerROS(std::string name, tf2_ros::Buffer* tf, costmap_2d::Costmap2DROS* costmap_ros) : + world_model_(NULL), tc_(NULL), costmap_ros_(NULL), tf_(NULL), setup_(false), initialized_(false), odom_helper_("odom") { + + //initialize the planner + initialize(name, tf, costmap_ros); + } + + void TrajectoryPlannerROS::initialize( + std::string name, + tf2_ros::Buffer* tf, + costmap_2d::Costmap2DROS* costmap_ros){ + if (! isInitialized()) { + + ros::NodeHandle private_nh("~/" + name); + g_plan_pub_ = private_nh.advertise("global_plan", 1); + l_plan_pub_ = private_nh.advertise("local_plan", 1); + + + tf_ = tf; + costmap_ros_ = costmap_ros; + rot_stopped_velocity_ = 1e-2; + trans_stopped_velocity_ = 1e-2; + double sim_time, sim_granularity, angular_sim_granularity; + int vx_samples, vtheta_samples; + double path_distance_bias, goal_distance_bias, occdist_scale, heading_lookahead, oscillation_reset_dist, escape_reset_dist, escape_reset_theta; + bool holonomic_robot, dwa, simple_attractor, heading_scoring; + double heading_scoring_timestep; + double max_vel_x, min_vel_x; + double backup_vel; + double stop_time_buffer; + std::string world_model_type; + rotating_to_goal_ = false; + + //initialize the copy of the costmap the controller will use + costmap_ = costmap_ros_->getCostmap(); + + + global_frame_ = costmap_ros_->getGlobalFrameID(); + robot_base_frame_ = costmap_ros_->getBaseFrameID(); + private_nh.param("prune_plan", prune_plan_, true); + + private_nh.param("yaw_goal_tolerance", yaw_goal_tolerance_, 0.05); + private_nh.param("xy_goal_tolerance", xy_goal_tolerance_, 0.10); + private_nh.param("acc_lim_x", acc_lim_x_, 2.5); + private_nh.param("acc_lim_y", acc_lim_y_, 2.5); + private_nh.param("acc_lim_theta", acc_lim_theta_, 3.2); + + private_nh.param("stop_time_buffer", stop_time_buffer, 0.2); + + private_nh.param("latch_xy_goal_tolerance", latch_xy_goal_tolerance_, false); + + //Since I screwed up nicely in my documentation, I'm going to add errors + //informing the user if they've set one of the wrong parameters + if(private_nh.hasParam("acc_limit_x")) + ROS_ERROR("You are using acc_limit_x where you should be using acc_lim_x. Please change your configuration files appropriately. The documentation used to be wrong on this, sorry for any confusion."); + + if(private_nh.hasParam("acc_limit_y")) + ROS_ERROR("You are using acc_limit_y where you should be using acc_lim_y. Please change your configuration files appropriately. The documentation used to be wrong on this, sorry for any confusion."); + + if(private_nh.hasParam("acc_limit_th")) + ROS_ERROR("You are using acc_limit_th where you should be using acc_lim_th. Please change your configuration files appropriately. The documentation used to be wrong on this, sorry for any confusion."); + + //Assuming this planner is being run within the navigation stack, we can + //just do an upward search for the frequency at which its being run. This + //also allows the frequency to be overwritten locally. + std::string controller_frequency_param_name; + if(!private_nh.searchParam("controller_frequency", controller_frequency_param_name)) + sim_period_ = 0.05; + else + { + double controller_frequency = 0; + private_nh.param(controller_frequency_param_name, controller_frequency, 20.0); + if(controller_frequency > 0) + sim_period_ = 1.0 / controller_frequency; + else + { + ROS_WARN("A controller_frequency less than 0 has been set. Ignoring the parameter, assuming a rate of 20Hz"); + sim_period_ = 0.05; + } + } + ROS_INFO("Sim period is set to %.2f", sim_period_); + + private_nh.param("sim_time", sim_time, 1.0); + private_nh.param("sim_granularity", sim_granularity, 0.025); + private_nh.param("angular_sim_granularity", angular_sim_granularity, sim_granularity); + private_nh.param("vx_samples", vx_samples, 3); + private_nh.param("vtheta_samples", vtheta_samples, 20); + + path_distance_bias = nav_core::loadParameterWithDeprecation(private_nh, + "path_distance_bias", + "pdist_scale", + 0.6); + goal_distance_bias = nav_core::loadParameterWithDeprecation(private_nh, + "goal_distance_bias", + "gdist_scale", + 0.6); + // values of the deprecated params need to be applied to the current params, as defaults + // of defined for dynamic reconfigure will override them otherwise. + if (private_nh.hasParam("pdist_scale") & !private_nh.hasParam("path_distance_bias")) + { + private_nh.setParam("path_distance_bias", path_distance_bias); + } + if (private_nh.hasParam("gdist_scale") & !private_nh.hasParam("goal_distance_bias")) + { + private_nh.setParam("goal_distance_bias", goal_distance_bias); + } + + private_nh.param("occdist_scale", occdist_scale, 0.01); + + bool meter_scoring; + if ( ! private_nh.hasParam("meter_scoring")) { + ROS_WARN("Trajectory Rollout planner initialized with param meter_scoring not set. Set it to true to make your settings robust against changes of costmap resolution."); + } else { + private_nh.param("meter_scoring", meter_scoring, false); + + if(meter_scoring) { + //if we use meter scoring, then we want to multiply the biases by the resolution of the costmap + double resolution = costmap_->getResolution(); + goal_distance_bias *= resolution; + path_distance_bias *= resolution; + } else { + ROS_WARN("Trajectory Rollout planner initialized with param meter_scoring set to false. Set it to true to make your settings robust against changes of costmap resolution."); + } + } + + private_nh.param("heading_lookahead", heading_lookahead, 0.325); + private_nh.param("oscillation_reset_dist", oscillation_reset_dist, 0.05); + private_nh.param("escape_reset_dist", escape_reset_dist, 0.10); + private_nh.param("escape_reset_theta", escape_reset_theta, M_PI_4); + private_nh.param("holonomic_robot", holonomic_robot, true); + private_nh.param("max_vel_x", max_vel_x, 0.5); + private_nh.param("min_vel_x", min_vel_x, 0.1); + + double max_rotational_vel; + private_nh.param("max_rotational_vel", max_rotational_vel, 1.0); + max_vel_th_ = max_rotational_vel; + min_vel_th_ = -1.0 * max_rotational_vel; + + min_in_place_vel_th_ = nav_core::loadParameterWithDeprecation(private_nh, + "min_in_place_vel_theta", + "min_in_place_rotational_vel", 0.4); + reached_goal_ = false; + backup_vel = -0.1; + if(private_nh.getParam("backup_vel", backup_vel)) + ROS_WARN("The backup_vel parameter has been deprecated in favor of the escape_vel parameter. To switch, just change the parameter name in your configuration files."); + + //if both backup_vel and escape_vel are set... we'll use escape_vel + private_nh.getParam("escape_vel", backup_vel); + + if(backup_vel >= 0.0) + ROS_WARN("You've specified a positive escape velocity. This is probably not what you want and will cause the robot to move forward instead of backward. You should probably change your escape_vel parameter to be negative"); + + private_nh.param("world_model", world_model_type, std::string("costmap")); + private_nh.param("dwa", dwa, true); + private_nh.param("heading_scoring", heading_scoring, false); + private_nh.param("heading_scoring_timestep", heading_scoring_timestep, 0.8); + + simple_attractor = false; + + //parameters for using the freespace controller + double min_pt_separation, max_obstacle_height, grid_resolution; + private_nh.param("point_grid/max_sensor_range", max_sensor_range_, 2.0); + private_nh.param("point_grid/min_pt_separation", min_pt_separation, 0.01); + private_nh.param("point_grid/max_obstacle_height", max_obstacle_height, 2.0); + private_nh.param("point_grid/grid_resolution", grid_resolution, 0.2); + + ROS_ASSERT_MSG(world_model_type == "costmap", "At this time, only costmap world models are supported by this controller"); + world_model_ = new CostmapModel(*costmap_); + std::vector y_vels = loadYVels(private_nh); + + footprint_spec_ = costmap_ros_->getRobotFootprint(); + + tc_ = new TrajectoryPlanner(*world_model_, *costmap_, footprint_spec_, + acc_lim_x_, acc_lim_y_, acc_lim_theta_, sim_time, sim_granularity, vx_samples, vtheta_samples, path_distance_bias, + goal_distance_bias, occdist_scale, heading_lookahead, oscillation_reset_dist, escape_reset_dist, escape_reset_theta, holonomic_robot, + max_vel_x, min_vel_x, max_vel_th_, min_vel_th_, min_in_place_vel_th_, backup_vel, + dwa, heading_scoring, heading_scoring_timestep, meter_scoring, simple_attractor, y_vels, stop_time_buffer, sim_period_, angular_sim_granularity); + + map_viz_.initialize(name, + global_frame_, + [this](int cx, int cy, float &path_cost, float &goal_cost, float &occ_cost, float &total_cost){ + return tc_->getCellCosts(cx, cy, path_cost, goal_cost, occ_cost, total_cost); + }); + initialized_ = true; + + dsrv_ = new dynamic_reconfigure::Server(private_nh); + dynamic_reconfigure::Server::CallbackType cb = [this](auto& config, auto level){ reconfigureCB(config, level); }; + dsrv_->setCallback(cb); + + } else { + ROS_WARN("This planner has already been initialized, doing nothing"); + } + } + + std::vector TrajectoryPlannerROS::loadYVels(ros::NodeHandle node){ + std::vector y_vels; + + std::string y_vel_list; + if(node.getParam("y_vels", y_vel_list)){ + typedef boost::tokenizer > tokenizer; + boost::char_separator sep("[], "); + tokenizer tokens(y_vel_list, sep); + + for(tokenizer::iterator i = tokens.begin(); i != tokens.end(); i++){ + y_vels.push_back(atof((*i).c_str())); + } + } + else{ + //if no values are passed in, we'll provide defaults + y_vels.push_back(-0.3); + y_vels.push_back(-0.1); + y_vels.push_back(0.1); + y_vels.push_back(0.3); + } + + return y_vels; + } + + TrajectoryPlannerROS::~TrajectoryPlannerROS() { + //make sure to clean things up + delete dsrv_; + + if(tc_ != NULL) + delete tc_; + + if(world_model_ != NULL) + delete world_model_; + } + + bool TrajectoryPlannerROS::stopWithAccLimits(const geometry_msgs::PoseStamped& global_pose, const geometry_msgs::PoseStamped& robot_vel, geometry_msgs::Twist& cmd_vel){ + //slow down with the maximum possible acceleration... we should really use the frequency that we're running at to determine what is feasible + //but we'll use a tenth of a second to be consistent with the implementation of the local planner. + double vx = sign(robot_vel.pose.position.x) * std::max(0.0, (fabs(robot_vel.pose.position.x) - acc_lim_x_ * sim_period_)); + double vy = sign(robot_vel.pose.position.y) * std::max(0.0, (fabs(robot_vel.pose.position.y) - acc_lim_y_ * sim_period_)); + + double vel_yaw = tf2::getYaw(robot_vel.pose.orientation); + double vth = sign(vel_yaw) * std::max(0.0, (fabs(vel_yaw) - acc_lim_theta_ * sim_period_)); + + //we do want to check whether or not the command is valid + double yaw = tf2::getYaw(global_pose.pose.orientation); + bool valid_cmd = tc_->checkTrajectory(global_pose.pose.position.x, global_pose.pose.position.y, yaw, + robot_vel.pose.position.x, robot_vel.pose.position.y, vel_yaw, vx, vy, vth); + + //if we have a valid command, we'll pass it on, otherwise we'll command all zeros + if(valid_cmd){ + ROS_DEBUG("Slowing down... using vx, vy, vth: %.2f, %.2f, %.2f", vx, vy, vth); + cmd_vel.linear.x = vx; + cmd_vel.linear.y = vy; + cmd_vel.angular.z = vth; + return true; + } + + cmd_vel.linear.x = 0.0; + cmd_vel.linear.y = 0.0; + cmd_vel.angular.z = 0.0; + return false; + } + + bool TrajectoryPlannerROS::rotateToGoal(const geometry_msgs::PoseStamped& global_pose, const geometry_msgs::PoseStamped& robot_vel, double goal_th, geometry_msgs::Twist& cmd_vel){ + double yaw = tf2::getYaw(global_pose.pose.orientation); + double vel_yaw = tf2::getYaw(robot_vel.pose.orientation); + cmd_vel.linear.x = 0; + cmd_vel.linear.y = 0; + double ang_diff = angles::shortest_angular_distance(yaw, goal_th); + + double v_theta_samp = ang_diff > 0.0 ? std::min(max_vel_th_, + std::max(min_in_place_vel_th_, ang_diff)) : std::max(min_vel_th_, + std::min(-1.0 * min_in_place_vel_th_, ang_diff)); + + //take the acceleration limits of the robot into account + double max_acc_vel = fabs(vel_yaw) + acc_lim_theta_ * sim_period_; + double min_acc_vel = fabs(vel_yaw) - acc_lim_theta_ * sim_period_; + + v_theta_samp = sign(v_theta_samp) * std::min(std::max(fabs(v_theta_samp), min_acc_vel), max_acc_vel); + + //we also want to make sure to send a velocity that allows us to stop when we reach the goal given our acceleration limits + double max_speed_to_stop = sqrt(2 * acc_lim_theta_ * fabs(ang_diff)); + + v_theta_samp = sign(v_theta_samp) * std::min(max_speed_to_stop, fabs(v_theta_samp)); + + // Re-enforce min_in_place_vel_th_. It is more important than the acceleration limits. + v_theta_samp = v_theta_samp > 0.0 + ? std::min( max_vel_th_, std::max( min_in_place_vel_th_, v_theta_samp )) + : std::max( min_vel_th_, std::min( -1.0 * min_in_place_vel_th_, v_theta_samp )); + + //we still want to lay down the footprint of the robot and check if the action is legal + bool valid_cmd = tc_->checkTrajectory(global_pose.pose.position.x, global_pose.pose.position.y, yaw, + robot_vel.pose.position.x, robot_vel.pose.position.y, vel_yaw, 0.0, 0.0, v_theta_samp); + + ROS_DEBUG("Moving to desired goal orientation, th cmd: %.2f, valid_cmd: %d", v_theta_samp, valid_cmd); + + if(valid_cmd){ + cmd_vel.angular.z = v_theta_samp; + return true; + } + + cmd_vel.angular.z = 0.0; + return false; + + } + + bool TrajectoryPlannerROS::setPlan(const std::vector& orig_global_plan){ + if (! isInitialized()) { + ROS_ERROR("This planner has not been initialized, please call initialize() before using this planner"); + return false; + } + + //reset the global plan + global_plan_.clear(); + global_plan_ = orig_global_plan; + + //when we get a new plan, we also want to clear any latch we may have on goal tolerances + xy_tolerance_latch_ = false; + //reset the at goal flag + reached_goal_ = false; + return true; + } + + bool TrajectoryPlannerROS::computeVelocityCommands(geometry_msgs::Twist& cmd_vel){ + if (! isInitialized()) { + ROS_ERROR("This planner has not been initialized, please call initialize() before using this planner"); + return false; + } + + std::vector local_plan; + geometry_msgs::PoseStamped global_pose; + if (!costmap_ros_->getRobotPose(global_pose)) { + return false; + } + + std::vector transformed_plan; + //get the global plan in our frame + if (!transformGlobalPlan(*tf_, global_plan_, global_pose, *costmap_, global_frame_, transformed_plan)) { + ROS_WARN("Could not transform the global plan to the frame of the controller"); + return false; + } + + //now we'll prune the plan based on the position of the robot + if(prune_plan_) + prunePlan(global_pose, transformed_plan, global_plan_); + + geometry_msgs::PoseStamped drive_cmds; + drive_cmds.header.frame_id = robot_base_frame_; + + geometry_msgs::PoseStamped robot_vel; + odom_helper_.getRobotVel(robot_vel); + + /* For timing uncomment + struct timeval start, end; + double start_t, end_t, t_diff; + gettimeofday(&start, NULL); + */ + + //if the global plan passed in is empty... we won't do anything + if(transformed_plan.empty()) + return false; + + const geometry_msgs::PoseStamped& goal_point = transformed_plan.back(); + //we assume the global goal is the last point in the global plan + const double goal_x = goal_point.pose.position.x; + const double goal_y = goal_point.pose.position.y; + + const double yaw = tf2::getYaw(goal_point.pose.orientation); + + double goal_th = yaw; + + //check to see if we've reached the goal position + if (xy_tolerance_latch_ || (getGoalPositionDistance(global_pose, goal_x, goal_y) <= xy_goal_tolerance_)) { + + //if the user wants to latch goal tolerance, if we ever reach the goal location, we'll + //just rotate in place + if (latch_xy_goal_tolerance_) { + xy_tolerance_latch_ = true; + } + + double angle = getGoalOrientationAngleDifference(global_pose, goal_th); + //check to see if the goal orientation has been reached + if (fabs(angle) <= yaw_goal_tolerance_) { + //set the velocity command to zero + cmd_vel.linear.x = 0.0; + cmd_vel.linear.y = 0.0; + cmd_vel.angular.z = 0.0; + rotating_to_goal_ = false; + xy_tolerance_latch_ = false; + reached_goal_ = true; + } else { + //we need to call the next two lines to make sure that the trajectory + //planner updates its path distance and goal distance grids + tc_->updatePlan(transformed_plan); + Trajectory path = tc_->findBestPath(global_pose, robot_vel, drive_cmds); + map_viz_.publishCostCloud(costmap_); + + //copy over the odometry information + nav_msgs::Odometry base_odom; + odom_helper_.getOdom(base_odom); + + //if we're not stopped yet... we want to stop... taking into account the acceleration limits of the robot + if ( ! rotating_to_goal_ && !base_local_planner::stopped(base_odom, rot_stopped_velocity_, trans_stopped_velocity_)) { + if ( ! stopWithAccLimits(global_pose, robot_vel, cmd_vel)) { + return false; + } + } + //if we're stopped... then we want to rotate to goal + else{ + //set this so that we know its OK to be moving + rotating_to_goal_ = true; + if(!rotateToGoal(global_pose, robot_vel, goal_th, cmd_vel)) { + return false; + } + } + } + + //publish an empty plan because we've reached our goal position + publishPlan(transformed_plan, g_plan_pub_); + publishPlan(local_plan, l_plan_pub_); + + //we don't actually want to run the controller when we're just rotating to goal + return true; + } + + tc_->updatePlan(transformed_plan); + + //compute what trajectory to drive along + Trajectory path = tc_->findBestPath(global_pose, robot_vel, drive_cmds); + + map_viz_.publishCostCloud(costmap_); + /* For timing uncomment + gettimeofday(&end, NULL); + start_t = start.tv_sec + double(start.tv_usec) / 1e6; + end_t = end.tv_sec + double(end.tv_usec) / 1e6; + t_diff = end_t - start_t; + ROS_INFO("Cycle time: %.9f", t_diff); + */ + + //pass along drive commands + cmd_vel.linear.x = drive_cmds.pose.position.x; + cmd_vel.linear.y = drive_cmds.pose.position.y; + cmd_vel.angular.z = tf2::getYaw(drive_cmds.pose.orientation); + + //if we cannot move... tell someone + if (path.cost_ < 0) { + ROS_DEBUG_NAMED("trajectory_planner_ros", + "The rollout planner failed to find a valid plan. This means that the footprint of the robot was in collision for all simulated trajectories."); + local_plan.clear(); + publishPlan(transformed_plan, g_plan_pub_); + publishPlan(local_plan, l_plan_pub_); + return false; + } + + ROS_DEBUG_NAMED("trajectory_planner_ros", "A valid velocity command of (%.2f, %.2f, %.2f) was found for this cycle.", + cmd_vel.linear.x, cmd_vel.linear.y, cmd_vel.angular.z); + + // Fill out the local plan + for (unsigned int i = 0; i < path.getPointsSize(); ++i) { + double p_x, p_y, p_th; + path.getPoint(i, p_x, p_y, p_th); + geometry_msgs::PoseStamped pose; + pose.header.frame_id = global_frame_; + pose.header.stamp = ros::Time::now(); + pose.pose.position.x = p_x; + pose.pose.position.y = p_y; + pose.pose.position.z = 0.0; + tf2::Quaternion q; + q.setRPY(0, 0, p_th); + tf2::convert(q, pose.pose.orientation); + local_plan.push_back(pose); + } + + //publish information to the visualizer + publishPlan(transformed_plan, g_plan_pub_); + publishPlan(local_plan, l_plan_pub_); + return true; + } + + bool TrajectoryPlannerROS::checkTrajectory(double vx_samp, double vy_samp, double vtheta_samp, bool update_map){ + geometry_msgs::PoseStamped global_pose; + if(costmap_ros_->getRobotPose(global_pose)){ + if(update_map){ + //we need to give the planne some sort of global plan, since we're only checking for legality + //we'll just give the robots current position + std::vector plan; + plan.push_back(global_pose); + tc_->updatePlan(plan, true); + } + + //copy over the odometry information + nav_msgs::Odometry base_odom; + { + boost::recursive_mutex::scoped_lock lock(odom_lock_); + base_odom = base_odom_; + } + + return tc_->checkTrajectory(global_pose.pose.position.x, global_pose.pose.position.y, tf2::getYaw(global_pose.pose.orientation), + base_odom.twist.twist.linear.x, + base_odom.twist.twist.linear.y, + base_odom.twist.twist.angular.z, vx_samp, vy_samp, vtheta_samp); + + } + ROS_WARN("Failed to get the pose of the robot. No trajectories will pass as legal in this case."); + return false; + } + + + double TrajectoryPlannerROS::scoreTrajectory(double vx_samp, double vy_samp, double vtheta_samp, bool update_map){ + // Copy of checkTrajectory that returns a score instead of True / False + geometry_msgs::PoseStamped global_pose; + if(costmap_ros_->getRobotPose(global_pose)){ + if(update_map){ + //we need to give the planne some sort of global plan, since we're only checking for legality + //we'll just give the robots current position + std::vector plan; + plan.push_back(global_pose); + tc_->updatePlan(plan, true); + } + + //copy over the odometry information + nav_msgs::Odometry base_odom; + { + boost::recursive_mutex::scoped_lock lock(odom_lock_); + base_odom = base_odom_; + } + + return tc_->scoreTrajectory(global_pose.pose.position.x, global_pose.pose.position.y, tf2::getYaw(global_pose.pose.orientation), + base_odom.twist.twist.linear.x, + base_odom.twist.twist.linear.y, + base_odom.twist.twist.angular.z, vx_samp, vy_samp, vtheta_samp); + + } + ROS_WARN("Failed to get the pose of the robot. No trajectories will pass as legal in this case."); + return -1.0; + } + + bool TrajectoryPlannerROS::isGoalReached() { + if (! isInitialized()) { + ROS_ERROR("This planner has not been initialized, please call initialize() before using this planner"); + return false; + } + //return flag set in controller + return reached_goal_; + } +}; diff --git a/navigations/base_local_planner/src/twirling_cost_function.cpp b/navigations/base_local_planner/src/twirling_cost_function.cpp new file mode 100755 index 0000000..3f29135 --- /dev/null +++ b/navigations/base_local_planner/src/twirling_cost_function.cpp @@ -0,0 +1,18 @@ +/* + * twirling_cost_function.cpp + * + * Created on: Apr 20, 2016 + * Author: Morgan Quigley + */ + +#include + +#include + +namespace base_local_planner { + +double TwirlingCostFunction::scoreTrajectory(Trajectory &traj) { + return fabs(traj.thetav_); // add cost for making the robot spin +} + +} /* namespace base_local_planner */ diff --git a/navigations/base_local_planner/src/voxel_grid_model.cpp b/navigations/base_local_planner/src/voxel_grid_model.cpp new file mode 100755 index 0000000..32596aa --- /dev/null +++ b/navigations/base_local_planner/src/voxel_grid_model.cpp @@ -0,0 +1,314 @@ +/********************************************************************* +* +* Software License Agreement (BSD License) +* +* Copyright (c) 2008, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of the Willow Garage nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* +* Author: Eitan Marder-Eppstein +*********************************************************************/ +#include +#include + +using namespace std; +using namespace costmap_2d; + +namespace base_local_planner { + VoxelGridModel::VoxelGridModel(double size_x, double size_y, double size_z, double xy_resolution, double z_resolution, + double origin_x, double origin_y, double origin_z, double max_z, double obstacle_range) : + obstacle_grid_(size_x, size_y, size_z), xy_resolution_(xy_resolution), z_resolution_(z_resolution), + origin_x_(origin_x), origin_y_(origin_y), origin_z_(origin_z), + max_z_(max_z), sq_obstacle_range_(obstacle_range * obstacle_range) {} + + double VoxelGridModel::footprintCost(const geometry_msgs::Point& position, const std::vector& footprint, + double inscribed_radius, double circumscribed_radius){ + if(footprint.size() < 3) + return -1.0; + + //now we really have to lay down the footprint in the costmap grid + unsigned int x0, x1, y0, y1; + double line_cost = 0.0; + + //we need to rasterize each line in the footprint + for(unsigned int i = 0; i < footprint.size() - 1; ++i){ + //get the cell coord of the first point + if(!worldToMap2D(footprint[i].x, footprint[i].y, x0, y0)) + return -1.0; + + //get the cell coord of the second point + if(!worldToMap2D(footprint[i + 1].x, footprint[i + 1].y, x1, y1)) + return -1.0; + + line_cost = lineCost(x0, x1, y0, y1); + + //if there is an obstacle that hits the line... we know that we can return false right away + if(line_cost < 0) + return -1.0; + } + + //we also need to connect the first point in the footprint to the last point + //get the cell coord of the last point + if(!worldToMap2D(footprint.back().x, footprint.back().y, x0, y0)) + return -1.0; + + //get the cell coord of the first point + if(!worldToMap2D(footprint.front().x, footprint.front().y, x1, y1)) + return -1.0; + + line_cost = lineCost(x0, x1, y0, y1); + + if(line_cost < 0) + return -1.0; + + //if all line costs are legal... then we can return that the footprint is legal + return 0.0; + } + + //calculate the cost of a ray-traced line + double VoxelGridModel::lineCost(int x0, int x1, + int y0, int y1){ + //Bresenham Ray-Tracing + int deltax = abs(x1 - x0); // The difference between the x's + int deltay = abs(y1 - y0); // The difference between the y's + int x = x0; // Start x off at the first pixel + int y = y0; // Start y off at the first pixel + + int xinc1, xinc2, yinc1, yinc2; + int den, num, numadd, numpixels; + + double line_cost = 0.0; + double point_cost = -1.0; + + if (x1 >= x0) // The x-values are increasing + { + xinc1 = 1; + xinc2 = 1; + } + else // The x-values are decreasing + { + xinc1 = -1; + xinc2 = -1; + } + + if (y1 >= y0) // The y-values are increasing + { + yinc1 = 1; + yinc2 = 1; + } + else // The y-values are decreasing + { + yinc1 = -1; + yinc2 = -1; + } + + if (deltax >= deltay) // There is at least one x-value for every y-value + { + xinc1 = 0; // Don't change the x when numerator >= denominator + yinc2 = 0; // Don't change the y for every iteration + den = deltax; + num = deltax / 2; + numadd = deltay; + numpixels = deltax; // There are more x-values than y-values + } + else // There is at least one y-value for every x-value + { + xinc2 = 0; // Don't change the x for every iteration + yinc1 = 0; // Don't change the y when numerator >= denominator + den = deltay; + num = deltay / 2; + numadd = deltax; + numpixels = deltay; // There are more y-values than x-values + } + + for (int curpixel = 0; curpixel <= numpixels; curpixel++) + { + point_cost = pointCost(x, y); //Score the current point + + if(point_cost < 0) + return -1; + + if(line_cost < point_cost) + line_cost = point_cost; + + num += numadd; // Increase the numerator by the top of the fraction + if (num >= den) // Check if numerator >= denominator + { + num -= den; // Calculate the new numerator value + x += xinc1; // Change the x as appropriate + y += yinc1; // Change the y as appropriate + } + x += xinc2; // Change the x as appropriate + y += yinc2; // Change the y as appropriate + } + + return line_cost; + } + + double VoxelGridModel::pointCost(int x, int y){ + //if the cell is in an obstacle the path is invalid + if(obstacle_grid_.getVoxelColumn(x, y)){ + return -1; + } + + return 1; + } + + void VoxelGridModel::updateWorld(const std::vector& footprint, + const vector& observations, const vector& laser_scans){ + + //remove points in the laser scan boundry + for(unsigned int i = 0; i < laser_scans.size(); ++i) + removePointsInScanBoundry(laser_scans[i], 10.0); + + //iterate through all observations and update the grid + for(vector::const_iterator it = observations.begin(); it != observations.end(); ++it){ + const Observation& obs = *it; + const sensor_msgs::PointCloud2& cloud = *(obs.cloud_); + + sensor_msgs::PointCloud2ConstIterator iter_x(cloud, "x"); + sensor_msgs::PointCloud2ConstIterator iter_y(cloud, "y"); + sensor_msgs::PointCloud2ConstIterator iter_z(cloud, "z"); + + geometry_msgs::Point32 pt; + + for(; iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z){ + //filter out points that are too high + if(*iter_z > max_z_) + continue; + + //compute the squared distance from the hitpoint to the pointcloud's origin + double sq_dist = (*iter_x - obs.origin_.x) * (*iter_x - obs.origin_.x) + + (*iter_y - obs.origin_.y) * (*iter_y - obs.origin_.y) + + (*iter_z - obs.origin_.z) * (*iter_z - obs.origin_.z); + + if(sq_dist >= sq_obstacle_range_) + continue; + + //insert the point + pt.x = *iter_x; + pt.y = *iter_y; + pt.z = *iter_z; + insert(pt); + } + } + + //remove the points that are in the footprint of the robot + //removePointsInPolygon(footprint); + } + + void VoxelGridModel::removePointsInScanBoundry(const PlanarLaserScan& laser_scan, double raytrace_range){ + if(laser_scan.cloud.points.size() == 0) + return; + + unsigned int sensor_x, sensor_y, sensor_z; + double ox = laser_scan.origin.x; + double oy = laser_scan.origin.y; + double oz = laser_scan.origin.z; + + if(!worldToMap3D(ox, oy, oz, sensor_x, sensor_y, sensor_z)) + return; + + for(unsigned int i = 0; i < laser_scan.cloud.points.size(); ++i){ + double wpx = laser_scan.cloud.points[i].x; + double wpy = laser_scan.cloud.points[i].y; + double wpz = laser_scan.cloud.points[i].z; + + double distance = dist(ox, oy, oz, wpx, wpy, wpz); + double scaling_fact = raytrace_range / distance; + scaling_fact = scaling_fact > 1.0 ? 1.0 : scaling_fact; + wpx = scaling_fact * (wpx - ox) + ox; + wpy = scaling_fact * (wpy - oy) + oy; + wpz = scaling_fact * (wpz - oz) + oz; + + //we can only raytrace to a maximum z height + if(wpz >= max_z_){ + //we know we want the vector's z value to be max_z + double a = wpx - ox; + double b = wpy - oy; + double c = wpz - oz; + double t = (max_z_ - .01 - oz) / c; + wpx = ox + a * t; + wpy = oy + b * t; + wpz = oz + c * t; + } + //and we can only raytrace down to the floor + else if(wpz < 0.0){ + //we know we want the vector's z value to be 0.0 + double a = wpx - ox; + double b = wpy - oy; + double c = wpz - oz; + double t = (0.0 - oz) / c; + wpx = ox + a * t; + wpy = oy + b * t; + wpz = oz + c * t; + } + + unsigned int point_x, point_y, point_z; + if(worldToMap3D(wpx, wpy, wpz, point_x, point_y, point_z)){ + obstacle_grid_.clearVoxelLine(sensor_x, sensor_y, sensor_z, point_x, point_y, point_z); + } + } + } + + void VoxelGridModel::getPoints(sensor_msgs::PointCloud2& cloud){ + size_t n = 0; + + for(unsigned int i = 0; i < obstacle_grid_.sizeX(); ++i) + for(unsigned int j = 0; j < obstacle_grid_.sizeY(); ++j) + for(unsigned int k = 0; k < obstacle_grid_.sizeZ(); ++k) + if(obstacle_grid_.getVoxel(i, j, k)) + ++n; + + sensor_msgs::PointCloud2Modifier modifier(cloud); + modifier.setPointCloud2FieldsByString(1, "xyz"); + modifier.resize(n); + + sensor_msgs::PointCloud2Iterator iter_x(cloud, "x"); + sensor_msgs::PointCloud2Iterator iter_y(cloud, "y"); + sensor_msgs::PointCloud2Iterator iter_z(cloud, "z"); + + for(unsigned int i = 0; i < obstacle_grid_.sizeX(); ++i){ + for(unsigned int j = 0; j < obstacle_grid_.sizeY(); ++j){ + for(unsigned int k = 0; k < obstacle_grid_.sizeZ(); ++k){ + if(obstacle_grid_.getVoxel(i, j, k)){ + double wx, wy, wz; + mapToWorld3D(i, j, k, wx, wy, wz); + *iter_x = wx; + *iter_y = wy; + *iter_z = wz; + ++iter_x; + ++iter_y; + ++iter_z; + } + } + } + } + } +}; diff --git a/navigations/base_local_planner/test/footprint_helper_test.cpp b/navigations/base_local_planner/test/footprint_helper_test.cpp new file mode 100755 index 0000000..5d3f768 --- /dev/null +++ b/navigations/base_local_planner/test/footprint_helper_test.cpp @@ -0,0 +1,145 @@ +/* + * footprint_helper_test.cpp + * + * Created on: May 2, 2012 + * Author: tkruse + */ + +#include + +#include + +#include + +#include +#include +#include + +#include "wavefront_map_accessor.h" + +namespace base_local_planner { + + +class FootprintHelperTest : public testing::Test { +public: + FootprintHelper fh; + + FootprintHelperTest() { + } + + virtual void TestBody(){} + + void correctLineCells() { + std::vector footprint; + fh.getLineCells(0, 10, 0, 10, footprint); + EXPECT_EQ(11, footprint.size()); + EXPECT_EQ(footprint[0].x, 0); + EXPECT_EQ(footprint[0].y, 0); + EXPECT_EQ(footprint[5].x, 5); + EXPECT_EQ(footprint[5].y, 5); + EXPECT_EQ(footprint[10].x, 10); + EXPECT_EQ(footprint[10].y, 10); + } + + void correctFootprint(){ + MapGrid* mg = new MapGrid (10, 10); + WavefrontMapAccessor* wa = new WavefrontMapAccessor(mg, .25); + const costmap_2d::Costmap2D& map = *wa; + + std::vector footprint_spec; + geometry_msgs::Point pt; + //create a square footprint + pt.x = 2; + pt.y = 2; + footprint_spec.push_back(pt); + pt.x = 2; + pt.y = -2; + footprint_spec.push_back(pt); + pt.x = -2; + pt.y = -2; + footprint_spec.push_back(pt); + pt.x = -2; + pt.y = 2; + footprint_spec.push_back(pt); + + Eigen::Vector3f pos(4.5, 4.5, 0); + //just create a basic footprint + std::vector footprint = fh.getFootprintCells(pos, footprint_spec, map, false); + + EXPECT_EQ(20, footprint.size()); + //we expect the front line to be first + EXPECT_EQ(footprint[0].x, 6); EXPECT_EQ(footprint[0].y, 6); + EXPECT_EQ(footprint[1].x, 6); EXPECT_EQ(footprint[1].y, 5); + EXPECT_EQ(footprint[2].x, 6); EXPECT_EQ(footprint[2].y, 4); + EXPECT_EQ(footprint[3].x, 6); EXPECT_EQ(footprint[3].y, 3); + EXPECT_EQ(footprint[4].x, 6); EXPECT_EQ(footprint[4].y, 2); + + //next the right line + EXPECT_EQ(footprint[5].x, 6); EXPECT_EQ(footprint[5].y, 2); + EXPECT_EQ(footprint[6].x, 5); EXPECT_EQ(footprint[6].y, 2); + EXPECT_EQ(footprint[7].x, 4); EXPECT_EQ(footprint[7].y, 2); + EXPECT_EQ(footprint[8].x, 3); EXPECT_EQ(footprint[8].y, 2); + EXPECT_EQ(footprint[9].x, 2); EXPECT_EQ(footprint[9].y, 2); + + //next the back line + EXPECT_EQ(footprint[10].x, 2); EXPECT_EQ(footprint[10].y, 2); + EXPECT_EQ(footprint[11].x, 2); EXPECT_EQ(footprint[11].y, 3); + EXPECT_EQ(footprint[12].x, 2); EXPECT_EQ(footprint[12].y, 4); + EXPECT_EQ(footprint[13].x, 2); EXPECT_EQ(footprint[13].y, 5); + EXPECT_EQ(footprint[14].x, 2); EXPECT_EQ(footprint[14].y, 6); + + //finally the left line + EXPECT_EQ(footprint[15].x, 2); EXPECT_EQ(footprint[15].y, 6); + EXPECT_EQ(footprint[16].x, 3); EXPECT_EQ(footprint[16].y, 6); + EXPECT_EQ(footprint[17].x, 4); EXPECT_EQ(footprint[17].y, 6); + EXPECT_EQ(footprint[18].x, 5); EXPECT_EQ(footprint[18].y, 6); + EXPECT_EQ(footprint[19].x, 6); EXPECT_EQ(footprint[19].y, 6); + + + pos = Eigen::Vector3f(4.5, 4.5, M_PI_2); + //check that rotation of the footprint works + footprint = fh.getFootprintCells(pos, footprint_spec, map, false); + + //first the left line + EXPECT_EQ(footprint[0].x, 2); EXPECT_EQ(footprint[0].y, 6); + EXPECT_EQ(footprint[1].x, 3); EXPECT_EQ(footprint[1].y, 6); + EXPECT_EQ(footprint[2].x, 4); EXPECT_EQ(footprint[2].y, 6); + EXPECT_EQ(footprint[3].x, 5); EXPECT_EQ(footprint[3].y, 6); + EXPECT_EQ(footprint[4].x, 6); EXPECT_EQ(footprint[4].y, 6); + + //next the front line + EXPECT_EQ(footprint[5].x, 6); EXPECT_EQ(footprint[5].y, 6); + EXPECT_EQ(footprint[6].x, 6); EXPECT_EQ(footprint[6].y, 5); + EXPECT_EQ(footprint[7].x, 6); EXPECT_EQ(footprint[7].y, 4); + EXPECT_EQ(footprint[8].x, 6); EXPECT_EQ(footprint[8].y, 3); + EXPECT_EQ(footprint[9].x, 6); EXPECT_EQ(footprint[9].y, 2); + + //next the right line + EXPECT_EQ(footprint[10].x, 6); EXPECT_EQ(footprint[10].y, 2); + EXPECT_EQ(footprint[11].x, 5); EXPECT_EQ(footprint[11].y, 2); + EXPECT_EQ(footprint[12].x, 4); EXPECT_EQ(footprint[12].y, 2); + EXPECT_EQ(footprint[13].x, 3); EXPECT_EQ(footprint[13].y, 2); + EXPECT_EQ(footprint[14].x, 2); EXPECT_EQ(footprint[14].y, 2); + + //next the back line + EXPECT_EQ(footprint[15].x, 2); EXPECT_EQ(footprint[15].y, 2); + EXPECT_EQ(footprint[16].x, 2); EXPECT_EQ(footprint[16].y, 3); + EXPECT_EQ(footprint[17].x, 2); EXPECT_EQ(footprint[17].y, 4); + EXPECT_EQ(footprint[18].x, 2); EXPECT_EQ(footprint[18].y, 5); + EXPECT_EQ(footprint[19].x, 2); EXPECT_EQ(footprint[19].y, 6); + } + +}; + + +TEST(FootprintHelperTest, correctFootprint){ + FootprintHelperTest tct; + tct.correctFootprint(); +} + +TEST(FootprintHelperTest, correctLineCells){ + FootprintHelperTest tct; + tct.correctLineCells(); +} + +} diff --git a/navigations/base_local_planner/test/gtest_main.cpp b/navigations/base_local_planner/test/gtest_main.cpp new file mode 100755 index 0000000..8d5005c --- /dev/null +++ b/navigations/base_local_planner/test/gtest_main.cpp @@ -0,0 +1,18 @@ +/* + * gtest_main.cpp + * + * Created on: Apr 6, 2012 + * Author: tkruse + */ + +#include + +#include + +int main(int argc, char **argv) { + std::cout << "Running main() from gtest_main.cc\n"; + + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} + diff --git a/navigations/base_local_planner/test/line_iterator_test.cpp b/navigations/base_local_planner/test/line_iterator_test.cpp new file mode 100755 index 0000000..2ff7c42 --- /dev/null +++ b/navigations/base_local_planner/test/line_iterator_test.cpp @@ -0,0 +1,81 @@ +/* + * Copyright (c) 2012, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include + +#include "base_local_planner/line_iterator.h" + +TEST( LineIterator, south ) +{ + base_local_planner::LineIterator line( 1, 2, 1, 4 ); + EXPECT_TRUE( line.isValid() ); + EXPECT_EQ( 1, line.getX() ); + EXPECT_EQ( 2, line.getY() ); + line.advance(); + EXPECT_TRUE( line.isValid() ); + EXPECT_EQ( 1, line.getX() ); + EXPECT_EQ( 3, line.getY() ); + line.advance(); + EXPECT_TRUE( line.isValid() ); + EXPECT_EQ( 1, line.getX() ); + EXPECT_EQ( 4, line.getY() ); + line.advance(); + EXPECT_FALSE( line.isValid() ); +} + +TEST( LineIterator, north_north_west ) +{ + base_local_planner::LineIterator line( 0, 0, -2, -4 ); + EXPECT_TRUE( line.isValid() ); + EXPECT_EQ( 0, line.getX() ); + EXPECT_EQ( 0, line.getY() ); + line.advance(); + EXPECT_TRUE( line.isValid() ); + EXPECT_EQ( -1, line.getX() ); + EXPECT_EQ( -1, line.getY() ); + line.advance(); + EXPECT_TRUE( line.isValid() ); + EXPECT_EQ( -1, line.getX() ); + EXPECT_EQ( -2, line.getY() ); + line.advance(); + EXPECT_TRUE( line.isValid() ); + EXPECT_EQ( -2, line.getX() ); + EXPECT_EQ( -3, line.getY() ); + line.advance(); + EXPECT_TRUE( line.isValid() ); + EXPECT_EQ( -2, line.getX() ); + EXPECT_EQ( -4, line.getY() ); + line.advance(); + EXPECT_FALSE( line.isValid() ); +} + +int main( int argc, char **argv ) { + testing::InitGoogleTest( &argc, argv ); + return RUN_ALL_TESTS(); +} diff --git a/navigations/base_local_planner/test/map_grid_test.cpp b/navigations/base_local_planner/test/map_grid_test.cpp new file mode 100755 index 0000000..59b63f2 --- /dev/null +++ b/navigations/base_local_planner/test/map_grid_test.cpp @@ -0,0 +1,206 @@ +/* + * map_grid_test.cpp + * + * Created on: May 2, 2012 + * Author: tkruse + */ +#include + +#include + +#include +#include + +#include "wavefront_map_accessor.h" + +namespace base_local_planner { + +TEST(MapGridTest, initNull){ + MapGrid map_grid; + EXPECT_EQ(0, map_grid.size_x_); + EXPECT_EQ(0, map_grid.size_y_); +} + +TEST(MapGridTest, operatorBrackets){ + MapGrid map_grid(10, 10); + map_grid(3, 5).target_dist = 5; + EXPECT_EQ(5, map_grid.getCell(3, 5).target_dist); +} + +TEST(MapGridTest, copyConstructor){ + MapGrid map_grid(10, 10); + map_grid(3, 5).target_dist = 5; + MapGrid map_grid2; + map_grid2 = map_grid; + EXPECT_EQ(5, map_grid(3, 5).target_dist); +} + +TEST(MapGridTest, getIndex){ + MapGrid map_grid(10, 10); + EXPECT_EQ(53, map_grid.getIndex(3, 5)); +} + +TEST(MapGridTest, reset){ + MapGrid map_grid(10, 10); + map_grid(0, 0).target_dist = 1; + map_grid(0, 0).target_mark = true; + map_grid(0, 0).within_robot = true; + map_grid(3, 5).target_dist = 1; + map_grid(3, 5).target_mark = true; + map_grid(3, 5).within_robot = true; + map_grid(9, 9).target_dist = 1; + map_grid(9, 9).target_mark = true; + map_grid(9, 9).within_robot = true; + EXPECT_EQ(1, map_grid(0, 0).target_dist); + EXPECT_EQ(true, map_grid(0, 0).target_mark); + EXPECT_EQ(true, map_grid(0, 0).within_robot); + EXPECT_EQ(1, map_grid(3, 5).target_dist); + EXPECT_EQ(true, map_grid(3, 5).target_mark); + EXPECT_EQ(true, map_grid(3, 5).within_robot); + EXPECT_EQ(1, map_grid(9, 9).target_dist); + EXPECT_EQ(true, map_grid(9, 9).target_mark); + EXPECT_EQ(true, map_grid(9, 9).within_robot); + + map_grid.resetPathDist(); + + EXPECT_EQ(map_grid.unreachableCellCosts(), map_grid(9, 9).target_dist); + EXPECT_EQ(false, map_grid(9, 9).target_mark); + EXPECT_EQ(false, map_grid(9, 9).within_robot); + EXPECT_EQ(map_grid.unreachableCellCosts(), map_grid(3, 5).target_dist); + EXPECT_EQ(false, map_grid(3, 5).target_mark); + EXPECT_EQ(false, map_grid(3, 5).within_robot); + EXPECT_EQ(map_grid.unreachableCellCosts(), map_grid(0, 0).target_dist); + EXPECT_EQ(false, map_grid(0, 0).target_mark); + EXPECT_EQ(false, map_grid(0, 0).within_robot); +} + + +TEST(MapGridTest, properGridConstruction){ + MapGrid mg(10, 10); + MapCell mc; + + for(int i = 0; i < 10; ++i){ + for(int j = 0; j < 10; ++j){ + EXPECT_FLOAT_EQ(mg(i, j).cx, i); + EXPECT_FLOAT_EQ(mg(i, j).cy, j); + } + } +} + +TEST(MapGridTest, sizeCheck){ + MapGrid mg(10, 10); + MapCell mc; + + mg.sizeCheck(20, 25); + + for(int i = 0; i < 20; ++i){ + for(int j = 0; j < 25; ++j){ + EXPECT_FLOAT_EQ(mg(i, j).cx, i); + EXPECT_FLOAT_EQ(mg(i, j).cy, j); + } + } +} + +TEST(MapGridTest, adjustPlanEmpty){ + MapGrid mg(10, 10); + const std::vector global_plan_in; + std::vector global_plan_out; + double resolution = 0; + mg.adjustPlanResolution(global_plan_in, global_plan_out, resolution); + EXPECT_EQ(0, global_plan_out.size()); +} + +TEST(MapGridTest, adjustPlan){ + MapGrid mg(10, 10); + std::vector global_plan_in; + std::vector global_plan_out; + double resolution = 1; + geometry_msgs::PoseStamped start; + start.pose.position.x = 1; + start.pose.position.y = 1; + geometry_msgs::PoseStamped end; + end.pose.position.x = 5; + end.pose.position.y = 5; + global_plan_in.push_back(start); + global_plan_in.push_back(end); + mg.adjustPlanResolution(global_plan_in, global_plan_out, resolution); + + EXPECT_EQ(1, global_plan_out[0].pose.position.x); + EXPECT_EQ(1, global_plan_out[0].pose.position.y); + EXPECT_EQ(5, global_plan_out.back().pose.position.x); + EXPECT_EQ(5, global_plan_out.back().pose.position.y); + + for (unsigned int i = 1; i < global_plan_out.size(); ++i) + { + geometry_msgs::Point& p0 = global_plan_out[i - 1].pose.position; + geometry_msgs::Point& p1 = global_plan_out[i].pose.position; + double d = hypot(p0.x - p1.x, p0.y - p1.y); + EXPECT_LT(d, resolution); + } +} + +TEST(MapGridTest, adjustPlan2){ + std::vector base_plan, result; + + // Push two points, at (0,0) and (0,1). Gap is 1 meter + base_plan.push_back(geometry_msgs::PoseStamped()); + base_plan.push_back(geometry_msgs::PoseStamped()); + base_plan.back().pose.position.y = 1.0; + + // resolution >= 1, path won't change + MapGrid::adjustPlanResolution(base_plan, result, 2.0); + EXPECT_EQ(2, result.size()); + result.clear(); + MapGrid::adjustPlanResolution(base_plan, result, 1.0); + EXPECT_EQ(2, result.size()); + result.clear(); + + // 0.5 <= resolution < 1.0, one point should be added in the middle + MapGrid::adjustPlanResolution(base_plan, result, 0.8); + EXPECT_EQ(3, result.size()); + result.clear(); + MapGrid::adjustPlanResolution(base_plan, result, 0.5); + EXPECT_EQ(3, result.size()); + result.clear(); + + // 0.333 <= resolution < 0.5, two points should be added in the middle + MapGrid::adjustPlanResolution(base_plan, result, 0.34); + EXPECT_EQ(4, result.size()); + result.clear(); + + // 0.25 <= resolution < 0.333, three points should be added in the middle + MapGrid::adjustPlanResolution(base_plan, result, 0.32); + EXPECT_EQ(5, result.size()); + result.clear(); + + MapGrid::adjustPlanResolution(base_plan, result, 0.1); + EXPECT_EQ(11, result.size()); + result.clear(); +} + +TEST(MapGridTest, distancePropagation){ + MapGrid mg(10, 10); + + WavefrontMapAccessor* wa = new WavefrontMapAccessor(&mg, .25); + std::queue dist_queue; + mg.computeTargetDistance(dist_queue, *wa); + EXPECT_EQ(false, mg(0, 0).target_mark); + + MapCell& mc = mg.getCell(0, 0); + mc.target_dist = 0.0; + mc.target_mark = true; + dist_queue.push(&mc); + mg.computeTargetDistance(dist_queue, *wa); + EXPECT_EQ(true, mg(0, 0).target_mark); + EXPECT_EQ(0.0, mg(0, 0).target_dist); + EXPECT_EQ(true, mg(1, 1).target_mark); + EXPECT_EQ(2.0, mg(1, 1).target_dist); + EXPECT_EQ(true, mg(0, 4).target_mark); + EXPECT_EQ(4.0, mg(0, 4).target_dist); + EXPECT_EQ(true, mg(4, 0).target_mark); + EXPECT_EQ(4.0, mg(4, 0).target_dist); + EXPECT_EQ(true, mg(9, 9).target_mark); + EXPECT_EQ(18.0, mg(9, 9).target_dist); +} + +} diff --git a/navigations/base_local_planner/test/trajectory_generator_test.cpp b/navigations/base_local_planner/test/trajectory_generator_test.cpp new file mode 100755 index 0000000..6aa3c5d --- /dev/null +++ b/navigations/base_local_planner/test/trajectory_generator_test.cpp @@ -0,0 +1,26 @@ +/* + * footprint_helper_test.cpp + * + * Created on: May 2, 2012 + * Author: tkruse + */ + +#include + +#include + +#include + +namespace base_local_planner { + +class TrajectoryGeneratorTest : public testing::Test { +public: + SimpleTrajectoryGenerator tg; + + TrajectoryGeneratorTest() { + } + + virtual void TestBody(){} +}; + +} diff --git a/navigations/base_local_planner/test/utest.cpp b/navigations/base_local_planner/test/utest.cpp new file mode 100755 index 0000000..dea4c2d --- /dev/null +++ b/navigations/base_local_planner/test/utest.cpp @@ -0,0 +1,215 @@ +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2008, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the Willow Garage nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *********************************************************************/ +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +#include "wavefront_map_accessor.h" + +using namespace std; + +namespace base_local_planner { + +class TrajectoryPlannerTest : public testing::Test { + public: + TrajectoryPlannerTest(MapGrid* g, WavefrontMapAccessor* wave, const costmap_2d::Costmap2D& map, std::vector footprint_spec); + void correctFootprint(); + void footprintObstacles(); + void checkGoalDistance(); + void checkPathDistance(); + virtual void TestBody(){} + + MapGrid* map_; + WavefrontMapAccessor* wa; + CostmapModel cm; + TrajectoryPlanner tc; +}; + +TrajectoryPlannerTest::TrajectoryPlannerTest(MapGrid* g, WavefrontMapAccessor* wave, const costmap_2d::Costmap2D& map, std::vector footprint_spec) +: map_(g), wa(wave), cm(map), tc(cm, map, footprint_spec, 0.0, 1.0, 1.0, 1.0, 1.0, 2.0) +{} + + + +void TrajectoryPlannerTest::footprintObstacles(){ + //place an obstacle + map_->operator ()(4, 6).target_dist = 1; + wa->synchronize(); + EXPECT_EQ(wa->getCost(4,6), costmap_2d::LETHAL_OBSTACLE); + Trajectory traj(0, 0, 0, 0.1, 30); + //tc->generateTrajectory(4.5, 4.5, M_PI_2, 0, 0, 0, 4, 0, 0, 4, 0, 0, DBL_MAX, traj, 2, 30); + tc.generateTrajectory(4.5, 4.5, M_PI_2, 0, 0, 0, 4, 0, 0, 4, 0, 0, DBL_MAX, traj); + //we expect this path to hit the obstacle + EXPECT_FLOAT_EQ(traj.cost_, -1.0); + + //place a wall next to the footprint of the robot + tc.path_map_(7, 1).target_dist = 1; + tc.path_map_(7, 3).target_dist = 1; + tc.path_map_(7, 4).target_dist = 1; + tc.path_map_(7, 5).target_dist = 1; + tc.path_map_(7, 6).target_dist = 1; + tc.path_map_(7, 7).target_dist = 1; + wa->synchronize(); + + //try to rotate into it + //tc->generateTrajectory(4.5, 4.5, M_PI_2, 0, 0, 0, 0, 0, M_PI_2, 0, 0, M_PI_4, 100, traj, 2, 30); + tc.generateTrajectory(4.5, 4.5, M_PI_2, 0, 0, 0, 0, 0, M_PI_2, 0, 0, M_PI_4, 100, traj); + //we expect this path to hit the obstacle + EXPECT_FLOAT_EQ(traj.cost_, -1.0); +} + +void TrajectoryPlannerTest::checkGoalDistance(){ + //let's box a cell in and make sure that its distance gets set to max + map_->operator ()(1, 2).target_dist = 1; + map_->operator ()(1, 1).target_dist = 1; + map_->operator ()(1, 0).target_dist = 1; + map_->operator ()(2, 0).target_dist = 1; + map_->operator ()(3, 0).target_dist = 1; + map_->operator ()(3, 1).target_dist = 1; + map_->operator ()(3, 2).target_dist = 1; + map_->operator ()(2, 2).target_dist = 1; + wa->synchronize(); + + //set a goal + tc.path_map_.resetPathDist(); + queue target_dist_queue; + MapCell& current = tc.path_map_(4, 9); + current.target_dist = 0.0; + current.target_mark = true; + target_dist_queue.push(¤t); + tc.path_map_.computeTargetDistance(target_dist_queue, tc.costmap_); + + EXPECT_FLOAT_EQ(tc.path_map_(4, 8).target_dist, 1.0); + EXPECT_FLOAT_EQ(tc.path_map_(4, 7).target_dist, 2.0); + EXPECT_FLOAT_EQ(tc.path_map_(4, 6).target_dist, 100.0); //there's an obstacle here placed above + EXPECT_FLOAT_EQ(tc.path_map_(4, 5).target_dist, 6.0); + EXPECT_FLOAT_EQ(tc.path_map_(4, 4).target_dist, 7.0); + EXPECT_FLOAT_EQ(tc.path_map_(4, 3).target_dist, 8.0); + EXPECT_FLOAT_EQ(tc.path_map_(4, 2).target_dist, 9.0); + EXPECT_FLOAT_EQ(tc.path_map_(4, 1).target_dist, 10.0); + EXPECT_FLOAT_EQ(tc.path_map_(4, 0).target_dist, 11.0); + EXPECT_FLOAT_EQ(tc.path_map_(5, 8).target_dist, 2.0); + EXPECT_FLOAT_EQ(tc.path_map_(9, 4).target_dist, 10.0); + + //check the boxed in cell + EXPECT_FLOAT_EQ(100.0, tc.path_map_(2, 2).target_dist); + +} + +void TrajectoryPlannerTest::checkPathDistance(){ + tc.path_map_.resetPathDist(); + queue target_dist_queue; + MapCell& current = tc.path_map_(4, 9); + current.target_dist = 0.0; + current.target_mark = true; + target_dist_queue.push(¤t); + tc.path_map_.computeTargetDistance(target_dist_queue, tc.costmap_); + + EXPECT_FLOAT_EQ(tc.path_map_(4, 8).target_dist, 1.0); + EXPECT_FLOAT_EQ(tc.path_map_(4, 7).target_dist, 2.0); + EXPECT_FLOAT_EQ(tc.path_map_(4, 6).target_dist, 100.0); //there's an obstacle here placed above + EXPECT_FLOAT_EQ(tc.path_map_(4, 5).target_dist, 6.0); + EXPECT_FLOAT_EQ(tc.path_map_(4, 4).target_dist, 7.0); + EXPECT_FLOAT_EQ(tc.path_map_(4, 3).target_dist, 8.0); + EXPECT_FLOAT_EQ(tc.path_map_(4, 2).target_dist, 9.0); + EXPECT_FLOAT_EQ(tc.path_map_(4, 1).target_dist, 10.0); + EXPECT_FLOAT_EQ(tc.path_map_(4, 0).target_dist, 11.0); + EXPECT_FLOAT_EQ(tc.path_map_(5, 8).target_dist, 2.0); + EXPECT_FLOAT_EQ(tc.path_map_(9, 4).target_dist, 10.0); + + //check the boxed in cell + EXPECT_FLOAT_EQ(tc.path_map_(2, 2).target_dist, 100.0); + +} + + +TrajectoryPlannerTest* tct = NULL; + +TrajectoryPlannerTest* setup_testclass_singleton() { + if (tct == NULL) { + MapGrid* mg = new MapGrid (10, 10); + WavefrontMapAccessor* wa = new WavefrontMapAccessor(mg, .25); + const costmap_2d::Costmap2D& map = *wa; + std::vector footprint_spec; + geometry_msgs::Point pt; + //create a square footprint + pt.x = 2; + pt.y = 2; + footprint_spec.push_back(pt); + pt.x = 2; + pt.y = -2; + footprint_spec.push_back(pt); + pt.x = -2; + pt.y = -2; + footprint_spec.push_back(pt); + pt.x = -2; + pt.y = 2; + footprint_spec.push_back(pt); + + tct = new base_local_planner::TrajectoryPlannerTest(mg, wa, map, footprint_spec); + } + return tct; +} + +//make sure that trajectories that intersect obstacles are invalidated +TEST(TrajectoryPlannerTest, footprintObstacles){ + TrajectoryPlannerTest* tct = setup_testclass_singleton(); + tct->footprintObstacles(); +} + +//make sure that goal distance is being computed as expected +TEST(TrajectoryPlannerTest, checkGoalDistance){ + TrajectoryPlannerTest* tct = setup_testclass_singleton(); + tct->checkGoalDistance(); +} + +//make sure that path distance is being computed as expected +TEST(TrajectoryPlannerTest, checkPathDistance){ + TrajectoryPlannerTest* tct = setup_testclass_singleton(); + tct->checkPathDistance(); +} + +}; //namespace diff --git a/navigations/base_local_planner/test/velocity_iterator_test.cpp b/navigations/base_local_planner/test/velocity_iterator_test.cpp new file mode 100755 index 0000000..44bc113 --- /dev/null +++ b/navigations/base_local_planner/test/velocity_iterator_test.cpp @@ -0,0 +1,178 @@ +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2008, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the Willow Garage nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *********************************************************************/ + + + + +#include + +#include + + +namespace base_local_planner { + +TEST(VelocityIteratorTest, testsingle) { + double result[5]; + int i = 0; + for(base_local_planner::VelocityIterator x_it(0.0, 0.0, 1); !x_it.isFinished(); x_it++) { + result[i] = x_it.getVelocity(); + i++; + } + EXPECT_EQ(1, i); + EXPECT_EQ(0, result[0]); +} + +TEST(VelocityIteratorTest, testsingle_pos) { + double result[5]; + int i = 0; + for(base_local_planner::VelocityIterator x_it(2.2, 2.2, 1); !x_it.isFinished(); x_it++) { + result[i] = x_it.getVelocity(); + i++; + } + EXPECT_EQ(1, i); + EXPECT_EQ(2.2, result[0]); +} + +TEST(VelocityIteratorTest, testsingle_neg) { + double result[5]; + int i = 0; + for(base_local_planner::VelocityIterator x_it(-3.3, -3.3, 1); !x_it.isFinished(); x_it++) { + result[i] = x_it.getVelocity(); + i++; + } + EXPECT_EQ(1, i); + EXPECT_EQ(-3.3, result[0]); +} + +TEST(VelocityIteratorTest, test1) { + double result[5]; + int i = 0; + for(base_local_planner::VelocityIterator x_it(-30, 30, 1); !x_it.isFinished(); x_it++) { + result[i] = x_it.getVelocity(); + i++; + } + EXPECT_EQ(3, i); + double expected [3]= {-30.0, 0.0, 30.0}; + for (int j = 0; j < 3; ++j) { + EXPECT_EQ(expected[j], result[j]); + } +} + +TEST(VelocityIteratorTest, test1_pos) { + double result[5]; + int i = 0; + for(base_local_planner::VelocityIterator x_it(10, 30, 1); !x_it.isFinished(); x_it++) { + result[i] = x_it.getVelocity(); + i++; + } + EXPECT_EQ(2, i); + double expected [2]= {10.0, 30.0}; + for (int j = 0; j < 2; ++j) { + EXPECT_EQ(expected[j], result[j]); + } +} + +TEST(VelocityIteratorTest, test1_neg) { + double result[5]; + int i = 0; + for(base_local_planner::VelocityIterator x_it(-30, -10, 1); !x_it.isFinished(); x_it++) { + result[i] = x_it.getVelocity(); + i++; + } + EXPECT_EQ(2, i); + double expected [2]= {-30.0, -10.0}; + for (int j = 0; j < 2; ++j) { + EXPECT_EQ(expected[j], result[j]); + } +} + +TEST(VelocityIteratorTest, test3) { + double result[5]; + int i = 0; + for(base_local_planner::VelocityIterator x_it(-30, 30, 3); !x_it.isFinished(); x_it++) { + result[i] = x_it.getVelocity(); + i++; + } + EXPECT_EQ(3, i); + double expected [3]= {-30.0, 0.0, 30}; + for (int j = 0; j < 3; ++j) { + EXPECT_EQ(expected[j], result[j]); + } +} + +TEST(VelocityIteratorTest, test4) { + double result[5]; + int i = 0; + for(base_local_planner::VelocityIterator x_it(-30, 30, 4); !x_it.isFinished(); x_it++) { + result[i] = x_it.getVelocity(); + i++; + } + EXPECT_EQ(5, i); + double expected [5]= {-30.0, -10.0, 0.0, 10.0, 30}; + for (int j = 0; j < 5; ++j) { + EXPECT_EQ(expected[j], result[j]); + } +} + +TEST(VelocityIteratorTest, test_shifted) { + // test where zero is not in the middle + double result[5]; + int i = 0; + for(base_local_planner::VelocityIterator x_it(-10, 50, 4); !x_it.isFinished(); x_it++) { + result[i] = x_it.getVelocity(); + i++; + } + EXPECT_EQ(5, i); + double expected [5]= {-10.0, 0.0, 10.0, 30, 50}; + for (int j = 0; j < 5; ++j) { + EXPECT_EQ(expected[j], result[j]); + } +} + +TEST(VelocityIteratorTest, test_cranky) { + // test where one value is almost zero (nothing to do about that) + double result[5]; + int i = 0; + for(base_local_planner::VelocityIterator x_it(-10.00001, 10, 3); !x_it.isFinished(); x_it++) { + result[i] = x_it.getVelocity(); + i++; + } + EXPECT_EQ(4, i); + for (int j = 0; j < 5; ++j) { + double expected [5]= {-10.00001, -0.000005, 0.0, 10.0}; + EXPECT_FLOAT_EQ(expected[j], result[j]); + } +} + +} // namespace diff --git a/navigations/base_local_planner/test/wavefront_map_accessor.h b/navigations/base_local_planner/test/wavefront_map_accessor.h new file mode 100755 index 0000000..a7b3454 --- /dev/null +++ b/navigations/base_local_planner/test/wavefront_map_accessor.h @@ -0,0 +1,50 @@ +/* + * wavefront_map_accessor.h + * + * Created on: May 2, 2012 + * Author: tkruse + */ + +#ifndef WAVEFRONT_MAP_ACCESSOR_H_ +#define WAVEFRONT_MAP_ACCESSOR_H_ +#include +namespace base_local_planner { + +/** + * Map_grids rely on costmaps to identify obstacles. We need a costmap that we can easily manipulate for unit tests. + * This class has a grid map where we can set grid cell state, and a synchronize method to make the costmap match. + */ +class WavefrontMapAccessor : public costmap_2d::Costmap2D { + public: + WavefrontMapAccessor(MapGrid* map, double outer_radius) + : costmap_2d::Costmap2D(map->size_x_, map->size_y_, 1, 0, 0), + map_(map), outer_radius_(outer_radius) { + synchronize(); + } + + virtual ~WavefrontMapAccessor(){}; + + void synchronize(){ + // Write Cost Data from the map + for(unsigned int x = 0; x < size_x_; x++){ + for (unsigned int y = 0; y < size_y_; y++){ + unsigned int ind = x + (y * size_x_); + if(map_->operator ()(x, y).target_dist == 1) { + costmap_[ind] = costmap_2d::LETHAL_OBSTACLE; + } else { + costmap_[ind] = 0; + } + } + } + } + + private: + MapGrid* map_; + double outer_radius_; +}; + +} + + + +#endif /* WAVEFRONT_MAP_ACCESSOR_H_ */ diff --git a/navigations/carrot_planner/CHANGELOG.rst b/navigations/carrot_planner/CHANGELOG.rst new file mode 100755 index 0000000..12fa2fe --- /dev/null +++ b/navigations/carrot_planner/CHANGELOG.rst @@ -0,0 +1,133 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package carrot_planner +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +1.17.3 (2023-01-10) +------------------- +* [ROS-O] various patches (`#1225 `_) + * do not specify obsolete c++11 standard + this breaks with current versions of log4cxx. + * update pluginlib include paths + the non-hpp headers have been deprecated since kinetic + * use lambdas in favor of boost::bind + Using boost's _1 as a global system is deprecated since C++11. + The ROS packages in Debian removed the implicit support for the global symbols, + so this code fails to compile there without the patch. +* Contributors: Michael Görner + +1.17.2 (2022-06-20) +------------------- +* Fix carrot planner (`#1056 `_) + * fix memory leak of world_model\_ + * fix uninitialized raw pointers + * move the angles header into cpp + * add missing angles dependency + Co-authored-by: Dima Dorezyuk +* Contributors: Dima Dorezyuk + +1.17.1 (2020-08-27) +------------------- + +1.17.0 (2020-04-02) +------------------- +* Merge pull request `#982 `_ from ros-planning/noetic_prep + Noetic Migration +* increase required cmake version +* Contributors: Michael Ferguson + +1.16.6 (2020-03-18) +------------------- + +1.16.5 (2020-03-15) +------------------- +* [melodic] updated install for better portability. (`#973 `_) +* Contributors: Sean Yen + +1.16.4 (2020-03-04) +------------------- +* [Windows][melodic] Navigation (except for map_server and amcl) Windows build bring up (`#851 `_) +* Contributors: Sean Yen + +1.16.3 (2019-11-15) +------------------- + +1.16.2 (2018-07-31) +------------------- +* Merge pull request `#773 `_ from ros-planning/packaging_fixes + packaging fixes +* fix depends of carrot_planner + * declare direct dependency on tf2 + * alphabetize the depends in CMake +* Contributors: Michael Ferguson + +1.16.1 (2018-07-28) +------------------- + +1.16.0 (2018-07-25) +------------------- +* Switch to TF2 `#755 `_ +* Contributors: Michael Ferguson, Rein Appeldoorn, Vincent Rabaud + +1.15.2 (2018-03-22) +------------------- +* Merge pull request `#673 `_ from ros-planning/email_update_lunar + update maintainer email (lunar) +* Merge pull request `#649 `_ from aaronhoy/lunar_add_ahoy + Add myself as a maintainer. +* Contributors: Aaron Hoy, Michael Ferguson + +1.15.1 (2017-08-14) +------------------- + +1.15.0 (2017-08-07) +------------------- +* convert packages to format2 +* Fix CMakeLists + package.xmls (`#548 `_) +* Contributors: Martin Günther, Mikael Arguedas, Vincent Rabaud + +1.14.0 (2016-05-20) +------------------- + +1.13.1 (2015-10-29) +------------------- + +1.13.0 (2015-03-17) +------------------- + +1.12.0 (2015-02-04) +------------------- +* update maintainer email +* Contributors: Michael Ferguson + +1.11.15 (2015-02-03) +-------------------- +* Add ARCHIVE_DESTINATION for static builds +* Contributors: Gary Servin + +1.11.14 (2014-12-05) +-------------------- + +1.11.13 (2014-10-02) +-------------------- + +1.11.12 (2014-10-01) +-------------------- + +1.11.11 (2014-07-23) +-------------------- + +1.11.10 (2014-06-25) +-------------------- + +1.11.9 (2014-06-10) +------------------- + +1.11.8 (2014-05-21) +------------------- + +1.11.7 (2014-05-21) +------------------- + +1.11.4 (2013-09-27) +------------------- +* Package URL Updates diff --git a/navigations/carrot_planner/CMakeLists.txt b/navigations/carrot_planner/CMakeLists.txt new file mode 100755 index 0000000..f0a9632 --- /dev/null +++ b/navigations/carrot_planner/CMakeLists.txt @@ -0,0 +1,58 @@ +cmake_minimum_required(VERSION 3.0.2) +project(carrot_planner) + +find_package(catkin REQUIRED + COMPONENTS + angles + base_local_planner + costmap_2d + nav_core + pluginlib + roscpp + tf2 + tf2_geometry_msgs + tf2_ros +) + +include_directories( + include + ${catkin_INCLUDE_DIRS} + ) +add_definitions(${EIGEN3_DEFINITIONS}) + +catkin_package( + INCLUDE_DIRS include + LIBRARIES carrot_planner + CATKIN_DEPENDS + angles + base_local_planner + costmap_2d + nav_core + pluginlib + roscpp + tf2 + tf2_ros +) + +add_library(carrot_planner src/carrot_planner.cpp) +add_dependencies(carrot_planner ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) +target_link_libraries(carrot_planner + ${catkin_LIBRARIES} + ) + +install(TARGETS carrot_planner + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} + ) + +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} + PATTERN ".svn" EXCLUDE +) + +install(FILES bgp_plugin.xml + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) + + diff --git a/navigations/carrot_planner/bgp_plugin.xml b/navigations/carrot_planner/bgp_plugin.xml new file mode 100755 index 0000000..cde6b32 --- /dev/null +++ b/navigations/carrot_planner/bgp_plugin.xml @@ -0,0 +1,7 @@ + + + + A simple planner that seeks to place a legal carrot in-front of the robot + + + diff --git a/navigations/carrot_planner/include/carrot_planner/carrot_planner.h b/navigations/carrot_planner/include/carrot_planner/carrot_planner.h new file mode 100755 index 0000000..c240de4 --- /dev/null +++ b/navigations/carrot_planner/include/carrot_planner/carrot_planner.h @@ -0,0 +1,107 @@ +/********************************************************************* +* +* Software License Agreement (BSD License) +* +* Copyright (c) 2008, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of Willow Garage, Inc. nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* +* Author: Eitan Marder-Eppstein +*********************************************************************/ +#ifndef CARROT_PLANNER_H_ +#define CARROT_PLANNER_H_ +#include +#include +#include +#include + +#include + +#include +#include + +namespace carrot_planner{ + /** + * @class CarrotPlanner + * @brief Provides a simple global planner that will compute a valid goal point for the local planner by walking back along the vector between the robot and the user-specified goal point until a valid cost is found. + */ + class CarrotPlanner : public nav_core::BaseGlobalPlanner { + public: + /** + * @brief Constructor for the CarrotPlanner + */ + CarrotPlanner(); + /** + * @brief Constructor for the CarrotPlanner + * @param name The name of this planner + * @param costmap_ros A pointer to the ROS wrapper of the costmap to use for planning + */ + CarrotPlanner(std::string name, costmap_2d::Costmap2DROS* costmap_ros); + + /** + * @brief Destructor + */ + ~CarrotPlanner(); + + /** + * @brief Initialization function for the CarrotPlanner + * @param name The name of this planner + * @param costmap_ros A pointer to the ROS wrapper of the costmap to use for planning + */ + void initialize(std::string name, costmap_2d::Costmap2DROS* costmap_ros); + + /** + * @brief Given a goal pose in the world, compute a plan + * @param start The start pose + * @param goal The goal pose + * @param plan The plan... filled by the planner + * @return True if a valid plan was found, false otherwise + */ + bool makePlan(const geometry_msgs::PoseStamped& start, + const geometry_msgs::PoseStamped& goal, std::vector& plan); + + private: + costmap_2d::Costmap2DROS* costmap_ros_; + double step_size_, min_dist_from_robot_; + costmap_2d::Costmap2D* costmap_; + base_local_planner::WorldModel* world_model_; ///< @brief The world model that the controller will use + + /** + * @brief Checks the legality of the robot footprint at a position and orientation using the world model + * @param x_i The x position of the robot + * @param y_i The y position of the robot + * @param theta_i The orientation of the robot + * @return + */ + double footprintCost(double x_i, double y_i, double theta_i); + + bool initialized_; + }; +}; +#endif diff --git a/navigations/carrot_planner/package.xml b/navigations/carrot_planner/package.xml new file mode 100755 index 0000000..db21567 --- /dev/null +++ b/navigations/carrot_planner/package.xml @@ -0,0 +1,39 @@ + + + + carrot_planner + 1.17.3 + + + This planner attempts to find a legal place to put a carrot for the robot to follow. It does this by moving back along the vector between the robot and the goal point. + + + Eitan Marder-Eppstein + Sachin Chitta + contradict@gmail.com + Aaron Hoy + David V. Lu!! + Michael Ferguson + BSD + http://wiki.ros.org/carrot_planner + + catkin + + tf2_geometry_msgs + + angles + base_local_planner + costmap_2d + eigen + nav_core + pluginlib + roscpp + tf2 + tf2_ros + + + + + + + diff --git a/navigations/carrot_planner/src/carrot_planner.cpp b/navigations/carrot_planner/src/carrot_planner.cpp new file mode 100755 index 0000000..4d6fb9b --- /dev/null +++ b/navigations/carrot_planner/src/carrot_planner.cpp @@ -0,0 +1,175 @@ +/********************************************************************* +* +* Software License Agreement (BSD License) +* +* Copyright (c) 2008, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of Willow Garage, Inc. nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* +* Authors: Eitan Marder-Eppstein, Sachin Chitta +*********************************************************************/ +#include +#include +#include +#include +#include +#include + +//register this planner as a BaseGlobalPlanner plugin +PLUGINLIB_EXPORT_CLASS(carrot_planner::CarrotPlanner, nav_core::BaseGlobalPlanner) + +namespace carrot_planner { + + CarrotPlanner::CarrotPlanner() + : costmap_ros_(NULL), costmap_(NULL), world_model_(NULL), initialized_(false){} + + CarrotPlanner::CarrotPlanner(std::string name, costmap_2d::Costmap2DROS* costmap_ros) + : costmap_ros_(NULL), costmap_(NULL), world_model_(NULL), initialized_(false){ + initialize(name, costmap_ros); + } + + CarrotPlanner::~CarrotPlanner() { + // deleting a nullptr is a noop + delete world_model_; + } + + void CarrotPlanner::initialize(std::string name, costmap_2d::Costmap2DROS* costmap_ros){ + if(!initialized_){ + costmap_ros_ = costmap_ros; + costmap_ = costmap_ros_->getCostmap(); + + ros::NodeHandle private_nh("~/" + name); + private_nh.param("step_size", step_size_, costmap_->getResolution()); + private_nh.param("min_dist_from_robot", min_dist_from_robot_, 0.10); + world_model_ = new base_local_planner::CostmapModel(*costmap_); + + initialized_ = true; + } + else + ROS_WARN("This planner has already been initialized... doing nothing"); + } + + //we need to take the footprint of the robot into account when we calculate cost to obstacles + double CarrotPlanner::footprintCost(double x_i, double y_i, double theta_i){ + if(!initialized_){ + ROS_ERROR("The planner has not been initialized, please call initialize() to use the planner"); + return -1.0; + } + + std::vector footprint = costmap_ros_->getRobotFootprint(); + //if we have no footprint... do nothing + if(footprint.size() < 3) + return -1.0; + + //check if the footprint is legal + double footprint_cost = world_model_->footprintCost(x_i, y_i, theta_i, footprint); + return footprint_cost; + } + + + bool CarrotPlanner::makePlan(const geometry_msgs::PoseStamped& start, + const geometry_msgs::PoseStamped& goal, std::vector& plan){ + + if(!initialized_){ + ROS_ERROR("The planner has not been initialized, please call initialize() to use the planner"); + return false; + } + + ROS_DEBUG("Got a start: %.2f, %.2f, and a goal: %.2f, %.2f", start.pose.position.x, start.pose.position.y, goal.pose.position.x, goal.pose.position.y); + + plan.clear(); + costmap_ = costmap_ros_->getCostmap(); + + if(goal.header.frame_id != costmap_ros_->getGlobalFrameID()){ + ROS_ERROR("This planner as configured will only accept goals in the %s frame, but a goal was sent in the %s frame.", + costmap_ros_->getGlobalFrameID().c_str(), goal.header.frame_id.c_str()); + return false; + } + + const double start_yaw = tf2::getYaw(start.pose.orientation); + const double goal_yaw = tf2::getYaw(goal.pose.orientation); + + //we want to step back along the vector created by the robot's position and the goal pose until we find a legal cell + double goal_x = goal.pose.position.x; + double goal_y = goal.pose.position.y; + double start_x = start.pose.position.x; + double start_y = start.pose.position.y; + + double diff_x = goal_x - start_x; + double diff_y = goal_y - start_y; + double diff_yaw = angles::normalize_angle(goal_yaw-start_yaw); + + double target_x = goal_x; + double target_y = goal_y; + double target_yaw = goal_yaw; + + bool done = false; + double scale = 1.0; + double dScale = 0.01; + + while(!done) + { + if(scale < 0) + { + target_x = start_x; + target_y = start_y; + target_yaw = start_yaw; + ROS_WARN("The carrot planner could not find a valid plan for this goal"); + break; + } + target_x = start_x + scale * diff_x; + target_y = start_y + scale * diff_y; + target_yaw = angles::normalize_angle(start_yaw + scale * diff_yaw); + + double footprint_cost = footprintCost(target_x, target_y, target_yaw); + if(footprint_cost >= 0) + { + done = true; + } + scale -=dScale; + } + + plan.push_back(start); + geometry_msgs::PoseStamped new_goal = goal; + tf2::Quaternion goal_quat; + goal_quat.setRPY(0, 0, target_yaw); + + new_goal.pose.position.x = target_x; + new_goal.pose.position.y = target_y; + + new_goal.pose.orientation.x = goal_quat.x(); + new_goal.pose.orientation.y = goal_quat.y(); + new_goal.pose.orientation.z = goal_quat.z(); + new_goal.pose.orientation.w = goal_quat.w(); + + plan.push_back(new_goal); + return (done); + } + +}; diff --git a/navigations/clear_costmap_recovery/CHANGELOG.rst b/navigations/clear_costmap_recovery/CHANGELOG.rst new file mode 100755 index 0000000..d3d40a9 --- /dev/null +++ b/navigations/clear_costmap_recovery/CHANGELOG.rst @@ -0,0 +1,163 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package clear_costmap_recovery +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +1.17.3 (2023-01-10) +------------------- +* [ROS-O] various patches (`#1225 `_) + * do not specify obsolete c++11 standard + this breaks with current versions of log4cxx. + * update pluginlib include paths + the non-hpp headers have been deprecated since kinetic + * use lambdas in favor of boost::bind + Using boost's _1 as a global system is deprecated since C++11. + The ROS packages in Debian removed the implicit support for the global symbols, + so this code fails to compile there without the patch. +* Contributors: Michael Görner + +1.17.2 (2022-06-20) +------------------- +* check if the layer is derived from costmap_2d::CostmapLayer (`#1054 `_) + Co-authored-by: Dima Dorezyuk +* Add invert_area_to_clear to clear costmap recovery behavior (`#1030 `_) +* Contributors: Dima Dorezyuk, G.Doisy + +1.17.1 (2020-08-27) +------------------- + +1.17.0 (2020-04-02) +------------------- +* Merge pull request `#982 `_ from ros-planning/noetic_prep + Noetic Migration +* increase required cmake version +* Contributors: Michael Ferguson + +1.16.6 (2020-03-18) +------------------- + +1.16.5 (2020-03-15) +------------------- +* [melodic] updated install for better portability. (`#973 `_) +* Contributors: Sean Yen + +1.16.4 (2020-03-04) +------------------- +* [Windows][melodic] Navigation (except for map_server and amcl) Windows build bring up (`#851 `_) +* Contributors: Sean Yen + +1.16.3 (2019-11-15) +------------------- +* Merge pull request `#877 `_ from SteveMacenski/layer_clear_area-melodic + [melodic] moving clearing area method to costmap_layer so other applications can clear other types. +* Merge branch 'melodic-devel' into layer_clear_area-melodic +* Add force_updating and affected_maps parameters to tailor clear costmaps recovey (`#838 `_) + behavior +* clear area in layer for melodic +* Contributors: Jorge Santos Simón, Michael Ferguson, Steven Macenski, stevemacenski + +1.16.2 (2018-07-31) +------------------- + +1.16.1 (2018-07-28) +------------------- + +1.16.0 (2018-07-25) +------------------- +* Switch to TF2 `#755 `_ +* Contributors: Michael Ferguson, Vincent Rabaud + +1.15.2 (2018-03-22) +------------------- +* Merge pull request `#673 `_ from ros-planning/email_update_lunar + update maintainer email (lunar) +* Merge pull request `#649 `_ from aaronhoy/lunar_add_ahoy + Add myself as a maintainer. +* Rebase PRs from Indigo/Kinetic (`#637 `_) + * Respect planner_frequency intended behavior (`#622 `_) + * Only do a getRobotPose when no start pose is given (`#628 `_) + Omit the unnecessary call to getRobotPose when the start pose was + already given, so that move_base can also generate a path in + situations where getRobotPose would fail. + This is actually to work around an issue of getRobotPose randomly + failing. + * Update gradient_path.cpp (`#576 `_) + * Update gradient_path.cpp + * Update navfn.cpp + * update to use non deprecated pluginlib macro (`#630 `_) + * update to use non deprecated pluginlib macro + * multiline version as well + * Print SDL error on IMG_Load failure in server_map (`#631 `_) +* Contributors: Aaron Hoy, David V. Lu!!, Michael Ferguson + +1.15.1 (2017-08-14) +------------------- + +1.15.0 (2017-08-07) +------------------- +* convert packages to format2 +* Fix CMakeLists + package.xmls (`#548 `_) +* import only PCL common +* remove GCC warnings +* Contributors: Martin Günther, Mikael Arguedas, Vincent Rabaud + +1.14.0 (2016-05-20) +------------------- + +1.13.1 (2015-10-29) +------------------- +* proper locking during costmap update +* Contributors: Michael Ferguson + +1.13.0 (2015-03-17) +------------------- + +1.12.0 (2015-02-04) +------------------- +* update maintainer email +* Contributors: Michael Ferguson + +1.11.15 (2015-02-03) +-------------------- +* Add ARCHIVE_DESTINATION for static builds +* Contributors: Gary Servin + +1.11.14 (2014-12-05) +-------------------- + +1.11.13 (2014-10-02) +-------------------- +* Fix the build (layers library is exported by costmap_2d) +* Contributors: Michael Ferguson + +1.11.12 (2014-10-01) +-------------------- +* Clarify debug messages +* Initial Clearing Costmap parameter change +* Contributors: David Lu!!, Michael Ferguson + +1.11.11 (2014-07-23) +-------------------- + +1.11.10 (2014-06-25) +-------------------- + +1.11.9 (2014-06-10) +------------------- + +1.11.8 (2014-05-21) +------------------- + +1.11.7 (2014-05-21) +------------------- +* update build to find eigen using cmake_modules +* Contributors: Michael Ferguson + +1.11.5 (2014-01-30) +------------------- +* Misc. other commits from Groovy Branch +* Change maintainer from Hersh to Lu + +1.11.4 (2013-09-27) +------------------- +* Package URL Updates +* Fix bounds setting diff --git a/navigations/clear_costmap_recovery/CMakeLists.txt b/navigations/clear_costmap_recovery/CMakeLists.txt new file mode 100755 index 0000000..f0753b2 --- /dev/null +++ b/navigations/clear_costmap_recovery/CMakeLists.txt @@ -0,0 +1,66 @@ +cmake_minimum_required(VERSION 3.0.2) +project(clear_costmap_recovery) + +find_package(catkin REQUIRED + COMPONENTS + cmake_modules + costmap_2d + nav_core + pluginlib + roscpp + tf2_ros + ) + +find_package(Eigen3 REQUIRED) +remove_definitions(-DDISABLE_LIBUSB-1.0) +include_directories( + include + ${catkin_INCLUDE_DIRS} + ${EIGEN3_INCLUDE_DIRS} +) +add_definitions(${EIGEN3_DEFINITIONS}) + +catkin_package( + INCLUDE_DIRS include + LIBRARIES clear_costmap_recovery + CATKIN_DEPENDS + costmap_2d + nav_core + pluginlib + roscpp + tf2_ros +) + +add_library(clear_costmap_recovery src/clear_costmap_recovery.cpp) +add_dependencies(clear_costmap_recovery ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) +target_link_libraries(clear_costmap_recovery ${catkin_LIBRARIES}) + + +## Configure Tests +if(CATKIN_ENABLE_TESTING) + # Find package test dependencies + find_package(rostest REQUIRED) + + # Add the test folder to the include directories + include_directories(test) + + # Create targets for test executables + add_rostest_gtest(clear_tester test/clear_tests.launch test/clear_tester.cpp) + target_link_libraries(clear_tester clear_costmap_recovery ${GTEST_LIBRARIES}) +endif() + + +install(TARGETS clear_costmap_recovery + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} + ) + +install(FILES ccr_plugin.xml + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) + +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} + PATTERN ".svn" EXCLUDE +) diff --git a/navigations/clear_costmap_recovery/ccr_plugin.xml b/navigations/clear_costmap_recovery/ccr_plugin.xml new file mode 100755 index 0000000..93f2af2 --- /dev/null +++ b/navigations/clear_costmap_recovery/ccr_plugin.xml @@ -0,0 +1,7 @@ + + + + A recovery behavior that reverts the costmap to the static map outside of a user specified window. + + + diff --git a/navigations/clear_costmap_recovery/include/clear_costmap_recovery/clear_costmap_recovery.h b/navigations/clear_costmap_recovery/include/clear_costmap_recovery/clear_costmap_recovery.h new file mode 100755 index 0000000..c7be30a --- /dev/null +++ b/navigations/clear_costmap_recovery/include/clear_costmap_recovery/clear_costmap_recovery.h @@ -0,0 +1,88 @@ +/********************************************************************* +* +* Software License Agreement (BSD License) +* +* Copyright (c) 2009, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of Willow Garage, Inc. nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* +* Author: Eitan Marder-Eppstein +*********************************************************************/ +#ifndef CLEAR_COSTMAP_RECOVERY_H_ +#define CLEAR_COSTMAP_RECOVERY_H_ +#include +#include +#include +#include + +namespace clear_costmap_recovery{ + /** + * @class ClearCostmapRecovery + * @brief A recovery behavior that reverts the navigation stack's costmaps to the static map outside of a user-specified region. + */ + class ClearCostmapRecovery : public nav_core::RecoveryBehavior { + public: + /** + * @brief Constructor, make sure to call initialize in addition to actually initialize the object + * @param + * @return + */ + ClearCostmapRecovery(); + + /** + * @brief Initialization function for the ClearCostmapRecovery recovery behavior + * @param tf A pointer to a transform listener + * @param global_costmap A pointer to the global_costmap used by the navigation stack + * @param local_costmap A pointer to the local_costmap used by the navigation stack + */ + void initialize(std::string name, tf2_ros::Buffer* tf, + costmap_2d::Costmap2DROS* global_costmap, costmap_2d::Costmap2DROS* local_costmap); + + /** + * @brief Run the ClearCostmapRecovery recovery behavior. Reverts the + * costmap to the static map outside of a user-specified window and + * clears unknown space around the robot. + */ + void runBehavior(); + + private: + void clear(costmap_2d::Costmap2DROS* costmap); + void clearMap(boost::shared_ptr costmap, double pose_x, double pose_y); + costmap_2d::Costmap2DROS* global_costmap_, *local_costmap_; + std::string name_; + tf2_ros::Buffer* tf_; + bool initialized_; + bool force_updating_; ///< force costmap update after clearing, so we don't need to wait for update thread + double reset_distance_; + bool invert_area_to_clear_; + std::string affected_maps_; ///< clear only local, global or both costmaps + std::set clearable_layers_; ///< Layer names which will be cleared. + }; +}; +#endif diff --git a/navigations/clear_costmap_recovery/package.xml b/navigations/clear_costmap_recovery/package.xml new file mode 100755 index 0000000..69ebf07 --- /dev/null +++ b/navigations/clear_costmap_recovery/package.xml @@ -0,0 +1,37 @@ + + + + clear_costmap_recovery + 1.17.3 + + + This package provides a recovery behavior for the navigation stack that attempts to clear space by reverting the costmaps used by the navigation stack to the static map outside of a given area. + + + Eitan Marder-Eppstein + contradict@gmail.com + David V. Lu!! + Michael Ferguson + Aaron Hoy + BSD + http://wiki.ros.org/clear_costmap_recovery + + catkin + + cmake_modules + + costmap_2d + eigen + nav_core + pluginlib + roscpp + tf2_ros + + rostest + + + + + + + diff --git a/navigations/clear_costmap_recovery/src/clear_costmap_recovery.cpp b/navigations/clear_costmap_recovery/src/clear_costmap_recovery.cpp new file mode 100755 index 0000000..98fc9c1 --- /dev/null +++ b/navigations/clear_costmap_recovery/src/clear_costmap_recovery.cpp @@ -0,0 +1,204 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2009, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: Eitan Marder-Eppstein + *********************************************************************/ +#include +#include +#include +#include + +// register this planner as a RecoveryBehavior plugin +PLUGINLIB_EXPORT_CLASS(clear_costmap_recovery::ClearCostmapRecovery, nav_core::RecoveryBehavior) + +using costmap_2d::NO_INFORMATION; + +namespace clear_costmap_recovery +{ + ClearCostmapRecovery::ClearCostmapRecovery() : global_costmap_(NULL), local_costmap_(NULL), + tf_(NULL), initialized_(false) {} + + void ClearCostmapRecovery::initialize(std::string name, tf2_ros::Buffer *tf, + costmap_2d::Costmap2DROS *global_costmap, costmap_2d::Costmap2DROS *local_costmap) + { + if (!initialized_) + { + name_ = name; + tf_ = tf; + global_costmap_ = global_costmap; + local_costmap_ = local_costmap; + + // get some parameters from the parameter server + ros::NodeHandle private_nh("~/" + name_); + + private_nh.param("reset_distance", reset_distance_, 3.0); + private_nh.param("invert_area_to_clear", invert_area_to_clear_, false); + private_nh.param("force_updating", force_updating_, false); + private_nh.param("affected_maps", affected_maps_, std::string("both")); + if (affected_maps_ != "local" && affected_maps_ != "global" && affected_maps_ != "both") + { + ROS_WARN("Wrong value for affected_maps parameter: '%s'; valid values are 'local', 'global' or 'both'; " + "defaulting to 'both'", + affected_maps_.c_str()); + affected_maps_ = "both"; + } + + std::vector clearable_layers_default, clearable_layers; + clearable_layers_default.push_back(std::string("obstacles")); + private_nh.param("layer_names", clearable_layers, clearable_layers_default); + + for (unsigned i = 0; i < clearable_layers.size(); i++) + { + ROS_INFO("Recovery behavior will clear layer '%s'", clearable_layers[i].c_str()); + clearable_layers_.insert(clearable_layers[i]); + } + initialized_ = true; + } + else + { + ROS_ERROR("You should not call initialize twice on this object, doing nothing "); + } + } + + void ClearCostmapRecovery::runBehavior() + { + if (!initialized_) + { + ROS_ERROR("This object must be initialized before runBehavior is called"); + return; + } + + if (global_costmap_ == NULL || local_costmap_ == NULL) + { + ROS_ERROR("The costmaps passed to the ClearCostmapRecovery object cannot be NULL. Doing nothing."); + return; + } + + if (!invert_area_to_clear_) + { + ROS_WARN("%s is Clearing %s costmap%s outside a square (%.2fm) large centered on the robot.", name_.c_str(),affected_maps_.c_str(), + affected_maps_ == "both" ? "s" : "", reset_distance_); + } + else + { + ROS_WARN("%s is Clearing %s costmap%s inside a square (%.2fm) large centered on the robot.", name_.c_str(), affected_maps_.c_str(), + affected_maps_ == "both" ? "s" : "", reset_distance_); + } + + ros::WallTime t0 = ros::WallTime::now(); + if (affected_maps_ == "global" || affected_maps_ == "both") + { + clear(global_costmap_); + + if (force_updating_) + global_costmap_->updateMap(); + + ROS_DEBUG("Global costmap cleared in %fs", (ros::WallTime::now() - t0).toSec()); + } + + t0 = ros::WallTime::now(); + if (affected_maps_ == "local" || affected_maps_ == "both") + { + clear(local_costmap_); + + if (force_updating_) + local_costmap_->updateMap(); + + ROS_DEBUG("Local costmap cleared in %fs", (ros::WallTime::now() - t0).toSec()); + } + } + + void ClearCostmapRecovery::clear(costmap_2d::Costmap2DROS *costmap) + { + std::vector> *plugins = costmap->getLayeredCostmap()->getPlugins(); + + geometry_msgs::PoseStamped pose; + + if (!costmap->getRobotPose(pose)) + { + ROS_ERROR("Cannot clear map because pose cannot be retrieved"); + return; + } + + double x = pose.pose.position.x; + double y = pose.pose.position.y; + + for (std::vector>::iterator pluginp = plugins->begin(); pluginp != plugins->end(); ++pluginp) + { + boost::shared_ptr plugin = *pluginp; + std::string name = plugin->getName(); + int slash = name.rfind('/'); + if (slash != std::string::npos) + { + name = name.substr(slash + 1); + } + + if (clearable_layers_.count(name) != 0) + { + // check if the value is convertable + if (!dynamic_cast(plugin.get())) + { + ROS_ERROR_STREAM("Layer " << name << " is not derived from costmap_2d::CostmapLayer"); + continue; + } + + boost::shared_ptr costmap; + costmap = boost::static_pointer_cast(plugin); + clearMap(costmap, x, y); + } + } + } + + void ClearCostmapRecovery::clearMap(boost::shared_ptr costmap, + double pose_x, double pose_y) + { + boost::unique_lock lock(*(costmap->getMutex())); + + double start_point_x = pose_x - reset_distance_ / 2; + double start_point_y = pose_y - reset_distance_ / 2; + double end_point_x = start_point_x + reset_distance_; + double end_point_y = start_point_y + reset_distance_; + + int start_x, start_y, end_x, end_y; + costmap->worldToMapNoBounds(start_point_x, start_point_y, start_x, start_y); + costmap->worldToMapNoBounds(end_point_x, end_point_y, end_x, end_y); + costmap->clearArea(start_x, start_y, end_x, end_y, invert_area_to_clear_); + + double ox = costmap->getOriginX(), oy = costmap->getOriginY(); + double width = costmap->getSizeInMetersX(), height = costmap->getSizeInMetersY(); + costmap->addExtraBounds(ox, oy, ox + width, oy + height); + return; + } + +}; diff --git a/navigations/clear_costmap_recovery/test/clear_tester.cpp b/navigations/clear_costmap_recovery/test/clear_tester.cpp new file mode 100755 index 0000000..4e89dbf --- /dev/null +++ b/navigations/clear_costmap_recovery/test/clear_tester.cpp @@ -0,0 +1,95 @@ +#include +#include +#include + +#include +#include + +tf2_ros::Buffer* transformer; +tf2_ros::TransformListener* tfl; + +using costmap_2d::LETHAL_OBSTACLE; + +void testClearBehavior(std::string name, + double distance, + bool obstacles, + bool static_map, + costmap_2d::Costmap2DROS* global_costmap, + costmap_2d::Costmap2DROS* local_costmap){ + clear_costmap_recovery::ClearCostmapRecovery clear = clear_costmap_recovery::ClearCostmapRecovery(); + + ros::NodeHandle clr("~/" + name); + clr.setParam("reset_distance", distance); + + std::vector clearable_layers; + if(obstacles) + clearable_layers.push_back( std::string("obstacles") ); + if(static_map) + clearable_layers.push_back( std::string("static_map") ); + + clr.setParam("layer_names", clearable_layers); + + clear.initialize(name, transformer, global_costmap, local_costmap); + + clear.runBehavior(); +} + +void testCountLethal(std::string name, double distance, bool obstacles, bool static_map, int global_lethal, int local_lethal=0) +{ + costmap_2d::Costmap2DROS global(name + "/global", *transformer); + costmap_2d::Costmap2DROS local(name + "/local" , *transformer); + boost::shared_ptr olayer; + + std::vector >* plugins = global.getLayeredCostmap()->getPlugins(); + for (std::vector >::iterator pluginp = plugins->begin(); pluginp != plugins->end(); ++pluginp) { + boost::shared_ptr plugin = *pluginp; + if(plugin->getName().find("obstacles")!=std::string::npos){ + olayer = boost::static_pointer_cast(plugin); + addObservation(&(*olayer), 5.0, 0.0, MAX_Z/2, 0, 0, MAX_Z/2); + addObservation(&(*olayer), 0.0, 5.0, MAX_Z/2, 0, 0, MAX_Z/2); + } + } + + global.updateMap(); + local.updateMap(); + olayer->clearStaticObservations(true, true); + + testClearBehavior("clear", distance, obstacles, static_map, &global, &local); + + global.updateMap(); + local.updateMap(); + + printMap(*global.getCostmap()); + ASSERT_EQ(countValues(*global.getCostmap(), LETHAL_OBSTACLE), global_lethal); + ASSERT_EQ(countValues( *local.getCostmap(), LETHAL_OBSTACLE), local_lethal); + +} + +TEST(ClearTester, basicTest){ + testCountLethal("base", 3.0, true, false, 20); +} + +TEST(ClearTester, bigRadiusTest){ + testCountLethal("base", 20.0, true, false, 22); +} + +TEST(ClearTester, clearNoLayersTest){ + testCountLethal("base", 20.0, false, false, 22); +} + +TEST(ClearTester, clearBothTest){ + testCountLethal("base", 3.0, true, true, 0); +} + +TEST(ClearTester, clearBothTest2){ + testCountLethal("base", 12.0, true, true, 6); +} + + +int main(int argc, char** argv){ + ros::init(argc, argv, "clear_tests"); + testing::InitGoogleTest(&argc, argv); + transformer = new tf2_ros::Buffer(ros::Duration(10)); + tfl = new tf2_ros::TransformListener(*transformer); + return RUN_ALL_TESTS(); +} diff --git a/navigations/clear_costmap_recovery/test/clear_tests.launch b/navigations/clear_costmap_recovery/test/clear_tests.launch new file mode 100755 index 0000000..acebad2 --- /dev/null +++ b/navigations/clear_costmap_recovery/test/clear_tests.launch @@ -0,0 +1,6 @@ + + + + + + diff --git a/navigations/clear_costmap_recovery/test/params.yaml b/navigations/clear_costmap_recovery/test/params.yaml new file mode 100755 index 0000000..7ebca4e --- /dev/null +++ b/navigations/clear_costmap_recovery/test/params.yaml @@ -0,0 +1,13 @@ +base: + global: + plugins: + - {name: static_map, type: "costmap_2d::StaticLayer"} + - {name: obstacles, type: "costmap_2d::ObstacleLayer"} + - {name: inflation, type: "costmap_2d::InflationLayer"} + obstacles: + track_unknown_space: true + local: + plugins: [] + robot_radius: .5 +clear: + clearing_distance: 7.0 diff --git a/navigations/costmap_2d b/navigations/costmap_2d new file mode 160000 index 0000000..f97f0e7 --- /dev/null +++ b/navigations/costmap_2d @@ -0,0 +1 @@ +Subproject commit f97f0e7f3f22c721e85a95b864a63a7a7e4833e8 diff --git a/navigations/costmap_converter/.gitlab-ci.yml b/navigations/costmap_converter/.gitlab-ci.yml new file mode 100755 index 0000000..9833056 --- /dev/null +++ b/navigations/costmap_converter/.gitlab-ci.yml @@ -0,0 +1,23 @@ +build-kinetic: + variables: + ROSDISTRO: "kinetic" + CATKIN_WS: "/root/catkin_ws" + stage: build + image: osrf/ros:$ROSDISTRO-desktop-full + before_script: + - apt-get -qq update + - apt-get -qq install git-core python-catkin-tools curl + - mkdir -p $CATKIN_WS/src + - cp -a . $CATKIN_WS/src/ + - cd $CATKIN_WS + - rosdep update + - rosdep install -y --from-paths src --ignore-src --rosdistro $ROSDISTRO --as-root=apt:false + script: + - source /ros_entrypoint.sh + - cd $CATKIN_WS + - catkin build -i -s --no-status + only: + - master + tags: + - ubuntu + - docker \ No newline at end of file diff --git a/navigations/costmap_converter/.travis.yml b/navigations/costmap_converter/.travis.yml new file mode 100755 index 0000000..dfa1f14 --- /dev/null +++ b/navigations/costmap_converter/.travis.yml @@ -0,0 +1,109 @@ +# Generic .travis.yml file for running continuous integration on Travis-CI with +# any ROS package. +# +# This installs ROS on a clean Travis-CI virtual machine, creates a ROS +# workspace, resolves all listed dependencies, and sets environment variables +# (setup.bash). Then, it compiles the entire ROS workspace (ensuring there are +# no compilation errors), and runs all the tests. If any of the compilation/test +# phases fail, the build is marked as a failure. +# +# We handle two types of package dependencies: +# - packages (ros and otherwise) available through apt-get. These are installed +# using rosdep, based on the information in the ROS package.xml. +# - dependencies that must be checked out from source. These are handled by +# 'wstool', and should be listed in a file named dependencies.rosinstall. +# +# There are two variables you may want to change: +# - ROS_DISTRO (default is indigo). Note that packages must be available for +# ubuntu 14.04 trusty. +# - ROSINSTALL_FILE (default is dependencies.rosinstall inside the repo +# root). This should list all necessary repositories in wstool format (see +# the ros wiki). If the file does not exists then nothing happens. +# +# See the README.md for more information. +# +# Author: Felix Duvallet + +# NOTE: The build lifecycle on Travis.ci is something like this: +# before_install +# install +# before_script +# script +# after_success or after_failure +# after_script +# OPTIONAL before_deploy +# OPTIONAL deploy +# OPTIONAL after_deploy + +################################################################################ + +# Use ubuntu trusty (14.04) with sudo privileges. +dist: trusty +sudo: required +language: + - generic +cache: + - apt + +# Configuration variables. All variables are global now, but this can be used to +# trigger a build matrix for different ROS distributions if desired. +env: + global: + - ROS_CI_DESKTOP="`lsb_release -cs`" # e.g. [precise|trusty|...] + - CI_SOURCE_PATH=$(pwd) + - ROSINSTALL_FILE=$CI_SOURCE_PATH/dependencies.rosinstall + - CATKIN_OPTIONS=$CI_SOURCE_PATH/catkin.options + - ROS_PARALLEL_JOBS='-j8 -l6' + matrix: + - ROS_DISTRO=indigo + - ROS_DISTRO=jade + + +################################################################################ + +# Install system dependencies, namely a very barebones ROS setup. +before_install: + - sudo sh -c "echo \"deb http://packages.ros.org/ros/ubuntu $ROS_CI_DESKTOP main\" > /etc/apt/sources.list.d/ros-latest.list" + - wget http://packages.ros.org/ros.key -O - | sudo apt-key add - + - sudo apt-get update -qq + - sudo apt-get install -y python-catkin-pkg python-rosdep python-wstool ros-$ROS_DISTRO-catkin + - source /opt/ros/$ROS_DISTRO/setup.bash + # Prepare rosdep to install dependencies. + - sudo rosdep init + - rosdep update + +# Create a catkin workspace with the package under integration. +install: + - mkdir -p ~/catkin_ws/src + - cd ~/catkin_ws/src + - catkin_init_workspace + # Create the devel/setup.bash (run catkin_make with an empty workspace) and + # source it to set the path variables. + - cd ~/catkin_ws + - catkin_make + - source devel/setup.bash + # Add the package under integration to the workspace using a symlink. + - cd ~/catkin_ws/src + - ln -s $CI_SOURCE_PATH . + +# Install all dependencies, using wstool and rosdep. +# wstool looks for a ROSINSTALL_FILE defined in the environment variables. +before_script: + # source dependencies: install using wstool. + - cd ~/catkin_ws/src + - wstool init + - if [[ -f $ROSINSTALL_FILE ]] ; then wstool merge $ROSINSTALL_FILE ; fi + - wstool up + # package depdencies: install using rosdep. + - cd ~/catkin_ws + - rosdep install -y --from-paths src --ignore-src --rosdistro $ROS_DISTRO + +# Compile and test. If the CATKIN_OPTIONS file exists, use it as an argument to +# catkin_make. +script: + - cd ~/catkin_ws + - catkin_make $( [ -f $CATKIN_OPTIONS ] && cat $CATKIN_OPTIONS ) + # Testing: Use both run_tests (to see the output) and test (to error out). + - catkin_make run_tests # This always returns 0, but looks pretty. + - catkin_make test # This will return non-zero if a test fails. + diff --git a/navigations/costmap_converter/CHANGELOG.rst b/navigations/costmap_converter/CHANGELOG.rst new file mode 100755 index 0000000..a0d3f14 --- /dev/null +++ b/navigations/costmap_converter/CHANGELOG.rst @@ -0,0 +1,95 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package costmap_converter +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +0.0.13 (2020-05-13) +------------------- +* Changed minimum CMake version to 3.1 +* Fixed wrong return type of method pointToNeighborCells +* OpenCV 4 compatibility fix (Thanks to daviddudas) +* Contributors: Christoph Rösmann, daviddudas + +0.0.12 (2019-12-02) +------------------- +* CostmapToPolygons: Simplification of the polygon by Douglas-Peucker algorithm (reduces the density of points in the polygon). +* Bugfixes +* Contributors: Rainer Kümmerle + +0.0.11 (2019-10-26) +------------------- +* rostest integration to avoid running a roscore separately for unit testing +* Contributors: Christoph Rösmann + +0.0.10 (2019-10-26) +------------------- +* Runtime improvements for CostmapToPolygonsDBSMCCH (`#12 `_) + * Grid lookup for regionQuery + * use a grid structure for looking up nearest neighbors + * parameters in a struct + * guard the parameters by drawing a copy from dynamic reconfigure + * Adding some test cases for regionQuery and dbScan + * Avoid computing sqrt at the end of convexHull2 + * Add doxygen comments for the neighbor lookup + * Change the param read to one liners + * Add test on empty map for dbScan +* Contributors: Rainer Kümmerle + +0.0.9 (2018-05-28) +------------------ +* Moved plugin loader for static costmap conversion to BaseCostmapToDynamicObstacles. + The corresponding ROS parameter `static_converter_plugin` is now defined in the CostmapToDynamicObstacles namespace. +* Contributors: Christoph Rösmann + +0.0.8 (2018-05-17) +------------------ +* Standalone converter subscribes now to costmap updates. Fixes `#1 `_ +* Adds radius field for circular obstacles to ObstacleMsg +* Stacked costmap conversion (`#7 `_). + E.g., it is now possible combine a dynamic obstacle and static obstacle converter plugin. +* Contributors: Christoph Rösmann, Franz Albers + +0.0.7 (2017-09-20) +------------------ +* Fixed some compilation issues (C++11 compiler flags and opencv2 on indigo/jade). +* Dynamic obstacle plugin: obstacle velocity is now published for both x and y coordinates rather than the absolute value + +0.0.6 (2017-09-18) +------------------ +* This pull request adds the costmap to dynamic obstacles plugin (written by Franz Albers). + It detects the dynamic foreground of the costmap (based on the temporal evolution of the costmap) + including blobs representing the obstacles. Furthermore, Kalman-based tracking is applied to estimate + the current velocity for each obstacle. + **Note, this plugin is still experimental.** +* New message types are introduced: costmap\_converter::ObstacleMsg and costmap\_converter::ObstacleArrayMsg. + These types extend the previous polygon representation by additional velocity, orientation and id information. +* The API has been extended to provide obstacles via the new ObstacleArrayMsg type instead of vector of polygons. +* Contributors: Franz Albers, Christoph Rösmann + +0.0.5 (2016-02-01) +------------------ +* Major changes regarding the line detection based on the convex hull + (it should be much more robust now). +* Concave hull plugin added. +* The cluster size can now be limited from above using a specific parameter. + This implicitly avoids large clusters forming a 'L' or 'U'. +* All parameters can now be adjusted using dynamic_reconfigure (rqt_reconfigure). +* Some parameter names changed. +* Line plugin based on ransac: line inliers must now be placed inbetween the start and end of a line. + +0.0.4 (2016-01-11) +------------------ +* Fixed conversion from map to world coordinates if the costmap is not quadratic. + +0.0.3 (2015-12-23) +------------------ +* The argument list of the initialize method requires a nodehandle from now on. This facilitates the handling of parameter namespaces for multiple instantiations of the plugin. +* This change is pushed immediately as a single release to avoid API breaks (since version 0.0.2 is not on the official repos up to now). + +0.0.2 (2015-12-22) +------------------ +* Added a plugin for converting the costmap to lines using ransac + +0.0.1 (2015-12-21) +------------------ +* First release of the package including a pluginlib interface, two plugins (costmap to polygons and costmap to lines) and a standalone conversion node. + diff --git a/navigations/costmap_converter/CMakeLists.txt b/navigations/costmap_converter/CMakeLists.txt new file mode 100755 index 0000000..9ae9e9a --- /dev/null +++ b/navigations/costmap_converter/CMakeLists.txt @@ -0,0 +1,244 @@ +cmake_minimum_required(VERSION 3.1) +project(costmap_converter) + +# Set to Release in order to speed up the program significantly +set(CMAKE_BUILD_TYPE Release) #None, Debug, Release, RelWithDebInfo, MinSizeRel +## Find catkin macros and libraries +## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) +## is used, also find other catkin packages +find_package(catkin REQUIRED COMPONENTS + geometry_msgs + roscpp + std_msgs + message_generation + costmap_2d + dynamic_reconfigure + pluginlib + cv_bridge +) + +## System dependencies are found with CMake's conventions +# find_package(Boost REQUIRED COMPONENTS system) +find_package(OpenCV REQUIRED) + +###set(CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}) +###find_package(Eigen3 REQUIRED) +###set(EXTERNAL_INCLUDE_DIRS ${Eigen3_INCLUDE_DIRS}) + +if (CATKIN_ENABLE_TESTING) + find_package(rostest REQUIRED) +endif() + +## Uncomment this if the package has a setup.py. This macro ensures +## modules and global scripts declared therein get installed +## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html +# catkin_python_setup() + +## C++11 support +IF(NOT MSVC) + include(CheckCXXCompilerFlag) + CHECK_CXX_COMPILER_FLAG("-std=c++11" COMPILER_SUPPORTS_CXX11) + CHECK_CXX_COMPILER_FLAG("-std=c++0x" COMPILER_SUPPORTS_CXX0X) +if(COMPILER_SUPPORTS_CXX11) + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11") +elseif(COMPILER_SUPPORTS_CXX0X) + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++0x") +else() + message(STATUS "The compiler ${CMAKE_CXX_COMPILER} has no C++11 support which is required + by linked third party packages starting from ROS Jade. Ignore this message for ROS Indigo.") +endif() +endif() + +################################################ +## Declare ROS messages, services and actions ## +################################################ + +## To declare and build messages, services or actions from within this +## package, follow these steps: +## * Let MSG_DEP_SET be the set of packages whose message types you use in +## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...). +## * In the file package.xml: +## * add a build_depend and a run_depend tag for each package in MSG_DEP_SET +## * If MSG_DEP_SET isn't empty the following dependencies might have been +## pulled in transitively but can be declared for certainty nonetheless: +## * add a build_depend tag for "message_generation" +## * add a run_depend tag for "message_runtime" +## * In this file (CMakeLists.txt): +## * add "message_generation" and every package in MSG_DEP_SET to +## find_package(catkin REQUIRED COMPONENTS ...) +## * add "message_runtime" and every package in MSG_DEP_SET to +## catkin_package(CATKIN_DEPENDS ...) +## * uncomment the add_*_files sections below as needed +## and list every .msg/.srv/.action file to be processed +## * uncomment the generate_messages entry below +## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...) + +## Generate messages in the 'msg' folder +add_message_files( + FILES + ObstacleMsg.msg + ObstacleArrayMsg.msg +) + +## Generate services in the 'srv' folder +# add_service_files( +# FILES +# Service1.srv +# Service2.srv +# ) + +## Generate actions in the 'action' folder +# add_action_files( +# FILES +# Action1.action +# Action2.action +# ) + +## Generate added messages and services with any dependencies listed here +generate_messages( + DEPENDENCIES + geometry_msgs std_msgs +) + +#add dynamic reconfigure api +#find_package(catkin REQUIRED dynamic_reconfigure) +generate_dynamic_reconfigure_options( + cfg/dynamic_reconfigure/CostmapToPolygonsDBSMCCH.cfg + cfg/dynamic_reconfigure/CostmapToPolygonsDBSConcaveHull.cfg + cfg/dynamic_reconfigure/CostmapToLinesDBSMCCH.cfg + cfg/dynamic_reconfigure/CostmapToLinesDBSRANSAC.cfg + cfg/dynamic_reconfigure/CostmapToDynamicObstacles.cfg +) + +################################### +## catkin specific configuration ## +################################### +## The catkin_package macro generates cmake config files for your package +## Declare things to be passed to dependent projects +## INCLUDE_DIRS: uncomment this if you package contains header files +## LIBRARIES: libraries you create in this project that dependent projects also need +## CATKIN_DEPENDS: catkin_packages dependent projects also need +## DEPENDS: system dependencies of this project that dependent projects also need +catkin_package( + INCLUDE_DIRS include + LIBRARIES costmap_converter + CATKIN_DEPENDS + geometry_msgs + pluginlib + roscpp + std_msgs + message_runtime + dynamic_reconfigure + costmap_2d + #DEPENDS +) + +########### +## Build ## +########### + +## Specify additional locations of header files +## Your package locations should be listed before other locations +# include_directories(include) +include_directories( + include + ${catkin_INCLUDE_DIRS} + ${OpenCV_INCLUDE_DIRS} +) + +## Declare a cpp library +add_library(costmap_converter src/costmap_to_polygons.cpp + src/costmap_to_polygons_concave.cpp + src/costmap_to_lines_convex_hull.cpp + src/costmap_to_lines_ransac.cpp + src/costmap_to_dynamic_obstacles/costmap_to_dynamic_obstacles.cpp + src/costmap_to_dynamic_obstacles/background_subtractor.cpp + src/costmap_to_dynamic_obstacles/blob_detector.cpp + src/costmap_to_dynamic_obstacles/multitarget_tracker/Ctracker.cpp + src/costmap_to_dynamic_obstacles/multitarget_tracker/Kalman.cpp + src/costmap_to_dynamic_obstacles/multitarget_tracker/HungarianAlg.cpp +) +target_link_libraries(costmap_converter ${catkin_LIBRARIES} ${OpenCV_LIBRARIES}) +# target_compile_features(costmap_converter PUBLIC cxx_nullptr cxx_range_for) + +# Dynamic reconfigure: make sure configure headers raare built before any node using them +add_dependencies(costmap_converter ${PROJECT_NAME}_gencfg) +# Generate messages before compiling the lib +add_dependencies(costmap_converter ${PROJECT_NAME}_generate_messages_cpp) + +## Declare a cpp executable +add_executable(standalone_converter src/costmap_converter_node.cpp) +target_link_libraries(standalone_converter ${catkin_LIBRARIES} ) +add_dependencies(standalone_converter costmap_converter) + +# (un)set: cmake -DCVV_DEBUG_MODE=OFF .. +option(CVV_DEBUG_MODE "cvvisual-debug-mode" ON) +if(CVV_DEBUG_MODE MATCHES ON) + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -DCVVISUAL_DEBUGMODE") +endif() + + + +############# +## Install ## +############# + +# all install targets should use catkin DESTINATION variables +# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html + +## Mark executable scripts (Python etc.) for installation +## in contrast to setup.py, you can choose the destination +# install(PROGRAMS +# scripts/my_python_script +# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + +## Mark executables and/or libraries for installation + +## Mark executables and/or libraries for installation +install(TARGETS costmap_converter + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +) +install(TARGETS standalone_converter + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) + +## Mark cpp header files for installation +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} + #FILES_MATCHING PATTERN "*.h" + PATTERN ".svn" EXCLUDE +) + +## Mark other files for installation (e.g. launch and bag files, etc.) +install(FILES + plugins.xml + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) + +install(DIRECTORY + cfg + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} + PATTERN ".svn" EXCLUDE +) + + +############# +## Testing ## +############# + +if (CATKIN_ENABLE_TESTING) + add_rostest_gtest(test_costmap_polygons test/costmap_polygons.test test/costmap_polygons.cpp) + if(TARGET test_costmap_polygons) + target_link_libraries(test_costmap_polygons costmap_converter) + endif() +endif() + +## Add gtest based cpp test target and link libraries +# catkin_add_gtest(${PROJECT_NAME}-test test/test_drawing.cpp) +# if(TARGET ${PROJECT_NAME}-test) +# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME}) +# endif() + +## Add folders to be run by python nosetests +# catkin_add_nosetests(test) diff --git a/navigations/costmap_converter/README.md b/navigations/costmap_converter/README.md new file mode 100755 index 0000000..9e3fd2a --- /dev/null +++ b/navigations/costmap_converter/README.md @@ -0,0 +1,30 @@ +costmap_converter ROS Package +============================= + +A ros package that includes plugins and nodes to convert occupied costmap2d cells to primitive types + +Build status of the *master* branch: +- ROS Buildfarm Noetic: [![Noetic Build Status](http://build.ros.org/buildStatus/icon?job=Ndev__costmap_converter__ubuntu_focal_amd64)](http://build.ros.org/job/Ndev__costmap_converter__ubuntu_focal_amd64/) +- ROS Buildfarm Melodic: [![Melodic Build Status](http://build.ros.org/buildStatus/icon?job=Mdev__costmap_converter__ubuntu_bionic_amd64)](http://build.ros.org/job/Mdev__costmap_converter__ubuntu_bionic_amd64/) + + +### Contributors + +- Christoph Rösmann +- Franz Albers (*CostmapToDynamicObstacles* plugin) +- Otniel Rinaldo + + +### License + +The *costmap_converter* package is licensed under the BSD license. +It depends on other ROS packages, which are listed in the package.xml. They are also BSD licensed. + +Some third-party dependencies are included that are licensed under different terms: + - *MultitargetTracker*, GNU GPLv3, https://github.com/Smorodov/Multitarget-tracker + (partially required for the *CostmapToDynamicObstacles* plugin) + +All packages included are distributed in the hope that they will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the licenses for more details. + + + diff --git a/navigations/costmap_converter/cfg/dynamic_reconfigure/CostmapToDynamicObstacles.cfg b/navigations/costmap_converter/cfg/dynamic_reconfigure/CostmapToDynamicObstacles.cfg new file mode 100755 index 0000000..7e18a9e --- /dev/null +++ b/navigations/costmap_converter/cfg/dynamic_reconfigure/CostmapToDynamicObstacles.cfg @@ -0,0 +1,136 @@ +#!/usr/bin/env python + +from dynamic_reconfigure.parameter_generator_catkin import * + +gen = ParameterGenerator() + +# For integers and doubles: +# Name Type Reconfiguration level +# Description +# Default Min Max + +################################################################## +###################### Foreground detection ###################### +gen.add("alpha_slow", double_t, 0, + "Foreground detection: Learning rate of the slow filter", + 0.3, 0.0, 1.0) + +gen.add("alpha_fast", double_t, 0, + "Foreground detection: Learning rate of the fast filter", + 0.85, 0.0, 1.0) + +gen.add("beta", double_t, 0, + "Foreground detection: Weighting coefficient between a pixels value and the mean of its nearest neighbors", + 0.85, 0.0, 1.0) + +gen.add("min_sep_between_slow_and_fast_filter", int_t, 0, + "Foreground detection: Minimal difference between the fast and the slow filter to recognize a obstacle as dynamic", + 80, 0, 255) + +gen.add("min_occupancy_probability", int_t, 0, + "Foreground detection: Minimal value of the fast filter to recognize a obstacle as dynamic", + 180, 0, 255) + +gen.add("max_occupancy_neighbors", int_t, 0, + "Foreground detection: Maximal mean value of the nearest neighbors of a pixel in the slow filter", + 80, 0, 255) + +gen.add("morph_size", int_t, 0, + "Foreground detection: Size of the structuring element for the closing operation", + 1, 0, 10) + +gen.add("publish_static_obstacles", bool_t, 0, + "Include static obstacles as single-point polygons", + True) + +############################################################ +###################### Blob detection ###################### + +# These parameters are commented out, because the input image for the blob detection is already binary -> irrelevant +#gen.add("threshold_step", double_t, 0, +# "Blob detection: Distance between neighboring thresholds", +# 256.0, 0.0, 256.0) +# +#gen.add("min_threshold", double_t, 0, +# "Blob detection: Convert the source image to binary images by applying several thresholds, starting at min_threshold", +# 1, 0, 255) +# +#gen.add("max_threshold", double_t, 0, +# "Blob detection: Convert the source image to binary images by applying several thresholds, ending at max_threshold", +# 255, 0, 255) +# +#gen.add("min_repeatability", int_t, 0, +# "Blob detection: Minimal number of detections of a blob in the several thresholds to be considered as real blob", +# 1, 1, 10) +# +gen.add("min_distance_between_blobs", double_t, 0, + "Blob detection: Minimal distance between centers of two blobs to be considered as seperate blobs", + 10, 0.0, 300.0) + +gen.add("filter_by_area", bool_t, 0, + "Blob detection: Filter blobs based on number of pixels", + True) + +gen.add("min_area", int_t, 0, + "Blob detection: Minimal number of pixels a blob consists of", + 3, 0, 300) + +gen.add("max_area", int_t, 0, + "Blob detection: Maximal number of pixels a blob consists of", + 300, 0, 300) + +gen.add("filter_by_circularity", bool_t, 0, + "Blob detection: Filter blobs based on their circularity", + True) + +gen.add("min_circularity", double_t, 0, + "Blob detection: Minimal circularity value (0 in case of a line)", + 0.2, 0.0, 1.0) + +gen.add("max_circularity", double_t, 0, + "Blob detection: Maximal circularity value (1 in case of a circle)", + 1.0, 0.0, 1.0) + +gen.add("filter_by_inertia", bool_t, 0, + "Blob detection: Filter blobs based on their inertia ratio", + True) + +gen.add("min_inertia_ratio", double_t, 0, + "Blob detection: Minimal inertia ratio", + 0.2, 0.0, 1.0) + +gen.add("max_inertia_ratio", double_t, 0, + "Blob detection: Maximal inertia ratio", + 1.0, 0.0, 1.0) + +gen.add("filter_by_convexity", bool_t, 0, + "Blob detection: Filter blobs based on their convexity (Blob area / area of its convex hull)", + False) + +gen.add("min_convexity", double_t, 0, + "Blob detection: Minimum convexity ratio", + 0.0, 0.0, 1.0) + +gen.add("max_convexity", double_t, 0, + "Blob detection: Maximal convexity ratio", + 1.0, 0.0, 1.0) + +################################################################ +#################### Tracking ################################## +gen.add("dt", double_t, 0, + "Tracking: Time for one timestep of the kalman filter", + 0.2, 0.1, 3.0) + +gen.add("dist_thresh", double_t, 0, + "Tracking: Maximum distance between two points to be considered in the assignment problem", + 20.0, 0.0, 150.0) + +gen.add("max_allowed_skipped_frames", int_t, 0, + "Tracking: Maximum number of frames a object is tracked while it is not seen", + 3, 0, 10) + +gen.add("max_trace_length", int_t, 0, + "Tracking: Maximum number of Points in a objects trace", + 10, 1, 100) + +exit(gen.generate("costmap_converter", "standalone_converter", "CostmapToDynamicObstacles")) diff --git a/navigations/costmap_converter/cfg/dynamic_reconfigure/CostmapToLinesDBSMCCH.cfg b/navigations/costmap_converter/cfg/dynamic_reconfigure/CostmapToLinesDBSMCCH.cfg new file mode 100755 index 0000000..1dd917c --- /dev/null +++ b/navigations/costmap_converter/cfg/dynamic_reconfigure/CostmapToLinesDBSMCCH.cfg @@ -0,0 +1,41 @@ +#!/usr/bin/env python + +from dynamic_reconfigure.parameter_generator_catkin import * + +gen = ParameterGenerator() + +# For integers and doubles: +# Name Type Reconfiguration level +# Description +# Default Min Max + + +gen.add("cluster_max_distance", double_t, 0, + "Parameter for DB_Scan, maximum distance to neighbors [m]", + 0.4, 0.0, 10.0) + +gen.add("cluster_min_pts", int_t, 0, + "Parameter for DB_Scan: minimum number of points that define a cluster", + 2, 1, 20) + +gen.add("cluster_max_pts", int_t, 0, + "Parameter for DB_Scan: maximum number of points that define a cluster (limit cluster size to avoid large L- and U-shapes)", + 30, 2, 200) + +gen.add("convex_hull_min_pt_separation", double_t, 0, + "Clear keypoints of the convex polygon that are close to each other [distance in meters] (0: keep all)", + 0.1, 0.0, 10.0) + +gen.add("support_pts_max_dist", double_t, 0, + "Minimum distance from a point to the line to be counted as support point", + 0.3, 0.0, 10.0) + +gen.add("support_pts_max_dist_inbetween", double_t, 0, + "A line is only defined, if the distance between two consecutive support points is less than this treshold. Set to 0 in order to deactivate this check.", + 1.0, 0.0, 10.0) + +gen.add("min_support_pts", int_t, 0, + "Minimum number of support points to represent a line", + 2, 0, 50) + +exit(gen.generate("costmap_converter", "standalone_converter", "CostmapToLinesDBSMCCH")) diff --git a/navigations/costmap_converter/cfg/dynamic_reconfigure/CostmapToLinesDBSRANSAC.cfg b/navigations/costmap_converter/cfg/dynamic_reconfigure/CostmapToLinesDBSRANSAC.cfg new file mode 100755 index 0000000..2c5b322 --- /dev/null +++ b/navigations/costmap_converter/cfg/dynamic_reconfigure/CostmapToLinesDBSRANSAC.cfg @@ -0,0 +1,54 @@ +#!/usr/bin/env python + +from dynamic_reconfigure.parameter_generator_catkin import * + +gen = ParameterGenerator() + +# For integers and doubles: +# Name Type Reconfiguration level +# Description +# Default Min Max + + +gen.add("cluster_max_distance", double_t, 0, + "Parameter for DB_Scan, maximum distance to neighbors [m]", + 0.4, 0.0, 10.0) + +gen.add("cluster_min_pts", int_t, 0, + "Parameter for DB_Scan: minimum number of points that define a cluster", + 2, 1, 20) + +gen.add("cluster_max_pts", int_t, 0, + "Parameter for DB_Scan: maximum number of points that define a cluster (limit cluster size to avoid large L- and U-shapes)", + 30, 2, 200) + +gen.add("ransac_inlier_distance", double_t, 0, + "Maximum distance to the line segment for inliers", + 0.2, 0.0, 10.0) + +gen.add("ransac_min_inliers", int_t, 0, + "Minimum numer of inliers required to form a line", + 10, 0, 100) + +gen.add("ransac_no_iterations", int_t, 0, + "Number of ransac iterations", + 2000, 1, 10000) + +gen.add("ransac_remainig_outliers", int_t, 0, + "Repeat ransac until the number of outliers is as specified here", + 3, 0, 50) + +gen.add("ransac_convert_outlier_pts", bool_t, 0, + "Convert remaining outliers to single points.", + True) + +gen.add("ransac_filter_remaining_outlier_pts", bool_t, 0, + "Filter the interior of remaining outliers and keep only keypoints of their convex hull", + False) + +gen.add("convex_hull_min_pt_separation", double_t, 0, + "Clear keypoints of the convex polygon that are close to each other [distance in meters] (0: keep all)", + 0.1, 0.0, 10.0) + + +exit(gen.generate("costmap_converter", "standalone_converter", "CostmapToLinesDBSRANSAC")) diff --git a/navigations/costmap_converter/cfg/dynamic_reconfigure/CostmapToPolygonsDBSConcaveHull.cfg b/navigations/costmap_converter/cfg/dynamic_reconfigure/CostmapToPolygonsDBSConcaveHull.cfg new file mode 100755 index 0000000..7e4d49f --- /dev/null +++ b/navigations/costmap_converter/cfg/dynamic_reconfigure/CostmapToPolygonsDBSConcaveHull.cfg @@ -0,0 +1,33 @@ +#!/usr/bin/env python + +from dynamic_reconfigure.parameter_generator_catkin import * + +gen = ParameterGenerator() + +# For integers and doubles: +# Name Type Reconfiguration level +# Description +# Default Min Max + + +gen.add("cluster_max_distance", double_t, 0, + "Parameter for DB_Scan, maximum distance to neighbors [m]", + 0.4, 0.0, 10.0) + +gen.add("cluster_min_pts", int_t, 0, + "Parameter for DB_Scan: minimum number of points that define a cluster", + 2, 1, 20) + +gen.add("cluster_max_pts", int_t, 0, + "Parameter for DB_Scan: maximum number of points that define a cluster (limit cluster size to avoid large L- and U-shapes)", + 30, 2, 200) + +gen.add("convex_hull_min_pt_separation", double_t, 0, + "Clear keypoints of the convex polygon that are close to each other [distance in meters] (0: keep all)", + 0.1, 0.0, 10.0) + +gen.add("concave_hull_depth", double_t, 0, + "Smaller depth: sharper surface, depth -> high value: convex hull", + 2.0, 0.0, 100.0) + +exit(gen.generate("costmap_converter", "standalone_converter", "CostmapToPolygonsDBSConcaveHull")) diff --git a/navigations/costmap_converter/cfg/dynamic_reconfigure/CostmapToPolygonsDBSMCCH.cfg b/navigations/costmap_converter/cfg/dynamic_reconfigure/CostmapToPolygonsDBSMCCH.cfg new file mode 100755 index 0000000..d5cc11a --- /dev/null +++ b/navigations/costmap_converter/cfg/dynamic_reconfigure/CostmapToPolygonsDBSMCCH.cfg @@ -0,0 +1,29 @@ +#!/usr/bin/env python + +from dynamic_reconfigure.parameter_generator_catkin import * + +gen = ParameterGenerator() + +# For integers and doubles: +# Name Type Reconfiguration level +# Description +# Default Min Max + + +gen.add("cluster_max_distance", double_t, 0, + "Parameter for DB_Scan, maximum distance to neighbors [m]", + 0.4, 0.0, 10.0) + +gen.add("cluster_min_pts", int_t, 0, + "Parameter for DB_Scan: minimum number of points that define a cluster", + 2, 1, 20) + +gen.add("cluster_max_pts", int_t, 0, + "Parameter for DB_Scan: maximum number of points that define a cluster (limit cluster size to avoid large L- and U-shapes)", + 30, 2, 200) + +gen.add("convex_hull_min_pt_separation", double_t, 0, + "Clear keypoints of the convex polygon that are close to each other [distance in meters] (0: keep all)", + 0.1, 0.0, 10.0) + +exit(gen.generate("costmap_converter", "standalone_converter", "CostmapToPolygonsDBSMCCH")) diff --git a/navigations/costmap_converter/include/costmap_converter/costmap_converter_interface.h b/navigations/costmap_converter/include/costmap_converter/costmap_converter_interface.h new file mode 100755 index 0000000..922180a --- /dev/null +++ b/navigations/costmap_converter/include/costmap_converter/costmap_converter_interface.h @@ -0,0 +1,368 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2016 + * TU Dortmund - Institute of Control Theory and Systems Engineering. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the institute nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: Christoph Rösmann, Otniel Rinaldo + *********************************************************************/ + +#ifndef COSTMAP_CONVERTER_INTERFACE_H_ +#define COSTMAP_CONVERTER_INTERFACE_H_ + +//#include +#include +#include +#include +#include +#include +#include +#include + + +namespace costmap_converter +{ +//! Typedef for a shared dynamic obstacle container +typedef boost::shared_ptr ObstacleArrayPtr; +//! Typedef for a shared dynamic obstacle container (read-only access) +typedef boost::shared_ptr< const ObstacleArrayMsg > ObstacleArrayConstPtr; + +//! Typedef for a shared polygon container +typedef boost::shared_ptr< std::vector > PolygonContainerPtr; +//! Typedef for a shared polygon container (read-only access) +typedef boost::shared_ptr< const std::vector > PolygonContainerConstPtr; + + +/** + * @class BaseCostmapToPolygons + * @brief This abstract class defines the interface for plugins that convert the costmap into polygon types + * + * Plugins must accept a costmap_2d::Costmap2D datatype as information source. + * The interface provides two different use cases: + * 1. Manual call to conversion routines: setCostmap2D(), compute() and getPolygons() + * (in subsequent calls setCostmap2D() can be substituted by updateCostmap2D()) + * 2. Repeatedly process costmap with a specific rate (startWorker() and stopWorker()): + * Make sure that the costmap is valid while the worker is active (you can specify your own spinner or activate a threaded spinner). + * Costmaps can be obtained by invoking getPolygons(). + */ +class BaseCostmapToPolygons +{ +public: + + /** + * @brief Initialize the plugin + * @param nh Nodehandle that defines the namespace for parameters + */ + virtual void initialize(ros::NodeHandle nh) = 0; + + /** + * @brief Destructor + */ + virtual ~BaseCostmapToPolygons() + { + stopWorker(); + } + + + /** + * @brief Pass a pointer to the costap to the plugin. + * @warning The plugin should handle the costmap's mutex locking. + * @sa updateCostmap2D + * @param costmap Pointer to the costmap2d source + */ + virtual void setCostmap2D(costmap_2d::Costmap2D* costmap) = 0; + + /** + * @brief Get updated data from the previously set Costmap2D + * @warning The plugin should handle the costmap's mutex locking. + * @sa setCostmap2D + */ + virtual void updateCostmap2D() = 0; + + /** + * @brief This method performs the actual work (conversion of the costmap to polygons) + */ + virtual void compute() = 0; + + /** + * @brief Get a shared instance of the current polygon container + * + * If this method is not implemented by any subclass (plugin) the returned shared + * pointer is empty. + * @remarks If compute() or startWorker() has not been called before, this method returns an empty instance! + * @warning The underlying plugin must ensure that this method is thread safe. + * @return Shared instance of the current polygon container + */ + virtual PolygonContainerConstPtr getPolygons(){return PolygonContainerConstPtr();} + + /** + * @brief Get a shared instance of the current obstacle container + * If this method is not overwritten by the underlying plugin, the obstacle container just imports getPolygons(). + * @remarks If compute() or startWorker() has not been called before, this method returns an empty instance! + * @warning The underlying plugin must ensure that this method is thread safe. + * @return Shared instance of the current obstacle container + * @sa getPolygons + */ + virtual ObstacleArrayConstPtr getObstacles() + { + ObstacleArrayPtr obstacles = boost::make_shared(); + PolygonContainerConstPtr polygons = getPolygons(); + if (polygons) + { + for (const geometry_msgs::Polygon& polygon : *polygons) + { + obstacles->obstacles.emplace_back(); + obstacles->obstacles.back().polygon = polygon; + } + } + return obstacles; + } + + /** + * @brief Set name of robot's odometry topic + * + * Some plugins might require odometry information + * to compensate the robot's ego motion + * @param odom_topic topic name + */ + virtual void setOdomTopic(const std::string& odom_topic) {} + + /** + * @brief Determines whether an additional plugin for subsequent costmap conversion is specified + * + * @return false, since all plugins for static costmap conversion are independent + */ + virtual bool stackedCostmapConversion() {return false;} + + /** + * @brief Instantiate a worker that repeatedly coverts the most recent costmap to polygons. + * The worker is implemented as a timer event that is invoked at a specific \c rate. + * The passed \c costmap pointer must be valid at the complete time and must be lockable. + * By specifying the argument \c spin_thread the timer event is invoked in a separate + * thread and callback queue or otherwise it is called from the global callback queue (of the + * node in which the plugin is used). + * @param rate The rate that specifies how often the costmap should be updated + * @param costmap Pointer to the underlying costmap (must be valid and lockable as long as the worker is active + * @param spin_thread if \c true,the timer is invoked in a separate thread, otherwise in the default callback queue) + */ + void startWorker(ros::Rate rate, costmap_2d::Costmap2D* costmap, bool spin_thread = false) + { + setCostmap2D(costmap); + + if (spin_thread_) + { + { + boost::mutex::scoped_lock terminate_lock(terminate_mutex_); + need_to_terminate_ = true; + } + spin_thread_->join(); + delete spin_thread_; + } + + if (spin_thread) + { + ROS_DEBUG_NAMED("costmap_converter", "Spinning up a thread for the CostmapToPolygons plugin"); + need_to_terminate_ = false; + spin_thread_ = new boost::thread(boost::bind(&BaseCostmapToPolygons::spinThread, this)); + nh_.setCallbackQueue(&callback_queue_); + } + else + { + spin_thread_ = NULL; + nh_.setCallbackQueue(ros::getGlobalCallbackQueue()); + } + + worker_timer_ = nh_.createTimer(rate, &BaseCostmapToPolygons::workerCallback, this); + } + + /** + * @brief Stop the worker that repeatedly converts the costmap to polygons + */ + void stopWorker() + { + worker_timer_.stop(); + if (spin_thread_) + { + { + boost::mutex::scoped_lock terminate_lock(terminate_mutex_); + need_to_terminate_ = true; + } + spin_thread_->join(); + delete spin_thread_; + } + } + +protected: + + /** + * @brief Protected constructor that should be called by subclasses + */ + BaseCostmapToPolygons() : nh_("~costmap_to_polygons"), spin_thread_(NULL), need_to_terminate_(false) {} + + /** + * @brief Blocking method that checks for new timer events (active if startWorker() is called with spin_thread enabled) + */ + void spinThread() + { + while (nh_.ok()) + { + { + boost::mutex::scoped_lock terminate_lock(terminate_mutex_); + if (need_to_terminate_) + break; + } + callback_queue_.callAvailable(ros::WallDuration(0.1f)); + } + } + + /** + * @brief The callback of the worker that performs the actual work (updating the costmap and converting it to polygons) + */ + void workerCallback(const ros::TimerEvent&) + { + updateCostmap2D(); + compute(); + } + +private: + ros::Timer worker_timer_; + ros::NodeHandle nh_; + boost::thread* spin_thread_; + ros::CallbackQueue callback_queue_; + boost::mutex terminate_mutex_; + bool need_to_terminate_; +}; + + +/** + * @class BaseCostmapToDynamicPolygons + * @brief This class extends the BaseCostmapToPolygongs class for dynamic costmap conversion plugins in order to incorporate a subsequent costmap converter plugin for static obstacles + * + * This class should not be instantiated. + */ +class BaseCostmapToDynamicObstacles : public BaseCostmapToPolygons +{ +public: + + /** + * @brief Load underlying static costmap conversion plugin via plugin-loader + * @param plugin_name Exact class name of the plugin to be loaded, e.g. + * costmap_converter::CostmapToPolygonsDBSMCCH + * @param nh_parent NodeHandle which is extended by the namespace of the static conversion plugin + */ + void loadStaticCostmapConverterPlugin(const std::string& plugin_name, ros::NodeHandle nh_parent) + { + try + { + static_costmap_converter_ = static_converter_loader_.createInstance(plugin_name); + + if(boost::dynamic_pointer_cast(static_costmap_converter_)) + { + throw pluginlib::PluginlibException("The specified plugin for static costmap conversion is a dynamic plugin. Specify a static plugin."); + } + std::string raw_plugin_name = static_converter_loader_.getName(plugin_name); + static_costmap_converter_->initialize(ros::NodeHandle(nh_parent, raw_plugin_name)); + setStaticCostmapConverterPlugin(static_costmap_converter_); + ROS_INFO_STREAM("CostmapToDynamicObstacles: underlying costmap conversion plugin for static obstacles " << plugin_name << " loaded."); + } + catch(const pluginlib::PluginlibException& ex) + { + ROS_WARN("CostmapToDynamicObstacles: The specified costmap converter plugin cannot be loaded. Continuing without subsequent conversion of static obstacles. Error message: %s", ex.what()); + static_costmap_converter_.reset(); + } + } + + /** + * @brief Set the underlying plugin for subsequent costmap conversion of the static background of the costmap + * @param static_costmap_converter shared pointer to the static costmap conversion plugin + */ + void setStaticCostmapConverterPlugin(boost::shared_ptr static_costmap_converter) + { + static_costmap_converter_ = static_costmap_converter; + } + + /** + * @brief Set the costmap for the underlying plugin + * @param static_costmap Costmap2D, which contains the static part of the original costmap + */ + void setStaticCostmap(boost::shared_ptr static_costmap) + { + static_costmap_converter_->setCostmap2D(static_costmap.get()); + } + + /** + * @brief Apply the underlying plugin for static costmap conversion + */ + void convertStaticObstacles() + { + static_costmap_converter_->compute(); + } + + /** + * @brief Get the converted polygons from the underlying plugin + * @return Shared instance of the underlying plugins polygon container + */ + PolygonContainerConstPtr getStaticPolygons() + { + return static_costmap_converter_->getPolygons(); + } + + /** + * @brief Determines whether an additional plugin for subsequent costmap conversion is specified + * + * @return true, if a plugin for subsequent costmap conversion is specified + */ + bool stackedCostmapConversion() + { + if(static_costmap_converter_) + return true; + else + return false; + } + +protected: + /** + * @brief Protected constructor that should be called by subclasses + */ + BaseCostmapToDynamicObstacles() : static_converter_loader_("costmap_converter", "costmap_converter::BaseCostmapToPolygons"), static_costmap_converter_() {} + +private: + pluginlib::ClassLoader static_converter_loader_; + boost::shared_ptr static_costmap_converter_; +}; + + +} + + + +#endif // end COSTMAP_CONVERTER_INTERFACE_H_ diff --git a/navigations/costmap_converter/include/costmap_converter/costmap_to_dynamic_obstacles/background_subtractor.h b/navigations/costmap_converter/include/costmap_converter/costmap_to_dynamic_obstacles/background_subtractor.h new file mode 100755 index 0000000..3e3d716 --- /dev/null +++ b/navigations/costmap_converter/include/costmap_converter/costmap_to_dynamic_obstacles/background_subtractor.h @@ -0,0 +1,115 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2017 + * TU Dortmund - Institute of Control Theory and Systems Engineering. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the institute nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Notes: + * The following code makes use of the OpenCV library. + * OpenCV is licensed under the terms of the 3-clause BSD License. + * + * Authors: Franz Albers, Christoph Rösmann + *********************************************************************/ + +#ifndef BACKGROUNDSUBTRACTOR_H_ +#define BACKGROUNDSUBTRACTOR_H_ + +#include + +/** + * @class BackgroundSubtractor + * @brief Perform background subtraction to extract the "moving" foreground + * + * This class is based on OpenCV's background subtraction class cv::BackgroundSubtractor. + * It has been modified in order to incorporate a specialized bandpass filter. + * + * See http://docs.opencv.org/3.2.0/d7/df6/classcv_1_1BackgroundSubtractor.html for the original class. + */ +class BackgroundSubtractor +{ +public: + struct Params + { + double alpha_slow; //!< Filter constant (learning rate) of the slow filter part + double alpha_fast; //!< Filter constant (learning rate) of the fast filter part + double beta; + double min_sep_between_fast_and_slow_filter; + double min_occupancy_probability; + double max_occupancy_neighbors; + int morph_size; + }; + + //! Constructor that accepts a specific parameter configuration + BackgroundSubtractor(const Params& parameters); + + /** + * @brief Computes a foreground mask + * @param[in] image Next video frame + * @param[out] fg_mask Foreground mask as an 8-bit binary image + * @param[in] shift_x Translation along the x axis between the current and previous image + * @param[in] shift_y Translation along the y axis between the current and previous image + */ + void apply(const cv::Mat& image, cv::Mat& fg_mask, int shift_x = 0, int shift_y = 0); + + /** + * @brief OpenCV Visualization + * @param name Id/name of the opencv window + * @param image Image to be visualized + */ + void visualize(const std::string& name, const cv::Mat& image); + + /** + * @brief Export vector of matrices to yaml file + * @remarks This method is intended for debugging purposes + * @param filename Desired filename including path and excluding file suffix + * @param mat_vec Vector of cv::Mat to be exported + */ + void writeMatToYAML(const std::string& filename, const std::vector& mat_vec); + + //! Update internal parameters + void updateParameters(const Params& parameters); + +private: + //! Transform/shift all internal matrices/grids according to a given translation vector + void transformToCurrentFrame(int shift_x, int shift_y); + + cv::Mat occupancy_grid_fast_; + cv::Mat occupancy_grid_slow_; + cv::Mat current_frame_; + + int previous_shift_x_; + int previous_shift_y_; + + Params params_; +}; + +#endif // BACKGROUNDSUBTRACTOR_H_ diff --git a/navigations/costmap_converter/include/costmap_converter/costmap_to_dynamic_obstacles/blob_detector.h b/navigations/costmap_converter/include/costmap_converter/costmap_to_dynamic_obstacles/blob_detector.h new file mode 100755 index 0000000..ac9b80a --- /dev/null +++ b/navigations/costmap_converter/include/costmap_converter/costmap_to_dynamic_obstacles/blob_detector.h @@ -0,0 +1,111 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2017 + * TU Dortmund - Institute of Control Theory and Systems Engineering. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the institute nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Notes: + * The following code makes use of the OpenCV library. + * OpenCV is licensed under the terms of the 3-clause BSD License. + * + * Authors: Franz Albers, Christoph Rösmann + *********************************************************************/ + +#ifndef BLOBDETECTOR_H_ +#define BLOBDETECTOR_H_ + +// Basically the OpenCV SimpleBlobDetector, extended with getContours() + +#include + +/** + * @class BlobDetector + * @brief Detect blobs in image (specialized for dynamic obstacles in the costmap) + * + * This class is based on OpenCV's blob detector cv::SimpleBlobDetector. + * It has been modified and specialized for dynamic obstacle tracking in the costmap: + * -> The modified version also returns contours of the blob. + * + * See http://docs.opencv.org/trunk/d0/d7a/classcv_1_1SimpleBlobDetector.html for the original class. + */ +class BlobDetector : public cv::SimpleBlobDetector +{ +public: + //! Default constructor which optionally accepts custom parameters + BlobDetector(const cv::SimpleBlobDetector::Params& parameters = cv::SimpleBlobDetector::Params()); + + //! Create shared instance of the blob detector with given parameters + static cv::Ptr create(const BlobDetector::Params& params); + + /** + * @brief Detects keypoints in an image and extracts contours + * + * In contrast to the original detect method, this extended version + * also extracts contours. Contours can be accessed by getContours() + * after invoking this method. + * + * @todo The mask option is currently not implemented. + * + * @param image image + * @param keypoints The detected keypoints. + * @param mask Mask specifying where to look for keypoints (optional). It must be a 8-bit integer + * matrix with non-zero values in the region of interest. + */ + virtual void detect(const cv::Mat& image, std::vector& keypoints, + const cv::Mat& mask = cv::Mat()); + + /** + * @brief Access contours extracted during detection stage + * @return Read-only reference to the contours set of the previous detect() run + */ + const std::vector>& getContours() { return contours_; } + + //! Update internal parameters + void updateParameters(const cv::SimpleBlobDetector::Params& parameters); + +protected: + struct Center + { + cv::Point2d location; + double radius; + double confidence; + }; + + virtual void findBlobs(const cv::Mat& image, const cv::Mat& binary_image, std::vector
& centers, + std::vector>& cur_contours) const; + + std::vector> contours_; + + Params params_; +}; + +#endif // BLOBDETECTOR_H_ diff --git a/navigations/costmap_converter/include/costmap_converter/costmap_to_dynamic_obstacles/costmap_to_dynamic_obstacles.h b/navigations/costmap_converter/include/costmap_converter/costmap_to_dynamic_obstacles/costmap_to_dynamic_obstacles.h new file mode 100755 index 0000000..47873c2 --- /dev/null +++ b/navigations/costmap_converter/include/costmap_converter/costmap_to_dynamic_obstacles/costmap_to_dynamic_obstacles.h @@ -0,0 +1,212 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2017 + * TU Dortmund - Institute of Control Theory and Systems Engineering. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the institute nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Notes: + * The following code makes use of the OpenCV library. + * OpenCV is licensed under the terms of the 3-clause BSD License. + * + * Authors: Franz Albers, Christoph Rösmann + *********************************************************************/ + +#ifndef COSTMAP_TO_DYNAMIC_OBSTACLES_H_ +#define COSTMAP_TO_DYNAMIC_OBSTACLES_H_ + +// ROS +#include +#include +#include +#include + +// OpenCV +#include +#include +#include + +// dynamic reconfigure +#include +#include + +// Own includes +#include +#include +#include + +// STL +#include + +namespace costmap_converter { + +/** + * @class CostmapToDynamicObstacles + * @brief This class converts the costmap_2d into dynamic obstacles. + * + * Static obstacles are treated as point obstacles. + */ +class CostmapToDynamicObstacles : public BaseCostmapToDynamicObstacles +{ +public: + /** + * @brief Constructor + */ + CostmapToDynamicObstacles(); + + /** + * @brief Destructor + */ + virtual ~CostmapToDynamicObstacles(); + + /** + * @brief Initialize the plugin + * @param nh Nodehandle that defines the namespace for parameters + */ + virtual void initialize(ros::NodeHandle nh); + + /** + * @brief This method performs the actual work (conversion of the costmap to + * obstacles) + */ + virtual void compute(); + + /** + * @brief Pass a pointer to the costmap to the plugin. + * @sa updateCostmap2D + * @param costmap Pointer to the costmap2d source + */ + virtual void setCostmap2D(costmap_2d::Costmap2D* costmap); + + /** + * @brief Get updated data from the previously set Costmap2D + * @sa setCostmap2D + */ + virtual void updateCostmap2D(); + + /** + * @brief Get a shared instance of the current obstacle container + * @remarks If compute() or startWorker() has not been called before, this + * method returns an empty instance! + * @return Shared instance of the current obstacle container + */ + ObstacleArrayConstPtr getObstacles(); + + /** + * @brief Set name of robot's odometry topic + * + * @warning The method must be called before initialize() + * + * Some plugins might require odometry information + * to compensate the robot's ego motion + * @param odom_topic topic name + */ + virtual void setOdomTopic(const std::string& odom_topic) + { + odom_topic_ = odom_topic; + } + + /** + * @brief OpenCV Visualization + * @param name Id/name of the opencv window + * @param image Image to be visualized + */ + void visualize(const std::string& name, const cv::Mat& image); + +protected: + /** + * @brief Converts the estimated velocity of a tracked object to m/s and + * returns it + * @param idx Index of the tracked object in the tracker + * @return Point_t, which represents velocity in [m/s] of object(idx) in x,y,z + * coordinates + */ + Point_t getEstimatedVelocityOfObject(unsigned int idx); + + /** + * @brief Gets the last observed contour of a object and converts it from [px] + * to [m] + * @param[in] idx Index of the tracked object in the tracker + * @param[out] contour vector of Point_t, which represents the last observed contour in [m] + * in x,y,z coordinates + */ + void getContour(unsigned int idx, std::vector& contour); + + /** + * @brief Thread-safe update of the internal obstacle container (that is + * shared using getObstacles() from outside this + * class) + * @param obstacles Updated obstacle container + */ + void updateObstacleContainer(ObstacleArrayPtr obstacles); + +private: + boost::mutex mutex_; + costmap_2d::Costmap2D* costmap_; + cv::Mat costmap_mat_; + ObstacleArrayPtr obstacles_; + cv::Mat fg_mask_; + std::unique_ptr bg_sub_; + cv::Ptr blob_det_; + std::vector keypoints_; + std::unique_ptr tracker_; + ros::Subscriber odom_sub_; + Point_t ego_vel_; + + std::string odom_topic_ = "/odom"; + bool publish_static_obstacles_ = true; + + dynamic_reconfigure::Server* + dynamic_recfg_; //!< Dynamic reconfigure server to allow config + //! modifications at runtime + + /** + * @brief Callback for the odometry messages of the observing robot. + * + * Used to convert the velocity of obstacles to the /map frame. + * @param msg The Pointer to the nav_msgs::Odometry of the observing robot + */ + void odomCallback(const nav_msgs::Odometry::ConstPtr &msg); + + /** + * @brief Callback for the dynamic_reconfigure node. + * + * This callback allows to modify parameters dynamically at runtime without + * restarting the node + * @param config Reference to the dynamic reconfigure config + * @param level Dynamic reconfigure level + */ + void reconfigureCB(CostmapToDynamicObstaclesConfig &config, uint32_t level); +}; + +} // end namespace costmap_converter + +#endif /* COSTMAP_TO_DYNAMIC_OBSTACLES_H_ */ diff --git a/navigations/costmap_converter/include/costmap_converter/costmap_to_dynamic_obstacles/multitarget_tracker/Ctracker.h b/navigations/costmap_converter/include/costmap_converter/costmap_to_dynamic_obstacles/multitarget_tracker/Ctracker.h new file mode 100755 index 0000000..ca0f01e --- /dev/null +++ b/navigations/costmap_converter/include/costmap_converter/costmap_to_dynamic_obstacles/multitarget_tracker/Ctracker.h @@ -0,0 +1,96 @@ +// Based on https://github.com/Smorodov/Multitarget-tracker/tree/master/Tracker, GPLv3 +// Refer to README.md in this directory. + +#pragma once +#include "Kalman.h" +#include "HungarianAlg.h" +#include "defines.h" +#include +#include +#include +#include + +// -------------------------------------------------------------------------- +class CTrack +{ +public: + CTrack(const Point_t& p, const std::vector& contour, track_t dt, size_t trackID) + : track_id(trackID), + skipped_frames(0), + prediction(p), + lastContour(contour), + KF(p, dt) + { + } + + track_t CalcDist(const Point_t& p) + { + Point_t diff = prediction - p; + return std::sqrt(diff.x * diff.x + diff.y * diff.y + diff.z * diff.z); + } + + void Update(const Point_t& p, const std::vector& contour, bool dataCorrect, size_t max_trace_length) + { + KF.Prediction(); + prediction = KF.Update(p, dataCorrect); + + if (dataCorrect) + { + lastContour = contour; + } + + if (trace.size() > max_trace_length) + { + trace.erase(trace.begin(), trace.end() - max_trace_length); + } + + trace.push_back(prediction); + } + + // Returns contour in [px], not in [m]! + std::vector getLastContour() const + { + return lastContour; + } + + // Returns velocity in [px/s], not in [m/s]! + Point_t getEstimatedVelocity() const + { + return KF.LastVelocity; + } + + std::vector trace; + size_t track_id; + size_t skipped_frames; + +private: + Point_t prediction; + std::vector lastContour; // Contour liegt immer auf ganzen Pixeln -> Integer Punkt + TKalmanFilter KF; +}; + +// -------------------------------------------------------------------------- +class CTracker +{ +public: + struct Params{ + track_t dt; // time for one step of the filter + track_t dist_thresh;// distance threshold. Pairs of points with higher distance are not considered in the assignment problem + int max_allowed_skipped_frames; // Maximum number of frames the track is maintained without seeing the object in the measurement data + int max_trace_length; // Maximum trace length + }; + + CTracker(const Params& parameters); + ~CTracker(void); + + std::vector> tracks; + void Update(const std::vector& detectedCentroid, const std::vector > &contour); + + void updateParameters(const Params ¶meters); + +private: + // Aggregated parameters for the tracker object + Params params; + // ID for the upcoming CTrack object + size_t NextTrackID; +}; diff --git a/navigations/costmap_converter/include/costmap_converter/costmap_to_dynamic_obstacles/multitarget_tracker/HungarianAlg.h b/navigations/costmap_converter/include/costmap_converter/costmap_to_dynamic_obstacles/multitarget_tracker/HungarianAlg.h new file mode 100755 index 0000000..0985ae7 --- /dev/null +++ b/navigations/costmap_converter/include/costmap_converter/costmap_to_dynamic_obstacles/multitarget_tracker/HungarianAlg.h @@ -0,0 +1,60 @@ +// Based on https://github.com/Smorodov/Multitarget-tracker/tree/master/Tracker, GPLv3 +// Refer to README.md in this directory. + +#include +#include +#include +#include +#include "defines.h" + +// http://community.topcoder.com/tc?module=Static&d1=tutorials&d2=hungarianAlgorithm + +typedef std::vector assignments_t; +typedef std::vector distMatrix_t; + +class AssignmentProblemSolver +{ +private: + // -------------------------------------------------------------------------- + // Computes the optimal assignment (minimum overall costs) using Munkres algorithm. + // -------------------------------------------------------------------------- + void assignmentoptimal(assignments_t& assignment, track_t& cost, const distMatrix_t& distMatrixIn, size_t nOfRows, + size_t nOfColumns); + void buildassignmentvector(assignments_t& assignment, bool* starMatrix, size_t nOfRows, size_t nOfColumns); + void computeassignmentcost(const assignments_t& assignment, track_t& cost, const distMatrix_t& distMatrixIn, + size_t nOfRows); + void step2a(assignments_t& assignment, track_t* distMatrix, bool* starMatrix, bool* newStarMatrix, bool* primeMatrix, + bool* coveredColumns, bool* coveredRows, size_t nOfRows, size_t nOfColumns, size_t minDim); + void step2b(assignments_t& assignment, track_t* distMatrix, bool* starMatrix, bool* newStarMatrix, bool* primeMatrix, + bool* coveredColumns, bool* coveredRows, size_t nOfRows, size_t nOfColumns, size_t minDim); + void step3(assignments_t& assignment, track_t* distMatrix, bool* starMatrix, bool* newStarMatrix, bool* primeMatrix, + bool* coveredColumns, bool* coveredRows, size_t nOfRows, size_t nOfColumns, size_t minDim); + void step4(assignments_t& assignment, track_t* distMatrix, bool* starMatrix, bool* newStarMatrix, bool* primeMatrix, + bool* coveredColumns, bool* coveredRows, size_t nOfRows, size_t nOfColumns, size_t minDim, size_t row, + size_t col); + void step5(assignments_t& assignment, track_t* distMatrix, bool* starMatrix, bool* newStarMatrix, bool* primeMatrix, + bool* coveredColumns, bool* coveredRows, size_t nOfRows, size_t nOfColumns, size_t minDim); + // -------------------------------------------------------------------------- + // Computes a suboptimal solution. Good for cases with many forbidden assignments. + // -------------------------------------------------------------------------- + void assignmentsuboptimal1(assignments_t& assignment, track_t& cost, const distMatrix_t& distMatrixIn, size_t nOfRows, + size_t nOfColumns); + // -------------------------------------------------------------------------- + // Computes a suboptimal solution. Good for cases with many forbidden assignments. + // -------------------------------------------------------------------------- + void assignmentsuboptimal2(assignments_t& assignment, track_t& cost, const distMatrix_t& distMatrixIn, size_t nOfRows, + size_t nOfColumns); + +public: + enum TMethod + { + optimal, + many_forbidden_assignments, + without_forbidden_assignments + }; + + AssignmentProblemSolver(); + ~AssignmentProblemSolver(); + track_t Solve(const distMatrix_t& distMatrixIn, size_t nOfRows, size_t nOfColumns, assignments_t& assignment, + TMethod Method = optimal); +}; diff --git a/navigations/costmap_converter/include/costmap_converter/costmap_to_dynamic_obstacles/multitarget_tracker/Kalman.h b/navigations/costmap_converter/include/costmap_converter/costmap_to_dynamic_obstacles/multitarget_tracker/Kalman.h new file mode 100755 index 0000000..34a5319 --- /dev/null +++ b/navigations/costmap_converter/include/costmap_converter/costmap_to_dynamic_obstacles/multitarget_tracker/Kalman.h @@ -0,0 +1,20 @@ +// Based on https://github.com/Smorodov/Multitarget-tracker/tree/master/Tracker, GPLv3 +// Refer to README.md in this directory. + +#pragma once +#include "defines.h" +#include + +// http://www.morethantechnical.com/2011/06/17/simple-kalman-filter-for-tracking-using-opencv-2-2-w-code/ +class TKalmanFilter +{ +public: + TKalmanFilter(Point_t p, track_t deltatime = 0.2); + ~TKalmanFilter(); + void Prediction(); + Point_t Update(Point_t p, bool DataCorrect); + cv::KalmanFilter* kalman; + track_t dt; + Point_t LastPosition; // contour in [px] + Point_t LastVelocity; // velocity in [px/s] +}; diff --git a/navigations/costmap_converter/include/costmap_converter/costmap_to_dynamic_obstacles/multitarget_tracker/README.md b/navigations/costmap_converter/include/costmap_converter/costmap_to_dynamic_obstacles/multitarget_tracker/README.md new file mode 100755 index 0000000..3fb4614 --- /dev/null +++ b/navigations/costmap_converter/include/costmap_converter/costmap_to_dynamic_obstacles/multitarget_tracker/README.md @@ -0,0 +1,13 @@ +Multitarget Tracker +=================== + +This code is mostly copied from the (MultitargetTracker)[https://github.com/Smorodov/Multitarget-tracker]. +It is utilized for the *CostmapToDynamicObstacles* plugin. + +The *MultitargetTracker* is licensed under (GNU GPLv3)[https://www.gnu.org/licenses/gpl-3.0.txt]. +The package itself depends on other third party packages with different licenses (refer to the package repository). + +TODO: Include the whole package as external CMake project. + + + diff --git a/navigations/costmap_converter/include/costmap_converter/costmap_to_dynamic_obstacles/multitarget_tracker/defines.h b/navigations/costmap_converter/include/costmap_converter/costmap_to_dynamic_obstacles/multitarget_tracker/defines.h new file mode 100755 index 0000000..203004f --- /dev/null +++ b/navigations/costmap_converter/include/costmap_converter/costmap_to_dynamic_obstacles/multitarget_tracker/defines.h @@ -0,0 +1,9 @@ +// Based on https://github.com/Smorodov/Multitarget-tracker/tree/master/Tracker, GPLv3 +// Refer to README.md in this directory. + +#pragma once +#include + +typedef float track_t; +typedef cv::Point3_ Point_t; +#define Mat_t CV_32FC diff --git a/navigations/costmap_converter/include/costmap_converter/costmap_to_lines_convex_hull.h b/navigations/costmap_converter/include/costmap_converter/costmap_to_lines_convex_hull.h new file mode 100755 index 0000000..810b726 --- /dev/null +++ b/navigations/costmap_converter/include/costmap_converter/costmap_to_lines_convex_hull.h @@ -0,0 +1,137 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2016, + * TU Dortmund - Institute of Control Theory and Systems Engineering. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the institute nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: Christoph Rösmann, Otniel Rinaldo + *********************************************************************/ + +#ifndef COSTMAP_TO_LINES_CONVEX_HULL_H_ +#define COSTMAP_TO_LINES_CONVEX_HULL_H_ + +#include +#include + +// dynamic reconfigure +#include + +namespace costmap_converter +{ + +/** + * @class CostmapToLinesDBSMCCH + * @brief This class converts the costmap_2d into a set of lines (and points) + * + * The conversion is performed in three stages: + * 1. Clusters in the costmap are collected using the DBSCAN Algorithm (https://en.wikipedia.org/wiki/DBSCAN) + * Reference: Ester, Martin; Kriegel, Hans-Peter; Sander, Jörg; Xu, Xiaowei, + * A density-based algorithm for discovering clusters in large spatial databases with noise. + * Proceedings of the Second International Conference on Knowledge Discovery and Data Mining. AAAI Press. 1996. pp. 226–231. ISBN 1-57735-004-9. + * + * 2. In the subsequent stage, the convex hull of each cluster is determined using the monotone chain algorithm aka Andrew's algorithm: + * C++ implementation example: http://www.algorithmist.com/index.php/Monotone_Chain_Convex_Hull ( GNU Free Documentation License 1.2 ) + * Reference: A. M. Andrew, "Another Efficient Algorithm for Convex Hulls in Two Dimensions", Info. Proc. Letters 9, 216-219 (1979). + * + * 3. In the third step extract lines from each polygon (convex hull) if there exist at least a predefined number of support points. + * + * The output is a container of polygons (but each polygon does only contain a single vertex (point) or two vertices (line) + */ + class CostmapToLinesDBSMCCH : public CostmapToPolygonsDBSMCCH + { + public: + + /** + * @brief Constructor + */ + CostmapToLinesDBSMCCH(); + + /** + * @brief Destructor + */ + virtual ~CostmapToLinesDBSMCCH(); + + /** + * @brief Initialize the plugin + * @param nh Nodehandle that defines the namespace for parameters + */ + virtual void initialize(ros::NodeHandle nh); + + /** + * @brief This method performs the actual work (conversion of the costmap to polygons) + */ + virtual void compute(); + + + protected: + + /** + * @brief Extract points and lines from a given cluster by checking all keypoint pairs of the convex hull for a minimum number of support points + * @param cluster list of points in the cluster + * @param polygon convex hull of the cluster \c cluster + * @param[out] lines back_inserter object to a sequence of polygon msgs (new lines will be pushed back) + */ + void extractPointsAndLines(std::vector& cluster, const geometry_msgs::Polygon& polygon, std::back_insert_iterator< std::vector > lines); + + + + protected: + + double support_pts_max_dist_inbetween_; + double support_pts_max_dist_; + int min_support_pts_; + + private: + + /** + * @brief Callback for the dynamic_reconfigure node. + * + * This callback allows to modify parameters dynamically at runtime without restarting the node + * @param config Reference to the dynamic reconfigure config + * @param level Dynamic reconfigure level + */ + void reconfigureCB(CostmapToLinesDBSMCCHConfig& config, uint32_t level); + + dynamic_reconfigure::Server* dynamic_recfg_; //!< Dynamic reconfigure server to allow config modifications at runtime + + }; + + + + + + + + +} //end namespace teb_local_planner + +#endif /* COSTMAP_TO_LINES_CONVEX_HULL_H_ */ diff --git a/navigations/costmap_converter/include/costmap_converter/costmap_to_lines_ransac.h b/navigations/costmap_converter/include/costmap_converter/costmap_to_lines_ransac.h new file mode 100755 index 0000000..4c37650 --- /dev/null +++ b/navigations/costmap_converter/include/costmap_converter/costmap_to_lines_ransac.h @@ -0,0 +1,187 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2016, + * TU Dortmund - Institute of Control Theory and Systems Engineering. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the institute nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: Christoph Rösmann + *********************************************************************/ + +#ifndef COSTMAP_TO_LINES_RANSAC_H_ +#define COSTMAP_TO_LINES_RANSAC_H_ + +#include +#include +#include +#include + +#include + +namespace costmap_converter +{ + +/** + * @class CostmapToLinesDBSRANSAC + * @brief This class converts the costmap_2d into a set of lines (and points) + * + * The conversion is performed in two stages: + * 1. Clusters in the costmap are collected using the DBSCAN Algorithm (https://en.wikipedia.org/wiki/DBSCAN) + * Reference: Ester, Martin; Kriegel, Hans-Peter; Sander, Jörg; Xu, Xiaowei, + * A density-based algorithm for discovering clusters in large spatial databases with noise. + * Proceedings of the Second International Conference on Knowledge Discovery and Data Mining. AAAI Press. 1996. pp. 226–231. ISBN 1-57735-004-9. + * + * 2. The RANSAC algorithm is used to find straight line segment models (https://en.wikipedia.org/wiki/RANSAC) + * RANSAC is called repeatedly to find multiple lines per cluster until the number of inliners is below a specific threshold. + * In that case the remaining outliers are used as points or keypoints of their convex hull are used as points (depending on a paramter). + * The latter one applies as a filter. The convex assumption is not strict in practice, since the remaining regions/cluster (line inliers are removed) + * should be dense and small. For details about the convex hull algorithm, refer to costmap_converter::CostmapToPolygonsDBSMCCH. + * Resulting lines of RANSAC are currently not refined by linear regression. + * + * The output is a container of polygons (but each polygon does only contain a single vertex (point) or two vertices (line) + */ + class CostmapToLinesDBSRANSAC : public CostmapToPolygonsDBSMCCH + { + public: + + /** + * @brief Constructor + */ + CostmapToLinesDBSRANSAC(); + + /** + * @brief Destructor + */ + virtual ~CostmapToLinesDBSRANSAC(); + + /** + * @brief Initialize the plugin + * @param nh Nodehandle that defines the namespace for parameters + */ + virtual void initialize(ros::NodeHandle nh); + + /** + * @brief This method performs the actual work (conversion of the costmap to polygons) + */ + virtual void compute(); + + + /** + * @brief Check if the candidate point is an inlier. + * @param point generic 2D point type defining the reference point + * @param line_start generic 2D point type defining the start of the line + * @param line_end generic 2D point type defining the end of the line + * @param min_distance minimum distance allowed + * @tparam Point generic point type that should provide (writable) x and y member fiels. + * @tparam LinePoint generic point type that should provide (writable) x and y member fiels. + * @return \c true if inlier, \c false otherwise + */ + template + static bool isInlier(const Point& point, const LinePoint& line_start, const LinePoint& line_end, double min_distance); + + protected: + + double ransac_inlier_distance_; //!< Maximum distance to the line segment for inliers + int ransac_min_inliers_; //!< Minimum numer of inliers required to form a line + int ransac_no_iterations_; //!< Number of ransac iterations + int ransac_remainig_outliers_; //!< Repeat ransac until the number of outliers is as specified here + bool ransac_convert_outlier_pts_; //!< If \c true, convert remaining outliers to single points. + bool ransac_filter_remaining_outlier_pts_; //!< If \c true, filter the interior of remaining outliers and keep only keypoints of their convex hull + + + boost::random::mt19937 rnd_generator_; //!< Random number generator for ransac with default seed + + + /** + * @brief Find a straight line segment in a point cloud with RANSAC (without linear regression). + * @param data set of 2D data points + * @param inlier_distance maximum distance that inliers must satisfy + * @param no_iterations number of RANSAC iterations + * @param min_inliers minimum number of inliers to return true + * @param[out] best_model start and end of the best straight line segment + * @param[out] inliers inlier keypoints are written to this container [optional] + * @param[out] outliers outlier keypoints are written to this container [optional] + * @return \c false, if \c min_inliers is not satisfied, \c true otherwise + */ + bool lineRansac(const std::vector& data, double inlier_distance, int no_iterations, int min_inliers, + std::pair& best_model, std::vector* inliers = NULL, + std::vector* outliers = NULL); + + /** + * @brief Perform a simple linear regression in order to fit a straight line 'y = slope*x + intercept' + * @param data set of 2D data points + * @param[out] slope The slope of the fitted line + * @param[out] intercept The intercept / offset of the line + * @param[out] mean_x_out mean of the x-values of the data [optional] + * @param[out] mean_y_out mean of the y-values of the data [optional] + * @return \c true, if a valid line has been fitted, \c false otherwise. + */ + bool linearRegression(const std::vector& data, double& slope, double& intercept, + double* mean_x_out = NULL, double* mean_y_out = NULL); + + + +// void adjustLineLength(const std::vector& data, const KeyPoint& linept1, const KeyPoint& linept2, +// KeyPoint& line_start, KeyPoint& line_end); + + private: + + /** + * @brief Callback for the dynamic_reconfigure node. + * + * This callback allows to modify parameters dynamically at runtime without restarting the node + * @param config Reference to the dynamic reconfigure config + * @param level Dynamic reconfigure level + */ + void reconfigureCB(CostmapToLinesDBSRANSACConfig& config, uint32_t level); + + dynamic_reconfigure::Server* dynamic_recfg_; //!< Dynamic reconfigure server to allow config modifications at runtime + + }; + + + +template +bool CostmapToLinesDBSRANSAC::isInlier(const Point& point, const LinePoint& line_start, const LinePoint& line_end, double min_distance) +{ + bool is_inbetween = false; + double distance = computeDistanceToLineSegment(point, line_start, line_end, &is_inbetween); + if (!is_inbetween) + return false; + if (distance <= min_distance) + return true; + return false; +} + + +} //end namespace teb_local_planner + +#endif /* COSTMAP_TO_LINES_RANSAC_H_ */ diff --git a/navigations/costmap_converter/include/costmap_converter/costmap_to_polygons.h b/navigations/costmap_converter/include/costmap_converter/costmap_to_polygons.h new file mode 100755 index 0000000..021c641 --- /dev/null +++ b/navigations/costmap_converter/include/costmap_converter/costmap_to_polygons.h @@ -0,0 +1,336 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2016, + * TU Dortmund - Institute of Control Theory and Systems Engineering. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the institute nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: Christoph Rösmann, Otniel Rinaldo + *********************************************************************/ + +#ifndef COSTMAP_TO_POLYGONS_H_ +#define COSTMAP_TO_POLYGONS_H_ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +// dynamic reconfigure +#include +#include + + +namespace costmap_converter +{ + +/** + * @class CostmapToPolygonsDBSMCCH + * @brief This class converts the costmap_2d into a set of convex polygons (and points) + * + * The conversion is performed in two stages: + * 1. Clusters in the costmap are collected using the DBSCAN Algorithm (https://en.wikipedia.org/wiki/DBSCAN) + * Reference: Ester, Martin; Kriegel, Hans-Peter; Sander, Jörg; Xu, Xiaowei, + * A density-based algorithm for discovering clusters in large spatial databases with noise. + * Proceedings of the Second International Conference on Knowledge Discovery and Data Mining. AAAI Press. 1996. pp. 226–231. ISBN 1-57735-004-9. + * + * 2. In the subsequent stage, clusters are converted into convex polgons using the monotone chain algorithm aka Andrew's algorithm: + * C++ implementation example: http://www.algorithmist.com/index.php/Monotone_Chain_Convex_Hull ( GNU Free Documentation License 1.2 ) + * Reference: A. M. Andrew, "Another Efficient Algorithm for Convex Hulls in Two Dimensions", Info. Proc. Letters 9, 216-219 (1979). + * + * All single points that do not define a cluster (noise) are also treated as polygon (represented as a single vertex) + */ +class CostmapToPolygonsDBSMCCH : public BaseCostmapToPolygons +{ + public: + + /** + * @struct KeyPoint + * @brief Defines a keypoint in metric coordinates of the map + */ + struct KeyPoint + { + //! Default constructor + KeyPoint() {} + //! Constructor with point initialization + KeyPoint(double x_, double y_) : x(x_), y(y_) {} + double x; //!< x coordinate [m] + double y; //!< y coordinate [m] + + //! Convert keypoint to geometry_msgs::Point message type + void toPointMsg(geometry_msgs::Point& point) const {point.x=x; point.y=y; point.z=0;} + //! Convert keypoint to geometry_msgs::Point32 message type + void toPointMsg(geometry_msgs::Point32& point) const {point.x=x; point.y=y; point.z=0;} + }; + + /** + * @struct Parameters + * @brief Defines the parameters of the algorithm + */ + struct Parameters + { + Parameters() : max_distance_(0.4), min_pts_(2), max_pts_(30), min_keypoint_separation_(0.1) {} + // DBSCAN parameters + double max_distance_; //!< Parameter for DB_Scan, maximum distance to neighbors [m] + int min_pts_; //!< Parameter for DB_Scan: minimum number of points that define a cluster + int max_pts_; //!< Parameter for DB_Scan: maximum number of points that define a cluster (to avoid large L- and U-shapes) + + // convex hull parameters + double min_keypoint_separation_; //!< Clear keypoints of the convex polygon that are close to each other [distance in meters] (0: keep all) + }; + + /** + * @brief Constructor + */ + CostmapToPolygonsDBSMCCH(); + + /** + * @brief Destructor + */ + virtual ~CostmapToPolygonsDBSMCCH(); + + /** + * @brief Initialize the plugin + * @param nh Nodehandle that defines the namespace for parameters + */ + virtual void initialize(ros::NodeHandle nh); + + /** + * @brief This method performs the actual work (conversion of the costmap to polygons) + */ + virtual void compute(); + + /** + * @brief Pass a pointer to the costap to the plugin. + * @sa updateCostmap2D + * @param costmap Pointer to the costmap2d source + */ + virtual void setCostmap2D(costmap_2d::Costmap2D* costmap); + + /** + * @brief Get updated data from the previously set Costmap2D + * @sa setCostmap2D + */ + virtual void updateCostmap2D(); + + + /** + * @brief Convert a generi point type to a geometry_msgs::Polygon + * @param point generic 2D point type + * @param[out] polygon already instantiated polygon that will be filled with a single point + * @tparam Point generic point type that should provide (writable) x and y member fiels. + */ + template< typename Point> + static void convertPointToPolygon(const Point& point, geometry_msgs::Polygon& polygon) + { + polygon.points.resize(1); + polygon.points.front().x = point.x; + polygon.points.front().y = point.y; + polygon.points.front().z = 0; + } + + /** + * @brief Get a shared instance of the current polygon container + * @remarks If compute() or startWorker() has not been called before, this method returns an empty instance! + * @return Shared instance of the current polygon container + */ + PolygonContainerConstPtr getPolygons(); + + + + protected: + + /** + * @brief DBSCAN algorithm for clustering + * + * Clusters in the costmap are collected using the DBSCAN Algorithm (https://en.wikipedia.org/wiki/DBSCAN) + * Reference: Ester, Martin; Kriegel, Hans-Peter; Sander, Jörg; Xu, Xiaowei, + * A density-based algorithm for discovering clusters in large spatial databases with noise. + * Proceedings of the Second International Conference on Knowledge Discovery and Data Mining. AAAI Press. 1996. pp. 226–231. ISBN 1-57735-004-9. + * + * @param[out] clusters clusters will added to this output-argument (a sequence of keypoints for each cluster) + * the first cluster (clusters[0]) will contain all noise points (that does not fulfil the min_pts condition + */ + void dbScan(std::vector< std::vector >& clusters); + + /** + * @brief Helper function for dbScan to search for neighboring points + * + * @param curr_index index to the current item in \c occupied_cells + * @param[out] neighbor_indices list of neighbors (indices of \c occupied cells) + */ + void regionQuery(int curr_index, std::vector& neighbor_indices); + + /** + * @brief helper function for adding a point to the lookup data structures + */ + void addPoint(double x, double y) + { + int idx = occupied_cells_.size(); + occupied_cells_.emplace_back(x, y); + int cx, cy; + pointToNeighborCells(occupied_cells_.back(), cx, cy); + int nidx = neighborCellsToIndex(cx, cy); + if (nidx >= 0) + neighbor_lookup_[nidx].push_back(idx); + } + + /** + * @brief Compute the convex hull for a single cluster (monotone chain algorithm) + * + * Clusters are converted into convex polgons using the monotone chain algorithm aka Andrew's algorithm: + * C++ implementation example: http://www.algorithmist.com/index.php/Monotone_Chain_Convex_Hull ( GNU Free Documentation License 1.2 ) + * Reference: A. M. Andrew, "Another Efficient Algorithm for Convex Hulls in Two Dimensions", Info. Proc. Letters 9, 216-219 (1979). + * @remarks The algorithm seems to cut edges, thus we give a try to convexHull2(). + * @todo Evaluate and figure out whether convexHull() or convexHull2() is better suited (performance, quality, ...) + * @remarks The last point is the same as the first one + * @param cluster list of keypoints that should be converted into a polygon + * @param[out] polygon the resulting convex polygon + */ + void convexHull(std::vector& cluster, geometry_msgs::Polygon& polygon); + + /** + * @brief Compute the convex hull for a single cluster + * + * Clusters are converted into convex polgons using an algorithm provided here: + * https://bitbucket.org/vostreltsov/concave-hull/overview + * The convex hull algorithm is part of the concave hull algorithm. + * The license is WTFPL 2.0 and permits any usage. + * + * @remarks The last point is the same as the first one + * @param cluster list of keypoints that should be converted into a polygon + * @param[out] polygon the resulting convex polygon + * @todo Evaluate and figure out whether convexHull() or convexHull2() is better suited (performance, quality, ...) + */ + void convexHull2(std::vector& cluster, geometry_msgs::Polygon& polygon); + + /** + * @brief Simplify a polygon by removing points. + * + * We apply the Douglas-Peucker Algorithm to simplify the edges of the polygon. + * Internally, the parameter min_keypoint_separation is used for deciding whether + * a point is considered close to an edge and to be merged into the line. + */ + void simplifyPolygon(geometry_msgs::Polygon& polygon); + + /** + * @brief 2D Cross product of two vectors defined by two points and a common origin + * @param O Origin + * @param A First point + * @param B Second point + * @tparam P1 2D Point type with x and y member fields + * @tparam P2 2D Point type with x and y member fields + * @tparam P3 2D Point type with x and y member fields + */ + template + long double cross(const P1& O, const P2& A, const P3& B) + { + return (long double)(A.x - O.x) * (long double)(B.y - O.y) - (long double)(A.y - O.y) * (long double)(B.x - O.x); + } + + + /** + * @brief Thread-safe update of the internal polygon container (that is shared using getPolygons() from outside this class) + * @param polygons Updated polygon container + */ + void updatePolygonContainer(PolygonContainerPtr polygons); + + + std::vector occupied_cells_; //!< List of occupied cells in the current map (updated by updateCostmap2D()) + + std::vector > neighbor_lookup_; //! array of cells for neighbor lookup + int neighbor_size_x_; //! size of the neighbour lookup in x (number of cells) + int neighbor_size_y_; //! size of the neighbour lookup in y (number of cells) + double offset_x_; //! offset [meters] in x for the lookup grid + double offset_y_; //! offset [meters] in y for the lookup grid + + /** + * @brief convert a 2d cell coordinate into the 1D index of the array + * @param cx the x index of the cell + * @param cy the y index of the cell + */ + int neighborCellsToIndex(int cx, int cy) + { + if (cx < 0 || cx >= neighbor_size_x_ || cy < 0 || cy >= neighbor_size_y_) + return -1; + return cy * neighbor_size_x_ + cx; + } + + /** + * @brief compute the cell indices of a keypoint + * @param kp key point given in world coordinates [m, m] + * @param cx output cell index in x direction + * @param cy output cell index in y direction + */ + void pointToNeighborCells(const KeyPoint& kp, int& cx, int& cy) + { + cx = int((kp.x - offset_x_) / parameter_.max_distance_); + cy = int((kp.y - offset_y_) / parameter_.max_distance_); + } + + + Parameters parameter_; //< active parameters throughout computation + Parameters parameter_buffered_; //< the buffered parameters that are offered to dynamic reconfigure + boost::mutex parameter_mutex_; //!< Mutex that keeps track about the ownership of the shared polygon instance + + private: + + /** + * @brief Callback for the dynamic_reconfigure node. + * + * This callback allows to modify parameters dynamically at runtime without restarting the node + * @param config Reference to the dynamic reconfigure config + * @param level Dynamic reconfigure level + */ + void reconfigureCB(CostmapToPolygonsDBSMCCHConfig& config, uint32_t level); + + + PolygonContainerPtr polygons_; //!< Current shared container of polygons + boost::mutex mutex_; //!< Mutex that keeps track about the ownership of the shared polygon instance + + dynamic_reconfigure::Server* dynamic_recfg_; //!< Dynamic reconfigure server to allow config modifications at runtime + + costmap_2d::Costmap2D *costmap_; //!< Pointer to the costmap2d + +}; + + +} //end namespace teb_local_planner + +#endif /* COSTMAP_TO_POLYGONS_H_ */ diff --git a/navigations/costmap_converter/include/costmap_converter/costmap_to_polygons_concave.h b/navigations/costmap_converter/include/costmap_converter/costmap_to_polygons_concave.h new file mode 100755 index 0000000..8c61140 --- /dev/null +++ b/navigations/costmap_converter/include/costmap_converter/costmap_to_polygons_concave.h @@ -0,0 +1,202 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2016, + * TU Dortmund - Institute of Control Theory and Systems Engineering. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the institute nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: Christoph Rösmann + *********************************************************************/ + +#ifndef COSTMAP_TO_POLYGONS_CONCAVE_H_ +#define COSTMAP_TO_POLYGONS_CONCAVE_H_ + +#include +#include + +// dynamic reconfigure +#include +#include + + +namespace costmap_converter +{ + +/** + * @class CostmapToPolygonsDBSConcaveHull + * @brief This class converts the costmap_2d into a set of non-convex polygons (and points) + * + * All single points that do not define a cluster (noise) are also treated as polygon (represented as a single vertex) + * @todo change the class hierarchy to a clearer and more generic one + */ +class CostmapToPolygonsDBSConcaveHull : public CostmapToPolygonsDBSMCCH +{ + public: + + + + /** + * @brief Constructor + */ + CostmapToPolygonsDBSConcaveHull(); + + /** + * @brief Destructor + */ + virtual ~CostmapToPolygonsDBSConcaveHull(); + + /** + * @brief Initialize the plugin + * @param nh Nodehandle that defines the namespace for parameters + */ + virtual void initialize(ros::NodeHandle nh); + + + /** + * @brief This method performs the actual work (conversion of the costmap to polygons) + */ + virtual void compute(); + + protected: + + + /** + * @brief Compute the concave hull for a single cluster + * + * @remarks The last point is the same as the first one + * @param cluster list of keypoints that should be converted into a polygon + * @param depth Smaller depth: sharper surface, depth -> high value: convex hull + * @param[out] polygon the resulting convex polygon + */ + void concaveHull(std::vector& cluster, double depth, geometry_msgs::Polygon& polygon); + + void concaveHullClusterCut(std::vector& cluster, double depth, geometry_msgs::Polygon& polygon); + + template + std::size_t findNearestInnerPoint(PointLine line_start, PointLine line_end, const std::vector& cluster, const std::vector& hull, bool* found); + + + template + bool checkLineIntersection(const Point1& line1_start, const Point2& line1_end, const Point3& line2_start, const Point4& line2_end); + + template + bool checkLineIntersection(const std::vector& hull, const Point1& current_line_start, + const Point2& current_line_end, const Point3& test_line_start, const Point4& test_line_end); + + double concave_hull_depth_; + + private: + + /** + * @brief Callback for the dynamic_reconfigure node. + * + * This callback allows to modify parameters dynamically at runtime without restarting the node + * @param config Reference to the dynamic reconfigure config + * @param level Dynamic reconfigure level + */ + void reconfigureCB(CostmapToPolygonsDBSConcaveHullConfig& config, uint32_t level); + + dynamic_reconfigure::Server* dynamic_recfg_; //!< Dynamic reconfigure server to allow config modifications at runtime + + +}; + + +template +std::size_t CostmapToPolygonsDBSConcaveHull::findNearestInnerPoint(PointLine line_start, PointLine line_end, const std::vector& cluster, const std::vector& hull, bool* found) +{ + std::size_t nearsest_idx = 0; + double distance = 0; + *found = false; + + for (std::size_t i = 0; i < cluster.size(); ++i) + { + // Skip points that are already in the hull + if (std::find_if( hull.begin(), hull.end(), boost::bind(isApprox2d, _1, boost::cref(cluster[i]), 1e-5) ) != hull.end() ) + continue; + + double dist = computeDistanceToLineSegment(cluster[i], line_start, line_end); + bool skip = false; + for (int j = 0; !skip && j < (int)hull.size() - 1; ++j) + { + double dist_temp = computeDistanceToLineSegment(cluster[i], hull[j], hull[j + 1]); + skip |= dist_temp < dist; + } + if (skip) + continue; + + if (!(*found) || dist < distance) + { + nearsest_idx = i; + distance = dist; + *found = true; + } + } + return nearsest_idx; +} + + +template +bool CostmapToPolygonsDBSConcaveHull::checkLineIntersection(const Point1& line1_start, const Point2& line1_end, const Point3& line2_start, const Point4& line2_end) +{ + double dx1 = line1_end.x - line1_start.x; + double dy1 = line1_end.y - line1_start.y; + double dx2 = line2_end.x - line2_start.x; + double dy2 = line2_end.y - line2_start.y; + double s = (-dy1 * (line1_start.x - line2_start.x) + dx1 * (line1_start.y - line2_start.y)) / (-dx2 * dy1 + dx1 * dy2); + double t = ( dx2 * (line1_start.y - line2_start.y) - dy2 * (line1_start.x - line2_start.x)) / (-dx2 * dy1 + dx1 * dy2); + return (s > 0 && s < 1 && t > 0 && t < 1); +} + + +template +bool CostmapToPolygonsDBSConcaveHull::checkLineIntersection(const std::vector& hull, const Point1& current_line_start, + const Point2& current_line_end, const Point3& test_line_start, const Point4& test_line_end) +{ + for (int i = 0; i < (int)hull.size() - 2; i++) + { + if (isApprox2d(current_line_start, hull[i], 1e-5) && isApprox2d(current_line_end, hull[i+1], 1e-5)) + { + continue; + } + + if (checkLineIntersection(test_line_start, test_line_end, hull[i], hull[i+1])) + { + return true; + } + } + return false; +} + + +} //end namespace teb_local_planner + +#endif /* COSTMAP_TO_POLYGONS_CONCAVE_H_ */ diff --git a/navigations/costmap_converter/include/costmap_converter/misc.h b/navigations/costmap_converter/include/costmap_converter/misc.h new file mode 100755 index 0000000..b3500a7 --- /dev/null +++ b/navigations/costmap_converter/include/costmap_converter/misc.h @@ -0,0 +1,157 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2016, + * TU Dortmund - Institute of Control Theory and Systems Engineering. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the institute nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: Christoph Rösmann + *********************************************************************/ + +#ifndef MISC_H_ +#define MISC_H_ + +#include +#include + +namespace costmap_converter +{ + +/** + * @brief Calculate the distance between a point and a straight line (with infinite length) + * @param point generic 2D point type defining the reference point + * @param line_pt1 generic 2D point as part of the line + * @param line_pt2 generic 2D point as part of the line + * @tparam Point generic point type that should provide x and y member fiels. + * @tparam LinePoint generic point type that should provide x and y member fiels. + * @return (minimum) euclidean distance to the line segment + */ +template +inline double computeDistanceToLine(const Point& point, const LinePoint& line_pt1, const LinePoint& line_pt2) +{ + double dx = line_pt2.x - line_pt1.x; + double dy = line_pt2.y - line_pt1.y; + + double length = std::sqrt(dx*dx + dy*dy); + + if (length>0) + return std::abs(dy * point.x - dx * point.y + line_pt2.x * line_pt1.y - line_pt2.y * line_pt1.x) / length; + + return std::sqrt(std::pow(point.x - line_pt1.x, 2) + std::pow(point.y - line_pt1.y, 2)); +} + + +/** + * @brief Calculate the squared distance between a point and a straight line segment + * @param point generic 2D point type defining the reference point + * @param line_start generic 2D point type defining the start of the line + * @param line_end generic 2D point type defining the end of the line + * @param[out] is_inbetween write \c true, if the point is placed inbetween start and end [optional] + * @tparam Point generic point type that should provide x and y member fiels. + * @tparam LinePoint generic point type that should provide x and y member fiels. + * @return (minimum) squared euclidean distance to the line segment + */ +template +inline double computeSquaredDistanceToLineSegment(const Point& point, const LinePoint& line_start, const LinePoint& line_end, bool* is_inbetween=NULL) +{ + double dx = line_end.x - line_start.x; + double dy = line_end.y - line_start.y; + + double length_sqr = dx*dx + dy*dy; + + double u = 0; + + if (length_sqr > 0) + u = ((point.x - line_start.x) * dx + (point.y - line_start.y) * dy) / length_sqr; + + if (is_inbetween) + *is_inbetween = (u>=0 && u<=1); + + if (u <= 0) + return std::pow(point.x-line_start.x,2) + std::pow(point.y-line_start.y,2); + + if (u >= 1) + return std::pow(point.x-line_end.x,2) + std::pow(point.y-line_end.y,2); + + return std::pow(point.x - (line_start.x+u*dx) ,2) + std::pow(point.y - (line_start.y+u*dy),2); +} + +/** + * @brief Calculate the distance between a point and a straight line segment + * @param point generic 2D point type defining the reference point + * @param line_start generic 2D point type defining the start of the line + * @param line_end generic 2D point type defining the end of the line + * @param[out] is_inbetween write \c true, if the point is placed inbetween start and end [optional] + * @tparam Point generic point type that should provide x and y member fiels. + * @tparam LinePoint generic point type that should provide x and y member fiels. + * @return (minimum) euclidean distance to the line segment + */ +template +inline double computeDistanceToLineSegment(const Point& point, const LinePoint& line_start, const LinePoint& line_end, bool* is_inbetween=NULL) +{ + return std::sqrt(computeSquaredDistanceToLineSegment(point, line_start, line_end, is_inbetween)); +} + + +/** + * @brief Calculate the distance between two 2d points + * @param pt1 generic 2D point + * @param pt2 generic 2D point + * @tparam Point1 generic point type that should provide x and y member fiels. + * @tparam Point2 generic point type that should provide x and y member fiels. + * @return euclidean distance to the line segment + */ +template +inline double norm2d(const Point1& pt1, const Point2& pt2) +{ + return std::sqrt( std::pow(pt2.x - pt1.x, 2) + std::pow(pt2.y - pt1.y, 2) ); +} + +/** + * @brief Check if two points are approximately defining the same one + * @param pt1 generic 2D point + * @param pt2 generic 2D point + * @param threshold define the minimum threshold |pt1.x-pt2.y| < tresh && |pt1.y-pt2.y| < tresh + * @tparam Point1 generic point type that should provide x and y member fiels. + * @tparam Point2 generic point type that should provide x and y member fiels. + * @return \c true, if similar, \c false otherwise + */ +template +inline bool isApprox2d(const Point1& pt1, const Point2& pt2, double threshold) +{ + return ( std::abs(pt2.x-pt1.x) + + costmap_converter + 0.0.13 + + A ros package that includes plugins and nodes to convert occupied costmap2d cells to primitive types. + + + Christoph Rösmann + + Christoph Rösmann + Franz Albers + Otniel Rinaldo + + BSD + + http://wiki.ros.org/costmap_converter + + catkin + + message_generation + + message_runtime + message_runtime + + rostest + + geometry_msgs + roscpp + std_msgs + costmap_2d + dynamic_reconfigure + pluginlib + cv_bridge + + + + + + diff --git a/navigations/costmap_converter/plugins.xml b/navigations/costmap_converter/plugins.xml new file mode 100755 index 0000000..682f96f --- /dev/null +++ b/navigations/costmap_converter/plugins.xml @@ -0,0 +1,38 @@ + + + + + This class converts costmap2d obstacles into a vector of convex polygons. + Clustering is performed with DBScan. Convex polygons are detected using the Monotone Chain Convex Hull algorithm. + + + + + + This class converts costmap2d obstacles into a vector of lines (represented as polygon msg). + Clustering is performed with DBScan. Clusters are transformed into convex polygons using the Monotone Chain Convex Hull algorithm. + The resulting keypoints are used for possible line candidates. + A line is only defined if there exist a specified number of support points between each keypoint pair. + + + + + + This class converts costmap2d obstacles into a vector of lines (represented as polygon msg). + Clustering is performed with DBScan. For each cluster RANSAC is applied sequentally to fit multiple line models. + + + + + + This class converts costmap2d obstacles into a vector of non-convex (concave) polygons. + + + + + + This class detects and tracks obstacles from a sequence of costmaps. + + + + diff --git a/navigations/costmap_converter/src/costmap_converter_node.cpp b/navigations/costmap_converter/src/costmap_converter_node.cpp new file mode 100755 index 0000000..4127084 --- /dev/null +++ b/navigations/costmap_converter/src/costmap_converter_node.cpp @@ -0,0 +1,296 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2016, + * TU Dortmund - Institute of Control Theory and Systems Engineering. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the institute nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: Christoph Rösmann, Otniel Rinaldo + *********************************************************************/ + +#include + +#include +#include +#include +#include + +#include +#include + + + +class CostmapStandaloneConversion +{ +public: + CostmapStandaloneConversion() : converter_loader_("costmap_converter", "costmap_converter::BaseCostmapToPolygons"), n_("~") + { + // load converter plugin from parameter server, otherwise set default + std::string converter_plugin = "costmap_converter::CostmapToPolygonsDBSMCCH"; + n_.param("converter_plugin", converter_plugin, converter_plugin); + + try + { + converter_ = converter_loader_.createInstance(converter_plugin); + } + catch(const pluginlib::PluginlibException& ex) + { + ROS_ERROR("The plugin failed to load for some reason. Error: %s", ex.what()); + ros::shutdown(); + } + + ROS_INFO_STREAM("Standalone costmap converter:" << converter_plugin << " loaded."); + + std::string costmap_topic = "/move_base/local_costmap/costmap"; + n_.param("costmap_topic", costmap_topic, costmap_topic); + + std::string costmap_update_topic = "/move_base/local_costmap/costmap_updates"; + n_.param("costmap_update_topic", costmap_update_topic, costmap_update_topic); + + std::string obstacles_topic = "costmap_obstacles"; + n_.param("obstacles_topic", obstacles_topic, obstacles_topic); + + std::string polygon_marker_topic = "costmap_polygon_markers"; + n_.param("polygon_marker_topic", polygon_marker_topic, polygon_marker_topic); + + costmap_sub_ = n_.subscribe(costmap_topic, 1, &CostmapStandaloneConversion::costmapCallback, this); + costmap_update_sub_ = n_.subscribe(costmap_update_topic, 1, &CostmapStandaloneConversion::costmapUpdateCallback, this); + obstacle_pub_ = n_.advertise(obstacles_topic, 1000); + marker_pub_ = n_.advertise(polygon_marker_topic, 10); + + occupied_min_value_ = 100; + n_.param("occupied_min_value", occupied_min_value_, occupied_min_value_); + + std::string odom_topic = "/odom"; + n_.param("odom_topic", odom_topic, odom_topic); + + if (converter_) + { + converter_->setOdomTopic(odom_topic); + converter_->initialize(n_); + converter_->setCostmap2D(&map_); + //converter_->startWorker(ros::Rate(5), &map, true); + } + } + + + void costmapCallback(const nav_msgs::OccupancyGridConstPtr& msg) + { + ROS_INFO_ONCE("Got first costmap callback. This message will be printed once"); + + if (msg->info.width != map_.getSizeInCellsX() || msg->info.height != map_.getSizeInCellsY() || msg->info.resolution != map_.getResolution()) + { + ROS_INFO("New map format, resizing and resetting map..."); + map_.resizeMap(msg->info.width, msg->info.height, msg->info.resolution, msg->info.origin.position.x, msg->info.origin.position.y); + } + else + { + map_.updateOrigin(msg->info.origin.position.x, msg->info.origin.position.y); + } + + + for (std::size_t i=0; i < msg->data.size(); ++i) + { + unsigned int mx, my; + map_.indexToCells((unsigned int)i, mx, my); + map_.setCost(mx, my, msg->data[i] >= occupied_min_value_ ? 255 : 0 ); + } + + // convert + converter_->updateCostmap2D(); + converter_->compute(); + costmap_converter::ObstacleArrayConstPtr obstacles = converter_->getObstacles(); + + if (!obstacles) + return; + + obstacle_pub_.publish(obstacles); + + frame_id_ = msg->header.frame_id; + + publishAsMarker(frame_id_, *obstacles, marker_pub_); + } + + void costmapUpdateCallback(const map_msgs::OccupancyGridUpdateConstPtr& update) + { + unsigned int di = 0; + for (unsigned int y = 0; y < update->height ; ++y) + { + for (unsigned int x = 0; x < update->width ; ++x) + { + map_.setCost(x, y, update->data[di++] >= occupied_min_value_ ? 255 : 0 ); + } + } + + // convert + // TODO(roesmann): currently, the converter updates the complete costmap and not the part which is updated in this callback + converter_->updateCostmap2D(); + converter_->compute(); + costmap_converter::ObstacleArrayConstPtr obstacles = converter_->getObstacles(); + + if (!obstacles) + return; + + obstacle_pub_.publish(obstacles); + + publishAsMarker(frame_id_, *obstacles, marker_pub_); + } + + void publishAsMarker(const std::string& frame_id, const std::vector& polygonStamped, ros::Publisher& marker_pub) + { + visualization_msgs::Marker line_list; + line_list.header.frame_id = frame_id; + line_list.header.stamp = ros::Time::now(); + line_list.ns = "Polygons"; + line_list.action = visualization_msgs::Marker::ADD; + line_list.pose.orientation.w = 1.0; + + line_list.id = 0; + line_list.type = visualization_msgs::Marker::LINE_LIST; + + line_list.scale.x = 0.1; + line_list.color.g = 1.0; + line_list.color.a = 1.0; + + for (std::size_t i=0; i converter_loader_; + boost::shared_ptr converter_; + + ros::NodeHandle n_; + ros::Subscriber costmap_sub_; + ros::Subscriber costmap_update_sub_; + ros::Publisher obstacle_pub_; + ros::Publisher marker_pub_; + + std::string frame_id_; + int occupied_min_value_; + + costmap_2d::Costmap2D map_; + +}; + + +int main(int argc, char** argv) +{ + ros::init(argc, argv, "costmap_converter"); + + CostmapStandaloneConversion convert_process; + + ros::spin(); + + return 0; +} + + diff --git a/navigations/costmap_converter/src/costmap_to_dynamic_obstacles/background_subtractor.cpp b/navigations/costmap_converter/src/costmap_to_dynamic_obstacles/background_subtractor.cpp new file mode 100755 index 0000000..37256bc --- /dev/null +++ b/navigations/costmap_converter/src/costmap_to_dynamic_obstacles/background_subtractor.cpp @@ -0,0 +1,115 @@ +#include +//#include +#include + +BackgroundSubtractor::BackgroundSubtractor(const Params ¶meters): params_(parameters) +{ +} + +void BackgroundSubtractor::apply(const cv::Mat& image, cv::Mat& fg_mask, int shift_x, int shift_y) +{ + current_frame_ = image; + + // occupancy grids are empty only once in the beginning -> initialize variables + if (occupancy_grid_fast_.empty() && occupancy_grid_slow_.empty()) + { + occupancy_grid_fast_ = current_frame_; + occupancy_grid_slow_ = current_frame_; + previous_shift_x_ = shift_x; + previous_shift_y_ = shift_y; + return; + } + + // Shift previous occupancy grid to new location (match current_frame_) + int shift_relative_to_previous_pos_x_ = shift_x - previous_shift_x_; + int shift_relative_to_previous_pos_y_ = shift_y - previous_shift_y_; + previous_shift_x_ = shift_x; + previous_shift_y_ = shift_y; + + // if(shift_relative_to_previous_pos_x_ != 0 || shift_relative_to_previous_pos_y_ != 0) + transformToCurrentFrame(shift_relative_to_previous_pos_x_, shift_relative_to_previous_pos_y_); + + // cvv::debugFilter(occupancy_grid_fast_, currentFrame_, CVVISUAL_LOCATION); + + // Calculate normalized sum (mean) of nearest neighbors + int size = 3; // 3, 5, 7, .... + cv::Mat nearest_neighbor_mean_fast(occupancy_grid_fast_.size(), CV_8UC1); + cv::Mat nearest_neighbor_mean_slow(occupancy_grid_slow_.size(), CV_8UC1); + cv::boxFilter(occupancy_grid_fast_, nearest_neighbor_mean_fast, -1, cv::Size(size, size), cv::Point(-1, -1), true, + cv::BORDER_REPLICATE); + cv::boxFilter(occupancy_grid_slow_, nearest_neighbor_mean_slow, -1, cv::Size(size, size), cv::Point(-1, -1), true, + cv::BORDER_REPLICATE); + // cv::GaussianBlur(occupancy_grid_fast_, nearest_neighbor_mean_fast, cv::Size(size,size), 1, 1, cv::BORDER_REPLICATE); + // cv::GaussianBlur(occupancy_grid_fast_, nearest_neighbor_mean_fast, cv::Size(size,size), 1, 1, cv::BORDER_REPLICATE); + + // compute time mean value for each pixel according to learningrate alpha + // occupancy_grid_fast_ = beta*(alpha_fast*current_frame_ + (1.0-alpha_fast)*occupancy_grid_fast_) + (1-beta)*nearest_neighbor_mean_fast; + cv::addWeighted(current_frame_, params_.alpha_fast, occupancy_grid_fast_, (1 - params_.alpha_fast), 0, occupancy_grid_fast_); + cv::addWeighted(occupancy_grid_fast_, params_.beta, nearest_neighbor_mean_fast, (1 - params_.beta), 0, occupancy_grid_fast_); + // occupancy_grid_slow_ = beta*(alpha_slow*current_frame_ + (1.0-alpha_slow)*occupancy_grid_slow) + (1-beta)*nearest_neighbor_mean_slow; + cv::addWeighted(current_frame_, params_.alpha_slow, occupancy_grid_slow_, (1 - params_.alpha_slow), 0, occupancy_grid_slow_); + cv::addWeighted(occupancy_grid_slow_, params_.beta, nearest_neighbor_mean_slow, (1 - params_.beta), 0, occupancy_grid_slow_); + + // 1) Obstacles should be detected after a minimum response of the fast filter + // occupancy_grid_fast_ > min_occupancy_probability + cv::threshold(occupancy_grid_fast_, occupancy_grid_fast_, params_.min_occupancy_probability, 0 /*unused*/, cv::THRESH_TOZERO); + // 2) Moving obstacles have a minimum difference between the responses of the slow and fast filter + // occupancy_grid_fast_-occupancy_grid_slow_ > min_sep_between_fast_and_slow_filter + cv::threshold(occupancy_grid_fast_ - occupancy_grid_slow_, fg_mask, params_.min_sep_between_fast_and_slow_filter, 255, + cv::THRESH_BINARY); + // 3) Dismiss static obstacles + // nearest_neighbor_mean_slow < max_occupancy_neighbors + cv::threshold(nearest_neighbor_mean_slow, nearest_neighbor_mean_slow, params_.max_occupancy_neighbors, 255, cv::THRESH_BINARY_INV); + cv::bitwise_and(nearest_neighbor_mean_slow, fg_mask, fg_mask); + + //visualize("Current frame", currentFrame_); + cv::Mat setBorderToZero = cv::Mat(current_frame_.size(), CV_8UC1, 0.0); + int border = 5; + setBorderToZero(cv::Rect(border, border, current_frame_.cols-2*border, current_frame_.rows-2*border)) = 255; + + cv::bitwise_and(setBorderToZero, fg_mask, fg_mask); + + // cv::imwrite("/home/albers/Desktop/currentFrame.png", currentFrame_); + // visualize("Foreground mask", fgMask); + + // Closing Operation + cv::Mat element = cv::getStructuringElement(cv::MORPH_ELLIPSE, + cv::Size(2*params_.morph_size + 1, 2*params_.morph_size + 1), + cv::Point(params_.morph_size, params_.morph_size)); + cv::dilate(fg_mask, fg_mask, element); + cv::dilate(fg_mask, fg_mask, element); + cv::erode(fg_mask, fg_mask, element); +} + +void BackgroundSubtractor::transformToCurrentFrame(int shift_x, int shift_y) +{ + // TODO: initialize with current_frame (first observed image) rather than zeros + + // Translate (shift) image in costmap coordinates + // in cv::Mat: shift X -> to the left; shift y -> to the top + cv::Mat temp_fast, temp_slow; + cv::Mat translation_mat = (cv::Mat_(2, 3, CV_64F) << 1, 0, -shift_x, 0, 1, -shift_y); + cv::warpAffine(occupancy_grid_fast_, temp_fast, translation_mat, occupancy_grid_fast_.size()); // can't operate in-place + cv::warpAffine(occupancy_grid_slow_, temp_slow, translation_mat, occupancy_grid_slow_.size()); // can't operate in-place + + // cvv::debugFilter(occupancy_grid_fast_, temp_fast); + + occupancy_grid_fast_ = temp_fast; + occupancy_grid_slow_ = temp_slow; +} + +void BackgroundSubtractor::visualize(const std::string& name, const cv::Mat& image) +{ + if (!image.empty()) + { + cv::Mat im = image.clone(); + cv::flip(im, im, 0); + cv::imshow(name, im); + cv::waitKey(1); + } +} + +void BackgroundSubtractor::updateParameters(const Params ¶meters) +{ + params_ = parameters; +} diff --git a/navigations/costmap_converter/src/costmap_to_dynamic_obstacles/blob_detector.cpp b/navigations/costmap_converter/src/costmap_to_dynamic_obstacles/blob_detector.cpp new file mode 100755 index 0000000..c7352f4 --- /dev/null +++ b/navigations/costmap_converter/src/costmap_to_dynamic_obstacles/blob_detector.cpp @@ -0,0 +1,193 @@ +#include +#include +#include + +BlobDetector::BlobDetector(const SimpleBlobDetector::Params& parameters) : params_(parameters) {} + +cv::Ptr BlobDetector::create(const cv::SimpleBlobDetector::Params& params) +{ + return cv::Ptr (new BlobDetector(params)); // compatibility with older versions + //return cv::makePtr(params); +} + +void BlobDetector::detect(const cv::Mat& image, std::vector& keypoints, const cv::Mat&) +{ + // TODO: support mask + contours_.clear(); + + keypoints.clear(); + cv::Mat grayscale_image; + if (image.channels() == 3) + cv::cvtColor(image, grayscale_image, cv::COLOR_BGR2GRAY); + else + grayscale_image = image; + + if (grayscale_image.type() != CV_8UC1) + { + //CV_Error(cv::Error::StsUnsupportedFormat, "Blob detector only supports 8-bit images!"); + std::cerr << "Blob detector only supports 8-bit images!\n"; + } + + std::vector> centers; + std::vector> contours; + for (double thresh = params_.minThreshold; thresh < params_.maxThreshold; thresh += params_.thresholdStep) + { + cv::Mat binarized_image; + cv::threshold(grayscale_image, binarized_image, thresh, 255, cv::THRESH_BINARY); + + std::vector
cur_centers; + std::vector> cur_contours, new_contours; + findBlobs(grayscale_image, binarized_image, cur_centers, cur_contours); + std::vector> new_centers; + for (std::size_t i = 0; i < cur_centers.size(); ++i) + { + bool isNew = true; + for (std::size_t j = 0; j < centers.size(); ++j) + { + double dist = cv::norm(centers[j][centers[j].size() / 2].location - cur_centers[i].location); + isNew = dist >= params_.minDistBetweenBlobs && dist >= centers[j][centers[j].size() / 2].radius && + dist >= cur_centers[i].radius; + if (!isNew) + { + centers[j].push_back(cur_centers[i]); + + size_t k = centers[j].size() - 1; + while (k > 0 && centers[j][k].radius < centers[j][k - 1].radius) + { + centers[j][k] = centers[j][k - 1]; + k--; + } + centers[j][k] = cur_centers[i]; + + break; + } + } + if (isNew) + { + new_centers.push_back(std::vector
(1, cur_centers[i])); + new_contours.push_back(cur_contours[i]); + } + } + std::copy(new_centers.begin(), new_centers.end(), std::back_inserter(centers)); + std::copy(new_contours.begin(), new_contours.end(), std::back_inserter(contours)); + } + + for (size_t i = 0; i < centers.size(); ++i) + { + if (centers[i].size() < params_.minRepeatability) + continue; + cv::Point2d sum_point(0, 0); + double normalizer = 0; + for (std::size_t j = 0; j < centers[i].size(); ++j) + { + sum_point += centers[i][j].confidence * centers[i][j].location; + normalizer += centers[i][j].confidence; + } + sum_point *= (1. / normalizer); + cv::KeyPoint kpt(sum_point, (float)(centers[i][centers[i].size() / 2].radius)); + keypoints.push_back(kpt); + contours_.push_back(contours[i]); + } +} + +void BlobDetector::findBlobs(const cv::Mat& image, const cv::Mat& binary_image, std::vector
& centers, + std::vector>& cur_contours) const +{ + (void)image; + centers.clear(); + cur_contours.clear(); + + std::vector> contours; + cv::Mat tmp_binary_image = binary_image.clone(); + cv::findContours(tmp_binary_image, contours, cv::RETR_LIST, cv::CHAIN_APPROX_SIMPLE); + + for (std::size_t contour_idx = 0; contour_idx < contours.size(); ++contour_idx) + { + Center center; + center.confidence = 1; + cv::Moments moms = cv::moments(cv::Mat(contours[contour_idx])); + if (params_.filterByArea) + { + double area = moms.m00; + if (area < params_.minArea || area >= params_.maxArea) + continue; + } + + if (params_.filterByCircularity) + { + double area = moms.m00; + double perimeter = cv::arcLength(cv::Mat(contours[contour_idx]), true); + double ratio = 4 * CV_PI * area / (perimeter * perimeter); + if (ratio < params_.minCircularity || ratio >= params_.maxCircularity) + continue; + } + + if (params_.filterByInertia) + { + double denominator = std::sqrt(std::pow(2 * moms.mu11, 2) + std::pow(moms.mu20 - moms.mu02, 2)); + const double eps = 1e-2; + double ratio; + if (denominator > eps) + { + double cosmin = (moms.mu20 - moms.mu02) / denominator; + double sinmin = 2 * moms.mu11 / denominator; + double cosmax = -cosmin; + double sinmax = -sinmin; + + double imin = 0.5 * (moms.mu20 + moms.mu02) - 0.5 * (moms.mu20 - moms.mu02) * cosmin - moms.mu11 * sinmin; + double imax = 0.5 * (moms.mu20 + moms.mu02) - 0.5 * (moms.mu20 - moms.mu02) * cosmax - moms.mu11 * sinmax; + ratio = imin / imax; + } + else + { + ratio = 1; + } + + if (ratio < params_.minInertiaRatio || ratio >= params_.maxInertiaRatio) + continue; + + center.confidence = ratio * ratio; + } + + if (params_.filterByConvexity) + { + std::vector hull; + cv::convexHull(cv::Mat(contours[contour_idx]), hull); + double area = cv::contourArea(cv::Mat(contours[contour_idx])); + double hullArea = cv::contourArea(cv::Mat(hull)); + double ratio = area / hullArea; + if (ratio < params_.minConvexity || ratio >= params_.maxConvexity) + continue; + } + + if (moms.m00 == 0.0) + continue; + center.location = cv::Point2d(moms.m10 / moms.m00, moms.m01 / moms.m00); + + if (params_.filterByColor) + { + if (binary_image.at(cvRound(center.location.y), cvRound(center.location.x)) != params_.blobColor) + continue; + } + + // compute blob radius + { + std::vector dists; + for (std::size_t point_idx = 0; point_idx < contours[contour_idx].size(); ++point_idx) + { + cv::Point2d pt = contours[contour_idx][point_idx]; + dists.push_back(cv::norm(center.location - pt)); + } + std::sort(dists.begin(), dists.end()); + center.radius = (dists[(dists.size() - 1) / 2] + dists[dists.size() / 2]) / 2.; + } + + centers.push_back(center); + cur_contours.push_back(contours[contour_idx]); + } +} + +void BlobDetector::updateParameters(const Params& parameters) +{ + params_ = parameters; +} diff --git a/navigations/costmap_converter/src/costmap_to_dynamic_obstacles/costmap_to_dynamic_obstacles.cpp b/navigations/costmap_converter/src/costmap_to_dynamic_obstacles/costmap_to_dynamic_obstacles.cpp new file mode 100755 index 0000000..92cc442 --- /dev/null +++ b/navigations/costmap_converter/src/costmap_to_dynamic_obstacles/costmap_to_dynamic_obstacles.cpp @@ -0,0 +1,476 @@ +#include + +#include +#include + +PLUGINLIB_EXPORT_CLASS(costmap_converter::CostmapToDynamicObstacles, costmap_converter::BaseCostmapToPolygons) + +namespace costmap_converter +{ + +CostmapToDynamicObstacles::CostmapToDynamicObstacles() : BaseCostmapToDynamicObstacles() +{ + ego_vel_.x = ego_vel_.y = ego_vel_.z = 0; + costmap_ = nullptr; + dynamic_recfg_ = nullptr; +} + +CostmapToDynamicObstacles::~CostmapToDynamicObstacles() +{ + if(dynamic_recfg_ != nullptr) + delete dynamic_recfg_; +} + +void CostmapToDynamicObstacles::initialize(ros::NodeHandle nh) +{ + costmap_ = nullptr; + + // We need the odometry from the robot to compensate the ego motion + ros::NodeHandle gn; // create odom topic w.r.t. global node handle + odom_sub_ = gn.subscribe(odom_topic_, 1, &CostmapToDynamicObstacles::odomCallback, this); + + nh.param("publish_static_obstacles", publish_static_obstacles_, publish_static_obstacles_); + + ////////////////////////////////// + // Foreground detection parameters + BackgroundSubtractor::Params bg_sub_params; + + bg_sub_params.alpha_slow = 0.3; + nh.param("alpha_slow", bg_sub_params.alpha_slow, bg_sub_params.alpha_slow); + + bg_sub_params.alpha_fast = 0.85; + nh.param("alpha_fast", bg_sub_params.alpha_fast, bg_sub_params.alpha_fast); + + bg_sub_params.beta = 0.85; + nh.param("beta", bg_sub_params.beta, bg_sub_params.beta); + + bg_sub_params.min_occupancy_probability = 180; + nh.param("min_occupancy_probability", bg_sub_params.min_occupancy_probability, bg_sub_params.min_occupancy_probability); + + bg_sub_params.min_sep_between_fast_and_slow_filter = 80; + nh.param("min_sep_between_slow_and_fast_filter", bg_sub_params.min_sep_between_fast_and_slow_filter, bg_sub_params.min_sep_between_fast_and_slow_filter); + + bg_sub_params.max_occupancy_neighbors = 100; + nh.param("max_occupancy_neighbors", bg_sub_params.max_occupancy_neighbors, bg_sub_params.max_occupancy_neighbors); + + bg_sub_params.morph_size = 1; + nh.param("morph_size", bg_sub_params.morph_size, bg_sub_params.morph_size); + + bg_sub_ = std::unique_ptr(new BackgroundSubtractor(bg_sub_params)); + + //////////////////////////// + // Blob detection parameters + BlobDetector::Params blob_det_params; + + blob_det_params.filterByColor = true; // actually filterByIntensity, always true + blob_det_params.blobColor = 255; // Extract light blobs + blob_det_params.thresholdStep = 256; // Input for blob detection is already a binary image + blob_det_params.minThreshold = 127; + blob_det_params.maxThreshold = 255; + blob_det_params.minRepeatability = 1; + + blob_det_params.minDistBetweenBlobs = 10; + nh.param("min_distance_between_blobs", blob_det_params.minDistBetweenBlobs, blob_det_params.minDistBetweenBlobs); + + blob_det_params.filterByArea = true; + nh.param("filter_by_area", blob_det_params.filterByArea, blob_det_params.filterByArea); + + blob_det_params.minArea = 3; // Filter out blobs with less pixels + nh.param("min_area", blob_det_params.minArea, blob_det_params.minArea); + + blob_det_params.maxArea = 300; + nh.param("max_area", blob_det_params.maxArea, blob_det_params.maxArea); + + blob_det_params.filterByCircularity = true; // circularity = 4*pi*area/perimeter^2 + nh.param("filter_by_circularity", blob_det_params.filterByCircularity, blob_det_params.filterByCircularity); + + blob_det_params.minCircularity = 0.2; + nh.param("min_circularity", blob_det_params.minCircularity, blob_det_params.minCircularity); + + blob_det_params.maxCircularity = 1; // maximal 1 (in case of a circle) + nh.param("max_circularity", blob_det_params.maxCircularity, blob_det_params.maxCircularity); + + blob_det_params.filterByInertia = true; // Filter blobs based on their elongation + nh.param("filter_by_intertia", blob_det_params.filterByInertia, blob_det_params.filterByInertia); + + blob_det_params.minInertiaRatio = 0.2; // minimal 0 (in case of a line) + nh.param("min_inertia_ratio", blob_det_params.minInertiaRatio, blob_det_params.minInertiaRatio); + + blob_det_params.maxInertiaRatio = 1; // maximal 1 (in case of a circle) + nh.param("max_intertia_ratio", blob_det_params.maxInertiaRatio, blob_det_params.maxInertiaRatio); + + blob_det_params.filterByConvexity = false; // Area of the Blob / Area of its convex hull + nh.param("filter_by_convexity", blob_det_params.filterByConvexity, blob_det_params.filterByConvexity); + + blob_det_params.minConvexity = 0; // minimal 0 + nh.param("min_convexity", blob_det_params.minConvexity, blob_det_params.minConvexity); + + blob_det_params.maxConvexity = 1; // maximal 1 + nh.param("max_convexity", blob_det_params.maxConvexity, blob_det_params.maxConvexity); + + blob_det_ = BlobDetector::create(blob_det_params); + + //////////////////////////////////// + // Tracking parameters + CTracker::Params tracker_params; + tracker_params.dt = 0.2; + nh.param("dt", tracker_params.dt, tracker_params.dt); + + tracker_params.dist_thresh = 60.0; + nh.param("dist_thresh", tracker_params.dist_thresh, tracker_params.dist_thresh); + + tracker_params.max_allowed_skipped_frames = 3; + nh.param("max_allowed_skipped_frames", tracker_params.max_allowed_skipped_frames, tracker_params.max_allowed_skipped_frames); + + tracker_params.max_trace_length = 10; + nh.param("max_trace_length", tracker_params.max_trace_length, tracker_params.max_trace_length); + + tracker_ = std::unique_ptr(new CTracker(tracker_params)); + + + //////////////////////////////////// + // Static costmap conversion parameters + std::string static_converter_plugin = "costmap_converter::CostmapToPolygonsDBSMCCH"; + nh.param("static_converter_plugin", static_converter_plugin, static_converter_plugin); + loadStaticCostmapConverterPlugin(static_converter_plugin, nh); + + + // setup dynamic reconfigure + dynamic_recfg_ = new dynamic_reconfigure::Server(nh); + dynamic_reconfigure::Server::CallbackType cb = boost::bind(&CostmapToDynamicObstacles::reconfigureCB, this, _1, _2); + dynamic_recfg_->setCallback(cb); +} + +void CostmapToDynamicObstacles::compute() +{ + if (costmap_mat_.empty()) + return; + + /////////////////////////// Foreground detection //////////////////////////////////// + // Dynamic obstacles are separated from static obstacles + int origin_x = round(costmap_->getOriginX() / costmap_->getResolution()); + int origin_y = round(costmap_->getOriginY() / costmap_->getResolution()); + // ROS_INFO("Origin x [m]: %f Origin_y [m]: %f", costmap_->getOriginX(), costmap_->getOriginY()); + // ROS_INFO("Origin x [px]: %d \t Origin_y [px]: %d", originX, originY); + + bg_sub_->apply(costmap_mat_, fg_mask_, origin_x, origin_y); + + // if no foreground object is detected, no ObstacleMsgs need to be published + if (fg_mask_.empty()) + return; + + cv::Mat bg_mat; + if (publish_static_obstacles_) + { + // Get static obstacles + bg_mat = costmap_mat_ - fg_mask_; + // visualize("bg_mat", bg_mat); + } + + + /////////////////////////////// Blob detection ///////////////////////////////////// + // Centers and contours of Blobs are detected + blob_det_->detect(fg_mask_, keypoints_); + std::vector> contours = blob_det_->getContours(); + + + ////////////////////////////// Tracking //////////////////////////////////////////// + // Objects are assigned to objects from previous frame based on Hungarian Algorithm + // Object velocities are estimated using a Kalman Filter + std::vector detected_centers(keypoints_.size()); + for (int i = 0; i < keypoints_.size(); i++) + { + detected_centers.at(i).x = keypoints_.at(i).pt.x; + detected_centers.at(i).y = keypoints_.at(i).pt.y; + detected_centers.at(i).z = 0; // Currently unused! + } + + tracker_->Update(detected_centers, contours); + + + ///////////////////////////////////// Output /////////////////////////////////////// + /* + cv::Mat fg_mask_with_keypoints = cv::Mat::zeros(fg_mask.size(), CV_8UC3); + cv::cvtColor(fg_mask, fg_mask_with_keypoints, cv::COLOR_GRAY2BGR); + + for (int i = 0; i < (int)tracker_->tracks.size(); ++i) + cv::rectangle(fg_mask_with_keypoints, cv::boundingRect(tracker_->tracks[i]->getLastContour()), + cv::Scalar(0, 0, 255), 1); + + //visualize("fgMaskWithKeyPoints", fgMaskWithKeypoints); + //cv::imwrite("/home/albers/Desktop/fgMask.png", fgMask); + //cv::imwrite("/home/albers/Desktop/fgMaskWithKeyPoints.png", fgMaskWithKeypoints); + */ + + //////////////////////////// Fill ObstacleContainerPtr ///////////////////////////// + ObstacleArrayPtr obstacles(new ObstacleArrayMsg); + // header.seq is automatically filled + obstacles->header.stamp = ros::Time::now(); + obstacles->header.frame_id = "/map"; //Global frame /map + + // For all tracked objects + for (unsigned int i = 0; i < (unsigned int)tracker_->tracks.size(); ++i) + { + geometry_msgs::Polygon polygon; + + // TODO directly create polygon inside getContour and avoid copy + std::vector contour; + getContour(i, contour); // this method also transforms map to world coordinates + + // convert contour to polygon + for (const Point_t& pt : contour) + { + polygon.points.emplace_back(); + polygon.points.back().x = pt.x; + polygon.points.back().y = pt.y; + polygon.points.back().z = 0; + } + + obstacles->obstacles.emplace_back(); + obstacles->obstacles.back().polygon = polygon; + + // Set obstacle ID + obstacles->obstacles.back().id = tracker_->tracks.at(i)->track_id; + + // Set orientation + geometry_msgs::QuaternionStamped orientation; + + Point_t vel = getEstimatedVelocityOfObject(i); + double yaw = std::atan2(vel.y, vel.x); + //ROS_INFO("yaw: %f", yaw); + obstacles->obstacles.back().orientation = tf::createQuaternionMsgFromYaw(yaw); + + // Set velocity + geometry_msgs::TwistWithCovariance velocities; + //velocities.twist.linear.x = std::sqrt(vel.x*vel.x + vel.y*vel.y); + //velocities.twist.linear.y = 0; + velocities.twist.linear.x = vel.x; + velocities.twist.linear.y = vel.y; // TODO(roesmann): don't we need to consider the transformation between opencv's and costmap's coordinate frames? + velocities.twist.linear.z = 0; + velocities.twist.angular.x = 0; + velocities.twist.angular.y = 0; + velocities.twist.angular.z = 0; + + // TODO: use correct covariance matrix + velocities.covariance = {1, 0, 0, 0, 0, 0, + 0, 1, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, + 0, 0, 0, 1, 0, 0, + 0, 0, 0, 0, 1, 0, + 0, 0, 0, 0, 0, 1}; + + obstacles->obstacles.back().velocities = velocities; + } + + ////////////////////////// Static obstacles //////////////////////////// + if (publish_static_obstacles_) + { + uchar* img_data = bg_mat.data; + int width = bg_mat.cols; + int height = bg_mat.rows; + int stride = bg_mat.step; + + if (stackedCostmapConversion()) + { + // Create new costmap with static obstacles (background) + boost::shared_ptr static_costmap(new costmap_2d::Costmap2D(costmap_->getSizeInCellsX(), + costmap_->getSizeInCellsY(), + costmap_->getResolution(), + costmap_->getOriginX(), + costmap_->getOriginY())); + for(int i = 0; i < height; i++) + { + for(int j = 0; j < width; j++) + { + static_costmap->setCost(j, i, img_data[i * stride + j]); + } + } + + // Apply static obstacle conversion plugin + setStaticCostmap(static_costmap); + convertStaticObstacles(); + + // Store converted static obstacles for publishing + auto static_polygons = getStaticPolygons(); + for (auto it = static_polygons->begin(); it != static_polygons->end(); ++it) + { + obstacles->obstacles.emplace_back(); + obstacles->obstacles.back().polygon = *it; + obstacles->obstacles.back().velocities.twist.linear.x = 0; + obstacles->obstacles.back().velocities.twist.linear.y = 0; + obstacles->obstacles.back().id = -1; + } + } + // Otherwise leave static obstacles point-shaped + else + { + for(int i = 0; i < height; i++) + { + for(int j = 0; j < width; j++) + { + uchar value = img_data[i * stride + j]; + if (value > 0) + { + // obstacle found + obstacles->obstacles.emplace_back(); + geometry_msgs::Point32 pt; + pt.x = (double)j*costmap_->getResolution() + costmap_->getOriginX(); + pt.y = (double)i*costmap_->getResolution() + costmap_->getOriginY(); + obstacles->obstacles.back().polygon.points.push_back(pt); + obstacles->obstacles.back().velocities.twist.linear.x = 0; + obstacles->obstacles.back().velocities.twist.linear.y = 0; + obstacles->obstacles.back().id = -1; + } + } + } + } + } + + updateObstacleContainer(obstacles); +} + +void CostmapToDynamicObstacles::setCostmap2D(costmap_2d::Costmap2D* costmap) +{ + if (!costmap) + return; + + costmap_ = costmap; + + updateCostmap2D(); +} + +void CostmapToDynamicObstacles::updateCostmap2D() +{ + if (!costmap_->getMutex()) + { + ROS_ERROR("Cannot update costmap since the mutex pointer is null"); + return; + } + costmap_2d::Costmap2D::mutex_t::scoped_lock lock(*costmap_->getMutex()); + + // Initialize costmapMat_ directly with the unsigned char array of costmap_ + //costmap_mat_ = cv::Mat(costmap_->getSizeInCellsX(), costmap_->getSizeInCellsY(), CV_8UC1, + // costmap_->getCharMap()).clone(); // Deep copy: TODO + costmap_mat_ = cv::Mat(costmap_->getSizeInCellsX(), costmap_->getSizeInCellsY(), CV_8UC1, + costmap_->getCharMap()); +} + +ObstacleArrayConstPtr CostmapToDynamicObstacles::getObstacles() +{ + boost::mutex::scoped_lock lock(mutex_); + return obstacles_; +} + +void CostmapToDynamicObstacles::updateObstacleContainer(ObstacleArrayPtr obstacles) +{ + boost::mutex::scoped_lock lock(mutex_); + obstacles_ = obstacles; +} + +Point_t CostmapToDynamicObstacles::getEstimatedVelocityOfObject(unsigned int idx) +{ + // vel [px/s] * costmapResolution [m/px] = vel [m/s] + Point_t vel = tracker_->tracks.at(idx)->getEstimatedVelocity() * costmap_->getResolution() + ego_vel_; + + //ROS_INFO("vel x: %f, vel y: %f, vel z: %f", vel.x, vel.y, vel.z); + // velocity in /map frame + return vel; +} + +void CostmapToDynamicObstacles::odomCallback(const nav_msgs::Odometry::ConstPtr& msg) +{ + ROS_INFO_ONCE("CostmapToDynamicObstacles: odom received."); + + tf::Quaternion pose; + tf::quaternionMsgToTF(msg->pose.pose.orientation, pose); + + tf::Vector3 twistLinear; + tf::vector3MsgToTF(msg->twist.twist.linear, twistLinear); + + // velocity of the robot in x, y and z coordinates + tf::Vector3 vel = tf::quatRotate(pose, twistLinear); + ego_vel_.x = vel.x(); + ego_vel_.y = vel.y(); + ego_vel_.z = vel.z(); +} + +void CostmapToDynamicObstacles::reconfigureCB(CostmapToDynamicObstaclesConfig& config, uint32_t level) +{ + publish_static_obstacles_ = config.publish_static_obstacles; + + // BackgroundSubtraction Parameters + BackgroundSubtractor::Params bg_sub_params; + bg_sub_params.alpha_slow = config.alpha_slow; + bg_sub_params.alpha_fast = config.alpha_fast; + bg_sub_params.beta = config.beta; + bg_sub_params.min_sep_between_fast_and_slow_filter = config.min_sep_between_slow_and_fast_filter; + bg_sub_params.min_occupancy_probability = config.min_occupancy_probability; + bg_sub_params.max_occupancy_neighbors = config.max_occupancy_neighbors; + bg_sub_params.morph_size = config.morph_size; + bg_sub_->updateParameters(bg_sub_params); + + // BlobDetector Parameters + BlobDetector::Params blob_det_params; + // necessary, because blobDetParams are otherwise initialized with default values for dark blobs + blob_det_params.filterByColor = true; // actually filterByIntensity, always true + blob_det_params.blobColor = 255; // Extract light blobs + blob_det_params.thresholdStep = 256; // Input for blobDetection is already a binary image + blob_det_params.minThreshold = 127; + blob_det_params.maxThreshold = 255; + blob_det_params.minRepeatability = 1; + blob_det_params.minDistBetweenBlobs = config.min_distance_between_blobs; // TODO: Currently not working as expected + blob_det_params.filterByArea = config.filter_by_area; + blob_det_params.minArea = config.min_area; + blob_det_params.maxArea = config.max_area; + blob_det_params.filterByCircularity = config.filter_by_circularity; + blob_det_params.minCircularity = config.min_circularity; + blob_det_params.maxCircularity = config.max_circularity; + blob_det_params.filterByInertia = config.filter_by_inertia; + blob_det_params.minInertiaRatio = config.min_inertia_ratio; + blob_det_params.maxInertiaRatio = config.max_inertia_ratio; + blob_det_params.filterByConvexity = config.filter_by_convexity; + blob_det_params.minConvexity = config.min_convexity; + blob_det_params.maxConvexity = config.max_convexity; + blob_det_->updateParameters(blob_det_params); + + // Tracking Parameters + CTracker::Params tracking_params; + tracking_params.dt = config.dt; + tracking_params.dist_thresh = config.dist_thresh; + tracking_params.max_allowed_skipped_frames = config.max_allowed_skipped_frames; + tracking_params.max_trace_length = config.max_trace_length; + tracker_->updateParameters(tracking_params); +} + +void CostmapToDynamicObstacles::getContour(unsigned int idx, std::vector& contour) +{ + assert(!tracker_->tracks.empty() && idx < tracker_->tracks.size()); + + contour.clear(); + + // contour [px] * costmapResolution [m/px] = contour [m] + std::vector contour2i = tracker_->tracks.at(idx)->getLastContour(); + + contour.reserve(contour2i.size()); + + Point_t costmap_origin(costmap_->getOriginX(), costmap_->getOriginY(), 0); + + for (std::size_t i = 0; i < contour2i.size(); ++i) + { + contour.push_back((Point_t(contour2i.at(i).x, contour2i.at(i).y, 0.0)*costmap_->getResolution()) + + costmap_origin); // Shift to /map + } + +} + +void CostmapToDynamicObstacles::visualize(const std::string& name, const cv::Mat& image) +{ + if (!image.empty()) + { + cv::Mat im = image.clone(); + cv::flip(im, im, 0); + cv::imshow(name, im); + cv::waitKey(1); + } +} +} diff --git a/navigations/costmap_converter/src/costmap_to_dynamic_obstacles/multitarget_tracker/Ctracker.cpp b/navigations/costmap_converter/src/costmap_to_dynamic_obstacles/multitarget_tracker/Ctracker.cpp new file mode 100755 index 0000000..68af0a8 --- /dev/null +++ b/navigations/costmap_converter/src/costmap_to_dynamic_obstacles/multitarget_tracker/Ctracker.cpp @@ -0,0 +1,130 @@ +// Based on https://github.com/Smorodov/Multitarget-tracker/tree/master/Tracker, GPLv3 +// Refer to README.md in this directory. + +#include + +// --------------------------------------------------------------------------- +// Tracker. Manage tracks. Create, remove, update. +// --------------------------------------------------------------------------- +CTracker::CTracker(const Params ¶meters) + : params(parameters), + NextTrackID(0) +{ +} +// --------------------------------------------------------------------------- +// +// --------------------------------------------------------------------------- +void CTracker::Update(const std::vector& detectedCentroid, const std::vector< std::vector >& contours) +{ + // Each contour has a centroid + assert(detectedCentroid.size() == contours.size()); + + // ----------------------------------- + // If there is no tracks yet, then every cv::Point begins its own track. + // ----------------------------------- + if (tracks.size() == 0) + { + // If no tracks yet + for (size_t i = 0; i < detectedCentroid.size(); ++i) + { + tracks.push_back( + std::unique_ptr(new CTrack(detectedCentroid[i], contours[i], params.dt, NextTrackID++))); + } + } + + size_t N = tracks.size(); + size_t M = detectedCentroid.size(); + + assignments_t assignment; + + if (!tracks.empty()) + { + // Distance matrix of N-th Track to the M-th detectedCentroid + distMatrix_t Cost(N * M); + + // calculate distance between the blobs centroids + for (size_t i = 0; i < tracks.size(); i++) + { + for (size_t j = 0; j < detectedCentroid.size(); j++) + { + Cost[i + j * N] = tracks[i]->CalcDist(detectedCentroid[j]); + } + } + + // ----------------------------------- + // Solving assignment problem (tracks and predictions of Kalman filter) + // ----------------------------------- + AssignmentProblemSolver APS; + APS.Solve(Cost, N, M, assignment, AssignmentProblemSolver::optimal); + + // ----------------------------------- + // clean assignment from pairs with large distance + // ----------------------------------- + for (size_t i = 0; i < assignment.size(); i++) + { + if (assignment[i] != -1) + { + if (Cost[i + assignment[i] * N] > params.dist_thresh) + { + assignment[i] = -1; + tracks[i]->skipped_frames = 1; + } + } + else + { + // If track have no assigned detect, then increment skipped frames counter. + tracks[i]->skipped_frames++; + } + } + + // ----------------------------------- + // If track didn't get detects long time, remove it. + // ----------------------------------- + for (int i = 0; i < static_cast(tracks.size()); i++) + { + if (tracks[i]->skipped_frames > params.max_allowed_skipped_frames) + { + tracks.erase(tracks.begin() + i); + assignment.erase(assignment.begin() + i); + i--; + } + } + } + + // ----------------------------------- + // Search for unassigned detects and start new tracks for them. + // ----------------------------------- + for (size_t i = 0; i < detectedCentroid.size(); ++i) + { + if (find(assignment.begin(), assignment.end(), i) == assignment.end()) + { + tracks.push_back(std::unique_ptr(new CTrack(detectedCentroid[i], contours[i], params.dt, NextTrackID++))); + } + } + + // Update Kalman Filters state + + for (size_t i = 0; i < assignment.size(); i++) + { + // If track updated less than one time, than filter state is not correct. + + if (assignment[i] != -1) // If we have assigned detect, then update using its coordinates, + { + tracks[i]->skipped_frames = 0; + tracks[i]->Update(detectedCentroid[assignment[i]], contours[assignment[i]], true, params.max_trace_length); + } + else // if not continue using predictions + { + tracks[i]->Update(Point_t(), std::vector(), false, params.max_trace_length); + } + } +} + +void CTracker::updateParameters(const Params ¶meters) +{ + params = parameters; +} +// --------------------------------------------------------------------------- +// +// --------------------------------------------------------------------------- +CTracker::~CTracker(void) {} diff --git a/navigations/costmap_converter/src/costmap_to_dynamic_obstacles/multitarget_tracker/HungarianAlg.cpp b/navigations/costmap_converter/src/costmap_to_dynamic_obstacles/multitarget_tracker/HungarianAlg.cpp new file mode 100755 index 0000000..33ef4b9 --- /dev/null +++ b/navigations/costmap_converter/src/costmap_to_dynamic_obstacles/multitarget_tracker/HungarianAlg.cpp @@ -0,0 +1,732 @@ +// Based on https://github.com/Smorodov/Multitarget-tracker/tree/master/Tracker, GPLv3 +// Refer to README.md in this directory. + +#include +#include + +AssignmentProblemSolver::AssignmentProblemSolver() {} + +AssignmentProblemSolver::~AssignmentProblemSolver() {} + +track_t AssignmentProblemSolver::Solve(const distMatrix_t& distMatrixIn, size_t nOfRows, size_t nOfColumns, + std::vector& assignment, TMethod Method) +{ + assignment.resize(nOfRows, -1); + + track_t cost = 0; + + switch (Method) + { + case optimal: + assignmentoptimal(assignment, cost, distMatrixIn, nOfRows, nOfColumns); + break; + + case many_forbidden_assignments: + assignmentsuboptimal1(assignment, cost, distMatrixIn, nOfRows, nOfColumns); + break; + + case without_forbidden_assignments: + assignmentsuboptimal2(assignment, cost, distMatrixIn, nOfRows, nOfColumns); + break; + } + + return cost; +} +// -------------------------------------------------------------------------- +// Computes the optimal assignment (minimum overall costs) using Munkres algorithm. +// -------------------------------------------------------------------------- +void AssignmentProblemSolver::assignmentoptimal(assignments_t& assignment, track_t& cost, + const distMatrix_t& distMatrixIn, size_t nOfRows, size_t nOfColumns) +{ + // Generate distance cv::Matrix + // and check cv::Matrix elements positiveness :) + + // Total elements number + size_t nOfElements = nOfRows * nOfColumns; + // Memory allocation + track_t* distMatrix = (track_t*)malloc(nOfElements * sizeof(track_t)); + // Pointer to last element + track_t* distMatrixEnd = distMatrix + nOfElements; + + for (size_t row = 0; row < nOfElements; row++) + { + track_t value = distMatrixIn[row]; + assert(value >= 0); + distMatrix[row] = value; + } + + // Memory allocation + bool* coveredColumns = (bool*)calloc(nOfColumns, sizeof(bool)); + bool* coveredRows = (bool*)calloc(nOfRows, sizeof(bool)); + bool* starMatrix = (bool*)calloc(nOfElements, sizeof(bool)); + bool* primeMatrix = (bool*)calloc(nOfElements, sizeof(bool)); + bool* newStarMatrix = (bool*)calloc(nOfElements, sizeof(bool)); /* used in step4 */ + + /* preliminary steps */ + if (nOfRows <= nOfColumns) + { + for (size_t row = 0; row < nOfRows; row++) + { + /* find the smallest element in the row */ + track_t* distMatrixTemp = distMatrix + row; + track_t minValue = *distMatrixTemp; + distMatrixTemp += nOfRows; + while (distMatrixTemp < distMatrixEnd) + { + track_t value = *distMatrixTemp; + if (value < minValue) + { + minValue = value; + } + distMatrixTemp += nOfRows; + } + /* subtract the smallest element from each element of the row */ + distMatrixTemp = distMatrix + row; + while (distMatrixTemp < distMatrixEnd) + { + *distMatrixTemp -= minValue; + distMatrixTemp += nOfRows; + } + } + /* Steps 1 and 2a */ + for (size_t row = 0; row < nOfRows; row++) + { + for (size_t col = 0; col < nOfColumns; col++) + { + if (distMatrix[row + nOfRows * col] == 0) + { + if (!coveredColumns[col]) + { + starMatrix[row + nOfRows * col] = true; + coveredColumns[col] = true; + break; + } + } + } + } + } + else /* if(nOfRows > nOfColumns) */ + { + for (size_t col = 0; col < nOfColumns; col++) + { + /* find the smallest element in the column */ + track_t* distMatrixTemp = distMatrix + nOfRows * col; + track_t* columnEnd = distMatrixTemp + nOfRows; + track_t minValue = *distMatrixTemp++; + while (distMatrixTemp < columnEnd) + { + track_t value = *distMatrixTemp++; + if (value < minValue) + { + minValue = value; + } + } + /* subtract the smallest element from each element of the column */ + distMatrixTemp = distMatrix + nOfRows * col; + while (distMatrixTemp < columnEnd) + { + *distMatrixTemp++ -= minValue; + } + } + /* Steps 1 and 2a */ + for (size_t col = 0; col < nOfColumns; col++) + { + for (size_t row = 0; row < nOfRows; row++) + { + if (distMatrix[row + nOfRows * col] == 0) + { + if (!coveredRows[row]) + { + starMatrix[row + nOfRows * col] = true; + coveredColumns[col] = true; + coveredRows[row] = true; + break; + } + } + } + } + + for (size_t row = 0; row < nOfRows; row++) + { + coveredRows[row] = false; + } + } + /* move to step 2b */ + step2b(assignment, distMatrix, starMatrix, newStarMatrix, primeMatrix, coveredColumns, coveredRows, nOfRows, + nOfColumns, (nOfRows <= nOfColumns) ? nOfRows : nOfColumns); + /* compute cost and remove invalid assignments */ + computeassignmentcost(assignment, cost, distMatrixIn, nOfRows); + /* free allocated memory */ + free(distMatrix); + free(coveredColumns); + free(coveredRows); + free(starMatrix); + free(primeMatrix); + free(newStarMatrix); + return; +} +// -------------------------------------------------------------------------- +// +// -------------------------------------------------------------------------- +void AssignmentProblemSolver::buildassignmentvector(assignments_t& assignment, bool* starMatrix, size_t nOfRows, + size_t nOfColumns) +{ + for (size_t row = 0; row < nOfRows; row++) + { + for (size_t col = 0; col < nOfColumns; col++) + { + if (starMatrix[row + nOfRows * col]) + { + assignment[row] = static_cast(col); + break; + } + } + } +} +// -------------------------------------------------------------------------- +// +// -------------------------------------------------------------------------- +void AssignmentProblemSolver::computeassignmentcost(const assignments_t& assignment, track_t& cost, + const distMatrix_t& distMatrixIn, size_t nOfRows) +{ + for (size_t row = 0; row < nOfRows; row++) + { + const int col = assignment[row]; + if (col >= 0) + { + cost += distMatrixIn[row + nOfRows * col]; + } + } +} + +// -------------------------------------------------------------------------- +// +// -------------------------------------------------------------------------- +void AssignmentProblemSolver::step2a(assignments_t& assignment, track_t* distMatrix, bool* starMatrix, + bool* newStarMatrix, bool* primeMatrix, bool* coveredColumns, bool* coveredRows, + size_t nOfRows, size_t nOfColumns, size_t minDim) +{ + bool* starMatrixTemp, *columnEnd; + /* cover every column containing a starred zero */ + for (size_t col = 0; col < nOfColumns; col++) + { + starMatrixTemp = starMatrix + nOfRows * col; + columnEnd = starMatrixTemp + nOfRows; + while (starMatrixTemp < columnEnd) + { + if (*starMatrixTemp++) + { + coveredColumns[col] = true; + break; + } + } + } + /* move to step 3 */ + step2b(assignment, distMatrix, starMatrix, newStarMatrix, primeMatrix, coveredColumns, coveredRows, nOfRows, + nOfColumns, minDim); +} + +// -------------------------------------------------------------------------- +// +// -------------------------------------------------------------------------- +void AssignmentProblemSolver::step2b(assignments_t& assignment, track_t* distMatrix, bool* starMatrix, + bool* newStarMatrix, bool* primeMatrix, bool* coveredColumns, bool* coveredRows, + size_t nOfRows, size_t nOfColumns, size_t minDim) +{ + /* count covered columns */ + size_t nOfCoveredColumns = 0; + for (size_t col = 0; col < nOfColumns; col++) + { + if (coveredColumns[col]) + { + nOfCoveredColumns++; + } + } + if (nOfCoveredColumns == minDim) + { + /* algorithm finished */ + buildassignmentvector(assignment, starMatrix, nOfRows, nOfColumns); + } + else + { + /* move to step 3 */ + step3(assignment, distMatrix, starMatrix, newStarMatrix, primeMatrix, coveredColumns, coveredRows, nOfRows, + nOfColumns, minDim); + } +} + +// -------------------------------------------------------------------------- +// +// -------------------------------------------------------------------------- +void AssignmentProblemSolver::step3(assignments_t& assignment, track_t* distMatrix, bool* starMatrix, + bool* newStarMatrix, bool* primeMatrix, bool* coveredColumns, bool* coveredRows, + size_t nOfRows, size_t nOfColumns, size_t minDim) +{ + bool zerosFound = true; + while (zerosFound) + { + zerosFound = false; + for (size_t col = 0; col < nOfColumns; col++) + { + if (!coveredColumns[col]) + { + for (size_t row = 0; row < nOfRows; row++) + { + if ((!coveredRows[row]) && (distMatrix[row + nOfRows * col] == 0)) + { + /* prime zero */ + primeMatrix[row + nOfRows * col] = true; + /* find starred zero in current row */ + size_t starCol = 0; + for (; starCol < nOfColumns; starCol++) + { + if (starMatrix[row + nOfRows * starCol]) + { + break; + } + } + if (starCol == nOfColumns) /* no starred zero found */ + { + /* move to step 4 */ + step4(assignment, distMatrix, starMatrix, newStarMatrix, primeMatrix, coveredColumns, coveredRows, + nOfRows, nOfColumns, minDim, row, col); + return; + } + else + { + coveredRows[row] = true; + coveredColumns[starCol] = false; + zerosFound = true; + break; + } + } + } + } + } + } + /* move to step 5 */ + step5(assignment, distMatrix, starMatrix, newStarMatrix, primeMatrix, coveredColumns, coveredRows, nOfRows, + nOfColumns, minDim); +} + +// -------------------------------------------------------------------------- +// +// -------------------------------------------------------------------------- +void AssignmentProblemSolver::step4(assignments_t& assignment, track_t* distMatrix, bool* starMatrix, + bool* newStarMatrix, bool* primeMatrix, bool* coveredColumns, bool* coveredRows, + size_t nOfRows, size_t nOfColumns, size_t minDim, size_t row, size_t col) +{ + const size_t nOfElements = nOfRows * nOfColumns; + /* generate temporary copy of starMatrix */ + for (size_t n = 0; n < nOfElements; n++) + { + newStarMatrix[n] = starMatrix[n]; + } + /* star current zero */ + newStarMatrix[row + nOfRows * col] = true; + /* find starred zero in current column */ + size_t starCol = col; + size_t starRow = 0; + for (; starRow < nOfRows; starRow++) + { + if (starMatrix[starRow + nOfRows * starCol]) + { + break; + } + } + while (starRow < nOfRows) + { + /* unstar the starred zero */ + newStarMatrix[starRow + nOfRows * starCol] = false; + /* find primed zero in current row */ + size_t primeRow = starRow; + size_t primeCol = 0; + for (; primeCol < nOfColumns; primeCol++) + { + if (primeMatrix[primeRow + nOfRows * primeCol]) + { + break; + } + } + /* star the primed zero */ + newStarMatrix[primeRow + nOfRows * primeCol] = true; + /* find starred zero in current column */ + starCol = primeCol; + for (starRow = 0; starRow < nOfRows; starRow++) + { + if (starMatrix[starRow + nOfRows * starCol]) + { + break; + } + } + } + /* use temporary copy as new starMatrix */ + /* delete all primes, uncover all rows */ + for (size_t n = 0; n < nOfElements; n++) + { + primeMatrix[n] = false; + starMatrix[n] = newStarMatrix[n]; + } + for (size_t n = 0; n < nOfRows; n++) + { + coveredRows[n] = false; + } + /* move to step 2a */ + step2a(assignment, distMatrix, starMatrix, newStarMatrix, primeMatrix, coveredColumns, coveredRows, nOfRows, + nOfColumns, minDim); +} + +// -------------------------------------------------------------------------- +// +// -------------------------------------------------------------------------- +void AssignmentProblemSolver::step5(assignments_t& assignment, track_t* distMatrix, bool* starMatrix, + bool* newStarMatrix, bool* primeMatrix, bool* coveredColumns, bool* coveredRows, + size_t nOfRows, size_t nOfColumns, size_t minDim) +{ + /* find smallest uncovered element h */ + float h = std::numeric_limits::max(); + for (size_t row = 0; row < nOfRows; row++) + { + if (!coveredRows[row]) + { + for (size_t col = 0; col < nOfColumns; col++) + { + if (!coveredColumns[col]) + { + const float value = distMatrix[row + nOfRows * col]; + if (value < h) + { + h = value; + } + } + } + } + } + /* add h to each covered row */ + for (size_t row = 0; row < nOfRows; row++) + { + if (coveredRows[row]) + { + for (size_t col = 0; col < nOfColumns; col++) + { + distMatrix[row + nOfRows * col] += h; + } + } + } + /* subtract h from each uncovered column */ + for (size_t col = 0; col < nOfColumns; col++) + { + if (!coveredColumns[col]) + { + for (size_t row = 0; row < nOfRows; row++) + { + distMatrix[row + nOfRows * col] -= h; + } + } + } + /* move to step 3 */ + step3(assignment, distMatrix, starMatrix, newStarMatrix, primeMatrix, coveredColumns, coveredRows, nOfRows, + nOfColumns, minDim); +} + +// -------------------------------------------------------------------------- +// Computes a suboptimal solution. Good for cases without forbidden assignments. +// -------------------------------------------------------------------------- +void AssignmentProblemSolver::assignmentsuboptimal2(assignments_t& assignment, track_t& cost, + const distMatrix_t& distMatrixIn, size_t nOfRows, size_t nOfColumns) +{ + /* make working copy of distance Matrix */ + const size_t nOfElements = nOfRows * nOfColumns; + float* distMatrix = (float*)malloc(nOfElements * sizeof(float)); + for (size_t n = 0; n < nOfElements; n++) + { + distMatrix[n] = distMatrixIn[n]; + } + + /* recursively search for the minimum element and do the assignment */ + for (;;) + { + /* find minimum distance observation-to-track pair */ + float minValue = std::numeric_limits::max(); + size_t tmpRow = 0; + size_t tmpCol = 0; + for (size_t row = 0; row < nOfRows; row++) + { + for (size_t col = 0; col < nOfColumns; col++) + { + const float value = distMatrix[row + nOfRows * col]; + if (value != std::numeric_limits::max() && (value < minValue)) + { + minValue = value; + tmpRow = row; + tmpCol = col; + } + } + } + + if (minValue != std::numeric_limits::max()) + { + assignment[tmpRow] = static_cast(tmpCol); + cost += minValue; + for (size_t n = 0; n < nOfRows; n++) + { + distMatrix[n + nOfRows * tmpCol] = std::numeric_limits::max(); + } + for (size_t n = 0; n < nOfColumns; n++) + { + distMatrix[tmpRow + nOfRows * n] = std::numeric_limits::max(); + } + } + else + { + break; + } + } + + free(distMatrix); +} +// -------------------------------------------------------------------------- +// Computes a suboptimal solution. Good for cases with many forbidden assignments. +// -------------------------------------------------------------------------- +void AssignmentProblemSolver::assignmentsuboptimal1(assignments_t& assignment, track_t& cost, + const distMatrix_t& distMatrixIn, size_t nOfRows, size_t nOfColumns) +{ + /* make working copy of distance Matrix */ + const size_t nOfElements = nOfRows * nOfColumns; + float* distMatrix = (float*)malloc(nOfElements * sizeof(float)); + for (size_t n = 0; n < nOfElements; n++) + { + distMatrix[n] = distMatrixIn[n]; + } + + /* allocate memory */ + int* nOfValidObservations = (int*)calloc(nOfRows, sizeof(int)); + int* nOfValidTracks = (int*)calloc(nOfColumns, sizeof(int)); + + /* compute number of validations */ + bool infiniteValueFound = false; + bool finiteValueFound = false; + for (size_t row = 0; row < nOfRows; row++) + { + for (size_t col = 0; col < nOfColumns; col++) + { + if (distMatrix[row + nOfRows * col] != std::numeric_limits::max()) + { + nOfValidTracks[col] += 1; + nOfValidObservations[row] += 1; + finiteValueFound = true; + } + else + { + infiniteValueFound = true; + } + } + } + + if (infiniteValueFound) + { + if (!finiteValueFound) + { + free(nOfValidTracks); + free(nOfValidObservations); + free(distMatrix); + return; + } + bool repeatSteps = true; + + while (repeatSteps) + { + repeatSteps = false; + + /* step 1: reject assignments of multiply validated tracks to singly validated observations */ + for (size_t col = 0; col < nOfColumns; col++) + { + bool singleValidationFound = false; + for (size_t row = 0; row < nOfRows; row++) + { + if (distMatrix[row + nOfRows * col] != std::numeric_limits::max() && + (nOfValidObservations[row] == 1)) + { + singleValidationFound = true; + break; + } + + if (singleValidationFound) + { + for (size_t row = 0; row < nOfRows; row++) + if ((nOfValidObservations[row] > 1) && + distMatrix[row + nOfRows * col] != std::numeric_limits::max()) + { + distMatrix[row + nOfRows * col] = std::numeric_limits::max(); + nOfValidObservations[row] -= 1; + nOfValidTracks[col] -= 1; + repeatSteps = true; + } + } + } + } + + /* step 2: reject assignments of multiply validated observations to singly validated tracks */ + if (nOfColumns > 1) + { + for (size_t row = 0; row < nOfRows; row++) + { + bool singleValidationFound = false; + for (size_t col = 0; col < nOfColumns; col++) + { + if (distMatrix[row + nOfRows * col] != std::numeric_limits::max() && (nOfValidTracks[col] == 1)) + { + singleValidationFound = true; + break; + } + } + + if (singleValidationFound) + { + for (size_t col = 0; col < nOfColumns; col++) + { + if ((nOfValidTracks[col] > 1) && distMatrix[row + nOfRows * col] != std::numeric_limits::max()) + { + distMatrix[row + nOfRows * col] = std::numeric_limits::max(); + nOfValidObservations[row] -= 1; + nOfValidTracks[col] -= 1; + repeatSteps = true; + } + } + } + } + } + } /* while(repeatSteps) */ + + /* for each multiply validated track that validates only with singly validated */ + /* observations, choose the observation with minimum distance */ + for (size_t row = 0; row < nOfRows; row++) + { + if (nOfValidObservations[row] > 1) + { + bool allSinglyValidated = true; + float minValue = std::numeric_limits::max(); + size_t tmpCol = 0; + for (size_t col = 0; col < nOfColumns; col++) + { + const float value = distMatrix[row + nOfRows * col]; + if (value != std::numeric_limits::max()) + { + if (nOfValidTracks[col] > 1) + { + allSinglyValidated = false; + break; + } + else if ((nOfValidTracks[col] == 1) && (value < minValue)) + { + tmpCol = col; + minValue = value; + } + } + } + + if (allSinglyValidated) + { + assignment[row] = static_cast(tmpCol); + cost += minValue; + for (size_t n = 0; n < nOfRows; n++) + { + distMatrix[n + nOfRows * tmpCol] = std::numeric_limits::max(); + } + for (size_t n = 0; n < nOfColumns; n++) + { + distMatrix[row + nOfRows * n] = std::numeric_limits::max(); + } + } + } + } + + // for each multiply validated observation that validates only with singly validated track, choose the track with + // minimum distance + for (size_t col = 0; col < nOfColumns; col++) + { + if (nOfValidTracks[col] > 1) + { + bool allSinglyValidated = true; + float minValue = std::numeric_limits::max(); + size_t tmpRow = 0; + for (size_t row = 0; row < nOfRows; row++) + { + const float value = distMatrix[row + nOfRows * col]; + if (value != std::numeric_limits::max()) + { + if (nOfValidObservations[row] > 1) + { + allSinglyValidated = false; + break; + } + else if ((nOfValidObservations[row] == 1) && (value < minValue)) + { + tmpRow = row; + minValue = value; + } + } + } + + if (allSinglyValidated) + { + assignment[tmpRow] = static_cast(col); + cost += minValue; + for (size_t n = 0; n < nOfRows; n++) + { + distMatrix[n + nOfRows * col] = std::numeric_limits::max(); + } + for (size_t n = 0; n < nOfColumns; n++) + { + distMatrix[tmpRow + nOfRows * n] = std::numeric_limits::max(); + } + } + } + } + } /* if(infiniteValueFound) */ + + /* now, recursively search for the minimum element and do the assignment */ + for (;;) + { + /* find minimum distance observation-to-track pair */ + float minValue = std::numeric_limits::max(); + size_t tmpRow = 0; + size_t tmpCol = 0; + for (size_t row = 0; row < nOfRows; row++) + { + for (size_t col = 0; col < nOfColumns; col++) + { + const float value = distMatrix[row + nOfRows * col]; + if (value != std::numeric_limits::max() && (value < minValue)) + { + minValue = value; + tmpRow = row; + tmpCol = col; + } + } + } + + if (minValue != std::numeric_limits::max()) + { + assignment[tmpRow] = static_cast(tmpCol); + cost += minValue; + for (size_t n = 0; n < nOfRows; n++) + { + distMatrix[n + nOfRows * tmpCol] = std::numeric_limits::max(); + } + for (size_t n = 0; n < nOfColumns; n++) + { + distMatrix[tmpRow + nOfRows * n] = std::numeric_limits::max(); + } + } + else + { + break; + } + } + + /* free allocated memory */ + free(nOfValidObservations); + free(nOfValidTracks); + free(distMatrix); +} diff --git a/navigations/costmap_converter/src/costmap_to_dynamic_obstacles/multitarget_tracker/Kalman.cpp b/navigations/costmap_converter/src/costmap_to_dynamic_obstacles/multitarget_tracker/Kalman.cpp new file mode 100755 index 0000000..7bf8e71 --- /dev/null +++ b/navigations/costmap_converter/src/costmap_to_dynamic_obstacles/multitarget_tracker/Kalman.cpp @@ -0,0 +1,99 @@ +// Based on https://github.com/Smorodov/Multitarget-tracker/tree/master/Tracker, GPLv3 +// Refer to README.md in this directory. + +#include +#include "opencv2/opencv.hpp" +#include +#include + +//--------------------------------------------------------------------------- +//--------------------------------------------------------------------------- +TKalmanFilter::TKalmanFilter(Point_t pt, track_t deltatime) +{ + // time increment (lower values makes target more "massive") + dt = deltatime; + + // 6 state variables [x y z xdot ydot zdot], 3 measurements [x y z] + kalman = new cv::KalmanFilter(6, 3, 0); + // Transition cv::Matrix + kalman->transitionMatrix = (cv::Mat_(6, 6) << + 1, 0, 0, dt, 0, 0, + 0, 1, 0, 0, dt, 0, + 0, 0, 1, 0, 0, dt, + 0, 0, 0, 1, 0, 0, + 0, 0, 0, 0, 1, 0, + 0, 0, 0, 0, 0, 1); + // init... + LastPosition = pt; + kalman->statePre.at(0) = pt.x; + kalman->statePre.at(1) = pt.y; + kalman->statePre.at(2) = pt.z; + + kalman->statePre.at(3) = 0; + kalman->statePre.at(4) = 0; + kalman->statePre.at(5) = 0; + + kalman->statePost.at(0) = pt.x; + kalman->statePost.at(1) = pt.y; + kalman->statePost.at(2) = pt.z; + + // Nur x, y und z Koordinaten messbar! + kalman->measurementMatrix = (cv::Mat_(3, 6) << + 1, 0, 0, 0, 0, 0, + 0, 1, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0); + + float sigma = 0.5; // Assume standard deviation for acceleration, todo: dynamic reconfigure + float c1 = pow(dt,4.0)/4.0; + float c2 = pow(dt,2.0); + float c3 = pow(dt,3.0)/2.0; + kalman->processNoiseCov = sigma*sigma*(cv::Mat_(6, 6) << + c1, 0, 0, c3, 0, 0, + 0, c1, 0, 0, c3, 0, + 0, 0, c1, 0, 0, c3, + c3, 0, 0, c2, 0, 0, + 0, c3, 0, 0, c2, 0, + 0, 0, c3, 0, 0, c2); + + cv::setIdentity(kalman->measurementNoiseCov, cv::Scalar::all(5e-2)); + + cv::setIdentity(kalman->errorCovPost, cv::Scalar::all(1000000)); +} +//--------------------------------------------------------------------------- +TKalmanFilter::~TKalmanFilter() { delete kalman; } + +//--------------------------------------------------------------------------- +void TKalmanFilter::Prediction() +{ + cv::Mat prediction = kalman->predict(); + LastPosition = Point_t(prediction.at(0), prediction.at(1), prediction.at(2)); + LastVelocity = Point_t(prediction.at(3), prediction.at(4), prediction.at(5)); +} + +//--------------------------------------------------------------------------- +Point_t TKalmanFilter::Update(Point_t p, bool DataCorrect) +{ + cv::Mat measurement(3, 1, Mat_t(1)); + if (!DataCorrect) + { + measurement.at(0) = LastPosition.x; // update using prediction + measurement.at(1) = LastPosition.y; + measurement.at(2) = LastPosition.z; + } + else + { + measurement.at(0) = p.x; // update using measurements + measurement.at(1) = p.y; + measurement.at(2) = p.z; + } + // Correction + cv::Mat estimated = kalman->correct(measurement); + LastPosition.x = estimated.at(0); // update using measurements + LastPosition.y = estimated.at(1); + LastPosition.z = estimated.at(2); + LastVelocity.x = estimated.at(3); + LastVelocity.y = estimated.at(4); + LastVelocity.z = estimated.at(5); + return LastPosition; +} +//--------------------------------------------------------------------------- diff --git a/navigations/costmap_converter/src/costmap_to_dynamic_obstacles/multitarget_tracker/README.md b/navigations/costmap_converter/src/costmap_to_dynamic_obstacles/multitarget_tracker/README.md new file mode 100755 index 0000000..3fb4614 --- /dev/null +++ b/navigations/costmap_converter/src/costmap_to_dynamic_obstacles/multitarget_tracker/README.md @@ -0,0 +1,13 @@ +Multitarget Tracker +=================== + +This code is mostly copied from the (MultitargetTracker)[https://github.com/Smorodov/Multitarget-tracker]. +It is utilized for the *CostmapToDynamicObstacles* plugin. + +The *MultitargetTracker* is licensed under (GNU GPLv3)[https://www.gnu.org/licenses/gpl-3.0.txt]. +The package itself depends on other third party packages with different licenses (refer to the package repository). + +TODO: Include the whole package as external CMake project. + + + diff --git a/navigations/costmap_converter/src/costmap_to_lines_convex_hull.cpp b/navigations/costmap_converter/src/costmap_to_lines_convex_hull.cpp new file mode 100755 index 0000000..19e71b8 --- /dev/null +++ b/navigations/costmap_converter/src/costmap_to_lines_convex_hull.cpp @@ -0,0 +1,289 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2016, + * TU Dortmund - Institute of Control Theory and Systems Engineering. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the institute nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: Christoph Rösmann, Otniel Rinaldo + *********************************************************************/ + +#include +#include +#include +#include +#include + +PLUGINLIB_EXPORT_CLASS(costmap_converter::CostmapToLinesDBSMCCH, costmap_converter::BaseCostmapToPolygons) + +namespace costmap_converter +{ + +CostmapToLinesDBSMCCH::CostmapToLinesDBSMCCH() : CostmapToPolygonsDBSMCCH() +{ + dynamic_recfg_ = NULL; +} + +CostmapToLinesDBSMCCH::~CostmapToLinesDBSMCCH() +{ + if (dynamic_recfg_ != NULL) + delete dynamic_recfg_; +} + +void CostmapToLinesDBSMCCH::initialize(ros::NodeHandle nh) +{ + // DB SCAN + nh.param("cluster_max_distance", parameter_.max_distance_, 0.4); + nh.param("cluster_min_pts", parameter_.min_pts_, 2); + nh.param("cluster_max_pts", parameter_.max_pts_, 30); + // convex hull + nh.param("convex_hull_min_pt_separation", parameter_.min_keypoint_separation_, 0.1); + parameter_buffered_ = parameter_; + + // Line extraction + nh.param("support_pts_max_dist", support_pts_max_dist_, 0.3); + nh.param("support_pts_max_dist_inbetween", support_pts_max_dist_inbetween_, 1.0); + nh.param("min_support_pts", min_support_pts_, 2); + + // setup dynamic reconfigure + dynamic_recfg_ = new dynamic_reconfigure::Server(nh); + dynamic_reconfigure::Server::CallbackType cb = boost::bind(&CostmapToLinesDBSMCCH::reconfigureCB, this, _1, _2); + dynamic_recfg_->setCallback(cb); + + // deprecated + if (nh.hasParam("support_pts_min_dist_") || nh.hasParam("support_pts_min_dist")) + ROS_WARN("CostmapToLinesDBSMCCH: Parameter 'support_pts_min_dist' is deprecated and not included anymore."); + if (nh.hasParam("min_support_pts_")) + ROS_WARN("CostmapToLinesDBSMCCH: Parameter 'min_support_pts_' is not found. Remove the underscore."); +} + +void CostmapToLinesDBSMCCH::compute() +{ + std::vector< std::vector > clusters; + dbScan(clusters); + + // Create new polygon container + PolygonContainerPtr polygons(new std::vector()); + + + // add convex hulls to polygon container + for (int i = 1; i push_back( geometry_msgs::Polygon() ); + convertPointToPolygon(clusters.front()[i], polygons->back()); + } + } + + // replace shared polygon container + updatePolygonContainer(polygons); +} + +typedef CostmapToLinesDBSMCCH CL; +bool sort_keypoint_x(const std::size_t& i, const std::size_t& j, const std::vector& cluster) +{ return (cluster[i].x& cluster) +{ return (cluster[i].y& cluster, const geometry_msgs::Polygon& polygon, + std::back_insert_iterator< std::vector > lines) +{ + if (polygon.points.empty()) + return; + + if (polygon.points.size() < 2) + { + lines = polygon; // our polygon is just a point, push back onto the output sequence + return; + } + int n = (int)polygon.points.size(); + + for (int i=1; ix - vertex1->x; + double dy = vertex2->y - vertex1->y; +// double norm = std::sqrt(dx*dx + dy*dy); +// dx /= norm; +// dy /= norm; +// for (int j=i; j<(int)polygon.points.size() - 2; ++j) +// { +// const geometry_msgs::Point32* vertex_jp2 = &polygon.points[j+2]; +// double dx2 = vertex_jp2->x - vertex2->x; +// double dy2 = vertex_jp2->y - vertex2->y; +// double norm2 = std::sqrt(dx2*dx2 + dy2*dy2); +// dx2 /= norm2; +// dy2 /= norm2; +// if (std::abs(dx*dx2 + dy*dy2) < 0.05) //~3 degree +// { +// vertex2 = &polygon.points[j+2]; +// i = j; // DO NOT USE "i" afterwards +// } +// else break; +// } + + //Search support points + std::vector support_points; // store indices of cluster + + for (std::size_t k = 0; k < cluster.size(); ++k) + { + bool is_inbetween = false; + double dist_line_to_point = computeDistanceToLineSegment( cluster[k], *vertex1, *vertex2, &is_inbetween ); + + if(is_inbetween && dist_line_to_point <= support_pts_max_dist_) + { + support_points.push_back(k); + continue; + } + } + + // now check if the inlier models a line by checking the minimum distance between all support points (avoid lines over gaps) + // and by checking if the minium number of points is reached // deactivate by setting support_pts_max_dist_inbetween_==0 + bool is_line=true; + if (support_pts_max_dist_inbetween_!=0) + { + if ((int)support_points.size() >= min_support_pts_ + 2) // +2 since start and goal are included + { + // sort points + if (std::abs(dx) >= std::abs(dy)) + std::sort(support_points.begin(), support_points.end(), boost::bind(sort_keypoint_x, _1, _2, boost::cref(cluster))); + else + std::sort(support_points.begin(), support_points.end(), boost::bind(sort_keypoint_y, _1, _2, boost::cref(cluster))); + + // now calculate distances + for (int k = 1; k < int(support_points.size()); ++k) + { + double dist_x = cluster[support_points[k]].x - cluster[support_points[k-1]].x; + double dist_y = cluster[support_points[k]].y - cluster[support_points[k-1]].y; + double dist = std::sqrt( dist_x*dist_x + dist_y*dist_y); + if (dist > support_pts_max_dist_inbetween_) + { + is_line = false; + break; + } + } + + } + else + is_line = false; + } + + if (is_line) + { + // line found: + geometry_msgs::Polygon line; + line.points.push_back(*vertex1); + line.points.push_back(*vertex2); + lines = line; // back insertion + + // remove inlier from list + // iterate in reverse order, otherwise indices are not valid after erasing elements + std::vector::reverse_iterator support_it = support_points.rbegin(); + for (; support_it != support_points.rend(); ++support_it) + { + cluster.erase(cluster.begin() + *support_it); + } + } + else + { + // remove goal, since it will be added in the subsequent iteration + //support_points.pop_back(); + // old: +// // add vertex 1 as single point +// geometry_msgs::Polygon point; +// point.points.push_back(*vertex1); +// lines = point; // back insertion + + // add complete inlier set as points +// for (int k = 0; k < int(support_points.size()); ++k) +// { +// geometry_msgs::Polygon polygon; +// convertPointToPolygon(cluster[support_points[k]], polygon); +// lines = polygon; // back insertion +// } + + // remove inlier from list and add them as point obstacles + // iterate in reverse order, otherwise indices are not valid after erasing elements + std::vector::reverse_iterator support_it = support_points.rbegin(); + for (; support_it != support_points.rend(); ++support_it) + { + geometry_msgs::Polygon polygon; + convertPointToPolygon(cluster[*support_it], polygon); + lines = polygon; // back insertion + + cluster.erase(cluster.begin() + *support_it); + } + } + } + + // add all remaining cluster points, that do not belong to a line + for (int i=0; i<(int)cluster.size();++i) + { + geometry_msgs::Polygon polygon; + convertPointToPolygon(cluster[i], polygon); + lines = polygon; // back insertion + } + +} + +void CostmapToLinesDBSMCCH::reconfigureCB(CostmapToLinesDBSMCCHConfig& config, uint32_t level) +{ + boost::mutex::scoped_lock lock(parameter_mutex_); + parameter_buffered_.max_distance_ = config.cluster_max_distance; + parameter_buffered_.min_pts_ = config.cluster_min_pts; + parameter_buffered_.max_pts_ = config.cluster_max_pts; + parameter_buffered_.min_keypoint_separation_ = config.cluster_min_pts; + support_pts_max_dist_ = config.support_pts_max_dist; + support_pts_max_dist_inbetween_ = config.support_pts_max_dist_inbetween; + min_support_pts_ = config.min_support_pts; +} + + + +}//end namespace costmap_converter + + diff --git a/navigations/costmap_converter/src/costmap_to_lines_ransac.cpp b/navigations/costmap_converter/src/costmap_to_lines_ransac.cpp new file mode 100755 index 0000000..648098c --- /dev/null +++ b/navigations/costmap_converter/src/costmap_to_lines_ransac.cpp @@ -0,0 +1,342 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2016, + * TU Dortmund - Institute of Control Theory and Systems Engineering. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the institute nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: Christoph Rösmann + *********************************************************************/ + +#include +#include +#include +#include + +PLUGINLIB_EXPORT_CLASS(costmap_converter::CostmapToLinesDBSRANSAC, costmap_converter::BaseCostmapToPolygons) + +namespace costmap_converter +{ + +CostmapToLinesDBSRANSAC::CostmapToLinesDBSRANSAC() : CostmapToPolygonsDBSMCCH() +{ + dynamic_recfg_ = NULL; +} + +CostmapToLinesDBSRANSAC::~CostmapToLinesDBSRANSAC() +{ + if (dynamic_recfg_ != NULL) + delete dynamic_recfg_; +} + +void CostmapToLinesDBSRANSAC::initialize(ros::NodeHandle nh) +{ + // DB SCAN + nh.param("cluster_max_distance", parameter_.max_distance_, 0.4); + nh.param("cluster_min_pts", parameter_.min_pts_, 2); + nh.param("cluster_max_pts", parameter_.max_pts_, 30); + // convex hull (only necessary if outlier filtering is enabled) + nh.param("convex_hull_min_pt_separation", parameter_.min_keypoint_separation_, 0.1); + parameter_buffered_ = parameter_; + + // ransac + nh.param("ransac_inlier_distance", ransac_inlier_distance_, 0.2); + nh.param("ransac_min_inliers", ransac_min_inliers_, 10); + nh.param("ransac_no_iterations", ransac_no_iterations_, 2000); + nh.param("ransac_remainig_outliers", ransac_remainig_outliers_, 3); + nh.param("ransac_convert_outlier_pts", ransac_convert_outlier_pts_, true); + nh.param("ransac_filter_remaining_outlier_pts", ransac_filter_remaining_outlier_pts_, false); + + // setup dynamic reconfigure + dynamic_recfg_ = new dynamic_reconfigure::Server(nh); + dynamic_reconfigure::Server::CallbackType cb = boost::bind(&CostmapToLinesDBSRANSAC::reconfigureCB, this, _1, _2); + dynamic_recfg_->setCallback(cb); +} + +void CostmapToLinesDBSRANSAC::compute() +{ + std::vector< std::vector > clusters; + dbScan(clusters); + + // Create new polygon container + PolygonContainerPtr polygons(new std::vector()); + + + // fit lines using ransac for each cluster + for (int i = 1; i ransac_remainig_outliers_) + { +// std::vector inliers; + std::vector outliers; + std::pair model; + if (!lineRansac(clusters[i], ransac_inlier_distance_, ransac_no_iterations_, ransac_min_inliers_, model, NULL, &outliers ) ) + break; + + // add to polygon container + geometry_msgs::Polygon line; + line.points.resize(2); + model.first.toPointMsg(line.points.front()); + model.second.toPointMsg(line.points.back()); + polygons->push_back(line); + + clusters[i] = outliers; + } + // create point polygons for remaining outliers + if (ransac_convert_outlier_pts_) + { + if (ransac_filter_remaining_outlier_pts_) + { + // take edge points of a convex polygon + // these points define a cluster and since all lines are extracted, + // we remove points from the interior... + geometry_msgs::Polygon polygon; + convexHull2(clusters[i], polygon); + for (int j=0; j < (int)polygon.points.size(); ++j) + { + polygons->push_back(geometry_msgs::Polygon()); + convertPointToPolygon(polygon.points[j], polygons->back()); + } + } + else + { + for (int j = 0; j < (int)clusters[i].size(); ++j) + { + polygons->push_back(geometry_msgs::Polygon()); + convertPointToPolygon(clusters[i][j], polygons->back()); + } + } + + } + + + } + + // add our non-cluster points to the polygon container (as single points) + if (!clusters.empty()) + { + for (int i=0; i < clusters.front().size(); ++i) + { + polygons->push_back( geometry_msgs::Polygon() ); + convertPointToPolygon(clusters.front()[i], polygons->back()); + } + } + + // replace shared polygon container + updatePolygonContainer(polygons); +} + + +bool CostmapToLinesDBSRANSAC::lineRansac(const std::vector& data, double inlier_distance, int no_iterations, + int min_inliers, std::pair& best_model, + std::vector* inliers, std::vector* outliers) +{ + if (data.size() < 2 || data.size() < min_inliers) + { + return false; + } + + boost::random::uniform_int_distribution<> distribution(0, data.size()-1); + + std::pair best_model_idx; + int best_no_inliers = -1; + + + for (int i=0; i < no_iterations; ++i) + { + // choose random points to define a line candidate + int start_idx = distribution(rnd_generator_); + int end_idx = start_idx; + while (end_idx == start_idx) + end_idx = distribution(rnd_generator_); + + + // compute inliers + int no_inliers = 0; + for (int j=0; j<(int)data.size(); ++j) + { + if ( isInlier(data[j], data[start_idx], data[end_idx], inlier_distance) ) + ++no_inliers; + } + + if (no_inliers > best_no_inliers) + { + best_no_inliers = no_inliers; + best_model_idx.first = start_idx; + best_model_idx.second = end_idx; + } + } + + best_model.first = data[best_model_idx.first]; + best_model.second = data[best_model_idx.second]; + + if (best_no_inliers < min_inliers) + return false; + + // Now repeat the calculation for the best model in order to obtain the inliers and outliers set + // This might be faster if no_iterations is large, but TEST + if (inliers || outliers) + { + if (inliers) + inliers->clear(); + if (outliers) + outliers->clear(); + + int no_inliers = 0; + for (int i=0; i<(int)data.size(); ++i) + { + if ( isInlier( data[i], best_model.first, best_model.second, inlier_distance ) ) + { + if (inliers) + inliers->push_back( data[i] ); + } + else + { + if (outliers) + outliers->push_back( data[i] ); + } + } + } + + return true; +} + +bool CostmapToLinesDBSRANSAC::linearRegression(const std::vector& data, double& slope, double& intercept, + double* mean_x_out, double* mean_y_out) +{ + if (data.size() < 2) + { + ROS_ERROR("CostmapToLinesDBSRANSAC: at least 2 data points required for linear regression"); + return false; + } + + double mean_x = 0; + double mean_y = 0; + for (int i=0; i<(int)data.size(); ++i) + { + mean_x += data[i].x; + mean_y += data[i].y; + } + mean_x /= double(data.size()); + mean_y /= double(data.size()); + + if (mean_x_out) + *mean_x_out = mean_x; + + if (mean_y_out) + *mean_y_out = mean_y; + + double numerator = 0.0; + double denominator = 0.0; + + for(int i=0; i<(int)data.size(); ++i) + { + double dx = data[i].x - mean_x; + numerator += dx * (data[i].y - mean_y); + denominator += dx*dx; + } + + if (denominator == 0) + { + ROS_ERROR("CostmapToLinesDBSRANSAC: linear regression failed, denominator 0"); + return false; + } + else + slope = numerator / denominator; + + intercept = mean_y - slope * mean_x; + return true; +} + + +void CostmapToLinesDBSRANSAC::reconfigureCB(CostmapToLinesDBSRANSACConfig& config, uint32_t level) +{ + boost::mutex::scoped_lock lock(parameter_mutex_); + parameter_buffered_.max_distance_ = config.cluster_max_distance; + parameter_buffered_.min_pts_ = config.cluster_min_pts; + parameter_buffered_.max_pts_ = config.cluster_max_pts; + parameter_buffered_.min_keypoint_separation_ = config.cluster_min_pts; + ransac_inlier_distance_ = config.ransac_inlier_distance; + ransac_min_inliers_ = config.ransac_min_inliers; + ransac_no_iterations_ = config.ransac_no_iterations; + ransac_remainig_outliers_ = config.ransac_remainig_outliers; + ransac_convert_outlier_pts_ = config.ransac_convert_outlier_pts; + ransac_filter_remaining_outlier_pts_ = config.ransac_filter_remaining_outlier_pts; +} + + +/* +void CostmapToLinesDBSRANSAC::adjustLineLength(const std::vector& data, const KeyPoint& linept1, const KeyPoint& linept2, + KeyPoint& line_start, KeyPoint& line_end) +{ + line_start = linept1; + line_end = linept2; + + // infinite line is defined by linept1 and linept2 + double dir_x = line_end.x - line_start.x; + double dir_y = line_end.y - line_start.y; + double norm = std::sqrt(dir_x*dir_x + dir_y*dir_y); + dir_x /= norm; + dir_y /= norm; + + // project data onto the line and check if the distance is increased in both directions + for (int i=0; i < (int) data.size(); ++i) + { + double dx = data[i].x - line_start.x; + double dy = data[i].y - line_start.y; + // check scalar product at start + double extension = dx*dir_x + dy*dir_y; + if (extension<0) + { + line_start.x -= dir_x*extension; + line_start.y -= dir_y*extension; + } + else + { + dx = data[i].x - line_end.x; + dy = data[i].y - line_end.y; + // check scalar product at end + double extension = dx*dir_x + dy*dir_y; + if (extension>0) + { + line_end.x += dir_x*extension; + line_end.y += dir_y*extension; + } + } + } + +}*/ + + +}//end namespace costmap_converter + + diff --git a/navigations/costmap_converter/src/costmap_to_polygons.cpp b/navigations/costmap_converter/src/costmap_to_polygons.cpp new file mode 100755 index 0000000..537dcb5 --- /dev/null +++ b/navigations/costmap_converter/src/costmap_to_polygons.cpp @@ -0,0 +1,503 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2016, + * TU Dortmund - Institute of Control Theory and Systems Engineering. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the institute nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: Christoph Rösmann, Otniel Rinaldo + *********************************************************************/ + +#include +#include +#include +#include +#include + +PLUGINLIB_EXPORT_CLASS(costmap_converter::CostmapToPolygonsDBSMCCH, costmap_converter::BaseCostmapToPolygons) + +namespace +{ + +/** + * @brief Douglas-Peucker Algorithm for fitting lines into ordered set of points + * + * Douglas-Peucker Algorithm, see https://en.wikipedia.org/wiki/Ramer%E2%80%93Douglas%E2%80%93Peucker_algorithm + * + * @param begin iterator pointing to the begin of the range of points + * @param end interator pointing to the end of the range of points + * @param epsilon distance criteria for removing points if it is closer to the line segment than this + * @param result the simplified polygon + */ +std::vector douglasPeucker(std::vector::iterator begin, + std::vector::iterator end, double epsilon) +{ + if (std::distance(begin, end) <= 2) + { + return std::vector(begin, end); + } + + // Find the point with the maximum distance from the line [begin, end) + double dmax = std::numeric_limits::lowest(); + std::vector::iterator max_dist_it; + std::vector::iterator last = std::prev(end); + for (auto it = std::next(begin); it != last; ++it) + { + double d = costmap_converter::computeSquaredDistanceToLineSegment(*it, *begin, *last); + if (d > dmax) + { + max_dist_it = it; + dmax = d; + } + } + + if (dmax < epsilon * epsilon) + { // termination criterion reached, line is good enough + std::vector result; + result.push_back(*begin); + result.push_back(*last); + return result; + } + + // Recursive calls for the two splitted parts + auto firstLineSimplified = douglasPeucker(begin, std::next(max_dist_it), epsilon); + auto secondLineSimplified = douglasPeucker(max_dist_it, end, epsilon); + + // Combine the two lines into one line and return the merged line. + // Note that we have to skip the first point of the second line, as it is duplicated above. + firstLineSimplified.insert(firstLineSimplified.end(), + std::make_move_iterator(std::next(secondLineSimplified.begin())), + std::make_move_iterator(secondLineSimplified.end())); + return firstLineSimplified; +} + +} // end namespace + +namespace costmap_converter +{ + +CostmapToPolygonsDBSMCCH::CostmapToPolygonsDBSMCCH() : BaseCostmapToPolygons() +{ + costmap_ = NULL; + dynamic_recfg_ = NULL; + neighbor_size_x_ = neighbor_size_y_ = -1; + offset_x_ = offset_y_ = 0.; +} + +CostmapToPolygonsDBSMCCH::~CostmapToPolygonsDBSMCCH() +{ + if (dynamic_recfg_ != NULL) + delete dynamic_recfg_; +} + +void CostmapToPolygonsDBSMCCH::initialize(ros::NodeHandle nh) +{ + costmap_ = NULL; + + nh.param("cluster_max_distance", parameter_.max_distance_, 0.4); + nh.param("cluster_min_pts", parameter_.min_pts_, 2); + nh.param("cluster_max_pts", parameter_.max_pts_, 30); + nh.param("convex_hull_min_pt_separation", parameter_.min_keypoint_separation_, 0.1); + + parameter_buffered_ = parameter_; + + // setup dynamic reconfigure + dynamic_recfg_ = new dynamic_reconfigure::Server(nh); + dynamic_reconfigure::Server::CallbackType cb = boost::bind(&CostmapToPolygonsDBSMCCH::reconfigureCB, this, _1, _2); + dynamic_recfg_->setCallback(cb); +} + + +void CostmapToPolygonsDBSMCCH::compute() +{ + std::vector< std::vector > clusters; + dbScan(clusters); + + // Create new polygon container + PolygonContainerPtr polygons(new std::vector()); + + + // add convex hulls to polygon container + for (std::size_t i = 1; i push_back( geometry_msgs::Polygon() ); + convexHull2(clusters[i], polygons->back() ); + } + + // add our non-cluster points to the polygon container (as single points) + if (!clusters.empty()) + { + for (std::size_t i=0; i < clusters.front().size(); ++i) + { + polygons->push_back( geometry_msgs::Polygon() ); + convertPointToPolygon(clusters.front()[i], polygons->back()); + } + } + + // replace shared polygon container + updatePolygonContainer(polygons); +} + +void CostmapToPolygonsDBSMCCH::setCostmap2D(costmap_2d::Costmap2D *costmap) +{ + if (!costmap) + return; + + costmap_ = costmap; + + updateCostmap2D(); +} + +void CostmapToPolygonsDBSMCCH::updateCostmap2D() +{ + occupied_cells_.clear(); + + if (!costmap_->getMutex()) + { + ROS_ERROR("Cannot update costmap since the mutex pointer is null"); + return; + } + + { // get a copy of our parameters from dynamic reconfigure + boost::mutex::scoped_lock lock(parameter_mutex_); + parameter_ = parameter_buffered_; + } + + costmap_2d::Costmap2D::mutex_t::scoped_lock lock(*costmap_->getMutex()); + + // allocate neighbor lookup + int cells_x = int(costmap_->getSizeInMetersX() / parameter_.max_distance_) + 1; + int cells_y = int(costmap_->getSizeInMetersY() / parameter_.max_distance_) + 1; + + if (cells_x != neighbor_size_x_ || cells_y != neighbor_size_y_) { + neighbor_size_x_ = cells_x; + neighbor_size_y_ = cells_y; + neighbor_lookup_.resize(neighbor_size_x_ * neighbor_size_y_); + } + offset_x_ = costmap_->getOriginX(); + offset_y_ = costmap_->getOriginY(); + for (auto& n : neighbor_lookup_) + n.clear(); + + // get indices of obstacle cells + for(std::size_t i = 0; i < costmap_->getSizeInCellsX(); i++) + { + for(std::size_t j = 0; j < costmap_->getSizeInCellsY(); j++) + { + int value = costmap_->getCost(i,j); + if(value >= costmap_2d::LETHAL_OBSTACLE) + { + double x, y; + costmap_->mapToWorld((unsigned int)i, (unsigned int)j, x, y); + addPoint(x, y); + } + } + } +} + + +void CostmapToPolygonsDBSMCCH::dbScan(std::vector< std::vector >& clusters) +{ + std::vector visited(occupied_cells_.size(), false); + + clusters.clear(); + + //DB Scan Algorithm + int cluster_id = 0; // current cluster_id + clusters.push_back(std::vector()); + for(int i = 0; i< (int)occupied_cells_.size(); i++) + { + if(!visited[i]) //keypoint has not been visited before + { + visited[i] = true; // mark as visited + std::vector neighbors; + regionQuery(i, neighbors); //Find neighbors around the keypoint + if((int)neighbors.size() < parameter_.min_pts_) //If not enough neighbors are found, mark as noise + { + clusters[0].push_back(occupied_cells_[i]); + } + else + { + ++cluster_id; // increment current cluster_id + clusters.push_back(std::vector()); + + // Expand the cluster + clusters[cluster_id].push_back(occupied_cells_[i]); + for(int j = 0; j<(int)neighbors.size(); j++) + { + if ((int)clusters[cluster_id].size() == parameter_.max_pts_) + break; + + if(!visited[neighbors[j]]) //keypoint has not been visited before + { + visited[neighbors[j]] = true; // mark as visited + std::vector further_neighbors; + regionQuery(neighbors[j], further_neighbors); //Find more neighbors around the new keypoint +// if(further_neighbors.size() < min_pts_) +// { +// clusters[0].push_back(occupied_cells[neighbors[j]]); +// } +// else + if ((int)further_neighbors.size() >= parameter_.min_pts_) + { + // neighbors found + neighbors.insert(neighbors.end(), further_neighbors.begin(), further_neighbors.end()); //Add these newfound P' neighbour to P neighbour vector "nb_indeces" + clusters[cluster_id].push_back(occupied_cells_[neighbors[j]]); + } + } + } + } + } + } +} + +void CostmapToPolygonsDBSMCCH::regionQuery(int curr_index, std::vector& neighbors) +{ + neighbors.clear(); + + double dist_sqr_threshold = parameter_.max_distance_ * parameter_.max_distance_; + const KeyPoint& kp = occupied_cells_[curr_index]; + int cx, cy; + pointToNeighborCells(kp, cx,cy); + + // loop over the neighboring cells for looking up the points + const int offsets[9][2] = {{-1, -1}, {0, -1}, {1, -1}, + {-1, 0}, {0, 0}, {1, 0}, + {-1, 1}, {0, 1}, {1, 1}}; + for (int i = 0; i < 9; ++i) + { + int idx = neighborCellsToIndex(cx + offsets[i][0], cy + offsets[i][1]); + if (idx < 0 || idx >= int(neighbor_lookup_.size())) + continue; + const std::vector& pointIndicesToCheck = neighbor_lookup_[idx]; + for (int point_idx : pointIndicesToCheck) { + if (point_idx == curr_index) // point is not a neighbor to itself + continue; + const KeyPoint& other = occupied_cells_[point_idx]; + double dx = other.x - kp.x; + double dy = other.y - kp.y; + double dist_sqr = dx*dx + dy*dy; + if (dist_sqr <= dist_sqr_threshold) + neighbors.push_back(point_idx); + } + } +} + +bool isXCoordinateSmaller(const CostmapToPolygonsDBSMCCH::KeyPoint& p1, const CostmapToPolygonsDBSMCCH::KeyPoint& p2) +{ + return p1.x < p2.x || (p1.x == p2.x && p1.y < p2.y); +} + +void CostmapToPolygonsDBSMCCH::convexHull(std::vector& cluster, geometry_msgs::Polygon& polygon) +{ + //Monotone Chain ConvexHull Algorithm source from http://www.algorithmist.com/index.php/Monotone_Chain_Convex_Hull + + int k = 0; + int n = cluster.size(); + + // sort points according to x coordinate (TODO. is it already sorted due to the map representation?) + std::sort(cluster.begin(), cluster.end(), isXCoordinateSmaller); + + polygon.points.resize(2*n); + + // lower hull + for (int i = 0; i < n; ++i) + { + while (k >= 2 && cross(polygon.points[k-2], polygon.points[k-1], cluster[i]) <= 0) + { + --k; + } + cluster[i].toPointMsg(polygon.points[k]); + ++k; + } + + // upper hull + for (int i = n-2, t = k+1; i >= 0; --i) + { + while (k >= t && cross(polygon.points[k-2], polygon.points[k-1], cluster[i]) <= 0) + { + --k; + } + cluster[i].toPointMsg(polygon.points[k]); + ++k; + } + + + polygon.points.resize(k); // original + // TEST we skip the last point, since in our definition the polygon vertices do not contain the start/end vertex twice. +// polygon.points.resize(k-1); // TODO remove last point from the algorithm above to reduce computational cost + + simplifyPolygon(polygon); +} + + + +void CostmapToPolygonsDBSMCCH::convexHull2(std::vector& cluster, geometry_msgs::Polygon& polygon) +{ + std::vector& P = cluster; + std::vector& points = polygon.points; + + // Sort P by x and y + std::sort(P.begin(), P.end(), isXCoordinateSmaller); + + // the output array H[] will be used as the stack + int i; // array scan index + + // Get the indices of points with min x-coord and min|max y-coord + int minmin = 0, minmax; + double xmin = P[0].x; + for (i = 1; i < (int)P.size(); i++) + if (P[i].x != xmin) break; + minmax = i - 1; + if (minmax == (int)P.size() - 1) + { // degenerate case: all x-coords == xmin + points.push_back(geometry_msgs::Point32()); + P[minmin].toPointMsg(points.back()); + if (P[minmax].y != P[minmin].y) // a nontrivial segment + { + points.push_back(geometry_msgs::Point32()); + P[minmax].toPointMsg(points.back()); + } + // add polygon endpoint + points.push_back(geometry_msgs::Point32()); + P[minmin].toPointMsg(points.back()); + return; + } + + // Get the indices of points with max x-coord and min|max y-coord + int maxmin, maxmax = (int)P.size() - 1; + double xmax = P.back().x; + for (i = P.size() - 2; i >= 0; i--) + if (P[i].x != xmax) break; + maxmin = i+1; + + // Compute the lower hull on the stack H + // push minmin point onto stack + points.push_back(geometry_msgs::Point32()); + P[minmin].toPointMsg(points.back()); + i = minmax; + while (++i <= maxmin) + { + // the lower line joins P[minmin] with P[maxmin] + if (cross(P[minmin], P[maxmin], P[i]) >= 0 && i < maxmin) + continue; // ignore P[i] above or on the lower line + + while (points.size() > 1) // there are at least 2 points on the stack + { + // test if P[i] is left of the line at the stack top + if (cross(points[points.size() - 2], points.back(), P[i]) > 0) + break; // P[i] is a new hull vertex + points.pop_back(); // pop top point off stack + } + // push P[i] onto stack + points.push_back(geometry_msgs::Point32()); + P[i].toPointMsg(points.back()); + } + + // Next, compute the upper hull on the stack H above the bottom hull + if (maxmax != maxmin) // if distinct xmax points + { + // push maxmax point onto stack + points.push_back(geometry_msgs::Point32()); + P[maxmax].toPointMsg(points.back()); + } + int bot = (int)points.size(); // the bottom point of the upper hull stack + i = maxmin; + while (--i >= minmax) + { + // the upper line joins P[maxmax] with P[minmax] + if (cross( P[maxmax], P[minmax], P[i]) >= 0 && i > minmax) + continue; // ignore P[i] below or on the upper line + + while ((int)points.size() > bot) // at least 2 points on the upper stack + { + // test if P[i] is left of the line at the stack top + if (cross(points[points.size() - 2], points.back(), P[i]) > 0) + break; // P[i] is a new hull vertex + points.pop_back(); // pop top point off stack + } + // push P[i] onto stack + points.push_back(geometry_msgs::Point32()); + P[i].toPointMsg(points.back()); + } + if (minmax != minmin) + { + // push joining endpoint onto stack + points.push_back(geometry_msgs::Point32()); + P[minmin].toPointMsg(points.back()); + } + + simplifyPolygon(polygon); +} + +void CostmapToPolygonsDBSMCCH::simplifyPolygon(geometry_msgs::Polygon& polygon) +{ + size_t triangleThreshold = 3; + // check if first and last point are the same. If yes, a triangle has 4 points + if (polygon.points.size() > 1 + && std::abs(polygon.points.front().x - polygon.points.back().x) < 1e-5 + && std::abs(polygon.points.front().y - polygon.points.back().y) < 1e-5) + { + triangleThreshold = 4; + } + if (polygon.points.size() <= triangleThreshold) // nothing to do for triangles or lines + return; + // TODO Reason about better start conditions for splitting lines, e.g., by + // https://en.wikipedia.org/wiki/Rotating_calipers + polygon.points = douglasPeucker(polygon.points.begin(), polygon.points.end(), parameter_.min_keypoint_separation_);; +} + +void CostmapToPolygonsDBSMCCH::updatePolygonContainer(PolygonContainerPtr polygons) +{ + boost::mutex::scoped_lock lock(mutex_); + polygons_ = polygons; +} + + +PolygonContainerConstPtr CostmapToPolygonsDBSMCCH::getPolygons() +{ + boost::mutex::scoped_lock lock(mutex_); + PolygonContainerConstPtr polygons = polygons_; + return polygons; +} + +void CostmapToPolygonsDBSMCCH::reconfigureCB(CostmapToPolygonsDBSMCCHConfig& config, uint32_t level) +{ + boost::mutex::scoped_lock lock(parameter_mutex_); + parameter_buffered_.max_distance_ = config.cluster_max_distance; + parameter_buffered_.min_pts_ = config.cluster_min_pts; + parameter_buffered_.max_pts_ = config.cluster_max_pts; + parameter_buffered_.min_keypoint_separation_ = config.convex_hull_min_pt_separation; +} + +}//end namespace costmap_converter + + diff --git a/navigations/costmap_converter/src/costmap_to_polygons_concave.cpp b/navigations/costmap_converter/src/costmap_to_polygons_concave.cpp new file mode 100755 index 0000000..c84717f --- /dev/null +++ b/navigations/costmap_converter/src/costmap_to_polygons_concave.cpp @@ -0,0 +1,220 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2016, + * TU Dortmund - Institute of Control Theory and Systems Engineering. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the institute nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: Christoph Rösmann, Otniel Rinaldo + *********************************************************************/ + +#include + +#include + +PLUGINLIB_EXPORT_CLASS(costmap_converter::CostmapToPolygonsDBSConcaveHull, costmap_converter::BaseCostmapToPolygons) + +namespace costmap_converter +{ + +CostmapToPolygonsDBSConcaveHull::CostmapToPolygonsDBSConcaveHull() : CostmapToPolygonsDBSMCCH() +{ + dynamic_recfg_ = NULL; +} + +CostmapToPolygonsDBSConcaveHull::~CostmapToPolygonsDBSConcaveHull() +{ + if (dynamic_recfg_ != NULL) + delete dynamic_recfg_; +} + +void CostmapToPolygonsDBSConcaveHull::initialize(ros::NodeHandle nh) +{ + nh.param("cluster_max_distance", parameter_.max_distance_, 0.4); + nh.param("cluster_min_pts", parameter_.min_pts_, 2); + nh.param("cluster_max_pts", parameter_.max_pts_, 30); + nh.param("convex_hull_min_pt_separation", parameter_.min_keypoint_separation_, 0.1); + parameter_buffered_ = parameter_; + + nh.param("concave_hull_depth", concave_hull_depth_, 2.0); + + // setup dynamic reconfigure + dynamic_recfg_ = new dynamic_reconfigure::Server(nh); + dynamic_reconfigure::Server::CallbackType cb = boost::bind(&CostmapToPolygonsDBSConcaveHull::reconfigureCB, this, _1, _2); + dynamic_recfg_->setCallback(cb); +} + + +void CostmapToPolygonsDBSConcaveHull::compute() +{ + std::vector< std::vector > clusters; + dbScan(clusters); + + // Create new polygon container + PolygonContainerPtr polygons(new std::vector()); + + + // add convex hulls to polygon container + for (int i = 1; i push_back( geometry_msgs::Polygon() ); + concaveHull(clusters[i], concave_hull_depth_, polygons->back() ); + } + + // add our non-cluster points to the polygon container (as single points) + if (!clusters.empty()) + { + for (int i=0; i < clusters.front().size(); ++i) + { + polygons->push_back( geometry_msgs::Polygon() ); + convertPointToPolygon(clusters.front()[i], polygons->back()); + } + } + + // replace shared polygon container + updatePolygonContainer(polygons); +} + + +void CostmapToPolygonsDBSConcaveHull::concaveHull(std::vector& cluster, double depth, geometry_msgs::Polygon& polygon) +{ + // start with convex hull + convexHull2(cluster, polygon); + + std::vector& concave_list = polygon.points; + + for (int i = 0; i < (int)concave_list.size() - 1; ++i) + { + + // find nearest inner point pk from line (vertex1 -> vertex2) + const geometry_msgs::Point32& vertex1 = concave_list[i]; + const geometry_msgs::Point32& vertex2 = concave_list[i+1]; + + bool found; + size_t nearest_idx = findNearestInnerPoint(vertex1, vertex2, cluster, concave_list, &found); + if (!found) + continue; + + double line_length = norm2d(vertex1, vertex2); + + double dst1 = norm2d(cluster[nearest_idx], vertex1); + double dst2 = norm2d(cluster[nearest_idx], vertex2); + double dd = std::min(dst1, dst2); + if (dd<1e-8) + continue; + + if (line_length / dd > depth) + { + // Check that new candidate edge will not intersect existing edges. + bool intersects = checkLineIntersection(concave_list, vertex1, vertex2, vertex1, cluster[nearest_idx]); + intersects |= checkLineIntersection(concave_list, vertex1, vertex2, cluster[nearest_idx], vertex2); + if (!intersects) + { + geometry_msgs::Point32 new_point; + cluster[nearest_idx].toPointMsg(new_point); + concave_list.insert(concave_list.begin() + i + 1, new_point); + i--; + } + } + } +} + + +void CostmapToPolygonsDBSConcaveHull::concaveHullClusterCut(std::vector& cluster, double depth, geometry_msgs::Polygon& polygon) +{ + // start with convex hull + convexHull2(cluster, polygon); + + std::vector& concave_list = polygon.points; + + // get line length + double mean_length = 0; + for (int i = 0; i < (int)concave_list.size() - 1; ++i) + { + mean_length += norm2d(concave_list[i],concave_list[i+1]); + } + mean_length /= double(concave_list.size()); + + for (int i = 0; i < (int)concave_list.size() - 1; ++i) + { + + // find nearest inner point pk from line (vertex1 -> vertex2) + const geometry_msgs::Point32& vertex1 = concave_list[i]; + const geometry_msgs::Point32& vertex2 = concave_list[i+1]; + + double line_length = norm2d(vertex1, vertex2); + + bool found; + size_t nearest_idx = findNearestInnerPoint(vertex1, vertex2, cluster, concave_list, &found); + if (!found) + { + continue; + } + + + double dst1 = norm2d(cluster[nearest_idx], vertex1); + double dst2 = norm2d(cluster[nearest_idx], vertex2); + double dd = std::min(dst1, dst2); + if (dd<1e-8) + continue; + + if (line_length / dd > depth) + { + // Check that new candidate edge will not intersect existing edges. + bool intersects = checkLineIntersection(concave_list, vertex1, vertex2, vertex1, cluster[nearest_idx]); + intersects |= checkLineIntersection(concave_list, vertex1, vertex2, cluster[nearest_idx], vertex2); + if (!intersects) + { + geometry_msgs::Point32 new_point; + cluster[nearest_idx].toPointMsg(new_point); + concave_list.insert(concave_list.begin() + i + 1, new_point); + i--; + } + } + } +} + + + + +void CostmapToPolygonsDBSConcaveHull::reconfigureCB(CostmapToPolygonsDBSConcaveHullConfig& config, uint32_t level) +{ + boost::mutex::scoped_lock lock(parameter_mutex_); + parameter_buffered_.max_distance_ = config.cluster_max_distance; + parameter_buffered_.min_pts_ = config.cluster_min_pts; + parameter_buffered_.max_pts_ = config.cluster_max_pts; + parameter_buffered_.min_keypoint_separation_ = config.cluster_min_pts; + concave_hull_depth_ = config.concave_hull_depth; +} + +}//end namespace costmap_converter + + diff --git a/navigations/costmap_converter/test/costmap_polygons.cpp b/navigations/costmap_converter/test/costmap_polygons.cpp new file mode 100755 index 0000000..2ea98cd --- /dev/null +++ b/navigations/costmap_converter/test/costmap_polygons.cpp @@ -0,0 +1,232 @@ +#include +#include +#include + +#include + +namespace { +geometry_msgs::Point32 create_point(double x, double y) +{ + geometry_msgs::Point32 result; + result.x = x; + result.y = y; + result.z = 0.; + return result; +} +} // end namespace + +// make things accesible in the test +class CostmapToPolygons : public costmap_converter::CostmapToPolygonsDBSMCCH +{ + public: + const std::vector& points() const {return occupied_cells_;} + costmap_converter::CostmapToPolygonsDBSMCCH::Parameters& parameters() {return parameter_;} + using costmap_converter::CostmapToPolygonsDBSMCCH::addPoint; + using costmap_converter::CostmapToPolygonsDBSMCCH::regionQuery; + using costmap_converter::CostmapToPolygonsDBSMCCH::dbScan; + using costmap_converter::CostmapToPolygonsDBSMCCH::convexHull2; + using costmap_converter::CostmapToPolygonsDBSMCCH::simplifyPolygon; +}; + +class CostmapToPolygonsDBSMCCHTest : public ::testing::Test +{ + protected: + void SetUp() override { + // parameters + costmap_to_polygons.parameters().max_distance_ = 0.5; + costmap_to_polygons.parameters().max_pts_ = 100; + costmap_to_polygons.parameters().min_pts_ = 2; + costmap_to_polygons.parameters().min_keypoint_separation_ = 0.1; + + costmap.reset(new costmap_2d::Costmap2D(100, 100, 0.1, -5., -5.)); + costmap_to_polygons.setCostmap2D(costmap.get()); + + std::random_device rand_dev; + std::mt19937 generator(rand_dev()); + std::uniform_real_distribution<> random_angle(-M_PI, M_PI); + std::uniform_real_distribution<> random_dist(0., costmap_to_polygons.parameters().max_distance_); + + costmap_to_polygons.addPoint(0., 0.); + costmap_to_polygons.addPoint(1.3, 1.3); + + // adding random points + double center_x = costmap_to_polygons.points()[0].x; + double center_y = costmap_to_polygons.points()[0].y; + for (int i = 0; i < costmap_to_polygons.parameters().max_pts_ - 1; ++i) + { + double alpha = random_angle(generator); + double dist = random_dist(generator); + double wx = center_x + std::cos(alpha) * dist; + double wy = center_y + std::sin(alpha) * dist; + costmap_to_polygons.addPoint(wx, wy); + } + + // some noisy points not belonging to a cluster + costmap_to_polygons.addPoint(-1, -1); + costmap_to_polygons.addPoint(-2, -2); + + // adding random points + center_x = costmap_to_polygons.points()[1].x; + center_y = costmap_to_polygons.points()[1].y; + for (int i = 0; i < costmap_to_polygons.parameters().max_pts_/2; ++i) + { + double alpha = random_angle(generator); + double dist = random_dist(generator); + double wx = center_x + std::cos(alpha) * dist; + double wy = center_y + std::sin(alpha) * dist; + costmap_to_polygons.addPoint(wx, wy); + } + } + + void regionQueryTrivial(int curr_index, std::vector& neighbor_indices) + { + neighbor_indices.clear(); + const auto& query_point = costmap_to_polygons.points()[curr_index]; + for (int i = 0; i < int(costmap_to_polygons.points().size()); ++i) + { + if (i == curr_index) + continue; + const auto& kp = costmap_to_polygons.points()[i]; + double dx = query_point.x - kp.x; + double dy = query_point.y - kp.y; + double dist = sqrt(dx*dx + dy*dy); + if (dist < costmap_to_polygons.parameters().max_distance_) + neighbor_indices.push_back(i); + } + } + + CostmapToPolygons costmap_to_polygons; + std::shared_ptr costmap; +}; + +TEST_F(CostmapToPolygonsDBSMCCHTest, regionQuery) +{ + std::vector neighbors, neighbors_trivial; + costmap_to_polygons.regionQuery(0, neighbors); + regionQueryTrivial(0, neighbors_trivial); + ASSERT_EQ(costmap_to_polygons.parameters().max_pts_ - 1, int(neighbors.size())); + ASSERT_EQ(neighbors_trivial.size(), neighbors.size()); + std::sort(neighbors.begin(), neighbors.end()); + ASSERT_EQ(neighbors_trivial, neighbors); + + costmap_to_polygons.regionQuery(1, neighbors); + regionQueryTrivial(1, neighbors_trivial); + ASSERT_EQ(costmap_to_polygons.parameters().max_pts_/2, int(neighbors.size())); + ASSERT_EQ(neighbors_trivial.size(), neighbors.size()); + std::sort(neighbors.begin(), neighbors.end()); + ASSERT_EQ(neighbors_trivial, neighbors); +} + +TEST_F(CostmapToPolygonsDBSMCCHTest, dbScan) +{ + std::vector< std::vector > clusters; + costmap_to_polygons.dbScan(clusters); + + ASSERT_EQ(3, clusters.size()); + ASSERT_EQ(2, clusters[0].size()); // noisy points not belonging to a cluster + ASSERT_EQ(costmap_to_polygons.parameters().max_pts_, clusters[1].size()); // first cluster at (0,0) + ASSERT_EQ(costmap_to_polygons.parameters().max_pts_/2 + 1, clusters[2].size()); // second cluster at (1,1) +} + +TEST(CostmapToPolygonsDBSMCCH, EmptyMap) +{ + std::shared_ptr costmap = + std::make_shared(costmap_2d::Costmap2D(100, 100, 0.1, -5., -5.)); + CostmapToPolygons costmap_to_polygons; + costmap_to_polygons.setCostmap2D(costmap.get()); + + std::vector< std::vector > clusters; + costmap_to_polygons.dbScan(clusters); + ASSERT_EQ(1, clusters.size()); // noise cluster exists + ASSERT_EQ(0, clusters[0].size()); // noise clsuter is empty +} + +TEST(CostmapToPolygonsDBSMCCH, SimplifyPolygon) +{ + const double simplification_threshold = 0.1; + CostmapToPolygons costmap_to_polygons; + costmap_to_polygons.parameters().min_keypoint_separation_ = simplification_threshold; + + geometry_msgs::Polygon polygon; + polygon.points.push_back(create_point(0., 0.)); + polygon.points.push_back(create_point(1., 0.)); + + // degenerate case with just two points + geometry_msgs::Polygon original_polygon = polygon; + costmap_to_polygons.simplifyPolygon(polygon); + ASSERT_EQ(2, polygon.points.size()); + for (size_t i = 0; i < polygon.points.size(); ++i) + { + ASSERT_FLOAT_EQ(original_polygon.points[i].x, polygon.points[i].x); + ASSERT_FLOAT_EQ(original_polygon.points[i].y, polygon.points[i].y); + } + + // degenerate case with three points + polygon.points.push_back(create_point(1., simplification_threshold / 2.)); + original_polygon = polygon; + costmap_to_polygons.simplifyPolygon(polygon); + ASSERT_EQ(3, polygon.points.size()); + for (size_t i = 0; i < polygon.points.size(); ++i) + { + ASSERT_FLOAT_EQ(original_polygon.points[i].x, polygon.points[i].x); + ASSERT_FLOAT_EQ(original_polygon.points[i].y, polygon.points[i].y); + } + + polygon.points.push_back(create_point(1., 1.)); + original_polygon = polygon; + // remove the point that has to be removed by the simplification + original_polygon.points.erase(original_polygon.points.begin()+2); + costmap_to_polygons.simplifyPolygon(polygon); + ASSERT_EQ(3, polygon.points.size()); + for (size_t i = 0; i < polygon.points.size(); ++i) + { + ASSERT_FLOAT_EQ(original_polygon.points[i].x, polygon.points[i].x); + ASSERT_FLOAT_EQ(original_polygon.points[i].y, polygon.points[i].y); + } +} + +TEST(CostmapToPolygonsDBSMCCH, SimplifyPolygonPerfectLines) +{ + const double simplification_threshold = 0.1; + CostmapToPolygons costmap_to_polygons; + costmap_to_polygons.parameters().min_keypoint_separation_ = simplification_threshold; + + geometry_msgs::Polygon polygon; + for (int i = 0; i <= 100; ++i) + polygon.points.push_back(create_point(i*1., 0.)); + geometry_msgs::Point32 lastPoint = polygon.points.back(); + for (int i = 0; i <= 100; ++i) + polygon.points.push_back(create_point(lastPoint.x, lastPoint.y + i * 1.)); + lastPoint = polygon.points.back(); + for (int i = 0; i <= 100; ++i) + polygon.points.push_back(create_point(lastPoint.x + i * 1., lastPoint.y)); + lastPoint = polygon.points.back(); + for (int i = 0; i <= 100; ++i) + polygon.points.push_back(create_point(lastPoint.x, lastPoint.y + i * 1.)); + lastPoint = polygon.points.back(); + for (int i = 0; i <= 100; ++i) + polygon.points.push_back(create_point(lastPoint.x + i * 1., lastPoint.y)); + + costmap_to_polygons.simplifyPolygon(polygon); + ASSERT_EQ(6, polygon.points.size()); + ASSERT_FLOAT_EQ( 0., polygon.points[0].x); + ASSERT_FLOAT_EQ( 0., polygon.points[0].y); + ASSERT_FLOAT_EQ(100., polygon.points[1].x); + ASSERT_FLOAT_EQ( 0., polygon.points[1].y); + ASSERT_FLOAT_EQ(100., polygon.points[2].x); + ASSERT_FLOAT_EQ(100., polygon.points[2].y); + ASSERT_FLOAT_EQ(200., polygon.points[3].x); + ASSERT_FLOAT_EQ(100., polygon.points[3].y); + ASSERT_FLOAT_EQ(200., polygon.points[4].x); + ASSERT_FLOAT_EQ(200., polygon.points[4].y); + ASSERT_FLOAT_EQ(300., polygon.points[5].x); + ASSERT_FLOAT_EQ(200., polygon.points[5].y); +} + +int main(int argc, char** argv) +{ + testing::InitGoogleTest(&argc, argv); + ros::init(argc, argv, "CostmapConverterTester"); + ros::NodeHandle nh; + return RUN_ALL_TESTS(); +} \ No newline at end of file diff --git a/navigations/costmap_converter/test/costmap_polygons.test b/navigations/costmap_converter/test/costmap_polygons.test new file mode 100755 index 0000000..8f42354 --- /dev/null +++ b/navigations/costmap_converter/test/costmap_polygons.test @@ -0,0 +1,3 @@ + + + diff --git a/navigations/costmap_queue/CMakeLists.txt b/navigations/costmap_queue/CMakeLists.txt new file mode 100755 index 0000000..b76d121 --- /dev/null +++ b/navigations/costmap_queue/CMakeLists.txt @@ -0,0 +1,46 @@ +cmake_minimum_required(VERSION 3.0.2) +project(costmap_queue) + +set_directory_properties(PROPERTIES COMPILE_OPTIONS "-std=c++11;-Wall;-Werror") + +find_package(catkin REQUIRED COMPONENTS + nav_core2 + roscpp +) + +catkin_package( + INCLUDE_DIRS include + CATKIN_DEPENDS nav_core2 roscpp + LIBRARIES ${PROJECT_NAME} +) + +include_directories( + include ${catkin_INCLUDE_DIRS} +) + +add_library(${PROJECT_NAME} + src/costmap_queue.cpp + src/limited_costmap_queue.cpp +) +target_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES}) + +if (CATKIN_ENABLE_TESTING) + catkin_add_gtest(mbq_test test/mbq_test.cpp) + target_link_libraries(mbq_test ${catkin_LIBRARIES}) + + catkin_add_gtest(${PROJECT_NAME}_utest test/utest.cpp) + target_link_libraries(${PROJECT_NAME}_utest ${PROJECT_NAME} ${catkin_LIBRARIES}) + + find_package(roslint REQUIRED) + roslint_cpp() + roslint_add_test() +endif (CATKIN_ENABLE_TESTING) + +install(TARGETS ${PROJECT_NAME} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} +) +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} +) diff --git a/navigations/costmap_queue/README.md b/navigations/costmap_queue/README.md new file mode 100755 index 0000000..2b34cbf --- /dev/null +++ b/navigations/costmap_queue/README.md @@ -0,0 +1,22 @@ +# costmap_queue + +This package contains helper classes that implement one particular common costmap operation: figuring out the distance of every cell to a subset of those cells. + +## Inflation Example +Let's assume you have a grid `G` and you know that there are lethal obstacles in a subset of those cells `O`. You want to mark all cells within distance `r` with one value, and all cells within a greater distance `r2` with another. + +One costly way to do this would be to to iterate through all the cells `g` in `G`, calculate the distance from `g` to each cell in `O`, find the minimum distance, and compare to `r` and `r2`. This is roughly quadratic with the number of cells. + +The more efficient way to do it is to start with all the cells in `O` in a queue. For each cell you dequeue, you calculate the distance to its origin cell from `O` and then enqueue all of its neighbors. This approach is roughly linear with the number of cells, although you need to be careful to not incur too many costs from resorting the queue. + +## Map Based Queue +While this operation could be done with the standard priority queue implementation, it can be optimized by using a custom priority queue based on `std::map`. This relies on the fact that many of the items inserted into the queue will have the same priority. In the `costmap_queue`, the priorities used are distances on the grid, of which there are a finite number. Thus by grouping all of the elements of the same weight into a vector together, and storing them in the `std::map` with their priority, we can eliminate the need to resort after each individual item is popped. This is based on the [optimizations to the Inflation algorithm](https://github.com/ros-planning/navigation/pull/525). + +Also, since the same (or similar) distances will be used in the `costmap_queue` from iteration to iteration, additional time can be saved by not destroying the vectors in the map, and reusing them iteration to iteration. + +## Costmap Queue +The `CostmapQueue` class operates on a `nav_core2::Costmap`. First, you must enqueue all of the "subset" of cells (i.e. `O` in the above example) using `enqueueCell`. Then, while the queue is not empty (i.e. `isEmpty` is false), you can call `costmap_queue::CellData cell = q.getNextCell();` to get the next cell in the queue. + +The `CellData` class contains 5 values: `x_` and `y_` are the coordinates for the current cell, `src_x_` and `src_y_` are the coordinates for the original cell, and `distance_` is the distance between them. + +By default, `CostmapQueue` will iterate through all the cells in the `Costmap`. If you want to limit it to only cells within a certain distance, you can use `LimitedCostmapQueue` instead. diff --git a/navigations/costmap_queue/include/costmap_queue/costmap_queue.h b/navigations/costmap_queue/include/costmap_queue/costmap_queue.h new file mode 100755 index 0000000..e2d97cd --- /dev/null +++ b/navigations/costmap_queue/include/costmap_queue/costmap_queue.h @@ -0,0 +1,190 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef COSTMAP_QUEUE_COSTMAP_QUEUE_H +#define COSTMAP_QUEUE_COSTMAP_QUEUE_H + +#include +#include +#include +#include +#include +#include +#include + +namespace costmap_queue +{ +/** + * @class CellData + * @brief Storage for cell information used during queue expansion + */ +class CellData +{ +public: + /** + * @brief Real Constructor + * @param d The distance to the nearest obstacle + * @param x The x coordinate of the cell in the cost map + * @param y The y coordinate of the cell in the cost map + * @param sx The x coordinate of the closest source cell in the costmap + * @param sy The y coordinate of the closest source cell in the costmap + */ + CellData(const double d, const unsigned int x, const unsigned int y, const unsigned int sx, const unsigned int sy) : + distance_(d), x_(x), y_(y), src_x_(sx), src_y_(sy) + { + } + + /** + * @brief Default Constructor - Should be used sparingly + */ + CellData() : + distance_(std::numeric_limits::max()), x_(0), y_(0), src_x_(0), src_y_(0) + { + } + + double distance_; + unsigned int x_, y_; + unsigned int src_x_, src_y_; +}; + +/** + * @class CostmapQueue + * @brief A tool for finding the cells closest to some set of originating cells. + * + * A common operation with costmaps is to define a set of cells in the costmap, and then + * perform some operation on all the other cells based on which cell in the original set + * the other cells are closest to. This operation is done in the inflation layer to figure out + * how far each cell is from an obstacle, and is also used in a number of Trajectory cost functions. + * + * It is implemented with a queue. The standard operation is to enqueueCell the original set, and then + * retreive the other cells with the isEmpty/getNextCell iterator-like functionality. getNextCell + * returns an object that contains the coordinates of this cell and the origin cell, as well as + * the distance between them. By default, the Euclidean distance is used for ordering, but passing in + * manhattan=true to the constructor will use the Manhattan distance. + * + * The validCellToQueue overridable-function allows for deriving classes to limit the queue traversal + * to a subset of all costmap cells. LimitedCostmapQueue does this by ignoring distances above a limit. + * + */ +class CostmapQueue : public MapBasedQueue +{ +public: + /** + * @brief constructor + * @param costmap Costmap which defines the size/number of cells + * @param manhattan If true, sort cells by Manhattan distance, otherwise use Euclidean distance + */ + explicit CostmapQueue(nav_core2::Costmap& costmap, bool manhattan = false); + + /** + * @brief Clear the queue + */ + void reset() override; + + /** + * @brief Add a cell the queue + * @param x X coordinate of the cell + * @param y Y coordinate of the cell + */ + void enqueueCell(unsigned int x, unsigned int y); + + /** + * @brief Get the next cell to examine, and enqueue its neighbors as needed + * @return The next cell + * + * NB: Assumes that isEmpty has been called before this call and returned false + */ + CellData getNextCell(); + + /** + * @brief Get the maximum x or y distance we'll need to calculate the distance between + */ + virtual int getMaxDistance() const { return std::max(costmap_.getWidth(), costmap_.getHeight()); } + + /** + * @brief Check to see if we should add this cell to the queue. Always true unless overridden. + * @param cell The cell to check + * @return True, unless overriden + */ + virtual bool validCellToQueue(const CellData& cell) { return true; } + + /** + * @brief convenience definition for a pointer + */ + using Ptr = std::shared_ptr; +protected: + /** + * @brief Enqueue a cell with the given coordinates and the given source cell + */ + void enqueueCell(unsigned int cur_x, unsigned int cur_y, unsigned int src_x, unsigned int src_y); + + /** + * @brief Compute the cached distances + */ + void computeCache(); + + nav_core2::Costmap& costmap_; + + // This really should be VectorNavGrid, but since + // vector is wacky, it would result in compile errors. + nav_grid::VectorNavGrid seen_; + bool manhattan_; +protected: + /** + * @brief Lookup pre-computed distances + * @param cur_x The x coordinate of the current cell + * @param cur_y The y coordinate of the current cell + * @param src_x The x coordinate of the source cell + * @param src_y The y coordinate of the source cell + * @return Precomputed distance + * + * NB: Note that while abs() has the correct behavior i.e. abs(2 - 5) ==> 3. + * std::abs() without explicit casting does not have the correct behavior + * i.e. std::abs(2 - 5) ==> (the unsigned version of) -3. + * We're using explicit casting here to ensure the behavior is not compiler dependent. + * std::abs(static_cast(2) - static_cast(5)) ==> 3. + */ + inline double distanceLookup(const unsigned int cur_x, const unsigned int cur_y, + const unsigned int src_x, const unsigned int src_y) + { + unsigned int dx = std::abs(static_cast(cur_x) - static_cast(src_x)); + unsigned int dy = std::abs(static_cast(cur_y) - static_cast(src_y)); + return cached_distances_[dx][dy]; + } + std::vector > cached_distances_; + int cached_max_distance_; +}; +} // namespace costmap_queue + +#endif // COSTMAP_QUEUE_COSTMAP_QUEUE_H diff --git a/navigations/costmap_queue/include/costmap_queue/limited_costmap_queue.h b/navigations/costmap_queue/include/costmap_queue/limited_costmap_queue.h new file mode 100755 index 0000000..a85dd9f --- /dev/null +++ b/navigations/costmap_queue/include/costmap_queue/limited_costmap_queue.h @@ -0,0 +1,61 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef COSTMAP_QUEUE_LIMITED_COSTMAP_QUEUE_H +#define COSTMAP_QUEUE_LIMITED_COSTMAP_QUEUE_H + +#include + +namespace costmap_queue +{ + +/** + * @class LimitedCostmapQueue + * @brief Extension of Costmap Queue where distances are limited to a given distance from source cells. + */ +class LimitedCostmapQueue : public CostmapQueue +{ +public: + /** + * @brief Constructor with limit as an integer number of cells. + */ + LimitedCostmapQueue(nav_core2::Costmap& costmap, const int cell_distance_limit); + bool validCellToQueue(const CellData& cell) override; + int getMaxDistance() const override; +protected: + int max_distance_; +}; +} // namespace costmap_queue + +#endif // COSTMAP_QUEUE_LIMITED_COSTMAP_QUEUE_H diff --git a/navigations/costmap_queue/include/costmap_queue/map_based_queue.h b/navigations/costmap_queue/include/costmap_queue/map_based_queue.h new file mode 100755 index 0000000..4c76093 --- /dev/null +++ b/navigations/costmap_queue/include/costmap_queue/map_based_queue.h @@ -0,0 +1,173 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef COSTMAP_QUEUE_MAP_BASED_QUEUE_H +#define COSTMAP_QUEUE_MAP_BASED_QUEUE_H + +#include +#include +#include +#include +#include + +namespace costmap_queue +{ +/** + * @brief Templatized interface for a priority queue + * + * This is faster than the std::priority_queue implementation in certain cases because iterating does + * not require resorting after every element is examined. + * Based on https://github.com/ros-planning/navigation/pull/525 + * The relative speed of this against the priority queue depends how many items with each + * priority are inserted into the queue. + * + * One additional speed up depends on the patterns of priorities during each iteration of the queue. + * If the same priorities are inserted into the queue on every iteration, then it is quicker to + * set reset_bins = false, such that the priority bins are not reset and will not have to be recreated + * on each iteration. + */ +template +class MapBasedQueue +{ +public: + /** + * @brief Default Constructor + */ + explicit MapBasedQueue(bool reset_bins = true) : reset_bins_(reset_bins), item_count_(0) + { + reset(); + } + + /** + * @brief Clear the queue + */ + virtual void reset() + { + if (reset_bins_ || item_count_ > 0) + { + item_bins_.clear(); + item_count_ = 0; + } + iter_ = last_insert_iter_ = item_bins_.end(); + } + + /** + * @brief Add a new item to the queue with a set priority + * @param priority Priority of the item + * @param item Payload item + */ + void enqueue(const double priority, item_t item) + { + // We keep track of the last priority we inserted. If this items priority matches the previous insertion + // we can avoid searching through all the bins. + if (last_insert_iter_ == item_bins_.end() || last_insert_iter_->first != priority) + { + last_insert_iter_ = item_bins_.find(priority); + + // If not found, create a new bin + if (last_insert_iter_ == item_bins_.end()) + { + auto map_item = std::make_pair(priority, std::move(std::vector())); + + // Inserts an item if it doesn't exist. Returns an iterator to the item whether it existed or was inserted. + std::pair insert_result = item_bins_.insert(std::move(map_item)); + last_insert_iter_ = insert_result.first; + } + } + + // Add the item to the vector for this map key + last_insert_iter_->second.push_back(item); + item_count_++; + + // Use short circuiting to check if we want to update the iterator + if (iter_ == item_bins_.end() || priority < iter_->first) + { + iter_ = last_insert_iter_; + } + } + + /** + * @brief Check to see if there is anything in the queue + * @return True if there is nothing in the queue + * + * Must be called prior to front/pop. + */ + bool isEmpty() + { + return item_count_ == 0; + } + + /** + * @brief Return the item at the front of the queue + * @return The item at the front of the queue + */ + item_t& front() + { + if (iter_ == item_bins_.end()) + { + throw std::out_of_range("front() called on empty costmap_queue::MapBasedQueue!"); + } + + return iter_->second.back(); + } + + /** + * @brief Remove (and destroy) the item at the front of the queue + */ + void pop() + { + if (iter_ != item_bins_.end() && !iter_->second.empty()) + { + iter_->second.pop_back(); + item_count_--; + } + + auto not_empty = [](const typename ItemMap::value_type& key_val) { return !key_val.second.empty(); }; + iter_ = std::find_if(iter_, item_bins_.end(), not_empty); + } + +protected: + using ItemMap = std::map>; + using ItemMapIterator = typename ItemMap::iterator; + + bool reset_bins_; + + ItemMap item_bins_; + unsigned int item_count_; + ItemMapIterator iter_; + ItemMapIterator last_insert_iter_; +}; +} // namespace costmap_queue + +#endif // COSTMAP_QUEUE_MAP_BASED_QUEUE_H diff --git a/navigations/costmap_queue/package.xml b/navigations/costmap_queue/package.xml new file mode 100755 index 0000000..9390403 --- /dev/null +++ b/navigations/costmap_queue/package.xml @@ -0,0 +1,17 @@ + + + costmap_queue + 0.3.0 + Tool for iterating through the cells of a costmap to find the closest distance to a subset of cells. + + David V. Lu!! + + BSD + + catkin + nav_core2 + roscpp + roslint + rosunit + + diff --git a/navigations/costmap_queue/src/costmap_queue.cpp b/navigations/costmap_queue/src/costmap_queue.cpp new file mode 100755 index 0000000..61c7ec6 --- /dev/null +++ b/navigations/costmap_queue/src/costmap_queue.cpp @@ -0,0 +1,125 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ +#include +#include +#include + +namespace costmap_queue +{ + +CostmapQueue::CostmapQueue(nav_core2::Costmap& costmap, bool manhattan) : + MapBasedQueue(false), costmap_(costmap), seen_(0), manhattan_(manhattan), cached_max_distance_(-1) +{ + reset(); +} + +void CostmapQueue::reset() +{ + seen_.setInfo(costmap_.getInfo()); + seen_.reset(); + computeCache(); + MapBasedQueue::reset(); +} + +void CostmapQueue::enqueueCell(unsigned int x, unsigned int y) +{ + enqueueCell(x, y, x, y); +} + +void CostmapQueue::enqueueCell(unsigned int cur_x, unsigned int cur_y, + unsigned int src_x, unsigned int src_y) +{ + if (seen_(cur_x, cur_y)) return; + + // we compute our distance table one cell further than the inflation radius dictates so we can make the check below + double distance = distanceLookup(cur_x, cur_y, src_x, src_y); + CellData data(distance, cur_x, cur_y, src_x, src_y); + if (validCellToQueue(data)) + { + seen_.setValue(cur_x, cur_y, 1); + enqueue(distance, data); + } +} + +CellData CostmapQueue::getNextCell() +{ + // get the highest priority cell and pop it off the priority queue + CellData current_cell = front(); + pop(); + + unsigned int mx = current_cell.x_; + unsigned int my = current_cell.y_; + unsigned int sx = current_cell.src_x_; + unsigned int sy = current_cell.src_y_; + + // attempt to put the neighbors of the current cell onto the queue + if (mx > 0) + enqueueCell(mx - 1, my, sx, sy); + if (my > 0) + enqueueCell(mx, my - 1, sx, sy); + if (mx < costmap_.getWidth() - 1) + enqueueCell(mx + 1, my, sx, sy); + if (my < costmap_.getHeight() - 1) + enqueueCell(mx, my + 1, sx, sy); + + return current_cell; +} + +void CostmapQueue::computeCache() +{ + int max_distance = getMaxDistance(); + if (max_distance == cached_max_distance_) return; + cached_distances_.clear(); + + cached_distances_.resize(max_distance + 2); + + for (unsigned int i = 0; i < cached_distances_.size(); ++i) + { + cached_distances_[i].resize(max_distance + 2); + for (unsigned int j = 0; j < cached_distances_[i].size(); ++j) + { + if (manhattan_) + { + cached_distances_[i][j] = i + j; + } + else + { + cached_distances_[i][j] = hypot(i, j); + } + } + } + cached_max_distance_ = max_distance; +} + +} // namespace costmap_queue diff --git a/navigations/costmap_queue/src/limited_costmap_queue.cpp b/navigations/costmap_queue/src/limited_costmap_queue.cpp new file mode 100755 index 0000000..603a55e --- /dev/null +++ b/navigations/costmap_queue/src/limited_costmap_queue.cpp @@ -0,0 +1,56 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ +#include + +namespace costmap_queue +{ + +LimitedCostmapQueue::LimitedCostmapQueue(nav_core2::Costmap& costmap, const int distance_limit) : + CostmapQueue(costmap) +{ + max_distance_ = distance_limit; + reset(); +} + +int LimitedCostmapQueue::getMaxDistance() const +{ + return max_distance_; +} + +bool LimitedCostmapQueue::validCellToQueue(const CellData& cell) +{ + return cell.distance_ <= max_distance_; +} + +} // namespace costmap_queue diff --git a/navigations/costmap_queue/test/mbq_test.cpp b/navigations/costmap_queue/test/mbq_test.cpp new file mode 100755 index 0000000..4fad77a --- /dev/null +++ b/navigations/costmap_queue/test/mbq_test.cpp @@ -0,0 +1,118 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ +#include +#include +#include + +using costmap_queue::MapBasedQueue; + +void letter_test(MapBasedQueue& q, const char test_letter) +{ + ASSERT_FALSE(q.isEmpty()); + char c = q.front(); + EXPECT_EQ(c, test_letter); + q.pop(); +} + +TEST(MapBasedQueue, emptyQueue) +{ + MapBasedQueue q; + EXPECT_TRUE(q.isEmpty()); + q.enqueue(1.0, 'A'); + EXPECT_FALSE(q.isEmpty()); +} + +TEST(MapBasedQueue, checkOrdering) +{ + MapBasedQueue q; + q.enqueue(1.0, 'A'); + q.enqueue(3.0, 'B'); + q.enqueue(2.0, 'C'); + q.enqueue(5.0, 'D'); + q.enqueue(0.0, 'E'); + + std::string expected = "EACBD"; + for (unsigned int i = 0; i < expected.size(); i++) + { + letter_test(q, expected[i]); + } + EXPECT_TRUE(q.isEmpty()); +} + +TEST(MapBasedQueue, checkDynamicOrdering) +{ + MapBasedQueue q; + q.enqueue(1.0, 'A'); + q.enqueue(3.0, 'B'); + q.enqueue(2.0, 'C'); + q.enqueue(5.0, 'D'); + + std::string expected = "ACB"; + for (unsigned int i = 0; i < expected.size(); i++) + { + letter_test(q, expected[i]); + } + + q.enqueue(0.0, 'E'); + letter_test(q, 'E'); +} + +TEST(MapBasedQueue, checkDynamicOrdering2) +{ + MapBasedQueue q; + q.enqueue(1.0, 'A'); + q.enqueue(2.0, 'B'); + letter_test(q, 'A'); + q.enqueue(3.0, 'C'); + letter_test(q, 'B'); +} + +TEST(MapBasedQueue, checkDynamicOrdering3) +{ + MapBasedQueue q; + q.enqueue(1.0, 'A'); + q.enqueue(2.0, 'B'); + q.enqueue(5.0, 'D'); + letter_test(q, 'A'); + letter_test(q, 'B'); + q.enqueue(1.0, 'C'); + letter_test(q, 'C'); + letter_test(q, 'D'); +} + +int main(int argc, char **argv) +{ + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/navigations/costmap_queue/test/utest.cpp b/navigations/costmap_queue/test/utest.cpp new file mode 100755 index 0000000..2cc018f --- /dev/null +++ b/navigations/costmap_queue/test/utest.cpp @@ -0,0 +1,208 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ +#include +#include +#include +#include +#include +#include +#include + + +nav_core2::BasicCostmap costmap; + +TEST(CostmapQueue, basicQueue) +{ + costmap_queue::CostmapQueue q(costmap); + int count = 0; + q.enqueueCell(0, 0); + while (!q.isEmpty()) + { + costmap_queue::CellData cell = q.getNextCell(); + EXPECT_FLOAT_EQ(cell.distance_, hypot(cell.x_, cell.y_)); + count++; + } + EXPECT_EQ(count, 25); +} + +TEST(CostmapQueue, reverseQueue) +{ + costmap_queue::CostmapQueue q(costmap); + int count = 0; + q.enqueueCell(4, 4); + while (!q.isEmpty()) + { + costmap_queue::CellData cell = q.getNextCell(); + EXPECT_FLOAT_EQ(cell.distance_, hypot(4.0 - static_cast(cell.x_), + 4.0 - static_cast(cell.y_))); + count++; + } + EXPECT_EQ(count, 25); +} + +TEST(CostmapQueue, bigTest) +{ + nav_grid::NavGridInfo big_info; + big_info.width = 500; + big_info.height = 500; + + nav_core2::BasicCostmap big_map; + big_map.setInfo(big_info); + costmap_queue::CostmapQueue q(big_map); + int count = 0; + q.enqueueCell(0, 0); + while (!q.isEmpty()) + { + costmap_queue::CellData cell = q.getNextCell(); + EXPECT_FLOAT_EQ(cell.distance_, hypot(cell.x_, cell.y_)); + count++; + } + EXPECT_EQ(count, 500 * 500); +} + +TEST(CostmapQueue, linearQueue) +{ + costmap_queue::CostmapQueue q(costmap); + int count = 0; + q.enqueueCell(0, 0); + q.enqueueCell(0, 1); + q.enqueueCell(0, 2); + q.enqueueCell(0, 3); + q.enqueueCell(0, 4); + while (!q.isEmpty()) + { + costmap_queue::CellData cell = q.getNextCell(); + EXPECT_FLOAT_EQ(cell.distance_, cell.x_); + count++; + } + EXPECT_EQ(count, 25); +} + +TEST(CostmapQueue, crossQueue) +{ + costmap_queue::CostmapQueue q(costmap); + int count = 0; + int xs[] = {1, 2, 2, 3}; + int ys[] = {2, 1, 3, 2}; + int N = 4; + for (int i = 0; i < N; i++) + { + q.enqueueCell(xs[i], ys[i]); + } + + while (!q.isEmpty()) + { + costmap_queue::CellData cell = q.getNextCell(); + double min_d = 1000; + + for (int i = 0; i < N; i++) + { + double dd = hypot(xs[i] - static_cast(cell.x_), ys[i] - static_cast(cell.y_)); + min_d = std::min(min_d, dd); + } + EXPECT_FLOAT_EQ(cell.distance_, min_d); + count++; + } + EXPECT_EQ(count, 25); +} + +TEST(CostmapQueue, limitedQueue) +{ + costmap_queue::LimitedCostmapQueue q(costmap, 5); + int count = 0; + q.enqueueCell(0, 0); + while (!q.isEmpty()) + { + costmap_queue::CellData cell = q.getNextCell(); + EXPECT_FLOAT_EQ(cell.distance_, hypot(cell.x_, cell.y_)); + count++; + } + EXPECT_EQ(count, 24); + + costmap_queue::LimitedCostmapQueue q2(costmap, 3); + count = 0; + q2.enqueueCell(0, 0); + while (!q2.isEmpty()) + { + q2.getNextCell(); + count++; + } + EXPECT_EQ(count, 11); +} + + +TEST(CostmapQueue, changingSize) +{ + nav_grid::NavGridInfo info0; + info0.width = 2; + info0.height = 3; + + nav_grid::NavGridInfo info1; + info1.width = 6; + info1.height = 7; + + nav_core2::BasicCostmap size_map; + size_map.setInfo(info0); + costmap_queue::CostmapQueue q(size_map); + unsigned int count = 0; + q.enqueueCell(0, 0); + while (!q.isEmpty()) + { + q.getNextCell(); + count++; + } + + EXPECT_EQ(count, info0.width * info0.height); + + size_map.setInfo(info1); + q.reset(); + count = 0; + q.enqueueCell(0, 0); + while (!q.isEmpty()) + { + q.getNextCell(); + count++; + } + EXPECT_EQ(count, info1.width * info1.height); +} + +int main(int argc, char **argv) +{ + testing::InitGoogleTest(&argc, argv); + nav_grid::NavGridInfo info; + info.width = 5; + info.height = 5; + costmap.setInfo(info); + return RUN_ALL_TESTS(); +} diff --git a/navigations/dwa_local_planner/CHANGELOG.rst b/navigations/dwa_local_planner/CHANGELOG.rst new file mode 100755 index 0000000..54bf376 --- /dev/null +++ b/navigations/dwa_local_planner/CHANGELOG.rst @@ -0,0 +1,163 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package dwa_local_planner +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +1.17.3 (2023-01-10) +------------------- +* [ROS-O] various patches (`#1225 `_) + * do not specify obsolete c++11 standard + this breaks with current versions of log4cxx. + * update pluginlib include paths + the non-hpp headers have been deprecated since kinetic + * use lambdas in favor of boost::bind + Using boost's _1 as a global system is deprecated since C++11. + The ROS packages in Debian removed the implicit support for the global symbols, + so this code fails to compile there without the patch. +* Contributors: Michael Görner + +1.17.2 (2022-06-20) +------------------- + +1.17.1 (2020-08-27) +------------------- + +1.17.0 (2020-04-02) +------------------- +* Merge pull request `#982 `_ from ros-planning/noetic_prep + Noetic Migration +* increase required cmake version +* Contributors: Michael Ferguson + +1.16.6 (2020-03-18) +------------------- + +1.16.5 (2020-03-15) +------------------- +* [melodic] updated install for better portability. (`#973 `_) +* Contributors: Sean Yen + +1.16.4 (2020-03-04) +------------------- +* Fixes gdist- and pdist_scale node paramter names (`#936 `_) + Renames goal and path distance dynamic reconfigure parameter + names in the cfg file in order to actually make the parameters + used by the trajectory planner changeable. + Fixes `#935 `_ +* Contributors: David Leins + +1.16.3 (2019-11-15) +------------------- +* Set footprint before in place rotation continuation (`#829 `_) (`#861 `_) + * Make sure to call setFootprint() before an in-place rotation + * Change to const reference + * Remove footprint from findBestPath +* Contributors: David V. Lu!! + +1.16.2 (2018-07-31) +------------------- +* Merge pull request `#773 `_ from ros-planning/packaging_fixes + packaging fixes +* fix depends for dwa_local_planner + * add tf2_geometry_msgs (due to https://github.com/ros/geometry2/issues/275) + * add missing depends on angles, sensor_msgs, tf2 +* Contributors: Michael Ferguson + +1.16.1 (2018-07-28) +------------------- + +1.16.0 (2018-07-25) +------------------- +* Merge pull request `#765 `_ from ros-planning/remove_pcl + remove left over PCL depends in dwa_local_planner +* Remove PCL from local planners +* Switch to TF2 `#755 `_ +* Make trajectory scoring scales consistent. +* unify parameter names between base_local_planner and dwa_local_planner + addresses parts of `#90 `_ +* Contributors: David V. Lu, Michael Ferguson, Pavlo Kolomiiets, Vincent Rabaud, moriarty + +1.15.2 (2018-03-22) +------------------- +* Merge pull request `#673 `_ from ros-planning/email_update_lunar + update maintainer email (lunar) +* Merge pull request `#649 `_ from aaronhoy/lunar_add_ahoy + Add myself as a maintainer. +* Contributors: Aaron Hoy, Michael Ferguson + +1.15.1 (2017-08-14) +------------------- + +1.15.0 (2017-08-07) +------------------- +* convert packages to format2 +* Add cost function to prevent unnecessary spinning +* Fix CMakeLists + package.xmls (`#548 `_) +* import only PCL common +* remove GCC warnings +* Fix CMake warnings +* Contributors: Martin Günther, Mikael Arguedas, Morgan Quigley, Vincent Rabaud + +1.14.0 (2016-05-20) +------------------- + +1.13.1 (2015-10-29) +------------------- + +1.13.0 (2015-03-17) +------------------- +* link only libraries found with find_package +* Contributors: Lukas Bulwahn + +1.12.0 (2015-02-04) +------------------- +* update maintainer email +* Contributors: Michael Ferguson + +1.11.15 (2015-02-03) +-------------------- +* Add ARCHIVE_DESTINATION for static builds +* Contributors: Gary Servin + +1.11.14 (2014-12-05) +-------------------- + +1.11.13 (2014-10-02) +-------------------- + +1.11.12 (2014-10-01) +-------------------- + +1.11.11 (2014-07-23) +-------------------- + +1.11.10 (2014-06-25) +-------------------- + +1.11.9 (2014-06-10) +------------------- + +1.11.8 (2014-05-21) +------------------- + +1.11.7 (2014-05-21) +------------------- +* update build to find eigen using cmake_modules +* Contributors: Michael Ferguson + +1.11.5 (2014-01-30) +------------------- +* Fix for `#5 `_ +* Parameter to sum scores in DWA Planner +* Keep consistent allignment_cost scale + Use the configured alignment cost instead of resetting to 1.0. This + condition (farther from goal than forward_point_distance) is probably + met at the start of navigation, it seems this cost should be obeyed + until the robot gets close, then ignored completely. +* Cheat factor for end of DWA Plans +* Change maintainer from Hersh to Lu + +1.11.4 (2013-09-27) +------------------- +* Package URL Updates +* Changed new Odom-Helper::initialize() function to setOdomTopic(). +* some more corrections for the pointcloud object bug diff --git a/navigations/dwa_local_planner/CMakeLists.txt b/navigations/dwa_local_planner/CMakeLists.txt new file mode 100755 index 0000000..dbeda46 --- /dev/null +++ b/navigations/dwa_local_planner/CMakeLists.txt @@ -0,0 +1,67 @@ +cmake_minimum_required(VERSION 3.0.2) +project(dwa_local_planner) + +find_package(catkin REQUIRED + COMPONENTS + angles + base_local_planner + cmake_modules + costmap_2d + dynamic_reconfigure + nav_core + nav_msgs + pluginlib + sensor_msgs + roscpp + tf2 + tf2_geometry_msgs + tf2_ros + ) + +find_package(Eigen3 REQUIRED) +remove_definitions(-DDISABLE_LIBUSB-1.0) +include_directories( + include + ${catkin_INCLUDE_DIRS} + ${EIGEN3_INCLUDE_DIRS} + ) +add_definitions(${EIGEN3_DEFINITIONS}) + +# dynamic reconfigure +generate_dynamic_reconfigure_options( + cfg/DWAPlanner.cfg +) + +catkin_package( + INCLUDE_DIRS include + LIBRARIES dwa_local_planner + CATKIN_DEPENDS + base_local_planner + dynamic_reconfigure + nav_msgs + pluginlib + sensor_msgs + roscpp + tf2 + tf2_ros +) + +add_library(dwa_local_planner src/dwa_planner.cpp src/dwa_planner_ros.cpp) +add_dependencies(dwa_local_planner ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) +target_link_libraries(dwa_local_planner ${catkin_LIBRARIES}) +target_compile_options(dwa_local_planner PUBLIC "-Wno-terminate") + +install(TARGETS dwa_local_planner + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} + ) + +install(FILES blp_plugin.xml + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) + +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} + PATTERN ".svn" EXCLUDE +) diff --git a/navigations/dwa_local_planner/blp_plugin.xml b/navigations/dwa_local_planner/blp_plugin.xml new file mode 100755 index 0000000..2b10073 --- /dev/null +++ b/navigations/dwa_local_planner/blp_plugin.xml @@ -0,0 +1,7 @@ + + + + A implementation of a local planner using either a DWA approach based on configuration parameters. + + + diff --git a/navigations/dwa_local_planner/cfg/DWAPlanner.cfg b/navigations/dwa_local_planner/cfg/DWAPlanner.cfg new file mode 100755 index 0000000..29e32b6 --- /dev/null +++ b/navigations/dwa_local_planner/cfg/DWAPlanner.cfg @@ -0,0 +1,39 @@ +#!/usr/bin/env python +# DWA Planner configuration + +from dynamic_reconfigure.parameter_generator_catkin import ParameterGenerator, double_t, int_t, bool_t +from local_planner_limits import add_generic_localplanner_params + +gen = ParameterGenerator() + +# This unusual line allows to reuse existing parameter definitions +# that concern all localplanners +add_generic_localplanner_params(gen) + +gen.add("sim_time", double_t, 0, "The amount of time to roll trajectories out for in seconds", 1.7, 0) +gen.add("sim_granularity", double_t, 0, "The granularity with which to check for collisions along each trajectory in meters", 0.025, 0) +gen.add("angular_sim_granularity", double_t, 0, "The granularity with which to check for collisions for rotations in radians", 0.1, 0) + +gen.add("path_distance_bias", double_t, 0, "The weight for the path distance part of the cost function", 0.6, 0.0) +gen.add("goal_distance_bias", double_t, 0, "The weight for the goal distance part of the cost function", 0.8, 0.0) +gen.add("occdist_scale", double_t, 0, "The weight for the obstacle distance part of the cost function", 0.01, 0.0) +gen.add("twirling_scale", double_t, 0, "The weight for penalizing any changes in robot heading", 0.0, 0.0) + +gen.add("stop_time_buffer", double_t, 0, "The amount of time that the robot must stop before a collision in order for a trajectory to be considered valid in seconds", 0.2, 0) +gen.add("oscillation_reset_dist", double_t, 0, "The distance the robot must travel before oscillation flags are reset, in meters", 0.05, 0) +gen.add("oscillation_reset_angle", double_t, 0, "The angle the robot must turn before oscillation flags are reset, in radians", 0.2, 0) + +gen.add("forward_point_distance", double_t, 0, "The distance from the center point of the robot to place an additional scoring point, in meters", 0.325) + +gen.add("scaling_speed", double_t, 0, "The absolute value of the velocity at which to start scaling the robot's footprint, in m/s", 0.25, 0) +gen.add("max_scaling_factor", double_t, 0, "The maximum factor to scale the robot's footprint by", 0.2, 0) + +gen.add("vx_samples", int_t, 0, "The number of samples to use when exploring the x velocity space", 3, 1) +gen.add("vy_samples", int_t, 0, "The number of samples to use when exploring the y velocity space", 10, 1) +gen.add("vth_samples", int_t, 0, "The number of samples to use when exploring the theta velocity space", 20, 1) + +gen.add("use_dwa", bool_t, 0, "Use dynamic window approach to constrain sampling velocities to small window.", True) + +gen.add("restore_defaults", bool_t, 0, "Restore to the original configuration.", False) + +exit(gen.generate("dwa_local_planner", "dwa_local_planner", "DWAPlanner")) diff --git a/navigations/dwa_local_planner/include/dwa_local_planner/dwa_planner.h b/navigations/dwa_local_planner/include/dwa_local_planner/dwa_planner.h new file mode 100755 index 0000000..70b4c71 --- /dev/null +++ b/navigations/dwa_local_planner/include/dwa_local_planner/dwa_planner.h @@ -0,0 +1,185 @@ +/********************************************************************* +* +* Software License Agreement (BSD License) +* +* Copyright (c) 2009, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of Willow Garage, Inc. nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* +* Author: Eitan Marder-Eppstein +*********************************************************************/ +#ifndef DWA_LOCAL_PLANNER_DWA_PLANNER_H_ +#define DWA_LOCAL_PLANNER_DWA_PLANNER_H_ + +#include +#include + + +#include + +//for creating a local cost grid +#include + +//for obstacle data access +#include + +#include +#include +#include +#include + +#include +#include +#include +#include +#include + +#include + +namespace dwa_local_planner { + /** + * @class DWAPlanner + * @brief A class implementing a local planner using the Dynamic Window Approach + */ + class DWAPlanner { + public: + /** + * @brief Constructor for the planner + * @param name The name of the planner + * @param costmap_ros A pointer to the costmap instance the planner should use + * @param global_frame the frame id of the tf frame to use + */ + DWAPlanner(std::string name, base_local_planner::LocalPlannerUtil *planner_util); + + /** + * @brief Reconfigures the trajectory planner + */ + void reconfigure(DWAPlannerConfig &cfg); + + /** + * @brief Check if a trajectory is legal for a position/velocity pair + * @param pos The robot's position + * @param vel The robot's velocity + * @param vel_samples The desired velocity + * @return True if the trajectory is valid, false otherwise + */ + bool checkTrajectory( + const Eigen::Vector3f pos, + const Eigen::Vector3f vel, + const Eigen::Vector3f vel_samples); + + /** + * @brief Given the current position and velocity of the robot, find the best trajectory to exectue + * @param global_pose The current position of the robot + * @param global_vel The current velocity of the robot + * @param drive_velocities The velocities to send to the robot base + * @return The highest scoring trajectory. A cost >= 0 means the trajectory is legal to execute. + */ + base_local_planner::Trajectory findBestPath( + const geometry_msgs::PoseStamped& global_pose, + const geometry_msgs::PoseStamped& global_vel, + geometry_msgs::PoseStamped& drive_velocities); + + /** + * @brief Update the cost functions before planning + * @param global_pose The robot's current pose + * @param new_plan The new global plan + * @param footprint_spec The robot's footprint + * + * The obstacle cost function gets the footprint. + * The path and goal cost functions get the global_plan + * The alignment cost functions get a version of the global plan + * that is modified based on the global_pose + */ + void updatePlanAndLocalCosts(const geometry_msgs::PoseStamped& global_pose, + const std::vector& new_plan, + const std::vector& footprint_spec); + + /** + * @brief Get the period at which the local planner is expected to run + * @return The simulation period + */ + double getSimPeriod() { return sim_period_; } + + /** + * @brief Compute the components and total cost for a map grid cell + * @param cx The x coordinate of the cell in the map grid + * @param cy The y coordinate of the cell in the map grid + * @param path_cost Will be set to the path distance component of the cost function + * @param goal_cost Will be set to the goal distance component of the cost function + * @param occ_cost Will be set to the costmap value of the cell + * @param total_cost Will be set to the value of the overall cost function, taking into account the scaling parameters + * @return True if the cell is traversible and therefore a legal location for the robot to move to + */ + bool getCellCosts(int cx, int cy, float &path_cost, float &goal_cost, float &occ_cost, float &total_cost); + + /** + * sets new plan and resets state + */ + bool setPlan(const std::vector& orig_global_plan); + + private: + + base_local_planner::LocalPlannerUtil *planner_util_; + + double stop_time_buffer_; ///< @brief How long before hitting something we're going to enforce that the robot stop + double path_distance_bias_, goal_distance_bias_, occdist_scale_; + Eigen::Vector3f vsamples_; + + double sim_period_;///< @brief The number of seconds to use to compute max/min vels for dwa + base_local_planner::Trajectory result_traj_; + + double forward_point_distance_; + + std::vector global_plan_; + + boost::mutex configuration_mutex_; + std::string frame_id_; + ros::Publisher traj_cloud_pub_; + bool publish_cost_grid_pc_; ///< @brief Whether or not to build and publish a PointCloud + bool publish_traj_pc_; + + double cheat_factor_; + + base_local_planner::MapGridVisualizer map_viz_; ///< @brief The map grid visualizer for outputting the potential field generated by the cost function + + // see constructor body for explanations + base_local_planner::SimpleTrajectoryGenerator generator_; + base_local_planner::OscillationCostFunction oscillation_costs_; + base_local_planner::ObstacleCostFunction obstacle_costs_; + base_local_planner::MapGridCostFunction path_costs_; + base_local_planner::MapGridCostFunction goal_costs_; + base_local_planner::MapGridCostFunction goal_front_costs_; + base_local_planner::MapGridCostFunction alignment_costs_; + base_local_planner::TwirlingCostFunction twirling_costs_; + + base_local_planner::SimpleScoredSamplingPlanner scored_sampling_planner_; + }; +}; +#endif diff --git a/navigations/dwa_local_planner/include/dwa_local_planner/dwa_planner_ros.h b/navigations/dwa_local_planner/include/dwa_local_planner/dwa_planner_ros.h new file mode 100755 index 0000000..4da6411 --- /dev/null +++ b/navigations/dwa_local_planner/include/dwa_local_planner/dwa_planner_ros.h @@ -0,0 +1,159 @@ +/********************************************************************* +* +* Software License Agreement (BSD License) +* +* Copyright (c) 2009, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of Willow Garage, Inc. nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* +* Author: Eitan Marder-Eppstein +*********************************************************************/ +#ifndef DWA_LOCAL_PLANNER_DWA_PLANNER_ROS_H_ +#define DWA_LOCAL_PLANNER_DWA_PLANNER_ROS_H_ + +#include +#include + +#include + +#include +#include + +#include + +#include + +#include +#include +#include + +#include + +#include + +namespace dwa_local_planner { + /** + * @class DWAPlannerROS + * @brief ROS Wrapper for the DWAPlanner that adheres to the + * BaseLocalPlanner interface and can be used as a plugin for move_base. + */ + class DWAPlannerROS : public nav_core::BaseLocalPlanner { + public: + /** + * @brief Constructor for DWAPlannerROS wrapper + */ + DWAPlannerROS(); + + /** + * @brief Constructs the ros wrapper + * @param name The name to give this instance of the trajectory planner + * @param tf A pointer to a transform listener + * @param costmap The cost map to use for assigning costs to trajectories + */ + void initialize(std::string name, tf2_ros::Buffer* tf, + costmap_2d::Costmap2DROS* costmap_ros); + + /** + * @brief Destructor for the wrapper + */ + ~DWAPlannerROS(); + + /** + * @brief Given the current position, orientation, and velocity of the robot, + * compute velocity commands to send to the base + * @param cmd_vel Will be filled with the velocity command to be passed to the robot base + * @return True if a valid trajectory was found, false otherwise + */ + bool computeVelocityCommands(geometry_msgs::Twist& cmd_vel); + + + /** + * @brief Given the current position, orientation, and velocity of the robot, + * compute velocity commands to send to the base, using dynamic window approach + * @param cmd_vel Will be filled with the velocity command to be passed to the robot base + * @return True if a valid trajectory was found, false otherwise + */ + bool dwaComputeVelocityCommands(geometry_msgs::PoseStamped& global_pose, geometry_msgs::Twist& cmd_vel); + + /** + * @brief Set the plan that the controller is following + * @param orig_global_plan The plan to pass to the controller + * @return True if the plan was updated successfully, false otherwise + */ + bool setPlan(const std::vector& orig_global_plan); + + /** + * @brief Check if the goal pose has been achieved + * @return True if achieved, false otherwise + */ + bool isGoalReached(); + + + + bool isInitialized() { + return initialized_; + } + + private: + /** + * @brief Callback to update the local planner's parameters based on dynamic reconfigure + */ + void reconfigureCB(DWAPlannerConfig &config, uint32_t level); + + void publishLocalPlan(std::vector& path); + + void publishGlobalPlan(std::vector& path); + + tf2_ros::Buffer* tf_; ///< @brief Used for transforming point clouds + + // for visualisation, publishers of global and local plan + ros::Publisher g_plan_pub_, l_plan_pub_; + + base_local_planner::LocalPlannerUtil planner_util_; + + boost::shared_ptr dp_; ///< @brief The trajectory controller + + costmap_2d::Costmap2DROS* costmap_ros_; + + dynamic_reconfigure::Server *dsrv_; + dwa_local_planner::DWAPlannerConfig default_config_; + bool setup_; + geometry_msgs::PoseStamped current_pose_; + + base_local_planner::LatchedStopRotateController latchedStopRotateController_; + + + bool initialized_; + + + base_local_planner::OdometryHelperRos odom_helper_; + std::string odom_topic_; + }; +}; +#endif diff --git a/navigations/dwa_local_planner/package.xml b/navigations/dwa_local_planner/package.xml new file mode 100755 index 0000000..dfd9d0a --- /dev/null +++ b/navigations/dwa_local_planner/package.xml @@ -0,0 +1,50 @@ + + + + dwa_local_planner + 1.17.3 + + + This package provides an implementation of the Dynamic Window Approach to + local robot navigation on a plane. Given a global plan to follow and a + costmap, the local planner produces velocity commands to send to a mobile + base. This package supports any robot who's footprint can be represented as + a convex polygon or cicrle, and exposes its configuration as ROS parameters + that can be set in a launch file. The parameters for this planner are also + dynamically reconfigurable. This package's ROS wrapper adheres to the + BaseLocalPlanner interface specified in the nav_core package. + + + Eitan Marder-Eppstein + contradict@gmail.com + David V. Lu!! + Michael Ferguson + Aaron Hoy + BSD + http://wiki.ros.org/dwa_local_planner + + catkin + + angles + cmake_modules + + base_local_planner + costmap_2d + dynamic_reconfigure + eigen + nav_core + nav_msgs + pluginlib + sensor_msgs + roscpp + tf2 + tf2_geometry_msgs + tf2_ros + + + + + + + + diff --git a/navigations/dwa_local_planner/src/dwa_planner.cpp b/navigations/dwa_local_planner/src/dwa_planner.cpp new file mode 100755 index 0000000..5abeb6c --- /dev/null +++ b/navigations/dwa_local_planner/src/dwa_planner.cpp @@ -0,0 +1,394 @@ +/********************************************************************* +* +* Software License Agreement (BSD License) +* +* Copyright (c) 2009, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of Willow Garage, Inc. nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* +* Author: Eitan Marder-Eppstein +*********************************************************************/ +#include +#include +#include + +//for computing path distance +#include + +#include + +#include +#include +#include +#include + +namespace dwa_local_planner { + void DWAPlanner::reconfigure(DWAPlannerConfig &config) + { + + boost::mutex::scoped_lock l(configuration_mutex_); + + generator_.setParameters( + config.sim_time, + config.sim_granularity, + config.angular_sim_granularity, + config.use_dwa, + sim_period_); + + double resolution = planner_util_->getCostmap()->getResolution(); + path_distance_bias_ = resolution * config.path_distance_bias; + // pdistscale used for both path and alignment, set forward_point_distance to zero to discard alignment + path_costs_.setScale(path_distance_bias_); + alignment_costs_.setScale(path_distance_bias_); + + goal_distance_bias_ = resolution * config.goal_distance_bias; + goal_costs_.setScale(goal_distance_bias_); + goal_front_costs_.setScale(goal_distance_bias_); + + occdist_scale_ = config.occdist_scale; + obstacle_costs_.setScale(occdist_scale_); + + stop_time_buffer_ = config.stop_time_buffer; + oscillation_costs_.setOscillationResetDist(config.oscillation_reset_dist, config.oscillation_reset_angle); + forward_point_distance_ = config.forward_point_distance; + goal_front_costs_.setXShift(forward_point_distance_); + alignment_costs_.setXShift(forward_point_distance_); + + // obstacle costs can vary due to scaling footprint feature + obstacle_costs_.setParams(config.max_vel_trans, config.max_scaling_factor, config.scaling_speed); + + twirling_costs_.setScale(config.twirling_scale); + + int vx_samp, vy_samp, vth_samp; + vx_samp = config.vx_samples; + vy_samp = config.vy_samples; + vth_samp = config.vth_samples; + + if (vx_samp <= 0) { + ROS_WARN("You've specified that you don't want any samples in the x dimension. We'll at least assume that you want to sample one value... so we're going to set vx_samples to 1 instead"); + vx_samp = 1; + config.vx_samples = vx_samp; + } + + if (vy_samp <= 0) { + ROS_WARN("You've specified that you don't want any samples in the y dimension. We'll at least assume that you want to sample one value... so we're going to set vy_samples to 1 instead"); + vy_samp = 1; + config.vy_samples = vy_samp; + } + + if (vth_samp <= 0) { + ROS_WARN("You've specified that you don't want any samples in the th dimension. We'll at least assume that you want to sample one value... so we're going to set vth_samples to 1 instead"); + vth_samp = 1; + config.vth_samples = vth_samp; + } + + vsamples_[0] = vx_samp; + vsamples_[1] = vy_samp; + vsamples_[2] = vth_samp; + + + } + + DWAPlanner::DWAPlanner(std::string name, base_local_planner::LocalPlannerUtil *planner_util) : + planner_util_(planner_util), + obstacle_costs_(planner_util->getCostmap()), + path_costs_(planner_util->getCostmap()), + goal_costs_(planner_util->getCostmap(), 0.0, 0.0, true), + goal_front_costs_(planner_util->getCostmap(), 0.0, 0.0, true), + alignment_costs_(planner_util->getCostmap()) + { + ros::NodeHandle private_nh("~/" + name); + + goal_front_costs_.setStopOnFailure( false ); + alignment_costs_.setStopOnFailure( false ); + + //Assuming this planner is being run within the navigation stack, we can + //just do an upward search for the frequency at which its being run. This + //also allows the frequency to be overwritten locally. + std::string controller_frequency_param_name; + if(!private_nh.searchParam("controller_frequency", controller_frequency_param_name)) { + sim_period_ = 0.05; + } else { + double controller_frequency = 0; + private_nh.param(controller_frequency_param_name, controller_frequency, 20.0); + if(controller_frequency > 0) { + sim_period_ = 1.0 / controller_frequency; + } else { + ROS_WARN("A controller_frequency less than 0 has been set. Ignoring the parameter, assuming a rate of 20Hz"); + sim_period_ = 0.05; + } + } + ROS_INFO("Sim period is set to %.2f", sim_period_); + + oscillation_costs_.resetOscillationFlags(); + + bool sum_scores; + private_nh.param("sum_scores", sum_scores, false); + obstacle_costs_.setSumScores(sum_scores); + + + private_nh.param("publish_cost_grid_pc", publish_cost_grid_pc_, false); + map_viz_.initialize(name, + planner_util->getGlobalFrame(), + [this](int cx, int cy, float &path_cost, float &goal_cost, float &occ_cost, float &total_cost){ + return getCellCosts(cx, cy, path_cost, goal_cost, occ_cost, total_cost); + }); + + private_nh.param("global_frame_id", frame_id_, std::string("odom")); + + traj_cloud_pub_ = private_nh.advertise("trajectory_cloud", 1); + private_nh.param("publish_traj_pc", publish_traj_pc_, false); + + // set up all the cost functions that will be applied in order + // (any function returning negative values will abort scoring, so the order can improve performance) + std::vector critics; + critics.push_back(&oscillation_costs_); // discards oscillating motions (assisgns cost -1) + critics.push_back(&obstacle_costs_); // discards trajectories that move into obstacles + critics.push_back(&goal_front_costs_); // prefers trajectories that make the nose go towards (local) nose goal + critics.push_back(&alignment_costs_); // prefers trajectories that keep the robot nose on nose path + critics.push_back(&path_costs_); // prefers trajectories on global path + critics.push_back(&goal_costs_); // prefers trajectories that go towards (local) goal, based on wave propagation + critics.push_back(&twirling_costs_); // optionally prefer trajectories that don't spin + + // trajectory generators + std::vector generator_list; + generator_list.push_back(&generator_); + + scored_sampling_planner_ = base_local_planner::SimpleScoredSamplingPlanner(generator_list, critics); + + private_nh.param("cheat_factor", cheat_factor_, 1.0); + } + + // used for visualization only, total_costs are not really total costs + bool DWAPlanner::getCellCosts(int cx, int cy, float &path_cost, float &goal_cost, float &occ_cost, float &total_cost) { + + path_cost = path_costs_.getCellCosts(cx, cy); + goal_cost = goal_costs_.getCellCosts(cx, cy); + occ_cost = planner_util_->getCostmap()->getCost(cx, cy); + if (path_cost == path_costs_.obstacleCosts() || + path_cost == path_costs_.unreachableCellCosts() || + occ_cost >= costmap_2d::INSCRIBED_INFLATED_OBSTACLE) { + return false; + } + + total_cost = + path_distance_bias_ * path_cost + + goal_distance_bias_ * goal_cost + + occdist_scale_ * occ_cost; + return true; + } + + bool DWAPlanner::setPlan(const std::vector& orig_global_plan) { + oscillation_costs_.resetOscillationFlags(); + return planner_util_->setPlan(orig_global_plan); + } + + /** + * This function is used when other strategies are to be applied, + * but the cost functions for obstacles are to be reused. + */ + bool DWAPlanner::checkTrajectory( + Eigen::Vector3f pos, + Eigen::Vector3f vel, + Eigen::Vector3f vel_samples){ + oscillation_costs_.resetOscillationFlags(); + base_local_planner::Trajectory traj; + geometry_msgs::PoseStamped goal_pose = global_plan_.back(); + Eigen::Vector3f goal(goal_pose.pose.position.x, goal_pose.pose.position.y, tf2::getYaw(goal_pose.pose.orientation)); + base_local_planner::LocalPlannerLimits limits = planner_util_->getCurrentLimits(); + generator_.initialise(pos, + vel, + goal, + &limits, + vsamples_); + generator_.generateTrajectory(pos, vel, vel_samples, traj); + double cost = scored_sampling_planner_.scoreTrajectory(traj, -1); + //if the trajectory is a legal one... the check passes + if(cost >= 0) { + return true; + } + ROS_WARN("Invalid Trajectory %f, %f, %f, cost: %f", vel_samples[0], vel_samples[1], vel_samples[2], cost); + + //otherwise the check fails + return false; + } + + + void DWAPlanner::updatePlanAndLocalCosts( + const geometry_msgs::PoseStamped& global_pose, + const std::vector& new_plan, + const std::vector& footprint_spec) { + global_plan_.resize(new_plan.size()); + for (unsigned int i = 0; i < new_plan.size(); ++i) { + global_plan_[i] = new_plan[i]; + } + + obstacle_costs_.setFootprint(footprint_spec); + + // costs for going away from path + path_costs_.setTargetPoses(global_plan_); + + // costs for not going towards the local goal as much as possible + goal_costs_.setTargetPoses(global_plan_); + + // alignment costs + geometry_msgs::PoseStamped goal_pose = global_plan_.back(); + + Eigen::Vector3f pos(global_pose.pose.position.x, global_pose.pose.position.y, tf2::getYaw(global_pose.pose.orientation)); + double sq_dist = + (pos[0] - goal_pose.pose.position.x) * (pos[0] - goal_pose.pose.position.x) + + (pos[1] - goal_pose.pose.position.y) * (pos[1] - goal_pose.pose.position.y); + + // we want the robot nose to be drawn to its final position + // (before robot turns towards goal orientation), not the end of the + // path for the robot center. Choosing the final position after + // turning towards goal orientation causes instability when the + // robot needs to make a 180 degree turn at the end + std::vector front_global_plan = global_plan_; + double angle_to_goal = atan2(goal_pose.pose.position.y - pos[1], goal_pose.pose.position.x - pos[0]); + front_global_plan.back().pose.position.x = front_global_plan.back().pose.position.x + + forward_point_distance_ * cos(angle_to_goal); + front_global_plan.back().pose.position.y = front_global_plan.back().pose.position.y + forward_point_distance_ * + sin(angle_to_goal); + + goal_front_costs_.setTargetPoses(front_global_plan); + + // keeping the nose on the path + if (sq_dist > forward_point_distance_ * forward_point_distance_ * cheat_factor_) { + alignment_costs_.setScale(path_distance_bias_); + // costs for robot being aligned with path (nose on path, not ju + alignment_costs_.setTargetPoses(global_plan_); + } else { + // once we are close to goal, trying to keep the nose close to anything destabilizes behavior. + alignment_costs_.setScale(0.0); + } + } + + + /* + * given the current state of the robot, find a good trajectory + */ + base_local_planner::Trajectory DWAPlanner::findBestPath( + const geometry_msgs::PoseStamped& global_pose, + const geometry_msgs::PoseStamped& global_vel, + geometry_msgs::PoseStamped& drive_velocities) { + + //make sure that our configuration doesn't change mid-run + boost::mutex::scoped_lock l(configuration_mutex_); + + Eigen::Vector3f pos(global_pose.pose.position.x, global_pose.pose.position.y, tf2::getYaw(global_pose.pose.orientation)); + Eigen::Vector3f vel(global_vel.pose.position.x, global_vel.pose.position.y, tf2::getYaw(global_vel.pose.orientation)); + geometry_msgs::PoseStamped goal_pose = global_plan_.back(); + Eigen::Vector3f goal(goal_pose.pose.position.x, goal_pose.pose.position.y, tf2::getYaw(goal_pose.pose.orientation)); + base_local_planner::LocalPlannerLimits limits = planner_util_->getCurrentLimits(); + + // prepare cost functions and generators for this run + generator_.initialise(pos, + vel, + goal, + &limits, + vsamples_); + + result_traj_.cost_ = -7; + // find best trajectory by sampling and scoring the samples + std::vector all_explored; + scored_sampling_planner_.findBestTrajectory(result_traj_, &all_explored); + + if(publish_traj_pc_) + { + sensor_msgs::PointCloud2 traj_cloud; + traj_cloud.header.frame_id = frame_id_; + traj_cloud.header.stamp = ros::Time::now(); + + sensor_msgs::PointCloud2Modifier cloud_mod(traj_cloud); + cloud_mod.setPointCloud2Fields(5, "x", 1, sensor_msgs::PointField::FLOAT32, + "y", 1, sensor_msgs::PointField::FLOAT32, + "z", 1, sensor_msgs::PointField::FLOAT32, + "theta", 1, sensor_msgs::PointField::FLOAT32, + "cost", 1, sensor_msgs::PointField::FLOAT32); + + unsigned int num_points = 0; + for(std::vector::iterator t=all_explored.begin(); t != all_explored.end(); ++t) + { + if (t->cost_<0) + continue; + num_points += t->getPointsSize(); + } + + cloud_mod.resize(num_points); + sensor_msgs::PointCloud2Iterator iter_x(traj_cloud, "x"); + for(std::vector::iterator t=all_explored.begin(); t != all_explored.end(); ++t) + { + if(t->cost_<0) + continue; + // Fill out the plan + for(unsigned int i = 0; i < t->getPointsSize(); ++i) { + double p_x, p_y, p_th; + t->getPoint(i, p_x, p_y, p_th); + iter_x[0] = p_x; + iter_x[1] = p_y; + iter_x[2] = 0.0; + iter_x[3] = p_th; + iter_x[4] = t->cost_; + ++iter_x; + } + } + traj_cloud_pub_.publish(traj_cloud); + } + + // verbose publishing of point clouds + if (publish_cost_grid_pc_) { + //we'll publish the visualization of the costs to rviz before returning our best trajectory + map_viz_.publishCostCloud(planner_util_->getCostmap()); + } + + // debrief stateful scoring functions + oscillation_costs_.updateOscillationFlags(pos, &result_traj_, planner_util_->getCurrentLimits().min_vel_trans); + + //if we don't have a legal trajectory, we'll just command zero + if (result_traj_.cost_ < 0) { + drive_velocities.pose.position.x = 0; + drive_velocities.pose.position.y = 0; + drive_velocities.pose.position.z = 0; + drive_velocities.pose.orientation.w = 1; + drive_velocities.pose.orientation.x = 0; + drive_velocities.pose.orientation.y = 0; + drive_velocities.pose.orientation.z = 0; + } else { + drive_velocities.pose.position.x = result_traj_.xv_; + drive_velocities.pose.position.y = result_traj_.yv_; + drive_velocities.pose.position.z = 0; + tf2::Quaternion q; + q.setRPY(0, 0, result_traj_.thetav_); + tf2::convert(q, drive_velocities.pose.orientation); + } + + return result_traj_; + } +}; diff --git a/navigations/dwa_local_planner/src/dwa_planner_ros.cpp b/navigations/dwa_local_planner/src/dwa_planner_ros.cpp new file mode 100755 index 0000000..c0551da --- /dev/null +++ b/navigations/dwa_local_planner/src/dwa_planner_ros.cpp @@ -0,0 +1,314 @@ +/********************************************************************* +* +* Software License Agreement (BSD License) +* +* Copyright (c) 2009, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of Willow Garage, Inc. nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* +* Author: Eitan Marder-Eppstein +*********************************************************************/ + +#include +#include +#include + +#include + +#include + +#include +#include +#include + +#include + +//register this planner as a BaseLocalPlanner plugin +PLUGINLIB_EXPORT_CLASS(dwa_local_planner::DWAPlannerROS, nav_core::BaseLocalPlanner) + +namespace dwa_local_planner { + + void DWAPlannerROS::reconfigureCB(DWAPlannerConfig &config, uint32_t level) { + if (setup_ && config.restore_defaults) { + config = default_config_; + config.restore_defaults = false; + } + if ( ! setup_) { + default_config_ = config; + setup_ = true; + } + + // update generic local planner params + base_local_planner::LocalPlannerLimits limits; + limits.max_vel_trans = config.max_vel_trans; + limits.min_vel_trans = config.min_vel_trans; + limits.max_vel_x = config.max_vel_x; + limits.min_vel_x = config.min_vel_x; + limits.max_vel_y = config.max_vel_y; + limits.min_vel_y = config.min_vel_y; + limits.max_vel_theta = config.max_vel_theta; + limits.min_vel_theta = config.min_vel_theta; + limits.acc_lim_x = config.acc_lim_x; + limits.acc_lim_y = config.acc_lim_y; + limits.acc_lim_theta = config.acc_lim_theta; + limits.acc_lim_trans = config.acc_lim_trans; + limits.xy_goal_tolerance = config.xy_goal_tolerance; + limits.yaw_goal_tolerance = config.yaw_goal_tolerance; + limits.prune_plan = config.prune_plan; + limits.trans_stopped_vel = config.trans_stopped_vel; + limits.theta_stopped_vel = config.theta_stopped_vel; + planner_util_.reconfigureCB(limits, config.restore_defaults); + + // update dwa specific configuration + dp_->reconfigure(config); + } + + DWAPlannerROS::DWAPlannerROS() : initialized_(false), + odom_helper_("odom"), setup_(false) { + + } + + void DWAPlannerROS::initialize( + std::string name, + tf2_ros::Buffer* tf, + costmap_2d::Costmap2DROS* costmap_ros) { + if (! isInitialized()) { + + ros::NodeHandle private_nh("~/" + name); + g_plan_pub_ = private_nh.advertise("global_plan", 1); + l_plan_pub_ = private_nh.advertise("local_plan", 1); + tf_ = tf; + costmap_ros_ = costmap_ros; + costmap_ros_->getRobotPose(current_pose_); + + // make sure to update the costmap we'll use for this cycle + costmap_2d::Costmap2D* costmap = costmap_ros_->getCostmap(); + + planner_util_.initialize(tf, costmap, costmap_ros_->getGlobalFrameID()); + + //create the actual planner that we'll use.. it'll configure itself from the parameter server + dp_ = boost::shared_ptr(new DWAPlanner(name, &planner_util_)); + + if( private_nh.getParam( "odom_topic", odom_topic_ )) + { + odom_helper_.setOdomTopic( odom_topic_ ); + } + + initialized_ = true; + + // Warn about deprecated parameters -- remove this block in N-turtle + nav_core::warnRenamedParameter(private_nh, "max_vel_trans", "max_trans_vel"); + nav_core::warnRenamedParameter(private_nh, "min_vel_trans", "min_trans_vel"); + nav_core::warnRenamedParameter(private_nh, "max_vel_theta", "max_rot_vel"); + nav_core::warnRenamedParameter(private_nh, "min_vel_theta", "min_rot_vel"); + nav_core::warnRenamedParameter(private_nh, "acc_lim_trans", "acc_limit_trans"); + nav_core::warnRenamedParameter(private_nh, "theta_stopped_vel", "rot_stopped_vel"); + + dsrv_ = new dynamic_reconfigure::Server(private_nh); + dynamic_reconfigure::Server::CallbackType cb = [this](auto& config, auto level){ reconfigureCB(config, level); }; + dsrv_->setCallback(cb); + } + else{ + ROS_WARN("This planner has already been initialized, doing nothing."); + } + } + + bool DWAPlannerROS::setPlan(const std::vector& orig_global_plan) { + if (! isInitialized()) { + ROS_ERROR("This planner has not been initialized, please call initialize() before using this planner"); + return false; + } + //when we get a new plan, we also want to clear any latch we may have on goal tolerances + latchedStopRotateController_.resetLatching(); + + ROS_INFO("Got new plan"); + return dp_->setPlan(orig_global_plan); + } + + bool DWAPlannerROS::isGoalReached() { + if (! isInitialized()) { + ROS_ERROR("This planner has not been initialized, please call initialize() before using this planner"); + return false; + } + if ( ! costmap_ros_->getRobotPose(current_pose_)) { + ROS_ERROR("Could not get robot pose"); + return false; + } + + if(latchedStopRotateController_.isGoalReached(&planner_util_, odom_helper_, current_pose_)) { + ROS_INFO("Goal reached"); + return true; + } else { + return false; + } + } + + void DWAPlannerROS::publishLocalPlan(std::vector& path) { + base_local_planner::publishPlan(path, l_plan_pub_); + } + + + void DWAPlannerROS::publishGlobalPlan(std::vector& path) { + base_local_planner::publishPlan(path, g_plan_pub_); + } + + DWAPlannerROS::~DWAPlannerROS(){ + //make sure to clean things up + delete dsrv_; + } + + + + bool DWAPlannerROS::dwaComputeVelocityCommands(geometry_msgs::PoseStamped &global_pose, geometry_msgs::Twist& cmd_vel) { + // dynamic window sampling approach to get useful velocity commands + if(! isInitialized()){ + ROS_ERROR("This planner has not been initialized, please call initialize() before using this planner"); + return false; + } + + geometry_msgs::PoseStamped robot_vel; + odom_helper_.getRobotVel(robot_vel); + + /* For timing uncomment + struct timeval start, end; + double start_t, end_t, t_diff; + gettimeofday(&start, NULL); + */ + + //compute what trajectory to drive along + geometry_msgs::PoseStamped drive_cmds; + drive_cmds.header.frame_id = costmap_ros_->getBaseFrameID(); + + // call with updated footprint + base_local_planner::Trajectory path = dp_->findBestPath(global_pose, robot_vel, drive_cmds); + //ROS_ERROR("Best: %.2f, %.2f, %.2f, %.2f", path.xv_, path.yv_, path.thetav_, path.cost_); + + /* For timing uncomment + gettimeofday(&end, NULL); + start_t = start.tv_sec + double(start.tv_usec) / 1e6; + end_t = end.tv_sec + double(end.tv_usec) / 1e6; + t_diff = end_t - start_t; + ROS_INFO("Cycle time: %.9f", t_diff); + */ + + //pass along drive commands + cmd_vel.linear.x = drive_cmds.pose.position.x; + cmd_vel.linear.y = drive_cmds.pose.position.y; + cmd_vel.angular.z = tf2::getYaw(drive_cmds.pose.orientation); + + //if we cannot move... tell someone + std::vector local_plan; + if(path.cost_ < 0) { + ROS_DEBUG_NAMED("dwa_local_planner", + "The dwa local planner failed to find a valid plan, cost functions discarded all candidates. This can mean there is an obstacle too close to the robot."); + local_plan.clear(); + publishLocalPlan(local_plan); + return false; + } + + ROS_DEBUG_NAMED("dwa_local_planner", "A valid velocity command of (%.2f, %.2f, %.2f) was found for this cycle.", + cmd_vel.linear.x, cmd_vel.linear.y, cmd_vel.angular.z); + + // Fill out the local plan + for(unsigned int i = 0; i < path.getPointsSize(); ++i) { + double p_x, p_y, p_th; + path.getPoint(i, p_x, p_y, p_th); + + geometry_msgs::PoseStamped p; + p.header.frame_id = costmap_ros_->getGlobalFrameID(); + p.header.stamp = ros::Time::now(); + p.pose.position.x = p_x; + p.pose.position.y = p_y; + p.pose.position.z = 0.0; + tf2::Quaternion q; + q.setRPY(0, 0, p_th); + tf2::convert(q, p.pose.orientation); + local_plan.push_back(p); + } + + //publish information to the visualizer + + publishLocalPlan(local_plan); + return true; + } + + + + + bool DWAPlannerROS::computeVelocityCommands(geometry_msgs::Twist& cmd_vel) { + // dispatches to either dwa sampling control or stop and rotate control, depending on whether we have been close enough to goal + if ( ! costmap_ros_->getRobotPose(current_pose_)) { + ROS_ERROR("Could not get robot pose"); + return false; + } + std::vector transformed_plan; + if ( ! planner_util_.getLocalPlan(current_pose_, transformed_plan)) { + ROS_ERROR("Could not get local plan"); + return false; + } + + //if the global plan passed in is empty... we won't do anything + if(transformed_plan.empty()) { + ROS_WARN_NAMED("dwa_local_planner", "Received an empty transformed plan."); + return false; + } + ROS_DEBUG_NAMED("dwa_local_planner", "Received a transformed plan with %zu points.", transformed_plan.size()); + + // update plan in dwa_planner even if we just stop and rotate, to allow checkTrajectory + dp_->updatePlanAndLocalCosts(current_pose_, transformed_plan, costmap_ros_->getRobotFootprint()); + + if (latchedStopRotateController_.isPositionReached(&planner_util_, current_pose_)) { + //publish an empty plan because we've reached our goal position + std::vector local_plan; + std::vector transformed_plan; + publishGlobalPlan(transformed_plan); + publishLocalPlan(local_plan); + base_local_planner::LocalPlannerLimits limits = planner_util_.getCurrentLimits(); + return latchedStopRotateController_.computeVelocityCommandsStopRotate( + cmd_vel, + limits.getAccLimits(), + dp_->getSimPeriod(), + &planner_util_, + odom_helper_, + current_pose_, + [this](auto pos, auto vel, auto vel_samples){ return dp_->checkTrajectory(pos, vel, vel_samples); }); + } else { + bool isOk = dwaComputeVelocityCommands(current_pose_, cmd_vel); + if (isOk) { + publishGlobalPlan(transformed_plan); + } else { + ROS_WARN_NAMED("dwa_local_planner", "DWA planner failed to produce path."); + std::vector empty_plan; + publishGlobalPlan(empty_plan); + } + return isOk; + } + } + +}; diff --git a/navigations/dwb_critics/CMakeLists.txt b/navigations/dwb_critics/CMakeLists.txt new file mode 100755 index 0000000..e6222b4 --- /dev/null +++ b/navigations/dwb_critics/CMakeLists.txt @@ -0,0 +1,64 @@ +cmake_minimum_required(VERSION 3.0.2) +project(dwb_critics) + +set_directory_properties(PROPERTIES COMPILE_OPTIONS "-std=c++11;-Wall;-Werror") + +find_package(catkin REQUIRED COMPONENTS + angles + costmap_queue + dwb_local_planner + geometry_msgs + nav_2d_msgs + nav_2d_utils + nav_core2 + nav_grid_iterators + pluginlib + roscpp + sensor_msgs +) + +catkin_package( + INCLUDE_DIRS include + LIBRARIES ${PROJECT_NAME} + CATKIN_DEPENDS angles costmap_queue dwb_local_planner geometry_msgs nav_2d_msgs nav_2d_utils nav_core2 nav_grid_iterators pluginlib roscpp sensor_msgs +) + +include_directories( + include + ${catkin_INCLUDE_DIRS} +) + +add_library(${PROJECT_NAME} + src/alignment_util.cpp + src/map_grid.cpp + src/goal_dist.cpp + src/path_dist.cpp + src/goal_align.cpp + src/path_align.cpp + src/base_obstacle.cpp + src/obstacle_footprint.cpp + src/oscillation.cpp + src/prefer_forward.cpp + src/rotate_to_goal.cpp + src/twirling.cpp +) +add_dependencies(${PROJECT_NAME} ${catkin_EXPORTED_TARGETS}) +target_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES}) + +if(CATKIN_ENABLE_TESTING) + find_package(roslint REQUIRED) + roslint_cpp() + roslint_add_test() +endif() + +install(TARGETS ${PROJECT_NAME} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} +) +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} +) +install(FILES default_critics.xml + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) diff --git a/navigations/dwb_critics/README.md b/navigations/dwb_critics/README.md new file mode 100755 index 0000000..98b5932 --- /dev/null +++ b/navigations/dwb_critics/README.md @@ -0,0 +1,31 @@ +# dwb_critics +This package contains plugin implementations of `dwb_local_planner::TrajectoryCritic` sufficient to replicate the behavior of `dwa_local_planner`. + +## Obstacle Avoidance +There are two options for critics that examine the contents of the costmap and reject trajectories that come close to obstacles. + * `BaseObstacleCritic` assumes a circular robot, and therefore only needs to check one cell in the costmap for each pose in the trajectory (assuming the costmap is properly inflated). + * `ObstacleFootprintCritic` uses the robot's footprint and checks all of the cells along the outline of the robot's footprint at each pose. + +## Progress Toward the Goal along the Path +There are two critics which evaluate the robot's position at the end of the trajectory relative to the goal pose and the global plan. + * `GoalDistCritic` estimates the distance from the last pose to the goal pose. + * `PathDistCritic` estimates the distance from the last pose to the closest pose in the global plan. + +## Alignment +There are also two critics for keeping the robot pointed in the right direction. They use a point on the front of the robot as a proxy to calculate which way the robot is pointed. + * `GoalAlignCritic` estimates the distance from the front of the robot to the goal pose. This score will be higher if the robot is pointed away from the goal. + * `PathAlignCritic` estimates the distance from the front of the robot to the closest point in the global plan. This score will be higher if the robot is pointed away from the global plan. + +## Rotating to the Goal +There is a special case in the navigation when the robot reaches the correct XY position, but still needs to rotate to the proper yaw. The standard critics will not be useful in this case. Instead we have `RotateToGoalCritic` which operates in a couple different modes. + * If the robot is not yet in the correct XY position, it has no effect on the trajectory score. + * If the robot is at the correct XY position but still moving, this critic will score the trajecotries such that the robot slows down. + * If the robot is at the correct XY position and stopped its forward motion, the critic will + A) Disallow trajectories with forward motion + B) Score trajectories (rotations) based on how close to the goal yaw they get. + +## Other Critics + * `OscillationCritic` detects oscillations by looking at the sign of the commanded motions. For example, if in a short window, the robot moves forward and then backward, it will penalize further trajectories that move forward again, as that is considered an oscillation. + * `PreferForwardCritic` was implemented but not used by `DWA` and penalize trajectories that move backwards and/or turn too much. + * `TwirlingCritic` penalizes trajectories with rotational velocities + diff --git a/navigations/dwb_critics/default_critics.xml b/navigations/dwb_critics/default_critics.xml new file mode 100755 index 0000000..8a39896 --- /dev/null +++ b/navigations/dwb_critics/default_critics.xml @@ -0,0 +1,42 @@ + + + + Penalize trajectories with move backwards and/or turn too much + + + Scores trajectories based on how far along the global path they end up. + + + Scores trajectories based on how far from the global path the front of the robot ends up. + + + + Scores trajectories based on whether the robot ends up pointing toward the eventual goal + + + + Scores trajectories based on how far from the global path they end up. + + + Checks to see whether the sign of the commanded velocity flips frequently + + + Forces the commanded trajectories to only be rotations if within a certain distance window + + + + Uses costmap 2d to assign negative costs if a circular robot + would collide at any point of the trajectory. + + + + Uses costmap 2d to assign negative costs if robot footprint is in obstacle + on any point of the trajectory. + + + + Penalize trajectories with rotational velocities + + + + diff --git a/navigations/dwb_critics/include/dwb_critics/alignment_util.h b/navigations/dwb_critics/include/dwb_critics/alignment_util.h new file mode 100755 index 0000000..3f1c718 --- /dev/null +++ b/navigations/dwb_critics/include/dwb_critics/alignment_util.h @@ -0,0 +1,54 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef DWB_CRITICS_ALIGNMENT_UTIL_H +#define DWB_CRITICS_ALIGNMENT_UTIL_H + +#include + +namespace dwb_critics +{ +/** + * @brief Projects the given pose forward the specified distance in the x direction. + * @param pose Input pose + * @param distance distance to move (in meters) + * @return Pose distance meters in front of input pose. + * + * (used in both path_align and dist_align) + */ +geometry_msgs::Pose2D getForwardPose(const geometry_msgs::Pose2D& pose, double distance); + +} // namespace dwb_critics + +#endif // DWB_CRITICS_ALIGNMENT_UTIL_H diff --git a/navigations/dwb_critics/include/dwb_critics/base_obstacle.h b/navigations/dwb_critics/include/dwb_critics/base_obstacle.h new file mode 100755 index 0000000..e1e484a --- /dev/null +++ b/navigations/dwb_critics/include/dwb_critics/base_obstacle.h @@ -0,0 +1,79 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef DWB_CRITICS_BASE_OBSTACLE_H +#define DWB_CRITICS_BASE_OBSTACLE_H + +#include + +namespace dwb_critics +{ +/** + * @class BaseObstacleCritic + * @brief Uses costmap to assign negative costs if a circular robot would collide at any point of the trajectory. + * + * This class can only be used to figure out if a circular robot is in collision. If the cell corresponding + * with any of the poses in the Trajectory is an obstacle, inscribed obstacle or unknown, it will return a + * negative cost. Otherwise it will return either the final pose's cost, or the sum of all poses, depending + * on the sum_scores parameter. + * + * Other classes (like ObstacleFootprintCritic) can do more advanced checking for collisions. + */ +class BaseObstacleCritic : public dwb_local_planner::TrajectoryCritic +{ +public: + void onInit() override; + double scoreTrajectory(const dwb_msgs::Trajectory2D& traj) override; + void addCriticVisualization(sensor_msgs::PointCloud& pc) override; + + /** + * @brief Return the obstacle score for a particular pose + * @param costmap Dereferenced costmap + * @param pose Pose to check + */ + virtual double scorePose(const nav_core2::Costmap& costmap, const geometry_msgs::Pose2D& pose); + + /** + * @brief Check to see whether a given cell cost is valid for driving through. + * @param cost Cost of the cell + * @return Return true if valid cell + */ + virtual bool isValidCost(const unsigned char cost); + +protected: + bool sum_scores_; +}; +} // namespace dwb_critics + +#endif // DWB_CRITICS_BASE_OBSTACLE_H diff --git a/navigations/dwb_critics/include/dwb_critics/goal_align.h b/navigations/dwb_critics/include/dwb_critics/goal_align.h new file mode 100755 index 0000000..dbba03e --- /dev/null +++ b/navigations/dwb_critics/include/dwb_critics/goal_align.h @@ -0,0 +1,65 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ +#ifndef DWB_CRITICS_GOAL_ALIGN_H_ +#define DWB_CRITICS_GOAL_ALIGN_H_ + +#include +#include +#include + +namespace dwb_critics +{ + +/** + * @class GoalAlignCritic + * @brief Scores trajectories based on whether the robot ends up pointing toward the eventual goal + * + * Similar to GoalDistCritic, this critic finds the pose from the global path farthest from the robot + * that is still on the costmap and then evaluates how far the front of the robot is from that point. + * This works as a proxy to calculating which way the robot should be pointing. + */ +class GoalAlignCritic: public GoalDistCritic +{ +public: + GoalAlignCritic() : forward_point_distance_(0.0) {} + void onInit() override; + bool prepare(const geometry_msgs::Pose2D& pose, const nav_2d_msgs::Twist2D& vel, + const geometry_msgs::Pose2D& goal, const nav_2d_msgs::Path2D& global_plan) override; + double scorePose(const geometry_msgs::Pose2D& pose) override; +protected: + double forward_point_distance_; +}; + +} // namespace dwb_critics +#endif // DWB_CRITICS_GOAL_ALIGN_H_ diff --git a/navigations/dwb_critics/include/dwb_critics/goal_dist.h b/navigations/dwb_critics/include/dwb_critics/goal_dist.h new file mode 100755 index 0000000..62c083a --- /dev/null +++ b/navigations/dwb_critics/include/dwb_critics/goal_dist.h @@ -0,0 +1,60 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ +#ifndef DWB_CRITICS_GOAL_DIST_H_ +#define DWB_CRITICS_GOAL_DIST_H_ + +#include +#include + +namespace dwb_critics +{ +/** + * @class GoalDistCritic + * @brief Scores trajectories based on how far along the global path they end up. + * + * This trajectory critic helps ensure progress along the global path. It finds the pose from the + * global path farthest from the robot that is still on the costmap, and aims for that point by + * assigning the lowest cost to the cell corresponding with that farthest pose. + */ +class GoalDistCritic: public MapGridCritic +{ +public: + bool prepare(const geometry_msgs::Pose2D& pose, const nav_2d_msgs::Twist2D& vel, + const geometry_msgs::Pose2D& goal, const nav_2d_msgs::Path2D& global_plan) override; +protected: + bool getLastPoseOnCostmap(const nav_2d_msgs::Path2D& global_plan, unsigned int& x, unsigned int& y); +}; + +} // namespace dwb_critics +#endif // DWB_CRITICS_GOAL_DIST_H_ diff --git a/navigations/dwb_critics/include/dwb_critics/map_grid.h b/navigations/dwb_critics/include/dwb_critics/map_grid.h new file mode 100755 index 0000000..8a1abdc --- /dev/null +++ b/navigations/dwb_critics/include/dwb_critics/map_grid.h @@ -0,0 +1,134 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef DWB_CRITICS_MAP_GRID_H +#define DWB_CRITICS_MAP_GRID_H + +#include +#include +#include +#include + +namespace dwb_critics +{ +/** + * @class MapGridCritic + * @brief breadth-first scoring of all the cells in the costmap + * + * This TrajectoryCritic assigns a score to every cell in the costmap based on + * the distance to the cell from some set of source points. The cells corresponding + * with the source points are marked with some initial score, and then every other cell + * is updated with a score based on its relation to the closest source cell, based on a + * breadth-first exploration of the cells of the costmap. + * + * This approach was chosen for computational efficiency, such that each trajectory + * need not be compared to the list of source points. + */ +class MapGridCritic: public dwb_local_planner::TrajectoryCritic +{ +public: + MapGridCritic() : cell_values_(-1.0) {} + + // Standard TrajectoryCritic Interface + void onInit() override; + double scoreTrajectory(const dwb_msgs::Trajectory2D& traj) override; + void addCriticVisualization(sensor_msgs::PointCloud& pc) override; + double getScale() const override { return costmap_->getResolution() * 0.5 * scale_; } + + // Helper Functions + /** + * @brief Retrieve the score for a single pose + * @param pose The pose to score, assumed to be in the same frame as the costmap + * @return The score associated with the cell of the costmap where the pose lies + */ + virtual double scorePose(const geometry_msgs::Pose2D& pose); + + /** + * @brief Retrieve the score for a particular cell of the costmap + * @param x x-coordinate within the costmap + * @param y y-coordinate within the costmap + * @return the score associated with that cell. + */ + inline double getScore(unsigned int x, unsigned int y) { return cell_values_(x, y); } + + /** + * @brief Sets the score of a particular cell to the obstacle cost + * @param x X coordinate of cell + * @param y Y coordinate of cell + */ + void setAsObstacle(unsigned int x, unsigned int y); + +protected: + /** + * @brief Separate modes for aggregating scores across the multiple poses in a trajectory. + * + * Last returns the score associated with the last pose in the trajectory + * Sum returns the sum of all the scores + * Product returns the product of all the (non-zero) scores + */ + enum class ScoreAggregationType {Last, Sum, Product}; + + /** + * @class MapGridQueue + * @brief Subclass of CostmapQueue that avoids Obstacles and Unknown Values + */ + class MapGridQueue : public costmap_queue::CostmapQueue + { + public: + MapGridQueue(nav_core2::Costmap& costmap, MapGridCritic& parent) + : costmap_queue::CostmapQueue(costmap, true), parent_(parent) {} + bool validCellToQueue(const costmap_queue::CellData& cell) override; + protected: + MapGridCritic& parent_; + }; + + /** + * @brief Clear the queue and set cell_values_ to the appropriate number of unreachableCellScore + */ + void reset() override; + + /** + * @brief Go through the queue and set the cells to the Manhattan distance from their parents + */ + void propogateManhattanDistances(); + + std::shared_ptr queue_; + nav_grid::VectorNavGrid cell_values_; + double obstacle_score_, unreachable_score_; ///< Special cell_values + bool stop_on_failure_; + ScoreAggregationType aggregationType_; +}; +} // namespace dwb_critics + +#endif // DWB_CRITICS_MAP_GRID_H diff --git a/navigations/dwb_critics/include/dwb_critics/metratronik_technik.h b/navigations/dwb_critics/include/dwb_critics/metratronik_technik.h new file mode 100755 index 0000000..fc3c378 --- /dev/null +++ b/navigations/dwb_critics/include/dwb_critics/metratronik_technik.h @@ -0,0 +1,126 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef METRATRONIK_TECHNIK_H_INCLUDE_ +#define METRATRONIK_TECHNIK_H_INCLUDE_ + +#include +#include +#include +#include +#include + +namespace dwb_critics +{ + /* data */ + struct lineEquation + { + geometry_msgs::Pose2D Gi; /* 𝑮𝒊(𝒙𝒊,𝒚𝒊) */ + geometry_msgs::Pose2D Gj; /* 𝑮𝒋(𝒙𝒋,𝒚𝒋) */ + float a, b, c; /* 𝒂𝒙+𝒃𝒚+𝒄=𝟎 */ + }; + + /* Save data present position */ + struct presentPosition + { + float Gxh, Gyh; /* 𝑮𝒋(𝒙h,𝒚h) The head position in Robot */ + float Yaw_degree; /* Angle of Robot (degree) */ + float Yaw_rad; /* Angle of Robot (degree) */ + float error_line; /* 𝒆(𝑮,𝒍𝒊𝒏𝒆)=|𝒂𝒙+𝒃𝒚+𝒄|/sqrt(𝒂^2+𝒃^2) */ + double distanceToEnd; /* The distance from robot to End point */ + double distanceToStart; /* The distance from robot to End point */ + }; + + class NoSolution : public std::exception + { + public: + const char *what() const throw() + { + return "Robot cannot calculate error line!"; + } + }; + + class MetratronikTechnikCritic : public dwb_local_planner::TrajectoryCritic + { + public: + void onInit() override; + void reset() override; + bool prepare(const geometry_msgs::Pose2D &pose, const nav_2d_msgs::Twist2D &vel, + const geometry_msgs::Pose2D &goal, const nav_2d_msgs::Path2D &global_plan) override; + double scoreTrajectory(const dwb_msgs::Trajectory2D &traj) override; + + protected: + /** + * @brief Assuming that this is an actual rotation when near the goal, score the trajectory. + * + * Phương pháp này (dễ dàng ghi đè) giả định rằng người phê bình đang ở giai đoạn thứ ba (như mô tả ở trên) + * và trả về một số điểm cho quỹ đạo tương ứng với độ lệch mục tiêu. + * @param traj Trajectory to score + * @return numeric score + */ + virtual double scoreMetratronikTechnik(const dwb_msgs::Trajectory2D &traj); + bool getPosition(const geometry_msgs::Pose2D &robot_pose, const nav_2d_msgs::Path2D &global_plan, double &position); + unsigned getGoalIndex(const geometry_msgs::Pose2D &robot_pose, + const std::vector &plan, + unsigned int start_index, + unsigned int last_valid_index) const; + + /** + * @brief To caculated the equation of the line + * @param start_point start point of the line + * @param end_point end point of the line + */ + bool getLine(geometry_msgs::Pose2D start_point, geometry_msgs::Pose2D end_point, lineEquation &leq); + + /** + * @brief Calculating error + * @param[in] Lm The distance from the center of the wheel axis to the center line + * @param[in] Yaw_degree Angle of Robot (degree) + */ + presentPosition calculateError(const lineEquation &leq, const float Lm, const geometry_msgs::Pose2D robot_pose, float pha); + + bool in_window_, running_; + double sq_window_; + double xy_local_goal_tolerance_; + double xy_local_goal_tolerance_sq_; ///< Cached squared tolerance + double current_speed_, stopped_velocity_; + double slowing_factor_; + double current_position_; + double angle_threshold_; + double Lm_; + double dxy_sq_; + std::vector reached_intermediate_goals_; + }; +} +#endif \ No newline at end of file diff --git a/navigations/dwb_critics/include/dwb_critics/obstacle_footprint.h b/navigations/dwb_critics/include/dwb_critics/obstacle_footprint.h new file mode 100755 index 0000000..2f1836a --- /dev/null +++ b/navigations/dwb_critics/include/dwb_critics/obstacle_footprint.h @@ -0,0 +1,70 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef DWB_CRITICS_OBSTACLE_FOOTPRINT_H +#define DWB_CRITICS_OBSTACLE_FOOTPRINT_H + +#include +#include +#include + +namespace dwb_critics +{ + +/** + * @class ObstacleFootprintCritic + * @brief Uses costmap 2d to assign negative costs if robot footprint is in obstacle on any point of the trajectory. + * + * Internally, this technically only checks if the border of the footprint collides with anything for computational + * efficiency. This is valid if the obstacles in the local costmap are inflated. + * + * A more robust class could check every cell within the robot's footprint without inflating the obstacles, + * at some computational cost. That is left as an excercise to the reader. + */ +class ObstacleFootprintCritic : public BaseObstacleCritic +{ +public: + void onInit() override; + bool prepare(const geometry_msgs::Pose2D& pose, const nav_2d_msgs::Twist2D& vel, + const geometry_msgs::Pose2D& goal, const nav_2d_msgs::Path2D& global_plan) override; + double scorePose(const nav_core2::Costmap& costmap, const geometry_msgs::Pose2D& pose) override; + virtual double scorePose(const nav_core2::Costmap& costmap, const geometry_msgs::Pose2D& pose, + const nav_2d_msgs::Polygon2D& oriented_footprint); + double getScale() const override { return costmap_->getResolution() * scale_; } +protected: + nav_2d_msgs::Polygon2D footprint_spec_; +}; +} // namespace dwb_critics + +#endif // DWB_CRITICS_OBSTACLE_FOOTPRINT_H diff --git a/navigations/dwb_critics/include/dwb_critics/oscillation.h b/navigations/dwb_critics/include/dwb_critics/oscillation.h new file mode 100755 index 0000000..b34ad39 --- /dev/null +++ b/navigations/dwb_critics/include/dwb_critics/oscillation.h @@ -0,0 +1,154 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef DWB_CRITICS_OSCILLATION_H_ +#define DWB_CRITICS_OSCILLATION_H_ + +#include +#include +#include + +namespace dwb_critics +{ + +/** + * @class OscillationCritic + * @brief Checks to see whether the sign of the commanded velocity flips frequently + * + * This critic figures out if the commanded trajectories are oscillating by seeing + * if one of the dimensions (x,y,theta) flips from positive to negative and then back + * (or vice versa) without moving sufficiently far or waiting sufficiently long. + * + * Scenario 1: Robot moves one meter forward, and then two millimeters backward. + * Another forward motion would be considered oscillating, since the x dimension would then + * flip from positive to negative and then back to negative. Hence, when scoring different + * trajectories, positive velocity commands will get the oscillation_score (-5.0, or invalid) + * and only negative velocity commands will be considered valid. + + * Scenario 2: Robot moves one meter forward, and then one meter backward. + * The robot has thus moved one meter since flipping the sign of the x direction, which + * is greater than our oscillation_reset_dist, so its not considered oscillating, so all + * trajectories are considered valid. + * + * Note: The critic will only check oscillations in the x dimension while it exceeds + * a particular value (x_only_threshold_). If it dips below that magnitude, it will + * also check for oscillations in the y and theta dimensions. If x_only_threshold_ is + * negative, then the critic will always check all dimensions. + * + * Implementation Details: + * The critic saves the robot's current position when it prepares, and what the actual + * commanded velocity was during the debrief step. Upon debriefing, if the sign of any of + * dimensions has flipped since the last command, the position is saved as prev_stationary_pose_. + * + * If the linear or angular distance from prev_stationary_pose_ to the current pose exceeds + * the limits, the oscillation flags are reset so the previous sign change is no longer remembered. + * This assumes that oscillation_reset_dist_ or oscillation_reset_angle_ are positive. Otherwise, + * it uses a time based delay reset function. + */ +class OscillationCritic: public dwb_local_planner::TrajectoryCritic +{ +public: + void onInit() override; + bool prepare(const geometry_msgs::Pose2D& pose, const nav_2d_msgs::Twist2D& vel, + const geometry_msgs::Pose2D& goal, const nav_2d_msgs::Path2D& global_plan) override; + double scoreTrajectory(const dwb_msgs::Trajectory2D& traj) override; + void reset() override; + void debrief(const nav_2d_msgs::Twist2D& cmd_vel) override; + +protected: + /** + * @class CommandTrend + * @brief Helper class for performing the same logic on the x,y and theta dimensions + */ + class CommandTrend + { + public: + CommandTrend(); + void reset(); + + /** + * @brief update internal flags based on the commanded velocity + * @param velocity commanded velocity for the dimension this trend is tracking + * @return true if the sign has flipped + */ + bool update(double velocity); + + /** + * @brief Check to see whether the proposed velocity would be considered oscillating + * @param velocity the velocity to evaluate + * @return true if the sign has flipped more than once + */ + bool isOscillating(double velocity); + + /** + * @brief Check whether we are currently tracking a flipped sign + * @return True if the sign has flipped + */ + bool hasSignFlipped(); + + protected: + // Simple Enum for Tracking + enum class Sign { ZERO, POSITIVE, NEGATIVE }; + + Sign sign_; + bool positive_only_, negative_only_; + }; + + /** + * @brief Given a command that has been selected, track each component's sign for oscillations + * @param cmd_vel The command velocity selected by the algorithm + * @return True if the sign on any of the components flipped + */ + bool setOscillationFlags(const nav_2d_msgs::Twist2D& cmd_vel); + + /** + * @brief Return true if the robot has travelled far enough or waited long enough + */ + bool resetAvailable(); + + CommandTrend x_trend_, y_trend_, theta_trend_; + double oscillation_reset_dist_, oscillation_reset_angle_, x_only_threshold_; + double oscillation_reset_time_; + + // Cached square parameter + double oscillation_reset_dist_sq_; + + // Saved positions + geometry_msgs::Pose2D pose_, prev_stationary_pose_; + // Saved timestamp + ros::Time prev_reset_time_; +}; + +} // namespace dwb_critics +#endif // DWB_CRITICS_OSCILLATION_H_ diff --git a/navigations/dwb_critics/include/dwb_critics/path_align.h b/navigations/dwb_critics/include/dwb_critics/path_align.h new file mode 100755 index 0000000..8063f8a --- /dev/null +++ b/navigations/dwb_critics/include/dwb_critics/path_align.h @@ -0,0 +1,71 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ +#ifndef DWB_CRITICS_PATH_ALIGN_H_ +#define DWB_CRITICS_PATH_ALIGN_H_ + +#include +#include +#include + +namespace dwb_critics +{ +/** + * @class PathAlignCritic + * @brief Scores trajectories based on how far from the global path the front of the robot ends up. + * + * This uses the costmap grid as a proxy for calculating which way the robot should be facing relative + * to the global path. Instead of scoring how far the center of the robot is away from the global path, + * this critic calculates how far a point forward_point_distance in front of the robot is from the global + * path. This biases the planner toward trajectories that line up with the global plan. + * + * When the robot is near the end of the path, the scale of this critic is set to zero. When the projected + * point is past the global goal, we no longer want this critic to try to align to a part of the global path + * that isn't there. + */ +class PathAlignCritic: public PathDistCritic +{ +public: + PathAlignCritic() : zero_scale_(false), forward_point_distance_(0.0) {} + void onInit() override; + bool prepare(const geometry_msgs::Pose2D& pose, const nav_2d_msgs::Twist2D& vel, + const geometry_msgs::Pose2D& goal, const nav_2d_msgs::Path2D& global_plan) override; + double getScale() const override; + double scorePose(const geometry_msgs::Pose2D& pose) override; +protected: + bool zero_scale_; + double forward_point_distance_; +}; + +} // namespace dwb_critics +#endif // DWB_CRITICS_PATH_ALIGN_H_ diff --git a/navigations/dwb_critics/include/dwb_critics/path_dist.h b/navigations/dwb_critics/include/dwb_critics/path_dist.h new file mode 100755 index 0000000..4f8c28d --- /dev/null +++ b/navigations/dwb_critics/include/dwb_critics/path_dist.h @@ -0,0 +1,53 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ +#ifndef DWB_CRITICS_PATH_DIST_H_ +#define DWB_CRITICS_PATH_DIST_H_ + +#include + +namespace dwb_critics +{ +/** + * @class PathDistCritic + * @brief Scores trajectories based on how far from the global path they end up. + */ +class PathDistCritic: public MapGridCritic +{ +public: + bool prepare(const geometry_msgs::Pose2D& pose, const nav_2d_msgs::Twist2D& vel, + const geometry_msgs::Pose2D& goal, const nav_2d_msgs::Path2D& global_plan) override; +}; + +} // namespace dwb_critics +#endif // DWB_CRITICS_PATH_DIST_H_ diff --git a/navigations/dwb_critics/include/dwb_critics/prefer_forward.h b/navigations/dwb_critics/include/dwb_critics/prefer_forward.h new file mode 100755 index 0000000..64bb547 --- /dev/null +++ b/navigations/dwb_critics/include/dwb_critics/prefer_forward.h @@ -0,0 +1,65 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef DWB_CRITICS_PREFER_FORWARD_H_ +#define DWB_CRITICS_PREFER_FORWARD_H_ + +#include +#include + +namespace dwb_critics +{ + +/** + * @class PreferForwardCritic + * @brief Penalize trajectories with move backwards and/or turn too much + * + * Has three different scoring conditions: + * 1) If the trajectory's x velocity is negative, return the penalty + * 2) If the trajectory's x is low and the theta is also low, return the penalty. + * 3) Otherwise, return a scaled version of the trajectory's theta. + */ +class PreferForwardCritic: public dwb_local_planner::TrajectoryCritic +{ +public: + PreferForwardCritic() : penalty_(1.0), strafe_x_(0.1), strafe_theta_(0.2), theta_scale_(10.0) {} + void onInit() override; + double scoreTrajectory(const dwb_msgs::Trajectory2D& traj) override; + +protected: + double penalty_, strafe_x_, strafe_theta_, theta_scale_; +}; + +} /* namespace dwb_critics */ +#endif /* DWB_CRITICS_PREFER_FORWARD_H_ */ diff --git a/navigations/dwb_critics/include/dwb_critics/rotate_to_goal.h b/navigations/dwb_critics/include/dwb_critics/rotate_to_goal.h new file mode 100755 index 0000000..5d9f599 --- /dev/null +++ b/navigations/dwb_critics/include/dwb_critics/rotate_to_goal.h @@ -0,0 +1,100 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ +#ifndef DWB_CRITICS_ROTATE_TO_GOAL_H_ +#define DWB_CRITICS_ROTATE_TO_GOAL_H_ + +#include +#include +#include + +namespace dwb_critics +{ + +/** + * @class RotateToGoalCritic + * @brief Forces the commanded trajectories to only be rotations if within a certain distance window + * + * This used to be built in to the DWA Local Planner as the LatchedStopRotate controller, + * but has been moved to a critic for consistency. + * + * The critic has three distinct phases. + * 1) If the current pose is outside xy_goal_tolerance LINEAR distance from the goal pose, this critic + * will just return score 0.0. + * 2) If within the xy_goal_tolerance and the robot is still moving with non-zero linear motion, this critic + * will only allow trajectories that are slower than the current speed in order to stop the robot (within + * the robot's acceleration limits). The returned score will be the robot's linear speed squared, multiplied + * by the slowing_factor parameter (default 5.0) added to the result of scoreRotation. + * 3) If within the xy_goal_tolerance and the robot has sufficiently small linear motion, this critic will + * score trajectories that have linear movement as invalid and score the rest based on the result of the + * scoreRotation method + * + * The scoreRotation method can be overriden, but the default behavior is to return the shortest angular distance + * between the goal pose and a pose from the trajectory. Which pose depends on the lookahead_time parameter. + * * If the lookahead_time parameter is negative, the pose evaluated will be the last pose in the trajectory, + * which is the same as DWA's behavior. This is the default. + * * Otherwise, a new pose will be projected using the dwb_local_planner::projectPose. By using a lookahead + * time shorter than sim_time, the critic will be less concerned about overshooting the goal yaw and thus will + * continue to turn faster for longer. + */ +class RotateToGoalCritic : public dwb_local_planner::TrajectoryCritic +{ +public: + void onInit() override; + void reset() override; + bool prepare(const geometry_msgs::Pose2D& pose, const nav_2d_msgs::Twist2D& vel, + const geometry_msgs::Pose2D& goal, const nav_2d_msgs::Path2D& global_plan) override; + double scoreTrajectory(const dwb_msgs::Trajectory2D& traj) override; + + /** + * @brief Assuming that this is an actual rotation when near the goal, score the trajectory. + * + * This (easily overridden) method assumes that the critic is in the third phase (as described above) + * and returns a numeric score for the trajectory relative to the goal yaw. + * @param traj Trajectory to score + * @return numeric score + */ + virtual double scoreRotation(const dwb_msgs::Trajectory2D& traj); + +protected: + bool in_window_, rotating_; + double goal_yaw_; + double xy_goal_tolerance_; + double xy_goal_tolerance_sq_; ///< Cached squared tolerance + double current_xy_speed_sq_, stopped_xy_velocity_sq_; + double slowing_factor_; + double lookahead_time_; +}; + +} // namespace dwb_critics +#endif // DWB_CRITICS_ROTATE_TO_GOAL_H_ diff --git a/navigations/dwb_critics/include/dwb_critics/twirling.h b/navigations/dwb_critics/include/dwb_critics/twirling.h new file mode 100755 index 0000000..65a3d59 --- /dev/null +++ b/navigations/dwb_critics/include/dwb_critics/twirling.h @@ -0,0 +1,59 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef DWB_CRITICS_TWIRLING_H +#define DWB_CRITICS_TWIRLING_H + +#include + +namespace dwb_critics +{ +/** + * @class TwirlingCritic + * @brief Penalize trajectories with rotational velocities + * + * This class provides a cost based on how much a robot "twirls" on its way to the goal. With + * differential-drive robots, there isn't a choice, but with holonomic or near-holonomic robots, + * sometimes a robot spins more than you'd like on its way to a goal. This class provides a way + * to assign a penalty purely to rotational velocities. + */ +class TwirlingCritic: public dwb_local_planner::TrajectoryCritic +{ +public: + void onInit() override; + double scoreTrajectory(const dwb_msgs::Trajectory2D& traj) override; +}; +} // namespace dwb_critics + +#endif // DWB_CRITICS_TWIRLING_H diff --git a/navigations/dwb_critics/package.xml b/navigations/dwb_critics/package.xml new file mode 100755 index 0000000..81c272a --- /dev/null +++ b/navigations/dwb_critics/package.xml @@ -0,0 +1,30 @@ + + + dwb_critics + 0.3.0 + + Implementations for dwb_local_planner TrajectoryCritic interface + + + David V. Lu!! + David V. Lu!! + + BSD + catkin + angles + costmap_queue + dwb_local_planner + geometry_msgs + nav_2d_msgs + nav_2d_utils + nav_core2 + nav_grid_iterators + pluginlib + roscpp + sensor_msgs + roslint + + + + + diff --git a/navigations/dwb_critics/src/alignment_util.cpp b/navigations/dwb_critics/src/alignment_util.cpp new file mode 100755 index 0000000..3fefce9 --- /dev/null +++ b/navigations/dwb_critics/src/alignment_util.cpp @@ -0,0 +1,47 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include + +namespace dwb_critics +{ +geometry_msgs::Pose2D getForwardPose(const geometry_msgs::Pose2D& pose, double distance) +{ + geometry_msgs::Pose2D forward_pose; + forward_pose.x = pose.x + distance * cos(pose.theta); + forward_pose.y = pose.y + distance * sin(pose.theta); + forward_pose.theta = pose.theta; + return forward_pose; +} +} // namespace dwb_critics diff --git a/navigations/dwb_critics/src/base_obstacle.cpp b/navigations/dwb_critics/src/base_obstacle.cpp new file mode 100755 index 0000000..2af947a --- /dev/null +++ b/navigations/dwb_critics/src/base_obstacle.cpp @@ -0,0 +1,102 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include +#include +#include + +PLUGINLIB_EXPORT_CLASS(dwb_critics::BaseObstacleCritic, dwb_local_planner::TrajectoryCritic) + +namespace dwb_critics +{ + +void BaseObstacleCritic::onInit() +{ + critic_nh_.param("sum_scores", sum_scores_, false); +} + +double BaseObstacleCritic::scoreTrajectory(const dwb_msgs::Trajectory2D& traj) +{ + const nav_core2::Costmap& costmap = *costmap_; + double score = 0.0; + for (unsigned int i = 0; i < traj.poses.size(); ++i) + { + double pose_score = scorePose(costmap, traj.poses[i]); + // Optimized/branchless version of if (sum_scores_) score += pose_score, else score = pose_score; + score = static_cast(sum_scores_) * score + pose_score; + } + return score; +} + +double BaseObstacleCritic::scorePose(const nav_core2::Costmap& costmap, const geometry_msgs::Pose2D& pose) +{ + unsigned int cell_x, cell_y; + if (!worldToGridBounded(costmap.getInfo(), pose.x, pose.y, cell_x, cell_y)) + throw nav_core2::IllegalTrajectoryException(name_, "Trajectory Goes Off Grid."); + unsigned char cost = costmap(cell_x, cell_y); + if (!isValidCost(cost)) + throw nav_core2::IllegalTrajectoryException(name_, "Trajectory Hits Obstacle."); + return cost; +} + +bool BaseObstacleCritic::isValidCost(const unsigned char cost) +{ + return cost != costmap_->LETHAL_OBSTACLE && + cost != costmap_->INSCRIBED_INFLATED_OBSTACLE && + cost != costmap_->NO_INFORMATION; +} + +void BaseObstacleCritic::addCriticVisualization(sensor_msgs::PointCloud& pc) +{ + sensor_msgs::ChannelFloat32 grid_scores; + grid_scores.name = name_; + + const nav_core2::Costmap& costmap = *costmap_; + unsigned int size_x = costmap.getWidth(); + unsigned int size_y = costmap.getHeight(); + grid_scores.values.resize(size_x * size_y); + unsigned int i = 0; + for (unsigned int cy = 0; cy < size_y; cy++) + { + for (unsigned int cx = 0; cx < size_x; cx++) + { + grid_scores.values[i] = costmap(cx, cy); + i++; + } + } + pc.channels.push_back(grid_scores); +} + +} // namespace dwb_critics diff --git a/navigations/dwb_critics/src/goal_align.cpp b/navigations/dwb_critics/src/goal_align.cpp new file mode 100755 index 0000000..21b48c5 --- /dev/null +++ b/navigations/dwb_critics/src/goal_align.cpp @@ -0,0 +1,76 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ +#include +#include +#include +#include +#include +#include + +namespace dwb_critics +{ + +void GoalAlignCritic::onInit() +{ + GoalDistCritic::onInit(); + stop_on_failure_ = false; + forward_point_distance_ = nav_2d_utils::searchAndGetParam(critic_nh_, "forward_point_distance", 0.325); +} + +bool GoalAlignCritic::prepare(const geometry_msgs::Pose2D& pose, const nav_2d_msgs::Twist2D& vel, + const geometry_msgs::Pose2D& goal, + const nav_2d_msgs::Path2D& global_plan) +{ + // we want the robot nose to be drawn to its final position + // (before robot turns towards goal orientation), not the end of the + // path for the robot center. Choosing the final position after + // turning towards goal orientation causes instability when the + // robot needs to make a 180 degree turn at the end + double angle_to_goal = atan2(goal.y - pose.y, goal.x - pose.x); + + nav_2d_msgs::Path2D target_poses = global_plan; + target_poses.poses.back().x += forward_point_distance_ * cos(angle_to_goal); + target_poses.poses.back().y += forward_point_distance_ * sin(angle_to_goal); + + return GoalDistCritic::prepare(pose, vel, goal, target_poses); +} + +double GoalAlignCritic::scorePose(const geometry_msgs::Pose2D& pose) +{ + return GoalDistCritic::scorePose(getForwardPose(pose, forward_point_distance_)); +} + +} // namespace dwb_critics + +PLUGINLIB_EXPORT_CLASS(dwb_critics::GoalAlignCritic, dwb_local_planner::TrajectoryCritic) diff --git a/navigations/dwb_critics/src/goal_dist.cpp b/navigations/dwb_critics/src/goal_dist.cpp new file mode 100755 index 0000000..102868f --- /dev/null +++ b/navigations/dwb_critics/src/goal_dist.cpp @@ -0,0 +1,104 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ +#include +#include +#include +#include +#include + +namespace dwb_critics +{ +bool GoalDistCritic::prepare(const geometry_msgs::Pose2D& pose, const nav_2d_msgs::Twist2D& vel, + const geometry_msgs::Pose2D& goal, + const nav_2d_msgs::Path2D& global_plan) +{ + reset(); + + unsigned int local_goal_x, local_goal_y; + if (!getLastPoseOnCostmap(global_plan, local_goal_x, local_goal_y)) + { + return false; + } + + // Enqueue just the last pose + cell_values_.setValue(local_goal_x, local_goal_y, 0.0); + queue_->enqueueCell(local_goal_x, local_goal_y); + + propogateManhattanDistances(); + + return true; +} + +bool GoalDistCritic::getLastPoseOnCostmap(const nav_2d_msgs::Path2D& global_plan, unsigned int& x, unsigned int& y) +{ + const nav_core2::Costmap& costmap = *costmap_; + const nav_grid::NavGridInfo& info = costmap.getInfo(); + nav_2d_msgs::Path2D adjusted_global_plan = nav_2d_utils::adjustPlanResolution(global_plan, info.resolution); + bool started_path = false; + + // skip global path points until we reach the border of the local map + for (unsigned int i = 0; i < adjusted_global_plan.poses.size(); ++i) + { + double g_x = adjusted_global_plan.poses[i].x; + double g_y = adjusted_global_plan.poses[i].y; + unsigned int map_x, map_y; + if (worldToGridBounded(info, g_x, g_y, map_x, map_y) && costmap(map_x, map_y) != costmap.NO_INFORMATION) + { + // Still on the costmap. Continue. + x = map_x; + y = map_y; + started_path = true; + } + else if (started_path) + { + // Off the costmap after being on the costmap. Return the last saved indices. + return true; + } + // else, we have not yet found a point on the costmap, so we just continue + } + + if (started_path) + { + return true; + } + else + { + ROS_ERROR_NAMED("GoalDistCritic", "None of the points of the global plan were in the local costmap."); + return false; + } +} + +} // namespace dwb_critics + +PLUGINLIB_EXPORT_CLASS(dwb_critics::GoalDistCritic, dwb_local_planner::TrajectoryCritic) diff --git a/navigations/dwb_critics/src/map_grid.cpp b/navigations/dwb_critics/src/map_grid.cpp new file mode 100755 index 0000000..df16f4d --- /dev/null +++ b/navigations/dwb_critics/src/map_grid.cpp @@ -0,0 +1,202 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include +#include +#include +#include +#include + +namespace dwb_critics +{ + +// Customization of the CostmapQueue validCellToQueue method +bool MapGridCritic::MapGridQueue::validCellToQueue(const costmap_queue::CellData& cell) +{ + unsigned char cost = costmap_(cell.x_, cell.y_); + if (cost == costmap_.LETHAL_OBSTACLE || + cost == costmap_.INSCRIBED_INFLATED_OBSTACLE || + cost == costmap_.NO_INFORMATION) + { + parent_.setAsObstacle(cell.x_, cell.y_); + return false; + } + + return true; +} + +void MapGridCritic::onInit() +{ + queue_ = std::make_shared(*costmap_, *this); + + // Always set to true, but can be overriden by subclasses + stop_on_failure_ = true; + + std::string aggro_str; + critic_nh_.param("aggregation_type", aggro_str, std::string("last")); + std::transform(aggro_str.begin(), aggro_str.end(), aggro_str.begin(), ::tolower); + if (aggro_str == "last") + { + aggregationType_ = ScoreAggregationType::Last; + } + else if (aggro_str == "sum") + { + aggregationType_ = ScoreAggregationType::Sum; + } + else if (aggro_str == "product") + { + aggregationType_ = ScoreAggregationType::Product; + } + else + { + ROS_ERROR_NAMED("MapGridCritic", "aggregation_type parameter \"%s\" invalid. Using Last.", aggro_str.c_str()); + aggregationType_ = ScoreAggregationType::Last; + } +} + +void MapGridCritic::setAsObstacle(unsigned int x, unsigned int y) +{ + cell_values_.setValue(x, y, obstacle_score_); +} + +void MapGridCritic::reset() +{ + queue_->reset(); + if (costmap_->getInfo() == cell_values_.getInfo()) + { + cell_values_.reset(); + } + else + { + obstacle_score_ = static_cast(costmap_->getWidth() * costmap_->getHeight()); + unreachable_score_ = obstacle_score_ + 1.0; + cell_values_.setDefaultValue(unreachable_score_); + cell_values_.setInfo(costmap_->getInfo()); + } +} + +void MapGridCritic::propogateManhattanDistances() +{ + while (!queue_->isEmpty()) + { + costmap_queue::CellData cell = queue_->getNextCell(); + cell_values_.setValue(cell.x_, cell.y_, + std::abs(static_cast(cell.src_x_) - static_cast(cell.x_)) + + std::abs(static_cast(cell.src_y_) - static_cast(cell.y_))); + } +} + +double MapGridCritic::scoreTrajectory(const dwb_msgs::Trajectory2D& traj) +{ + double score = 0.0; + unsigned int start_index = 0; + if (aggregationType_ == ScoreAggregationType::Product) + { + score = 1.0; + } + else if (aggregationType_ == ScoreAggregationType::Last && !stop_on_failure_) + { + start_index = traj.poses.size() - 1; + } + double grid_dist; + + for (unsigned int i = start_index; i < traj.poses.size(); ++i) + { + grid_dist = scorePose(traj.poses[i]); + if (stop_on_failure_) + { + if (grid_dist == obstacle_score_) + { + throw nav_core2::IllegalTrajectoryException(name_, "Trajectory Hits Obstacle."); + } + else if (grid_dist == unreachable_score_) + { + throw nav_core2::IllegalTrajectoryException(name_, "Trajectory Hits Unreachable Area."); + } + } + + switch (aggregationType_) + { + case ScoreAggregationType::Last: + score = grid_dist; + break; + case ScoreAggregationType::Sum: + score += grid_dist; + break; + case ScoreAggregationType::Product: + if (score > 0) + { + score *= grid_dist; + } + break; + } + } + + return score; +} + +double MapGridCritic::scorePose(const geometry_msgs::Pose2D& pose) +{ + unsigned int cell_x, cell_y; + // we won't allow trajectories that go off the map... shouldn't happen that often anyways + if (!worldToGridBounded(costmap_->getInfo(), pose.x, pose.y, cell_x, cell_y)) + { + throw nav_core2::IllegalTrajectoryException(name_, "Trajectory Goes Off Grid."); + } + return getScore(cell_x, cell_y); +} + +void MapGridCritic::addCriticVisualization(sensor_msgs::PointCloud& pc) +{ + sensor_msgs::ChannelFloat32 grid_scores; + grid_scores.name = name_; + + const nav_core2::Costmap& costmap = *costmap_; + unsigned int size_x = costmap.getWidth(); + unsigned int size_y = costmap.getHeight(); + grid_scores.values.resize(size_x * size_y); + unsigned int i = 0; + for (unsigned int cy = 0; cy < size_y; cy++) + { + for (unsigned int cx = 0; cx < size_x; cx++) + { + grid_scores.values[i] = getScore(cx, cy); + i++; + } + } + pc.channels.push_back(grid_scores); +} + +} // namespace dwb_critics diff --git a/navigations/dwb_critics/src/metratronik_technik.cpp b/navigations/dwb_critics/src/metratronik_technik.cpp new file mode 100755 index 0000000..302ff49 --- /dev/null +++ b/navigations/dwb_critics/src/metratronik_technik.cpp @@ -0,0 +1,362 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ +#include +#include +#include +#include +#include +#include + +const double EPSILON = 1E-5; + +PLUGINLIB_EXPORT_CLASS(dwb_critics::MetratronikTechnikCritic, dwb_local_planner::TrajectoryCritic) + +namespace dwb_critics +{ + inline double hypot_sq(double dx, double dy) + { + return dx * dx + dy * dy; + } + + void MetratronikTechnikCritic::onInit() + { + xy_local_goal_tolerance_ = nav_2d_utils::searchAndGetParam(critic_nh_, "xy_goal_tolerance", 0.25); + xy_local_goal_tolerance_sq_ = xy_local_goal_tolerance_ * xy_local_goal_tolerance_; + stopped_velocity_ = nav_2d_utils::searchAndGetParam(critic_nh_, "trans_stopped_velocity", 0.25); + critic_nh_.param("sq_window", sq_window_, 1.0); + critic_nh_.param("slowing_factor", slowing_factor_, 5.0); + critic_nh_.param("angle_threshold", angle_threshold_, 0.436332313); + critic_nh_.param("Lm", Lm_, 0.436332313); + reset(); + } + + void MetratronikTechnikCritic::reset() + { + in_window_ = false; + running_ = false; + } + + bool MetratronikTechnikCritic::prepare(const geometry_msgs::Pose2D &pose, const nav_2d_msgs::Twist2D &vel, + const geometry_msgs::Pose2D &goal, const nav_2d_msgs::Path2D &global_plan) + { + if (!getPosition(pose, global_plan, current_position_)) + { + return false; + } + // ROS_INFO("current_position_"); + dxy_sq_ = hypot_sq(pose.x - goal.x, pose.y - goal.y); + in_window_ = in_window_ || dxy_sq_ <= sq_window_; + current_speed_ = vel.x; + running_ = running_ || (in_window_ && vel.x > 0.0 && vel.x <= stopped_velocity_); + return true; + } + + double MetratronikTechnikCritic::scoreTrajectory(const dwb_msgs::Trajectory2D &traj) + { + if (!in_window_) + { + return 0.0; + } + else if (!running_) + { + return fabs(slowing_factor_ + scoreMetratronikTechnik(traj)); + } + // If we're sufficiently close to the goal, any transforming velocity is invalid + if (fabs(traj.velocity.x) > stopped_velocity_ || fabs(traj.velocity.y) > stopped_velocity_) + { + return fabs(traj.velocity.x + slowing_factor_ + scoreMetratronikTechnik(traj)); + } + return 0.01 * scoreMetratronikTechnik(traj); + } + + double MetratronikTechnikCritic::scoreMetratronikTechnik(const dwb_msgs::Trajectory2D &traj) + { + if (traj.poses.empty()) + { + throw nav_core2::IllegalTrajectoryException(name_, "Empty trajectory."); + } + double k_reduce_v = cos(((M_PI / 2) / Lm_) * current_position_); + double result_linear_x = traj.velocity.x * k_reduce_v; + double k_reduce_w_v = cos(((M_PI / 2) / stopped_velocity_) * result_linear_x); + double result_angular_z = atan(current_position_ / Lm_) * fabs(k_reduce_w_v); + + double running_time = traj.time_offsets.back().toSec(); + double score_linear_x = fabs(traj.velocity.x * running_time - sqrt(dxy_sq_)); + // ROS_INFO("%f %f %f %f", running_time,fabs(traj.velocity.x*running_time), sqrt(dxy_sq_), score_linear_x); + double score_angular_z = fabs(traj.velocity.theta - result_angular_z); + // ROS_INFO("%f %f %f %f %f %f %f", result_linear_x, traj.velocity.x, result_angular_z, traj.velocity.theta, score_linear_x, score_angular_z, score_angular_z + score_linear_x); + return score_angular_z + score_linear_x; + } + + bool MetratronikTechnikCritic::getPosition(const geometry_msgs::Pose2D &robot_pose, const nav_2d_msgs::Path2D &global_plan, double &position) + { + const nav_core2::Costmap &costmap = *costmap_; + const nav_grid::NavGridInfo &info = costmap.getInfo(); + + if (global_plan.poses.empty()) + { + ROS_ERROR_NAMED("MetratronikTechnikCritic", "The global plan was empty."); + return false; + } + // Chuyển đổi dữ liệu kế hoạch đường đi 'nav_2d_msgs::Path2D' sang 'std::vector' + std::vector plan = nav_2d_utils::adjustPlanResolution(global_plan, info.resolution).poses; + // unsigned int start_index = 0; + // double distance_to_start = std::numeric_limits::infinity(); + // bool started_path = false; + // for (unsigned int i = 0; i < plan.size(); i++) + // { + // double g_x = plan[i].x; + // double g_y = plan[i].y; + // unsigned int map_x, map_y; + // if (worldToGridBounded(info, g_x, g_y, map_x, map_y) // chuyển tọa độ từ đơn vị mét sang pixel + // && costmap(map_x, map_y) != nav_core2::Costmap::NO_INFORMATION) + // { // chi phí phải khác -1 + // // Still on the costmap. Continue. + // double distance = nav_2d_utils::poseDistance(plan[i], robot_pose); // Tính khoảng cách từ vị trí của robot đến pose đang xét + // if (distance_to_start > distance) + // { + // start_index = i; + // distance_to_start = distance; + // started_path = true; + // } + // else + // { + // // Plan is going away from the robot again. It's possible that it comes back and we would find a pose that's + // // even closer to the robot, but then we would skip over parts of the plan. + // break; + // } + // } + // else if (started_path) + // { + // // Off the costmap after being on the costmap. + // break; + // } + // // else, we have not yet found a point on the costmap, so we just continue + // } + // // Nếu khồng tìm được điểm gần với robot nhất thì trả về false + // if (!started_path) + // { + // ROS_ERROR_NAMED("MetratronikTechnikCritic", "None of the points of the global plan were in the local costmap."); + // return false; + // } + + // // current_index_ = start_index; + // // find the "last valid pose", i.e. the last pose on the plan after the start pose that is still on the local map + // // Tìm điểm pose cuôi cùng sau điểm pose bắt đầu và có tồn tại trong local map + // unsigned int last_valid_index = start_index; + // for (unsigned int i = start_index + 1; i < plan.size(); i++) + // { + // double g_x = plan[i].x; + // double g_y = plan[i].y; + // unsigned int map_x, map_y; + // if (worldToGridBounded(info, g_x, g_y, map_x, map_y) && costmap(map_x, map_y) != nav_core2::Costmap::NO_INFORMATION) + // { + // // Still on the costmap. Continue. + // last_valid_index = i; + // } + // else + // { + // // Off the costmap after being on the costmap. + // break; + // } + // } + + // // find the "goal pose" by walking along the plan as long as each step leads far enough away from the starting point, + // // i.e. is within angle_threshold_ of the starting direction. + // // Tìm điểm mục tiêu chạy từ điểm start pose đến last valid pose dọc thep plan + // unsigned int goal_index = start_index; + + // while (goal_index < last_valid_index && critic_nh_.ok()) + // { + // // Tìm kiếm vị trí điểm mục tiêu phù hợp + // goal_index = getGoalIndex(robot_pose, plan, start_index, last_valid_index); + + // // check if goal already reached + // bool goal_already_reached = false; + // for (auto &reached_intermediate_goal : reached_intermediate_goals_) + // { + // double distance = nav_2d_utils::poseDistance(reached_intermediate_goal, plan[goal_index]); + // if (distance < xy_local_goal_tolerance_) + // { + // goal_already_reached = true; + // // choose a new start_index by walking along the plan until we're outside xy_local_goal_tolerance_ and try again + // // (start_index is now > goal_index) + // for (start_index = goal_index; start_index <= last_valid_index; ++start_index) + // { + // distance = nav_2d_utils::poseDistance(reached_intermediate_goal, plan[start_index]); + // if (distance >= xy_local_goal_tolerance_) + // break; + // } + + // break; + // } + // } + + // if (!goal_already_reached) + // { + // // new goal not in reached_intermediate_goals_ + // double distance = nav_2d_utils::poseDistance(plan[goal_index], robot_pose); + // if (distance < xy_local_goal_tolerance_) + // { + // // the robot has currently reached the goal + // reached_intermediate_goals_.push_back(plan[goal_index]); + // ROS_DEBUG_NAMED("MetratronikTechnikCritic", "Number of reached_intermediate goals: %zu", reached_intermediate_goals_.size()); + // } + // else + // { + // // we've found a new goal! + // break; + // } + // } + // } + // if (start_index >= goal_index) + // return false; + lineEquation leq; + getLine(plan.front(), plan.back(), leq); + position = calculateError(leq, Lm_, robot_pose, 0).error_line; + return true; + } + + unsigned int MetratronikTechnikCritic::getGoalIndex(const geometry_msgs::Pose2D &robot_pose, + const std::vector &plan, + unsigned int start_index, + unsigned int last_valid_index) const + { + if (start_index >= last_valid_index) + return last_valid_index; + + unsigned int goal_index = start_index; + + for (unsigned int i = start_index + 1; i <= last_valid_index; ++i) + { + const double current_direction_x = plan[i].x - plan[i - 1].x; + const double current_direction_y = plan[i].y - plan[i - 1].y; + if (fabs(current_direction_x) > 1e-9 || fabs(current_direction_y) > 1e-9) + { + double current_angle = atan2(current_direction_y, current_direction_x); + if (fabs(remainder(robot_pose.theta - current_angle, 2 * M_PI)) > angle_threshold_) + break; + + goal_index = i; + } + } + if (nav_2d_utils::poseDistance(plan[goal_index], plan[last_valid_index]) <= xy_local_goal_tolerance_) + goal_index = last_valid_index; + + return goal_index; + } + + bool MetratronikTechnikCritic::getLine(geometry_msgs::Pose2D start_point, geometry_msgs::Pose2D end_point, lineEquation &leq) + { + /** + * Phương trình đường thẳng có dạng: + * (y - yi)/(yj - yi) = (x - xi)/(xj - xi) + */ + leq.Gi = start_point; + leq.Gj = end_point; + leq.a = (leq.Gj.y - leq.Gi.y); + leq.b = (leq.Gi.x - leq.Gj.x); + leq.c = (leq.Gj.x * leq.Gi.y - leq.Gi.x * leq.Gj.y); + return leq.a != 0 || leq.b != 0; + } + + presentPosition MetratronikTechnikCritic::calculateError(const lineEquation &leq, const float Lm, const geometry_msgs::Pose2D robot_pose, float pha) + { + presentPosition present_pose; + float Yaw_rad = robot_pose.theta; + float Yaw = ((Yaw_rad * 180) / M_PI); + Yaw_rad = (Yaw - pha) * M_PI / 180; + /* + * Tính tọa độ điểm R + */ + float G_xr = float(robot_pose.x); + float G_yr = float(robot_pose.y); + /* + * Tính tọa độ điểm H + */ + present_pose.Gxh = G_xr + Lm * cos(Yaw_rad); + present_pose.Gyh = G_yr + Lm * sin(Yaw_rad); + /** + * Phương trình đường thẳng (rh) có dạng: + * (y - yr)/(yh - yr) = (x - xr)/(xh - xr) + */ + float A_rh = (present_pose.Gyh - G_yr); + float B_rh = (G_xr - present_pose.Gxh); + float C_rh = (present_pose.Gxh * G_yr - G_xr * present_pose.Gyh); + /* + * Phương trình đường thẳng vuông góc (y - yr)/(yh - yr) = (x - xr)/(xh - xr) + * và đi qua Gh có dạng: + * -B_rh*(x - Gxh) + Arh*(y - Gyh) = 0 + */ + float A_he = -B_rh; + float B_he = A_rh; + float C_he = (-B_rh) * (-present_pose.Gxh) + A_rh * (-present_pose.Gyh); + /* + * Đường thẳng (he) giao với đường thẳng (ij) tại e + * vậy G_xe và G_ye là nghiệm của hệ phương trình 2 ẩn của 2 đường thẳng trên: + */ + float D = A_he * leq.b - leq.a * B_he; + float Dx = (-C_he) * leq.b - (-leq.c) * B_he; + float Dy = A_he * (-leq.c) - leq.a * (-C_he); + /* + * Tính tọa độ điểm E + */ + if (D == 0) + { + if (Dx + Dy == 0) + { + /* + * Vì hai đường thẳng trùng nhau nên sai số giữa robot và đường đi là bằng 0 + */ + present_pose.error_line = 0; + } + else + throw NoSolution(); + } + else + { + float G_xe = Dx / D; + float G_ye = Dy / D; + /* + * Tính khoảng cách từ điểm E đến đường thẳng (RH) + */ + present_pose.error_line = -(A_rh * G_xe + B_rh * G_ye + C_rh) / (sqrt(pow(A_rh, 2) + pow(B_rh, 2))); + } + present_pose.distanceToEnd = sqrt(pow((leq.Gj.x - G_xr), 2) + pow((leq.Gj.y - G_yr), 2)); + present_pose.distanceToStart = sqrt(pow((leq.Gi.x - G_xr), 2) + pow((leq.Gi.y - G_yr), 2)); + + return present_pose; + } + +} /* namespace dwb_critics */ \ No newline at end of file diff --git a/navigations/dwb_critics/src/obstacle_footprint.cpp b/navigations/dwb_critics/src/obstacle_footprint.cpp new file mode 100755 index 0000000..0c652aa --- /dev/null +++ b/navigations/dwb_critics/src/obstacle_footprint.cpp @@ -0,0 +1,99 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +PLUGINLIB_EXPORT_CLASS(dwb_critics::ObstacleFootprintCritic, dwb_local_planner::TrajectoryCritic) + +namespace dwb_critics +{ + +void ObstacleFootprintCritic::onInit() +{ + BaseObstacleCritic::onInit(); + footprint_spec_ = nav_2d_utils::footprintFromParams(critic_nh_); +} + +bool ObstacleFootprintCritic::prepare(const geometry_msgs::Pose2D& pose, const nav_2d_msgs::Twist2D& vel, + const geometry_msgs::Pose2D& goal, const nav_2d_msgs::Path2D& global_plan) +{ + if (footprint_spec_.points.size() == 0) + { + ROS_ERROR_NAMED("ObstacleFootprintCritic", "Footprint spec is empty, maybe missing call to setFootprint?"); + return false; + } + return true; +} + +double ObstacleFootprintCritic::scorePose(const nav_core2::Costmap& costmap, const geometry_msgs::Pose2D& pose) +{ + unsigned int cell_x, cell_y; + if (!worldToGridBounded(costmap.getInfo(), pose.x, pose.y, cell_x, cell_y)) + throw nav_core2::IllegalTrajectoryException(name_, "Trajectory Goes Off Grid."); + return scorePose(costmap, pose, nav_2d_utils::movePolygonToPose(footprint_spec_, pose)); +} + +double ObstacleFootprintCritic::scorePose(const nav_core2::Costmap& costmap, const geometry_msgs::Pose2D& pose, + const nav_2d_msgs::Polygon2D& footprint) +{ + unsigned char footprint_cost = 0; + nav_grid::NavGridInfo info = costmap.getInfo(); + for (nav_grid::Index index : nav_grid_iterators::PolygonOutline(&info, footprint)) + { + unsigned char cost = costmap(index.x, index.y); + // if the cell is in an obstacle the path is invalid or unknown + if (cost == costmap.LETHAL_OBSTACLE) + { + throw nav_core2::IllegalTrajectoryException(name_, "Trajectory Hits Obstacle."); + } + else if (cost == costmap.NO_INFORMATION) + { + throw nav_core2::IllegalTrajectoryException(name_, "Trajectory Hits Unknown Region."); + } + footprint_cost = std::max(cost, footprint_cost); + } + + // if all line costs are legal... then we can return that the footprint is legal + return footprint_cost; +} + +} // namespace dwb_critics diff --git a/navigations/dwb_critics/src/oscillation.cpp b/navigations/dwb_critics/src/oscillation.cpp new file mode 100755 index 0000000..5e075a6 --- /dev/null +++ b/navigations/dwb_critics/src/oscillation.cpp @@ -0,0 +1,223 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include +#include +#include +#include +#include +#include + +PLUGINLIB_EXPORT_CLASS(dwb_critics::OscillationCritic, dwb_local_planner::TrajectoryCritic) + +namespace dwb_critics +{ + +OscillationCritic::CommandTrend::CommandTrend() +{ + reset(); +} + +void OscillationCritic::CommandTrend::reset() +{ + sign_ = Sign::ZERO; + positive_only_ = false; + negative_only_ = false; +} + +bool OscillationCritic::CommandTrend::update(double velocity) +{ + bool flag_set = false; + if (velocity < 0.0) + { + if (sign_ == Sign::POSITIVE) + { + negative_only_ = true; + flag_set = true; + } + sign_ = Sign::NEGATIVE; + } + else if (velocity > 0.0) + { + if (sign_ == Sign::NEGATIVE) + { + positive_only_ = true; + flag_set = true; + } + sign_ = Sign::POSITIVE; + } + return flag_set; +} + +bool OscillationCritic::CommandTrend::isOscillating(double velocity) +{ + return (positive_only_ && velocity < 0.0) || (negative_only_ && velocity > 0.0); +} + +bool OscillationCritic::CommandTrend::hasSignFlipped() +{ + return positive_only_ || negative_only_; +} + +void OscillationCritic::onInit() +{ + oscillation_reset_dist_ = nav_2d_utils::searchAndGetParam(critic_nh_, "oscillation_reset_dist", 0.05); + oscillation_reset_dist_sq_ = oscillation_reset_dist_ * oscillation_reset_dist_; + oscillation_reset_angle_ = nav_2d_utils::searchAndGetParam(critic_nh_, "oscillation_reset_angle", 0.2); + oscillation_reset_time_ = nav_2d_utils::searchAndGetParam(critic_nh_, "oscillation_reset_time", -1.0); + + /** + * Historical Parameter Loading + * If x_only_threshold is set, use that. + * If min_speed_xy is set in the namespace (as it is often used for trajectory generation), use that. + * If min_trans_vel is set in the namespace, as it used to be used for trajectory generation, complain then use that. + * Otherwise, set x_only_threshold_ to 0.05 + */ + std::string resolved_name; + if (critic_nh_.hasParam("x_only_threshold")) + { + critic_nh_.getParam("x_only_threshold", x_only_threshold_); + } + else if (critic_nh_.searchParam("min_speed_xy", resolved_name)) + { + critic_nh_.getParam(resolved_name, x_only_threshold_); + } + else if (critic_nh_.searchParam("min_trans_vel", resolved_name)) + { + ROS_WARN_NAMED("OscillationCritic", "Parameter min_trans_vel is deprecated. " + "Please use the name min_speed_xy or x_only_threshold instead."); + critic_nh_.getParam(resolved_name, x_only_threshold_); + } + else + { + x_only_threshold_ = 0.05; + } + + reset(); +} + +bool OscillationCritic::prepare(const geometry_msgs::Pose2D& pose, + const nav_2d_msgs::Twist2D& vel, + const geometry_msgs::Pose2D& goal, + const nav_2d_msgs::Path2D& global_plan) +{ + pose_ = pose; + return true; +} + +void OscillationCritic::debrief(const nav_2d_msgs::Twist2D& cmd_vel) +{ + if (setOscillationFlags(cmd_vel)) + { + prev_stationary_pose_ = pose_; + prev_reset_time_ = ros::Time::now(); + } + + // if we've got restrictions... check if we can reset any oscillation flags + if (x_trend_.hasSignFlipped() || y_trend_.hasSignFlipped() || theta_trend_.hasSignFlipped()) + { + // Reset flags if enough time or distance has passed + if (resetAvailable()) + { + reset(); + } + } +} + +bool OscillationCritic::resetAvailable() +{ + if (oscillation_reset_dist_ >= 0.0) + { + double x_diff = pose_.x - prev_stationary_pose_.x; + double y_diff = pose_.y - prev_stationary_pose_.y; + double sq_dist = x_diff * x_diff + y_diff * y_diff; + if (sq_dist > oscillation_reset_dist_sq_) + { + return true; + } + } + if (oscillation_reset_angle_ >= 0.0) + { + double th_diff = pose_.theta - prev_stationary_pose_.theta; + if (fabs(th_diff) > oscillation_reset_angle_) + { + return true; + } + } + if (oscillation_reset_time_ >= 0.0) + { + double t_diff = (ros::Time::now() - prev_reset_time_).toSec(); + if (t_diff > oscillation_reset_time_) + { + return true; + } + } + return false; +} + +void OscillationCritic::reset() +{ + x_trend_.reset(); + y_trend_.reset(); + theta_trend_.reset(); +} + +bool OscillationCritic::setOscillationFlags(const nav_2d_msgs::Twist2D& cmd_vel) +{ + bool flag_set = false; + // set oscillation flags for moving forward and backward + flag_set |= x_trend_.update(cmd_vel.x); + + // we'll only set flags for strafing and rotating when we're not moving forward at all + if (x_only_threshold_ < 0.0 || fabs(cmd_vel.x) <= x_only_threshold_) + { + flag_set |= y_trend_.update(cmd_vel.y); + flag_set |= theta_trend_.update(cmd_vel.theta); + } + return flag_set; +} + +double OscillationCritic::scoreTrajectory(const dwb_msgs::Trajectory2D& traj) +{ + if (x_trend_.isOscillating(traj.velocity.x) || + y_trend_.isOscillating(traj.velocity.y) || + theta_trend_.isOscillating(traj.velocity.theta)) + { + throw nav_core2::IllegalTrajectoryException(name_, "Trajectory is oscillating."); + } + return 0.0; +} + +} // namespace dwb_critics diff --git a/navigations/dwb_critics/src/path_align.cpp b/navigations/dwb_critics/src/path_align.cpp new file mode 100755 index 0000000..e56343e --- /dev/null +++ b/navigations/dwb_critics/src/path_align.cpp @@ -0,0 +1,87 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ +#include +#include +#include +#include +#include +#include + +namespace dwb_critics +{ + +void PathAlignCritic::onInit() +{ + PathDistCritic::onInit(); + stop_on_failure_ = false; + forward_point_distance_ = nav_2d_utils::searchAndGetParam(critic_nh_, "forward_point_distance", 0.325); +} + +bool PathAlignCritic::prepare(const geometry_msgs::Pose2D& pose, const nav_2d_msgs::Twist2D& vel, + const geometry_msgs::Pose2D& goal, + const nav_2d_msgs::Path2D& global_plan) +{ + double dx = pose.x - goal.x; + double dy = pose.y - goal.y; + double sq_dist = dx * dx + dy * dy; + if (sq_dist > forward_point_distance_ * forward_point_distance_) + { + zero_scale_ = false; + } + else + { + // once we are close to goal, trying to keep the nose close to anything destabilizes behavior. + zero_scale_ = true; + return true; + } + + return PathDistCritic::prepare(pose, vel, goal, global_plan); +} + +double PathAlignCritic::getScale() const +{ + if (zero_scale_) + return 0.0; + else + return costmap_->getResolution() * 0.5 * scale_; +} + +double PathAlignCritic::scorePose(const geometry_msgs::Pose2D& pose) +{ + return PathDistCritic::scorePose(getForwardPose(pose, forward_point_distance_)); +} + +} // namespace dwb_critics + +PLUGINLIB_EXPORT_CLASS(dwb_critics::PathAlignCritic, dwb_local_planner::TrajectoryCritic) diff --git a/navigations/dwb_critics/src/path_dist.cpp b/navigations/dwb_critics/src/path_dist.cpp new file mode 100755 index 0000000..dbee172 --- /dev/null +++ b/navigations/dwb_critics/src/path_dist.cpp @@ -0,0 +1,92 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ +#include +#include +#include +#include +#include + +namespace dwb_critics +{ +bool PathDistCritic::prepare(const geometry_msgs::Pose2D& pose, const nav_2d_msgs::Twist2D& vel, + const geometry_msgs::Pose2D& goal, + const nav_2d_msgs::Path2D& global_plan) +{ + reset(); + const nav_core2::Costmap& costmap = *costmap_; + const nav_grid::NavGridInfo& info = costmap.getInfo(); + bool started_path = false; + + nav_2d_msgs::Path2D adjusted_global_plan = nav_2d_utils::adjustPlanResolution(global_plan, info.resolution); + + if (adjusted_global_plan.poses.size() != global_plan.poses.size()) + { + ROS_DEBUG_NAMED("PathDistCritic", "Adjusted global plan resolution, added %zu points", + adjusted_global_plan.poses.size() - global_plan.poses.size()); + } + + unsigned int i; + // put global path points into local map until we reach the border of the local map + for (i = 0; i < adjusted_global_plan.poses.size(); ++i) + { + double g_x = adjusted_global_plan.poses[i].x; + double g_y = adjusted_global_plan.poses[i].y; + unsigned int map_x, map_y; + if (worldToGridBounded(info, g_x, g_y, map_x, map_y) && costmap(map_x, map_y) != costmap.NO_INFORMATION) + { + cell_values_.setValue(map_x, map_y, 0.0); + queue_->enqueueCell(map_x, map_y); + started_path = true; + } + else if (started_path) + { + break; + } + } + if (!started_path) + { + ROS_ERROR_NAMED("PathDistCritic", + "None of the %d first of %zu (%zu) points of the global plan were in the local costmap and free", + i, adjusted_global_plan.poses.size(), global_plan.poses.size()); + return false; + } + + propogateManhattanDistances(); + + return true; +} + +} // namespace dwb_critics + +PLUGINLIB_EXPORT_CLASS(dwb_critics::PathDistCritic, dwb_local_planner::TrajectoryCritic) diff --git a/navigations/dwb_critics/src/prefer_forward.cpp b/navigations/dwb_critics/src/prefer_forward.cpp new file mode 100755 index 0000000..1f730b4 --- /dev/null +++ b/navigations/dwb_critics/src/prefer_forward.cpp @@ -0,0 +1,69 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include +#include + +PLUGINLIB_EXPORT_CLASS(dwb_critics::PreferForwardCritic, dwb_local_planner::TrajectoryCritic) + +namespace dwb_critics +{ + +void PreferForwardCritic::onInit() +{ + critic_nh_.param("penalty", penalty_, 1.0); + critic_nh_.param("strafe_x", strafe_x_, 0.1); + critic_nh_.param("strafe_theta", strafe_theta_, 0.2); + critic_nh_.param("theta_scale", theta_scale_, 10.0); +} + +double PreferForwardCritic::scoreTrajectory(const dwb_msgs::Trajectory2D& traj) +{ + // backward motions bad on a robot without backward sensors + if (traj.velocity.x < 0.0) + { + return penalty_; + } + // strafing motions also bad on such a robot + if (traj.velocity.x < strafe_x_ && fabs(traj.velocity.theta) < strafe_theta_) + { + return penalty_; + } + + // the more we rotate, the less we progress forward + return fabs(traj.velocity.theta) * theta_scale_; +} + +} /* namespace dwb_critics */ diff --git a/navigations/dwb_critics/src/rotate_to_goal.cpp b/navigations/dwb_critics/src/rotate_to_goal.cpp new file mode 100755 index 0000000..bbcaf9f --- /dev/null +++ b/navigations/dwb_critics/src/rotate_to_goal.cpp @@ -0,0 +1,130 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ +#include +#include +#include +#include +#include +#include +#include +#include + +const double EPSILON = 1E-5; + +PLUGINLIB_EXPORT_CLASS(dwb_critics::RotateToGoalCritic, dwb_local_planner::TrajectoryCritic) + +namespace dwb_critics +{ + +inline double hypot_sq(double dx, double dy) +{ + return dx * dx + dy * dy; +} + +void RotateToGoalCritic::onInit() +{ + xy_goal_tolerance_ = nav_2d_utils::searchAndGetParam(critic_nh_, "xy_goal_tolerance", 0.25); + xy_goal_tolerance_sq_ = xy_goal_tolerance_ * xy_goal_tolerance_; + double stopped_xy_velocity = nav_2d_utils::searchAndGetParam(critic_nh_, "trans_stopped_velocity", 0.25); + stopped_xy_velocity_sq_ = stopped_xy_velocity * stopped_xy_velocity; + critic_nh_.param("slowing_factor", slowing_factor_, 5.0); + critic_nh_.param("lookahead_time", lookahead_time_, -1.0); + reset(); +} + +void RotateToGoalCritic::reset() +{ + in_window_ = false; + rotating_ = false; +} + +bool RotateToGoalCritic::prepare(const geometry_msgs::Pose2D& pose, const nav_2d_msgs::Twist2D& vel, + const geometry_msgs::Pose2D& goal, + const nav_2d_msgs::Path2D& global_plan) +{ + double dxy_sq = hypot_sq(pose.x - goal.x, pose.y - goal.y); + in_window_ = in_window_ || dxy_sq <= xy_goal_tolerance_sq_; + current_xy_speed_sq_ = hypot_sq(vel.x, vel.y); + rotating_ = rotating_ || (in_window_ && current_xy_speed_sq_ <= stopped_xy_velocity_sq_); + goal_yaw_ = goal.theta; + return true; +} + +double RotateToGoalCritic::scoreTrajectory(const dwb_msgs::Trajectory2D& traj) +{ + // If we're not sufficiently close to the goal, we don't care what the twist is + if (!in_window_) + { + return 0.0; + } + else if (!rotating_) + { + double speed_sq = hypot_sq(traj.velocity.x, traj.velocity.y); + if (speed_sq >= current_xy_speed_sq_) + { + throw nav_core2::IllegalTrajectoryException(name_, "Not slowing down near goal."); + } + return speed_sq * slowing_factor_ + scoreRotation(traj); + } + + // If we're sufficiently close to the goal, any transforming velocity is invalid + if (fabs(traj.velocity.x) > EPSILON || fabs(traj.velocity.y) > EPSILON) + { + throw nav_core2::IllegalTrajectoryException(name_, "Nonrotation command near goal."); + } + + return scoreRotation(traj); +} + +double RotateToGoalCritic::scoreRotation(const dwb_msgs::Trajectory2D& traj) +{ + if (traj.poses.empty()) + { + throw nav_core2::IllegalTrajectoryException(name_, "Empty trajectory."); + } + + double end_yaw; + if (lookahead_time_ >= 0.0) + { + geometry_msgs::Pose2D eval_pose = dwb_local_planner::projectPose(traj, lookahead_time_); + end_yaw = eval_pose.theta; + } + else + { + end_yaw = traj.poses.back().theta; + } + return fabs(angles::shortest_angular_distance(end_yaw, goal_yaw_)); +} + +} /* namespace dwb_critics */ diff --git a/navigations/dwb_critics/src/twirling.cpp b/navigations/dwb_critics/src/twirling.cpp new file mode 100755 index 0000000..88769ed --- /dev/null +++ b/navigations/dwb_critics/src/twirling.cpp @@ -0,0 +1,55 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include + +namespace dwb_critics +{ +void TwirlingCritic::onInit() +{ + // Scale is set to 0 by default, so if it was not set otherwise, set to 0 + if (!critic_nh_.hasParam("scale")) + { + scale_ = 0.0; + } +} + +double TwirlingCritic::scoreTrajectory(const dwb_msgs::Trajectory2D& traj) +{ + return fabs(traj.velocity.theta); // add cost for making the robot spin +} +} // namespace dwb_critics + +PLUGINLIB_EXPORT_CLASS(dwb_critics::TwirlingCritic, dwb_local_planner::TrajectoryCritic) diff --git a/navigations/dwb_local_planner/.$structure.drawio.bkp b/navigations/dwb_local_planner/.$structure.drawio.bkp new file mode 100755 index 0000000..85345d2 --- /dev/null +++ b/navigations/dwb_local_planner/.$structure.drawio.bkp @@ -0,0 +1,62 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/navigations/dwb_local_planner/.$structure.drawio.dtmp b/navigations/dwb_local_planner/.$structure.drawio.dtmp new file mode 100755 index 0000000..06884b4 --- /dev/null +++ b/navigations/dwb_local_planner/.$structure.drawio.dtmp @@ -0,0 +1,152 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/navigations/dwb_local_planner/CMakeLists.txt b/navigations/dwb_local_planner/CMakeLists.txt new file mode 100755 index 0000000..d56ce91 --- /dev/null +++ b/navigations/dwb_local_planner/CMakeLists.txt @@ -0,0 +1,80 @@ +cmake_minimum_required(VERSION 3.0.2) +project(dwb_local_planner) + +set_directory_properties(PROPERTIES COMPILE_OPTIONS "-std=c++11;-Wall;-Werror") + +find_package(catkin REQUIRED COMPONENTS + dwb_msgs + geometry_msgs + nav_2d_msgs + nav_2d_utils + nav_core2 + nav_msgs + pluginlib + roscpp + sensor_msgs + tf + visualization_msgs +) + +catkin_package( + INCLUDE_DIRS include + LIBRARIES dwb_local_planner debug_dwb_local_planner trajectory_utils + CATKIN_DEPENDS + dwb_msgs geometry_msgs nav_2d_msgs nav_2d_utils nav_core2 + nav_msgs pluginlib roscpp sensor_msgs tf visualization_msgs +) + +include_directories( + include + ${catkin_INCLUDE_DIRS} +) + +add_library(dwb_local_planner src/dwb_local_planner.cpp + src/backwards_compatibility.cpp + src/publisher.cpp + src/illegal_trajectory_tracker.cpp +) +target_link_libraries(dwb_local_planner ${catkin_LIBRARIES}) +add_dependencies(dwb_local_planner ${catkin_EXPORTED_TARGETS}) + +add_library(debug_dwb_local_planner src/debug_dwb_local_planner.cpp) +target_link_libraries(debug_dwb_local_planner ${catkin_LIBRARIES} dwb_local_planner) +add_dependencies(debug_dwb_local_planner ${catkin_EXPORTED_TARGETS}) + +add_library(trajectory_utils src/trajectory_utils.cpp) +target_link_libraries(trajectory_utils ${catkin_LIBRARIES}) + +add_executable(${PROJECT_NAME}_planner_node src/planner_node.cpp) +target_link_libraries(${PROJECT_NAME}_planner_node ${catkin_LIBRARIES} debug_dwb_local_planner) +add_dependencies(${PROJECT_NAME}_planner_node ${catkin_EXPORTED_TARGETS}) +set_target_properties(${PROJECT_NAME}_planner_node PROPERTIES OUTPUT_NAME planner_node PREFIX "") + +if(CATKIN_ENABLE_TESTING) + find_package(rostest REQUIRED) + find_package(roslint REQUIRED) + roslint_cpp() + roslint_add_test() + + catkin_add_gtest(utils_test test/utils_test.cpp) + target_link_libraries(utils_test trajectory_utils) +endif() + +install(TARGETS ${PROJECT_NAME}_planner_node + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) +install(TARGETS dwb_local_planner debug_dwb_local_planner trajectory_utils + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} +) +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} +) +install(FILES plugins.xml + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) +install(DIRECTORY launch/ + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch + FILES_MATCHING PATTERN "*.launch" +) diff --git a/navigations/dwb_local_planner/README.md b/navigations/dwb_local_planner/README.md new file mode 100755 index 0000000..870ac46 --- /dev/null +++ b/navigations/dwb_local_planner/README.md @@ -0,0 +1,100 @@ +# dwb_local_planner + + > I suppose it is tempting, if the only tool you have is a hammer, to treat everything as if it were a nail. + - Abraham Maslow + + > I love/hate pluginlib. + - David Lu!! + +This local planner implementation rewrites and extends the functionality of `dwa_local_planner`, thus it is logically called `dwb_local_planner`. The goal is to make as many parts of the functionality as possible customizable, either through pluginlib or directly extending the implementing classes. + +The goal of a local planner is to take the global plan and local costmap and produce the command velocities that will presumably move the robot to the goal. Both dwa and dwb do this via sampling, i.e. generating plausible velocity commands and evaluating them on various metrics and selecting the one with the best score, until the robot reaches its goal. + +The form of the evaluation is critical. Let's say we are evaluating a given command to see if it collides with any obstacles in the costmap. The key question is where the robot will drive using the command. For this, you need to know the position and velocity of the robot, plus you will need to consider the kinematics of the robot. To this end, we do not evaluate the velocities in isolation, but instead score the trajectory which contains not only the velocity, but an array of some number of sample poses that we anticipate the robot to drive along. + +## Data Structures +The navigation stack is only capable of navigation in 2.5 dimensions (i.e. x, y and theta), thus most of the interfaces deal with `geometry_msgs/Pose2D` and `nav_2d_msgs/Twist2D` rather than the more general `Pose` and `Twist`. + +## Code Structure +### Twist Generator +The first component is the twist generator, which is responsible for determining which velocity commands are evaluating and creating trajectories from them. The interface for generating the commands is iterator-based. +``` +void startNewIteration(const nav_2d_msgs::Twist2D& current_velocity) +bool hasMoreTwists() +bool nextTwist(nav_2d_msgs::Twist2D& twist) +``` +For debugging purposes, there is also a ROS service interface for the twist generator. +``` +# dwb_msgs/srv/GenerateTwists.srv +nav_2d_msgs/Twist2D current_vel +--- +nav_2d_msgs/Twist2D[] twists +``` + +The second half is for generating the trajectory, which creates a Trajectory2D. +``` +# dwb_msgs/msg/Trajectory2D.msg +nav_2d_msgs/Twist2D velocity +duration duration +geometry_msgs/Pose2D[] poses +``` + +Code API: +``` +bool generateTrajectory(const geometry_msgs::Pose2D& start_pose, const nav_2d_msgs::Twist2D& start_vel, + const nav_2d_msgs::Twist2D& cmd_vel, + dwb_msgs::Trajectory2D& traj) +``` + +This also has a ROS service interface. +``` +# dwb_msgs/srv/GenerateTrajectory.srv +geometry_msgs/Pose2D start_pose +nav_2d_msgs/Twist2D start_vel +nav_2d_msgs/Twist2D cmd_vel +--- +dwb_msgs/Trajectory2D traj +``` + +How precisely DWB performs these tasks is relegated to a plugin. + +## Goal Checker +Are we there yet? Another plugin determines whether the robot has reached its goal. This allows for variation in combining how accurate the xy position has to be with the rotation, and whether the robot has stopped completely. + +Code API: +``` +virtual bool isGoalReached(const geometry_msgs::Pose2D& query_pose, const geometry_msgs::Pose2D& goal_pose, + const nav_2d_msgs::Twist2D& velocity) +``` + +## Trajectory Critics +[Critics](https://www.youtube.com/watch?v=X6I_dKUYyI4) like to give things scores. Once we know we're not a the goal and have a bunch of candidate trajectories, we evaluate them based on a collections of TrajectoryCritics. Here's the life-cycle. + + * `void initialize(const ros::NodeHandle& planner_nh, std::string name, nav_core2::Costmap::Ptr costmap)` - called once on startup, and then calls `onInit` + * `void onInit()` - May be overwritten to load parameters as needed. + * `void reset()` - called at the beginning of every new navigation, i.e. when we get a new global goal via `setGoalPose`. + * `bool prepare(const geometry_msgs::Pose2D& pose, const nav_2d_msgs::Twist2D& vel, const geometry_msgs::Pose2D& goal, const nav_2d_msgs::Path2D& global_plan)` - called once per iteration of the planner, prior to the evaluation of all the trajectories + * `double scoreTrajectory(const dwb_msgs::Trajectory2D& traj)` - called once per trajectory + * `void debrief(const nav_2d_msgs::Twist2D& cmd_vel)` - called after all the trajectories to notify what trajectory was chosen. + +Each critic will provide a `double` score and has an associated scale. The score used for the trajectory as a whole will be the sum of all the critic scores multiplied by their respective scales. + +There is also a ROS service interface associated with the scoring trajectories. +``` +# dwb_msgs/srv/DebugLocalPlan.srv +nav_2d_msgs/Pose2DStamped pose +nav_2d_msgs/Twist2D velocity +nav_2d_msgs/Path2D global_plan +--- +LocalPlanEvaluation results + Header header + dwb_msgs/TrajectoryScore[] twists + nav_2d_msgs/SampedTwist2D traj + dwb_msgs/CriticScore[] scores + string name + float32 raw_score + float32 scale + float32 total + uint16 best_index + uint16 worst_index +``` diff --git a/navigations/dwb_local_planner/include/dwb_local_planner/backwards_compatibility.h b/navigations/dwb_local_planner/include/dwb_local_planner/backwards_compatibility.h new file mode 100755 index 0000000..31b368f --- /dev/null +++ b/navigations/dwb_local_planner/include/dwb_local_planner/backwards_compatibility.h @@ -0,0 +1,55 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ +#ifndef DWB_LOCAL_PLANNER_BACKWARDS_COMPATIBILITY_H +#define DWB_LOCAL_PLANNER_BACKWARDS_COMPATIBILITY_H + +#include +#include + +namespace dwb_local_planner +{ + +std::string getBackwardsCompatibleDefaultGenerator(const ros::NodeHandle& nh); + +/** + * @brief Load parameters to emulate dwa_local_planner + * + * If no critic parameters are specified, this function should be called + * to load/move parameters that will emulate the behavior of dwa_local_planner + * + * @param nh NodeHandle to load parameters from + */ +void loadBackwardsCompatibleParameters(const ros::NodeHandle& nh); +} // namespace dwb_local_planner +#endif // DWB_LOCAL_PLANNER_BACKWARDS_COMPATIBILITY_H diff --git a/navigations/dwb_local_planner/include/dwb_local_planner/debug_dwb_local_planner.h b/navigations/dwb_local_planner/include/dwb_local_planner/debug_dwb_local_planner.h new file mode 100755 index 0000000..f72fda9 --- /dev/null +++ b/navigations/dwb_local_planner/include/dwb_local_planner/debug_dwb_local_planner.h @@ -0,0 +1,81 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef DWB_LOCAL_PLANNER_DEBUG_DWB_LOCAL_PLANNER_H +#define DWB_LOCAL_PLANNER_DEBUG_DWB_LOCAL_PLANNER_H + +#include +#include +#include +#include +#include +#include +#include + +namespace dwb_local_planner +{ + +/** + * @brief A version of DWBLocalPlanner with ROS services for the major components. + * + * Advertises three services: GenerateTwists, GenerateTrajectory and DebugLocalPlan + */ +class DebugDWBLocalPlanner: public DWBLocalPlanner +{ +public: + /** + * @brief Override the DWB constructor to also advertise the services + */ + void initialize(const ros::NodeHandle& parent, const std::string& name, + TFListenerPtr tf, nav_core2::Costmap::Ptr costmap) override; +protected: + bool generateTwistsService(dwb_msgs::GenerateTwists::Request &req, + dwb_msgs::GenerateTwists::Response &res); + bool generateTrajectoryService(dwb_msgs::GenerateTrajectory::Request &req, + dwb_msgs::GenerateTrajectory::Response &res); + bool scoreTrajectoryService(dwb_msgs::ScoreTrajectory::Request &req, + dwb_msgs::ScoreTrajectory::Response &res); + bool getCriticScoreService(dwb_msgs::GetCriticScore::Request &req, + dwb_msgs::GetCriticScore::Response &res); + bool debugLocalPlanService(dwb_msgs::DebugLocalPlan::Request &req, + dwb_msgs::DebugLocalPlan::Response &res); + + TrajectoryCritic::Ptr getCritic(std::string name); + + ros::ServiceServer twist_gen_service_, generate_traj_service_, score_service_, critic_service_, debug_service_; +}; + +} // namespace dwb_local_planner + +#endif // DWB_LOCAL_PLANNER_DEBUG_DWB_LOCAL_PLANNER_H diff --git a/navigations/dwb_local_planner/include/dwb_local_planner/dwb_local_planner.h b/navigations/dwb_local_planner/include/dwb_local_planner/dwb_local_planner.h new file mode 100755 index 0000000..9d71dcf --- /dev/null +++ b/navigations/dwb_local_planner/include/dwb_local_planner/dwb_local_planner.h @@ -0,0 +1,217 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef DWB_LOCAL_PLANNER_DWB_LOCAL_PLANNER_H +#define DWB_LOCAL_PLANNER_DWB_LOCAL_PLANNER_H + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +namespace dwb_local_planner +{ + +/** + * @class DWBLocalPlanner + * @brief Plugin-based flexible local_planner + */ +class DWBLocalPlanner: public nav_core2::LocalPlanner +{ +public: + /** + * @brief Constructor that brings up pluginlib loaders + */ + DWBLocalPlanner(); + + virtual ~DWBLocalPlanner() {} + + /** + * @brief nav_core2 initialization + * @param name Namespace for this planner + * @param tf TFListener pointer + * @param costmap_ros Costmap pointer + */ + void initialize(const ros::NodeHandle& parent, const std::string& name, + TFListenerPtr tf, nav_core2::Costmap::Ptr costmap) override; + + /** + * @brief nav_core2 setGoalPose - Sets the global goal pose + * @param goal_pose The Goal Pose + */ + void setGoalPose(const nav_2d_msgs::Pose2DStamped& goal_pose) override; + + /** + * @brief nav_core2 setPlan - Sets the global plan + * @param path The global plan + */ + void setPlan(const nav_2d_msgs::Path2D& path) override; + + /** + * @brief nav_core2 computeVelocityCommands - calculates the best command given the current pose and velocity + * + * It is presumed that the global plan is already set. + * + * This is mostly a wrapper for the protected computeVelocityCommands + * function which has additional debugging info. + * + * @param pose Current robot pose + * @param velocity Current robot velocity + * @return The best command for the robot to drive + */ + nav_2d_msgs::Twist2DStamped computeVelocityCommands(const nav_2d_msgs::Pose2DStamped& pose, + const nav_2d_msgs::Twist2D& velocity) override; + + /** + * @brief nav_core2 isGoalReached - Check whether the robot has reached its goal, given the current pose & velocity. + * + * The pose that it checks against is the last pose in the current global plan. + * The calculation is delegated to the goal_checker plugin. + * + * @param pose Current pose + * @param velocity Current velocity + * @return True if the robot should be considered as having reached the goal. + */ + bool isGoalReached(const nav_2d_msgs::Pose2DStamped& pose, const nav_2d_msgs::Twist2D& velocity) override; + + /** + * @brief Score a given command. Can be used for testing. + * + * Given a trajectory, calculate the score where lower scores are better. + * If the given (positive) score exceeds the best_score, calculation may be cut short, as the + * score can only go up from there. + * + * @param traj Trajectory to check + * @param best_score If positive, the threshold for early termination + * @return The full scoring of the input trajectory + */ + virtual dwb_msgs::TrajectoryScore scoreTrajectory(const dwb_msgs::Trajectory2D& traj, double best_score = -1); + + /** + * @brief Compute the best command given the current pose and velocity, with possible debug information + * + * Same as above computeVelocityCommands, but with debug results. + * If the results pointer is not null, additional information about the twists + * evaluated will be in results after the call. + * + * @param pose Current robot pose + * @param velocity Current robot velocity + * @param results Output param, if not null, will be filled in with full evaluation results + * @return Best command + */ + virtual nav_2d_msgs::Twist2DStamped computeVelocityCommands(const nav_2d_msgs::Pose2DStamped& pose, + const nav_2d_msgs::Twist2D& velocity, + std::shared_ptr& results); + + +protected: + /** + * @brief Helper method for preparing for the core scoring algorithm + * + * Runs the prepare method on all the critics with freshly transformed data + */ + virtual void prepare(const nav_2d_msgs::Pose2DStamped& pose, const nav_2d_msgs::Twist2D& velocity); + + /** + * @brief Iterate through all the twists and find the best one + */ + virtual dwb_msgs::TrajectoryScore coreScoringAlgorithm(const geometry_msgs::Pose2D& pose, + const nav_2d_msgs::Twist2D velocity, + std::shared_ptr& results); + + /** + * @brief Transforms global plan into same frame as pose, clips far away poses and possibly prunes passed poses + * + * Three key operations + * 1) Transforms global plan into frame of the given pose + * 2) Only returns poses that are near the robot, i.e. whether they are likely on the local costmap + * 3) If prune_plan_ is true, it will remove all points that we've already passed from both the transformed plan + * and the saved global_plan_. Technically, it iterates to a pose on the path that is within prune_distance_ + * of the robot and erases all poses before that. + */ + virtual nav_2d_msgs::Path2D transformGlobalPlan(const nav_2d_msgs::Pose2DStamped& pose); + + /** + * @brief Helper method to transform a given pose to the local costmap frame. + */ + geometry_msgs::Pose2D transformPoseToLocal(const nav_2d_msgs::Pose2DStamped& pose); + + nav_2d_msgs::Path2D global_plan_; ///< Saved Global Plan + nav_2d_msgs::Pose2DStamped goal_pose_; ///< Saved Goal Pose + bool prune_plan_; + double prune_distance_; + bool debug_trajectory_details_; + bool short_circuit_trajectory_evaluation_; + + // Plugin handling + pluginlib::ClassLoader traj_gen_loader_; + TrajectoryGenerator::Ptr traj_generator_; + pluginlib::ClassLoader goal_checker_loader_; + GoalChecker::Ptr goal_checker_; + pluginlib::ClassLoader critic_loader_; + std::vector critics_; + + /** + * @brief try to resolve a possibly shortened critic name with the default namespaces and the suffix "Critic" + * + * @param base_name The name of the critic as read in from the parameter server + * @return Our attempted resolution of the name, with namespace prepended and/or the suffix Critic appended + */ + std::string resolveCriticClassName(std::string base_name); + + /** + * @brief Load the critic parameters from the namespace + * @param name The namespace of this planner. + */ + virtual void loadCritics(const std::string name); + + std::vector default_critic_namespaces_; + + nav_core2::Costmap::Ptr costmap_; + bool update_costmap_before_planning_; + TFListenerPtr tf_; + DWBPublisher pub_; + + ros::NodeHandle planner_nh_; + ros::Publisher traj_pub_; +}; + +} // namespace dwb_local_planner + +#endif // DWB_LOCAL_PLANNER_DWB_LOCAL_PLANNER_H diff --git a/navigations/dwb_local_planner/include/dwb_local_planner/goal_checker.h b/navigations/dwb_local_planner/include/dwb_local_planner/goal_checker.h new file mode 100755 index 0000000..a1fe187 --- /dev/null +++ b/navigations/dwb_local_planner/include/dwb_local_planner/goal_checker.h @@ -0,0 +1,86 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef DWB_LOCAL_PLANNER_GOAL_CHECKER_H +#define DWB_LOCAL_PLANNER_GOAL_CHECKER_H + +#include +#include +#include +#include + +namespace dwb_local_planner +{ + +/** + * @class GoalChecker + * @brief Function-object for checking whether a goal has been reached + * + * This class defines the plugin interface for determining whether you have reached + * the goal state. This primarily consists of checking the relative positions of two poses + * (which are presumed to be in the same frame). It can also check the velocity, as some + * applications require that robot be stopped to be considered as having reached the goal. + */ +class GoalChecker +{ +public: + using Ptr = std::shared_ptr; + + virtual ~GoalChecker() {} + + /** + * @brief Initialize any parameters from the NodeHandle + * @param nh NodeHandle for grabbing parameters + */ + virtual void initialize(const ros::NodeHandle& nh) = 0; + + /** + * @brief Reset the state of the goal checker (if any) + */ + virtual void reset() {} + + /** + * @brief Check whether the goal should be considered reached + * @param query_pose The pose to check + * @param goal_pose The pose to check against + * @param velocity The robot's current velocity + * @return True if goal is reached + */ + virtual bool isGoalReached(const geometry_msgs::Pose2D& query_pose, const geometry_msgs::Pose2D& goal_pose, + const nav_2d_msgs::Twist2D& velocity) = 0; +}; + +} // namespace dwb_local_planner + +#endif // DWB_LOCAL_PLANNER_GOAL_CHECKER_H diff --git a/navigations/dwb_local_planner/include/dwb_local_planner/illegal_trajectory_tracker.h b/navigations/dwb_local_planner/include/dwb_local_planner/illegal_trajectory_tracker.h new file mode 100755 index 0000000..f5e9698 --- /dev/null +++ b/navigations/dwb_local_planner/include/dwb_local_planner/illegal_trajectory_tracker.h @@ -0,0 +1,75 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef DWB_LOCAL_PLANNER_ILLEGAL_TRAJECTORY_TRACKER_H +#define DWB_LOCAL_PLANNER_ILLEGAL_TRAJECTORY_TRACKER_H + +#include +#include +#include +#include + +namespace dwb_local_planner +{ +class IllegalTrajectoryTracker +{ +public: + IllegalTrajectoryTracker() : legal_count_(0), illegal_count_(0) {} + + void addIllegalTrajectory(const nav_core2::IllegalTrajectoryException& e); + void addLegalTrajectory(); + + std::map< std::pair, double> getPercentages() const; + + std::string getMessage() const; +protected: + std::map< std::pair, unsigned int> counts_; + unsigned int legal_count_, illegal_count_; +}; + +/** + * @class NoLegalTrajectoriesException + * @brief Thrown when all the trajectories explored are illegal + */ +class NoLegalTrajectoriesException: public nav_core2::NoLegalTrajectoriesException +{ +public: + explicit NoLegalTrajectoriesException(const IllegalTrajectoryTracker& tracker) + : nav_core2::NoLegalTrajectoriesException(tracker.getMessage()), tracker_(tracker) {} + IllegalTrajectoryTracker tracker_; +}; + +} // namespace dwb_local_planner + +#endif // DWB_LOCAL_PLANNER_ILLEGAL_TRAJECTORY_TRACKER_H diff --git a/navigations/dwb_local_planner/include/dwb_local_planner/publisher.h b/navigations/dwb_local_planner/include/dwb_local_planner/publisher.h new file mode 100755 index 0000000..08a595f --- /dev/null +++ b/navigations/dwb_local_planner/include/dwb_local_planner/publisher.h @@ -0,0 +1,107 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef DWB_LOCAL_PLANNER_PUBLISHER_H +#define DWB_LOCAL_PLANNER_PUBLISHER_H + +#include +#include +#include +#include +#include +#include + +namespace dwb_local_planner +{ + +/** + * @class DWBPublisher + * @brief Consolidation of all the publishing logic for the DWB Local Planner. + * + * Right now, it can publish + * 1) The Global Plan (as passed in using setPath) + * 2) The Local Plan (after it is calculated) + * 3) The Transformed Global Plan (since it may be different than the global) + * 4) The Full LocalPlanEvaluation + * 5) Markers representing the different trajectories evaluated + * 6) The CostGrid (in the form of a complex PointCloud2) + */ +class DWBPublisher +{ +public: + /** + * @brief Load the parameters and advertise topics as needed + * @param nh NodeHandle to load parameters from + */ + void initialize(ros::NodeHandle& nh); + + /** + * @brief Does the publisher require that the LocalPlanEvaluation be saved + * @return True if the Evaluation is needed to publish either directly or as trajectories + */ + bool shouldRecordEvaluation() { return publish_evaluation_ || publish_trajectories_; } + + /** + * @brief If the pointer is not null, publish the evaluation and trajectories as needed + */ + void publishEvaluation(std::shared_ptr results); + void publishLocalPlan(const std_msgs::Header& header, const dwb_msgs::Trajectory2D& traj); + void publishCostGrid(const nav_core2::Costmap::Ptr costmap, const std::vector critics); + void publishGlobalPlan(const nav_2d_msgs::Path2D plan); + void publishTransformedPlan(const nav_2d_msgs::Path2D plan); + void publishLocalPlan(const nav_2d_msgs::Path2D plan); + void publishInputParams(const nav_grid::NavGridInfo& info, const geometry_msgs::Pose2D& start_pose, + const nav_2d_msgs::Twist2D& velocity, const geometry_msgs::Pose2D& goal_pose); + +protected: + void publishTrajectories(const dwb_msgs::LocalPlanEvaluation& results); + + // Helper function for publishing other plans + void publishGenericPlan(const nav_2d_msgs::Path2D plan, const ros::Publisher pub, bool flag); + + // Flags for turning on/off publishing specific components + bool publish_evaluation_, publish_global_plan_, publish_transformed_, publish_local_plan_, publish_trajectories_; + bool publish_cost_grid_pc_, publish_input_params_; + + // Marker Lifetime + ros::Duration marker_lifetime_; + + // Publisher Objects + ros::Publisher eval_pub_, global_pub_, transformed_pub_, local_pub_, marker_pub_, cost_grid_pc_pub_, + info_pub_, pose_pub_, goal_pub_, velocity_pub_; +}; + +} // namespace dwb_local_planner + +#endif // DWB_LOCAL_PLANNER_PUBLISHER_H diff --git a/navigations/dwb_local_planner/include/dwb_local_planner/trajectory_critic.h b/navigations/dwb_local_planner/include/dwb_local_planner/trajectory_critic.h new file mode 100755 index 0000000..c37d8ea --- /dev/null +++ b/navigations/dwb_local_planner/include/dwb_local_planner/trajectory_critic.h @@ -0,0 +1,177 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef DWB_LOCAL_PLANNER_TRAJECTORY_CRITIC_H +#define DWB_LOCAL_PLANNER_TRAJECTORY_CRITIC_H + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +namespace dwb_local_planner +{ +/** + * @class TrajectoryCritic + * @brief Evaluates a Trajectory2D to produce a score + * + * This class defines the plugin interface for the TrajectoryCritic which + * gives scores to trajectories, where lower numbers are better, but negative + * scores are considered invalid. + * + * The general lifecycle is + * 1) initialize is called once at the beginning which in turn calls onInit. + * Derived classes may override onInit to load parameters as needed. + * 2) prepare is called once before each set of trajectories. + * It is presumed that there are multiple trajectories that we want to evaluate, + * and there may be some shared work that can be done beforehand to optimize + * the scoring of each individual trajectory. + * 3) scoreTrajectory is called once per trajectory and returns the score. + * 4) debrief is called after each set of trajectories with the chosen trajectory. + * This can be used for stateful critics that monitor the trajectory through time. + * + * Optionally, there is also a debugging mechanism for certain types of critics in the + * addCriticVisualization method. If the score for a trajectory depends on its relationship to + * the costmap, addCriticVisualization can provide that information to the dwb_local_planner + * which will publish the grid scores as a PointCloud2. + */ +class TrajectoryCritic +{ +public: + using Ptr = std::shared_ptr; + + virtual ~TrajectoryCritic() {} + + /** + * @brief Initialize the critic with appropriate pointers and parameters + * + * The name and costmap are stored as member variables. + * A NodeHandle for the critic is created with the namespace of the planner NodeHandle + * + * @param planner_nh Planner Nodehandle + * @param name The name of this critic + * @param costmap_ros Pointer to the costmap + */ + void initialize(const ros::NodeHandle& planner_nh, std::string name, nav_core2::Costmap::Ptr costmap) + { + name_ = name; + costmap_ = costmap; + planner_nh_ = planner_nh; + critic_nh_ = ros::NodeHandle(planner_nh_, name_); + critic_nh_.param("scale", scale_, 1.0); + onInit(); + } + + virtual void onInit() {} + + /** + * @brief Reset the state of the critic + * + * Reset is called when the planner receives a new global goal. + * This can be used to discard information specific to one plan. + */ + virtual void reset() {} + + /** + * @brief Prior to evaluating any trajectories, look at contextual information constant across all trajectories + * + * Subclasses may overwrite. Return false in case there is any error. + * + * @param pose Current pose (costmap frame) + * @param vel Current velocity + * @param goal The final goal (costmap frame) + * @param global_plan Transformed global plan in costmap frame, possibly cropped to nearby points + */ + virtual bool prepare(const geometry_msgs::Pose2D& pose, const nav_2d_msgs::Twist2D& vel, + const geometry_msgs::Pose2D& goal, + const nav_2d_msgs::Path2D& global_plan) + { + return true; + } + + /** + * @brief Return a raw score for the given trajectory. + * + * scores < 0 are considered invalid/errors, such as collisions + * This is the raw score in that the scale should not be applied to it. + */ + virtual double scoreTrajectory(const dwb_msgs::Trajectory2D& traj) = 0; + + /** + * @brief debrief informs the critic what the chosen cmd_vel was (if it cares) + */ + virtual void debrief(const nav_2d_msgs::Twist2D& cmd_vel) {} + + /** + * @brief Add information to the given pointcloud for debugging costmap-grid based scores + * + * addCriticVisualization is an optional debugging mechanism for providing rich information + * about the cost for certain trajectories. Some critics will have scoring mechanisms + * wherein there will be some score for each cell in the costmap. This could be as + * straightforward as the cost in the costmap, or it could be the number of cells away + * from the goal pose. + * + * Prior to calling this, dwb_local_planner will load the PointCloud's header and the points + * in row-major order. The critic may then add a ChannelFloat to the channels member of the PC + * with the same number of values as the points array. This information may then be converted + * and published as a PointCloud2. + * + * @param pc PointCloud to add channels to + */ + virtual void addCriticVisualization(sensor_msgs::PointCloud& pc) {} + + std::string getName() + { + return name_; + } + + virtual double getScale() const { return scale_; } + void setScale(const double scale) { scale_ = scale; } +protected: + std::string name_; + nav_core2::Costmap::Ptr costmap_; + double scale_; + ros::NodeHandle critic_nh_, planner_nh_; +}; + +} // namespace dwb_local_planner + +#endif // DWB_LOCAL_PLANNER_TRAJECTORY_CRITIC_H diff --git a/navigations/dwb_local_planner/include/dwb_local_planner/trajectory_generator.h b/navigations/dwb_local_planner/include/dwb_local_planner/trajectory_generator.h new file mode 100755 index 0000000..061466c --- /dev/null +++ b/navigations/dwb_local_planner/include/dwb_local_planner/trajectory_generator.h @@ -0,0 +1,130 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef DWB_LOCAL_PLANNER_TRAJECTORY_GENERATOR_H +#define DWB_LOCAL_PLANNER_TRAJECTORY_GENERATOR_H + +#include +#include +#include +#include +#include + +namespace dwb_local_planner +{ + +/** + * @class TrajectoryGenerator + * @brief Interface for iterating through possible velocities and creating trajectories + * + * This class defines the plugin interface for two separate but related components. + * + * First, this class provides an iterator interface for exploring all of the velocities + * to search, given the current velocity. + * + * Second, the class gives an independent interface for creating a trajectory from a twist, + * i.e. projecting it out in time and space. + * + * Both components rely heavily on the robot's kinematic model, and can share many parameters, + * which is why they are grouped into a singular class. + */ +class TrajectoryGenerator +{ +public: + using Ptr = std::shared_ptr; + + virtual ~TrajectoryGenerator() {} + + /** + * @brief Initialize parameters as needed + * @param nh NodeHandle to read parameters from + */ + virtual void initialize(ros::NodeHandle& nh) = 0; + + /** + * @brief Reset the state (if any) when the planner gets a new goal + */ + virtual void reset() {} + + /** + * @brief Start a new iteration based on the current velocity + * @param current_velocity + */ + virtual void startNewIteration(const nav_2d_msgs::Twist2D& current_velocity) = 0; + + /** + * @brief Test to see whether there are more twists to test + * @return True if more twists, false otherwise + */ + virtual bool hasMoreTwists() = 0; + + /** + * @brief Return the next twist and advance the iteration + * @return The Twist! + */ + virtual nav_2d_msgs::Twist2D nextTwist() = 0; + + /** + * @brief Get all the twists for an iteration. + * + * Note: Resets the iterator if one is in process + * + * @param current_velocity + * @return all the twists + */ + virtual std::vector getTwists(const nav_2d_msgs::Twist2D& current_velocity) + { + std::vector twists; + startNewIteration(current_velocity); + while (hasMoreTwists()) + { + twists.push_back(nextTwist()); + } + return twists; + } + + /** + * @brief Given a cmd_vel in the robot's frame and initial conditions, generate a Trajectory2D + * @param start_pose Current robot location + * @param start_vel Current robot velocity + * @param cmd_vel The desired command velocity + */ + virtual dwb_msgs::Trajectory2D generateTrajectory(const geometry_msgs::Pose2D& start_pose, + const nav_2d_msgs::Twist2D& start_vel, + const nav_2d_msgs::Twist2D& cmd_vel) = 0; +}; + +} // namespace dwb_local_planner + +#endif // DWB_LOCAL_PLANNER_TRAJECTORY_GENERATOR_H diff --git a/navigations/dwb_local_planner/include/dwb_local_planner/trajectory_utils.h b/navigations/dwb_local_planner/include/dwb_local_planner/trajectory_utils.h new file mode 100755 index 0000000..f9577c1 --- /dev/null +++ b/navigations/dwb_local_planner/include/dwb_local_planner/trajectory_utils.h @@ -0,0 +1,65 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef DWB_LOCAL_PLANNER_TRAJECTORY_UTILS_H +#define DWB_LOCAL_PLANNER_TRAJECTORY_UTILS_H + +#include + +namespace dwb_local_planner +{ + +/** + * @brief Helper function to find a pose in the trajectory with a particular time time_offset + * @param trajectory The trajectory to search + * @param time_offset The desired time_offset + * @return reference to the pose that is closest to the particular time offset + * + * Linearly searches through the poses. Once the poses time_offset is greater than the desired time_offset, + * the search ends, since the poses have increasing time_offsets. + */ +const geometry_msgs::Pose2D& getClosestPose(const dwb_msgs::Trajectory2D& trajectory, const double time_offset); + +/** + * @brief Helper function to create a pose with an exact time_offset by linearly interpolating between existing poses + * @param trajectory The trajectory with pose and time offset information + * @param time_offset The desired time_offset + * @return New Pose2D with interpolated values + * @note If the given time offset is outside the bounds of the trajectory, the return pose will be either the first or last pose. + */ +geometry_msgs::Pose2D projectPose(const dwb_msgs::Trajectory2D& trajectory, const double time_offset); + +} // namespace dwb_local_planner + +#endif // DWB_LOCAL_PLANNER_TRAJECTORY_UTILS_H diff --git a/navigations/dwb_local_planner/launch/plan_node.launch b/navigations/dwb_local_planner/launch/plan_node.launch new file mode 100755 index 0000000..00cae27 --- /dev/null +++ b/navigations/dwb_local_planner/launch/plan_node.launch @@ -0,0 +1,14 @@ + + + + wait_for_transform: false + pose_update_frequency: -1.0 + update_frequency: -1.0 + origin_x: -5.0 + origin_y: -5.0 + global_frame: /odom + + + + + diff --git a/navigations/dwb_local_planner/package.xml b/navigations/dwb_local_planner/package.xml new file mode 100755 index 0000000..3ccfcae --- /dev/null +++ b/navigations/dwb_local_planner/package.xml @@ -0,0 +1,32 @@ + + + dwb_local_planner + 0.3.0 + + Plugin based local planner implementing the nav_core2::LocalPlanner interface. + + + David V. Lu!! + David V. Lu!! + + BSD + + catkin + dwb_msgs + geometry_msgs + nav_2d_msgs + nav_2d_utils + nav_core2 + nav_msgs + pluginlib + roscpp + sensor_msgs + tf + visualization_msgs + roslint + rostest + rosunit + + + + diff --git a/navigations/dwb_local_planner/plugins.xml b/navigations/dwb_local_planner/plugins.xml new file mode 100755 index 0000000..6186200 --- /dev/null +++ b/navigations/dwb_local_planner/plugins.xml @@ -0,0 +1,12 @@ + + + + + + + + + + + + diff --git a/navigations/dwb_local_planner/src/backwards_compatibility.cpp b/navigations/dwb_local_planner/src/backwards_compatibility.cpp new file mode 100755 index 0000000..105b242 --- /dev/null +++ b/navigations/dwb_local_planner/src/backwards_compatibility.cpp @@ -0,0 +1,81 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ +#include +#include +#include +#include + +namespace dwb_local_planner +{ + +using nav_2d_utils::moveParameter; + +std::string getBackwardsCompatibleDefaultGenerator(const ros::NodeHandle& nh) +{ + bool use_dwa; + nh.param("use_dwa", use_dwa, true); + if (use_dwa) + { + return "dwb_plugins::LimitedAccelGenerator"; + } + else + { + return "dwb_plugins::StandardTrajectoryGenerator"; + } +} + +void loadBackwardsCompatibleParameters(const ros::NodeHandle& nh) +{ + std::vector critic_names; + ROS_INFO_NAMED("DWBLocalPlanner", "No critics configured! Using the default set."); + critic_names.push_back("RotateToGoal"); // discards trajectories that move forward when already at goal + critic_names.push_back("Oscillation"); // discards oscillating motions (assisgns cost -1) + critic_names.push_back("ObstacleFootprint"); // discards trajectories that move into obstacles + critic_names.push_back("GoalAlign"); // prefers trajectories that make the nose go towards (local) nose goal + critic_names.push_back("PathAlign"); // prefers trajectories that keep the robot nose on nose path + critic_names.push_back("PathDist"); // prefers trajectories on global path + critic_names.push_back("GoalDist"); // prefers trajectories that go towards (local) goal, + // based on wave propagation + nh.setParam("critics", critic_names); + moveParameter(nh, "path_distance_bias", "PathAlign/scale", 32.0, false); + moveParameter(nh, "goal_distance_bias", "GoalAlign/scale", 24.0, false); + moveParameter(nh, "path_distance_bias", "PathDist/scale", 32.0); + moveParameter(nh, "goal_distance_bias", "GoalDist/scale", 24.0); + moveParameter(nh, "occdist_scale", "ObstacleFootprint/scale", 0.01); + + moveParameter(nh, "max_scaling_factor", "ObstacleFootprint/max_scaling_factor", 0.2); + moveParameter(nh, "scaling_speed", "ObstacleFootprint/scaling_speed", 0.25); +} + +} // namespace dwb_local_planner diff --git a/navigations/dwb_local_planner/src/debug_dwb_local_planner.cpp b/navigations/dwb_local_planner/src/debug_dwb_local_planner.cpp new file mode 100755 index 0000000..74dadc7 --- /dev/null +++ b/navigations/dwb_local_planner/src/debug_dwb_local_planner.cpp @@ -0,0 +1,150 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include +#include +#include +#include +#include + +namespace dwb_local_planner +{ + +void DebugDWBLocalPlanner::initialize(const ros::NodeHandle& parent, const std::string& name, + TFListenerPtr tf, nav_core2::Costmap::Ptr costmap) +{ + DWBLocalPlanner::initialize(parent, name, tf, costmap); + + debug_service_ = planner_nh_.advertiseService("debug_local_plan", + &DebugDWBLocalPlanner::debugLocalPlanService, this); + twist_gen_service_ = planner_nh_.advertiseService("generate_twists", + &DebugDWBLocalPlanner::generateTwistsService, this); + score_service_ = planner_nh_.advertiseService("score_trajectory", + &DebugDWBLocalPlanner::scoreTrajectoryService, this); + critic_service_ = planner_nh_.advertiseService("get_critic_score", + &DebugDWBLocalPlanner::getCriticScoreService, this); + generate_traj_service_ = planner_nh_.advertiseService("generate_traj", + &DebugDWBLocalPlanner::generateTrajectoryService, this); +} + +bool DebugDWBLocalPlanner::generateTwistsService(dwb_msgs::GenerateTwists::Request &req, + dwb_msgs::GenerateTwists::Response &res) +{ + res.twists = traj_generator_->getTwists(req.current_vel); + return true; +} + +bool DebugDWBLocalPlanner::generateTrajectoryService(dwb_msgs::GenerateTrajectory::Request &req, + dwb_msgs::GenerateTrajectory::Response &res) +{ + res.traj = traj_generator_->generateTrajectory(req.start_pose, req.start_vel, req.cmd_vel); + return true; +} + +bool DebugDWBLocalPlanner::scoreTrajectoryService(dwb_msgs::ScoreTrajectory::Request &req, + dwb_msgs::ScoreTrajectory::Response &res) +{ + if (req.goal.header.frame_id != "") + setGoalPose(req.goal); + if (req.global_plan.poses.size() > 0) + setPlan(req.global_plan); + + prepare(req.pose, req.velocity); + res.score = scoreTrajectory(req.traj); + return true; +} + +TrajectoryCritic::Ptr DebugDWBLocalPlanner::getCritic(std::string name) +{ + for (TrajectoryCritic::Ptr critic : critics_) + { + if (critic->getName() == name) + return critic; + } + return nullptr; +} + +bool DebugDWBLocalPlanner::getCriticScoreService(dwb_msgs::GetCriticScore::Request &req, + dwb_msgs::GetCriticScore::Response &res) +{ + TrajectoryCritic::Ptr critic = getCritic(req.critic_name); + if (critic == nullptr) + { + ROS_WARN_NAMED("DebugDWBLocalPlanner", "Critic %s not found!", req.critic_name.c_str()); + return false; + } + if (req.goal.header.frame_id != "") + setGoalPose(req.goal); + if (req.global_plan.poses.size() > 0) + setPlan(req.global_plan); + + // This prepares all the critics, even though we only need to prepare the one + prepare(req.pose, req.velocity); + + res.score.raw_score = critic->scoreTrajectory(req.traj); + res.score.scale = critic->getScale(); + res.score.name = req.critic_name; + + pub_.publishCostGrid(costmap_, critics_); + + return true; +} + +bool DebugDWBLocalPlanner::debugLocalPlanService(dwb_msgs::DebugLocalPlan::Request &req, + dwb_msgs::DebugLocalPlan::Response &res) +{ + if (req.goal.header.frame_id != "") + setGoalPose(req.goal); + if (req.global_plan.poses.size() > 0) + setPlan(req.global_plan); + std::shared_ptr results = std::make_shared(); + try + { + computeVelocityCommands(req.pose, req.velocity, results); + res.results = *results; + return true; + } + catch (const nav_core2::PlannerException& e) + { + ROS_ERROR_NAMED("DebugDWBLocalPlanner", "Exception in computeVelocityCommands: %s", e.what()); + return false; + } +} + +} // namespace dwb_local_planner + + +// register this planner as a LocalPlanner plugin +PLUGINLIB_EXPORT_CLASS(dwb_local_planner::DebugDWBLocalPlanner, nav_core2::LocalPlanner) diff --git a/navigations/dwb_local_planner/src/dwb_local_planner.cpp b/navigations/dwb_local_planner/src/dwb_local_planner.cpp new file mode 100755 index 0000000..6079fad --- /dev/null +++ b/navigations/dwb_local_planner/src/dwb_local_planner.cpp @@ -0,0 +1,506 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +namespace dwb_local_planner +{ + + DWBLocalPlanner::DWBLocalPlanner() : traj_gen_loader_("dwb_local_planner", "dwb_local_planner::TrajectoryGenerator"), + goal_checker_loader_("dwb_local_planner", "dwb_local_planner::GoalChecker"), + critic_loader_("dwb_local_planner", "dwb_local_planner::TrajectoryCritic") + { + } + + void DWBLocalPlanner::initialize(const ros::NodeHandle &parent, const std::string &name, + TFListenerPtr tf, nav_core2::Costmap::Ptr costmap) + { + tf_ = tf; + costmap_ = costmap; + planner_nh_ = ros::NodeHandle(parent, name); + + // This is needed when using the CostmapAdapter to ensure that the costmap's info matches the rolling window + planner_nh_.param("update_costmap_before_planning", update_costmap_before_planning_, true); + + planner_nh_.param("prune_plan", prune_plan_, true); + planner_nh_.param("prune_distance", prune_distance_, 1.0); + planner_nh_.param("short_circuit_trajectory_evaluation", short_circuit_trajectory_evaluation_, true); + planner_nh_.param("debug_trajectory_details", debug_trajectory_details_, false); + pub_.initialize(planner_nh_); + traj_pub_ = planner_nh_.advertise("traj_base", 1); + // Plugins + std::string traj_generator_name; + planner_nh_.param("trajectory_generator_name", traj_generator_name, + getBackwardsCompatibleDefaultGenerator(planner_nh_)); + ROS_INFO_NAMED("DWBLocalPlanner", "Using Trajectory Generator \"%s\"", traj_generator_name.c_str()); + traj_generator_ = std::move(traj_gen_loader_.createUniqueInstance(traj_generator_name)); + traj_generator_->initialize(planner_nh_); + + std::string goal_checker_name; + planner_nh_.param("goal_checker_name", goal_checker_name, std::string("dwb_plugins::SimpleGoalChecker")); + ROS_INFO_NAMED("DWBLocalPlanner", "Using Goal Checker \"%s\"", goal_checker_name.c_str()); + goal_checker_ = std::move(goal_checker_loader_.createUniqueInstance(goal_checker_name)); + goal_checker_->initialize(planner_nh_); + + loadCritics(name); + } + + std::string DWBLocalPlanner::resolveCriticClassName(std::string base_name) + { + if (base_name.find("Critic") == std::string::npos) + { + base_name = base_name + "Critic"; + } + + if (base_name.find("::") == std::string::npos) + { + for (unsigned int j = 0; j < default_critic_namespaces_.size(); j++) + { + std::string full_name = default_critic_namespaces_[j] + "::" + base_name; + if (critic_loader_.isClassAvailable(full_name)) + { + return full_name; + } + } + } + return base_name; + } + + void DWBLocalPlanner::loadCritics(const std::string name) + { + planner_nh_.param("default_critic_namespaces", default_critic_namespaces_); + if (default_critic_namespaces_.size() == 0) + { + default_critic_namespaces_.push_back("dwb_critics"); + } + + if (!planner_nh_.hasParam("critics")) + { + loadBackwardsCompatibleParameters(planner_nh_); + } + + std::vector critic_names; + planner_nh_.getParam("critics", critic_names); + for (unsigned int i = 0; i < critic_names.size(); i++) + { + std::string plugin_name = critic_names[i]; + std::string plugin_class; + planner_nh_.param(plugin_name + "/class", plugin_class, plugin_name); + plugin_class = resolveCriticClassName(plugin_class); + + TrajectoryCritic::Ptr plugin = std::move(critic_loader_.createUniqueInstance(plugin_class)); + ROS_INFO_NAMED("DWBLocalPlanner", "Using critic \"%s\" (%s)", plugin_name.c_str(), plugin_class.c_str()); + critics_.push_back(plugin); + plugin->initialize(planner_nh_, plugin_name, costmap_); + } + } + + bool DWBLocalPlanner::isGoalReached(const nav_2d_msgs::Pose2DStamped &pose, const nav_2d_msgs::Twist2D &velocity) + { + if (goal_pose_.header.frame_id == "") + { + ROS_WARN_NAMED("DWBLocalPlanner", "Cannot check if the goal is reached without the goal being set!"); + return false; + } + + // Update time stamp of goal pose + goal_pose_.header.stamp = pose.header.stamp; + + bool ret = goal_checker_->isGoalReached(transformPoseToLocal(pose), transformPoseToLocal(goal_pose_), velocity); + + if (ret) + { + ROS_INFO_THROTTLE_NAMED(1.0, "DWBLocalPlanner", "Goal reached!"); + } + return ret; + } + + void DWBLocalPlanner::setGoalPose(const nav_2d_msgs::Pose2DStamped &goal_pose) + { + ROS_INFO_NAMED("DWBLocalPlanner", "New Goal Received."); + goal_pose_ = goal_pose; + traj_generator_->reset(); + goal_checker_->reset(); + for (TrajectoryCritic::Ptr critic : critics_) + { + critic->reset(); + } + } + + void DWBLocalPlanner::setPlan(const nav_2d_msgs::Path2D &path) + { + pub_.publishGlobalPlan(path); + global_plan_ = path; + } + + nav_2d_msgs::Twist2DStamped DWBLocalPlanner::computeVelocityCommands(const nav_2d_msgs::Pose2DStamped &pose, + // fr-> 102 LocalPlannerAdapter::computeVelocityCommands(..) + const nav_2d_msgs::Twist2D &velocity) + { + std::shared_ptr results = nullptr; + if (pub_.shouldRecordEvaluation()) + { + results = std::make_shared(); + } + + try + { // to -> 227 - DWBLocalPlanner::computeVelocityCommands(...) + nav_2d_msgs::Twist2DStamped cmd_vel = computeVelocityCommands(pose, velocity, results); + pub_.publishEvaluation(results); + return cmd_vel; + } + catch (const nav_core2::PlannerException &e) + { + pub_.publishEvaluation(results); + throw; + } + } + + void DWBLocalPlanner::prepare(const nav_2d_msgs::Pose2DStamped &pose, const nav_2d_msgs::Twist2D &velocity) + { + if (update_costmap_before_planning_) + { + costmap_->update(); + } + nav_2d_msgs::Path2D transformed_plan = transformGlobalPlan(pose); + pub_.publishTransformedPlan(transformed_plan); + + // Update time stamp of goal pose + goal_pose_.header.stamp = pose.header.stamp; + + geometry_msgs::Pose2D local_start_pose = transformPoseToLocal(pose), + local_goal_pose = transformPoseToLocal(goal_pose_); + + pub_.publishInputParams(costmap_->getInfo(), local_start_pose, velocity, local_goal_pose); + + for (TrajectoryCritic::Ptr critic : critics_) + { + if (!critic->prepare(local_start_pose, velocity, local_goal_pose, transformed_plan)) + { + ROS_WARN_NAMED("DWBLocalPlanner", "Critic \"%s\" failed to prepare", critic->getName().c_str()); + } + } + } + + nav_2d_msgs::Twist2DStamped DWBLocalPlanner::computeVelocityCommands(const nav_2d_msgs::Pose2DStamped &pose, + // fr -> 179 DWBLocalPlanner::computeVelocityCommands( + const nav_2d_msgs::Twist2D &velocity, std::shared_ptr &results) + { + if (results) + { + results->header.frame_id = pose.header.frame_id; + results->header.stamp = ros::Time::now(); + } + prepare(pose, velocity); + + try + { + // to 282 -> DWBLocalPlanner::coreScoringAlgorithm() + dwb_msgs::TrajectoryScore best = coreScoringAlgorithm(pose.pose, velocity, results); + + // Return Value + nav_2d_msgs::Twist2DStamped cmd_vel; + cmd_vel.header.stamp = ros::Time::now(); + cmd_vel.velocity = best.traj.velocity; + + // debrief stateful critics + for (TrajectoryCritic::Ptr critic : critics_) + { + critic->debrief(cmd_vel.velocity); + } + + pub_.publishLocalPlan(pose.header, best.traj); + pub_.publishCostGrid(costmap_, critics_); + + return cmd_vel; + } + catch (const NoLegalTrajectoriesException &e) + { + nav_2d_msgs::Twist2D empty_cmd; + dwb_msgs::Trajectory2D empty_traj; + // debrief stateful scoring functions + for (TrajectoryCritic::Ptr critic : critics_) + { + critic->debrief(empty_cmd); + } + pub_.publishLocalPlan(pose.header, empty_traj); + pub_.publishCostGrid(costmap_, critics_); + + throw; + } + } + + dwb_msgs::TrajectoryScore DWBLocalPlanner::coreScoringAlgorithm(const geometry_msgs::Pose2D &pose, + // fr -> 249 dwb_msgs::TrajectoryScore best = coreScoringAlgorithm(pose.pose, velocity, results); + const nav_2d_msgs::Twist2D velocity, + std::shared_ptr &results) + { + nav_2d_msgs::Twist2D twist; + dwb_msgs::Trajectory2D traj; + dwb_msgs::TrajectoryScore best, worst; + best.total = -1; + worst.total = -1; + IllegalTrajectoryTracker tracker; + traj_generator_->startNewIteration(velocity); // nhận tốc độ hiện tại từ odom + + while (traj_generator_->hasMoreTwists()) // return current_ > max_vel_ + EPSILON; + { + twist = traj_generator_->nextTwist(); + + traj = traj_generator_->generateTrajectory(pose, velocity, twist); + + try + { + dwb_msgs::TrajectoryScore score = scoreTrajectory(traj, best.total); + + tracker.addLegalTrajectory(); + if (results) + { + results->twists.push_back(score); + } + if (best.total < 0 || score.total < best.total) + { + best = score; + if (results) + { + results->best_index = results->twists.size() - 1; + } + } + if (worst.total < 0 || score.total > worst.total) + { + worst = score; + if (results) + { + results->worst_index = results->twists.size() - 1; + } + } + } + catch (const nav_core2::IllegalTrajectoryException &e) + { + if (results) + { + dwb_msgs::TrajectoryScore failed_score; + failed_score.traj = traj; + + dwb_msgs::CriticScore cs; + cs.name = e.getCriticName(); + cs.raw_score = -1.0; + failed_score.scores.push_back(cs); + failed_score.total = -1.0; + results->twists.push_back(failed_score); + } + tracker.addIllegalTrajectory(e); + } + } + + if (best.total < 0) + { + if (debug_trajectory_details_) + { + ROS_ERROR_NAMED("DWBLocalPlanner", "%s", tracker.getMessage().c_str()); + for (auto const &x : tracker.getPercentages()) + { + ROS_ERROR_NAMED("DWBLocalPlanner", "%.2f: %10s/%s", x.second, x.first.first.c_str(), x.first.second.c_str()); + } + } + throw NoLegalTrajectoriesException(tracker); + } + nav_msgs::Path pathMsg; + pathMsg.header.frame_id = "odom"; + for (const auto& pose2D : traj.poses) { + geometry_msgs::PoseStamped pose; + pose.header.stamp = ros::Time::now(); // You can set the timestamp as needed + pose.pose.position.x = pose2D.x; + pose.pose.position.y = pose2D.y; + tf2::Quaternion temp; + temp.setRPY(0, 0, pose2D.theta); + pose.pose.orientation.x = temp.getX(); + pose.pose.orientation.y = temp.getY(); + pose.pose.orientation.z = temp.getZ(); + pose.pose.orientation.w = temp.getW(); + // You may need to set other fields like orientation if needed. + + pathMsg.poses.push_back(pose); + } + traj_pub_.publish(pathMsg); + return best; + } + + dwb_msgs::TrajectoryScore DWBLocalPlanner::scoreTrajectory(const dwb_msgs::Trajectory2D &traj, + double best_score) + { + dwb_msgs::TrajectoryScore score; + score.traj = traj; + + for (TrajectoryCritic::Ptr critic : critics_) + { + dwb_msgs::CriticScore cs; + cs.name = critic->getName(); + cs.scale = critic->getScale(); + + if (cs.scale == 0.0) + { + score.scores.push_back(cs); + continue; + } + double critic_score = critic->scoreTrajectory(traj); + cs.raw_score = critic_score; + score.scores.push_back(cs); + score.total += critic_score * cs.scale; + if (short_circuit_trajectory_evaluation_ && best_score > 0 && score.total > best_score) + { + // since we keep adding positives, once we are worse than the best, we will stay worse + break; + } + } + return score; + } + + double getSquareDistance(const geometry_msgs::Pose2D &pose_a, const geometry_msgs::Pose2D &pose_b) + { + double x_diff = pose_a.x - pose_b.x; + double y_diff = pose_a.y - pose_b.y; + return x_diff * x_diff + y_diff * y_diff; + } + + nav_2d_msgs::Path2D DWBLocalPlanner::transformGlobalPlan(const nav_2d_msgs::Pose2DStamped &pose) + { + + nav_2d_msgs::Path2D transformed_plan; + if (global_plan_.poses.size() == 0) + { + throw nav_core2::PlannerException("Received plan with zero length"); + } + + // let's get the pose of the robot in the frame of the plan + nav_2d_msgs::Pose2DStamped robot_pose; + if (!nav_2d_utils::transformPose(tf_, global_plan_.header.frame_id, pose, robot_pose)) + { + throw nav_core2::PlannerTFException("Unable to transform robot pose into global plan's frame"); + } + + transformed_plan.header.frame_id = costmap_->getFrameId(); + transformed_plan.header.stamp = pose.header.stamp; + + // we'll discard points on the plan that are outside the local costmap + double dist_threshold = std::max(costmap_->getWidth(), costmap_->getHeight()) * costmap_->getResolution() / 2.0; + double sq_dist_threshold = dist_threshold * dist_threshold; + nav_2d_msgs::Pose2DStamped stamped_pose; + stamped_pose.header.frame_id = global_plan_.header.frame_id; + + for (unsigned int i = 0; i < global_plan_.poses.size(); i++) + { + bool should_break = false; + if (getSquareDistance(robot_pose.pose, global_plan_.poses[i]) > sq_dist_threshold) + { + if (transformed_plan.poses.size() == 0) + { + // we need to skip to a point on the plan that is within a certain distance of the robot + continue; + } + else + { + // we're done transforming points + should_break = true; + } + } + + // now we'll transform until points are outside of our distance threshold + stamped_pose.pose = global_plan_.poses[i]; + transformed_plan.poses.push_back(transformPoseToLocal(stamped_pose)); + if (should_break) + break; + } + + // Prune both plans based on robot position + // Note that this part of the algorithm assumes that the global plan starts near the robot (at one point) + // Otherwise it may take a few iterations to converge to the proper behavior + if (prune_plan_) + { + // let's get the pose of the robot in the frame of the transformed_plan/costmap + nav_2d_msgs::Pose2DStamped costmap_pose; + if (!nav_2d_utils::transformPose(tf_, transformed_plan.header.frame_id, pose, costmap_pose)) + { + throw nav_core2::PlannerTFException("Unable to transform robot pose into costmap's frame"); + } + + ROS_ASSERT(global_plan_.poses.size() >= transformed_plan.poses.size()); + std::vector::iterator it = transformed_plan.poses.begin(); + std::vector::iterator global_it = global_plan_.poses.begin(); + double sq_prune_dist = prune_distance_ * prune_distance_; + while (it != transformed_plan.poses.end()) + { + const geometry_msgs::Pose2D &w = *it; + // Fixed error bound of 1 meter for now. Can reduce to a portion of the map size or based on the resolution + if (getSquareDistance(costmap_pose.pose, w) < sq_prune_dist) + { + ROS_DEBUG_NAMED("DWBLocalPlanner", "Nearest waypoint to <%f, %f> is <%f, %f>\n", + costmap_pose.pose.x, costmap_pose.pose.y, w.x, w.y); + break; + } + it = transformed_plan.poses.erase(it); + global_it = global_plan_.poses.erase(global_it); + } + pub_.publishGlobalPlan(global_plan_); + } + + if (transformed_plan.poses.size() == 0) + { + throw nav_core2::PlannerException("Resulting plan has 0 poses in it."); + } + return transformed_plan; + } + + geometry_msgs::Pose2D DWBLocalPlanner::transformPoseToLocal(const nav_2d_msgs::Pose2DStamped &pose) + { + return nav_2d_utils::transformStampedPose(tf_, pose, costmap_->getFrameId()); + } + +} // namespace dwb_local_planner + +// register this planner as a LocalPlanner plugin +PLUGINLIB_EXPORT_CLASS(dwb_local_planner::DWBLocalPlanner, nav_core2::LocalPlanner) diff --git a/navigations/dwb_local_planner/src/illegal_trajectory_tracker.cpp b/navigations/dwb_local_planner/src/illegal_trajectory_tracker.cpp new file mode 100755 index 0000000..c9c2cc4 --- /dev/null +++ b/navigations/dwb_local_planner/src/illegal_trajectory_tracker.cpp @@ -0,0 +1,82 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include +#include +#include +#include + +namespace dwb_local_planner +{ +void IllegalTrajectoryTracker::addIllegalTrajectory(const nav_core2::IllegalTrajectoryException& e) +{ + counts_[std::make_pair(e.getCriticName(), e.what())]++; + illegal_count_++; +} + +void IllegalTrajectoryTracker::addLegalTrajectory() +{ + legal_count_++; +} + +std::map< std::pair, double> IllegalTrajectoryTracker::getPercentages() const +{ + std::map< std::pair, double> percents; + double denominator = static_cast(legal_count_ + illegal_count_); + for (auto const& x : counts_) + { + percents[x.first] = static_cast(x.second) / denominator; + } + return percents; +} + +std::string IllegalTrajectoryTracker::getMessage() const +{ + std::ostringstream msg; + if (legal_count_ == 0) + { + msg << "No valid trajectories out of " << illegal_count_ << "! "; + } + else + { + unsigned int total = legal_count_ + illegal_count_; + msg << legal_count_ << " valid trajectories found ("; + msg << static_cast(100 * legal_count_) / static_cast(total); + msg << "% of " << total << "). "; + } + return msg.str(); +} + +} // namespace dwb_local_planner diff --git a/navigations/dwb_local_planner/src/planner_node.cpp b/navigations/dwb_local_planner/src/planner_node.cpp new file mode 100755 index 0000000..6ead35b --- /dev/null +++ b/navigations/dwb_local_planner/src/planner_node.cpp @@ -0,0 +1,60 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ +#include +#include +#include +#include +#include +#include + +int main(int argc, char** argv) +{ + ros::init(argc, argv, "plan_node"); + ros::NodeHandle private_nh("~"); + + dwb_local_planner::DebugDWBLocalPlanner planner; + ROS_INFO("Plan Node"); + + TFListenerPtr tf = std::make_shared(); + tf2_ros::TransformListener tf2(*tf); + + pluginlib::ClassLoader costmap_loader("nav_core2", "nav_core2::Costmap"); + std::string costmap_class; + private_nh.param("local_costmap_class", costmap_class, std::string("nav_core_adapter::CostmapAdapter")); + nav_core2::Costmap::Ptr costmap = costmap_loader.createUniqueInstance(costmap_class); + costmap->initialize(private_nh, "costmap", tf); + + planner.initialize(private_nh, "dwb_local_planner", tf, costmap); + ros::spin(); +} diff --git a/navigations/dwb_local_planner/src/publisher.cpp b/navigations/dwb_local_planner/src/publisher.cpp new file mode 100755 index 0000000..ca1b9ea --- /dev/null +++ b/navigations/dwb_local_planner/src/publisher.cpp @@ -0,0 +1,246 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ +#include +#include +#include +#include +#include +#include +#include +#include +#include + +namespace dwb_local_planner +{ + +void DWBPublisher::initialize(ros::NodeHandle& nh) +{ + ros::NodeHandle global_nh; + // Load Publishers + nh.param("publish_evaluation", publish_evaluation_, true); + if (publish_evaluation_) + eval_pub_ = nh.advertise("evaluation", 1); + + nh.param("publish_input_params", publish_input_params_, true); + if (publish_input_params_) + { + info_pub_ = nh.advertise("info", 1); + pose_pub_ = nh.advertise("pose", 1); + goal_pub_ = nh.advertise("goal", 1); + velocity_pub_ = nh.advertise("velocity", 1); + } + + nh.param("publish_global_plan", publish_global_plan_, true); + if (publish_global_plan_) + global_pub_ = nh.advertise("global_plan", 1); + + nh.param("publish_transformed_plan", publish_transformed_, true); + if (publish_transformed_) + transformed_pub_ = nh.advertise("transformed_global_plan", 1); + + nh.param("publish_local_plan", publish_local_plan_, true); + if (publish_local_plan_) + local_pub_ = nh.advertise("local_plan", 1); + + nh.param("publish_trajectories", publish_trajectories_, true); + if (publish_trajectories_) + marker_pub_ = global_nh.advertise("marker", 1); + double marker_lifetime; + nh.param("marker_lifetime", marker_lifetime, 0.1); + marker_lifetime_ = ros::Duration(marker_lifetime); + + nh.param("publish_cost_grid_pc", publish_cost_grid_pc_, false); + if (publish_cost_grid_pc_) + cost_grid_pc_pub_ = nh.advertise("cost_cloud", 1); +} + +void DWBPublisher::publishEvaluation(std::shared_ptr results) +{ + if (results == nullptr) return; + if (publish_evaluation_ && eval_pub_.getNumSubscribers() > 0) + { + eval_pub_.publish(*results); + } + publishTrajectories(*results); +} + +void DWBPublisher::publishTrajectories(const dwb_msgs::LocalPlanEvaluation& results) +{ + if (!publish_trajectories_ || marker_pub_.getNumSubscribers() == 0) return; + visualization_msgs::MarkerArray ma; + visualization_msgs::Marker m; + + if (results.twists.size() == 0) return; + + geometry_msgs::Point pt; + + m.header = results.header; + m.type = m.LINE_STRIP; + m.pose.orientation.w = 1; + m.scale.x = 0.002; + m.color.a = 1.0; + m.lifetime = marker_lifetime_; + + double best_cost = results.twists[results.best_index].total, + worst_cost = results.twists[results.worst_index].total, + denominator = worst_cost - best_cost; + if (std::fabs(denominator) < 1e-9) + { + denominator = 1.0; + } + + for (unsigned int i = 0; i < results.twists.size(); i++) + { + const dwb_msgs::TrajectoryScore& twist = results.twists[i]; + if (twist.total >= 0) + { + m.color.r = 1 - (twist.total - best_cost) / denominator; + m.color.g = 1 - (twist.total - best_cost) / denominator; + m.color.b = 1; + m.ns = "ValidTrajectories"; + } + else + { + m.color.b = 0; + m.ns = "InvalidTrajectories"; + } + m.points.clear(); + for (unsigned int j = 0; j < twist.traj.poses.size(); ++j) + { + pt.x = twist.traj.poses[j].x; + pt.y = twist.traj.poses[j].y; + pt.z = 0; + m.points.push_back(pt); + } + ma.markers.push_back(m); + m.id += 1; + } + + marker_pub_.publish(ma); +} + +void DWBPublisher::publishLocalPlan(const std_msgs::Header& header, + const dwb_msgs::Trajectory2D& traj) +{ + if (!publish_local_plan_ || local_pub_.getNumSubscribers() == 0) return; + + nav_msgs::Path path = nav_2d_utils::poses2DToPath(traj.poses, header.frame_id, header.stamp); + local_pub_.publish(path); +} + +void DWBPublisher::publishCostGrid(const nav_core2::Costmap::Ptr costmap, + const std::vector critics) +{ + if (!publish_cost_grid_pc_ || cost_grid_pc_pub_.getNumSubscribers() == 0) return; + + const nav_grid::NavGridInfo& info = costmap->getInfo(); + sensor_msgs::PointCloud cost_grid_pc; + cost_grid_pc.header.frame_id = info.frame_id; + cost_grid_pc.header.stamp = ros::Time::now(); + + double x_coord, y_coord; + unsigned int n = info.width * info.height; + cost_grid_pc.points.resize(n); + unsigned int i = 0; + for (unsigned int cy = 0; cy < info.height; cy++) + { + for (unsigned int cx = 0; cx < info.width; cx++) + { + gridToWorld(info, cx, cy, x_coord, y_coord); + cost_grid_pc.points[i].x = x_coord; + cost_grid_pc.points[i].y = y_coord; + i++; + } + } + + sensor_msgs::ChannelFloat32 totals; + totals.name = "total_cost"; + totals.values.resize(n); + + for (TrajectoryCritic::Ptr critic : critics) + { + unsigned int channel_index = cost_grid_pc.channels.size(); + critic->addCriticVisualization(cost_grid_pc); + if (channel_index == cost_grid_pc.channels.size()) + { + // No channels were added, so skip to next critic + continue; + } + double scale = critic->getScale(); + for (i = 0; i < n; i++) + { + totals.values[i] += cost_grid_pc.channels[channel_index].values[i] * scale; + } + } + cost_grid_pc.channels.push_back(totals); + + sensor_msgs::PointCloud2 cost_grid_pc2; + convertPointCloudToPointCloud2(cost_grid_pc, cost_grid_pc2); + cost_grid_pc_pub_.publish(cost_grid_pc2); +} + +void DWBPublisher::publishGlobalPlan(const nav_2d_msgs::Path2D plan) +{ + publishGenericPlan(plan, global_pub_, publish_global_plan_); +} + +void DWBPublisher::publishTransformedPlan(const nav_2d_msgs::Path2D plan) +{ + publishGenericPlan(plan, transformed_pub_, publish_transformed_); +} + +void DWBPublisher::publishLocalPlan(const nav_2d_msgs::Path2D plan) +{ + publishGenericPlan(plan, local_pub_, publish_local_plan_); +} + +void DWBPublisher::publishGenericPlan(const nav_2d_msgs::Path2D plan, const ros::Publisher pub, bool flag) +{ + if (!flag || pub.getNumSubscribers() == 0) return; + nav_msgs::Path path = nav_2d_utils::pathToPath(plan); + pub.publish(path); +} + +void DWBPublisher::publishInputParams(const nav_grid::NavGridInfo& info, const geometry_msgs::Pose2D& start_pose, + const nav_2d_msgs::Twist2D& velocity, const geometry_msgs::Pose2D& goal_pose) +{ + if (!publish_input_params_) return; + + info_pub_.publish(nav_2d_utils::toMsg(info)); + pose_pub_.publish(start_pose); + goal_pub_.publish(goal_pose); + velocity_pub_.publish(velocity); +} + +} // namespace dwb_local_planner diff --git a/navigations/dwb_local_planner/src/trajectory_utils.cpp b/navigations/dwb_local_planner/src/trajectory_utils.cpp new file mode 100755 index 0000000..d2f4d88 --- /dev/null +++ b/navigations/dwb_local_planner/src/trajectory_utils.cpp @@ -0,0 +1,105 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include + +namespace dwb_local_planner +{ +const geometry_msgs::Pose2D& getClosestPose(const dwb_msgs::Trajectory2D& trajectory, const double time_offset) +{ + ros::Duration goal_time(time_offset); + const unsigned int num_poses = trajectory.poses.size(); + if (num_poses == 0) + { + throw nav_core2::PlannerException("Cannot call getClosestPose on empty trajectory."); + } + unsigned int closest_index = num_poses; + double closest_diff = 0.0; + for (unsigned int i=0; i < num_poses; ++i) + { + double diff = fabs((trajectory.time_offsets[i] - goal_time).toSec()); + if (closest_index == num_poses || diff < closest_diff) + { + closest_index = i; + closest_diff = diff; + } + if (goal_time < trajectory.time_offsets[i]) + { + break; + } + } + return trajectory.poses[closest_index]; +} + +geometry_msgs::Pose2D projectPose(const dwb_msgs::Trajectory2D& trajectory, const double time_offset) +{ + ros::Duration goal_time(time_offset); + const unsigned int num_poses = trajectory.poses.size(); + if (num_poses == 0) + { + throw nav_core2::PlannerException("Cannot call projectPose on empty trajectory."); + } + if (goal_time <= trajectory.time_offsets[0]) + { + return trajectory.poses[0]; + } + else if (goal_time >= trajectory.time_offsets[num_poses - 1]) + { + return trajectory.poses[num_poses - 1]; + } + + for (unsigned int i=0; i < num_poses - 1; ++i) + { + if (goal_time >= trajectory.time_offsets[i] && goal_time < trajectory.time_offsets[i+1]) + { + double time_diff = (trajectory.time_offsets[i+1] - trajectory.time_offsets[i]).toSec(); + double ratio = (goal_time - trajectory.time_offsets[i]).toSec() / time_diff; + double inv_ratio = 1.0 - ratio; + const geometry_msgs::Pose2D& pose_a = trajectory.poses[i]; + const geometry_msgs::Pose2D& pose_b = trajectory.poses[i + 1]; + geometry_msgs::Pose2D projected; + projected.x = pose_a.x * inv_ratio + pose_b.x * ratio; + projected.y = pose_a.y * inv_ratio + pose_b.y * ratio; + projected.theta = pose_a.theta * inv_ratio + pose_b.theta * ratio; + return projected; + } + } + + // Should not reach this point + return trajectory.poses[num_poses - 1]; +} + + +} // namespace dwb_local_planner diff --git a/navigations/dwb_local_planner/structure.drawio b/navigations/dwb_local_planner/structure.drawio new file mode 100755 index 0000000..cf5a72f --- /dev/null +++ b/navigations/dwb_local_planner/structure.drawio @@ -0,0 +1,74 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/navigations/dwb_local_planner/test/utils_test.cpp b/navigations/dwb_local_planner/test/utils_test.cpp new file mode 100755 index 0000000..2cff319 --- /dev/null +++ b/navigations/dwb_local_planner/test/utils_test.cpp @@ -0,0 +1,115 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include + +using dwb_local_planner::getClosestPose; +using dwb_local_planner::projectPose; + +TEST(Utils, ClosestPose) +{ + dwb_msgs::Trajectory2D traj; + traj.poses.resize(4); + traj.time_offsets.resize(4); + for (unsigned int i=0; i < traj.poses.size(); i++) + { + double d = static_cast(i); + traj.poses[i].x = d; + traj.time_offsets[i] = ros::Duration(d); + } + + EXPECT_DOUBLE_EQ(getClosestPose(traj, 0.0).x, traj.poses[0].x); + EXPECT_DOUBLE_EQ(getClosestPose(traj, -1.0).x, traj.poses[0].x); + EXPECT_DOUBLE_EQ(getClosestPose(traj, 0.4).x, traj.poses[0].x); + EXPECT_DOUBLE_EQ(getClosestPose(traj, 0.5).x, traj.poses[0].x); + EXPECT_DOUBLE_EQ(getClosestPose(traj, 0.51).x, traj.poses[1].x); + EXPECT_DOUBLE_EQ(getClosestPose(traj, 1.0).x, traj.poses[1].x); + EXPECT_DOUBLE_EQ(getClosestPose(traj, 1.4999).x, traj.poses[1].x); + EXPECT_DOUBLE_EQ(getClosestPose(traj, 2.0).x, traj.poses[2].x); + EXPECT_DOUBLE_EQ(getClosestPose(traj, 2.51).x, traj.poses[3].x); + EXPECT_DOUBLE_EQ(getClosestPose(traj, 3.5).x, traj.poses[3].x); +} + +TEST(Utils, ProjectPose) +{ + dwb_msgs::Trajectory2D traj; + traj.poses.resize(4); + traj.time_offsets.resize(4); + for (unsigned int i=0; i < traj.poses.size(); i++) + { + double d = static_cast(i); + traj.poses[i].x = d; + traj.poses[i].y = 30.0 - 2.0 * d; + traj.poses[i].theta = 0.42; + traj.time_offsets[i] = ros::Duration(d); + } + + EXPECT_DOUBLE_EQ(projectPose(traj, 0.0).x, 0.0); + EXPECT_DOUBLE_EQ(projectPose(traj, 0.0).y, 30.0); + EXPECT_DOUBLE_EQ(projectPose(traj, 0.0).theta, 0.42); + EXPECT_DOUBLE_EQ(projectPose(traj, -1.0).x, 0.0); + EXPECT_DOUBLE_EQ(projectPose(traj, -1.0).y, 30.0); + EXPECT_DOUBLE_EQ(projectPose(traj, -1.0).theta, 0.42); + EXPECT_DOUBLE_EQ(projectPose(traj, 0.4).x, 0.4); + EXPECT_DOUBLE_EQ(projectPose(traj, 0.4).y, 29.2); + EXPECT_DOUBLE_EQ(projectPose(traj, 0.4).theta, 0.42); + EXPECT_DOUBLE_EQ(projectPose(traj, 0.5).x, 0.5); + EXPECT_DOUBLE_EQ(projectPose(traj, 0.5).y, 29.0); + EXPECT_DOUBLE_EQ(projectPose(traj, 0.5).theta, 0.42); + EXPECT_DOUBLE_EQ(projectPose(traj, 0.51).x, 0.51); + EXPECT_DOUBLE_EQ(projectPose(traj, 0.51).y, 28.98); + EXPECT_DOUBLE_EQ(projectPose(traj, 0.51).theta, 0.42); + EXPECT_DOUBLE_EQ(projectPose(traj, 1.0).x, 1.0); + EXPECT_DOUBLE_EQ(projectPose(traj, 1.0).y, 28.0); + EXPECT_DOUBLE_EQ(projectPose(traj, 1.0).theta, 0.42); + EXPECT_DOUBLE_EQ(projectPose(traj, 1.4999).x, 1.4999); + EXPECT_DOUBLE_EQ(projectPose(traj, 1.4999).y, 27.0002); + EXPECT_DOUBLE_EQ(projectPose(traj, 1.4999).theta, 0.42); + EXPECT_DOUBLE_EQ(projectPose(traj, 2.0).x, 2.0); + EXPECT_DOUBLE_EQ(projectPose(traj, 2.0).y, 26.0); + EXPECT_DOUBLE_EQ(projectPose(traj, 2.0).theta, 0.42); + EXPECT_FLOAT_EQ(projectPose(traj, 2.51).x, 2.51); + EXPECT_FLOAT_EQ(projectPose(traj, 2.51).y, 24.98); + EXPECT_DOUBLE_EQ(projectPose(traj, 2.51).theta, 0.42); + EXPECT_DOUBLE_EQ(projectPose(traj, 3.5).x, 3.0); + EXPECT_DOUBLE_EQ(projectPose(traj, 3.5).y, 24.0); + EXPECT_DOUBLE_EQ(projectPose(traj, 3.5).theta, 0.42); +} + +int main(int argc, char **argv) +{ + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/navigations/dwb_msgs/CMakeLists.txt b/navigations/dwb_msgs/CMakeLists.txt new file mode 100755 index 0000000..204ada8 --- /dev/null +++ b/navigations/dwb_msgs/CMakeLists.txt @@ -0,0 +1,25 @@ +cmake_minimum_required(VERSION 3.0.2) +project(dwb_msgs) + +find_package(catkin REQUIRED + COMPONENTS geometry_msgs nav_2d_msgs message_generation nav_msgs +) + +add_message_files(FILES + CriticScore.msg + LocalPlanEvaluation.msg + Trajectory2D.msg + TrajectoryScore.msg +) +add_service_files(FILES + DebugLocalPlan.srv + GenerateTrajectory.srv + GenerateTwists.srv + GetCriticScore.srv + ScoreTrajectory.srv +) +generate_messages(DEPENDENCIES geometry_msgs nav_2d_msgs nav_msgs) + +catkin_package( + CATKIN_DEPENDS geometry_msgs message_runtime nav_2d_msgs nav_msgs +) diff --git a/navigations/dwb_msgs/msg/CriticScore.msg b/navigations/dwb_msgs/msg/CriticScore.msg new file mode 100755 index 0000000..7923c5e --- /dev/null +++ b/navigations/dwb_msgs/msg/CriticScore.msg @@ -0,0 +1,7 @@ +# The result from one critic scoring a Twist. +# Name of the critic +string name +# Score for the critic, not multiplied by the scale +float32 raw_score +# Scale for the critic, multiplied by the raw_score and added to the total score +float32 scale diff --git a/navigations/dwb_msgs/msg/LocalPlanEvaluation.msg b/navigations/dwb_msgs/msg/LocalPlanEvaluation.msg new file mode 100755 index 0000000..f0b6548 --- /dev/null +++ b/navigations/dwb_msgs/msg/LocalPlanEvaluation.msg @@ -0,0 +1,10 @@ +# Full Scoring for running the local planner + +# Header, used for timestamp +Header header +# All the trajectories evaluated and their scores +TrajectoryScore[] twists +# Convenience index of the best (lowest) score in the twists array +uint16 best_index +# Convenience index of the worst (highest) score in the twists array. Useful for scaling. +uint16 worst_index diff --git a/navigations/dwb_msgs/msg/Trajectory2D.msg b/navigations/dwb_msgs/msg/Trajectory2D.msg new file mode 100755 index 0000000..f8e3a9c --- /dev/null +++ b/navigations/dwb_msgs/msg/Trajectory2D.msg @@ -0,0 +1,11 @@ +# For a given velocity command, the poses that the robot will go to in the allotted time. + +# Input Velocity +nav_2d_msgs/Twist2D velocity + +# Poses the robot will go to, given our kinematic model +geometry_msgs/Pose2D[] poses + +# Time difference between the current pose and the poses in the trajectory. +# Parallel array to poses. Length should be the same. +duration[] time_offsets diff --git a/navigations/dwb_msgs/msg/TrajectoryScore.msg b/navigations/dwb_msgs/msg/TrajectoryScore.msg new file mode 100755 index 0000000..7ff4917 --- /dev/null +++ b/navigations/dwb_msgs/msg/TrajectoryScore.msg @@ -0,0 +1,8 @@ +# Complete scoring for a given twist. + +# The trajectory being scored +Trajectory2D traj +# The Scores for each of the critics employed +CriticScore[] scores +# Convenience member that totals the critic scores +float32 total diff --git a/navigations/dwb_msgs/package.xml b/navigations/dwb_msgs/package.xml new file mode 100755 index 0000000..0add28f --- /dev/null +++ b/navigations/dwb_msgs/package.xml @@ -0,0 +1,19 @@ + + + dwb_msgs + 0.3.0 + Message/Service definitions specifically for the dwb_local_planner + + David V. Lu!! + + BSD + + catkin + geometry_msgs + nav_2d_msgs + nav_msgs + message_generation + message_runtime + message_runtime + + diff --git a/navigations/dwb_msgs/srv/DebugLocalPlan.srv b/navigations/dwb_msgs/srv/DebugLocalPlan.srv new file mode 100755 index 0000000..eaba760 --- /dev/null +++ b/navigations/dwb_msgs/srv/DebugLocalPlan.srv @@ -0,0 +1,7 @@ +# For a given pose velocity and global_plan, run the local planner and return full results +nav_2d_msgs/Pose2DStamped pose +nav_2d_msgs/Twist2D velocity +nav_2d_msgs/Path2D global_plan +nav_2d_msgs/Pose2DStamped goal +--- +LocalPlanEvaluation results diff --git a/navigations/dwb_msgs/srv/GenerateTrajectory.srv b/navigations/dwb_msgs/srv/GenerateTrajectory.srv new file mode 100755 index 0000000..330aec5 --- /dev/null +++ b/navigations/dwb_msgs/srv/GenerateTrajectory.srv @@ -0,0 +1,6 @@ +# For a given start pose, velocity and desired velocity, generate which poses will be visited +geometry_msgs/Pose2D start_pose +nav_2d_msgs/Twist2D start_vel +nav_2d_msgs/Twist2D cmd_vel +--- +Trajectory2D traj diff --git a/navigations/dwb_msgs/srv/GenerateTwists.srv b/navigations/dwb_msgs/srv/GenerateTwists.srv new file mode 100755 index 0000000..72cfdc8 --- /dev/null +++ b/navigations/dwb_msgs/srv/GenerateTwists.srv @@ -0,0 +1,4 @@ +# For a given velocity, generate which twist commands will be evaluated +nav_2d_msgs/Twist2D current_vel +--- +nav_2d_msgs/Twist2D[] twists diff --git a/navigations/dwb_msgs/srv/GetCriticScore.srv b/navigations/dwb_msgs/srv/GetCriticScore.srv new file mode 100755 index 0000000..0c48ab0 --- /dev/null +++ b/navigations/dwb_msgs/srv/GetCriticScore.srv @@ -0,0 +1,8 @@ +nav_2d_msgs/Pose2DStamped pose +nav_2d_msgs/Twist2D velocity +nav_2d_msgs/Path2D global_plan +nav_2d_msgs/Pose2DStamped goal +Trajectory2D traj +string critic_name +--- +CriticScore score diff --git a/navigations/dwb_msgs/srv/ScoreTrajectory.srv b/navigations/dwb_msgs/srv/ScoreTrajectory.srv new file mode 100755 index 0000000..97dddd2 --- /dev/null +++ b/navigations/dwb_msgs/srv/ScoreTrajectory.srv @@ -0,0 +1,7 @@ +nav_2d_msgs/Pose2DStamped pose +nav_2d_msgs/Twist2D velocity +nav_2d_msgs/Path2D global_plan +nav_2d_msgs/Pose2DStamped goal +Trajectory2D traj +--- +TrajectoryScore score diff --git a/navigations/dwb_plugins/CMakeLists.txt b/navigations/dwb_plugins/CMakeLists.txt new file mode 100755 index 0000000..d2879f2 --- /dev/null +++ b/navigations/dwb_plugins/CMakeLists.txt @@ -0,0 +1,61 @@ +cmake_minimum_required(VERSION 3.0.2) +project(dwb_plugins) + +set_directory_properties(PROPERTIES COMPILE_OPTIONS "-std=c++11;-Wall;-Werror") + +find_package(catkin REQUIRED COMPONENTS angles dwb_local_planner dynamic_reconfigure nav_2d_msgs nav_2d_utils nav_core2 pluginlib roscpp) + +generate_dynamic_reconfigure_options(cfg/KinematicParams.cfg) + +catkin_package( + INCLUDE_DIRS include + CATKIN_DEPENDS angles dwb_local_planner dynamic_reconfigure nav_2d_msgs nav_2d_utils nav_core2 pluginlib roscpp + LIBRARIES simple_goal_checker stopped_goal_checker standard_traj_generator +) + +include_directories( + include ${catkin_INCLUDE_DIRS} +) + +add_library(simple_goal_checker src/simple_goal_checker.cpp) +target_link_libraries(simple_goal_checker ${catkin_LIBRARIES}) +add_dependencies(simple_goal_checker ${catkin_EXPORTED_TARGETS} ${dwb_plugins_EXPORTED_TARGETS}) + +add_library(stopped_goal_checker src/stopped_goal_checker.cpp) +target_link_libraries(stopped_goal_checker simple_goal_checker ${catkin_LIBRARIES}) +add_dependencies(stopped_goal_checker ${catkin_EXPORTED_TARGETS} ${dwb_plugins_EXPORTED_TARGETS}) + +add_library(standard_traj_generator + src/standard_traj_generator.cpp + src/limited_accel_generator.cpp + src/kinematic_parameters.cpp + src/xy_theta_iterator.cpp) +target_link_libraries(standard_traj_generator ${catkin_LIBRARIES}) +add_dependencies(standard_traj_generator ${catkin_EXPORTED_TARGETS} ${dwb_plugins_EXPORTED_TARGETS}) + +if (CATKIN_ENABLE_TESTING) + catkin_add_gtest(vtest test/velocity_iterator_test.cpp) + + find_package(rostest REQUIRED) + add_rostest_gtest(goal_checker test/goal_checker.launch test/goal_checker.cpp) + target_link_libraries(goal_checker simple_goal_checker stopped_goal_checker ${GTEST_LIBRARIES}) + + add_rostest_gtest(twist_gen_test test/twist_gen.launch test/twist_gen.cpp) + target_link_libraries(twist_gen_test standard_traj_generator ${GTEST_LIBRARIES}) + + find_package(roslint REQUIRED) + roslint_cpp() + roslint_add_test() +endif (CATKIN_ENABLE_TESTING) + +install(TARGETS simple_goal_checker stopped_goal_checker standard_traj_generator + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} +) +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} +) +install(FILES plugins.xml + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) diff --git a/navigations/dwb_plugins/README.md b/navigations/dwb_plugins/README.md new file mode 100755 index 0000000..cd0200c --- /dev/null +++ b/navigations/dwb_plugins/README.md @@ -0,0 +1,44 @@ +# dwb_plugins + +This package contains the standard implementations of the GoalChecker and TrajectoryGenerators for `dwb_local_planner`. The TrajectoryCritic implementations are in `dwb_critics`. + +## Goal Checkers +There are two goal checkers implemented. +### SimpleGoalChecker +SimpleGoalChecker will return true indicating a goal has been reached when the query pose is sufficiently close to the goal pose. It does this by comparing the cartesian difference against the `xy_goal_tolerance` and the shortest angular difference to the `yaw_goal_tolerance`. It does not check velocity. + +If the `stateful` parameter is set to true (which it is by default), once the desired cartesian difference is obtained, it will not check the cartesian difference again (until reset) and only check the yaw tolerance. This handles cases where the robot may accidentally leave the desired `xy_goal_tolerance` while rotating to the desired yaw. If `stateful` is true, this won't force the robot to try to move closer to the goal again, and instead just rotate to the goal. + +### StoppedGoalChecker +StoppedGoalChecker builds off of the above functionality, but also ensures that the robot's linear velocity is less than `trans_stopped_velocity` and the rotational velocity is less than `rot_stopped_velocity`. + +## Trajectory Generation +Trajectory Generation covers two separate but related components. + * First, it defines which command velocities are available, given the current velocity. + * Second, given a velocity, it defines the trajectory the robot would take. + +Generally, the available velocities are constrained by the robot's velocity and acceleration limits. + +![velocity limits diagram](doc/VelocitySpace.png) + +In the above diagram, the robot's current velocity is marked with a blue circle, and the grey rectangle marks the allowable velocities, limited by acceleration, and the robot's maximum x velocity. However, the exact size of the rectangle also depends on a time parameter, which we get into below. + +When converting the velocities to trajectories, the robot's position is projected ahead in both time and space. This is dependent on a time parameter (called `sim_time`) for how far into the future to project the robot's position. For a simple example, assume we had a robot at `x=0` travelling at `xv=2.0`, and we want to calculate the trajectory for `xv=2.0`. It might result in the following poses if `sim_time=2.0`. + * `t=0.0, x=0` + * `t=1.0, x=2.0` + * `t=2.0, x=4.0` + +However, the trajectory is more open to interpretation when the speed is not constant. + +### StandardTrajGenerator and LimitedAccelGenerator +To replicate the functionality of `dwa_local_planner`, this package implements two TrajectoryGenerators. StandardTrajGenerator is equivalent to using DWA with `use_dwa=false` and LimitedAccelGenerator is equivalent to DWA with `use_dwa=true` (which is the default). The key difference in these generators are how time and acceleration are handled. + +As discussed above, `sim_time` is the parameter used for determining the time ellapsed in the trajectories (DWA's default was 1.7 seconds). In `StandardTrajGenerator` the available command velocities are limited by velocities reachable given the robot's acceleration in `sim_time`, i.e. the maximum available linear velocity is `vel_x + accel_x * sim_time`. In practice, given the relatively high value of `sim_time`, `StandardTrajGenerator` would allow for high accelerations almost instantaenously. For example, if initially motionless, with an accerlation of 1.0 m/s^2 and `sim_time=1.7`, the initial velocity could be 1.7 m/s. + +In `LimitedAccelGenerator` the time used for calculating the accerlation portion is either the parameter `sim_period`, or the inverse of the `controller_frequency` (i.e. if `controller_frequency` is 20.0, `sim_period` is set to 0.05). Then the maximum linear velocity is calculated with `vel_x + accel_x * sim_period`. This results in MUCH lower velocities. + +The other key difference between these two is how the acceleration is handled over time in the trajectory generation. In `StandardTrajGenerator` the velocity is allowed to change over the course of the trajectory based on the robot's acceleration, ramping up to the command velocity. In `LimitedAccelGenerator` the velocity is constant throughout the trajectory. + +In the below example, the velocities are shown for an initial speed of 0.0 and commanded speed of 3.5 m/s. + +![standard position and velocity](doc/std_pv.png)![limited acceleration position and velocity](doc/lim_pv.png) \ No newline at end of file diff --git a/navigations/dwb_plugins/cfg/KinematicParams.cfg b/navigations/dwb_plugins/cfg/KinematicParams.cfg new file mode 100755 index 0000000..51dab28 --- /dev/null +++ b/navigations/dwb_plugins/cfg/KinematicParams.cfg @@ -0,0 +1,33 @@ +#!/usr/bin/env python +from dynamic_reconfigure.parameter_generator_catkin import ParameterGenerator, double_t + +gen = ParameterGenerator() + +# velocities +gen.add('min_vel_x', double_t, 0, 'The minimum x velocity for the robot in m/s', 0.0) +gen.add('max_vel_x', double_t, 0, 'The maximum x velocity for the robot in m/s', 0.55) +gen.add('min_vel_y', double_t, 0, 'The minimum y velocity for the robot in m/s', -0.1) +gen.add('max_vel_y', double_t, 0, 'The maximum y velocity for the robot in m/s', 0.1) +gen.add('max_vel_theta', double_t, 0, 'The absolute value of the maximum rotational velocity for the robot in rad/s. ' + 'The minimum rotational velocity is assumed to be -max_vel_theta', 1.0) + +# acceleration +gen.add('acc_lim_x', double_t, 0, 'The acceleration limit of the robot in the x direction in m/s^2', 2.5) +gen.add('acc_lim_y', double_t, 0, 'The acceleration limit of the robot in the y direction in m/s^2', 2.5) +gen.add('acc_lim_theta', double_t, 0, 'The acceleration limit of the robot in the theta direction in rad/s^2', 3.2) + +gen.add('decel_lim_x', double_t, 0, 'The deceleration limit of the robot in the x direction in m/s^2', -2.5) +gen.add('decel_lim_y', double_t, 0, 'The deceleration limit of the robot in the y direction in m/s^2', -2.5) +gen.add('decel_lim_theta', double_t, 0, 'The deceleration limit of the robot in the theta direction in rad/s^2', -3.2) + +gen.add('min_speed_xy', double_t, 0, 'The absolute value of the minimum translational/xy velocity in m/s. ' + 'If the value is negative, then the min speed will be arbitrarily close to 0.0. ' + 'Previously called min_trans_vel', 0.1) +gen.add('max_speed_xy', double_t, 0, 'The absolute value of the maximum translational/xy velocity in m/s. ' + 'If the value is negative, then the max speed is hypot(max_vel_x, max_vel_y). ' + 'Previously called max_trans_vel', 0.55) +gen.add('min_speed_theta', double_t, 0, 'The absolute value of the minimum rotational velocity in rad/s. ' + 'If the value is negative, then the min speed will be arbitrarily close to 0.0.' + ' Previously called min_rot_vel', 0.4) + +exit(gen.generate('dwb_plugins', 'dwb_plugins', 'KinematicParams')) diff --git a/navigations/dwb_plugins/doc/VelocitySpace.png b/navigations/dwb_plugins/doc/VelocitySpace.png new file mode 100755 index 0000000..cb5e660 Binary files /dev/null and b/navigations/dwb_plugins/doc/VelocitySpace.png differ diff --git a/navigations/dwb_plugins/doc/lim_pv.png b/navigations/dwb_plugins/doc/lim_pv.png new file mode 100755 index 0000000..c680bdc Binary files /dev/null and b/navigations/dwb_plugins/doc/lim_pv.png differ diff --git a/navigations/dwb_plugins/doc/std_pv.png b/navigations/dwb_plugins/doc/std_pv.png new file mode 100755 index 0000000..0307645 Binary files /dev/null and b/navigations/dwb_plugins/doc/std_pv.png differ diff --git a/navigations/dwb_plugins/include/dwb_plugins/kinematic_parameters.h b/navigations/dwb_plugins/include/dwb_plugins/kinematic_parameters.h new file mode 100755 index 0000000..5e9b3b7 --- /dev/null +++ b/navigations/dwb_plugins/include/dwb_plugins/kinematic_parameters.h @@ -0,0 +1,113 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef DWB_PLUGINS_KINEMATIC_PARAMETERS_H +#define DWB_PLUGINS_KINEMATIC_PARAMETERS_H + +#include +#include +#include +#include + +namespace dwb_plugins +{ + +/** + * @class KinematicParameters + * @brief A dynamically reconfigurable class containing one representation of the robot's kinematics + */ +class KinematicParameters +{ +public: + KinematicParameters(); + void initialize(const ros::NodeHandle& nh); + + inline double getMinX() { return min_vel_x_; } + inline double getMaxX() { return max_vel_x_; } + inline double getAccX() { return acc_lim_x_; } + inline double getDecelX() { return decel_lim_x_; } + + inline double getMinY() { return min_vel_y_; } + inline double getMaxY() { return max_vel_y_; } + inline double getAccY() { return acc_lim_y_; } + inline double getDecelY() { return decel_lim_y_; } + + inline double getMinSpeedXY() { return min_speed_xy_; } + + inline double getMinTheta() { return -max_vel_theta_; } + inline double getMaxTheta() { return max_vel_theta_; } + inline double getAccTheta() { return acc_lim_theta_; } + inline double getDecelTheta() { return decel_lim_theta_; } + inline double getMinSpeedTheta() { return min_speed_theta_; } + + /** + * @brief Check to see whether the combined x/y/theta velocities are valid + * @return True if the magnitude hypot(x,y) and theta are within the robot's absolute limits + * + * This is based on three parameters: min_speed_xy, max_speed_xy and min_speed_theta. + * The speed is valid if + * 1) The combined magnitude hypot(x,y) is less than max_speed_xy (or max_speed_xy is negative) + * AND + * 2) min_speed_xy is negative or min_speed_theta is negative or + * hypot(x,y) is greater than min_speed_xy or fabs(theta) is greater than min_speed_theta. + * + * In English, it makes sure the diagonal motion is not too fast, + * and that the velocity is moving in some meaningful direction. + * + * In Latin, quod si motus sit signum quaerit et movere ieiunium et significantissime comprehendite. + */ + bool isValidSpeed(double x, double y, double theta); + + using Ptr = std::shared_ptr; +protected: + // For parameter descriptions, see cfg/KinematicParams.cfg + double min_vel_x_, min_vel_y_; + double max_vel_x_, max_vel_y_, max_vel_theta_; + + double min_speed_xy_, max_speed_xy_; + double min_speed_theta_; + + double acc_lim_x_, acc_lim_y_, acc_lim_theta_; + double decel_lim_x_, decel_lim_y_, decel_lim_theta_; + + // Cached square values of min_speed_xy and max_speed_xy + double min_speed_xy_sq_, max_speed_xy_sq_; + + void reconfigureCB(KinematicParamsConfig &config, uint32_t level); + std::shared_ptr > dsrv_; +}; + +} // namespace dwb_plugins + +#endif // DWB_PLUGINS_KINEMATIC_PARAMETERS_H diff --git a/navigations/dwb_plugins/include/dwb_plugins/limited_accel_generator.h b/navigations/dwb_plugins/include/dwb_plugins/limited_accel_generator.h new file mode 100755 index 0000000..806457a --- /dev/null +++ b/navigations/dwb_plugins/include/dwb_plugins/limited_accel_generator.h @@ -0,0 +1,69 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef DWB_PLUGINS_LIMITED_ACCEL_GENERATOR_H +#define DWB_PLUGINS_LIMITED_ACCEL_GENERATOR_H + +#include + +namespace dwb_plugins +{ +/** + * @class LimitedAccelGenerator + * @brief Limits the acceleration in the generated trajectories to a fraction of the simulated time. + */ +class LimitedAccelGenerator : public StandardTrajectoryGenerator +{ +public: + void initialize(ros::NodeHandle& nh) override; + void checkUseDwaParam(const ros::NodeHandle& nh) override; + void startNewIteration(const nav_2d_msgs::Twist2D& current_velocity) override; +protected: + /** + * @brief Calculate the velocity after a set period of time, given the desired velocity and acceleration limits + * + * Unlike the StandardTrajectoryGenerator, the velocity remains constant in the LimitedAccelGenerator + * + * @param cmd_vel Desired velocity + * @param start_vel starting velocity + * @param dt amount of time in seconds + * @return cmd_vel + */ + nav_2d_msgs::Twist2D computeNewVelocity(const nav_2d_msgs::Twist2D& cmd_vel, const nav_2d_msgs::Twist2D& start_vel, + const double dt) override; + double acceleration_time_; +}; +} // namespace dwb_plugins + +#endif // DWB_PLUGINS_LIMITED_ACCEL_GENERATOR_H diff --git a/navigations/dwb_plugins/include/dwb_plugins/one_d_velocity_iterator.h b/navigations/dwb_plugins/include/dwb_plugins/one_d_velocity_iterator.h new file mode 100755 index 0000000..5015d40 --- /dev/null +++ b/navigations/dwb_plugins/include/dwb_plugins/one_d_velocity_iterator.h @@ -0,0 +1,215 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef DWB_PLUGINS_ONE_D_VELOCITY_ITERATOR_H +#define DWB_PLUGINS_ONE_D_VELOCITY_ITERATOR_H + +#include +#include + +namespace dwb_plugins +{ + +const double EPSILON = 1E-5; + +/** + * @brief Given initial conditions and a time, figure out the end velocity + * + * @param v0 Initial velocity + * @param accel The acceleration rate + * @param decel The decceleration rate + * @param dt Delta time - amount of time to project into the future + * @param target target velocity + * @return The velocity dt seconds after v0. + */ +inline double projectVelocity(double v0, double accel, double decel, double dt, double target) +{ + double magnitude; + if (fabs(v0) < EPSILON) + { + // Starting from standstill, always accelerate + if (target >= 0.0) + { + magnitude = fabs(accel); + } + else + { + magnitude = -fabs(accel); + } + } + else if (v0 > 0.0) + { + if (v0 < target) + { + // Acceleration (speed magnitude increases) + magnitude = fabs(accel); + } + else + { + // Deceleration (speed magnitude decreases) + magnitude = -fabs(decel); + } + } + else + { + if (v0 < target) + { + // Deceleration (speed magnitude decreases) + magnitude = fabs(decel); + } + else + { + // Acceleration (speed magnitude increases) + magnitude = -fabs(accel); + } + } + + double v1 = v0 + magnitude * dt; + if (magnitude > 0.0) + { + return std::min(target, v1); + } + else + { + return std::max(target, v1); + } +} + +/** + * @class OneDVelocityIterator + * @brief An iterator for generating a number of samples in a range + * + * In its simplest usage, this gives us N (num_samples) different velocities that are reachable + * given our current velocity. However, there is some fancy logic around zero velocities and + * the min/max velocities + * + * If the current velocity is 2 m/s, and the acceleration limit is 1 m/ss and the acc_time is 1 s, + * this class would provide velocities between 1 m/s and 3 m/s. + * + * + * + */ +class OneDVelocityIterator +{ +public: + /** + * @brief Constructor for the velocity iterator + * + * @param current Current velocity + * @param min Minimum velocity allowable + * @param max Maximum velocity allowable + * @param acc_limit Acceleration Limit + * @param decel_limit Deceleration Limit + * @param num_samples The number of samples to return + */ + OneDVelocityIterator(double current, double min, double max, double acc_limit, double decel_limit, double acc_time, + int num_samples) + { + if (current < min) + { + current = min; + } + else if (current > max) + { + current = max; + } + max_vel_ = projectVelocity(current, acc_limit, decel_limit, acc_time, max); + min_vel_ = projectVelocity(current, acc_limit, decel_limit, acc_time, min); + reset(); + + if (fabs(min_vel_ - max_vel_) < EPSILON) + { + increment_ = 1.0; + return; + } + num_samples = std::max(2, num_samples); + + // e.g. for 4 samples, split distance in 3 even parts + increment_ = (max_vel_ - min_vel_) / std::max(1, (num_samples - 1)); + } + + /** + * @brief Get the next velocity available + */ + double getVelocity() const + { + if (return_zero_now_) return 0.0; + return current_; + } + + /** + * @brief Increment the iterator + */ + OneDVelocityIterator& operator++() + { + if (return_zero_ && current_ < 0.0 && current_ + increment_ > 0.0 && current_ + increment_ <= max_vel_ + EPSILON) + { + return_zero_now_ = true; + return_zero_ = false; + } + else + { + current_ += increment_; + return_zero_now_ = false; + } + return *this; + } + + /** + * @brief Reset back to the first velocity + */ + void reset() + { + current_ = min_vel_; + return_zero_ = true; + return_zero_now_ = false; + } + + /** + * If we have returned all the velocities for this iteration + */ + bool isFinished() const + { + return current_ > max_vel_ + EPSILON; + } + +private: + bool return_zero_, return_zero_now_; + double min_vel_, max_vel_; + double current_; + double increment_; +}; +} // namespace dwb_plugins + +#endif // DWB_PLUGINS_ONE_D_VELOCITY_ITERATOR_H diff --git a/navigations/dwb_plugins/include/dwb_plugins/simple_goal_checker.h b/navigations/dwb_plugins/include/dwb_plugins/simple_goal_checker.h new file mode 100755 index 0000000..954d13d --- /dev/null +++ b/navigations/dwb_plugins/include/dwb_plugins/simple_goal_checker.h @@ -0,0 +1,70 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef DWB_PLUGINS_SIMPLE_GOAL_CHECKER_H +#define DWB_PLUGINS_SIMPLE_GOAL_CHECKER_H + +#include +#include + +namespace dwb_plugins +{ + +/** + * @class SimpleGoalChecker + * @brief Goal Checker plugin that only checks the position difference + * + * This class can be stateful if the stateful parameter is set to true (which it is by default). + * This means that the goal checker will not check if the xy position matches again once it is found to be true. + */ +class SimpleGoalChecker : public dwb_local_planner::GoalChecker +{ +public: + SimpleGoalChecker(); + // Standard GoalChecker Interface + void initialize(const ros::NodeHandle& nh) override; + void reset() override; + bool isGoalReached(const geometry_msgs::Pose2D& query_pose, const geometry_msgs::Pose2D& goal_pose, + const nav_2d_msgs::Twist2D& velocity) override; +protected: + double xy_goal_tolerance_, yaw_goal_tolerance_; + bool stateful_, check_xy_; + + // Cached squared xy_goal_tolerance_ + double xy_goal_tolerance_sq_; +}; + +} // namespace dwb_plugins + +#endif // DWB_PLUGINS_SIMPLE_GOAL_CHECKER_H diff --git a/navigations/dwb_plugins/include/dwb_plugins/standard_traj_generator.h b/navigations/dwb_plugins/include/dwb_plugins/standard_traj_generator.h new file mode 100755 index 0000000..476b799 --- /dev/null +++ b/navigations/dwb_plugins/include/dwb_plugins/standard_traj_generator.h @@ -0,0 +1,148 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef DWB_PLUGINS_STANDARD_TRAJ_GENERATOR_H +#define DWB_PLUGINS_STANDARD_TRAJ_GENERATOR_H + +#include +#include +#include +#include +#include +#include + +namespace dwb_plugins +{ + +/** + * @class StandardTrajectoryGenerator + * @brief Standard DWA-like trajectory generator. + */ +class StandardTrajectoryGenerator : public dwb_local_planner::TrajectoryGenerator +{ +public: + // Standard TrajectoryGenerator interface + void initialize(ros::NodeHandle& nh) override; + void startNewIteration(const nav_2d_msgs::Twist2D& current_velocity) override; + bool hasMoreTwists() override; + nav_2d_msgs::Twist2D nextTwist() override; + + dwb_msgs::Trajectory2D generateTrajectory(const geometry_msgs::Pose2D& start_pose, + const nav_2d_msgs::Twist2D& start_vel, + const nav_2d_msgs::Twist2D& cmd_vel) override; +protected: + /** + * @brief Initialize the VelocityIterator pointer. Put in its own function for easy overriding + */ + virtual void initializeIterator(ros::NodeHandle& nh); + + /** + * @brief Check if the deprecated use_dwa parameter is set to the functionality that matches this class + * + * The functionality guarded by the use_dwa parameter has been split between this class and the derived + * LimitedAccelGenerator. If use_dwa was false, this class should be used. If it was true, then LimitedAccelGenerator. + * If this is NOT the case, this function will throw an exception. + */ + virtual void checkUseDwaParam(const ros::NodeHandle& nh); + + /** + * @brief Calculate the velocity after a set period of time, given the desired velocity and acceleration limits + * + * @param cmd_vel Desired velocity + * @param start_vel starting velocity + * @param dt amount of time in seconds + * @return new velocity after dt seconds + */ + virtual nav_2d_msgs::Twist2D computeNewVelocity(const nav_2d_msgs::Twist2D& cmd_vel, + const nav_2d_msgs::Twist2D& start_vel, + const double dt); + + /** + * @brief Use the robot's kinematic model to predict new positions for the robot + * + * @param start_pose Starting pose + * @param vel Actual robot velocity (assumed to be within acceleration limits) + * @param dt amount of time in seconds + * @return New pose after dt seconds + */ + virtual geometry_msgs::Pose2D computeNewPosition(const geometry_msgs::Pose2D start_pose, + const nav_2d_msgs::Twist2D& vel, + const double dt); + + + /** + * @brief Compute an array of time deltas between the points in the generated trajectory. + * + * @param cmd_vel The desired command velocity + * @return vector of the difference between each time step in the generated trajectory + * + * If we are discretizing by time, the returned vector will be the same constant time_granularity + * for all cmd_vels. Otherwise, you will get times based on the linear/angular granularity. + * + * Right now the vector contains a single value repeated many times, but this method could be overridden + * to allow for dynamic spacing + */ + virtual std::vector getTimeSteps(const nav_2d_msgs::Twist2D& cmd_vel); + + KinematicParameters::Ptr kinematics_; + std::shared_ptr velocity_iterator_; + + double sim_time_; + + // Sampling Parameters + bool discretize_by_time_; + double time_granularity_; ///< If discretizing by time, the amount of time between each point in the traj + double linear_granularity_; ///< If not discretizing by time, the amount of linear space between points + double angular_granularity_; ///< If not discretizing by time, the amount of angular space between points + + /* Backwards Compatibility Parameter: include_last_point + * + * dwa had an off-by-one error built into it. + * It generated N trajectory points, where N = ceil(sim_time / time_delta). + * If for example, sim_time=3.0 and time_delta=1.5, it would generate trajectories with 2 points, which + * indeed were time_delta seconds apart. However, the points would be at t=0 and t=1.5, and thus the + * actual sim_time was much less than advertised. + * + * This is remedied by adding one final point at t=sim_time, but only if include_last_point_ is true. + * + * Nothing I could find actually used the time_delta variable or seemed to care that the trajectories + * were not projected out as far as they intended. + */ + bool include_last_point_; +}; + + +} // namespace dwb_plugins + +#endif // DWB_PLUGINS_STANDARD_TRAJ_GENERATOR_H diff --git a/navigations/dwb_plugins/include/dwb_plugins/stopped_goal_checker.h b/navigations/dwb_plugins/include/dwb_plugins/stopped_goal_checker.h new file mode 100755 index 0000000..a1caae0 --- /dev/null +++ b/navigations/dwb_plugins/include/dwb_plugins/stopped_goal_checker.h @@ -0,0 +1,62 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef DWB_PLUGINS_STOPPED_GOAL_CHECKER_H +#define DWB_PLUGINS_STOPPED_GOAL_CHECKER_H + +#include +#include + +namespace dwb_plugins +{ + +/** + * @class StoppedGoalChecker + * @brief Goal Checker plugin that checks the position difference and velocity + */ +class StoppedGoalChecker : public SimpleGoalChecker +{ +public: + StoppedGoalChecker(); + // Standard GoalChecker Interface + void initialize(const ros::NodeHandle& nh) override; + bool isGoalReached(const geometry_msgs::Pose2D& query_pose, const geometry_msgs::Pose2D& goal_pose, + const nav_2d_msgs::Twist2D& velocity) override; +protected: + double rot_stopped_velocity_, trans_stopped_velocity_; +}; + +} // namespace dwb_plugins + +#endif // DWB_PLUGINS_STOPPED_GOAL_CHECKER_H diff --git a/navigations/dwb_plugins/include/dwb_plugins/velocity_iterator.h b/navigations/dwb_plugins/include/dwb_plugins/velocity_iterator.h new file mode 100755 index 0000000..4a97df3 --- /dev/null +++ b/navigations/dwb_plugins/include/dwb_plugins/velocity_iterator.h @@ -0,0 +1,55 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef DWB_PLUGINS_VELOCITY_ITERATOR_H +#define DWB_PLUGINS_VELOCITY_ITERATOR_H + +#include +#include +#include + +namespace dwb_plugins +{ +class VelocityIterator +{ +public: + virtual ~VelocityIterator() {} + virtual void initialize(ros::NodeHandle& nh, KinematicParameters::Ptr kinematics) = 0; + virtual void startNewIteration(const nav_2d_msgs::Twist2D& current_velocity, double dt) = 0; + virtual bool hasMoreTwists() = 0; + virtual nav_2d_msgs::Twist2D nextTwist() = 0; +}; +} // namespace dwb_plugins + +#endif // DWB_PLUGINS_VELOCITY_ITERATOR_H diff --git a/navigations/dwb_plugins/include/dwb_plugins/xy_theta_iterator.h b/navigations/dwb_plugins/include/dwb_plugins/xy_theta_iterator.h new file mode 100755 index 0000000..10c5288 --- /dev/null +++ b/navigations/dwb_plugins/include/dwb_plugins/xy_theta_iterator.h @@ -0,0 +1,62 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef DWB_PLUGINS_XY_THETA_ITERATOR_H +#define DWB_PLUGINS_XY_THETA_ITERATOR_H + +#include +#include +#include + +namespace dwb_plugins +{ +class XYThetaIterator : public VelocityIterator +{ +public: + XYThetaIterator() : kinematics_(nullptr), x_it_(nullptr), y_it_(nullptr), th_it_(nullptr) {} + void initialize(ros::NodeHandle& nh, KinematicParameters::Ptr kinematics) override; + void startNewIteration(const nav_2d_msgs::Twist2D& current_velocity, double dt) override; + bool hasMoreTwists() override; + nav_2d_msgs::Twist2D nextTwist() override; +protected: + virtual bool isValidVelocity(); + void iterateToValidVelocity(); + int vx_samples_, vy_samples_, vtheta_samples_; + KinematicParameters::Ptr kinematics_; + + std::shared_ptr x_it_, y_it_, th_it_; +}; +} // namespace dwb_plugins + +#endif // DWB_PLUGINS_XY_THETA_ITERATOR_H diff --git a/navigations/dwb_plugins/package.xml b/navigations/dwb_plugins/package.xml new file mode 100755 index 0000000..537ac93 --- /dev/null +++ b/navigations/dwb_plugins/package.xml @@ -0,0 +1,30 @@ + + + dwb_plugins + 0.3.0 + + Standard implementations of the GoalChecker + and TrajectoryGenerators for dwb_local_planner + + + David V. Lu!! + + BSD + + catkin + angles + dwb_local_planner + dynamic_reconfigure + nav_2d_msgs + nav_2d_utils + nav_core2 + pluginlib + roscpp + roslint + rostest + rosunit + + + + + diff --git a/navigations/dwb_plugins/plugins.xml b/navigations/dwb_plugins/plugins.xml new file mode 100755 index 0000000..88d59ae --- /dev/null +++ b/navigations/dwb_plugins/plugins.xml @@ -0,0 +1,20 @@ + + + + + + + + + + + + + + + + + + + + diff --git a/navigations/dwb_plugins/src/kinematic_parameters.cpp b/navigations/dwb_plugins/src/kinematic_parameters.cpp new file mode 100755 index 0000000..0547a16 --- /dev/null +++ b/navigations/dwb_plugins/src/kinematic_parameters.cpp @@ -0,0 +1,126 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include +#include +#include + +using nav_2d_utils::moveDeprecatedParameter; +namespace dwb_plugins +{ + +const double EPSILON = 1E-5; + +/** + * @brief Helper function to set the deceleration to the negative acceleration if it was not already set. + * @param nh NodeHandle + * @param dimension String representing the dimension, used in constructing parameter names + */ +void setDecelerationAsNeeded(const ros::NodeHandle& nh, const std::string dimension) +{ + std::string decel_param = "decel_lim_" + dimension; + if (nh.hasParam(decel_param)) return; + + std::string accel_param = "acc_lim_" + dimension; + if (!nh.hasParam(accel_param)) return; + + double accel; + nh.getParam(accel_param, accel); + nh.setParam(decel_param, -accel); +} + +KinematicParameters::KinematicParameters() : + min_vel_x_(0.0), min_vel_y_(0.0), max_vel_x_(0.0), max_vel_y_(0.0), max_vel_theta_(0.0), + min_speed_xy_(0.0), max_speed_xy_(0.0), min_speed_theta_(0.0), + acc_lim_x_(0.0), acc_lim_y_(0.0), acc_lim_theta_(0.0), + decel_lim_x_(0.0), decel_lim_y_(0.0), decel_lim_theta_(0.0), + min_speed_xy_sq_(0.0), max_speed_xy_sq_(0.0), + dsrv_(nullptr) +{ +} + +void KinematicParameters::initialize(const ros::NodeHandle& nh) +{ + // Special handling for renamed parameters + moveDeprecatedParameter(nh, "max_vel_theta", "max_rot_vel"); + moveDeprecatedParameter(nh, "min_speed_xy", "min_trans_vel"); + moveDeprecatedParameter(nh, "max_speed_xy", "max_trans_vel"); + moveDeprecatedParameter(nh, "min_speed_theta", "min_rot_vel"); + + // Set the deceleration parameters to negative the acceleration if the deceleration not already specified + setDecelerationAsNeeded(nh, "x"); + setDecelerationAsNeeded(nh, "y"); + setDecelerationAsNeeded(nh, "theta"); + + // the rest of the initial values are loaded through the dynamic reconfigure mechanisms + dsrv_ = std::make_shared >(nh); + dynamic_reconfigure::Server::CallbackType cb = + boost::bind(&KinematicParameters::reconfigureCB, this, _1, _2); + dsrv_->setCallback(cb); +} + +void KinematicParameters::reconfigureCB(KinematicParamsConfig &config, uint32_t level) +{ + min_vel_x_ = config.min_vel_x; + min_vel_y_ = config.min_vel_y; + max_vel_x_ = config.max_vel_x; + max_vel_y_ = config.max_vel_y; + max_vel_theta_ = config.max_vel_theta; + + min_speed_xy_ = config.min_speed_xy; + max_speed_xy_ = config.max_speed_xy; + min_speed_xy_sq_ = min_speed_xy_ * min_speed_xy_; + max_speed_xy_sq_ = max_speed_xy_ * max_speed_xy_; + min_speed_theta_ = config.min_speed_theta; + + acc_lim_x_ = config.acc_lim_x; + acc_lim_y_ = config.acc_lim_y; + acc_lim_theta_ = config.acc_lim_theta; + decel_lim_x_ = config.decel_lim_x; + decel_lim_y_ = config.decel_lim_y; + decel_lim_theta_ = config.decel_lim_theta; +} + +bool KinematicParameters::isValidSpeed(double x, double y, double theta) +{ + double vmag_sq = x * x + y * y; + if (max_speed_xy_ >= 0.0 && vmag_sq > max_speed_xy_sq_ + EPSILON) return false; + if (min_speed_xy_ >= 0.0 && vmag_sq + EPSILON < min_speed_xy_sq_ && + min_speed_theta_ >= 0.0 && fabs(theta) + EPSILON < min_speed_theta_) return false; + if (vmag_sq == 0.0 && theta == 0.0) return false; + return true; +} + +} // namespace dwb_plugins diff --git a/navigations/dwb_plugins/src/limited_accel_generator.cpp b/navigations/dwb_plugins/src/limited_accel_generator.cpp new file mode 100755 index 0000000..c7ae92f --- /dev/null +++ b/navigations/dwb_plugins/src/limited_accel_generator.cpp @@ -0,0 +1,92 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include +#include +#include +#include + +namespace dwb_plugins +{ + +void LimitedAccelGenerator::initialize(ros::NodeHandle& nh) +{ + StandardTrajectoryGenerator::initialize(nh); + if (nh.hasParam("sim_period")) + { + nh.getParam("sim_period", acceleration_time_); + } + else + { + double controller_frequency = nav_2d_utils::searchAndGetParam(nh, "controller_frequency", 20.0); + if (controller_frequency > 0) + { + acceleration_time_ = 1.0 / controller_frequency; + } + else + { + ROS_WARN_NAMED("LimitedAccelGenerator", "A controller_frequency less than or equal to 0 has been set. " + "Ignoring the parameter, assuming a rate of 20Hz"); + acceleration_time_ = 0.05; + } + } +} + +void LimitedAccelGenerator::checkUseDwaParam(const ros::NodeHandle& nh) +{ + bool use_dwa; + nh.param("use_dwa", use_dwa, true); + if (!use_dwa) + { + throw nav_core2::PlannerException("Deprecated parameter use_dwa set to false. " + "Please use StandardTrajectoryGenerator for that functionality."); + } +} + +void LimitedAccelGenerator::startNewIteration(const nav_2d_msgs::Twist2D& current_velocity) +{ + // Limit our search space to just those within the limited acceleration_time + velocity_iterator_->startNewIteration(current_velocity, acceleration_time_); +} + +nav_2d_msgs::Twist2D LimitedAccelGenerator::computeNewVelocity(const nav_2d_msgs::Twist2D& cmd_vel, + const nav_2d_msgs::Twist2D& start_vel, const double dt) +{ + return cmd_vel; +} + +} // namespace dwb_plugins + +PLUGINLIB_EXPORT_CLASS(dwb_plugins::LimitedAccelGenerator, dwb_local_planner::TrajectoryGenerator) diff --git a/navigations/dwb_plugins/src/simple_goal_checker.cpp b/navigations/dwb_plugins/src/simple_goal_checker.cpp new file mode 100755 index 0000000..fe17ee8 --- /dev/null +++ b/navigations/dwb_plugins/src/simple_goal_checker.cpp @@ -0,0 +1,84 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include +#include + +namespace dwb_plugins +{ + +SimpleGoalChecker::SimpleGoalChecker() : + xy_goal_tolerance_(0.25), yaw_goal_tolerance_(0.25), stateful_(true), check_xy_(true), xy_goal_tolerance_sq_(0.0625) +{ +} + +void SimpleGoalChecker::initialize(const ros::NodeHandle& nh) +{ + nh.param("xy_goal_tolerance", xy_goal_tolerance_, 0.25); + nh.param("yaw_goal_tolerance", yaw_goal_tolerance_, 0.25); + nh.param("stateful", stateful_, true); + xy_goal_tolerance_sq_ = xy_goal_tolerance_ * xy_goal_tolerance_; +} + +void SimpleGoalChecker::reset() +{ + check_xy_ = true; +} + +bool SimpleGoalChecker::isGoalReached(const geometry_msgs::Pose2D& query_pose, const geometry_msgs::Pose2D& goal_pose, + const nav_2d_msgs::Twist2D& velocity) +{ + if (check_xy_) + { + double dx = query_pose.x - goal_pose.x, + dy = query_pose.y - goal_pose.y; + if (dx * dx + dy * dy > xy_goal_tolerance_sq_) + { + return false; + } + // We are within the window + // If we are stateful, change the state. + if (stateful_) + { + check_xy_ = false; + } + } + double dyaw = angles::shortest_angular_distance(query_pose.theta, goal_pose.theta); + return fabs(dyaw) < yaw_goal_tolerance_; +} + +} // namespace dwb_plugins + +PLUGINLIB_EXPORT_CLASS(dwb_plugins::SimpleGoalChecker, dwb_local_planner::GoalChecker) diff --git a/navigations/dwb_plugins/src/standard_traj_generator.cpp b/navigations/dwb_plugins/src/standard_traj_generator.cpp new file mode 100755 index 0000000..10668ff --- /dev/null +++ b/navigations/dwb_plugins/src/standard_traj_generator.cpp @@ -0,0 +1,203 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +using nav_2d_utils::loadParameterWithDeprecation; + +namespace dwb_plugins +{ + +void StandardTrajectoryGenerator::initialize(ros::NodeHandle& nh) +{ + kinematics_ = std::make_shared(); + kinematics_->initialize(nh); + initializeIterator(nh); + + nh.param("sim_time", sim_time_, 1.7); + checkUseDwaParam(nh); + + nh.param("include_last_point", include_last_point_, true); + + /* + * If discretize_by_time, then sim_granularity represents the amount of time that should be between + * two successive points on the trajectory. + * + * If discretize_by_time is false, then sim_granularity is the maximum amount of distance between + * two successive points on the trajectory, and angular_sim_granularity is the maximum amount of + * angular distance between two successive points. + */ + nh.param("discretize_by_time", discretize_by_time_, false); + if (discretize_by_time_) + { + time_granularity_ = loadParameterWithDeprecation(nh, "time_granularity", "sim_granularity", 0.025); + } + else + { + linear_granularity_ = loadParameterWithDeprecation(nh, "linear_granularity", "sim_granularity", 0.025); + angular_granularity_ = loadParameterWithDeprecation(nh, "angular_granularity", "angular_sim_granularity", 0.1); + } +} + +void StandardTrajectoryGenerator::initializeIterator(ros::NodeHandle& nh) +{ + velocity_iterator_ = std::make_shared(); + velocity_iterator_->initialize(nh, kinematics_); +} + +void StandardTrajectoryGenerator::checkUseDwaParam(const ros::NodeHandle& nh) +{ + bool use_dwa; + nh.param("use_dwa", use_dwa, false); + if (use_dwa) + { + throw nav_core2::PlannerException("Deprecated parameter use_dwa set to true. " + "Please use LimitedAccelGenerator for that functionality."); + } +} + +void StandardTrajectoryGenerator::startNewIteration(const nav_2d_msgs::Twist2D& current_velocity) +{ + velocity_iterator_->startNewIteration(current_velocity, sim_time_); +} + +bool StandardTrajectoryGenerator::hasMoreTwists() +{ + return velocity_iterator_->hasMoreTwists(); +} + +nav_2d_msgs::Twist2D StandardTrajectoryGenerator::nextTwist() +{ + return velocity_iterator_->nextTwist(); +} + +std::vector StandardTrajectoryGenerator::getTimeSteps(const nav_2d_msgs::Twist2D& cmd_vel) +{ + std::vector steps; + if (discretize_by_time_) + { + steps.resize(ceil(sim_time_ / time_granularity_)); + } + else // discretize by distance + { + double vmag = hypot(cmd_vel.x, cmd_vel.y); + + // the distance the robot would travel in sim_time if it did not change velocity + double projected_linear_distance = vmag * sim_time_; + + // the angle the robot would rotate in sim_time + double projected_angular_distance = fabs(cmd_vel.theta) * sim_time_; + + // Pick the maximum of the two + int num_steps = ceil(std::max(projected_linear_distance / linear_granularity_, + projected_angular_distance / angular_granularity_)); + steps.resize(num_steps); + } + if (steps.size() == 0) + { + steps.resize(1); + } + std::fill(steps.begin(), steps.end(), sim_time_ / steps.size()); + return steps; +} + +dwb_msgs::Trajectory2D StandardTrajectoryGenerator::generateTrajectory(const geometry_msgs::Pose2D& start_pose, + const nav_2d_msgs::Twist2D& start_vel, // from odometry + const nav_2d_msgs::Twist2D& cmd_vel) // twist = traj_generator_->nextTwist(); +{ + dwb_msgs::Trajectory2D traj; + traj.velocity = cmd_vel; + + // simulate the trajectory + geometry_msgs::Pose2D pose = start_pose; + nav_2d_msgs::Twist2D vel = start_vel; + double running_time = 0.0; + std::vector steps = getTimeSteps(cmd_vel); + + for (double dt : steps) + { + traj.poses.push_back(pose); + traj.time_offsets.push_back(ros::Duration(running_time)); + // calculate velocities + vel = computeNewVelocity(cmd_vel, vel, dt); + + // update the position of the robot using the velocities passed in + pose = computeNewPosition(pose, vel, dt); + running_time += dt; + } // end for simulation steps + + if (include_last_point_) + { + traj.poses.push_back(pose); + traj.time_offsets.push_back(ros::Duration(running_time)); + } + + return traj; +} + +/** + * change vel using acceleration limits to converge towards sample_target-vel + */ +nav_2d_msgs::Twist2D StandardTrajectoryGenerator::computeNewVelocity(const nav_2d_msgs::Twist2D& cmd_vel, + const nav_2d_msgs::Twist2D& start_vel, const double dt) +{ + nav_2d_msgs::Twist2D new_vel; + new_vel.x = projectVelocity(start_vel.x, kinematics_->getAccX(), kinematics_->getDecelX(), dt, cmd_vel.x); + new_vel.y = projectVelocity(start_vel.y, kinematics_->getAccY(), kinematics_->getDecelY(), dt, cmd_vel.y); + new_vel.theta = projectVelocity(start_vel.theta, kinematics_->getAccTheta(), kinematics_->getDecelTheta(), + dt, cmd_vel.theta); + return new_vel; +} + +geometry_msgs::Pose2D StandardTrajectoryGenerator::computeNewPosition(const geometry_msgs::Pose2D start_pose, + const nav_2d_msgs::Twist2D& vel, const double dt) +{ + geometry_msgs::Pose2D new_pose; + new_pose.x = start_pose.x + (vel.x * cos(start_pose.theta) + vel.y * cos(M_PI_2 + start_pose.theta)) * dt; + new_pose.y = start_pose.y + (vel.x * sin(start_pose.theta) + vel.y * sin(M_PI_2 + start_pose.theta)) * dt; + new_pose.theta = start_pose.theta + vel.theta * dt; + return new_pose; +} + +} // namespace dwb_plugins + +PLUGINLIB_EXPORT_CLASS(dwb_plugins::StandardTrajectoryGenerator, dwb_local_planner::TrajectoryGenerator) diff --git a/navigations/dwb_plugins/src/stopped_goal_checker.cpp b/navigations/dwb_plugins/src/stopped_goal_checker.cpp new file mode 100755 index 0000000..731a576 --- /dev/null +++ b/navigations/dwb_plugins/src/stopped_goal_checker.cpp @@ -0,0 +1,67 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include + +namespace dwb_plugins +{ + +StoppedGoalChecker::StoppedGoalChecker() : + SimpleGoalChecker(), rot_stopped_velocity_(0.25), trans_stopped_velocity_(0.25) +{ +} + +void StoppedGoalChecker::initialize(const ros::NodeHandle& nh) +{ + SimpleGoalChecker::initialize(nh); + nh.param("rot_stopped_velocity", rot_stopped_velocity_, 0.25); + nh.param("trans_stopped_velocity", trans_stopped_velocity_, 0.25); +} + +bool StoppedGoalChecker::isGoalReached(const geometry_msgs::Pose2D& query_pose, const geometry_msgs::Pose2D& goal_pose, + const nav_2d_msgs::Twist2D& velocity) +{ + bool ret = SimpleGoalChecker::isGoalReached(query_pose, goal_pose, velocity); + if (!ret) + { + return ret; + } + return fabs(velocity.theta) <= rot_stopped_velocity_ + && fabs(velocity.x) <= trans_stopped_velocity_ && fabs(velocity.y) <= trans_stopped_velocity_; +} + +} // namespace dwb_plugins + +PLUGINLIB_EXPORT_CLASS(dwb_plugins::StoppedGoalChecker, dwb_local_planner::GoalChecker) diff --git a/navigations/dwb_plugins/src/xy_theta_iterator.cpp b/navigations/dwb_plugins/src/xy_theta_iterator.cpp new file mode 100755 index 0000000..a11ebc2 --- /dev/null +++ b/navigations/dwb_plugins/src/xy_theta_iterator.cpp @@ -0,0 +1,107 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include +#include + +namespace dwb_plugins +{ +void XYThetaIterator::initialize(ros::NodeHandle& nh, KinematicParameters::Ptr kinematics) +{ + kinematics_ = kinematics; + nh.param("vx_samples", vx_samples_, 20); + nh.param("vy_samples", vy_samples_, 5); + vtheta_samples_ = nav_2d_utils::loadParameterWithDeprecation(nh, "vtheta_samples", "vth_samples", 20); +} + +void XYThetaIterator::startNewIteration(const nav_2d_msgs::Twist2D& current_velocity, double dt) +{ + x_it_ = std::make_shared(current_velocity.x, kinematics_->getMinX(), kinematics_->getMaxX(), + kinematics_->getAccX(), kinematics_->getDecelX(), dt, vx_samples_); + y_it_ = std::make_shared(current_velocity.y, kinematics_->getMinY(), kinematics_->getMaxY(), + kinematics_->getAccY(), kinematics_->getDecelY(), dt, vy_samples_); + th_it_ = std::make_shared(current_velocity.theta, + kinematics_->getMinTheta(), kinematics_->getMaxTheta(), + kinematics_->getAccTheta(), kinematics_->getDecelTheta(), + dt, vtheta_samples_); + if (!isValidVelocity()) + { + iterateToValidVelocity(); + } +} + +bool XYThetaIterator::isValidVelocity() +{ + return kinematics_->isValidSpeed(x_it_->getVelocity(), y_it_->getVelocity(), th_it_->getVelocity()); +} + +bool XYThetaIterator::hasMoreTwists() +{ + return x_it_ && !x_it_->isFinished(); +} + + +nav_2d_msgs::Twist2D XYThetaIterator::nextTwist() +{ + nav_2d_msgs::Twist2D velocity; + velocity.x = x_it_->getVelocity(); + velocity.y = y_it_->getVelocity(); + velocity.theta = th_it_->getVelocity(); + iterateToValidVelocity(); + + return velocity; +} + +void XYThetaIterator::iterateToValidVelocity() +{ + bool valid = false; + while (!valid && hasMoreTwists()) + { + ++(*th_it_); + if (th_it_->isFinished()) + { + th_it_->reset(); + ++(*y_it_); + if (y_it_->isFinished()) + { + y_it_->reset(); + ++(*x_it_); + } + } + valid = isValidVelocity(); + } +} + +} // namespace dwb_plugins diff --git a/navigations/dwb_plugins/test/goal_checker.cpp b/navigations/dwb_plugins/test/goal_checker.cpp new file mode 100755 index 0000000..0b28db4 --- /dev/null +++ b/navigations/dwb_plugins/test/goal_checker.cpp @@ -0,0 +1,107 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ +#include +#include +#include + +using dwb_plugins::SimpleGoalChecker; +using dwb_plugins::StoppedGoalChecker; + +void checkMacro(dwb_local_planner::GoalChecker& gc, + double x0, double y0, double theta0, + double x1, double y1, double theta1, + double xv, double yv, double thetav, + bool expected_result) +{ + gc.reset(); + geometry_msgs::Pose2D pose0, pose1; + pose0.x = x0; + pose0.y = y0; + pose0.theta = theta0; + pose1.x = x1; + pose1.y = y1; + pose1.theta = theta1; + nav_2d_msgs::Twist2D v; + v.x = xv; + v.y = yv; + v.theta = thetav; + if (expected_result) + EXPECT_TRUE(gc.isGoalReached(pose0, pose1, v)); + else + EXPECT_FALSE(gc.isGoalReached(pose0, pose1, v)); +} + +void sameResult(dwb_local_planner::GoalChecker& gc0, dwb_local_planner::GoalChecker& gc1, + double x0, double y0, double theta0, + double x1, double y1, double theta1, + double xv, double yv, double thetav, + bool expected_result) +{ + checkMacro(gc0, x0, y0, theta0, x1, y1, theta1, xv, yv, thetav, expected_result); + checkMacro(gc1, x0, y0, theta0, x1, y1, theta1, xv, yv, thetav, expected_result); +} + +void trueFalse(dwb_local_planner::GoalChecker& gc0, dwb_local_planner::GoalChecker& gc1, + double x0, double y0, double theta0, + double x1, double y1, double theta1, + double xv, double yv, double thetav) +{ + checkMacro(gc0, x0, y0, theta0, x1, y1, theta1, xv, yv, thetav, true); + checkMacro(gc1, x0, y0, theta0, x1, y1, theta1, xv, yv, thetav, false); +} + +TEST(VelocityIterator, two_checks) +{ + ros::NodeHandle x; + SimpleGoalChecker gc; + StoppedGoalChecker sgc; + gc.initialize(x); + sgc.initialize(x); + sameResult(gc, sgc, 0, 0, 0, 0, 0, 0, 0, 0, 0, true); + sameResult(gc, sgc, 0, 0, 0, 1, 0, 0, 0, 0, 0, false); + sameResult(gc, sgc, 0, 0, 0, 0, 1, 0, 0, 0, 0, false); + sameResult(gc, sgc, 0, 0, 0, 0, 0, 1, 0, 0, 0, false); + sameResult(gc, sgc, 0, 0, 3.14, 0, 0, -3.14, 0, 0, 0, true); + trueFalse(gc, sgc, 0, 0, 3.14, 0, 0, -3.14, 1, 0, 0); + trueFalse(gc, sgc, 0, 0, 0, 0, 0, 0, 1, 0, 0); + trueFalse(gc, sgc, 0, 0, 0, 0, 0, 0, 0, 1, 0); + trueFalse(gc, sgc, 0, 0, 0, 0, 0, 0, 0, 0, 1); +} + +int main(int argc, char **argv) +{ + ros::init(argc, argv, "goal_checker"); + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/navigations/dwb_plugins/test/goal_checker.launch b/navigations/dwb_plugins/test/goal_checker.launch new file mode 100755 index 0000000..d4f0b69 --- /dev/null +++ b/navigations/dwb_plugins/test/goal_checker.launch @@ -0,0 +1,3 @@ + + + diff --git a/navigations/dwb_plugins/test/twist_gen.cpp b/navigations/dwb_plugins/test/twist_gen.cpp new file mode 100755 index 0000000..f7c9a58 --- /dev/null +++ b/navigations/dwb_plugins/test/twist_gen.cpp @@ -0,0 +1,422 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ +#include +#include +#include +#include +#include +#include + +using dwb_plugins::StandardTrajectoryGenerator; + +geometry_msgs::Pose2D origin; +nav_2d_msgs::Twist2D zero; +nav_2d_msgs::Twist2D forward; + +void checkLimits(const std::vector& twists, + double exp_min_x, double exp_max_x, double exp_min_y, double exp_max_y, + double exp_min_theta, double exp_max_theta, + double exp_max_xy = -1.0, + double exp_min_xy = -1.0, double exp_min_speed_theta = -1.0) +{ + ASSERT_GT(twists.size(), 0U); + nav_2d_msgs::Twist2D first = twists[0]; + + double min_x = first.x, max_x = first.x, min_y = first.y, max_y = first.y; + double min_theta = first.theta, max_theta = first.theta; + double max_xy = hypot(first.x, first.y); + + for (nav_2d_msgs::Twist2D twist : twists) + { + min_x = std::min(min_x, twist.x); + min_y = std::min(min_y, twist.y); + min_theta = std::min(min_theta, twist.theta); + max_x = std::max(max_x, twist.x); + max_y = std::max(max_y, twist.y); + max_theta = std::max(max_theta, twist.theta); + double hyp = hypot(twist.x, twist.y); + max_xy = std::max(max_xy, hyp); + + if (exp_min_xy >= 0 && exp_min_speed_theta >= 0) + { + EXPECT_TRUE(fabs(twist.theta) >= exp_min_speed_theta || hyp >= exp_min_xy); + } + } + EXPECT_DOUBLE_EQ(min_x, exp_min_x); + EXPECT_DOUBLE_EQ(max_x, exp_max_x); + EXPECT_DOUBLE_EQ(min_y, exp_min_y); + EXPECT_DOUBLE_EQ(max_y, exp_max_y); + EXPECT_DOUBLE_EQ(min_theta, exp_min_theta); + EXPECT_DOUBLE_EQ(max_theta, exp_max_theta); + if (exp_max_xy >= 0) + { + EXPECT_DOUBLE_EQ(max_xy, exp_max_xy); + } +} + +TEST(VelocityIterator, standard_gen) +{ + ros::NodeHandle nh("st_gen"); + StandardTrajectoryGenerator gen; + gen.initialize(nh); + std::vector twists = gen.getTwists(zero); + EXPECT_EQ(twists.size(), 1926U); + checkLimits(twists, 0.0, 0.55, -0.1, 0.1, -1.0, 1.0, 0.55, 0.1, 0.4); +} + +TEST(VelocityIterator, max_xy) +{ + ros::NodeHandle nh("max_xy"); + nh.setParam("max_speed_xy", 1.0); + StandardTrajectoryGenerator gen; + gen.initialize(nh); + + std::vector twists = gen.getTwists(zero); + // Expect more twists since max_speed_xy is now beyond feasible limits + EXPECT_EQ(twists.size(), 2010U); + checkLimits(twists, 0.0, 0.55, -0.1, 0.1, -1.0, 1.0, hypot(0.55, 0.1)); +} + +TEST(VelocityIterator, min_xy) +{ + ros::NodeHandle nh("min_xy"); + nh.setParam("min_speed_xy", -1); + StandardTrajectoryGenerator gen; + gen.initialize(nh); + std::vector twists = gen.getTwists(zero); + // Expect even more since theres no min_speed_xy + EXPECT_EQ(twists.size(), 2015U); + checkLimits(twists, 0.0, 0.55, -0.1, 0.1, -1.0, 1.0); +} + +TEST(VelocityIterator, min_theta) +{ + ros::NodeHandle nh("min_theta"); + nh.setParam("min_speed_theta", -1); + StandardTrajectoryGenerator gen; + gen.initialize(nh); + std::vector twists = gen.getTwists(zero); + // Expect even more since theres no min_speed_xy + EXPECT_EQ(twists.size(), 2015U); + checkLimits(twists, 0.0, 0.55, -0.1, 0.1, -1.0, 1.0); +} + +TEST(VelocityIterator, no_limits) +{ + ros::NodeHandle nh("no_limits"); + nh.setParam("max_speed_xy", -1.0); + nh.setParam("min_speed_xy", -1); + nh.setParam("min_speed_theta", -1); + StandardTrajectoryGenerator gen; + gen.initialize(nh); + std::vector twists = gen.getTwists(zero); + // vx_samples * vtheta_samples * vy_samples + added zero theta samples - (0,0,0) + EXPECT_EQ(twists.size(), static_cast(20 * 20 * 5 + 100 - 1)); + checkLimits(twists, 0.0, 0.55, -0.1, 0.1, -1.0, 1.0, hypot(0.55, 0.1), 0.0, 0.0); +} + +TEST(VelocityIterator, no_limits_samples) +{ + ros::NodeHandle nh("no_limits_samples"); + nh.setParam("max_speed_xy", -1.0); + nh.setParam("min_speed_xy", -1); + nh.setParam("min_speed_theta", -1); + int x_samples = 10, y_samples = 3, theta_samples = 5; + nh.setParam("vx_samples", x_samples); + nh.setParam("vy_samples", y_samples); + nh.setParam("vtheta_samples", theta_samples); + StandardTrajectoryGenerator gen; + gen.initialize(nh); + std::vector twists = gen.getTwists(zero); + EXPECT_EQ(twists.size(), static_cast(x_samples * y_samples * theta_samples - 1)); + checkLimits(twists, 0.0, 0.55, -0.1, 0.1, -1.0, 1.0, hypot(0.55, 0.1), 0.0, 0.0); +} + +TEST(VelocityIterator, dwa_gen_exception) +{ + ros::NodeHandle nh("dwa_gen_exception"); + nh.setParam("use_dwa", true); + StandardTrajectoryGenerator gen; + EXPECT_THROW(gen.initialize(nh), nav_core2::PlannerException); +} + +TEST(VelocityIterator, no_dwa_gen_exception) +{ + ros::NodeHandle nh("no_dwa_gen_exception"); + nh.setParam("use_dwa", false); + dwb_plugins::LimitedAccelGenerator gen; + EXPECT_THROW(gen.initialize(nh), nav_core2::PlannerException); +} + +TEST(VelocityIterator, dwa_gen) +{ + ros::NodeHandle nh("dwa_gen"); + nh.setParam("use_dwa", true); + nh.setParam("min_speed_theta", -1); + dwb_plugins::LimitedAccelGenerator gen; + gen.initialize(nh); + std::vector twists = gen.getTwists(zero); + // Same as no-limits since everything is within our velocity limits + EXPECT_EQ(twists.size(), static_cast(20 * 20 * 5 + 100 - 1)); + checkLimits(twists, 0.0, 0.125, -0.1, 0.1, -0.16, 0.16, hypot(0.125, 0.1), 0.0, 0.1); +} + +TEST(VelocityIterator, dwa_gen_no_param) +{ + ros::NodeHandle nh("dwa_gen_no_param"); + nh.setParam("min_speed_theta", -1); + dwb_plugins::LimitedAccelGenerator gen; + gen.initialize(nh); + std::vector twists = gen.getTwists(zero); + EXPECT_EQ(twists.size(), static_cast(20 * 20 * 5 + 100 - 1)); + checkLimits(twists, 0.0, 0.125, -0.1, 0.1, -0.16, 0.16, hypot(0.125, 0.1), 0.0, 0.1); +} + +TEST(VelocityIterator, nonzero) +{ + ros::NodeHandle nh("nonzero"); + nh.setParam("use_dwa", true); + nh.setParam("min_speed_theta", -1); + dwb_plugins::LimitedAccelGenerator gen; + gen.initialize(nh); + nav_2d_msgs::Twist2D initial; + initial.x = 0.1; + initial.y = -0.08; + initial.theta = 0.05; + std::vector twists = gen.getTwists(initial); + EXPECT_EQ(twists.size(), 2519U); + checkLimits(twists, 0.0, 0.225, -0.1, 0.045, -0.11000000000000003, 0.21, + 0.24622144504490268, 0.0, 0.1); +} + +void matchPose(const geometry_msgs::Pose2D& a, const geometry_msgs::Pose2D& b) +{ + EXPECT_DOUBLE_EQ(a.x, b.x); + EXPECT_DOUBLE_EQ(a.y, b.y); + EXPECT_DOUBLE_EQ(a.theta, b.theta); +} + +void matchPose(const geometry_msgs::Pose2D& a, const double x, const double y, const double theta) +{ + EXPECT_DOUBLE_EQ(a.x, x); + EXPECT_DOUBLE_EQ(a.y, y); + EXPECT_DOUBLE_EQ(a.theta, theta); +} + +void matchTwist(const nav_2d_msgs::Twist2D& a, const nav_2d_msgs::Twist2D& b) +{ + EXPECT_DOUBLE_EQ(a.x, b.x); + EXPECT_DOUBLE_EQ(a.y, b.y); + EXPECT_DOUBLE_EQ(a.theta, b.theta); +} + +void matchTwist(const nav_2d_msgs::Twist2D& a, const double x, const double y, const double theta) +{ + EXPECT_DOUBLE_EQ(a.x, x); + EXPECT_DOUBLE_EQ(a.y, y); + EXPECT_DOUBLE_EQ(a.theta, theta); +} + +const double DEFAULT_SIM_TIME = 1.7; + +TEST(TrajectoryGenerator, basic) +{ + ros::NodeHandle nh("basic"); + StandardTrajectoryGenerator gen; + nh.setParam("linear_granularity", 0.5); + gen.initialize(nh); + dwb_msgs::Trajectory2D res = gen.generateTrajectory(origin, forward, forward); + matchTwist(res.velocity, forward); + EXPECT_DOUBLE_EQ(res.time_offsets.back().toSec(), DEFAULT_SIM_TIME); + int n = res.poses.size(); + EXPECT_EQ(n, 3); + ASSERT_GT(n, 0); + + matchPose(res.poses[0], origin); + matchPose(res.poses[n - 1], DEFAULT_SIM_TIME * forward.x, 0, 0); +} + +TEST(TrajectoryGenerator, basic_no_last_point) +{ + ros::NodeHandle nh("basic_no_last_point"); + StandardTrajectoryGenerator gen; + nh.setParam("include_last_point", false); + nh.setParam("linear_granularity", 0.5); + gen.initialize(nh); + dwb_msgs::Trajectory2D res = gen.generateTrajectory(origin, forward, forward); + matchTwist(res.velocity, forward); + EXPECT_DOUBLE_EQ(res.time_offsets.back().toSec(), DEFAULT_SIM_TIME / 2); + int n = res.poses.size(); + EXPECT_EQ(n, 2); + ASSERT_GT(n, 0); + + matchPose(res.poses[0], origin); + matchPose(res.poses[n - 1], 0.255, 0, 0); +} + +TEST(TrajectoryGenerator, too_slow) +{ + ros::NodeHandle nh("too_slow"); + StandardTrajectoryGenerator gen; + nh.setParam("linear_granularity", 0.5); + gen.initialize(nh); + nav_2d_msgs::Twist2D cmd; + cmd.x = 0.2; + dwb_msgs::Trajectory2D res = gen.generateTrajectory(origin, cmd, cmd); + matchTwist(res.velocity, cmd); + EXPECT_DOUBLE_EQ(res.time_offsets.back().toSec(), DEFAULT_SIM_TIME); + int n = res.poses.size(); + EXPECT_EQ(n, 2); + ASSERT_GT(n, 0); + + matchPose(res.poses[0], origin); +} + +TEST(TrajectoryGenerator, holonomic) +{ + ros::NodeHandle nh("holonomic"); + StandardTrajectoryGenerator gen; + nh.setParam("linear_granularity", 0.5); + gen.initialize(nh); + nav_2d_msgs::Twist2D cmd; + cmd.x = 0.3; + cmd.y = 0.2; + dwb_msgs::Trajectory2D res = gen.generateTrajectory(origin, cmd, cmd); + matchTwist(res.velocity, cmd); + EXPECT_DOUBLE_EQ(res.time_offsets.back().toSec(), DEFAULT_SIM_TIME); + int n = res.poses.size(); + EXPECT_EQ(n, 3); + ASSERT_GT(n, 0); + + matchPose(res.poses[0], origin); + matchPose(res.poses[n - 1], cmd.x*DEFAULT_SIM_TIME, cmd.y*DEFAULT_SIM_TIME, 0); +} + +TEST(TrajectoryGenerator, twisty) +{ + ros::NodeHandle nh("twisty"); + StandardTrajectoryGenerator gen; + nh.setParam("linear_granularity", 0.5); + nh.setParam("angular_granularity", 0.025); + gen.initialize(nh); + nav_2d_msgs::Twist2D cmd; + cmd.x = 0.3; + cmd.y = -0.2; + cmd.theta = 0.111; + dwb_msgs::Trajectory2D res = gen.generateTrajectory(origin, cmd, cmd); + matchTwist(res.velocity, cmd); + EXPECT_NEAR(res.time_offsets.back().toSec(), DEFAULT_SIM_TIME, 1.0E-5); + // Given the number of poses, the resulting time is slightly less precise + int n = res.poses.size(); + EXPECT_EQ(n, 9); + ASSERT_GT(n, 0); + + matchPose(res.poses[0], origin); + matchPose(res.poses[n - 1], 0.5355173615993063, -0.29635287789821596, cmd.theta * DEFAULT_SIM_TIME); +} + +TEST(TrajectoryGenerator, sim_time) +{ + ros::NodeHandle nh("sim_time"); + const double sim_time = 2.5; + nh.setParam("sim_time", sim_time); + nh.setParam("linear_granularity", 0.5); + StandardTrajectoryGenerator gen; + gen.initialize(nh); + dwb_msgs::Trajectory2D res = gen.generateTrajectory(origin, forward, forward); + matchTwist(res.velocity, forward); + EXPECT_DOUBLE_EQ(res.time_offsets.back().toSec(), sim_time); + int n = res.poses.size(); + EXPECT_EQ(n, 3); + ASSERT_GT(n, 0); + + matchPose(res.poses[0], origin); + matchPose(res.poses[n - 1], sim_time * forward.x, 0, 0); +} + +TEST(TrajectoryGenerator, accel) +{ + ros::NodeHandle nh("accel"); + nh.setParam("sim_time", 5.0); + nh.setParam("discretize_by_time", true); + nh.setParam("sim_granularity", 1.0); + nh.setParam("acc_lim_x", 0.1); + nh.setParam("min_speed_xy", -1.0); + StandardTrajectoryGenerator gen; + gen.initialize(nh); + + dwb_msgs::Trajectory2D res = gen.generateTrajectory(origin, zero, forward); + matchTwist(res.velocity, forward); + EXPECT_DOUBLE_EQ(res.time_offsets.back().toSec(), 5.0); + ASSERT_EQ(res.poses.size(), 6U); + matchPose(res.poses[0], origin); + matchPose(res.poses[1], 0.1, 0, 0); + matchPose(res.poses[2], 0.3, 0, 0); + matchPose(res.poses[3], 0.6, 0, 0); + matchPose(res.poses[4], 0.9, 0, 0); + matchPose(res.poses[5], 1.2, 0, 0); +} + +TEST(TrajectoryGenerator, dwa) +{ + ros::NodeHandle nh("dwa"); + nh.setParam("use_dwa", true); + nh.setParam("sim_period", 1.0); + nh.setParam("sim_time", 5.0); + nh.setParam("discretize_by_time", true); + nh.setParam("sim_granularity", 1.0); + nh.setParam("acc_lim_x", 0.1); + nh.setParam("min_speed_xy", -1.0); + dwb_plugins::LimitedAccelGenerator gen; + gen.initialize(nh); + + dwb_msgs::Trajectory2D res = gen.generateTrajectory(origin, zero, forward); + matchTwist(res.velocity, forward); + EXPECT_DOUBLE_EQ(res.time_offsets.back().toSec(), 5.0); + ASSERT_EQ(res.poses.size(), 6U); + matchPose(res.poses[0], origin); + matchPose(res.poses[1], 0.3, 0, 0); + matchPose(res.poses[2], 0.6, 0, 0); + matchPose(res.poses[3], 0.9, 0, 0); + matchPose(res.poses[4], 1.2, 0, 0); + matchPose(res.poses[5], 1.5, 0, 0); +} + +int main(int argc, char **argv) +{ + forward.x = 0.3; + ros::init(argc, argv, "twist_gen"); + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/navigations/dwb_plugins/test/twist_gen.launch b/navigations/dwb_plugins/test/twist_gen.launch new file mode 100755 index 0000000..b1f044c --- /dev/null +++ b/navigations/dwb_plugins/test/twist_gen.launch @@ -0,0 +1,3 @@ + + + diff --git a/navigations/dwb_plugins/test/velocity_iterator_test.cpp b/navigations/dwb_plugins/test/velocity_iterator_test.cpp new file mode 100755 index 0000000..63d6ee7 --- /dev/null +++ b/navigations/dwb_plugins/test/velocity_iterator_test.cpp @@ -0,0 +1,155 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ +#include +#include + +using dwb_plugins::OneDVelocityIterator; +using dwb_plugins::projectVelocity; + +const double EPSILON = 1e-3; + +TEST(VelocityIterator, basics) +{ + OneDVelocityIterator it(2.0, 0.0, 5.0, 1.0, -1.0, 1.0, 2); + EXPECT_FALSE(it.isFinished()); + EXPECT_NEAR(it.getVelocity(), 1.0, EPSILON); + EXPECT_FALSE(it.isFinished()); + ++it; + EXPECT_FALSE(it.isFinished()); + EXPECT_NEAR(it.getVelocity(), 3.0, EPSILON); + EXPECT_FALSE(it.isFinished()); + ++it; + EXPECT_TRUE(it.isFinished()); + it.reset(); + EXPECT_FALSE(it.isFinished()); + EXPECT_NEAR(it.getVelocity(), 1.0, EPSILON); +} + +TEST(VelocityIterator, limits) +{ + OneDVelocityIterator it(2.0, 1.5, 2.5, 1.0, -1.0, 1.0, 2); + EXPECT_NEAR(it.getVelocity(), 1.5, EPSILON); + ++it; + EXPECT_NEAR(it.getVelocity(), 2.5, EPSILON); +} + +TEST(VelocityIterator, acceleration) +{ + OneDVelocityIterator it(2.0, 0.0, 5.0, 0.5, -0.5, 1.0, 2); + EXPECT_NEAR(it.getVelocity(), 1.5, EPSILON); + ++it; + EXPECT_NEAR(it.getVelocity(), 2.5, EPSILON); +} + + +TEST(VelocityIterator, time) +{ + OneDVelocityIterator it(2.0, 0.0, 5.0, 1.0, -1.0, 0.5, 2); + EXPECT_NEAR(it.getVelocity(), 1.5, EPSILON); + ++it; + EXPECT_NEAR(it.getVelocity(), 2.5, EPSILON); +} + +TEST(VelocityIterator, samples) +{ + OneDVelocityIterator it(2.0, 0.0, 5.0, 1.0, -1.0, 1.0, 3); + EXPECT_NEAR(it.getVelocity(), 1.0, EPSILON); + ++it; + EXPECT_NEAR(it.getVelocity(), 2.0, EPSILON); + ++it; + EXPECT_NEAR(it.getVelocity(), 3.0, EPSILON); + ++it; + EXPECT_TRUE(it.isFinished()); +} + + +TEST(VelocityIterator, samples2) +{ + OneDVelocityIterator it(2.0, 0.0, 5.0, 1.0, -1.0, 1.0, 5); + EXPECT_NEAR(it.getVelocity(), 1.0, EPSILON); + ++it; + EXPECT_NEAR(it.getVelocity(), 1.5, EPSILON); + ++it; + EXPECT_NEAR(it.getVelocity(), 2.0, EPSILON); + ++it; + EXPECT_NEAR(it.getVelocity(), 2.5, EPSILON); + ++it; + EXPECT_NEAR(it.getVelocity(), 3.0, EPSILON); + ++it; + EXPECT_TRUE(it.isFinished()); +} + +TEST(VelocityIterator, around_zero) +{ + OneDVelocityIterator it(0.0, -5.0, 5.0, 1.0, -1.0, 1.0, 2); + EXPECT_NEAR(it.getVelocity(), -1.0, EPSILON); + ++it; + EXPECT_NEAR(it.getVelocity(), 0.0, EPSILON); + ++it; + EXPECT_NEAR(it.getVelocity(), 1.0, EPSILON); + ++it; +} + +TEST(VelocityIterator, around_zero2) +{ + OneDVelocityIterator it(0.0, -5.0, 5.0, 1.0, -1.0, 1.0, 4); + EXPECT_NEAR(it.getVelocity(), -1.0, EPSILON); + ++it; + EXPECT_NEAR(it.getVelocity(), -0.3333, EPSILON); + ++it; + EXPECT_NEAR(it.getVelocity(), 0.0, EPSILON); + ++it; + EXPECT_NEAR(it.getVelocity(), 0.3333, EPSILON); + ++it; + EXPECT_NEAR(it.getVelocity(), 1.0, EPSILON); + ++it; +} + +TEST(VelocityIterator, acceleration_magnitude) +{ + double accel_rate = 2.0; + double decel_rate = -3.0; + EXPECT_NEAR(projectVelocity(+0.0, accel_rate, decel_rate, 0.1, +1.5), +0.2, EPSILON); + EXPECT_NEAR(projectVelocity(+0.0, accel_rate, decel_rate, 0.1, -1.5), -0.2, EPSILON); + EXPECT_NEAR(projectVelocity(+1.0, accel_rate, decel_rate, 0.1, +1.5), +1.2, EPSILON); + EXPECT_NEAR(projectVelocity(+1.0, accel_rate, decel_rate, 0.1, +0.5), +0.7, EPSILON); + EXPECT_NEAR(projectVelocity(-1.0, accel_rate, decel_rate, 0.1, -1.5), -1.2, EPSILON); + EXPECT_NEAR(projectVelocity(-1.0, accel_rate, decel_rate, 0.1, -0.5), -0.7, EPSILON); +} + +int main(int argc, char **argv) +{ + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/navigations/follow_waypoints/CMakeLists.txt b/navigations/follow_waypoints/CMakeLists.txt new file mode 100755 index 0000000..809cd6c --- /dev/null +++ b/navigations/follow_waypoints/CMakeLists.txt @@ -0,0 +1,210 @@ +cmake_minimum_required(VERSION 3.0.2) +project(follow_waypoints) + +## Compile as C++11, supported in ROS Kinetic and newer +# add_compile_options(-std=c++11) + +## Find catkin macros and libraries +## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) +## is used, also find other catkin packages +find_package(catkin REQUIRED COMPONENTS + actionlib + dynamic_reconfigure + geometry_msgs + move_base_msgs + roscpp + std_msgs + tf +) + +## System dependencies are found with CMake's conventions +# find_package(Boost REQUIRED COMPONENTS system) + + +## Uncomment this if the package has a setup.py. This macro ensures +## modules and global scripts declared therein get installed +## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html +# catkin_python_setup() + +################################################ +## Declare ROS messages, services and actions ## +################################################ + +## To declare and build messages, services or actions from within this +## package, follow these steps: +## * Let MSG_DEP_SET be the set of packages whose message types you use in +## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...). +## * In the file package.xml: +## * add a build_depend tag for "message_generation" +## * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET +## * If MSG_DEP_SET isn't empty the following dependency has been pulled in +## but can be declared for certainty nonetheless: +## * add a exec_depend tag for "message_runtime" +## * In this file (CMakeLists.txt): +## * add "message_generation" and every package in MSG_DEP_SET to +## find_package(catkin REQUIRED COMPONENTS ...) +## * add "message_runtime" and every package in MSG_DEP_SET to +## catkin_package(CATKIN_DEPENDS ...) +## * uncomment the add_*_files sections below as needed +## and list every .msg/.srv/.action file to be processed +## * uncomment the generate_messages entry below +## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...) + +## Generate messages in the 'msg' folder +# add_message_files( +# FILES +# Message1.msg +# Message2.msg +# ) + +## Generate services in the 'srv' folder +# add_service_files( +# FILES +# Service1.srv +# Service2.srv +# ) + +## Generate actions in the 'action' folder +# add_action_files( +# FILES +# Action1.action +# Action2.action +# ) + +## Generate added messages and services with any dependencies listed here +# generate_messages(DEPENDENCIES geometry_msgs) + +################################################ +## Declare ROS dynamic reconfigure parameters ## +################################################ + +## To declare and build dynamic reconfigure parameters within this +## package, follow these steps: +## * In the file package.xml: +## * add a build_depend and a exec_depend tag for "dynamic_reconfigure" +## * In this file (CMakeLists.txt): +## * add "dynamic_reconfigure" to +## find_package(catkin REQUIRED COMPONENTS ...) +## * uncomment the "generate_dynamic_reconfigure_options" section below +## and list every .cfg file to be processed + +## Generate dynamic reconfigure parameters in the 'cfg' folder +generate_dynamic_reconfigure_options( + cfg/FollowWayPoints.cfg +) + +################################### +## catkin specific configuration ## +################################### +## The catkin_package macro generates cmake config files for your package +## Declare things to be passed to dependent projects +## INCLUDE_DIRS: uncomment this if your package contains header files +## LIBRARIES: libraries you create in this project that dependent projects also need +## CATKIN_DEPENDS: catkin_packages dependent projects also need +## DEPENDS: system dependencies of this project that dependent projects also need +catkin_package( + INCLUDE_DIRS include + LIBRARIES ${PROJECT_NAME} + CATKIN_DEPENDS actionlib geometry_msgs move_base_msgs roscpp std_msgs message_runtime +# DEPENDS system_lib +) + +########### +## Build ## +########### + +## Specify additional locations of header files +## Your package locations should be listed before other locations +include_directories( + include + ${catkin_INCLUDE_DIRS} +) + +## Declare a C++ library +add_library(${PROJECT_NAME} + src/follow_waypoints.cpp +) + +## Add cmake target dependencies of the library +## as an example, code may need to be generated before libraries +## either from message generation or dynamic reconfigure +add_dependencies(${PROJECT_NAME} ${PROJECT_NAME}_gencfg ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) + +## Declare a C++ executable +## With catkin_make all packages are built within a single CMake context +## The recommended prefix ensures that target names across packages don't collide +add_executable(${PROJECT_NAME}_node src/follow_waypoints_node.cpp) + +## Rename C++ executable without prefix +## The above recommended prefix causes long target names, the following renames the +## target back to the shorter version for ease of user use +## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node" +# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "") + +## Add cmake target dependencies of the executable +## same as for the library above +add_dependencies(${PROJECT_NAME}_node ${PROJECT_NAME}_gencfg ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) + +## Specify libraries to link a library or executable target against + +target_link_libraries(${PROJECT_NAME} + ${catkin_LIBRARIES} +) + +target_link_libraries(${PROJECT_NAME}_node + ${PROJECT_NAME} + ${catkin_LIBRARIES} +) + +############# +## Install ## +############# + +# all install targets should use catkin DESTINATION variables +# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html + +## Mark executable scripts (Python etc.) for installation +## in contrast to setup.py, you can choose the destination +# catkin_install_python(PROGRAMS +# scripts/my_python_script +# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + +## Mark executables for installation +## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html +install(TARGETS ${PROJECT_NAME}_node + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) + +## Mark libraries for installation +## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html +install(TARGETS ${PROJECT_NAME} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} +) + +## Mark cpp header files for installation +install(DIRECTORY launch/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}/launch +) + +## Mark other files for installation (e.g. launch and bag files, etc.) +# install(FILES +# # myfile1 +# # myfile2 +# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +# ) + +############# +## Testing ## +############# + +## Add gtest based cpp test target and link libraries +# catkin_add_gtest(${PROJECT_NAME}-test test/test_follow_waypoints.cpp) +# if(TARGET ${PROJECT_NAME}-test) +# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME}) +# endif() + +## Add folders to be run by python nosetests +# catkin_add_nosetests(test) diff --git a/navigations/follow_waypoints/cfg/FollowWayPoints.cfg b/navigations/follow_waypoints/cfg/FollowWayPoints.cfg new file mode 100755 index 0000000..17d6095 --- /dev/null +++ b/navigations/follow_waypoints/cfg/FollowWayPoints.cfg @@ -0,0 +1,8 @@ +#!/usr/bin/env python +PACKAGE = 'follow_waypoints' +from dynamic_reconfigure.parameter_generator_catkin import * + +gen = ParameterGenerator() +gen.add("patrol_mode", bool_t, 0, "Follow the currently given waypoints repeatedly", False) + +exit(gen.generate(PACKAGE, "follow_waypoints", "FollowWayPoints")) diff --git a/navigations/follow_waypoints/include/follow_waypoints/follow_waypoints.h b/navigations/follow_waypoints/include/follow_waypoints/follow_waypoints.h new file mode 100755 index 0000000..760f84b --- /dev/null +++ b/navigations/follow_waypoints/include/follow_waypoints/follow_waypoints.h @@ -0,0 +1,69 @@ +#ifndef FOLLOW_WAYPOINTS_H_ +#define FOLLOW_WAYPOINTS_H_ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +namespace follow_waypoints +{ + class FollowWayPoints + { + public: + FollowWayPoints(ros::NodeHandlePtr nh, std::string node_name); + virtual ~FollowWayPoints(); + void run(); + private: + void dyn_callback(follow_waypoints::FollowWayPointsConfig &config, int32_t level); + bool make_path_ready(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res); + bool do_path_reset(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res); + void point_cb(geometry_msgs::PointStamped point); + void pub_waypoints_list(); + void send_move_base_goal(geometry_msgs::PoseWithCovarianceStamped pose); + void run_once(); + geometry_msgs::PoseWithCovarianceStamped to_pose_with_Cov(geometry_msgs::PointStamped point); + geometry_msgs::PoseArray toPoseArray(std::vector waypoints); + + std::string frame_id_; + std::string odom_frame_id_; + std::string base_frame_id_; + std::string waypoints_to_follow_topic_; + std::string waypoints_list_topic_; + double wait_duration_; + double distance_tolerance_; + bool path_ready_; + bool waypoints_are_poses_; + + // TF Initialisation ------------------------------------------------------------------- + tf::TransformListener tf_; + tf::TransformListener listener_; + + ros::NodeHandlePtr private_nh_; + ros::ServiceServer path_ready_srv_; + ros::ServiceServer path_reset_srv_; + ros::Publisher pose_array_publisher_; + ros::Subscriber waypoints_sub_; + actionlib::SimpleActionClient* move_base_client_; + std::vector waypoints_; + dynamic_reconfigure::Server server; + dynamic_reconfigure::Server::CallbackType f; + follow_waypoints::FollowWayPointsConfig dyn_config_; + /* Create Thread */ + boost::thread lineThread; + ros::Rate* loop_rate_; + }; +} //follow_waypoints + +#endif \ No newline at end of file diff --git a/navigations/follow_waypoints/launch/follow_waypoints.launch b/navigations/follow_waypoints/launch/follow_waypoints.launch new file mode 100755 index 0000000..f728c4e --- /dev/null +++ b/navigations/follow_waypoints/launch/follow_waypoints.launch @@ -0,0 +1,26 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/navigations/follow_waypoints/package.xml b/navigations/follow_waypoints/package.xml new file mode 100755 index 0000000..bb239b2 --- /dev/null +++ b/navigations/follow_waypoints/package.xml @@ -0,0 +1,79 @@ + + + follow_waypoints + 0.0.0 + The follow_waypoints package + + + + + robotics + + + + + + TODO + + + + + + + + + + + + + + + + + + + + + + + + message_generation + + + + + + message_runtime + + + + + catkin + geometry_msgs + roscpp + std_msgs + geometry_msgs + roscpp + std_msgs + geometry_msgs + roscpp + std_msgs + + actionlib + actionlib + + dynamic_reconfigure + dynamic_reconfigure + + move_base_msgs + move_base_msgs + + tf + tf + + + + + + + diff --git a/navigations/follow_waypoints/src/follow_waypoints.cpp b/navigations/follow_waypoints/src/follow_waypoints.cpp new file mode 100755 index 0000000..1fe30ce --- /dev/null +++ b/navigations/follow_waypoints/src/follow_waypoints.cpp @@ -0,0 +1,285 @@ +#include "follow_waypoints/follow_waypoints.h" + +namespace follow_waypoints +{ + FollowWayPoints::FollowWayPoints(ros::NodeHandlePtr nh, std::string node_name) : private_nh_(nh) + { + if(private_nh_ == NULL) exit(0); + // private_nh_ = ros::NodeHandle("~/"+node_name); + // Read parameters off the parameter server -------------------------------------------- + private_nh_->param("goal_frame_id", frame_id_, std::string("map")); + private_nh_->param("odom_frame_id", odom_frame_id_, std::string("odom")); + private_nh_->param("base_frame_id", base_frame_id_, std::string("base_footprint")); + private_nh_->param("wait_duration", wait_duration_, 0.0); + private_nh_->param("waypoint_distance_tolerance", distance_tolerance_, 0.0); + private_nh_->param("waypoints_to_follow_topic", waypoints_to_follow_topic_, std::string("/clicked_points")); + private_nh_->param("waypoints_list_topic", waypoints_list_topic_, std::string("/waypoints")); + + // listen to points or to poses? + private_nh_->param("waypoints_are_poses", waypoints_are_poses_, true); + + // list of waypoints to follow + // self.waypoints = collections.deque() + + // Is the path provided by the user ready to follow? + path_ready_ = false; + + // Dynamic Reconfigure ----------------------------------------------------------------- + f = boost::bind(&FollowWayPoints::dyn_callback, this, _1, _2); + server.setCallback(f); + + // move_base Action client ------------------------------------------------------------- + move_base_client_ = new actionlib::SimpleActionClient("/move_base", true); + ROS_INFO("Connecting to move_base..."); + if(move_base_client_ != NULL) move_base_client_->waitForServer(); + ROS_INFO("Connected to move_base."); + + // Subscribers & Publishers & Services initialisation ---------------------------------- + path_ready_srv_ = private_nh_->advertiseService("/path_ready",&FollowWayPoints::make_path_ready, this); + path_reset_srv_ = private_nh_->advertiseService("/path_reset",&FollowWayPoints::do_path_reset, this); + ROS_INFO("Ready to add two ints."); + + // publish waypoints as pose array - visualise them in rviz + pose_array_publisher_ = private_nh_->advertise(waypoints_list_topic_,1, true); + + // Listen to the goal locations + waypoints_sub_ = private_nh_->subscribe(waypoints_to_follow_topic_, 1000, &FollowWayPoints::point_cb, this); + loop_rate_ = new ros::Rate(20); + // // Create thread + // lineThread = boost::thread(&FollowWayPoints::run, this); + // if(lineThread.joinable()) { + // lineThread.join(); + // } + } + + FollowWayPoints::~FollowWayPoints() + { + delete(move_base_client_); + + } + + void FollowWayPoints::dyn_callback(follow_waypoints::FollowWayPointsConfig &config, int32_t level) + { + dyn_config_ = config; + ROS_INFO("Reconfigure Request: %d", config.patrol_mode); + } + + bool FollowWayPoints::make_path_ready(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res) + { + path_ready_ = true; + res.success = path_ready_; + res.message = "path_ready_ = true"; + return true; + } + + bool FollowWayPoints::do_path_reset(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res) + { + ROS_WARN("Issuing cancel command to move_base"); + + ros::Publisher pub = private_nh_->advertise("/move_base/cancel", 1); + pub.publish(actionlib_msgs::GoalID()); + ROS_WARN("move_base goal cancelled."); + + if(!waypoints_.empty()) + { + waypoints_.clear(); + pub_waypoints_list(); + } + res.success = path_ready_; + res.message = "move_base goal cancelled."; + return true; + } + + void FollowWayPoints::pub_waypoints_list() + { + pose_array_publisher_.publish(toPoseArray(waypoints_)); + } + + void FollowWayPoints::point_cb(geometry_msgs::PointStamped point) + { + waypoints_.insert(waypoints_.end(), this->to_pose_with_Cov(point)); + ROS_INFO("Added new waypoint -> (%f, %f) | # Waypoints: %d", point.point.x, point.point.y, (int)waypoints_.size()); + if(waypoints_.size() > 1) + { + for(int i = 0; i < waypoints_.size() - 1; i++) + { + double x1 = waypoints_[i].pose.pose.position.x; + double y1 = waypoints_[i].pose.pose.position.y; + double x2 = waypoints_[i+1].pose.pose.position.x; + double y2 = waypoints_[i+1].pose.pose.position.y; + double theta = atan2(y2 - y1, x2 - x1); + tf2::Quaternion temp; + temp.setRPY(0, 0, theta); + waypoints_[i+1].pose.pose.orientation.x = temp.getX(); + waypoints_[i+1].pose.pose.orientation.y = temp.getY(); + waypoints_[i+1].pose.pose.orientation.z = temp.getZ(); + waypoints_[i+1].pose.pose.orientation.w = temp.getW(); + } + } + else + { + tf::StampedTransform transform; + try + { + listener_.lookupTransform(frame_id_, base_frame_id_, ros::Time(0), transform); + } + catch (tf::TransformException &ex) + { + ROS_ERROR("%s",ex.what()); + ros::Duration(1.0).sleep(); + return; + } + double x1 = transform.getOrigin().x(); + double y1 = transform.getOrigin().y(); + double x2 = waypoints_[0].pose.pose.position.x; + double y2 = waypoints_[0].pose.pose.position.y; + double theta = atan2(y2 - y1, x2 - x1); + tf2::Quaternion temp; + temp.setRPY(0, 0, theta); + waypoints_[0].pose.pose.orientation.x = temp.getX(); + waypoints_[0].pose.pose.orientation.y = temp.getY(); + waypoints_[0].pose.pose.orientation.z = temp.getZ(); + waypoints_[0].pose.pose.orientation.w = temp.getW(); + } + this->pub_waypoints_list(); + } + + void FollowWayPoints::send_move_base_goal(geometry_msgs::PoseWithCovarianceStamped pose) + { + move_base_msgs::MoveBaseGoal goal; + goal.target_pose.header.frame_id = frame_id_; + goal.target_pose.pose.position = pose.pose.pose.position; + goal.target_pose.pose.orientation = pose.pose.pose.orientation; + ROS_INFO("Executing move_base goal -> (%f, %f) ...", pose.pose.pose.position.x, pose.pose.pose.position.y); + if(move_base_client_ != NULL) move_base_client_->sendGoal(goal); + } + + void FollowWayPoints::run_once() + { + if(!path_ready_) + { + ros::Duration(1.0).sleep(); + return; + } + if(waypoints_.empty()) + { + ROS_WARN("No more waypoints to follow."); + path_ready_ = false; + return; + } + + ROS_INFO("Following path with # %d waypoints...", (int)waypoints_.size()); + tf::StampedTransform transform; + try + { + listener_.lookupTransform(frame_id_, base_frame_id_, ros::Time(0), transform); + } + catch (tf::TransformException &ex) + { + ROS_ERROR("%s",ex.what()); + ros::Duration(1.0).sleep(); + return; + } + double x1 = transform.getOrigin().x(); + double y1 = transform.getOrigin().y(); + double x2 = waypoints_[0].pose.pose.position.x; + double y2 = waypoints_[0].pose.pose.position.y; + double theta = atan2(y2 - y1, x2 - x1); + tf2::Quaternion temp; + temp.setRPY(0, 0, theta); + waypoints_[0].pose.pose.orientation.x = temp.getX(); + waypoints_[0].pose.pose.orientation.y = temp.getY(); + waypoints_[0].pose.pose.orientation.z = temp.getZ(); + waypoints_[0].pose.pose.orientation.w = temp.getW(); + + // we have waypoints, let's follow them! + while (!waypoints_.empty() && ros::ok()) + { + geometry_msgs::PoseWithCovarianceStamped goal = waypoints_.front(); + if(dyn_config_.patrol_mode) + { + + } + else + { + // not in patrol mode - forget about this waypoint + waypoints_.erase(waypoints_.begin()); + } + send_move_base_goal(goal); + if(!(distance_tolerance_ > 0.0)) + { + // just wait until move_base reaches the goal... + if(move_base_client_ != NULL) move_base_client_->waitForResult(); + ROS_INFO("Waiting for %f seconds before proceeding to the next goal...", wait_duration_); + ros::Duration(wait_duration_).sleep(); + } + else + { + /** + raise NotImplementedError("distance_tolerance not implemented yet.") + + TODO - Rewrite + This is the loop which exist when the robot is near a certain GOAL point. + */ + double distance = 10.0; + while(distance > distance_tolerance_) + { + try + { + listener_.lookupTransform(frame_id_, base_frame_id_, ros::Time(0), transform); + } + catch (tf::TransformException &ex) + { + ROS_ERROR("%s",ex.what()); + ros::Duration(1.0).sleep(); + continue; + } + distance = sqrt( + pow(goal.pose.pose.position.x - transform.getOrigin().x(), 2) + + pow(goal.pose.pose.position.y - transform.getOrigin().y(), 2) + ); + ros::spinOnce(); + } + } + // current waypoint has now been reached! move on to the next waypoint on the next + // iteration + this->pub_waypoints_list(); + ros::spinOnce(); + loop_rate_->sleep(); + + } + } + + void FollowWayPoints::run() + { + while (ros::ok()) + { + this->run_once(); + ros::spinOnce(); + } + } + + geometry_msgs::PoseWithCovarianceStamped FollowWayPoints::to_pose_with_Cov(geometry_msgs::PointStamped point) + { + geometry_msgs::PoseWithCovarianceStamped pose; + pose.header = point.header; + pose.pose.pose.position = point.point; + geometry_msgs::Quaternion angle; + angle.x = 0; + angle.y = 0; + angle.z = 0; + angle.w = 1; + pose.pose.pose.orientation = angle; + return pose; + } + + geometry_msgs::PoseArray FollowWayPoints::toPoseArray(std::vector waypoints)\ + { + geometry_msgs::PoseArray poses; + poses.header.frame_id = frame_id_; + for(int i = 0; i < waypoints_.size(); i++) + poses.poses.insert(poses.poses.begin() , waypoints_[i].pose.pose); + return poses; + } + +} \ No newline at end of file diff --git a/navigations/follow_waypoints/src/follow_waypoints_node.cpp b/navigations/follow_waypoints/src/follow_waypoints_node.cpp new file mode 100755 index 0000000..a7f6ee1 --- /dev/null +++ b/navigations/follow_waypoints/src/follow_waypoints_node.cpp @@ -0,0 +1,14 @@ +#include +#include "follow_waypoints/follow_waypoints.h" + +void dyn_callback(follow_waypoints::FollowWayPointsConfig &config, int32_t level); + +int main(int argc, char** argv){ + ros::init(argc, argv, "follow_waypoints_node"); + ros::NodeHandlePtr nh = boost::make_shared(); + follow_waypoints::FollowWayPoints* foll = new follow_waypoints::FollowWayPoints(nh, "follow_waypoints_node"); + foll->run(); + ros::spin(); + return(0); +} + diff --git a/navigations/geographic_info/README.rst b/navigations/geographic_info/README.rst new file mode 100755 index 0000000..e68bdae --- /dev/null +++ b/navigations/geographic_info/README.rst @@ -0,0 +1,13 @@ +geographic_info repository +========================== + +ROS messages and interfaces for mapping and coordinate conversions, +part of the ROS Geographic Information project. + + * http://en.wikipedia.org/wiki/Geographic_information_system + +ROS documentation: + + * http://wiki.ros.org/geographic_info + * http://wiki.ros.org/geographic_msgs + * http://wiki.ros.org/geodesy diff --git a/navigations/geographic_info/geodesy/CHANGELOG.rst b/navigations/geographic_info/geodesy/CHANGELOG.rst new file mode 100755 index 0000000..d5ee034 --- /dev/null +++ b/navigations/geographic_info/geodesy/CHANGELOG.rst @@ -0,0 +1,67 @@ +Change history +============== + +0.5.3 (2018-03-27) +------------------ + +0.5.2 (2017-04-15) +------------------ + +0.5.1 (2017-04-15) +------------------ + +0.5.0 (2017-04-07) +------------------ + + * Removed Python setup install_requires option. + +0.4.0 (2014-09-18) +------------------ + + * Released to Indigo. + * Remove deprecated geodesy.gen_uuid module (`#4`_). + +0.3.2 (2014-08-30) +------------------ + + * Released to Indigo. + * Make C++ template declaration for WGS-84 header compatible with GCC + 4.7 compiler (`#12`_), thanks to Mike Purvis and Dirk Thomas. + +0.3.1 (2013-10-03) +------------------ + + * Fix ROS Hydro header install problem (`#9`_). + +0.3.0 (2013-08-03) +------------------ + + * Released to Hydro. + * Convert to catkin build (`#3`_). + * Remove unnecessary roscpp and rospy dependencies (`#6`_). + +0.2.1 (2012-08-13) +------------------ + + * Released to Fuerte. + * Released to Groovy: 2013-03-27. + * Use unique_identifier for UUID interfaces. + +0.2.0 (2012-06-02) +------------------ + + * Many new mapping messages and services added. + * Use PROJ.4 library for Python geodesy API (C++ API not ported to + PROJ.4 yet). + * Released to Electric. + +0.1.0 (2012-04-10) +------------------ + + * Initial release to Electric. + +.. _`#3`: https://github.com/ros-geographic-info/geographic_info/issues/3 +.. _`#4`: https://github.com/ros-geographic-info/geographic_info/issues/4 +.. _`#6`: https://github.com/ros-geographic-info/geographic_info/issues/6 +.. _`#9`: https://github.com/ros-geographic-info/geographic_info/issues/9 +.. _`#12`: https://github.com/ros-geographic-info/geographic_info/issues/12 diff --git a/navigations/geographic_info/geodesy/CMakeLists.txt b/navigations/geographic_info/geodesy/CMakeLists.txt new file mode 100755 index 0000000..fdc9f09 --- /dev/null +++ b/navigations/geographic_info/geodesy/CMakeLists.txt @@ -0,0 +1,56 @@ +# http://ros.org/doc/groovy/api/catkin/html/user_guide/supposed.html +cmake_minimum_required(VERSION 3.0.2) +project(geodesy) +find_package(catkin REQUIRED + COMPONENTS + angles + geographic_msgs + geometry_msgs + sensor_msgs + tf + unique_id + uuid_msgs) + +include_directories(include ${catkin_INCLUDE_DIRS}) +catkin_python_setup() + +# what other packages will need to use this one +catkin_package(CATKIN_DEPENDS + geographic_msgs + geometry_msgs + sensor_msgs + tf + unique_id + uuid_msgs + INCLUDE_DIRS include + LIBRARIES geoconv) + +# build C++ coordinate conversion library +add_library(geoconv src/conv/utm_conversions.cpp) +target_link_libraries(geoconv ${catkin_LIBRARIES}) +add_dependencies(geoconv ${catkin_EXPORTED_TARGETS}) + +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}) +install(TARGETS geoconv + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) + +# unit tests +if (CATKIN_ENABLE_TESTING) + + catkin_add_gtest(test_wgs84 tests/test_wgs84.cpp) + target_link_libraries(test_wgs84 ${catkin_LIBRARIES}) + add_dependencies(test_wgs84 ${catkin_EXPORTED_TARGETS}) + + catkin_add_gtest(test_utm tests/test_utm.cpp) + target_link_libraries(test_utm geoconv ${catkin_LIBRARIES}) + add_dependencies(test_utm ${catkin_EXPORTED_TARGETS}) + + catkin_add_nosetests(tests/test_bounding_box.py) + catkin_add_nosetests(tests/test_props.py) + catkin_add_nosetests(tests/test_utm.py) + catkin_add_nosetests(tests/test_wu_point.py) + +endif (CATKIN_ENABLE_TESTING) diff --git a/navigations/geographic_info/geodesy/doc/CHANGELOG.rst b/navigations/geographic_info/geodesy/doc/CHANGELOG.rst new file mode 100755 index 0000000..d5ee034 --- /dev/null +++ b/navigations/geographic_info/geodesy/doc/CHANGELOG.rst @@ -0,0 +1,67 @@ +Change history +============== + +0.5.3 (2018-03-27) +------------------ + +0.5.2 (2017-04-15) +------------------ + +0.5.1 (2017-04-15) +------------------ + +0.5.0 (2017-04-07) +------------------ + + * Removed Python setup install_requires option. + +0.4.0 (2014-09-18) +------------------ + + * Released to Indigo. + * Remove deprecated geodesy.gen_uuid module (`#4`_). + +0.3.2 (2014-08-30) +------------------ + + * Released to Indigo. + * Make C++ template declaration for WGS-84 header compatible with GCC + 4.7 compiler (`#12`_), thanks to Mike Purvis and Dirk Thomas. + +0.3.1 (2013-10-03) +------------------ + + * Fix ROS Hydro header install problem (`#9`_). + +0.3.0 (2013-08-03) +------------------ + + * Released to Hydro. + * Convert to catkin build (`#3`_). + * Remove unnecessary roscpp and rospy dependencies (`#6`_). + +0.2.1 (2012-08-13) +------------------ + + * Released to Fuerte. + * Released to Groovy: 2013-03-27. + * Use unique_identifier for UUID interfaces. + +0.2.0 (2012-06-02) +------------------ + + * Many new mapping messages and services added. + * Use PROJ.4 library for Python geodesy API (C++ API not ported to + PROJ.4 yet). + * Released to Electric. + +0.1.0 (2012-04-10) +------------------ + + * Initial release to Electric. + +.. _`#3`: https://github.com/ros-geographic-info/geographic_info/issues/3 +.. _`#4`: https://github.com/ros-geographic-info/geographic_info/issues/4 +.. _`#6`: https://github.com/ros-geographic-info/geographic_info/issues/6 +.. _`#9`: https://github.com/ros-geographic-info/geographic_info/issues/9 +.. _`#12`: https://github.com/ros-geographic-info/geographic_info/issues/12 diff --git a/navigations/geographic_info/geodesy/doc/conf.py b/navigations/geographic_info/geodesy/doc/conf.py new file mode 100755 index 0000000..a737634 --- /dev/null +++ b/navigations/geographic_info/geodesy/doc/conf.py @@ -0,0 +1,251 @@ +# -*- coding: utf-8 -*- +# +# geodesy documentation build configuration file, created by +# sphinx-quickstart on Wed Apr 25 16:01:20 2012. +# +# This file is execfile()d with the current directory set to its containing dir. +# +# Note that not all possible configuration values are present in this +# autogenerated file. +# +# All configuration values have a default; values that are commented out +# serve to show the default. + +## get catkin package information +import os +import catkin_pkg.package +catkin_dir = os.path.dirname(os.path.dirname(os.path.abspath(__file__))) +catkin_package = catkin_pkg.package.parse_package( + os.path.join(catkin_dir, catkin_pkg.package.PACKAGE_MANIFEST_FILENAME)) + +# If extensions (or modules to document with autodoc) are in another directory, +# add these directories to sys.path here. If the directory is relative to the +# documentation root, use os.path.abspath to make it absolute, like shown here. +#sys.path.insert(0, os.path.abspath('.')) + +# -- General configuration ----------------------------------------------------- + +# If your documentation needs a minimal Sphinx version, state it here. +#needs_sphinx = '1.0' + +# Add any Sphinx extension module names here, as strings. They can be extensions +# coming with Sphinx (named 'sphinx.ext.*') or your custom ones. +extensions = ['sphinx.ext.autodoc', 'sphinx.ext.intersphinx', 'sphinx.ext.todo', 'sphinx.ext.viewcode'] + +# Add any paths that contain templates here, relative to this directory. +templates_path = ['_templates'] + +# The suffix of source filenames. +source_suffix = '.rst' + +# The encoding of source files. +#source_encoding = 'utf-8-sig' + +# The master toctree document. +master_doc = 'index' + +# General information about the project. +project = u'geodesy' +copyright = u'2012, Jack O\'Quin' + +# The version info for the project you're documenting, acts as replacement for +# |version| and |release|, also used in various other places throughout the +# built documents. +# +# The short X.Y version. +version = catkin_package.version +# The full version, including alpha/beta/rc tags. +release = catkin_package.version + +# The language for content autogenerated by Sphinx. Refer to documentation +# for a list of supported languages. +#language = None + +# There are two options for replacing |today|: either, you set today to some +# non-false value, then it is used: +#today = '' +# Else, today_fmt is used as the format for a strftime call. +#today_fmt = '%B %d, %Y' + +# List of patterns, relative to source directory, that match files and +# directories to ignore when looking for source files. +exclude_patterns = ['_build'] + +# The reST default role (used for this markup: `text`) to use for all documents. +#default_role = None + +# If true, '()' will be appended to :func: etc. cross-reference text. +#add_function_parentheses = True + +# If true, the current module name will be prepended to all description +# unit titles (such as .. function::). +#add_module_names = True + +# If true, sectionauthor and moduleauthor directives will be shown in the +# output. They are ignored by default. +#show_authors = False + +# The name of the Pygments (syntax highlighting) style to use. +pygments_style = 'sphinx' + +# A list of ignored prefixes for module index sorting. +#modindex_common_prefix = [] + + +# -- Options for HTML output --------------------------------------------------- + +# The theme to use for HTML and HTML Help pages. See the documentation for +# a list of builtin themes. +html_theme = 'default' + +# Theme options are theme-specific and customize the look and feel of a theme +# further. For a list of options available for each theme, see the +# documentation. +#html_theme_options = {} + +# Add any paths that contain custom themes here, relative to this directory. +#html_theme_path = [] + +# The name for this set of Sphinx documents. If None, it defaults to +# " v documentation". +#html_title = None + +# A shorter title for the navigation bar. Default is the same as html_title. +#html_short_title = None + +# The name of an image file (relative to this directory) to place at the top +# of the sidebar. +#html_logo = None + +# The name of an image file (within the static path) to use as favicon of the +# docs. This file should be a Windows icon file (.ico) being 16x16 or 32x32 +# pixels large. +#html_favicon = None + +# Add any paths that contain custom static files (such as style sheets) here, +# relative to this directory. They are copied after the builtin static files, +# so a file named "default.css" will overwrite the builtin "default.css". +html_static_path = [] + +# If not '', a 'Last updated on:' timestamp is inserted at every page bottom, +# using the given strftime format. +#html_last_updated_fmt = '%b %d, %Y' + +# If true, SmartyPants will be used to convert quotes and dashes to +# typographically correct entities. +#html_use_smartypants = True + +# Custom sidebar templates, maps document names to template names. +#html_sidebars = {} + +# Additional templates that should be rendered to pages, maps page names to +# template names. +#html_additional_pages = {} + +# If false, no module index is generated. +#html_domain_indices = True + +# If false, no index is generated. +#html_use_index = True + +# If true, the index is split into individual pages for each letter. +#html_split_index = False + +# If true, links to the reST sources are added to the pages. +#html_show_sourcelink = True + +# If true, "Created using Sphinx" is shown in the HTML footer. Default is True. +#html_show_sphinx = True + +# If true, "(C) Copyright ..." is shown in the HTML footer. Default is True. +#html_show_copyright = True + +# If true, an OpenSearch description file will be output, and all pages will +# contain a tag referring to it. The value of this option must be the +# base URL from which the finished HTML is served. +#html_use_opensearch = '' + +# This is the file name suffix for HTML files (e.g. ".xhtml"). +#html_file_suffix = None + +# Output file base name for HTML help builder. +htmlhelp_basename = 'geodesydoc' + + +# -- Options for LaTeX output -------------------------------------------------- + +latex_elements = { +# The paper size ('letterpaper' or 'a4paper'). +#'papersize': 'letterpaper', + +# The font size ('10pt', '11pt' or '12pt'). +#'pointsize': '10pt', + +# Additional stuff for the LaTeX preamble. +#'preamble': '', +} + +# Grouping the document tree into LaTeX files. List of tuples +# (source start file, target name, title, author, documentclass [howto/manual]). +latex_documents = [ + ('index', 'geodesy.tex', u'geodesy Documentation', + u'Jack O\'Quin', 'manual'), +] + +# The name of an image file (relative to this directory) to place at the top of +# the title page. +#latex_logo = None + +# For "manual" documents, if this is true, then toplevel headings are parts, +# not chapters. +#latex_use_parts = False + +# If true, show page references after internal links. +#latex_show_pagerefs = False + +# If true, show URL addresses after external links. +#latex_show_urls = False + +# Documents to append as an appendix to all manuals. +#latex_appendices = [] + +# If false, no module index is generated. +#latex_domain_indices = True + + +# -- Options for manual page output -------------------------------------------- + +# One entry per manual page. List of tuples +# (source start file, name, description, authors, manual section). +man_pages = [ + ('index', 'geodesy', u'geodesy Documentation', + [u'Jack O\'Quin'], 1) +] + +# If true, show URL addresses after external links. +#man_show_urls = False + + +# -- Options for Texinfo output ------------------------------------------------ + +# Grouping the document tree into Texinfo files. List of tuples +# (source start file, target name, title, author, +# dir menu entry, description, category) +texinfo_documents = [ + ('index', 'geodesy', u'geodesy Documentation', + u'Jack O\'Quin', 'geodesy', 'One line description of project.', + 'Miscellaneous'), +] + +# Documents to append as an appendix to all manuals. +#texinfo_appendices = [] + +# If false, no module index is generated. +#texinfo_domain_indices = True + +# How to display URL addresses: 'footnote', 'no', or 'inline'. +#texinfo_show_urls = 'footnote' + + +# Example configuration for intersphinx: refer to the Python standard library. +intersphinx_mapping = {'http://docs.python.org/': None} diff --git a/navigations/geographic_info/geodesy/doc/geodesy.bounding_box.rst b/navigations/geographic_info/geodesy/doc/geodesy.bounding_box.rst new file mode 100755 index 0000000..4d7c385 --- /dev/null +++ b/navigations/geographic_info/geodesy/doc/geodesy.bounding_box.rst @@ -0,0 +1,5 @@ +geodesy.bounding_box +-------------------- + +.. automodule:: geodesy.bounding_box + :members: diff --git a/navigations/geographic_info/geodesy/doc/geodesy.gen_uuid.rst b/navigations/geographic_info/geodesy/doc/geodesy.gen_uuid.rst new file mode 100755 index 0000000..f0530ce --- /dev/null +++ b/navigations/geographic_info/geodesy/doc/geodesy.gen_uuid.rst @@ -0,0 +1,21 @@ +geodesy.gen_uuid +---------------- + +.. module:: geodesy.gen_uuid + +Generate UUIDs for Geographic Information messages. + +.. deprecated:: 0.3.0 + +*This module was removed with version 0.4.0 in ROS Indigo.* + +Instead, use the `unique_id`_ package, which has been stable and +available since ROS Fuerte: + + * ``geodesy.gen_uuid.generate(url, id)`` becomes + ``unique_id.fromURL(url+str(id))`` + + * ``geodesy.gen_uuid.makeUniqueID(url, id)`` becomes + ``unique_id.toMsg(unique_id.fromURL(url+str(id)))`` + +.. _`unique_id`: http://wiki.ros.org/unique_id diff --git a/navigations/geographic_info/geodesy/doc/geodesy.props.rst b/navigations/geographic_info/geodesy/doc/geodesy.props.rst new file mode 100755 index 0000000..2a511f9 --- /dev/null +++ b/navigations/geographic_info/geodesy/doc/geodesy.props.rst @@ -0,0 +1,5 @@ +geodesy.props +------------- + +.. automodule:: geodesy.props + :members: diff --git a/navigations/geographic_info/geodesy/doc/geodesy.utm.rst b/navigations/geographic_info/geodesy/doc/geodesy.utm.rst new file mode 100755 index 0000000..93c5ee0 --- /dev/null +++ b/navigations/geographic_info/geodesy/doc/geodesy.utm.rst @@ -0,0 +1,5 @@ +geodesy.utm +----------- + +.. automodule:: geodesy.utm + :members: diff --git a/navigations/geographic_info/geodesy/doc/geodesy.wu_point.rst b/navigations/geographic_info/geodesy/doc/geodesy.wu_point.rst new file mode 100755 index 0000000..41abdf9 --- /dev/null +++ b/navigations/geographic_info/geodesy/doc/geodesy.wu_point.rst @@ -0,0 +1,5 @@ +geodesy.wu_point +---------------- + +.. automodule:: geodesy.wu_point + :members: diff --git a/navigations/geographic_info/geodesy/doc/index.rst b/navigations/geographic_info/geodesy/doc/index.rst new file mode 100755 index 0000000..3809f57 --- /dev/null +++ b/navigations/geographic_info/geodesy/doc/index.rst @@ -0,0 +1,22 @@ +.. geodesy documentation master file, created by + sphinx-quickstart on Wed Apr 25 16:01:20 2012. + You can adapt this file completely to your liking, but it should at least + contain the root `toctree` directive. + +geodesy: Python APIs for Geographic coordinates +=============================================== + +Contents: + +.. toctree:: + :maxdepth: 2 + :glob: + + geodesy.* + CHANGELOG + +Indices and tables +================== + +* :ref:`genindex` +* :ref:`modindex` diff --git a/navigations/geographic_info/geodesy/include/geodesy/utm.h b/navigations/geographic_info/geodesy/include/geodesy/utm.h new file mode 100755 index 0000000..7122ddf --- /dev/null +++ b/navigations/geographic_info/geodesy/include/geodesy/utm.h @@ -0,0 +1,266 @@ +/* -*- mode: C++ -*- */ +/* $Id: 284edbd641a3576af22c2d4fbe5f27f1d17ec24d $ */ + +/********************************************************************* +* Software License Agreement (BSD License) +* +* Copyright (C) 2011 Jack O'Quin +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of the author nor other contributors may be +* used to endorse or promote products derived from this software +* without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +*********************************************************************/ + +#ifndef _UTM_H_ +#define _UTM_H_ + +#include +#include +#include +#include + +#include + +#include +#include +#include + +/** @file + + @brief Universal Transverse Mercator coordinates + + For outdoor robotics applications, Euclidean projections like UTM + are easier to work with than latitude and longitude. This system + is slightly more general than strict UTM. It is based on the + Military Grid Reference System (MGRS), which can be extended to + cover the poles, allowing well-defined transformations for every + latitude and longitude. + + @todo add Universal Polar Stereographic support + + @author Jack O'Quin + */ + +namespace geodesy +{ + +/** Universal Transverse Mercator (UTM) point. + * + * The @c altitude may be specified (3D) or not (2D). The @c + * altitude of a 2D point is not a number (NaN). + * + * Including the top-level grid zone designator (GZD) from the + * Military Grid Reference System (MGRS) permits unambiguous use of + * Universal Polar Stereographic (UPS) coordinates for the polar + * regions not covered by UTM, making this representation more + * general than pure UTM. + */ +class UTMPoint +{ + public: + + /** Null constructor. Makes a 2D, invalid point object. */ + UTMPoint(): + easting(0.0), + northing(0.0), + altitude(std::numeric_limits::quiet_NaN()), + zone(0), + band(' ') + {} + + /** Copy constructor. */ + UTMPoint(const UTMPoint &that): + easting(that.easting), + northing(that.northing), + altitude(that.altitude), + zone(that.zone), + band(that.band) + {} + + UTMPoint(const geographic_msgs::GeoPoint &pt); + + /** Create a flattened 2-D grid point. */ + UTMPoint(double _easting, double _northing, uint8_t _zone, char _band): + easting(_easting), + northing(_northing), + altitude(std::numeric_limits::quiet_NaN()), + zone(_zone), + band(_band) + {} + + /** Create a 3-D grid point. */ + UTMPoint(double _easting, double _northing, double _altitude, + uint8_t _zone, char _band): + easting(_easting), + northing(_northing), + altitude(_altitude), + zone(_zone), + band(_band) + {} + + // data members + double easting; ///< easting within grid zone [meters] + double northing; ///< northing within grid zone [meters] + double altitude; ///< altitude above ellipsoid [meters] or NaN + uint8_t zone; ///< UTM longitude zone number + char band; ///< MGRS latitude band letter + +}; // class UTMPoint + +/** Universal Transverse Mercator (UTM) pose */ +class UTMPose +{ + public: + + /** Null constructor. Makes a 2D, invalid pose object. */ + UTMPose(): + position(), + orientation() + {} + + /** Copy constructor. */ + UTMPose(const UTMPose &that): + position(that.position), + orientation(that.orientation) + {} + + /** Create from a WGS 84 geodetic pose. */ + UTMPose(const geographic_msgs::GeoPose &pose): + position(pose.position), + orientation(pose.orientation) + {} + + /** Create from a UTMPoint and a quaternion. */ + UTMPose(UTMPoint pt, + const geometry_msgs::Quaternion &q): + position(pt), + orientation(q) + {} + + /** Create from a WGS 84 geodetic point and a quaternion. */ + UTMPose(const geographic_msgs::GeoPoint &pt, + const geometry_msgs::Quaternion &q): + position(pt), + orientation(q) + {} + + // data members + UTMPoint position; + geometry_msgs::Quaternion orientation; + +}; // class UTMPose + +// conversion function prototypes +void fromMsg(const geographic_msgs::GeoPoint &from, UTMPoint &to, + const bool& force_zone=false, const char& band='A', const uint8_t& zone=0 ); +void fromMsg(const geographic_msgs::GeoPose &from, UTMPose &to, + const bool& force_zone=false, const char& band='A', const uint8_t& zone=0 ); +geographic_msgs::GeoPoint toMsg(const UTMPoint &from); +geographic_msgs::GeoPose toMsg(const UTMPose &from); + +/** @return true if no altitude specified. */ +static inline bool is2D(const UTMPoint &pt) +{ + // true if altitude is a NaN + return (pt.altitude != pt.altitude); +} + +/** @return true if no altitude specified. */ +static inline bool is2D(const UTMPose &pose) +{ + // true if position has no altitude + return is2D(pose.position); +} + +bool isValid(const UTMPoint &pt); +bool isValid(const UTMPose &pose); + +/** Normalize UTM point. + * + * Ensures the point is within its canonical grid zone. + */ +static inline void normalize(UTMPoint &pt) +{ + geographic_msgs::GeoPoint ll(toMsg(pt)); + normalize(ll); + fromMsg(ll, pt); +} + +/** Output stream operator for UTM point. */ +static inline std::ostream& operator<<(std::ostream& out, const UTMPoint &pt) +{ + out << "(" << std::setprecision(10) << pt.easting << ", " + << pt.northing << ", " << std::setprecision(6) << pt.altitude + << " [" << (unsigned) pt.zone << pt.band << "])"; + return out; +} + +/** Output stream operator for UTM pose. */ +static inline std::ostream& operator<<(std::ostream& out, const UTMPose &pose) +{ + out << pose.position << ", ([" + << pose.orientation.x << ", " + << pose.orientation.y << ", " + << pose.orientation.z << "], " + << pose.orientation.w << ")"; + return out; +} + +/** @return true if two points have the same Grid Zone Designator */ +static inline bool sameGridZone(const UTMPoint &pt1, const UTMPoint &pt2) +{ + return ((pt1.zone == pt2.zone) && (pt1.band == pt2.band)); +} + +/** @return true if two poses have the same Grid Zone Designator */ +static inline bool sameGridZone(const UTMPose &pose1, const UTMPose &pose2) +{ + return sameGridZone(pose1.position, pose2.position); +} + +/** @return a geometry Point corresponding to a UTM point. */ +static inline geometry_msgs::Point toGeometry(const UTMPoint &from) +{ + geometry_msgs::Point to; + to.x = from.easting; + to.y = from.northing; + to.z = from.altitude; + return to; +} + +/** @return a geometry Pose corresponding to a UTM pose. */ +static inline geometry_msgs::Pose toGeometry(const UTMPose &from) +{ + geometry_msgs::Pose to; + to.position = toGeometry(from.position); + to.orientation = from.orientation; + return to; +} + +}; // namespace geodesy + +#endif // _UTM_H_ diff --git a/navigations/geographic_info/geodesy/include/geodesy/wgs84.h b/navigations/geographic_info/geodesy/include/geodesy/wgs84.h new file mode 100755 index 0000000..d34970a --- /dev/null +++ b/navigations/geographic_info/geodesy/include/geodesy/wgs84.h @@ -0,0 +1,241 @@ +/* -*- mode: C++ -*- */ +/* $Id: 7290b1e8d933f52fa8cbf73baaf239c93a783478 $ */ + +/********************************************************************* +* Software License Agreement (BSD License) +* +* Copyright (C) 2011 Jack O'Quin +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of the author nor other contributors may be +* used to endorse or promote products derived from this software +* without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +*********************************************************************/ + +#ifndef _WGS84_H_ +#define _WGS84_H_ + +#include +#include +#include +#include +#include +#include + +/** @file + + @brief WGS 84 geodetic system for ROS latitude and longitude messages + + Standard ROS latitude and longitude coordinates are defined in + terms of the World Geodetic System (WGS 84) ellipsoid used by most + navigation satellite receivers. + + Many other geodetic coordinate systems can be defined. They + should always be converted to WGS 84 when publishing ROS messages + to avoid confusion among subscribers. + + @author Jack O'Quin + */ + +namespace geodesy +{ + /** Convert any coordinate to any other via intermediate WGS 84 + * representation. + * + * @author Tully Foote + * + * @note Every coordinate type @b must implement fromMsg() and + * toMsg() functions for both points and poses. + */ + template + void convert(const From &from, To &to); + + /** Convert any coordinate to itself. */ + template + void convert(const Same &from, Same &to); + + /** Convert one WGS 84 geodetic point to another. + * + * @param from WGS 84 point message. + * @param to another point. + */ + static inline void fromMsg(const geographic_msgs::GeoPoint &from, + geographic_msgs::GeoPoint &to) + { + convert(from, to); + } + + /** Convert one WGS 84 geodetic pose to another. + * + * @param from WGS 84 pose message. + * @param to another pose. + */ + static inline void fromMsg(const geographic_msgs::GeoPose &from, + geographic_msgs::GeoPose &to) + { + convert(from, to); + } + + /** @return true if no altitude specified. */ + static inline bool is2D(const geographic_msgs::GeoPoint &pt) + { + return (pt.altitude != pt.altitude); + } + + /** @return true if pose has no altitude. */ + static inline bool is2D(const geographic_msgs::GeoPose &pose) + { + return is2D(pose.position); + } + + /** @return true if point is valid. */ + static inline bool isValid(const geographic_msgs::GeoPoint &pt) + { + if (pt.latitude < -90.0 || pt.latitude > 90.0) + return false; + + if (pt.longitude < -180.0 || pt.longitude >= 180.0) + return false; + + return true; + } + + /** @return true if pose is valid. */ + static inline bool isValid(const geographic_msgs::GeoPose &pose) + { + // check that orientation quaternion is normalized + double len2 = (pose.orientation.x * pose.orientation.x + + pose.orientation.y * pose.orientation.y + + pose.orientation.z * pose.orientation.z + + pose.orientation.w * pose.orientation.w); + if (fabs(len2 - 1.0) > tf::QUATERNION_TOLERANCE) + return false; + + return isValid(pose.position); + } + + /** Normalize a WGS 84 geodetic point. + * + * @param pt point to normalize. + * + * Normalizes the longitude to [-180, 180). + * Clamps latitude to [-90, 90]. + */ + static inline void normalize(geographic_msgs::GeoPoint &pt) + { + pt.longitude = + (fmod(fmod((pt.longitude + 180.0), 360.0) + 360.0, 360.0) - 180.0); + pt.latitude = std::min(std::max(pt.latitude, -90.0), 90.0); + } + + /** @return a 2D WGS 84 geodetic point message. */ + static inline geographic_msgs::GeoPoint toMsg(double lat, double lon) + { + geographic_msgs::GeoPoint pt; + pt.latitude = lat; + pt.longitude = lon; + pt.altitude = std::numeric_limits::quiet_NaN(); + return pt; + } + + /** @return a 3D WGS 84 geodetic point message. */ + static inline geographic_msgs::GeoPoint + toMsg(double lat, double lon, double alt) + { + geographic_msgs::GeoPoint pt; + pt.latitude = lat; + pt.longitude = lon; + pt.altitude = alt; + return pt; + } + + /** @return a WGS 84 geodetic point message from a NavSatFix. */ + static inline geographic_msgs::GeoPoint + toMsg(const sensor_msgs::NavSatFix &fix) + { + geographic_msgs::GeoPoint pt; + pt.latitude = fix.latitude; + pt.longitude = fix.longitude; + pt.altitude = fix.altitude; + return pt; + } + + /** @return a WGS 84 geodetic point message from another. */ + static inline geographic_msgs::GeoPoint + toMsg(const geographic_msgs::GeoPoint &from) + { + return from; + } + + /** @return a WGS 84 geodetic pose message from a point and a + * quaternion. + */ + static inline geographic_msgs::GeoPose + toMsg(const geographic_msgs::GeoPoint &pt, + const geometry_msgs::Quaternion &q) + { + geographic_msgs::GeoPose pose; + pose.position = pt; + pose.orientation = q; + return pose; + } + + /** @return a WGS 84 geodetic pose message from a NavSatFix and a + * quaternion. + */ + static inline geographic_msgs::GeoPose + toMsg(const sensor_msgs::NavSatFix &fix, + const geometry_msgs::Quaternion &q) + { + geographic_msgs::GeoPose pose; + pose.position = toMsg(fix); + pose.orientation = q; + return pose; + } + + /** @return a WGS 84 geodetic pose message from another. */ + static inline geographic_msgs::GeoPose + toMsg(const geographic_msgs::GeoPose &from) + { + return from; + } + + template + void convert(const From &from, To &to) + { + fromMsg(toMsg(from), to); + } + + template + void convert(const Same &from, Same &to) + { + if (&from != &to) + to = from; + } + +}; // namespace geodesy + +#endif // _WGS84_H_ diff --git a/navigations/geographic_info/geodesy/mainpage.dox b/navigations/geographic_info/geodesy/mainpage.dox new file mode 100755 index 0000000..33846fb --- /dev/null +++ b/navigations/geographic_info/geodesy/mainpage.dox @@ -0,0 +1,9 @@ +/** +\mainpage +\htmlinclude manifest.html + +This package provides C++ APIs for manipulating geodetic coordinates. + +It has no nodes, utilities, or scripts. + +*/ diff --git a/navigations/geographic_info/geodesy/package.xml b/navigations/geographic_info/geodesy/package.xml new file mode 100755 index 0000000..0335aa3 --- /dev/null +++ b/navigations/geographic_info/geodesy/package.xml @@ -0,0 +1,52 @@ + + + + geodesy + 0.5.6 + + Python and C++ interfaces for manipulating geodetic coordinates. + + Jack O'Quin + Steve Macenski + Jack O'Quin + BSD + + http://wiki.ros.org/geodesy + https://github.com/ros-geographic-info/geographic_info/issues + https://github.com/ros-geographic-info/geographic_info.git + + catkin + + angles + geographic_msgs + geometry_msgs + sensor_msgs + tf + unique_id + uuid_msgs + + geographic_msgs + geometry_msgs + tf + sensor_msgs + unique_id + uuid_msgs + + python-pyproj + python3-pyproj + + python-setuptools + python3-setuptools + + + rosunit + + + python-catkin-pkg-modules + python3-catkin-pkg-modules + + + + + + diff --git a/navigations/geographic_info/geodesy/rosdoc.yaml b/navigations/geographic_info/geodesy/rosdoc.yaml new file mode 100755 index 0000000..1ad8a9d --- /dev/null +++ b/navigations/geographic_info/geodesy/rosdoc.yaml @@ -0,0 +1,9 @@ + - builder: doxygen + name: C++ API + output_dir: c++ + file_patterns: '*.c *.cpp *.h *.cc *.hh *.dox' + - builder: sphinx + name: Python API + sphinx_root_dir: doc + output_dir: python + diff --git a/navigations/geographic_info/geodesy/setup.py b/navigations/geographic_info/geodesy/setup.py new file mode 100755 index 0000000..6cf0c06 --- /dev/null +++ b/navigations/geographic_info/geodesy/setup.py @@ -0,0 +1,11 @@ +#!/usr/bin/env python + +from catkin_pkg.python_setup import generate_distutils_setup +from setuptools import setup + +d = generate_distutils_setup( + packages=['geodesy'], + package_dir={'': 'src'}, + ) + +setup(**d) diff --git a/navigations/geographic_info/geodesy/src/conv/utm_conversions.cpp b/navigations/geographic_info/geodesy/src/conv/utm_conversions.cpp new file mode 100755 index 0000000..890ebc7 --- /dev/null +++ b/navigations/geographic_info/geodesy/src/conv/utm_conversions.cpp @@ -0,0 +1,339 @@ +/* $Id: 67e70c2a6633d089c804653bac18a8b325f3082b $ */ + +/********************************************************************* +* Software License Agreement (BSD License) +* +* Copyright (C) 2011 Chuck Gantz, Jack O'Quin +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of the author nor other contributors may be +* used to endorse or promote products derived from this software +* without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +*********************************************************************/ + +//#include +#include +#include +#include + +/** @file + + @brief Universal Transverse Mercator transforms. + + Functions to convert WGS 84 (ellipsoidal) latitude and longitude + to and from (Euclidean) UTM coordinates. + + @todo handle Universal Polar Stereographic (UPS) zones + + @author Chuck Gantz, Globalstar, Inc. + @author Jack O'Quin, for ROS interface +*/ + +namespace geodesy +{ + +// WGS84 Parameters +#define WGS84_A 6378137.0 // major axis +#define WGS84_B 6356752.31424518 // minor axis +#define WGS84_F 0.0033528107 // ellipsoid flattening +#define WGS84_E 0.0818191908 // first eccentricity +#define WGS84_EP 0.0820944379 // second eccentricity + +// UTM Parameters +#define UTM_K0 0.9996 // scale factor +#define UTM_FE 500000.0 // false easting +#define UTM_FN_N 0.0 // false northing, northern hemisphere +#define UTM_FN_S 10000000.0 // false northing, southern hemisphere +#define UTM_E2 (WGS84_E*WGS84_E) // e^2 +#define UTM_E4 (UTM_E2*UTM_E2) // e^4 +#define UTM_E6 (UTM_E4*UTM_E2) // e^6 +#define UTM_EP2 (UTM_E2/(1-UTM_E2)) // e'^2 + + +/** + * Determine the correct UTM band letter for the given latitude. + * (Does not currently handle polar (UPS) zones: A, B, Y, Z). + * + * @return ' ' if latitude is outside the UTM limits of +84 to -80 + */ +static char UTMBand(double Lat, double Lon) +{ + char LetterDesignator; + + if ((84 >= Lat) && (Lat >= 72)) LetterDesignator = 'X'; + else if ((72 > Lat) && (Lat >= 64)) LetterDesignator = 'W'; + else if ((64 > Lat) && (Lat >= 56)) LetterDesignator = 'V'; + else if ((56 > Lat) && (Lat >= 48)) LetterDesignator = 'U'; + else if ((48 > Lat) && (Lat >= 40)) LetterDesignator = 'T'; + else if ((40 > Lat) && (Lat >= 32)) LetterDesignator = 'S'; + else if ((32 > Lat) && (Lat >= 24)) LetterDesignator = 'R'; + else if ((24 > Lat) && (Lat >= 16)) LetterDesignator = 'Q'; + else if ((16 > Lat) && (Lat >= 8)) LetterDesignator = 'P'; + else if (( 8 > Lat) && (Lat >= 0)) LetterDesignator = 'N'; + else if (( 0 > Lat) && (Lat >= -8)) LetterDesignator = 'M'; + else if ((-8 > Lat) && (Lat >= -16)) LetterDesignator = 'L'; + else if((-16 > Lat) && (Lat >= -24)) LetterDesignator = 'K'; + else if((-24 > Lat) && (Lat >= -32)) LetterDesignator = 'J'; + else if((-32 > Lat) && (Lat >= -40)) LetterDesignator = 'H'; + else if((-40 > Lat) && (Lat >= -48)) LetterDesignator = 'G'; + else if((-48 > Lat) && (Lat >= -56)) LetterDesignator = 'F'; + else if((-56 > Lat) && (Lat >= -64)) LetterDesignator = 'E'; + else if((-64 > Lat) && (Lat >= -72)) LetterDesignator = 'D'; + else if((-72 > Lat) && (Lat >= -80)) LetterDesignator = 'C'; + // '_' is an error flag, the Latitude is outside the UTM limits + else LetterDesignator = ' '; + + return LetterDesignator; +} + +/** Convert UTM point to WGS 84 geodetic point. + * + * Equations from USGS Bulletin 1532 + * + * @param from UTM point. + * @return WGS 84 point message. + */ +geographic_msgs::GeoPoint toMsg(const UTMPoint &from) +{ + //remove 500,000 meter offset for longitude + double x = from.easting - 500000.0; + double y = from.northing; + + double k0 = UTM_K0; + double a = WGS84_A; + double eccSquared = UTM_E2; + double eccPrimeSquared; + double e1 = (1-sqrt(1-eccSquared))/(1+sqrt(1-eccSquared)); + double N1, T1, C1, R1, D, M; + double LongOrigin; + double mu, phi1Rad; + + if ((from.band - 'N') < 0) + { + //point is in southern hemisphere + //remove 10,000,000 meter offset used for southern hemisphere + y -= 10000000.0; + } + + //+3 puts origin in middle of zone + LongOrigin = (from.zone - 1)*6 - 180 + 3; + eccPrimeSquared = (eccSquared)/(1-eccSquared); + + M = y / k0; + mu = M/(a*(1-eccSquared/4-3*eccSquared*eccSquared/64 + -5*eccSquared*eccSquared*eccSquared/256)); + + phi1Rad = mu + ((3*e1/2-27*e1*e1*e1/32)*sin(2*mu) + + (21*e1*e1/16-55*e1*e1*e1*e1/32)*sin(4*mu) + + (151*e1*e1*e1/96)*sin(6*mu)); + + N1 = a/sqrt(1-eccSquared*sin(phi1Rad)*sin(phi1Rad)); + T1 = tan(phi1Rad)*tan(phi1Rad); + C1 = eccPrimeSquared*cos(phi1Rad)*cos(phi1Rad); + R1 = a*(1-eccSquared)/pow(1-eccSquared*sin(phi1Rad)*sin(phi1Rad), 1.5); + D = x/(N1*k0); + + // function result + geographic_msgs::GeoPoint to; + to.altitude = from.altitude; + to.latitude = + phi1Rad - ((N1*tan(phi1Rad)/R1) + *(D*D/2 + -(5+3*T1+10*C1-4*C1*C1-9*eccPrimeSquared)*D*D*D*D/24 + +(61+90*T1+298*C1+45*T1*T1-252*eccPrimeSquared + -3*C1*C1)*D*D*D*D*D*D/720)); + to.latitude = angles::to_degrees(to.latitude); + to.longitude = ((D-(1+2*T1+C1)*D*D*D/6 + +(5-2*C1+28*T1-3*C1*C1+8*eccPrimeSquared+24*T1*T1) + *D*D*D*D*D/120) + / cos(phi1Rad)); + to.longitude = LongOrigin + angles::to_degrees(to.longitude); + + // Normalize latitude and longitude to valid ranges. + normalize(to); + return to; +} + +/** Convert WGS 84 geodetic point to UTM point. + * + * Equations from USGS Bulletin 1532 + * + * @param from WGS 84 point message. + * @param to UTM point. + */ +void fromMsg(const geographic_msgs::GeoPoint &from, UTMPoint &to, + const bool& force_zone, const char& band, const uint8_t& zone) +{ + double Lat = from.latitude; + double Long = from.longitude; + + double a = WGS84_A; + double eccSquared = UTM_E2; + double k0 = UTM_K0; + + double LongOrigin; + double eccPrimeSquared; + double N, T, C, A, M; + + // Make sure the longitude is between -180.00 .. 179.9 + // (JOQ: this is broken for Long < -180, do a real normalize) + double LongTemp = (Long+180)-int((Long+180)/360)*360-180; + double LatRad = angles::from_degrees(Lat); + double LongRad = angles::from_degrees(LongTemp); + double LongOriginRad; + + to.altitude = from.altitude; + if (!force_zone) + to.zone = int((LongTemp + 180)/6) + 1; + else + to.zone = zone; + + if( Lat >= 56.0 && Lat < 64.0 && LongTemp >= 3.0 && LongTemp < 12.0 ) + to.zone = 32; + + // Special zones for Svalbard + if( Lat >= 72.0 && Lat < 84.0 ) + { + if( LongTemp >= 0.0 && LongTemp < 9.0 ) to.zone = 31; + else if( LongTemp >= 9.0 && LongTemp < 21.0 ) to.zone = 33; + else if( LongTemp >= 21.0 && LongTemp < 33.0 ) to.zone = 35; + else if( LongTemp >= 33.0 && LongTemp < 42.0 ) to.zone = 37; + } + // +3 puts origin in middle of zone + LongOrigin = (to.zone - 1)*6 - 180 + 3; + LongOriginRad = angles::from_degrees(LongOrigin); + + // compute the UTM band from the latitude + if (!force_zone) + to.band = UTMBand(Lat, LongTemp); + else + to.band = band; + + + +#if 0 + if (to.band == ' ') + throw std::range_error; +#endif + + eccPrimeSquared = (eccSquared)/(1-eccSquared); + + N = a/sqrt(1-eccSquared*sin(LatRad)*sin(LatRad)); + T = tan(LatRad)*tan(LatRad); + C = eccPrimeSquared*cos(LatRad)*cos(LatRad); + A = cos(LatRad)*(LongRad-LongOriginRad); + + M = a*((1 - eccSquared/4 - 3*eccSquared*eccSquared/64 + - 5*eccSquared*eccSquared*eccSquared/256) * LatRad + - (3*eccSquared/8 + 3*eccSquared*eccSquared/32 + + 45*eccSquared*eccSquared*eccSquared/1024)*sin(2*LatRad) + + (15*eccSquared*eccSquared/256 + + 45*eccSquared*eccSquared*eccSquared/1024)*sin(4*LatRad) + - (35*eccSquared*eccSquared*eccSquared/3072)*sin(6*LatRad)); + + to.easting = (double) + (k0*N*(A+(1-T+C)*A*A*A/6 + + (5-18*T+T*T+72*C-58*eccPrimeSquared)*A*A*A*A*A/120) + + 500000.0); + + to.northing = (double) + (k0*(M+N*tan(LatRad) + *(A*A/2+(5-T+9*C+4*C*C)*A*A*A*A/24 + + (61-58*T+T*T+600*C-330*eccPrimeSquared)*A*A*A*A*A*A/720))); + + if(Lat < 0) + { + //10000000 meter offset for southern hemisphere + to.northing += 10000000.0; + } +} + +/** @return true if point is valid. */ +bool isValid(const UTMPoint &pt) +{ + if (pt.zone < 1 || pt.zone > 60) + return false; + + if (!isupper(pt.band) || pt.band == 'I' || pt.band == 'O') + return false; + + // The Universal Polar Stereographic bands are not currently + // supported. When they are: A, B, Y and Z will be valid (and the + // zone number will be ignored). + if (pt.band < 'C' || pt.band > 'X') + return false; + + return true; +} + +/** Create UTM point from WGS 84 geodetic point. */ +UTMPoint::UTMPoint(const geographic_msgs::GeoPoint &pt) +{ + fromMsg(pt, *this); +} + +/** Convert UTM pose to WGS 84 geodetic pose. + * + * @param from UTM pose. + * @return WGS 84 pose message. + */ +geographic_msgs::GeoPose toMsg(const UTMPose &from) +{ + geographic_msgs::GeoPose to; + to.position = toMsg(from.position); + to.orientation = from.orientation; + return to; +} + +/** Convert WGS 84 geodetic pose to UTM pose. + * + * @param from WGS 84 pose message. + * @param to UTM pose. + * + * @todo define the orientation transformation properly + */ +void fromMsg(const geographic_msgs::GeoPose &from, UTMPose &to, + const bool& force_zone, const char& band, const uint8_t& zone) +{ + fromMsg(from.position, to.position, force_zone, band, zone); + to.orientation = from.orientation; +} + +/** @return true if pose is valid. */ +bool isValid(const UTMPose &pose) +{ + if (!isValid(pose.position)) + return false; + + // check that orientation quaternion is normalized + double len2 = (pose.orientation.x * pose.orientation.x + + pose.orientation.y * pose.orientation.y + + pose.orientation.z * pose.orientation.z + + pose.orientation.w * pose.orientation.w); + return fabs(len2 - 1.0) <= tf::QUATERNION_TOLERANCE; +} + +} // end namespace geodesy diff --git a/navigations/geographic_info/geodesy/src/geodesy/__init__.py b/navigations/geographic_info/geodesy/src/geodesy/__init__.py new file mode 100755 index 0000000..e69de29 diff --git a/navigations/geographic_info/geodesy/src/geodesy/bounding_box.py b/navigations/geographic_info/geodesy/src/geodesy/bounding_box.py new file mode 100755 index 0000000..625934b --- /dev/null +++ b/navigations/geographic_info/geodesy/src/geodesy/bounding_box.py @@ -0,0 +1,126 @@ +# Software License Agreement (BSD License) +# +# Copyright (C) 2012, Jack O'Quin +# All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# * Redistributions in binary form must reproduce the above +# copyright notice, this list of conditions and the following +# disclaimer in the documentation and/or other materials provided +# with the distribution. +# * Neither the name of the author nor of other contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. + +""" +.. module:: bounding_box + +Bounding box functions for geographic maps. + +.. _`geographic_msgs/BoundingBox`: http://ros.org/doc/api/geographic_msgs/html/msg/BoundingBox.html + +""" + +from geographic_msgs.msg import BoundingBox + +def getLatLong(bbox): + """ + Get the tuple of minimum and maximum latitudes and longitudes. + + :param bbox: `geographic_msgs/BoundingBox`_. + :returns: (min_lat, min_lon, max_lat, max_lon) + """ + return (bbox.min_pt.latitude, bbox.min_pt.longitude, + bbox.max_pt.latitude, bbox.max_pt.longitude) + +def is2D(bbox): + """ + Two-dimensional bounding box predicate. + + :param bbox: `geographic_msgs/BoundingBox`_. + :returns: True if *bbox* matches any altitude. + """ + return bbox.min_pt.altitude != bbox.min_pt.altitude + +def isGlobal(bbox): + """ + Global bounding box predicate. + + :param bbox: `geographic_msgs/BoundingBox`_. + :returns: True if *bbox* matches any global coordinate. + """ + return bbox.min_pt.latitude != bbox.min_pt.latitude + +def makeBounds2D(min_lat, min_lon, max_lat, max_lon): + """ + Create a 2D geographic bounding box (ignoring altitudes). + + :param min_lat: Minimum latitude. + :param min_lon: Minimum longitude. + :param max_lat: Maximum latitude. + :param max_lon: Maximum longitude. + :returns: `geographic_msgs/BoundingBox`_ object. + """ + bbox = BoundingBox() + bbox.min_pt.latitude = min_lat + bbox.min_pt.longitude = min_lon + bbox.min_pt.altitude = float('nan') + bbox.max_pt.latitude = max_lat + bbox.max_pt.longitude = max_lon + bbox.max_pt.altitude = float('nan') + return bbox + +def makeBounds3D(min_lat, min_lon, min_alt, + max_lat, max_lon, max_alt): + """ + Create a 3D geographic bounding box (including altitudes). + + :param min_lat: Minimum latitude. + :param min_lon: Minimum longitude. + :param min_alt: Minimum altitude. + :param max_lat: Maximum latitude. + :param max_lon: Maximum longitude. + :param max_alt: Maximum altitude. + :returns: `geographic_msgs/BoundingBox`_ object. + """ + bbox = BoundingBox() + bbox.min_pt.latitude = min_lat + bbox.min_pt.longitude = min_lon + bbox.min_pt.altitude = min_alt + bbox.max_pt.latitude = max_lat + bbox.max_pt.longitude = max_lon + bbox.max_pt.altitude = max_alt + return bbox + +def makeGlobal(): + """ + Create a global bounding box, which matches any valid coordinate. + + :returns: `geographic_msgs/BoundingBox`_ object. + """ + bbox = BoundingBox() + bbox.min_pt.latitude = float('nan') + bbox.min_pt.longitude = float('nan') + bbox.min_pt.altitude = float('nan') + bbox.max_pt.latitude = float('nan') + bbox.max_pt.longitude = float('nan') + bbox.max_pt.altitude = float('nan') + return bbox diff --git a/navigations/geographic_info/geodesy/src/geodesy/props.py b/navigations/geographic_info/geodesy/src/geodesy/props.py new file mode 100755 index 0000000..6b27353 --- /dev/null +++ b/navigations/geographic_info/geodesy/src/geodesy/props.py @@ -0,0 +1,87 @@ +# Software License Agreement (BSD License) +# +# Copyright (C) 2012, Jack O'Quin +# All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# * Redistributions in binary form must reproduce the above +# copyright notice, this list of conditions and the following +# disclaimer in the documentation and/or other materials provided +# with the distribution. +# * Neither the name of the author nor of other contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. + +""" +.. module:: props + +`geographic_msgs/KeyValue`_ property interface for Geographic Information messages. + +.. _`geographic_msgs/KeyValue`: http://ros.org/doc/api/geographic_msgs/html/msg/KeyValue.html + +""" + +from geographic_msgs.msg import KeyValue + +def get(msg, key): + """ Get property value. + + :param msg: Message containing properties. + :param key: Property key to match. + + :returns: Corresponding value, if defined; None otherwise. + Beware: the value may be '', which evaluates False as a + predicate, use ``is not None`` to test for presence. + """ + for prop in msg.props: + if prop.key == key: + return prop.value + return None + +def match(msg, key_set): + """ Match message properties. + + :param msg: Message containing properties. + :param key_set: Set of property keys to match. + :returns: (key, value) of first property matched; None otherwise. + :raises: :exc:`ValueError` if key_set is not a set + """ + if type(key_set) is not set: + raise ValueError('property matching requires a set of keys') + for prop in msg.props: + if prop.key in key_set: + return (prop.key, prop.value) + return None + +def put(msg, key, val=''): + """ Add KeyValue to message properties. + + :param msg: Message to update. + :param key: Property key name. + :param value: Corresponding value string (default ''). + """ + for prop in msg.props: + if prop.key == key: + # key already present, update value + prop.value = str(val) + return + # key missing, append a new KeyValue pair + msg.props.append(KeyValue(key=key, value=str(val))) diff --git a/navigations/geographic_info/geodesy/src/geodesy/utm.py b/navigations/geographic_info/geodesy/src/geodesy/utm.py new file mode 100755 index 0000000..6648337 --- /dev/null +++ b/navigations/geographic_info/geodesy/src/geodesy/utm.py @@ -0,0 +1,191 @@ +# Software License Agreement (BSD License) +# +# Copyright (C) 2012, Jack O'Quin +# All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# * Redistributions in binary form must reproduce the above +# copyright notice, this list of conditions and the following +# disclaimer in the documentation and/or other materials provided +# with the distribution. +# * Neither the name of the author nor of other contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. + +""" +.. module:: utm + +Universal Transverse Mercator coordinate module. + +:todo: add Universal Polar Stereographic (UPS_) support + +.. _MGRS: http://en.wikipedia.org/wiki/Military_grid_reference_system +.. _`PROJ.4`: http://trac.osgeo.org/proj/ +.. _pyproj: http://pypi.python.org/pypi/pyproj +.. _UPS: http://en.wikipedia.org/wiki/Universal_Polar_Stereographic_coordinate_system +.. _UTM: http://en.wikipedia.org/wiki/Universal_Transverse_Mercator_coordinate_system + +.. _`geometry_msgs/Point`: http://ros.org/doc/api/geometry_msgs/html/msg/Point.html +.. _`geographic_msgs/GeoPoint`: http://ros.org/doc/api/geographic_msgs/html/msg/GeoPoint.html + +""" + +import math +import pyproj + +from geographic_msgs.msg import GeoPoint +from geometry_msgs.msg import Point + +class UTMPoint: + """Universal Transverse Mercator (UTM_) point class. + + For outdoor robotics applications, Euclidean projections like UTM_ + are easier to work with than latitude and longitude. This system + is slightly more general than strict UTM. It is based on the + Military Grid Reference System (MGRS_), which can be extended to + cover the poles, allowing well-defined transformations for every + latitude and longitude. + + This implementation uses the pyproj_ wrapper for the `PROJ.4`_ + Cartographic Projections Library. + + :param easting: UTM easting (meters) + :param northing: UTM northing (meters) + :param altitude: altitude above the WGS84 ellipsoid (meters), + none if NaN. + :param zone: UTM longitude zone + :param band: MGRS latitude band letter + + """ + + def __init__(self, easting=float('nan'), northing=float('nan'), + altitude=float('nan'), zone=0, band=' '): + """Construct UTMPoint object. """ + self.easting = easting + self.northing = northing + self.altitude = altitude + self.zone = zone + self.band = band + + def __str__(self): + """ :returns: string representation of :class:`UTMPoint`. """ + # uses python3-compatible str.format() method: + return 'UTM: [{0:.3f}, {1:.3f}, {2:.3f}, {3}{4}]'.format( + self.easting, self.northing, self.altitude, self.zone, self.band) + + def gridZone(self): + """:returns: (zone, band) tuple. """ + return (self.zone, self.band) + + def is2D(self): + """:returns: True if altitude is not defined.""" + return self.altitude != self.altitude + + def toPoint(self): + """:returns: corresponding `geometry_msgs/Point`_ message. + :todo: clamp message longitude to [-180..180] + """ + if not self.valid(): + raise ValueError('invalid UTM point: ' + str(self)) + pt = Point(x = self.easting, y = self.northing) + if not self.is2D(): + pt.z = self.altitude + return pt + + def toMsg(self): + """:returns: corresponding `geographic_msgs/GeoPoint`_ message. + :todo: clamp message longitude to [-180..180] + """ + if not self.valid(): + raise ValueError('invalid UTM point: ' + str(self)) + utm_proj = pyproj.Proj(proj='utm', zone=self.zone, datum='WGS84') + msg = GeoPoint(altitude=self.altitude) + msg.longitude, msg.latitude = utm_proj(self.easting, self.northing, + inverse=True) + return msg + + def valid(self): + """:returns: True if this is a valid UTM point. """ + return (self.easting == self.easting + and self.northing == self.northing + and self.band != ' ') + +def fromLatLong(latitude, longitude, altitude=float('nan')): + """Generate :class:`UTMPoint` from latitude, longitude and (optional) altitude. + + Latitude and longitude are expressed in degrees, relative to the + WGS84 ellipsoid. + + :param latitude: [degrees], negative is South. + :param longitude: [degrees], negative is West. + :param altitude: [meters], negative is below the ellipsoid. + + :returns: :class:`UTMPoint` object. + """ + z, b = gridZone(latitude, longitude) + utm_proj = pyproj.Proj(proj='utm', zone=z, datum='WGS84') + e, n = utm_proj(longitude, latitude) + return UTMPoint(easting=e, northing=n, altitude=altitude, zone=z, band=b) + +def fromMsg(msg): + """ + :param msg: `geographic_msgs/GeoPoint`_ message. + :returns: :class:`UTMPoint` object. + """ + return fromLatLong(msg.latitude, msg.longitude, msg.altitude) + +def gridZone(lat, lon): + """Find UTM zone and MGRS band for latitude and longitude. + + :param lat: latitude in degrees, negative is South. + :param lon: longitude in degrees, negative is West. + :returns: (zone, band) tuple. + :raises: :exc:`ValueError` if lon not in [-180..180] or if lat + has no corresponding band letter. + + :todo: handle polar (UPS_) zones: A, B, Y, Z. + """ + if -180.0 > lon or lon > 180.0: + raise ValueError('invalid longitude: ' + str(lon)) + zone = int((lon + 180.0)//6.0) + 1 + band = ' ' + if 84 >= lat and lat >= 72: band = 'X' + elif 72 > lat and lat >= 64: band = 'W' + elif 64 > lat and lat >= 56: band = 'V' + elif 56 > lat and lat >= 48: band = 'U' + elif 48 > lat and lat >= 40: band = 'T' + elif 40 > lat and lat >= 32: band = 'S' + elif 32 > lat and lat >= 24: band = 'R' + elif 24 > lat and lat >= 16: band = 'Q' + elif 16 > lat and lat >= 8: band = 'P' + elif 8 > lat and lat >= 0: band = 'N' + elif 0 > lat and lat >= -8: band = 'M' + elif -8 > lat and lat >= -16: band = 'L' + elif -16 > lat and lat >= -24: band = 'K' + elif -24 > lat and lat >= -32: band = 'J' + elif -32 > lat and lat >= -40: band = 'H' + elif -40 > lat and lat >= -48: band = 'G' + elif -48 > lat and lat >= -56: band = 'F' + elif -56 > lat and lat >= -64: band = 'E' + elif -64 > lat and lat >= -72: band = 'D' + elif -72 > lat and lat >= -80: band = 'C' + else: raise ValueError('latitude out of UTM range: ' + str(lat)) + return (zone, band) diff --git a/navigations/geographic_info/geodesy/src/geodesy/wu_point.py b/navigations/geographic_info/geodesy/src/geodesy/wu_point.py new file mode 100755 index 0000000..5a4148e --- /dev/null +++ b/navigations/geographic_info/geodesy/src/geodesy/wu_point.py @@ -0,0 +1,272 @@ +# Software License Agreement (BSD License) +# +# Copyright (C) 2012, Jack O'Quin +# All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# * Redistributions in binary form must reproduce the above +# copyright notice, this list of conditions and the following +# disclaimer in the documentation and/or other materials provided +# with the distribution. +# * Neither the name of the author nor of other contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. + +""" +.. module:: wu_point + +Convenience classes for manipulating way points and their associated +Universal Transverse Mercator (UTM_) coordinates. + +.. _UTM: http://en.wikipedia.org/wiki/Universal_Transverse_Mercator_coordinate_system +.. _UUID: http://en.wikipedia.org/wiki/Uuid + +.. _`geographic_msgs/GeographicMap`: http://ros.org/doc/api/geographic_msgs/html/msg/GeographicMap.html +.. _`geographic_msgs/GeoPoint`: http://ros.org/doc/api/geographic_msgs/html/msg/GeoPoint.html +.. _`geographic_msgs/RouteNetwork`: http://ros.org/doc/api/geographic_msgs/html/msg/RouteNetwork.html +.. _`geographic_msgs/WayPoint`: http://ros.org/doc/api/geographic_msgs/html/msg/WayPoint.html +.. _`geometry_msgs/Point`: http://ros.org/doc/api/geometry_msgs/html/msg/Point.html + +""" + +import math +import geodesy.utm + +from geographic_msgs.msg import WayPoint +from geometry_msgs.msg import Point + +class WuPoint(): + """ + :class:`WuPoint` represents a map way point with associated UTM_ + information. + + :param waypt: `geographic_msgs/WayPoint`_ message. + :param utm: Corresponding :class:`geodesy.utm.UTMPoint` object. If None + provided, the *utm* object will be created. + + .. describe:: str(wu_point) + + :returns: String representation of :class:`WuPoint` object. + """ + + def __init__(self, waypt, utm=None): + """Constructor. + + Collects relevant information from the way point message, and + creates the corresponding :class:`geodesy.utm.UTMPoint`. + """ + self.way_pt = waypt + + if utm: + self.utm = utm + else: + # convert latitude and longitude to UTM (ignoring altitude) + self.utm = geodesy.utm.fromMsg(waypt.position) + + def __str__(self): + """:returns: String representation of :class:`WuPoint` """ + # uses python3-compatible str.format() method: + return str(self.way_pt) + '\n' + str(self.utm) + + def is2D(self): + """:returns: True if no altitude provided. """ + geo_point = self.way_pt.position + return geo_point.altitude != geo_point.altitude + + def position(self): + """:returns: Corresponding `geographic_msgs/GeoPoint`_ message.""" + return self.way_pt.position + + def toPoint(self): + """:returns: Corresponding `geometry_msgs/Point`_ message.""" + return self.utm.toPoint() + + def toPointXY(self): + """:returns: `geometry_msgs/Point`_ with X and Y coordinates, and Z coordinate of zero. """ + return Point(x = self.utm.easting, y = self.utm.northing) + + def toWayPoint(self): + """:returns: Corresponding `geographic_msgs/WayPoint`_ message. """ + return self.way_pt + + def uuid(self): + """:returns: UUID_ of way point. """ + return self.way_pt.id.uuid + +class WuPointSet(): + """ + :class:`WuPointSet` is a container for the way points in a + `geographic_msgs/GeographicMap`_ or + `geographic_msgs/RouteNetwork`_ message. UTM_ coordinates are + available for each way point, but they are evaluated lazily, only + when needed. + + :param points: array of `geographic_msgs/WayPoint`_ messages + + :class:`WuPointSet` supports these standard container operations: + + .. describe:: len(wu_set) + + :returns: The number of points in the set. + + .. describe:: wu_set[uuid] + + :returns: The point with key *uuid*. Raises a :exc:`KeyError` + if *uuid* is not in the set. + + .. describe:: uuid in wu_set + + :returns: ``True`` if *wu_set* has a key *uuid*, else ``False``. + + .. describe:: uuid not in wu_set + + Equivalent to ``not uuid in wu_set``. + + .. describe:: iter(wu_set) + + :returns: An iterator over the points in the set. + + These methods are also provided: + + """ + + def __init__(self, points): + """Constructor. + + Collects relevant way point information from the way point + array, and provides convenient access to the data. + """ + self.points = points + + # Initialize way point information. + self.way_point_ids = {} # points symbol table + self.n_points = len(self.points) + for wid in range(self.n_points): + self.way_point_ids[self.points[wid].id.uuid] = wid + self.way_point_ids = dict(self.way_point_ids) + # Create empty list of UTM points, corresponding to map points. + # They will be evaluated lazily, when first needed. + self.utm_points = [None for wid in range(self.n_points)] + + def __contains__(self, item): + """ Point set membership. """ + return item in self.way_point_ids + + def __getitem__(self, key): + """ + :param key: UUID_ of desired point. + :returns: Named :class:`WuPoint`. + :raises: :exc:`KeyError` if no such point + """ + index = self.way_point_ids[key] + return self._get_point_with_utm(index) + + def __iter__(self): + """ Points iterator. """ + self.iter_index = 0 + return self + + def __len__(self): + """Point set length.""" + return self.n_points + + def _get_point_with_utm(self, index): + """Get way point with UTM coordinates. + + Creates the corresponding :class:`UTMPoint`, if necessary. + + :param index: Index of point in self. + :returns: Corresponding :class:`WuPoint` object. + """ + way_pt = self.points[index] + utm_pt = list(self.utm_points)[index] + if utm_pt is not None: + utm_pt = geodesy.utm.fromMsg(way_pt.position) + self.utm_points[index] = utm_pt + return WuPoint(way_pt, utm=utm_pt) + + def distance2D(self, idx1, idx2): + """ Compute 2D Euclidean distance between points. + + :param idx1: Index of first point. + :param idx2: Index of second point. + + :returns: Distance in meters within the UTM XY + plane. Altitudes are ignored. + """ + p1 = self._get_point_with_utm(idx1) + p2 = self._get_point_with_utm(idx2) + dx = p2.utm.easting - p1.utm.easting + dy = p2.utm.northing - p1.utm.northing + return math.sqrt(dx*dx + dy*dy) + + def distance3D(self, idx1, idx2): + """ Compute 3D Euclidean distance between points. + + :param idx1: Index of first point. + :param idx2: Index of second point. + + :returns: Distance in meters between two UTM points, including + altitudes. + """ + p1 = self._get_point_with_utm(idx1) + p2 = self._get_point_with_utm(idx2) + dx = p2.utm.easting - p1.utm.easting + dy = p2.utm.northing - p1.utm.northing + dz = p2.utm.altitude - p1.utm.altitude + return math.sqrt(dx*dx + dy*dy + dz*dz) + + def get(self, key, default=None): + """ Get point, if defined. + + :param key: UUID_ of desired point. + :param default: value to return if no such point. + :returns: Named :class:`WuPoint`, if successful; otherwise default. + """ + index = self.way_point_ids.get(key) + if index is not None: + return self._get_point_with_utm(index) + else: + return default + + def index(self, key, default=None): + """ Get index of point, if defined. + + :param key: UUID_ of desired point. + :param default: value to return if no such point. + :returns: Index of point, if successful; otherwise default. + Beware: the index may be 0, which evaluates False as + a predicate, use ``is not None`` to test for + presence. + """ + return self.way_point_ids.get(key, default) + + def __next__(self): + """ Next iteration point. + + :returns: Next :class:`WuPoint`. + :raises: :exc:`StopIteration` when finished. + """ + i = self.iter_index + if i >= self.n_points: + raise StopIteration + self.iter_index = i + 1 + return self._get_point_with_utm(i) diff --git a/navigations/geographic_info/geodesy/tests/test_bounding_box.py b/navigations/geographic_info/geodesy/tests/test_bounding_box.py new file mode 100755 index 0000000..2e68da6 --- /dev/null +++ b/navigations/geographic_info/geodesy/tests/test_bounding_box.py @@ -0,0 +1,50 @@ +#!/usr/bin/env python + +import unittest + +from geodesy.bounding_box import * # module being tested + +class TestPythonBoundingBox(unittest.TestCase): + """Unit tests for Python bounding box functions. """ + + def test_global_bounding_box(self): + bb = makeGlobal() + self.assertTrue(isGlobal(bb)) + + def test_2d_bounding_box(self): + min_lat = 30.3787400 + min_lon = -97.7344500 + max_lat = 30.3947700 + max_lon = -97.7230800 + bb = makeBounds2D(min_lat, min_lon, max_lat, max_lon) + self.assertFalse(isGlobal(bb)) + self.assertTrue(is2D(bb)) + min_lat2, min_lon2, max_lat2, max_lon2 = getLatLong(bb) + self.assertEqual(min_lat, min_lat2) + self.assertEqual(min_lon, min_lon2) + self.assertEqual(max_lat, max_lat2) + self.assertEqual(max_lon, max_lon2) + + def test_3d_bounding_box(self): + min_lat = 30.3787400 + min_lon = -97.7344500 + min_alt = 200.0 + max_lat = 30.3947700 + max_lon = -97.7230800 + max_alt = 400.0 + bb = makeBounds3D(min_lat, min_lon, min_alt, + max_lat, max_lon, max_alt) + self.assertFalse(isGlobal(bb)) + self.assertFalse(is2D(bb)) + min_lat2, min_lon2, max_lat2, max_lon2 = getLatLong(bb) + self.assertEqual(min_lat, min_lat2) + self.assertEqual(min_lon, min_lon2) + self.assertEqual(min_alt, bb.min_pt.altitude) + self.assertEqual(max_lat, max_lat2) + self.assertEqual(max_lon, max_lon2) + self.assertEqual(max_alt, bb.max_pt.altitude) + +if __name__ == '__main__': + import rosunit + PKG='geodesy' + rosunit.unitrun(PKG, 'test_uuid_py', TestPythonBoundingBox) diff --git a/navigations/geographic_info/geodesy/tests/test_props.py b/navigations/geographic_info/geodesy/tests/test_props.py new file mode 100755 index 0000000..002fdee --- /dev/null +++ b/navigations/geographic_info/geodesy/tests/test_props.py @@ -0,0 +1,76 @@ +#!/usr/bin/env python + +import sys +import unittest + +from geodesy.props import * # module being tested + +from geographic_msgs.msg import KeyValue +from geographic_msgs.msg import MapFeature +from geographic_msgs.msg import RouteSegment +from geographic_msgs.msg import WayPoint + +class TestPythonProps(unittest.TestCase): + """Unit tests for Python KeyValue property handling. + """ + + def test_empty_feature_match(self): + f = MapFeature() + self.assertEqual(match(f, set(['no', 'such', 'property'])), None) + + def test_empty_property_set(self): + f = MapFeature() + put(f, 'valid', 'any') + self.assertEqual(match(f, set()), None) + + def test_feature_match(self): + f = MapFeature() + put(f, 'different') + put(f, 'valid', 'any') + prop = match(f, set(['a', 'valid', 'property'])) + self.assertNotEqual(prop, None) + self.assertEqual(prop, ('valid', 'any')) + k, v = prop + self.assertEqual(k, 'valid') + self.assertEqual(v, 'any') + + def test_empty_waypoint_match(self): + p = WayPoint() + self.assertEqual(match(p, set(['nothing', 'defined'])), None) + + def test_waypoint_match(self): + p = WayPoint() + put(p, 'another', 'anything') + put(p, 'name', 'myself') + prop = match(p, set(['name'])) + self.assertNotEqual(prop, None) + k, v = prop + self.assertEqual(k, 'name') + self.assertEqual(v, 'myself') + + def test_segment_value_change(self): + s = RouteSegment() + put(s, 'another', 'anything') + put(s, 'name', 'myself') + self.assertEqual(get(s, 'name'), 'myself') + put(s, 'name', 'alias') + self.assertEqual(get(s, 'name'), 'alias') + + def test_segment_null_value(self): + s = RouteSegment() + put(s, 'another', 'anything') + put(s, 'name') + self.assertEqual(get(s, 'name'), '') + put(s, 'name', 'myself') + self.assertEqual(get(s, 'name'), 'myself') + + def test_invalid_key_set(self): + f = MapFeature() + put(f, 'notset', 'any') + self.assertEqual(get(f, 'notset'), 'any') + self.assertRaises(ValueError, match, f, 'notset') + +if __name__ == '__main__': + import rosunit + PKG='geodesy' + rosunit.unitrun(PKG, 'test_uuid_py', TestPythonProps) diff --git a/navigations/geographic_info/geodesy/tests/test_utm.cpp b/navigations/geographic_info/geodesy/tests/test_utm.cpp new file mode 100755 index 0000000..a1fa404 --- /dev/null +++ b/navigations/geographic_info/geodesy/tests/test_utm.cpp @@ -0,0 +1,478 @@ +/* $Id: 47db7b5025f4ca800961335f30ef67b18cfe69ca $ */ + +/********************************************************************* +* Software License Agreement (BSD License) +* +* Copyright (c) 2011 Jack O'Quin +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of the author nor other contributors may be +* used to endorse or promote products derived from this software +* without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +*********************************************************************/ + +#include +#include +#include +#include "geodesy/utm.h" + + +/////////////////////////////////////////////////////////////// +// Utility functions +/////////////////////////////////////////////////////////////// + +// check that two UTM points are near each other +void check_utm_near(const geodesy::UTMPoint &pt1, + const geodesy::UTMPoint &pt2, + double abs_err) +{ + EXPECT_NEAR(pt1.easting, pt2.easting, abs_err); + EXPECT_NEAR(pt1.northing, pt2.northing, abs_err); + EXPECT_NEAR(pt1.altitude, pt2.altitude, abs_err); + EXPECT_EQ(pt1.zone, pt2.zone); + EXPECT_EQ(pt1.band, pt2.band); +} + +/////////////////////////////////////////////////////////////// +// Test cases +/////////////////////////////////////////////////////////////// + +// Test null constructor +TEST(UTMPoint, nullConstructor) +{ + geodesy::UTMPoint pt; + + EXPECT_EQ(pt.easting, 0.0); + EXPECT_EQ(pt.northing, 0.0); + EXPECT_TRUE(geodesy::is2D(pt)); + EXPECT_EQ(pt.zone, 0); + EXPECT_EQ(pt.band, ' '); + EXPECT_FALSE(geodesy::isValid(pt)); +} + +// Test 2D constructor +TEST(UTMPoint, flatConstructor) +{ + double e = 1000.0; + double n = 2400.0; + uint8_t z = 14; + char b = 'R'; + geodesy::UTMPoint pt(e, n, z, b); + + EXPECT_TRUE(geodesy::is2D(pt)); + EXPECT_TRUE(geodesy::isValid(pt)); + + EXPECT_EQ(pt.easting, e); + EXPECT_EQ(pt.northing, n); + EXPECT_EQ(pt.zone, z); + EXPECT_EQ(pt.band, b); +} + +// Test 3D constructor +TEST(UTMPoint, hasAltitude) +{ + double e = 1000.0; + double n = 2400.0; + double a = 200.0; + uint8_t z = 14; + char b = 'R'; + geodesy::UTMPoint pt(e, n, a, z, b); + + EXPECT_FALSE(geodesy::is2D(pt)); + EXPECT_TRUE(geodesy::isValid(pt)); + + EXPECT_EQ(pt.easting, e); + EXPECT_EQ(pt.northing, n); + EXPECT_EQ(pt.zone, z); + EXPECT_EQ(pt.band, b); +} + +// Test copy constructor +TEST(UTMPoint, copyConstructor) +{ + double e = 1000.0; + double n = 2400.0; + double a = 200.0; + uint8_t z = 14; + char b = 'R'; + geodesy::UTMPoint pt1(e, n, a, z, b); + geodesy::UTMPoint pt2(pt1); + + EXPECT_FALSE(geodesy::is2D(pt2)); + EXPECT_TRUE(geodesy::isValid(pt2)); + + EXPECT_EQ(pt2.easting, e); + EXPECT_EQ(pt2.northing, n); + EXPECT_EQ(pt2.zone, z); + EXPECT_EQ(pt2.band, b); +} + +// Test UTM point constructor from WGS 84 +TEST(UTMPoint, fromLatLong) +{ + // University of Texas, Austin, Pickle Research Campus + double lat = 30.385315; + double lon = -97.728524; + double alt = 209.0; + + geographic_msgs::GeoPoint ll; + ll.latitude = lat; + ll.longitude = lon; + ll.altitude = alt; + + // create UTM from point + geodesy::UTMPoint pt(ll); + + double e = 622159.34; + double n = 3362168.30; + uint8_t z = 14; + char b = 'R'; + double abs_err = 0.01; + + EXPECT_FALSE(geodesy::is2D(pt)); + EXPECT_TRUE(geodesy::isValid(pt)); + + EXPECT_NEAR(pt.easting, e, abs_err); + EXPECT_NEAR(pt.northing, n, abs_err); + EXPECT_NEAR(pt.altitude, alt, abs_err); + EXPECT_EQ(pt.zone, z); + EXPECT_EQ(pt.band, b); +} + +// Test zone numbers +TEST(UTMPoint, testZones) +{ + geodesy::UTMPoint pt; + pt.band = 'X'; // supply a valid band letter + + pt.zone = 0; + EXPECT_FALSE(geodesy::isValid(pt)); + + pt.zone = 61; + EXPECT_FALSE(geodesy::isValid(pt)); + + pt.zone = 255; + EXPECT_FALSE(geodesy::isValid(pt)); + + // these should all work + for (uint8_t b = 1; b <= 60; ++b) + { + pt.zone = b; + EXPECT_TRUE(geodesy::isValid(pt)); + } +} + +// Test band letters +TEST(UTMPoint, testBands) +{ + geodesy::UTMPoint pt; + pt.zone = 14; // supply a valid zone number + EXPECT_FALSE(geodesy::isValid(pt)); + + pt.band = '9'; + EXPECT_FALSE(geodesy::isValid(pt)); + + pt.band = ';'; + EXPECT_FALSE(geodesy::isValid(pt)); + + pt.band = 'I'; + EXPECT_FALSE(geodesy::isValid(pt)); + + pt.band = 'O'; + EXPECT_FALSE(geodesy::isValid(pt)); + + pt.band = 'Y'; + EXPECT_FALSE(geodesy::isValid(pt)); + + pt.band = 'r'; + EXPECT_FALSE(geodesy::isValid(pt)); + + // this should work + pt.band = 'X'; + EXPECT_TRUE(geodesy::isValid(pt)); +} + +// Test null pose constructor +TEST(UTMPose, nullConstructor) +{ + geodesy::UTMPose pose; + + EXPECT_TRUE(geodesy::is2D(pose)); + EXPECT_FALSE(geodesy::isValid(pose)); +} + +// Test pose constructor from point and quaternion +TEST(UTMPose, pointQuaternionConstructor) +{ + double e = 1000.0; + double n = 2400.0; + double a = 200.0; + uint8_t z = 14; + char b = 'R'; + geodesy::UTMPoint pt(e, n, a, z, b); + + geometry_msgs::Quaternion q; // identity quaternion + q.x = 1.0; + q.y = 0.0; + q.z = 0.0; + q.w = 0.0; + geodesy::UTMPose pose(pt, q); + + EXPECT_FALSE(geodesy::is2D(pose)); + EXPECT_TRUE(geodesy::isValid(pose)); + + EXPECT_EQ(pose.position.easting, pt.easting); + EXPECT_EQ(pose.position.northing, pt.northing); + EXPECT_EQ(pose.position.altitude, pt.altitude); + EXPECT_EQ(pose.position.zone, pt.zone); + EXPECT_EQ(pose.position.band, pt.band); + + EXPECT_EQ(pose.orientation.w, q.w); + EXPECT_EQ(pose.orientation.x, q.x); + EXPECT_EQ(pose.orientation.y, q.y); + EXPECT_EQ(pose.orientation.z, q.z); +} + +// Test pose quaternion validation +TEST(UTMPose, quaternionValidation) +{ + double e = 1000.0; + double n = 2400.0; + double a = 200.0; + uint8_t z = 14; + char b = 'R'; + geodesy::UTMPoint pt(e, n, a, z, b); + + // identity quaternion + geometry_msgs::Quaternion q; + q.x = 1.0; + q.y = 0.0; + q.z = 0.0; + q.w = 0.0; + geodesy::UTMPose pose1(pt, q); + EXPECT_TRUE(geodesy::isValid(pose1)); + + // valid quaternion + q.x = 0.7071; + q.y = 0.0; + q.z = 0.0; + q.w = 0.7071; + geodesy::UTMPose pose2(pt, q); + EXPECT_TRUE(geodesy::isValid(pose2)); + + // quaternion not normalized + q.x = 0.8071; + q.y = 0.0; + q.z = 0.0; + q.w = 0.8071; + geodesy::UTMPose pose3(pt, q); + EXPECT_FALSE(geodesy::isValid(pose3)); + + // zero quaternion (not normalized) + q.x = 0.0; + q.y = 0.0; + q.z = 0.0; + q.w = 0.0; + geodesy::UTMPose pose4(pt, q); + EXPECT_FALSE(geodesy::isValid(pose4)); +} + +// Test UTM pose conversion +TEST(UTMConvert, fromUtmPoseToLatLongAndBack) +{ + double e = 500000.0; // central meridian of each zone + double n = 1000.0; + double alt = 100.0; + char b = 'N'; + + // try every possible zone of longitude + for (uint8_t z = 1; z <= 60; ++z) + { + for (unsigned int heading = 0; heading < 360; heading++) + { + geodesy::UTMPose ps1(geodesy::UTMPoint(e, n, alt, z, b), + tf::createQuaternionMsgFromYaw(angles::from_degrees(heading))); + geographic_msgs::GeoPose ll; + convert(ps1, ll); + geodesy::UTMPose ps2; + convert(ll, ps2); + + EXPECT_TRUE(geodesy::isValid(ps1)); + EXPECT_TRUE(geodesy::isValid(ps2)); + check_utm_near(ps1.position, ps2.position, 0.000001); + EXPECT_DOUBLE_EQ(tf::getYaw(ps1.orientation), tf::getYaw(ps2.orientation)); + } + } +} + +// Test conversion from UTM to WGS 84 and back +TEST(UTMConvert, fromUtmToLatLongAndBack) +{ + double e = 500000.0; // central meridian of each zone + double n = 1000.0; + double alt = 100.0; + char b = 'N'; + + // try every possible zone of longitude + for (uint8_t z = 1; z <= 60; ++z) + { + geodesy::UTMPoint pt1(e, n, alt, z, b); + geographic_msgs::GeoPoint ll; + convert(pt1, ll); + geodesy::UTMPoint pt2; + convert(ll, pt2); + + EXPECT_TRUE(geodesy::isValid(pt1)); + EXPECT_TRUE(geodesy::isValid(pt2)); + check_utm_near(pt1, pt2, 0.000001); + } +} + +// Test conversion from WGS 84 to UTM and back +TEST(UTMConvert, fromLatLongToUtmAndBack) +{ + double alt = 100.0; + + // Try every possible degree of latitude and longitude. Avoid the + // international date line. Even though the converted longitude is + // close, it may end up less than -180 and hence inValid(). + for (double lon = -179.5; lon < 180.0; lon += 1.0) + { + for (double lat = -80.0; lat <= 84.0; lat += 1.0) + { + geographic_msgs::GeoPoint pt1(geodesy::toMsg(lat, lon, alt)); + EXPECT_TRUE(geodesy::isValid(pt1)); + + geodesy::UTMPoint utm(pt1); + EXPECT_TRUE(geodesy::isValid(utm)); + + geographic_msgs::GeoPoint pt2(geodesy::toMsg(utm)); + EXPECT_TRUE(geodesy::isValid(pt2)); + + EXPECT_NEAR(pt1.latitude, pt2.latitude, 0.0000001); + EXPECT_NEAR(pt1.longitude, pt2.longitude, 0.0000012); + EXPECT_NEAR(pt1.altitude, pt2.altitude, 0.000001); + } + } +} + +// Test conversion from WGS 84 to UTM and back at international date line +TEST(UTMConvert, internationalDateLine) +{ + double alt = 100.0; + double lon = -180.0; + + for (double lat = -80.0; lat <= 84.0; lat += 1.0) + { + geographic_msgs::GeoPoint pt1(geodesy::toMsg(lat, lon, alt)); + EXPECT_TRUE(geodesy::isValid(pt1)); + + geodesy::UTMPoint utm; + geodesy::fromMsg(pt1, utm); + EXPECT_TRUE(geodesy::isValid(utm)); + + geographic_msgs::GeoPoint pt2(geodesy::toMsg(utm)); + EXPECT_TRUE(geodesy::isValid(pt2)); + EXPECT_NEAR(pt1.latitude, pt2.latitude, 0.0000001); + EXPECT_NEAR(pt1.altitude, pt2.altitude, 0.000001); + + if (pt2.longitude - pt1.longitude > 359.0) + { + // pt2 seems to be slightly across the international date + // line from pt2, so de-normalize it + pt2.longitude -= 360.0; + } + EXPECT_NEAR(pt1.longitude, pt2.longitude, 0.0000012); + } +} + +// Test point output stream operator +TEST(OStream, point) +{ + geodesy::UTMPoint pt1; + std::ostringstream out1; + out1 << pt1; + std::string expected("(0, 0, nan [0 ])"); + EXPECT_EQ(out1.str(), expected); + + geodesy::UTMPoint pt2(622159.338, 3362168.303, 209, 14, 'R'); + std::ostringstream out2; + out2 << pt2; + expected = "(622159.338, 3362168.303, 209 [14R])"; + EXPECT_EQ(out2.str(), expected); +} + +// Test pose output stream operator +TEST(OStream, pose) +{ + geodesy::UTMPoint pt(1000.0, 2400.0, 200.0, 14, 'R'); + geometry_msgs::Quaternion q; + q.w = 1.0; + q.x = 0.0; + q.y = 0.0; + q.z = 0.0; + geodesy::UTMPose pose(pt, q); + + std::ostringstream out; + out << pose; + std::string expected("(1000, 2400, 200 [14R]), ([0, 0, 0], 1)"); + EXPECT_EQ(out.str(), expected); +} + +TEST(ForceUTMZone, point) +{ + + geographic_msgs::GeoPoint zone2, zone3; + zone2.latitude=24.02; + zone2 = geodesy::toMsg(24.02, 5.999); + zone3 = geodesy::toMsg(24.02, 6.001); + geodesy::UTMPoint pt2, pt3, pt4; + geodesy::fromMsg(zone2, pt2); + geodesy::fromMsg(zone3, pt3); + + EXPECT_FALSE(geodesy::sameGridZone(pt2, pt3) ); + + double diffx = pt2.easting - pt3.easting; + double diffy = pt2.northing - pt3.northing; + double distance = std::sqrt(diffx*diffx + diffy*diffy); + + //Now force the pt3 into pt2's grid zone + geodesy::fromMsg(zone3, pt4, true, pt2.band, pt2.zone); + diffx = pt2.easting - pt4.easting; + diffy = pt2.northing - pt4.northing; + double distance2 = std::sqrt(diffx*diffx + diffy*diffy); + ROS_INFO("Prev Distance %f, Actual Distance %f", distance, distance2); + EXPECT_LT(distance2, distance); +} + +// Run all the tests that were declared with TEST() +int main(int argc, char **argv) +{ + testing::InitGoogleTest(&argc, argv); + + // run the tests in this thread + return RUN_ALL_TESTS(); +} diff --git a/navigations/geographic_info/geodesy/tests/test_utm.py b/navigations/geographic_info/geodesy/tests/test_utm.py new file mode 100755 index 0000000..e122916 --- /dev/null +++ b/navigations/geographic_info/geodesy/tests/test_utm.py @@ -0,0 +1,58 @@ +#!/usr/bin/env python + +import sys +import unittest + +from geodesy.utm import * + +## A sample python unit test +class TestUTMPoint(unittest.TestCase): + + def test_null_constructor(self): + pt = UTMPoint() + self.assertFalse(pt.valid(), + msg='uninitialized UTMPoint should be invalid: ' + str(pt)) + self.assertTrue(pt.is2D(), + msg='this UTMPoint should be 2D: ' + str(pt)) + self.assertRaises(ValueError, pt.toMsg) + + def test_wgs84_utm_conversion_3d(self): + # UTM point in Pickle Research Campus, University of Texas, Austin + ll = GeoPoint(latitude = 30.385315, + longitude = -97.728524, + altitude = 209.0) + pt = fromMsg(ll) + self.assertEqual(str(pt), 'UTM: [622159.338, 3362168.303, 209.000, 14R]', + msg='conversion failed: ' + str(pt)) + self.assertTrue(pt.valid(), msg='invalid UTMPoint: ' + str(pt)) + self.assertFalse(pt.is2D(), msg='this UTMPoint should be 3D: ' + str(pt)) + self.assertEqual(pt.gridZone(), (14, 'R')) + self.assertEqual(str(pt.toMsg()), str(ll), + msg='GeoPoint conversion failed for: ' + str(pt)) + point_xyz = pt.toPoint() + self.assertAlmostEqual(point_xyz.x, 622159.338, places = 3) + self.assertAlmostEqual(point_xyz.y, 3362168.303, places = 3) + self.assertAlmostEqual(point_xyz.z, 209.0, places = 3) + + def test_wgs84_utm_conversion_2d(self): + # same point, but without altitude + lat = 30.385315 + lon = -97.728524 + alt = float('nan') + pt = fromLatLong(lat, lon) + self.assertEqual(str(pt), 'UTM: [622159.338, 3362168.303, nan, 14R]', + msg='conversion failed: ' + str(pt)) + self.assertTrue(pt.valid(), msg='invalid UTMPoint: ' + str(pt)) + self.assertTrue(pt.is2D(), msg='this UTMPoint should be 2D: ' + str(pt)) + self.assertEqual(pt.gridZone(), (14, 'R')) + self.assertEqual(str(pt.toMsg()), str(GeoPoint(lat, lon, alt)), + msg='GeoPoint conversion failed for: ' + str(pt)) + point_xy = pt.toPoint() + self.assertAlmostEqual(point_xy.x, 622159.338, places = 3) + self.assertAlmostEqual(point_xy.y, 3362168.303, places = 3) + self.assertAlmostEqual(point_xy.z, 0.0, places = 3) + +if __name__ == '__main__': + import rosunit + PKG='geodesy' + rosunit.unitrun(PKG, 'test_utm_py', TestUTMPoint) diff --git a/navigations/geographic_info/geodesy/tests/test_wgs84.cpp b/navigations/geographic_info/geodesy/tests/test_wgs84.cpp new file mode 100755 index 0000000..149fe6c --- /dev/null +++ b/navigations/geographic_info/geodesy/tests/test_wgs84.cpp @@ -0,0 +1,292 @@ +/* $Id: c7a178b0bbba69e8bf70b12ea1fe76e0cc5a4bff $ */ + +/********************************************************************* +* Software License Agreement (BSD License) +* +* Copyright (c) 2011 Jack O'Quin +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of the author nor other contributors may be +* used to endorse or promote products derived from this software +* without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +*********************************************************************/ + +#include +#include +#include "geodesy/wgs84.h" + +/////////////////////////////////////////////////////////////// +// Utility functions +/////////////////////////////////////////////////////////////// + +// check that normalize of (lat1, lon1) yields (lat2, lon2) +void check_normalize(double lat1, double lon1, double lat2, double lon2) +{ + double epsilon = 1e-9; + geographic_msgs::GeoPoint pt; + pt.latitude = lat1; + pt.longitude = lon1; + geodesy::normalize(pt); + EXPECT_NEAR(lat2, pt.latitude, epsilon); + EXPECT_NEAR(lon2, pt.longitude, epsilon); +} + +/////////////////////////////////////////////////////////////// +// Test cases +/////////////////////////////////////////////////////////////// + +// Test null point constructor +TEST(GeoPoint, nullConstructor) +{ + geographic_msgs::GeoPoint pt; + + EXPECT_FALSE(geodesy::is2D(pt)); + EXPECT_TRUE(geodesy::isValid(pt)); +} + +// Test point with no altitude +TEST(GeoPoint, noAltitude) +{ + geographic_msgs::GeoPoint pt(geodesy::toMsg(0.0, 0.0)); + EXPECT_TRUE(geodesy::is2D(pt)); +} + +// Test creating point from NavSatFix message +TEST(GeoPoint, fromNavSatFix) +{ + double lat = 30.0; + double lon = -97.0; + double alt = 208.0; + sensor_msgs::NavSatFix fix; + fix.latitude = lat; + fix.longitude = lon; + fix.altitude = alt; + + geographic_msgs::GeoPoint pt(geodesy::toMsg(fix)); + + EXPECT_FALSE(geodesy::is2D(pt)); + EXPECT_TRUE(geodesy::isValid(pt)); + + EXPECT_EQ(pt.latitude, lat); + EXPECT_EQ(pt.longitude, lon); + EXPECT_EQ(pt.altitude, alt); +} + +// Test point with valid altitude +TEST(GeoPoint, hasAltitude) +{ + geographic_msgs::GeoPoint pt(geodesy::toMsg(30.0, 206.0, -97.0)); + EXPECT_FALSE(geodesy::is2D(pt)); + + pt.altitude = -100.0; + EXPECT_FALSE(geodesy::is2D(pt)); + + pt.altitude = 20000.0; + EXPECT_FALSE(geodesy::is2D(pt)); + + pt.altitude = 0.0; + EXPECT_FALSE(geodesy::is2D(pt)); +} + +// Test valid latitudes and longitudes +TEST(GeoPoint, validLatLong) +{ + geographic_msgs::GeoPoint pt; + + pt.latitude = 90.0; + EXPECT_TRUE(geodesy::isValid(pt)); + + pt.latitude = -90.0; + EXPECT_TRUE(geodesy::isValid(pt)); + + pt.latitude = 30.0; + pt.longitude = -97.0; + EXPECT_TRUE(geodesy::isValid(pt)); + + pt.longitude = 179.999999; + EXPECT_TRUE(geodesy::isValid(pt)); + + pt.longitude = -180.0; + EXPECT_TRUE(geodesy::isValid(pt)); +} + +// Test valid latitudes and longitudes +TEST(GeoPoint, invalidLatLong) +{ + geographic_msgs::GeoPoint pt; + + pt.latitude = 90.001; + EXPECT_FALSE(geodesy::isValid(pt)); + + pt.latitude = -90.3; + EXPECT_FALSE(geodesy::isValid(pt)); + + pt.latitude = 30.0; + pt.longitude = -1000.0; + EXPECT_FALSE(geodesy::isValid(pt)); + + pt.longitude = 180.0; + EXPECT_FALSE(geodesy::isValid(pt)); + + pt.longitude = 180.0001; + EXPECT_FALSE(geodesy::isValid(pt)); + + pt.longitude = -180.999; + EXPECT_FALSE(geodesy::isValid(pt)); +} + +TEST(GeoPoint, normalize) +{ + check_normalize(0, 0, 0, 0); + + // longitude range + check_normalize(0, 90, 0, 90); + check_normalize(0, 180, 0, -180); + check_normalize(0, 270, 0, -90); + check_normalize(0, 360, 0, 0); + check_normalize(0, 450, 0, 90); + check_normalize(0, 540, 0, -180); + check_normalize(0, 630, 0, -90); + check_normalize(0, 720, 0, 0); + + check_normalize(0, -90, 0, -90); + check_normalize(0, -180, 0, -180); + check_normalize(0, -270, 0, 90); + check_normalize(0, -360, 0, 0); + check_normalize(0, -450, 0, -90); + check_normalize(0, -540, 0, -180); + check_normalize(0, -630, 0, 90); + check_normalize(0, -720, 0, 0); + + check_normalize(0, 45, 0, 45); + check_normalize(0, 135, 0, 135); + check_normalize(0, 225, 0, -135); + check_normalize(0, 315, 0, -45); + + check_normalize(0, -45, 0, -45); + check_normalize(0, -135, 0, -135); + check_normalize(0, -225, 0, 135); + check_normalize(0, -315, 0, 45); + + check_normalize(0, 91, 0, 91); + check_normalize(0, 181, 0, -179); + check_normalize(0, 271, 0, -89); + check_normalize(0, 361, 0, 1); + check_normalize(0, 451, 0, 91); + + check_normalize(0, -91, 0, -91); + check_normalize(0, -181, 0, 179); + check_normalize(0, -271, 0, 89); + check_normalize(0, -361, 0, -1); + check_normalize(0, -451, 0, -91); + + // latitude range + check_normalize(15, 0, 15, 0); + check_normalize(30, 0, 30, 0); + check_normalize(45, 0, 45, 0); + check_normalize(60, 0, 60, 0); + check_normalize(75, 0, 75, 0); + check_normalize(90, 0, 90, 0); + check_normalize(105, 0, 90, 0); + check_normalize(89.999999, 0, 89.999999, 0); + check_normalize(90.000001, 0, 90, 0); + + check_normalize(-15, 0, -15, 0); + check_normalize(-30, 0, -30, 0); + check_normalize(-45, 0, -45, 0); + check_normalize(-60, 0, -60, 0); + check_normalize(-75, 0, -75, 0); + check_normalize(-90, 0, -90, 0); + check_normalize(-105, 0, -90, 0); + check_normalize(-89.999999, 0, -89.999999, 0); + check_normalize(-90.000001, 0, -90, 0); + +} + +// Test null pose constructor +TEST(GeoPose, nullConstructor) +{ + geographic_msgs::GeoPose pose; + + EXPECT_FALSE(geodesy::is2D(pose)); + EXPECT_FALSE(geodesy::isValid(pose)); +} + +// Test validity of various quaternions +TEST(GeoPose, quaternionValidity) +{ + geographic_msgs::GeoPose pose; + EXPECT_FALSE(geodesy::isValid(pose)); + + pose.orientation.x = 1.0; // identity quaternion + EXPECT_TRUE(geodesy::isValid(pose)); + + pose.orientation.x = 0.7071; // also valid + pose.orientation.y = 0.7071; + EXPECT_TRUE(geodesy::isValid(pose)); + + pose.orientation.x = 0.8071; // not normalized + pose.orientation.y = 0.8071; + EXPECT_FALSE(geodesy::isValid(pose)); +} + +// Test trivial point conversion +TEST(Convert, GeoPointToGeoPoint) +{ + geographic_msgs::GeoPoint pt1(geodesy::toMsg(30.0, 206.0, -97.0)); + geographic_msgs::GeoPoint pt2; + + geodesy::convert(pt1, pt2); + + EXPECT_EQ(pt1.latitude, pt2.latitude); + EXPECT_EQ(pt1.longitude, pt2.longitude); + EXPECT_EQ(pt1.altitude, pt2.altitude); +} + +// Test trivial pose conversion +TEST(Convert, GeoPoseToGeoPose) +{ + geographic_msgs::GeoPoint pt(geodesy::toMsg(30.0, 206.0, -97.0)); + geometry_msgs::Quaternion q; + geographic_msgs::GeoPose pose1(geodesy::toMsg(pt, q)); + geographic_msgs::GeoPose pose2; + + geodesy::convert(pose1, pose2); + + EXPECT_EQ(pose1.position.latitude, pose2.position.latitude); + EXPECT_EQ(pose1.position.longitude, pose2.position.longitude); + EXPECT_EQ(pose1.position.altitude, pose2.position.altitude); +} + + +// Run all the tests that were declared with TEST() +int main(int argc, char **argv) +{ + testing::InitGoogleTest(&argc, argv); + + // run the tests in this thread + return RUN_ALL_TESTS(); +} diff --git a/navigations/geographic_info/geodesy/tests/test_wu_point.py b/navigations/geographic_info/geodesy/tests/test_wu_point.py new file mode 100755 index 0000000..8584324 --- /dev/null +++ b/navigations/geographic_info/geodesy/tests/test_wu_point.py @@ -0,0 +1,137 @@ +#!/usr/bin/env python + +import unittest + +from geographic_msgs.msg import GeographicMap +from geographic_msgs.msg import GeoPoint +from geographic_msgs.msg import WayPoint +from geometry_msgs.msg import Point +from uuid_msgs.msg import UniqueID + +from geodesy.wu_point import * + +def fromLatLong(lat, lon, alt=float('nan')): + """Generate WayPoint from latitude, longitude and (optional) altitude. + + :returns: minimal WayPoint object just for test cases. + """ + geo_pt = GeoPoint(latitude = lat, longitude = lon, altitude = alt) + return WayPoint(position = geo_pt) + +class TestWuPoint(unittest.TestCase): + """Unit tests for WuPoint classes. + """ + + def test_real_point(self): + ll = GeoPoint(latitude = 30.385315, + longitude = -97.728524, + altitude = 209.0) + msg = WayPoint(position = ll) + pt = WuPoint(msg) + self.assertEqual(pt.toWayPoint(), msg) + self.assertEqual(str(pt.utm), + 'UTM: [622159.338, 3362168.303, 209.000, 14R]') + + point_xyz = pt.toPoint() + self.assertAlmostEqual(point_xyz.x, 622159.338, places = 3) + self.assertAlmostEqual(point_xyz.y, 3362168.303, places = 3) + self.assertAlmostEqual(point_xyz.z, 209.0, places = 3) + + point_xy = pt.toPointXY() + self.assertAlmostEqual(point_xy.x, 622159.338, places = 3) + self.assertAlmostEqual(point_xy.y, 3362168.303, places = 3) + self.assertAlmostEqual(point_xy.z, 0.0, places = 3) + + def test_valid_points(self): + lon = -177.0 + zone = 1 + while lon < 180.0: + pt = WuPoint(fromLatLong(-80.0, lon)) + self.assertEqual(pt.utm.gridZone(), (zone, 'C')) + pt = WuPoint(fromLatLong(-30.385315, lon)) + self.assertEqual(pt.utm.gridZone(), (zone, 'J')) + pt = WuPoint(fromLatLong(-0.000001, lon)) + self.assertEqual(pt.utm.gridZone(), (zone, 'M')) + pt = WuPoint(fromLatLong(0.0, lon)) + self.assertEqual(pt.utm.gridZone(), (zone, 'N')) + pt = WuPoint(fromLatLong(30.385315, lon)) + self.assertEqual(pt.utm.gridZone(), (zone, 'R')) + pt = WuPoint(fromLatLong(84.0, lon)) + self.assertEqual(pt.utm.gridZone(), (zone, 'X')) + lon += 6.0 + zone += 1 + + def test_invalid_points(self): + self.assertRaises(ValueError, WuPoint, + fromLatLong(90.385315, -97.728524)) + self.assertRaises(ValueError, WuPoint, + fromLatLong(30.385315, -197.728524)) + # this will be valid when we add UPS support for the poles: + self.assertRaises(ValueError, WuPoint, + fromLatLong(-80.385315,-97.728524)) + + def test_empty_point_set(self): + # test WuPointSet iterator with empty list + wupts = WuPointSet(GeographicMap().points) + i = 0 + for w in wupts: + self.fail(msg='there are no points in this map') + i += 1 + self.assertEqual(i, 0) + + uu = 'da7c242f-2efe-5175-9961-49cc621b80b9' + self.assertEqual(wupts.get(uu), None) + + def test_three_point_set(self): + # test data + uuids = ['da7c242f-2efe-5175-9961-49cc621b80b9', + '812f1c08-a34b-5a21-92b9-18b2b0cf4950', + '6f0606f6-a776-5940-b5ea-5e889b32c712'] + latitudes = [30.3840168, 30.3857290, 30.3866750] + longitudes = [-97.7282100, -97.7316754, -97.7270967] + eastings = [622191.124, 621856.023, 622294.785] + northings = [3362024.764, 3362210.790, 3362320.569] + + points = [] + for i in range(len(uuids)): + latlon = GeoPoint(latitude = latitudes[i], + longitude = longitudes[i]) + points.append(WayPoint(id = UniqueID(uuid = uuids[i]), + position = latlon)) + + # test iterator + wupts = WuPointSet(points) + i = 0 + for w in wupts: + self.assertEqual(w.uuid(), uuids[i]) + self.assertEqual(wupts[uuids[i]].uuid(), uuids[i]) + self.assertAlmostEqual(w.utm.easting, eastings[i], places=3) + self.assertAlmostEqual(w.utm.northing, northings[i], places=3) + point_xy = w.toPointXY() + self.assertAlmostEqual(point_xy.x, eastings[i], places = 3) + self.assertAlmostEqual(point_xy.y, northings[i], places = 3) + self.assertAlmostEqual(point_xy.z, 0.0, places = 3) + i += 1 + self.assertEqual(i, 3) + self.assertEqual(len(wupts), 3) + + bogus = '00000000-c433-5c42-be2e-fbd97ddff9ac' + self.assertFalse(bogus in wupts) + self.assertEqual(wupts.get(bogus), None) + + uu = uuids[1] + self.assertTrue(uu in wupts) + wpt = wupts[uu] + self.assertEqual(wpt.uuid(), uu) + self.assertNotEqual(wupts.get(uu), None) + self.assertEqual(wupts.get(uu).uuid(), uu) + + # test index() function + for i in xrange(len(uuids)): + self.assertEqual(wupts.index(uuids[i]), i) + self.assertEqual(wupts.points[i].id.uuid, uuids[i]) + +if __name__ == '__main__': + import rosunit + PKG='geodesy' + rosunit.unitrun(PKG, 'test_xml_map_py', TestWuPoint) diff --git a/navigations/geographic_info/geographic_info/CHANGELOG.rst b/navigations/geographic_info/geographic_info/CHANGELOG.rst new file mode 100755 index 0000000..e7f5cb8 --- /dev/null +++ b/navigations/geographic_info/geographic_info/CHANGELOG.rst @@ -0,0 +1,51 @@ +Change history +============== + +0.5.3 (2018-03-27) +------------------ + +0.5.2 (2017-04-15) +------------------ + +0.5.1 (2017-04-15) +------------------ + +0.5.0 (2017-04-07) +------------------ + +0.4.0 (2014-09-18) +------------------ + +0.3.2 (2014-08-30) +------------------ + +0.3.1 (2013-10-03) +------------------ + +0.3.0 (2013-08-03) +------------------ + + * Released to Hydro. + * Convert to catkin build (`#3`_). + * Make **geographic_info** into a metapackage, depending on the + **geographic_msgs** and **geodesy** packages. It should only be + used for dependencies in dry stacks. Wet packages will depend + directly on **geographic_msgs** and **geodesy**. + +0.2.1 (2012-08-13) +------------------ + + * Released to Fuerte. + * Released to Groovy: 2013-03-27. + +0.2.0 (2012-06-02) +------------------ + + * Released to Electric. + +0.1.0 (2012-04-10) +------------------ + + * Initial release to Electric. + +.. _`#3`: https://github.com/ros-geographic-info/geographic_info/issues/3 diff --git a/navigations/geographic_info/geographic_info/CMakeLists.txt b/navigations/geographic_info/geographic_info/CMakeLists.txt new file mode 100755 index 0000000..5e26000 --- /dev/null +++ b/navigations/geographic_info/geographic_info/CMakeLists.txt @@ -0,0 +1,4 @@ +cmake_minimum_required(VERSION 3.0.2) +project(geographic_info) +find_package(catkin REQUIRED) +catkin_metapackage() diff --git a/navigations/geographic_info/geographic_info/package.xml b/navigations/geographic_info/geographic_info/package.xml new file mode 100755 index 0000000..7051790 --- /dev/null +++ b/navigations/geographic_info/geographic_info/package.xml @@ -0,0 +1,27 @@ + + + geographic_info + 0.5.6 + + Geographic information metapackage. + + Not needed for wet packages, use only to resolve dry stack + dependencies. + + Jack O'Quin + Jack O'Quin + BSD + http://wiki.ros.org/geographic_info + https://github.com/ros-geographic-info/geographic_info + https://github.com/ros-geographic-info/geographic_info/issues + + catkin + + geodesy + geographic_msgs + + + + + + diff --git a/navigations/geographic_info/geographic_msgs/CHANGELOG.rst b/navigations/geographic_info/geographic_msgs/CHANGELOG.rst new file mode 100755 index 0000000..0b721f4 --- /dev/null +++ b/navigations/geographic_info/geographic_msgs/CHANGELOG.rst @@ -0,0 +1,62 @@ +Change history +============== + +0.5.3 (2018-03-27) +------------------ + +* Add additional information to ``GetGeoPath`` service response. + +0.5.2 (2017-04-15) +------------------ + +* Fix merge error in GeoPath message. + +0.5.1 (2017-04-15) +------------------ + +* Add GeoPath message with poses. +* Add GetGeoPath service (`#7`_). + +0.5.0 (2017-04-07) +------------------ + +* Add new ``GeoPointStamped`` and ``GeoPoseStamped`` messages. + +0.4.0 (2014-09-18) +------------------ + +0.3.2 (2014-08-30) +------------------ + + * Add missing ``geometry_msgs`` dependency to ``catkin_package()`` + components in CMakeLists.txt (`#13`_), thanks to Timo Roehling. + +0.3.1 (2013-10-03) +------------------ + +0.3.0 (2013-08-03) +------------------ + + * Released to Hydro. + * Convert to catkin build (`#3`_). + +0.2.1 (2012-08-13) +------------------ + + * Released to Fuerte. + * Released to Groovy: 2013-03-27. + +0.2.0 (2012-06-02) +------------------ + + * Released to Electric. + +0.1.0 (2012-04-10) +------------------ + + * Initial release to Electric. + +.. _`#3`: https://github.com/ros-geographic-info/geographic_info/issues/3 +.. _`#6`: https://github.com/ros-geographic-info/geographic_info/issues/6 +.. _`#7`: https://github.com/ros-geographic-info/geographic_info/issues/7 +.. _`#13`: https://github.com/ros-geographic-info/geographic_info/pull/13 diff --git a/navigations/geographic_info/geographic_msgs/CMakeLists.txt b/navigations/geographic_info/geographic_msgs/CMakeLists.txt new file mode 100755 index 0000000..d937147 --- /dev/null +++ b/navigations/geographic_info/geographic_msgs/CMakeLists.txt @@ -0,0 +1,51 @@ +cmake_minimum_required(VERSION 3.0.2) +project(geographic_msgs) + +find_package(catkin REQUIRED + COMPONENTS + message_generation + geometry_msgs + std_msgs + uuid_msgs +) + +add_message_files( + DIRECTORY msg + FILES + BoundingBox.msg + GeographicMapChanges.msg + GeographicMap.msg + GeoPath.msg + GeoPoint.msg + GeoPointStamped.msg + GeoPose.msg + GeoPoseWithCovariance.msg + GeoPoseStamped.msg + GeoPoseWithCovarianceStamped.msg + KeyValue.msg + MapFeature.msg + RouteNetwork.msg + RoutePath.msg + RouteSegment.msg + WayPoint.msg +) + +add_service_files( + DIRECTORY srv + FILES + GetGeographicMap.srv + GetGeoPath.srv + GetRoutePlan.srv + UpdateGeographicMap.srv +) + +generate_messages( + DEPENDENCIES + geometry_msgs + std_msgs + uuid_msgs +) + +catkin_package( + CATKIN_DEPENDS message_runtime geometry_msgs uuid_msgs std_msgs +) diff --git a/navigations/geographic_info/geographic_msgs/mainpage.dox b/navigations/geographic_info/geographic_msgs/mainpage.dox new file mode 100755 index 0000000..77a740c --- /dev/null +++ b/navigations/geographic_info/geographic_msgs/mainpage.dox @@ -0,0 +1,9 @@ +/** +\mainpage +\htmlinclude manifest.html + +This package provides ROS messages for Geographic Information. + +It has no nodes, utilities, scripts or C++ API. + +*/ diff --git a/navigations/geographic_info/geographic_msgs/msg/BoundingBox.msg b/navigations/geographic_info/geographic_msgs/msg/BoundingBox.msg new file mode 100755 index 0000000..5e82e75 --- /dev/null +++ b/navigations/geographic_info/geographic_msgs/msg/BoundingBox.msg @@ -0,0 +1,13 @@ +# Geographic map bounding box. +# +# The two GeoPoints denote diagonally opposite corners of the box. +# +# If min_pt.latitude is NaN, the bounding box is "global", matching +# any valid latitude, longitude and altitude. +# +# If min_pt.altitude is NaN, the bounding box is two-dimensional and +# matches any altitude within the specified latitude and longitude +# range. + +GeoPoint min_pt # lowest and most Southwestern corner +GeoPoint max_pt # highest and most Northeastern corner diff --git a/navigations/geographic_info/geographic_msgs/msg/GeoPath.msg b/navigations/geographic_info/geographic_msgs/msg/GeoPath.msg new file mode 100755 index 0000000..6663339 --- /dev/null +++ b/navigations/geographic_info/geographic_msgs/msg/GeoPath.msg @@ -0,0 +1,2 @@ +std_msgs/Header header +geographic_msgs/GeoPoseStamped[] poses diff --git a/navigations/geographic_info/geographic_msgs/msg/GeoPoint.msg b/navigations/geographic_info/geographic_msgs/msg/GeoPoint.msg new file mode 100755 index 0000000..90d36f2 --- /dev/null +++ b/navigations/geographic_info/geographic_msgs/msg/GeoPoint.msg @@ -0,0 +1,13 @@ +# Geographic point, using the WGS 84 reference ellipsoid. + +# Latitude [degrees]. Positive is north of equator; negative is south +# (-90 <= latitude <= +90). +float64 latitude + +# Longitude [degrees]. Positive is east of prime meridian; negative is +# west (-180 <= longitude <= +180). At the poles, latitude is -90 or +# +90, and longitude is irrelevant, but must be in range. +float64 longitude + +# Altitude [m]. Positive is above the WGS 84 ellipsoid (NaN if unspecified). +float64 altitude diff --git a/navigations/geographic_info/geographic_msgs/msg/GeoPointStamped.msg b/navigations/geographic_info/geographic_msgs/msg/GeoPointStamped.msg new file mode 100755 index 0000000..16e2b1f --- /dev/null +++ b/navigations/geographic_info/geographic_msgs/msg/GeoPointStamped.msg @@ -0,0 +1,2 @@ +Header header +geographic_msgs/GeoPoint position diff --git a/navigations/geographic_info/geographic_msgs/msg/GeoPose.msg b/navigations/geographic_info/geographic_msgs/msg/GeoPose.msg new file mode 100755 index 0000000..906fc50 --- /dev/null +++ b/navigations/geographic_info/geographic_msgs/msg/GeoPose.msg @@ -0,0 +1,7 @@ +# Geographic pose, using the WGS 84 reference ellipsoid. +# +# Orientation uses the East-North-Up (ENU) frame of reference. +# (But, what about singularities at the poles?) + +GeoPoint position +geometry_msgs/Quaternion orientation diff --git a/navigations/geographic_info/geographic_msgs/msg/GeoPoseStamped.msg b/navigations/geographic_info/geographic_msgs/msg/GeoPoseStamped.msg new file mode 100755 index 0000000..e7b8d79 --- /dev/null +++ b/navigations/geographic_info/geographic_msgs/msg/GeoPoseStamped.msg @@ -0,0 +1,2 @@ +Header header +geographic_msgs/GeoPose pose diff --git a/navigations/geographic_info/geographic_msgs/msg/GeoPoseWithCovariance.msg b/navigations/geographic_info/geographic_msgs/msg/GeoPoseWithCovariance.msg new file mode 100755 index 0000000..6a35630 --- /dev/null +++ b/navigations/geographic_info/geographic_msgs/msg/GeoPoseWithCovariance.msg @@ -0,0 +1,12 @@ +# Geographic pose, using the WGS 84 reference ellipsoid. +# +# Orientation uses the East-North-Up (ENU) frame of reference. +# (But, what about singularities at the poles?) + +GeoPose pose + +# Row-major representation of the 6x6 covariance matrix +# The orientation parameters use a fixed-axis representation. +# In order, the parameters are: +# (Lat, Lon, Alt, rotation about E (East) axis, rotation about N (North) axis, rotation about U (Up) axis) +float64[36] covariance diff --git a/navigations/geographic_info/geographic_msgs/msg/GeoPoseWithCovarianceStamped.msg b/navigations/geographic_info/geographic_msgs/msg/GeoPoseWithCovarianceStamped.msg new file mode 100755 index 0000000..e0e2dc9 --- /dev/null +++ b/navigations/geographic_info/geographic_msgs/msg/GeoPoseWithCovarianceStamped.msg @@ -0,0 +1,2 @@ +Header header +geographic_msgs/GeoPoseWithCovariance pose diff --git a/navigations/geographic_info/geographic_msgs/msg/GeographicMap.msg b/navigations/geographic_info/geographic_msgs/msg/GeographicMap.msg new file mode 100755 index 0000000..58e7f19 --- /dev/null +++ b/navigations/geographic_info/geographic_msgs/msg/GeographicMap.msg @@ -0,0 +1,11 @@ +# Geographic map for a specified region. + +Header header # stamp specifies time + # frame_id (normally /map) + +uuid_msgs/UniqueID id # identifier for this map +BoundingBox bounds # 2D bounding box containing map + +WayPoint[] points # way-points +MapFeature[] features # map features +KeyValue[] props # map properties diff --git a/navigations/geographic_info/geographic_msgs/msg/GeographicMapChanges.msg b/navigations/geographic_info/geographic_msgs/msg/GeographicMapChanges.msg new file mode 100755 index 0000000..f1b572d --- /dev/null +++ b/navigations/geographic_info/geographic_msgs/msg/GeographicMapChanges.msg @@ -0,0 +1,7 @@ +# A list of geographic map changes. + +Header header # stamp specifies time of change + # frame_id (normally /map) + +GeographicMap diffs # new and changed points and features +uuid_msgs/UniqueID[] deletes # deleted map components diff --git a/navigations/geographic_info/geographic_msgs/msg/KeyValue.msg b/navigations/geographic_info/geographic_msgs/msg/KeyValue.msg new file mode 100755 index 0000000..cd6048b --- /dev/null +++ b/navigations/geographic_info/geographic_msgs/msg/KeyValue.msg @@ -0,0 +1,7 @@ +# Geographic map tag (key, value) pair +# +# This is equivalent to diagnostic_msgs/KeyValue, repeated here to +# avoid introducing a trivial stack dependency. + +string key # tag label +string value # corresponding value diff --git a/navigations/geographic_info/geographic_msgs/msg/MapFeature.msg b/navigations/geographic_info/geographic_msgs/msg/MapFeature.msg new file mode 100755 index 0000000..49e040b --- /dev/null +++ b/navigations/geographic_info/geographic_msgs/msg/MapFeature.msg @@ -0,0 +1,11 @@ +# Geographic map feature. +# +# A list of WayPoint IDs for features like streets, highways, hiking +# trails, the outlines of buildings and parking lots in sequential +# order. +# +# Feature lists may also contain other feature lists as members. + +uuid_msgs/UniqueID id # Unique feature identifier +uuid_msgs/UniqueID[] components # Sequence of feature components +KeyValue[] props # Key/value properties for this feature diff --git a/navigations/geographic_info/geographic_msgs/msg/RouteNetwork.msg b/navigations/geographic_info/geographic_msgs/msg/RouteNetwork.msg new file mode 100755 index 0000000..a4c1e35 --- /dev/null +++ b/navigations/geographic_info/geographic_msgs/msg/RouteNetwork.msg @@ -0,0 +1,16 @@ +# Geographic map route network. +# +# A directed graph of WayPoint nodes and RouteSegment edges. This +# information is extracted from the more-detailed contents of a +# GeographicMap. A RouteNetwork contains only the way points and +# route segments of interest for path planning. + +Header header + +uuid_msgs/UniqueID id # This route network identifier +BoundingBox bounds # 2D bounding box for network + +WayPoint[] points # Way points in this network +RouteSegment[] segments # Directed edges of this network + +KeyValue[] props # Network key/value properties diff --git a/navigations/geographic_info/geographic_msgs/msg/RoutePath.msg b/navigations/geographic_info/geographic_msgs/msg/RoutePath.msg new file mode 100755 index 0000000..29d09be --- /dev/null +++ b/navigations/geographic_info/geographic_msgs/msg/RoutePath.msg @@ -0,0 +1,11 @@ +# Path through a route network. +# +# A path is a sequence of RouteSegment edges. This information is +# extracted from a RouteNetwork graph. A RoutePath lists the route +# segments needed to reach some chosen goal. + +Header header + +uuid_msgs/UniqueID network # Route network containing this path +uuid_msgs/UniqueID[] segments # Sequence of RouteSegment IDs +KeyValue[] props # Key/value properties diff --git a/navigations/geographic_info/geographic_msgs/msg/RouteSegment.msg b/navigations/geographic_info/geographic_msgs/msg/RouteSegment.msg new file mode 100755 index 0000000..9b802d1 --- /dev/null +++ b/navigations/geographic_info/geographic_msgs/msg/RouteSegment.msg @@ -0,0 +1,12 @@ +# Route network segment. +# +# This is one directed edge of a RouteNetwork graph. It represents a +# known path from one way point to another. If the path is two-way, +# there will be another RouteSegment with "start" and "end" reversed. + +uuid_msgs/UniqueID id # Unique identifier for this segment + +uuid_msgs/UniqueID start # beginning way point of segment +uuid_msgs/UniqueID end # ending way point of segment + +KeyValue[] props # segment properties diff --git a/navigations/geographic_info/geographic_msgs/msg/WayPoint.msg b/navigations/geographic_info/geographic_msgs/msg/WayPoint.msg new file mode 100755 index 0000000..2f216d5 --- /dev/null +++ b/navigations/geographic_info/geographic_msgs/msg/WayPoint.msg @@ -0,0 +1,5 @@ +# Way-point element for a geographic map. + +uuid_msgs/UniqueID id # Unique way-point identifier +GeoPoint position # Position relative to WGS 84 ellipsoid +KeyValue[] props # Key/value properties for this point diff --git a/navigations/geographic_info/geographic_msgs/package.xml b/navigations/geographic_info/geographic_msgs/package.xml new file mode 100755 index 0000000..254e932 --- /dev/null +++ b/navigations/geographic_info/geographic_msgs/package.xml @@ -0,0 +1,28 @@ + + + geographic_msgs + 0.5.6 + + ROS messages for Geographic Information Systems. + + Jack O'Quin + Jack O'Quin + BSD + + http://wiki.ros.org/geographic_msgs + https://github.com/ros-geographic-info/geographic_info/issues + https://github.com/ros-geographic-info/geographic_info.git + + catkin + + message_generation + geometry_msgs + std_msgs + uuid_msgs + + message_runtime + geometry_msgs + std_msgs + uuid_msgs + + diff --git a/navigations/geographic_info/geographic_msgs/srv/GetGeoPath.srv b/navigations/geographic_info/geographic_msgs/srv/GetGeoPath.srv new file mode 100755 index 0000000..94c2a01 --- /dev/null +++ b/navigations/geographic_info/geographic_msgs/srv/GetGeoPath.srv @@ -0,0 +1,17 @@ +# Searches for given start and goal the nearest route segments +# and determine the path through the RouteNetwork + +geographic_msgs/GeoPoint start # starting point +geographic_msgs/GeoPoint goal # goal point + +--- + +bool success # true if the call succeeded +string status # more details + +geographic_msgs/GeoPath plan # path to follow + +uuid_msgs/UniqueID network # the uuid of the RouteNetwork +uuid_msgs/UniqueID start_seg # the uuid of the starting RouteSegment +uuid_msgs/UniqueID goal_seg # the uuid of the ending RouteSegment +float64 distance # the length of the plan diff --git a/navigations/geographic_info/geographic_msgs/srv/GetGeographicMap.srv b/navigations/geographic_info/geographic_msgs/srv/GetGeographicMap.srv new file mode 100755 index 0000000..ecaa592 --- /dev/null +++ b/navigations/geographic_info/geographic_msgs/srv/GetGeographicMap.srv @@ -0,0 +1,15 @@ +# This service requests a region of a geographic map. + +string url # where to read map data + +# Bounding box for the desired map. If all zeros, provide all data +# available from the specified URL. +BoundingBox bounds + +--- + +bool success # true if the call succeeded +string status # more details + +# The requested map, its bounds may differ from the requested bounds. +GeographicMap map diff --git a/navigations/geographic_info/geographic_msgs/srv/GetRoutePlan.srv b/navigations/geographic_info/geographic_msgs/srv/GetRoutePlan.srv new file mode 100755 index 0000000..f1bb88f --- /dev/null +++ b/navigations/geographic_info/geographic_msgs/srv/GetRoutePlan.srv @@ -0,0 +1,14 @@ +# Get a plan to traverse a route network from start to goal. +# +# Similar to nav_msgs/GetPlan, but constrained to use the route network. + +uuid_msgs/UniqueID network # route network to use +uuid_msgs/UniqueID start # starting way point +uuid_msgs/UniqueID goal # goal way point + +--- + +bool success # true if the call succeeded +string status # more details + +RoutePath plan # path to follow diff --git a/navigations/geographic_info/geographic_msgs/srv/UpdateGeographicMap.srv b/navigations/geographic_info/geographic_msgs/srv/UpdateGeographicMap.srv new file mode 100755 index 0000000..f390cd3 --- /dev/null +++ b/navigations/geographic_info/geographic_msgs/srv/UpdateGeographicMap.srv @@ -0,0 +1,9 @@ +# This service updates a geographic map. + +# Changes to geographic map. +GeographicMapChanges updates + +--- + +bool success # true if the call succeeded +string status # more details diff --git a/navigations/geometry2/tf2_geometry_msgs/CHANGELOG.rst b/navigations/geometry2/tf2_geometry_msgs/CHANGELOG.rst new file mode 100755 index 0000000..2fead0b --- /dev/null +++ b/navigations/geometry2/tf2_geometry_msgs/CHANGELOG.rst @@ -0,0 +1,248 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package tf2_geometry_msgs +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +0.7.6 (2022-10-11) +------------------ +* remove method with misleading doc (`#534 `_) +* Contributors: Wellington Castro + +0.7.5 (2020-09-01) +------------------ + +0.7.4 (2020-09-01) +------------------ + +0.7.3 (2020-08-25) +------------------ +* Use list instead of set to make build reproducible (`#473 `_) +* Contributors: Jochen Sprickerhof + +0.7.2 (2020-06-08) +------------------ + +0.7.1 (2020-05-13) +------------------ +* import setup from setuptools instead of distutils-core (`#449 `_) +* Contributors: Alejandro Hernández Cordero + +0.7.0 (2020-03-09) +------------------ +* Replace kdl packages with rosdep keys (`#447 `_) +* Bump CMake version to avoid CMP0048 warning (`#445 `_) +* Make kdl headers available (`#419 `_) +* FIx python3 compatibility for noetic (`#416 `_) +* add from STL (`#366 `_) +* use ROS_DEPRECATED macro for portability (`#362 `_) + * use ROS_DEPRECATED for better portability + * change ROS_DEPRECATED position (`#5 `_) +* Contributors: James Xu, Shane Loretz, Tully Foote + +0.6.5 (2018-11-16) +------------------ +* Fix python3 import error +* Contributors: Timon Engelke + +0.6.4 (2018-11-06) +------------------ + +0.6.3 (2018-07-09) +------------------ +* Changed access to Vector to prevent memory leak (`#305 `_) +* Added WrenchStamped transformation (`#302 `_) +* Contributors: Denis Štogl, Markus Grimm + +0.6.2 (2018-05-02) +------------------ + +0.6.1 (2018-03-21) +------------------ + +0.6.0 (2018-03-21) +------------------ +* Boilerplate for Sphinx (`#284 `_) + Fixes `#264 `_ +* tf2_geometry_msgs added doTransform implementations for not stamped types (`#262 `_) + * tf2_geometry_msgs added doTransform implementations for not stamped Point, Quaterion, Pose and Vector3 message types +* New functionality to transform PoseWithCovarianceStamped messages. (`#282 `_) + * New functionality to transform PoseWithCovarianceStamped messages. +* Contributors: Blake Anderson, Tully Foote, cwecht + +0.5.17 (2018-01-01) +------------------- + +0.5.16 (2017-07-14) +------------------- +* remove explicit templating to standardize on overloading. But provide backwards compatibility with deprecation. +* adding unit tests for conversions +* Copy transform before altering it in do_transform_vector3 [issue 233] (`#235 `_) +* store gtest return value as int (`#229 `_) +* Document the lifetime of the returned reference for getFrameId and getTimestamp +* tf2_geometry_msgs: using tf2::Transform in doTransform-functions, marked gmTransformToKDL as deprecated +* Switch tf2_geometry_msgs to use package.xml format 2 (`#217 `_) +* tf2_geometry_msgs: added missing conversion functions +* Contributors: Christopher Wecht, Sebastian Wagner, Tully Foote, dhood, pAIgn10 + +0.5.15 (2017-01-24) +------------------- + +0.5.14 (2017-01-16) +------------------- +* Add doxygen documentation for tf2_geometry_msgs +* Contributors: Jackie Kay + +0.5.13 (2016-03-04) +------------------- +* Add missing python_orocos_kdl dependency +* make example into unit test +* vector3 not affected by translation +* Contributors: Daniel Claes, chapulina + +0.5.12 (2015-08-05) +------------------- +* Merge pull request `#112 `_ from vrabaud/getYaw + Get yaw +* add toMsg and fromMsg for QuaternionStamped +* Contributors: Tully Foote, Vincent Rabaud + +0.5.11 (2015-04-22) +------------------- + +0.5.10 (2015-04-21) +------------------- + +0.5.9 (2015-03-25) +------------------ + +0.5.8 (2015-03-17) +------------------ +* remove useless Makefile files +* tf2 optimizations +* add conversions of type between tf2 and geometry_msgs +* fix ODR violations +* Contributors: Vincent Rabaud + +0.5.7 (2014-12-23) +------------------ +* fixing transitive dependency for kdl. Fixes `#53 `_ +* Contributors: Tully Foote + +0.5.6 (2014-09-18) +------------------ + +0.5.5 (2014-06-23) +------------------ + +0.5.4 (2014-05-07) +------------------ + +0.5.3 (2014-02-21) +------------------ + +0.5.2 (2014-02-20) +------------------ + +0.5.1 (2014-02-14) +------------------ + +0.5.0 (2014-02-14) +------------------ + +0.4.10 (2013-12-26) +------------------- + +0.4.9 (2013-11-06) +------------------ + +0.4.8 (2013-11-06) +------------------ + +0.4.7 (2013-08-28) +------------------ + +0.4.6 (2013-08-28) +------------------ + +0.4.5 (2013-07-11) +------------------ + +0.4.4 (2013-07-09) +------------------ +* making repo use CATKIN_ENABLE_TESTING correctly and switching rostest to be a test_depend with that change. + +0.4.3 (2013-07-05) +------------------ + +0.4.2 (2013-07-05) +------------------ + +0.4.1 (2013-07-05) +------------------ + +0.4.0 (2013-06-27) +------------------ +* moving convert methods back into tf2 because it does not have any ros dependencies beyond ros::Time which is already a dependency of tf2 +* Cleaning up unnecessary dependency on roscpp +* converting contents of tf2_ros to be properly namespaced in the tf2_ros namespace +* Cleaning up packaging of tf2 including: + removing unused nodehandle + cleaning up a few dependencies and linking + removing old backup of package.xml + making diff minimally different from tf version of library +* Restoring test packages and bullet packages. + reverting 3570e8c42f9b394ecbfd9db076b920b41300ad55 to get back more of the packages previously implemented + reverting 04cf29d1b58c660fdc999ab83563a5d4b76ab331 to fix `#7 `_ + +0.3.6 (2013-03-03) +------------------ + +0.3.5 (2013-02-15 14:46) +------------------------ +* 0.3.4 -> 0.3.5 + +0.3.4 (2013-02-15 13:14) +------------------------ +* 0.3.3 -> 0.3.4 + +0.3.3 (2013-02-15 11:30) +------------------------ +* 0.3.2 -> 0.3.3 + +0.3.2 (2013-02-15 00:42) +------------------------ +* 0.3.1 -> 0.3.2 + +0.3.1 (2013-02-14) +------------------ +* 0.3.0 -> 0.3.1 + +0.3.0 (2013-02-13) +------------------ +* switching to version 0.3.0 +* add setup.py +* added setup.py etc to tf2_geometry_msgs +* adding tf2 dependency to tf2_geometry_msgs +* adding tf2_geometry_msgs to groovy-devel (unit tests disabled) +* fixing groovy-devel +* removing bullet and kdl related packages +* disabling tf2_geometry_msgs due to missing kdl dependency +* catkinizing geometry-experimental +* catkinizing tf2_geometry_msgs +* add twist, wrench and pose conversion to kdl, fix message to message conversion by adding specific conversion functions +* merge tf2_cpp and tf2_py into tf2_ros +* Got transform with types working in python +* A working first version of transforming and converting between different types +* Moving from camelCase to undescores to be in line with python style guides +* Fixing tests now that Buffer creates a NodeHandle +* add posestamped +* import vector3stamped +* add support for Vector3Stamped and PoseStamped +* add support for PointStamped geometry_msgs +* add regression tests for geometry_msgs point, vector and pose +* Fixing missing export, compiling version of buffer_client test +* add bullet transforms, and create tests for bullet and kdl +* working transformations of messages +* add support for PoseStamped message +* test for pointstamped +* add PointStamped message transform methods +* transform for vector3stamped message diff --git a/navigations/geometry2/tf2_geometry_msgs/CMakeLists.txt b/navigations/geometry2/tf2_geometry_msgs/CMakeLists.txt new file mode 100755 index 0000000..fd1f0e1 --- /dev/null +++ b/navigations/geometry2/tf2_geometry_msgs/CMakeLists.txt @@ -0,0 +1,52 @@ +cmake_minimum_required(VERSION 3.0.2) +project(tf2_geometry_msgs) + +find_package(orocos_kdl) +find_package(catkin REQUIRED COMPONENTS geometry_msgs tf2_ros tf2) +find_package(Boost COMPONENTS thread REQUIRED) + +# Issue #53 +find_library(KDL_LIBRARY REQUIRED NAMES orocos-kdl HINTS ${orocos_kdl_LIBRARY_DIRS}) + +catkin_package( + LIBRARIES ${KDL_LIBRARY} + INCLUDE_DIRS include + DEPENDS orocos_kdl + CATKIN_DEPENDS geometry_msgs tf2_ros tf2) + + +include_directories(include + ${catkin_INCLUDE_DIRS} +) + +link_directories(${orocos_kdl_LIBRARY_DIRS}) + + + +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} +) + +catkin_python_setup() + +if(CATKIN_ENABLE_TESTING) + +catkin_add_gtest(test_tomsg_frommsg test/test_tomsg_frommsg.cpp) +target_include_directories(test_tomsg_frommsg PUBLIC ${orocos_kdl_INCLUDE_DIRS}) +target_link_libraries(test_tomsg_frommsg ${catkin_LIBRARIES} ${GTEST_LIBRARIES} ${orocos_kdl_LIBRARIES}) + +find_package(catkin REQUIRED COMPONENTS geometry_msgs rostest tf2_ros tf2) + +add_executable(test_geometry_msgs EXCLUDE_FROM_ALL test/test_tf2_geometry_msgs.cpp) +target_include_directories(test_geometry_msgs PUBLIC ${orocos_kdl_INCLUDE_DIRS}) +target_link_libraries(test_geometry_msgs ${catkin_LIBRARIES} ${GTEST_LIBRARIES} ${orocos_kdl_LIBRARIES}) +add_rostest(${CMAKE_CURRENT_SOURCE_DIR}/test/test.launch) +add_rostest(${CMAKE_CURRENT_SOURCE_DIR}/test/test_python.launch) + + +if(TARGET tests) + add_dependencies(tests test_geometry_msgs) +endif() + + +endif() diff --git a/navigations/geometry2/tf2_geometry_msgs/conf.py b/navigations/geometry2/tf2_geometry_msgs/conf.py new file mode 100755 index 0000000..d358e5b --- /dev/null +++ b/navigations/geometry2/tf2_geometry_msgs/conf.py @@ -0,0 +1,290 @@ +# -*- coding: utf-8 -*- +# +# tf2_geometry_msgs documentation build configuration file, created by +# sphinx-quickstart on Tue Feb 13 15:34:25 2018. +# +# This file is execfile()d with the current directory set to its +# containing dir. +# +# Note that not all possible configuration values are present in this +# autogenerated file. +# +# All configuration values have a default; values that are commented out +# serve to show the default. + +import sys +import os + +# If extensions (or modules to document with autodoc) are in another directory, +# add these directories to sys.path here. If the directory is relative to the +# documentation root, use os.path.abspath to make it absolute, like shown here. +#sys.path.insert(0, os.path.abspath('.')) + +# -- General configuration ------------------------------------------------ + +# If your documentation needs a minimal Sphinx version, state it here. +#needs_sphinx = '1.0' + +# Add any Sphinx extension module names here, as strings. They can be +# extensions coming with Sphinx (named 'sphinx.ext.*') or your custom +# ones. +extensions = [ + 'sphinx.ext.autodoc', + 'sphinx.ext.doctest', + 'sphinx.ext.intersphinx', + 'sphinx.ext.todo', + 'sphinx.ext.pngmath', + 'sphinx.ext.viewcode', +] + +# Add any paths that contain templates here, relative to this directory. +templates_path = ['_templates'] + +# The suffix(es) of source filenames. +# You can specify multiple suffix as a list of string: +# source_suffix = ['.rst', '.md'] +source_suffix = '.rst' + +# The encoding of source files. +#source_encoding = 'utf-8-sig' + +# The master toctree document. +master_doc = 'index' + +# General information about the project. +project = u'tf2_geometry_msgs' +copyright = u'2018, Open Source Robotics Foundation, Inc.' +author = u'Tully Foote' + +# The version info for the project you're documenting, acts as replacement for +# |version| and |release|, also used in various other places throughout the +# built documents. +# +# The short X.Y version. +version = u'0.1' +# The full version, including alpha/beta/rc tags. +release = u'0.1' + +# The language for content autogenerated by Sphinx. Refer to documentation +# for a list of supported languages. +# +# This is also used if you do content translation via gettext catalogs. +# Usually you set "language" from the command line for these cases. +language = None + +# There are two options for replacing |today|: either, you set today to some +# non-false value, then it is used: +#today = '' +# Else, today_fmt is used as the format for a strftime call. +#today_fmt = '%B %d, %Y' + +# List of patterns, relative to source directory, that match files and +# directories to ignore when looking for source files. +exclude_patterns = ['_build'] + +# The reST default role (used for this markup: `text`) to use for all +# documents. +#default_role = None + +# If true, '()' will be appended to :func: etc. cross-reference text. +#add_function_parentheses = True + +# If true, the current module name will be prepended to all description +# unit titles (such as .. function::). +#add_module_names = True + +# If true, sectionauthor and moduleauthor directives will be shown in the +# output. They are ignored by default. +#show_authors = False + +# The name of the Pygments (syntax highlighting) style to use. +pygments_style = 'sphinx' + +# A list of ignored prefixes for module index sorting. +#modindex_common_prefix = [] + +# If true, keep warnings as "system message" paragraphs in the built documents. +#keep_warnings = False + +# -- Options for HTML output --------------------------------------------------- + +# The theme to use for HTML and HTML Help pages. Major themes that come with +# Sphinx are currently 'default' and 'sphinxdoc'. +html_theme = 'default' + +# Theme options are theme-specific and customize the look and feel of a theme +# further. For a list of options available for each theme, see the +# documentation. +#html_theme_options = {} + +# Add any paths that contain custom themes here, relative to this directory. +#html_theme_path = [] + +# The name for this set of Sphinx documents. If None, it defaults to +# " v documentation". +#html_title = None + +# A shorter title for the navigation bar. Default is the same as html_title. +#html_short_title = None + +# The name of an image file (relative to this directory) to place at the top +# of the sidebar. +#html_logo = None + +# The name of an image file (relative to this directory) to use as a favicon of +# the docs. This file should be a Windows icon file (.ico) being 16x16 or 32x32 +# pixels large. +#html_favicon = None + +# Add any paths that contain custom static files (such as style sheets) here, +# relative to this directory. They are copied after the builtin static files, +# so a file named "default.css" will overwrite the builtin "default.css". +html_static_path = ['_static'] + +# Add any extra paths that contain custom files (such as robots.txt or +# .htaccess) here, relative to this directory. These files are copied +# directly to the root of the documentation. +#html_extra_path = [] + +# If not '', a 'Last updated on:' timestamp is inserted at every page bottom, +# using the given strftime format. +#html_last_updated_fmt = '%b %d, %Y' + +# If true, SmartyPants will be used to convert quotes and dashes to +# typographically correct entities. +#html_use_smartypants = True + +# Custom sidebar templates, maps document names to template names. +#html_sidebars = {} + +# Additional templates that should be rendered to pages, maps page names to +# template names. +#html_additional_pages = {} + +# If false, no module index is generated. +#html_domain_indices = True + +# If false, no index is generated. +#html_use_index = True + +# If true, the index is split into individual pages for each letter. +#html_split_index = False + +# If true, links to the reST sources are added to the pages. +#html_show_sourcelink = True + +# If true, "Created using Sphinx" is shown in the HTML footer. Default is True. +#html_show_sphinx = True + +# If true, "(C) Copyright ..." is shown in the HTML footer. Default is True. +#html_show_copyright = True + +# If true, an OpenSearch description file will be output, and all pages will +# contain a tag referring to it. The value of this option must be the +# base URL from which the finished HTML is served. +#html_use_opensearch = '' + +# This is the file name suffix for HTML files (e.g. ".xhtml"). +#html_file_suffix = None + +# Language to be used for generating the HTML full-text search index. +# Sphinx supports the following languages: +# 'da', 'de', 'en', 'es', 'fi', 'fr', 'hu', 'it', 'ja' +# 'nl', 'no', 'pt', 'ro', 'ru', 'sv', 'tr' +#html_search_language = 'en' + +# A dictionary with options for the search language support, empty by default. +# Now only 'ja' uses this config value +#html_search_options = {'type': 'default'} + +# The name of a javascript file (relative to the configuration directory) that +# implements a search results scorer. If empty, the default will be used. +#html_search_scorer = 'scorer.js' + +# Output file base name for HTML help builder. +htmlhelp_basename = 'tf2_geometry_msgsdoc' + +# -- Options for LaTeX output --------------------------------------------- + +latex_elements = { +# The paper size ('letterpaper' or 'a4paper'). +#'papersize': 'letterpaper', + +# The font size ('10pt', '11pt' or '12pt'). +#'pointsize': '10pt', + +# Additional stuff for the LaTeX preamble. +#'preamble': '', + +# Latex figure (float) alignment +#'figure_align': 'htbp', +} + +# Grouping the document tree into LaTeX files. List of tuples +# (source start file, target name, title, +# author, documentclass [howto, manual, or own class]). +latex_documents = [ + (master_doc, 'tf2_geometry_msgs.tex', u'tf2\\_geometry\\_msgs Documentation', + u'Tully Foote', 'manual'), +] + +# The name of an image file (relative to this directory) to place at the top of +# the title page. +#latex_logo = None + +# For "manual" documents, if this is true, then toplevel headings are parts, +# not chapters. +#latex_use_parts = False + +# If true, show page references after internal links. +#latex_show_pagerefs = False + +# If true, show URL addresses after external links. +#latex_show_urls = False + +# Documents to append as an appendix to all manuals. +#latex_appendices = [] + +# If false, no module index is generated. +#latex_domain_indices = True + + +# -- Options for manual page output --------------------------------------- + +# One entry per manual page. List of tuples +# (source start file, name, description, authors, manual section). +man_pages = [ + (master_doc, 'tf2_geometry_msgs', u'tf2_geometry_msgs Documentation', + [author], 1) +] + +# If true, show URL addresses after external links. +#man_show_urls = False + + +# -- Options for Texinfo output ------------------------------------------- + +# Grouping the document tree into Texinfo files. List of tuples +# (source start file, target name, title, author, +# dir menu entry, description, category) +texinfo_documents = [ + (master_doc, 'tf2_geometry_msgs', u'tf2_geometry_msgs Documentation', + author, 'tf2_geometry_msgs', 'One line description of project.', + 'Miscellaneous'), +] + +# Documents to append as an appendix to all manuals. +#texinfo_appendices = [] + +# If false, no module index is generated. +#texinfo_domain_indices = True + +# How to display URL addresses: 'footnote', 'no', or 'inline'. +#texinfo_show_urls = 'footnote' + +# If true, do not generate a @detailmenu in the "Top" node's menu. +#texinfo_no_detailmenu = False + + +# Example configuration for intersphinx: refer to the Python standard library. +intersphinx_mapping = {'https://docs.python.org/': None} diff --git a/navigations/geometry2/tf2_geometry_msgs/include/tf2_geometry_msgs/tf2_geometry_msgs.h b/navigations/geometry2/tf2_geometry_msgs/include/tf2_geometry_msgs/tf2_geometry_msgs.h new file mode 100755 index 0000000..f0ef5f7 --- /dev/null +++ b/navigations/geometry2/tf2_geometry_msgs/include/tf2_geometry_msgs/tf2_geometry_msgs.h @@ -0,0 +1,1057 @@ +/* + * Copyright (c) 2008, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +/** \author Wim Meeussen */ + +#ifndef TF2_GEOMETRY_MSGS_H +#define TF2_GEOMETRY_MSGS_H + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include + +#include "ros/macros.h" + +namespace tf2 +{ + +/** \brief Convert a TransformStamped message to a KDL frame. + * \param t TransformStamped message to convert. + * \return The converted KDL Frame. + * \deprecated + */ +inline +ROS_DEPRECATED KDL::Frame gmTransformToKDL(const geometry_msgs::TransformStamped& t); +inline +KDL::Frame gmTransformToKDL(const geometry_msgs::TransformStamped& t) + { + return KDL::Frame(KDL::Rotation::Quaternion(t.transform.rotation.x, t.transform.rotation.y, + t.transform.rotation.z, t.transform.rotation.w), + KDL::Vector(t.transform.translation.x, t.transform.translation.y, t.transform.translation.z)); + } + + +/*************/ +/** Vector3 **/ +/*************/ + +/** \brief Convert a tf2 Vector3 type to its equivalent geometry_msgs representation. + * This function is a specialization of the toMsg template defined in tf2/convert.h. + * \param in A tf2 Vector3 object. + * \return The Vector3 converted to a geometry_msgs message type. + */ +inline +geometry_msgs::Vector3 toMsg(const tf2::Vector3& in) +{ + geometry_msgs::Vector3 out; + out.x = in.getX(); + out.y = in.getY(); + out.z = in.getZ(); + return out; +} + +/** \brief Convert a Vector3 message to its equivalent tf2 representation. + * This function is a specialization of the fromMsg template defined in tf2/convert.h. + * \param in A Vector3 message type. + * \param out The Vector3 converted to a tf2 type. + */ +inline +void fromMsg(const geometry_msgs::Vector3& in, tf2::Vector3& out) +{ + out = tf2::Vector3(in.x, in.y, in.z); +} + + +/********************/ +/** Vector3Stamped **/ +/********************/ + +/** \brief Extract a timestamp from the header of a Vector message. + * This function is a specialization of the getTimestamp template defined in tf2/convert.h. + * \param t VectorStamped message to extract the timestamp from. + * \return The timestamp of the message. The lifetime of the returned reference + * is bound to the lifetime of the argument. + */ +template <> +inline + const ros::Time& getTimestamp(const geometry_msgs::Vector3Stamped& t) {return t.header.stamp;} + +/** \brief Extract a frame ID from the header of a Vector message. + * This function is a specialization of the getFrameId template defined in tf2/convert.h. + * \param t VectorStamped message to extract the frame ID from. + * \return A string containing the frame ID of the message. The lifetime of the + * returned reference is bound to the lifetime of the argument. + */ +template <> +inline + const std::string& getFrameId(const geometry_msgs::Vector3Stamped& t) {return t.header.frame_id;} + + +/** \brief Trivial "conversion" function for Vector3 message type. + * This function is a specialization of the toMsg template defined in tf2/convert.h. + * \param in A Vector3Stamped message. + * \return The input argument. + */ +inline +geometry_msgs::Vector3Stamped toMsg(const geometry_msgs::Vector3Stamped& in) +{ + return in; +} + +/** \brief Trivial "conversion" function for Vector3 message type. + * This function is a specialization of the fromMsg template defined in tf2/convert.h. + * \param msg A Vector3Stamped message. + * \param out The input argument. + */ +inline +void fromMsg(const geometry_msgs::Vector3Stamped& msg, geometry_msgs::Vector3Stamped& out) +{ + out = msg; +} + +/** \brief Convert as stamped tf2 Vector3 type to its equivalent geometry_msgs representation. + * This function is a specialization of the toMsg template defined in tf2/convert.h. + * \param in An instance of the tf2::Vector3 specialization of the tf2::Stamped template. + * \return The Vector3Stamped converted to a geometry_msgs Vector3Stamped message type. + */ +inline +geometry_msgs::Vector3Stamped toMsg(const tf2::Stamped& in) +{ + geometry_msgs::Vector3Stamped out; + out.header.stamp = in.stamp_; + out.header.frame_id = in.frame_id_; + out.vector.x = in.getX(); + out.vector.y = in.getY(); + out.vector.z = in.getZ(); + return out; +} + +/** \brief Convert a Vector3Stamped message to its equivalent tf2 representation. + * This function is a specialization of the fromMsg template defined in tf2/convert.h. + * \param msg A Vector3Stamped message. + * \param out The Vector3Stamped converted to the equivalent tf2 type. + */ +inline +void fromMsg(const geometry_msgs::Vector3Stamped& msg, tf2::Stamped& out) +{ + out.stamp_ = msg.header.stamp; + out.frame_id_ = msg.header.frame_id; + out.setData(tf2::Vector3(msg.vector.x, msg.vector.y, msg.vector.z)); +} + + +/***********/ +/** Point **/ +/***********/ + +/** \brief Convert a tf2 Vector3 type to its equivalent geometry_msgs representation. + * This function is a specialization of the toMsg template defined in tf2/convert.h. + * \param in A tf2 Vector3 object. + * \return The Vector3 converted to a geometry_msgs message type. + */ +inline +geometry_msgs::Point& toMsg(const tf2::Vector3& in, geometry_msgs::Point& out) +{ + out.x = in.getX(); + out.y = in.getY(); + out.z = in.getZ(); + return out; +} + +/** \brief Convert a Vector3 message to its equivalent tf2 representation. + * This function is a specialization of the fromMsg template defined in tf2/convert.h. + * \param in A Vector3 message type. + * \param out The Vector3 converted to a tf2 type. + */ +inline +void fromMsg(const geometry_msgs::Point& in, tf2::Vector3& out) +{ + out = tf2::Vector3(in.x, in.y, in.z); +} + + +/******************/ +/** PointStamped **/ +/******************/ + +/** \brief Extract a timestamp from the header of a Point message. + * This function is a specialization of the getTimestamp template defined in tf2/convert.h. + * \param t PointStamped message to extract the timestamp from. + * \return The timestamp of the message. The lifetime of the returned reference + * is bound to the lifetime of the argument. + */ +template <> +inline + const ros::Time& getTimestamp(const geometry_msgs::PointStamped& t) {return t.header.stamp;} + +/** \brief Extract a frame ID from the header of a Point message. + * This function is a specialization of the getFrameId template defined in tf2/convert.h. + * \param t PointStamped message to extract the frame ID from. + * \return A string containing the frame ID of the message. The lifetime of the + * returned reference is bound to the lifetime of the argument. + */ +template <> +inline + const std::string& getFrameId(const geometry_msgs::PointStamped& t) {return t.header.frame_id;} + +/** \brief Trivial "conversion" function for Point message type. + * This function is a specialization of the toMsg template defined in tf2/convert.h. + * \param in A PointStamped message. + * \return The input argument. + */ +inline +geometry_msgs::PointStamped toMsg(const geometry_msgs::PointStamped& in) +{ + return in; +} + +/** \brief Trivial "conversion" function for Point message type. + * This function is a specialization of the fromMsg template defined in tf2/convert.h. + * \param msg A PointStamped message. + * \param out The input argument. + */ +inline +void fromMsg(const geometry_msgs::PointStamped& msg, geometry_msgs::PointStamped& out) +{ + out = msg; +} + +/** \brief Convert as stamped tf2 Vector3 type to its equivalent geometry_msgs representation. + * This function is a specialization of the toMsg template defined in tf2/convert.h. + * \param in An instance of the tf2::Vector3 specialization of the tf2::Stamped template. + * \return The Vector3Stamped converted to a geometry_msgs PointStamped message type. + */ +inline +geometry_msgs::PointStamped toMsg(const tf2::Stamped& in, geometry_msgs::PointStamped & out) +{ + out.header.stamp = in.stamp_; + out.header.frame_id = in.frame_id_; + out.point.x = in.getX(); + out.point.y = in.getY(); + out.point.z = in.getZ(); + return out; +} + +/** \brief Convert a PointStamped message to its equivalent tf2 representation. + * This function is a specialization of the fromMsg template defined in tf2/convert.h. + * \param msg A PointStamped message. + * \param out The PointStamped converted to the equivalent tf2 type. + */ +inline +void fromMsg(const geometry_msgs::PointStamped& msg, tf2::Stamped& out) +{ + out.stamp_ = msg.header.stamp; + out.frame_id_ = msg.header.frame_id; + out.setData(tf2::Vector3(msg.point.x, msg.point.y, msg.point.z)); +} + + +/****************/ +/** Quaternion **/ +/****************/ + +/** \brief Convert a tf2 Quaternion type to its equivalent geometry_msgs representation. + * This function is a specialization of the toMsg template defined in tf2/convert.h. + * \param in A tf2 Quaternion object. + * \return The Quaternion converted to a geometry_msgs message type. + */ +inline +geometry_msgs::Quaternion toMsg(const tf2::Quaternion& in) +{ + geometry_msgs::Quaternion out; + out.w = in.getW(); + out.x = in.getX(); + out.y = in.getY(); + out.z = in.getZ(); + return out; +} + +/** \brief Convert a Quaternion message to its equivalent tf2 representation. + * This function is a specialization of the fromMsg template defined in tf2/convert.h. + * \param in A Quaternion message type. + * \param out The Quaternion converted to a tf2 type. + */ +inline +void fromMsg(const geometry_msgs::Quaternion& in, tf2::Quaternion& out) +{ + // w at the end in the constructor + out = tf2::Quaternion(in.x, in.y, in.z, in.w); +} + + +/***********************/ +/** QuaternionStamped **/ +/***********************/ + +/** \brief Extract a timestamp from the header of a Quaternion message. + * This function is a specialization of the getTimestamp template defined in tf2/convert.h. + * \param t QuaternionStamped message to extract the timestamp from. + * \return The timestamp of the message. The lifetime of the returned reference + * is bound to the lifetime of the argument. + */ +template <> +inline +const ros::Time& getTimestamp(const geometry_msgs::QuaternionStamped& t) {return t.header.stamp;} + +/** \brief Extract a frame ID from the header of a Quaternion message. + * This function is a specialization of the getFrameId template defined in tf2/convert.h. + * \param t QuaternionStamped message to extract the frame ID from. + * \return A string containing the frame ID of the message. The lifetime of the + * returned reference is bound to the lifetime of the argument. + */ +template <> +inline +const std::string& getFrameId(const geometry_msgs::QuaternionStamped& t) {return t.header.frame_id;} + +/** \brief Trivial "conversion" function for Quaternion message type. + * This function is a specialization of the toMsg template defined in tf2/convert.h. + * \param in A QuaternionStamped message. + * \return The input argument. + */ +inline +geometry_msgs::QuaternionStamped toMsg(const geometry_msgs::QuaternionStamped& in) +{ + return in; +} + +/** \brief Trivial "conversion" function for Quaternion message type. + * This function is a specialization of the fromMsg template defined in tf2/convert.h. + * \param msg A QuaternionStamped message. + * \param out The input argument. + */ +inline +void fromMsg(const geometry_msgs::QuaternionStamped& msg, geometry_msgs::QuaternionStamped& out) +{ + out = msg; +} + +/** \brief Convert as stamped tf2 Quaternion type to its equivalent geometry_msgs representation. + * This function is a specialization of the toMsg template defined in tf2/convert.h. + * \param in An instance of the tf2::Quaternion specialization of the tf2::Stamped template. + * \return The QuaternionStamped converted to a geometry_msgs QuaternionStamped message type. + */ +inline +geometry_msgs::QuaternionStamped toMsg(const tf2::Stamped& in) +{ + geometry_msgs::QuaternionStamped out; + out.header.stamp = in.stamp_; + out.header.frame_id = in.frame_id_; + out.quaternion.w = in.getW(); + out.quaternion.x = in.getX(); + out.quaternion.y = in.getY(); + out.quaternion.z = in.getZ(); + return out; +} + +template <> +inline +ROS_DEPRECATED geometry_msgs::QuaternionStamped toMsg(const tf2::Stamped& in); + + +//Backwards compatibility remove when forked for Lunar or newer +template <> +inline +geometry_msgs::QuaternionStamped toMsg(const tf2::Stamped& in) +{ + return toMsg(in); +} + +/** \brief Convert a QuaternionStamped message to its equivalent tf2 representation. + * This function is a specialization of the fromMsg template defined in tf2/convert.h. + * \param in A QuaternionStamped message type. + * \param out The QuaternionStamped converted to the equivalent tf2 type. + */ +inline +void fromMsg(const geometry_msgs::QuaternionStamped& in, tf2::Stamped& out) +{ + out.stamp_ = in.header.stamp; + out.frame_id_ = in.header.frame_id; + tf2::Quaternion tmp; + fromMsg(in.quaternion, tmp); + out.setData(tmp); +} + +template<> +inline +ROS_DEPRECATED void fromMsg(const geometry_msgs::QuaternionStamped& in, tf2::Stamped& out); + +//Backwards compatibility remove when forked for Lunar or newer +template<> +inline +void fromMsg(const geometry_msgs::QuaternionStamped& in, tf2::Stamped& out) +{ + fromMsg(in, out); +} + +/**********/ +/** Pose **/ +/**********/ + +/** \brief Convert a tf2 Transform type to an equivalent geometry_msgs Pose message. + * \param in A tf2 Transform object. + * \param out The Transform converted to a geometry_msgs Pose message type. + */ +inline +geometry_msgs::Pose& toMsg(const tf2::Transform& in, geometry_msgs::Pose& out) +{ + toMsg(in.getOrigin(), out.position); + out.orientation = toMsg(in.getRotation()); + return out; +} + +/** \brief Convert a geometry_msgs Pose message to an equivalent tf2 Transform type. + * \param in A Pose message. + * \param out The Pose converted to a tf2 Transform type. + */ +inline +void fromMsg(const geometry_msgs::Pose& in, tf2::Transform& out) +{ + out.setOrigin(tf2::Vector3(in.position.x, in.position.y, in.position.z)); + // w at the end in the constructor + out.setRotation(tf2::Quaternion(in.orientation.x, in.orientation.y, in.orientation.z, in.orientation.w)); +} + + + +/*****************/ +/** PoseStamped **/ +/*****************/ + +/** \brief Extract a timestamp from the header of a Pose message. + * This function is a specialization of the getTimestamp template defined in tf2/convert.h. + * \param t PoseStamped message to extract the timestamp from. + * \return The timestamp of the message. + */ +template <> +inline + const ros::Time& getTimestamp(const geometry_msgs::PoseStamped& t) {return t.header.stamp;} + +/** \brief Extract a frame ID from the header of a Pose message. + * This function is a specialization of the getFrameId template defined in tf2/convert.h. + * \param t PoseStamped message to extract the frame ID from. + * \return A string containing the frame ID of the message. + */ +template <> +inline + const std::string& getFrameId(const geometry_msgs::PoseStamped& t) {return t.header.frame_id;} + +/** \brief Trivial "conversion" function for Pose message type. + * This function is a specialization of the toMsg template defined in tf2/convert.h. + * \param in A PoseStamped message. + * \return The input argument. + */ +inline +geometry_msgs::PoseStamped toMsg(const geometry_msgs::PoseStamped& in) +{ + return in; +} + +/** \brief Trivial "conversion" function for Pose message type. + * This function is a specialization of the toMsg template defined in tf2/convert.h. + * \param msg A PoseStamped message. + * \param out The input argument. + */ +inline +void fromMsg(const geometry_msgs::PoseStamped& msg, geometry_msgs::PoseStamped& out) +{ + out = msg; +} + +/** \brief Convert as stamped tf2 Pose type to its equivalent geometry_msgs representation. + * This function is a specialization of the toMsg template defined in tf2/convert.h. + * \param in An instance of the tf2::Pose specialization of the tf2::Stamped template. + * \return The PoseStamped converted to a geometry_msgs PoseStamped message type. + */ +inline +geometry_msgs::PoseStamped toMsg(const tf2::Stamped& in, geometry_msgs::PoseStamped & out) +{ + out.header.stamp = in.stamp_; + out.header.frame_id = in.frame_id_; + toMsg(in.getOrigin(), out.pose.position); + out.pose.orientation = toMsg(in.getRotation()); + return out; +} + +/** \brief Convert a PoseStamped message to its equivalent tf2 representation. + * This function is a specialization of the fromMsg template defined in tf2/convert.h. + * \param msg A PoseStamped message. + * \param out The PoseStamped converted to the equivalent tf2 type. + */ +inline +void fromMsg(const geometry_msgs::PoseStamped& msg, tf2::Stamped& out) +{ + out.stamp_ = msg.header.stamp; + out.frame_id_ = msg.header.frame_id; + tf2::Transform tmp; + fromMsg(msg.pose, tmp); + out.setData(tmp); +} + +/*******************************/ +/** PoseWithCovarianceStamped **/ +/*******************************/ + +/** \brief Extract a timestamp from the header of a PoseWithCovarianceStamped message. + * This function is a specialization of the getTimestamp template defined in tf2/convert.h. + * \param t PoseWithCovarianceStamped message to extract the timestamp from. + * \return The timestamp of the message. + */ +template <> +inline + const ros::Time& getTimestamp(const geometry_msgs::PoseWithCovarianceStamped& t) {return t.header.stamp;} + +/** \brief Extract a frame ID from the header of a PoseWithCovarianceStamped message. + * This function is a specialization of the getFrameId template defined in tf2/convert.h. + * \param t PoseWithCovarianceStamped message to extract the frame ID from. + * \return A string containing the frame ID of the message. + */ +template <> +inline + const std::string& getFrameId(const geometry_msgs::PoseWithCovarianceStamped& t) {return t.header.frame_id;} + +/** \brief Trivial "conversion" function for PoseWithCovarianceStamped message type. + * This function is a specialization of the toMsg template defined in tf2/convert.h. + * \param in A PoseWithCovarianceStamped message. + * \return The input argument. + */ +inline +geometry_msgs::PoseWithCovarianceStamped toMsg(const geometry_msgs::PoseWithCovarianceStamped& in) +{ + return in; +} + +/** \brief Trivial "conversion" function for PoseWithCovarianceStamped message type. + * This function is a specialization of the toMsg template defined in tf2/convert.h. + * \param msg A PoseWithCovarianceStamped message. + * \param out The input argument. + */ +inline +void fromMsg(const geometry_msgs::PoseWithCovarianceStamped& msg, geometry_msgs::PoseWithCovarianceStamped& out) +{ + out = msg; +} + +/** \brief Convert as stamped tf2 PoseWithCovarianceStamped type to its equivalent geometry_msgs representation. + * This function is a specialization of the toMsg template defined in tf2/convert.h. + * \param in An instance of the tf2::Pose specialization of the tf2::Stamped template. + * \return The PoseWithCovarianceStamped converted to a geometry_msgs PoseWithCovarianceStamped message type. + */ +inline +geometry_msgs::PoseWithCovarianceStamped toMsg(const tf2::Stamped& in, geometry_msgs::PoseWithCovarianceStamped & out) +{ + out.header.stamp = in.stamp_; + out.header.frame_id = in.frame_id_; + toMsg(in.getOrigin(), out.pose.pose.position); + out.pose.pose.orientation = toMsg(in.getRotation()); + return out; +} + +/** \brief Convert a PoseWithCovarianceStamped message to its equivalent tf2 representation. + * This function is a specialization of the fromMsg template defined in tf2/convert.h. + * \param msg A PoseWithCovarianceStamped message. + * \param out The PoseWithCovarianceStamped converted to the equivalent tf2 type. + */ +inline +void fromMsg(const geometry_msgs::PoseWithCovarianceStamped& msg, tf2::Stamped& out) +{ + out.stamp_ = msg.header.stamp; + out.frame_id_ = msg.header.frame_id; + tf2::Transform tmp; + fromMsg(msg.pose, tmp); + out.setData(tmp); +} + +/***************/ +/** Transform **/ +/***************/ + +/** \brief Convert a tf2 Transform type to its equivalent geometry_msgs representation. + * This function is a specialization of the toMsg template defined in tf2/convert.h. + * \param in A tf2 Transform object. + * \return The Transform converted to a geometry_msgs message type. + */ +inline +geometry_msgs::Transform toMsg(const tf2::Transform& in) +{ + geometry_msgs::Transform out; + out.translation = toMsg(in.getOrigin()); + out.rotation = toMsg(in.getRotation()); + return out; +} + +/** \brief Convert a Transform message to its equivalent tf2 representation. + * This function is a specialization of the toMsg template defined in tf2/convert.h. + * \param in A Transform message type. + * \param out The Transform converted to a tf2 type. + */ +inline +void fromMsg(const geometry_msgs::Transform& in, tf2::Transform& out) +{ + tf2::Vector3 v; + fromMsg(in.translation, v); + out.setOrigin(v); + // w at the end in the constructor + tf2::Quaternion q; + fromMsg(in.rotation, q); + out.setRotation(q); +} + + +/**********************/ +/** TransformStamped **/ +/**********************/ + +/** \brief Extract a timestamp from the header of a Transform message. + * This function is a specialization of the getTimestamp template defined in tf2/convert.h. + * \param t TransformStamped message to extract the timestamp from. + * \return The timestamp of the message. + */ +template <> +inline +const ros::Time& getTimestamp(const geometry_msgs::TransformStamped& t) {return t.header.stamp;} + +/** \brief Extract a frame ID from the header of a Transform message. + * This function is a specialization of the getFrameId template defined in tf2/convert.h. + * \param t TransformStamped message to extract the frame ID from. + * \return A string containing the frame ID of the message. + */ +template <> +inline +const std::string& getFrameId(const geometry_msgs::TransformStamped& t) {return t.header.frame_id;} + +/** \brief Trivial "conversion" function for Transform message type. + * This function is a specialization of the toMsg template defined in tf2/convert.h. + * \param in A TransformStamped message. + * \return The input argument. + */ +inline +geometry_msgs::TransformStamped toMsg(const geometry_msgs::TransformStamped& in) +{ + return in; +} +/** \brief Trivial "conversion" function for TransformStamped message type. + * This function is a specialization of the toMsg template defined in tf2/convert.h. + * \param msg A TransformStamped message. + * \param out The input argument. + */ +inline +void fromMsg(const geometry_msgs::TransformStamped& msg, geometry_msgs::TransformStamped& out) +{ + out = msg; +} + +/** \brief Convert as stamped tf2 Transform type to its equivalent geometry_msgs representation. + * This function is a specialization of the toMsg template defined in tf2/convert.h. + * \param in An instance of the tf2::Transform specialization of the tf2::Stamped template. + * \return The tf2::Stamped converted to a geometry_msgs TransformStamped message type. + */ +inline +geometry_msgs::TransformStamped toMsg(const tf2::Stamped& in) +{ + geometry_msgs::TransformStamped out; + out.header.stamp = in.stamp_; + out.header.frame_id = in.frame_id_; + out.transform.translation = toMsg(in.getOrigin()); + out.transform.rotation = toMsg(in.getRotation()); + return out; +} + + +/** \brief Convert a TransformStamped message to its equivalent tf2 representation. + * This function is a specialization of the fromMsg template defined in tf2/convert.h. + * \param msg A TransformStamped message. + * \param out The TransformStamped converted to the equivalent tf2 type. + */ +inline +void fromMsg(const geometry_msgs::TransformStamped& msg, tf2::Stamped& out) +{ + out.stamp_ = msg.header.stamp; + out.frame_id_ = msg.header.frame_id; + tf2::Transform tmp; + fromMsg(msg.transform, tmp); + out.setData(tmp); +} + +/** \brief Apply a geometry_msgs TransformStamped to an geometry_msgs Point type. + * This function is a specialization of the doTransform template defined in tf2/convert.h. + * \param t_in The point to transform, as a Point3 message. + * \param t_out The transformed point, as a Point3 message. + * \param transform The timestamped transform to apply, as a TransformStamped message. + */ +template <> +inline + void doTransform(const geometry_msgs::Point& t_in, geometry_msgs::Point& t_out, const geometry_msgs::TransformStamped& transform) + { + tf2::Transform t; + fromMsg(transform.transform, t); + tf2::Vector3 v_in; + fromMsg(t_in, v_in); + tf2::Vector3 v_out = t * v_in; + toMsg(v_out, t_out); + } + +/** \brief Apply a geometry_msgs TransformStamped to an stamped geometry_msgs Point type. + * This function is a specialization of the doTransform template defined in tf2/convert.h. + * \param t_in The point to transform, as a timestamped Point3 message. + * \param t_out The transformed point, as a timestamped Point3 message. + * \param transform The timestamped transform to apply, as a TransformStamped message. + */ +template <> +inline + void doTransform(const geometry_msgs::PointStamped& t_in, geometry_msgs::PointStamped& t_out, const geometry_msgs::TransformStamped& transform) + { + doTransform(t_in.point, t_out.point, transform); + t_out.header.stamp = transform.header.stamp; + t_out.header.frame_id = transform.header.frame_id; + } + +/** \brief Apply a geometry_msgs TransformStamped to an geometry_msgs Quaternion type. + * This function is a specialization of the doTransform template defined in tf2/convert.h. + * \param t_in The quaternion to transform, as a Quaternion3 message. + * \param t_out The transformed quaternion, as a Quaternion3 message. + * \param transform The timestamped transform to apply, as a TransformStamped message. + */ +template <> +inline +void doTransform(const geometry_msgs::Quaternion& t_in, geometry_msgs::Quaternion& t_out, const geometry_msgs::TransformStamped& transform) +{ + tf2::Quaternion t, q_in; + fromMsg(transform.transform.rotation, t); + fromMsg(t_in, q_in); + + tf2::Quaternion q_out = t * q_in; + t_out = toMsg(q_out); +} + +/** \brief Apply a geometry_msgs TransformStamped to an stamped geometry_msgs Quaternion type. + * This function is a specialization of the doTransform template defined in tf2/convert.h. + * \param t_in The quaternion to transform, as a timestamped Quaternion3 message. + * \param t_out The transformed quaternion, as a timestamped Quaternion3 message. + * \param transform The timestamped transform to apply, as a TransformStamped message. + */ +template <> +inline +void doTransform(const geometry_msgs::QuaternionStamped& t_in, geometry_msgs::QuaternionStamped& t_out, const geometry_msgs::TransformStamped& transform) +{ + doTransform(t_in.quaternion, t_out.quaternion, transform); + t_out.header.stamp = transform.header.stamp; + t_out.header.frame_id = transform.header.frame_id; +} + + +/** \brief Apply a geometry_msgs TransformStamped to an geometry_msgs Pose type. +* This function is a specialization of the doTransform template defined in tf2/convert.h. +* \param t_in The pose to transform, as a Pose3 message. +* \param t_out The transformed pose, as a Pose3 message. +* \param transform The timestamped transform to apply, as a TransformStamped message. +*/ +template <> +inline +void doTransform(const geometry_msgs::Pose& t_in, geometry_msgs::Pose& t_out, const geometry_msgs::TransformStamped& transform) +{ + tf2::Vector3 v; + fromMsg(t_in.position, v); + tf2::Quaternion r; + fromMsg(t_in.orientation, r); + + tf2::Transform t; + fromMsg(transform.transform, t); + tf2::Transform v_out = t * tf2::Transform(r, v); + toMsg(v_out, t_out); +} + +/** \brief Apply a geometry_msgs TransformStamped to an stamped geometry_msgs Pose type. +* This function is a specialization of the doTransform template defined in tf2/convert.h. +* \param t_in The pose to transform, as a timestamped Pose3 message. +* \param t_out The transformed pose, as a timestamped Pose3 message. +* \param transform The timestamped transform to apply, as a TransformStamped message. +*/ +template <> +inline +void doTransform(const geometry_msgs::PoseStamped& t_in, geometry_msgs::PoseStamped& t_out, const geometry_msgs::TransformStamped& transform) +{ + doTransform(t_in.pose, t_out.pose, transform); + t_out.header.stamp = transform.header.stamp; + t_out.header.frame_id = transform.header.frame_id; +} + +/** \brief Transform the covariance matrix of a PoseWithCovarianceStamped message to a new frame. +* \param t_in The covariance matrix to transform. +* \param transform The timestamped transform to apply, as a TransformStamped message. +* \return The transformed covariance matrix. +*/ +inline +geometry_msgs::PoseWithCovariance::_covariance_type transformCovariance(const geometry_msgs::PoseWithCovariance::_covariance_type& cov_in, const tf2::Transform& transform) +{ + /** + * To transform a covariance matrix: + * + * [R 0] COVARIANCE [R' 0 ] + * [0 R] [0 R'] + * + * Where: + * R is the rotation matrix (3x3). + * R' is the transpose of the rotation matrix. + * COVARIANCE is the 6x6 covariance matrix to be transformed. + */ + + // get rotation matrix transpose + const tf2::Matrix3x3 R_transpose = transform.getBasis().transpose(); + + // convert the covariance matrix into four 3x3 blocks + const tf2::Matrix3x3 cov_11(cov_in[0], cov_in[1], cov_in[2], + cov_in[6], cov_in[7], cov_in[8], + cov_in[12], cov_in[13], cov_in[14]); + const tf2::Matrix3x3 cov_12(cov_in[3], cov_in[4], cov_in[5], + cov_in[9], cov_in[10], cov_in[11], + cov_in[15], cov_in[16], cov_in[17]); + const tf2::Matrix3x3 cov_21(cov_in[18], cov_in[19], cov_in[20], + cov_in[24], cov_in[25], cov_in[26], + cov_in[30], cov_in[31], cov_in[32]); + const tf2::Matrix3x3 cov_22(cov_in[21], cov_in[22], cov_in[23], + cov_in[27], cov_in[28], cov_in[29], + cov_in[33], cov_in[34], cov_in[35]); + + // perform blockwise matrix multiplication + const tf2::Matrix3x3 result_11 = transform.getBasis()*cov_11*R_transpose; + const tf2::Matrix3x3 result_12 = transform.getBasis()*cov_12*R_transpose; + const tf2::Matrix3x3 result_21 = transform.getBasis()*cov_21*R_transpose; + const tf2::Matrix3x3 result_22 = transform.getBasis()*cov_22*R_transpose; + + // form the output + geometry_msgs::PoseWithCovariance::_covariance_type output; + output[0] = result_11[0][0]; + output[1] = result_11[0][1]; + output[2] = result_11[0][2]; + output[6] = result_11[1][0]; + output[7] = result_11[1][1]; + output[8] = result_11[1][2]; + output[12] = result_11[2][0]; + output[13] = result_11[2][1]; + output[14] = result_11[2][2]; + + output[3] = result_12[0][0]; + output[4] = result_12[0][1]; + output[5] = result_12[0][2]; + output[9] = result_12[1][0]; + output[10] = result_12[1][1]; + output[11] = result_12[1][2]; + output[15] = result_12[2][0]; + output[16] = result_12[2][1]; + output[17] = result_12[2][2]; + + output[18] = result_21[0][0]; + output[19] = result_21[0][1]; + output[20] = result_21[0][2]; + output[24] = result_21[1][0]; + output[25] = result_21[1][1]; + output[26] = result_21[1][2]; + output[30] = result_21[2][0]; + output[31] = result_21[2][1]; + output[32] = result_21[2][2]; + + output[21] = result_22[0][0]; + output[22] = result_22[0][1]; + output[23] = result_22[0][2]; + output[27] = result_22[1][0]; + output[28] = result_22[1][1]; + output[29] = result_22[1][2]; + output[33] = result_22[2][0]; + output[34] = result_22[2][1]; + output[35] = result_22[2][2]; + + return output; +} + +/** \brief Apply a geometry_msgs TransformStamped to an geometry_msgs PoseWithCovarianceStamped type. +* This function is a specialization of the doTransform template defined in tf2/convert.h. +* \param t_in The pose to transform, as a timestamped PoseWithCovarianceStamped message. +* \param t_out The transformed pose, as a timestamped PoseWithCovarianceStamped message. +* \param transform The timestamped transform to apply, as a TransformStamped message. +*/ +template <> +inline +void doTransform(const geometry_msgs::PoseWithCovarianceStamped& t_in, geometry_msgs::PoseWithCovarianceStamped& t_out, const geometry_msgs::TransformStamped& transform) +{ + tf2::Vector3 v; + fromMsg(t_in.pose.pose.position, v); + tf2::Quaternion r; + fromMsg(t_in.pose.pose.orientation, r); + + tf2::Transform t; + fromMsg(transform.transform, t); + tf2::Transform v_out = t * tf2::Transform(r, v); + toMsg(v_out, t_out.pose.pose); + t_out.header.stamp = transform.header.stamp; + t_out.header.frame_id = transform.header.frame_id; + + t_out.pose.covariance = transformCovariance(t_in.pose.covariance, t); +} + +/** \brief Apply a geometry_msgs TransformStamped to an geometry_msgs Transform type. + * This function is a specialization of the doTransform template defined in tf2/convert.h. + * \param t_in The frame to transform, as a timestamped Transform3 message. + * \param t_out The frame transform, as a timestamped Transform3 message. + * \param transform The timestamped transform to apply, as a TransformStamped message. + */ +template <> +inline +void doTransform(const geometry_msgs::TransformStamped& t_in, geometry_msgs::TransformStamped& t_out, const geometry_msgs::TransformStamped& transform) + { + tf2::Transform input; + fromMsg(t_in.transform, input); + + tf2::Transform t; + fromMsg(transform.transform, t); + tf2::Transform v_out = t * input; + + t_out.transform = toMsg(v_out); + t_out.header.stamp = transform.header.stamp; + t_out.header.frame_id = transform.header.frame_id; + } + +/** \brief Apply a geometry_msgs TransformStamped to an geometry_msgs Vector type. + * This function is a specialization of the doTransform template defined in tf2/convert.h. + * \param t_in The vector to transform, as a Vector3 message. + * \param t_out The transformed vector, as a Vector3 message. + * \param transform The timestamped transform to apply, as a TransformStamped message. + */ +template <> +inline + void doTransform(const geometry_msgs::Vector3& t_in, geometry_msgs::Vector3& t_out, const geometry_msgs::TransformStamped& transform) + { + tf2::Transform t; + fromMsg(transform.transform, t); + tf2::Vector3 v_out = t.getBasis() * tf2::Vector3(t_in.x, t_in.y, t_in.z); + t_out.x = v_out[0]; + t_out.y = v_out[1]; + t_out.z = v_out[2]; + } + +/** \brief Apply a geometry_msgs TransformStamped to an stamped geometry_msgs Vector type. + * This function is a specialization of the doTransform template defined in tf2/convert.h. + * \param t_in The vector to transform, as a timestamped Vector3 message. + * \param t_out The transformed vector, as a timestamped Vector3 message. + * \param transform The timestamped transform to apply, as a TransformStamped message. + */ +template <> +inline + void doTransform(const geometry_msgs::Vector3Stamped& t_in, geometry_msgs::Vector3Stamped& t_out, const geometry_msgs::TransformStamped& transform) + { + doTransform(t_in.vector, t_out.vector, transform); + t_out.header.stamp = transform.header.stamp; + t_out.header.frame_id = transform.header.frame_id; + } + + +/**********************/ +/*** WrenchStamped ****/ +/**********************/ +template <> +inline +const ros::Time& getTimestamp(const geometry_msgs::WrenchStamped& t) {return t.header.stamp;} + + +template <> +inline +const std::string& getFrameId(const geometry_msgs::WrenchStamped& t) {return t.header.frame_id;} + + +inline +geometry_msgs::WrenchStamped toMsg(const geometry_msgs::WrenchStamped& in) +{ + return in; +} + +inline +void fromMsg(const geometry_msgs::WrenchStamped& msg, geometry_msgs::WrenchStamped& out) +{ + out = msg; +} + + +inline +geometry_msgs::WrenchStamped toMsg(const tf2::Stamped>& in, geometry_msgs::WrenchStamped & out) +{ + out.header.stamp = in.stamp_; + out.header.frame_id = in.frame_id_; + out.wrench.force = toMsg(in[0]); + out.wrench.torque = toMsg(in[1]); + return out; +} + + +inline +void fromMsg(const geometry_msgs::WrenchStamped& msg, tf2::Stamped>& out) +{ + out.stamp_ = msg.header.stamp; + out.frame_id_ = msg.header.frame_id; + tf2::Vector3 tmp; + fromMsg(msg.wrench.force, tmp); + tf2::Vector3 tmp1; + fromMsg(msg.wrench.torque, tmp1); + std::array tmp_array; + tmp_array[0] = tmp; + tmp_array[1] = tmp1; + out.setData(tmp_array); +} + +template<> +inline +void doTransform(const geometry_msgs::Wrench& t_in, geometry_msgs::Wrench& t_out, const geometry_msgs::TransformStamped& transform) +{ + doTransform(t_in.force, t_out.force, transform); + doTransform(t_in.torque, t_out.torque, transform); +} + + +template<> +inline +void doTransform(const geometry_msgs::WrenchStamped& t_in, geometry_msgs::WrenchStamped& t_out, const geometry_msgs::TransformStamped& transform) +{ + doTransform(t_in.wrench, t_out.wrench, transform); + t_out.header.stamp = transform.header.stamp; + t_out.header.frame_id = transform.header.frame_id; +} + +} // namespace + +#endif // TF2_GEOMETRY_MSGS_H diff --git a/navigations/geometry2/tf2_geometry_msgs/index.rst b/navigations/geometry2/tf2_geometry_msgs/index.rst new file mode 100755 index 0000000..b2cbcad --- /dev/null +++ b/navigations/geometry2/tf2_geometry_msgs/index.rst @@ -0,0 +1,17 @@ +Welcome to tf2_geometry_msgs's documentation! +============================================= + +Contents: + +.. toctree:: + :maxdepth: 2 + + + +Indices and tables +================== + +* :ref:`genindex` +* :ref:`modindex` +* :ref:`search` + diff --git a/navigations/geometry2/tf2_geometry_msgs/mainpage.dox b/navigations/geometry2/tf2_geometry_msgs/mainpage.dox new file mode 100755 index 0000000..3641532 --- /dev/null +++ b/navigations/geometry2/tf2_geometry_msgs/mainpage.dox @@ -0,0 +1,19 @@ +/** +\mainpage +\htmlinclude manifest.html + +\b tf2_geometry_msgs contains functions for converting between various geometry_msgs data types. + +This library is an implementation of the templated conversion interface specified in tf/convert.h. +It offers conversion and transform convenience functions between various geometry_msgs data types, +such as Vector, Point, Pose, Transform, Quaternion, etc. + +See the Conversions overview +wiki page for more information about datatype conversion in tf2. + +\section codeapi Code API + +This library consists of one header only, tf2_geometry_msgs/tf2_geometry_msgs.h, which consists mostly of +specializations of template functions defined in tf2/convert.h. + +*/ diff --git a/navigations/geometry2/tf2_geometry_msgs/package.xml b/navigations/geometry2/tf2_geometry_msgs/package.xml new file mode 100755 index 0000000..1cf8129 --- /dev/null +++ b/navigations/geometry2/tf2_geometry_msgs/package.xml @@ -0,0 +1,27 @@ + + tf2_geometry_msgs + 0.7.6 + + tf2_geometry_msgs + + Wim Meeussen + Tully Foote + BSD + + http://www.ros.org/wiki/tf2_ros + + catkin + + geometry_msgs + liborocos-kdl-dev + tf2 + tf2_ros + + python3-pykdl + + python3-pykdl + + ros_environment + rostest + + diff --git a/navigations/geometry2/tf2_geometry_msgs/rosdoc.yaml b/navigations/geometry2/tf2_geometry_msgs/rosdoc.yaml new file mode 100755 index 0000000..a1d78b9 --- /dev/null +++ b/navigations/geometry2/tf2_geometry_msgs/rosdoc.yaml @@ -0,0 +1,7 @@ + - builder: doxygen + name: C++ API + output_dir: c++ + file_patterns: '*.c *.cpp *.h *.cc *.hh *.dox' + - builder: sphinx + name: Python API + output_dir: python diff --git a/navigations/geometry2/tf2_geometry_msgs/scripts/test.py b/navigations/geometry2/tf2_geometry_msgs/scripts/test.py new file mode 100755 index 0000000..25555da --- /dev/null +++ b/navigations/geometry2/tf2_geometry_msgs/scripts/test.py @@ -0,0 +1,100 @@ +#!/usr/bin/env python + +import unittest +import rospy +import PyKDL +import tf2_ros +import tf2_geometry_msgs +from geometry_msgs.msg import TransformStamped, PointStamped, Vector3Stamped, PoseStamped, WrenchStamped + +class GeometryMsgs(unittest.TestCase): + def test_transform(self): + b = tf2_ros.Buffer() + t = TransformStamped() + t.transform.translation.x = 1 + t.transform.rotation.x = 1 + t.header.stamp = rospy.Time(2.0) + t.header.frame_id = 'a' + t.child_frame_id = 'b' + b.set_transform(t, 'eitan_rocks') + out = b.lookup_transform('a','b', rospy.Time(2.0), rospy.Duration(2.0)) + self.assertEqual(out.transform.translation.x, 1) + self.assertEqual(out.transform.rotation.x, 1) + self.assertEqual(out.header.frame_id, 'a') + self.assertEqual(out.child_frame_id, 'b') + + v = PointStamped() + v.header.stamp = rospy.Time(2) + v.header.frame_id = 'a' + v.point.x = 1 + v.point.y = 2 + v.point.z = 3 + out = b.transform(v, 'b') + self.assertEqual(out.point.x, 0) + self.assertEqual(out.point.y, -2) + self.assertEqual(out.point.z, -3) + + v = PoseStamped() + v.header.stamp = rospy.Time(2) + v.header.frame_id = 'a' + v.pose.position.x = 1 + v.pose.position.y = 2 + v.pose.position.z = 3 + v.pose.orientation.x = 1 + out = b.transform(v, 'b') + self.assertEqual(out.pose.position.x, 0) + self.assertEqual(out.pose.position.y, -2) + self.assertEqual(out.pose.position.z, -3) + + # Translation shouldn't affect Vector3 + t = TransformStamped() + t.transform.translation.x = 1 + t.transform.translation.y = 2 + t.transform.translation.z = 3 + t.transform.rotation.w = 1 + v = Vector3Stamped() + v.vector.x = 1 + v.vector.y = 0 + v.vector.z = 0 + out = tf2_geometry_msgs.do_transform_vector3(v, t) + self.assertEqual(out.vector.x, 1) + self.assertEqual(out.vector.y, 0) + self.assertEqual(out.vector.z, 0) + + # Rotate Vector3 180 deg about y + t = TransformStamped() + t.transform.translation.x = 1 + t.transform.translation.y = 2 + t.transform.translation.z = 3 + t.transform.rotation.y = 1 + + v = Vector3Stamped() + v.vector.x = 1 + v.vector.y = 0 + v.vector.z = 0 + + out = tf2_geometry_msgs.do_transform_vector3(v, t) + self.assertEqual(out.vector.x, -1) + self.assertEqual(out.vector.y, 0) + self.assertEqual(out.vector.z, 0) + + v = WrenchStamped() + v.wrench.force.x = 1 + v.wrench.force.y = 0 + v.wrench.force.z = 0 + v.wrench.torque.x = 1 + v.wrench.torque.y = 0 + v.wrench.torque.z = 0 + + out = tf2_geometry_msgs.do_transform_wrench(v, t) + self.assertEqual(out.wrench.force.x, -1) + self.assertEqual(out.wrench.force.y, 0) + self.assertEqual(out.wrench.force.z, 0) + self.assertEqual(out.wrench.torque.x, -1) + self.assertEqual(out.wrench.torque.y, 0) + self.assertEqual(out.wrench.torque.z, 0) + +if __name__ == '__main__': + import rosunit + rospy.init_node('test_tf2_geometry_msgs_python') + rosunit.unitrun("test_tf2_geometry_msgs", "test_tf2_geometry_msgs_python", GeometryMsgs) diff --git a/navigations/geometry2/tf2_geometry_msgs/setup.py b/navigations/geometry2/tf2_geometry_msgs/setup.py new file mode 100755 index 0000000..689f124 --- /dev/null +++ b/navigations/geometry2/tf2_geometry_msgs/setup.py @@ -0,0 +1,13 @@ +#!/usr/bin/env python + +from setuptools import setup +from catkin_pkg.python_setup import generate_distutils_setup + +d = generate_distutils_setup( + packages=['tf2_geometry_msgs'], + package_dir={'': 'src'}, + requires=['rospy','geometry_msgs','tf2_ros','orocos_kdl'] +) + +setup(**d) + diff --git a/navigations/geometry2/tf2_geometry_msgs/src/tf2_geometry_msgs/__init__.py b/navigations/geometry2/tf2_geometry_msgs/src/tf2_geometry_msgs/__init__.py new file mode 100755 index 0000000..e072bac --- /dev/null +++ b/navigations/geometry2/tf2_geometry_msgs/src/tf2_geometry_msgs/__init__.py @@ -0,0 +1 @@ +from .tf2_geometry_msgs import * diff --git a/navigations/geometry2/tf2_geometry_msgs/src/tf2_geometry_msgs/tf2_geometry_msgs.py b/navigations/geometry2/tf2_geometry_msgs/src/tf2_geometry_msgs/tf2_geometry_msgs.py new file mode 100755 index 0000000..f0edee2 --- /dev/null +++ b/navigations/geometry2/tf2_geometry_msgs/src/tf2_geometry_msgs/tf2_geometry_msgs.py @@ -0,0 +1,110 @@ +# Copyright (c) 2008, Willow Garage, Inc. +# All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# * Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in the +# documentation and/or other materials provided with the distribution. +# * Neither the name of the Willow Garage, Inc. nor the names of its +# contributors may be used to endorse or promote products derived from +# this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. + +# author: Wim Meeussen + +from geometry_msgs.msg import PoseStamped, Vector3Stamped, PointStamped, WrenchStamped +import PyKDL +import rospy +import tf2_ros +import copy + +def to_msg_msg(msg): + return msg + +tf2_ros.ConvertRegistration().add_to_msg(Vector3Stamped, to_msg_msg) +tf2_ros.ConvertRegistration().add_to_msg(PoseStamped, to_msg_msg) +tf2_ros.ConvertRegistration().add_to_msg(PointStamped, to_msg_msg) + +def from_msg_msg(msg): + return msg + +tf2_ros.ConvertRegistration().add_from_msg(Vector3Stamped, from_msg_msg) +tf2_ros.ConvertRegistration().add_from_msg(PoseStamped, from_msg_msg) +tf2_ros.ConvertRegistration().add_from_msg(PointStamped, from_msg_msg) + +def transform_to_kdl(t): + return PyKDL.Frame(PyKDL.Rotation.Quaternion(t.transform.rotation.x, t.transform.rotation.y, + t.transform.rotation.z, t.transform.rotation.w), + PyKDL.Vector(t.transform.translation.x, + t.transform.translation.y, + t.transform.translation.z)) + + +# PointStamped +def do_transform_point(point, transform): + p = transform_to_kdl(transform) * PyKDL.Vector(point.point.x, point.point.y, point.point.z) + res = PointStamped() + res.point.x = p[0] + res.point.y = p[1] + res.point.z = p[2] + res.header = transform.header + return res +tf2_ros.TransformRegistration().add(PointStamped, do_transform_point) + + +# Vector3Stamped +def do_transform_vector3(vector3, transform): + transform = copy.deepcopy(transform) + transform.transform.translation.x = 0; + transform.transform.translation.y = 0; + transform.transform.translation.z = 0; + p = transform_to_kdl(transform) * PyKDL.Vector(vector3.vector.x, vector3.vector.y, vector3.vector.z) + res = Vector3Stamped() + res.vector.x = p[0] + res.vector.y = p[1] + res.vector.z = p[2] + res.header = transform.header + return res +tf2_ros.TransformRegistration().add(Vector3Stamped, do_transform_vector3) + +# PoseStamped +def do_transform_pose(pose, transform): + f = transform_to_kdl(transform) * PyKDL.Frame(PyKDL.Rotation.Quaternion(pose.pose.orientation.x, pose.pose.orientation.y, + pose.pose.orientation.z, pose.pose.orientation.w), + PyKDL.Vector(pose.pose.position.x, pose.pose.position.y, pose.pose.position.z)) + res = PoseStamped() + res.pose.position.x = f[(0, 3)] + res.pose.position.y = f[(1, 3)] + res.pose.position.z = f[(2, 3)] + (res.pose.orientation.x, res.pose.orientation.y, res.pose.orientation.z, res.pose.orientation.w) = f.M.GetQuaternion() + res.header = transform.header + return res +tf2_ros.TransformRegistration().add(PoseStamped, do_transform_pose) + +# WrenchStamped +def do_transform_wrench(wrench, transform): + force = Vector3Stamped() + torque = Vector3Stamped() + force.vector = wrench.wrench.force + torque.vector = wrench.wrench.torque + res = WrenchStamped() + res.wrench.force = do_transform_vector3(force, transform).vector + res.wrench.torque = do_transform_vector3(torque, transform).vector + res.header = transform.header + return res +tf2_ros.TransformRegistration().add(WrenchStamped, do_transform_wrench) diff --git a/navigations/geometry2/tf2_geometry_msgs/test/test.launch b/navigations/geometry2/tf2_geometry_msgs/test/test.launch new file mode 100755 index 0000000..53bab78 --- /dev/null +++ b/navigations/geometry2/tf2_geometry_msgs/test/test.launch @@ -0,0 +1,3 @@ + + + \ No newline at end of file diff --git a/navigations/geometry2/tf2_geometry_msgs/test/test_python.launch b/navigations/geometry2/tf2_geometry_msgs/test/test_python.launch new file mode 100755 index 0000000..b6bc793 --- /dev/null +++ b/navigations/geometry2/tf2_geometry_msgs/test/test_python.launch @@ -0,0 +1,3 @@ + + + diff --git a/navigations/geometry2/tf2_geometry_msgs/test/test_tf2_geometry_msgs.cpp b/navigations/geometry2/tf2_geometry_msgs/test/test_tf2_geometry_msgs.cpp new file mode 100755 index 0000000..860db53 --- /dev/null +++ b/navigations/geometry2/tf2_geometry_msgs/test/test_tf2_geometry_msgs.cpp @@ -0,0 +1,380 @@ +/* + * Copyright (c) 2008, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +/** \author Wim Meeussen */ + + +#include +#include +#include +#include +#include +#include + +tf2_ros::Buffer* tf_buffer; +geometry_msgs::TransformStamped t; +static const double EPS = 1e-3; + + +TEST(TfGeometry, Frame) +{ + geometry_msgs::PoseStamped v1; + v1.pose.position.x = 1; + v1.pose.position.y = 2; + v1.pose.position.z = 3; + v1.pose.orientation.x = 1; + v1.header.stamp = ros::Time(2); + v1.header.frame_id = "A"; + + // simple api + geometry_msgs::PoseStamped v_simple = tf_buffer->transform(v1, "B", ros::Duration(2.0)); + EXPECT_NEAR(v_simple.pose.position.x, -9, EPS); + EXPECT_NEAR(v_simple.pose.position.y, 18, EPS); + EXPECT_NEAR(v_simple.pose.position.z, 27, EPS); + EXPECT_NEAR(v_simple.pose.orientation.x, 0.0, EPS); + EXPECT_NEAR(v_simple.pose.orientation.y, 0.0, EPS); + EXPECT_NEAR(v_simple.pose.orientation.z, 0.0, EPS); + EXPECT_NEAR(v_simple.pose.orientation.w, 1.0, EPS); + + // advanced api + geometry_msgs::PoseStamped v_advanced = tf_buffer->transform(v1, "B", ros::Time(2.0), + "A", ros::Duration(3.0)); + EXPECT_NEAR(v_advanced.pose.position.x, -9, EPS); + EXPECT_NEAR(v_advanced.pose.position.y, 18, EPS); + EXPECT_NEAR(v_advanced.pose.position.z, 27, EPS); + EXPECT_NEAR(v_advanced.pose.orientation.x, 0.0, EPS); + EXPECT_NEAR(v_advanced.pose.orientation.y, 0.0, EPS); + EXPECT_NEAR(v_advanced.pose.orientation.z, 0.0, EPS); + EXPECT_NEAR(v_advanced.pose.orientation.w, 1.0, EPS); +} + +TEST(TfGeometry, PoseWithCovarianceStamped) +{ + geometry_msgs::PoseWithCovarianceStamped v1; + v1.pose.pose.position.x = 1; + v1.pose.pose.position.y = 2; + v1.pose.pose.position.z = 3; + v1.pose.pose.orientation.x = 1; + v1.header.stamp = ros::Time(2); + v1.header.frame_id = "A"; + v1.pose.covariance[0] = 1; + v1.pose.covariance[7] = 1; + v1.pose.covariance[14] = 1; + v1.pose.covariance[21] = 1; + v1.pose.covariance[28] = 1; + v1.pose.covariance[35] = 1; + + // simple api + const geometry_msgs::PoseWithCovarianceStamped v_simple = tf_buffer->transform(v1, "B", ros::Duration(2.0)); + EXPECT_NEAR(v_simple.pose.pose.position.x, -9, EPS); + EXPECT_NEAR(v_simple.pose.pose.position.y, 18, EPS); + EXPECT_NEAR(v_simple.pose.pose.position.z, 27, EPS); + EXPECT_NEAR(v_simple.pose.pose.orientation.x, 0.0, EPS); + EXPECT_NEAR(v_simple.pose.pose.orientation.y, 0.0, EPS); + EXPECT_NEAR(v_simple.pose.pose.orientation.z, 0.0, EPS); + EXPECT_NEAR(v_simple.pose.pose.orientation.w, 1.0, EPS); + + // no rotation in this transformation, so no change to covariance + EXPECT_NEAR(v_simple.pose.covariance[0], 1.0, EPS); + EXPECT_NEAR(v_simple.pose.covariance[7], 1.0, EPS); + EXPECT_NEAR(v_simple.pose.covariance[14], 1.0, EPS); + EXPECT_NEAR(v_simple.pose.covariance[21], 1.0, EPS); + EXPECT_NEAR(v_simple.pose.covariance[28], 1.0, EPS); + EXPECT_NEAR(v_simple.pose.covariance[35], 1.0, EPS); + + // advanced api + const geometry_msgs::PoseWithCovarianceStamped v_advanced = tf_buffer->transform(v1, "B", ros::Time(2.0), + "A", ros::Duration(3.0)); + EXPECT_NEAR(v_advanced.pose.pose.position.x, -9, EPS); + EXPECT_NEAR(v_advanced.pose.pose.position.y, 18, EPS); + EXPECT_NEAR(v_advanced.pose.pose.position.z, 27, EPS); + EXPECT_NEAR(v_advanced.pose.pose.orientation.x, 0.0, EPS); + EXPECT_NEAR(v_advanced.pose.pose.orientation.y, 0.0, EPS); + EXPECT_NEAR(v_advanced.pose.pose.orientation.z, 0.0, EPS); + EXPECT_NEAR(v_advanced.pose.pose.orientation.w, 1.0, EPS); + + // no rotation in this transformation, so no change to covariance + EXPECT_NEAR(v_advanced.pose.covariance[0], 1.0, EPS); + EXPECT_NEAR(v_advanced.pose.covariance[7], 1.0, EPS); + EXPECT_NEAR(v_advanced.pose.covariance[14], 1.0, EPS); + EXPECT_NEAR(v_advanced.pose.covariance[21], 1.0, EPS); + EXPECT_NEAR(v_advanced.pose.covariance[28], 1.0, EPS); + EXPECT_NEAR(v_advanced.pose.covariance[35], 1.0, EPS); + + /** now add rotation to transform to test the effect on covariance **/ + + // rotate pi/2 radians about x-axis + geometry_msgs::TransformStamped t_rot; + t_rot.transform.rotation = tf2::toMsg(tf2::Quaternion(tf2::Vector3(1,0,0), M_PI/2)); + t_rot.header.stamp = ros::Time(2.0); + t_rot.header.frame_id = "A"; + t_rot.child_frame_id = "rotated"; + tf_buffer->setTransform(t_rot, "rotation_test"); + + // need to put some covariance in the matrix + v1.pose.covariance[1] = 1; + v1.pose.covariance[6] = 1; + v1.pose.covariance[12] = 1; + + // perform rotation + const geometry_msgs::PoseWithCovarianceStamped v_rotated = tf_buffer->transform(v1, "rotated", ros::Duration(2.0)); + + // the covariance matrix should now be transformed + EXPECT_NEAR(v_rotated.pose.covariance[0], 1.0, EPS); + EXPECT_NEAR(v_rotated.pose.covariance[1], 0.0, EPS); + EXPECT_NEAR(v_rotated.pose.covariance[2],-1.0, EPS); + EXPECT_NEAR(v_rotated.pose.covariance[6], 1.0, EPS); + EXPECT_NEAR(v_rotated.pose.covariance[7], 1.0, EPS); + EXPECT_NEAR(v_rotated.pose.covariance[8], 0.0, EPS); + EXPECT_NEAR(v_rotated.pose.covariance[12],-1.0, EPS); + EXPECT_NEAR(v_rotated.pose.covariance[13], 0.0, EPS); + EXPECT_NEAR(v_rotated.pose.covariance[14], 1.0, EPS); + + // set buffer back to original transform + tf_buffer->setTransform(t, "test"); +} + +TEST(TfGeometry, Transform) +{ + geometry_msgs::TransformStamped v1; + v1.transform.translation.x = 1; + v1.transform.translation.y = 2; + v1.transform.translation.z = 3; + v1.transform.rotation.x = 1; + v1.header.stamp = ros::Time(2); + v1.header.frame_id = "A"; + + // simple api + geometry_msgs::TransformStamped v_simple = tf_buffer->transform(v1, "B", ros::Duration(2.0)); + EXPECT_NEAR(v_simple.transform.translation.x, -9, EPS); + EXPECT_NEAR(v_simple.transform.translation.y, 18, EPS); + EXPECT_NEAR(v_simple.transform.translation.z, 27, EPS); + EXPECT_NEAR(v_simple.transform.rotation.x, 0.0, EPS); + EXPECT_NEAR(v_simple.transform.rotation.y, 0.0, EPS); + EXPECT_NEAR(v_simple.transform.rotation.z, 0.0, EPS); + EXPECT_NEAR(v_simple.transform.rotation.w, 1.0, EPS); + + + // advanced api + geometry_msgs::TransformStamped v_advanced = tf_buffer->transform(v1, "B", ros::Time(2.0), + "A", ros::Duration(3.0)); + EXPECT_NEAR(v_advanced.transform.translation.x, -9, EPS); + EXPECT_NEAR(v_advanced.transform.translation.y, 18, EPS); + EXPECT_NEAR(v_advanced.transform.translation.z, 27, EPS); + EXPECT_NEAR(v_advanced.transform.rotation.x, 0.0, EPS); + EXPECT_NEAR(v_advanced.transform.rotation.y, 0.0, EPS); + EXPECT_NEAR(v_advanced.transform.rotation.z, 0.0, EPS); + EXPECT_NEAR(v_advanced.transform.rotation.w, 1.0, EPS); +} + +TEST(TfGeometry, Vector) +{ + geometry_msgs::Vector3Stamped v1, res; + v1.vector.x = 1; + v1.vector.y = 2; + v1.vector.z = 3; + v1.header.stamp = ros::Time(2.0); + v1.header.frame_id = "A"; + + // simple api + geometry_msgs::Vector3Stamped v_simple = tf_buffer->transform(v1, "B", ros::Duration(2.0)); + EXPECT_NEAR(v_simple.vector.x, 1, EPS); + EXPECT_NEAR(v_simple.vector.y, -2, EPS); + EXPECT_NEAR(v_simple.vector.z, -3, EPS); + + // advanced api + geometry_msgs::Vector3Stamped v_advanced = tf_buffer->transform(v1, "B", ros::Time(2.0), + "A", ros::Duration(3.0)); + EXPECT_NEAR(v_advanced.vector.x, 1, EPS); + EXPECT_NEAR(v_advanced.vector.y, -2, EPS); + EXPECT_NEAR(v_advanced.vector.z, -3, EPS); +} + + +TEST(TfGeometry, Point) +{ + geometry_msgs::PointStamped v1, res; + v1.point.x = 1; + v1.point.y = 2; + v1.point.z = 3; + v1.header.stamp = ros::Time(2.0); + v1.header.frame_id = "A"; + + // simple api + geometry_msgs::PointStamped v_simple = tf_buffer->transform(v1, "B", ros::Duration(2.0)); + EXPECT_NEAR(v_simple.point.x, -9, EPS); + EXPECT_NEAR(v_simple.point.y, 18, EPS); + EXPECT_NEAR(v_simple.point.z, 27, EPS); + + // advanced api + geometry_msgs::PointStamped v_advanced = tf_buffer->transform(v1, "B", ros::Time(2.0), + "A", ros::Duration(3.0)); + EXPECT_NEAR(v_advanced.point.x, -9, EPS); + EXPECT_NEAR(v_advanced.point.y, 18, EPS); + EXPECT_NEAR(v_advanced.point.z, 27, EPS); +} + +TEST(TfGeometry, doTransformPoint) +{ + geometry_msgs::Point v1, res; + v1.x = 2; + v1.y = 1; + v1.z = 3; + + geometry_msgs::TransformStamped trafo; + trafo.transform.translation.x = -1; + trafo.transform.translation.y = 2; + trafo.transform.translation.z = -3; + trafo.transform.rotation = tf2::toMsg(tf2::Quaternion(tf2::Vector3(0,0,1), -M_PI / 2.0)); + + tf2::doTransform(v1, res, trafo); + + EXPECT_NEAR(res.x, 0, EPS); + EXPECT_NEAR(res.y, 0, EPS); + EXPECT_NEAR(res.z, 0, EPS); +} + +TEST(TfGeometry, doTransformQuaterion) +{ + geometry_msgs::Quaternion v1, res; + v1.w = 1; + + geometry_msgs::TransformStamped trafo; + trafo.transform.translation.x = -1; + trafo.transform.translation.y = 2; + trafo.transform.translation.z = -3; + trafo.transform.rotation = tf2::toMsg(tf2::Quaternion(tf2::Vector3(0,0,1), -M_PI / 2.0)); + + tf2::doTransform(v1, res, trafo); + + EXPECT_NEAR(res.x, trafo.transform.rotation.x, EPS); + EXPECT_NEAR(res.y, trafo.transform.rotation.y, EPS); + EXPECT_NEAR(res.z, trafo.transform.rotation.z, EPS); + EXPECT_NEAR(res.w, trafo.transform.rotation.w, EPS); +} + +TEST(TfGeometry, doTransformPose) +{ + geometry_msgs::Pose v1, res; + v1.position.x = 2; + v1.position.y = 1; + v1.position.z = 3; + v1.orientation.w = 1; + + geometry_msgs::TransformStamped trafo; + trafo.transform.translation.x = -1; + trafo.transform.translation.y = 2; + trafo.transform.translation.z = -3; + trafo.transform.rotation = tf2::toMsg(tf2::Quaternion(tf2::Vector3(0,0,1), -M_PI / 2.0)); + + tf2::doTransform(v1, res, trafo); + + EXPECT_NEAR(res.position.x, 0, EPS); + EXPECT_NEAR(res.position.y, 0, EPS); + EXPECT_NEAR(res.position.z, 0, EPS); + + EXPECT_NEAR(res.orientation.x, trafo.transform.rotation.x, EPS); + EXPECT_NEAR(res.orientation.y, trafo.transform.rotation.y, EPS); + EXPECT_NEAR(res.orientation.z, trafo.transform.rotation.z, EPS); + EXPECT_NEAR(res.orientation.w, trafo.transform.rotation.w, EPS); +} + +TEST(TfGeometry, doTransformVector3) +{ + geometry_msgs::Vector3 v1, res; + v1.x = 2; + v1.y = 1; + v1.z = 3; + + geometry_msgs::TransformStamped trafo; + trafo.transform.translation.x = -1; + trafo.transform.translation.y = 2; + trafo.transform.translation.z = -3; + trafo.transform.rotation = tf2::toMsg(tf2::Quaternion(tf2::Vector3(0,0,1), -M_PI / 2.0)); + + tf2::doTransform(v1, res, trafo); + + EXPECT_NEAR(res.x, 1, EPS); + EXPECT_NEAR(res.y, -2, EPS); + EXPECT_NEAR(res.z, 3, EPS); +} + +TEST(TfGeometry, doTransformWrench) +{ + geometry_msgs::Wrench v1, res; + v1.force.x = 2; + v1.force.y = 1; + v1.force.z = 3; + v1.torque.x = 2; + v1.torque.y = 1; + v1.torque.z = 3; + + geometry_msgs::TransformStamped trafo; + trafo.transform.translation.x = -1; + trafo.transform.translation.y = 2; + trafo.transform.translation.z = -3; + trafo.transform.rotation = tf2::toMsg(tf2::Quaternion(tf2::Vector3(0,0,1), -M_PI / 2.0)); + + tf2::doTransform(v1, res, trafo); + EXPECT_NEAR(res.force.x, 1, EPS); + EXPECT_NEAR(res.force.y, -2, EPS); + EXPECT_NEAR(res.force.z, 3, EPS); + + EXPECT_NEAR(res.torque.x, 1, EPS); + EXPECT_NEAR(res.torque.y, -2, EPS); + EXPECT_NEAR(res.torque.z, 3, EPS); +} + +int main(int argc, char **argv){ + testing::InitGoogleTest(&argc, argv); + ros::init(argc, argv, "test"); + ros::NodeHandle n; + + tf_buffer = new tf2_ros::Buffer(); + tf_buffer->setUsingDedicatedThread(true); + + // populate buffer + t.transform.translation.x = 10; + t.transform.translation.y = 20; + t.transform.translation.z = 30; + t.transform.rotation.x = 1; + t.header.stamp = ros::Time(2.0); + t.header.frame_id = "A"; + t.child_frame_id = "B"; + tf_buffer->setTransform(t, "test"); + + int ret = RUN_ALL_TESTS(); + delete tf_buffer; + return ret; +} + + + + + diff --git a/navigations/geometry2/tf2_geometry_msgs/test/test_tomsg_frommsg.cpp b/navigations/geometry2/tf2_geometry_msgs/test/test_tomsg_frommsg.cpp new file mode 100755 index 0000000..3139f23 --- /dev/null +++ b/navigations/geometry2/tf2_geometry_msgs/test/test_tomsg_frommsg.cpp @@ -0,0 +1,405 @@ +/* + * Copyright (c) 2008, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +/** \author Wim Meeussen */ + + +#include +#include + +static const double EPS = 1e-6; + +tf2::Vector3 get_tf2_vector() +{ + return tf2::Vector3(1.0, 2.0, 3.0); +} + +geometry_msgs::Vector3& value_initialize(geometry_msgs::Vector3 &m1) +{ + m1.x = 1; + m1.y = 2; + m1.z = 3; + return m1; +} + +std_msgs::Header& value_initialize(std_msgs::Header & h) +{ + h.stamp = ros::Time(10); + h.frame_id = "foobar"; + return h; +} + +geometry_msgs::Vector3Stamped& value_initialize(geometry_msgs::Vector3Stamped &m1) +{ + value_initialize(m1.header); + value_initialize(m1.vector); + return m1; +} + +geometry_msgs::Point& value_initialize(geometry_msgs::Point &m1) +{ + m1.x = 1; + m1.y = 2; + m1.z = 3; + return m1; +} + +geometry_msgs::PointStamped& value_initialize(geometry_msgs::PointStamped &m1) +{ + value_initialize(m1.header); + value_initialize(m1.point); + return m1; +} + +geometry_msgs::Quaternion & value_initialize(geometry_msgs::Quaternion &m1) +{ + m1.x = 0; + m1.y = 0; + m1.z = 0.7071067811; + m1.w = 0.7071067811; + return m1; +} + +geometry_msgs::QuaternionStamped& value_initialize(geometry_msgs::QuaternionStamped &m1) +{ + value_initialize(m1.header); + value_initialize(m1.quaternion); + return m1; +} + +geometry_msgs::Pose & value_initialize(geometry_msgs::Pose & m1) +{ + value_initialize(m1.position); + value_initialize(m1.orientation); + return m1; +} + +geometry_msgs::PoseStamped& value_initialize(geometry_msgs::PoseStamped &m1) +{ + value_initialize(m1.header); + value_initialize(m1.pose); + return m1; +} + +geometry_msgs::Transform & value_initialize(geometry_msgs::Transform & m1) +{ + value_initialize(m1.translation); + value_initialize(m1.rotation); + return m1; +} + +geometry_msgs::TransformStamped& value_initialize(geometry_msgs::TransformStamped &m1) +{ + value_initialize(m1.header); + value_initialize(m1.transform); + return m1; +} + +void expect_near(const std_msgs::Header & h1, const std_msgs::Header & h2) +{ + EXPECT_NEAR(h1.stamp.toSec(), h2.stamp.toSec(), EPS); + EXPECT_STREQ(h1.frame_id.c_str(), h2.frame_id.c_str()); +} + +/* + * Vector3 + */ +void expect_near(const geometry_msgs::Vector3 & v1, const tf2::Vector3 & v2) +{ + EXPECT_NEAR(v1.x, v2.x(), EPS); + EXPECT_NEAR(v1.y, v2.y(), EPS); + EXPECT_NEAR(v1.z, v2.z(), EPS); +} + +void expect_near(const geometry_msgs::Vector3 & v1, const geometry_msgs::Vector3 & v2) +{ + EXPECT_NEAR(v1.x, v2.x, EPS); + EXPECT_NEAR(v1.y, v2.y, EPS); + EXPECT_NEAR(v1.z, v2.z, EPS); +} + +void expect_near(const tf2::Vector3 & v1, const tf2::Vector3 & v2) +{ + EXPECT_NEAR(v1.x(), v2.x(), EPS); + EXPECT_NEAR(v1.y(), v2.y(), EPS); + EXPECT_NEAR(v1.z(), v2.z(), EPS); +} + +void expect_near(const geometry_msgs::Vector3Stamped & p1, const geometry_msgs::Vector3Stamped & p2) +{ + expect_near(p1.header, p2.header); + expect_near(p1.vector, p2.vector); +} + +/* + * Point + */ +void expect_near(const geometry_msgs::Point & p1, const tf2::Vector3 & v2) +{ + EXPECT_NEAR(p1.x, v2.x(), EPS); + EXPECT_NEAR(p1.y, v2.y(), EPS); + EXPECT_NEAR(p1.z, v2.z(), EPS); +} + +void expect_near(const geometry_msgs::Point & p1, const geometry_msgs::Point & v2) +{ + EXPECT_NEAR(p1.x, v2.x, EPS); + EXPECT_NEAR(p1.y, v2.y, EPS); + EXPECT_NEAR(p1.z, v2.z, EPS); +} + +void expect_near(const geometry_msgs::PointStamped & p1, const geometry_msgs::PointStamped & p2) +{ + expect_near(p1.header, p2.header); + expect_near(p1.point, p2.point); +} + + +/* + * Quaternion + */ +void expect_near(const geometry_msgs::Quaternion & q1, const tf2::Quaternion & v2) +{ + EXPECT_NEAR(q1.x, v2.x(), EPS); + EXPECT_NEAR(q1.y, v2.y(), EPS); + EXPECT_NEAR(q1.z, v2.z(), EPS); +} + +void expect_near(const geometry_msgs::Quaternion & q1, const geometry_msgs::Quaternion & v2) +{ + EXPECT_NEAR(q1.x, v2.x, EPS); + EXPECT_NEAR(q1.y, v2.y, EPS); + EXPECT_NEAR(q1.z, v2.z, EPS); +} + +void expect_near(const geometry_msgs::QuaternionStamped & p1, const geometry_msgs::QuaternionStamped & p2) +{ + expect_near(p1.header, p2.header); + expect_near(p1.quaternion, p2.quaternion); +} + +/* + * Pose + */ +void expect_near(const geometry_msgs::Pose & p, const tf2::Transform & t) +{ + expect_near(p.position, t.getOrigin()); + expect_near(p.orientation, t.getRotation()); +} + +void expect_near(const geometry_msgs::Pose & p1, const geometry_msgs::Pose & p2) +{ + expect_near(p1.position, p2.position); + expect_near(p1.orientation, p2.orientation); +} + +void expect_near(const geometry_msgs::PoseStamped & p1, const geometry_msgs::PoseStamped & p2) +{ + expect_near(p1.header, p2.header); + expect_near(p1.pose, p2.pose); +} + +/* + * Transform + */ +void expect_near(const geometry_msgs::Transform & p, const tf2::Transform & t) +{ + expect_near(p.translation, t.getOrigin()); + expect_near(p.rotation, t.getRotation()); +} + +void expect_near(const geometry_msgs::Transform & p1, const geometry_msgs::Transform & p2) +{ + expect_near(p1.translation, p2.translation); + expect_near(p1.rotation, p2.rotation); +} + +void expect_near(const geometry_msgs::TransformStamped & p1, const geometry_msgs::TransformStamped & p2) +{ + expect_near(p1.header, p2.header); + expect_near(p1.transform, p2.transform); +} + +/* + * Stamped templated expect_near + */ + +template +void expect_near(const tf2::Stamped& s1, const tf2::Stamped& s2) +{ + expect_near((T)s1, (T)s2); +} + +/********************* + * Tests + *********************/ + +TEST(tf2_geometry_msgs, Vector3) +{ + geometry_msgs::Vector3 m1; + value_initialize(m1); + tf2::Vector3 v1; + fromMsg(m1, v1); + SCOPED_TRACE("m1 v1"); + expect_near(m1, v1); + geometry_msgs::Vector3 m2 = toMsg(v1); + SCOPED_TRACE("m1 m2"); + expect_near(m1, m2); +} + +TEST(tf2_geometry_msgs, Point) +{ + geometry_msgs::Point m1; + value_initialize(m1); + tf2::Vector3 v1; + SCOPED_TRACE("m1 v1"); + fromMsg(m1, v1); + expect_near(m1, v1); + geometry_msgs::Point m2 = toMsg(v1, m2); + SCOPED_TRACE("m1 m2"); + expect_near(m1, m2); +} + +TEST(tf2_geometry_msgs, Quaternion) +{ + geometry_msgs::Quaternion m1; + value_initialize(m1); + tf2::Quaternion q1; + SCOPED_TRACE("m1 q1"); + fromMsg(m1, q1); + expect_near(m1, q1); + geometry_msgs::Quaternion m2 = toMsg(q1); + SCOPED_TRACE("m1 m2"); + expect_near(m1, m2); +} + +TEST(tf2_geometry_msgs, Pose) +{ + geometry_msgs::Pose m1; + value_initialize(m1); + tf2::Transform t1; + fromMsg(m1, t1); + SCOPED_TRACE("m1 t1"); + expect_near(m1, t1); + geometry_msgs::Pose m2 = toMsg(t1, m2); + SCOPED_TRACE("m1 m2"); + expect_near(m1, m2); +} + +TEST(tf2_geometry_msgs, Transform) +{ + geometry_msgs::Transform m1; + value_initialize(m1); + tf2::Transform t1; + fromMsg(m1, t1); + SCOPED_TRACE("m1 t1"); + expect_near(m1, t1); + geometry_msgs::Transform m2 = toMsg(t1); + SCOPED_TRACE("m1 m2"); + expect_near(m1, m2); +} + +TEST(tf2_geometry_msgs, Vector3Stamped) +{ + geometry_msgs::Vector3Stamped m1; + value_initialize(m1); + tf2::Stamped v1; + fromMsg(m1, v1); + SCOPED_TRACE("m1 v1"); + // expect_near(m1, v1); + geometry_msgs::Vector3Stamped m2; + m2 = toMsg(v1); + SCOPED_TRACE("m1 m2"); + expect_near(m1, m2); +} + +TEST(tf2_geometry_msgs, PointStamped) +{ + geometry_msgs::PointStamped m1; + value_initialize(m1); + tf2::Stamped v1; + fromMsg(m1, v1); + SCOPED_TRACE("m1 v1"); + // expect_near(m1, v1); //TODO implement cross verification explicityly + geometry_msgs::PointStamped m2; + m2 = toMsg(v1, m2); + SCOPED_TRACE("m1 m2"); + expect_near(m1, m2); +} + +TEST(tf2_geometry_msgs, QuaternionStamped) +{ + geometry_msgs::QuaternionStamped m1; + value_initialize(m1); + tf2::Stamped v1; + fromMsg(m1, v1); + SCOPED_TRACE("m1 v1"); + // expect_near(m1, v1); //TODO implement cross verification explicityly + geometry_msgs::QuaternionStamped m2; + m2 = tf2::toMsg(v1); + SCOPED_TRACE("m1 m2"); + expect_near(m1, m2); +} + +TEST(tf2_geometry_msgs, PoseStamped) +{ + geometry_msgs::PoseStamped m1; + value_initialize(m1); + tf2::Stamped v1; + SCOPED_TRACE("m1 v1"); + fromMsg(m1, v1); + // expect_near(m1, v1); //TODO implement cross verification explicityly + geometry_msgs::PoseStamped m2; + m2 = tf2::toMsg(v1, m2); + SCOPED_TRACE("m1 m2"); + expect_near(m1, m2); +} + +TEST(tf2_geometry_msgs, TransformStamped) +{ + geometry_msgs::TransformStamped m1; + value_initialize(m1); + tf2::Stamped v1; + fromMsg(m1, v1); + SCOPED_TRACE("m1 v1"); + // expect_near(m1, v1); + geometry_msgs::TransformStamped m2; + m2 = tf2::toMsg(v1); + SCOPED_TRACE("m1 m2"); + expect_near(m1, m2); +} + + + + +int main(int argc, char **argv){ + testing::InitGoogleTest(&argc, argv); + int ret = RUN_ALL_TESTS(); + return ret; +} diff --git a/navigations/geometry2/tf2_ros/CHANGELOG.rst b/navigations/geometry2/tf2_ros/CHANGELOG.rst new file mode 100755 index 0000000..b8c476f --- /dev/null +++ b/navigations/geometry2/tf2_ros/CHANGELOG.rst @@ -0,0 +1,371 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package tf2_ros +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +0.7.6 (2022-10-11) +------------------ +* tf2_ros polling interval proportional to timeout (`#492 `_) + * polling interval proportional to timeout + * CAN_TRANSFORM_POLLING_SCALE as global + * add DEFAULT_CAN_TRANSFORM_POLLING_SCALE +* Removed print statements from buffer interface (`#530 `_) +* Switch to new boost/bind/bind.hpp (`#528 `_) +* Updating the documentation to reflect current constructor for a MessageFilter (`#527 `_) +* (tf2_ros) Docs working on python 3 (`#521 `_) +* Mitigate flakey test in tf2_ros (`#490 `_) +* Contributors: Atsushi Watanabe, Janno Lunenburg, Jochen Sprickerhof, Matthijs van der Burgh, Shih-Wei Guo, Tassos Natsakis + +0.7.5 (2020-09-01) +------------------ + +0.7.4 (2020-09-01) +------------------ + +0.7.3 (2020-08-25) +------------------ +* Use correct frame service name in docstrings. (`#476 `_) + Replaces the deprecated names + {tf_frames, view_frames} -> tf2_frames +* Cherry-picking various commits from Melodic (`#471 `_) + * Revert "rework Eigen functions namespace hack" (`#436 `_) + * Fixed warnings in message_filter.h (`#434 `_) + the variables are not used in function body and caused -Wunused-parameter to trigger with -Wall + * Fix ambiguous call for tf2::convert on MSVC (`#444 `_) + * rework ambiguous call on MSVC. +* Contributors: Michael Grupp, Robert Haschke + +0.7.2 (2020-06-08) +------------------ + +0.7.1 (2020-05-13) +------------------ +* StatisTransformBroadcaster: simplify/modernize code +* [noetic] cherry-pick Windows fixes from melodic-devel (`#450 `_) + * [Windows][melodic-devel] Fix install locations (`#442 `_) + * fixed install locations of tf2 + * [windows][melodic] more portable fixes. (`#443 `_) + * more portable fixes. +* import setup from setuptools instead of distutils-core (`#449 `_) +* Contributors: Alejandro Hernández Cordero, Robert Haschke, Sean Yen + +0.7.0 (2020-03-09) +------------------ +* Bump CMake version to avoid CMP0048 warning (`#445 `_) +* Add arguments to TransformListener constructors that accept TransportHints for the tf topic subscriber (`#438 `_) +* Merge pull request `#404 `_ from otamachan/remove-load-manifest + Remove roslib.load_manifest +* Merge pull request `#402 `_ from rhaschke/fix-message-filter + Fix message filter +* resolve virtual function call in destructor +* remove pending callbacks in clear() +* Merge pull request `#372 `_ from lucasw/patch-1 + spelling fix: seperate -> separate +* Merge pull request `#369 `_ from magazino/fix-dangling-reference +* Fix dangling iterator references in buffer_server.cpp +* Remove some useless code from buffer_server_main.cpp (`#368 `_) +* Mark check_frequency as deprecated in docstring. +* Follow `#337 `_: use actionlib API in BufferClient::processGoal() +* Test for equality to None with 'is' instead of '==' (`#355 `_) +* added parameter to advertise tf2-frames as a service, if needed +* Contributors: Daniel Ingram, Emre Sahin, JonasTietz, Lucas Walter, Michael Grupp, Robert Haschke, Shane Loretz, Tamaki Nishino, Tully Foote, toliver + +0.6.5 (2018-11-16) +------------------ +* Protect the time reset logic from a race condition. + Fixes `#341 `_ + This could incorrectly trigger a buffer clear if two concurrent callbacks were invoked. +* Contributors: Tully Foote + +0.6.4 (2018-11-06) +------------------ +* fix(buffer-client): Use actionlib api for obtaining result + Use the API provided by actionlib for waiting for result. This will improve the response time and prevent problems with custom solutions (see `#178 `_). This change makes constructor parameter check_frequency obsolute and deprecates it. +* Add check to buffer_client.py to make sure result is available + Related issue: `#178 `_ +* Add check to reset buffer when rostime goes backwards +* Fixed the value of expected_success_count\_ +* Added a tf2_ros message filter unittest with multiple target frames and non-zero time tolerance +* Contributors: Ewoud Pool, Jørgen Borgesen, Stephen Williams + +0.6.3 (2018-07-09) +------------------ + +0.6.2 (2018-05-02) +------------------ +* update buffer_server_name (`#296 `_) + * use nodename as namespace + * Update `#209 `_ to provide backwards compatibility. +* Contributors: Jihoon Lee, Tully Foote + +0.6.1 (2018-03-21) +------------------ + +0.6.0 (2018-03-21) +------------------ +* tf2_ros::Buffer: canTransform can now deal with timeouts smaller than 10ms by using the hunderdth of the timeout for sleeping (`#286 `_) +* More spinning to make sure the message gets through for `#129 `_ `#283 `_ +* Contributors: Tully Foote, cwecht + +0.5.17 (2018-01-01) +------------------- +* Merge pull request `#260 `_ from randoms/indigo-devel + fix python3 import error +* Merge pull request `#257 `_ from delftrobotics-forks/python3 + Make tf2_py python3 compatible again +* Use python3 print function. +* Contributors: Maarten de Vries, Tully Foote, randoms + +0.5.16 (2017-07-14) +------------------- +* Merge pull request `#144 `_ from clearpathrobotics/dead_lock_fix + Solve a bug that causes a deadlock in MessageFilter +* Clear error string if it exists from the external entry points. + Fixes `#117 `_ +* Make buff_size and tcp_nodelay and subscriber queue size mutable. +* Remove generate_rand_vectors() from a number of tests. (`#227 `_) + * Remove generate_rand_vectors() from a number of tests. +* Log jump duration on backwards time jump detection. (`#234 `_) +* replaced dependencies on tf2_msgs_gencpp by exported dependencies +* Use new-style objects in python 2 +* Solve a bug that causes a deadlock in MessageFilter +* Contributors: Adel Fakih, Chris Lalancette, Christopher Wecht, Eric Wieser, Koji Terada, Stephan, Tully Foote, koji_terada + +0.5.15 (2017-01-24) +------------------- +* tf2_ros: add option to unregister TransformListener (`#201 `_) +* Contributors: Hans-Joachim Krauch + +0.5.14 (2017-01-16) +------------------- +* Drop roslib.load_manifest (`#191 `_) +* Adds ability to load TF from the ROS parameter server. +* Code linting & reorganization +* Fix indexing beyond end of array +* added a static transform broadcaster in python +* lots more documentation +* remove BufferCore doc, add BufferClient/BufferServer doc for C++, add Buffer/BufferInterface Python documentation +* Better overview for Python +* Contributors: Eric Wieser, Felix Duvallet, Jackie Kay, Mikael Arguedas, Mike Purvis + +0.5.13 (2016-03-04) +------------------- +* fix documentation warnings +* Adding tests to package +* Contributors: Laurent GEORGE, Vincent Rabaud + +0.5.12 (2015-08-05) +------------------- +* remove annoying gcc warning + This is because the roslog macro cannot have two arguments that are + formatting strings: we need to concatenate them first. +* break canTransform loop only for non-tiny negative time deltas + (At least) with Python 2 ros.Time.now() is not necessarily monotonic + and one can experience negative time deltas (usually well below 1s) + on real hardware under full load. This check was originally introduced + to allow for backjumps with rosbag replays, and only there it makes sense. + So we'll add a small duration threshold to ignore backjumps due to + non-monotonic clocks. +* Contributors: Vincent Rabaud, v4hn + +0.5.11 (2015-04-22) +------------------- +* do not short circuit waitForTransform timeout when running inside pytf. Fixes `#102 `_ + roscpp is not initialized inside pytf which means that ros::ok is not + valid. This was causing the timer to abort immediately. + This breaks support for pytf with respect to early breaking out of a loop re `#26 `_. + This is conceptually broken in pytf, and is fixed in tf2_ros python implementation. + If you want this behavior I recommend switching to the tf2 python bindings. +* inject timeout information into error string for canTransform with timeout +* Contributors: Tully Foote + +0.5.10 (2015-04-21) +------------------- +* switch to use a shared lock with upgrade instead of only a unique lock. For `#91 `_ +* Update message_filter.h +* filters: fix unsupported old messages with frame_id starting with '/' +* Enabled tf2 documentation +* make sure the messages get processed before testing the effects. Fixes `#88 `_ +* allowing to use message filters with PCL types +* Contributors: Brice Rebsamen, Jackie Kay, Tully Foote, Vincent Rabaud, jmtatsch + +0.5.9 (2015-03-25) +------------------ +* changed queue_size in Python transform boradcaster to match that in c++ +* Contributors: mrath + +0.5.8 (2015-03-17) +------------------ +* fix deadlock `#79 `_ +* break out of loop if ros is shutdown. Fixes `#26 `_ +* remove useless Makefile files +* Fix static broadcaster with rpy args +* Contributors: Paul Bovbel, Tully Foote, Vincent Rabaud + +0.5.7 (2014-12-23) +------------------ +* Added 6 param transform again + Yes, using Euler angles is a bad habit. But it is much more convenient if you just need a rotation by 90° somewhere to set it up in Euler angles. So I added the option to supply only the 3 angles. +* Remove tf2_py dependency for Android +* Contributors: Achim Königs, Gary Servin + +0.5.6 (2014-09-18) +------------------ +* support if canTransform(...): in python `#57 `_ +* Support clearing the cache when time jumps backwards `#68 `_ +* Contributors: Tully Foote + +0.5.5 (2014-06-23) +------------------ + +0.5.4 (2014-05-07) +------------------ +* surpressing autostart on the server objects to not incur warnings +* switch to boost signals2 following `ros/ros_comm#267 `_, blocking `ros/geometry#23 `_ +* fix compilation with gcc 4.9 +* make can_transform correctly wait +* explicitly set the publish queue size for rospy +* Contributors: Tully Foote, Vincent Rabaud, v4hn + +0.5.3 (2014-02-21) +------------------ + +0.5.2 (2014-02-20) +------------------ + +0.5.1 (2014-02-14) +------------------ +* adding const to MessageEvent data +* Contributors: Tully Foote + +0.5.0 (2014-02-14) +------------------ +* TF2 uses message events to get connection header information +* Contributors: Kevin Watts + +0.4.10 (2013-12-26) +------------------- +* adding support for static transforms in python listener. Fixes `#46 `_ +* Contributors: Tully Foote + +0.4.9 (2013-11-06) +------------------ + +0.4.8 (2013-11-06) +------------------ +* fixing pytf failing to sleep https://github.com/ros/geometry/issues/30 +* moving python documentation to tf2_ros from tf2 to follow the code +* Fixed static_transform_publisher duplicate check, added rostest. + +0.4.7 (2013-08-28) +------------------ +* fixing new conditional to cover the case that time has not progressed yet port forward of `ros/geometry#35 `_ in the python implementation +* fixing new conditional to cover the case that time has not progressed yet port forward of `ros/geometry#35 `_ + +0.4.6 (2013-08-28) +------------------ +* patching python implementation for `#24 `_ as well +* Stop waiting if time jumps backwards. fixes `#24 `_ +* patch to work around uninitiaized time. `#30 https://github.com/ros/geometry/issues/30`_ +* Removing unnecessary CATKIN_DEPENDS `#18 `_ + +0.4.5 (2013-07-11) +------------------ +* Revert "cherrypicking groovy patch for `#10 `_ into hydro" + This reverts commit 296d4916706d64f719b8c1592ab60d3686f994e1. + It was not starting up correctly. +* fixing usage string to show quaternions and using quaternions in the test app +* cherrypicking groovy patch for `#10 `_ into hydro + +0.4.4 (2013-07-09) +------------------ +* making repo use CATKIN_ENABLE_TESTING correctly and switching rostest to be a test_depend with that change. +* reviving unrun unittest and adding CATKIN_ENABLE_TESTING guards + +0.4.3 (2013-07-05) +------------------ + +0.4.2 (2013-07-05) +------------------ + +0.4.1 (2013-07-05) +------------------ +* adding queue accessors lost in the new API +* exposing dedicated thread logic in BufferCore and checking in Buffer +* adding methods to enable backwards compatability for passing through to tf::Transformer + +0.4.0 (2013-06-27) +------------------ +* splitting rospy dependency into tf2_py so tf2 is pure c++ library. +* moving convert methods back into tf2 because it does not have any ros dependencies beyond ros::Time which is already a dependency of tf2 +* Cleaning up unnecessary dependency on roscpp +* converting contents of tf2_ros to be properly namespaced in the tf2_ros namespace +* fixing return by value for tranform method without preallocatoin +* Cleaning up packaging of tf2 including: + removing unused nodehandle + cleaning up a few dependencies and linking + removing old backup of package.xml + making diff minimally different from tf version of library +* Restoring test packages and bullet packages. + reverting 3570e8c42f9b394ecbfd9db076b920b41300ad55 to get back more of the packages previously implemented + reverting 04cf29d1b58c660fdc999ab83563a5d4b76ab331 to fix `#7 `_ +* Added link against catkin_LIBRARIES for tf2_ros lib, also CMakeLists.txt clean up + +0.3.6 (2013-03-03) +------------------ + +0.3.5 (2013-02-15 14:46) +------------------------ +* 0.3.4 -> 0.3.5 + +0.3.4 (2013-02-15 13:14) +------------------------ +* 0.3.3 -> 0.3.4 + +0.3.3 (2013-02-15 11:30) +------------------------ +* 0.3.2 -> 0.3.3 + +0.3.2 (2013-02-15 00:42) +------------------------ +* 0.3.1 -> 0.3.2 + +0.3.1 (2013-02-14) +------------------ +* 0.3.0 -> 0.3.1 + +0.3.0 (2013-02-13) +------------------ +* switching to version 0.3.0 +* Merge pull request `#2 `_ from KaijenHsiao/groovy-devel + added setup.py and catkin_python_setup() to tf2_ros +* added setup.py and catkin_python_setup() to tf2_ros +* fixing cmake target collisions +* fixing catkin message dependencies +* removing packages with missing deps +* catkin fixes +* catkinizing geometry-experimental +* catkinizing tf2_ros +* catching None result in buffer client before it becomes an AttributeError, raising tf2.TransformException instead +* oneiric linker fixes, bump version to 0.2.3 +* fix deprecated use of Header +* merged faust's changes 864 and 865 into non_optimized branch: BufferCore instead of Buffer in TransformListener, and added a constructor that takes a NodeHandle. +* add buffer server binary +* fix compilation on 32bit +* add missing file +* build buffer server +* TransformListener only needs a BufferCore +* Add TransformListener constructor that takes a NodeHandle so you can specify a callback queue to use +* Add option to use a callback queue in the message filter +* move the message filter to tf2_ros +* add missing std_msgs dependency +* missed 2 lines in last commit +* removing auto clearing from listener for it's unexpected from a library +* static transform tested and working +* subscriptions to tf_static unshelved +* static transform publisher executable running +* latching static transform publisher +* cleaning out old commented code +* Only query rospy.Time.now() when the timeout is greater than 0 +* debug comments removed +* move to tf2_ros completed. tests pass again +* merge tf2_cpp and tf2_py into tf2_ros diff --git a/navigations/geometry2/tf2_ros/CMakeLists.txt b/navigations/geometry2/tf2_ros/CMakeLists.txt new file mode 100755 index 0000000..cb01537 --- /dev/null +++ b/navigations/geometry2/tf2_ros/CMakeLists.txt @@ -0,0 +1,153 @@ +cmake_minimum_required(VERSION 3.0.2) +project(tf2_ros) + +if(NOT ANDROID) +set(TF2_PY tf2_py) +endif() + +find_package(catkin REQUIRED COMPONENTS + actionlib + actionlib_msgs + geometry_msgs + message_filters + roscpp + rosgraph + rospy + tf2 + tf2_msgs + ${TF2_PY} +) +find_package(Boost REQUIRED COMPONENTS thread) + +catkin_python_setup() + +catkin_package( + INCLUDE_DIRS include + LIBRARIES ${PROJECT_NAME} + CATKIN_DEPENDS + actionlib + actionlib_msgs + geometry_msgs + message_filters + roscpp + rosgraph + tf2 + tf2_msgs + ${TF2_PY} +) + +include_directories(include ${catkin_INCLUDE_DIRS}) + +# tf2_ros library +add_library(${PROJECT_NAME} + src/buffer.cpp + src/transform_listener.cpp + src/buffer_client.cpp + src/buffer_server.cpp + src/transform_broadcaster.cpp + src/static_transform_broadcaster.cpp +) +add_dependencies(${PROJECT_NAME} ${catkin_EXPORTED_TARGETS}) +target_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES}) + +# buffer_server executable +add_executable(${PROJECT_NAME}_buffer_server src/buffer_server_main.cpp) +add_dependencies(${PROJECT_NAME}_buffer_server ${catkin_EXPORTED_TARGETS}) +target_link_libraries(${PROJECT_NAME}_buffer_server + ${PROJECT_NAME} + ${catkin_LIBRARIES} + ${Boost_LIBRARIES} +) +set_target_properties(${PROJECT_NAME}_buffer_server + PROPERTIES OUTPUT_NAME buffer_server +) + +# static_transform_publisher +add_executable(${PROJECT_NAME}_static_transform_publisher + src/static_transform_broadcaster_program.cpp +) +add_dependencies(${PROJECT_NAME}_static_transform_publisher ${catkin_EXPORTED_TARGETS}) +target_link_libraries(${PROJECT_NAME}_static_transform_publisher + ${PROJECT_NAME} + ${catkin_LIBRARIES} +) +set_target_properties(${PROJECT_NAME}_static_transform_publisher + PROPERTIES OUTPUT_NAME static_transform_publisher +) + +# Install library +install(TARGETS + ${PROJECT_NAME} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} +) + +# Install executable +install(TARGETS + ${PROJECT_NAME}_buffer_server ${PROJECT_NAME}_static_transform_publisher + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) + +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} +) + + +# Tests +if(CATKIN_ENABLE_TESTING) + +# new requirements for testing +find_package(catkin REQUIRED COMPONENTS + actionlib + actionlib_msgs + geometry_msgs + message_filters + roscpp + rosgraph + rospy + rostest + tf2 + tf2_msgs + ${TF2_PY} +) + + + +# tf2_ros_test_listener +add_executable(${PROJECT_NAME}_test_listener EXCLUDE_FROM_ALL test/listener_unittest.cpp) +add_dependencies(${PROJECT_NAME}_test_listener ${catkin_EXPORTED_TARGETS}) +add_executable(${PROJECT_NAME}_test_time_reset EXCLUDE_FROM_ALL test/time_reset_test.cpp) +add_dependencies(${PROJECT_NAME}_test_time_reset ${catkin_EXPORTED_TARGETS}) +add_executable(${PROJECT_NAME}_test_message_filter EXCLUDE_FROM_ALL test/message_filter_test.cpp) +add_dependencies(${PROJECT_NAME}_test_message_filter ${catkin_EXPORTED_TARGETS}) + +target_link_libraries(${PROJECT_NAME}_test_listener + ${PROJECT_NAME} + ${catkin_LIBRARIES} + ${GTEST_LIBRARIES} +) + +target_link_libraries(${PROJECT_NAME}_test_time_reset + ${PROJECT_NAME} + ${catkin_LIBRARIES} + ${GTEST_LIBRARIES} +) + +target_link_libraries(${PROJECT_NAME}_test_message_filter + ${PROJECT_NAME} + ${catkin_LIBRARIES} + ${GTEST_LIBRARIES} +) + +add_dependencies(tests ${PROJECT_NAME}_test_listener) +add_dependencies(tests ${PROJECT_NAME}_test_time_reset) +add_dependencies(tests ${PROJECT_NAME}_test_message_filter) + +add_rostest(test/transform_listener_unittest.launch) +add_rostest(test/transform_listener_time_reset_test.launch) +add_rostest(test/message_filter_test.launch) + +endif() diff --git a/navigations/geometry2/tf2_ros/doc/conf.py b/navigations/geometry2/tf2_ros/doc/conf.py new file mode 100755 index 0000000..b983654 --- /dev/null +++ b/navigations/geometry2/tf2_ros/doc/conf.py @@ -0,0 +1,204 @@ +# -*- coding: utf-8 -*- +# +# tf documentation build configuration file, created by +# sphinx-quickstart on Mon Jun 1 14:21:53 2009. +# +# This file is execfile()d with the current directory set to its containing dir. +# +# Note that not all possible configuration values are present in this +# autogenerated file. +# +# All configuration values have a default; values that are commented out +# serve to show the default. + +import sys, os + +# If extensions (or modules to document with autodoc) are in another directory, +# add these directories to sys.path here. If the directory is relative to the +# documentation root, use os.path.abspath to make it absolute, like shown here. +#sys.path.append(os.path.abspath('.')) + +# -- General configuration ----------------------------------------------------- + +# Add any Sphinx extension module names here, as strings. They can be extensions +# coming with Sphinx (named 'sphinx.ext.*') or your custom ones. +extensions = ['sphinx.ext.autodoc', 'sphinx.ext.doctest', 'sphinx.ext.intersphinx', 'sphinx.ext.imgmath'] + +# Add any paths that contain templates here, relative to this directory. +templates_path = ['_templates'] + +# The suffix of source filenames. +source_suffix = '.rst' + +# The encoding of source files. +#source_encoding = 'utf-8' + +# The master toctree document. +master_doc = 'index' + +# General information about the project. +project = u'tf' +copyright = u'2009, Willow Garage, Inc.' + +# The version info for the project you're documenting, acts as replacement for +# |version| and |release|, also used in various other places throughout the +# built documents. +# +# The short X.Y version. +version = '0.1' +# The full version, including alpha/beta/rc tags. +release = '0.1.0' + +# The language for content autogenerated by Sphinx. Refer to documentation +# for a list of supported languages. +#language = None + +# There are two options for replacing |today|: either, you set today to some +# non-false value, then it is used: +#today = '' +# Else, today_fmt is used as the format for a strftime call. +#today_fmt = '%B %d, %Y' + +# List of documents that shouldn't be included in the build. +#unused_docs = [] + +# List of directories, relative to source directory, that shouldn't be searched +# for source files. +exclude_trees = ['_build'] + +# The reST default role (used for this markup: `text`) to use for all documents. +#default_role = None + +# If true, '()' will be appended to :func: etc. cross-reference text. +#add_function_parentheses = True + +# If true, the current module name will be prepended to all description +# unit titles (such as .. function::). +#add_module_names = True + +# If true, sectionauthor and moduleauthor directives will be shown in the +# output. They are ignored by default. +#show_authors = False + +# The name of the Pygments (syntax highlighting) style to use. +pygments_style = 'sphinx' + +# A list of ignored prefixes for module index sorting. +#modindex_common_prefix = [] + + +# -- Options for HTML output --------------------------------------------------- + +# The theme to use for HTML and HTML Help pages. Major themes that come with +# Sphinx are currently 'default' and 'sphinxdoc'. +html_theme = 'default' + +# Theme options are theme-specific and customize the look and feel of a theme +# further. For a list of options available for each theme, see the +# documentation. +#html_theme_options = {} + +# Add any paths that contain custom themes here, relative to this directory. +#html_theme_path = [] + +# The name for this set of Sphinx documents. If None, it defaults to +# " v documentation". +#html_title = None + +# A shorter title for the navigation bar. Default is the same as html_title. +#html_short_title = None + +# The name of an image file (relative to this directory) to place at the top +# of the sidebar. +#html_logo = None + +# The name of an image file (within the static path) to use as favicon of the +# docs. This file should be a Windows icon file (.ico) being 16x16 or 32x32 +# pixels large. +#html_favicon = None + +# Add any paths that contain custom static files (such as style sheets) here, +# relative to this directory. They are copied after the builtin static files, +# so a file named "default.css" will overwrite the builtin "default.css". +#html_static_path = ['_static'] + +# If not '', a 'Last updated on:' timestamp is inserted at every page bottom, +# using the given strftime format. +#html_last_updated_fmt = '%b %d, %Y' + +# If true, SmartyPants will be used to convert quotes and dashes to +# typographically correct entities. +#html_use_smartypants = True + +# Custom sidebar templates, maps document names to template names. +#html_sidebars = {} + +# Additional templates that should be rendered to pages, maps page names to +# template names. +#html_additional_pages = {} + +# If false, no module index is generated. +#html_use_modindex = True + +# If false, no index is generated. +#html_use_index = True + +# If true, the index is split into individual pages for each letter. +#html_split_index = False + +# If true, links to the reST sources are added to the pages. +#html_show_sourcelink = True + +# If true, an OpenSearch description file will be output, and all pages will +# contain a tag referring to it. The value of this option must be the +# base URL from which the finished HTML is served. +#html_use_opensearch = '' + +# If nonempty, this is the file name suffix for HTML files (e.g. ".xhtml"). +#html_file_suffix = '' + +# Output file base name for HTML help builder. +htmlhelp_basename = 'tfdoc' + + +# -- Options for LaTeX output -------------------------------------------------- + +# The paper size ('letter' or 'a4'). +#latex_paper_size = 'letter' + +# The font size ('10pt', '11pt' or '12pt'). +#latex_font_size = '10pt' + +# Grouping the document tree into LaTeX files. List of tuples +# (source start file, target name, title, author, documentclass [howto/manual]). +latex_documents = [ + ('index', 'tf.tex', u'stereo\\_utils Documentation', + u'Tully Foote and Eitan Marder-Eppstein', 'manual'), +] + +# The name of an image file (relative to this directory) to place at the top of +# the title page. +#latex_logo = None + +# For "manual" documents, if this is true, then toplevel headings are parts, +# not chapters. +#latex_use_parts = False + +# Additional stuff for the LaTeX preamble. +#latex_preamble = '' + +# Documents to append as an appendix to all manuals. +#latex_appendices = [] + +# If false, no module index is generated. +#latex_use_modindex = True + + +# Example configuration for intersphinx: refer to the Python standard library. +intersphinx_mapping = { + 'http://docs.python.org/': None, + 'http://docs.opencv.org/3.0-last-rst/': None, + 'http://docs.scipy.org/doc/numpy' : None + } + +autoclass_content = "both" diff --git a/navigations/geometry2/tf2_ros/doc/index.rst b/navigations/geometry2/tf2_ros/doc/index.rst new file mode 100755 index 0000000..083feb1 --- /dev/null +++ b/navigations/geometry2/tf2_ros/doc/index.rst @@ -0,0 +1,48 @@ +tf2_ros Overview +================ + +This is the Python API reference for the tf2_ros package. + +To broadcast transforms using ROS: +- Call :meth:`rospy.init` to initialize a node. +- Construct a :class:`tf2_ros.TransformBroadcaster`. +- Pass a :class:`geometry_msgs.TransformStamped` message to :meth:`tf2_ros.TransformBroadcaster.sendTransform`. + + - Alternatively, pass a vector of :class:`geometry_msgs.TransformStamped` messages. + +To listen for transforms using ROS: +- Construct an instance of a class that implements :class:`tf2_ros.BufferInterface`. + + - :class:`tf2_ros.Buffer` is the standard implementation which offers a tf2_frames service that can respond to requests with a :class:`tf2_msgs.FrameGraph`. + - :class:`tf2_ros.BufferClient` uses an :class:`actionlib.SimpleActionClient` to wait for the requested transform to become available. + +- Pass the :class:`tf2_ros.Buffer` to the constructor of :class:`tf2_ros.TransformListener`. + - Optionally, pass a :class:`ros.NodeHandle` (otherwise TransformListener will connect to the node for the process). + - Optionally, specify if the TransformListener runs in its own thread or not. + +- Use :meth:`tf2_ros.BufferInterface.transform` to apply a transform on the tf server to an input frame. + - Or, check if a transform is available with :meth:`tf2_ros.BufferInterface.can_transform`. + - Then, call :meth:`tf2_ros.BufferInterface.lookup_transform` to get the transform between two frames. + +For more information, see the tf2 tutorials: http://wiki.ros.org/tf2/Tutorials + +Or, get an `overview`_ of data type conversion methods in geometry_experimental packages. + +See http://wiki.ros.org/tf2/Tutorials for more detailed usage. + +.. _overview: http://wiki.ros.org/tf2/Tutorials/Migration/DataConversions + +Classes and Exceptions +====================== + +.. toctree:: + :maxdepth: 2 + + tf2_ros + + +Indices and tables +================== + +* :ref:`genindex` +* :ref:`search` diff --git a/navigations/geometry2/tf2_ros/doc/mainpage.dox b/navigations/geometry2/tf2_ros/doc/mainpage.dox new file mode 100755 index 0000000..420a674 --- /dev/null +++ b/navigations/geometry2/tf2_ros/doc/mainpage.dox @@ -0,0 +1,41 @@ +/** +\mainpage +\htmlinclude manifest.html + +\b tf2_ros is the C++ ROS wrapper around the tf2 transform library. + +\section codeapi Code API + +To broadcast transforms using ROS: +- Call ros::init() to initialize a node. +- Construct a tf2_ros::TransformBroadcaster. +- Pass a geometry_msgs::TransformStamped message to tf2_ros::TransformBroadcaster::sendTransform(). + - Alternatively, pass a vector of geometry_msgs::TransformStamped messages. +- Use tf2_ros::StaticTransformBroadcaster for "latching" behavior when transforms that are not expected to change. + +To listen for transforms using ROS: +- Construct an instance of a class that implements tf2_ros::BufferInterface. + - tf2_ros::Buffer is the standard implementation which offers a tf2_frames service that can respond to requests with a tf2_msgs::FrameGraph. + - tf2_ros::BufferClient uses an actionlib::SimpleActionClient to wait for the requested transform to become available. + - It should be used with a tf2_ros::BufferServer, which offers the corresponding actionlib::ActionSErver. +- Pass the tf2_ros::Buffer to the constructor of tf2_ros::TransformListener. + - Optionally, pass a ros::NodeHandle (otherwise TransformListener will connect to the node for the process). + - Optionally, specify if the TransformListener runs in its own thread or not. +- Use tf2_ros::BufferInterface::transform() to apply a transform on the tf server to an input frame. + - Or, check if a transform is available with tf2_ros::BufferInterface::canTransform(). + - Then, call tf2_ros::BufferInterface::lookupTransform() to get the transform between two frames. +- Construct a tf2_ros::MessageFilter with the TransformListener to apply a transformation to incoming frames. + - This is especially useful when streaming sensor data. + +List of exceptions thrown in this library: +- tf2::LookupException +- tf2::ConnectivityException +- tf2::ExtrapolationException +- tf2::InvalidArgumentException +- tf2::TimeoutException +- tf2::TransformException + +For more information, see the tf2 tutorials: http://wiki.ros.org/tf2/Tutorials + +Or, get an overview of data type conversion methods in geometry_experimental packages. +*/ diff --git a/navigations/geometry2/tf2_ros/doc/tf2_ros.rst b/navigations/geometry2/tf2_ros/doc/tf2_ros.rst new file mode 100755 index 0000000..10845ed --- /dev/null +++ b/navigations/geometry2/tf2_ros/doc/tf2_ros.rst @@ -0,0 +1,73 @@ +tf_ros2 Python API +================== + +Exceptions +---------- + +.. exception:: tf2.TransformException + + base class for tf exceptions. Because :exc:`tf2.TransformException` is the + base class for other exceptions, you can catch all tf exceptions + by writing:: + + try: + # do some tf2 work + except tf2.TransformException: + print "some tf2 exception happened" + + +.. exception:: tf2.ConnectivityException + + subclass of :exc:`TransformException`. + Raised when that the fixed_frame tree is not connected between the frames requested. + +.. exception:: tf2.LookupException + + subclass of :exc:`TransformException`. + Raised when a tf method has attempted to access a frame, but + the frame is not in the graph. + The most common reason for this is that the frame is not + being published, or a parent frame was not set correctly + causing the tree to be broken. + +.. exception:: tf2.ExtrapolationException + + subclass of :exc:`TransformException` + Raised when a tf method would have required extrapolation beyond current limits. + + +.. exception:: tf2.InvalidArgumentException + + subclass of :exc:`TransformException`. + Raised when the arguments to the method are called improperly formed. An example of why this might be raised is if an argument is nan. + +.. autoexception:: tf2_ros.buffer_interface.TypeException + +.. autoexception:: tf2_ros.buffer_interface.NotImplementedException + + +BufferInterface +--------------- +.. autoclass:: tf2_ros.buffer_interface.BufferInterface + :members: + +Buffer +------ +.. autoclass:: tf2_ros.buffer.Buffer + :members: + +BufferClient +------------ +.. autoclass:: tf2_ros.buffer_client.BufferClient + :members: + + +TransformBroadcaster +-------------------- +.. autoclass:: tf2_ros.transform_broadcaster.TransformBroadcaster + :members: + +TransformListener +----------------- +.. autoclass:: tf2_ros.transform_listener.TransformListener + :members: diff --git a/navigations/geometry2/tf2_ros/include/tf2_ros/buffer.h b/navigations/geometry2/tf2_ros/include/tf2_ros/buffer.h new file mode 100755 index 0000000..835dfa2 --- /dev/null +++ b/navigations/geometry2/tf2_ros/include/tf2_ros/buffer.h @@ -0,0 +1,144 @@ +/* + * Copyright (c) 2008, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +/** \author Wim Meeussen */ + +#ifndef TF2_ROS_BUFFER_H +#define TF2_ROS_BUFFER_H + +#include +#include +#include +#include +#include + + +namespace tf2_ros +{ + + /** \brief Standard implementation of the tf2_ros::BufferInterface abstract data type. + * + * Inherits tf2_ros::BufferInterface and tf2::BufferCore. + * Stores known frames and optionally offers a ROS service, "tf2_frames", which responds to client requests + * with a response containing a tf2_msgs::FrameGraph representing the relationship of known frames. + */ + class Buffer: public BufferInterface, public tf2::BufferCore + { + public: + using tf2::BufferCore::lookupTransform; + using tf2::BufferCore::canTransform; + + /** + * @brief Constructor for a Buffer object + * @param cache_time How long to keep a history of transforms + * @param debug Whether to advertise the tf2_frames service that exposes debugging information from the buffer + * @return + */ + Buffer(ros::Duration cache_time = ros::Duration(BufferCore::DEFAULT_CACHE_TIME), bool debug = false); + + /** \brief Get the transform between two frames by frame ID. + * \param target_frame The frame to which data should be transformed + * \param source_frame The frame where the data originated + * \param time The time at which the value of the transform is desired. (0 will get the latest) + * \param timeout How long to block before failing + * \return The transform between the frames + * + * Possible exceptions tf2::LookupException, tf2::ConnectivityException, + * tf2::ExtrapolationException, tf2::InvalidArgumentException + */ + virtual geometry_msgs::TransformStamped + lookupTransform(const std::string& target_frame, const std::string& source_frame, + const ros::Time& time, const ros::Duration timeout) const; + + /** \brief Get the transform between two frames by frame ID assuming fixed frame. + * \param target_frame The frame to which data should be transformed + * \param target_time The time to which the data should be transformed. (0 will get the latest) + * \param source_frame The frame where the data originated + * \param source_time The time at which the source_frame should be evaluated. (0 will get the latest) + * \param fixed_frame The frame in which to assume the transform is constant in time. + * \param timeout How long to block before failing + * \return The transform between the frames + * + * Possible exceptions tf2::LookupException, tf2::ConnectivityException, + * tf2::ExtrapolationException, tf2::InvalidArgumentException + */ + virtual geometry_msgs::TransformStamped + lookupTransform(const std::string& target_frame, const ros::Time& target_time, + const std::string& source_frame, const ros::Time& source_time, + const std::string& fixed_frame, const ros::Duration timeout) const; + + + /** \brief Test if a transform is possible + * \param target_frame The frame into which to transform + * \param source_frame The frame from which to transform + * \param target_time The time at which to transform + * \param timeout How long to block before failing + * \param errstr A pointer to a string which will be filled with why the transform failed, if not NULL + * \return True if the transform is possible, false otherwise + */ + virtual bool + canTransform(const std::string& target_frame, const std::string& source_frame, + const ros::Time& target_time, const ros::Duration timeout, std::string* errstr = NULL) const; + + /** \brief Test if a transform is possible + * \param target_frame The frame into which to transform + * \param target_time The time into which to transform + * \param source_frame The frame from which to transform + * \param source_time The time from which to transform + * \param fixed_frame The frame in which to treat the transform as constant in time + * \param timeout How long to block before failing + * \param errstr A pointer to a string which will be filled with why the transform failed, if not NULL + * \return True if the transform is possible, false otherwise + */ + virtual bool + canTransform(const std::string& target_frame, const ros::Time& target_time, + const std::string& source_frame, const ros::Time& source_time, + const std::string& fixed_frame, const ros::Duration timeout, std::string* errstr = NULL) const; + + + + + private: + bool getFrames(tf2_msgs::FrameGraph::Request& req, tf2_msgs::FrameGraph::Response& res) ; + + + // conditionally error if dedicated_thread unset. + bool checkAndErrorDedicatedThreadPresent(std::string* errstr) const; + + ros::ServiceServer frames_server_; + + + }; // class + +static const std::string threading_error = "Do not call canTransform or lookupTransform with a timeout unless you are using another thread for populating data. Without a dedicated thread it will always timeout. If you have a separate thread servicing tf messages, call setUsingDedicatedThread(true) on your Buffer instance."; + + +} // namespace + +#endif // TF2_ROS_BUFFER_H diff --git a/navigations/geometry2/tf2_ros/include/tf2_ros/buffer_client.h b/navigations/geometry2/tf2_ros/include/tf2_ros/buffer_client.h new file mode 100755 index 0000000..a5b0c08 --- /dev/null +++ b/navigations/geometry2/tf2_ros/include/tf2_ros/buffer_client.h @@ -0,0 +1,139 @@ +/********************************************************************* +* +* Software License Agreement (BSD License) +* +* Copyright (c) 2009, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of Willow Garage, Inc. nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* +* Author: Eitan Marder-Eppstein +*********************************************************************/ +#ifndef TF2_ROS_BUFFER_CLIENT_H_ +#define TF2_ROS_BUFFER_CLIENT_H_ + +#include +#include +#include + +namespace tf2_ros +{ + /** \brief Action client-based implementation of the tf2_ros::BufferInterface abstract data type. + * + * BufferClient uses actionlib to coordinate waiting for available transforms. + * + * You can use this class with a tf2_ros::BufferServer and tf2_ros::TransformListener in a separate process. + */ + class BufferClient : public BufferInterface + { + public: + typedef actionlib::SimpleActionClient LookupActionClient; + + /** \brief BufferClient constructor + * \param ns The namespace in which to look for a BufferServer + * \param check_frequency Deprecated, not used anymore + * \param timeout_padding The amount of time to allow passed the desired timeout on the client side for communication lag + */ + BufferClient(std::string ns, double check_frequency = 10.0, ros::Duration timeout_padding = ros::Duration(2.0)); + + /** \brief Get the transform between two frames by frame ID. + * \param target_frame The frame to which data should be transformed + * \param source_frame The frame where the data originated + * \param time The time at which the value of the transform is desired. (0 will get the latest) + * \param timeout How long to block before failing + * \return The transform between the frames + * + * Possible exceptions tf2::LookupException, tf2::ConnectivityException, + * tf2::ExtrapolationException, tf2::InvalidArgumentException + */ + virtual geometry_msgs::TransformStamped + lookupTransform(const std::string& target_frame, const std::string& source_frame, + const ros::Time& time, const ros::Duration timeout = ros::Duration(0.0)) const; + + /** \brief Get the transform between two frames by frame ID assuming fixed frame. + * \param target_frame The frame to which data should be transformed + * \param target_time The time to which the data should be transformed. (0 will get the latest) + * \param source_frame The frame where the data originated + * \param source_time The time at which the source_frame should be evaluated. (0 will get the latest) + * \param fixed_frame The frame in which to assume the transform is constant in time. + * \param timeout How long to block before failing + * \return The transform between the frames + * + * Possible exceptions tf2::LookupException, tf2::ConnectivityException, + * tf2::ExtrapolationException, tf2::InvalidArgumentException + */ + virtual geometry_msgs::TransformStamped + lookupTransform(const std::string& target_frame, const ros::Time& target_time, + const std::string& source_frame, const ros::Time& source_time, + const std::string& fixed_frame, const ros::Duration timeout = ros::Duration(0.0)) const; + + /** \brief Test if a transform is possible + * \param target_frame The frame into which to transform + * \param source_frame The frame from which to transform + * \param time The time at which to transform + * \param timeout How long to block before failing + * \param errstr A pointer to a string which will be filled with why the transform failed, if not NULL + * \return True if the transform is possible, false otherwise + */ + virtual bool + canTransform(const std::string& target_frame, const std::string& source_frame, + const ros::Time& time, const ros::Duration timeout = ros::Duration(0.0), std::string* errstr = NULL) const; + + /** \brief Test if a transform is possible + * \param target_frame The frame into which to transform + * \param target_time The time into which to transform + * \param source_frame The frame from which to transform + * \param source_time The time from which to transform + * \param fixed_frame The frame in which to treat the transform as constant in time + * \param timeout How long to block before failing + * \param errstr A pointer to a string which will be filled with why the transform failed, if not NULL + * \return True if the transform is possible, false otherwise + */ + virtual bool + canTransform(const std::string& target_frame, const ros::Time& target_time, + const std::string& source_frame, const ros::Time& source_time, + const std::string& fixed_frame, const ros::Duration timeout = ros::Duration(0.0), std::string* errstr = NULL) const; + + /** \brief Block until the action server is ready to respond to requests. + * \param timeout Time to wait for the server. + * \return True if the server is ready, false otherwise. + */ + bool waitForServer(const ros::Duration& timeout = ros::Duration(0)) + { + return client_.waitForServer(timeout); + } + + private: + geometry_msgs::TransformStamped processGoal(const tf2_msgs::LookupTransformGoal& goal) const; + geometry_msgs::TransformStamped processResult(const tf2_msgs::LookupTransformResult& result) const; + mutable LookupActionClient client_; + double check_frequency_; + ros::Duration timeout_padding_; + }; +}; +#endif diff --git a/navigations/geometry2/tf2_ros/include/tf2_ros/buffer_interface.h b/navigations/geometry2/tf2_ros/include/tf2_ros/buffer_interface.h new file mode 100755 index 0000000..9215008 --- /dev/null +++ b/navigations/geometry2/tf2_ros/include/tf2_ros/buffer_interface.h @@ -0,0 +1,267 @@ +/* + * Copyright (c) 2008, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +/** \author Wim Meeussen */ + +#ifndef TF2_ROS_BUFFER_INTERFACE_H +#define TF2_ROS_BUFFER_INTERFACE_H + +#include +#include +#include +#include +#include +#include + +namespace tf2_ros +{ + +/** \brief Abstract interface for wrapping tf2::BufferCore in a ROS-based API. + * Implementations include tf2_ros::Buffer and tf2_ros::BufferClient. + */ +class BufferInterface +{ +public: + + /** \brief Get the transform between two frames by frame ID. + * \param target_frame The frame to which data should be transformed + * \param source_frame The frame where the data originated + * \param time The time at which the value of the transform is desired. (0 will get the latest) + * \param timeout How long to block before failing + * \return The transform between the frames + * + * Possible exceptions tf2::LookupException, tf2::ConnectivityException, + * tf2::ExtrapolationException, tf2::InvalidArgumentException + */ + virtual geometry_msgs::TransformStamped + lookupTransform(const std::string& target_frame, const std::string& source_frame, + const ros::Time& time, const ros::Duration timeout) const = 0; + + /** \brief Get the transform between two frames by frame ID assuming fixed frame. + * \param target_frame The frame to which data should be transformed + * \param target_time The time to which the data should be transformed. (0 will get the latest) + * \param source_frame The frame where the data originated + * \param source_time The time at which the source_frame should be evaluated. (0 will get the latest) + * \param fixed_frame The frame in which to assume the transform is constant in time. + * \param timeout How long to block before failing + * \return The transform between the frames + * + * Possible exceptions tf2::LookupException, tf2::ConnectivityException, + * tf2::ExtrapolationException, tf2::InvalidArgumentException + */ + virtual geometry_msgs::TransformStamped + lookupTransform(const std::string& target_frame, const ros::Time& target_time, + const std::string& source_frame, const ros::Time& source_time, + const std::string& fixed_frame, const ros::Duration timeout) const = 0; + + + /** \brief Test if a transform is possible + * \param target_frame The frame into which to transform + * \param source_frame The frame from which to transform + * \param time The time at which to transform + * \param timeout How long to block before failing + * \param errstr A pointer to a string which will be filled with why the transform failed, if not NULL + * \return True if the transform is possible, false otherwise + */ + virtual bool + canTransform(const std::string& target_frame, const std::string& source_frame, + const ros::Time& time, const ros::Duration timeout, std::string* errstr = NULL) const = 0; + + /** \brief Test if a transform is possible + * \param target_frame The frame into which to transform + * \param target_time The time into which to transform + * \param source_frame The frame from which to transform + * \param source_time The time from which to transform + * \param fixed_frame The frame in which to treat the transform as constant in time + * \param timeout How long to block before failing + * \param errstr A pointer to a string which will be filled with why the transform failed, if not NULL + * \return True if the transform is possible, false otherwise + */ + virtual bool + canTransform(const std::string& target_frame, const ros::Time& target_time, + const std::string& source_frame, const ros::Time& source_time, + const std::string& fixed_frame, const ros::Duration timeout, std::string* errstr = NULL) const = 0; + + /** \brief Transform an input into the target frame. + * This function is templated and can take as input any valid mathematical object that tf knows + * how to apply a transform to, by way of the templated math conversions interface. + * For example, the template type could be a Transform, Pose, Vector, or Quaternion message + * type (as defined in geometry_msgs). + * \tparam T The type of the object to transform. + * \param in The object to transform + * \param out The transformed output, preallocated by the caller. + * \param target_frame The string identifer for the frame to transform into. + * \param timeout How long to wait for the target frame. Default value is zero (no blocking). + */ + template + T& transform(const T& in, T& out, + const std::string& target_frame, ros::Duration timeout=ros::Duration(0.0)) const + { + // do the transform + tf2::doTransform(in, out, lookupTransform(target_frame, tf2::getFrameId(in), tf2::getTimestamp(in), timeout)); + return out; + } + + /** \brief Transform an input into the target frame. + * This function is templated and can take as input any valid mathematical object that tf knows + * how to apply a transform to, by way of the templated math conversions interface. + * For example, the template type could be a Transform, Pose, Vector, or Quaternion message + * type (as defined in geometry_msgs). + * \tparam T The type of the object to transform. + * \param in The object to transform. + * \param target_frame The string identifer for the frame to transform into. + * \param timeout How long to wait for the target frame. Default value is zero (no blocking). + * \return The transformed output. + */ + template + T transform(const T& in, + const std::string& target_frame, ros::Duration timeout=ros::Duration(0.0)) const + { + T out; + return transform(in, out, target_frame, timeout); + } + + /** \brief Transform an input into the target frame and convert to a specified output type. + * It is templated on two types: the type of the input object and the type of the + * transformed output. + * For example, the template types could be Transform, Pose, Vector, or Quaternion messages + * type (as defined in geometry_msgs). + * The function will calculate the transformation and then convert the result into the + * specified output type. + * Compilation will fail if a known conversion does not exist bewteen the two template + * parameters. + * \tparam A The type of the object to transform. + * \tparam B The type of the transformed output. + * \param in The object to transform + * \param out The transformed output, converted to the specified type. + * \param target_frame The string identifer for the frame to transform into. + * \param timeout How long to wait for the target frame. Default value is zero (no blocking). + * \return The transformed output, converted to the specified type. + */ + template + B& transform(const A& in, B& out, + const std::string& target_frame, ros::Duration timeout=ros::Duration(0.0)) const + { + A copy = transform(in, target_frame, timeout); + tf2::convert(copy, out); + return out; + } + + /** \brief Transform an input into the target frame (advanced). + * This function is templated and can take as input any valid mathematical object that tf knows + * how to apply a transform to, by way of the templated math conversions interface. + * For example, the template type could be a Transform, Pose, Vector, or Quaternion message + * type (as defined in geometry_msgs). + * This function follows the advanced API, which allows transforming between different time + * points, and specifying a fixed frame that does not varying in time. + * \tparam T The type of the object to transform. + * \param in The object to transform + * \param out The transformed output, preallocated by the caller. + * \param target_frame The string identifer for the frame to transform into. + * \param target_time The time into which to transform + * \param fixed_frame The frame in which to treat the transform as constant in time. + * \param timeout How long to wait for the target frame. Default value is zero (no blocking). + */ + template + T& transform(const T& in, T& out, + const std::string& target_frame, const ros::Time& target_time, + const std::string& fixed_frame, ros::Duration timeout=ros::Duration(0.0)) const + { + // do the transform + tf2::doTransform(in, out, lookupTransform(target_frame, target_time, + tf2::getFrameId(in), tf2::getTimestamp(in), + fixed_frame, timeout)); + return out; + } + + + /** \brief Transform an input into the target frame (advanced). + * This function is templated and can take as input any valid mathematical object that tf knows + * how to apply a transform to, by way of the templated math conversions interface. + * For example, the template type could be a Transform, Pose, Vector, or Quaternion message + * type (as defined in geometry_msgs). + * This function follows the advanced API, which allows transforming between different time + * points, and specifying a fixed frame that does not varying in time. + * \tparam T The type of the object to transform. + * \param in The object to transform + * \param target_frame The string identifer for the frame to transform into. + * \param target_time The time into which to transform + * \param fixed_frame The frame in which to treat the transform as constant in time. + * \param timeout How long to wait for the target frame. Default value is zero (no blocking). + * \return The transformed output. + */ + template + T transform(const T& in, + const std::string& target_frame, const ros::Time& target_time, + const std::string& fixed_frame, ros::Duration timeout=ros::Duration(0.0)) const + { + T out; + return transform(in, out, target_frame, target_time, fixed_frame, timeout); + } + + + /** \brief Transform an input into the target frame and convert to a specified output type (advanced). + * It is templated on two types: the type of the input object and the type of the + * transformed output. + * For example, the template type could be a Transform, Pose, Vector, or Quaternion message + * type (as defined in geometry_msgs). + * The function will calculate the transformation and then convert the result into the + * specified output type. + * Compilation will fail if a known conversion does not exist bewteen the two template + * parameters. + * This function follows the advanced API, which allows transforming between different time + * points, and specifying a fixed frame that does not varying in time. + * \tparam A The type of the object to transform. + * \tparam B The type of the transformed output. + * \param in The object to transform + * \param out The transformed output, converted to the specified output type. + * \param target_frame The string identifer for the frame to transform into. + * \param target_time The time into which to transform + * \param fixed_frame The frame in which to treat the transform as constant in time. + * \param timeout How long to wait for the target frame. Default value is zero (no blocking). + * \return The transformed output, converted to the specified output type. + */ + template + B& transform(const A& in, B& out, + const std::string& target_frame, const ros::Time& target_time, + const std::string& fixed_frame, ros::Duration timeout=ros::Duration(0.0)) const + { + // do the transform + A copy = transform(in, target_frame, target_time, fixed_frame, timeout); + tf2::convert(copy, out); + return out; + } + + + }; // class + + +} // namespace + +#endif // TF2_ROS_BUFFER_INTERFACE_H diff --git a/navigations/geometry2/tf2_ros/include/tf2_ros/buffer_server.h b/navigations/geometry2/tf2_ros/include/tf2_ros/buffer_server.h new file mode 100755 index 0000000..7481466 --- /dev/null +++ b/navigations/geometry2/tf2_ros/include/tf2_ros/buffer_server.h @@ -0,0 +1,92 @@ +/********************************************************************* +* +* Software License Agreement (BSD License) +* +* Copyright (c) 2009, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of Willow Garage, Inc. nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* +* Author: Eitan Marder-Eppstein +*********************************************************************/ +#ifndef TF2_ROS_BUFFER_SERVER_H_ +#define TF2_ROS_BUFFER_SERVER_H_ + +#include +#include +#include +#include + +namespace tf2_ros +{ + /** \brief Action server for the actionlib-based implementation of tf2_ros::BufferInterface. + * + * Use this class with a tf2_ros::TransformListener in the same process. + * You can use this class with a tf2_ros::BufferClient in a different process. + */ + class BufferServer + { + private: + typedef actionlib::ActionServer LookupTransformServer; + typedef LookupTransformServer::GoalHandle GoalHandle; + + struct GoalInfo + { + GoalHandle handle; + ros::Time end_time; + }; + + public: + /** \brief Constructor + * \param buffer The Buffer that this BufferServer will wrap. + * \param ns The namespace in which to look for action clients. + * \param auto_start Pass argument to the constructor of the ActionServer. + * \param check_period How often to check for changes to known transforms (via a timer event). + */ + BufferServer(const Buffer& buffer, const std::string& ns, + bool auto_start = true, ros::Duration check_period = ros::Duration(0.01)); + + /** \brief Start the action server. + */ + void start(); + + private: + void goalCB(GoalHandle gh); + void cancelCB(GoalHandle gh); + void checkTransforms(const ros::TimerEvent& e); + bool canTransform(GoalHandle gh); + geometry_msgs::TransformStamped lookupTransform(GoalHandle gh); + + const Buffer& buffer_; + LookupTransformServer server_; + std::list active_goals_; + boost::mutex mutex_; + ros::Timer check_timer_; + }; +} +#endif diff --git a/navigations/geometry2/tf2_ros/include/tf2_ros/message_filter.h b/navigations/geometry2/tf2_ros/include/tf2_ros/message_filter.h new file mode 100755 index 0000000..e8a47f5 --- /dev/null +++ b/navigations/geometry2/tf2_ros/include/tf2_ros/message_filter.h @@ -0,0 +1,716 @@ +/* + * Copyright (c) 2010, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +/** \author Josh Faust */ + +#ifndef TF2_ROS_MESSAGE_FILTER_H +#define TF2_ROS_MESSAGE_FILTER_H + +#include + +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +#include +#include +#include + +#define TF2_ROS_MESSAGEFILTER_DEBUG(fmt, ...) \ + ROS_DEBUG_NAMED("message_filter", std::string(std::string("MessageFilter [target=%s]: ") + std::string(fmt)).c_str(), getTargetFramesString().c_str(), __VA_ARGS__) + +#define TF2_ROS_MESSAGEFILTER_WARN(fmt, ...) \ + ROS_WARN_NAMED("message_filter", std::string(std::string("MessageFilter [target=%s]: ") + std::string(fmt)).c_str(), getTargetFramesString().c_str(), __VA_ARGS__) + +namespace tf2_ros +{ + +namespace filter_failure_reasons +{ +enum FilterFailureReason +{ + /// The message buffer overflowed, and this message was pushed off the back of the queue, but the reason it was unable to be transformed is unknown. + Unknown, + /// The timestamp on the message is more than the cache length earlier than the newest data in the transform cache + OutTheBack, + /// The frame_id on the message is empty + EmptyFrameID, +}; +} +typedef filter_failure_reasons::FilterFailureReason FilterFailureReason; + +class MessageFilterBase +{ +public: + typedef std::vector V_string; + + virtual ~MessageFilterBase(){} + virtual void clear() = 0; + virtual void setTargetFrame(const std::string& target_frame) = 0; + virtual void setTargetFrames(const V_string& target_frames) = 0; + virtual void setTolerance(const ros::Duration& tolerance) = 0; +}; + +/** + * \brief Follows the patterns set by the message_filters package to implement a filter which only passes messages through once there is transform data available + * + * The callbacks used in this class are of the same form as those used by roscpp's message callbacks. + * + * MessageFilter is templated on a message type. + * + * \section example_usage Example Usage + * + * If you want to hook a MessageFilter into a ROS topic: +\verbatim +message_filters::Subscriber sub(node_handle_, "topic", 10); +tf2_ros::MessageFilter tf_filter(sub, tf_buffer_, "/map", 10, 0); +tf_filter.registerCallback(&MyClass::myCallback, this); +\endverbatim + */ +template +class MessageFilter : public MessageFilterBase, public message_filters::SimpleFilter +{ +public: + typedef boost::shared_ptr MConstPtr; + typedef ros::MessageEvent MEvent; + typedef boost::function FailureCallback; + typedef boost::signals2::signal FailureSignal; + + // If you hit this assert your message does not have a header, or does not have the HasHeader trait defined for it + // Actually, we need to check that the message has a header, or that it + // has the FrameId and Stamp traits. However I don't know how to do that + // so simply commenting out for now. + //ROS_STATIC_ASSERT(ros::message_traits::HasHeader::value); + + /** + * \brief Constructor + * + * \param bc The tf2::BufferCore this filter should use + * \param target_frame The frame this filter should attempt to transform to. To use multiple frames, pass an empty string here and use the setTargetFrames() function. + * \param queue_size The number of messages to queue up before throwing away old ones. 0 means infinite (dangerous). + * \param nh The NodeHandle whose callback queue we should add callbacks to + */ + MessageFilter(tf2::BufferCore& bc, const std::string& target_frame, uint32_t queue_size, const ros::NodeHandle& nh) + : bc_(bc) + , queue_size_(queue_size) + , callback_queue_(nh.getCallbackQueue()) + { + init(); + + setTargetFrame(target_frame); + } + + /** + * \brief Constructor + * + * \param f The filter to connect this filter's input to. Often will be a message_filters::Subscriber. + * \param bc The tf2::BufferCore this filter should use + * \param target_frame The frame this filter should attempt to transform to. To use multiple frames, pass an empty string here and use the setTargetFrames() function. + * \param queue_size The number of messages to queue up before throwing away old ones. 0 means infinite (dangerous). + * \param nh The NodeHandle whose callback queue we should add callbacks to + */ + template + MessageFilter(F& f, tf2::BufferCore& bc, const std::string& target_frame, uint32_t queue_size, const ros::NodeHandle& nh) + : bc_(bc) + , queue_size_(queue_size) + , callback_queue_(nh.getCallbackQueue()) + { + init(); + + setTargetFrame(target_frame); + + connectInput(f); + } + + /** + * \brief Constructor + * + * \param bc The tf2::BufferCore this filter should use + * \param target_frame The frame this filter should attempt to transform to. To use multiple frames, pass an empty string here and use the setTargetFrames() function. + * \param queue_size The number of messages to queue up before throwing away old ones. 0 means infinite (dangerous). + * \param cbqueue The callback queue to add callbacks to. If NULL, callbacks will happen from whatever thread either + * a) add() is called, which will generally be when the previous filter in the chain outputs a message, or + * b) tf2::BufferCore::setTransform() is called + */ + MessageFilter(tf2::BufferCore& bc, const std::string& target_frame, uint32_t queue_size, ros::CallbackQueueInterface* cbqueue) + : bc_(bc) + , queue_size_(queue_size) + , callback_queue_(cbqueue) + { + init(); + + setTargetFrame(target_frame); + } + + /** + * \brief Constructor + * + * \param f The filter to connect this filter's input to. Often will be a message_filters::Subscriber. + * \param bc The tf2::BufferCore this filter should use + * \param target_frame The frame this filter should attempt to transform to. To use multiple frames, pass an empty string here and use the setTargetFrames() function. + * \param queue_size The number of messages to queue up before throwing away old ones. 0 means infinite (dangerous). + * \param cbqueue The callback queue to add callbacks to. If NULL, callbacks will happen from whatever thread either + * a) add() is called, which will generally be when the previous filter in the chain outputs a message, or + * b) tf2::BufferCore::setTransform() is called + */ + template + MessageFilter(F& f, tf2::BufferCore& bc, const std::string& target_frame, uint32_t queue_size, ros::CallbackQueueInterface* cbqueue) + : bc_(bc) + , queue_size_(queue_size) + , callback_queue_(cbqueue) + { + init(); + + setTargetFrame(target_frame); + + connectInput(f); + } + + /** + * \brief Connect this filter's input to another filter's output. If this filter is already connected, disconnects first. + */ + template + void connectInput(F& f) + { + message_connection_.disconnect(); + message_connection_ = f.registerCallback(&MessageFilter::incomingMessage, this); + } + + /** + * \brief Destructor + */ + ~MessageFilter() + { + message_connection_.disconnect(); + + MessageFilter::clear(); + + TF2_ROS_MESSAGEFILTER_DEBUG("Successful Transforms: %llu, Discarded due to age: %llu, Transform messages received: %llu, Messages received: %llu, Total dropped: %llu", + (long long unsigned int)successful_transform_count_, + (long long unsigned int)failed_out_the_back_count_, (long long unsigned int)transform_message_count_, + (long long unsigned int)incoming_message_count_, (long long unsigned int)dropped_message_count_); + + } + + /** + * \brief Set the frame you need to be able to transform to before getting a message callback + */ + void setTargetFrame(const std::string& target_frame) + { + V_string frames; + frames.push_back(target_frame); + setTargetFrames(frames); + } + + /** + * \brief Set the frames you need to be able to transform to before getting a message callback + */ + void setTargetFrames(const V_string& target_frames) + { + boost::mutex::scoped_lock frames_lock(target_frames_mutex_); + + target_frames_.resize(target_frames.size()); + std::transform(target_frames.begin(), target_frames.end(), target_frames_.begin(), this->stripSlash); + expected_success_count_ = target_frames_.size() * (time_tolerance_.isZero() ? 1 : 2); + + std::stringstream ss; + for (V_string::iterator it = target_frames_.begin(); it != target_frames_.end(); ++it) + { + ss << *it << " "; + } + target_frames_string_ = ss.str(); + } + /** + * \brief Get the target frames as a string for debugging + */ + std::string getTargetFramesString() + { + boost::mutex::scoped_lock lock(target_frames_mutex_); + return target_frames_string_; + }; + + /** + * \brief Set the required tolerance for the notifier to return true + */ + void setTolerance(const ros::Duration& tolerance) + { + boost::mutex::scoped_lock lock(target_frames_mutex_); + time_tolerance_ = tolerance; + expected_success_count_ = target_frames_.size() * (time_tolerance_.isZero() ? 1 : 2); + } + + /** + * \brief Clear any messages currently in the queue + */ + void clear() + { + boost::unique_lock< boost::shared_mutex > unique_lock(messages_mutex_); + + TF2_ROS_MESSAGEFILTER_DEBUG("%s", "Cleared"); + + bc_.removeTransformableCallback(callback_handle_); + callback_handle_ = bc_.addTransformableCallback(boost::bind(&MessageFilter::transformable, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4, boost::placeholders::_5)); + + messages_.clear(); + message_count_ = 0; + + // remove pending callbacks in callback queue as well + if (callback_queue_) + callback_queue_->removeByID((uint64_t)this); + + warned_about_empty_frame_id_ = false; + } + + void add(const MEvent& evt) + { + if (target_frames_.empty()) + { + return; + } + + namespace mt = ros::message_traits; + const MConstPtr& message = evt.getMessage(); + std::string frame_id = stripSlash(mt::FrameId::value(*message)); + ros::Time stamp = mt::TimeStamp::value(*message); + + if (frame_id.empty()) + { + messageDropped(evt, filter_failure_reasons::EmptyFrameID); + return; + } + + // iterate through the target frames and add requests for each of them + MessageInfo info; + info.handles.reserve(expected_success_count_); + { + V_string target_frames_copy; + // Copy target_frames_ to avoid deadlock from #79 + { + boost::mutex::scoped_lock frames_lock(target_frames_mutex_); + target_frames_copy = target_frames_; + } + + V_string::iterator it = target_frames_copy.begin(); + V_string::iterator end = target_frames_copy.end(); + for (; it != end; ++it) + { + const std::string& target_frame = *it; + tf2::TransformableRequestHandle handle = bc_.addTransformableRequest(callback_handle_, target_frame, frame_id, stamp); + if (handle == 0xffffffffffffffffULL) // never transformable + { + messageDropped(evt, filter_failure_reasons::OutTheBack); + return; + } + else if (handle == 0) + { + ++info.success_count; + } + else + { + info.handles.push_back(handle); + } + + if (!time_tolerance_.isZero()) + { + handle = bc_.addTransformableRequest(callback_handle_, target_frame, frame_id, stamp + time_tolerance_); + if (handle == 0xffffffffffffffffULL) // never transformable + { + messageDropped(evt, filter_failure_reasons::OutTheBack); + return; + } + else if (handle == 0) + { + ++info.success_count; + } + else + { + info.handles.push_back(handle); + } + } + } + } + + + // We can transform already + if (info.success_count == expected_success_count_) + { + messageReady(evt); + } + else + { + boost::unique_lock< boost::shared_mutex > unique_lock(messages_mutex_); + // If this message is about to push us past our queue size, erase the oldest message + if (queue_size_ != 0 && message_count_ + 1 > queue_size_) + { + ++dropped_message_count_; + const MessageInfo& front = messages_.front(); + TF2_ROS_MESSAGEFILTER_DEBUG("Removed oldest message because buffer is full, count now %d (frame_id=%s, stamp=%f)", message_count_, + (mt::FrameId::value(*front.event.getMessage())).c_str(), mt::TimeStamp::value(*front.event.getMessage()).toSec()); + + V_TransformableRequestHandle::const_iterator it = front.handles.begin(); + V_TransformableRequestHandle::const_iterator end = front.handles.end(); + + for (; it != end; ++it) + { + bc_.cancelTransformableRequest(*it); + } + + messageDropped(front.event, filter_failure_reasons::Unknown); + messages_.pop_front(); + --message_count_; + } + + // Add the message to our list + info.event = evt; + messages_.push_back(info); + ++message_count_; + } + + TF2_ROS_MESSAGEFILTER_DEBUG("Added message in frame %s at time %.3f, count now %d", frame_id.c_str(), stamp.toSec(), message_count_); + + ++incoming_message_count_; + } + + /** + * \brief Manually add a message into this filter. + * \note If the message (or any other messages in the queue) are immediately transformable this will immediately call through to the output callback, possibly + * multiple times + */ + void add(const MConstPtr& message) + { + boost::shared_ptr > header(new std::map); + (*header)["callerid"] = "unknown"; + ros::WallTime n = ros::WallTime::now(); + ros::Time t(n.sec, n.nsec); + add(MEvent(message, header, t)); + } + + /** + * \brief Register a callback to be called when a message is about to be dropped + * \param callback The callback to call + */ + message_filters::Connection registerFailureCallback(const FailureCallback& callback) + { + boost::mutex::scoped_lock lock(failure_signal_mutex_); + return message_filters::Connection(boost::bind(&MessageFilter::disconnectFailure, this, boost::placeholders::_1), failure_signal_.connect(callback)); + } + + virtual void setQueueSize( uint32_t new_queue_size ) + { + queue_size_ = new_queue_size; + } + + virtual uint32_t getQueueSize() + { + return queue_size_; + } + + +private: + + void init() + { + message_count_ = 0; + successful_transform_count_ = 0; + failed_out_the_back_count_ = 0; + transform_message_count_ = 0; + incoming_message_count_ = 0; + dropped_message_count_ = 0; + time_tolerance_ = ros::Duration(0.0); + warned_about_empty_frame_id_ = false; + expected_success_count_ = 1; + + callback_handle_ = bc_.addTransformableCallback(boost::bind(&MessageFilter::transformable, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4, boost::placeholders::_5)); + } + + void transformable(tf2::TransformableRequestHandle request_handle, const std::string& /* target_frame */, const std::string& /* source_frame */, + ros::Time /* time */, tf2::TransformableResult result) + { + namespace mt = ros::message_traits; + + boost::upgrade_lock< boost::shared_mutex > lock(messages_mutex_); + + // find the message this request is associated with + typename L_MessageInfo::iterator msg_it = messages_.begin(); + typename L_MessageInfo::iterator msg_end = messages_.end(); + for (; msg_it != msg_end; ++msg_it) + { + MessageInfo& info = *msg_it; + V_TransformableRequestHandle::const_iterator handle_it = std::find(info.handles.begin(), info.handles.end(), request_handle); + if (handle_it != info.handles.end()) + { + // found msg_it + ++info.success_count; + break; + } + } + + if (msg_it == msg_end) + { + return; + } + + const MessageInfo& info = *msg_it; + if (info.success_count < expected_success_count_) + { + return; + } + + bool can_transform = true; + const MConstPtr& message = info.event.getMessage(); + std::string frame_id = stripSlash(mt::FrameId::value(*message)); + ros::Time stamp = mt::TimeStamp::value(*message); + + if (result == tf2::TransformAvailable) + { + boost::mutex::scoped_lock frames_lock(target_frames_mutex_); + // make sure we can still perform all the necessary transforms + typename V_string::iterator it = target_frames_.begin(); + typename V_string::iterator end = target_frames_.end(); + for (; it != end; ++it) + { + const std::string& target = *it; + if (!bc_.canTransform(target, frame_id, stamp)) + { + can_transform = false; + break; + } + + if (!time_tolerance_.isZero()) + { + if (!bc_.canTransform(target, frame_id, stamp + time_tolerance_)) + { + can_transform = false; + break; + } + } + } + } + else + { + can_transform = false; + } + + // We will be mutating messages now, require unique lock + boost::upgrade_to_unique_lock< boost::shared_mutex > uniqueLock(lock); + if (can_transform) + { + TF2_ROS_MESSAGEFILTER_DEBUG("Message ready in frame %s at time %.3f, count now %d", frame_id.c_str(), stamp.toSec(), message_count_ - 1); + + ++successful_transform_count_; + + messageReady(info.event); + + } + else + { + ++dropped_message_count_; + + TF2_ROS_MESSAGEFILTER_DEBUG("Discarding message in frame %s at time %.3f, count now %d", frame_id.c_str(), stamp.toSec(), message_count_ - 1); + messageDropped(info.event, filter_failure_reasons::Unknown); + } + + messages_.erase(msg_it); + --message_count_; + } + + /** + * \brief Callback that happens when we receive a message on the message topic + */ + void incomingMessage(const ros::MessageEvent& evt) + { + add(evt); + } + + void checkFailures() + { + if (next_failure_warning_.isZero()) + { + next_failure_warning_ = ros::WallTime::now() + ros::WallDuration(15); + } + + if (ros::WallTime::now() >= next_failure_warning_) + { + if (incoming_message_count_ - message_count_ == 0) + { + return; + } + + double dropped_pct = (double)dropped_message_count_ / (double)(incoming_message_count_ - message_count_); + if (dropped_pct > 0.95) + { + TF2_ROS_MESSAGEFILTER_WARN("Dropped %.2f%% of messages so far. Please turn the [%s.message_notifier] rosconsole logger to DEBUG for more information.", dropped_pct*100, ROSCONSOLE_DEFAULT_NAME); + next_failure_warning_ = ros::WallTime::now() + ros::WallDuration(60); + + if ((double)failed_out_the_back_count_ / (double)dropped_message_count_ > 0.5) + { + TF2_ROS_MESSAGEFILTER_WARN(" The majority of dropped messages were due to messages growing older than the TF cache time. The last message's timestamp was: %f, and the last frame_id was: %s", last_out_the_back_stamp_.toSec(), last_out_the_back_frame_.c_str()); + } + } + } + } + + struct CBQueueCallback : public ros::CallbackInterface + { + CBQueueCallback(MessageFilter* filter, const MEvent& event, bool success, FilterFailureReason reason) + : event_(event) + , filter_(filter) + , reason_(reason) + , success_(success) + {} + + + virtual CallResult call() + { + if (success_) + { + filter_->signalMessage(event_); + } + else + { + filter_->signalFailure(event_, reason_); + } + + return Success; + } + + private: + MEvent event_; + MessageFilter* filter_; + FilterFailureReason reason_; + bool success_; + }; + + void messageDropped(const MEvent& evt, FilterFailureReason reason) + { + if (callback_queue_) + { + ros::CallbackInterfacePtr cb(new CBQueueCallback(this, evt, false, reason)); + callback_queue_->addCallback(cb, (uint64_t)this); + } + else + { + signalFailure(evt, reason); + } + } + + void messageReady(const MEvent& evt) + { + if (callback_queue_) + { + ros::CallbackInterfacePtr cb(new CBQueueCallback(this, evt, true, filter_failure_reasons::Unknown)); + callback_queue_->addCallback(cb, (uint64_t)this); + } + else + { + this->signalMessage(evt); + } + } + + void disconnectFailure(const message_filters::Connection& c) + { + boost::mutex::scoped_lock lock(failure_signal_mutex_); + c.getBoostConnection().disconnect(); + } + + void signalFailure(const MEvent& evt, FilterFailureReason reason) + { + boost::mutex::scoped_lock lock(failure_signal_mutex_); + failure_signal_(evt.getMessage(), reason); + } + + static + std::string stripSlash(const std::string& in) + { + if ( !in.empty() && (in[0] == '/')) + { + std::string out = in; + out.erase(0, 1); + return out; + } + return in; + } + + tf2::BufferCore& bc_; ///< The Transformer used to determine if transformation data is available + V_string target_frames_; ///< The frames we need to be able to transform to before a message is ready + std::string target_frames_string_; + boost::mutex target_frames_mutex_; ///< A mutex to protect access to the target_frames_ list and target_frames_string. + uint32_t queue_size_; ///< The maximum number of messages we queue up + tf2::TransformableCallbackHandle callback_handle_; + + typedef std::vector V_TransformableRequestHandle; + struct MessageInfo + { + MessageInfo() + : success_count(0) + {} + + MEvent event; + V_TransformableRequestHandle handles; + uint32_t success_count; + }; + typedef std::list L_MessageInfo; + L_MessageInfo messages_; + uint32_t message_count_; ///< The number of messages in the list. Used because \.size() may have linear cost + boost::shared_mutex messages_mutex_; ///< The mutex used for locking message list operations + uint32_t expected_success_count_; + + bool warned_about_empty_frame_id_; + + uint64_t successful_transform_count_; + uint64_t failed_out_the_back_count_; + uint64_t transform_message_count_; + uint64_t incoming_message_count_; + uint64_t dropped_message_count_; + + ros::Time last_out_the_back_stamp_; + std::string last_out_the_back_frame_; + + ros::WallTime next_failure_warning_; + + ros::Duration time_tolerance_; ///< Provide additional tolerance on time for messages which are stamped but can have associated duration + + message_filters::Connection message_connection_; + + FailureSignal failure_signal_; + boost::mutex failure_signal_mutex_; + + ros::CallbackQueueInterface* callback_queue_; +}; + +} // namespace tf2 + +#endif diff --git a/navigations/geometry2/tf2_ros/include/tf2_ros/static_transform_broadcaster.h b/navigations/geometry2/tf2_ros/include/tf2_ros/static_transform_broadcaster.h new file mode 100755 index 0000000..bc7be91 --- /dev/null +++ b/navigations/geometry2/tf2_ros/include/tf2_ros/static_transform_broadcaster.h @@ -0,0 +1,75 @@ +/* + * Copyright (c) 2008, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + + +/** \author Tully Foote */ + +#ifndef TF2_ROS_STATICTRANSFORMBROADCASTER_H +#define TF2_ROS_STATICTRANSFORMBROADCASTER_H + + + +#include "ros/ros.h" +#include "geometry_msgs/TransformStamped.h" +#include "tf2_msgs/TFMessage.h" + +namespace tf2_ros +{ + + +/** \brief This class provides an easy way to publish coordinate frame transform information. + * It will handle all the messaging and stuffing of messages. And the function prototypes lay out all the + * necessary data needed for each message. */ + +class StaticTransformBroadcaster{ +public: + /** \brief Constructor (needs a ros::Node reference) */ + StaticTransformBroadcaster(); + + /** \brief Send a TransformStamped message + * The stamped data structure includes frame_id, and time, and parent_id already. */ + void sendTransform(const geometry_msgs::TransformStamped & transform) { + sendTransform(std::vector({transform})); + } + + /** \brief Send a vector of TransformStamped messages + * The stamped data structure includes frame_id, and time, and parent_id already. */ + void sendTransform(const std::vector & transforms); + +private: + /// Internal reference to ros::Node + ros::NodeHandle node_; + ros::Publisher publisher_; + tf2_msgs::TFMessage net_message_; + +}; + +} + +#endif //TF_STATICTRANSFORMBROADCASTER_H diff --git a/navigations/geometry2/tf2_ros/include/tf2_ros/transform_broadcaster.h b/navigations/geometry2/tf2_ros/include/tf2_ros/transform_broadcaster.h new file mode 100755 index 0000000..4f5f35c --- /dev/null +++ b/navigations/geometry2/tf2_ros/include/tf2_ros/transform_broadcaster.h @@ -0,0 +1,78 @@ +/* + * Copyright (c) 2008, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + + +/** \author Tully Foote */ + +#ifndef TF2_ROS_TRANSFORMBROADCASTER_H +#define TF2_ROS_TRANSFORMBROADCASTER_H + + + +#include "ros/ros.h" +#include "geometry_msgs/TransformStamped.h" +namespace tf2_ros +{ + + +/** \brief This class provides an easy way to publish coordinate frame transform information. + * It will handle all the messaging and stuffing of messages. And the function prototypes lay out all the + * necessary data needed for each message. */ + +class TransformBroadcaster{ +public: + /** \brief Constructor (needs a ros::Node reference) */ + TransformBroadcaster(); + + /** \brief Send a StampedTransform + * The stamped data structure includes frame_id, and time, and parent_id already. */ + // void sendTransform(const StampedTransform & transform); + + /** \brief Send a vector of StampedTransforms + * The stamped data structure includes frame_id, and time, and parent_id already. */ + //void sendTransform(const std::vector & transforms); + + /** \brief Send a TransformStamped message + * The stamped data structure includes frame_id, and time, and parent_id already. */ + void sendTransform(const geometry_msgs::TransformStamped & transform); + + /** \brief Send a vector of TransformStamped messages + * The stamped data structure includes frame_id, and time, and parent_id already. */ + void sendTransform(const std::vector & transforms); + +private: + /// Internal reference to ros::Node + ros::NodeHandle node_; + ros::Publisher publisher_; + +}; + +} + +#endif //TF_TRANSFORMBROADCASTER_H diff --git a/navigations/geometry2/tf2_ros/include/tf2_ros/transform_listener.h b/navigations/geometry2/tf2_ros/include/tf2_ros/transform_listener.h new file mode 100755 index 0000000..69f555d --- /dev/null +++ b/navigations/geometry2/tf2_ros/include/tf2_ros/transform_listener.h @@ -0,0 +1,92 @@ +/* + * Copyright (c) 2008, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +/** \author Tully Foote */ + +#ifndef TF2_ROS_TRANSFORMLISTENER_H +#define TF2_ROS_TRANSFORMLISTENER_H + +#include "std_msgs/Empty.h" +#include "tf2_msgs/TFMessage.h" +#include "ros/ros.h" +#include "ros/callback_queue.h" + +#include "tf2_ros/buffer.h" + +#include "boost/thread.hpp" + +namespace tf2_ros{ + +/** \brief This class provides an easy way to request and receive coordinate frame transform information. + */ +class TransformListener +{ + +public: + /**@brief Constructor for transform listener */ + TransformListener(tf2::BufferCore& buffer, bool spin_thread = true, + ros::TransportHints transport_hints = ros::TransportHints()); + TransformListener(tf2::BufferCore& buffer, const ros::NodeHandle& nh, bool spin_thread = true, + ros::TransportHints transport_hints = ros::TransportHints()); + + ~TransformListener(); + +private: + + /// Initialize this transform listener, subscribing, advertising services, etc. + void init(); + void initWithThread(); + + /// Callback function for ros message subscription + void subscription_callback(const ros::MessageEvent& msg_evt); + void static_subscription_callback(const ros::MessageEvent& msg_evt); + void subscription_callback_impl(const ros::MessageEvent& msg_evt, bool is_static); + + ros::CallbackQueue tf_message_callback_queue_; + boost::thread* dedicated_listener_thread_; + ros::NodeHandle node_; + ros::Subscriber message_subscriber_tf_; + ros::Subscriber message_subscriber_tf_static_; + tf2::BufferCore& buffer_; + bool using_dedicated_thread_; + ros::TransportHints transport_hints_; + ros::Time last_update_; + + void dedicatedListenerThread() + { + while (using_dedicated_thread_) + { + tf_message_callback_queue_.callAvailable(ros::WallDuration(0.01)); + } + }; + +}; +} + +#endif //TF_TRANSFORMLISTENER_H diff --git a/navigations/geometry2/tf2_ros/package.xml b/navigations/geometry2/tf2_ros/package.xml new file mode 100755 index 0000000..daf58e5 --- /dev/null +++ b/navigations/geometry2/tf2_ros/package.xml @@ -0,0 +1,43 @@ + + tf2_ros + 0.7.6 + + This package contains the ROS bindings for the tf2 library, for both Python and C++. + + Eitan Marder-Eppstein + Wim Meeussen + Tully Foote + BSD + + http://www.ros.org/wiki/tf2_ros + + catkin + + actionlib + actionlib_msgs + geometry_msgs + message_filters + roscpp + rosgraph + rospy + std_msgs + tf2 + tf2_msgs + tf2_py + xmlrpcpp + + actionlib + actionlib_msgs + geometry_msgs + message_filters + roscpp + rosgraph + rospy + std_msgs + tf2 + tf2_msgs + tf2_py + xmlrpcpp + + rostest + diff --git a/navigations/geometry2/tf2_ros/rosdoc.yaml b/navigations/geometry2/tf2_ros/rosdoc.yaml new file mode 100755 index 0000000..0efc7fd --- /dev/null +++ b/navigations/geometry2/tf2_ros/rosdoc.yaml @@ -0,0 +1,8 @@ + - builder: doxygen + name: C++ API + output_dir: c++ + file_patterns: '*.c *.cpp *.h *.cc *.hh *.dox' + - builder: sphinx + name: Python API + output_dir: python + sphinx_root_dir: doc diff --git a/navigations/geometry2/tf2_ros/setup.py b/navigations/geometry2/tf2_ros/setup.py new file mode 100755 index 0000000..a621cec --- /dev/null +++ b/navigations/geometry2/tf2_ros/setup.py @@ -0,0 +1,13 @@ +#!/usr/bin/env python + +from setuptools import setup +from catkin_pkg.python_setup import generate_distutils_setup + +d = generate_distutils_setup( + packages=['tf2_ros'], + package_dir={'': 'src'}, + requires=['rospy', 'actionlib', 'actionlib_msgs', 'tf2_msgs', + 'tf2_py', 'geometry_msgs'] +) + +setup(**d) diff --git a/navigations/geometry2/tf2_ros/src/buffer.cpp b/navigations/geometry2/tf2_ros/src/buffer.cpp new file mode 100755 index 0000000..8030301 --- /dev/null +++ b/navigations/geometry2/tf2_ros/src/buffer.cpp @@ -0,0 +1,201 @@ +/* + * Copyright (c) 2008, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +/** \author Wim Meeussen */ + + +#include "tf2_ros/buffer.h" + +#include +#include + +namespace tf2_ros +{ + +static const double CAN_TRANSFORM_POLLING_SCALE = 0.01; + +Buffer::Buffer(ros::Duration cache_time, bool debug) : + BufferCore(cache_time) +{ + if(debug && !ros::service::exists("~tf2_frames", false)) + { + ros::NodeHandle n("~"); + frames_server_ = n.advertiseService("tf2_frames", &Buffer::getFrames, this); + } +} + +geometry_msgs::TransformStamped +Buffer::lookupTransform(const std::string& target_frame, const std::string& source_frame, + const ros::Time& time, const ros::Duration timeout) const +{ + canTransform(target_frame, source_frame, time, timeout); + return lookupTransform(target_frame, source_frame, time); +} + + +geometry_msgs::TransformStamped +Buffer::lookupTransform(const std::string& target_frame, const ros::Time& target_time, + const std::string& source_frame, const ros::Time& source_time, + const std::string& fixed_frame, const ros::Duration timeout) const +{ + canTransform(target_frame, target_time, source_frame, source_time, fixed_frame, timeout); + return lookupTransform(target_frame, target_time, source_frame, source_time, fixed_frame); +} + +/** This is a workaround for the case that we're running inside of + rospy and ros::Time is not initialized inside the c++ instance. + This makes the system fall back to Wall time if not initialized. +*/ +ros::Time now_fallback_to_wall() +{ + try + { + return ros::Time::now(); + } + catch (ros::TimeNotInitializedException ex) + { + ros::WallTime wt = ros::WallTime::now(); + return ros::Time(wt.sec, wt.nsec); + } +} + +/** This is a workaround for the case that we're running inside of + rospy and ros::Time is not initialized inside the c++ instance. + This makes the system fall back to Wall time if not initialized. + https://github.com/ros/geometry/issues/30 +*/ +void sleep_fallback_to_wall(const ros::Duration& d) +{ + try + { + d.sleep(); + } + catch (ros::TimeNotInitializedException ex) + { + ros::WallDuration wd = ros::WallDuration(d.sec, d.nsec); + wd.sleep(); + } +} + +void conditionally_append_timeout_info(std::string * errstr, const ros::Time& start_time, + const ros::Duration& timeout) +{ + if (errstr) + { + std::stringstream ss; + ss << ". canTransform returned after "<< (now_fallback_to_wall() - start_time).toSec() \ + <<" timeout was " << timeout.toSec() << "."; + (*errstr) += ss.str(); + } +} + +bool +Buffer::canTransform(const std::string& target_frame, const std::string& source_frame, + const ros::Time& time, const ros::Duration timeout, std::string* errstr) const +{ + // Clear the errstr before populating it if it's valid. + if (errstr) + { + errstr->clear(); + } + + if (!checkAndErrorDedicatedThreadPresent(errstr)) + return false; + + // poll for transform if timeout is set + ros::Time start_time = now_fallback_to_wall(); + const ros::Duration sleep_duration = timeout * CAN_TRANSFORM_POLLING_SCALE; + while (now_fallback_to_wall() < start_time + timeout && + !canTransform(target_frame, source_frame, time) && + (now_fallback_to_wall()+ros::Duration(3.0) >= start_time) && //don't wait when we detect a bag loop + (ros::ok() || !ros::isInitialized())) // Make sure we haven't been stopped (won't work for pytf) + { + sleep_fallback_to_wall(sleep_duration); + } + bool retval = canTransform(target_frame, source_frame, time, errstr); + conditionally_append_timeout_info(errstr, start_time, timeout); + return retval; +} + + +bool +Buffer::canTransform(const std::string& target_frame, const ros::Time& target_time, + const std::string& source_frame, const ros::Time& source_time, + const std::string& fixed_frame, const ros::Duration timeout, std::string* errstr) const +{ + // Clear the errstr before populating it if it's valid. + if (errstr) + { + errstr->clear(); + } + + if (!checkAndErrorDedicatedThreadPresent(errstr)) + return false; + + // poll for transform if timeout is set + ros::Time start_time = now_fallback_to_wall(); + const ros::Duration sleep_duration = timeout * CAN_TRANSFORM_POLLING_SCALE; + while (now_fallback_to_wall() < start_time + timeout && + !canTransform(target_frame, target_time, source_frame, source_time, fixed_frame) && + (now_fallback_to_wall()+ros::Duration(3.0) >= start_time) && //don't wait when we detect a bag loop + (ros::ok() || !ros::isInitialized())) // Make sure we haven't been stopped (won't work for pytf) + { + sleep_fallback_to_wall(sleep_duration); + } + bool retval = canTransform(target_frame, target_time, source_frame, source_time, fixed_frame, errstr); + conditionally_append_timeout_info(errstr, start_time, timeout); + return retval; +} + + +bool Buffer::getFrames(tf2_msgs::FrameGraph::Request& req, tf2_msgs::FrameGraph::Response& res) +{ + res.frame_yaml = allFramesAsYAML(); + return true; +} + + + +bool Buffer::checkAndErrorDedicatedThreadPresent(std::string* error_str) const +{ + if (isUsingDedicatedThread()) + return true; + + + + if (error_str) + *error_str = tf2_ros::threading_error; + + ROS_ERROR("%s", tf2_ros::threading_error.c_str()); + return false; +} + + + +} diff --git a/navigations/geometry2/tf2_ros/src/buffer_client.cpp b/navigations/geometry2/tf2_ros/src/buffer_client.cpp new file mode 100755 index 0000000..98c56dd --- /dev/null +++ b/navigations/geometry2/tf2_ros/src/buffer_client.cpp @@ -0,0 +1,162 @@ +/********************************************************************* +* +* Software License Agreement (BSD License) +* +* Copyright (c) 2009, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of Willow Garage, Inc. nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* +* Author: Eitan Marder-Eppstein +*********************************************************************/ +#include + +namespace tf2_ros +{ + BufferClient::BufferClient(std::string ns, double check_frequency, ros::Duration timeout_padding): + client_(ns), + check_frequency_(check_frequency), + timeout_padding_(timeout_padding) + { + } + + geometry_msgs::TransformStamped BufferClient::lookupTransform(const std::string& target_frame, const std::string& source_frame, + const ros::Time& time, const ros::Duration timeout) const + { + //populate the goal message + tf2_msgs::LookupTransformGoal goal; + goal.target_frame = target_frame; + goal.source_frame = source_frame; + goal.source_time = time; + goal.timeout = timeout; + goal.advanced = false; + + return processGoal(goal); + } + + geometry_msgs::TransformStamped BufferClient::lookupTransform(const std::string& target_frame, const ros::Time& target_time, + const std::string& source_frame, const ros::Time& source_time, + const std::string& fixed_frame, const ros::Duration timeout) const + { + //populate the goal message + tf2_msgs::LookupTransformGoal goal; + goal.target_frame = target_frame; + goal.source_frame = source_frame; + goal.source_time = source_time; + goal.timeout = timeout; + goal.target_time = target_time; + goal.fixed_frame = fixed_frame; + goal.advanced = true; + + return processGoal(goal); + } + + geometry_msgs::TransformStamped BufferClient::processGoal(const tf2_msgs::LookupTransformGoal& goal) const + { + client_.sendGoal(goal); + + //this shouldn't happen, but could in rare cases where the server hangs + if(!client_.waitForResult(goal.timeout + timeout_padding_)) + { + //make sure to cancel the goal the server is pursuing + client_.cancelGoal(); + throw tf2::TimeoutException("The LookupTransform goal sent to the BufferServer did not come back in the specified time. Something is likely wrong with the server."); + } + + if(client_.getState() != actionlib::SimpleClientGoalState::SUCCEEDED) + throw tf2::TimeoutException("The LookupTransform goal sent to the BufferServer did not come back with SUCCEEDED status. Something is likely wrong with the server."); + + //process the result for errors and return it + return processResult(*client_.getResult()); + } + + geometry_msgs::TransformStamped BufferClient::processResult(const tf2_msgs::LookupTransformResult& result) const + { + //if there's no error, then we'll just return the transform + if(result.error.error != result.error.NO_ERROR){ + //otherwise, we'll have to throw the appropriate exception + if(result.error.error == result.error.LOOKUP_ERROR) + throw tf2::LookupException(result.error.error_string); + + if(result.error.error == result.error.CONNECTIVITY_ERROR) + throw tf2::ConnectivityException(result.error.error_string); + + if(result.error.error == result.error.EXTRAPOLATION_ERROR) + throw tf2::ExtrapolationException(result.error.error_string); + + if(result.error.error == result.error.INVALID_ARGUMENT_ERROR) + throw tf2::InvalidArgumentException(result.error.error_string); + + if(result.error.error == result.error.TIMEOUT_ERROR) + throw tf2::TimeoutException(result.error.error_string); + + throw tf2::TransformException(result.error.error_string); + } + + return result.transform; + } + + bool BufferClient::canTransform(const std::string& target_frame, const std::string& source_frame, + const ros::Time& time, const ros::Duration timeout, std::string* errstr) const + { + try + { + lookupTransform(target_frame, source_frame, time, timeout); + return true; + } + catch(tf2::TransformException& ex) + { + if(errstr) + { + errstr->clear(); + *errstr = ex.what(); + } + return false; + } + } + + bool BufferClient::canTransform(const std::string& target_frame, const ros::Time& target_time, + const std::string& source_frame, const ros::Time& source_time, + const std::string& fixed_frame, const ros::Duration timeout, std::string* errstr) const + { + try + { + lookupTransform(target_frame, target_time, source_frame, source_time, fixed_frame, timeout); + return true; + } + catch(tf2::TransformException& ex) + { + if(errstr) + { + errstr->clear(); + *errstr = ex.what(); + } + return false; + } + } +}; diff --git a/navigations/geometry2/tf2_ros/src/buffer_server.cpp b/navigations/geometry2/tf2_ros/src/buffer_server.cpp new file mode 100755 index 0000000..898c803 --- /dev/null +++ b/navigations/geometry2/tf2_ros/src/buffer_server.cpp @@ -0,0 +1,222 @@ +/********************************************************************* +* +* Software License Agreement (BSD License) +* +* Copyright (c) 2009, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of Willow Garage, Inc. nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* +* Author: Eitan Marder-Eppstein +*********************************************************************/ +#include + +namespace tf2_ros +{ + BufferServer::BufferServer(const Buffer& buffer, const std::string& ns, bool auto_start, ros::Duration check_period): + buffer_(buffer), + server_(ros::NodeHandle(), + ns, + boost::bind(&BufferServer::goalCB, this, boost::placeholders::_1), + boost::bind(&BufferServer::cancelCB, this, boost::placeholders::_1), + auto_start) + { + ros::NodeHandle n; + check_timer_ = n.createTimer(check_period, boost::bind(&BufferServer::checkTransforms, this, boost::placeholders::_1)); + } + + void BufferServer::checkTransforms(const ros::TimerEvent& e) + { + (void) e; //Unused + boost::mutex::scoped_lock l(mutex_); + for(std::list::iterator it = active_goals_.begin(); it != active_goals_.end();) + { + GoalInfo& info = *it; + + //we want to lookup a transform if the time on the goal + //has expired, or a transform is available + if(canTransform(info.handle) || info.end_time < ros::Time::now()) + { + tf2_msgs::LookupTransformResult result; + + //try to populate the result, catching exceptions if they occur + try + { + result.transform = lookupTransform(info.handle); + } + catch (tf2::ConnectivityException &ex) + { + result.error.error = result.error.CONNECTIVITY_ERROR; + result.error.error_string = ex.what(); + } + catch (tf2::LookupException &ex) + { + result.error.error = result.error.LOOKUP_ERROR; + result.error.error_string = ex.what(); + } + catch (tf2::ExtrapolationException &ex) + { + result.error.error = result.error.EXTRAPOLATION_ERROR; + result.error.error_string = ex.what(); + } + catch (tf2::InvalidArgumentException &ex) + { + result.error.error = result.error.INVALID_ARGUMENT_ERROR; + result.error.error_string = ex.what(); + } + catch (tf2::TimeoutException &ex) + { + result.error.error = result.error.TIMEOUT_ERROR; + result.error.error_string = ex.what(); + } + catch (tf2::TransformException &ex) + { + result.error.error = result.error.TRANSFORM_ERROR; + result.error.error_string = ex.what(); + } + + //make sure to pass the result to the client + //even failed transforms are considered a success + //since the request was successfully processed + info.handle.setSucceeded(result); + it = active_goals_.erase(it); + } + else + ++it; + } + } + + void BufferServer::cancelCB(GoalHandle gh) + { + boost::mutex::scoped_lock l(mutex_); + //we need to find the goal in the list and remove it... also setting it as canceled + //if its not in the list, we won't do anything since it will have already been set + //as completed + for(std::list::iterator it = active_goals_.begin(); it != active_goals_.end();) + { + GoalInfo& info = *it; + if(info.handle == gh) + { + info.handle.setCanceled(); + it = active_goals_.erase(it); + return; + } + else + ++it; + } + } + + void BufferServer::goalCB(GoalHandle gh) + { + //we'll accept all goals we get + gh.setAccepted(); + + //if the transform isn't immediately available, we'll push it onto our list to check + //along with the time that the goal will end + GoalInfo goal_info; + goal_info.handle = gh; + goal_info.end_time = ros::Time::now() + gh.getGoal()->timeout; + + //we can do a quick check here to see if the transform is valid + //we'll also do this if the end time has been reached + if(canTransform(gh) || goal_info.end_time <= ros::Time::now()) + { + tf2_msgs::LookupTransformResult result; + try + { + result.transform = lookupTransform(gh); + } + catch (tf2::ConnectivityException &ex) + { + result.error.error = result.error.CONNECTIVITY_ERROR; + result.error.error_string = ex.what(); + } + catch (tf2::LookupException &ex) + { + result.error.error = result.error.LOOKUP_ERROR; + result.error.error_string = ex.what(); + } + catch (tf2::ExtrapolationException &ex) + { + result.error.error = result.error.EXTRAPOLATION_ERROR; + result.error.error_string = ex.what(); + } + catch (tf2::InvalidArgumentException &ex) + { + result.error.error = result.error.INVALID_ARGUMENT_ERROR; + result.error.error_string = ex.what(); + } + catch (tf2::TimeoutException &ex) + { + result.error.error = result.error.TIMEOUT_ERROR; + result.error.error_string = ex.what(); + } + catch (tf2::TransformException &ex) + { + result.error.error = result.error.TRANSFORM_ERROR; + result.error.error_string = ex.what(); + } + + gh.setSucceeded(result); + return; + } + + boost::mutex::scoped_lock l(mutex_); + active_goals_.push_back(goal_info); + } + + bool BufferServer::canTransform(GoalHandle gh) + { + const tf2_msgs::LookupTransformGoal::ConstPtr& goal = gh.getGoal(); + + //check whether we need to used the advanced or simple api + if(!goal->advanced) + return buffer_.canTransform(goal->target_frame, goal->source_frame, goal->source_time); + + return buffer_.canTransform(goal->target_frame, goal->target_time, + goal->source_frame, goal->source_time, goal->fixed_frame); + } + + geometry_msgs::TransformStamped BufferServer::lookupTransform(GoalHandle gh) + { + const tf2_msgs::LookupTransformGoal::ConstPtr& goal = gh.getGoal(); + + //check whether we need to used the advanced or simple api + if(!goal->advanced) + return buffer_.lookupTransform(goal->target_frame, goal->source_frame, goal->source_time); + + return buffer_.lookupTransform(goal->target_frame, goal->target_time, + goal->source_frame, goal->source_time, goal->fixed_frame); + } + + void BufferServer::start() + { + server_.start(); + } + +}; diff --git a/navigations/geometry2/tf2_ros/src/buffer_server_main.cpp b/navigations/geometry2/tf2_ros/src/buffer_server_main.cpp new file mode 100755 index 0000000..85a79c2 --- /dev/null +++ b/navigations/geometry2/tf2_ros/src/buffer_server_main.cpp @@ -0,0 +1,71 @@ +/********************************************************************* +* +* Software License Agreement (BSD License) +* +* Copyright (c) 2009, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of Willow Garage, Inc. nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* +* Author: Wim Meeussen +*********************************************************************/ +#include +#include +#include + +int main(int argc, char** argv) +{ + ros::init(argc, argv, "tf_buffer"); + ros::NodeHandle nh; + + double buffer_size; + nh.param("buffer_size", buffer_size, 120.0); + + bool publish_frame_service; + nh.param("publish_frame_service", publish_frame_service, false); + + // Legacy behavior re: #209 + bool use_node_namespace; + nh.param("use_node_namespace", use_node_namespace, false); + std::string node_name; + if (use_node_namespace) + { + node_name = ros::this_node::getName(); + } + else + { + node_name = "tf2_buffer_server"; + } + + tf2_ros::Buffer buffer_core(ros::Duration(buffer_size), publish_frame_service); + tf2_ros::TransformListener listener(buffer_core); + tf2_ros::BufferServer buffer_server(buffer_core, node_name , false); + buffer_server.start(); + + ros::spin(); +} diff --git a/navigations/geometry2/tf2_ros/src/static_transform_broadcaster.cpp b/navigations/geometry2/tf2_ros/src/static_transform_broadcaster.cpp new file mode 100755 index 0000000..2e20842 --- /dev/null +++ b/navigations/geometry2/tf2_ros/src/static_transform_broadcaster.cpp @@ -0,0 +1,64 @@ +/* + * Copyright (c) 2008, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + + +/** \author Tully Foote */ + + +#include "ros/ros.h" +#include "tf2_msgs/TFMessage.h" +#include "tf2_ros/static_transform_broadcaster.h" +#include + +namespace tf2_ros { + +StaticTransformBroadcaster::StaticTransformBroadcaster() +{ + publisher_ = node_.advertise("/tf_static", 100, true); +}; + +void StaticTransformBroadcaster::sendTransform(const std::vector & msgtf) +{ + for (const geometry_msgs::TransformStamped& input : msgtf) + { + auto predicate = [&input](const geometry_msgs::TransformStamped existing) { + return input.child_frame_id == existing.child_frame_id; + }; + auto existing = std::find_if(net_message_.transforms.begin(), net_message_.transforms.end(), predicate); + + if (existing != net_message_.transforms.end()) + *existing = input; + else + net_message_.transforms.push_back(input); + } + + publisher_.publish(net_message_); +} + +} diff --git a/navigations/geometry2/tf2_ros/src/static_transform_broadcaster_program.cpp b/navigations/geometry2/tf2_ros/src/static_transform_broadcaster_program.cpp new file mode 100755 index 0000000..3485d1d --- /dev/null +++ b/navigations/geometry2/tf2_ros/src/static_transform_broadcaster_program.cpp @@ -0,0 +1,145 @@ +/* + * Copyright (c) 2008, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include +#include "tf2_ros/static_transform_broadcaster.h" + + +bool validateXmlRpcTf(XmlRpc::XmlRpcValue tf_data) { + // Validate a TF stored in XML RPC format: ensures the appropriate fields + // exist. Note this does not check data types. + return tf_data.hasMember("child_frame_id") && + tf_data.hasMember("header") && + tf_data["header"].hasMember("frame_id") && + tf_data.hasMember("transform") && + tf_data["transform"].hasMember("translation") && + tf_data["transform"]["translation"].hasMember("x") && + tf_data["transform"]["translation"].hasMember("y") && + tf_data["transform"]["translation"].hasMember("z") && + tf_data["transform"].hasMember("rotation") && + tf_data["transform"]["rotation"].hasMember("x") && + tf_data["transform"]["rotation"].hasMember("y") && + tf_data["transform"]["rotation"].hasMember("z") && + tf_data["transform"]["rotation"].hasMember("w"); +}; + +int main(int argc, char ** argv) +{ + //Initialize ROS + ros::init(argc, argv,"static_transform_publisher", ros::init_options::AnonymousName); + tf2_ros::StaticTransformBroadcaster broadcaster; + geometry_msgs::TransformStamped msg; + + if(argc == 10) + { + msg.transform.translation.x = atof(argv[1]); + msg.transform.translation.y = atof(argv[2]); + msg.transform.translation.z = atof(argv[3]); + msg.transform.rotation.x = atof(argv[4]); + msg.transform.rotation.y = atof(argv[5]); + msg.transform.rotation.z = atof(argv[6]); + msg.transform.rotation.w = atof(argv[7]); + msg.header.stamp = ros::Time::now(); + msg.header.frame_id = argv[8]; + msg.child_frame_id = argv[9]; + } + else if (argc == 9) + { + msg.transform.translation.x = atof(argv[1]); + msg.transform.translation.y = atof(argv[2]); + msg.transform.translation.z = atof(argv[3]); + + tf2::Quaternion quat; + quat.setRPY(atof(argv[6]), atof(argv[5]), atof(argv[4])); + msg.transform.rotation.x = quat.x(); + msg.transform.rotation.y = quat.y(); + msg.transform.rotation.z = quat.z(); + msg.transform.rotation.w = quat.w(); + + msg.header.stamp = ros::Time::now(); + msg.header.frame_id = argv[7]; + msg.child_frame_id = argv[8]; + } + else if (argc == 2) { + const std::string param_name = argv[1]; + ROS_INFO_STREAM("Looking for TF in parameter: " << param_name); + XmlRpc::XmlRpcValue tf_data; + + if (!ros::param::has(param_name) || !ros::param::get(param_name, tf_data)) { + ROS_FATAL_STREAM("Could not read TF from parameter server: " << param_name); + return -1; + } + + // Check that all required members are present & of the right type. + if (!validateXmlRpcTf(tf_data)) { + ROS_FATAL_STREAM("Could not validate XmlRpcC for TF data: " << tf_data); + return -1; + } + + msg.transform.translation.x = (double) tf_data["transform"]["translation"]["x"]; + msg.transform.translation.y = (double) tf_data["transform"]["translation"]["y"]; + msg.transform.translation.z = (double) tf_data["transform"]["translation"]["z"]; + msg.transform.rotation.x = (double) tf_data["transform"]["rotation"]["x"]; + msg.transform.rotation.y = (double) tf_data["transform"]["rotation"]["y"]; + msg.transform.rotation.z = (double) tf_data["transform"]["rotation"]["z"]; + msg.transform.rotation.w = (double) tf_data["transform"]["rotation"]["w"]; + msg.header.stamp = ros::Time::now(); + msg.header.frame_id = (std::string) tf_data["header"]["frame_id"]; + msg.child_frame_id = (std::string) tf_data["child_frame_id"]; + } + else + { + printf("A command line utility for manually sending a transform.\n"); + //printf("It will periodicaly republish the given transform. \n"); + printf("Usage: static_transform_publisher x y z qx qy qz qw frame_id child_frame_id \n"); + printf("OR \n"); + printf("Usage: static_transform_publisher x y z yaw pitch roll frame_id child_frame_id \n"); + printf("OR \n"); + printf("Usage: static_transform_publisher /param_name \n"); + printf("\nThis transform is the transform of the coordinate frame from frame_id into the coordinate frame \n"); + printf("of the child_frame_id. \n"); + ROS_ERROR("static_transform_publisher exited due to not having the right number of arguments"); + return -1; + } + + // Checks: frames should not be the same. + if (msg.header.frame_id == msg.child_frame_id) + { + ROS_FATAL("target_frame and source frame are the same (%s, %s) this cannot work", + msg.header.frame_id.c_str(), msg.child_frame_id.c_str()); + return 1; + } + + broadcaster.sendTransform(msg); + ROS_INFO("Spinning until killed publishing %s to %s", + msg.header.frame_id.c_str(), msg.child_frame_id.c_str()); + ros::spin(); + return 0; +}; diff --git a/navigations/geometry2/tf2_ros/src/tf2_ros/__init__.py b/navigations/geometry2/tf2_ros/src/tf2_ros/__init__.py new file mode 100755 index 0000000..af5642c --- /dev/null +++ b/navigations/geometry2/tf2_ros/src/tf2_ros/__init__.py @@ -0,0 +1,44 @@ +#! /usr/bin/python +#*********************************************************** +#* Software License Agreement (BSD License) +#* +#* Copyright (c) 2009, Willow Garage, Inc. +#* All rights reserved. +#* +#* Redistribution and use in source and binary forms, with or without +#* modification, are permitted provided that the following conditions +#* are met: +#* +#* * Redistributions of source code must retain the above copyright +#* notice, this list of conditions and the following disclaimer. +#* * Redistributions in binary form must reproduce the above +#* copyright notice, this list of conditions and the following +#* disclaimer in the documentation and/or other materials provided +#* with the distribution. +#* * Neither the name of Willow Garage, Inc. nor the names of its +#* contributors may be used to endorse or promote products derived +#* from this software without specific prior written permission. +#* +#* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +#* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +#* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +#* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +#* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +#* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +#* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +#* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +#* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +#* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +#* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +#* POSSIBILITY OF SUCH DAMAGE. +#* +#* Author: Eitan Marder-Eppstein +#*********************************************************** +from __future__ import absolute_import +from tf2_py import * +from .buffer_interface import * +from .buffer import * +from .buffer_client import * +from .transform_listener import * +from .transform_broadcaster import * +from .static_transform_broadcaster import * diff --git a/navigations/geometry2/tf2_ros/src/tf2_ros/__pycache__/buffer.cpython-38.pyc b/navigations/geometry2/tf2_ros/src/tf2_ros/__pycache__/buffer.cpython-38.pyc new file mode 100644 index 0000000..cb47bdd Binary files /dev/null and b/navigations/geometry2/tf2_ros/src/tf2_ros/__pycache__/buffer.cpython-38.pyc differ diff --git a/navigations/geometry2/tf2_ros/src/tf2_ros/__pycache__/buffer_client.cpython-38.pyc b/navigations/geometry2/tf2_ros/src/tf2_ros/__pycache__/buffer_client.cpython-38.pyc new file mode 100644 index 0000000..cbd1b39 Binary files /dev/null and b/navigations/geometry2/tf2_ros/src/tf2_ros/__pycache__/buffer_client.cpython-38.pyc differ diff --git a/navigations/geometry2/tf2_ros/src/tf2_ros/__pycache__/buffer_interface.cpython-38.pyc b/navigations/geometry2/tf2_ros/src/tf2_ros/__pycache__/buffer_interface.cpython-38.pyc new file mode 100644 index 0000000..8801da8 Binary files /dev/null and b/navigations/geometry2/tf2_ros/src/tf2_ros/__pycache__/buffer_interface.cpython-38.pyc differ diff --git a/navigations/geometry2/tf2_ros/src/tf2_ros/__pycache__/static_transform_broadcaster.cpython-38.pyc b/navigations/geometry2/tf2_ros/src/tf2_ros/__pycache__/static_transform_broadcaster.cpython-38.pyc new file mode 100644 index 0000000..c9ba81a Binary files /dev/null and b/navigations/geometry2/tf2_ros/src/tf2_ros/__pycache__/static_transform_broadcaster.cpython-38.pyc differ diff --git a/navigations/geometry2/tf2_ros/src/tf2_ros/__pycache__/transform_broadcaster.cpython-38.pyc b/navigations/geometry2/tf2_ros/src/tf2_ros/__pycache__/transform_broadcaster.cpython-38.pyc new file mode 100644 index 0000000..a6aa445 Binary files /dev/null and b/navigations/geometry2/tf2_ros/src/tf2_ros/__pycache__/transform_broadcaster.cpython-38.pyc differ diff --git a/navigations/geometry2/tf2_ros/src/tf2_ros/__pycache__/transform_listener.cpython-38.pyc b/navigations/geometry2/tf2_ros/src/tf2_ros/__pycache__/transform_listener.cpython-38.pyc new file mode 100644 index 0000000..7e8587d Binary files /dev/null and b/navigations/geometry2/tf2_ros/src/tf2_ros/__pycache__/transform_listener.cpython-38.pyc differ diff --git a/navigations/geometry2/tf2_ros/src/tf2_ros/buffer.py b/navigations/geometry2/tf2_ros/src/tf2_ros/buffer.py new file mode 100755 index 0000000..ff23d26 --- /dev/null +++ b/navigations/geometry2/tf2_ros/src/tf2_ros/buffer.py @@ -0,0 +1,162 @@ +# Copyright (c) 2008, Willow Garage, Inc. +# All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# * Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in the +# documentation and/or other materials provided with the distribution. +# * Neither the name of the Willow Garage, Inc. nor the names of its +# contributors may be used to endorse or promote products derived from +# this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. + +# author: Wim Meeussen + +import rospy +import tf2_py as tf2 +import tf2_ros +from tf2_msgs.srv import FrameGraph, FrameGraphResponse +import rosgraph.masterapi + +DEFAULT_CAN_TRANSFORM_POLLING_SCALE = 0.01 + +class Buffer(tf2.BufferCore, tf2_ros.BufferInterface): + """ + Standard implementation of the :class:`tf2_ros.BufferInterface` abstract data type. + + Inherits from :class:`tf2_ros.buffer_interface.BufferInterface` and :class:`tf2.BufferCore`. + + Stores known frames and optionally offers a ROS service, "tf2_frames", which responds to client requests + with a response containing a :class:`tf2_msgs.FrameGraph` representing the relationship of + known frames. + """ + + def __init__(self, cache_time = None, debug = True): + """ + .. function:: __init__(cache_time = None, debug = True) + + Constructor. + + :param cache_time: (Optional) How long to retain past information in BufferCore. + :param debug: (Optional) If true, check if another tf2_frames service has been advertised. + """ + if cache_time != None: + tf2.BufferCore.__init__(self, cache_time) + else: + tf2.BufferCore.__init__(self) + tf2_ros.BufferInterface.__init__(self) + + if debug: + #Check to see if the service has already been advertised in this node + try: + m = rosgraph.masterapi.Master(rospy.get_name()) + m.lookupService('~tf2_frames') + except (rosgraph.masterapi.Error, rosgraph.masterapi.Failure): + self.frame_server = rospy.Service('~tf2_frames', FrameGraph, self.__get_frames) + + self.CAN_TRANSFORM_POLLING_SCALE = DEFAULT_CAN_TRANSFORM_POLLING_SCALE + + def __get_frames(self, req): + return FrameGraphResponse(self.all_frames_as_yaml()) + + def lookup_transform(self, target_frame, source_frame, time, timeout=rospy.Duration(0.0)): + """ + Get the transform from the source frame to the target frame. + + :param target_frame: Name of the frame to transform into. + :param source_frame: Name of the input frame. + :param time: The time at which to get the transform. (0 will get the latest) + :param timeout: (Optional) Time to wait for the target frame to become available. + :return: The transform between the frames. + :rtype: :class:`geometry_msgs.msg.TransformStamped` + """ + + self.can_transform(target_frame, source_frame, time, timeout) + return self.lookup_transform_core(target_frame, source_frame, time) + + def lookup_transform_full(self, target_frame, target_time, source_frame, source_time, fixed_frame, timeout=rospy.Duration(0.0)): + """ + Get the transform from the source frame to the target frame using the advanced API. + + :param target_frame: Name of the frame to transform into. + :param target_time: The time to transform to. (0 will get the latest) + :param source_frame: Name of the input frame. + :param source_time: The time at which source_frame will be evaluated. (0 will get the latest) + :param fixed_frame: Name of the frame to consider constant in time. + :param timeout: (Optional) Time to wait for the target frame to become available. + :return: The transform between the frames. + :rtype: :class:`geometry_msgs.msg.TransformStamped` + """ + self.can_transform_full(target_frame, target_time, source_frame, source_time, fixed_frame, timeout) + return self.lookup_transform_full_core(target_frame, target_time, source_frame, source_time, fixed_frame) + + + def can_transform(self, target_frame, source_frame, time, timeout=rospy.Duration(0.0), return_debug_tuple=False): + """ + Check if a transform from the source frame to the target frame is possible. + + :param target_frame: Name of the frame to transform into. + :param source_frame: Name of the input frame. + :param time: The time at which to get the transform. (0 will get the latest) + :param timeout: (Optional) Time to wait for the target frame to become available. + :param return_debug_type: (Optional) If true, return a tuple representing debug information. + :return: True if the transform is possible, false otherwise. + :rtype: bool + """ + if timeout != rospy.Duration(0.0): + start_time = rospy.Time.now() + polling_interval = timeout * self.CAN_TRANSFORM_POLLING_SCALE + while (rospy.Time.now() < start_time + timeout and + not self.can_transform_core(target_frame, source_frame, time)[0] and + (rospy.Time.now()+rospy.Duration(3.0)) >= start_time): # big jumps in time are likely bag loops, so break for them + rospy.sleep(polling_interval) + core_result = self.can_transform_core(target_frame, source_frame, time) + if return_debug_tuple: + return core_result + return core_result[0] + + def can_transform_full(self, target_frame, target_time, source_frame, source_time, fixed_frame, timeout=rospy.Duration(0.0), + + return_debug_tuple=False): + """ + Check if a transform from the source frame to the target frame is possible (advanced API). + + Must be implemented by a subclass of BufferInterface. + + :param target_frame: Name of the frame to transform into. + :param target_time: The time to transform to. (0 will get the latest) + :param source_frame: Name of the input frame. + :param source_time: The time at which source_frame will be evaluated. (0 will get the latest) + :param fixed_frame: Name of the frame to consider constant in time. + :param timeout: (Optional) Time to wait for the target frame to become available. + :param return_debug_type: (Optional) If true, return a tuple representing debug information. + :return: True if the transform is possible, false otherwise. + :rtype: bool + """ + if timeout != rospy.Duration(0.0): + start_time = rospy.Time.now() + polling_interval = timeout * self.CAN_TRANSFORM_POLLING_SCALE + while (rospy.Time.now() < start_time + timeout and + not self.can_transform_full_core(target_frame, target_time, source_frame, source_time, fixed_frame)[0] and + (rospy.Time.now()+rospy.Duration(3.0)) >= start_time): # big jumps in time are likely bag loops, so break for them + rospy.sleep(polling_interval) + core_result = self.can_transform_full_core(target_frame, target_time, source_frame, source_time, fixed_frame) + if return_debug_tuple: + return core_result + return core_result[0] + diff --git a/navigations/geometry2/tf2_ros/src/tf2_ros/buffer_client.py b/navigations/geometry2/tf2_ros/src/tf2_ros/buffer_client.py new file mode 100755 index 0000000..ae4d9fe --- /dev/null +++ b/navigations/geometry2/tf2_ros/src/tf2_ros/buffer_client.py @@ -0,0 +1,196 @@ +#! /usr/bin/python +#*********************************************************** +#* Software License Agreement (BSD License) +#* +#* Copyright (c) 2009, Willow Garage, Inc. +#* All rights reserved. +#* +#* Redistribution and use in source and binary forms, with or without +#* modification, are permitted provided that the following conditions +#* are met: +#* +#* * Redistributions of source code must retain the above copyright +#* notice, this list of conditions and the following disclaimer. +#* * Redistributions in binary form must reproduce the above +#* copyright notice, this list of conditions and the following +#* disclaimer in the documentation and/or other materials provided +#* with the distribution. +#* * Neither the name of Willow Garage, Inc. nor the names of its +#* contributors may be used to endorse or promote products derived +#* from this software without specific prior written permission. +#* +#* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +#* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +#* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +#* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +#* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +#* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +#* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +#* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +#* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +#* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +#* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +#* POSSIBILITY OF SUCH DAMAGE. +#* +#* Author: Eitan Marder-Eppstein +#*********************************************************** +import rospy +import actionlib +import tf2_py as tf2 +import tf2_ros + +from tf2_msgs.msg import LookupTransformAction, LookupTransformGoal +from actionlib_msgs.msg import GoalStatus + +class BufferClient(tf2_ros.BufferInterface): + """ + Action client-based implementation of BufferInterface. + """ + def __init__(self, ns, check_frequency = None, timeout_padding = rospy.Duration.from_sec(2.0)): + """ + .. function:: __init__(ns, check_frequency = None, timeout_padding = rospy.Duration.from_sec(2.0)) + + Constructor. + + :param ns: The namespace in which to look for a BufferServer. + :param check_frequency: How frequently to check for updates to known transforms. + :param timeout_padding: A constant timeout to add to blocking calls. + """ + tf2_ros.BufferInterface.__init__(self) + self.client = actionlib.SimpleActionClient(ns, LookupTransformAction) + self.timeout_padding = timeout_padding + + if check_frequency is not None: + rospy.logwarn('Argument check_frequency is deprecated and should not be used.') + + def wait_for_server(self, timeout = rospy.Duration()): + """ + Block until the action server is ready to respond to requests. + + :param timeout: Time to wait for the server. + :return: True if the server is ready, false otherwise. + :rtype: bool + """ + return self.client.wait_for_server(timeout) + + # lookup, simple api + def lookup_transform(self, target_frame, source_frame, time, timeout=rospy.Duration(0.0)): + """ + Get the transform from the source frame to the target frame. + + :param target_frame: Name of the frame to transform into. + :param source_frame: Name of the input frame. + :param time: The time at which to get the transform. (0 will get the latest) + :param timeout: (Optional) Time to wait for the target frame to become available. + :return: The transform between the frames. + :rtype: :class:`geometry_msgs.msg.TransformStamped` + """ + goal = LookupTransformGoal() + goal.target_frame = target_frame; + goal.source_frame = source_frame; + goal.source_time = time; + goal.timeout = timeout; + goal.advanced = False; + + return self.__process_goal(goal) + + # lookup, advanced api + def lookup_transform_full(self, target_frame, target_time, source_frame, source_time, fixed_frame, timeout=rospy.Duration(0.0)): + """ + Get the transform from the source frame to the target frame using the advanced API. + + :param target_frame: Name of the frame to transform into. + :param target_time: The time to transform to. (0 will get the latest) + :param source_frame: Name of the input frame. + :param source_time: The time at which source_frame will be evaluated. (0 will get the latest) + :param fixed_frame: Name of the frame to consider constant in time. + :param timeout: (Optional) Time to wait for the target frame to become available. + :return: The transform between the frames. + :rtype: :class:`geometry_msgs.msg.TransformStamped` + """ + goal = LookupTransformGoal() + goal.target_frame = target_frame; + goal.source_frame = source_frame; + goal.source_time = source_time; + goal.timeout = timeout; + goal.target_time = target_time; + goal.fixed_frame = fixed_frame; + goal.advanced = True; + + return self.__process_goal(goal) + + # can, simple api + def can_transform(self, target_frame, source_frame, time, timeout=rospy.Duration(0.0)): + """ + Check if a transform from the source frame to the target frame is possible. + + :param target_frame: Name of the frame to transform into. + :param source_frame: Name of the input frame. + :param time: The time at which to get the transform. (0 will get the latest) + :param timeout: (Optional) Time to wait for the target frame to become available. + :param return_debug_type: (Optional) If true, return a tuple representing debug information. + :return: True if the transform is possible, false otherwise. + :rtype: bool + """ + try: + self.lookup_transform(target_frame, source_frame, time, timeout) + return True + except tf2.TransformException: + return False + + + # can, advanced api + def can_transform_full(self, target_frame, target_time, source_frame, source_time, fixed_frame, timeout=rospy.Duration(0.0)): + """ + Check if a transform from the source frame to the target frame is possible (advanced API). + + Must be implemented by a subclass of BufferInterface. + + :param target_frame: Name of the frame to transform into. + :param target_time: The time to transform to. (0 will get the latest) + :param source_frame: Name of the input frame. + :param source_time: The time at which source_frame will be evaluated. (0 will get the latest) + :param fixed_frame: Name of the frame to consider constant in time. + :param timeout: (Optional) Time to wait for the target frame to become available. + :param return_debug_type: (Optional) If true, return a tuple representing debug information. + :return: True if the transform is possible, false otherwise. + :rtype: bool + """ + try: + self.lookup_transform_full(target_frame, target_time, source_frame, source_time, fixed_frame, timeout) + return True + except tf2.TransformException: + return False + + def __process_goal(self, goal): + self.client.send_goal(goal) + + if not self.client.wait_for_result(goal.timeout + self.timeout_padding): + #This shouldn't happen, but could in rare cases where the server hangs + raise tf2.TimeoutException("The LookupTransform goal sent to the BufferServer did not come back in the specified time. Something is likely wrong with the server") + + if self.client.get_state() != GoalStatus.SUCCEEDED: + raise tf2.TimeoutException("The LookupTransform goal sent to the BufferServer did not come back with SUCCEEDED status. Something is likely wrong with the server.") + + return self.__process_result(self.client.get_result()) + + def __process_result(self, result): + if not result: + raise tf2.TransformException("The BufferServer returned None for result! Something is likely wrong with the server.") + if not result.error: + raise tf2.TransformException("The BufferServer returned None for result.error! Something is likely wrong with the server.") + if result.error.error != result.error.NO_ERROR: + if result.error.error == result.error.LOOKUP_ERROR: + raise tf2.LookupException(result.error.error_string) + if result.error.error == result.error.CONNECTIVITY_ERROR: + raise tf2.ConnectivityException(result.error.error_string) + if result.error.error == result.error.EXTRAPOLATION_ERROR: + raise tf2.ExtrapolationException(result.error.error_string) + if result.error.error == result.error.INVALID_ARGUMENT_ERROR: + raise tf2.InvalidArgumentException(result.error.error_string) + if result.error.error == result.error.TIMEOUT_ERROR: + raise tf2.TimeoutException(result.error.error_string) + + raise tf2.TransformException(result.error.error_string) + + return result.transform diff --git a/navigations/geometry2/tf2_ros/src/tf2_ros/buffer_interface.py b/navigations/geometry2/tf2_ros/src/tf2_ros/buffer_interface.py new file mode 100755 index 0000000..a8d7867 --- /dev/null +++ b/navigations/geometry2/tf2_ros/src/tf2_ros/buffer_interface.py @@ -0,0 +1,251 @@ +# Copyright (c) 2008, Willow Garage, Inc. +# All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# * Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in the +# documentation and/or other materials provided with the distribution. +# * Neither the name of the Willow Garage, Inc. nor the names of its +# contributors may be used to endorse or promote products derived from +# this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. + +# author: Wim Meeussen + +from __future__ import print_function + +import rospy +import tf2_py as tf2 +import tf2_ros +from copy import deepcopy +from std_msgs.msg import Header + +class BufferInterface: + """ + Abstract interface for wrapping the Python bindings for the tf2 library in + a ROS-based convenience API. + Implementations include :class:tf2_ros.buffer.Buffer and + :class:tf2_ros.buffer_client.BufferClient. + """ + def __init__(self): + self.registration = tf2_ros.TransformRegistration() + + # transform, simple api + def transform(self, object_stamped, target_frame, timeout=rospy.Duration(0.0), new_type = None): + """ + Transform an input into the target frame. + + The input must be a known transformable type (by way of the tf2 data type conversion interface). + + If new_type is not None, the type specified must have a valid conversion from the input type, + else the function will raise an exception. + + :param object_stamped: The timestamped object the transform. + :param target_frame: Name of the frame to transform the input into. + :param timeout: (Optional) Time to wait for the target frame to become available. + :param new_type: (Optional) Type to convert the object to. + :return: The transformed, timestamped output, possibly converted to a new type. + """ + do_transform = self.registration.get(type(object_stamped)) + res = do_transform(object_stamped, self.lookup_transform(target_frame, object_stamped.header.frame_id, + object_stamped.header.stamp, timeout)) + if not new_type: + return res + + return convert(res, new_type) + + # transform, advanced api + def transform_full(self, object_stamped, target_frame, target_time, fixed_frame, timeout=rospy.Duration(0.0), new_type = None): + """ + Transform an input into the target frame (advanced API). + + The input must be a known transformable type (by way of the tf2 data type conversion interface). + + If new_type is not None, the type specified must have a valid conversion from the input type, + else the function will raise an exception. + + This function follows the advanced API, which allows tranforming between different time points, + as well as specifying a frame to be considered fixed in time. + + :param object_stamped: The timestamped object the transform. + :param target_frame: Name of the frame to transform the input into. + :param target_time: Time to transform the input into. + :param fixed_frame: Name of the frame to consider constant in time. + :param timeout: (Optional) Time to wait for the target frame to become available. + :param new_type: (Optional) Type to convert the object to. + :return: The transformed, timestamped output, possibly converted to a new type. + """ + do_transform = self.registration.get(type(object_stamped)) + res = do_transform(object_stamped, self.lookup_transform_full(target_frame, target_time, + object_stamped.header.frame_id, object_stamped.header.stamp, + fixed_frame, timeout)) + if not new_type: + return res + + return convert(res, new_type) + + def lookup_transform(self, target_frame, source_frame, time, timeout=rospy.Duration(0.0)): + """ + Get the transform from the source frame to the target frame. + + Must be implemented by a subclass of BufferInterface. + + :param target_frame: Name of the frame to transform into. + :param source_frame: Name of the input frame. + :param time: The time at which to get the transform. (0 will get the latest) + :param timeout: (Optional) Time to wait for the target frame to become available. + :return: The transform between the frames. + :rtype: :class:`geometry_msgs.msg.TransformStamped` + """ + raise NotImplementedException() + + def lookup_transform_full(self, target_frame, target_time, source_frame, source_time, fixed_frame, timeout=rospy.Duration(0.0)): + """ + Get the transform from the source frame to the target frame using the advanced API. + + Must be implemented by a subclass of BufferInterface. + + :param target_frame: Name of the frame to transform into. + :param target_time: The time to transform to. (0 will get the latest) + :param source_frame: Name of the input frame. + :param source_time: The time at which source_frame will be evaluated. (0 will get the latest) + :param fixed_frame: Name of the frame to consider constant in time. + :param timeout: (Optional) Time to wait for the target frame to become available. + :return: The transform between the frames. + :rtype: :class:`geometry_msgs.msg.TransformStamped` + """ + raise NotImplementedException() + + # can, simple api + def can_transform(self, target_frame, source_frame, time, timeout=rospy.Duration(0.0)): + """ + Check if a transform from the source frame to the target frame is possible. + + Must be implemented by a subclass of BufferInterface. + + :param target_frame: Name of the frame to transform into. + :param source_frame: Name of the input frame. + :param time: The time at which to get the transform. (0 will get the latest) + :param timeout: (Optional) Time to wait for the target frame to become available. + :return: True if the transform is possible, false otherwise. + :rtype: bool + """ + raise NotImplementedException() + + # can, advanced api + def can_transform_full(self, target_frame, target_time, source_frame, source_time, fixed_frame, timeout=rospy.Duration(0.0)): + """ + Check if a transform from the source frame to the target frame is possible (advanced API). + + Must be implemented by a subclass of BufferInterface. + + :param target_frame: Name of the frame to transform into. + :param target_time: The time to transform to. (0 will get the latest) + :param source_frame: Name of the input frame. + :param source_time: The time at which source_frame will be evaluated. (0 will get the latest) + :param fixed_frame: Name of the frame to consider constant in time. + :param timeout: (Optional) Time to wait for the target frame to become available. + :return: True if the transform is possible, false otherwise. + :rtype: bool + """ + raise NotImplementedException() + + +def Stamped(obj, stamp, frame_id): + obj.header = Header(frame_id=frame_id, stamp=stamp) + return obj + + + +class TypeException(Exception): + """ + Raised when an unexpected type is received while registering a transform + in :class:`tf2_ros.buffer_interface.BufferInterface`. + """ + def __init__(self, errstr): + self.errstr = errstr + +class NotImplementedException(Exception): + """ + Raised when can_transform or lookup_transform is not implemented in a + subclass of :class:`tf2_ros.buffer_interface.BufferInterface`. + """ + def __init__(self): + self.errstr = 'CanTransform or LookupTransform not implemented' + + +class TransformRegistration(): + __type_map = {} + + def print_me(self): + print(TransformRegistration.__type_map) + + def add(self, key, callback): + TransformRegistration.__type_map[key] = callback + + def get(self, key): + if not key in TransformRegistration.__type_map: + raise TypeException('Type %s if not loaded or supported'% str(key)) + else: + return TransformRegistration.__type_map[key] + +class ConvertRegistration(): + __to_msg_map = {} + __from_msg_map = {} + __convert_map = {} + + def add_from_msg(self, key, callback): + ConvertRegistration.__from_msg_map[key] = callback + + def add_to_msg(self, key, callback): + ConvertRegistration.__to_msg_map[key] = callback + + def add_convert(self, key, callback): + ConvertRegistration.__convert_map[key] = callback + + def get_from_msg(self, key): + if not key in ConvertRegistration.__from_msg_map: + raise TypeException('Type %s if not loaded or supported'% str(key)) + else: + return ConvertRegistration.__from_msg_map[key] + + def get_to_msg(self, key): + if not key in ConvertRegistration.__to_msg_map: + raise TypeException('Type %s if not loaded or supported'%str(key)) + else: + return ConvertRegistration.__to_msg_map[key] + + def get_convert(self, key): + if not key in ConvertRegistration.__convert_map: + raise TypeException("Type %s if not loaded or supported" % str(key)) + else: + return ConvertRegistration.__convert_map[key] + +def convert(a, b_type): + c = ConvertRegistration() + #check if an efficient conversion function between the types exists + try: + f = c.get_convert((type(a), b_type)) + return f(a) + except TypeException: + if type(a) == b_type: + return deepcopy(a) + + f_to = c.get_to_msg(type(a)) + f_from = c.get_from_msg(b_type) + return f_from(f_to(a)) diff --git a/navigations/geometry2/tf2_ros/src/tf2_ros/static_transform_broadcaster.py b/navigations/geometry2/tf2_ros/src/tf2_ros/static_transform_broadcaster.py new file mode 100755 index 0000000..064a687 --- /dev/null +++ b/navigations/geometry2/tf2_ros/src/tf2_ros/static_transform_broadcaster.py @@ -0,0 +1,51 @@ +# Software License Agreement (BSD License) +# +# Copyright (c) 2008, Willow Garage, Inc. +# All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# * Redistributions in binary form must reproduce the above +# copyright notice, this list of conditions and the following +# disclaimer in the documentation and/or other materials provided +# with the distribution. +# * Neither the name of the Willow Garage nor the names of its +# contributors may be used to endorse or promote products derived +# from this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. + +import rospy +from tf2_msgs.msg import TFMessage +from geometry_msgs.msg import TransformStamped + + +class StaticTransformBroadcaster(object): + """ + :class:`StaticTransformBroadcaster` is a convenient way to send static transformation on the ``"/tf_static"`` message topic. + """ + + def __init__(self): + self.pub_tf = rospy.Publisher("/tf_static", TFMessage, queue_size=100, latch=True) + + def sendTransform(self, transform): + if not isinstance(transform, list): + transform = [transform] + self.pub_tf.publish(TFMessage(transform)) + + diff --git a/navigations/geometry2/tf2_ros/src/tf2_ros/transform_broadcaster.py b/navigations/geometry2/tf2_ros/src/tf2_ros/transform_broadcaster.py new file mode 100755 index 0000000..e86e835 --- /dev/null +++ b/navigations/geometry2/tf2_ros/src/tf2_ros/transform_broadcaster.py @@ -0,0 +1,56 @@ +# Software License Agreement (BSD License) +# +# Copyright (c) 2008, Willow Garage, Inc. +# All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# * Redistributions in binary form must reproduce the above +# copyright notice, this list of conditions and the following +# disclaimer in the documentation and/or other materials provided +# with the distribution. +# * Neither the name of the Willow Garage nor the names of its +# contributors may be used to endorse or promote products derived +# from this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. + +import rospy +from tf2_msgs.msg import TFMessage +from geometry_msgs.msg import TransformStamped + + +class TransformBroadcaster: + """ + :class:`TransformBroadcaster` is a convenient way to send transformation updates on the ``"/tf"`` message topic. + """ + + def __init__(self): + self.pub_tf = rospy.Publisher("/tf", TFMessage, queue_size=100) + + def sendTransform(self, transform): + """ + Send a transform, or a list of transforms, to the Buffer associated with this TransformBroadcaster. + + :param transform: A transform or list of transforms to send. + """ + if not isinstance(transform, list): + transform = [transform] + self.pub_tf.publish(TFMessage(transform)) + + diff --git a/navigations/geometry2/tf2_ros/src/tf2_ros/transform_listener.py b/navigations/geometry2/tf2_ros/src/tf2_ros/transform_listener.py new file mode 100755 index 0000000..53625e8 --- /dev/null +++ b/navigations/geometry2/tf2_ros/src/tf2_ros/transform_listener.py @@ -0,0 +1,89 @@ +# Copyright (c) 2008, Willow Garage, Inc. +# All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# * Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in the +# documentation and/or other materials provided with the distribution. +# * Neither the name of the Willow Garage, Inc. nor the names of its +# contributors may be used to endorse or promote products derived from +# this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. + +# author: Wim Meeussen + +import threading + +import rospy +from tf2_msgs.msg import TFMessage + + +class TransformListener: + """ + :class:`TransformListener` is a convenient way to listen for coordinate frame transformation info. + This class takes an object that instantiates the :class:`BufferInterface` interface, to which + it propagates changes to the tf frame graph. + """ + def __init__(self, buffer, queue_size=None, buff_size=65536, tcp_nodelay=False): + """ + .. function:: __init__(buffer, queue_size=None, buff_size=65536, tcp_nodelay=False): + + Constructor. + + :param buffer: The buffer to propagate changes to when tf info updates. + :param queue_size: Maximum number of messages to receive at a time. This will generally be 1 or None (infinite, default). buff_size should be increased if this parameter is set as incoming data still needs to sit in the incoming buffer before being discarded. Setting queue_size buff_size to a non-default value affects all subscribers to this topic in this process. + :param buff_size: Incoming message buffer size in bytes. If queue_size is set, this should be set to a number greater than the queue_size times the average message size. Setting buff_size to a non-default value affects all subscribers to this topic in this process. + :param tcp_nodelay: If True, request TCP_NODELAY from publisher. Use of this option is not generally recommended in most cases as it is better to rely on timestamps in message data. Setting tcp_nodelay to True enables TCP_NODELAY for all subscribers in the same python process. + """ + self.buffer = buffer + self.last_update = rospy.Time.now() + self.last_update_lock = threading.Lock() + self.tf_sub = rospy.Subscriber("/tf", TFMessage, self.callback, queue_size=queue_size, buff_size=buff_size, tcp_nodelay=tcp_nodelay) + self.tf_static_sub = rospy.Subscriber("/tf_static", TFMessage, self.static_callback, queue_size=queue_size, buff_size=buff_size, tcp_nodelay=tcp_nodelay) + + def __del__(self): + self.unregister() + + def unregister(self): + """ + Unregisters all tf subscribers. + """ + self.tf_sub.unregister() + self.tf_static_sub.unregister() + + def check_for_reset(self): + # Lock to prevent different threads racing on this test and update. + # https://github.com/ros/geometry2/issues/341 + with self.last_update_lock: + now = rospy.Time.now() + if now < self.last_update: + rospy.logwarn("Detected jump back in time of %fs. Clearing TF buffer." % (self.last_update - now).to_sec()) + self.buffer.clear() + self.last_update = now + + def callback(self, data): + self.check_for_reset() + who = data._connection_header.get('callerid', "default_authority") + for transform in data.transforms: + self.buffer.set_transform(transform, who) + + def static_callback(self, data): + self.check_for_reset() + who = data._connection_header.get('callerid', "default_authority") + for transform in data.transforms: + self.buffer.set_transform_static(transform, who) diff --git a/navigations/geometry2/tf2_ros/src/transform_broadcaster.cpp b/navigations/geometry2/tf2_ros/src/transform_broadcaster.cpp new file mode 100755 index 0000000..94cce47 --- /dev/null +++ b/navigations/geometry2/tf2_ros/src/transform_broadcaster.cpp @@ -0,0 +1,66 @@ +/* + * Copyright (c) 2008, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + + +/** \author Tully Foote */ + + +#include "ros/ros.h" +#include "tf2_msgs/TFMessage.h" +#include "tf2_ros/transform_broadcaster.h" + +namespace tf2_ros { + +TransformBroadcaster::TransformBroadcaster() +{ + publisher_ = node_.advertise("/tf", 100); +}; + +void TransformBroadcaster::sendTransform(const geometry_msgs::TransformStamped & msgtf) +{ + std::vector v1; + v1.push_back(msgtf); + sendTransform(v1); +} + + +void TransformBroadcaster::sendTransform(const std::vector & msgtf) +{ + tf2_msgs::TFMessage message; + for (std::vector::const_iterator it = msgtf.begin(); it != msgtf.end(); ++it) + { + message.transforms.push_back(*it); + } + publisher_.publish(message); +} + + +} + + diff --git a/navigations/geometry2/tf2_ros/src/transform_listener.cpp b/navigations/geometry2/tf2_ros/src/transform_listener.cpp new file mode 100755 index 0000000..78646f8 --- /dev/null +++ b/navigations/geometry2/tf2_ros/src/transform_listener.cpp @@ -0,0 +1,136 @@ +/* + * Copyright (c) 2008, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +/** \author Tully Foote */ + +#include "tf2_ros/transform_listener.h" + + +using namespace tf2_ros; + + +TransformListener::TransformListener(tf2::BufferCore& buffer, bool spin_thread, ros::TransportHints transport_hints): + dedicated_listener_thread_(NULL), buffer_(buffer), using_dedicated_thread_(false), transport_hints_(transport_hints) +{ + if (spin_thread) + initWithThread(); + else + init(); +} + +TransformListener::TransformListener(tf2::BufferCore& buffer, const ros::NodeHandle& nh, bool spin_thread, + ros::TransportHints transport_hints) +: dedicated_listener_thread_(NULL) +, node_(nh) +, buffer_(buffer) +, using_dedicated_thread_(false) +, transport_hints_(transport_hints) +{ + if (spin_thread) + initWithThread(); + else + init(); +} + +TransformListener::~TransformListener() +{ + using_dedicated_thread_ = false; + if (dedicated_listener_thread_) + { + dedicated_listener_thread_->join(); + delete dedicated_listener_thread_; + } +} + +void TransformListener::init() +{ + message_subscriber_tf_ = node_.subscribe("/tf", 100, boost::bind(&TransformListener::subscription_callback, this, boost::placeholders::_1), ros::VoidConstPtr(), transport_hints_); ///\todo magic number + message_subscriber_tf_static_ = node_.subscribe("/tf_static", 100, boost::bind(&TransformListener::static_subscription_callback, this, boost::placeholders::_1)); ///\todo magic number +} + +void TransformListener::initWithThread() +{ + using_dedicated_thread_ = true; + ros::SubscribeOptions ops_tf = ros::SubscribeOptions::create("/tf", 100, boost::bind(&TransformListener::subscription_callback, this, boost::placeholders::_1), ros::VoidPtr(), &tf_message_callback_queue_); ///\todo magic number + ops_tf.transport_hints = transport_hints_; + message_subscriber_tf_ = node_.subscribe(ops_tf); + + ros::SubscribeOptions ops_tf_static = ros::SubscribeOptions::create("/tf_static", 100, boost::bind(&TransformListener::static_subscription_callback, this, boost::placeholders::_1), ros::VoidPtr(), &tf_message_callback_queue_); ///\todo magic number + message_subscriber_tf_static_ = node_.subscribe(ops_tf_static); + + dedicated_listener_thread_ = new boost::thread(boost::bind(&TransformListener::dedicatedListenerThread, this)); + + //Tell the buffer we have a dedicated thread to enable timeouts + buffer_.setUsingDedicatedThread(true); +} + + + +void TransformListener::subscription_callback(const ros::MessageEvent& msg_evt) +{ + subscription_callback_impl(msg_evt, false); +} +void TransformListener::static_subscription_callback(const ros::MessageEvent& msg_evt) +{ + subscription_callback_impl(msg_evt, true); +} + +void TransformListener::subscription_callback_impl(const ros::MessageEvent& msg_evt, bool is_static) +{ + ros::Time now = ros::Time::now(); + if(now < last_update_){ + ROS_WARN_STREAM("Detected jump back in time of " << (last_update_ - now).toSec() << "s. Clearing TF buffer."); + buffer_.clear(); + } + last_update_ = now; + + + + const tf2_msgs::TFMessage& msg_in = *(msg_evt.getConstMessage()); + std::string authority = msg_evt.getPublisherName(); // lookup the authority + for (unsigned int i = 0; i < msg_in.transforms.size(); i++) + { + try + { + buffer_.setTransform(msg_in.transforms[i], authority, is_static); + } + + catch (tf2::TransformException& ex) + { + ///\todo Use error reporting + std::string temp = ex.what(); + ROS_ERROR("Failure to set recieved transform from %s to %s with error: %s\n", msg_in.transforms[i].child_frame_id.c_str(), msg_in.transforms[i].header.frame_id.c_str(), temp.c_str()); + } + } +}; + + + + + diff --git a/navigations/geometry2/tf2_ros/test/listener_unittest.cpp b/navigations/geometry2/tf2_ros/test/listener_unittest.cpp new file mode 100755 index 0000000..61e9a31 --- /dev/null +++ b/navigations/geometry2/tf2_ros/test/listener_unittest.cpp @@ -0,0 +1,51 @@ +/* + * Copyright (c) 2008, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include + +using namespace tf2; + +TEST(tf2_ros_transform, transform_listener) +{ + tf2_ros::Buffer buffer; + tf2_ros::TransformListener tfl(buffer); +} + +TEST(tf2_ros_transform, transform_listener_transport_hints) +{ + tf2_ros::Buffer buffer; + tf2_ros::TransformListener tfl(buffer, true, ros::TransportHints().tcpNoDelay()); +} + +int main(int argc, char **argv){ + testing::InitGoogleTest(&argc, argv); + ros::init(argc, argv, "transform_listener_unittest"); + return RUN_ALL_TESTS(); +} diff --git a/navigations/geometry2/tf2_ros/test/message_filter_test.cpp b/navigations/geometry2/tf2_ros/test/message_filter_test.cpp new file mode 100755 index 0000000..b613d24 --- /dev/null +++ b/navigations/geometry2/tf2_ros/test/message_filter_test.cpp @@ -0,0 +1,125 @@ +/* + * Copyright (c) 2014, Open Source Robotics Foundation + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include + + +void spin_for_a_second() +{ + ros::spinOnce(); + for (uint8_t i = 0; i < 10; ++i) + { + std::this_thread::sleep_for(std::chrono::microseconds(100)); + ros::spinOnce(); + } +} + +bool filter_callback_fired = false; +void filter_callback(const geometry_msgs::PointStamped& msg) +{ + filter_callback_fired = true; +} + +TEST(tf2_ros_message_filter, multiple_frames_and_time_tolerance) +{ + ros::NodeHandle nh; + message_filters::Subscriber sub; + sub.subscribe(nh, "point", 10); + + tf2_ros::Buffer buffer; + tf2_ros::TransformListener tfl(buffer); + tf2_ros::MessageFilter filter(buffer, "map", 10, nh); + filter.connectInput(sub); + filter.registerCallback(&filter_callback); + // Register multiple target frames + std::vector frames; + frames.push_back("odom"); + frames.push_back("map"); + filter.setTargetFrames(frames); + // Set a non-zero time tolerance + filter.setTolerance(ros::Duration(1, 0)); + + // Publish static transforms so the frame transformations will always be valid + tf2_ros::StaticTransformBroadcaster tfb; + geometry_msgs::TransformStamped map_to_odom; + map_to_odom.header.stamp = ros::Time(0, 0); + map_to_odom.header.frame_id = "map"; + map_to_odom.child_frame_id = "odom"; + map_to_odom.transform.translation.x = 0.0; + map_to_odom.transform.translation.y = 0.0; + map_to_odom.transform.translation.z = 0.0; + map_to_odom.transform.rotation.x = 0.0; + map_to_odom.transform.rotation.y = 0.0; + map_to_odom.transform.rotation.z = 0.0; + map_to_odom.transform.rotation.w = 1.0; + tfb.sendTransform(map_to_odom); + + geometry_msgs::TransformStamped odom_to_base; + odom_to_base.header.stamp = ros::Time(0, 0); + odom_to_base.header.frame_id = "odom"; + odom_to_base.child_frame_id = "base"; + odom_to_base.transform.translation.x = 0.0; + odom_to_base.transform.translation.y = 0.0; + odom_to_base.transform.translation.z = 0.0; + odom_to_base.transform.rotation.x = 0.0; + odom_to_base.transform.rotation.y = 0.0; + odom_to_base.transform.rotation.z = 0.0; + odom_to_base.transform.rotation.w = 1.0; + tfb.sendTransform(odom_to_base); + + // Publish a Point message in the "base" frame + ros::Publisher pub = nh.advertise("point", 10); + geometry_msgs::PointStamped point; + point.header.stamp = ros::Time::now(); + point.header.frame_id = "base"; + pub.publish(point); + + // make sure it arrives + spin_for_a_second(); + + // The filter callback should have been fired because all required transforms are available + ASSERT_TRUE(filter_callback_fired); +} + +int main(int argc, char **argv){ + testing::InitGoogleTest(&argc, argv); + ros::init(argc, argv, "tf2_ros_message_filter"); + return RUN_ALL_TESTS(); +} diff --git a/navigations/geometry2/tf2_ros/test/message_filter_test.launch b/navigations/geometry2/tf2_ros/test/message_filter_test.launch new file mode 100755 index 0000000..b32f8dc --- /dev/null +++ b/navigations/geometry2/tf2_ros/test/message_filter_test.launch @@ -0,0 +1,4 @@ + + + + diff --git a/navigations/geometry2/tf2_ros/test/time_reset_test.cpp b/navigations/geometry2/tf2_ros/test/time_reset_test.cpp new file mode 100755 index 0000000..541fac0 --- /dev/null +++ b/navigations/geometry2/tf2_ros/test/time_reset_test.cpp @@ -0,0 +1,111 @@ +/* + * Copyright (c) 2014, Open Source Robotics Foundation + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include +#include +#include +#include +#include + +using namespace tf2; + +void spin_for_a_second() +{ + ros::spinOnce(); + for (uint8_t i = 0; i < 10; ++i) + { + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + ros::spinOnce(); + } +} + +TEST(tf2_ros_transform_listener, time_backwards) +{ + + tf2_ros::Buffer buffer; + tf2_ros::TransformListener tfl(buffer); + tf2_ros::TransformBroadcaster tfb; + + ros::NodeHandle nh = ros::NodeHandle(); + + ros::Publisher clock = nh.advertise("/clock", 5); + + rosgraph_msgs::Clock c; + c.clock = ros::Time(100); + clock.publish(c); + + // basic test + ASSERT_FALSE(buffer.canTransform("foo", "bar", ros::Time(101, 0))); + + // set the transform + geometry_msgs::TransformStamped msg; + msg.header.stamp = ros::Time(100, 0); + msg.header.frame_id = "foo"; + msg.child_frame_id = "bar"; + msg.transform.rotation.x = 1.0; + tfb.sendTransform(msg); + msg.header.stamp = ros::Time(102, 0); + tfb.sendTransform(msg); + + + // make sure it arrives + spin_for_a_second(); + + // verify it's been set + ASSERT_TRUE(buffer.canTransform("foo", "bar", ros::Time(101, 0))); + + c.clock = ros::Time(90); + clock.publish(c); + + // make sure it arrives + spin_for_a_second(); + + //Send another message to trigger clock test on an unrelated frame + msg.header.stamp = ros::Time(110, 0); + msg.header.frame_id = "foo2"; + msg.child_frame_id = "bar2"; + tfb.sendTransform(msg); + + // make sure it arrives + spin_for_a_second(); + + //verify the data's been cleared + ASSERT_FALSE(buffer.canTransform("foo", "bar", ros::Time(101, 0))); + +} + + + + +int main(int argc, char **argv){ + testing::InitGoogleTest(&argc, argv); + ros::init(argc, argv, "transform_listener_backwards_reset"); + return RUN_ALL_TESTS(); +} diff --git a/navigations/geometry2/tf2_ros/test/transform_listener_time_reset_test.launch b/navigations/geometry2/tf2_ros/test/transform_listener_time_reset_test.launch new file mode 100755 index 0000000..ae31a90 --- /dev/null +++ b/navigations/geometry2/tf2_ros/test/transform_listener_time_reset_test.launch @@ -0,0 +1,4 @@ + + + + \ No newline at end of file diff --git a/navigations/geometry2/tf2_ros/test/transform_listener_unittest.launch b/navigations/geometry2/tf2_ros/test/transform_listener_unittest.launch new file mode 100755 index 0000000..42a8149 --- /dev/null +++ b/navigations/geometry2/tf2_ros/test/transform_listener_unittest.launch @@ -0,0 +1,3 @@ + + + \ No newline at end of file diff --git a/navigations/geometry2/tf2_sensor_msgs/CHANGELOG.rst b/navigations/geometry2/tf2_sensor_msgs/CHANGELOG.rst new file mode 100755 index 0000000..51fd4ef --- /dev/null +++ b/navigations/geometry2/tf2_sensor_msgs/CHANGELOG.rst @@ -0,0 +1,110 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package tf2_sensor_msgs +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +0.7.6 (2022-10-11) +------------------ + +0.7.5 (2020-09-01) +------------------ + +0.7.4 (2020-09-01) +------------------ + +0.7.3 (2020-08-25) +------------------ +* Use list instead of set to make build reproducible (`#473 `_) +* Contributors: Jochen Sprickerhof + +0.7.2 (2020-06-08) +------------------ + +0.7.1 (2020-05-13) +------------------ +* import setup from setuptools instead of distutils-core (`#449 `_) +* Contributors: Alejandro Hernández Cordero + +0.7.0 (2020-03-09) +------------------ +* Replace kdl packages with rosdep keys (`#447 `_) +* Bump CMake version to avoid CMP0048 warning (`#445 `_) +* Merge pull request `#378 `_ from peci1/tf2_sensor_msgs_isometry + Affine->Isometry +* Python 3 compatibility: relative imports and print statement +* Contributors: Martin Pecka, Shane Loretz, Timon Engelke, Tully Foote + +0.6.5 (2018-11-16) +------------------ + +0.6.4 (2018-11-06) +------------------ + +0.6.3 (2018-07-09) +------------------ + +0.6.2 (2018-05-02) +------------------ + +0.6.1 (2018-03-21) +------------------ + +0.6.0 (2018-03-21) +------------------ + +0.5.17 (2018-01-01) +------------------- +* Merge pull request `#257 `_ from delftrobotics-forks/python3 + Make tf2_py python3 compatible again +* Use python3 print function. +* Contributors: Maarten de Vries, Tully Foote + +0.5.16 (2017-07-14) +------------------- +* Fix do_transform_cloud for multi-channelled pointcloud2. (`#241 `_) +* store gtest return value as int (`#229 `_) +* Document the lifetime of the returned reference for getFrameId and getTimestamp +* Find eigen in a much nicer way. +* Switch tf2_sensor_msgs over to package format 2. +* Contributors: Atsushi Watanabe, Chris Lalancette, dhood + +0.5.15 (2017-01-24) +------------------- + +0.5.14 (2017-01-16) +------------------- + +0.5.13 (2016-03-04) +------------------- +* add missing Python runtime dependency +* fix wrong comment +* Adding tests to package +* Fixing do_transform_cloud for python + The previous code was not used at all (it was a mistake in the __init_\_.py so + the do_transform_cloud was not available to the python users). + The python code need some little correction (e.g there is no method named + read_cloud but it's read_points for instance, and as we are in python we can't + use the same trick as in c++ when we got an immutable) +* Contributors: Laurent GEORGE, Vincent Rabaud + +0.5.12 (2015-08-05) +------------------- + +0.5.11 (2015-04-22) +------------------- + +0.5.10 (2015-04-21) +------------------- + +0.5.9 (2015-03-25) +------------------ + +0.5.8 (2015-03-17) +------------------ +* ODR violation fixes and more conversions +* Fix keeping original pointcloud header in transformed pointcloud +* Contributors: Paul Bovbel, Tully Foote, Vincent Rabaud + +0.5.7 (2014-12-23) +------------------ +* add support for transforming sensor_msgs::PointCloud2 +* Contributors: Vincent Rabaud diff --git a/navigations/geometry2/tf2_sensor_msgs/CMakeLists.txt b/navigations/geometry2/tf2_sensor_msgs/CMakeLists.txt new file mode 100755 index 0000000..763f260 --- /dev/null +++ b/navigations/geometry2/tf2_sensor_msgs/CMakeLists.txt @@ -0,0 +1,56 @@ +cmake_minimum_required(VERSION 3.0.2) +project(tf2_sensor_msgs) + +find_package(catkin REQUIRED COMPONENTS cmake_modules sensor_msgs tf2_ros tf2) +find_package(Boost COMPONENTS thread REQUIRED) + +# Finding Eigen is somewhat complicated because of our need to support Ubuntu +# all the way back to saucy. First we look for the Eigen3 cmake module +# provided by the libeigen3-dev on newer Ubuntu. If that fails, then we +# fall-back to the version provided by cmake_modules, which is a stand-in. +find_package(Eigen3 QUIET) +if(NOT EIGEN3_FOUND) + find_package(cmake_modules REQUIRED) + find_package(Eigen REQUIRED) + set(EIGEN3_INCLUDE_DIRS ${EIGEN_INCLUDE_DIRS}) +endif() + +# Note that eigen 3.2 (on Ubuntu Wily) only provides EIGEN3_INCLUDE_DIR, +# not EIGEN3_INCLUDE_DIRS, so we have to set the latter from the former. +if(NOT EIGEN3_INCLUDE_DIRS) + set(EIGEN3_INCLUDE_DIRS ${EIGEN3_INCLUDE_DIR}) +endif() + +catkin_package( + INCLUDE_DIRS include + CATKIN_DEPENDS sensor_msgs tf2_ros tf2 + DEPENDS EIGEN3 +) + + +include_directories(include + ${catkin_INCLUDE_DIRS} + ${EIGEN3_INCLUDE_DIRS} +) + +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} +) + +catkin_python_setup() + +if(CATKIN_ENABLE_TESTING) + catkin_add_nosetests(test/test_tf2_sensor_msgs.py) + + find_package(catkin REQUIRED COMPONENTS geometry_msgs sensor_msgs rostest tf2_ros tf2) + + add_executable(test_tf2_sensor_msgs_cpp EXCLUDE_FROM_ALL test/test_tf2_sensor_msgs.cpp) + target_link_libraries(test_tf2_sensor_msgs_cpp ${catkin_LIBRARIES} ${GTEST_LIBRARIES}) + + + if(TARGET tests) + add_dependencies(tests test_tf2_sensor_msgs_cpp) + endif() + add_rostest(${CMAKE_CURRENT_SOURCE_DIR}/test/test.launch) + +endif() diff --git a/navigations/geometry2/tf2_sensor_msgs/include/tf2_sensor_msgs/tf2_sensor_msgs.h b/navigations/geometry2/tf2_sensor_msgs/include/tf2_sensor_msgs/tf2_sensor_msgs.h new file mode 100755 index 0000000..9e16e0d --- /dev/null +++ b/navigations/geometry2/tf2_sensor_msgs/include/tf2_sensor_msgs/tf2_sensor_msgs.h @@ -0,0 +1,107 @@ +/* + * Copyright (c) 2008, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef TF2_SENSOR_MSGS_H +#define TF2_SENSOR_MSGS_H + +#include +#include +#include +#include +#include + +namespace tf2 +{ + +/********************/ +/** PointCloud2 **/ +/********************/ + +/** \brief Extract a timestamp from the header of a PointCloud2 message. + * This function is a specialization of the getTimestamp template defined in tf2/convert.h. + * \param t PointCloud2 message to extract the timestamp from. + * \return The timestamp of the message. The lifetime of the returned reference + * is bound to the lifetime of the argument. + */ +template <> +inline +const ros::Time& getTimestamp(const sensor_msgs::PointCloud2& p) {return p.header.stamp;} + +/** \brief Extract a frame ID from the header of a PointCloud2 message. + * This function is a specialization of the getFrameId template defined in tf2/convert.h. + * \param t PointCloud2 message to extract the frame ID from. + * \return A string containing the frame ID of the message. The lifetime of the + * returned reference is bound to the lifetime of the argument. + */ +template <> +inline +const std::string& getFrameId(const sensor_msgs::PointCloud2 &p) {return p.header.frame_id;} + +// this method needs to be implemented by client library developers +template <> +inline +void doTransform(const sensor_msgs::PointCloud2 &p_in, sensor_msgs::PointCloud2 &p_out, const geometry_msgs::TransformStamped& t_in) +{ + p_out = p_in; + p_out.header = t_in.header; + Eigen::Transform t = Eigen::Translation3f(t_in.transform.translation.x, t_in.transform.translation.y, + t_in.transform.translation.z) * Eigen::Quaternion( + t_in.transform.rotation.w, t_in.transform.rotation.x, + t_in.transform.rotation.y, t_in.transform.rotation.z); + + sensor_msgs::PointCloud2ConstIterator x_in(p_in, "x"); + sensor_msgs::PointCloud2ConstIterator y_in(p_in, "y"); + sensor_msgs::PointCloud2ConstIterator z_in(p_in, "z"); + + sensor_msgs::PointCloud2Iterator x_out(p_out, "x"); + sensor_msgs::PointCloud2Iterator y_out(p_out, "y"); + sensor_msgs::PointCloud2Iterator z_out(p_out, "z"); + + Eigen::Vector3f point; + for(; x_in != x_in.end(); ++x_in, ++y_in, ++z_in, ++x_out, ++y_out, ++z_out) { + point = t * Eigen::Vector3f(*x_in, *y_in, *z_in); + *x_out = point.x(); + *y_out = point.y(); + *z_out = point.z(); + } +} +inline +sensor_msgs::PointCloud2 toMsg(const sensor_msgs::PointCloud2 &in) +{ + return in; +} +inline +void fromMsg(const sensor_msgs::PointCloud2 &msg, sensor_msgs::PointCloud2 &out) +{ + out = msg; +} + +} // namespace + +#endif // TF2_SENSOR_MSGS_H diff --git a/navigations/geometry2/tf2_sensor_msgs/package.xml b/navigations/geometry2/tf2_sensor_msgs/package.xml new file mode 100755 index 0000000..78b7ef3 --- /dev/null +++ b/navigations/geometry2/tf2_sensor_msgs/package.xml @@ -0,0 +1,31 @@ + + tf2_sensor_msgs + 0.7.6 + + Small lib to transform sensor_msgs with tf. Most notably, PointCloud2 + + Vincent Rabaud + Vincent Rabaud + BSD + + http://www.ros.org/wiki/tf2_ros + + catkin + + cmake_modules + eigen + + sensor_msgs + tf2 + tf2_ros + + python3-pykdl + rospy + + eigen + + rostest + geometry_msgs + + + diff --git a/navigations/geometry2/tf2_sensor_msgs/setup.py b/navigations/geometry2/tf2_sensor_msgs/setup.py new file mode 100755 index 0000000..c6c730d --- /dev/null +++ b/navigations/geometry2/tf2_sensor_msgs/setup.py @@ -0,0 +1,13 @@ +#!/usr/bin/env python + +from setuptools import setup +from catkin_pkg.python_setup import generate_distutils_setup + +d = generate_distutils_setup( + packages=['tf2_sensor_msgs'], + package_dir={'': 'src'}, + requires=['rospy','sensor_msgs','tf2_ros','orocos_kdl'] +) + +setup(**d) + diff --git a/navigations/geometry2/tf2_sensor_msgs/src/tf2_sensor_msgs/__init__.py b/navigations/geometry2/tf2_sensor_msgs/src/tf2_sensor_msgs/__init__.py new file mode 100755 index 0000000..187bd6b --- /dev/null +++ b/navigations/geometry2/tf2_sensor_msgs/src/tf2_sensor_msgs/__init__.py @@ -0,0 +1 @@ +from .tf2_sensor_msgs import * diff --git a/navigations/geometry2/tf2_sensor_msgs/src/tf2_sensor_msgs/tf2_sensor_msgs.py b/navigations/geometry2/tf2_sensor_msgs/src/tf2_sensor_msgs/tf2_sensor_msgs.py new file mode 100755 index 0000000..74cacd3 --- /dev/null +++ b/navigations/geometry2/tf2_sensor_msgs/src/tf2_sensor_msgs/tf2_sensor_msgs.py @@ -0,0 +1,60 @@ +# Copyright (c) 2008, Willow Garage, Inc. +# All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# * Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in the +# documentation and/or other materials provided with the distribution. +# * Neither the name of the Willow Garage, Inc. nor the names of its +# contributors may be used to endorse or promote products derived from +# this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. + +from sensor_msgs.msg import PointCloud2 +from sensor_msgs.point_cloud2 import read_points, create_cloud +import PyKDL +import rospy +import tf2_ros + +def to_msg_msg(msg): + return msg + +tf2_ros.ConvertRegistration().add_to_msg(PointCloud2, to_msg_msg) + +def from_msg_msg(msg): + return msg + +tf2_ros.ConvertRegistration().add_from_msg(PointCloud2, from_msg_msg) + +def transform_to_kdl(t): + return PyKDL.Frame(PyKDL.Rotation.Quaternion(t.transform.rotation.x, t.transform.rotation.y, + t.transform.rotation.z, t.transform.rotation.w), + PyKDL.Vector(t.transform.translation.x, + t.transform.translation.y, + t.transform.translation.z)) + +# PointStamped +def do_transform_cloud(cloud, transform): + t_kdl = transform_to_kdl(transform) + points_out = [] + for p_in in read_points(cloud): + p_out = t_kdl * PyKDL.Vector(p_in[0], p_in[1], p_in[2]) + points_out.append((p_out[0], p_out[1], p_out[2]) + p_in[3:]) + res = create_cloud(transform.header, cloud.fields, points_out) + return res +tf2_ros.TransformRegistration().add(PointCloud2, do_transform_cloud) diff --git a/navigations/geometry2/tf2_sensor_msgs/test/test.launch b/navigations/geometry2/tf2_sensor_msgs/test/test.launch new file mode 100755 index 0000000..a948a06 --- /dev/null +++ b/navigations/geometry2/tf2_sensor_msgs/test/test.launch @@ -0,0 +1,3 @@ + + + diff --git a/navigations/geometry2/tf2_sensor_msgs/test/test_tf2_sensor_msgs.cpp b/navigations/geometry2/tf2_sensor_msgs/test/test_tf2_sensor_msgs.cpp new file mode 100755 index 0000000..8607501 --- /dev/null +++ b/navigations/geometry2/tf2_sensor_msgs/test/test_tf2_sensor_msgs.cpp @@ -0,0 +1,104 @@ +/* + * Copyright (c) 2008, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + + +#include +#include +#include +#include +#include +#include + +tf2_ros::Buffer* tf_buffer; +static const double EPS = 1e-3; + + +TEST(Tf2Sensor, PointCloud2) +{ + sensor_msgs::PointCloud2 cloud; + sensor_msgs::PointCloud2Modifier modifier(cloud); + modifier.setPointCloud2FieldsByString(2, "xyz", "rgb"); + modifier.resize(1); + + sensor_msgs::PointCloud2Iterator iter_x(cloud, "x"); + sensor_msgs::PointCloud2Iterator iter_y(cloud, "y"); + sensor_msgs::PointCloud2Iterator iter_z(cloud, "z"); + + *iter_x = 1; + *iter_y = 2; + *iter_z = 3; + + cloud.header.stamp = ros::Time(2); + cloud.header.frame_id = "A"; + + // simple api + sensor_msgs::PointCloud2 cloud_simple = tf_buffer->transform(cloud, "B", ros::Duration(2.0)); + sensor_msgs::PointCloud2Iterator iter_x_after(cloud_simple, "x"); + sensor_msgs::PointCloud2Iterator iter_y_after(cloud_simple, "y"); + sensor_msgs::PointCloud2Iterator iter_z_after(cloud_simple, "z"); + EXPECT_NEAR(*iter_x_after, -9, EPS); + EXPECT_NEAR(*iter_y_after, 18, EPS); + EXPECT_NEAR(*iter_z_after, 27, EPS); + + // advanced api + sensor_msgs::PointCloud2 cloud_advanced = tf_buffer->transform(cloud, "B", ros::Time(2.0), + "A", ros::Duration(3.0)); + sensor_msgs::PointCloud2Iterator iter_x_advanced(cloud_advanced, "x"); + sensor_msgs::PointCloud2Iterator iter_y_advanced(cloud_advanced, "y"); + sensor_msgs::PointCloud2Iterator iter_z_advanced(cloud_advanced, "z"); + EXPECT_NEAR(*iter_x_advanced, -9, EPS); + EXPECT_NEAR(*iter_y_advanced, 18, EPS); + EXPECT_NEAR(*iter_z_advanced, 27, EPS); +} + +int main(int argc, char **argv){ + testing::InitGoogleTest(&argc, argv); + ros::init(argc, argv, "test"); + ros::NodeHandle n; + + tf_buffer = new tf2_ros::Buffer(); + + // populate buffer + geometry_msgs::TransformStamped t; + t.transform.translation.x = 10; + t.transform.translation.y = 20; + t.transform.translation.z = 30; + t.transform.rotation.x = 1; + t.transform.rotation.y = 0; + t.transform.rotation.z = 0; + t.transform.rotation.w = 0; + t.header.stamp = ros::Time(2.0); + t.header.frame_id = "A"; + t.child_frame_id = "B"; + tf_buffer->setTransform(t, "test"); + + int ret = RUN_ALL_TESTS(); + delete tf_buffer; + return ret; +} diff --git a/navigations/geometry2/tf2_sensor_msgs/test/test_tf2_sensor_msgs.py b/navigations/geometry2/tf2_sensor_msgs/test/test_tf2_sensor_msgs.py new file mode 100755 index 0000000..b797b7a --- /dev/null +++ b/navigations/geometry2/tf2_sensor_msgs/test/test_tf2_sensor_msgs.py @@ -0,0 +1,103 @@ +#!/usr/bin/env python + +from __future__ import print_function + +import unittest +import struct +import tf2_sensor_msgs +from sensor_msgs import point_cloud2 +from sensor_msgs.msg import PointField +from tf2_ros import TransformStamped +import copy + +## A sample python unit test +class PointCloudConversions(unittest.TestCase): + def setUp(self): + self.point_cloud_in = point_cloud2.PointCloud2() + self.point_cloud_in.fields = [PointField('x', 0, PointField.FLOAT32, 1), + PointField('y', 4, PointField.FLOAT32, 1), + PointField('z', 8, PointField.FLOAT32, 1)] + + self.point_cloud_in.point_step = 4 * 3 + self.point_cloud_in.height = 1 + # we add two points (with x, y, z to the cloud) + self.point_cloud_in.width = 2 + self.point_cloud_in.row_step = self.point_cloud_in.point_step * self.point_cloud_in.width + + points = [1, 2, 0, 10, 20, 30] + self.point_cloud_in.data = struct.pack('%sf' % len(points), *points) + + + self.transform_translate_xyz_300 = TransformStamped() + self.transform_translate_xyz_300.transform.translation.x = 300 + self.transform_translate_xyz_300.transform.translation.y = 300 + self.transform_translate_xyz_300.transform.translation.z = 300 + self.transform_translate_xyz_300.transform.rotation.w = 1 # no rotation so we only set w + + assert(list(point_cloud2.read_points(self.point_cloud_in)) == [(1.0, 2.0, 0.0), (10.0, 20.0, 30.0)]) + + def test_simple_transform(self): + old_data = copy.deepcopy(self.point_cloud_in.data) # deepcopy is not required here because we have a str for now + point_cloud_transformed = tf2_sensor_msgs.do_transform_cloud(self.point_cloud_in, self.transform_translate_xyz_300) + + k = 300 + expected_coordinates = [(1+k, 2+k, 0+k), (10+k, 20+k, 30+k)] + new_points = list(point_cloud2.read_points(point_cloud_transformed)) + print("new_points are %s" % new_points) + assert(expected_coordinates == new_points) + assert(old_data == self.point_cloud_in.data) # checking no modification in input cloud + + +## A simple unit test for tf2_sensor_msgs.do_transform_cloud (multi channel version) +class PointCloudConversionsMultichannel(unittest.TestCase): + TRANSFORM_OFFSET_DISTANCE = 300 + + def setUp(self): + self.point_cloud_in = point_cloud2.PointCloud2() + self.point_cloud_in.fields = [PointField('x', 0, PointField.FLOAT32, 1), + PointField('y', 4, PointField.FLOAT32, 1), + PointField('z', 8, PointField.FLOAT32, 1), + PointField('index', 12, PointField.INT32, 1)] + + self.point_cloud_in.point_step = 4 * 4 + self.point_cloud_in.height = 1 + # we add two points (with x, y, z to the cloud) + self.point_cloud_in.width = 2 + self.point_cloud_in.row_step = self.point_cloud_in.point_step * self.point_cloud_in.width + + self.points = [(1.0, 2.0, 0.0, 123), (10.0, 20.0, 30.0, 456)] + for point in self.points: + self.point_cloud_in.data += struct.pack('3fi', *point) + + self.transform_translate_xyz_300 = TransformStamped() + self.transform_translate_xyz_300.transform.translation.x = self.TRANSFORM_OFFSET_DISTANCE + self.transform_translate_xyz_300.transform.translation.y = self.TRANSFORM_OFFSET_DISTANCE + self.transform_translate_xyz_300.transform.translation.z = self.TRANSFORM_OFFSET_DISTANCE + self.transform_translate_xyz_300.transform.rotation.w = 1 # no rotation so we only set w + + assert(list(point_cloud2.read_points(self.point_cloud_in)) == self.points) + + def test_simple_transform_multichannel(self): + old_data = copy.deepcopy(self.point_cloud_in.data) # deepcopy is not required here because we have a str for now + point_cloud_transformed = tf2_sensor_msgs.do_transform_cloud(self.point_cloud_in, self.transform_translate_xyz_300) + + expected_coordinates = [] + for point in self.points: + expected_coordinates += [( + point[0] + self.TRANSFORM_OFFSET_DISTANCE, + point[1] + self.TRANSFORM_OFFSET_DISTANCE, + point[2] + self.TRANSFORM_OFFSET_DISTANCE, + point[3] # index channel must be kept same + )] + + new_points = list(point_cloud2.read_points(point_cloud_transformed)) + print("new_points are %s" % new_points) + assert(expected_coordinates == new_points) + assert(old_data == self.point_cloud_in.data) # checking no modification in input cloud + + +if __name__ == '__main__': + import rosunit + rosunit.unitrun("test_tf2_sensor_msgs", "test_point_cloud_conversion", PointCloudConversions) + rosunit.unitrun("test_tf2_sensor_msgs", "test_point_cloud_conversion", PointCloudConversionsMultichannel) + diff --git a/navigations/global_planner/CHANGELOG.rst b/navigations/global_planner/CHANGELOG.rst new file mode 100755 index 0000000..316c2a8 --- /dev/null +++ b/navigations/global_planner/CHANGELOG.rst @@ -0,0 +1,194 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package global_planner +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +1.17.3 (2023-01-10) +------------------- +* [ROS-O] various patches (`#1225 `_) + * do not specify obsolete c++11 standard + this breaks with current versions of log4cxx. + * update pluginlib include paths + the non-hpp headers have been deprecated since kinetic + * use lambdas in favor of boost::bind + Using boost's _1 as a global system is deprecated since C++11. + The ROS packages in Debian removed the implicit support for the global symbols, + so this code fails to compile there without the patch. +* Contributors: Michael Görner + +1.17.2 (2022-06-20) +------------------- +* Throttled failed to get plan error to 5 seconds (`#1102 `_) +* Fixed the risk of divide by zero. (`#1099 `_) +* No virtual destructor polyformic classes fixed. (`#1100 `_) +* Fixes `#1026 `_ (`#1028 `_) +* correctly delete previously allocated array (`#1025 `_) + Co-authored-by: Fedor Vlasov +* Contributors: David V. Lu!!, Noriaki Ando, Orhan G. Hafif, mechatheo + +1.17.1 (2020-08-27) +------------------- + +1.17.0 (2020-04-02) +------------------- +* Merge pull request `#982 `_ from ros-planning/noetic_prep + Noetic Migration +* increase required cmake version +* Contributors: Michael Ferguson + +1.16.6 (2020-03-18) +------------------- + +1.16.5 (2020-03-15) +------------------- +* [melodic] updated install for better portability. (`#973 `_) +* Contributors: Sean Yen + +1.16.4 (2020-03-04) +------------------- +* [Windows][melodic] Navigation (except for map_server and amcl) Windows build bring up (`#851 `_) +* parameter for enabling outlineMap added (`#926 `_) +* Contributors: Pavel Shumejko, Sean Yen + +1.16.3 (2019-11-15) +------------------- +* Remove unused visualize_potential (`#866 `_) +* remove unused costmap_pub_frequency (`#858 `_) +* Fix `#845 `_ (`#846 `_) +* Merge pull request `#831 `_ from ros-planning/feature/remove_slashes + [melodic] Remove leading slashes from default frame_id parameters +* Remove leading slashes from default frame_id parameters +* Contributors: David V. Lu, David V. Lu!!, Michael Ferguson, Stepan Kostusiev + +1.16.2 (2018-07-31) +------------------- + +1.16.1 (2018-07-28) +------------------- + +1.16.0 (2018-07-25) +------------------- +* Switch to TF2 `#755 `_ +* feat(orientation_filter): Added additional orientation filter options (`#739 `_) + * feat(orientation_filter): Added additional orientation filter options + Enables plan references with different orientations for omni-base + controllers. The following options are added: + - Backward (backward path traversal, pose points to previous point) + - Leftward (lateral path traversal in the positive y direction) + - Rightward (lateral path traversal in the negative y direction) + * Updated orientation filter option description + * Added window size parameter to orientation filter + Previously, the orientation was calculated using the current and the + next point. However, when the path is somewhat jumpy, this results in + poor orientations. By adding this parameter and altering the orientation + calculation, the calculated orientation can be smoothened along the path + by taking into account a larger window. The orientation of index point i + will be calculated using the positions of i - window_size and i + + window_size. +* Contributors: Michael Ferguson, Rein Appeldoorn, Vincent Rabaud + +1.15.2 (2018-03-22) +------------------- +* Merge pull request `#673 `_ from ros-planning/email_update_lunar + update maintainer email (lunar) +* Merge pull request `#649 `_ from aaronhoy/lunar_add_ahoy + Add myself as a maintainer. +* Rebase PRs from Indigo/Kinetic (`#637 `_) + * Respect planner_frequency intended behavior (`#622 `_) + * Only do a getRobotPose when no start pose is given (`#628 `_) + Omit the unnecessary call to getRobotPose when the start pose was + already given, so that move_base can also generate a path in + situations where getRobotPose would fail. + This is actually to work around an issue of getRobotPose randomly + failing. + * Update gradient_path.cpp (`#576 `_) + * Update gradient_path.cpp + * Update navfn.cpp + * update to use non deprecated pluginlib macro (`#630 `_) + * update to use non deprecated pluginlib macro + * multiline version as well + * Print SDL error on IMG_Load failure in server_map (`#631 `_) +* Contributors: Aaron Hoy, David V. Lu!!, Michael Ferguson + +1.15.1 (2017-08-14) +------------------- + +1.15.0 (2017-08-07) +------------------- +* convert packages to format2 +* Fix CMakeLists + package.xmls (`#548 `_) +* Fix to increment 'cycle' in while loop (`#546 `_) +* Fix to check index value before accessing to element of potential array (`#547 `_) +* Set frame_id and stamp on Path message even if path is not found. (`#533 `_) +* Contributors: Junya Hayashi, Martin Günther, Mikael Arguedas + +1.14.0 (2016-05-20) +------------------- + +1.13.1 (2015-10-29) +------------------- +* Add missing angles dependecy +* Fix for `#337 `_ +* Contributors: David V. Lu!!, Gary Servin + +1.13.0 (2015-03-17) +------------------- +* Fixing various memory freeing operations +* Add Orientation Filter to Global Planner +* Contributors: Alex Bencz, David V. Lu!!, James Servos, Michael Ferguson + +1.12.0 (2015-02-04) +------------------- +* update maintainer email +* Contributors: Michael Ferguson + +1.11.15 (2015-02-03) +-------------------- + +1.11.14 (2014-12-05) +-------------------- + +1.11.13 (2014-10-02) +-------------------- + +1.11.12 (2014-10-01) +-------------------- +* Add Gradient Path's cycle limit to GridPath +* When clearing endpoint, do not overwrite potentials +* Consolidate usage of POT_HIGH +* Contributors: David V. Lu!! + +1.11.11 (2014-07-23) +-------------------- +* Minor code cleanup +* Update package.xml +* Contributors: David Lu!!, Enrique Fernández Perdomo + +1.11.10 (2014-06-25) +-------------------- +* Remove unnecessary colons +* global_planner now pushes the goal onto the end of the global path +* move_base planService now searches out from desired goal +* Contributors: David Lu!!, Kaijen Hsiao + +1.11.9 (2014-06-10) +------------------- +* uses ::hypot(x, y) instead of sqrt(x*x, y*y) +* Contributors: Enrique Fernández Perdomo + +1.11.8 (2014-05-21) +------------------- + +1.11.7 (2014-05-21) +------------------- + +1.11.5 (2014-01-30) +------------------- +* Global Planner Cleanup +* Create the vector reversed instead of reverse it after +* Reversed the plan vector +* global_planner: Fix bgp_plugin.xml file and install it +* Improved Global Planner (from Groovy branch) + +1.11.4 (2013-09-27) +------------------- +* Package URL Updates diff --git a/navigations/global_planner/CMakeLists.txt b/navigations/global_planner/CMakeLists.txt new file mode 100755 index 0000000..33415a3 --- /dev/null +++ b/navigations/global_planner/CMakeLists.txt @@ -0,0 +1,77 @@ +cmake_minimum_required(VERSION 3.0.2) +project(global_planner) + +find_package(catkin REQUIRED + COMPONENTS + angles + costmap_2d + dynamic_reconfigure + geometry_msgs + nav_core + navfn + nav_msgs + pluginlib + roscpp + tf2_geometry_msgs + tf2_ros +) + +generate_dynamic_reconfigure_options( + cfg/GlobalPlanner.cfg +) + +catkin_package( + INCLUDE_DIRS include + LIBRARIES ${PROJECT_NAME} + CATKIN_DEPENDS + costmap_2d + dynamic_reconfigure + geometry_msgs + nav_core + navfn + nav_msgs + pluginlib + roscpp + tf2_ros +) + +include_directories( + include + ${catkin_INCLUDE_DIRS} +) + +add_library(${PROJECT_NAME} + src/quadratic_calculator.cpp + src/dijkstra.cpp + src/astar.cpp + src/grid_path.cpp + src/gradient_path.cpp + src/orientation_filter.cpp + src/planner_core.cpp +) +add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) +target_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES}) + +add_executable(planner + src/plan_node.cpp +) +add_dependencies(planner ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) +target_link_libraries(planner + ${PROJECT_NAME} + ${catkin_LIBRARIES} +) + +install(TARGETS ${PROJECT_NAME} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) + +install(TARGETS planner + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) + +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} + PATTERN ".svn" EXCLUDE) + +install(FILES bgp_plugin.xml + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) diff --git a/navigations/global_planner/bgp_plugin.xml b/navigations/global_planner/bgp_plugin.xml new file mode 100755 index 0000000..39d42fc --- /dev/null +++ b/navigations/global_planner/bgp_plugin.xml @@ -0,0 +1,7 @@ + + + + A implementation of a grid based planner using Dijkstras or A* + + + diff --git a/navigations/global_planner/cfg/GlobalPlanner.cfg b/navigations/global_planner/cfg/GlobalPlanner.cfg new file mode 100755 index 0000000..f43700c --- /dev/null +++ b/navigations/global_planner/cfg/GlobalPlanner.cfg @@ -0,0 +1,33 @@ +#!/usr/bin/env python +PACKAGE = "global_planner" + +from dynamic_reconfigure.parameter_generator_catkin import ParameterGenerator, int_t, double_t, bool_t + +gen = ParameterGenerator() + +gen.add("lethal_cost", int_t, 0, "Lethal Cost", 253, 1, 255) +gen.add("neutral_cost", int_t, 0, "Neutral Cost", 50, 1, 255) +gen.add("cost_factor", double_t, 0, "Factor to multiply each cost from costmap by", 3.0, 0.01, 5.0) +gen.add("publish_potential", bool_t, 0, "Publish Potential Costmap", True) + +orientation_enum = gen.enum([ + gen.const("None", int_t, 0, "No orientations added except goal orientation"), + gen.const("Forward", int_t, 1, + "Positive x axis points along path, except for the goal orientation"), + gen.const("Interpolate", int_t, 2, "Orientations are a linear blend of start and goal pose"), + gen.const("ForwardThenInterpolate", + int_t, 3, "Forward orientation until last straightaway, then a linear blend until the goal pose"), + gen.const("Backward", int_t, 4, + "Negative x axis points along the path, except for the goal orientation"), + gen.const("Leftward", int_t, 5, + "Positive y axis points along the path, except for the goal orientation"), + gen.const("Rightward", int_t, 6, + "Negative y axis points along the path, except for the goal orientation"), +], "How to set the orientation of each point") + +gen.add("orientation_mode", int_t, 0, "How to set the orientation of each point", 1, 0, 6, + edit_method=orientation_enum) +gen.add("orientation_window_size", int_t, 0, "What window to use to determine the orientation based on the " + "position derivative specified by the orientation mode", 1, 1, 255) + +exit(gen.generate(PACKAGE, "global_planner", "GlobalPlanner")) diff --git a/navigations/global_planner/include/global_planner/astar.h b/navigations/global_planner/include/global_planner/astar.h new file mode 100755 index 0000000..21f0e5d --- /dev/null +++ b/navigations/global_planner/include/global_planner/astar.h @@ -0,0 +1,76 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2008, 2013, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: Eitan Marder-Eppstein + * David V. Lu!! + *********************************************************************/ +#ifndef _ASTAR_H +#define _ASTAR_H + +#include +#include +#include +#include + +namespace global_planner { +class Index { + public: + Index(int a, float b) { + i = a; + cost = b; + } + int i; + float cost; +}; + +struct greater1 { + bool operator()(const Index& a, const Index& b) const { + return a.cost > b.cost; + } +}; + +class AStarExpansion : public Expander { + public: + AStarExpansion(PotentialCalculator* p_calc, int nx, int ny); + virtual ~AStarExpansion() {} + bool calculatePotentials(unsigned char* costs, double start_x, double start_y, double end_x, double end_y, int cycles, + float* potential); + private: + void add(unsigned char* costs, float* potential, float prev_potential, int next_i, int end_x, int end_y); + std::vector queue_; +}; + +} //end namespace global_planner +#endif + diff --git a/navigations/global_planner/include/global_planner/dijkstra.h b/navigations/global_planner/include/global_planner/dijkstra.h new file mode 100755 index 0000000..89646ce --- /dev/null +++ b/navigations/global_planner/include/global_planner/dijkstra.h @@ -0,0 +1,110 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2008, 2013, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: Eitan Marder-Eppstein + * David V. Lu!! + *********************************************************************/ +#ifndef _DIJKSTRA_H +#define _DIJKSTRA_H + +#define PRIORITYBUFSIZE 10000 +#include +#include +#include +#include + +#include +#include + +// inserting onto the priority blocks +#define push_cur(n) { if (n>=0 && n=0 && n=0 && n= lethal_cost_) + c = lethal_cost_ - 1; + return c; + } + return lethal_cost_; + } + + /** block priority buffers */ + int *buffer1_, *buffer2_, *buffer3_; /**< storage buffers for priority blocks */ + int *currentBuffer_, *nextBuffer_, *overBuffer_; /**< priority buffer block ptrs */ + int currentEnd_, nextEnd_, overEnd_; /**< end points of arrays */ + bool *pending_; /**< pending_ cells during propagation */ + bool precise_; + + /** block priority thresholds */ + float threshold_; /**< current threshold */ + float priorityIncrement_; /**< priority threshold increment */ + +}; +} //end namespace global_planner +#endif diff --git a/navigations/global_planner/include/global_planner/expander.h b/navigations/global_planner/include/global_planner/expander.h new file mode 100755 index 0000000..6df8e52 --- /dev/null +++ b/navigations/global_planner/include/global_planner/expander.h @@ -0,0 +1,107 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2008, 2013, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: Eitan Marder-Eppstein + * David V. Lu!! + *********************************************************************/ +#ifndef _EXPANDER_H +#define _EXPANDER_H +#include +#include + +namespace global_planner { + +class Expander { + public: + Expander(PotentialCalculator* p_calc, int nx, int ny) : + unknown_(true), lethal_cost_(253), neutral_cost_(50), factor_(3.0), p_calc_(p_calc) { + setSize(nx, ny); + } + virtual ~Expander() {} + virtual bool calculatePotentials(unsigned char* costs, double start_x, double start_y, double end_x, double end_y, + int cycles, float* potential) = 0; + + /** + * @brief Sets or resets the size of the map + * @param nx The x size of the map + * @param ny The y size of the map + */ + virtual void setSize(int nx, int ny) { + nx_ = nx; + ny_ = ny; + ns_ = nx * ny; + } /**< sets or resets the size of the map */ + void setLethalCost(unsigned char lethal_cost) { + lethal_cost_ = lethal_cost; + } + void setNeutralCost(unsigned char neutral_cost) { + neutral_cost_ = neutral_cost; + } + void setFactor(float factor) { + factor_ = factor; + } + void setHasUnknown(bool unknown) { + unknown_ = unknown; + } + + void clearEndpoint(unsigned char* costs, float* potential, int gx, int gy, int s){ + int startCell = toIndex(gx, gy); + for(int i=-s;i<=s;i++){ + for(int j=-s;j<=s;j++){ + int n = startCell+i+nx_*j; + if(potential[n]calculatePotential(potential, c, n); + potential[n] = pot; + } + } + } + + protected: + inline int toIndex(int x, int y) { + return x + nx_ * y; + } + + int nx_, ny_, ns_; /**< size of grid, in pixels */ + bool unknown_; + unsigned char lethal_cost_, neutral_cost_; + int cells_visited_; + float factor_; + PotentialCalculator* p_calc_; + +}; + +} //end namespace global_planner +#endif diff --git a/navigations/global_planner/include/global_planner/gradient_path.h b/navigations/global_planner/include/global_planner/gradient_path.h new file mode 100755 index 0000000..619f9be --- /dev/null +++ b/navigations/global_planner/include/global_planner/gradient_path.h @@ -0,0 +1,78 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2008, 2013, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: Eitan Marder-Eppstein + * David V. Lu!! + *********************************************************************/ +#ifndef _GRADIENT_PATH_H +#define _GRADIENT_PATH_H + +#include +#include +#include + +namespace global_planner { + +class GradientPath : public Traceback { + public: + GradientPath(PotentialCalculator* p_calc); + virtual ~GradientPath(); + + void setSize(int xs, int ys); + + // + // Path construction + // Find gradient at array points, interpolate path + // Use step size of pathStep, usually 0.5 pixel + // + // Some sanity checks: + // 1. Stuck at same index position + // 2. Doesn't get near goal + // 3. Surrounded by high potentials + // + bool getPath(float* potential, double start_x, double start_y, double end_x, double end_y, std::vector >& path); + private: + inline int getNearestPoint(int stc, float dx, float dy) { + int pt = stc + (int)round(dx) + (int)(xs_ * round(dy)); + return std::max(0, std::min(xs_ * ys_ - 1, pt)); + } + float gradCell(float* potential, int n); + + float *gradx_, *grady_; /**< gradient arrays, size of potential array */ + + float pathStep_; /**< step size for following gradient */ +}; + +} //end namespace global_planner +#endif diff --git a/navigations/global_planner/include/global_planner/grid_path.h b/navigations/global_planner/include/global_planner/grid_path.h new file mode 100755 index 0000000..ed37f4e --- /dev/null +++ b/navigations/global_planner/include/global_planner/grid_path.h @@ -0,0 +1,53 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2008, 2013, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: Eitan Marder-Eppstein + * David V. Lu!! + *********************************************************************/ +#ifndef _GRID_PATH_H +#define _GRID_PATH_H +#include +#include + +namespace global_planner { + +class GridPath : public Traceback { + public: + GridPath(PotentialCalculator* p_calc): Traceback(p_calc){} + virtual ~GridPath() {} + bool getPath(float* potential, double start_x, double start_y, double end_x, double end_y, std::vector >& path); +}; + +} //end namespace global_planner +#endif diff --git a/navigations/global_planner/include/global_planner/orientation_filter.h b/navigations/global_planner/include/global_planner/orientation_filter.h new file mode 100755 index 0000000..6f52eb4 --- /dev/null +++ b/navigations/global_planner/include/global_planner/orientation_filter.h @@ -0,0 +1,67 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2015, David V. Lu!! + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of David V. Lu nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: David V. Lu!! + *********************************************************************/ +#ifndef GLOBAL_PLANNER_ORIENTATION_FILTER_H +#define GLOBAL_PLANNER_ORIENTATION_FILTER_H +#include + +namespace global_planner { + +enum OrientationMode { NONE, FORWARD, INTERPOLATE, FORWARDTHENINTERPOLATE, BACKWARD, LEFTWARD, RIGHTWARD }; + +class OrientationFilter { + public: + OrientationFilter() : omode_(NONE) {} + + + virtual void processPath(const geometry_msgs::PoseStamped& start, + std::vector& path); + + void setAngleBasedOnPositionDerivative(std::vector& path, int index); + void interpolate(std::vector& path, + int start_index, int end_index); + + void setMode(OrientationMode new_mode){ omode_ = new_mode; } + void setMode(int new_mode){ setMode((OrientationMode) new_mode); } + + void setWindowSize(size_t window_size){ window_size_ = window_size; } + protected: + OrientationMode omode_; + int window_size_; +}; + +} //end namespace global_planner +#endif diff --git a/navigations/global_planner/include/global_planner/planner_core.h b/navigations/global_planner/include/global_planner/planner_core.h new file mode 100755 index 0000000..5c2f7fb --- /dev/null +++ b/navigations/global_planner/include/global_planner/planner_core.h @@ -0,0 +1,212 @@ +#ifndef _PLANNERCORE_H +#define _PLANNERCORE_H +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2008, 2013, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: Eitan Marder-Eppstein + * David V. Lu!! + *********************************************************************/ +#define POT_HIGH 1.0e10 // unassigned cell potential +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +namespace global_planner { + +class Expander; +class GridPath; + +/** + * @class PlannerCore + * @brief Provides a ROS wrapper for the global_planner planner which runs a fast, interpolated navigation function on a costmap. + */ + +class GlobalPlanner : public nav_core::BaseGlobalPlanner { + public: + /** + * @brief Default constructor for the PlannerCore object + */ + GlobalPlanner(); + + /** + * @brief Constructor for the PlannerCore object + * @param name The name of this planner + * @param costmap A pointer to the costmap to use + * @param frame_id Frame of the costmap + */ + GlobalPlanner(std::string name, costmap_2d::Costmap2D* costmap, std::string frame_id); + + /** + * @brief Default deconstructor for the PlannerCore object + */ + ~GlobalPlanner(); + + /** + * @brief Initialization function for the PlannerCore object + * @param name The name of this planner + * @param costmap_ros A pointer to the ROS wrapper of the costmap to use for planning + */ + void initialize(std::string name, costmap_2d::Costmap2DROS* costmap_ros); + + void initialize(std::string name, costmap_2d::Costmap2D* costmap, std::string frame_id); + + /** + * @brief Given a goal pose in the world, compute a plan + * @param start The start pose + * @param goal The goal pose + * @param plan The plan... filled by the planner + * @return True if a valid plan was found, false otherwise + */ + bool makePlan(const geometry_msgs::PoseStamped& start, const geometry_msgs::PoseStamped& goal, + std::vector& plan); + + /** + * @brief Given a goal pose in the world, compute a plan + * @param start The start pose + * @param goal The goal pose + * @param tolerance The tolerance on the goal point for the planner + * @param plan The plan... filled by the planner + * @return True if a valid plan was found, false otherwise + */ + bool makePlan(const geometry_msgs::PoseStamped& start, const geometry_msgs::PoseStamped& goal, double tolerance, + std::vector& plan); + + /** + * @brief Computes the full navigation function for the map given a point in the world to start from + * @param world_point The point to use for seeding the navigation function + * @return True if the navigation function was computed successfully, false otherwise + */ + bool computePotential(const geometry_msgs::Point& world_point); + + /** + * @brief Compute a plan to a goal after the potential for a start point has already been computed (Note: You should call computePotential first) + * @param start_x + * @param start_y + * @param end_x + * @param end_y + * @param goal The goal pose to create a plan to + * @param plan The plan... filled by the planner + * @return True if a valid plan was found, false otherwise + */ + bool getPlanFromPotential(double start_x, double start_y, double end_x, double end_y, + const geometry_msgs::PoseStamped& goal, + std::vector& plan); + + /** + * @brief Get the potential, or naviagation cost, at a given point in the world (Note: You should call computePotential first) + * @param world_point The point to get the potential for + * @return The navigation function's value at that point in the world + */ + double getPointPotential(const geometry_msgs::Point& world_point); + + /** + * @brief Check for a valid potential value at a given point in the world (Note: You should call computePotential first) + * @param world_point The point to get the potential for + * @return True if the navigation function is valid at that point in the world, false otherwise + */ + bool validPointPotential(const geometry_msgs::Point& world_point); + + /** + * @brief Check for a valid potential value at a given point in the world (Note: You should call computePotential first) + * @param world_point The point to get the potential for + * @param tolerance The tolerance on searching around the world_point specified + * @return True if the navigation function is valid at that point in the world, false otherwise + */ + bool validPointPotential(const geometry_msgs::Point& world_point, double tolerance); + + /** + * @brief Publish a path for visualization purposes + */ + void publishPlan(const std::vector& path); + + bool makePlanService(nav_msgs::GetPlan::Request& req, nav_msgs::GetPlan::Response& resp); + + protected: + + /** + * @brief Store a copy of the current costmap in \a costmap. Called by makePlan. + */ + costmap_2d::Costmap2D* costmap_; + std::string frame_id_; + ros::Publisher plan_pub_; + bool initialized_, allow_unknown_; + + private: + void mapToWorld(double mx, double my, double& wx, double& wy); + bool worldToMap(double wx, double wy, double& mx, double& my); + void clearRobotCell(const geometry_msgs::PoseStamped& global_pose, unsigned int mx, unsigned int my); + void publishPotential(float* potential); + + double planner_window_x_, planner_window_y_, default_tolerance_; + boost::mutex mutex_; + ros::ServiceServer make_plan_srv_; + + PotentialCalculator* p_calc_; + Expander* planner_; + Traceback* path_maker_; + OrientationFilter* orientation_filter_; + + bool publish_potential_; + ros::Publisher potential_pub_; + int publish_scale_; + + void outlineMap(unsigned char* costarr, int nx, int ny, unsigned char value); + + float* potential_array_; + unsigned int start_x_, start_y_, end_x_, end_y_; + + bool old_navfn_behavior_; + float convert_offset_; + + bool outline_map_; + + dynamic_reconfigure::Server *dsrv_; + void reconfigureCB(global_planner::GlobalPlannerConfig &config, uint32_t level); + +}; + +} //end namespace global_planner + +#endif diff --git a/navigations/global_planner/include/global_planner/potential_calculator.h b/navigations/global_planner/include/global_planner/potential_calculator.h new file mode 100755 index 0000000..9284abb --- /dev/null +++ b/navigations/global_planner/include/global_planner/potential_calculator.h @@ -0,0 +1,82 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2008, 2013, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: Eitan Marder-Eppstein + * David V. Lu!! + *********************************************************************/ +#ifndef _POTENTIAL_CALCULATOR_H +#define _POTENTIAL_CALCULATOR_H + +#include + +namespace global_planner { + +class PotentialCalculator { + public: + PotentialCalculator(int nx, int ny) { + setSize(nx, ny); + } + virtual ~PotentialCalculator() {} + virtual float calculatePotential(float* potential, unsigned char cost, int n, float prev_potential=-1){ + if(prev_potential < 0){ + // get min of neighbors + float min_h = std::min( potential[n - 1], potential[n + 1] ), + min_v = std::min( potential[n - nx_], potential[n + nx_]); + prev_potential = std::min(min_h, min_v); + } + + return prev_potential + cost; + } + + /** + * @brief Sets or resets the size of the map + * @param nx The x size of the map + * @param ny The y size of the map + */ + virtual void setSize(int nx, int ny) { + nx_ = nx; + ny_ = ny; + ns_ = nx * ny; + } /**< sets or resets the size of the map */ + + protected: + inline int toIndex(int x, int y) { + return x + nx_ * y; + } + + int nx_, ny_, ns_; /**< size of grid, in pixels */ +}; + +} //end namespace global_planner +#endif diff --git a/navigations/global_planner/include/global_planner/quadratic_calculator.h b/navigations/global_planner/include/global_planner/quadratic_calculator.h new file mode 100755 index 0000000..74da818 --- /dev/null +++ b/navigations/global_planner/include/global_planner/quadratic_calculator.h @@ -0,0 +1,54 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2008, 2013, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: Eitan Marder-Eppstein + * David V. Lu!! + *********************************************************************/ +#ifndef _QUADRATIC_CALCULATOR_H +#define _QUADRATIC_CALCULATOR_H +#include +#include + +namespace global_planner { + +class QuadraticCalculator : public PotentialCalculator { + public: + QuadraticCalculator(int nx, int ny): PotentialCalculator(nx,ny) {} + + float calculatePotential(float* potential, unsigned char cost, int n, float prev_potential); +}; + + +} //end namespace global_planner +#endif diff --git a/navigations/global_planner/include/global_planner/traceback.h b/navigations/global_planner/include/global_planner/traceback.h new file mode 100755 index 0000000..d9d7381 --- /dev/null +++ b/navigations/global_planner/include/global_planner/traceback.h @@ -0,0 +1,67 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2008, 2013, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: Eitan Marder-Eppstein + * David V. Lu!! + *********************************************************************/ +#ifndef _TRACEBACK_H +#define _TRACEBACK_H +#include +#include + +namespace global_planner { + +class Traceback { + public: + Traceback(PotentialCalculator* p_calc) : p_calc_(p_calc) {} + virtual ~Traceback() {} + virtual bool getPath(float* potential, double start_x, double start_y, double end_x, double end_y, std::vector >& path) = 0; + virtual void setSize(int xs, int ys) { + xs_ = xs; + ys_ = ys; + } + inline int getIndex(int x, int y) { + return x + y * xs_; + } + void setLethalCost(unsigned char lethal_cost) { + lethal_cost_ = lethal_cost; + } + protected: + int xs_, ys_; + unsigned char lethal_cost_; + PotentialCalculator* p_calc_; +}; + +} //end namespace global_planner +#endif diff --git a/navigations/global_planner/package.xml b/navigations/global_planner/package.xml new file mode 100755 index 0000000..9b62295 --- /dev/null +++ b/navigations/global_planner/package.xml @@ -0,0 +1,36 @@ + + + + global_planner + 1.17.3 + + A path planner library and node. + + David V. Lu!! + Michael Ferguson + Aaron Hoy + BSD + + David Lu!! + http://wiki.ros.org/global_planner + + catkin + + angles + tf2_geometry_msgs + + costmap_2d + dynamic_reconfigure + geometry_msgs + nav_core + nav_msgs + navfn + pluginlib + roscpp + tf2_ros + + + + + + diff --git a/navigations/global_planner/src/astar.cpp b/navigations/global_planner/src/astar.cpp new file mode 100755 index 0000000..696756f --- /dev/null +++ b/navigations/global_planner/src/astar.cpp @@ -0,0 +1,98 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2008, 2013, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: Eitan Marder-Eppstein + * David V. Lu!! + *********************************************************************/ +#include +#include + +namespace global_planner { + +AStarExpansion::AStarExpansion(PotentialCalculator* p_calc, int xs, int ys) : + Expander(p_calc, xs, ys) { +} + +bool AStarExpansion::calculatePotentials(unsigned char* costs, double start_x, double start_y, double end_x, double end_y, + int cycles, float* potential) { + queue_.clear(); + int start_i = toIndex(start_x, start_y); + queue_.push_back(Index(start_i, 0)); + + std::fill(potential, potential + ns_, POT_HIGH); + potential[start_i] = 0; + + int goal_i = toIndex(end_x, end_y); + int cycle = 0; + + while (queue_.size() > 0 && cycle < cycles) { + Index top = queue_[0]; + std::pop_heap(queue_.begin(), queue_.end(), greater1()); + queue_.pop_back(); + + int i = top.i; + if (i == goal_i) + return true; + + add(costs, potential, potential[i], i + 1, end_x, end_y); + add(costs, potential, potential[i], i - 1, end_x, end_y); + add(costs, potential, potential[i], i + nx_, end_x, end_y); + add(costs, potential, potential[i], i - nx_, end_x, end_y); + + cycle++; + } + + return false; +} + +void AStarExpansion::add(unsigned char* costs, float* potential, float prev_potential, int next_i, int end_x, + int end_y) { + if (next_i < 0 || next_i >= ns_) + return; + + if (potential[next_i] < POT_HIGH) + return; + + if(costs[next_i]>=lethal_cost_ && !(unknown_ && costs[next_i]==costmap_2d::NO_INFORMATION)) + return; + + potential[next_i] = p_calc_->calculatePotential(potential, costs[next_i] + neutral_cost_, next_i, prev_potential); + int x = next_i % nx_, y = next_i / nx_; + float distance = abs(end_x - x) + abs(end_y - y); + + queue_.push_back(Index(next_i, potential[next_i] + distance * neutral_cost_)); + std::push_heap(queue_.begin(), queue_.end(), greater1()); +} + +} //end namespace global_planner diff --git a/navigations/global_planner/src/dijkstra.cpp b/navigations/global_planner/src/dijkstra.cpp new file mode 100755 index 0000000..7e069d7 --- /dev/null +++ b/navigations/global_planner/src/dijkstra.cpp @@ -0,0 +1,234 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2008, 2013, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: Eitan Marder-Eppstein + * David V. Lu!! + *********************************************************************/ +#include +#include +namespace global_planner { + +DijkstraExpansion::DijkstraExpansion(PotentialCalculator* p_calc, int nx, int ny) : + Expander(p_calc, nx, ny), pending_(NULL), precise_(false) { + // priority buffers + buffer1_ = new int[PRIORITYBUFSIZE]; + buffer2_ = new int[PRIORITYBUFSIZE]; + buffer3_ = new int[PRIORITYBUFSIZE]; + + priorityIncrement_ = 2 * neutral_cost_; +} + +DijkstraExpansion::~DijkstraExpansion() { + delete[] buffer1_; + delete[] buffer2_; + delete[] buffer3_; + if (pending_) + delete[] pending_; +} + +// +// Set/Reset map size +// +void DijkstraExpansion::setSize(int xs, int ys) { + Expander::setSize(xs, ys); + if (pending_) + delete[] pending_; + + pending_ = new bool[ns_]; + memset(pending_, 0, ns_ * sizeof(bool)); +} + +// +// main propagation function +// Dijkstra method, breadth-first +// runs for a specified number of cycles, +// or until it runs out of cells to update, +// or until the Start cell is found (atStart = true) +// + +bool DijkstraExpansion::calculatePotentials(unsigned char* costs, double start_x, double start_y, double end_x, double end_y, + int cycles, float* potential) { + cells_visited_ = 0; + // priority buffers + threshold_ = lethal_cost_; + currentBuffer_ = buffer1_; + currentEnd_ = 0; + nextBuffer_ = buffer2_; + nextEnd_ = 0; + overBuffer_ = buffer3_; + overEnd_ = 0; + memset(pending_, 0, ns_ * sizeof(bool)); + std::fill(potential, potential + ns_, POT_HIGH); + + // set goal + int k = toIndex(start_x, start_y); + + if(precise_) + { + double dx = start_x - (int)start_x, dy = start_y - (int)start_y; + dx = floorf(dx * 100 + 0.5) / 100; + dy = floorf(dy * 100 + 0.5) / 100; + potential[k] = neutral_cost_ * 2 * dx * dy; + potential[k+1] = neutral_cost_ * 2 * (1-dx)*dy; + potential[k+nx_] = neutral_cost_*2*dx*(1-dy); + potential[k+nx_+1] = neutral_cost_*2*(1-dx)*(1-dy);//*/ + + push_cur(k+2); + push_cur(k-1); + push_cur(k+nx_-1); + push_cur(k+nx_+2); + + push_cur(k-nx_); + push_cur(k-nx_+1); + push_cur(k+nx_*2); + push_cur(k+nx_*2+1); + }else{ + potential[k] = 0; + push_cur(k+1); + push_cur(k-1); + push_cur(k-nx_); + push_cur(k+nx_); + } + + int nwv = 0; // max priority block size + int nc = 0; // number of cells put into priority blocks + int cycle = 0; // which cycle we're on + + // set up start cell + int startCell = toIndex(end_x, end_y); + + for (; cycle < cycles; cycle++) // go for this many cycles, unless interrupted + { + // + if (currentEnd_ == 0 && nextEnd_ == 0) // priority blocks empty + return false; + + // stats + nc += currentEnd_; + if (currentEnd_ > nwv) + nwv = currentEnd_; + + // reset pending_ flags on current priority buffer + int *pb = currentBuffer_; + int i = currentEnd_; + while (i-- > 0) + pending_[*(pb++)] = false; + + // process current priority buffer + pb = currentBuffer_; + i = currentEnd_; + while (i-- > 0) + updateCell(costs, potential, *pb++); + + // swap priority blocks currentBuffer_ <=> nextBuffer_ + currentEnd_ = nextEnd_; + nextEnd_ = 0; + pb = currentBuffer_; // swap buffers + currentBuffer_ = nextBuffer_; + nextBuffer_ = pb; + + // see if we're done with this priority level + if (currentEnd_ == 0) { + threshold_ += priorityIncrement_; // increment priority threshold + currentEnd_ = overEnd_; // set current to overflow block + overEnd_ = 0; + pb = currentBuffer_; // swap buffers + currentBuffer_ = overBuffer_; + overBuffer_ = pb; + } + + // check if we've hit the Start cell + if (potential[startCell] < POT_HIGH) + break; + } + //ROS_INFO("CYCLES %d/%d ", cycle, cycles); + if (cycle < cycles) + return true; // finished up here + else + return false; +} + +// +// Critical function: calculate updated potential value of a cell, +// given its neighbors' values +// Planar-wave update calculation from two lowest neighbors in a 4-grid +// Quadratic approximation to the interpolated value +// No checking of bounds here, this function should be fast +// + +#define INVSQRT2 0.707106781 + +inline void DijkstraExpansion::updateCell(unsigned char* costs, float* potential, int n) { + cells_visited_++; + + // do planar wave update + float c = getCost(costs, n); + if (c >= lethal_cost_) // don't propagate into obstacles + return; + + float pot = p_calc_->calculatePotential(potential, c, n); + + // now add affected neighbors to priority blocks + if (pot < potential[n]) { + float le = INVSQRT2 * (float)getCost(costs, n - 1); + float re = INVSQRT2 * (float)getCost(costs, n + 1); + float ue = INVSQRT2 * (float)getCost(costs, n - nx_); + float de = INVSQRT2 * (float)getCost(costs, n + nx_); + potential[n] = pot; + //ROS_INFO("UPDATE %d %d %d %f", n, n%nx, n/nx, potential[n]); + if (pot < threshold_) // low-cost buffer block + { + if (potential[n - 1] > pot + le) + push_next(n-1); + if (potential[n + 1] > pot + re) + push_next(n+1); + if (potential[n - nx_] > pot + ue) + push_next(n-nx_); + if (potential[n + nx_] > pot + de) + push_next(n+nx_); + } else // overflow block + { + if (potential[n - 1] > pot + le) + push_over(n-1); + if (potential[n + 1] > pot + re) + push_over(n+1); + if (potential[n - nx_] > pot + ue) + push_over(n-nx_); + if (potential[n + nx_] > pot + de) + push_over(n+nx_); + } + } +} + +} //end namespace global_planner diff --git a/navigations/global_planner/src/gradient_path.cpp b/navigations/global_planner/src/gradient_path.cpp new file mode 100755 index 0000000..009febe --- /dev/null +++ b/navigations/global_planner/src/gradient_path.cpp @@ -0,0 +1,315 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2008, 2013, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: Eitan Marder-Eppstein + * David V. Lu!! + *********************************************************************/ +#include +#include +#include +#include + +namespace global_planner { + +GradientPath::GradientPath(PotentialCalculator* p_calc) : + Traceback(p_calc), pathStep_(0.5) { + gradx_ = grady_ = NULL; +} + +GradientPath::~GradientPath() { + + if (gradx_) + delete[] gradx_; + if (grady_) + delete[] grady_; +} + +void GradientPath::setSize(int xs, int ys) { + Traceback::setSize(xs, ys); + if (gradx_) + delete[] gradx_; + if (grady_) + delete[] grady_; + gradx_ = new float[xs * ys]; + grady_ = new float[xs * ys]; +} + +bool GradientPath::getPath(float* potential, double start_x, double start_y, double goal_x, double goal_y, std::vector >& path) { + std::pair current; + int stc = getIndex(goal_x, goal_y); + + // set up offset + float dx = goal_x - (int)goal_x; + float dy = goal_y - (int)goal_y; + int ns = xs_ * ys_; + memset(gradx_, 0, ns * sizeof(float)); + memset(grady_, 0, ns * sizeof(float)); + + int c = 0; + while (c++ xs_ * ys_ - xs_) // would be out of bounds + { + printf("[PathCalc] Out of bounds\n"); + return false; + } + + current.first = nx; + current.second = ny; + + //ROS_INFO("%d %d | %f %f ", stc%xs_, stc/xs_, dx, dy); + + path.push_back(current); + + bool oscillation_detected = false; + int npath = path.size(); + if (npath > 2 && path[npath - 1].first == path[npath - 3].first + && path[npath - 1].second == path[npath - 3].second) { + ROS_DEBUG("[PathCalc] oscillation detected, attempting fix."); + oscillation_detected = true; + } + + int stcnx = stc + xs_; + int stcpx = stc - xs_; + + // check for potentials at eight positions near cell + if (potential[stc] >= POT_HIGH || potential[stc + 1] >= POT_HIGH || potential[stc - 1] >= POT_HIGH + || potential[stcnx] >= POT_HIGH || potential[stcnx + 1] >= POT_HIGH || potential[stcnx - 1] >= POT_HIGH + || potential[stcpx] >= POT_HIGH || potential[stcpx + 1] >= POT_HIGH || potential[stcpx - 1] >= POT_HIGH + || oscillation_detected) { + ROS_DEBUG("[Path] Pot fn boundary, following grid (%0.1f/%d)", potential[stc], (int) path.size()); + // check eight neighbors to find the lowest + int minc = stc; + int minp = potential[stc]; + int st = stcpx - 1; + if (potential[st] < minp) { + minp = potential[st]; + minc = st; + } + st++; + if (potential[st] < minp) { + minp = potential[st]; + minc = st; + } + st++; + if (potential[st] < minp) { + minp = potential[st]; + minc = st; + } + st = stc - 1; + if (potential[st] < minp) { + minp = potential[st]; + minc = st; + } + st = stc + 1; + if (potential[st] < minp) { + minp = potential[st]; + minc = st; + } + st = stcnx - 1; + if (potential[st] < minp) { + minp = potential[st]; + minc = st; + } + st++; + if (potential[st] < minp) { + minp = potential[st]; + minc = st; + } + st++; + if (potential[st] < minp) { + minp = potential[st]; + minc = st; + } + stc = minc; + dx = 0; + dy = 0; + + //ROS_DEBUG("[Path] Pot: %0.1f pos: %0.1f,%0.1f", + // potential[stc], path[npath-1].first, path[npath-1].second); + + if (potential[stc] >= POT_HIGH) { + ROS_DEBUG("[PathCalc] No path found, high potential"); + //savemap("navfn_highpot"); + return 0; + } + } + + // have a good gradient here + else { + + // get grad at four positions near cell + gradCell(potential, stc); + gradCell(potential, stc + 1); + gradCell(potential, stcnx); + gradCell(potential, stcnx + 1); + + // get interpolated gradient + float x1 = (1.0 - dx) * gradx_[stc] + dx * gradx_[stc + 1]; + float x2 = (1.0 - dx) * gradx_[stcnx] + dx * gradx_[stcnx + 1]; + float x = (1.0 - dy) * x1 + dy * x2; // interpolated x + float y1 = (1.0 - dx) * grady_[stc] + dx * grady_[stc + 1]; + float y2 = (1.0 - dx) * grady_[stcnx] + dx * grady_[stcnx + 1]; + float y = (1.0 - dy) * y1 + dy * y2; // interpolated y + + // show gradients + ROS_DEBUG( + "[Path] %0.2f,%0.2f %0.2f,%0.2f %0.2f,%0.2f %0.2f,%0.2f; final x=%.3f, y=%.3f\n", gradx_[stc], grady_[stc], gradx_[stc+1], grady_[stc+1], gradx_[stcnx], grady_[stcnx], gradx_[stcnx+1], grady_[stcnx+1], x, y); + + // check for zero gradient, failed + if (x == 0.0 && y == 0.0) { + ROS_DEBUG("[PathCalc] Zero gradient"); + return 0; + } + + // move in the right direction + float ss = pathStep_ / hypot(x, y); + dx += x * ss; + dy += y * ss; + + // check for overflow + if (dx > 1.0) { + stc++; + dx -= 1.0; + } + if (dx < -1.0) { + stc--; + dx += 1.0; + } + if (dy > 1.0) { + stc += xs_; + dy -= 1.0; + } + if (dy < -1.0) { + stc -= xs_; + dy += 1.0; + } + + } + + //printf("[Path] Pot: %0.1f grad: %0.1f,%0.1f pos: %0.1f,%0.1f\n", + // potential[stc], dx, dy, path[npath-1].first, path[npath-1].second); + } + + return false; +} + +/* + int + NavFn::calcPath(int n, int *st) + { + // set up start position at cell + // st is always upper left corner for 4-point bilinear interpolation + if (st == NULL) st = start; + int stc = st[1]*nx + st[0]; + + // go for cycles at most + for (int i=0; i 0.0) // check this cell + return 1.0; + + if (n < xs_ || n > xs_ * ys_ - xs_) // would be out of bounds + return 0.0; + float cv = potential[n]; + float dx = 0.0; + float dy = 0.0; + + // check for in an obstacle + if (cv >= POT_HIGH) { + if (potential[n - 1] < POT_HIGH) + dx = -lethal_cost_; + else if (potential[n + 1] < POT_HIGH) + dx = lethal_cost_; + + if (potential[n - xs_] < POT_HIGH) + dy = -lethal_cost_; + else if (potential[n + xs_] < POT_HIGH) + dy = lethal_cost_; + } + + else // not in an obstacle + { + // dx calc, average to sides + if (potential[n - 1] < POT_HIGH) + dx += potential[n - 1] - cv; + if (potential[n + 1] < POT_HIGH) + dx += cv - potential[n + 1]; + + // dy calc, average to sides + if (potential[n - xs_] < POT_HIGH) + dy += potential[n - xs_] - cv; + if (potential[n + xs_] < POT_HIGH) + dy += cv - potential[n + xs_]; + } + + // normalize + float norm = hypot(dx, dy); + if (norm > 0) { + norm = 1.0 / norm; + gradx_[n] = norm * dx; + grady_[n] = norm * dy; + } + return norm; +} + +} //end namespace global_planner + diff --git a/navigations/global_planner/src/grid_path.cpp b/navigations/global_planner/src/grid_path.cpp new file mode 100755 index 0000000..3bf49e4 --- /dev/null +++ b/navigations/global_planner/src/grid_path.cpp @@ -0,0 +1,85 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2008, 2013, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: Eitan Marder-Eppstein + * David V. Lu!! + *********************************************************************/ +#include +#include +#include +namespace global_planner { + +bool GridPath::getPath(float* potential, double start_x, double start_y, double end_x, double end_y, std::vector >& path) { + std::pair current; + current.first = end_x; + current.second = end_y; + + int start_index = getIndex(start_x, start_y); + + path.push_back(current); + int c = 0; + int ns = xs_ * ys_; + + while (getIndex(current.first, current.second) != start_index) { + float min_val = 1e10; + int min_x = 0, min_y = 0; + for (int xd = -1; xd <= 1; xd++) { + for (int yd = -1; yd <= 1; yd++) { + if (xd == 0 && yd == 0) + continue; + int x = current.first + xd, y = current.second + yd; + int index = getIndex(x, y); + if (potential[index] < min_val) { + min_val = potential[index]; + min_x = x; + min_y = y; + } + } + } + if (min_x == 0 && min_y == 0) + return false; + current.first = min_x; + current.second = min_y; + path.push_back(current); + + if(c++>ns*4){ + return false; + } + + } + return true; +} + +} //end namespace global_planner + diff --git a/navigations/global_planner/src/orientation_filter.cpp b/navigations/global_planner/src/orientation_filter.cpp new file mode 100755 index 0000000..4473dae --- /dev/null +++ b/navigations/global_planner/src/orientation_filter.cpp @@ -0,0 +1,135 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2015, David V. Lu!! + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of David V. Lu nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: David V. Lu!! + *********************************************************************/ +#include +#include +#include +#include +#include + +namespace global_planner { + +void set_angle(geometry_msgs::PoseStamped* pose, double angle) +{ + tf2::Quaternion q; + q.setRPY(0, 0, angle); + tf2::convert(q, pose->pose.orientation); +} + +void OrientationFilter::processPath(const geometry_msgs::PoseStamped& start, + std::vector& path) +{ + int n = path.size(); + if (n == 0) return; + switch(omode_) { + case FORWARD: + for(int i=0;i0 ){ + const double new_angle = tf2::getYaw(path[i-1].pose.orientation); + double diff = fabs(angles::shortest_angular_distance(new_angle, last)); + if( diff>0.35) + break; + else + i--; + } + + path[0].pose.orientation = start.pose.orientation; + interpolate(path, i, n-1); + break; + } +} + +void OrientationFilter::setAngleBasedOnPositionDerivative(std::vector& path, int index) +{ + int index0 = std::max(0, index - window_size_); + int index1 = std::min((int)path.size() - 1, index + window_size_); + + double x0 = path[index0].pose.position.x, + y0 = path[index0].pose.position.y, + x1 = path[index1].pose.position.x, + y1 = path[index1].pose.position.y; + + double angle = atan2(y1-y0,x1-x0); + set_angle(&path[index], angle); +} + +void OrientationFilter::interpolate(std::vector& path, + int start_index, int end_index) +{ + const double start_yaw = tf2::getYaw(path[start_index].pose.orientation), + end_yaw = tf2::getYaw(path[end_index ].pose.orientation); + double diff = angles::shortest_angular_distance(start_yaw, end_yaw); + double increment = diff/(end_index-start_index); + for(int i=start_index; i<=end_index; i++){ + double angle = start_yaw + increment * i; + set_angle(&path[i], angle); + } +} + + +}; diff --git a/navigations/global_planner/src/plan_node.cpp b/navigations/global_planner/src/plan_node.cpp new file mode 100755 index 0000000..c0156bf --- /dev/null +++ b/navigations/global_planner/src/plan_node.cpp @@ -0,0 +1,111 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2008, 2013, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: Bhaskara Marthi + * David V. Lu!! + *********************************************************************/ +#include +#include +#include +#include +#include + +namespace cm = costmap_2d; +namespace rm = geometry_msgs; + +using std::vector; +using rm::PoseStamped; +using std::string; +using cm::Costmap2D; +using cm::Costmap2DROS; + +namespace global_planner { + +class PlannerWithCostmap : public GlobalPlanner { + public: + PlannerWithCostmap(string name, Costmap2DROS* cmap); + bool makePlanService(navfn::MakeNavPlan::Request& req, navfn::MakeNavPlan::Response& resp); + + private: + void poseCallback(const rm::PoseStamped::ConstPtr& goal); + Costmap2DROS* cmap_; + ros::ServiceServer make_plan_service_; + ros::Subscriber pose_sub_; +}; + +bool PlannerWithCostmap::makePlanService(navfn::MakeNavPlan::Request& req, navfn::MakeNavPlan::Response& resp) { + vector path; + + req.start.header.frame_id = "map"; + req.goal.header.frame_id = "map"; + bool success = makePlan(req.start, req.goal, path); + resp.plan_found = success; + if (success) { + resp.path = path; + } + + return true; +} + +void PlannerWithCostmap::poseCallback(const rm::PoseStamped::ConstPtr& goal) { + geometry_msgs::PoseStamped global_pose; + cmap_->getRobotPose(global_pose); + vector path; + makePlan(global_pose, *goal, path); +} + +PlannerWithCostmap::PlannerWithCostmap(string name, Costmap2DROS* cmap) : + GlobalPlanner(name, cmap->getCostmap(), cmap->getGlobalFrameID()) { + ros::NodeHandle private_nh("~"); + cmap_ = cmap; + make_plan_service_ = private_nh.advertiseService("make_plan", &PlannerWithCostmap::makePlanService, this); + pose_sub_ = private_nh.subscribe("goal", 1, &PlannerWithCostmap::poseCallback, this); +} + +} // namespace + +int main(int argc, char** argv) { + ros::init(argc, argv, "global_planner"); + + tf2_ros::Buffer buffer(ros::Duration(10)); + tf2_ros::TransformListener tf(buffer); + + costmap_2d::Costmap2DROS lcr("costmap", buffer); + + global_planner::PlannerWithCostmap pppp("planner", &lcr); + + ros::spin(); + return 0; +} + diff --git a/navigations/global_planner/src/planner_core.cpp b/navigations/global_planner/src/planner_core.cpp new file mode 100755 index 0000000..5cfdd67 --- /dev/null +++ b/navigations/global_planner/src/planner_core.cpp @@ -0,0 +1,438 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2008, 2013, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: Eitan Marder-Eppstein + * David V. Lu!! + *********************************************************************/ +#include +#include +#include +#include + +#include +#include +#include +#include +#include + +//register this planner as a BaseGlobalPlanner plugin +PLUGINLIB_EXPORT_CLASS(global_planner::GlobalPlanner, nav_core::BaseGlobalPlanner) + +namespace global_planner { + +void GlobalPlanner::outlineMap(unsigned char* costarr, int nx, int ny, unsigned char value) { + unsigned char* pc = costarr; + for (int i = 0; i < nx; i++) + *pc++ = value; + pc = costarr + (ny - 1) * nx; + for (int i = 0; i < nx; i++) + *pc++ = value; + pc = costarr; + for (int i = 0; i < ny; i++, pc += nx) + *pc = value; + pc = costarr + nx - 1; + for (int i = 0; i < ny; i++, pc += nx) + *pc = value; +} + +GlobalPlanner::GlobalPlanner() : + costmap_(NULL), initialized_(false), allow_unknown_(true), + p_calc_(NULL), planner_(NULL), path_maker_(NULL), orientation_filter_(NULL), + potential_array_(NULL) { +} + +GlobalPlanner::GlobalPlanner(std::string name, costmap_2d::Costmap2D* costmap, std::string frame_id) : + GlobalPlanner() { + //initialize the planner + initialize(name, costmap, frame_id); +} + +GlobalPlanner::~GlobalPlanner() { + if (p_calc_) + delete p_calc_; + if (planner_) + delete planner_; + if (path_maker_) + delete path_maker_; + if (dsrv_) + delete dsrv_; +} + +void GlobalPlanner::initialize(std::string name, costmap_2d::Costmap2DROS* costmap_ros) { + initialize(name, costmap_ros->getCostmap(), costmap_ros->getGlobalFrameID()); +} + +void GlobalPlanner::initialize(std::string name, costmap_2d::Costmap2D* costmap, std::string frame_id) { + if (!initialized_) { + ros::NodeHandle private_nh("~/" + name); + costmap_ = costmap; + frame_id_ = frame_id; + + unsigned int cx = costmap->getSizeInCellsX(), cy = costmap->getSizeInCellsY(); + + private_nh.param("old_navfn_behavior", old_navfn_behavior_, false); + if(!old_navfn_behavior_) + convert_offset_ = 0.5; + else + convert_offset_ = 0.0; + + bool use_quadratic; + private_nh.param("use_quadratic", use_quadratic, true); + if (use_quadratic) + p_calc_ = new QuadraticCalculator(cx, cy); + else + p_calc_ = new PotentialCalculator(cx, cy); + + bool use_dijkstra; + private_nh.param("use_dijkstra", use_dijkstra, true); + if (use_dijkstra) + { + DijkstraExpansion* de = new DijkstraExpansion(p_calc_, cx, cy); + if(!old_navfn_behavior_) + de->setPreciseStart(true); + planner_ = de; + } + else + planner_ = new AStarExpansion(p_calc_, cx, cy); + + bool use_grid_path; + private_nh.param("use_grid_path", use_grid_path, false); + if (use_grid_path) + path_maker_ = new GridPath(p_calc_); + else + path_maker_ = new GradientPath(p_calc_); + + orientation_filter_ = new OrientationFilter(); + + plan_pub_ = private_nh.advertise("plan", 1); + potential_pub_ = private_nh.advertise("potential", 1); + + private_nh.param("allow_unknown", allow_unknown_, true); + planner_->setHasUnknown(allow_unknown_); + private_nh.param("planner_window_x", planner_window_x_, 0.0); + private_nh.param("planner_window_y", planner_window_y_, 0.0); + private_nh.param("default_tolerance", default_tolerance_, 0.0); + private_nh.param("publish_scale", publish_scale_, 100); + private_nh.param("outline_map", outline_map_, true); + + make_plan_srv_ = private_nh.advertiseService("make_plan", &GlobalPlanner::makePlanService, this); + + dsrv_ = new dynamic_reconfigure::Server(ros::NodeHandle("~/" + name)); + dynamic_reconfigure::Server::CallbackType cb = + [this](auto& config, auto level){ reconfigureCB(config, level); }; + dsrv_->setCallback(cb); + + initialized_ = true; + } else + ROS_WARN("This planner has already been initialized, you can't call it twice, doing nothing"); + +} + +void GlobalPlanner::reconfigureCB(global_planner::GlobalPlannerConfig& config, uint32_t level) { + planner_->setLethalCost(config.lethal_cost); + path_maker_->setLethalCost(config.lethal_cost); + planner_->setNeutralCost(config.neutral_cost); + planner_->setFactor(config.cost_factor); + publish_potential_ = config.publish_potential; + orientation_filter_->setMode(config.orientation_mode); + orientation_filter_->setWindowSize(config.orientation_window_size); +} + +void GlobalPlanner::clearRobotCell(const geometry_msgs::PoseStamped& global_pose, unsigned int mx, unsigned int my) { + if (!initialized_) { + ROS_ERROR( + "This planner has not been initialized yet, but it is being used, please call initialize() before use"); + return; + } + + //set the associated costs in the cost map to be free + costmap_->setCost(mx, my, costmap_2d::FREE_SPACE); +} + +bool GlobalPlanner::makePlanService(nav_msgs::GetPlan::Request& req, nav_msgs::GetPlan::Response& resp) { + makePlan(req.start, req.goal, resp.plan.poses); + + resp.plan.header.stamp = ros::Time::now(); + resp.plan.header.frame_id = frame_id_; + + return true; +} + +void GlobalPlanner::mapToWorld(double mx, double my, double& wx, double& wy) { + wx = costmap_->getOriginX() + (mx+convert_offset_) * costmap_->getResolution(); + wy = costmap_->getOriginY() + (my+convert_offset_) * costmap_->getResolution(); +} + +bool GlobalPlanner::worldToMap(double wx, double wy, double& mx, double& my) { + double origin_x = costmap_->getOriginX(), origin_y = costmap_->getOriginY(); + double resolution = costmap_->getResolution(); + + if (wx < origin_x || wy < origin_y) + return false; + + mx = (wx - origin_x) / resolution - convert_offset_; + my = (wy - origin_y) / resolution - convert_offset_; + + if (mx < costmap_->getSizeInCellsX() && my < costmap_->getSizeInCellsY()) + return true; + + return false; +} + +bool GlobalPlanner::makePlan(const geometry_msgs::PoseStamped& start, const geometry_msgs::PoseStamped& goal, + std::vector& plan) { + return makePlan(start, goal, default_tolerance_, plan); +} + +bool GlobalPlanner::makePlan(const geometry_msgs::PoseStamped& start, const geometry_msgs::PoseStamped& goal, + double tolerance, std::vector& plan) { + boost::mutex::scoped_lock lock(mutex_); + if (!initialized_) { + ROS_ERROR( + "This planner has not been initialized yet, but it is being used, please call initialize() before use"); + return false; + } + + //clear the plan, just in case + plan.clear(); + + ros::NodeHandle n; + std::string global_frame = frame_id_; + + //until tf can handle transforming things that are way in the past... we'll require the goal to be in our global frame + if (goal.header.frame_id != global_frame) { + ROS_ERROR( + "The goal pose passed to this planner must be in the %s frame. It is instead in the %s frame.", global_frame.c_str(), goal.header.frame_id.c_str()); + return false; + } + + if (start.header.frame_id != global_frame) { + ROS_ERROR( + "The start pose passed to this planner must be in the %s frame. It is instead in the %s frame.", global_frame.c_str(), start.header.frame_id.c_str()); + return false; + } + + double wx = start.pose.position.x; + double wy = start.pose.position.y; + + unsigned int start_x_i, start_y_i, goal_x_i, goal_y_i; + double start_x, start_y, goal_x, goal_y; + + if (!costmap_->worldToMap(wx, wy, start_x_i, start_y_i)) { + ROS_WARN_THROTTLE(1.0, + "The robot's start position is off the global costmap. Planning will always fail, are you sure the robot has been properly localized?"); + return false; + } + if(old_navfn_behavior_){ + start_x = start_x_i; + start_y = start_y_i; + }else{ + worldToMap(wx, wy, start_x, start_y); + } + + wx = goal.pose.position.x; + wy = goal.pose.position.y; + + if (!costmap_->worldToMap(wx, wy, goal_x_i, goal_y_i)) { + ROS_WARN_THROTTLE(1.0, + "The goal sent to the global planner is off the global costmap. Planning will always fail to this goal."); + return false; + } + if(old_navfn_behavior_){ + goal_x = goal_x_i; + goal_y = goal_y_i; + }else{ + worldToMap(wx, wy, goal_x, goal_y); + } + + //clear the starting cell within the costmap because we know it can't be an obstacle + clearRobotCell(start, start_x_i, start_y_i); + + int nx = costmap_->getSizeInCellsX(), ny = costmap_->getSizeInCellsY(); + + //make sure to resize the underlying array that Navfn uses + p_calc_->setSize(nx, ny); + planner_->setSize(nx, ny); + path_maker_->setSize(nx, ny); + potential_array_ = new float[nx * ny]; + + if(outline_map_) + outlineMap(costmap_->getCharMap(), nx, ny, costmap_2d::LETHAL_OBSTACLE); + + bool found_legal = planner_->calculatePotentials(costmap_->getCharMap(), start_x, start_y, goal_x, goal_y, + nx * ny * 2, potential_array_); + + if(!old_navfn_behavior_) + planner_->clearEndpoint(costmap_->getCharMap(), potential_array_, goal_x_i, goal_y_i, 2); + if(publish_potential_) + publishPotential(potential_array_); + + if (found_legal) { + //extract the plan + if (getPlanFromPotential(start_x, start_y, goal_x, goal_y, goal, plan)) { + //make sure the goal we push on has the same timestamp as the rest of the plan + geometry_msgs::PoseStamped goal_copy = goal; + goal_copy.header.stamp = ros::Time::now(); + plan.push_back(goal_copy); + } else { + ROS_ERROR("Failed to get a plan from potential when a legal potential was found. This shouldn't happen."); + } + }else{ + ROS_ERROR_THROTTLE(5.0, "Failed to get a plan."); + } + + // add orientations if needed + orientation_filter_->processPath(start, plan); + + //publish the plan for visualization purposes + publishPlan(plan); + delete[] potential_array_; + return !plan.empty(); +} + +void GlobalPlanner::publishPlan(const std::vector& path) { + if (!initialized_) { + ROS_ERROR( + "This planner has not been initialized yet, but it is being used, please call initialize() before use"); + return; + } + + //create a message for the plan + nav_msgs::Path gui_path; + gui_path.poses.resize(path.size()); + + gui_path.header.frame_id = frame_id_; + gui_path.header.stamp = ros::Time::now(); + + // Extract the plan in world co-ordinates, we assume the path is all in the same frame + for (unsigned int i = 0; i < path.size(); i++) { + gui_path.poses[i] = path[i]; + } + + plan_pub_.publish(gui_path); +} + +bool GlobalPlanner::getPlanFromPotential(double start_x, double start_y, double goal_x, double goal_y, + const geometry_msgs::PoseStamped& goal, + std::vector& plan) { + if (!initialized_) { + ROS_ERROR( + "This planner has not been initialized yet, but it is being used, please call initialize() before use"); + return false; + } + + std::string global_frame = frame_id_; + + //clear the plan, just in case + plan.clear(); + + std::vector > path; + + if (!path_maker_->getPath(potential_array_, start_x, start_y, goal_x, goal_y, path)) { + ROS_ERROR("NO PATH!"); + return false; + } + + ros::Time plan_time = ros::Time::now(); + for (int i = path.size() -1; i>=0; i--) { + std::pair point = path[i]; + //convert the plan to world coordinates + double world_x, world_y; + mapToWorld(point.first, point.second, world_x, world_y); + + geometry_msgs::PoseStamped pose; + pose.header.stamp = plan_time; + pose.header.frame_id = global_frame; + pose.pose.position.x = world_x; + pose.pose.position.y = world_y; + pose.pose.position.z = 0.0; + pose.pose.orientation.x = 0.0; + pose.pose.orientation.y = 0.0; + pose.pose.orientation.z = 0.0; + pose.pose.orientation.w = 1.0; + plan.push_back(pose); + } + if(old_navfn_behavior_){ + plan.push_back(goal); + } + return !plan.empty(); +} + +void GlobalPlanner::publishPotential(float* potential) +{ + int nx = costmap_->getSizeInCellsX(), ny = costmap_->getSizeInCellsY(); + double resolution = costmap_->getResolution(); + nav_msgs::OccupancyGrid grid; + // Publish Whole Grid + grid.header.frame_id = frame_id_; + grid.header.stamp = ros::Time::now(); + grid.info.resolution = resolution; + + grid.info.width = nx; + grid.info.height = ny; + + double wx, wy; + costmap_->mapToWorld(0, 0, wx, wy); + grid.info.origin.position.x = wx - resolution / 2; + grid.info.origin.position.y = wy - resolution / 2; + grid.info.origin.position.z = 0.0; + grid.info.origin.orientation.w = 1.0; + + grid.data.resize(nx * ny); + + float max = 0.0; + for (unsigned int i = 0; i < grid.data.size(); i++) { + float potential = potential_array_[i]; + if (potential < POT_HIGH) { + if (potential > max) { + max = potential; + } + } + } + + for (unsigned int i = 0; i < grid.data.size(); i++) { + if (potential_array_[i] >= POT_HIGH) { + grid.data[i] = -1; + } else { + if (fabs(max) < DBL_EPSILON) { + grid.data[i] = -1; + } else { + grid.data[i] = potential_array_[i] * publish_scale_ / max; + } + } + } + potential_pub_.publish(grid); +} + +} //end namespace global_planner diff --git a/navigations/global_planner/src/quadratic_calculator.cpp b/navigations/global_planner/src/quadratic_calculator.cpp new file mode 100755 index 0000000..afc6b46 --- /dev/null +++ b/navigations/global_planner/src/quadratic_calculator.cpp @@ -0,0 +1,77 @@ +/* + * Copyright (c) 2013, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include + +namespace global_planner { +float QuadraticCalculator::calculatePotential(float* potential, unsigned char cost, int n, float prev_potential) { + // get neighbors + float u, d, l, r; + l = potential[n - 1]; + r = potential[n + 1]; + u = potential[n - nx_]; + d = potential[n + nx_]; + // ROS_INFO("[Update] c: %f l: %f r: %f u: %f d: %f\n", + // potential[n], l, r, u, d); + // ROS_INFO("[Update] cost: %d\n", costs[n]); + + // find lowest, and its lowest neighbor + float ta, tc; + if (l < r) + tc = l; + else + tc = r; + if (u < d) + ta = u; + else + ta = d; + + float hf = cost; // traversability factor + float dc = tc - ta; // relative cost between ta,tc + if (dc < 0) // tc is lowest + { + dc = -dc; + ta = tc; + } + + // calculate new potential + if (dc >= hf) // if too large, use ta-only update + return ta + hf; + else // two-neighbor interpolation update + { + // use quadratic approximation + // might speed this up through table lookup, but still have to + // do the divide + float d = dc / hf; + float v = -0.2301 * d * d + 0.5307 * d + 0.7040; + return ta + hf * v; + } +} +} + diff --git a/navigations/map_msgs/CHANGELOG.rst b/navigations/map_msgs/CHANGELOG.rst new file mode 100755 index 0000000..8d24b21 --- /dev/null +++ b/navigations/map_msgs/CHANGELOG.rst @@ -0,0 +1,17 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package map_msgs +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +1.14.1 (2020-11-02) +------------------- + +1.14.0 (2020-03-10) +------------------- +* Bump CMake version to avoid CMP0048 + Signed-off-by: Shane Loretz +* Contributors: Shane Loretz + +1.13.0 (2015-03-16) +------------------- +* initial release from new repository +* Contributors: Michael Ferguson diff --git a/navigations/map_msgs/CMakeLists.txt b/navigations/map_msgs/CMakeLists.txt new file mode 100755 index 0000000..2bc7ccc --- /dev/null +++ b/navigations/map_msgs/CMakeLists.txt @@ -0,0 +1,42 @@ +cmake_minimum_required(VERSION 3.0.2) +project(map_msgs) + +find_package(catkin REQUIRED + COMPONENTS + message_generation + nav_msgs + sensor_msgs + std_msgs +) + +add_message_files( + FILES + OccupancyGridUpdate.msg + PointCloud2Update.msg + ProjectedMapInfo.msg + ProjectedMap.msg +) +add_service_files( + FILES + GetMapROI.srv + GetPointMapROI.srv + GetPointMap.srv + ProjectedMapsInfo.srv + SaveMap.srv + SetMapProjections.srv +) + +generate_messages( + DEPENDENCIES + nav_msgs + sensor_msgs + std_msgs +) + +catkin_package( + CATKIN_DEPENDS + message_runtime + nav_msgs + sensor_msgs + std_msgs +) diff --git a/navigations/map_msgs/msg/OccupancyGridUpdate.msg b/navigations/map_msgs/msg/OccupancyGridUpdate.msg new file mode 100755 index 0000000..3587fa8 --- /dev/null +++ b/navigations/map_msgs/msg/OccupancyGridUpdate.msg @@ -0,0 +1,6 @@ +std_msgs/Header header +int32 x +int32 y +uint32 width +uint32 height +int8[] data diff --git a/navigations/map_msgs/msg/PointCloud2Update.msg b/navigations/map_msgs/msg/PointCloud2Update.msg new file mode 100755 index 0000000..7637784 --- /dev/null +++ b/navigations/map_msgs/msg/PointCloud2Update.msg @@ -0,0 +1,5 @@ +uint32 ADD=0 +uint32 DELETE=1 +std_msgs/Header header +uint32 type # type of update, one of ADD or DELETE +sensor_msgs/PointCloud2 points diff --git a/navigations/map_msgs/msg/ProjectedMap.msg b/navigations/map_msgs/msg/ProjectedMap.msg new file mode 100755 index 0000000..e14a200 --- /dev/null +++ b/navigations/map_msgs/msg/ProjectedMap.msg @@ -0,0 +1,3 @@ +nav_msgs/OccupancyGrid map +float64 min_z +float64 max_z \ No newline at end of file diff --git a/navigations/map_msgs/msg/ProjectedMapInfo.msg b/navigations/map_msgs/msg/ProjectedMapInfo.msg new file mode 100755 index 0000000..bb35f20 --- /dev/null +++ b/navigations/map_msgs/msg/ProjectedMapInfo.msg @@ -0,0 +1,7 @@ +string frame_id +float64 x +float64 y +float64 width +float64 height +float64 min_z +float64 max_z \ No newline at end of file diff --git a/navigations/map_msgs/package.xml b/navigations/map_msgs/package.xml new file mode 100755 index 0000000..ca832ab --- /dev/null +++ b/navigations/map_msgs/package.xml @@ -0,0 +1,27 @@ + + map_msgs + 1.14.1 + + This package defines messages commonly used in mapping packages. + + Stéphane Magnenat + David V. Lu!! + Michael Ferguson + + BSD + http://ros.org/wiki/map_msgs + https://github.com/ros-planning/navigation_msgs/issues + + catkin + + message_generation + nav_msgs + sensor_msgs + std_msgs + + message_runtime + nav_msgs + sensor_msgs + std_msgs + + diff --git a/navigations/map_msgs/srv/GetMapROI.srv b/navigations/map_msgs/srv/GetMapROI.srv new file mode 100755 index 0000000..0ce2720 --- /dev/null +++ b/navigations/map_msgs/srv/GetMapROI.srv @@ -0,0 +1,6 @@ +float64 x +float64 y +float64 l_x +float64 l_y +--- +nav_msgs/OccupancyGrid sub_map \ No newline at end of file diff --git a/navigations/map_msgs/srv/GetPointMap.srv b/navigations/map_msgs/srv/GetPointMap.srv new file mode 100755 index 0000000..89668e6 --- /dev/null +++ b/navigations/map_msgs/srv/GetPointMap.srv @@ -0,0 +1,3 @@ +# Get the map as a sensor_msgs/PointCloud2 +--- +sensor_msgs/PointCloud2 map diff --git a/navigations/map_msgs/srv/GetPointMapROI.srv b/navigations/map_msgs/srv/GetPointMapROI.srv new file mode 100755 index 0000000..47284cc --- /dev/null +++ b/navigations/map_msgs/srv/GetPointMapROI.srv @@ -0,0 +1,9 @@ +float64 x +float64 y +float64 z +float64 r # if != 0, circular ROI of radius r +float64 l_x # if r == 0, length of AABB on x +float64 l_y # if r == 0, length of AABB on y +float64 l_z # if r == 0, length of AABB on z +--- +sensor_msgs/PointCloud2 sub_map \ No newline at end of file diff --git a/navigations/map_msgs/srv/ProjectedMapsInfo.srv b/navigations/map_msgs/srv/ProjectedMapsInfo.srv new file mode 100755 index 0000000..28c5388 --- /dev/null +++ b/navigations/map_msgs/srv/ProjectedMapsInfo.srv @@ -0,0 +1,2 @@ +map_msgs/ProjectedMapInfo[] projected_maps_info +--- diff --git a/navigations/map_msgs/srv/SaveMap.srv b/navigations/map_msgs/srv/SaveMap.srv new file mode 100755 index 0000000..5c1bfb5 --- /dev/null +++ b/navigations/map_msgs/srv/SaveMap.srv @@ -0,0 +1,3 @@ +# Save the map to the filesystem +std_msgs/String filename +--- diff --git a/navigations/map_msgs/srv/SetMapProjections.srv b/navigations/map_msgs/srv/SetMapProjections.srv new file mode 100755 index 0000000..dee9523 --- /dev/null +++ b/navigations/map_msgs/srv/SetMapProjections.srv @@ -0,0 +1,2 @@ +--- +map_msgs/ProjectedMapInfo[] projected_maps_info diff --git a/navigations/map_server/CHANGELOG.rst b/navigations/map_server/CHANGELOG.rst new file mode 100755 index 0000000..7c16d45 --- /dev/null +++ b/navigations/map_server/CHANGELOG.rst @@ -0,0 +1,212 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package map_server +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +1.17.3 (2023-01-10) +------------------- +* [ROS-O] various patches (`#1225 `_) + * do not specify obsolete c++11 standard + this breaks with current versions of log4cxx. + * update pluginlib include paths + the non-hpp headers have been deprecated since kinetic + * use lambdas in favor of boost::bind + Using boost's _1 as a global system is deprecated since C++11. + The ROS packages in Debian removed the implicit support for the global symbols, + so this code fails to compile there without the patch. +* Contributors: Michael Görner + +1.17.2 (2022-06-20) +------------------- +* Change_map service to map_server [Rebase/Noetic] (`#1029 `_) + * Refactored map loading from constructor to three methods + * Added change_map service using LoadMap.srv +* map_server: Initialise a NodeHandle in main. (`#1122 `_) +* Add debug output regarding waiting for time (`#1078 `_) + Added debug messages suggested in https://github.com/ros-planning/navigation/issues/1074#issuecomment-751557177. Makes it easier to discover if use_sim_time is true but no clock server is running +* crop_map: Fix extra pixel origin shift up every cropping (`#1064 `_) (`#1067 `_) + Co-authored-by: Pavlo Kolomiiets +* (map_server) add rtest dependency to tests (`#1061 `_) +* [noetic] MapServer variable cleanup: Precursor for `#1029 `_ (`#1043 `_) +* Contributors: Christian Fritz, David V. Lu!!, Matthijs van der Burgh, Nikos Koukis, Pavlo Kolomiiets + +1.17.1 (2020-08-27) +------------------- +* Initial map_server map_mode tests (`#1006 `_) +* [noetic] Adding CMake way to find yaml-cpp (`#998 `_) +* Contributors: David V. Lu!!, Sean Yen + +1.17.0 (2020-04-02) +------------------- +* Merge pull request `#982 `_ from ros-planning/noetic_prep + Noetic Migration +* increase required cmake version +* Contributors: Michael Ferguson + +1.16.6 (2020-03-18) +------------------- + +1.16.5 (2020-03-15) +------------------- +* [melodic] updated install for better portability. (`#973 `_) +* Contributors: Sean Yen + +1.16.4 (2020-03-04) +------------------- + +1.16.3 (2019-11-15) +------------------- +* Merge branch 'melodic-devel' into layer_clear_area-melodic +* Merge pull request `#850 `_ from seanyen/map_server_windows_fix + [Windows][melodic] map_server Windows build bring up +* map_server Windows build bring up + * Fix install location for Windows build. (On Windows build, shared library uses RUNTIME location, but not LIBRARY) + * Use boost::filesystem::path to handle path logic and remove the libgen.h dependency for better cross platform. + * Fix gtest hard-coded and add YAML library dir in CMakeList.txt. +* Contributors: Michael Ferguson, Sean Yen, Steven Macenski + +1.16.2 (2018-07-31) +------------------- + +1.16.1 (2018-07-28) +------------------- + +1.16.0 (2018-07-25) +------------------- +* Merge pull request `#735 `_ from ros-planning/melodic_708 + Allow specification of free/occupied thresholds for map_saver (`#708 `_) +* Allow specification of free/occupied thresholds for map_saver (`#708 `_) + * add occupied threshold command line parameter to map_saver (--occ) + * add free threshold command line parameter to map_saver (--free) +* Merge pull request `#704 `_ from DLu/fix573_lunar + Map server wait for a valid time fix [lunar] +* Map server wait for a valid time, fix `#573 `_ (`#700 `_) + When launching the map_server with Gazebo, the current time is picked + before the simulation is started and then has a value of 0. + Later when querying the stamp of the map, a value of has a special + signification on tf transform for example. +* Contributors: Michael Ferguson, Romain Reignier, ipa-fez + +1.15.2 (2018-03-22) +------------------- +* Merge pull request `#673 `_ from ros-planning/email_update_lunar + update maintainer email (lunar) +* Merge pull request `#649 `_ from aaronhoy/lunar_add_ahoy + Add myself as a maintainer. +* Rebase PRs from Indigo/Kinetic (`#637 `_) + * Respect planner_frequency intended behavior (`#622 `_) + * Only do a getRobotPose when no start pose is given (`#628 `_) + Omit the unnecessary call to getRobotPose when the start pose was + already given, so that move_base can also generate a path in + situations where getRobotPose would fail. + This is actually to work around an issue of getRobotPose randomly + failing. + * Update gradient_path.cpp (`#576 `_) + * Update gradient_path.cpp + * Update navfn.cpp + * update to use non deprecated pluginlib macro (`#630 `_) + * update to use non deprecated pluginlib macro + * multiline version as well + * Print SDL error on IMG_Load failure in server_map (`#631 `_) +* Use occupancy values when saving a map (`#613 `_) +* Closes `#625 `_ (`#627 `_) +* Contributors: Aaron Hoy, David V. Lu!!, Hunter Allen, Michael Ferguson + +1.15.1 (2017-08-14) +------------------- +* remove offending library export (fixes `#612 `_) +* Contributors: Michael Ferguson + +1.15.0 (2017-08-07) +------------------- +* Fix compiler warning for GCC 8. +* convert packages to format2 +* Merge pull request `#596 `_ from ros-planning/lunar_548 +* refactor to not use tf version 1 (`#561 `_) +* Fix CMakeLists + package.xmls (`#548 `_) +* Merge pull request `#560 `_ from wjwwood/map_server_fixup_cmake +* update to support Python 2 and 3 (`#559 `_) +* remove duplicate and unreferenced file (`#558 `_) +* remove trailing whitespace from map_server package (`#557 `_) +* fix cmake use of yaml-cpp and sdl / sdl-image +* Fix CMake warnings +* Contributors: Hunter L. Allen, Martin Günther, Michael Ferguson, Mikael Arguedas, Vincent Rabaud, William Woodall + +1.14.0 (2016-05-20) +------------------- +* Corrections to alpha channel detection and usage. + Changing to actually detect whether the image has an alpha channel instead of + inferring based on the number of channels. + Also reverting to legacy behavior of trinary mode overriding alpha removal. + This will cause the alpha channel to be averaged in with the others in trinary + mode, which is the current behavior before this PR. +* Removing some trailing whitespace. +* Use enum to control map interpretation +* Contributors: Aaron Hoy, David Lu + +1.13.1 (2015-10-29) +------------------- + +1.13.0 (2015-03-17) +------------------- +* rename image_loader library, fixes `#208 `_ +* Contributors: Michael Ferguson + +1.12.0 (2015-02-04) +------------------- +* update maintainer email +* Contributors: Michael Ferguson + +1.11.15 (2015-02-03) +-------------------- + +1.11.14 (2014-12-05) +-------------------- +* prevent inf loop +* Contributors: Jeremie Deray + +1.11.13 (2014-10-02) +-------------------- + +1.11.12 (2014-10-01) +-------------------- +* map_server: [style] alphabetize dependencies +* map_server: remove vestigial export line + the removed line does not do anything in catkin +* Contributors: William Woodall + +1.11.11 (2014-07-23) +-------------------- + +1.11.10 (2014-06-25) +-------------------- + +1.11.9 (2014-06-10) +------------------- + +1.11.8 (2014-05-21) +------------------- +* fix build, was broken by `#175 `_ +* Contributors: Michael Ferguson + +1.11.7 (2014-05-21) +------------------- +* make rostest in CMakeLists optional +* Contributors: Lukas Bulwahn + +1.11.5 (2014-01-30) +------------------- +* install crop map +* removing .py from executable script +* Map Server can serve maps with non-lethal values +* Added support for YAML-CPP 0.5+. + The new yaml-cpp API removes the "node >> outputvar;" operator, and + it has a new way of loading documents. There's no version hint in the + library's headers, so I'm getting the version number from pkg-config. +* check for CATKIN_ENABLE_TESTING +* Change maintainer from Hersh to Lu + +1.11.4 (2013-09-27) +------------------- +* prefix utest target to not collide with other targets +* Package URL Updates +* unique target names to avoid conflicts (e.g. with map-store) diff --git a/navigations/map_server/CMakeLists.txt b/navigations/map_server/CMakeLists.txt new file mode 100755 index 0000000..401e4fe --- /dev/null +++ b/navigations/map_server/CMakeLists.txt @@ -0,0 +1,135 @@ +cmake_minimum_required(VERSION 3.0.2) +project(map_server) + +find_package(catkin REQUIRED + COMPONENTS + roscpp + nav_msgs + tf2 + ) + +find_package(Bullet REQUIRED) +find_package(SDL REQUIRED) +find_package(SDL_image REQUIRED) +find_package(Boost REQUIRED COMPONENTS filesystem) + +find_package(PkgConfig REQUIRED) +pkg_check_modules(YAMLCPP yaml-cpp QUIET) +if(NOT YAMLCPP_FOUND) + find_package(yaml-cpp 0.6 REQUIRED) + set(YAMLCPP_INCLUDE_DIRS ${YAML_CPP_INCLUDE_DIR}) + set(YAMLCPP_LIBRARIES ${YAML_CPP_LIBRARIES}) + add_definitions(-DHAVE_YAMLCPP_GT_0_5_0) +else() + if(YAMLCPP_VERSION VERSION_GREATER "0.5.0") + add_definitions(-DHAVE_YAMLCPP_GT_0_5_0) + endif() + link_directories(${YAMLCPP_LIBRARY_DIRS}) +endif() + +catkin_package( + INCLUDE_DIRS + include + LIBRARIES + map_server_image_loader + CATKIN_DEPENDS + roscpp + nav_msgs + tf2 +) + +include_directories( + include + ${BULLET_INCLUDE_DIRS} + ${catkin_INCLUDE_DIRS} + ${SDL_INCLUDE_DIR} + ${SDL_IMAGE_INCLUDE_DIRS} + ${YAMLCPP_INCLUDE_DIRS} + ${Boost_INCLUDE_DIRS} +) + +add_library(map_server_image_loader + src/image_loader.cpp + src/image_16bit_loader.cpp + src/image_32bit_loader.cpp + ) +add_dependencies(map_server_image_loader ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) +target_link_libraries(map_server_image_loader + ${BULLET_LIBRARIES} + ${catkin_LIBRARIES} + ${SDL_LIBRARY} + ${SDL_IMAGE_LIBRARIES} +) + +add_executable(map_server src/main.cpp) +add_dependencies(map_server ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) +target_link_libraries(map_server + map_server_image_loader + ${YAMLCPP_LIBRARIES} + ${catkin_LIBRARIES} +) + +add_executable(map_server-map_saver src/map_saver.cpp) +add_dependencies(map_server-map_saver ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) +set_target_properties(map_server-map_saver PROPERTIES OUTPUT_NAME map_saver) +target_link_libraries(map_server-map_saver + ${catkin_LIBRARIES} +) + +# copy test data to same place as tests are run +function(copy_test_data) + cmake_parse_arguments(PROJECT "" "" "FILES" ${ARGN}) + foreach(datafile ${PROJECT_FILES}) + file(COPY ${datafile} DESTINATION ${PROJECT_BINARY_DIR}/test) + endforeach() +endfunction() + +## Tests +if(CATKIN_ENABLE_TESTING) + copy_test_data( FILES + test/testmap.bmp + test/testmap.png + test/spectrum.png ) + catkin_add_gtest(${PROJECT_NAME}_utest test/utest.cpp test/test_constants.cpp) + target_link_libraries(${PROJECT_NAME}_utest + map_server_image_loader + ${SDL_LIBRARY} + ${SDL_IMAGE_LIBRARIES} + ) + + find_package(roslib REQUIRED) + include_directories(${roslib_INCLUDE_DIRS}) + add_executable(rtest test/rtest.cpp test/test_constants.cpp) + add_dependencies(rtest ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) + add_dependencies(tests rtest) + target_link_libraries( rtest + ${GTEST_LIBRARIES} + ${catkin_LIBRARIES} + ${roslib_LIBRARIES} + ) + + # This has to be done after we've already built targets, or catkin variables get borked + find_package(rostest REQUIRED) + add_rostest(test/rtest.xml) +endif() + +## Install executables and/or libraries +install(TARGETS map_server-map_saver map_server + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) + +install(TARGETS map_server_image_loader + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) + +## Install project namespaced headers +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} + FILES_MATCHING PATTERN "*.h" + PATTERN ".svn" EXCLUDE) + +## Install excutable python script +install( + PROGRAMS + scripts/crop_map + DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) diff --git a/navigations/map_server/include/map_server/image_loader.h b/navigations/map_server/include/map_server/image_loader.h new file mode 100755 index 0000000..ea226d3 --- /dev/null +++ b/navigations/map_server/include/map_server/image_loader.h @@ -0,0 +1,115 @@ +/* + * Copyright (c) 2008, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ +#ifndef MAP_SERVER_MAP_SERVER_H +#define MAP_SERVER_MAP_SERVER_H + +/* + * Author: Brian Gerkey + */ + +#include "nav_msgs/GetMap.h" + +/** Map mode + * Default: TRINARY - + * value >= occ_th - Occupied (100) + * value <= free_th - Free (0) + * otherwise - Unknown + * SCALE - + * alpha < 1.0 - Unknown + * value >= occ_th - Occupied (100) + * value <= free_th - Free (0) + * otherwise - f( (free_th, occ_th) ) = (0, 100) + * (linearly map in between values to (0,100) + * RAW - + * value = value + */ +enum MapMode {TRINARY, SCALE, RAW}; + +namespace map_server +{ + +/** Read the image from file and fill out the resp object, for later + * use when our services are requested. + * + * @param resp The map wil be written into here + * @param fname The image file to read from + * @param res The resolution of the map (gets stored in resp) + * @param negate If true, then whiter pixels are occupied, and blacker + * pixels are free + * @param occ_th Threshold above which pixels are occupied + * @param free_th Threshold below which pixels are free + * @param origin Triple specifying 2-D pose of lower-left corner of image + * @param mode Map mode + * @throws std::runtime_error If the image file can't be loaded + * */ +void loadMapFromFile(nav_msgs::GetMap::Response* resp, + const char* fname, double res, bool negate, + double occ_th, double free_th, double* origin, + MapMode mode=TRINARY); + +/** Read the image from file and fill out the resp object, for later + * use when our services are requested. + * + * @param resp The map wil be written into here + * @param fname The image file to read from + * @param res The resolution of the map (gets stored in resp) + * @param negate If true, then whiter pixels are occupied, and blacker + * pixels are free + * @param occ_th Threshold above which pixels are occupied + * @param free_th Threshold below which pixels are free + * @param origin Triple specifying 2-D pose of lower-left corner of image + * @param mode Map mode + * @throws std::runtime_error If the image file can't be loaded + * */ +void loadMapFromFile16Bit(nav_msgs::GetMap::Response* resp, + const char* fname, double res, bool negate, + double occ_th, double free_th, double* origin, + MapMode mode=TRINARY); + +/** Read the image from file and fill out the resp object, for later + * use when our services are requested. + * + * @param resp The map wil be written into here + * @param fname The image file to read from + * @param res The resolution of the map (gets stored in resp) + * @param negate If true, then whiter pixels are occupied, and blacker + * pixels are free + * @param occ_th Threshold above which pixels are occupied + * @param free_th Threshold below which pixels are free + * @param origin Triple specifying 2-D pose of lower-left corner of image + * @param mode Map mode + * @throws std::runtime_error If the image file can't be loaded + * */ +void loadMapFromFile32Bit(nav_msgs::GetMap::Response* resp, + const char* fname, double res, bool negate, + double occ_th, double free_th, double* origin, + MapMode mode=TRINARY); +} + +#endif diff --git a/navigations/map_server/launch/test.launch b/navigations/map_server/launch/test.launch new file mode 100755 index 0000000..0d1c2dc --- /dev/null +++ b/navigations/map_server/launch/test.launch @@ -0,0 +1,4 @@ + + + + \ No newline at end of file diff --git a/navigations/map_server/maps/Direction_Zones_0.png b/navigations/map_server/maps/Direction_Zones_0.png new file mode 100755 index 0000000..5a98027 Binary files /dev/null and b/navigations/map_server/maps/Direction_Zones_0.png differ diff --git a/navigations/map_server/maps/Direction_Zones_180.png b/navigations/map_server/maps/Direction_Zones_180.png new file mode 100755 index 0000000..354d4c8 Binary files /dev/null and b/navigations/map_server/maps/Direction_Zones_180.png differ diff --git a/navigations/map_server/maps/Direction_Zones_270.png b/navigations/map_server/maps/Direction_Zones_270.png new file mode 100755 index 0000000..27a4eac Binary files /dev/null and b/navigations/map_server/maps/Direction_Zones_270.png differ diff --git a/navigations/map_server/maps/Direction_Zones_90.png b/navigations/map_server/maps/Direction_Zones_90.png new file mode 100755 index 0000000..a4337d5 Binary files /dev/null and b/navigations/map_server/maps/Direction_Zones_90.png differ diff --git a/navigations/map_server/maps/maze.png b/navigations/map_server/maps/maze.png new file mode 100755 index 0000000..41d6fa1 Binary files /dev/null and b/navigations/map_server/maps/maze.png differ diff --git a/navigations/map_server/maps/maze.yaml b/navigations/map_server/maps/maze.yaml new file mode 100755 index 0000000..67a3c33 --- /dev/null +++ b/navigations/map_server/maps/maze.yaml @@ -0,0 +1,6 @@ +image: Direction_Zones_90.png +resolution: 0.05 +origin: [0.0, 0.0, 0.0] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 diff --git a/navigations/map_server/maps/maze_virtual_walls.png b/navigations/map_server/maps/maze_virtual_walls.png new file mode 100755 index 0000000..e5dd8bb Binary files /dev/null and b/navigations/map_server/maps/maze_virtual_walls.png differ diff --git a/navigations/map_server/maps/maze_virtual_walls.yaml b/navigations/map_server/maps/maze_virtual_walls.yaml new file mode 100755 index 0000000..89320ac --- /dev/null +++ b/navigations/map_server/maps/maze_virtual_walls.yaml @@ -0,0 +1,6 @@ +image: maze_virtual_walls.png +resolution: 0.05 +origin: [0.0, 0.0, 0.0] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 diff --git a/navigations/map_server/package.xml b/navigations/map_server/package.xml new file mode 100755 index 0000000..640cc76 --- /dev/null +++ b/navigations/map_server/package.xml @@ -0,0 +1,33 @@ + + + + map_server + 1.17.3 + + + map_server provides the map_server ROS Node, which offers map data as a ROS Service. It also provides the map_saver command-line utility, which allows dynamically generated maps to be saved to file. + + + Brian Gerkey, Tony Pratkanis + contradict@gmail.com + David V. Lu!! + Michael Ferguson + Aaron Hoy + http://wiki.ros.org/map_server + BSD + + catkin + + bullet + nav_msgs + roscpp + sdl + sdl-image + tf2 + yaml-cpp + + roslib + rospy + rostest + rosunit + diff --git a/navigations/map_server/scripts/crop_map b/navigations/map_server/scripts/crop_map new file mode 100755 index 0000000..78b2c14 --- /dev/null +++ b/navigations/map_server/scripts/crop_map @@ -0,0 +1,109 @@ +#!/usr/bin/env python +# Software License Agreement (BSD License) +# +# Copyright (c) 2008, Willow Garage, Inc. +# All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# * Redistributions in binary form must reproduce the above +# copyright notice, this list of conditions and the following +# disclaimer in the documentation and/or other materials provided +# with the distribution. +# * Neither the name of the Willow Garage nor the names of its +# contributors may be used to endorse or promote products derived +# from this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# + +from __future__ import print_function + +import sys +import yaml +from PIL import Image +import math + +def find_bounds(map_image): + x_min = map_image.size[0] + x_end = 0 + y_min = map_image.size[1] + y_end = 0 + pix = map_image.load() + for x in range(map_image.size[0]): + for y in range(map_image.size[1]): + val = pix[x, y] + if val != 205: # not unknown + x_min = min(x, x_min) + x_end = max(x, x_end) + y_min = min(y, y_min) + y_end = max(y, y_end) + return x_min, x_end, y_min, y_end + +def computed_cropped_origin(map_image, bounds, resolution, origin): + """ Compute the image for the cropped map when map_image is cropped by bounds and had origin before. """ + ox = origin[0] + oy = origin[1] + oth = origin[2] + + # First figure out the delta we have to translate from the lower left corner (which is the origin) + # in the image system + dx = bounds[0] * resolution + dy = (map_image.size[1] - bounds[3] - 1) * resolution + + # Next rotate this by the theta and add to the old origin + + new_ox = ox + dx * math.cos(oth) - dy * math.sin(oth) + new_oy = oy + dx * math.sin(oth) + dy * math.cos(oth) + + return [new_ox, new_oy, oth] + +if __name__ == "__main__": + if len(sys.argv) < 2: + print("Usage: %s map.yaml [cropped.yaml]" % sys.argv[0], file=sys.stderr) + sys.exit(1) + + with open(sys.argv[1]) as f: + map_data = yaml.safe_load(f) + + if len(sys.argv) > 2: + crop_name = sys.argv[2] + if crop_name.endswith(".yaml"): + crop_name = crop_name[:-5] + crop_yaml = crop_name + ".yaml" + crop_image = crop_name + ".pgm" + else: + crop_yaml = "cropped.yaml" + crop_image = "cropped.pgm" + + map_image_file = map_data["image"] + resolution = map_data["resolution"] + origin = map_data["origin"] + map_image = Image.open(map_image_file) + + bounds = find_bounds(map_image) + + # left, upper, right, lower + cropped_image = map_image.crop((bounds[0], bounds[2], bounds[1] + 1, bounds[3] + 1)) + + cropped_image.save(crop_image) + map_data["image"] = crop_image + map_data["origin"] = computed_cropped_origin(map_image, bounds, resolution, origin) + with open(crop_yaml, "w") as f: + yaml.dump(map_data, f) + diff --git a/navigations/map_server/src/image_16bit_loader.cpp b/navigations/map_server/src/image_16bit_loader.cpp new file mode 100755 index 0000000..8d531ac --- /dev/null +++ b/navigations/map_server/src/image_16bit_loader.cpp @@ -0,0 +1,133 @@ +/* + * Copyright (c) 2008, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +/* + * This file contains helper functions for loading images as maps. + * + * Author: Brian Gerkey + */ + +#include +#include + +#include +#include + +// We use SDL_image to load the image from disk +#include + +// Use Bullet's Quaternion object to create one from Euler angles +#include + +#include "map_server/image_loader.h" +#include + +// compute linear index for given map coords +#define MAP_IDX(sx, i, j) ((sx) * (j) + (i)) + +namespace map_server +{ + +void loadMapFromFile16Bit(nav_msgs::GetMap::Response* resp, + const char* fname, double res, bool negate, + double occ_th, double free_th, double* origin, + MapMode mode) +{ + SDL_Surface* img; + + unsigned char* pixels; + unsigned char* p; + int rowstride, n_channels, avg_channels; + unsigned int i,j; + int k; + int alpha; + uint16_t color_avg; + + // Load the image using SDL. If we get NULL back, the image load failed. + if(!(img = IMG_Load(fname))) + { + std::string errmsg = std::string("failed to open image file \"") + + std::string(fname) + std::string("\": ") + IMG_GetError(); + throw std::runtime_error(errmsg); + } + + // Copy the image data into the map structure + resp->map.info.width = img->w*2; + resp->map.info.height = img->h; + resp->map.info.resolution = res; + resp->map.info.origin.position.x = *(origin); + resp->map.info.origin.position.y = *(origin+1); + resp->map.info.origin.position.z = 0.0; + btQuaternion q; + // setEulerZYX(yaw, pitch, roll) + q.setEulerZYX(*(origin+2), 0, 0); + resp->map.info.origin.orientation.x = q.x(); + resp->map.info.origin.orientation.y = q.y(); + resp->map.info.origin.orientation.z = q.z(); + resp->map.info.origin.orientation.w = q.w(); + + // Allocate space to hold the data + resp->map.data.resize(resp->map.info.width * resp->map.info.height); + + // Get values that we'll need to iterate through the pixels + rowstride = img->pitch; + n_channels = img->format->BytesPerPixel; + + // NOTE: Trinary mode still overrides here to preserve existing behavior. + // Alpha will be averaged in with color channels when using trinary mode. + if (mode==TRINARY || !img->format->Amask) + avg_channels = n_channels; + else + avg_channels = n_channels - 1; + // Copy pixel data into the map structure + pixels = (unsigned char*)(img->pixels); + for(j = 0; j < resp->map.info.height; j++) + { + for (i = 0; i < resp->map.info.width; i+=2) + { + // Compute mean of RGB for this pixel + p = pixels + j*rowstride + i/2*n_channels; + color_avg = (*(p) << 16) + (*(p+1) << 8) + (*(p+2)); + if (n_channels == 1) + alpha = 1; + else + alpha = *(p+n_channels-1); + + if(negate) + color_avg = 65535 - color_avg; + + resp->map.data[MAP_IDX(resp->map.info.width,i,resp->map.info.height - j - 1)] = (unsigned char)(color_avg & 0x00FF); + resp->map.data[MAP_IDX(resp->map.info.width,i+1,resp->map.info.height - j - 1)] = (unsigned char)((color_avg & 0xFF00) >> 8); + } + } + + SDL_FreeSurface(img); +} + +} diff --git a/navigations/map_server/src/image_32bit_loader.cpp b/navigations/map_server/src/image_32bit_loader.cpp new file mode 100755 index 0000000..1fccdf2 --- /dev/null +++ b/navigations/map_server/src/image_32bit_loader.cpp @@ -0,0 +1,134 @@ +/* + * Copyright (c) 2008, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +/* + * This file contains helper functions for loading images as maps. + * + * Author: Brian Gerkey + */ + +#include +#include + +#include +#include + +// We use SDL_image to load the image from disk +#include + +// Use Bullet's Quaternion object to create one from Euler angles +#include + +#include "map_server/image_loader.h" +#include + +// compute linear index for given map coords +#define MAP_IDX(sx, i, j) ((sx) * (j) + (i)) + +namespace map_server +{ + void loadMapFromFile32Bit(nav_msgs::GetMap::Response *resp, + const char *fname, double res, bool negate, + double occ_th, double free_th, double *origin, + MapMode mode) + { + SDL_Surface *img; + + unsigned char *pixels; + unsigned char *p; + int rowstride, n_channels, avg_channels; + unsigned int i, j; + int k; + int alpha; + uint32_t color_avg; + + // Load the image using SDL. If we get NULL back, the image load failed. + if (!(img = IMG_Load(fname))) + { + std::string errmsg = std::string("failed to open image file \"") + + std::string(fname) + std::string("\": ") + IMG_GetError(); + throw std::runtime_error(errmsg); + } + + // Copy the image data into the map structure + resp->map.info.width = img->w * 2; + resp->map.info.height = img->h * 2; + resp->map.info.resolution = res; + resp->map.info.origin.position.x = *(origin); + resp->map.info.origin.position.y = *(origin + 1); + resp->map.info.origin.position.z = 0.0; + btQuaternion q; + // setEulerZYX(yaw, pitch, roll) + q.setEulerZYX(*(origin + 2), 0, 0); + resp->map.info.origin.orientation.x = q.x(); + resp->map.info.origin.orientation.y = q.y(); + resp->map.info.origin.orientation.z = q.z(); + resp->map.info.origin.orientation.w = q.w(); + + // Allocate space to hold the data + resp->map.data.resize(resp->map.info.width * resp->map.info.height); + + // Get values that we'll need to iterate through the pixels + rowstride = img->pitch; + n_channels = img->format->BytesPerPixel; + + // NOTE: Trinary mode still overrides here to preserve existing behavior. + // Alpha will be averaged in with color channels when using trinary mode. + if (mode == TRINARY || !img->format->Amask) + avg_channels = n_channels; + else + avg_channels = n_channels - 1; + // Copy pixel data into the map structure + pixels = (unsigned char *)(img->pixels); + for (j = 0; j < resp->map.info.height; j += 2) + { + for (i = 0; i < resp->map.info.width; i += 2) + { + // Compute mean of RGB for this pixel + p = pixels + j / 2 * rowstride + i / 2 * n_channels; + color_avg = (*(p) << 16) + (*(p + 1) << 8) + (*(p + 2)); + if (n_channels == 1) + alpha = 1; + else + alpha = *(p + n_channels - 1); + + if (negate) + color_avg = 16777215 - color_avg; + + resp->map.data[MAP_IDX(resp->map.info.width, i, resp->map.info.height - j - 1)] = (color_avg >> 16u) & 0xFF; + resp->map.data[MAP_IDX(resp->map.info.width, i + 1, resp->map.info.height - j - 1)] = (color_avg >> 24u) & 0xFF; + resp->map.data[MAP_IDX(resp->map.info.width, i, resp->map.info.height - j - 2)] = (color_avg >> 0u) & 0xFF; + resp->map.data[MAP_IDX(resp->map.info.width, i + 1, resp->map.info.height - j - 2)] = (color_avg >> 8u) & 0xFF; + } + } + + SDL_FreeSurface(img); + } + +} diff --git a/navigations/map_server/src/image_loader.cpp b/navigations/map_server/src/image_loader.cpp new file mode 100755 index 0000000..02419bf --- /dev/null +++ b/navigations/map_server/src/image_loader.cpp @@ -0,0 +1,167 @@ +/* + * Copyright (c) 2008, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +/* + * This file contains helper functions for loading images as maps. + * + * Author: Brian Gerkey + */ + +#include +#include + +#include +#include + +// We use SDL_image to load the image from disk +#include + +// Use Bullet's Quaternion object to create one from Euler angles +#include + +#include "map_server/image_loader.h" +#include + +// compute linear index for given map coords +#define MAP_IDX(sx, i, j) ((sx) * (j) + (i)) + +namespace map_server +{ + +void +loadMapFromFile(nav_msgs::GetMap::Response* resp, + const char* fname, double res, bool negate, + double occ_th, double free_th, double* origin, + MapMode mode) +{ + SDL_Surface* img; + + unsigned char* pixels; + unsigned char* p; + unsigned char value; + int rowstride, n_channels, avg_channels; + unsigned int i,j; + int k; + double occ; + int alpha; + int color_sum; + double color_avg; + + // Load the image using SDL. If we get NULL back, the image load failed. + if(!(img = IMG_Load(fname))) + { + std::string errmsg = std::string("failed to open image file \"") + + std::string(fname) + std::string("\": ") + IMG_GetError(); + throw std::runtime_error(errmsg); + } + + // Copy the image data into the map structure + resp->map.info.width = img->w; + resp->map.info.height = img->h; + resp->map.info.resolution = res; + resp->map.info.origin.position.x = *(origin); + resp->map.info.origin.position.y = *(origin+1); + resp->map.info.origin.position.z = 0.0; + btQuaternion q; + // setEulerZYX(yaw, pitch, roll) + q.setEulerZYX(*(origin+2), 0, 0); + resp->map.info.origin.orientation.x = q.x(); + resp->map.info.origin.orientation.y = q.y(); + resp->map.info.origin.orientation.z = q.z(); + resp->map.info.origin.orientation.w = q.w(); + + // Allocate space to hold the data + resp->map.data.resize(resp->map.info.width * resp->map.info.height); + + // Get values that we'll need to iterate through the pixels + rowstride = img->pitch; + n_channels = img->format->BytesPerPixel; + + // NOTE: Trinary mode still overrides here to preserve existing behavior. + // Alpha will be averaged in with color channels when using trinary mode. + if (mode==TRINARY || !img->format->Amask) + avg_channels = n_channels; + else + avg_channels = n_channels - 1; + // Copy pixel data into the map structure + pixels = (unsigned char*)(img->pixels); + for(j = 0; j < resp->map.info.height; j++) + { + for (i = 0; i < resp->map.info.width; i++) + { + // Compute mean of RGB for this pixel + p = pixels + j*rowstride + i*n_channels; + color_sum = 0; + int color = 0; + for(k=0;kmap.data[MAP_IDX(resp->map.info.width,i,resp->map.info.height - j - 1)] = value; + continue; + } + + + // If negate is true, we consider blacker pixels free, and whiter + // pixels occupied. Otherwise, it's vice versa. + occ = (255 - color_avg) / 255.0; + + // Apply thresholds to RGB means to determine occupancy values for + // map. Note that we invert the graphics-ordering of the pixels to + // produce a map with cell (0,0) in the lower-left corner. + if(occ > occ_th) + value = +100; + else if(occ < free_th) + value = 0; + else if(mode==TRINARY || alpha < 1.0) + value = -1; + else { + double ratio = (occ - free_th) / (occ_th - free_th); + value = 1 + 98 * ratio; + } + + resp->map.data[MAP_IDX(resp->map.info.width,i,resp->map.info.height - j - 1)] = value; + } + } + + SDL_FreeSurface(img); +} + +} diff --git a/navigations/map_server/src/main.cpp b/navigations/map_server/src/main.cpp new file mode 100755 index 0000000..57843f7 --- /dev/null +++ b/navigations/map_server/src/main.cpp @@ -0,0 +1,412 @@ +/* + * Copyright (c) 2008, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +/* Author: Brian Gerkey */ + +#define USAGE "\nUSAGE: map_server \n" \ + " map.yaml: map description file\n" \ + "DEPRECATED USAGE: map_server \n" \ + " map: image file to load\n" \ + " resolution: map resolution [meters/pixel]" + +#include +#include +#include +#include + +#include "ros/ros.h" +#include "ros/console.h" +#include "map_server/image_loader.h" +#include "nav_msgs/MapMetaData.h" +#include "nav_msgs/LoadMap.h" +#include "yaml-cpp/yaml.h" + +#ifdef HAVE_YAMLCPP_GT_0_5_0 +// The >> operator disappeared in yaml-cpp 0.5, so this function is +// added to provide support for code written under the yaml-cpp 0.3 API. +template +void operator>>(const YAML::Node &node, T &i) +{ + i = node.as(); +} +#endif +#define MAP_IDX(sx, i, j) ((sx) * (j) + (i)) +class MapServer +{ +public: + /** Trivial constructor */ + MapServer(const std::string &fname, double res) + { + std::string mapfname = ""; + double origin[3]; + int negate; + double occ_th, free_th; + MapMode mode = TRINARY; + ros::NodeHandle private_nh("~"); + private_nh.param("frame_id", frame_id_, std::string("map")); + private_nh.param("type", type_, 8); + + // When called this service returns a copy of the current map + get_map_service_ = nh_.advertiseService("static_map", &MapServer::mapCallback, this); + + // Change the currently published map + change_map_srv_ = nh_.advertiseService("change_map", &MapServer::changeMapCallback, this); + + // Latched publisher for metadata + metadata_pub_ = nh_.advertise("map_metadata", 1, true); + + // Latched publisher for data + map_pub_ = nh_.advertise("map", 1, true); + if(type_ != 8) map_convert_ = nh_.advertise("map_convert", 1, true); + + deprecated_ = (res != 0); + if (!deprecated_) + { + if (!loadMapFromYaml(fname)) + { + exit(-1); + } + } + else + { + if (!loadMapFromParams(fname, res)) + { + exit(-1); + } + } + } + +private: + ros::NodeHandle nh_; + ros::Publisher map_pub_; + ros::Publisher map_convert_; + ros::Publisher metadata_pub_; + ros::ServiceServer get_map_service_; + ros::ServiceServer change_map_srv_; + bool deprecated_; + std::string frame_id_; + int type_; + + /** Callback invoked when someone requests our service */ + bool mapCallback(nav_msgs::GetMap::Request &req, + nav_msgs::GetMap::Response &res) + { + // request is empty; we ignore it + + // = operator is overloaded to make deep copy (tricky!) + res = map_resp_; + ROS_INFO("Sending map"); + + return true; + } + + /** Callback invoked when someone requests to change the map */ + bool changeMapCallback(nav_msgs::LoadMap::Request &request, + nav_msgs::LoadMap::Response &response) + { + if (loadMapFromYaml(request.map_url)) + { + response.result = response.RESULT_SUCCESS; + ROS_INFO("Changed map to %s", request.map_url.c_str()); + } + else + { + response.result = response.RESULT_UNDEFINED_FAILURE; + } + return true; + } + + /** Load a map given all the values needed to understand it + */ + bool loadMapFromValues(std::string map_file_name, double resolution, + int negate, double occ_th, double free_th, + double origin[3], MapMode mode) + { + ROS_INFO("Loading map from image \"%s\"", map_file_name.c_str()); + try + { + if (type_ == 32) + map_server::loadMapFromFile32Bit(&map_resp_, map_file_name.c_str(), + resolution, negate, occ_th, free_th, + origin, mode); + else if (type_ == 16) + map_server::loadMapFromFile16Bit(&map_resp_, map_file_name.c_str(), + resolution, negate, occ_th, free_th, + origin, mode); + else + map_server::loadMapFromFile(&map_resp_, map_file_name.c_str(), + resolution, negate, occ_th, free_th, + origin, mode); + } + catch (std::runtime_error &e) + { + ROS_ERROR("%s", e.what()); + return false; + } + + // To make sure get a consistent time in simulation + ros::Time::waitForValid(); + map_resp_.map.info.map_load_time = ros::Time::now(); + map_resp_.map.header.frame_id = frame_id_; + map_resp_.map.header.stamp = ros::Time::now(); + ROS_INFO("Read a %d X %d map @ %.3lf m/cell", + map_resp_.map.info.width, + map_resp_.map.info.height, + map_resp_.map.info.resolution); + meta_data_message_ = map_resp_.map.info; + + // Publish latched topics + metadata_pub_.publish(meta_data_message_); + map_pub_.publish(map_resp_.map); + + if (type_ == 16) + { + double occ_th = 0.65; + double free_th = 0.196; + nav_msgs::OccupancyGrid convert; + convert.header = map_resp_.map.header; + convert.info = map_resp_.map.info; + convert.info.width = map_resp_.map.info.width / 2; + convert.data.resize(convert.info.width * convert.info.height); + unsigned int color_sum, color; + double color_avg; + unsigned char value; + int size_y = map_resp_.map.info.height; + int size_x = map_resp_.map.info.width; + + for (int j = 0; j < map_resp_.map.info.height; j++) + { + for (int i = 0; i < map_resp_.map.info.width; i += 2) + { + unsigned char low = map_resp_.map.data[MAP_IDX(size_x, i, size_y - j - 1)]; + unsigned char high = map_resp_.map.data[MAP_IDX(size_x, i + 1, size_y - j - 1)]; + color = (int)((low & 0x00FF) | (high << 8)); + unsigned char red = (unsigned char)(color & 0x00FF0000) >> 16; + unsigned char green = (unsigned char)(color & 0x0000FF00) >> 8; + unsigned char blue = (unsigned char)(color & 0x000000FF); + color_sum = red + green + blue; + + color_avg = color_sum / 2.0; + + double occ = (255 - color_avg) / 255.0; + if (occ > occ_th) + value = +100; + else if (occ < free_th) + value = 0; + else + { + double ratio = (occ - free_th) / (occ_th - free_th); + value = 1 + 98 * ratio; + } + convert.data[MAP_IDX(size_x / 2, i / 2, size_y - j - 1)] = value; + } + } + map_convert_.publish(convert); + } + return true; + } + + /** Load a map using the deprecated method + */ + bool loadMapFromParams(std::string map_file_name, double resolution) + { + ros::NodeHandle private_nh("~"); + int negate; + double occ_th; + double free_th; + double origin[3]; + private_nh.param("negate", negate, 0); + private_nh.param("occupied_thresh", occ_th, 0.65); + private_nh.param("free_thresh", free_th, 0.196); + origin[0] = origin[1] = origin[2] = 0.0; + return loadMapFromValues(map_file_name, resolution, negate, occ_th, free_th, origin, TRINARY); + } + + /** Load a map given a path to a yaml file + */ + bool loadMapFromYaml(std::string path_to_yaml) + { + std::string mapfname; + MapMode mode; + double res; + int negate; + double occ_th; + double free_th; + double origin[3]; + std::ifstream fin(path_to_yaml.c_str()); + if (fin.fail()) + { + ROS_ERROR("Map_server could not open %s.", path_to_yaml.c_str()); + return false; + } +#ifdef HAVE_YAMLCPP_GT_0_5_0 + // The document loading process changed in yaml-cpp 0.5. + YAML::Node doc = YAML::Load(fin); +#else + YAML::Parser parser(fin); + YAML::Node doc; + parser.GetNextDocument(doc); +#endif + try + { + doc["resolution"] >> res; + } + catch (YAML::InvalidScalar &) + { + ROS_ERROR("The map does not contain a resolution tag or it is invalid."); + return false; + } + try + { + doc["negate"] >> negate; + } + catch (YAML::InvalidScalar &) + { + ROS_ERROR("The map does not contain a negate tag or it is invalid."); + return false; + } + try + { + doc["occupied_thresh"] >> occ_th; + } + catch (YAML::InvalidScalar &) + { + ROS_ERROR("The map does not contain an occupied_thresh tag or it is invalid."); + return false; + } + try + { + doc["free_thresh"] >> free_th; + } + catch (YAML::InvalidScalar &) + { + ROS_ERROR("The map does not contain a free_thresh tag or it is invalid."); + return false; + } + try + { + std::string modeS = ""; + doc["mode"] >> modeS; + + if (modeS == "trinary") + mode = TRINARY; + else if (modeS == "scale") + mode = SCALE; + else if (modeS == "raw") + mode = RAW; + else + { + ROS_ERROR("Invalid mode tag \"%s\".", modeS.c_str()); + return false; + } + } + catch (YAML::Exception &) + { + ROS_DEBUG("The map does not contain a mode tag or it is invalid... assuming Trinary"); + mode = TRINARY; + } + try + { + doc["origin"][0] >> origin[0]; + doc["origin"][1] >> origin[1]; + doc["origin"][2] >> origin[2]; + } + catch (YAML::InvalidScalar &) + { + ROS_ERROR("The map does not contain an origin tag or it is invalid."); + return false; + } + try + { + doc["image"] >> mapfname; + // TODO: make this path-handling more robust + if (mapfname.size() == 0) + { + ROS_ERROR("The image tag cannot be an empty string."); + return false; + } + + boost::filesystem::path mapfpath(mapfname); + if (!mapfpath.is_absolute()) + { + boost::filesystem::path dir(path_to_yaml); + dir = dir.parent_path(); + mapfpath = dir / mapfpath; + mapfname = mapfpath.string(); + } + } + catch (YAML::InvalidScalar &) + { + ROS_ERROR("The map does not contain an image tag or it is invalid."); + return false; + } + return loadMapFromValues(mapfname, res, negate, occ_th, free_th, origin, mode); + } + + /** The map data is cached here, to be sent out to service callers + */ + nav_msgs::MapMetaData meta_data_message_; + nav_msgs::GetMap::Response map_resp_; + + /* + void metadataSubscriptionCallback(const ros::SingleSubscriberPublisher& pub) + { + pub.publish( meta_data_message_ ); + } + */ +}; + +int main(int argc, char **argv) +{ + ros::init(argc, argv, "map_server", ros::init_options::AnonymousName); + ros::NodeHandle nh("~"); + if (argc != 3 && argc != 2) + { + ROS_ERROR("%s", USAGE); + exit(-1); + } + if (argc != 2) + { + ROS_WARN("Using deprecated map server interface. Please switch to new interface."); + } + std::string fname(argv[1]); + double res = (argc == 2) ? 0.0 : atof(argv[2]); + try + { + MapServer ms(fname, res); + ros::spin(); + } + catch (std::runtime_error &e) + { + ROS_ERROR("map_server exception: %s", e.what()); + return -1; + } + + return 0; +} diff --git a/navigations/map_server/src/map_saver.cpp b/navigations/map_server/src/map_saver.cpp new file mode 100755 index 0000000..aa6afb5 --- /dev/null +++ b/navigations/map_server/src/map_saver.cpp @@ -0,0 +1,217 @@ +/* + * map_saver + * Copyright (c) 2008, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include "ros/ros.h" +#include "ros/console.h" +#include "nav_msgs/GetMap.h" +#include "tf2/LinearMath/Matrix3x3.h" +#include "geometry_msgs/Quaternion.h" + +using namespace std; + +/** + * @brief Map generation node. + */ +class MapGenerator +{ + + public: + MapGenerator(const std::string& mapname, int threshold_occupied, int threshold_free) + : mapname_(mapname), saved_map_(false), threshold_occupied_(threshold_occupied), threshold_free_(threshold_free) + { + ros::NodeHandle n; + ROS_INFO("Waiting for the map"); + map_sub_ = n.subscribe("map", 1, &MapGenerator::mapCallback, this); + } + + void mapCallback(const nav_msgs::OccupancyGridConstPtr& map) + { + ROS_INFO("Received a %d X %d map @ %.3f m/pix", + map->info.width, + map->info.height, + map->info.resolution); + + + std::string mapdatafile = mapname_ + ".pgm"; + ROS_INFO("Writing map occupancy data to %s", mapdatafile.c_str()); + FILE* out = fopen(mapdatafile.c_str(), "w"); + if (!out) + { + ROS_ERROR("Couldn't save map file to %s", mapdatafile.c_str()); + return; + } + + fprintf(out, "P5\n# CREATOR: map_saver.cpp %.3f m/pix\n%d %d\n255\n", + map->info.resolution, map->info.width, map->info.height); + for(unsigned int y = 0; y < map->info.height; y++) { + for(unsigned int x = 0; x < map->info.width; x++) { + unsigned int i = x + (map->info.height - y - 1) * map->info.width; + if (map->data[i] >= 0 && map->data[i] <= threshold_free_) { // [0,free) + fputc(254, out); + } else if (map->data[i] >= threshold_occupied_) { // (occ,255] + fputc(000, out); + } else { //occ [0.25,0.65] + fputc(205, out); + } + } + } + + fclose(out); + + + std::string mapmetadatafile = mapname_ + ".yaml"; + ROS_INFO("Writing map occupancy data to %s", mapmetadatafile.c_str()); + FILE* yaml = fopen(mapmetadatafile.c_str(), "w"); + + + /* +resolution: 0.100000 +origin: [0.000000, 0.000000, 0.000000] +# +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 + + */ + + geometry_msgs::Quaternion orientation = map->info.origin.orientation; + tf2::Matrix3x3 mat(tf2::Quaternion( + orientation.x, + orientation.y, + orientation.z, + orientation.w + )); + double yaw, pitch, roll; + mat.getEulerYPR(yaw, pitch, roll); + + fprintf(yaml, "image: %s\nresolution: %f\norigin: [%f, %f, %f]\nnegate: 0\noccupied_thresh: 0.65\nfree_thresh: 0.196\n\n", + mapdatafile.c_str(), map->info.resolution, map->info.origin.position.x, map->info.origin.position.y, yaw); + + fclose(yaml); + + ROS_INFO("Done\n"); + saved_map_ = true; + } + + std::string mapname_; + ros::Subscriber map_sub_; + bool saved_map_; + int threshold_occupied_; + int threshold_free_; + +}; + +#define USAGE "Usage: \n" \ + " map_saver -h\n"\ + " map_saver [--occ ] [--free ] [-f ] [ROS remapping args]" + +int main(int argc, char** argv) +{ + ros::init(argc, argv, "map_saver"); + std::string mapname = "map"; + int threshold_occupied = 65; + int threshold_free = 25; + + for(int i=1; i 100) + { + ROS_ERROR("threshold_occupied must be between 1 and 100"); + return 1; + } + + } + else + { + puts(USAGE); + return 1; + } + } + else if (!strcmp(argv[i], "--free")) + { + if (++i < argc) + { + threshold_free = std::atoi(argv[i]); + if (threshold_free < 0 || threshold_free > 100) + { + ROS_ERROR("threshold_free must be between 0 and 100"); + return 1; + } + + } + else + { + puts(USAGE); + return 1; + } + } + else + { + puts(USAGE); + return 1; + } + } + + if (threshold_occupied <= threshold_free) + { + ROS_ERROR("threshold_free must be smaller than threshold_occupied"); + return 1; + } + + MapGenerator mg(mapname, threshold_occupied, threshold_free); + + while(!mg.saved_map_ && ros::ok()) + ros::spinOnce(); + + return 0; +} + + diff --git a/navigations/map_server/src/map_server.dox b/navigations/map_server/src/map_server.dox new file mode 100755 index 0000000..1e5b237 --- /dev/null +++ b/navigations/map_server/src/map_server.dox @@ -0,0 +1,9 @@ +/** + +@mainpage + +@htmlinclude manifest.html + +Command-line usage is in the wiki. +*/ + diff --git a/navigations/map_server/test/consumer.py b/navigations/map_server/test/consumer.py new file mode 100755 index 0000000..6ff7e78 --- /dev/null +++ b/navigations/map_server/test/consumer.py @@ -0,0 +1,71 @@ +#!/usr/bin/env python +# Software License Agreement (BSD License) +# +# Copyright (c) 2008, Willow Garage, Inc. +# All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# * Redistributions in binary form must reproduce the above +# copyright notice, this list of conditions and the following +# disclaimer in the documentation and/or other materials provided +# with the distribution. +# * Neither the name of the Willow Garage nor the names of its +# contributors may be used to endorse or promote products derived +# from this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# + +from __future__ import print_function + +PKG = 'static_map_server' +NAME = 'consumer' + +import sys +import unittest +import time + +import rospy +import rostest +from nav_msgs.srv import GetMap + + +class TestConsumer(unittest.TestCase): + def __init__(self, *args): + super(TestConsumer, self).__init__(*args) + self.success = False + + def callback(self, data): + print(rospy.get_caller_id(), "I heard %s" % data.data) + self.success = data.data and data.data.startswith('hello world') + rospy.signal_shutdown('test done') + + def test_consumer(self): + rospy.wait_for_service('static_map') + mapsrv = rospy.ServiceProxy('static_map', GetMap) + resp = mapsrv() + self.success = True + print(resp) + while not rospy.is_shutdown() and not self.success: # and time.time() < timeout_t: <== timeout_t doesn't exists?? + time.sleep(0.1) + self.assert_(self.success) + rospy.signal_shutdown('test done') + +if __name__ == '__main__': + rostest.rosrun(PKG, NAME, TestConsumer, sys.argv) diff --git a/navigations/map_server/test/rtest.cpp b/navigations/map_server/test/rtest.cpp new file mode 100755 index 0000000..27f607f --- /dev/null +++ b/navigations/map_server/test/rtest.cpp @@ -0,0 +1,198 @@ +/* + * Copyright (c) 2008, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +/* Author: Brian Gerkey */ + +#include +#include +#include +#include +#include +#include +#include +#include + +#include "test_constants.h" + +int g_argc; +char** g_argv; + +class MapClientTest : public testing::Test +{ + public: + // A node is needed to make a service call + ros::NodeHandle* n_; + + MapClientTest() + { + ros::init(g_argc, g_argv, "map_client_test"); + n_ = new ros::NodeHandle(); + got_map_ = false; + got_map_metadata_ = false; + } + + ~MapClientTest() + { + delete n_; + } + + bool got_map_; + boost::shared_ptr map_; + void mapCallback(const boost::shared_ptr& map) + { + map_ = map; + got_map_ = true; + } + + bool got_map_metadata_; + boost::shared_ptr map_metadata_; + void mapMetaDataCallback(const boost::shared_ptr& map_metadata) + { + map_metadata_ = map_metadata; + got_map_metadata_ = true; + } +}; + +/* Try to retrieve the map via service, and compare to ground truth */ +TEST_F(MapClientTest, call_service) +{ + nav_msgs::GetMap::Request req; + nav_msgs::GetMap::Response resp; + ASSERT_TRUE(ros::service::waitForService("static_map", 5000)); + ASSERT_TRUE(ros::service::call("static_map", req, resp)); + ASSERT_FLOAT_EQ(resp.map.info.resolution, g_valid_image_res); + ASSERT_EQ(resp.map.info.width, g_valid_image_width); + ASSERT_EQ(resp.map.info.height, g_valid_image_height); + ASSERT_STREQ(resp.map.header.frame_id.c_str(), "map"); + for(unsigned int i=0; i < resp.map.info.width * resp.map.info.height; i++) + ASSERT_EQ(g_valid_image_content[i], resp.map.data[i]); +} + +/* Try to retrieve the map via topic, and compare to ground truth */ +TEST_F(MapClientTest, subscribe_topic) +{ + ros::Subscriber sub = n_->subscribe("map", 1, [this](auto& map){ mapCallback(map); }); + + // Try a few times, because the server may not be up yet. + int i=20; + while(!got_map_ && i > 0) + { + ros::spinOnce(); + ros::Duration d = ros::Duration().fromSec(0.25); + d.sleep(); + i--; + } + ASSERT_TRUE(got_map_); + ASSERT_FLOAT_EQ(map_->info.resolution, g_valid_image_res); + ASSERT_EQ(map_->info.width, g_valid_image_width); + ASSERT_EQ(map_->info.height, g_valid_image_height); + ASSERT_STREQ(map_->header.frame_id.c_str(), "map"); + for(unsigned int i=0; i < map_->info.width * map_->info.height; i++) + ASSERT_EQ(g_valid_image_content[i], map_->data[i]); +} + +/* Try to retrieve the metadata via topic, and compare to ground truth */ +TEST_F(MapClientTest, subscribe_topic_metadata) +{ + ros::Subscriber sub = n_->subscribe("map_metadata", 1, [this](auto& map_metadata){ mapMetaDataCallback(map_metadata); }); + + // Try a few times, because the server may not be up yet. + int i=20; + while(!got_map_metadata_ && i > 0) + { + ros::spinOnce(); + ros::Duration d = ros::Duration().fromSec(0.25); + d.sleep(); + i--; + } + ASSERT_TRUE(got_map_metadata_); + ASSERT_FLOAT_EQ(map_metadata_->resolution, g_valid_image_res); + ASSERT_EQ(map_metadata_->width, g_valid_image_width); + ASSERT_EQ(map_metadata_->height, g_valid_image_height); +} + +/* Change the map, retrieve the map via topic, and compare to ground truth */ +TEST_F(MapClientTest, change_map) +{ + ros::Subscriber sub = n_->subscribe("map", 1, [this](auto& map){ mapCallback(map); }); + + // Try a few times, because the server may not be up yet. + for (int i = 20; i > 0 && !got_map_; i--) + { + ros::spinOnce(); + ros::Duration d = ros::Duration().fromSec(0.25); + d.sleep(); + } + ASSERT_TRUE(got_map_); + + // Now change the map + got_map_ = false; + nav_msgs::LoadMap::Request req; + nav_msgs::LoadMap::Response resp; + req.map_url = ros::package::getPath("map_server") + "/test/testmap2.yaml"; + ASSERT_TRUE(ros::service::waitForService("change_map", 5000)); + ASSERT_TRUE(ros::service::call("change_map", req, resp)); + ASSERT_EQ(0u, resp.result); + for (int i = 20; i > 0 && !got_map_; i--) + { + ros::spinOnce(); + ros::Duration d = ros::Duration().fromSec(0.25); + d.sleep(); + } + + ASSERT_FLOAT_EQ(tmap2::g_valid_image_res, map_->info.resolution); + ASSERT_EQ(tmap2::g_valid_image_width, map_->info.width); + ASSERT_EQ(tmap2::g_valid_image_height, map_->info.height); + ASSERT_STREQ("map", map_->header.frame_id.c_str()); + for(unsigned int i=0; i < map_->info.width * map_->info.height; i++) + ASSERT_EQ(tmap2::g_valid_image_content[i], map_->data[i]) << "idx:" << i; + + //Put the old map back so the next test isn't broken + got_map_ = false; + req.map_url = ros::package::getPath("map_server") + "/test/testmap.yaml"; + ASSERT_TRUE(ros::service::call("change_map", req, resp)); + ASSERT_EQ(0u, resp.result); + for (int i = 20; i > 0 && !got_map_; i--) + { + ros::spinOnce(); + ros::Duration d = ros::Duration().fromSec(0.25); + d.sleep(); + } + ASSERT_TRUE(got_map_); +} + +int main(int argc, char **argv) +{ + testing::InitGoogleTest(&argc, argv); + + g_argc = argc; + g_argv = argv; + + return RUN_ALL_TESTS(); +} diff --git a/navigations/map_server/test/rtest.xml b/navigations/map_server/test/rtest.xml new file mode 100755 index 0000000..e7afee9 --- /dev/null +++ b/navigations/map_server/test/rtest.xml @@ -0,0 +1,22 @@ + + + + + + + + + + + + + + + diff --git a/navigations/map_server/test/spectrum.png b/navigations/map_server/test/spectrum.png new file mode 100755 index 0000000..5e144eb Binary files /dev/null and b/navigations/map_server/test/spectrum.png differ diff --git a/navigations/map_server/test/test_constants.cpp b/navigations/map_server/test/test_constants.cpp new file mode 100755 index 0000000..4521521 --- /dev/null +++ b/navigations/map_server/test/test_constants.cpp @@ -0,0 +1,84 @@ +/* + * Copyright (c) 2008, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +/* Author: Brian Gerkey */ + +/* This file contains global constants shared among tests */ + +/* Note that these must be changed if the test image changes */ + +#include "test_constants.h" + +const unsigned int g_valid_image_width = 10; +const unsigned int g_valid_image_height = 10; +// Note that the image content is given in row-major order, with the +// lower-left pixel first. This is different from a graphics coordinate +// system, which starts with the upper-left pixel. The loadMapFromFile +// call converts from the latter to the former when it loads the image, and +// we want to compare against the result of that conversion. +const char g_valid_image_content[] = { +0,0,0,0,0,0,0,0,0,0, +100,100,100,100,0,0,100,100,100,0, +100,100,100,100,0,0,100,100,100,0, +100,0,0,0,0,0,0,0,0,0, +100,0,0,0,0,0,0,0,0,0, +100,0,0,0,0,0,100,100,0,0, +100,0,0,0,0,0,100,100,0,0, +100,0,0,0,0,0,100,100,0,0, +100,0,0,0,0,0,100,100,0,0, +100,0,0,0,0,0,0,0,0,0, +}; + +const char* g_valid_png_file = "test/testmap.png"; +const char* g_valid_bmp_file = "test/testmap.bmp"; +const char* g_spectrum_png_file = "test/spectrum.png"; + +const float g_valid_image_res = 0.1; + +// Constants for testmap2 +namespace tmap2 +{ + const char g_valid_image_content[] = { + 100,100,100,100,100,100,100,100,100,100,100,100, + 100,0,0,0,0,0,0,0,0,0,0,100, + 100,0,100,100,100,100,100,100,100,100,0,100, + 100,0,100,0,0,0,0,0,0,100,0,100, + 100,0,0,0,0,0,0,0,0,0,0,100, + 100,0,0,0,0,0,0,0,0,0,0,100, + 100,0,0,0,0,0,0,0,0,0,0,100, + 100,0,0,0,0,0,0,0,0,0,0,100, + 100,0,0,0,0,0,0,0,0,0,0,100, + 100,0,100,0,0,0,0,0,0,100,0,100, + 100,0,0,0,0,0,0,0,0,0,0,100, + 100,100,100,100,100,100,100,100,100,100,100,100, + }; + const float g_valid_image_res = 0.1; + const unsigned int g_valid_image_width = 12; + const unsigned int g_valid_image_height = 12; +} diff --git a/navigations/map_server/test/test_constants.h b/navigations/map_server/test/test_constants.h new file mode 100755 index 0000000..c23a578 --- /dev/null +++ b/navigations/map_server/test/test_constants.h @@ -0,0 +1,51 @@ +/* + * Copyright (c) 2008, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ +#ifndef MAP_SERVER_TEST_CONSTANTS_H +#define MAP_SERVER_TEST_CONSTANTS_H + +/* Author: Brian Gerkey */ + +/* This file externs global constants shared among tests */ + +extern const unsigned int g_valid_image_width; +extern const unsigned int g_valid_image_height; +extern const char g_valid_image_content[]; +extern const char* g_valid_png_file; +extern const char* g_valid_bmp_file; +extern const float g_valid_image_res; +extern const char* g_spectrum_png_file; + +namespace tmap2 { + extern const char g_valid_image_content[]; + extern const float g_valid_image_res; + extern const unsigned int g_valid_image_width; + extern const unsigned int g_valid_image_height; +} + +#endif diff --git a/navigations/map_server/test/testmap.bmp b/navigations/map_server/test/testmap.bmp new file mode 100755 index 0000000..dc8b114 Binary files /dev/null and b/navigations/map_server/test/testmap.bmp differ diff --git a/navigations/map_server/test/testmap.png b/navigations/map_server/test/testmap.png new file mode 100755 index 0000000..910c5c3 Binary files /dev/null and b/navigations/map_server/test/testmap.png differ diff --git a/navigations/map_server/test/testmap.yaml b/navigations/map_server/test/testmap.yaml new file mode 100755 index 0000000..8cf0d73 --- /dev/null +++ b/navigations/map_server/test/testmap.yaml @@ -0,0 +1,6 @@ +image: testmap.png +resolution: 0.1 +origin: [2.0, 3.0, 1.0] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 diff --git a/navigations/map_server/test/testmap2.png b/navigations/map_server/test/testmap2.png new file mode 100755 index 0000000..8ca9106 Binary files /dev/null and b/navigations/map_server/test/testmap2.png differ diff --git a/navigations/map_server/test/testmap2.yaml b/navigations/map_server/test/testmap2.yaml new file mode 100755 index 0000000..150a04a --- /dev/null +++ b/navigations/map_server/test/testmap2.yaml @@ -0,0 +1,6 @@ +image: testmap2.png +resolution: 0.1 +origin: [-2.0, -3.0, -1.0] +negate: 1 +occupied_thresh: 0.5 +free_thresh: 0.2 diff --git a/navigations/map_server/test/utest.cpp b/navigations/map_server/test/utest.cpp new file mode 100755 index 0000000..62c4b68 --- /dev/null +++ b/navigations/map_server/test/utest.cpp @@ -0,0 +1,149 @@ +/* + * Copyright (c) 2008, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +/* Author: Brian Gerkey */ + +#include // for std::runtime_error +#include +#include "map_server/image_loader.h" +#include "test_constants.h" + +/* Try to load a valid PNG file. Succeeds if no exception is thrown, and if + * the loaded image matches the known dimensions and content of the file. + * + * This test can fail on OS X, due to an apparent limitation of the + * underlying SDL_Image library. */ +TEST(MapServer, loadValidPNG) +{ + try + { + nav_msgs::GetMap::Response map_resp; + double origin[3] = { 0.0, 0.0, 0.0 }; + map_server::loadMapFromFile(&map_resp, g_valid_png_file, g_valid_image_res, false, 0.65, 0.1, origin); + EXPECT_FLOAT_EQ(map_resp.map.info.resolution, g_valid_image_res); + EXPECT_EQ(map_resp.map.info.width, g_valid_image_width); + EXPECT_EQ(map_resp.map.info.height, g_valid_image_height); + for(unsigned int i=0; i < map_resp.map.info.width * map_resp.map.info.height; i++) + EXPECT_EQ(g_valid_image_content[i], map_resp.map.data[i]); + } + catch(...) + { + ADD_FAILURE() << "Uncaught exception : " << "This is OK on OS X"; + } +} + +/* Try to load a valid BMP file. Succeeds if no exception is thrown, and if + * the loaded image matches the known dimensions and content of the file. */ +TEST(MapServer, loadValidBMP) +{ + try + { + nav_msgs::GetMap::Response map_resp; + double origin[3] = { 0.0, 0.0, 0.0 }; + map_server::loadMapFromFile(&map_resp, g_valid_bmp_file, g_valid_image_res, false, 0.65, 0.1, origin); + EXPECT_FLOAT_EQ(map_resp.map.info.resolution, g_valid_image_res); + EXPECT_EQ(map_resp.map.info.width, g_valid_image_width); + EXPECT_EQ(map_resp.map.info.height, g_valid_image_height); + for(unsigned int i=0; i < map_resp.map.info.width * map_resp.map.info.height; i++) + EXPECT_EQ(g_valid_image_content[i], map_resp.map.data[i]); + } + catch(...) + { + ADD_FAILURE() << "Uncaught exception"; + } +} + +/* Try to load an invalid file. Succeeds if a std::runtime_error exception + * is thrown. */ +TEST(MapServer, loadInvalidFile) +{ + try + { + nav_msgs::GetMap::Response map_resp; + double origin[3] = { 0.0, 0.0, 0.0 }; + map_server::loadMapFromFile(&map_resp, "foo", 0.1, false, 0.65, 0.1, origin); + } + catch(std::runtime_error &e) + { + SUCCEED(); + return; + } + catch(...) + { + FAIL() << "Uncaught exception"; + } + ADD_FAILURE() << "Didn't throw exception as expected"; +} + +std::vector countValues(const nav_msgs::GetMap::Response& map_resp) +{ + std::vector counts(256, 0); + for (unsigned int i = 0; i < map_resp.map.data.size(); i++) + { + unsigned char value = static_cast(map_resp.map.data[i]); + counts[value]++; + } + return counts; +} + +TEST(MapServer, testMapMode) +{ + nav_msgs::GetMap::Response map_resp; + double origin[3] = { 0.0, 0.0, 0.0 }; + + map_server::loadMapFromFile(&map_resp, g_spectrum_png_file, 0.1, false, 0.65, 0.1, origin, TRINARY); + std::vector trinary_counts = countValues(map_resp); + EXPECT_EQ(90u, trinary_counts[100]); + EXPECT_EQ(26u, trinary_counts[0]); + EXPECT_EQ(140u, trinary_counts[255]); + + map_server::loadMapFromFile(&map_resp, g_spectrum_png_file, 0.1, false, 0.65, 0.1, origin, SCALE); + std::vector scale_counts = countValues(map_resp); + EXPECT_EQ(90u, scale_counts[100]); + EXPECT_EQ(26u, scale_counts[0]); + unsigned int scaled_values = 0; + for (unsigned int i = 1; i < 100; i++) + { + scaled_values += scale_counts[i]; + } + EXPECT_EQ(140u, scaled_values); + + map_server::loadMapFromFile(&map_resp, g_spectrum_png_file, 0.1, false, 0.65, 0.1, origin, RAW); + std::vector raw_counts = countValues(map_resp); + for (unsigned int i = 0; i < raw_counts.size(); i++) + { + EXPECT_EQ(1u, raw_counts[i]) << i; + } +} + +int main(int argc, char **argv) +{ + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/navigations/move_base/CHANGELOG.rst b/navigations/move_base/CHANGELOG.rst new file mode 100755 index 0000000..e671c9a --- /dev/null +++ b/navigations/move_base/CHANGELOG.rst @@ -0,0 +1,198 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package move_base +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +1.17.3 (2023-01-10) +------------------- +* [ROS-O] various patches (`#1225 `_) + * do not specify obsolete c++11 standard + this breaks with current versions of log4cxx. + * update pluginlib include paths + the non-hpp headers have been deprecated since kinetic + * use lambdas in favor of boost::bind + Using boost's _1 as a global system is deprecated since C++11. + The ROS packages in Debian removed the implicit support for the global symbols, + so this code fails to compile there without the patch. +* Contributors: Michael Görner + +1.17.2 (2022-06-20) +------------------- +* Check if stamp of transformed pose is non-zero (`#1200 `_) +* Create move_base catkin library (`#1116 `_) + Co-authored-by: vkotaru +* move_base crash when using default recovery behaviors (`#1071 `_) +* Publish recovery behavior melodic (`#1051 `_) (`#1052 `_) + * First prototype of publishing recovery status + custom message tells you where the behavior occured, the name, index, + and total number of behaviors. + * fix message field typos + Co-authored-by: Peter Mitrano + Co-authored-by: Peter Mitrano +* Contributors: David V. Lu!!, Prasanth Kotaru, Yuki Furuta, mattp256 + +1.17.1 (2020-08-27) +------------------- +* Fix `#933 `_ (`#988 `_) +* Contributors: David V. Lu!! + +1.17.0 (2020-04-02) +------------------- +* Merge pull request `#982 `_ from ros-planning/noetic_prep + Noetic Migration +* increase required cmake version +* move_base: Add options for make_plan service (`#981 `_) + Adds the following two parameters for the ~make_plan service: + 1. make_plan_clear_costmap + Whether or not to clear the global costmap on make_plan service call. + 2. make_plan_add_unreachable_goal + Whether or not to add the original goal to the path if it is unreachable in the make_plan service call. +* Contributors: Michael Ferguson, nxdefiant + +1.16.6 (2020-03-18) +------------------- + +1.16.5 (2020-03-15) +------------------- + +1.16.4 (2020-03-04) +------------------- +* [Windows][melodic] Navigation (except for map_server and amcl) Windows build bring up (`#851 `_) +* Contributors: Sean Yen + +1.16.3 (2019-11-15) +------------------- +* Merge branch 'melodic-devel' into layer_clear_area-melodic +* Added publishZeroVelocity() before starting planner (`#751 `_) + Edit for Issue `#750 `_ +* Merge pull request `#831 `_ from ros-planning/feature/remove_slashes + [melodic] Remove leading slashes from default frame_id parameters +* Remove leading slashes from default frame_id parameters +* Contributors: David V. Lu, Michael Ferguson, SUNIL SULANIA, Steven Macenski + +1.16.2 (2018-07-31) +------------------- + +1.16.1 (2018-07-28) +------------------- + +1.16.0 (2018-07-25) +------------------- +* Switch to TF2 `#755 `_ +* Merge pull request `#723 `_ from moriarty/melodic-buildfarm-errors + Melodic buildfarm errors +* Merge pull request `#719 `_ from ros-planning/lunar_711 + adding mutex locks to costmap clearing service +* Contributors: Alexander Moriarty, Michael Ferguson, Vincent Rabaud, stevemacenski + +1.15.2 (2018-03-22) +------------------- +* Merge pull request `#673 `_ from ros-planning/email_update_lunar + update maintainer email (lunar) +* Merge pull request `#649 `_ from aaronhoy/lunar_add_ahoy + Add myself as a maintainer. +* Rebase PRs from Indigo/Kinetic (`#637 `_) + * Respect planner_frequency intended behavior (`#622 `_) + * Only do a getRobotPose when no start pose is given (`#628 `_) + Omit the unnecessary call to getRobotPose when the start pose was + already given, so that move_base can also generate a path in + situations where getRobotPose would fail. + This is actually to work around an issue of getRobotPose randomly + failing. + * Update gradient_path.cpp (`#576 `_) + * Update gradient_path.cpp + * Update navfn.cpp + * update to use non deprecated pluginlib macro (`#630 `_) + * update to use non deprecated pluginlib macro + * multiline version as well + * Print SDL error on IMG_Load failure in server_map (`#631 `_) +* Contributors: Aaron Hoy, David V. Lu!!, Michael Ferguson + +1.15.1 (2017-08-14) +------------------- + +1.15.0 (2017-08-07) +------------------- +* Add a max_planning_retries parameter to move_base [kinetic] (`#539 `_) +* Fix for `#517 `_: create a getRobotPose method on move_base instead of using that on the costmaps +* Fixed deadlock when changing global planner +* rebase fixups +* convert packages to format2 +* Fix CMakeLists + package.xmls (`#548 `_) +* Added deps to amcl costmap_2d move_base (`#512 `_) +* Fix CMake warnings +* move_base: Add move_base_msgs to find_package. +* Contributors: Jorge Santos, Jorge Santos Simón, Maarten de Vries, Martin Günther, Mikael Arguedas, Vincent Rabaud, mryellow, ne0 + +1.14.0 (2016-05-20) +------------------- + +1.13.1 (2015-10-29) +------------------- +* Removes installation of nonexistent directories +* use correct size for clearing window +* full name has been required for eons, this code just adds unneeded complexity +* remove ancient conversion scripts from v0.2 to v0.3 +* proper locking during costmap update +* Contributors: Michael Ferguson, Thiago de Freitas Oliveira Araujo + +1.13.0 (2015-03-17) +------------------- +* Fixing various memory freeing operations +* Contributors: Alex Bencz + +1.12.0 (2015-02-04) +------------------- +* update maintainer email +* Contributors: Michael Ferguson + +1.11.15 (2015-02-03) +-------------------- +* Disable global planner when resetting state. +* Mark move_base headers for installation +* Add ARCHIVE DESTINATION for move_base +* Break infinite loop when tolerance 0 is used +* remove partial usage of in the code +* Contributors: Gary Servin, Michael Ferguson, ohendriks, v4hn + +1.11.14 (2014-12-05) +-------------------- +* use timer rather than rate for immediate wakeup +* adding lock to planner makePlan fail case +* Contributors: Michael Ferguson, phil0stine + +1.11.13 (2014-10-02) +-------------------- + +1.11.12 (2014-10-01) +-------------------- + +1.11.11 (2014-07-23) +-------------------- +* removes trailing spaces and empty lines +* Contributors: Enrique Fernández Perdomo + +1.11.10 (2014-06-25) +-------------------- +* Remove unnecessary colons +* move_base planService now searches out from desired goal +* Contributors: David Lu!!, Kaijen Hsiao + +1.11.9 (2014-06-10) +------------------- +* uses ::hypot(x, y) instead of sqrt(x*x, y*y) +* Contributors: Enrique Fernández Perdomo + +1.11.8 (2014-05-21) +------------------- + +1.11.7 (2014-05-21) +------------------- +* update build to find eigen using cmake_modules +* Fix classloader warnings on exit of move_base +* Contributors: Michael Ferguson + +1.11.4 (2013-09-27) +------------------- +* Package URL Updates +* Reintroduce ClearCostmaps Service +* Add dependencies to recovery behaviors. diff --git a/navigations/move_base/CMakeLists.txt b/navigations/move_base/CMakeLists.txt new file mode 100755 index 0000000..beb36cf --- /dev/null +++ b/navigations/move_base/CMakeLists.txt @@ -0,0 +1,86 @@ +cmake_minimum_required(VERSION 3.0.2) +project(move_base) + +find_package(catkin REQUIRED COMPONENTS + actionlib + base_local_planner + clear_costmap_recovery + cmake_modules + costmap_2d + dynamic_reconfigure + geometry_msgs + message_generation + move_base_msgs + nav_core + nav_msgs + navfn + pluginlib + roscpp + rospy + rotate_recovery + std_srvs + tf2_geometry_msgs + tf2_ros +) +find_package(Eigen3 REQUIRED) +add_definitions(${EIGEN3_DEFINITIONS}) + +# dynamic reconfigure +generate_dynamic_reconfigure_options( + cfg/MoveBase.cfg +) + +catkin_package( + + INCLUDE_DIRS + include + ${EIGEN3_INCLUDE_DIRS} + LIBRARIES move_base + CATKIN_DEPENDS + dynamic_reconfigure + geometry_msgs + move_base_msgs + nav_msgs + roscpp +) + +include_directories( + include + ${catkin_INCLUDE_DIRS} + ${EIGEN3_INCLUDE_DIRS} +) + +# move_base +add_library(move_base + src/move_base.cpp +) +target_link_libraries(move_base + ${Boost_LIBRARIES} + ${catkin_LIBRARIES} + ) +add_dependencies(move_base ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) + +add_executable(move_base_node + src/move_base_node.cpp +) +add_dependencies(move_base_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) +target_link_libraries(move_base_node move_base) +set_target_properties(move_base_node PROPERTIES OUTPUT_NAME move_base) + +install( + TARGETS + move_base_node + DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) + +install( + TARGETS + move_base + DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +) + +## Mark cpp header files for installation +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} + FILES_MATCHING PATTERN "*.h" +) diff --git a/navigations/move_base/cfg/MoveBase.cfg b/navigations/move_base/cfg/MoveBase.cfg new file mode 100755 index 0000000..9eef29b --- /dev/null +++ b/navigations/move_base/cfg/MoveBase.cfg @@ -0,0 +1,33 @@ +#!/usr/bin/env python + +PACKAGE = 'move_base' + +from dynamic_reconfigure.parameter_generator_catkin import ParameterGenerator, str_t, double_t, bool_t, int_t + +gen = ParameterGenerator() + +gen.add("base_global_planner", str_t, 0, "The name of the plugin for the global planner to use with move_base.", "navfn/NavfnROS") +gen.add("base_local_planner", str_t, 0, "The name of the plugin for the local planner to use with move_base.", "base_local_planner/TrajectoryPlannerROS") + +#gen.add("recovery_behaviors", str_t, 0, "A list of recovery behavior plugins to use with move_base.", "[{name: conservative_reset, type: clear_costmap_recovery/ClearCostmapRecovery}, {name: rotate_recovery, type: rotate_recovery/RotateRecovery}, {name: aggressive_reset, type: clear_costmap_recovery/ClearCostmapRecovery}]") + +gen.add("planner_frequency", double_t, 0, "The rate in Hz at which to run the planning loop.", 0, 0, 100) +gen.add("controller_frequency", double_t, 0, "The rate in Hz at which to run the control loop and send velocity commands to the base.", 20, 0, 100) +gen.add("planner_patience", double_t, 0, "How long the planner will wait in seconds in an attempt to find a valid plan before space-clearing operations are performed.", 5.0, 0, 100) +gen.add("controller_patience", double_t, 0, "How long the controller will wait in seconds without receiving a valid control before space-clearing operations are performed.", 5.0, 0, 100) +gen.add("max_planning_retries", int_t, 0, "How many times we will recall the planner in an attempt to find a valid plan before space-clearing operations are performed", -1, -1, 1000) +gen.add("conservative_reset_dist", double_t, 0, "The distance away from the robot in meters at which obstacles will be cleared from the costmap when attempting to clear space in the map.", 3, 0, 50) + +gen.add("recovery_behavior_enabled", bool_t, 0, "Whether or not to enable the move_base recovery behaviors to attempt to clear out space.", True) +# Doesnt exist +gen.add("clearing_rotation_allowed", bool_t, 0, "Determines whether or not the robot will attempt an in-place rotation when attempting to clear out space.", True) +gen.add("shutdown_costmaps", bool_t, 0, "Determines whether or not to shutdown the costmaps of the node when move_base is in an inactive state", False) + +gen.add("oscillation_timeout", double_t, 0, "How long in seconds to allow for oscillation before executing recovery behaviors.", 0.0, 0, 60) +gen.add("oscillation_distance", double_t, 0, "How far in meters the robot must move to be considered not to be oscillating.", 0.5, 0, 10) + +gen.add("make_plan_clear_costmap", bool_t, 0, "Whether or not to clear the global costmap on make_plan service call.", True) +gen.add("make_plan_add_unreachable_goal", bool_t, 0, "Whether or not to add the original goal to the path if it is unreachable in the make_plan service call.", True) + +gen.add("restore_defaults", bool_t, 0, "Restore to the original configuration", False) +exit(gen.generate(PACKAGE, "move_base_node", "MoveBase")) diff --git a/navigations/move_base/include/move_base/Structor.drawio b/navigations/move_base/include/move_base/Structor.drawio new file mode 100755 index 0000000..c0be080 --- /dev/null +++ b/navigations/move_base/include/move_base/Structor.drawio @@ -0,0 +1,958 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/navigations/move_base/include/move_base/move_base.h b/navigations/move_base/include/move_base/move_base.h new file mode 100755 index 0000000..6f6bb90 --- /dev/null +++ b/navigations/move_base/include/move_base/move_base.h @@ -0,0 +1,243 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2008, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the Willow Garage nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: Eitan Marder-Eppstein + *********************************************************************/ +#ifndef NAV_MOVE_BASE_ACTION_H_ +#define NAV_MOVE_BASE_ACTION_H_ + +#include +#include + +#include + +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +#include +#include "move_base/MoveBaseConfig.h" + +namespace move_base +{ + // typedefs to help us out with the action server so that we don't hace to type so much + typedef actionlib::SimpleActionServer MoveBaseActionServer; + + enum MoveBaseState + { + PLANNING, + CONTROLLING, + CLEARING + }; + + enum RecoveryTrigger + { + PLANNING_R, + CONTROLLING_R, + OSCILLATION_R + }; + + /** + * @class MoveBase + * @brief A class that uses the actionlib::ActionServer interface that moves the robot base to a goal location. + */ + class MoveBase + { + public: + /** + * @brief Constructor for the actions + * @param name The name of the action + * @param tf A reference to a TransformListener + */ + MoveBase(tf2_ros::Buffer &tf); + + /** + * @brief Destructor - Cleans up + */ + virtual ~MoveBase(); + + /** + * @brief Performs a control cycle + * @param goal A reference to the goal to pursue + * @return True if processing of the goal is done, false otherwise + */ + bool executeCycle(geometry_msgs::PoseStamped &goal); + + private: + void clearDirectionalCostmap(); + /** + * @brief A service call that clears the costmaps of obstacles + * @param req The service request + * @param resp The service response + * @return True if the service call succeeds, false otherwise + */ + bool clearCostmapsService(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp); + + /** + * @brief A service call that can be made when the action is inactive that will return a plan + * @param req The goal request + * @param resp The plan request + * @return True if planning succeeded, false otherwise + */ + bool planService(nav_msgs::GetPlan::Request &req, nav_msgs::GetPlan::Response &resp); + + /** + * @brief Make a new global plan + * @param goal The goal to plan to + * @param plan Will be filled in with the plan made by the planner + * @return True if planning succeeds, false otherwise + */ + bool makePlan(const geometry_msgs::PoseStamped &goal, std::vector &plan); + + /** + * @brief Load the recovery behaviors for the navigation stack from the parameter server + * @param node The ros::NodeHandle to be used for loading parameters + * @return True if the recovery behaviors were loaded successfully, false otherwise + */ + bool loadRecoveryBehaviors(ros::NodeHandle node); + + /** + * @brief Loads the default recovery behaviors for the navigation stack + */ + void loadDefaultRecoveryBehaviors(); + + /** + * @brief Clears obstacles within a window around the robot + * @param size_x The x size of the window + * @param size_y The y size of the window + */ + void clearCostmapWindows(double size_x, double size_y); + + /** + * @brief Publishes a velocity command of zero to the base + */ + void publishZeroVelocity(); + + /** + * @brief Reset the state of the move_base action and send a zero velocity command to the base + */ + void resetState(); + + void goalCB(const geometry_msgs::PoseStamped::ConstPtr &goal); + + void planThread(); + + void executeCb(const move_base_msgs::MoveBaseGoalConstPtr &move_base_goal); + + bool isQuaternionValid(const geometry_msgs::Quaternion &q); + + bool getRobotPose(geometry_msgs::PoseStamped &global_pose, costmap_2d::Costmap2DROS *costmap); + + double distance(const geometry_msgs::PoseStamped &p1, const geometry_msgs::PoseStamped &p2); + + geometry_msgs::PoseStamped goalToGlobalFrame(const geometry_msgs::PoseStamped &goal_pose_msg); + + /** + * @brief This is used to wake the planner at periodic intervals. + */ + void wakePlanner(const ros::TimerEvent &event); + + tf2_ros::Buffer &tf_; + + MoveBaseActionServer *as_; + + boost::shared_ptr tc_; + costmap_2d::Costmap2DROS *planner_costmap_ros_; + + boost::shared_ptr planner_; + costmap_2d::Costmap2DROS *controller_costmap_ros_; + std::string robot_base_frame_, global_frame_; + + std::vector> recovery_behaviors_; + std::vector recovery_behavior_names_; + unsigned int recovery_index_; + + geometry_msgs::PoseStamped global_pose_; + double planner_frequency_, controller_frequency_, inscribed_radius_, circumscribed_radius_; + double planner_patience_, controller_patience_; + int32_t max_planning_retries_; + uint32_t planning_retries_; + double conservative_reset_dist_, clearing_radius_; + ros::Publisher current_goal_pub_, vel_pub_, action_goal_pub_, recovery_status_pub_; + ros::Subscriber goal_sub_; + ros::ServiceServer make_plan_srv_, clear_costmaps_srv_; + bool shutdown_costmaps_, clearing_rotation_allowed_, recovery_behavior_enabled_; + bool make_plan_clear_costmap_, make_plan_add_unreachable_goal_; + double oscillation_timeout_, oscillation_distance_; + + MoveBaseState state_; + RecoveryTrigger recovery_trigger_; + + ros::Time last_valid_plan_, last_valid_control_, last_oscillation_reset_; + geometry_msgs::PoseStamped oscillation_pose_; + pluginlib::ClassLoader bgp_loader_; + pluginlib::ClassLoader blp_loader_; + pluginlib::ClassLoader recovery_loader_; + + // set up plan triple buffer + std::vector *planner_plan_; + std::vector *latest_plan_; + std::vector *controller_plan_; + + // set up the planner's thread + bool runPlanner_; + boost::recursive_mutex planner_mutex_; + boost::condition_variable_any planner_cond_; + geometry_msgs::PoseStamped planner_goal_; + boost::thread *planner_thread_; + + boost::recursive_mutex configuration_mutex_; + dynamic_reconfigure::Server *dsrv_; + + void reconfigureCB(move_base::MoveBaseConfig &config, uint32_t level); + + move_base::MoveBaseConfig last_config_; + move_base::MoveBaseConfig default_config_; + bool setup_, p_freq_change_, c_freq_change_; + bool new_global_plan_; + boost::shared_ptr directional_costmap_; + }; +}; +#endif diff --git a/navigations/move_base/include/move_base/move_base.puml b/navigations/move_base/include/move_base/move_base.puml new file mode 100755 index 0000000..91ade5e --- /dev/null +++ b/navigations/move_base/include/move_base/move_base.puml @@ -0,0 +1,120 @@ +@startuml + +class MoveBase { + - tf_: tf2_ros::Buffer& + - as_: MoveBaseActionServer* + - tc_: boost::shared_ptr + - planner_costmap_ros_: costmap_2d::Costmap2DROS* + - controller_costmap_ros_: costmap_2d::Costmap2DROS* + - planner_: boost::shared_ptr + - robot_base_frame_: std::string + - global_frame_: std::string + - recovery_behaviors_: std::vector > + - recovery_behavior_names_: std::vector + - recovery_index_: unsigned int + - global_pose_: geometry_msgs::PoseStamped + - planner_frequency_: double + - controller_frequency_: double + - inscribed_radius_: double + - circumscribed_radius_: double + - planner_patience_: double + - controller_patience_: double + - max_planning_retries_: int32_t + - planning_retries_: uint32_t + - conservative_reset_dist_: double + - clearing_radius_: double + - current_goal_pub_: ros::Publisher + - vel_pub_: ros::Publisher + - action_goal_pub_: ros::Publisher + - recovery_status_pub_: ros::Publisher + - goal_sub_: ros::Subscriber + - make_plan_srv_: ros::ServiceServer + - clear_costmaps_srv_: ros::ServiceServer + - shutdown_costmaps_: bool + - clearing_rotation_allowed_: bool + - recovery_behavior_enabled_: bool + - make_plan_clear_costmap_: bool + - make_plan_add_unreachable_goal_: bool + - oscillation_timeout_: double + - oscillation_distance_: double + - state_: MoveBaseState + - recovery_trigger_: RecoveryTrigger + - last_valid_plan_: ros::Time + - last_valid_control_: ros::Time + - last_oscillation_reset_: ros::Time + - oscillation_pose_: geometry_msgs::PoseStamped + - bgp_loader_: pluginlib::ClassLoader + - blp_loader_: pluginlib::ClassLoader + - recovery_loader_: pluginlib::ClassLoader + - planner_plan_: std::vector* + - latest_plan_: std::vector* + - controller_plan_: std::vector* + - runPlanner_: bool + - planner_mutex_: boost::recursive_mutex + - planner_cond_: boost::condition_variable_any + - planner_goal_: geometry_msgs::PoseStamped + - planner_thread_: boost::thread* + - configuration_mutex_: boost::recursive_mutex + - dsrv_: dynamic_reconfigure::Server* + - last_config_: move_base::MoveBaseConfig + - default_config_: move_base::MoveBaseConfig + - setup_: bool + - p_freq_change_: bool + - c_freq_change_: bool + - new_global_plan_: bool + + MoveBase(tf: tf2_ros::Buffer&) + + ~MoveBase() + + executeCycle(goal: geometry_msgs::PoseStamped&): bool + - clearCostmapsService(req: std_srvs::Empty::Request&, resp: std_srvs::Empty::Response&): bool + - planService(req: nav_msgs::GetPlan::Request&, resp: nav_msgs::GetPlan::Response&): bool + - makePlan(goal: const geometry_msgs::PoseStamped&, plan: std::vector&): bool + - loadRecoveryBehaviors(node: ros::NodeHandle): bool + - loadDefaultRecoveryBehaviors(): void + - clearCostmapWindows(size_x: double, size_y: double): void + - publishZeroVelocity(): void + - resetState(): void + - goalCB(goal: const geometry_msgs::PoseStamped::ConstPtr&): void + - planThread(): void + - executeCb(move_base_goal: const move_base_msgs::MoveBaseGoalConstPtr&): void + - isQuaternionValid(q: const geometry_msgs::Quaternion&): bool + - getRobotPose(global_pose: geometry_msgs::PoseStamped&, costmap: costmap_2d::Costmap2DROS*): bool + - distance(p1: const geometry_msgs::PoseStamped&, p2: const geometry_msgs::PoseStamped&): double + - goalToGlobalFrame(goal_pose_msg: const geometry_msgs::PoseStamped&): geometry_msgs::PoseStamped + - wakePlanner(event: const ros::TimerEvent&): void + - reconfigureCB(config: move_base::MoveBaseConfig, level: uint32_t): void +} + +enum MoveBaseState { + PLANNING + CONTROLLING + CLEARING +} + +enum RecoveryTrigger { + PLANNING_R + CONTROLLING_R + OSCILLATION_R +} + +MoveBase --> tf2_ros::Buffer +MoveBase --> MoveBaseActionServer +MoveBase --> boost::shared_ptr +MoveBase --> costmap_2d::Costmap2DROS +MoveBase --> std::vector > +MoveBase --> std::vector +MoveBase --> geometry_msgs::PoseStamped +MoveBase --> ros::Publisher +MoveBase --> ros::Subscriber +MoveBase --> ros::ServiceServer +MoveBase --> ros::Time +MoveBase --> pluginlib::ClassLoader +MoveBase --> pluginlib::ClassLoader +MoveBase --> pluginlib::ClassLoader +MoveBase --> std::vector +MoveBase --> boost::recursive_mutex +MoveBase --> boost::condition_variable_any +MoveBase --> boost::thread +MoveBase --> dynamic_reconfigure::Server +MoveBase --> move_base::MoveBaseConfig + +@enduml \ No newline at end of file diff --git a/navigations/move_base/package.xml b/navigations/move_base/package.xml new file mode 100755 index 0000000..5a7209d --- /dev/null +++ b/navigations/move_base/package.xml @@ -0,0 +1,69 @@ + + + + move_base + 1.17.3 + + + The move_base package provides an implementation of an action (see the actionlib package) that, given a goal in the world, will attempt to reach it with a mobile base. The move_base node links together a global and local planner to accomplish its global navigation task. It supports any global planner adhering to the nav_core::BaseGlobalPlanner interface specified in the nav_core package and any local planner adhering to the nav_core::BaseLocalPlanner interface specified in the nav_core package. The move_base node also maintains two costmaps, one for the global planner, and one for a local planner (see the costmap_2d package) that are used to accomplish navigation tasks. + + + Eitan Marder-Eppstein + contradict@gmail.com + David V. Lu!! + Michael Ferguson + Aaron Hoy + BSD + http://wiki.ros.org/move_base + + catkin + + cmake_modules + message_generation + tf2_geometry_msgs + + actionlib + + costmap_2d + costmap_2d + + dynamic_reconfigure + geometry_msgs + + move_base_msgs + move_base_msgs + + nav_core + nav_core + + nav_msgs + nav_msgs + + pluginlib + pluginlib + + roscpp + rospy + std_srvs + + tf2_ros + tf2_ros + + visualization_msgs + + + base_local_planner + base_local_planner + + clear_costmap_recovery + clear_costmap_recovery + + navfn + navfn + + rotate_recovery + rotate_recovery + + message_runtime + + diff --git a/navigations/move_base/planner_test.xml b/navigations/move_base/planner_test.xml new file mode 100755 index 0000000..655f243 --- /dev/null +++ b/navigations/move_base/planner_test.xml @@ -0,0 +1,12 @@ + + + + + + + + + + + + diff --git a/navigations/move_base/src/move_base.cpp b/navigations/move_base/src/move_base.cpp new file mode 100755 index 0000000..c571e8c --- /dev/null +++ b/navigations/move_base/src/move_base.cpp @@ -0,0 +1,1430 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2008, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the Willow Garage nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: Eitan Marder-Eppstein + * Mike Phillips (put the planner in its own thread) + *********************************************************************/ +#include +#include +#include + +#include +#include + +#include + +#include + +namespace move_base +{ + + MoveBase::MoveBase(tf2_ros::Buffer &tf) : tf_(tf), + as_(NULL), + planner_costmap_ros_(NULL), controller_costmap_ros_(NULL), + bgp_loader_("nav_core", "nav_core::BaseGlobalPlanner"), + blp_loader_("nav_core", "nav_core::BaseLocalPlanner"), + recovery_loader_("nav_core", "nav_core::RecoveryBehavior"), + planner_plan_(NULL), latest_plan_(NULL), controller_plan_(NULL), + runPlanner_(false), setup_(false), p_freq_change_(false), c_freq_change_(false), new_global_plan_(false) + { + + as_ = new MoveBaseActionServer( + ros::NodeHandle(), "move_base", [this](auto &goal) + { executeCb(goal); }, + false); + + ros::NodeHandle private_nh("~"); + ros::NodeHandle nh; + + recovery_trigger_ = PLANNING_R; + + // get some parameters that will be global to the move base node + std::string global_planner, local_planner; + // From /home/robotics/AGV/mir_robot_ws/src/mir_robot/mir_navigation/config/sbpl_global_params.yaml + private_nh.param("base_global_planner", global_planner, std::string("navfn/NavfnROS")); + // From /home/robotics/AGV/mir_robot_ws/src/mir_robot/mir_navigation/config/dwb_local_planner_params.yaml + if (!private_nh.param("base_local_planner", local_planner, std::string("base_local_planner/TrajectoryPlannerROS"))) + ROS_ERROR("faild"); + // From /home/robotics/AGV/mir_robot_ws/src/mir_robot/mir_navigation/config/costmap_common_params.yaml + private_nh.param("global_costmap/robot_base_frame", robot_base_frame_, std::string("base_link")); + // From /home/robotics/AGV/mir_robot_ws/src/mir_robot/mir_navigation/config/costmap_global_params.yaml + private_nh.param("global_costmap/global_frame", global_frame_, std::string("map")); + // From /home/robotics/AGV/mir_robot_ws/src/mir_robot/mir_navigation/config/move_base_common_params.yaml + private_nh.param("planner_frequency", planner_frequency_, 0.0); + // From /home/robotics/AGV/mir_robot_ws/src/mir_robot/mir_navigation/config/move_base_common_params.yaml + // Tần số điều khiển của Robot + private_nh.param("controller_frequency", controller_frequency_, 20.0); + // From /home/robotics/AGV/mir_robot_ws/src/mir_robot/mir_navigation/config/move_base_common_params.yaml + private_nh.param("planner_patience", planner_patience_, 5.0); + // From /home/robotics/AGV/mir_robot_ws/src/mir_robot/mir_navigation/config/move_base_common_params.yaml + private_nh.param("controller_patience", controller_patience_, 15.0); + // From /home/robotics/AGV/mir_robot_ws/src/mir_robot/mir_navigation/config/move_base_common_params.yaml + private_nh.param("max_planning_retries", max_planning_retries_, -1); // disabled by default + // From /home/robotics/AGV/mir_robot_ws/src/mir_robot/mir_navigation/config/move_base_common_params.yaml + private_nh.param("oscillation_timeout", oscillation_timeout_, 0.0); + // No path + private_nh.param("oscillation_distance", oscillation_distance_, 0.5); + + // parameters of make_plan service + // No path + private_nh.param("make_plan_clear_costmap", make_plan_clear_costmap_, true); + // No path + private_nh.param("make_plan_add_unreachable_goal", make_plan_add_unreachable_goal_, true); + + // set up plan triple buffer + planner_plan_ = new std::vector(); + latest_plan_ = new std::vector(); + controller_plan_ = new std::vector(); + + // set up the planner's thread + planner_thread_ = new boost::thread(boost::bind(&MoveBase::planThread, this)); + + // for commanding the base + vel_pub_ = nh.advertise("cmd_vel", 1); + current_goal_pub_ = private_nh.advertise("current_goal", 0); + + ros::NodeHandle action_nh("move_base"); + action_goal_pub_ = action_nh.advertise("goal", 1); + recovery_status_pub_ = action_nh.advertise("recovery_status", 1); + + // we'll provide a mechanism for some people to send goals as PoseStamped messages over a topic + // they won't get any useful information back about its status, but this is useful for tools + // like nav_view and rviz + ros::NodeHandle simple_nh("move_base_simple"); + goal_sub_ = simple_nh.subscribe("goal", 1, [this](auto &goal) + { goalCB(goal); }); + + // we'll assume the radius of the robot to be consistent with what's specified for the costmaps + // From config param + private_nh.param("local_costmap/inscribed_radius", inscribed_radius_, 0.325); + // ROS_ERROR("local_costmap/inscribed_radius: %f", inscribed_radius_); + private_nh.param("local_costmap/circumscribed_radius", circumscribed_radius_, 0.46); + // ROS_ERROR("local_costmap/circumscribed_radius: %f", circumscribed_radius_); + private_nh.param("clearing_radius", clearing_radius_, circumscribed_radius_); + // ROS_ERROR("clearing_radius: %f", clearing_radius_); + private_nh.param("conservative_reset_dist", conservative_reset_dist_, 3.0); + // ROS_ERROR("conservative_reset_dist: %f", conservative_reset_dist_); + private_nh.param("shutdown_costmaps", shutdown_costmaps_, false); + // ROS_ERROR("shutdown_costmaps: %d", shutdown_costmaps_); + private_nh.param("clearing_rotation_allowed", clearing_rotation_allowed_, true); + // ROS_ERROR("clearing_rotation_allowed: %d", clearing_rotation_allowed_); + private_nh.param("recovery_behavior_enabled", recovery_behavior_enabled_, true); + // ROS_ERROR("recovery_behavior_enabled: %d", recovery_behavior_enabled_); + + // create the ros wrapper for the planner's costmap... and initializer a pointer we'll use with the underlying map + planner_costmap_ros_ = new costmap_2d::Costmap2DROS("global_costmap", tf_); + planner_costmap_ros_->pause(); + + // initialize the global planner + try + { + planner_ = bgp_loader_.createInstance(global_planner); + // From void GlobalPlannerAdapter::initialize(std::string name, costmap_2d::Costmap2DROS* costmap_ros) + // ROS_WARN("move_base::initialize %s" , global_planner.c_str()); + ROS_INFO("Created global_planner %s", global_planner.c_str()); + planner_->initialize(bgp_loader_.getName(global_planner), planner_costmap_ros_); + } + catch (const pluginlib::PluginlibException &ex) + { + ROS_FATAL("Failed to create the %s planner, are you sure it is properly registered and that the containing library is built? Exception: %s", global_planner.c_str(), ex.what()); + exit(1); + } + // create the ros wrapper for the controller's costmap... and initializer a pointer we'll use with the underlying map + controller_costmap_ros_ = new costmap_2d::Costmap2DROS("local_costmap", tf_); + controller_costmap_ros_->pause(); + + // create a local planner + try + { + tc_ = blp_loader_.createInstance(local_planner); + ROS_INFO("Created local_planner %s", local_planner.c_str()); + // From void LocalPlannerAdapter::initialize(std::string name, tf2_ros::Buffer* tf, costmap_2d::Costmap2DROS* costmap_ros) + tc_->initialize(blp_loader_.getName(local_planner), &tf_, controller_costmap_ros_); + } + catch (const pluginlib::PluginlibException &ex) + { + ROS_FATAL("Failed to create the %s planner, are you sure it is properly registered and that the containing library is built? Exception: %s", local_planner.c_str(), ex.what()); + exit(1); + } + + // Start actively updating costmaps based on sensor data + planner_costmap_ros_->start(); + controller_costmap_ros_->start(); + + // advertise a service for getting a plan + make_plan_srv_ = private_nh.advertiseService("make_plan", &MoveBase::planService, this); + + // advertise a service for clearing the costmaps + clear_costmaps_srv_ = private_nh.advertiseService("clear_costmaps", &MoveBase::clearCostmapsService, this); + + // if we shutdown our costmaps when we're deactivated... we'll do that now + if (shutdown_costmaps_) + { + ROS_DEBUG_NAMED("move_base", "Stopping costmaps initially"); + planner_costmap_ros_->stop(); + controller_costmap_ros_->stop(); + } + + // load any user specified recovery behaviors, and if that fails load the defaults + if (!loadRecoveryBehaviors(private_nh)) + { + loadDefaultRecoveryBehaviors(); + } + + // initially, we'll need to make a plan + state_ = PLANNING; + + // we'll start executing recovery behaviors at the beginning of our list + recovery_index_ = 0; + + // we're all set up now so we can start the action server + as_->start(); + + dsrv_ = new dynamic_reconfigure::Server(ros::NodeHandle("~")); + dynamic_reconfigure::Server::CallbackType cb = [this](auto &config, auto level) + { reconfigureCB(config, level); }; + dsrv_->setCallback(cb); + + std::vector> *plugins = planner_costmap_ros_->getLayeredCostmap()->getPlugins(); + for (std::vector>::iterator pluginp = plugins->begin(); pluginp != plugins->end(); ++pluginp) + { + boost::shared_ptr plugin = *pluginp; + std::string name = plugin->getName(); + int slash = name.rfind('/'); + if (slash != std::string::npos) + { + name = name.substr(slash + 1); + } + + // check if the value is convertable + if (!dynamic_cast(plugin.get())) + { + continue; + } + directional_costmap_ = boost::static_pointer_cast(plugin); + } + } + + void MoveBase::reconfigureCB(move_base::MoveBaseConfig &config, uint32_t level) + { + boost::recursive_mutex::scoped_lock l(configuration_mutex_); + + // The first time we're called, we just want to make sure we have the + // original configuration + if (!setup_) + { + last_config_ = config; + default_config_ = config; + setup_ = true; + return; + } + + if (config.restore_defaults) + { + config = default_config_; + // if someone sets restore defaults on the parameter server, prevent looping + config.restore_defaults = false; + } + + if (planner_frequency_ != config.planner_frequency) + { + planner_frequency_ = config.planner_frequency; + p_freq_change_ = true; + } + + if (controller_frequency_ != config.controller_frequency) + { + controller_frequency_ = config.controller_frequency; + c_freq_change_ = true; + } + + planner_patience_ = config.planner_patience; + controller_patience_ = config.controller_patience; + max_planning_retries_ = config.max_planning_retries; + conservative_reset_dist_ = config.conservative_reset_dist; + + recovery_behavior_enabled_ = config.recovery_behavior_enabled; + clearing_rotation_allowed_ = config.clearing_rotation_allowed; + shutdown_costmaps_ = config.shutdown_costmaps; + + oscillation_timeout_ = config.oscillation_timeout; + oscillation_distance_ = config.oscillation_distance; + if (config.base_global_planner != last_config_.base_global_planner) + { + boost::shared_ptr old_planner = planner_; + // initialize the global planner + ROS_INFO("Loading global planner %s", config.base_global_planner.c_str()); + try + { + planner_ = bgp_loader_.createInstance(config.base_global_planner); + + // wait for the current planner to finish planning + boost::unique_lock lock(planner_mutex_); + + // Clean up before initializing the new planner + planner_plan_->clear(); + latest_plan_->clear(); + controller_plan_->clear(); + resetState(); + planner_->initialize(bgp_loader_.getName(config.base_global_planner), planner_costmap_ros_); + + lock.unlock(); + } + catch (const pluginlib::PluginlibException &ex) + { + ROS_FATAL("Failed to create the %s planner, are you sure it is properly registered and that the \ + containing library is built? Exception: %s", + config.base_global_planner.c_str(), ex.what()); + planner_ = old_planner; + config.base_global_planner = last_config_.base_global_planner; + } + } + + if (config.base_local_planner != last_config_.base_local_planner) + { + boost::shared_ptr old_planner = tc_; + // create a local planner + try + { + tc_ = blp_loader_.createInstance(config.base_local_planner); + // Clean up before initializing the new planner + planner_plan_->clear(); + latest_plan_->clear(); + controller_plan_->clear(); + resetState(); + tc_->initialize(blp_loader_.getName(config.base_local_planner), &tf_, controller_costmap_ros_); + } + catch (const pluginlib::PluginlibException &ex) + { + ROS_FATAL("Failed to create the %s planner, are you sure it is properly registered and that the \ + containing library is built? Exception: %s", + config.base_local_planner.c_str(), ex.what()); + tc_ = old_planner; + config.base_local_planner = last_config_.base_local_planner; + } + } + + make_plan_clear_costmap_ = config.make_plan_clear_costmap; + make_plan_add_unreachable_goal_ = config.make_plan_add_unreachable_goal; + + last_config_ = config; + } + + void MoveBase::goalCB(const geometry_msgs::PoseStamped::ConstPtr &goal) + { + ROS_DEBUG_NAMED("move_base", "In ROS goal callback, wrapping the PoseStamped in the action message and re-sending to the server."); + clearDirectionalCostmap(); + move_base_msgs::MoveBaseActionGoal action_goal; + action_goal.header.stamp = ros::Time::now(); + action_goal.goal.target_pose = *goal; + action_goal_pub_.publish(action_goal); + } + + void MoveBase::clearCostmapWindows(double size_x, double size_y) + { + geometry_msgs::PoseStamped global_pose; + + // clear the planner's costmap + getRobotPose(global_pose, planner_costmap_ros_); + + std::vector clear_poly; + double x = global_pose.pose.position.x; + double y = global_pose.pose.position.y; + geometry_msgs::Point pt; + + pt.x = x - size_x / 2; + pt.y = y - size_y / 2; + clear_poly.push_back(pt); + + pt.x = x + size_x / 2; + pt.y = y - size_y / 2; + clear_poly.push_back(pt); + + pt.x = x + size_x / 2; + pt.y = y + size_y / 2; + clear_poly.push_back(pt); + + pt.x = x - size_x / 2; + pt.y = y + size_y / 2; + clear_poly.push_back(pt); + + planner_costmap_ros_->getCostmap()->setConvexPolygonCost(clear_poly, costmap_2d::FREE_SPACE); + + // clear the controller's costmap + getRobotPose(global_pose, controller_costmap_ros_); + + clear_poly.clear(); + x = global_pose.pose.position.x; + y = global_pose.pose.position.y; + + pt.x = x - size_x / 2; + pt.y = y - size_y / 2; + clear_poly.push_back(pt); + + pt.x = x + size_x / 2; + pt.y = y - size_y / 2; + clear_poly.push_back(pt); + + pt.x = x + size_x / 2; + pt.y = y + size_y / 2; + clear_poly.push_back(pt); + + pt.x = x - size_x / 2; + pt.y = y + size_y / 2; + clear_poly.push_back(pt); + + controller_costmap_ros_->getCostmap()->setConvexPolygonCost(clear_poly, costmap_2d::FREE_SPACE); + } + + bool MoveBase::clearCostmapsService(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp) + { + // clear the costmaps + boost::unique_lock lock_controller(*(controller_costmap_ros_->getCostmap()->getMutex())); + controller_costmap_ros_->resetLayers(); + + boost::unique_lock lock_planner(*(planner_costmap_ros_->getCostmap()->getMutex())); + planner_costmap_ros_->resetLayers(); + return true; + } + + bool MoveBase::planService(nav_msgs::GetPlan::Request &req, nav_msgs::GetPlan::Response &resp) + { + if (as_->isActive()) + { + ROS_ERROR("move_base must be in an inactive state to make a plan for an external user"); + return false; + } + // make sure we have a costmap for our planner + if (planner_costmap_ros_ == NULL) + { + ROS_ERROR("move_base cannot make a plan for you because it doesn't have a costmap"); + return false; + } + + geometry_msgs::PoseStamped start; + // if the user does not specify a start pose, identified by an empty frame id, then use the robot's pose + if (req.start.header.frame_id.empty()) + { + geometry_msgs::PoseStamped global_pose; + if (!getRobotPose(global_pose, planner_costmap_ros_)) + { + ROS_ERROR("move_base cannot make a plan for you because it could not get the start pose of the robot"); + return false; + } + start = global_pose; + } + else + { + start = req.start; + } + + if (make_plan_clear_costmap_) + { + // update the copy of the costmap the planner uses + clearCostmapWindows(2 * clearing_radius_, 2 * clearing_radius_); + } + + // first try to make a plan to the exact desired goal + std::vector global_plan; + if (!planner_->makePlan(start, req.goal, global_plan) || global_plan.empty()) + { + ROS_DEBUG_NAMED("move_base", "Failed to find a plan to exact goal of (%.2f, %.2f), searching for a feasible goal within tolerance", + req.goal.pose.position.x, req.goal.pose.position.y); + + // search outwards for a feasible goal within the specified tolerance + geometry_msgs::PoseStamped p; + p = req.goal; + bool found_legal = false; + float resolution = planner_costmap_ros_->getCostmap()->getResolution(); + float search_increment = resolution * 3.0; + if (req.tolerance > 0.0 && req.tolerance < search_increment) + search_increment = req.tolerance; + for (float max_offset = search_increment; max_offset <= req.tolerance && !found_legal; max_offset += search_increment) + { + for (float y_offset = 0; y_offset <= max_offset && !found_legal; y_offset += search_increment) + { + for (float x_offset = 0; x_offset <= max_offset && !found_legal; x_offset += search_increment) + { + + // don't search again inside the current outer layer + if (x_offset < max_offset - 1e-9 && y_offset < max_offset - 1e-9) + continue; + + // search to both sides of the desired goal + for (float y_mult = -1.0; y_mult <= 1.0 + 1e-9 && !found_legal; y_mult += 2.0) + { + + // if one of the offsets is 0, -1*0 is still 0 (so get rid of one of the two) + if (y_offset < 1e-9 && y_mult < -1.0 + 1e-9) + continue; + + for (float x_mult = -1.0; x_mult <= 1.0 + 1e-9 && !found_legal; x_mult += 2.0) + { + if (x_offset < 1e-9 && x_mult < -1.0 + 1e-9) + continue; + + p.pose.position.y = req.goal.pose.position.y + y_offset * y_mult; + p.pose.position.x = req.goal.pose.position.x + x_offset * x_mult; + + if (planner_->makePlan(start, p, global_plan)) + { + if (!global_plan.empty()) + { + + if (make_plan_add_unreachable_goal_) + { + // adding the (unreachable) original goal to the end of the global plan, in case the local planner can get you there + //(the reachable goal should have been added by the global planner) + global_plan.push_back(req.goal); + } + + found_legal = true; + ROS_DEBUG_NAMED("move_base", "Found a plan to point (%.2f, %.2f)", p.pose.position.x, p.pose.position.y); + break; + } + } + else + { + ROS_DEBUG_NAMED("move_base", "Failed to find a plan to point (%.2f, %.2f)", p.pose.position.x, p.pose.position.y); + } + } + } + } + } + } + } + + // copy the plan into a message to send out + resp.plan.poses.resize(global_plan.size()); + for (unsigned int i = 0; i < global_plan.size(); ++i) + { + resp.plan.poses[i] = global_plan[i]; + } + + return true; + } + + MoveBase::~MoveBase() + { + recovery_behaviors_.clear(); + + delete dsrv_; + + if (as_ != NULL) + delete as_; + + if (planner_costmap_ros_ != NULL) + delete planner_costmap_ros_; + + if (controller_costmap_ros_ != NULL) + delete controller_costmap_ros_; + + planner_thread_->interrupt(); + planner_thread_->join(); + + delete planner_thread_; + + delete planner_plan_; + delete latest_plan_; + delete controller_plan_; + + planner_.reset(); + tc_.reset(); + } + + bool MoveBase::makePlan(const geometry_msgs::PoseStamped &goal, std::vector &plan) + { + boost::unique_lock lock(*(planner_costmap_ros_->getCostmap()->getMutex())); + + // make sure to set the plan to be empty initially + plan.clear(); + + // since this gets called on handle activate + if (planner_costmap_ros_ == NULL) + { + ROS_ERROR("Planner costmap ROS is NULL, unable to create global plan"); + return false; + } + // get the starting pose of the robot + geometry_msgs::PoseStamped global_pose; + if (!getRobotPose(global_pose, planner_costmap_ros_)) + { + ROS_WARN("Unable to get starting pose of robot, unable to create global plan"); + return false; + } + + const geometry_msgs::PoseStamped &start = global_pose; + ros::WallTime start_time = ros::WallTime::now(); + bool result_find_plan = planner_->makePlan(start, goal, plan); + ros::WallDuration t_diff = ros::WallTime::now() - start_time; + ROS_INFO("planner_->makePlan(start, goal, plan) cycle time: %.9f", t_diff.toSec()); + // if the planner fails or returns a zero length plan, planning failed + if (!result_find_plan || plan.empty()) + { + ROS_DEBUG_NAMED("move_base", "Failed to find a plan to point (%.2f, %.2f)", goal.pose.position.x, goal.pose.position.y); + return false; + } + else + { + try + { + if (directional_costmap_ != nullptr) + { + if(directional_costmap_->isEnabled()) + { + ROS_INFO("directional_costmap_ start"); + ros::WallTime start = ros::WallTime::now(); + bool result = true; + result = directional_costmap_->laneFilter(plan); + if (!result) + planner_costmap_ros_->updateMap(); + return result; + } + } + } + catch (const std::exception &e) + { + ROS_ERROR_STREAM(e.what() << '\n'); + return false; + } + } + return true; + } + + void MoveBase::publishZeroVelocity() + { + geometry_msgs::Twist cmd_vel; + cmd_vel.linear.x = 0.0; + cmd_vel.linear.y = 0.0; + cmd_vel.angular.z = 0.0; + vel_pub_.publish(cmd_vel); + } + + bool MoveBase::isQuaternionValid(const geometry_msgs::Quaternion &q) + { + // first we need to check if the quaternion has nan's or infs + if (!std::isfinite(q.x) || !std::isfinite(q.y) || !std::isfinite(q.z) || !std::isfinite(q.w)) + { + ROS_ERROR("Quaternion has nans or infs... discarding as a navigation goal"); + return false; + } + + tf2::Quaternion tf_q(q.x, q.y, q.z, q.w); + + // next, we need to check if the length of the quaternion is close to zero + if (tf_q.length2() < 1e-6) + { + ROS_ERROR("Quaternion has length close to zero... discarding as navigation goal"); + return false; + } + + // next, we'll normalize the quaternion and check that it transforms the vertical vector correctly + tf_q.normalize(); + + tf2::Vector3 up(0, 0, 1); + + double dot = up.dot(up.rotate(tf_q.getAxis(), tf_q.getAngle())); + + if (fabs(dot - 1) > 1e-3) + { + ROS_ERROR("Quaternion is invalid... for navigation the z-axis of the quaternion must be close to vertical."); + return false; + } + + return true; + } + + geometry_msgs::PoseStamped MoveBase::goalToGlobalFrame(const geometry_msgs::PoseStamped &goal_pose_msg) + { + std::string global_frame = planner_costmap_ros_->getGlobalFrameID(); + geometry_msgs::PoseStamped goal_pose, global_pose; + goal_pose = goal_pose_msg; + + // just get the latest available transform... for accuracy they should send + // goals in the frame of the planner + goal_pose.header.stamp = ros::Time(); + + try + { + tf_.transform(goal_pose_msg, global_pose, global_frame); + } + catch (tf2::TransformException &ex) + { + ROS_WARN("Failed to transform the goal pose from %s into the %s frame: %s", + goal_pose.header.frame_id.c_str(), global_frame.c_str(), ex.what()); + return goal_pose_msg; + } + + return global_pose; + } + + void MoveBase::wakePlanner(const ros::TimerEvent &event) + { + // we have slept long enough for rate + planner_cond_.notify_one(); + } + + void MoveBase::planThread() + { + ROS_DEBUG_NAMED("move_base_plan_thread", "Starting planner thread..."); + ros::NodeHandle n; + ros::Timer timer; + bool wait_for_wake = false; + boost::unique_lock lock(planner_mutex_); + while (n.ok()) + { + // check if we should run the planner (the mutex is locked) + while (wait_for_wake || !runPlanner_) + { + // if we should not be running the planner then suspend this thread + ROS_DEBUG_NAMED("move_base_plan_thread", "Planner thread is suspending"); + planner_cond_.wait(lock); + wait_for_wake = false; + } + ros::Time start_time = ros::Time::now(); + + // time to plan! get a copy of the goal and unlock the mutex + geometry_msgs::PoseStamped temp_goal = planner_goal_; + lock.unlock(); + ROS_DEBUG_NAMED("move_base_plan_thread", "Planning..."); + + // run planner + planner_plan_->clear(); + bool gotPlan = n.ok() && makePlan(temp_goal, *planner_plan_); + + if (gotPlan) + { + ROS_DEBUG_NAMED("move_base_plan_thread", "Got Plan with %zu points!", planner_plan_->size()); + // pointer swap the plans under mutex (the controller will pull from latest_plan_) + std::vector *temp_plan = planner_plan_; + + lock.lock(); + planner_plan_ = latest_plan_; + latest_plan_ = temp_plan; + last_valid_plan_ = ros::Time::now(); + planning_retries_ = 0; + new_global_plan_ = true; + + ROS_DEBUG_NAMED("move_base_plan_thread", "Generated a plan from the base_global_planner"); + + // make sure we only start the controller if we still haven't reached the goal + if (runPlanner_) + state_ = CONTROLLING; + if (planner_frequency_ <= 0) + runPlanner_ = false; + lock.unlock(); + } + // if we didn't get a plan and we are in the planning state (the robot isn't moving) + else if (state_ == PLANNING) + { + ROS_DEBUG_NAMED("move_base_plan_thread", "No Plan..."); + ros::Time attempt_end = last_valid_plan_ + ros::Duration(planner_patience_); + + // check if we've tried to make a plan for over our time limit or our maximum number of retries + // issue #496: we stop planning when one of the conditions is true, but if max_planning_retries_ + // is negative (the default), it is just ignored and we have the same behavior as ever + lock.lock(); + planning_retries_++; + if (runPlanner_ && + (ros::Time::now() > attempt_end || planning_retries_ > uint32_t(max_planning_retries_))) + { + // we'll move into our obstacle clearing mode + state_ = CLEARING; + runPlanner_ = false; // proper solution for issue #523 + ROS_ERROR("we'll move into our obstacle clearing mode"); + publishZeroVelocity(); + recovery_trigger_ = PLANNING_R; + } + + lock.unlock(); + } + + // take the mutex for the next iteration + lock.lock(); + + // setup sleep interface if needed + if (planner_frequency_ > 0) + { + ros::Duration sleep_time = (start_time + ros::Duration(1.0 / planner_frequency_)) - ros::Time::now(); + if (sleep_time > ros::Duration(0.0)) + { + wait_for_wake = true; + timer = n.createTimer(sleep_time, &MoveBase::wakePlanner, this); + } + } + } + } + + void MoveBase::executeCb(const move_base_msgs::MoveBaseGoalConstPtr &move_base_goal) + { + if (!isQuaternionValid(move_base_goal->target_pose.pose.orientation)) + { + as_->setAborted(move_base_msgs::MoveBaseResult(), "Aborting on goal because it was sent with an invalid quaternion"); + return; + } + // clear costmap from directional layer + geometry_msgs::PoseStamped goal = goalToGlobalFrame(move_base_goal->target_pose); + publishZeroVelocity(); + // we have a goal so start the planner + boost::unique_lock lock(planner_mutex_); + planner_goal_ = goal; + runPlanner_ = true; + planner_cond_.notify_one(); + lock.unlock(); + + current_goal_pub_.publish(goal); + + ros::Rate r(controller_frequency_); + if (shutdown_costmaps_) + { + ROS_DEBUG_NAMED("move_base", "Starting up costmaps that were shut down previously"); + planner_costmap_ros_->start(); + controller_costmap_ros_->start(); + } + + // we want to make sure that we reset the last time we had a valid plan and control + last_valid_control_ = ros::Time::now(); + last_valid_plan_ = ros::Time::now(); + last_oscillation_reset_ = ros::Time::now(); + planning_retries_ = 0; + + geometry_msgs::PoseStamped global_pose; + getRobotPose(global_pose, planner_costmap_ros_); + oscillation_pose_ = global_pose; + + ros::NodeHandle n; + while (n.ok()) + { + if (c_freq_change_) + { + ROS_INFO("Setting controller frequency to %.2f", controller_frequency_); + r = ros::Rate(controller_frequency_); + c_freq_change_ = false; + } + + if (as_->isPreemptRequested()) + { + if (as_->isNewGoalAvailable()) + { + // if we're active and a new goal is available, we'll accept it, but we won't shut anything down + move_base_msgs::MoveBaseGoal new_goal = *as_->acceptNewGoal(); + + if (!isQuaternionValid(new_goal.target_pose.pose.orientation)) + { + as_->setAborted(move_base_msgs::MoveBaseResult(), "Aborting on goal because it was sent with an invalid quaternion"); + return; + } + + goal = goalToGlobalFrame(new_goal.target_pose); + + // we'll make sure that we reset our state for the next execution cycle + recovery_index_ = 0; + state_ = PLANNING; + + // we have a new goal so make sure the planner is awake + lock.lock(); + planner_goal_ = goal; + runPlanner_ = true; + planner_cond_.notify_one(); + lock.unlock(); + + // publish the goal point to the visualizer + ROS_DEBUG_NAMED("move_base", "move_base has received a goal of x: %.2f, y: %.2f", goal.pose.position.x, goal.pose.position.y); + current_goal_pub_.publish(goal); + + // make sure to reset our timeouts and counters + last_valid_control_ = ros::Time::now(); + last_valid_plan_ = ros::Time::now(); + last_oscillation_reset_ = ros::Time::now(); + planning_retries_ = 0; + } + else + { + // if we've been preempted explicitly we need to shut things down + resetState(); + + // notify the ActionServer that we've successfully preempted + ROS_DEBUG_NAMED("move_base", "Move base preempting the current goal"); + as_->setPreempted(); + + // we'll actually return from execute after preempting + return; + } + } + + // we also want to check if we've changed global frames because we need to transform our goal pose + if (goal.header.frame_id != planner_costmap_ros_->getGlobalFrameID()) + { + goal = goalToGlobalFrame(goal); + + // we want to go back to the planning state for the next execution cycle + recovery_index_ = 0; + state_ = PLANNING; + + // we have a new goal so make sure the planner is awake + lock.lock(); + planner_goal_ = goal; + runPlanner_ = true; + planner_cond_.notify_one(); + lock.unlock(); + + // publish the goal point to the visualizer + ROS_DEBUG_NAMED("move_base", "The global frame for move_base has changed, new frame: %s, new goal position x: %.2f, y: %.2f", goal.header.frame_id.c_str(), goal.pose.position.x, goal.pose.position.y); + current_goal_pub_.publish(goal); + + // make sure to reset our timeouts and counters + last_valid_control_ = ros::Time::now(); + last_valid_plan_ = ros::Time::now(); + last_oscillation_reset_ = ros::Time::now(); + planning_retries_ = 0; + } + + // for timing that gives real time even in simulation + ros::WallTime start = ros::WallTime::now(); + + // the real work on pursuing a goal is done here + bool done = executeCycle(goal); + + // if we're done, then we'll return from execute + if (done) + return; + + // check if execution of the goal has completed in some way + + ros::WallDuration t_diff = ros::WallTime::now() - start; + ROS_DEBUG_NAMED("move_base", "Full control cycle time: %.9f\n", t_diff.toSec()); + + r.sleep(); + // make sure to sleep for the remainder of our cycle time + if (r.cycleTime() > ros::Duration(1 / controller_frequency_) && state_ == CONTROLLING) + ROS_WARN("Control loop missed its desired rate of %.4fHz... the loop actually took %.4f seconds", controller_frequency_, r.cycleTime().toSec()); + } + + // wake up the planner thread so that it can exit cleanly + lock.lock(); + runPlanner_ = true; + planner_cond_.notify_one(); + lock.unlock(); + + // if the node is killed then we'll abort and return + as_->setAborted(move_base_msgs::MoveBaseResult(), "Aborting on the goal because the node has been killed"); + return; + } + + double MoveBase::distance(const geometry_msgs::PoseStamped &p1, const geometry_msgs::PoseStamped &p2) + { + return hypot(p1.pose.position.x - p2.pose.position.x, p1.pose.position.y - p2.pose.position.y); + } + + bool MoveBase::executeCycle(geometry_msgs::PoseStamped &goal) + { + boost::recursive_mutex::scoped_lock ecl(configuration_mutex_); + // we need to be able to publish velocity commands + geometry_msgs::Twist cmd_vel; + + // update feedback to correspond to our curent position + geometry_msgs::PoseStamped global_pose; + getRobotPose(global_pose, planner_costmap_ros_); + const geometry_msgs::PoseStamped ¤t_position = global_pose; + + // push the feedback out + move_base_msgs::MoveBaseFeedback feedback; + feedback.base_position = current_position; + as_->publishFeedback(feedback); + + // check to see if we've moved far enough to reset our oscillation timeout + double current_distance = distance(current_position, oscillation_pose_); + if (current_distance >= oscillation_distance_) + { + last_oscillation_reset_ = ros::Time::now(); + oscillation_pose_ = current_position; + + // if our last recovery was caused by oscillation, we want to reset the recovery index + if (recovery_trigger_ == OSCILLATION_R) + recovery_index_ = 0; + } + + // check that the observation buffers for the costmap are current, we don't want to drive blind + if (!controller_costmap_ros_->isCurrent()) + { + ROS_WARN("[%s]:Sensor data is out of date, we're not going to allow commanding of the base for safety", ros::this_node::getName().c_str()); + publishZeroVelocity(); + return false; + } + + // if we have a new plan then grab it and give it to the controller + if (new_global_plan_) + { + // make sure to set the new plan flag to false + new_global_plan_ = false; + + ROS_DEBUG_NAMED("move_base", "Got a new plan...swap pointers"); + + // do a pointer swap under mutex + std::vector *temp_plan = controller_plan_; + + boost::unique_lock lock(planner_mutex_); + controller_plan_ = latest_plan_; + latest_plan_ = temp_plan; + lock.unlock(); + ROS_DEBUG_NAMED("move_base", "pointers swapped!"); + + if (!tc_->setPlan(*controller_plan_)) + { + // ABORT and SHUTDOWN COSTMAPS + ROS_ERROR("Failed to pass global plan to the controller, aborting."); + resetState(); + + // disable the planner thread + lock.lock(); + runPlanner_ = false; + lock.unlock(); + + as_->setAborted(move_base_msgs::MoveBaseResult(), "Failed to pass global plan to the controller."); + return true; + } + + // make sure to reset recovery_index_ since we were able to find a valid plan + if (recovery_trigger_ == PLANNING_R) + recovery_index_ = 0; + } + + // the move_base state machine, handles the control logic for navigation + switch (state_) + { + // if we are in a planning state, then we'll attempt to make a plan + case PLANNING: + { + boost::recursive_mutex::scoped_lock lock(planner_mutex_); + runPlanner_ = true; + planner_cond_.notify_one(); + } + ROS_DEBUG_NAMED("move_base", "Waiting for plan, in the planning state."); + break; + + // if we're controlling, we'll attempt to find valid velocity commands + case CONTROLLING: + ROS_DEBUG_NAMED("move_base", "In controlling state."); + + // check to see if we've reached our goal + if (tc_->isGoalReached()) + { + ROS_DEBUG_NAMED("move_base", "Goal reached!"); + resetState(); + + // disable the planner thread + boost::unique_lock lock(planner_mutex_); + runPlanner_ = false; + lock.unlock(); + clearDirectionalCostmap(); + as_->setSucceeded(move_base_msgs::MoveBaseResult(), "Goal reached."); + return true; + } + + // check for an oscillation condition + if (oscillation_timeout_ > 0.0 && + last_oscillation_reset_ + ros::Duration(oscillation_timeout_) < ros::Time::now()) + { + ROS_ERROR("check for an oscillation condition %f %f", last_oscillation_reset_.toSec(), ros::Time::now().toSec()); + publishZeroVelocity(); + state_ = CLEARING; + recovery_trigger_ = OSCILLATION_R; + } + + { + boost::unique_lock lock(*(controller_costmap_ros_->getCostmap()->getMutex())); + + if (tc_->computeVelocityCommands(cmd_vel)) + { + ROS_DEBUG_NAMED("move_base", "Got a valid command from the local planner: %.3lf, %.3lf, %.3lf", + cmd_vel.linear.x, cmd_vel.linear.y, cmd_vel.angular.z); + // ROS_INFO("Got a valid command from the local planner: %.3lf, %.3lf, %.3lf", + // cmd_vel.linear.x, cmd_vel.linear.y, cmd_vel.angular.z ); + last_valid_control_ = ros::Time::now(); + // make sure that we send the velocity command to the base + vel_pub_.publish(cmd_vel); + if (recovery_trigger_ == CONTROLLING_R) + recovery_index_ = 0; + } + else + { + ROS_DEBUG_NAMED("move_base", "The local planner could not find a valid plan."); + ROS_WARN("The local planner could not find a valid plan."); + ros::Time attempt_end = last_valid_control_ + ros::Duration(controller_patience_); + + // check if we've tried to find a valid control for longer than our time limit + if (ros::Time::now() > attempt_end) + { + // we'll move into our obstacle clearing mode + ROS_ERROR("we'll move into our obstacle clearing mode"); + publishZeroVelocity(); + state_ = CLEARING; + recovery_trigger_ = CONTROLLING_R; + } + else + { + // otherwise, if we can't find a valid control, we'll go back to planning + last_valid_plan_ = ros::Time::now(); + planning_retries_ = 0; + state_ = PLANNING; + ROS_ERROR("otherwise, if we can't find a valid control, we'll go back to planning"); + publishZeroVelocity(); + + // enable the planner thread in case it isn't running on a clock + boost::unique_lock lock(planner_mutex_); + runPlanner_ = true; + planner_cond_.notify_one(); + lock.unlock(); + } + } + } + + break; + + // we'll try to clear out space with any user-provided recovery behaviors + case CLEARING: + ROS_DEBUG_NAMED("move_base", "In clearing/recovery state"); + // we'll invoke whatever recovery behavior we're currently on if they're enabled + if (recovery_behavior_enabled_ && recovery_index_ < recovery_behaviors_.size()) + { + ROS_DEBUG_NAMED("move_base_recovery", "Executing behavior %u of %zu", recovery_index_ + 1, recovery_behaviors_.size()); + + move_base_msgs::RecoveryStatus msg; + msg.pose_stamped = current_position; + msg.current_recovery_number = recovery_index_; + msg.total_number_of_recoveries = recovery_behaviors_.size(); + msg.recovery_behavior_name = recovery_behavior_names_[recovery_index_]; + + recovery_status_pub_.publish(msg); + + recovery_behaviors_[recovery_index_]->runBehavior(); + + // we at least want to give the robot some time to stop oscillating after executing the behavior + last_oscillation_reset_ = ros::Time::now(); + + // we'll check if the recovery behavior actually worked + ROS_DEBUG_NAMED("move_base_recovery", "Going back to planning state"); + last_valid_plan_ = ros::Time::now(); + planning_retries_ = 0; + state_ = PLANNING; + + // update the index of the next recovery behavior that we'll try + recovery_index_++; + } + else + { + ROS_DEBUG_NAMED("move_base_recovery", "All recovery behaviors have failed, locking the planner and disabling it."); + // disable the planner thread + boost::unique_lock lock(planner_mutex_); + runPlanner_ = false; + lock.unlock(); + + ROS_DEBUG_NAMED("move_base_recovery", "Something should abort after this."); + + if (recovery_trigger_ == CONTROLLING_R) + { + ROS_ERROR("Aborting because a valid control could not be found. Even after executing all recovery behaviors"); + as_->setAborted(move_base_msgs::MoveBaseResult(), "Failed to find a valid control. Even after executing recovery behaviors."); + } + else if (recovery_trigger_ == PLANNING_R) + { + ROS_ERROR("Aborting because a valid plan could not be found. Even after executing all recovery behaviors"); + as_->setAborted(move_base_msgs::MoveBaseResult(), "Failed to find a valid plan. Even after executing recovery behaviors."); + } + else if (recovery_trigger_ == OSCILLATION_R) + { + ROS_ERROR("Aborting because the robot appears to be oscillating over and over. Even after executing all recovery behaviors"); + as_->setAborted(move_base_msgs::MoveBaseResult(), "Robot is oscillating. Even after executing recovery behaviors."); + } + resetState(); + return true; + } + break; + default: + ROS_ERROR("This case should never be reached, something is wrong, aborting"); + resetState(); + // disable the planner thread + boost::unique_lock lock(planner_mutex_); + runPlanner_ = false; + lock.unlock(); + as_->setAborted(move_base_msgs::MoveBaseResult(), "Reached a case that should not be hit in move_base. This is a bug, please report it."); + return true; + } + + // we aren't done yet + return false; + } + + bool MoveBase::loadRecoveryBehaviors(ros::NodeHandle node) + { + XmlRpc::XmlRpcValue behavior_list; + if (node.getParam("recovery_behaviors", behavior_list)) + { + if (behavior_list.getType() == XmlRpc::XmlRpcValue::TypeArray) + { + for (int i = 0; i < behavior_list.size(); ++i) + { + if (behavior_list[i].getType() == XmlRpc::XmlRpcValue::TypeStruct) + { + if (behavior_list[i].hasMember("name") && behavior_list[i].hasMember("type")) + { + // check for recovery behaviors with the same name + for (int j = i + 1; j < behavior_list.size(); j++) + { + if (behavior_list[j].getType() == XmlRpc::XmlRpcValue::TypeStruct) + { + if (behavior_list[j].hasMember("name") && behavior_list[j].hasMember("type")) + { + std::string name_i = behavior_list[i]["name"]; + std::string name_j = behavior_list[j]["name"]; + if (name_i == name_j) + { + ROS_ERROR("A recovery behavior with the name %s already exists, this is not allowed. Using the default recovery behaviors instead.", + name_i.c_str()); + return false; + } + } + } + } + } + else + { + ROS_ERROR("Recovery behaviors must have a name and a type and this does not. Using the default recovery behaviors instead."); + return false; + } + } + else + { + ROS_ERROR("Recovery behaviors must be specified as maps, but they are XmlRpcType %d. We'll use the default recovery behaviors instead.", + behavior_list[i].getType()); + return false; + } + } + + // if we've made it to this point, we know that the list is legal so we'll create all the recovery behaviors + for (int i = 0; i < behavior_list.size(); ++i) + { + try + { + // check if a non fully qualified name has potentially been passed in + if (!recovery_loader_.isClassAvailable(behavior_list[i]["type"])) + { + std::vector classes = recovery_loader_.getDeclaredClasses(); + for (unsigned int i = 0; i < classes.size(); ++i) + { + if (behavior_list[i]["type"] == recovery_loader_.getName(classes[i])) + { + // if we've found a match... we'll get the fully qualified name and break out of the loop + ROS_WARN("Recovery behavior specifications should now include the package name. You are using a deprecated API. Please switch from %s to %s in your yaml file.", + std::string(behavior_list[i]["type"]).c_str(), classes[i].c_str()); + behavior_list[i]["type"] = classes[i]; + break; + } + } + } + + boost::shared_ptr behavior(recovery_loader_.createInstance(behavior_list[i]["type"])); + + // shouldn't be possible, but it won't hurt to check + if (behavior.get() == NULL) + { + ROS_ERROR("The ClassLoader returned a null pointer without throwing an exception. This should not happen"); + return false; + } + + // initialize the recovery behavior with its name + behavior->initialize(behavior_list[i]["name"], &tf_, planner_costmap_ros_, controller_costmap_ros_); + recovery_behavior_names_.push_back(behavior_list[i]["name"]); + recovery_behaviors_.push_back(behavior); + } + catch (pluginlib::PluginlibException &ex) + { + ROS_ERROR("Failed to load a plugin. Using default recovery behaviors. Error: %s", ex.what()); + return false; + } + } + } + else + { + ROS_ERROR("The recovery behavior specification must be a list, but is of XmlRpcType %d. We'll use the default recovery behaviors instead.", + behavior_list.getType()); + return false; + } + } + else + { + // if no recovery_behaviors are specified, we'll just load the defaults + return false; + } + + // if we've made it here... we've constructed a recovery behavior list successfully + return true; + } + + // we'll load our default recovery behaviors here + void MoveBase::loadDefaultRecoveryBehaviors() + { + recovery_behaviors_.clear(); + try + { + // we need to set some parameters based on what's been passed in to us to maintain backwards compatibility + ros::NodeHandle n("~"); + n.setParam("conservative_reset/reset_distance", conservative_reset_dist_); + n.setParam("aggressive_reset/reset_distance", circumscribed_radius_ * 4); + + // first, we'll load a recovery behavior to clear the costmap + boost::shared_ptr cons_clear(recovery_loader_.createInstance("clear_costmap_recovery/ClearCostmapRecovery")); + cons_clear->initialize("conservative_reset", &tf_, planner_costmap_ros_, controller_costmap_ros_); + recovery_behavior_names_.push_back("conservative_reset"); + recovery_behaviors_.push_back(cons_clear); + + // next, we'll load a recovery behavior to rotate in place + boost::shared_ptr rotate(recovery_loader_.createInstance("rotate_recovery/RotateRecovery")); + if (clearing_rotation_allowed_) + { + rotate->initialize("rotate_recovery", &tf_, planner_costmap_ros_, controller_costmap_ros_); + recovery_behavior_names_.push_back("rotate_recovery"); + recovery_behaviors_.push_back(rotate); + } + + // next, we'll load a recovery behavior that will do an aggressive reset of the costmap + boost::shared_ptr ags_clear(recovery_loader_.createInstance("clear_costmap_recovery/ClearCostmapRecovery")); + ags_clear->initialize("aggressive_reset", &tf_, planner_costmap_ros_, controller_costmap_ros_); + recovery_behavior_names_.push_back("aggressive_reset"); + recovery_behaviors_.push_back(ags_clear); + + // we'll rotate in-place one more time + if (clearing_rotation_allowed_) + { + recovery_behaviors_.push_back(rotate); + recovery_behavior_names_.push_back("rotate_recovery"); + } + } + catch (pluginlib::PluginlibException &ex) + { + ROS_FATAL("Failed to load a plugin. This should not happen on default recovery behaviors. Error: %s", ex.what()); + } + + return; + } + + void MoveBase::resetState() + { + // Disable the planner thread + boost::unique_lock lock(planner_mutex_); + runPlanner_ = false; + lock.unlock(); + + // Reset statemachine + state_ = PLANNING; + recovery_index_ = 0; + recovery_trigger_ = PLANNING_R; + publishZeroVelocity(); + + // if we shutdown our costmaps when we're deactivated... we'll do that now + if (shutdown_costmaps_) + { + ROS_DEBUG_NAMED("move_base", "Stopping costmaps"); + planner_costmap_ros_->stop(); + controller_costmap_ros_->stop(); + } + } + + bool MoveBase::getRobotPose(geometry_msgs::PoseStamped &global_pose, costmap_2d::Costmap2DROS *costmap) + { + tf2::toMsg(tf2::Transform::getIdentity(), global_pose.pose); + geometry_msgs::PoseStamped robot_pose; + tf2::toMsg(tf2::Transform::getIdentity(), robot_pose.pose); + robot_pose.header.frame_id = robot_base_frame_; + robot_pose.header.stamp = ros::Time(); // latest available + ros::Time current_time = ros::Time::now(); // save time for checking tf delay later + + // get robot pose on the given costmap frame + try + { + tf_.transform(robot_pose, global_pose, costmap->getGlobalFrameID()); + } + catch (tf2::LookupException &ex) + { + ROS_ERROR_THROTTLE(1.0, "No Transform available Error looking up robot pose: %s\n", ex.what()); + return false; + } + catch (tf2::ConnectivityException &ex) + { + ROS_ERROR_THROTTLE(1.0, "Connectivity Error looking up robot pose: %s\n", ex.what()); + return false; + } + catch (tf2::ExtrapolationException &ex) + { + ROS_ERROR_THROTTLE(1.0, "Extrapolation Error looking up robot pose: %s\n", ex.what()); + return false; + } + + // check if global_pose time stamp is within costmap transform tolerance + if (!global_pose.header.stamp.isZero() && + current_time.toSec() - global_pose.header.stamp.toSec() > costmap->getTransformTolerance()) + { + ROS_WARN_THROTTLE(1.0, "Transform timeout for %s. " + "Current time: %.4f, pose stamp: %.4f, tolerance: %.4f", + costmap->getName().c_str(), + current_time.toSec(), global_pose.header.stamp.toSec(), costmap->getTransformTolerance()); + return false; + } + + return true; + } + void MoveBase::clearDirectionalCostmap() + { + try + { + if (directional_costmap_ != nullptr) + { + if(directional_costmap_->isEnabled()) + { + boost::unique_lock lock(*(directional_costmap_->getMutex())); + directional_costmap_->resetMap(); + directional_costmap_->reset(); + boost::unique_lock lock_planner(*(planner_costmap_ros_->getCostmap()->getMutex())); + planner_costmap_ros_->updateMap(); + lock.unlock(); + } + } + } + catch (const std::exception &e) + { + ROS_ERROR_STREAM(e.what() << '\n'); + return; + } + } +}; diff --git a/navigations/move_base/src/move_base_node.cpp b/navigations/move_base/src/move_base_node.cpp new file mode 100755 index 0000000..e1cdbd6 --- /dev/null +++ b/navigations/move_base/src/move_base_node.cpp @@ -0,0 +1,44 @@ +/* + * Copyright (c) 2013, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include + +int main(int argc, char** argv){ + ros::init(argc, argv, "move_base_node"); + tf2_ros::Buffer buffer(ros::Duration(10)); + tf2_ros::TransformListener tf(buffer); + + move_base::MoveBase move_base( buffer ); + + //ros::MultiThreadedSpinner s; + ros::spin(); + + return(0); +} diff --git a/navigations/move_base_flex/.gitignore b/navigations/move_base_flex/.gitignore new file mode 100755 index 0000000..437f3b2 --- /dev/null +++ b/navigations/move_base_flex/.gitignore @@ -0,0 +1,3 @@ +.* +cmake-build-debug +!/.gitignore diff --git a/navigations/move_base_flex/LICENSE b/navigations/move_base_flex/LICENSE new file mode 100755 index 0000000..2ab0f76 --- /dev/null +++ b/navigations/move_base_flex/LICENSE @@ -0,0 +1,29 @@ +BSD 3-Clause License + +Copyright (c) 2018, Magazino GmbH, Sebastian Pütz, Jorge Santos Simón +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name of the copyright holder nor the names of its + contributors may be used to endorse or promote products derived from + this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. diff --git a/navigations/move_base_flex/README.md b/navigations/move_base_flex/README.md new file mode 100755 index 0000000..c008297 --- /dev/null +++ b/navigations/move_base_flex/README.md @@ -0,0 +1,42 @@ +# Move Base Flex: A Highly Flexible Navigation Framework: + +This repository contains Move Base Flex (MBF), a backwards-compatible replacement for move_base. MBF can use existing plugins for move_base, and provides an enhanced version of the same ROS interface. It exposes action servers for planning, controlling and recovering, providing detailed information of the current state and the plugin's feedback. An external executive logic can use MBF and its actions to perform smart and flexible navigation strategies. For example, at [Magazino](https://www.magazino.eu/?lang=en) we have successfully deployed MBF at customer facilities to control TORU robots in highly dynamical environments. Furthermore, MBF enables the use of other map representations, e.g. meshes. The core features are: + +* Fully backwards-compatible with current ROS navigation. +* Actions for the submodules planning, controlling and recovering, and services to query the costmaps are provided. This interface allows external executives, e.g. SMACH, or Behavior Trees, to run highly flexible and complex navigation strategies. +* Comprehensive result and feedback information on all actions, including error codes and messages from the loaded plugins. For users still relying on a unique navigation interface, we have extended move_base action with detailed result and feedback information (though we still provide the current one). +* Separation between an abstract navigation framework and concrete implementations, allowing faster development of new applications, e.g. 3D navigation. +* Load multiple planners and controllers, selectable at runtime by setting one of the loaded plugin names in the action goal. +* Concurrency: Parallel planning, recovering, controlling by selecting different concurrency slots when defining the action goal. Only different plugins instances can run in parallel. + +Please see also the [Move Base Flex Documentation and Tutorials](https://wiki.ros.org/move_base_flex) in the ROS wiki. + +## Concepts & Architecture + +We have created Move Base Flex for a larger target group besides the standard developers and users of move_base and 2D navigation based on costmaps, as well as addressed move_base's limitations. Since robot navigation can be separated into planning and controlling in many cases, even for outdoor scenarios without the benefits of flat terrain, we designed MBF based on abstract planner-, controller- and recovery behavior-execution classes. To accomplish this goal, we created abstract base classes for the nav core BaseLocalPlanner, BaseGlobalPlanner and RecoveryBehavior plugin interfaces, extending the API to provide a richer and more expressive interface without breaking the current move_base plugin API. The new abstract interfaces allow plugins to return valuable information in each execution cycle, e.g. why a valid plan or a velocity command could not be computed. This information is then passed to the external executive logic through MBF planning, navigation or recovering actions’ feedback and result. The planner, controller and recovery behavior execution is implemented in the abstract execution classes without binding the software implementation to 2D costmaps. In our framework, MoveBase is just a particular implementation of a navigation system: its execution classes implement the abstract ones, bind the system to the costmaps. Thereby, the system can easily be used for other approaches, e.g. navigation on meshes or 3D occupancy grid maps. However, we provide a SimpleNavigationServer class without a binding to costmaps. + +MBF architecture: +![MBF architecture](doc/images/move_base_flex.png) + +## Future Work +MBF is an ongoing project. Some of the improvements that we have planned for the near future are: + +* Release MBF Mesh Navigation, see [mesh_navigation](https://github.com/uos/mesh_navigation). +* Auto select the active controller when having concurrently running controllers +* Add Ackermann steering API +* Multi Goal API + Action +* Add new navigation server and core packages using [grid_map](https://wiki.ros.org/grid_map). +* Constraints-based goal (see issue https://github.com/magazino/move_base_flex/issues/8) + +But, of course you are welcome to propose new fancy features and help make them a reality! Pull Requests are always welcome! + +## Build Status + +| | Master | Kinetic | Lunar | Melodic | Noetic | +|--------|--------|---------|-------|---------|--------| +| Travis | [![Build Status](https://api.travis-ci.com/magazino/move_base_flex.svg?branch=master)](https://travis-ci.com/magazino/move_base_flex) | [![Build Status](https://api.travis-ci.com/magazino/move_base_flex.svg?branch=kinetic)](https://travis-ci.com/magazino/move_base_flex) | [![Build Status](https://api.travis-ci.com/magazino/move_base_flex.svg?branch=lunar)](https://travis-ci.com/magazino/move_base_flex) | [![Build Status](https://api.travis-ci.com/magazino/move_base_flex.svg?branch=melodic)](https://travis-ci.com/magazino/move_base_flex) | [![Build Status](https://api.travis-ci.com/magazino/move_base_flex.svg?branch=noetic)](https://travis-ci.com/magazino/move_base_flex) | +| Binary Deb | | [![Build Status](http://build.ros.org/buildStatus/icon?job=Kbin_uX64__move_base_flex__ubuntu_xenial_amd64__binary)](http://build.ros.org/job/Kbin_uX64__move_base_flex__ubuntu_xenial_amd64__binary/) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Lbin_uX64__move_base_flex__ubuntu_xenial_amd64__binary)](http://build.ros.org/job/Lbin_uX64__move_base_flex__ubuntu_xenial_amd64__binary/) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Mbin_uB64__move_base_flex__ubuntu_bionic_amd64__binary)](http://build.ros.org/job/Mbin_uB64__move_base_flex__ubuntu_bionic_amd64__binary) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Nbin_uF64__move_base_flex__ubuntu_focal_amd64__binary)](http://build.ros.org/job/Nbin_uF64__move_base_flex__ubuntu_focal_amd64__binary) | +| Source Deb | | [![Build Status](http://build.ros.org/buildStatus/icon?job=Ksrc_uX__move_base_flex__ubuntu_xenial__source)](http://build.ros.org/job/Ksrc_uX__move_base_flex__ubuntu_xenial__source/) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Lsrc_uX__move_base_flex__ubuntu_xenial__source)](http://build.ros.org/job/Lsrc_uX__move_base_flex__ubuntu_xenial__source/) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Msrc_uB__move_base_flex__ubuntu_bionic__source)](http://build.ros.org/job/Msrc_uB__move_base_flex__ubuntu_bionic__source/) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Nsrc_uF__move_base_flex__ubuntu_focal__source)](http://build.ros.org/job/Nsrc_uF__move_base_flex__ubuntu_focal__source/) | +| Develop | | [![Build Status](http://build.ros.org/buildStatus/icon?job=Kdev__move_base_flex__ubuntu_xenial_amd64)](http://build.ros.org/job/Kdev__move_base_flex__ubuntu_xenial_amd64) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Ldev__move_base_flex__ubuntu_xenial_amd64)](http://build.ros.org/job/Ldev__move_base_flex__ubuntu_xenial_amd64) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Mdev__move_base_flex__ubuntu_bionic_amd64)](http://build.ros.org/job/Mdev__move_base_flex__ubuntu_bionic_amd64) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Ndev__move_base_flex__ubuntu_focal_amd64)](http://build.ros.org/job/Ndev__move_base_flex__ubuntu_focal_amd64) | +| Documentation | | [![Build Status](http://build.ros.org/buildStatus/icon?job=Kdoc__move_base_flex__ubuntu_xenial_amd64)](http://build.ros.org/job/Kdoc__move_base_flex__ubuntu_xenial_amd64) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Ldoc__move_base_flex__ubuntu_xenial_amd64)](http://build.ros.org/job/Ldoc__move_base_flex__ubuntu_xenial_amd64) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Mdoc__move_base_flex__ubuntu_bionic_amd64)](http://build.ros.org/job/Mdoc__move_base_flex__ubuntu_bionic_amd64)| [![Build Status](http://build.ros.org/buildStatus/icon?job=Ndoc__move_base_flex__ubuntu_focal_amd64)](http://build.ros.org/job/Ndoc__move_base_flex__ubuntu_focal_amd64)| + diff --git a/navigations/move_base_flex/doc/images/mbf_gridmap_nav.png b/navigations/move_base_flex/doc/images/mbf_gridmap_nav.png new file mode 100755 index 0000000..44ca269 Binary files /dev/null and b/navigations/move_base_flex/doc/images/mbf_gridmap_nav.png differ diff --git a/navigations/move_base_flex/doc/images/move_base_flex.pdf b/navigations/move_base_flex/doc/images/move_base_flex.pdf new file mode 100755 index 0000000..8a0f723 Binary files /dev/null and b/navigations/move_base_flex/doc/images/move_base_flex.pdf differ diff --git a/navigations/move_base_flex/doc/images/move_base_flex.png b/navigations/move_base_flex/doc/images/move_base_flex.png new file mode 100755 index 0000000..b08699c Binary files /dev/null and b/navigations/move_base_flex/doc/images/move_base_flex.png differ diff --git a/navigations/move_base_flex/doc/images/move_base_flex.svg b/navigations/move_base_flex/doc/images/move_base_flex.svg new file mode 100755 index 0000000..fba06f9 --- /dev/null +++ b/navigations/move_base_flex/doc/images/move_base_flex.svg @@ -0,0 +1,13452 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Service /make_plan nav_msgs/GetPlan + Legacy API Support + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Action /move_base move_base_msgs/MoveBase + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Topic /move_base_simple/goal geometry_msgs/PoseStamped + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + AbstractLocalPlanner + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + AbstractGlobalPlanner + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + AbstractRecoveryBehaviors + Plugin Interface + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +AbstractPlannerExecution + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +AbstractControllerExecution + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +AbstractRecoveryExecution + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +Move BasePlannerExecution + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +Move BaseControllerExecution + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +Move BaseRecoveryExecution + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Move BaseNavigationServer + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +TransformListener + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + AbstractNavigationServer + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +LocalCostmap + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +Global Costmap + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +Abstract Move Base Flex Level + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +thread + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +plugin + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +abstract class + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +inheritance + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +property + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +class + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +Action/recoverymbf_msgs/Recovery + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +Action/exe_pathmbf_msgs/ExePath + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +Action/get_pathmbf_msgs/GetPath + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +Service/check_pose_costmbf_msgs/CheckPose + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +Service/clear_costmapsstd_srvs/empty + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +Action/move_basembf_msgs/MoveBase +Action & Service Interface + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +message + +Move Base Implementation Level + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +© Sebastian Pütz <spuetz@uni-osnabrueck.de> (CC BY-SA 4.0) + diff --git a/navigations/move_base_flex/mbf_abstract_core/CHANGELOG.rst b/navigations/move_base_flex/mbf_abstract_core/CHANGELOG.rst new file mode 100755 index 0000000..281122d --- /dev/null +++ b/navigations/move_base_flex/mbf_abstract_core/CHANGELOG.rst @@ -0,0 +1,36 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package mbf_abstract_core +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +0.3.2 (2020-05-25) +------------------ + +0.3.1 (2020-04-07) +------------------ + +0.3.0 (2020-03-31) +------------------ +* unify license declaration to BSD-3 + +0.2.5 (2019-10-11) +------------------ + +0.2.4 (2019-06-16) +------------------ + +0.2.3 (2018-11-14) +------------------ + +0.2.2 (2018-10-10) +------------------ + +0.2.1 (2018-10-03) +------------------ + +0.2.0 (2018-09-11) +------------------ +* Update copyright and 3-clause-BSD license + +0.1.0 (2018-03-22) +------------------ +* First release of move_base_flex for kinetic and lunar diff --git a/navigations/move_base_flex/mbf_abstract_core/CMakeLists.txt b/navigations/move_base_flex/mbf_abstract_core/CMakeLists.txt new file mode 100755 index 0000000..a0165b6 --- /dev/null +++ b/navigations/move_base_flex/mbf_abstract_core/CMakeLists.txt @@ -0,0 +1,24 @@ +cmake_minimum_required(VERSION 2.8.3) +project(mbf_abstract_core) + +find_package(catkin REQUIRED + COMPONENTS + std_msgs + geometry_msgs + + ) + +catkin_package( + INCLUDE_DIRS + include + CATKIN_DEPENDS + std_msgs + geometry_msgs +) + + +## Install project namespaced headers +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} + FILES_MATCHING PATTERN "*.h" + PATTERN ".svn" EXCLUDE) diff --git a/navigations/move_base_flex/mbf_abstract_core/README.md b/navigations/move_base_flex/mbf_abstract_core/README.md new file mode 100755 index 0000000..e00872f --- /dev/null +++ b/navigations/move_base_flex/mbf_abstract_core/README.md @@ -0,0 +1,5 @@ +# Move Base Flex Abstract Core {#mainpage} + +The [mbf_abstract_core](wiki.ros.org/mbf_abstract_core) package of Move Base Flex (MBF) contains the abstract interfaces for planning controlling and recovering. Derived packages of the [mbf_abstract_nav](wiki.ros.org/mbf_abstract_nav) should use derived interfaces of the [mbf_abstract_core](wiki.ros.org/mbf_abstract_core) which then, for example, contain a method for initialization of the plugin, e.g. by handing over a pointer to the map representation of choice. + +The plugins which are loaded by Move Base Flex (a derived package of the mbf_abstract_nav) have to implement derived interfaces of the interfaces which are defined in this package. The mbf_abstract_core::AbstractPlanner provides an interface for a planner plugin to plan global paths. The mbf_abstract_core::AbstractController provides an interface for a controller plugin to control and move a robot. The mbf_abstract_core::AbstractRecovery provides an interface for a recovery plugin to recover the robot in deadlocked situations. diff --git a/navigations/move_base_flex/mbf_abstract_core/include/mbf_abstract_core/abstract_controller.h b/navigations/move_base_flex/mbf_abstract_core/include/mbf_abstract_core/abstract_controller.h new file mode 100755 index 0000000..2c5713f --- /dev/null +++ b/navigations/move_base_flex/mbf_abstract_core/include/mbf_abstract_core/abstract_controller.h @@ -0,0 +1,123 @@ +/* + * Copyright 2018, Sebastian Pütz + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * abstract_planner.h + * + * author: Sebastian Pütz + * + */ + +#ifndef MBF_ABSTRACT_CORE__ABSTRACT_CONTROLLER_H_ +#define MBF_ABSTRACT_CORE__ABSTRACT_CONTROLLER_H_ + +#include +#include +#include +#include +#include +#include + +namespace mbf_abstract_core{ + + class AbstractController{ + + public: + + typedef boost::shared_ptr< ::mbf_abstract_core::AbstractController > Ptr; + + /** + * @brief Destructor + */ + virtual ~AbstractController(){}; + + /** + * @brief Given the current position, orientation, and velocity of the robot, + * compute velocity commands to send to the base. + * @param pose The current pose of the robot. + * @param velocity The current velocity of the robot. + * @param cmd_vel Will be filled with the velocity command to be passed to the robot base. + * @param message Optional more detailed outcome as a string + * @return Result code as described on ExePath action result: + * SUCCESS = 0 + * 1..9 are reserved as plugin specific non-error results + * FAILURE = 100 Unspecified failure, only used for old, non-mfb_core based plugins + * CANCELED = 101 + * NO_VALID_CMD = 102 + * PAT_EXCEEDED = 103 + * COLLISION = 104 + * OSCILLATION = 105 + * ROBOT_STUCK = 106 + * MISSED_GOAL = 107 + * MISSED_PATH = 108 + * BLOCKED_PATH = 109 + * INVALID_PATH = 110 + * TF_ERROR = 111 + * NOT_INITIALIZED = 112 + * INVALID_PLUGIN = 113 + * INTERNAL_ERROR = 114 + * 121..149 are reserved as plugin specific errors + */ + virtual uint32_t computeVelocityCommands(const geometry_msgs::PoseStamped& pose, + const geometry_msgs::TwistStamped& velocity, + geometry_msgs::TwistStamped &cmd_vel, + std::string &message) = 0; + + /** + * @brief Check if the goal pose has been achieved by the local planner + * @param angle_tolerance The angle tolerance in which the current pose will be partly accepted as reached goal + * @param dist_tolerance The distance tolerance in which the current pose will be partly accepted as reached goal + * @return True if achieved, false otherwise + */ + virtual bool isGoalReached(double dist_tolerance, double angle_tolerance) = 0; + + /** + * @brief Set the plan that the local planner is following + * @param plan The plan to pass to the local planner + * @return True if the plan was updated successfully, false otherwise + */ + virtual bool setPlan(const std::vector &plan) = 0; + + /** + * @brief Requests the planner to cancel, e.g. if it takes too much time. + * @return True if a cancel has been successfully requested, false if not implemented. + */ + virtual bool cancel() = 0; + + protected: + /** + * @brief Constructor + */ + AbstractController(){}; + }; +} /* namespace mbf_abstract_core */ + +#endif /* MBF_ABSTRACT_CORE__ABSTRACT_CONTROLLER_H_ */ diff --git a/navigations/move_base_flex/mbf_abstract_core/include/mbf_abstract_core/abstract_planner.h b/navigations/move_base_flex/mbf_abstract_core/include/mbf_abstract_core/abstract_planner.h new file mode 100755 index 0000000..a338f4f --- /dev/null +++ b/navigations/move_base_flex/mbf_abstract_core/include/mbf_abstract_core/abstract_planner.h @@ -0,0 +1,106 @@ +/* + * Copyright 2018, Sebastian Pütz + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * abstract_planner.h + * + * author: Sebastian Pütz + * + */ + +#ifndef MBF_ABSTRACT_CORE__ABSTRACT_PLANNER_H_ +#define MBF_ABSTRACT_CORE__ABSTRACT_PLANNER_H_ + +#include +#include +#include +#include +#include + +namespace mbf_abstract_core +{ + + class AbstractPlanner{ + + public: + typedef boost::shared_ptr< ::mbf_abstract_core::AbstractPlanner > Ptr; + + /** + * @brief Destructor + */ + virtual ~AbstractPlanner(){}; + + /** + * @brief Given a goal pose in the world, compute a plan. + * The final pose of the path must be within tolerance range (position and orientation) for this method + * to return a success outcome. + * @param start The start pose + * @param goal The goal pose + * @param dist_tolerance Tolerance in meters to the goal position + * @param angle_tolerance Tolerance in radians to the goal orientation + * @param plan The plan... filled by the planner + * @param cost The cost for the the plan + * @param message Optional more detailed outcome as a string + * @return Result code as described on GetPath action result: + * SUCCESS = 0 + * 1..9 are reserved as plugin specific non-error results + * FAILURE = 50 # Unspecified failure, only used for old, non-mfb_core based plugins + * CANCELED = 51 + * INVALID_START = 52 + * INVALID_GOAL = 53 + * NO_PATH_FOUND = 54 + * PAT_EXCEEDED = 55 + * EMPTY_PATH = 56 + * TF_ERROR = 57 + * NOT_INITIALIZED = 58 + * INVALID_PLUGIN = 59 + * INTERNAL_ERROR = 60 + * 71..99 are reserved as plugin specific errors + */ + virtual uint32_t makePlan(const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal, + double dist_tolerance, double angle_tolerance, + std::vector &plan, double &cost, std::string &message) = 0; + + /** + * @brief Requests the planner to cancel, e.g. if it takes too much time. + * @return True if a cancel has been successfully requested, false if not implemented. + */ + virtual bool cancel() = 0; + + protected: + /** + * @brief Constructor + */ + AbstractPlanner(){}; + }; +} /* namespace mbf_abstract_core */ + +#endif /* MBF_ABSTRACT_CORE__ABSTRACT_PLANNER_H_ */ diff --git a/navigations/move_base_flex/mbf_abstract_core/include/mbf_abstract_core/abstract_recovery.h b/navigations/move_base_flex/mbf_abstract_core/include/mbf_abstract_core/abstract_recovery.h new file mode 100755 index 0000000..8dd05eb --- /dev/null +++ b/navigations/move_base_flex/mbf_abstract_core/include/mbf_abstract_core/abstract_recovery.h @@ -0,0 +1,83 @@ +/* + * Copyright 2018, Sebastian Pütz + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * abstract_recovery.h + * + * author: Sebastian Pütz + * + */ + +#ifndef MBF_ABSTRACT_CORE__ABSTRACT_RECOVERY_H_ +#define MBF_ABSTRACT_CORE__ABSTRACT_RECOVERY_H_ + +#include +#include +#include + +namespace mbf_abstract_core { + /** + * @class AbstractRecovery + * @brief Provides an interface for recovery behaviors used in navigation. + * All recovery behaviors written as plugins for the navigation stack must adhere to this interface. + */ + class AbstractRecovery{ + public: + + typedef boost::shared_ptr< ::mbf_abstract_core::AbstractRecovery > Ptr; + + /** + * @brief Runs the AbstractRecovery + * @param message The recovery behavior could set, the message should correspond to the return value + * @return An outcome which will be hand over to the action result. + */ + virtual uint32_t runBehavior(std::string& message) = 0; + + /** + * @brief Virtual destructor for the interface + */ + virtual ~AbstractRecovery(){} + + /** + * @brief Requests the recovery behavior to cancel, e.g. if it takes too much time. + * @return True if a cancel has been successfully requested, false if not implemented. + */ + virtual bool cancel() = 0; + + protected: + /** + * @brief Constructor + */ + AbstractRecovery(){}; + }; +}; /* namespace mbf_abstract_core */ + +#endif /* MBF_ABSTRACT_CORE__ABSTRACT_RECOVERY_H_ */ diff --git a/navigations/move_base_flex/mbf_abstract_core/package.xml b/navigations/move_base_flex/mbf_abstract_core/package.xml new file mode 100755 index 0000000..b76cdd6 --- /dev/null +++ b/navigations/move_base_flex/mbf_abstract_core/package.xml @@ -0,0 +1,22 @@ + + + + mbf_abstract_core + 0.3.2 + + This package provides common interfaces for navigation specific robot actions. It contains the AbstractPlanner, AbstractController and AbstractRecovery plugin interfaces. This interfaces have to be implemented by the plugins to make the plugin available for Move Base Flex. The abstract classes provides a meaningful interface enabling the planners, controllers and recovery behaviors to return information, e.g. why something went wrong. Derivided interfaces can, for example, provide methods to initialize the planner, controller or recovery with map representations like costmap_2d, grid_map or other representations. + + http://wiki.ros.org/mbf_abstract_core + Sebastian Pütz + Jorge Santos + Sebastian Pütz + Jorge Santos + BSD-3 + catkin + geometry_msgs + std_msgs + + + + + diff --git a/navigations/move_base_flex/mbf_abstract_core/rosdoc.yaml b/navigations/move_base_flex/mbf_abstract_core/rosdoc.yaml new file mode 100755 index 0000000..cb8cf98 --- /dev/null +++ b/navigations/move_base_flex/mbf_abstract_core/rosdoc.yaml @@ -0,0 +1,4 @@ + - builder: doxygen + name: Move Base Flex + homepage: http://wiki.ros.org/move_base_flex + file_patterns: '*.c *.cpp *.h *.cc *.hh *.py *.md *.rst' diff --git a/navigations/move_base_flex/mbf_abstract_nav/CHANGELOG.rst b/navigations/move_base_flex/mbf_abstract_nav/CHANGELOG.rst new file mode 100755 index 0000000..23ce1a3 --- /dev/null +++ b/navigations/move_base_flex/mbf_abstract_nav/CHANGELOG.rst @@ -0,0 +1,82 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package mbf_abstract_nav +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +0.3.2 (2020-05-25) +------------------ +* Avoid duplicated warn logging output when we cannot cancel a plugin +* Remove unused methods and attributes from AbstractNavigationServer, which are already present at other places +* Reuse execution slots; cleanup only at destruction +* Enable different goal tolerance values for each action + +0.3.1 (2020-04-07) +------------------ + +0.3.0 (2020-03-31) +------------------ +* Clean up patience exceeded method +* Add last valid cmd time as class variable +* Add started state and improve output messages +* Unify license declaration to BSD-3 +* Add parameter force_stop_on_cancel to send a zero-speed command on cancelation (default: true) +* remove explicit boost-exception dependency, Boost >= 1.69 provides exception by default. +* Allow the user time-consuming cancel implementations +* Rename abstract_action.h as abstract_action_base.hpp +* Remane robot_Information.cpp as robot_information.cpp +* Unify headers definitions and namespace intentation +* Add parameter to actively stop once the goal is reached +* Exit immediately from action done callbacks when action_state is CANCELED + +0.2.5 (2019-10-11) +------------------ +* Update goal pose on replanning, so the feedback remains consistent +* Fix: Reset oscillation timer after executing a recovery behavior +* Remove debug log messages +* Do not pass boost functions to abstract server to (de)activate costmaps. + Run instead abstract methods (possibly) overridden in the costmap server, + all costmap-related handling refactored to a new CostmapWrapper class +* On controller execution, check that local costmap is current +* On move_base action, use MoveBaseResult constant to fill outcome in case of oscilation + +0.2.4 (2019-06-16) +------------------ +* Reduce log verbosity by combining lines and using more DEBUG +* Concurrency container refactoring +* Prevent LOST goals when replanning +* Set as canceled, when goals are preempted by a new plan +* move setAccepted to abstract action +* moved listener notification down after setVelocity +* fix: Correctly fill in the ExePathResult fields +* Fix controller_patience when controller_max_retries is -1 +* Change current_twist for last_cmd_vel on exe_path/feedback +* Replace recursive mutexes with normal ones when not needed +* Give feedback with outcome and message for success and error cases from the plugin. + +0.2.3 (2018-11-14) +------------------ +* Do not publish path from MBF +* Single publisher for controller execution objects +* Ignore max_retries if value is negative and patience if 0 +* Avoid annoying INFO log msg on recovery + +0.2.2 (2018-10-10) +------------------ +* Add outcome and message to the action's feedback in ExePath and MoveBase + +0.2.1 (2018-10-03) +------------------ +* Fix memory leak +* Fix uninitialized value for cost +* Make MBF melodic and indigo compatible +* Fix GoalHandle references bug in callbacks + +0.2.0 (2018-09-11) +------------------ +* Update copyright and 3-clause-BSD license +* Concurrency for planners, controllers and recovery behaviors +* New class structure, allowing multiple executoin instances +* Fixes minor bugs + +0.1.0 (2018-03-22) +------------------ +* First release of move_base_flex for kinetic and lunar diff --git a/navigations/move_base_flex/mbf_abstract_nav/CMakeLists.txt b/navigations/move_base_flex/mbf_abstract_nav/CMakeLists.txt new file mode 100755 index 0000000..8dcb99b --- /dev/null +++ b/navigations/move_base_flex/mbf_abstract_nav/CMakeLists.txt @@ -0,0 +1,89 @@ +cmake_minimum_required(VERSION 2.8.3) +project(mbf_abstract_nav) + +find_package(catkin REQUIRED + COMPONENTS + actionlib + actionlib_msgs + dynamic_reconfigure + geometry_msgs + mbf_msgs + mbf_abstract_core + mbf_utility + nav_msgs + roscpp + std_msgs + std_srvs + tf + xmlrpcpp + ) + +find_package(Boost COMPONENTS thread chrono REQUIRED) + +# dynamic reconfigure: we provide the abstract configuration common to all MBF-based navigation +# frameworks in a python module, so it can easily be included in particular navigation flavours +catkin_python_setup() + +generate_dynamic_reconfigure_options( + cfg/MoveBaseFlex.cfg +) + +set(MBF_ABSTRACT_SERVER_LIB mbf_abstract_server) + +catkin_package( + INCLUDE_DIRS include + LIBRARIES ${MBF_ABSTRACT_SERVER_LIB} + CATKIN_DEPENDS + actionlib + actionlib_msgs + dynamic_reconfigure + geometry_msgs + mbf_msgs + mbf_abstract_core + mbf_utility + nav_msgs + roscpp + std_msgs + std_srvs + tf + xmlrpcpp + DEPENDS Boost +) + + +include_directories( + include + ${catkin_INCLUDE_DIRS} + ${Boost_INCLUDE_DIRS} +) + +add_library(${MBF_ABSTRACT_SERVER_LIB} + src/controller_action.cpp + src/planner_action.cpp + src/recovery_action.cpp + src/move_base_action.cpp + src/abstract_execution_base.cpp + src/abstract_navigation_server.cpp + src/abstract_planner_execution.cpp + src/abstract_controller_execution.cpp + src/abstract_recovery_execution.cpp +) + +add_dependencies(${MBF_ABSTRACT_SERVER_LIB} ${PROJECT_NAME}_gencfg) +add_dependencies(${MBF_ABSTRACT_SERVER_LIB} ${catkin_EXPORTED_TARGETS}) +target_link_libraries(${MBF_ABSTRACT_SERVER_LIB} + ${catkin_LIBRARIES} + ${Boost_LIBRARIES} +) + +install(TARGETS + ${MBF_ABSTRACT_SERVER_LIB} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) + +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} +) + diff --git a/navigations/move_base_flex/mbf_abstract_nav/README.md b/navigations/move_base_flex/mbf_abstract_nav/README.md new file mode 100755 index 0000000..d89d1b1 --- /dev/null +++ b/navigations/move_base_flex/mbf_abstract_nav/README.md @@ -0,0 +1,5 @@ +# Move Base Flex Abstract Navigation Server {#mainpage} + +The mbf_abstract_nav package contains the abstract navigation server implementation of Move Base Flex (MBF). The abstract navigation server is not bound to any map representation. It provides the Actions for planning, controlling and recovering. At the time of start MBF loads all defined plugins. Therefor, it loads all plugins which are defined in the lists *planners*, *controllers* and *recovery_behaviors*. Each list holds a pair of a *name* and a *type*. The *type* defines which kind of plugin to load. The *name* defines under which name the plugin should be callable by the actions. + +![mbf_abstract_nav sketch](doc/images/mbf_abstract_nav_s.png) \ No newline at end of file diff --git a/navigations/move_base_flex/mbf_abstract_nav/cfg/MoveBaseFlex.cfg b/navigations/move_base_flex/mbf_abstract_nav/cfg/MoveBaseFlex.cfg new file mode 100755 index 0000000..9f0e9d5 --- /dev/null +++ b/navigations/move_base_flex/mbf_abstract_nav/cfg/MoveBaseFlex.cfg @@ -0,0 +1,13 @@ +#!/usr/bin/env python + +PACKAGE = 'mbf_abstract_nav' + +from mbf_abstract_nav import add_mbf_abstract_nav_params +from dynamic_reconfigure.parameter_generator_catkin import ParameterGenerator, str_t, double_t, bool_t, int_t + +gen = ParameterGenerator() + +add_mbf_abstract_nav_params(gen) + +gen.add("restore_defaults", bool_t, 0, "Restore to the original configuration", False) +exit(gen.generate(PACKAGE, "move_base_flex_node", "MoveBaseFlex")) diff --git a/navigations/move_base_flex/mbf_abstract_nav/doc/images/mbf_abstract_nav.png b/navigations/move_base_flex/mbf_abstract_nav/doc/images/mbf_abstract_nav.png new file mode 100755 index 0000000..55a938f Binary files /dev/null and b/navigations/move_base_flex/mbf_abstract_nav/doc/images/mbf_abstract_nav.png differ diff --git a/navigations/move_base_flex/mbf_abstract_nav/doc/images/mbf_abstract_nav_s.png b/navigations/move_base_flex/mbf_abstract_nav/doc/images/mbf_abstract_nav_s.png new file mode 100755 index 0000000..6aa7ba5 Binary files /dev/null and b/navigations/move_base_flex/mbf_abstract_nav/doc/images/mbf_abstract_nav_s.png differ diff --git a/navigations/move_base_flex/mbf_abstract_nav/include/mbf_abstract_nav/abstract_action_base.hpp b/navigations/move_base_flex/mbf_abstract_nav/include/mbf_abstract_nav/abstract_action_base.hpp new file mode 100755 index 0000000..ded2d2f --- /dev/null +++ b/navigations/move_base_flex/mbf_abstract_nav/include/mbf_abstract_nav/abstract_action_base.hpp @@ -0,0 +1,185 @@ +/* + * Copyright 2018, Sebastian Pütz + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * abstract_action.h + * + * author: Sebastian Pütz + * + */ + +#ifndef MBF_ABSTRACT_NAV__ABSTRACT_ACTION_BASE_H_ +#define MBF_ABSTRACT_NAV__ABSTRACT_ACTION_BASE_H_ + +#include +#include + +#include "mbf_abstract_nav/MoveBaseFlexConfig.h" + +namespace mbf_abstract_nav +{ + +template +class AbstractActionBase +{ + public: + typedef boost::shared_ptr Ptr; + typedef typename actionlib::ActionServer::GoalHandle GoalHandle; + typedef boost::function RunMethod; + typedef struct{ + typename Execution::Ptr execution; + boost::thread* thread_ptr = NULL; + GoalHandle goal_handle; + bool in_use = false; + } ConcurrencySlot; + + + AbstractActionBase( + const std::string &name, + const mbf_utility::RobotInformation &robot_info, + const RunMethod run_method + ) : name_(name), robot_info_(robot_info), run_(run_method){} + + virtual ~AbstractActionBase() + { + // cleanup threads used on executions + boost::lock_guard guard(slot_map_mtx_); + typename std::map::iterator slot_it = concurrency_slots_.begin(); + for (; slot_it != concurrency_slots_.end(); ++slot_it) + { + threads_.remove_thread(slot_it->second.thread_ptr); + delete slot_it->second.thread_ptr; + } + } + + virtual void start( + GoalHandle &goal_handle, + typename Execution::Ptr execution_ptr + ) + { + uint8_t slot = goal_handle.getGoal()->concurrency_slot; + + if(goal_handle.getGoalStatus().status == actionlib_msgs::GoalStatus::RECALLING) + { + goal_handle.setCanceled(); + } + else + { + boost::lock_guard guard(slot_map_mtx_); + typename std::map::iterator slot_it = concurrency_slots_.find(slot); + if (slot_it != concurrency_slots_.end() && slot_it->second.in_use) { + // if there is already a plugin running on the same slot, cancel it + slot_it->second.execution->cancel(); + + if (slot_it->second.thread_ptr->joinable()) { + slot_it->second.thread_ptr->join(); + } + } + + // fill concurrency slot with the new goal handle, execution, and working thread + concurrency_slots_[slot].in_use = true; + concurrency_slots_[slot].goal_handle = goal_handle; + concurrency_slots_[slot].goal_handle.setAccepted(); + concurrency_slots_[slot].execution = execution_ptr; + if (concurrency_slots_[slot].thread_ptr) + { + // cleanup previous execution; otherwise we will leak threads + threads_.remove_thread(concurrency_slots_[slot].thread_ptr); + delete concurrency_slots_[slot].thread_ptr; + } + concurrency_slots_[slot].thread_ptr = + threads_.create_thread(boost::bind(&AbstractActionBase::run, this, boost::ref(concurrency_slots_[slot]))); + } + } + + virtual void cancel(GoalHandle &goal_handle) + { + uint8_t slot = goal_handle.getGoal()->concurrency_slot; + + boost::lock_guard guard(slot_map_mtx_); + typename std::map::iterator slot_it = concurrency_slots_.find(slot); + if (slot_it != concurrency_slots_.end()) + { + concurrency_slots_[slot].execution->cancel(); + } + } + + virtual void run(ConcurrencySlot &slot) + { + slot.execution->preRun(); + run_(slot.goal_handle, *slot.execution); + ROS_DEBUG_STREAM_NAMED(name_, "Finished action \"" << name_ << "\" run method, waiting for execution thread to finish."); + slot.execution->join(); + ROS_DEBUG_STREAM_NAMED(name_, "Execution completed with goal status " + << (int)slot.goal_handle.getGoalStatus().status << ": "<< slot.goal_handle.getGoalStatus().text); + slot.execution->postRun(); + slot.in_use = false; + } + + virtual void reconfigureAll( + mbf_abstract_nav::MoveBaseFlexConfig &config, uint32_t level) + { + boost::lock_guard guard(slot_map_mtx_); + + typename std::map::iterator iter; + for(iter = concurrency_slots_.begin(); iter != concurrency_slots_.end(); ++iter) + { + iter->second.execution->reconfigure(config); + } + } + + virtual void cancelAll() + { + ROS_INFO_STREAM_NAMED(name_, "Cancel all goals for \"" << name_ << "\"."); + boost::lock_guard guard(slot_map_mtx_); + typename std::map::iterator iter; + for(iter = concurrency_slots_.begin(); iter != concurrency_slots_.end(); ++iter) + { + iter->second.execution->cancel(); + } + threads_.join_all(); + } + +protected: + const std::string &name_; + const mbf_utility::RobotInformation &robot_info_; + + RunMethod run_; + boost::thread_group threads_; + std::map concurrency_slots_; + + boost::mutex slot_map_mtx_; + +}; + +} + +#endif /* MBF_ABSTRACT_NAV__ABSTRACT_ACTION_BASE_H_ */ diff --git a/navigations/move_base_flex/mbf_abstract_nav/include/mbf_abstract_nav/abstract_controller_execution.h b/navigations/move_base_flex/mbf_abstract_nav/include/mbf_abstract_nav/abstract_controller_execution.h new file mode 100755 index 0000000..fb521e1 --- /dev/null +++ b/navigations/move_base_flex/mbf_abstract_nav/include/mbf_abstract_nav/abstract_controller_execution.h @@ -0,0 +1,372 @@ +/* + * Copyright 2018, Magazino GmbH, Sebastian Pütz, Jorge Santos Simón + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * abstract_controller_execution.h + * + * authors: + * Sebastian Pütz + * Jorge Santos Simón + * + */ + +#ifndef MBF_ABSTRACT_NAV__ABSTRACT_CONTROLLER_EXECUTION_H_ +#define MBF_ABSTRACT_NAV__ABSTRACT_CONTROLLER_EXECUTION_H_ + +#include +#include +#include + +#include +#include + +#include +#include +#include + +#include "mbf_abstract_nav/MoveBaseFlexConfig.h" +#include "mbf_abstract_nav/abstract_execution_base.h" + +namespace mbf_abstract_nav +{ + +/** + * @defgroup controller_execution Controller Execution Classes + * @brief The controller execution classes are derived from the AbstractControllerExecution and extends the + * functionality. The base controller execution code is located in the AbstractControllerExecution. + */ + +/** + * @brief The AbstractControllerExecution class loads and binds the controller plugin. It contains a thread + * running the plugin in a cycle to move the robot. An internal state is saved and will be pulled by + * server, to monitor controller execution. Due to a state change it wakes up all threads connected + * to the condition variable. + * + * @ingroup abstract_server controller_execution + */ + class AbstractControllerExecution : public AbstractExecutionBase + { + public: + + static const double DEFAULT_CONTROLLER_FREQUENCY; + + typedef boost::shared_ptr Ptr; + + /** + * @brief Constructor + * @param condition Thread sleep condition variable, to wake up connected threads + * @param controller_plugin_type The plugin type associated with the plugin to load + * @param tf_listener_ptr Shared pointer to a common tf listener + */ + AbstractControllerExecution( + const std::string &name, + const mbf_abstract_core::AbstractController::Ptr &controller_ptr, + const ros::Publisher &vel_pub, + const ros::Publisher &goal_pub, + const TFPtr &tf_listener_ptr, + const MoveBaseFlexConfig &config); + + /** + * @brief Destructor + */ + virtual ~AbstractControllerExecution(); + + /** + * @brief Starts the controller, a valid plan should be given in advance. + * @return false if the thread is already running, true if starting the controller succeeded! + */ + virtual bool start(); + + /** + * @brief Sets a new plan to the controller execution + * @param plan A vector of stamped poses. + * @param tolerance_from_action flag that will be set to true when the new plan (action) has tolerance + * @param action_dist_tolerance distance to goal tolerance specific for this new plan (action) + * @param action_angle_tolerance angle to goal tolerance specific for this new plan (action) + */ + void setNewPlan( + const std::vector &plan, + bool tolerance_from_action = false, + double action_dist_tolerance = 1.0, + double action_angle_tolerance = 3.1415); + + /** + * @brief Cancel the controller execution. + * This calls the cancel method of the controller plugin, sets the cancel_ flag to true, + * and waits for the control loop to stop. Normally called upon aborting the navigation. + * @return true, if the control loop stops within a cycle time. + */ + virtual bool cancel(); + + /** + * @brief Internal states + */ + enum ControllerState + { + INITIALIZED, ///< Controller has been initialized successfully. + STARTED, ///< Controller has been started. + PLANNING, ///< Executing the plugin. + NO_PLAN, ///< The controller has been started without a plan. + MAX_RETRIES, ///< Exceeded the maximum number of retries without a valid command. + PAT_EXCEEDED, ///< Exceeded the patience time without a valid command. + EMPTY_PLAN, ///< Received an empty plan. + INVALID_PLAN, ///< Received an invalid plan that the controller plugin rejected. + NO_LOCAL_CMD, ///< Received no velocity command by the plugin, in the current cycle. + GOT_LOCAL_CMD,///< Got a valid velocity command from the plugin. + ARRIVED_GOAL, ///< The robot arrived the goal. + CANCELED, ///< The controller has been canceled. + STOPPED, ///< The controller has been stopped! + INTERNAL_ERROR///< An internal error occurred. + }; + + /** + * @brief Return the current state of the controller execution. Thread communication safe. + * @return current state, enum value of ControllerState + */ + ControllerState getState(); + + /** + * @brief Returns the time of the last plugin call + * @return Time of the last plugin call + */ + ros::Time getLastPluginCallTime(); + + /** + * @brief Returns the last velocity command calculated by the plugin. Set by setVelocityCmd method. + * Note that it doesn't need to be a valid command sent to the robot, as we report also failed calls + * to the plugin on controller action feedback. + * @return The last valid velocity command. + */ + geometry_msgs::TwistStamped getVelocityCmd(); + + /** + * @brief Checks whether the patience duration time has been exceeded, ot not + * @return true, if the patience has been exceeded. + */ + bool isPatienceExceeded(); + + /** + * @brief Sets the controller frequency + * @param frequency The controller frequency + * @return true, if the controller frequency has been changed / set succesfully, false otherwise + */ + bool setControllerFrequency(double frequency); + + /** + * @brief Is called by the server thread to reconfigure the controller execution, + * if a user uses dynamic reconfigure to reconfigure the current state. + * @param config MoveBaseFlexConfig object + */ + void reconfigure(const MoveBaseFlexConfig &config); + + /** + * @brief Returns whether the robot should normally move or not. True if the controller seems to work properly. + * @return true, if the robot should normally move, false otherwise + */ + bool isMoving(); + + protected: + + /** + * @brief Request plugin for a new velocity command, given the current position, orientation, and velocity of the + * robot. We use this virtual method to give concrete implementations as move_base the chance to override it and do + * additional stuff, for example locking the costmap. + * @param pose the current pose of the robot. + * @param velocity the current velocity of the robot. + * @param cmd_vel Will be filled with the velocity command to be passed to the robot base. + * @param message Optional more detailed outcome as a string. + * @return Result code as described on ExePath action result and plugin's header. + */ + virtual uint32_t computeVelocityCmd(const geometry_msgs::PoseStamped &pose, + const geometry_msgs::TwistStamped &velocity, + geometry_msgs::TwistStamped &vel_cmd, std::string &message); + + /** + * @brief Sets the velocity command, to make it available for another thread + * @param vel_cmd_stamped current velocity command + */ + void setVelocityCmd(const geometry_msgs::TwistStamped &vel_cmd_stamped); + + //! the name of the loaded plugin + std::string plugin_name_; + + //! the local planer to calculate the velocity command + mbf_abstract_core::AbstractController::Ptr controller_; + + //! shared pointer to the shared tf listener + const TFPtr &tf_listener_ptr; + + //! The current cycle start time of the last cycle run. Will by updated each cycle. + ros::Time last_call_time_; + + //! The time the controller has been started. + ros::Time start_time_; + + //! The time the controller responded with a success output (output < 10). + ros::Time last_valid_cmd_time_; + + //! The maximum number of retries + int max_retries_; + + //! The time / duration of patience, before changing the state. + ros::Duration patience_; + + /** + * @brief The main run method, a thread will execute this method. It contains the main controller execution loop. + */ + virtual void run(); + + /** + * @brief Check if its safe to drive. + * This method gets called at every controller cycle, stopping the robot if its not. When overridden by + * child class, gives a chance to the specific execution implementation to stop the robot if it detects + * something wrong on the underlying map. + * @return Always true, unless overridden by child class. + */ + virtual bool safetyCheck() { return true; }; + + private: + + + /** + * @brief Publishes a velocity command with zero values to stop the robot. + */ + void publishZeroVelocity(); + + /** + * @brief Checks whether the goal has been reached in the range of tolerance or not + * @return true if the goal has been reached, false otherwise + */ + bool reachedGoalCheck(); + + /** + * @brief Computes the robot pose; + * @return true if the robot pose has been computed successfully, false otherwise. + */ + bool computeRobotPose(); + + /** + * @brief Sets the controller state. This method makes the communication of the state thread safe. + * @param state The current controller state. + */ + void setState(ControllerState state); + + //! mutex to handle safe thread communication for the current value of the state + boost::mutex state_mtx_; + + //! mutex to handle safe thread communication for the current plan + boost::mutex plan_mtx_; + + //! mutex to handle safe thread communication for the current velocity command + boost::mutex vel_cmd_mtx_; + + //! mutex to handle safe thread communication for the last plugin call time + boost::mutex lct_mtx_; + + //! true, if a new plan is available. See hasNewPlan()! + bool new_plan_; + + /** + * @brief Returns true if a new plan is available, false otherwise! A new plan is set by another thread! + * @return true, if a new plan has been set, false otherwise. + */ + bool hasNewPlan(); + + /** + * @brief Gets the new available plan. This method is thread safe. + * @return The plan + */ + std::vector getNewPlan(); + + //! the last calculated velocity command + geometry_msgs::TwistStamped vel_cmd_stamped_; + + //! the last set plan which is currently processed by the controller + std::vector plan_; + + //! the duration which corresponds with the controller frequency + boost::chrono::microseconds calling_duration_; + + //! the frame of the robot, which will be used to determine its position + std::string robot_frame_; + + //! the global frame the robot is controlling in + std::string global_frame_; + + //! publisher for the current velocity command + ros::Publisher vel_pub_; + + //! publisher for the current goal + ros::Publisher current_goal_pub_; + + //! the current controller state + AbstractControllerExecution::ControllerState state_; + + //! time before a timeout used for tf requests + double tf_timeout_; + + //! dynamic reconfigure config mutex, thread safe param reading and writing + boost::mutex configuration_mutex_; + + //! main controller loop variable, true if the controller is running, false otherwise + bool moving_; + + //! whether MBF should check if the robot has reached the goal, or delegate on the controller instead + bool mbf_check_goal_reached_; + + //! whether move base flex should force the robot to stop once the goal is reached + bool force_stop_at_goal_; + + //! whether move base flex should force the robot to stop on canceling navigation + bool force_stop_on_cancel_; + + //! distance tolerance to the given goal pose + double dist_tolerance_; + + //! angle tolerance to the given goal pose + double angle_tolerance_; + + //! current robot pose; + geometry_msgs::PoseStamped robot_pose_; + + //! whether check for action specific tolerance + bool tolerance_from_action_; + + //! replaces parameter dist_tolerance_ for the action + double action_dist_tolerance_; + + //! replaces parameter angle_tolerance_ for the action + double action_angle_tolerance_; + }; + +} /* namespace mbf_abstract_nav */ + +#endif /* MBF_ABSTRACT_NAV__ABSTRACT_CONTROLLER_EXECUTION_H_ */ diff --git a/navigations/move_base_flex/mbf_abstract_nav/include/mbf_abstract_nav/abstract_execution_base.h b/navigations/move_base_flex/mbf_abstract_nav/include/mbf_abstract_nav/abstract_execution_base.h new file mode 100755 index 0000000..a3f59c0 --- /dev/null +++ b/navigations/move_base_flex/mbf_abstract_nav/include/mbf_abstract_nav/abstract_execution_base.h @@ -0,0 +1,120 @@ +/* + * Copyright 2018, Sebastian Pütz + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * abstract_execution_base.h + * + * author: Sebastian Pütz + * + */ + +#ifndef MBF_ABSTRACT_NAV__ABSTRACT_EXECUTION_BASE_H_ +#define MBF_ABSTRACT_NAV__ABSTRACT_EXECUTION_BASE_H_ + +#include +#include +#include + +#include + +namespace mbf_abstract_nav +{ + +class AbstractExecutionBase +{ + public: + + AbstractExecutionBase(std::string name); + + virtual bool start(); + + virtual void stop(); + + /** + * @brief Cancel the plugin execution. + * @return true, if the plugin tries / tried to cancel the computation. + */ + virtual bool cancel() = 0; + + void join(); + + boost::cv_status waitForStateUpdate(boost::chrono::microseconds const &duration); + + /** + * @brief Gets the current plugin execution outcome + */ + uint32_t getOutcome(); + + /** + * @brief Gets the current plugin execution message + */ + std::string getMessage(); + + /** + * @brief Returns the name of the corresponding plugin + */ + std::string getName(); + + /** + * @brief Optional implementation-specific setup function, called right before execution. + */ + virtual void preRun() { }; + + /** + * @brief Optional implementation-specific cleanup function, called right after execution. + */ + virtual void postRun() { }; + +protected: + virtual void run() = 0; + + //! condition variable to wake up control thread + boost::condition_variable condition_; + + //! the controlling thread object + boost::thread thread_; + + //! flag for canceling controlling + bool cancel_; + + //! the last received plugin execution outcome + uint32_t outcome_; + + //! the last received plugin execution message + std::string message_; + + //! the plugin name; not the plugin type! + std::string name_; +}; + +} /* namespace mbf_abstract_nav */ + +#endif /* MBF_ABSTRACT_NAV__ABSTRACT_EXECUTION_BASE_H_ */ diff --git a/navigations/move_base_flex/mbf_abstract_nav/include/mbf_abstract_nav/abstract_navigation_server.h b/navigations/move_base_flex/mbf_abstract_nav/include/mbf_abstract_nav/abstract_navigation_server.h new file mode 100755 index 0000000..70a767e --- /dev/null +++ b/navigations/move_base_flex/mbf_abstract_nav/include/mbf_abstract_nav/abstract_navigation_server.h @@ -0,0 +1,359 @@ +/* + * Copyright 2018, Magazino GmbH, Sebastian Pütz, Jorge Santos Simón + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * abstract_navigation_server.h + * + * authors: + * Sebastian Pütz + * Jorge Santos Simón + * + */ + +#ifndef MBF_ABSTRACT_NAV__ABSTRACT_NAVIGATION_SERVER_H_ +#define MBF_ABSTRACT_NAV__ABSTRACT_NAVIGATION_SERVER_H_ + +#include + +#include +#include + +#include +#include +#include + +#include + +#include "mbf_abstract_nav/abstract_plugin_manager.h" +#include "mbf_abstract_nav/abstract_planner_execution.h" +#include "mbf_abstract_nav/abstract_controller_execution.h" +#include "mbf_abstract_nav/abstract_recovery_execution.h" + +#include "mbf_abstract_nav/planner_action.h" +#include "mbf_abstract_nav/controller_action.h" +#include "mbf_abstract_nav/recovery_action.h" +#include "mbf_abstract_nav/move_base_action.h" + +#include "mbf_abstract_nav/MoveBaseFlexConfig.h" + +namespace mbf_abstract_nav +{ + +/** + * @defgroup abstract_server Abstract Server + * @brief Classes belonging to the Abstract Server level. + */ + +/** + * @defgroup navigation_server Navigation Server Classes. + * @brief Classes combining the core logic and providing concrete implementations. + */ + + +//! GetPath action server +typedef actionlib::ActionServer ActionServerGetPath; +typedef boost::shared_ptr ActionServerGetPathPtr; + +//! ExePath action server +typedef actionlib::ActionServer ActionServerExePath; +typedef boost::shared_ptr ActionServerExePathPtr; + +//! Recovery action server +typedef actionlib::ActionServer ActionServerRecovery; +typedef boost::shared_ptr ActionServerRecoveryPtr; + +//! MoveBase action server +typedef actionlib::ActionServer ActionServerMoveBase; +typedef boost::shared_ptr ActionServerMoveBasePtr; + +//! ExePath action topic name +const std::string name_action_exe_path = "exe_path"; +//! GetPath action topic name +const std::string name_action_get_path = "get_path"; +//! Recovery action topic name +const std::string name_action_recovery = "recovery"; +//! MoveBase action topic name +const std::string name_action_move_base = "move_base"; + + +typedef boost::shared_ptr > DynamicReconfigureServer; + +/** + * @brief The AbstractNavigationServer is the abstract base class for all navigation servers in move_base_flex + * and bundles the @ref controller_execution "controller execution classes",the @ref planner_execution + * "planner execution classes" and the @ref recovery_execution "recovery execution classes". It provides + * the following action servers ActionServerGetPath -> callActionGetPath(), ActionServerExePath -> callActionExePath(), + * ActionServerRecovery -> callActionRecovery() and ActionServerMoveBase -> callActionMoveBase(). + * + * @ingroup abstract_server navigation_server + */ + class AbstractNavigationServer + { + public: + + /** + * @brief Constructor, reads all parameters and initializes all action servers and creates the plugin instances. + * Parameters are the concrete implementations of the abstract classes. + * @param tf_listener_ptr shared pointer to the common TransformListener buffering transformations + */ + AbstractNavigationServer(const TFPtr &tf_listener_ptr); + + /** + * @brief Destructor + */ + virtual ~AbstractNavigationServer(); + + virtual void stop(); + + /** + * @brief Create a new abstract planner execution. + * @param plugin_name Name of the planner to use. + * @param plugin_ptr Shared pointer to the plugin to use. + * @return Shared pointer to a new @ref planner_execution "PlannerExecution". + */ + virtual mbf_abstract_nav::AbstractPlannerExecution::Ptr newPlannerExecution( + const std::string &plugin_name, + const mbf_abstract_core::AbstractPlanner::Ptr &plugin_ptr); + + /** + * @brief Create a new abstract controller execution. + * @param plugin_name Name of the controller to use. + * @param plugin_ptr Shared pointer to the plugin to use. + * @return Shared pointer to a new @ref controller_execution "ControllerExecution". + */ + virtual mbf_abstract_nav::AbstractControllerExecution::Ptr newControllerExecution( + const std::string &plugin_name, + const mbf_abstract_core::AbstractController::Ptr &plugin_ptr); + + /** + * @brief Create a new abstract recovery behavior execution. + * @param plugin_name Name of the recovery behavior to run. + * @param plugin_ptr Shared pointer to the plugin to use + * @return Shared pointer to a new @ref recovery_execution "RecoveryExecution". + */ + virtual mbf_abstract_nav::AbstractRecoveryExecution::Ptr newRecoveryExecution( + const std::string &plugin_name, + const mbf_abstract_core::AbstractRecovery::Ptr &plugin_ptr); + + /** + * @brief Loads the plugin associated with the given planner_type parameter. + * @param planner_type The type of the planner plugin to load. + * @return Pointer to the loaded plugin + */ + virtual mbf_abstract_core::AbstractPlanner::Ptr loadPlannerPlugin(const std::string &planner_type) = 0; + + /** + * @brief Loads the plugin associated with the given controller type parameter + * @param controller_type The type of the controller plugin + * @return A shared pointer to a new loaded controller, if the controller plugin was loaded successfully, + * an empty pointer otherwise. + */ + virtual mbf_abstract_core::AbstractController::Ptr loadControllerPlugin(const std::string &controller_type) = 0; + + /** + * @brief Loads a Recovery plugin associated with given recovery type parameter + * @param recovery_name The name of the Recovery plugin + * @return A shared pointer to a Recovery plugin, if the plugin was loaded successfully, an empty pointer otherwise. + */ + virtual mbf_abstract_core::AbstractRecovery::Ptr loadRecoveryPlugin(const std::string &recovery_type) = 0; + + /** + * @brief Pure virtual method, the derived class has to implement. Depending on the plugin base class, + * some plugins need to be initialized! + * @param name The name of the planner + * @param planner_ptr pointer to the planner object which corresponds to the name param + * @return true if init succeeded, false otherwise + */ + virtual bool initializePlannerPlugin( + const std::string &name, + const mbf_abstract_core::AbstractPlanner::Ptr &planner_ptr + ) = 0; + + /** + * @brief Pure virtual method, the derived class has to implement. Depending on the plugin base class, + * some plugins need to be initialized! + * @param name The name of the controller + * @param controller_ptr pointer to the controller object which corresponds to the name param + * @return true if init succeeded, false otherwise + */ + virtual bool initializeControllerPlugin( + const std::string &name, + const mbf_abstract_core::AbstractController::Ptr &controller_ptr + ) = 0; + + /** + * @brief Pure virtual method, the derived class has to implement. Depending on the plugin base class, + * some plugins need to be initialized! + * @param name The name of the recovery behavior + * @param behavior_ptr pointer to the recovery behavior object which corresponds to the name param + * @return true if init succeeded, false otherwise + */ + virtual bool initializeRecoveryPlugin( + const std::string &name, + const mbf_abstract_core::AbstractRecovery::Ptr &behavior_ptr + ) = 0; + + + /** + * @brief GetPath action execution method. This method will be called if the action server receives a goal + * @param goal SimpleActionServer goal containing all necessary parameters for the action execution. See the action + * definitions in mbf_msgs. + */ + virtual void callActionGetPath(ActionServerGetPath::GoalHandle goal_handle); + + virtual void cancelActionGetPath(ActionServerGetPath::GoalHandle goal_handle); + + /** + * @brief ExePath action execution method. This method will be called if the action server receives a goal + * @param goal SimpleActionServer goal containing all necessary parameters for the action execution. See the action + * definitions in mbf_msgs. + */ + virtual void callActionExePath(ActionServerExePath::GoalHandle goal_handle); + + virtual void cancelActionExePath(ActionServerExePath::GoalHandle goal_handle); + + /** + * @brief Recovery action execution method. This method will be called if the action server receives a goal + * @param goal SimpleActionServer goal containing all necessary parameters for the action execution. See the action + * definitions in mbf_msgs. + */ + virtual void callActionRecovery(ActionServerRecovery::GoalHandle goal_handle); + + virtual void cancelActionRecovery(ActionServerRecovery::GoalHandle goal_handle); + + /** + * @brief MoveBase action execution method. This method will be called if the action server receives a goal + * @param goal SimpleActionServer goal containing all necessary parameters for the action execution. See the action + * definitions in mbf_msgs. + */ + virtual void callActionMoveBase(ActionServerMoveBase::GoalHandle goal_handle); + + virtual void cancelActionMoveBase(ActionServerMoveBase::GoalHandle goal_handle); + + /** + * @brief starts all action server. + */ + virtual void startActionServers(); + + /** + * @brief initializes all server components. Initializing the plugins of the @ref planner_execution "Planner", the + * @ref controller_execution "Controller", and the @ref recovery_execution "Recovery Behavior". + */ + virtual void initializeServerComponents(); + + protected: + + /** + * @brief Transforms a plan to the global frame (global_frame_) coord system. + * @param plan Input plan to be transformed. + * @param global_plan Output plan, which is then transformed to the global frame. + * @return true, if the transformation succeeded, false otherwise + */ + bool transformPlanToGlobalFrame(std::vector &plan, + std::vector &global_plan); + + /** + * @brief Start a dynamic reconfigure server. + * This must be called only if the extending doesn't create its own. + */ + virtual void startDynamicReconfigureServer(); + + /** + * @brief Reconfiguration method called by dynamic reconfigure + * @param config Configuration parameters. See the MoveBaseFlexConfig definition. + * @param level bit mask, which parameters are set. + */ + virtual void reconfigure(mbf_abstract_nav::MoveBaseFlexConfig &config, uint32_t level); + + //! Private node handle + ros::NodeHandle private_nh_; + + AbstractPluginManager planner_plugin_manager_; + AbstractPluginManager controller_plugin_manager_; + AbstractPluginManager recovery_plugin_manager_; + + //! shared pointer to the Recovery action server + ActionServerRecoveryPtr action_server_recovery_ptr_; + + //! shared pointer to the ExePath action server + ActionServerExePathPtr action_server_exe_path_ptr_; + + //! shared pointer to the GetPath action server + ActionServerGetPathPtr action_server_get_path_ptr_; + + //! shared pointer to the MoveBase action server + ActionServerMoveBasePtr action_server_move_base_ptr_; + + //! dynamic reconfigure server + DynamicReconfigureServer dsrv_; + + //! configuration mutex for derived classes and other threads. + boost::mutex configuration_mutex_; + + //! last configuration save + mbf_abstract_nav::MoveBaseFlexConfig last_config_; + + //! the default parameter configuration save + mbf_abstract_nav::MoveBaseFlexConfig default_config_; + + //! true, if the dynamic reconfigure has been setup. + bool setup_reconfigure_; + + //! the robot frame, to get the current robot pose in the global_frame_ + std::string robot_frame_; + + //! the global frame, in which the robot is moving + std::string global_frame_; + + //! timeout after tf returns without a result + ros::Duration tf_timeout_; + + //! shared pointer to the common TransformListener + const TFPtr tf_listener_ptr_; + + //! cmd_vel publisher for all controller execution objects + ros::Publisher vel_pub_; + + //! current_goal publisher for all controller execution objects + ros::Publisher goal_pub_; + + //! current robot state + mbf_utility::RobotInformation robot_info_; + + ControllerAction controller_action_; + PlannerAction planner_action_; + RecoveryAction recovery_action_; + MoveBaseAction move_base_action_; + }; + +} /* namespace mbf_abstract_nav */ + +#endif /* MBF_ABSTRACT_NAV__ABSTRACT_NAVIGATION_SERVER_H_ */ diff --git a/navigations/move_base_flex/mbf_abstract_nav/include/mbf_abstract_nav/abstract_planner_execution.h b/navigations/move_base_flex/mbf_abstract_nav/include/mbf_abstract_nav/abstract_planner_execution.h new file mode 100755 index 0000000..e32664f --- /dev/null +++ b/navigations/move_base_flex/mbf_abstract_nav/include/mbf_abstract_nav/abstract_planner_execution.h @@ -0,0 +1,313 @@ +/* + * Copyright 2018, Magazino GmbH, Sebastian Pütz, Jorge Santos Simón + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * abstract_planner_execution.h + * + * authors: + * Sebastian Pütz + * Jorge Santos Simón + * + */ + +#ifndef MBF_ABSTRACT_NAV__ABSTRACT_PLANNER_EXECUTION_H_ +#define MBF_ABSTRACT_NAV__ABSTRACT_PLANNER_EXECUTION_H_ + +#include +#include +#include + +#include + +#include +#include + +#include + +#include "mbf_abstract_nav/abstract_execution_base.h" + +namespace mbf_abstract_nav +{ + +/** + * @defgroup planner_execution Planner Execution Classes + * @brief The planner execution classes are derived from the AbstractPlannerExecution and extend the functionality. + * The base planner execution code is located in the AbstractPlannerExecution. + */ + +/** + * @brief The AbstractPlannerExecution class loads and binds the global planner plugin. It contains a thread running + * the plugin in a cycle to plan and re-plan. An internal state is saved and will be pulled by the server, which + * controls the global planner execution. Due to a state change it wakes up all threads connected to the + * condition variable. + * + * @ingroup abstract_server planner_execution + */ + class AbstractPlannerExecution : public AbstractExecutionBase + { + public: + + //! shared pointer type to the @ref planner_execution "planner execution". + typedef boost::shared_ptr Ptr; + + /** + * @brief Constructor + * @param name Name of this execution + * @param planner_ptr Pointer to the planner + * @param config Initial configuration for this execution + */ + AbstractPlannerExecution(const std::string &name, + const mbf_abstract_core::AbstractPlanner::Ptr &planner_ptr, + const MoveBaseFlexConfig &config); + + /** + * @brief Destructor + */ + virtual ~AbstractPlannerExecution(); + + /** + * @brief Returns a new plan, if one is available. + */ + std::vector getPlan() const; + + /** + * @brief Returns the last time a valid plan was available. + * @return time, the last valid plan was available. + */ + ros::Time getLastValidPlanTime() const; + + /** + * @brief Checks whether the patience was exceeded. + * @return true, if the patience duration was exceeded. + */ + bool isPatienceExceeded() const; + + /** + * @brief Internal states + */ + enum PlanningState + { + INITIALIZED, ///< Planner initialized. + STARTED, ///< Planner started. + PLANNING, ///< Executing the plugin. + FOUND_PLAN, ///< Found a valid plan. + MAX_RETRIES, ///< Exceeded the maximum number of retries without a valid command. + PAT_EXCEEDED, ///< Exceeded the patience time without a valid command. + NO_PLAN_FOUND,///< No plan has been found (MAX_RETRIES and PAT_EXCEEDED are 0). + CANCELED, ///< The planner has been canceled. + STOPPED, ///< The planner has been stopped. + INTERNAL_ERROR///< An internal error occurred. + }; + + /** + * @brief Returns the current internal state + * @return the current internal state + */ + PlanningState getState() const; + + /** + * @brief Gets planning frequency + */ + double getFrequency() const { return frequency_; }; + + /** + * @brief Gets computed costs + * @return The costs of the computed path + */ + double getCost() const; + + /** + * @brief Cancel the planner execution. This calls the cancel method of the planner plugin. + * This could be useful if the computation takes too much time, or if we are aborting the navigation. + * @return true, if the planner plugin tries / tried to cancel the planning step. + */ + virtual bool cancel(); + + /** + * @brief Sets a new goal pose for the planner execution + * @param goal the new goal pose + * @param dist_tolerance Tolerance in meters to the goal position + * @param angle_tolerance Tolerance in radians to the goal orientation + */ + void setNewGoal(const geometry_msgs::PoseStamped &goal, + double dist_tolerance, double angle_tolerance); + + /** + * @brief Sets a new start pose for the planner execution + * @param start new start pose + */ + void setNewStart(const geometry_msgs::PoseStamped &start); + + /** + * @brief Sets a new star and goal pose for the planner execution + * @param start new start pose + * @param goal new goal pose + * @param dist_tolerance Tolerance in meters to the goal position + * @param angle_tolerance Tolerance in radians to the goal orientation + */ + void setNewStartAndGoal(const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal, + double dist_tolerance, double angle_tolerance); + + /** + * @brief Starts the planner execution thread with the given parameters. + * @param start start pose for the planning + * @param goal goal pose for the planning + * @param dist_tolerance Tolerance in meters to the goal position + * @param angle_tolerance Tolerance in radians to the goal orientation + * @return true, if the planner thread has been started, false if the thread is already running. + */ + bool start(const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal, + double dist_tolerance, double angle_tolerance); + + /** + * @brief Is called by the server thread to reconfigure the controller execution, if a user uses dynamic reconfigure + * to reconfigure the current state. + * @param config MoveBaseFlexConfig object + */ + void reconfigure(const MoveBaseFlexConfig &config); + + protected: + + //! the local planer to calculate the robot trajectory + mbf_abstract_core::AbstractPlanner::Ptr planner_; + + //! the name of the loaded planner plugin + std::string plugin_name_; + + /** + * @brief The main run method, a thread will execute this method. It contains the main planner execution loop. + */ + virtual void run(); + + private: + + /** + * @brief calls the planner plugin to make a plan from the start pose to the goal pose. + * The final pose of the path must be within tolerance range (position and orientation) + * for this method to return a success outcome. + * @param start The start pose for planning + * @param goal The goal pose for planning + * @param dist_tolerance Tolerance in meters to the goal position + * @param angle_tolerance Tolerance in radians to the goal orientation + * @param plan The computed plan by the plugin + * @param cost The computed costs for the corresponding plan + * @param message An optional message which should correspond with the returned outcome + * @return An outcome number, see also the action definition in the GetPath.action file + */ + virtual uint32_t makePlan( + const geometry_msgs::PoseStamped &start, + const geometry_msgs::PoseStamped &goal, + double dist_tolerance, double angle_tolerance, + std::vector &plan, + double &cost, + std::string &message); + + /** + * @brief Sets the internal state, thread communication safe + * @param state the current state + * @param signalling set true to trigger the condition-variable for state-update + */ + void setState(PlanningState state, bool signalling); + + //! mutex to handle safe thread communication for the current state + mutable boost::mutex state_mtx_; + + //! mutex to handle safe thread communication for the plan and plan-costs + mutable boost::mutex plan_mtx_; + + //! mutex to handle safe thread communication for the goal and start pose. + mutable boost::mutex goal_start_mtx_; + + //! mutex to handle safe thread communication for the planning_ flag. + mutable boost::mutex planning_mtx_; + + //! dynamic reconfigure mutex for a thread safe communication + mutable boost::mutex configuration_mutex_; + + //! true, if a new goal pose has been set, until it is used. + bool has_new_goal_; + + //! true, if a new start pose has been set, until it is used. + bool has_new_start_; + + //! the last call start time, updated each cycle. + ros::Time last_call_start_time_; + + //! the last time a valid plan has been computed. + ros::Time last_valid_plan_time_; + + //! current global plan + std::vector plan_; + + //! current global plan cost + double cost_; + + //! the current start pose used for planning + geometry_msgs::PoseStamped start_; + + //! the current goal pose used for planning + geometry_msgs::PoseStamped goal_; + + //! optional linear goal tolerance, in meters + double dist_tolerance_; + + //! optional angular goal tolerance, in radians + double angle_tolerance_; + + //! planning cycle frequency (used only when running full navigation; we store here for grouping parameters nicely) + double frequency_; + + //! planning patience duration time + ros::Duration patience_; + + //! planning max retries + int max_retries_; + + //! main cycle variable of the execution loop + bool planning_; + + //! robot frame used for computing the current robot pose + std::string robot_frame_; + + //! the global frame in which the planner needs to plan + std::string global_frame_; + + //! shared pointer to a common TransformListener + const TFPtr tf_listener_ptr_; + + //! current internal state + PlanningState state_; + + }; + +} /* namespace mbf_abstract_nav */ + +#endif /* MBF_ABSTRACT_NAV__ABSTRACT_PLANNER_EXECUTION_H_ */ diff --git a/navigations/move_base_flex/mbf_abstract_nav/include/mbf_abstract_nav/abstract_plugin_manager.h b/navigations/move_base_flex/mbf_abstract_nav/include/mbf_abstract_nav/abstract_plugin_manager.h new file mode 100755 index 0000000..ce2ab4f --- /dev/null +++ b/navigations/move_base_flex/mbf_abstract_nav/include/mbf_abstract_nav/abstract_plugin_manager.h @@ -0,0 +1,85 @@ +/* + * Copyright 2018, Sebastian Pütz + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * abstract_plugin_manager.h + * + * author: Sebastian Pütz + * + */ + +#ifndef MBF_ABSTRACT_NAV__ABSTRACT_PLUGIN_MANAGER_H_ +#define MBF_ABSTRACT_NAV__ABSTRACT_PLUGIN_MANAGER_H_ + +#include + +namespace mbf_abstract_nav +{ + +template +class AbstractPluginManager +{ + public: + + typedef boost::function loadPluginFunction; + typedef boost::function initPluginFunction; + + AbstractPluginManager( + const std::string ¶m_name, + const loadPluginFunction &loadPlugin, + const initPluginFunction &initPlugin + ); + + bool loadPlugins(); + + bool hasPlugin(const std::string &name); + + std::string getType(const std::string &name); + + const std::vector& getLoadedNames(); + + typename PluginType::Ptr getPlugin(const std::string &name); + + void clearPlugins(); + + protected: + std::map plugins_; + std::map plugins_type_; + std::vector names_; + const std::string param_name_; + const loadPluginFunction loadPlugin_; + const initPluginFunction initPlugin_; +}; + +} /* namespace mbf_abstract_nav */ + +#include "impl/abstract_plugin_manager.tcc" +#endif /* MBF_ABSTRACT_NAV__ABSTRACT_PLUGIN_MANAGER_H_ */ diff --git a/navigations/move_base_flex/mbf_abstract_nav/include/mbf_abstract_nav/abstract_recovery_execution.h b/navigations/move_base_flex/mbf_abstract_nav/include/mbf_abstract_nav/abstract_recovery_execution.h new file mode 100755 index 0000000..e50d6a5 --- /dev/null +++ b/navigations/move_base_flex/mbf_abstract_nav/include/mbf_abstract_nav/abstract_recovery_execution.h @@ -0,0 +1,176 @@ +/* + * Copyright 2018, Magazino GmbH, Sebastian Pütz, Jorge Santos Simón + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * abstract_recovery_execution.h + * + * authors: + * Sebastian Pütz + * Jorge Santos Simón + * + */ + +#ifndef MBF_ABSTRACT_NAV__ABSTRACT_RECOVERY_EXECUTION_H_ +#define MBF_ABSTRACT_NAV__ABSTRACT_RECOVERY_EXECUTION_H_ + +#include +#include +#include + +#include +#include + +#include + +#include "mbf_abstract_nav/MoveBaseFlexConfig.h" +#include "mbf_abstract_nav/abstract_execution_base.h" + + +namespace mbf_abstract_nav +{ + +/** + * @defgroup recovery_execution Recovery Execution Classes + * @brief The recovery execution classes are derived from the RecoveryPlannerExecution and extends the functionality. + * The base recovery execution code is located in the AbstractRecoveryExecution. + */ + +/** + * @brief The AbstractRecoveryExecution class loads and binds the recovery behavior plugin. It contains a thread + * running the plugin, executing the recovery behavior. An internal state is saved and will be pulled by the + * server, which controls the recovery behavior execution. Due to a state change it wakes up all threads + * connected to the condition variable. + * + * @ingroup abstract_server recovery_execution + */ + class AbstractRecoveryExecution : public AbstractExecutionBase + { + public: + + typedef boost::shared_ptr Ptr; + + /** + * @brief Constructor + * @param condition Thread sleep condition variable, to wake up connected threads + * @param tf_listener_ptr Shared pointer to a common tf listener + */ + AbstractRecoveryExecution(const std::string &name, + const mbf_abstract_core::AbstractRecovery::Ptr &recovery_ptr, + const TFPtr &tf_listener_ptr, + const MoveBaseFlexConfig &config); + + /** + * @brief Destructor + */ + virtual ~AbstractRecoveryExecution(); + + /** + * @brief Checks whether the patience was exceeded. + * @return true, if the patience duration was exceeded. + */ + bool isPatienceExceeded(); + + /** + * @brief Cancel the planner execution. This calls the cancel method of the planner plugin. + * This could be useful if the computation takes too much time, or if we are aborting the navigation. + * @return true, if the planner plugin tries / tried to cancel the planning step. + */ + virtual bool cancel(); + + /** + * @brief internal state. + */ + enum RecoveryState + { + INITIALIZED, ///< The recovery execution has been initialized. + STARTED, ///< The recovery execution thread has been started. + RECOVERING, ///< The recovery behavior plugin is running. + WRONG_NAME, ///< The given name could not be associated with a load behavior. + RECOVERY_DONE, ///< The recovery behavior execution is done. + CANCELED, ///< The recovery execution was canceled. + STOPPED, ///< The recovery execution has been stopped. + INTERNAL_ERROR ///< An internal error occurred. + }; + + /** + * @brief Returns the current state, thread-safe communication + * @return current internal state + */ + AbstractRecoveryExecution::RecoveryState getState(); + + /** + * @brief Reconfigures the current configuration and reloads all parameters. This method is called from a dynamic + * reconfigure tool. + * @param config Current MoveBaseFlexConfig object. See the MoveBaseFlex.cfg definition. + */ + void reconfigure(const MoveBaseFlexConfig &config); + + protected: + + /** + * @brief Main execution method which will be executed by the recovery execution thread_. + */ + virtual void run(); + + //! the current loaded recovery behavior + mbf_abstract_core::AbstractRecovery::Ptr behavior_; + + //! shared pointer to common TransformListener + const TFPtr tf_listener_ptr_; + + private: + + /** + * @brief Sets the current internal state. This method is thread communication safe + * @param state The state to set. + */ + void setState(RecoveryState state); + + //! mutex to handle safe thread communication for the current state + boost::mutex state_mtx_; + + //! dynamic reconfigure and start time mutexes to mutually exclude read/write configuration + boost::mutex conf_mtx_; + boost::mutex time_mtx_; + + //! recovery behavior allowed time + ros::Duration patience_; + + //! recovery behavior start time + ros::Time start_time_; + + //! current internal state + RecoveryState state_; + }; + +} /* namespace mbf_abstract_nav */ + +#endif /* MBF_ABSTRACT_NAV__ABSTRACT_RECOVERY_EXECUTION_H_ */ diff --git a/navigations/move_base_flex/mbf_abstract_nav/include/mbf_abstract_nav/controller_action.h b/navigations/move_base_flex/mbf_abstract_nav/include/mbf_abstract_nav/controller_action.h new file mode 100755 index 0000000..d38411d --- /dev/null +++ b/navigations/move_base_flex/mbf_abstract_nav/include/mbf_abstract_nav/controller_action.h @@ -0,0 +1,103 @@ +/* + * Copyright 2018, Magazino GmbH, Sebastian Pütz, Jorge Santos Simón + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * controller_action.h + * + * authors: + * Sebastian Pütz + * Jorge Santos Simón + * + */ + +#ifndef MBF_ABSTRACT_NAV__CONTROLLER_ACTION_H_ +#define MBF_ABSTRACT_NAV__CONTROLLER_ACTION_H_ + +#include + +#include +#include + +#include "mbf_abstract_nav/abstract_action_base.hpp" +#include "mbf_abstract_nav/abstract_controller_execution.h" + +namespace mbf_abstract_nav +{ + +class ControllerAction : + public AbstractActionBase +{ + public: + + typedef boost::shared_ptr Ptr; + + ControllerAction(const std::string &name, + const mbf_utility::RobotInformation &robot_info); + + /** + * @brief Start controller action. + * Override abstract action version to allow updating current plan without stopping execution. + * @param goal_handle Reference to the goal handle received on action execution callback. + * @param execution_ptr Pointer to the execution descriptor. + */ + void start( + GoalHandle &goal_handle, + typename AbstractControllerExecution::Ptr execution_ptr + ); + + void run(GoalHandle &goal_handle, AbstractControllerExecution &execution); + +protected: + void publishExePathFeedback( + GoalHandle &goal_handle, + uint32_t outcome, const std::string &message, + const geometry_msgs::TwistStamped ¤t_twist); + + /** + * @brief Utility method to fill the ExePath action result in a single line + * @param outcome ExePath action outcome + * @param message ExePath action message + * @param result The action result to fill + */ + void fillExePathResult( + uint32_t outcome, const std::string &message, + mbf_msgs::ExePathResult &result); + + boost::mutex goal_mtx_; ///< lock goal handle for updating it while running + geometry_msgs::PoseStamped robot_pose_; ///< Current robot pose + geometry_msgs::PoseStamped goal_pose_; ///< Current goal pose + +}; +} + + + +#endif //MBF_ABSTRACT_NAV__CONTROLLER_ACTION_H_ diff --git a/navigations/move_base_flex/mbf_abstract_nav/include/mbf_abstract_nav/impl/abstract_plugin_manager.tcc b/navigations/move_base_flex/mbf_abstract_nav/include/mbf_abstract_nav/impl/abstract_plugin_manager.tcc new file mode 100755 index 0000000..1c23b7b --- /dev/null +++ b/navigations/move_base_flex/mbf_abstract_nav/include/mbf_abstract_nav/impl/abstract_plugin_manager.tcc @@ -0,0 +1,162 @@ +/* + * Copyright 2018, Sebastian Pütz + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * abstract_plugin_manager.h + * + * author: Sebastian Pütz + * + */ + +#ifndef MBF_ABSTRACT_NAV__ABSTRACT_PLUGIN_MANAGER_TCC_ +#define MBF_ABSTRACT_NAV__ABSTRACT_PLUGIN_MANAGER_TCC_ + +#include "mbf_abstract_nav/abstract_plugin_manager.h" +#include + +namespace mbf_abstract_nav{ + +template +AbstractPluginManager::AbstractPluginManager( + const std::string ¶m_name, + const loadPluginFunction &loadPlugin, + const initPluginFunction &initPlugin +) + : param_name_(param_name), loadPlugin_(loadPlugin), initPlugin_(initPlugin) +{ +} + +template +bool AbstractPluginManager::loadPlugins() +{ + ros::NodeHandle private_nh("~"); + + XmlRpc::XmlRpcValue plugin_param_list; + if(!private_nh.getParam(param_name_, plugin_param_list)) + { + ROS_WARN_STREAM("No " << param_name_ << " plugins configured! - Use the param \"" << param_name_ << "\", " + "which must be a list of tuples with a name and a type."); + return false; + } + + try + { + for (int i = 0; i < plugin_param_list.size(); i++) + { + XmlRpc::XmlRpcValue elem = plugin_param_list[i]; + + std::string name = elem["name"]; + std::string type = elem["type"]; + + if (plugins_.find(name) != plugins_.end()) + { + ROS_ERROR_STREAM("The plugin \"" << name << "\" has already been loaded! Names must be unique!"); + return false; + } + typename PluginType::Ptr plugin_ptr = loadPlugin_(type); + if(plugin_ptr && initPlugin_(name, plugin_ptr)) + { + + plugins_.insert( + std::pair(name, plugin_ptr)); + + plugins_type_.insert(std::pair(name, type)); // save name to type mapping + names_.push_back(name); + + ROS_INFO_STREAM("The plugin with the type \"" << type << "\" has been loaded successfully under the name \"" + << name << "\"."); + } + else + { + ROS_ERROR_STREAM("Could not load the plugin with the name \"" + << name << "\" and the type \"" << type << "\"!"); + } + } + } + catch (XmlRpc::XmlRpcException &e) + { + ROS_ERROR_STREAM("Invalid parameter structure. The \""<< param_name_ << "\" parameter has to be a list of structs " + << "with fields \"name\" and \"type\" of !"); + ROS_ERROR_STREAM(e.getMessage()); + return false; + } + // is there any plugin in the map? + return plugins_.empty() ? false : true; +} + +template +const std::vector& AbstractPluginManager::getLoadedNames() +{ + return names_; +} + +template +bool AbstractPluginManager::hasPlugin(const std::string &name) +{ + return static_cast(plugins_.count(name)); // returns 1 or 0; +} + +template +std::string AbstractPluginManager::getType(const std::string &name) +{ + std::map::iterator iter = plugins_type_.find(name); + return iter->second; +} + + +template +typename PluginType::Ptr AbstractPluginManager::getPlugin(const std::string &name) +{ + typename std::map::iterator new_plugin + = plugins_.find(name); + if(new_plugin != plugins_.end()) + { + ROS_DEBUG_STREAM("Found plugin with the name \"" << name << "\"."); + return new_plugin->second; + } + else + { + ROS_WARN_STREAM("The plugin with the name \"" << name << "\" has not yet been loaded!"); + return typename PluginType::Ptr(); // return null ptr + } +} + +template +void AbstractPluginManager::clearPlugins() { + plugins_.clear(); + plugins_type_.clear(); + names_.clear(); +} + +} /* namespace mbf_abstract_nav */ + +#endif //MBF_ABSTRACT_NAV__ABSTRACT_PLUGIN_MANAGER_TCC_ + diff --git a/navigations/move_base_flex/mbf_abstract_nav/include/mbf_abstract_nav/move_base_action.h b/navigations/move_base_flex/mbf_abstract_nav/include/mbf_abstract_nav/move_base_action.h new file mode 100755 index 0000000..e6b5f07 --- /dev/null +++ b/navigations/move_base_flex/mbf_abstract_nav/include/mbf_abstract_nav/move_base_action.h @@ -0,0 +1,192 @@ +/* + * Copyright 2018, Magazino GmbH, Sebastian Pütz, Jorge Santos Simón + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * move_base_action.h + * + * authors: + * Sebastian Pütz + * Jorge Santos Simón + * + */ +#ifndef MBF_ABSTRACT_NAV__MOVE_BASE_ACTION_H_ +#define MBF_ABSTRACT_NAV__MOVE_BASE_ACTION_H_ + +#include +#include + +#include +#include +#include +#include + +#include + +#include "mbf_abstract_nav/MoveBaseFlexConfig.h" + + +namespace mbf_abstract_nav +{ + +class MoveBaseAction +{ + public: + + //! Action clients for the MoveBase action + typedef actionlib::SimpleActionClient ActionClientGetPath; + typedef actionlib::SimpleActionClient ActionClientExePath; + typedef actionlib::SimpleActionClient ActionClientRecovery; + + typedef actionlib::ActionServer::GoalHandle GoalHandle; + + MoveBaseAction(const std::string &name, + const mbf_utility::RobotInformation &robot_info, + const std::vector &controllers); + + ~MoveBaseAction(); + + void start(GoalHandle &goal_handle); + + void cancel(); + + void reconfigure( + mbf_abstract_nav::MoveBaseFlexConfig &config, uint32_t level); + + protected: + + void actionExePathFeedback(const mbf_msgs::ExePathFeedbackConstPtr &feedback); + + void actionGetPathDone( + const actionlib::SimpleClientGoalState &state, + const mbf_msgs::GetPathResultConstPtr &result); + + void actionExePathActive(); + + void actionExePathDone( + const actionlib::SimpleClientGoalState &state, + const mbf_msgs::ExePathResultConstPtr &result); + + void actionGetPathReplanningDone( + const actionlib::SimpleClientGoalState &state, + const mbf_msgs::GetPathResultConstPtr &result); + + void actionRecoveryDone( + const actionlib::SimpleClientGoalState &state, + const mbf_msgs::RecoveryResultConstPtr &result); + + bool attemptRecovery(); + + /** + * Utility method that fills move base action result with the result of any of the action clients. + * @tparam ResultType + * @param result + * @param move_base_result + */ + template + void fillMoveBaseResult(const ResultType& result, mbf_msgs::MoveBaseResult& move_base_result) + { + // copy outcome and message from action client result + move_base_result.outcome = result.outcome; + move_base_result.message = result.message; + move_base_result.dist_to_goal = static_cast(mbf_utility::distance(robot_pose_, goal_pose_)); + move_base_result.angle_to_goal = static_cast(mbf_utility::angle(robot_pose_, goal_pose_)); + move_base_result.final_pose = robot_pose_; + } + + mbf_msgs::ExePathGoal exe_path_goal_; + mbf_msgs::GetPathGoal get_path_goal_; + mbf_msgs::RecoveryGoal recovery_goal_; + + geometry_msgs::PoseStamped last_oscillation_pose_; + ros::Time last_oscillation_reset_; + + //! timeout after a oscillation is detected + ros::Duration oscillation_timeout_; + + //! minimal move distance to not detect an oscillation + double oscillation_distance_; + + GoalHandle goal_handle_; + + std::string name_; + + //! current robot state + const mbf_utility::RobotInformation &robot_info_; + + //! current robot pose; updated with exe_path action feedback + geometry_msgs::PoseStamped robot_pose_; + + //! current goal pose; used to compute remaining distance and angle + geometry_msgs::PoseStamped goal_pose_; + + ros::NodeHandle private_nh_; + + //! Action client used by the move_base action + ActionClientExePath action_client_exe_path_; + + //! Action client used by the move_base action + ActionClientGetPath action_client_get_path_; + + //! Action client used by the move_base action + ActionClientRecovery action_client_recovery_; + + bool replanning_; + ros::Rate replanning_rate_; + boost::mutex replanning_mtx_; + + //! true, if recovery behavior for the MoveBase action is enabled. + bool recovery_enabled_; + + std::vector recovery_behaviors_; + + std::vector::iterator current_recovery_behavior_; + + const std::vector &behaviors_; + + enum MoveBaseActionState + { + NONE, + GET_PATH, + EXE_PATH, + RECOVERY, + OSCILLATING, + SUCCEEDED, + CANCELED, + FAILED + }; + + MoveBaseActionState action_state_; + MoveBaseActionState recovery_trigger_; +}; + +} /* mbf_abstract_nav */ + +#endif //MBF_ABSTRACT_NAV__MOVE_BASE_ACTION_H_ diff --git a/navigations/move_base_flex/mbf_abstract_nav/include/mbf_abstract_nav/planner_action.h b/navigations/move_base_flex/mbf_abstract_nav/include/mbf_abstract_nav/planner_action.h new file mode 100755 index 0000000..8431e36 --- /dev/null +++ b/navigations/move_base_flex/mbf_abstract_nav/include/mbf_abstract_nav/planner_action.h @@ -0,0 +1,92 @@ +/* + * Copyright 2018, Magazino GmbH, Sebastian Pütz, Jorge Santos Simón + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * planner_action.h + * + * authors: + * Sebastian Pütz + * Jorge Santos Simón + * + */ + +#ifndef MBF_ABSTRACT_NAV__PLANNER_ACTION_H_ +#define MBF_ABSTRACT_NAV__PLANNER_ACTION_H_ + +#include + +#include +#include + +#include "mbf_abstract_nav/abstract_action_base.hpp" +#include "mbf_abstract_nav/abstract_planner_execution.h" + + +namespace mbf_abstract_nav{ + + +class PlannerAction : public AbstractActionBase +{ + public: + + typedef boost::shared_ptr Ptr; + + PlannerAction( + const std::string &name, + const mbf_utility::RobotInformation &robot_info + ); + + void run(GoalHandle &goal_handle, AbstractPlannerExecution &execution); + + protected: + + /** + * @brief Transforms a plan to the global frame (global_frame_) coord system. + * @param plan Input plan to be transformed. + * @param global_plan Output plan, which is then transformed to the global frame. + * @return true, if the transformation succeeded, false otherwise + */ + bool transformPlanToGlobalFrame(std::vector &plan, + std::vector &global_plan); + + + private: + + //! Publisher to publish the current goal pose, which is used for path planning + ros::Publisher current_goal_pub_; + + //! Path sequence counter + unsigned int path_seq_count_; +}; + +} /* mbf_abstract_nav */ + +#endif /* MBF_ABSTRACT_NAV__PLANNER_ACTION_H_ */ diff --git a/navigations/move_base_flex/mbf_abstract_nav/include/mbf_abstract_nav/recovery_action.h b/navigations/move_base_flex/mbf_abstract_nav/include/mbf_abstract_nav/recovery_action.h new file mode 100755 index 0000000..5064770 --- /dev/null +++ b/navigations/move_base_flex/mbf_abstract_nav/include/mbf_abstract_nav/recovery_action.h @@ -0,0 +1,70 @@ +/* + * Copyright 2018, Magazino GmbH, Sebastian Pütz, Jorge Santos Simón + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * recovery_action.h + * + * authors: + * Sebastian Pütz + * Jorge Santos Simón + * + */ + +#ifndef MBF_ABSTRACT_NAV__RECOVERY_ACTION_H_ +#define MBF_ABSTRACT_NAV__RECOVERY_ACTION_H_ + +#include +#include + +#include +#include + +#include "mbf_abstract_nav/abstract_action_base.hpp" +#include "mbf_abstract_nav/abstract_recovery_execution.h" + +namespace mbf_abstract_nav +{ + +class RecoveryAction : public AbstractActionBase +{ + public: + + typedef boost::shared_ptr Ptr; + + RecoveryAction(const std::string &name, const mbf_utility::RobotInformation &robot_info); + + void run(GoalHandle &goal_handle, AbstractRecoveryExecution &execution); + +}; + +} /* mbf_abstract_nav */ + +#endif /* MBF_ABSTRACT_NAV__RECOVERY_ACTION_H_ */ diff --git a/navigations/move_base_flex/mbf_abstract_nav/package.xml b/navigations/move_base_flex/mbf_abstract_nav/package.xml new file mode 100755 index 0000000..ea91ea1 --- /dev/null +++ b/navigations/move_base_flex/mbf_abstract_nav/package.xml @@ -0,0 +1,46 @@ + + mbf_abstract_nav + 0.3.2 + + The mbf_abstract_nav package contains the abstract navigation server implementation of Move Base Flex (MBF). The abstract navigation server is not bound to any map representation. It provides the actions for planning, controlling and recovering. MBF loads all defined plugins at the program start. Therefor, it loads all plugins which are defined in the lists *planners*, *controllers* and *recovery_behaviors*. Each list holds a pair of a *name* and a *type*. The *type* defines which kind of plugin to load. The *name* defines under which name the plugin should be callable by the actions. + + http://wiki.ros.org/move_base_flex + Sebastian Pütz + Sebastian Pütz + Jorge Santos + BSD-3 + + catkin + + tf + roscpp + actionlib + actionlib_msgs + dynamic_reconfigure + std_msgs + std_srvs + nav_msgs + geometry_msgs + mbf_abstract_core + mbf_msgs + mbf_utility + xmlrpcpp + + tf + roscpp + actionlib + actionlib_msgs + dynamic_reconfigure + std_msgs + std_srvs + nav_msgs + geometry_msgs + mbf_abstract_core + mbf_msgs + mbf_utility + xmlrpcpp + + + + + diff --git a/navigations/move_base_flex/mbf_abstract_nav/rosdoc.yaml b/navigations/move_base_flex/mbf_abstract_nav/rosdoc.yaml new file mode 100755 index 0000000..772ff48 --- /dev/null +++ b/navigations/move_base_flex/mbf_abstract_nav/rosdoc.yaml @@ -0,0 +1,4 @@ + - builder: doxygen + name: Move Base Flex + homepage: http://wiki.ros.org/move_base_flex + file_patterns: '*.c *.cpp *.h *.cc *.hh *.py *.md' diff --git a/navigations/move_base_flex/mbf_abstract_nav/setup.py b/navigations/move_base_flex/mbf_abstract_nav/setup.py new file mode 100755 index 0000000..c21c6fe --- /dev/null +++ b/navigations/move_base_flex/mbf_abstract_nav/setup.py @@ -0,0 +1,10 @@ +#!/usr/bin/env python +from distutils.core import setup +from catkin_pkg.python_setup import generate_distutils_setup + +d = generate_distutils_setup( + packages = ['mbf_abstract_nav'], + package_dir = {'': 'src'}, +) + +setup(**d) diff --git a/navigations/move_base_flex/mbf_abstract_nav/src/abstract_controller_execution.cpp b/navigations/move_base_flex/mbf_abstract_nav/src/abstract_controller_execution.cpp new file mode 100755 index 0000000..9e2607a --- /dev/null +++ b/navigations/move_base_flex/mbf_abstract_nav/src/abstract_controller_execution.cpp @@ -0,0 +1,475 @@ +/* + * Copyright 2018, Magazino GmbH, Sebastian Pütz, Jorge Santos Simón + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * abstract_controller_execution.cpp + * + * authors: + * Sebastian Pütz + * Jorge Santos Simón + * + */ + +#include + +#include "mbf_abstract_nav/abstract_controller_execution.h" + +namespace mbf_abstract_nav +{ + +const double AbstractControllerExecution::DEFAULT_CONTROLLER_FREQUENCY = 100.0; // 100 Hz + +AbstractControllerExecution::AbstractControllerExecution( + const std::string &name, + const mbf_abstract_core::AbstractController::Ptr &controller_ptr, + const ros::Publisher &vel_pub, + const ros::Publisher &goal_pub, + const TFPtr &tf_listener_ptr, + const MoveBaseFlexConfig &config) : + AbstractExecutionBase(name), + controller_(controller_ptr), tf_listener_ptr(tf_listener_ptr), state_(INITIALIZED), + moving_(false), max_retries_(0), patience_(0), vel_pub_(vel_pub), current_goal_pub_(goal_pub), + calling_duration_(boost::chrono::microseconds(static_cast(1e6 / DEFAULT_CONTROLLER_FREQUENCY))) +{ + ros::NodeHandle nh; + ros::NodeHandle private_nh("~"); + + // non-dynamically reconfigurable parameters + private_nh.param("robot_frame", robot_frame_, std::string("base_link")); + private_nh.param("map_frame", global_frame_, std::string("map")); + private_nh.param("force_stop_at_goal", force_stop_at_goal_, false); + private_nh.param("force_stop_on_cancel", force_stop_on_cancel_, false); + private_nh.param("check_goal_reached", mbf_check_goal_reached_, false); + private_nh.param("dist_tolerance", dist_tolerance_, 0.1); + private_nh.param("angle_tolerance", angle_tolerance_, M_PI / 18.0); + private_nh.param("tf_timeout", tf_timeout_, 1.0); + + // dynamically reconfigurable parameters + reconfigure(config); +} + +AbstractControllerExecution::~AbstractControllerExecution() +{ +} + +bool AbstractControllerExecution::setControllerFrequency(double frequency) +{ + // set the calling duration by the moving frequency + if (frequency <= 0.0) + { + ROS_ERROR("Controller frequency must be greater than 0.0! No change of the frequency!"); + return false; + } + calling_duration_ = boost::chrono::microseconds(static_cast(1e6 / frequency)); + return true; +} + +void AbstractControllerExecution::reconfigure(const MoveBaseFlexConfig &config) +{ + boost::lock_guard guard(configuration_mutex_); + // Timeout granted to the controller. We keep calling it up to this time or up to max_retries times + // If it doesn't return within time, the navigator will cancel it and abort the corresponding action + patience_ = ros::Duration(config.controller_patience); + + setControllerFrequency(config.controller_frequency); + + max_retries_ = config.controller_max_retries; +} + + +bool AbstractControllerExecution::start() +{ + setState(STARTED); + if (moving_) + { + return false; // thread is already running. + } + moving_ = true; + return AbstractExecutionBase::start(); +} + + +void AbstractControllerExecution::setState(ControllerState state) +{ + boost::lock_guard guard(state_mtx_); + state_ = state; +} + + +typename AbstractControllerExecution::ControllerState +AbstractControllerExecution::getState() +{ + boost::lock_guard guard(state_mtx_); + return state_; +} + +void AbstractControllerExecution::setNewPlan( + const std::vector &plan, + bool tolerance_from_action, + double action_dist_tolerance, + double action_angle_tolerance) +{ + if (moving_) + { + // This is fine on continuous replanning + ROS_DEBUG("Setting new plan while moving"); + } + boost::lock_guard guard(plan_mtx_); + new_plan_ = true; + + plan_ = plan; + tolerance_from_action_ = tolerance_from_action; + action_dist_tolerance_ = action_dist_tolerance; + action_angle_tolerance_ = action_angle_tolerance; +} + + +bool AbstractControllerExecution::hasNewPlan() +{ + boost::lock_guard guard(plan_mtx_); + return new_plan_; +} + + +std::vector AbstractControllerExecution::getNewPlan() +{ + boost::lock_guard guard(plan_mtx_); + new_plan_ = false; + return plan_; +} + + +bool AbstractControllerExecution::computeRobotPose() +{ + if (!mbf_utility::getRobotPose(*tf_listener_ptr, robot_frame_, global_frame_, + ros::Duration(tf_timeout_), robot_pose_)) + { + ROS_ERROR_STREAM("Could not get the robot pose in the global frame. - robot frame: \"" + << robot_frame_ << "\" global frame: \"" << global_frame_); + message_ = "Could not get the robot pose"; + outcome_ = mbf_msgs::ExePathResult::TF_ERROR; + return false; + } + return true; +} + + +uint32_t AbstractControllerExecution::computeVelocityCmd(const geometry_msgs::PoseStamped &robot_pose, + const geometry_msgs::TwistStamped &robot_velocity, + geometry_msgs::TwistStamped &vel_cmd, + std::string &message) +{ + return controller_->computeVelocityCommands(robot_pose, robot_velocity, vel_cmd, message); +} + + +void AbstractControllerExecution::setVelocityCmd(const geometry_msgs::TwistStamped &vel_cmd) +{ + boost::lock_guard guard(vel_cmd_mtx_); + vel_cmd_stamped_ = vel_cmd; + if (vel_cmd_stamped_.header.stamp.isZero()) + vel_cmd_stamped_.header.stamp = ros::Time::now(); + // TODO what happen with frame id? + // TODO Add a queue here for handling the outcome, message and cmd_vel values bundled, + // TODO so there should be no loss of information in the feedback stream +} + + +geometry_msgs::TwistStamped AbstractControllerExecution::getVelocityCmd() +{ + boost::lock_guard guard(vel_cmd_mtx_); + return vel_cmd_stamped_; +} + + +ros::Time AbstractControllerExecution::getLastPluginCallTime() +{ + boost::lock_guard guard(lct_mtx_); + return last_call_time_; +} + + +bool AbstractControllerExecution::isPatienceExceeded() +{ + boost::lock_guard guard(lct_mtx_); + if(!patience_.isZero() && ros::Time::now() - start_time_ > patience_) // not zero -> activated, start_time handles init case + { + if(ros::Time::now() - last_call_time_ > patience_) + { + ROS_WARN_STREAM_THROTTLE(3, "The controller plugin \"" << name_ << "\" needs more time to compute in one run than the patience time!"); + return true; + } + if(ros::Time::now() - last_valid_cmd_time_ > patience_) + { + ROS_DEBUG_STREAM("The controller plugin \"" << name_ << "\" does not return a success state (outcome < 10) for more than the patience time in multiple runs!"); + return true; + } + } + return false; +} + + +bool AbstractControllerExecution::isMoving() +{ + return moving_; +} + +bool AbstractControllerExecution::reachedGoalCheck() +{ + // Use action-provided tolerances if requested, or use parameter values otherwise + double dist_tolerance = tolerance_from_action_ ? action_dist_tolerance_ : dist_tolerance_; + double angle_tolerance = tolerance_from_action_ ? action_angle_tolerance_ : angle_tolerance_; + + if (mbf_check_goal_reached_) + { + // MBF checks if we have reached the goal, or... + return mbf_utility::distance(robot_pose_, plan_.back()) < dist_tolerance && + mbf_utility::angle(robot_pose_, plan_.back()) < angle_tolerance; + } + // ...we let the controller decide + return controller_->isGoalReached(dist_tolerance, angle_tolerance); +} + +bool AbstractControllerExecution::cancel() +{ + // request the controller to cancel; it returns false if cancel is not implemented or rejected by the plugin + if (!controller_->cancel()) + { + ROS_WARN_STREAM("Cancel controlling failed. Wait until the current control cycle finished!"); + } + // then wait for the control cycle to stop (should happen immediately if the controller cancel returned true) + cancel_ = true; + if (waitForStateUpdate(boost::chrono::milliseconds(500)) == boost::cv_status::timeout) + { + // this situation should never happen; if it does, the action server will be unready for goals immediately sent + ROS_WARN_STREAM("Timeout while waiting for control cycle to stop; immediately sent goals can get stuck"); + return false; + } + return true; +} + + +void AbstractControllerExecution::run() +{ + start_time_ = ros::Time::now(); + + // init plan + std::vector plan; + if (!hasNewPlan()) + { + setState(NO_PLAN); + moving_ = false; + ROS_ERROR("robot navigation moving has no plan!"); + } + + last_valid_cmd_time_ = ros::Time(); + int retries = 0; + int seq = 0; + + try + { + while (moving_ && ros::ok()) + { + boost::chrono::thread_clock::time_point loop_start_time = boost::chrono::thread_clock::now(); + + if (cancel_) + { + if (force_stop_on_cancel_) + { + publishZeroVelocity(); // command the robot to stop on canceling navigation + } + setState(CANCELED); + condition_.notify_all(); + moving_ = false; + return; + } + + if (!safetyCheck()) + { + // the specific implementation must have detected a risk situation; at this abstract level, we + // cannot tell what the problem is, but anyway we command the robot to stop to avoid crashes + publishZeroVelocity(); // note that we still feedback command calculated by the plugin + boost::this_thread::sleep_for(calling_duration_); + } + + // update plan dynamically + if (hasNewPlan()) + { + plan = getNewPlan(); + + // check if plan is empty + if (plan.empty()) + { + setState(EMPTY_PLAN); + condition_.notify_all(); + moving_ = false; + return; + } + + // check if plan could be set + if (!controller_->setPlan(plan)) + { + setState(INVALID_PLAN); + condition_.notify_all(); + moving_ = false; + return; + } + current_goal_pub_.publish(plan.back()); + } + + // compute robot pose and store it in robot_pose_ + if (!computeRobotPose()) + { + publishZeroVelocity(); + setState(INTERNAL_ERROR); + condition_.notify_all(); + moving_ = false; + return; + } + + // ask planner if the goal is reached + if (reachedGoalCheck()) + { + ROS_DEBUG_STREAM_NAMED("abstract_controller_execution", "Reached the goal!"); + if (force_stop_at_goal_) + { + publishZeroVelocity(); + } + setState(ARRIVED_GOAL); + // goal reached, tell it the controller + condition_.notify_all(); + moving_ = false; + // if not, keep moving + } + else + { + setState(PLANNING); + + // save time and call the plugin + lct_mtx_.lock(); + last_call_time_ = ros::Time::now(); + lct_mtx_.unlock(); + + // call plugin to compute the next velocity command + geometry_msgs::TwistStamped cmd_vel_stamped; + geometry_msgs::TwistStamped robot_velocity; // TODO pass current velocity to the plugin! + outcome_ = computeVelocityCmd(robot_pose_, robot_velocity, cmd_vel_stamped, message_ = ""); + + if (outcome_ < 10) + { + setState(GOT_LOCAL_CMD); + vel_pub_.publish(cmd_vel_stamped.twist); + last_valid_cmd_time_ = ros::Time::now(); + retries = 0; + } + else + { + boost::lock_guard guard(configuration_mutex_); + if (max_retries_ >= 0 && ++retries > max_retries_) + { + setState(MAX_RETRIES); + moving_ = false; + } + else if (isPatienceExceeded()) + { + // patience limit enabled and running controller for more than patience without valid commands + setState(PAT_EXCEEDED); + moving_ = false; + } + else + { + setState(NO_LOCAL_CMD); // useful for server feedback + } + // could not compute a valid velocity command -> stop moving the robot + publishZeroVelocity(); // command the robot to stop; we still feedback command calculated by the plugin + } + + // set stamped values; timestamp and frame_id should be set by the plugin; otherwise setVelocityCmd will do + cmd_vel_stamped.header.seq = seq++; // sequence number + setVelocityCmd(cmd_vel_stamped); + condition_.notify_all(); + } + + boost::chrono::thread_clock::time_point end_time = boost::chrono::thread_clock::now(); + boost::chrono::microseconds execution_duration = + boost::chrono::duration_cast(end_time - loop_start_time); + configuration_mutex_.lock(); + boost::chrono::microseconds sleep_time = calling_duration_ - execution_duration; + configuration_mutex_.unlock(); + if (moving_ && ros::ok()) + { + if (sleep_time > boost::chrono::microseconds(0)) + { + // interruption point + boost::this_thread::sleep_for(sleep_time); + } + else + { + // provide an interruption point also with 0 or negative sleep_time + boost::this_thread::interruption_point(); + ROS_WARN_THROTTLE(1.0, "Calculation needs too much time to stay in the moving frequency! (%f > %f)", + execution_duration.count()/1000000.0, calling_duration_.count()/1000000.0); + } + } + } + } + catch (const boost::thread_interrupted &ex) + { + // Controller thread interrupted; in most cases we have started a new plan + // Can also be that robot is oscillating or we have exceeded planner patience + ROS_DEBUG_STREAM("Controller thread interrupted!"); + publishZeroVelocity(); + setState(STOPPED); + condition_.notify_all(); + moving_ = false; + } + catch (...) + { + message_ = "Unknown error occurred: " + boost::current_exception_diagnostic_information(); + ROS_FATAL_STREAM(message_); + setState(INTERNAL_ERROR); + } +} + + +void AbstractControllerExecution::publishZeroVelocity() +{ + geometry_msgs::Twist cmd_vel; + cmd_vel.linear.x = 0; + cmd_vel.linear.y = 0; + cmd_vel.linear.z = 0; + cmd_vel.angular.x = 0; + cmd_vel.angular.y = 0; + cmd_vel.angular.z = 0; + vel_pub_.publish(cmd_vel); +} + +} /* namespace mbf_abstract_nav */ diff --git a/navigations/move_base_flex/mbf_abstract_nav/src/abstract_execution_base.cpp b/navigations/move_base_flex/mbf_abstract_nav/src/abstract_execution_base.cpp new file mode 100755 index 0000000..18a9dbc --- /dev/null +++ b/navigations/move_base_flex/mbf_abstract_nav/src/abstract_execution_base.cpp @@ -0,0 +1,88 @@ +/* + * Copyright 2018, Sebastian Pütz + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * abstract_execution_base.cpp + * + * author: Sebastian Pütz + * + */ + +#include "mbf_abstract_nav/abstract_execution_base.h" + +namespace mbf_abstract_nav +{ + +AbstractExecutionBase::AbstractExecutionBase(std::string name) + : outcome_(255), cancel_(false), name_(name) +{ +} + +bool AbstractExecutionBase::start() +{ + thread_ = boost::thread(&AbstractExecutionBase::run, this); + return true; +} + +void AbstractExecutionBase::stop() +{ + ROS_WARN_STREAM("Try to stop the plugin \"" << name_ << "\" rigorously by interrupting the thread!"); + thread_.interrupt(); +} + +void AbstractExecutionBase::join(){ + if (thread_.joinable()) + thread_.join(); +} + +boost::cv_status AbstractExecutionBase::waitForStateUpdate(boost::chrono::microseconds const &duration) +{ + boost::mutex mutex; + boost::unique_lock lock(mutex); + return condition_.wait_for(lock, duration); +} + +uint32_t AbstractExecutionBase::getOutcome() +{ + return outcome_; +} + +std::string AbstractExecutionBase::getMessage() +{ + return message_; +} + +std::string AbstractExecutionBase::getName() +{ + return name_; +} + +} /* namespace mbf_abstract_nav */ diff --git a/navigations/move_base_flex/mbf_abstract_nav/src/abstract_navigation_server.cpp b/navigations/move_base_flex/mbf_abstract_nav/src/abstract_navigation_server.cpp new file mode 100755 index 0000000..a5cda16 --- /dev/null +++ b/navigations/move_base_flex/mbf_abstract_nav/src/abstract_navigation_server.cpp @@ -0,0 +1,382 @@ +/* + * Copyright 2018, Magazino GmbH, Sebastian Pütz, Jorge Santos Simón + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * abstract_navigation_server.cpp + * + * authors: + * Sebastian Pütz + * Jorge Santos Simón + * + */ + +#include + +#include "mbf_abstract_nav/abstract_navigation_server.h" + +namespace mbf_abstract_nav +{ + +AbstractNavigationServer::AbstractNavigationServer(const TFPtr &tf_listener_ptr) + : tf_listener_ptr_(tf_listener_ptr), private_nh_("~"), + planner_plugin_manager_("planners", + boost::bind(&AbstractNavigationServer::loadPlannerPlugin, this, _1), + boost::bind(&AbstractNavigationServer::initializePlannerPlugin, this, _1, _2)), + controller_plugin_manager_("controllers", + boost::bind(&AbstractNavigationServer::loadControllerPlugin, this, _1), + boost::bind(&AbstractNavigationServer::initializeControllerPlugin, this, _1, _2)), + recovery_plugin_manager_("recovery_behaviors", + boost::bind(&AbstractNavigationServer::loadRecoveryPlugin, this, _1), + boost::bind(&AbstractNavigationServer::initializeRecoveryPlugin, this, _1, _2)), + tf_timeout_(private_nh_.param("tf_timeout", 3.0)), + global_frame_(private_nh_.param("global_frame", "map")), + robot_frame_(private_nh_.param("robot_frame", "base_link")), + robot_info_(*tf_listener_ptr, global_frame_, robot_frame_, tf_timeout_), + controller_action_(name_action_exe_path, robot_info_), + planner_action_(name_action_get_path, robot_info_), + recovery_action_(name_action_recovery, robot_info_), + move_base_action_(name_action_move_base, robot_info_, recovery_plugin_manager_.getLoadedNames()) +{ + ros::NodeHandle nh; + + goal_pub_ = nh.advertise("current_goal", 1); + + // init cmd_vel publisher for the robot velocity + vel_pub_ = nh.advertise("cmd_vel", 1); + + action_server_get_path_ptr_ = ActionServerGetPathPtr( + new ActionServerGetPath( + private_nh_, + name_action_get_path, + boost::bind(&mbf_abstract_nav::AbstractNavigationServer::callActionGetPath, this, _1), + boost::bind(&mbf_abstract_nav::AbstractNavigationServer::cancelActionGetPath, this, _1), + false)); + + action_server_exe_path_ptr_ = ActionServerExePathPtr( + new ActionServerExePath( + private_nh_, + name_action_exe_path, + boost::bind(&mbf_abstract_nav::AbstractNavigationServer::callActionExePath, this, _1), + boost::bind(&mbf_abstract_nav::AbstractNavigationServer::cancelActionExePath, this, _1), + false)); + + action_server_recovery_ptr_ = ActionServerRecoveryPtr( + new ActionServerRecovery( + private_nh_, + name_action_recovery, + boost::bind(&mbf_abstract_nav::AbstractNavigationServer::callActionRecovery, this, _1), + boost::bind(&mbf_abstract_nav::AbstractNavigationServer::cancelActionRecovery, this, _1), + false)); + + action_server_move_base_ptr_ = ActionServerMoveBasePtr( + new ActionServerMoveBase( + private_nh_, + name_action_move_base, + boost::bind(&mbf_abstract_nav::AbstractNavigationServer::callActionMoveBase, this, _1), + boost::bind(&mbf_abstract_nav::AbstractNavigationServer::cancelActionMoveBase, this, _1), + false)); + + // XXX note that we don't start a dynamic reconfigure server, to avoid colliding with the one possibly created by + // the base class. If none, it should call startDynamicReconfigureServer method to start the one defined here for + // providing just the abstract server parameters +} + +void AbstractNavigationServer::initializeServerComponents() +{ + planner_plugin_manager_.loadPlugins(); + controller_plugin_manager_.loadPlugins(); + recovery_plugin_manager_.loadPlugins(); +} + +AbstractNavigationServer::~AbstractNavigationServer() +{ + +} + +void AbstractNavigationServer::callActionGetPath(ActionServerGetPath::GoalHandle goal_handle) +{ + const mbf_msgs::GetPathGoal &goal = *(goal_handle.getGoal().get()); + const geometry_msgs::Point &p = goal.target_pose.pose.position; + + std::string planner_name; + if(!planner_plugin_manager_.getLoadedNames().empty()) + { + planner_name = goal.planner.empty() ? planner_plugin_manager_.getLoadedNames().front() : goal.planner; + } + else + { + mbf_msgs::GetPathResult result; + result.outcome = mbf_msgs::GetPathResult::INVALID_PLUGIN; + result.message = "No plugins loaded at all!"; + ROS_WARN_STREAM_NAMED("get_path", result.message); + goal_handle.setRejected(result, result.message); + return; + } + + if(!planner_plugin_manager_.hasPlugin(planner_name)) + { + mbf_msgs::GetPathResult result; + result.outcome = mbf_msgs::GetPathResult::INVALID_PLUGIN; + result.message = "No plugin loaded with the given name \"" + goal.planner + "\"!"; + ROS_WARN_STREAM_NAMED("get_path", result.message); + goal_handle.setRejected(result, result.message); + return; + } + + mbf_abstract_core::AbstractPlanner::Ptr planner_plugin = planner_plugin_manager_.getPlugin(planner_name); + ROS_DEBUG_STREAM_NAMED("get_path", "Start action \"get_path\" using planner \"" << planner_name + << "\" of type \"" << planner_plugin_manager_.getType(planner_name) << "\""); + + + if(planner_plugin) + { + mbf_abstract_nav::AbstractPlannerExecution::Ptr planner_execution + = newPlannerExecution(planner_name, planner_plugin); + + //start another planning action + planner_action_.start(goal_handle, planner_execution); + } + else + { + mbf_msgs::GetPathResult result; + result.outcome = mbf_msgs::GetPathResult::INTERNAL_ERROR; + result.message = "Internal Error: \"planner_plugin\" pointer should not be a null pointer!"; + ROS_FATAL_STREAM_NAMED("get_path", result.message); + goal_handle.setRejected(result, result.message); + } +} + +void AbstractNavigationServer::cancelActionGetPath(ActionServerGetPath::GoalHandle goal_handle) +{ + ROS_INFO_STREAM_NAMED("get_path", "Cancel action \"get_path\""); + planner_action_.cancel(goal_handle); +} + +void AbstractNavigationServer::callActionExePath(ActionServerExePath::GoalHandle goal_handle) +{ + const mbf_msgs::ExePathGoal &goal = *(goal_handle.getGoal().get()); + + std::string controller_name; + if(!controller_plugin_manager_.getLoadedNames().empty()) + { + controller_name = goal.controller.empty() ? controller_plugin_manager_.getLoadedNames().front() : goal.controller; + } + else + { + mbf_msgs::ExePathResult result; + result.outcome = mbf_msgs::ExePathResult::INVALID_PLUGIN; + result.message = "No plugins loaded at all!"; + ROS_WARN_STREAM_NAMED("exe_path", result.message); + goal_handle.setRejected(result, result.message); + return; + } + + if(!controller_plugin_manager_.hasPlugin(controller_name)) + { + mbf_msgs::ExePathResult result; + result.outcome = mbf_msgs::ExePathResult::INVALID_PLUGIN; + result.message = "No plugin loaded with the given name \"" + goal.controller + "\"!"; + ROS_WARN_STREAM_NAMED("exe_path", result.message); + goal_handle.setRejected(result, result.message); + return; + } + + mbf_abstract_core::AbstractController::Ptr controller_plugin = controller_plugin_manager_.getPlugin(controller_name); + ROS_DEBUG_STREAM_NAMED("exe_path", "Start action \"exe_path\" using controller \"" << controller_name + << "\" of type \"" << controller_plugin_manager_.getType(controller_name) << "\""); + + + if(controller_plugin) + { + mbf_abstract_nav::AbstractControllerExecution::Ptr controller_execution + = newControllerExecution(controller_name, controller_plugin); + + // starts another controller action + controller_action_.start(goal_handle, controller_execution); + } + else + { + mbf_msgs::ExePathResult result; + result.outcome = mbf_msgs::ExePathResult::INTERNAL_ERROR; + result.message = "Internal Error: \"controller_plugin\" pointer should not be a null pointer!"; + ROS_FATAL_STREAM_NAMED("exe_path", result.message); + goal_handle.setRejected(result, result.message); + } +} + +void AbstractNavigationServer::cancelActionExePath(ActionServerExePath::GoalHandle goal_handle) +{ + ROS_INFO_STREAM_NAMED("exe_path", "Cancel action \"exe_path\""); + controller_action_.cancel(goal_handle); +} + +void AbstractNavigationServer::callActionRecovery(ActionServerRecovery::GoalHandle goal_handle) +{ + const mbf_msgs::RecoveryGoal &goal = *(goal_handle.getGoal().get()); + + std::string recovery_name; + + if(!recovery_plugin_manager_.getLoadedNames().empty()) + { + recovery_name = goal.behavior.empty() ? recovery_plugin_manager_.getLoadedNames().front() : goal.behavior; + } + else + { + mbf_msgs::RecoveryResult result; + result.outcome = mbf_msgs::RecoveryResult::INVALID_PLUGIN; + result.message = "No plugins loaded at all!"; + ROS_WARN_STREAM_NAMED("recovery", result.message); + goal_handle.setRejected(result, result.message); + return; + } + + if(!recovery_plugin_manager_.hasPlugin(recovery_name)) + { + mbf_msgs::RecoveryResult result; + result.outcome = mbf_msgs::RecoveryResult::INVALID_PLUGIN; + result.message = "No plugin loaded with the given name \"" + goal.behavior + "\"!"; + ROS_WARN_STREAM_NAMED("recovery", result.message); + goal_handle.setRejected(result, result.message); + return; + } + + mbf_abstract_core::AbstractRecovery::Ptr recovery_plugin = recovery_plugin_manager_.getPlugin(recovery_name); + ROS_DEBUG_STREAM_NAMED("recovery", "Start action \"recovery\" using recovery \"" << recovery_name + << "\" of type \"" << recovery_plugin_manager_.getType(recovery_name) << "\""); + + + if(recovery_plugin) + { + mbf_abstract_nav::AbstractRecoveryExecution::Ptr recovery_execution + = newRecoveryExecution(recovery_name, recovery_plugin); + + recovery_action_.start(goal_handle, recovery_execution); + } + else + { + mbf_msgs::RecoveryResult result; + result.outcome = mbf_msgs::RecoveryResult::INTERNAL_ERROR; + result.message = "Internal Error: \"recovery_plugin\" pointer should not be a null pointer!"; + ROS_FATAL_STREAM_NAMED("recovery", result.message); + goal_handle.setRejected(result, result.message); + } +} + +void AbstractNavigationServer::cancelActionRecovery(ActionServerRecovery::GoalHandle goal_handle) +{ + ROS_INFO_STREAM_NAMED("recovery", "Cancel action \"recovery\""); + recovery_action_.cancel(goal_handle); +} + +void AbstractNavigationServer::callActionMoveBase(ActionServerMoveBase::GoalHandle goal_handle) +{ + ROS_DEBUG_STREAM_NAMED("move_base", "Start action \"move_base\""); + move_base_action_.start(goal_handle); +} + +void AbstractNavigationServer::cancelActionMoveBase(ActionServerMoveBase::GoalHandle goal_handle) +{ + ROS_INFO_STREAM_NAMED("move_base", "Cancel action \"move_base\""); + move_base_action_.cancel(); +} + +mbf_abstract_nav::AbstractPlannerExecution::Ptr AbstractNavigationServer::newPlannerExecution( + const std::string &plugin_name, + const mbf_abstract_core::AbstractPlanner::Ptr &plugin_ptr) +{ + return boost::make_shared(plugin_name, plugin_ptr, last_config_); +} + +mbf_abstract_nav::AbstractControllerExecution::Ptr AbstractNavigationServer::newControllerExecution( + const std::string &plugin_name, + const mbf_abstract_core::AbstractController::Ptr &plugin_ptr) +{ + return boost::make_shared(plugin_name, plugin_ptr, vel_pub_, goal_pub_, + tf_listener_ptr_, last_config_); +} + +mbf_abstract_nav::AbstractRecoveryExecution::Ptr AbstractNavigationServer::newRecoveryExecution( + const std::string &plugin_name, + const mbf_abstract_core::AbstractRecovery::Ptr &plugin_ptr) +{ + return boost::make_shared(plugin_name, plugin_ptr, + tf_listener_ptr_, last_config_); +} + +void AbstractNavigationServer::startActionServers() +{ + action_server_get_path_ptr_->start(); + action_server_exe_path_ptr_->start(); + action_server_recovery_ptr_->start(); + action_server_move_base_ptr_->start(); +} + +void AbstractNavigationServer::startDynamicReconfigureServer() +{ + // dynamic reconfigure server + dsrv_ = boost::make_shared >(private_nh_); + dsrv_->setCallback(boost::bind(&AbstractNavigationServer::reconfigure, this, _1, _2)); +} + +void AbstractNavigationServer::reconfigure( + mbf_abstract_nav::MoveBaseFlexConfig &config, uint32_t level) +{ + boost::lock_guard guard(configuration_mutex_); + + // Make sure we have the original configuration the first time we're called, so we can restore it if needed + if (!setup_reconfigure_) + { + default_config_ = config; + setup_reconfigure_ = true; + } + + if (config.restore_defaults) + { + config = default_config_; + // if someone sets restore defaults on the parameter server, prevent looping + config.restore_defaults = false; + } + planner_action_.reconfigureAll(config, level); + controller_action_.reconfigureAll(config, level); + recovery_action_.reconfigureAll(config, level); + move_base_action_.reconfigure(config, level); + + last_config_ = config; +} + +void AbstractNavigationServer::stop(){ + planner_action_.cancelAll(); + controller_action_.cancelAll(); + recovery_action_.cancelAll(); + move_base_action_.cancel(); +} + +} /* namespace mbf_abstract_nav */ diff --git a/navigations/move_base_flex/mbf_abstract_nav/src/abstract_planner_execution.cpp b/navigations/move_base_flex/mbf_abstract_nav/src/abstract_planner_execution.cpp new file mode 100755 index 0000000..1c2e094 --- /dev/null +++ b/navigations/move_base_flex/mbf_abstract_nav/src/abstract_planner_execution.cpp @@ -0,0 +1,358 @@ +/* + * Copyright 2018, Magazino GmbH, Sebastian Pütz, Jorge Santos Simón + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * abstract_planner_execution.cpp + * + * authors: + * Sebastian Pütz + * Jorge Santos Simón + * + */ + +#include "mbf_abstract_nav/abstract_planner_execution.h" + +namespace mbf_abstract_nav +{ + +AbstractPlannerExecution::AbstractPlannerExecution( + const std::string &name, + const mbf_abstract_core::AbstractPlanner::Ptr &planner_ptr, + const MoveBaseFlexConfig &config) : + AbstractExecutionBase(name), + planner_(planner_ptr), state_(INITIALIZED), planning_(false), + has_new_start_(false), has_new_goal_(false) +{ + ros::NodeHandle private_nh("~"); + + // non-dynamically reconfigurable parameters + private_nh.param("robot_frame", robot_frame_, std::string("base_footprint")); + private_nh.param("map_frame", global_frame_, std::string("map")); + + // dynamically reconfigurable parameters + reconfigure(config); +} + +AbstractPlannerExecution::~AbstractPlannerExecution() +{ +} + + +double AbstractPlannerExecution::getCost() const +{ + boost::lock_guard guard(plan_mtx_); + // copy plan and costs to output + // if the planner plugin do not compute costs compute costs by discrete path length + if(cost_ == 0 && !plan_.empty()) + { + ROS_DEBUG_STREAM("Compute costs by discrete path length!"); + double cost = 0; + + geometry_msgs::PoseStamped prev_pose = plan_.front(); + for(std::vector::const_iterator iter = plan_.begin() + 1; iter != plan_.end(); ++iter) + { + cost += mbf_utility::distance(prev_pose, *iter); + prev_pose = *iter; + } + return cost; + } + return cost_; +} + +void AbstractPlannerExecution::reconfigure(const MoveBaseFlexConfig &config) +{ + boost::lock_guard guard(configuration_mutex_); + + max_retries_ = config.planner_max_retries; + frequency_ = config.planner_frequency; + + // Timeout granted to the global planner. We keep calling it up to this time or up to max_retries times + // If it doesn't return within time, the navigator will cancel it and abort the corresponding action + patience_ = ros::Duration(config.planner_patience); +} + + +typename AbstractPlannerExecution::PlanningState AbstractPlannerExecution::getState() const +{ + boost::lock_guard guard(state_mtx_); + return state_; +} + +void AbstractPlannerExecution::setState(PlanningState state, bool signalling) +{ + boost::lock_guard guard(state_mtx_); + state_ = state; + + // some states are quiet, most aren't + if(signalling) + condition_.notify_all(); +} + + +ros::Time AbstractPlannerExecution::getLastValidPlanTime() const +{ + boost::lock_guard guard(plan_mtx_); + return last_valid_plan_time_; +} + + +bool AbstractPlannerExecution::isPatienceExceeded() const +{ + return !patience_.isZero() && (ros::Time::now() - last_call_start_time_ > patience_); +} + + +std::vector AbstractPlannerExecution::getPlan() const +{ + boost::lock_guard guard(plan_mtx_); + // copy plan and costs to output + return plan_; +} + + +void AbstractPlannerExecution::setNewGoal(const geometry_msgs::PoseStamped &goal, + double dist_tolerance, double angle_tolerance) +{ + boost::lock_guard guard(goal_start_mtx_); + goal_ = goal; + dist_tolerance_ = dist_tolerance; + angle_tolerance_ = angle_tolerance; + has_new_goal_ = true; +} + + +void AbstractPlannerExecution::setNewStart(const geometry_msgs::PoseStamped &start) +{ + boost::lock_guard guard(goal_start_mtx_); + start_ = start; + has_new_start_ = true; +} + + +void AbstractPlannerExecution::setNewStartAndGoal(const geometry_msgs::PoseStamped &start, + const geometry_msgs::PoseStamped &goal, + double dist_tolerance, double angle_tolerance) +{ + boost::lock_guard guard(goal_start_mtx_); + start_ = start; + goal_ = goal; + dist_tolerance_ = dist_tolerance; + angle_tolerance_ = angle_tolerance; + has_new_start_ = true; + has_new_goal_ = true; +} + + +bool AbstractPlannerExecution::start(const geometry_msgs::PoseStamped &start, + const geometry_msgs::PoseStamped &goal, + double dist_tolerance, double angle_tolerance) +{ + if (planning_) + { + return false; + } + boost::lock_guard guard(planning_mtx_); + planning_ = true; + start_ = start; + goal_ = goal; + dist_tolerance_ = dist_tolerance; + angle_tolerance_ = angle_tolerance; + + const geometry_msgs::Point& s = start.pose.position; + const geometry_msgs::Point& g = goal.pose.position; + + ROS_DEBUG_STREAM("Start planning from the start pose: (" << s.x << ", " << s.y << ", " << s.z << ")" + << " to the goal pose: ("<< g.x << ", " << g.y << ", " << g.z << ")"); + + return AbstractExecutionBase::start(); +} + + +bool AbstractPlannerExecution::cancel() +{ + cancel_ = true; // force cancel immediately, as the call to cancel in the planner can take a while + + // returns false if cancel is not implemented or rejected by the planner (will run until completion) + if (!planner_->cancel()) + { + ROS_WARN_STREAM("Cancel planning failed or is not supported by the plugin. " + << "Wait until the current planning finished!"); + + return false; + } + return true; +} + +uint32_t AbstractPlannerExecution::makePlan(const geometry_msgs::PoseStamped &start, + const geometry_msgs::PoseStamped &goal, + double dist_tolerance, double angle_tolerance, + std::vector &plan, + double &cost, + std::string &message) +{ + return planner_->makePlan(start, goal, dist_tolerance, angle_tolerance, plan, cost, message); +} + +void AbstractPlannerExecution::run() +{ + setState(STARTED, false); + boost::lock_guard guard(planning_mtx_); + int retries = 0; + geometry_msgs::PoseStamped current_start = start_; + geometry_msgs::PoseStamped current_goal = goal_; + + bool success = false; + bool make_plan = false; + bool exceeded = false; + + last_call_start_time_ = ros::Time::now(); + last_valid_plan_time_ = ros::Time::now(); + + try + { + while (planning_ && ros::ok()) + { + boost::chrono::thread_clock::time_point start_time = boost::chrono::thread_clock::now(); + + // call the planner + std::vector plan; + double cost; + + // lock goal start mutex + goal_start_mtx_.lock(); + if (has_new_start_) + { + has_new_start_ = false; + current_start = start_; + ROS_INFO_STREAM("A new start pose is available. Planning with the new start pose!"); + exceeded = false; + const geometry_msgs::Point& s = start_.pose.position; + ROS_INFO_STREAM("New planning start pose: (" << s.x << ", " << s.y << ", " << s.z << ")"); + } + if (has_new_goal_) + { + has_new_goal_ = false; + current_goal = goal_; + ROS_INFO_STREAM("A new goal pose is available. Planning with the new goal pose and tolerances: " + << dist_tolerance_ << " m, " << angle_tolerance_ << " rad"); + exceeded = false; + const geometry_msgs::Point& g = goal_.pose.position; + ROS_INFO_STREAM("New goal pose: (" << g.x << ", " << g.y << ", " << g.z << ")"); + } + + make_plan = !(success || exceeded) || has_new_start_ || has_new_goal_; + + // unlock goal + goal_start_mtx_.unlock(); + setState(PLANNING, false); + if (make_plan) + { + outcome_ = makePlan(current_start, current_goal, dist_tolerance_, angle_tolerance_, plan, cost, message_); + success = outcome_ < 10; + + boost::lock_guard guard(configuration_mutex_); + + if (cancel_ && !isPatienceExceeded()) + { + ROS_INFO_STREAM("The planner \"" << name_ << "\" has been canceled!"); // but not due to patience exceeded + planning_ = false; + setState(CANCELED, true); + } + else if (success) + { + ROS_DEBUG_STREAM("Successfully found a plan."); + exceeded = false; + planning_ = false; + + plan_mtx_.lock(); + plan_ = plan; + // todo compute the cost once! + cost_ = cost; + last_valid_plan_time_ = ros::Time::now(); + plan_mtx_.unlock(); + setState(FOUND_PLAN, true); + } + else if (max_retries_ >= 0 && ++retries > max_retries_) + { + ROS_INFO_STREAM("Planning reached max retries! (" << max_retries_ << ")"); + exceeded = true; + planning_ = false; + setState(MAX_RETRIES, true); + } + else if (isPatienceExceeded()) + { + // Patience exceeded is handled at two levels: here to stop retrying planning when max_retries is + // disabled, and on the navigation server when the planner doesn't return for more that patience seconds. + // In the second case, the navigation server has tried to cancel planning (possibly without success, as + // old nav_core-based planners do not support canceling), and we add here the fact to the log for info + ROS_INFO_STREAM("Planning patience (" << patience_.toSec() << "s) has been exceeded" + << (cancel_ ? "; planner canceled!" : "")); + exceeded = true; + planning_ = false; + setState(PAT_EXCEEDED, true); + } + else if (max_retries_ == 0 && patience_.isZero()) + { + ROS_INFO_STREAM("Planning could not find a plan!"); + exceeded = true; + planning_ = false; + setState(NO_PLAN_FOUND, true); + } + else + { + exceeded = false; + ROS_DEBUG_STREAM("Planning could not find a plan! Trying again..."); + } + } + else if (cancel_) + { + ROS_INFO_STREAM("The global planner has been canceled!"); + planning_ = false; + setState(CANCELED, true); + } + } // while (planning_ && ros::ok()) + } + catch (const boost::thread_interrupted &ex) + { + // Planner thread interrupted; probably we have exceeded planner patience + ROS_WARN_STREAM("Planner thread interrupted!"); + planning_ = false; + setState(STOPPED, true); + } + catch (...) + { + ROS_FATAL_STREAM("Unknown error occurred: " << boost::current_exception_diagnostic_information()); + setState(INTERNAL_ERROR, true); + } +} + +} /* namespace mbf_abstract_nav */ + diff --git a/navigations/move_base_flex/mbf_abstract_nav/src/abstract_recovery_execution.cpp b/navigations/move_base_flex/mbf_abstract_nav/src/abstract_recovery_execution.cpp new file mode 100755 index 0000000..8ae8a34 --- /dev/null +++ b/navigations/move_base_flex/mbf_abstract_nav/src/abstract_recovery_execution.cpp @@ -0,0 +1,144 @@ +/* + * Copyright 2018, Magazino GmbH, Sebastian Pütz, Jorge Santos Simón + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * abstract_recovery_execution.cpp + * + * authors: + * Sebastian Pütz + * Jorge Santos Simón + * + */ + +#include + +#include + +namespace mbf_abstract_nav +{ + +AbstractRecoveryExecution::AbstractRecoveryExecution( + const std::string &name, + const mbf_abstract_core::AbstractRecovery::Ptr &recovery_ptr, + const TFPtr &tf_listener_ptr, + const MoveBaseFlexConfig &config) : + AbstractExecutionBase(name), + behavior_(recovery_ptr), tf_listener_ptr_(tf_listener_ptr), state_(INITIALIZED) +{ + // dynamically reconfigurable parameters + reconfigure(config); +} + +AbstractRecoveryExecution::~AbstractRecoveryExecution() +{ +} + + +void AbstractRecoveryExecution::reconfigure(const MoveBaseFlexConfig &config) +{ + boost::lock_guard guard(conf_mtx_); + + // Maximum time allowed to recovery behaviors. Intended as a safeward for the case a behavior hangs. + // If it doesn't return within time, the navigator will cancel it and abort the corresponding action. + patience_ = ros::Duration(config.recovery_patience); + + // Nothing else to do here, as recovery_enabled is loaded and used in the navigation server +} + + +void AbstractRecoveryExecution::setState(RecoveryState state) +{ + boost::lock_guard guard(state_mtx_); + state_ = state; +} + + +typename AbstractRecoveryExecution::RecoveryState AbstractRecoveryExecution::getState() +{ + boost::lock_guard guard(state_mtx_); + return state_; +} + +bool AbstractRecoveryExecution::cancel() +{ + cancel_ = true; + // returns false if cancel is not implemented or rejected by the recovery behavior (will run until completion) + if (!behavior_->cancel()) + { + ROS_WARN_STREAM("Cancel recovery behavior \"" << name_ << "\" failed or is not supported by the plugin. " + << "Wait until the current recovery behavior finished!"); + return false; + } + return true; +} + +bool AbstractRecoveryExecution::isPatienceExceeded() +{ + boost::lock_guard guard1(conf_mtx_); + boost::lock_guard guard2(time_mtx_); + ROS_DEBUG_STREAM("Patience: " << patience_ << ", start time: " << start_time_ << " now: " << ros::Time::now()); + return !patience_.isZero() && (ros::Time::now() - start_time_ > patience_); +} + +void AbstractRecoveryExecution::run() +{ + cancel_ = false; // reset the canceled state + + time_mtx_.lock(); + start_time_ = ros::Time::now(); + time_mtx_.unlock(); + setState(RECOVERING); + try + { + outcome_ = behavior_->runBehavior(message_); + if (cancel_) + { + setState(CANCELED); + } + else + { + setState(RECOVERY_DONE); + } + } + catch (boost::thread_interrupted &ex) + { + ROS_WARN_STREAM("Recovery \"" << name_ << "\" interrupted!"); + setState(STOPPED); + } + catch (...) + { + ROS_FATAL_STREAM("Unknown error occurred in recovery behavior \"" << name_ << "\": " << boost::current_exception_diagnostic_information()); + setState(INTERNAL_ERROR); + } + condition_.notify_one(); +} + +} /* namespace mbf_abstract_nav */ diff --git a/navigations/move_base_flex/mbf_abstract_nav/src/controller_action.cpp b/navigations/move_base_flex/mbf_abstract_nav/src/controller_action.cpp new file mode 100755 index 0000000..780115d --- /dev/null +++ b/navigations/move_base_flex/mbf_abstract_nav/src/controller_action.cpp @@ -0,0 +1,364 @@ +/* + * Copyright 2018, Magazino GmbH, Sebastian Pütz, Jorge Santos Simón + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * controller_action.cpp + * + * authors: + * Sebastian Pütz + * Jorge Santos Simón + * + */ + +#include "mbf_abstract_nav/controller_action.h" + +namespace mbf_abstract_nav +{ + +ControllerAction::ControllerAction( + const std::string &action_name, + const mbf_utility::RobotInformation &robot_info) + : AbstractActionBase(action_name, robot_info, boost::bind(&mbf_abstract_nav::ControllerAction::run, this, _1, _2)) +{ +} + +void ControllerAction::start( + GoalHandle &goal_handle, + typename AbstractControllerExecution::Ptr execution_ptr +) +{ + if(goal_handle.getGoalStatus().status == actionlib_msgs::GoalStatus::RECALLING) + { + goal_handle.setCanceled(); + return; + } + + uint8_t slot = goal_handle.getGoal()->concurrency_slot; + + bool update_plan = false; + slot_map_mtx_.lock(); + std::map::iterator slot_it = concurrency_slots_.find(slot); + if(slot_it != concurrency_slots_.end() && slot_it->second.in_use) + { + boost::lock_guard goal_guard(goal_mtx_); + if(slot_it->second.execution->getName() == goal_handle.getGoal()->controller || + goal_handle.getGoal()->controller.empty()) + { + update_plan = true; + // Goal requests to run the same controller on the same concurrency slot already in use: + // we update the goal handle and pass the new plan and tolerances from the action to the + // execution without stopping it + execution_ptr = slot_it->second.execution; + execution_ptr->setNewPlan(goal_handle.getGoal()->path.poses, + goal_handle.getGoal()->tolerance_from_action, + goal_handle.getGoal()->dist_tolerance, + goal_handle.getGoal()->angle_tolerance); + // Update also goal pose, so the feedback remains consistent + goal_pose_ = goal_handle.getGoal()->path.poses.back(); + mbf_msgs::ExePathResult result; + fillExePathResult(mbf_msgs::ExePathResult::CANCELED, "Goal preempted by a new plan", result); + concurrency_slots_[slot].goal_handle.setCanceled(result, result.message); + concurrency_slots_[slot].goal_handle = goal_handle; + concurrency_slots_[slot].goal_handle.setAccepted(); + } + } + slot_map_mtx_.unlock(); + if(!update_plan) + { + // Otherwise run parent version of this method + AbstractActionBase::start(goal_handle, execution_ptr); + } +} + +void ControllerAction::run(GoalHandle &goal_handle, AbstractControllerExecution &execution) +{ + goal_mtx_.lock(); + // Note that we always use the goal handle stored on the concurrency slots map, as it can change when replanning + uint8_t slot = goal_handle.getGoal()->concurrency_slot; + goal_mtx_.unlock(); + + ROS_DEBUG_STREAM_NAMED(name_, "Start action " << name_); + + // ensure we don't provide values from previous execution on case of error before filling both poses + goal_pose_ = geometry_msgs::PoseStamped(); + robot_pose_ = geometry_msgs::PoseStamped(); + + ros::NodeHandle private_nh("~"); + + double oscillation_timeout_tmp; + private_nh.param("oscillation_timeout", oscillation_timeout_tmp, 0.0); + ros::Duration oscillation_timeout(oscillation_timeout_tmp); + + double oscillation_distance; + private_nh.param("oscillation_distance", oscillation_distance, 0.03); + + mbf_msgs::ExePathResult result; + mbf_msgs::ExePathFeedback feedback; + + typename AbstractControllerExecution::ControllerState state_moving_input; + bool controller_active = true; + + goal_mtx_.lock(); + const mbf_msgs::ExePathGoal &goal = *(goal_handle.getGoal().get()); + + const std::vector &plan = goal.path.poses; + if (plan.empty()) + { + fillExePathResult(mbf_msgs::ExePathResult::INVALID_PATH, "Controller started with an empty plan!", result); + goal_handle.setAborted(result, result.message); + ROS_ERROR_STREAM_NAMED(name_, result.message << " Canceling the action call."); + controller_active = false; + goal_mtx_.unlock(); + return; + } + + goal_pose_ = plan.back(); + ROS_DEBUG_STREAM_NAMED(name_, "Called action \"" + << name_ << "\" with plan:" << std::endl + << "frame: \"" << goal.path.header.frame_id << "\" " << std::endl + << "stamp: " << goal.path.header.stamp << std::endl + << "poses: " << goal.path.poses.size() << std::endl + << "goal: (" << goal_pose_.pose.position.x << ", " + << goal_pose_.pose.position.y << ", " + << goal_pose_.pose.position.z << ")"); + + goal_mtx_.unlock(); + + + geometry_msgs::PoseStamped oscillation_pose; + ros::Time last_oscillation_reset = ros::Time::now(); + + bool first_cycle = true; + + while (controller_active && ros::ok()) + { + // goal_handle could change between the loop cycles due to adapting the plan + // with a new goal received for the same concurrency slot + if (!robot_info_.getRobotPose(robot_pose_)) + { + controller_active = false; + fillExePathResult(mbf_msgs::ExePathResult::TF_ERROR, "Could not get the robot pose!", result); + goal_mtx_.lock(); + goal_handle.setAborted(result, result.message); + goal_mtx_.unlock(); + ROS_ERROR_STREAM_NAMED(name_, result.message << " Canceling the action call."); + break; + } + + if (first_cycle) + { + // init oscillation pose + oscillation_pose = robot_pose_; + } + + goal_mtx_.lock(); + state_moving_input = execution.getState(); + + switch (state_moving_input) + { + case AbstractControllerExecution::INITIALIZED: + execution.setNewPlan(plan, goal.tolerance_from_action, goal.dist_tolerance, goal.angle_tolerance); + execution.start(); + break; + + case AbstractControllerExecution::STOPPED: + ROS_WARN_STREAM_NAMED(name_, "The controller has been stopped rigorously!"); + controller_active = false; + result.outcome = mbf_msgs::ExePathResult::STOPPED; + result.message = "Controller has been stopped!"; + goal_handle.setAborted(result, result.message); + break; + + case AbstractControllerExecution::CANCELED: + ROS_INFO_STREAM("Action \"exe_path\" canceled"); + fillExePathResult(mbf_msgs::ExePathResult::CANCELED, "Controller canceled", result); + goal_handle.setCanceled(result, result.message); + controller_active = false; + break; + + case AbstractControllerExecution::STARTED: + ROS_DEBUG_STREAM_NAMED(name_, "The moving has been started!"); + break; + + case AbstractControllerExecution::PLANNING: + if (execution.isPatienceExceeded()) + { + ROS_INFO_STREAM("Try to cancel the plugin \"" << name_ << "\" after the patience time has been exceeded!"); + if (execution.cancel()) + { + ROS_INFO_STREAM("Successfully canceled the plugin \"" << name_ << "\" after the patience time has been exceeded!"); + } + } + break; + + case AbstractControllerExecution::MAX_RETRIES: + ROS_WARN_STREAM_NAMED(name_, "The controller has been aborted after it exceeded the maximum number of retries!"); + controller_active = false; + fillExePathResult(execution.getOutcome(), execution.getMessage(), result); + goal_handle.setAborted(result, result.message); + break; + + case AbstractControllerExecution::PAT_EXCEEDED: + ROS_WARN_STREAM_NAMED(name_, "The controller has been aborted after it exceeded the patience time"); + controller_active = false; + fillExePathResult(mbf_msgs::ExePathResult::PAT_EXCEEDED, execution.getMessage(), result); + goal_handle.setAborted(result, result.message); + break; + + case AbstractControllerExecution::NO_PLAN: + ROS_WARN_STREAM_NAMED(name_, "The controller has been started without a plan!"); + controller_active = false; + fillExePathResult(mbf_msgs::ExePathResult::INVALID_PATH, "Controller started without a path", result); + goal_handle.setAborted(result, result.message); + break; + + case AbstractControllerExecution::EMPTY_PLAN: + ROS_WARN_STREAM_NAMED(name_, "The controller has received an empty plan"); + controller_active = false; + fillExePathResult(mbf_msgs::ExePathResult::INVALID_PATH, "Controller started with an empty plan", result); + goal_handle.setAborted(result, result.message); + break; + + case AbstractControllerExecution::INVALID_PLAN: + ROS_WARN_STREAM_NAMED(name_, "The controller has received an invalid plan"); + controller_active = false; + fillExePathResult(mbf_msgs::ExePathResult::INVALID_PATH, "Controller started with an invalid plan", result); + goal_handle.setAborted(result, result.message); + break; + + case AbstractControllerExecution::NO_LOCAL_CMD: + ROS_WARN_STREAM_THROTTLE_NAMED(3, name_, "No velocity command received from controller! " + << execution.getMessage()); + publishExePathFeedback(goal_handle, execution.getOutcome(), execution.getMessage(), execution.getVelocityCmd()); + break; + + case AbstractControllerExecution::GOT_LOCAL_CMD: + if (!oscillation_timeout.isZero()) + { + // check if oscillating + if (mbf_utility::distance(robot_pose_, oscillation_pose) >= oscillation_distance) + { + last_oscillation_reset = ros::Time::now(); + oscillation_pose = robot_pose_; + } + else if (last_oscillation_reset + oscillation_timeout < ros::Time::now()) + { + ROS_WARN_STREAM_NAMED(name_, "The controller is oscillating for " + << (ros::Time::now() - last_oscillation_reset).toSec() << "s"); + + execution.cancel(); + controller_active = false; + fillExePathResult(mbf_msgs::ExePathResult::OSCILLATION, "Oscillation detected!", result); + goal_handle.setAborted(result, result.message); + break; + } + } + publishExePathFeedback(goal_handle, execution.getOutcome(), execution.getMessage(), execution.getVelocityCmd()); + break; + + case AbstractControllerExecution::ARRIVED_GOAL: + ROS_DEBUG_STREAM_NAMED(name_, "Controller succeeded; arrived at goal"); + controller_active = false; + fillExePathResult(mbf_msgs::ExePathResult::SUCCESS, "Controller succeeded; arrived at goal!", result); + goal_handle.setSucceeded(result, result.message); + break; + + case AbstractControllerExecution::INTERNAL_ERROR: + ROS_FATAL_STREAM_NAMED(name_, "Internal error: Unknown error thrown by the plugin: " << execution.getMessage()); + controller_active = false; + fillExePathResult(mbf_msgs::ExePathResult::INTERNAL_ERROR, "Internal error: Unknown error thrown by the plugin!", result); + goal_handle.setAborted(result, result.message); + break; + + default: + std::stringstream ss; + ss << "Internal error: Unknown state in a move base flex controller execution with the number: " + << static_cast(state_moving_input); + fillExePathResult(mbf_msgs::ExePathResult::INTERNAL_ERROR, ss.str(), result); + ROS_FATAL_STREAM_NAMED(name_, result.message); + goal_handle.setAborted(result, result.message); + controller_active = false; + } + goal_mtx_.unlock(); + + if (controller_active) + { + // try to sleep a bit + // normally this thread should be woken up from the controller execution thread + // in order to transfer the results to the controller + execution.waitForStateUpdate(boost::chrono::milliseconds(500)); + } + + first_cycle = false; + } // while (controller_active && ros::ok()) + + if (!controller_active) + { + ROS_DEBUG_STREAM_NAMED(name_, "\"" << name_ << "\" action ended properly."); + } + else + { + // normal on continuous replanning + ROS_DEBUG_STREAM_NAMED(name_, "\"" << name_ << "\" action has been stopped!"); + } +} + +void ControllerAction::publishExePathFeedback( + GoalHandle &goal_handle, + uint32_t outcome, const std::string &message, + const geometry_msgs::TwistStamped ¤t_twist) +{ + mbf_msgs::ExePathFeedback feedback; + feedback.outcome = outcome; + feedback.message = message; + + feedback.last_cmd_vel = current_twist; + if (feedback.last_cmd_vel.header.stamp.isZero()) + feedback.last_cmd_vel.header.stamp = ros::Time::now(); + + feedback.current_pose = robot_pose_; + feedback.dist_to_goal = static_cast(mbf_utility::distance(robot_pose_, goal_pose_)); + feedback.angle_to_goal = static_cast(mbf_utility::angle(robot_pose_, goal_pose_)); + goal_handle.publishFeedback(feedback); +} + +void ControllerAction::fillExePathResult( + uint32_t outcome, const std::string &message, + mbf_msgs::ExePathResult &result) +{ + result.outcome = outcome; + result.message = message; + result.final_pose = robot_pose_; + result.dist_to_goal = static_cast(mbf_utility::distance(robot_pose_, goal_pose_)); + result.angle_to_goal = static_cast(mbf_utility::angle(robot_pose_, goal_pose_)); +} + +} /* mbf_abstract_nav */ diff --git a/navigations/move_base_flex/mbf_abstract_nav/src/mbf_abstract_nav/__init__.py b/navigations/move_base_flex/mbf_abstract_nav/src/mbf_abstract_nav/__init__.py new file mode 100755 index 0000000..d684cff --- /dev/null +++ b/navigations/move_base_flex/mbf_abstract_nav/src/mbf_abstract_nav/__init__.py @@ -0,0 +1,40 @@ +# Generic set of parameters required by any MBF-based navigation framework +# To use: +# +# from mbf_abstract_nav import add_mbf_abstract_nav_params +# gen = ParameterGenerator() +# add_mbf_abstract_nav_params(gen) +# ... +# WARN: parameters added here must be copied on the specific MBF implementation reconfigure callback, e.g. in: +# https://github.com/magazino/move_base_flex/blob/master/mbf_costmap_nav/src/mbf_costmap_nav/costmap_navigation_server.cpp#L130 +# Also, you need to touch https://github.com/magazino/move_base_flex/blob/master/mbf_costmap_nav/cfg/MoveBaseFlex.cfg +# when recompiling to ensure configuration code is regenerated with the new parameters + +# need this only for dataype declarations +from dynamic_reconfigure.parameter_generator_catkin import str_t, double_t, int_t, bool_t + + +def add_mbf_abstract_nav_params(gen): + gen.add("planner_frequency", double_t, 0, + "The rate in Hz at which to run the planning loop", 0, 0, 100) + gen.add("planner_patience", double_t, 0, + "How long the planner will wait in seconds in an attempt to find a valid plan before giving up", 5.0, 0, 100) + gen.add("planner_max_retries", int_t, 0, + "How many times we will recall the planner in an attempt to find a valid plan before giving up", -1, -1, 1000) + + gen.add("controller_frequency", double_t, 0, + "The rate in Hz at which to run the control loop and send velocity commands to the base", 20, 0, 100) + gen.add("controller_patience", double_t, 0, + "How long the controller will wait in seconds without receiving a valid control before giving up", 5.0, 0, 100) + gen.add("controller_max_retries", int_t, 0, + "How many times we will recall the controller in an attempt to find a valid command before giving up", -1, -1, 1000) + + gen.add("recovery_enabled", bool_t, 0, + "Whether or not to enable the move_base_flex recovery behaviors to attempt to clear out space", True) + gen.add("recovery_patience", double_t, 0, + "How much time we allow recovery behaviors to complete before canceling (or stopping if cancel fails) them", 15.0, 0, 100) + + gen.add("oscillation_timeout", double_t, 0, + "How long in seconds to allow for oscillation before executing recovery behaviors", 0.0, 0, 60) + gen.add("oscillation_distance", double_t, 0, + "How far in meters the robot must move to be considered not to be oscillating", 0.5, 0, 10) diff --git a/navigations/move_base_flex/mbf_abstract_nav/src/move_base_action.cpp b/navigations/move_base_flex/mbf_abstract_nav/src/move_base_action.cpp new file mode 100755 index 0000000..9de7338 --- /dev/null +++ b/navigations/move_base_flex/mbf_abstract_nav/src/move_base_action.cpp @@ -0,0 +1,586 @@ +/* + * Copyright 2018, Magazino GmbH, Sebastian Pütz, Jorge Santos Simón + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * move_base_action.cpp + * + * authors: + * Sebastian Pütz + * Jorge Santos Simón + * + */ + +#include + +#include "mbf_abstract_nav/MoveBaseFlexConfig.h" +#include "mbf_abstract_nav/move_base_action.h" + +namespace mbf_abstract_nav +{ + +MoveBaseAction::MoveBaseAction(const std::string &name, + const mbf_utility::RobotInformation &robot_info, + const std::vector &behaviors) + : name_(name), robot_info_(robot_info), private_nh_("~"), + action_client_exe_path_(private_nh_, "exe_path"), + action_client_get_path_(private_nh_, "get_path"), + action_client_recovery_(private_nh_, "recovery"), + oscillation_timeout_(0), + oscillation_distance_(0), + recovery_enabled_(true), + behaviors_(behaviors), + action_state_(NONE), + recovery_trigger_(NONE), + replanning_(false), + replanning_rate_(1.0) +{ +} + +MoveBaseAction::~MoveBaseAction() +{ +} + +void MoveBaseAction::reconfigure( + mbf_abstract_nav::MoveBaseFlexConfig &config, uint32_t level) +{ + if (config.planner_frequency > 0.0) + { + boost::lock_guard guard(replanning_mtx_); + if (!replanning_) + { + replanning_ = true; + if (action_state_ == EXE_PATH && + action_client_get_path_.getState() != actionlib::SimpleClientGoalState::PENDING && + action_client_get_path_.getState() != actionlib::SimpleClientGoalState::ACTIVE) + { + // exe_path is running and user has enabled replanning + ROS_INFO_STREAM_NAMED("move_base", "Planner frequency set to " << config.planner_frequency + << ": start replanning, using the \"get_path\" action!"); + action_client_get_path_.sendGoal( + get_path_goal_, + boost::bind(&MoveBaseAction::actionGetPathReplanningDone, this, _1, _2) + ); + } + } + replanning_rate_ = ros::Rate(config.planner_frequency); + } + else + replanning_ = false; + oscillation_timeout_ = ros::Duration(config.oscillation_timeout); + oscillation_distance_ = config.oscillation_distance; + recovery_enabled_ = config.recovery_enabled; +} + +void MoveBaseAction::cancel() +{ + action_state_ = CANCELED; + + if (!action_client_get_path_.getState().isDone()) + { + action_client_get_path_.cancelGoal(); + } + + if (!action_client_exe_path_.getState().isDone()) + { + action_client_exe_path_.cancelGoal(); + } + + if (!action_client_recovery_.getState().isDone()) + { + action_client_recovery_.cancelGoal(); + } +} + +void MoveBaseAction::start(GoalHandle &goal_handle) +{ + action_state_ = GET_PATH; + + goal_handle.setAccepted(); + + goal_handle_ = goal_handle; + + ROS_DEBUG_STREAM_NAMED("move_base", "Start action \"move_base\""); + + const mbf_msgs::MoveBaseGoal& goal = *goal_handle.getGoal(); + + mbf_msgs::MoveBaseResult move_base_result; + + get_path_goal_.target_pose = goal.target_pose; + get_path_goal_.use_start_pose = false; // use the robot pose + get_path_goal_.planner = goal.planner; + get_path_goal_.tolerance_from_action = goal.tolerance_from_action; + get_path_goal_.dist_tolerance = goal.dist_tolerance; + get_path_goal_.angle_tolerance = goal.angle_tolerance; + + exe_path_goal_.controller = goal.controller; + exe_path_goal_.tolerance_from_action = goal.tolerance_from_action; + exe_path_goal_.dist_tolerance = goal.dist_tolerance; + exe_path_goal_.angle_tolerance = goal.angle_tolerance; + + ros::Duration connection_timeout(1.0); + + last_oscillation_reset_ = ros::Time::now(); + + // start recovering with the first behavior, use the recovery behaviors from the action request, if specified, + // otherwise, use all loaded behaviors. + + recovery_behaviors_ = goal.recovery_behaviors.empty() ? behaviors_ : goal.recovery_behaviors; + current_recovery_behavior_ = recovery_behaviors_.begin(); + + // get the current robot pose only at the beginning, as exe_path will keep updating it as we move + if (!robot_info_.getRobotPose(robot_pose_)) + { + ROS_ERROR_STREAM_NAMED("move_base", "Could not get the current robot pose!"); + move_base_result.message = "Could not get the current robot pose!"; + move_base_result.outcome = mbf_msgs::MoveBaseResult::TF_ERROR; + goal_handle.setAborted(move_base_result, move_base_result.message); + return; + } + goal_pose_ = goal.target_pose; + + // wait for server connections + if (!action_client_get_path_.waitForServer(connection_timeout) || + !action_client_exe_path_.waitForServer(connection_timeout) || + !action_client_recovery_.waitForServer(connection_timeout)) + { + ROS_ERROR_STREAM_NAMED("move_base", "Could not connect to one or more of move_base_flex actions: " + "\"get_path\", \"exe_path\", \"recovery \"!"); + move_base_result.outcome = mbf_msgs::MoveBaseResult::INTERNAL_ERROR; + move_base_result.message = "Could not connect to the move_base_flex actions!"; + goal_handle.setAborted(move_base_result, move_base_result.message); + return; + } + + // call get_path action server to get a first plan + action_client_get_path_.sendGoal( + get_path_goal_, + boost::bind(&MoveBaseAction::actionGetPathDone, this, _1, _2)); +} + +void MoveBaseAction::actionExePathActive() +{ + ROS_DEBUG_STREAM_NAMED("move_base", "The \"exe_path\" action is active."); +} + +void MoveBaseAction::actionExePathFeedback( + const mbf_msgs::ExePathFeedbackConstPtr &feedback) +{ + mbf_msgs::MoveBaseFeedback move_base_feedback; + move_base_feedback.outcome = feedback->outcome; + move_base_feedback.message = feedback->message; + move_base_feedback.angle_to_goal = feedback->angle_to_goal; + move_base_feedback.dist_to_goal = feedback->dist_to_goal; + move_base_feedback.current_pose = feedback->current_pose; + move_base_feedback.last_cmd_vel = feedback->last_cmd_vel; + robot_pose_ = feedback->current_pose; + goal_handle_.publishFeedback(move_base_feedback); + + // we create a navigation-level oscillation detection using exe_path action's feedback, + // as the later doesn't handle oscillations created by quickly failing repeated plans + + // if oscillation detection is enabled by oscillation_timeout != 0 + if (!oscillation_timeout_.isZero()) + { + // check if oscillating + // moved more than the minimum oscillation distance + if (mbf_utility::distance(robot_pose_, last_oscillation_pose_) >= oscillation_distance_) + { + last_oscillation_reset_ = ros::Time::now(); + last_oscillation_pose_ = robot_pose_; + + if (recovery_trigger_ == OSCILLATING) + { + ROS_INFO_NAMED("move_base", "Recovered from robot oscillation: restart recovery behaviors"); + current_recovery_behavior_ = recovery_behaviors_.begin(); + recovery_trigger_ = NONE; + } + } + else if (last_oscillation_reset_ + oscillation_timeout_ < ros::Time::now()) + { + std::stringstream oscillation_msgs; + oscillation_msgs << "Robot is oscillating for " << (ros::Time::now() - last_oscillation_reset_).toSec() << "s!"; + ROS_WARN_STREAM_NAMED("move_base", oscillation_msgs.str()); + action_client_exe_path_.cancelGoal(); + + if (attemptRecovery()) + { + recovery_trigger_ = OSCILLATING; + } + else + { + mbf_msgs::MoveBaseResult move_base_result; + move_base_result.outcome = mbf_msgs::MoveBaseResult::OSCILLATION; + move_base_result.message = oscillation_msgs.str(); + move_base_result.final_pose = robot_pose_; + move_base_result.angle_to_goal = move_base_feedback.angle_to_goal; + move_base_result.dist_to_goal = move_base_feedback.dist_to_goal; + goal_handle_.setAborted(move_base_result, move_base_result.message); + } + } + } +} + +void MoveBaseAction::actionGetPathDone( + const actionlib::SimpleClientGoalState &state, + const mbf_msgs::GetPathResultConstPtr &result_ptr) +{ + const mbf_msgs::GetPathResult &get_path_result = *result_ptr; + mbf_msgs::MoveBaseResult move_base_result; + + // copy result from get_path action + fillMoveBaseResult(get_path_result, move_base_result); + + switch (state.state_) + { + case actionlib::SimpleClientGoalState::PENDING: + ROS_FATAL_STREAM_NAMED("move_base", "get_path PENDING state not implemented, this should not be reachable!"); + break; + + case actionlib::SimpleClientGoalState::SUCCEEDED: + ROS_DEBUG_STREAM_NAMED("move_base", "Action \"" + << "move_base\" received a path from \"" + << "get_path\": " << state.getText()); + + exe_path_goal_.path = get_path_result.path; + ROS_DEBUG_STREAM_NAMED("move_base", "Action \"" + << "move_base\" sends the path to \"" + << "exe_path\"."); + + if (recovery_trigger_ == GET_PATH) + { + ROS_WARN_NAMED("move_base", "Recovered from planner failure: restart recovery behaviors"); + current_recovery_behavior_ = recovery_behaviors_.begin(); + recovery_trigger_ = NONE; + } + + action_client_exe_path_.sendGoal( + exe_path_goal_, + boost::bind(&MoveBaseAction::actionExePathDone, this, _1, _2), + boost::bind(&MoveBaseAction::actionExePathActive, this), + boost::bind(&MoveBaseAction::actionExePathFeedback, this, _1)); + action_state_ = EXE_PATH; + break; + + case actionlib::SimpleClientGoalState::ABORTED: + + if (attemptRecovery()) + { + recovery_trigger_ = GET_PATH; + } + else + { + // copy result from get_path action + ROS_WARN_STREAM_NAMED("move_base", "Abort the execution of the planner: " << get_path_result.message); + goal_handle_.setAborted(move_base_result, state.getText()); + } + action_state_ = FAILED; + break; + + case actionlib::SimpleClientGoalState::RECALLED: + case actionlib::SimpleClientGoalState::PREEMPTED: + ROS_INFO_STREAM_NAMED("move_base", "The last action goal to \"get_path\" has been " << state.toString()); + if (action_state_ == CANCELED) + { + // move_base preempted while executing get_path; fill result and report canceled to the client + ROS_INFO_STREAM_NAMED("move_base", "move_base preempted while executing get_path"); + goal_handle_.setCanceled(move_base_result, state.getText()); + } + break; + + case actionlib::SimpleClientGoalState::REJECTED: + ROS_ERROR_STREAM_NAMED("move_base", "The last action goal to \"get_path\" has been " << state.toString()); + goal_handle_.setCanceled(move_base_result, state.getText()); + action_state_ = FAILED; + break; + + case actionlib::SimpleClientGoalState::LOST: + ROS_FATAL_STREAM_NAMED("move_base", "Connection lost to the action \"get_path\"!"); + goal_handle_.setAborted(); + action_state_ = FAILED; + break; + + default: + ROS_FATAL_STREAM_NAMED("move_base", "Reached unknown action server state!"); + goal_handle_.setAborted(); + action_state_ = FAILED; + break; + } + + // start replanning if enabled (can be disabled by dynamic reconfigure) and if we started following a path + if (!replanning_ || action_state_ != EXE_PATH) + return; + + // we reset the replan clock (we can have been stopped for a while) and make a fist sleep, so we don't replan + // just after start moving + boost::lock_guard guard(replanning_mtx_); + replanning_rate_.reset(); + replanning_rate_.sleep(); + if (!replanning_ || action_state_ != EXE_PATH || + action_client_get_path_.getState() == actionlib::SimpleClientGoalState::PENDING || + action_client_get_path_.getState() == actionlib::SimpleClientGoalState::ACTIVE) + return; // another chance to stop replannings after waiting for replanning period + ROS_INFO_STREAM_NAMED("move_base", "Start replanning, using the \"get_path\" action!"); + action_client_get_path_.sendGoal( + get_path_goal_, + boost::bind(&MoveBaseAction::actionGetPathReplanningDone, this, _1, _2) + ); +} + +void MoveBaseAction::actionExePathDone( + const actionlib::SimpleClientGoalState &state, + const mbf_msgs::ExePathResultConstPtr &result_ptr) +{ + ROS_DEBUG_STREAM_NAMED("move_base", "Action \"exe_path\" finished."); + + const mbf_msgs::ExePathResult& exe_path_result = *result_ptr; + mbf_msgs::MoveBaseResult move_base_result; + + // copy result from exe_path action + fillMoveBaseResult(exe_path_result, move_base_result); + + ROS_DEBUG_STREAM_NAMED("move_base", "Current state:" << state.toString()); + + switch (state.state_) + { + case actionlib::SimpleClientGoalState::SUCCEEDED: + move_base_result.outcome = mbf_msgs::MoveBaseResult::SUCCESS; + move_base_result.message = "Action \"move_base\" succeeded!"; + ROS_INFO_STREAM_NAMED("move_base", move_base_result.message); + goal_handle_.setSucceeded(move_base_result, move_base_result.message); + action_state_ = SUCCEEDED; + break; + + case actionlib::SimpleClientGoalState::ABORTED: + action_state_ = FAILED; + + switch (exe_path_result.outcome) + { + case mbf_msgs::ExePathResult::INVALID_PATH: + case mbf_msgs::ExePathResult::TF_ERROR: + case mbf_msgs::ExePathResult::NOT_INITIALIZED: + case mbf_msgs::ExePathResult::INVALID_PLUGIN: + case mbf_msgs::ExePathResult::INTERNAL_ERROR: + // none of these errors is recoverable + goal_handle_.setAborted(move_base_result, state.getText()); + break; + + default: + // all the rest are, so we start calling the recovery behaviors in sequence + + if (attemptRecovery()) + { + recovery_trigger_ = EXE_PATH; + } + else + { + ROS_WARN_STREAM_NAMED("move_base", "Abort the execution of the controller: " << exe_path_result.message); + goal_handle_.setAborted(move_base_result, state.getText()); + } + break; + } + break; + + case actionlib::SimpleClientGoalState::RECALLED: + case actionlib::SimpleClientGoalState::PREEMPTED: + ROS_INFO_STREAM_NAMED("move_base", "The last action goal to \"exe_path\" has been " << state.toString()); + if (action_state_ == CANCELED) + { + // move_base preempted while executing exe_path; fill result and report canceled to the client + ROS_INFO_STREAM_NAMED("move_base", "move_base preempted while executing exe_path"); + goal_handle_.setCanceled(move_base_result, state.getText()); + } + break; + + case actionlib::SimpleClientGoalState::REJECTED: + ROS_ERROR_STREAM_NAMED("move_base", "The last action goal to \"exe_path\" has been " << state.toString()); + goal_handle_.setCanceled(move_base_result, state.getText()); + action_state_ = FAILED; + break; + + case actionlib::SimpleClientGoalState::LOST: + ROS_FATAL_STREAM_NAMED("move_base", "Connection lost to the action \"exe_path\"!"); + goal_handle_.setAborted(); + action_state_ = FAILED; + break; + + default: + ROS_FATAL_STREAM_NAMED("move_base", "Reached unreachable case! Unknown SimpleActionServer state!"); + goal_handle_.setAborted(); + action_state_ = FAILED; + break; + } +} + +bool MoveBaseAction::attemptRecovery() +{ + if (!recovery_enabled_) + { + ROS_WARN_STREAM_NAMED("move_base", "Recovery behaviors are disabled!"); + return false; + } + + if (current_recovery_behavior_ == recovery_behaviors_.end()) + { + if (recovery_behaviors_.empty()) + { + ROS_WARN_STREAM_NAMED("move_base", "No Recovery Behaviors loaded!"); + } + else + { + ROS_WARN_STREAM_NAMED("move_base", "Executed all available recovery behaviors!"); + } + return false; + } + + recovery_goal_.behavior = *current_recovery_behavior_; + ROS_DEBUG_STREAM_NAMED("move_base", "Start recovery behavior\"" + << *current_recovery_behavior_ <<"\"."); + action_client_recovery_.sendGoal( + recovery_goal_, + boost::bind(&MoveBaseAction::actionRecoveryDone, this, _1, _2) + ); + action_state_ = RECOVERY; + return true; +} + +void MoveBaseAction::actionRecoveryDone( + const actionlib::SimpleClientGoalState &state, + const mbf_msgs::RecoveryResultConstPtr &result_ptr) +{ + // give the robot some time to stop oscillating after executing the recovery behavior + last_oscillation_reset_ = ros::Time::now(); + + const mbf_msgs::RecoveryResult& recovery_result = *result_ptr; + mbf_msgs::MoveBaseResult move_base_result; + + // copy result from recovery action + fillMoveBaseResult(recovery_result, move_base_result); + + switch (state.state_) + { + case actionlib::SimpleClientGoalState::REJECTED: + case actionlib::SimpleClientGoalState::ABORTED: + action_state_ = FAILED; + + ROS_DEBUG_STREAM_NAMED("move_base", "The recovery behavior \"" + << *current_recovery_behavior_ << "\" has failed. "); + ROS_DEBUG_STREAM("Recovery behavior message: " << recovery_result.message + << ", outcome: " << recovery_result.outcome); + + current_recovery_behavior_++; // use next behavior; + if (current_recovery_behavior_ == recovery_behaviors_.end()) + { + ROS_DEBUG_STREAM_NAMED("move_base", + "All recovery behaviors failed. Abort recovering and abort the move_base action"); + goal_handle_.setAborted(move_base_result, "All recovery behaviors failed."); + } + else + { + recovery_goal_.behavior = *current_recovery_behavior_; + + ROS_INFO_STREAM_NAMED("move_base", "Run the next recovery behavior \"" + << *current_recovery_behavior_ << "\"."); + action_client_recovery_.sendGoal( + recovery_goal_, + boost::bind(&MoveBaseAction::actionRecoveryDone, this, _1, _2) + ); + } + break; + case actionlib::SimpleClientGoalState::SUCCEEDED: + //go to planning state + ROS_DEBUG_STREAM_NAMED("move_base", "Execution of the recovery behavior \"" + << *current_recovery_behavior_ << "\" succeeded!"); + ROS_DEBUG_STREAM_NAMED("move_base", + "Try planning again and increment the current recovery behavior in the list."); + action_state_ = GET_PATH; + current_recovery_behavior_++; // use next behavior, the next time; + action_client_get_path_.sendGoal( + get_path_goal_, + boost::bind(&MoveBaseAction::actionGetPathDone, this, _1, _2) + ); + break; + case actionlib::SimpleClientGoalState::RECALLED: + case actionlib::SimpleClientGoalState::PREEMPTED: + ROS_INFO_STREAM_NAMED("move_base", "The last action goal to \"recovery\" has been preempted!"); + if (action_state_ == CANCELED) + { + // move_base preempted while executing a recovery; fill result and report canceled to the client + ROS_INFO_STREAM_NAMED("move_base", "move_base preempted while executing a recovery behavior"); + goal_handle_.setCanceled(move_base_result, state.getText()); + } + break; + + case actionlib::SimpleClientGoalState::LOST: + ROS_FATAL_STREAM_NAMED("move_base", "Connection lost to the action \"recovery\"!"); + goal_handle_.setAborted(); + action_state_ = FAILED; + break; + default: + ROS_FATAL_STREAM_NAMED("move_base", "Reached unreachable case! Unknown state!"); + goal_handle_.setAborted(); + action_state_ = FAILED; + break; + } +} + +void MoveBaseAction::actionGetPathReplanningDone( + const actionlib::SimpleClientGoalState &state, + const mbf_msgs::GetPathResultConstPtr &result) +{ + if (!replanning_ || action_state_ != EXE_PATH) + return; // replan only while following a path and if replanning is enabled (can be disabled by dynamic reconfigure) + + if (state == actionlib::SimpleClientGoalState::SUCCEEDED) + { + ROS_DEBUG_STREAM_NAMED("move_base", "Replanning succeeded; sending a goal to \"exe_path\" with the new plan"); + exe_path_goal_.path = result->path; + mbf_msgs::ExePathGoal goal(exe_path_goal_); + action_client_exe_path_.sendGoal( + goal, + boost::bind(&MoveBaseAction::actionExePathDone, this, _1, _2), + boost::bind(&MoveBaseAction::actionExePathActive, this), + boost::bind(&MoveBaseAction::actionExePathFeedback, this, _1)); + } + + replanning_mtx_.lock(); + replanning_rate_.sleep(); + replanning_mtx_.unlock(); + + if (!replanning_ || action_state_ != EXE_PATH) + return; // another chance to stop replannings after waiting for replanning period + + ROS_DEBUG_STREAM_NAMED("move_base", "Next replanning cycle, using the \"get_path\" action!"); + action_client_get_path_.sendGoal( + get_path_goal_, + boost::bind(&MoveBaseAction::actionGetPathReplanningDone, this, _1, _2)); // replanning +} + +} /* namespace mbf_abstract_nav */ diff --git a/navigations/move_base_flex/mbf_abstract_nav/src/planner_action.cpp b/navigations/move_base_flex/mbf_abstract_nav/src/planner_action.cpp new file mode 100755 index 0000000..d71aa15 --- /dev/null +++ b/navigations/move_base_flex/mbf_abstract_nav/src/planner_action.cpp @@ -0,0 +1,286 @@ +/* + * Copyright 2018, Magazino GmbH, Sebastian Pütz, Jorge Santos Simón + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * planner_action.cpp + * + * authors: + * Sebastian Pütz + * Jorge Santos Simón + * + */ + +#include + +#include "mbf_abstract_nav/planner_action.h" + +namespace mbf_abstract_nav +{ + +PlannerAction::PlannerAction( + const std::string &name, + const mbf_utility::RobotInformation &robot_info) + : AbstractActionBase(name, robot_info, boost::bind(&mbf_abstract_nav::PlannerAction::run, this, _1, _2)), path_seq_count_(0) +{ + ros::NodeHandle private_nh("~"); + // informative topics: current navigation goal + current_goal_pub_ = private_nh.advertise("current_goal", 1); +} + +void PlannerAction::run(GoalHandle &goal_handle, AbstractPlannerExecution &execution) +{ + const mbf_msgs::GetPathGoal& goal = *(goal_handle.getGoal().get()); + + mbf_msgs::GetPathResult result; + geometry_msgs::PoseStamped start_pose; + + result.path.header.seq = path_seq_count_++; + result.path.header.frame_id = robot_info_.getGlobalFrame(); + + double dist_tolerance = goal.tolerance_from_action ? goal.dist_tolerance : 0.0; + double angle_tolerance = goal.tolerance_from_action ? goal.angle_tolerance : 0.0; + bool use_start_pose = goal.use_start_pose; + current_goal_pub_.publish(goal.target_pose); + + bool planner_active = true; + + if (use_start_pose) + { + start_pose = goal.start_pose; + const geometry_msgs::Point& p = start_pose.pose.position; + ROS_DEBUG_STREAM_NAMED(name_, "Use the given start pose (" << p.x << ", " << p.y << ", " << p.z << ")."); + } + else + { + // get the current robot pose + if (!robot_info_.getRobotPose(start_pose)) + { + result.outcome = mbf_msgs::GetPathResult::TF_ERROR; + result.message = "Could not get the current robot pose!"; + goal_handle.setAborted(result, result.message); + ROS_ERROR_STREAM_NAMED(name_, result.message << " Canceling the action call."); + return; + } + else + { + const geometry_msgs::Point& p = start_pose.pose.position; + ROS_DEBUG_STREAM_NAMED(name_, "Got the current robot pose at (" + << p.x << ", " << p.y << ", " << p.z << ")."); + } + } + + AbstractPlannerExecution::PlanningState state_planning_input; + + std::vector plan, global_plan; + + while (planner_active && ros::ok()) + { + // get the current state of the planning thread + state_planning_input = execution.getState(); + + switch (state_planning_input) + { + case AbstractPlannerExecution::INITIALIZED: + ROS_DEBUG_STREAM_NAMED(name_, "planner state: initialized"); + if (!execution.start(start_pose, goal.target_pose, dist_tolerance, angle_tolerance)) + { + result.outcome = mbf_msgs::GetPathResult::INTERNAL_ERROR; + result.message = "Another thread is still planning!"; + goal_handle.setAborted(result, result.message); + ROS_ERROR_STREAM_NAMED(name_, result.message << " Canceling the action call."); + planner_active = false; + } + break; + + case AbstractPlannerExecution::STARTED: + ROS_DEBUG_STREAM_NAMED(name_, "planner state: started"); + break; + + case AbstractPlannerExecution::STOPPED: + ROS_DEBUG_STREAM_NAMED(name_, "planner state: stopped"); + ROS_WARN_STREAM_NAMED(name_, "Planning has been stopped rigorously!"); + result.outcome = mbf_msgs::GetPathResult::STOPPED; + result.message = "Global planner has been stopped!"; + goal_handle.setAborted(result, result.message); + planner_active = false; + break; + + case AbstractPlannerExecution::CANCELED: + ROS_DEBUG_STREAM_NAMED(name_, "planner state: canceled"); + ROS_DEBUG_STREAM_NAMED(name_, "Global planner has been canceled successfully"); + result.path.header.stamp = ros::Time::now(); + result.outcome = mbf_msgs::GetPathResult::CANCELED; + result.message = "Global planner has been canceled!"; + goal_handle.setCanceled(result, result.message); + planner_active = false; + break; + + // in progress + case AbstractPlannerExecution::PLANNING: + if (execution.isPatienceExceeded()) + { + ROS_INFO_STREAM_NAMED(name_, "Global planner patience has been exceeded! Cancel planning..."); + execution.cancel(); + } + else + { + ROS_DEBUG_THROTTLE_NAMED(2.0, name_, "planner state: planning"); + } + break; + + // found a new plan + case AbstractPlannerExecution::FOUND_PLAN: + // set time stamp to now + result.path.header.stamp = ros::Time::now(); + plan = execution.getPlan(); + + ROS_DEBUG_STREAM_NAMED(name_, "planner state: found plan with cost: " << execution.getCost()); + + if (!transformPlanToGlobalFrame(plan, global_plan)) + { + result.outcome = mbf_msgs::GetPathResult::TF_ERROR; + result.message = "Could not transform the plan to the global frame!"; + + ROS_ERROR_STREAM_NAMED(name_, result.message << " Canceling the action call."); + goal_handle.setAborted(result, result.message); + planner_active = false; + break; + } + + if (global_plan.empty()) + { + result.outcome = mbf_msgs::GetPathResult::EMPTY_PATH; + result.message = "Global planner returned an empty path!"; + + ROS_ERROR_STREAM_NAMED(name_, result.message); + goal_handle.setAborted(result, result.message); + planner_active = false; + break; + } + + result.path.poses = global_plan; + result.cost = execution.getCost(); + result.outcome = execution.getOutcome(); + result.message = execution.getMessage(); + goal_handle.setSucceeded(result, result.message); + + planner_active = false; + break; + + // no plan found + case AbstractPlannerExecution::NO_PLAN_FOUND: + ROS_DEBUG_STREAM_NAMED(name_, "planner state: no plan found"); + result.outcome = execution.getOutcome(); + result.message = execution.getMessage(); + goal_handle.setAborted(result, result.message); + planner_active = false; + break; + + case AbstractPlannerExecution::MAX_RETRIES: + ROS_DEBUG_STREAM_NAMED(name_, "Global planner reached the maximum number of retries"); + result.outcome = execution.getOutcome(); + result.message = execution.getMessage(); + goal_handle.setAborted(result, result.message); + planner_active = false; + break; + + case AbstractPlannerExecution::PAT_EXCEEDED: + ROS_DEBUG_STREAM_NAMED(name_, "Global planner exceeded the patience time"); + result.outcome = mbf_msgs::GetPathResult::PAT_EXCEEDED; + result.message = "Global planner exceeded the patience time"; + goal_handle.setAborted(result, result.message); + planner_active = false; + break; + + case AbstractPlannerExecution::INTERNAL_ERROR: + ROS_FATAL_STREAM_NAMED(name_, "Internal error: Unknown error thrown by the plugin!"); // TODO getMessage from planning + planner_active = false; + result.outcome = mbf_msgs::GetPathResult::INTERNAL_ERROR; + result.message = "Internal error: Unknown error thrown by the plugin!"; + goal_handle.setAborted(result, result.message); + break; + + default: + result.outcome = mbf_msgs::GetPathResult::INTERNAL_ERROR; + std::ostringstream ss; + ss << "Internal error: Unknown state in a move base flex planner execution with the number: " + << static_cast(state_planning_input); + result.message = ss.str(); + ROS_FATAL_STREAM_NAMED(name_, result.message); + goal_handle.setAborted(result, result.message); + planner_active = false; + } + + + if (planner_active) + { + // try to sleep a bit + // normally this thread should be woken up from the planner execution thread + // in order to transfer the results to the controller. + boost::mutex mutex; + boost::unique_lock lock(mutex); + execution.waitForStateUpdate(boost::chrono::milliseconds(500)); + } + } // while (planner_active && ros::ok()) + + if (!planner_active) + { + ROS_DEBUG_STREAM_NAMED(name_, "\"" << name_ << "\" action ended properly."); + } + else + { + ROS_ERROR_STREAM_NAMED(name_, "\"" << name_ << "\" action has been stopped!"); + } +} + +bool PlannerAction::transformPlanToGlobalFrame( + std::vector &plan, std::vector &global_plan) +{ + global_plan.clear(); + std::vector::iterator iter; + bool tf_success = false; + for (iter = plan.begin(); iter != plan.end(); ++iter) + { + geometry_msgs::PoseStamped global_pose; + tf_success = mbf_utility::transformPose(robot_info_.getTransformListener(), robot_info_.getGlobalFrame(), + robot_info_.getTfTimeout(), *iter, global_pose); + if (!tf_success) + { + ROS_ERROR_STREAM("Can not transform pose from the \"" << iter->header.frame_id << "\" frame into the \"" + << robot_info_.getGlobalFrame() << "\" frame !"); + return false; + } + global_plan.push_back(global_pose); + } + return true; +} + +} /* namespace mbf_abstract_nav */ diff --git a/navigations/move_base_flex/mbf_abstract_nav/src/recovery_action.cpp b/navigations/move_base_flex/mbf_abstract_nav/src/recovery_action.cpp new file mode 100755 index 0000000..8e953c4 --- /dev/null +++ b/navigations/move_base_flex/mbf_abstract_nav/src/recovery_action.cpp @@ -0,0 +1,156 @@ +/* + * Copyright 2018, Magazino GmbH, Sebastian Pütz, Jorge Santos Simón + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * recovery_action.cpp + * + * authors: + * Sebastian Pütz + * Jorge Santos Simón + * + */ + +#include "mbf_abstract_nav/recovery_action.h" + +namespace mbf_abstract_nav +{ + +RecoveryAction::RecoveryAction(const std::string &name, const mbf_utility::RobotInformation &robot_info) + : AbstractActionBase(name, robot_info, boost::bind(&mbf_abstract_nav::RecoveryAction::run, this, _1, _2)){} + +void RecoveryAction::run(GoalHandle &goal_handle, AbstractRecoveryExecution &execution) +{ + ROS_DEBUG_STREAM_NAMED(name_, "Start action " << name_); + + const mbf_msgs::RecoveryGoal &goal = *goal_handle.getGoal(); + mbf_msgs::RecoveryResult result; + result.used_plugin = goal.behavior; + bool recovery_active = true; + + typename AbstractRecoveryExecution::RecoveryState state_recovery_input; + + while (recovery_active && ros::ok()) + { + state_recovery_input = execution.getState(); + switch (state_recovery_input) + { + case AbstractRecoveryExecution::INITIALIZED: + ROS_DEBUG_STREAM_NAMED(name_, "Recovery behavior \"" << goal.behavior << "\" initialized."); + execution.start(); + break; + + case AbstractRecoveryExecution::STOPPED: + ROS_DEBUG_STREAM_NAMED(name_, "Recovery behavior stopped rigorously"); + result.outcome = mbf_msgs::RecoveryResult::STOPPED; + result.message = "Recovery has been stopped!"; + goal_handle.setAborted(result, result.message); + recovery_active = false; + break; + + case AbstractRecoveryExecution::STARTED: + ROS_DEBUG_STREAM_NAMED(name_, "Recovery behavior \"" << goal.behavior << "\" was started"); + break; + + case AbstractRecoveryExecution::RECOVERING: + + if (execution.isPatienceExceeded()) + { + ROS_INFO_STREAM("Recovery behavior \"" << goal.behavior << "\" patience exceeded! Cancel recovering..."); + execution.cancel(); + } + + ROS_DEBUG_STREAM_THROTTLE_NAMED(3, name_, "Recovering with: " << goal.behavior); + break; + + case AbstractRecoveryExecution::CANCELED: + // Recovery behavior supports cancel and it worked + recovery_active = false; // stopping the action + result.outcome = mbf_msgs::RecoveryResult::CANCELED; + result.message = "Recovery behaviour \"" + goal.behavior + "\" canceled!"; + goal_handle.setCanceled(result, result.message); + ROS_DEBUG_STREAM_NAMED(name_, result.message); + break; + + case AbstractRecoveryExecution::RECOVERY_DONE: + recovery_active = false; // stopping the action + result.outcome = execution.getOutcome(); + result.message = execution.getMessage(); + if (result.message.empty()) + { + if (result.outcome < 10) + result.message = "Recovery \"" + goal.behavior + "\" done"; + else + result.message = "Recovery \"" + goal.behavior + "\" FAILED"; + } + + ROS_DEBUG_STREAM_NAMED(name_, result.message); + goal_handle.setSucceeded(result, result.message); + break; + + case AbstractRecoveryExecution::INTERNAL_ERROR: + ROS_FATAL_STREAM_NAMED(name_, "Internal error: Unknown error thrown by the plugin!"); // TODO getMessage from recovery + recovery_active = false; + result.outcome = mbf_msgs::RecoveryResult::INTERNAL_ERROR; + result.message = "Internal error: Unknown error thrown by the plugin!"; + goal_handle.setAborted(result, result.message); + break; + + default: + result.outcome = mbf_msgs::RecoveryResult::INTERNAL_ERROR; + std::stringstream ss; + ss << "Internal error: Unknown state in a move base flex recovery execution with the number: " + << static_cast(state_recovery_input); + result.message = ss.str(); + ROS_FATAL_STREAM_NAMED(name_, result.message); + goal_handle.setAborted(result, result.message); + recovery_active = false; + } + + if (recovery_active) + { + // try to sleep a bit + // normally the thread should be woken up from the recovery unit + // in order to transfer the results to the controller + execution.waitForStateUpdate(boost::chrono::milliseconds(500)); + } + } // while (recovery_active && ros::ok()) + + if (!recovery_active) + { + ROS_DEBUG_STREAM_NAMED(name_, "\"" << name_ << "\" action ended properly."); + } + else + { + ROS_ERROR_STREAM_NAMED(name_, "\"" << name_ << "\" action has been stopped!"); + } +} + +} /* namespace mbf_abstract_nav */ diff --git a/navigations/move_base_flex/mbf_costmap_core/CHANGELOG.rst b/navigations/move_base_flex/mbf_costmap_core/CHANGELOG.rst new file mode 100755 index 0000000..744fc92 --- /dev/null +++ b/navigations/move_base_flex/mbf_costmap_core/CHANGELOG.rst @@ -0,0 +1,38 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package mbf_costmap_core +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +0.3.2 (2020-05-25) +------------------ + +0.3.1 (2020-04-07) +------------------ + +0.3.0 (2020-03-31) +------------------ +* unify license declaration to BSD-3 + +0.2.5 (2019-10-11) +------------------ + +0.2.4 (2019-06-16) +------------------ + +0.2.3 (2018-11-14) +------------------ + +0.2.2 (2018-10-10) +------------------ + +0.2.1 (2018-10-03) +------------------ +* Make MBF melodic and indigo compatible +* Fix GoalHandle references bug in callbacks + +0.2.0 (2018-09-11) +------------------ +* Concurrency for planners, controllers and recovery behaviors + +0.1.0 (2018-03-22) +------------------ +* First release of move_base_flex for kinetic and lunar diff --git a/navigations/move_base_flex/mbf_costmap_core/CMakeLists.txt b/navigations/move_base_flex/mbf_costmap_core/CMakeLists.txt new file mode 100755 index 0000000..22616dd --- /dev/null +++ b/navigations/move_base_flex/mbf_costmap_core/CMakeLists.txt @@ -0,0 +1,32 @@ +cmake_minimum_required(VERSION 2.8.3) +project(mbf_costmap_core) + +find_package(catkin REQUIRED + COMPONENTS + std_msgs + geometry_msgs + mbf_abstract_core + mbf_utility + tf + costmap_2d + nav_core + ) + +catkin_package( + INCLUDE_DIRS + include + CATKIN_DEPENDS + std_msgs + geometry_msgs + mbf_abstract_core + mbf_utility + tf + costmap_2d + nav_core +) + +## Install project namespaced headers +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} + FILES_MATCHING PATTERN "*.h" + PATTERN ".svn" EXCLUDE) diff --git a/navigations/move_base_flex/mbf_costmap_core/README.md b/navigations/move_base_flex/mbf_costmap_core/README.md new file mode 100755 index 0000000..4c507b0 --- /dev/null +++ b/navigations/move_base_flex/mbf_costmap_core/README.md @@ -0,0 +1,3 @@ +# Move Base Flex Costmap Navigation Core {#mainpage} + +This package provides common interfaces for navigation specific robot actions. It contains the CostmapPlanner, CostmapController and CostmapRecovery interfaces. The interfaces have to be implemented by the plugins to make them available for Move Base Flex using the [mbf_costmap_nav](wiki.ros.org/mbf_costmap_nav) navigation implementation. That implementation inherits the [mbf_abstract_nav](wiki.ros.org/mbf_abstract_nav) implementation and binds the system to a local and a global costmap. \ No newline at end of file diff --git a/navigations/move_base_flex/mbf_costmap_core/include/mbf_costmap_core/costmap_controller.h b/navigations/move_base_flex/mbf_costmap_core/include/mbf_costmap_core/costmap_controller.h new file mode 100755 index 0000000..bccd45a --- /dev/null +++ b/navigations/move_base_flex/mbf_costmap_core/include/mbf_costmap_core/costmap_controller.h @@ -0,0 +1,132 @@ +/* + * Copyright 2018, Sebastian Pütz + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * mbf_costmap_core.h + * + * author: Sebastian Pütz + * + */ + +#ifndef MBF_COSTMAP_CORE__COSTMAP_CONTROLLER_H_ +#define MBF_COSTMAP_CORE__COSTMAP_CONTROLLER_H_ + +#include +#include +#include + +namespace mbf_costmap_core { + /** + * @class LocalPlanner + * @brief Provides an interface for local planners used in navigation. + * All local planners written to work as MBF plugins must adhere to this interface. Alternatively, this + * class can also operate as a wrapper for old API nav_core-based plugins, providing backward compatibility. + */ + class CostmapController : public mbf_abstract_core::AbstractController{ + public: + + typedef boost::shared_ptr< ::mbf_costmap_core::CostmapController > Ptr; + + /** + * @brief Given the current position, orientation, and velocity of the robot, compute velocity commands + * to send to the base. + * @param pose the current pose of the robot. + * @param velocity the current velocity of the robot. + * @param cmd_vel Will be filled with the velocity command to be passed to the robot base. + * @param message Optional more detailed outcome as a string + * @return Result code as described on ExePath action result: + * SUCCESS = 0 + * 1..9 are reserved as plugin specific non-error results + * FAILURE = 100 Unspecified failure, only used for old, non-mfb_core based plugins + * CANCELED = 101 + * NO_VALID_CMD = 102 + * PAT_EXCEEDED = 103 + * COLLISION = 104 + * OSCILLATION = 105 + * ROBOT_STUCK = 106 + * MISSED_GOAL = 107 + * MISSED_PATH = 108 + * BLOCKED_PATH = 109 + * INVALID_PATH = 110 + * TF_ERROR = 111 + * NOT_INITIALIZED = 112 + * INVALID_PLUGIN = 113 + * INTERNAL_ERROR = 114 + * 121..149 are reserved as plugin specific errors + */ + virtual uint32_t computeVelocityCommands(const geometry_msgs::PoseStamped& pose, + const geometry_msgs::TwistStamped& velocity, + geometry_msgs::TwistStamped &cmd_vel, + std::string &message) = 0; + + /** + * @brief Check if the goal pose has been achieved by the local planner within tolerance limits + * @remark New on MBF API + * @param xy_tolerance Distance tolerance in meters + * @param yaw_tolerance Heading tolerance in radians + * @return True if achieved, false otherwise + */ + virtual bool isGoalReached(double xy_tolerance, double yaw_tolerance) = 0; + + /** + * @brief Set the plan that the local planner is following + * @param plan The plan to pass to the local planner + * @return True if the plan was updated successfully, false otherwise + */ + virtual bool setPlan(const std::vector &plan) = 0; + + /** + * @brief Requests the planner to cancel, e.g. if it takes too much time + * @remark New on MBF API + * @return True if a cancel has been successfully requested, false if not implemented. + */ + virtual bool cancel() = 0; + + /** + * @brief Constructs the local planner + * @param name The name to give this instance of the local planner + * @param tf A pointer to a transform listener + * @param costmap_ros The cost map to use for assigning costs to local plans + */ + virtual void initialize(std::string name, ::TF *tf, costmap_2d::Costmap2DROS *costmap_ros) = 0; + + /** + * @brief Virtual destructor for the interface + */ + virtual ~CostmapController(){} + + protected: + CostmapController(){} + + }; +} /* namespace mbf_costmap_core */ + +#endif /* MBF_COSTMAP_CORE__COSTMAP_CONTROLLER_H_ */ diff --git a/navigations/move_base_flex/mbf_costmap_core/include/mbf_costmap_core/costmap_planner.h b/navigations/move_base_flex/mbf_costmap_core/include/mbf_costmap_core/costmap_planner.h new file mode 100755 index 0000000..b9f8cb3 --- /dev/null +++ b/navigations/move_base_flex/mbf_costmap_core/include/mbf_costmap_core/costmap_planner.h @@ -0,0 +1,113 @@ +/* + * Copyright 2018, Sebastian Pütz + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * abstract_global_planner.h + * + * author: Sebastian Pütz + * + */ + +#ifndef MBF_COSTMAP_CORE__COSTMAP_PLANNER_H_ +#define MBF_COSTMAP_CORE__COSTMAP_PLANNER_H_ + +#include +#include + +namespace mbf_costmap_core { + /** + * @class CostmapPlanner + * @brief Provides an interface for global planners used in navigation. + * All global planners written to work as MBF plugins must adhere to this interface. Alternatively, this + * class can also operate as a wrapper for old API nav_core-based plugins, providing backward compatibility. + */ + class CostmapPlanner : public mbf_abstract_core::AbstractPlanner{ + public: + + typedef boost::shared_ptr< ::mbf_costmap_core::CostmapPlanner > Ptr; + + /** + * @brief Given a goal pose in the world, compute a plan + * The final pose of the path must be within tolerance range (position and orientation) + * for this method to return a success outcome. + * @param start The start pose + * @param goal The goal pose + * @param dist_tolerance Tolerance in meters to the goal position + * @param angle_tolerance Tolerance in radians to the goal orientation + * @param plan The plan... filled by the planner + * @param cost The cost for the the plan + * @param message Optional more detailed outcome as a string + * @return Result code as described on GetPath action result: + * SUCCESS = 0 + * 1..9 are reserved as plugin specific non-error results + * FAILURE = 50 # Unspecified failure, only used for old, non-mfb_core based plugins + * CANCELED = 51 + * INVALID_START = 52 + * INVALID_GOAL = 53 + * NO_PATH_FOUND = 54 + * PAT_EXCEEDED = 55 + * EMPTY_PATH = 56 + * TF_ERROR = 57 + * NOT_INITIALIZED = 58 + * INVALID_PLUGIN = 59 + * INTERNAL_ERROR = 60 + * 71..99 are reserved as plugin specific errors + */ + virtual uint32_t makePlan(const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal, + double dist_tolerance, double angle_tolerance, + std::vector &plan, double &cost, std::string &message) = 0; + + /** + * @brief Requests the planner to cancel, e.g. if it takes too much time. + * @remark New on MBF API + * @return True if a cancel has been successfully requested, false if not implemented. + */ + virtual bool cancel() = 0; + + /** + * @brief Initialization function for the CostmapPlanner + * @param name The name of this planner + * @param costmap_ros A pointer to the ROS wrapper of the costmap to use for planning + */ + virtual void initialize(std::string name, costmap_2d::Costmap2DROS *costmap_ros) = 0; + + /** + * @brief Virtual destructor for the interface + */ + virtual ~CostmapPlanner(){} + + protected: + CostmapPlanner(){} + + }; +} /* namespace mbf_costmap_core */ + +#endif /* MBF_COSTMAP_CORE__COSTMAP_PLANNER_H_ */ diff --git a/navigations/move_base_flex/mbf_costmap_core/include/mbf_costmap_core/costmap_recovery.h b/navigations/move_base_flex/mbf_costmap_core/include/mbf_costmap_core/costmap_recovery.h new file mode 100755 index 0000000..babbf6b --- /dev/null +++ b/navigations/move_base_flex/mbf_costmap_core/include/mbf_costmap_core/costmap_recovery.h @@ -0,0 +1,94 @@ +/* + * Copyright 2018, Sebastian Pütz + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * abstract_global_planner.h + * + * author: Sebastian Pütz + * + */ + +#ifndef MBF_COSTMAP_CORE__COSTMAP_RECOVERY_H_ +#define MBF_COSTMAP_CORE__COSTMAP_RECOVERY_H_ + +#include +#include +#include + +namespace mbf_costmap_core +{ +/** + * @class CostmapRecovery + * @brief Provides an interface for recovery behaviors used in navigation. + * All recovery behaviors written to work as MBF plugins must adhere to this interface. Alternatively, this + * class can also operate as a wrapper for old API nav_corebased plugins, providing backward compatibility. + */ +class CostmapRecovery : public mbf_abstract_core::AbstractRecovery{ + public: + + typedef boost::shared_ptr< ::mbf_costmap_core::CostmapRecovery> Ptr; + + /** + * @brief Initialization function for the CostmapRecovery + * @param tf A pointer to a transform listener + * @param global_costmap A pointer to the global_costmap used by the navigation stack + * @param local_costmap A pointer to the local_costmap used by the navigation stack + */ + virtual void initialize(std::string name, TF* tf, + costmap_2d::Costmap2DROS* global_costmap, + costmap_2d::Costmap2DROS* local_costmap) = 0; + + /** + * @brief Runs the CostmapRecovery + * @param message The recovery behavior could set, the message should correspond to the return value + * @return An outcome which will be hand over to the action result. + */ + virtual uint32_t runBehavior(std::string& message) = 0; + + /** + * @brief Requests the planner to cancel, e.g. if it takes too much time + * @remark New on MBF API + * @return True if a cancel has been successfully requested, false if not implemented. + */ + virtual bool cancel() = 0; + + /** + * @brief Virtual destructor for the interface + */ + virtual ~CostmapRecovery(){} + + protected: + CostmapRecovery(){} + +}; +} /* namespace mbf_costmap_core */ + +#endif /* MBF_COSTMAP_CORE__COSTMAP_RECOVERY_H_ */ diff --git a/navigations/move_base_flex/mbf_costmap_core/package.xml b/navigations/move_base_flex/mbf_costmap_core/package.xml new file mode 100755 index 0000000..e7513cc --- /dev/null +++ b/navigations/move_base_flex/mbf_costmap_core/package.xml @@ -0,0 +1,26 @@ + + + + mbf_costmap_core + 0.3.2 + + This package provides common interfaces for navigation specific robot actions. It contains the CostmapPlanner, CostmapController and CostmapRecovery interfaces. The interfaces have to be implemented by the plugins to make them available for Move Base Flex using the mbf_costmap_nav navigation implementation. That implementation inherits the mbf_abstract_nav implementation and binds the system to a local and a global costmap. + + http://wiki.ros.org/move_base_flex/mbf_costmap_core + Sebastian Pütz + Jorge Santos + Jorge Santos + Sebastian Pütz + BSD-3 + + catkin + + costmap_2d + geometry_msgs + mbf_abstract_core + mbf_utility + nav_core + std_msgs + tf + + diff --git a/navigations/move_base_flex/mbf_costmap_nav/CHANGELOG.rst b/navigations/move_base_flex/mbf_costmap_nav/CHANGELOG.rst new file mode 100755 index 0000000..80fc77f --- /dev/null +++ b/navigations/move_base_flex/mbf_costmap_nav/CHANGELOG.rst @@ -0,0 +1,55 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package mbf_costmap_nav +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +0.3.2 (2020-05-25) +------------------ +* Remove dependency on base_local_planner and move FootprintHelper class to mbf_costmap_nav and make it static + +0.3.1 (2020-04-07) +------------------ +* Ensure that check_costmap_mutex is destroyed after timer. +* Avoid crash on shutdown by stop shutdown_costmap_timer on destructor + and explicitly call the costmap_nav_srv destructor + +0.3.0 (2020-03-31) +------------------ +* add output for cancel method if nav_core plugin is wrapped +* unify license declaration to BSD-3 + +0.2.5 (2019-10-11) +------------------ +* Add clear_on_shutdown functionality +* Do not pass boost functions to abstract server to (de)activate costmaps. + Run instead abstract methods (possibly) overridden in the costmap server, + all costmap-related handling refactored to a new CostmapWrapper class +* On controller execution, check that local costmap is current + +0.2.4 (2019-06-16) +------------------ +* Add check_point_cost service +* Lock costmaps on clear_costmaps service +* Replace recursive mutexes with normal ones when not needed + +0.2.3 (2018-11-14) +------------------ +* single publisher for controller execution objects + +0.2.2 (2018-10-10) +------------------ +* Do not use MultiThreadedSpinner, as costmap updates can crash when combining laser scans and point clouds +* Make start/stop costmaps mutexed, since concurrent calls to start can lead to segfaults + +0.2.1 (2018-10-03) +------------------ +* Make MBF melodic and indigo compatible +* Fix GoalHandle references bug in callbacks + +0.2.0 (2018-09-11) +------------------ +* Update copyright and 3-clause-BSD license +* Concurrency for planners, controllers and recovery behaviors + +0.1.0 (2018-03-22) +------------------ +* First release of move_base_flex for kinetic and lunar diff --git a/navigations/move_base_flex/mbf_costmap_nav/CMakeLists.txt b/navigations/move_base_flex/mbf_costmap_nav/CMakeLists.txt new file mode 100755 index 0000000..c69c90f --- /dev/null +++ b/navigations/move_base_flex/mbf_costmap_nav/CMakeLists.txt @@ -0,0 +1,110 @@ +cmake_minimum_required(VERSION 2.8.3) +project(mbf_costmap_nav) + +find_package(catkin REQUIRED + COMPONENTS + costmap_2d + dynamic_reconfigure + geometry_msgs + mbf_abstract_nav + mbf_costmap_core + mbf_msgs + mbf_utility + nav_core + nav_msgs + roscpp + std_msgs + std_srvs + tf +) + +find_package(Boost COMPONENTS thread chrono REQUIRED) + +# dynamic reconfigure +generate_dynamic_reconfigure_options( + cfg/MoveBaseFlex.cfg +) + +set(MBF_NAV_CORE_WRAPPER_LIB mbf_nav_core_wrapper) +set(MBF_COSTMAP_2D_SERVER_LIB mbf_costmap_server) +set(MBF_COSTMAP_2D_SERVER_NODE mbf_costmap_nav) + +catkin_package( + INCLUDE_DIRS include + LIBRARIES ${MBF_COSTMAP_2D_SERVER_LIB} + CATKIN_DEPENDS + actionlib + actionlib_msgs + costmap_2d + dynamic_reconfigure + geometry_msgs + mbf_abstract_nav + mbf_costmap_core + mbf_msgs + mbf_utility + nav_core + nav_msgs + pluginlib + roscpp + std_msgs + std_srvs + tf + DEPENDS Boost +) + +include_directories( + include + ${catkin_INCLUDE_DIRS} + ${Boost_INCLUDE_DIRS} +) + +add_library(${MBF_NAV_CORE_WRAPPER_LIB} + src/nav_core_wrapper/wrapper_global_planner.cpp + src/nav_core_wrapper/wrapper_local_planner.cpp + src/nav_core_wrapper/wrapper_recovery_behavior.cpp +) +add_dependencies(${MBF_NAV_CORE_WRAPPER_LIB} ${catkin_EXPORTED_TARGETS}) +target_link_libraries(${MBF_NAV_CORE_WRAPPER_LIB} + ${catkin_LIBRARIES} + ${Boost_LIBRARIES} +) + +add_library(${MBF_COSTMAP_2D_SERVER_LIB} + src/mbf_costmap_nav/costmap_navigation_server.cpp + src/mbf_costmap_nav/costmap_planner_execution.cpp + src/mbf_costmap_nav/costmap_controller_execution.cpp + src/mbf_costmap_nav/costmap_recovery_execution.cpp + src/mbf_costmap_nav/costmap_wrapper.cpp + src/mbf_costmap_nav/footprint_helper.cpp +) +add_dependencies(${MBF_COSTMAP_2D_SERVER_LIB} ${catkin_EXPORTED_TARGETS}) +add_dependencies(${MBF_COSTMAP_2D_SERVER_LIB} ${MBF_NAV_CORE_WRAPPER_LIB}) +add_dependencies(${MBF_COSTMAP_2D_SERVER_LIB} ${PROJECT_NAME}_gencfg) + +target_link_libraries(${MBF_COSTMAP_2D_SERVER_LIB} + ${MBF_NAV_CORE_WRAPPER_LIB} + ${catkin_LIBRARIES} + ${Boost_LIBRARIES} +) + +add_executable(${MBF_COSTMAP_2D_SERVER_NODE} src/move_base_server_node.cpp) +add_dependencies(${MBF_COSTMAP_2D_SERVER_NODE} ${MBF_COSTMAP_2D_SERVER_LIB}) +target_link_libraries(${MBF_COSTMAP_2D_SERVER_NODE} + ${MBF_COSTMAP_2D_SERVER_LIB} + ${catkin_LIBRARIES} +) + +install(TARGETS + ${MBF_NAV_CORE_WRAPPER_LIB} ${MBF_COSTMAP_2D_SERVER_LIB} ${MBF_COSTMAP_2D_SERVER_NODE} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) + +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} +) + +catkin_install_python(PROGRAMS scripts/move_base_legacy_relay.py + DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) diff --git a/navigations/move_base_flex/mbf_costmap_nav/README.md b/navigations/move_base_flex/mbf_costmap_nav/README.md new file mode 100755 index 0000000..62621e4 --- /dev/null +++ b/navigations/move_base_flex/mbf_costmap_nav/README.md @@ -0,0 +1,8 @@ +# Move Base Flex Costmap Navigation Server {#mainpage} + +The mbf_costmap_nav package contains the costmap navigation server implementation of Move Base Flex (MBF). The costmap navigation server is bound to the [costmap_2d](http://wiki.ros.org/costmap_2d) representation. It provides the Actions for planning, controlling and recovering. At the time of start MBF loads all defined plugins. Therefor, it loads all plugins which are defined in the lists *planners*, *controllers* and *recovery_behaviors*. Each list holds a pair of a *name* and a *type*. The *type* defines which kind of plugin to load. The *name* defines under which name the plugin should be callable by the actions. + +Additionally the mbf_costmap_nav package comes with a wrapper for the old navigation stack and the plugins which inherits from the [nav_core](http://wiki.ros.org/nav_core) base classes. Preferably it tries to load plugins for the new api, therefore plugins could even support both [move_base](http://wiki.ros.org/move_base) and [move_base_flex](http://wiki.ros.org/move_base_flex) by inheriting both base classes. + + +![mbf_abstract_nav sketch](doc/images/mbf_costmap_nav_s.png) diff --git a/navigations/move_base_flex/mbf_costmap_nav/cfg/MoveBaseFlex.cfg b/navigations/move_base_flex/mbf_costmap_nav/cfg/MoveBaseFlex.cfg new file mode 100755 index 0000000..baffdfd --- /dev/null +++ b/navigations/move_base_flex/mbf_costmap_nav/cfg/MoveBaseFlex.cfg @@ -0,0 +1,21 @@ +#!/usr/bin/env python + +PACKAGE = 'mbf_costmap_nav' + +from mbf_abstract_nav import add_mbf_abstract_nav_params +from dynamic_reconfigure.parameter_generator_catkin import ParameterGenerator, str_t, double_t, bool_t, int_t + +gen = ParameterGenerator() + +# include the abstract configuration common to all MBF-based navigation plus costmap navigation specific parameters +add_mbf_abstract_nav_params(gen) + +gen.add("shutdown_costmaps", bool_t, 0, + "Determines whether or not to shutdown the costmaps of the node when move_base_flex is in an inactive state", + False) +gen.add("shutdown_costmaps_delay", double_t, 0, + "How long in seconds to wait after last action before shutting down the costmaps", 1.0, 0, 60) + +gen.add("restore_defaults", bool_t, 0, "Restore to the original configuration", False) + +exit(gen.generate(PACKAGE, "mbf_costmap_nav", "MoveBaseFlex")) diff --git a/navigations/move_base_flex/mbf_costmap_nav/doc/images/mbf_costmap_nav.png b/navigations/move_base_flex/mbf_costmap_nav/doc/images/mbf_costmap_nav.png new file mode 100755 index 0000000..a2064c9 Binary files /dev/null and b/navigations/move_base_flex/mbf_costmap_nav/doc/images/mbf_costmap_nav.png differ diff --git a/navigations/move_base_flex/mbf_costmap_nav/doc/images/mbf_costmap_nav_s.png b/navigations/move_base_flex/mbf_costmap_nav/doc/images/mbf_costmap_nav_s.png new file mode 100755 index 0000000..abdde27 Binary files /dev/null and b/navigations/move_base_flex/mbf_costmap_nav/doc/images/mbf_costmap_nav_s.png differ diff --git a/navigations/move_base_flex/mbf_costmap_nav/include/mbf_costmap_nav/costmap_controller_execution.h b/navigations/move_base_flex/mbf_costmap_nav/include/mbf_costmap_nav/costmap_controller_execution.h new file mode 100755 index 0000000..5a99bfa --- /dev/null +++ b/navigations/move_base_flex/mbf_costmap_nav/include/mbf_costmap_nav/costmap_controller_execution.h @@ -0,0 +1,145 @@ +/* + * Copyright 2018, Magazino GmbH, Sebastian Pütz, Jorge Santos Simón + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * costmap_controller_execution.h + * + * authors: + * Sebastian Pütz + * Jorge Santos Simón + * + */ + +#ifndef MBF_COSTMAP_NAV__COSTMAP_CONTROLLER_EXECUTION_H_ +#define MBF_COSTMAP_NAV__COSTMAP_CONTROLLER_EXECUTION_H_ + +#include +#include + +#include "mbf_costmap_nav/MoveBaseFlexConfig.h" +#include "mbf_costmap_nav/costmap_wrapper.h" + + +namespace mbf_costmap_nav +{ +/** + * @brief The CostmapControllerExecution binds a local costmap to the AbstractControllerExecution and uses the + * nav_core/BaseLocalPlanner class as base plugin interface. + * This class makes move_base_flex compatible to the old move_base. + * + * @ingroup controller_execution move_base_server + */ +class CostmapControllerExecution : public mbf_abstract_nav::AbstractControllerExecution +{ +public: + + /** + * @brief Constructor. + * @param controller_name Name of the controller to use. + * @param controller_ptr Shared pointer to the plugin to use. + * @param vel_pub Velocity commands publisher. + * @param goal_pub Goal pose publisher (just vor visualization). + * @param tf_listener_ptr Shared pointer to a common tf listener. + * @param costmap_ptr Shared pointer to the local costmap. + * @param config Current server configuration (dynamic). + */ + CostmapControllerExecution( + const std::string &controller_name, + const mbf_costmap_core::CostmapController::Ptr &controller_ptr, + const ros::Publisher &vel_pub, + const ros::Publisher &goal_pub, + const TFPtr &tf_listener_ptr, + const CostmapWrapper::Ptr &costmap_ptr, + const MoveBaseFlexConfig &config); + + /** + * @brief Destructor + */ + virtual ~CostmapControllerExecution(); + +private: + + /** + * @brief Implementation-specific setup function, called right before execution. + * This method overrides abstract execution empty implementation with underlying map-specific setup code. + */ + void preRun() + { + costmap_ptr_->checkActivate(); + }; + + /** + * @brief Implementation-specific cleanup function, called right after execution. + * This method overrides abstract execution empty implementation with underlying map-specific cleanup code. + */ + void postRun() + { + costmap_ptr_->checkDeactivate(); + }; + + /** + * @brief Implementation-specific safety check, called during execution to ensure it's safe to drive. + * This method overrides abstract execution empty implementation with underlying map-specific checks, + * more precisely if controller costmap is current. + * @return True if costmap is current, false otherwise. + */ + bool safetyCheck(); + + /** + * @brief Request plugin for a new velocity command. We override this method so we can lock the local costmap + * before calling the planner. + * @param pose the current pose of the robot. + * @param velocity the current velocity of the robot. + * @param cmd_vel Will be filled with the velocity command to be passed to the robot base. + * @param message Optional more detailed outcome as a string. + * @return Result code as described on ExePath action result and plugin's header. + */ + virtual uint32_t computeVelocityCmd( + const geometry_msgs::PoseStamped &robot_pose, + const geometry_msgs::TwistStamped &robot_velocity, + geometry_msgs::TwistStamped &vel_cmd, + std::string &message); + + mbf_abstract_nav::MoveBaseFlexConfig toAbstract(const MoveBaseFlexConfig &config); + + //! Shared pointer to thr local costmap + const CostmapWrapper::Ptr &costmap_ptr_; + + //! Whether to lock costmap before calling the controller (see issue #4 for details) + bool lock_costmap_; + + //! name of the controller plugin assigned by the class loader + std::string controller_name_; +}; + +} /* namespace mbf_costmap_nav */ + +#endif /* MBF_COSTMAP_NAV__COSTMAP_CONTROLLER_EXECUTION_H_ */ diff --git a/navigations/move_base_flex/mbf_costmap_nav/include/mbf_costmap_nav/costmap_navigation_server.h b/navigations/move_base_flex/mbf_costmap_nav/include/mbf_costmap_nav/costmap_navigation_server.h new file mode 100755 index 0000000..85bcdac --- /dev/null +++ b/navigations/move_base_flex/mbf_costmap_nav/include/mbf_costmap_nav/costmap_navigation_server.h @@ -0,0 +1,268 @@ +/* + * Copyright 2018, Magazino GmbH, Sebastian Pütz, Jorge Santos Simón + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * costmap_navigation_server.h + * + * authors: + * Sebastian Pütz + * Jorge Santos Simón + * + */ + +#ifndef MBF_COSTMAP_NAV__COSTMAP_NAVIGATION_SERVER_H_ +#define MBF_COSTMAP_NAV__COSTMAP_NAVIGATION_SERVER_H_ + +#include + +#include +#include +#include +#include + +#include +#include +#include + +#include "mbf_costmap_nav/MoveBaseFlexConfig.h" +#include "mbf_costmap_nav/costmap_planner_execution.h" +#include "mbf_costmap_nav/costmap_controller_execution.h" +#include "mbf_costmap_nav/costmap_recovery_execution.h" +#include "mbf_costmap_nav/costmap_wrapper.h" + + +namespace mbf_costmap_nav +{ +/** + * @defgroup move_base_server Move Base Server + * @brief Classes belonging to the Move Base Server level. + */ + + +typedef boost::shared_ptr > DynamicReconfigureServerCostmapNav; + +/** + * @brief The CostmapNavigationServer makes Move Base Flex backwards compatible to the old move_base. It combines the + * execution classes which use the nav_core/BaseLocalPlanner, nav_core/BaseCostmapPlanner and the + * nav_core/RecoveryBehavior base classes as plugin interfaces. These plugin interface are the same for the + * old move_base + * + * @ingroup navigation_server move_base_server + */ +class CostmapNavigationServer : public mbf_abstract_nav::AbstractNavigationServer +{ +public: + + typedef boost::shared_ptr Ptr; + + /** + * @brief Constructor + * @param tf_listener_ptr Shared pointer to a common TransformListener + */ + CostmapNavigationServer(const TFPtr &tf_listener_ptr); + + /** + * @brief Destructor + */ + virtual ~CostmapNavigationServer(); + + virtual void stop(); + +private: + + /** + * @brief Create a new planner execution. + * @param plugin_name Name of the planner to use. + * @param plugin_ptr Shared pointer to the plugin to use. + * @return Shared pointer to a new @ref planner_execution "PlannerExecution". + */ + virtual mbf_abstract_nav::AbstractPlannerExecution::Ptr newPlannerExecution( + const std::string &plugin_name, + const mbf_abstract_core::AbstractPlanner::Ptr plugin_ptr); + + /** + * @brief Create a new controller execution. + * @param plugin_name Name of the controller to use. + * @param plugin_ptr Shared pointer to the plugin to use. + * @return Shared pointer to a new @ref controller_execution "ControllerExecution". + */ + virtual mbf_abstract_nav::AbstractControllerExecution::Ptr newControllerExecution( + const std::string &plugin_name, + const mbf_abstract_core::AbstractController::Ptr plugin_ptr); + + /** + * @brief Create a new recovery behavior execution. + * @param plugin_name Name of the recovery behavior to run. + * @param plugin_ptr Shared pointer to the plugin to use + * @return Shared pointer to a new @ref recovery_execution "RecoveryExecution". + */ + virtual mbf_abstract_nav::AbstractRecoveryExecution::Ptr newRecoveryExecution( + const std::string &plugin_name, + const mbf_abstract_core::AbstractRecovery::Ptr plugin_ptr); + + /** + * @brief Loads the plugin associated with the given planner_type parameter. + * @param planner_type The type of the planner plugin to load. + * @return true, if the local planner plugin was successfully loaded. + */ + virtual mbf_abstract_core::AbstractPlanner::Ptr loadPlannerPlugin(const std::string &planner_type); + + /** + * @brief Initializes the controller plugin with its name and pointer to the costmap + * @param name The name of the planner + * @param planner_ptr pointer to the planner object which corresponds to the name param + * @return true if init succeeded, false otherwise + */ + virtual bool initializePlannerPlugin( + const std::string &name, + const mbf_abstract_core::AbstractPlanner::Ptr &planner_ptr + ); + + /** + * @brief Loads the plugin associated with the given controller type parameter + * @param controller_type The type of the controller plugin + * @return A shared pointer to a new loaded controller, if the controller plugin was loaded successfully, + * an empty pointer otherwise. + */ + virtual mbf_abstract_core::AbstractController::Ptr loadControllerPlugin(const std::string &controller_type); + + /** + * @brief Initializes the controller plugin with its name, a pointer to the TransformListener + * and pointer to the costmap + * @param name The name of the controller + * @param controller_ptr pointer to the controller object which corresponds to the name param + * @return true if init succeeded, false otherwise + */ + virtual bool initializeControllerPlugin( + const std::string &name, + const mbf_abstract_core::AbstractController::Ptr &controller_ptr + ); + + /** + * @brief Loads a Recovery plugin associated with given recovery type parameter + * @param recovery_name The name of the Recovery plugin + * @return A shared pointer to a Recovery plugin, if the plugin was loaded successfully, an empty pointer otherwise. + */ + virtual mbf_abstract_core::AbstractRecovery::Ptr loadRecoveryPlugin(const std::string &recovery_type); + + /** + * @brief Initializes a recovery behavior plugin with its name and pointers to the global and local costmaps + * @param name The name of the recovery behavior + * @param behavior_ptr pointer to the recovery behavior object which corresponds to the name param + * @return true if init succeeded, false otherwise + */ + virtual bool initializeRecoveryPlugin( + const std::string &name, + const mbf_abstract_core::AbstractRecovery::Ptr &behavior_ptr); + + /** + * @brief Callback method for the check_point_cost service + * @param request Request object, see the mbf_msgs/CheckPoint service definition file. + * @param response Response object, see the mbf_msgs/CheckPoint service definition file. + * @return true, if the service completed successfully, false otherwise + */ + bool callServiceCheckPointCost(mbf_msgs::CheckPoint::Request &request, + mbf_msgs::CheckPoint::Response &response); + + /** + * @brief Callback method for the check_pose_cost service + * @param request Request object, see the mbf_msgs/CheckPose service definition file. + * @param response Response object, see the mbf_msgs/CheckPose service definition file. + * @return true, if the service completed successfully, false otherwise + */ + bool callServiceCheckPoseCost(mbf_msgs::CheckPose::Request &request, + mbf_msgs::CheckPose::Response &response); + + /** + * @brief Callback method for the check_path_cost service + * @param request Request object, see the mbf_msgs/CheckPath service definition file. + * @param response Response object, see the mbf_msgs/CheckPath service definition file. + * @return true, if the service completed successfully, false otherwise + */ + bool callServiceCheckPathCost(mbf_msgs::CheckPath::Request &request, + mbf_msgs::CheckPath::Response &response); + + /** + * @brief Callback method for the make_plan service + * @param request Empty request object. + * @param response Empty response object. + * @return true, if the service completed successfully, false otherwise + */ + bool callServiceClearCostmaps(std_srvs::Empty::Request &request, std_srvs::Empty::Response &response); + + /** + * @brief Reconfiguration method called by dynamic reconfigure. + * @param config Configuration parameters. See the MoveBaseFlexConfig definition. + * @param level bit mask, which parameters are set. + */ + void reconfigure(mbf_costmap_nav::MoveBaseFlexConfig &config, uint32_t level); + + pluginlib::ClassLoader recovery_plugin_loader_; + pluginlib::ClassLoader nav_core_recovery_plugin_loader_; + pluginlib::ClassLoader controller_plugin_loader_; + pluginlib::ClassLoader nav_core_controller_plugin_loader_; + pluginlib::ClassLoader planner_plugin_loader_; + pluginlib::ClassLoader nav_core_planner_plugin_loader_; + + //! Dynamic reconfigure server for the mbf_costmap2d_specific part + DynamicReconfigureServerCostmapNav dsrv_costmap_; + + //! last configuration save + mbf_costmap_nav::MoveBaseFlexConfig last_config_; + + //! the default parameter configuration save + mbf_costmap_nav::MoveBaseFlexConfig default_config_; + + //! true, if the dynamic reconfigure has been setup + bool setup_reconfigure_; + + //! Shared pointer to the common local costmap + const CostmapWrapper::Ptr local_costmap_ptr_; + + //! Shared pointer to the common global costmap + const CostmapWrapper::Ptr global_costmap_ptr_; + + //! Service Server for the check_point_cost service + ros::ServiceServer check_point_cost_srv_; + + //! Service Server for the check_pose_cost service + ros::ServiceServer check_pose_cost_srv_; + + //! Service Server for the check_path_cost service + ros::ServiceServer check_path_cost_srv_; + + //! Service Server for the clear_costmap service + ros::ServiceServer clear_costmaps_srv_; +}; + +} /* namespace mbf_costmap_nav */ + +#endif /* MBF_COSTMAP_NAV__COSTMAP_NAVIGATION_SERVER_H_ */ diff --git a/navigations/move_base_flex/mbf_costmap_nav/include/mbf_costmap_nav/costmap_planner_execution.h b/navigations/move_base_flex/mbf_costmap_nav/include/mbf_costmap_nav/costmap_planner_execution.h new file mode 100755 index 0000000..7b1b32c --- /dev/null +++ b/navigations/move_base_flex/mbf_costmap_nav/include/mbf_costmap_nav/costmap_planner_execution.h @@ -0,0 +1,137 @@ +/* + * Copyright 2018, Magazino GmbH, Sebastian Pütz, Jorge Santos Simón + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * costmap_planner_execution.h + * + * authors: + * Sebastian Pütz + * Jorge Santos Simón + * + */ + +#ifndef MBF_COSTMAP_NAV__COSTMAP_PLANNER_EXECUTION_H_ +#define MBF_COSTMAP_NAV__COSTMAP_PLANNER_EXECUTION_H_ + +#include +#include + +#include "mbf_costmap_nav/MoveBaseFlexConfig.h" +#include "mbf_costmap_nav/costmap_wrapper.h" + + +namespace mbf_costmap_nav +{ +/** + * @brief The CostmapPlannerExecution binds a global costmap to the AbstractPlannerExecution and uses the + * nav_core/BaseCostmapPlanner class as base plugin interface. + * This class makes move_base_flex compatible to the old move_base. + * + * @ingroup planner_execution move_base_server + */ +class CostmapPlannerExecution : public mbf_abstract_nav::AbstractPlannerExecution +{ +public: + + /** + * @brief Constructor. + * @param planner_name Name of the planner to use. + * @param planner_ptr Shared pointer to the plugin to use. + * @param costmap_ptr Shared pointer to the global costmap. + * @param config Current server configuration (dynamic). + */ + CostmapPlannerExecution( + const std::string &planner_name, + const mbf_costmap_core::CostmapPlanner::Ptr &planner_ptr, + const CostmapWrapper::Ptr &costmap_ptr, + const MoveBaseFlexConfig &config); + + /** + * @brief Destructor + */ + virtual ~CostmapPlannerExecution(); + + +private: + /** + * @brief Implementation-specific setup function, called right before execution. + * This method overrides abstract execution empty implementation with underlying map-specific setup code. + */ + void preRun() + { + costmap_ptr_->checkActivate(); + }; + + /** + * @brief Implementation-specific cleanup function, called right after execution. + * This method overrides abstract execution empty implementation with underlying map-specific cleanup code. + */ + void postRun() + { + costmap_ptr_->checkDeactivate(); + }; + + mbf_abstract_nav::MoveBaseFlexConfig toAbstract(const MoveBaseFlexConfig &config); + + /** + * @brief Calls the planner plugin to make a plan from the start pose to the goal pose. + * The final pose of the path must be within tolerance range (position and orientation) + * for this method to return a success outcome. + * @param start The start pose for planning + * @param goal The goal pose for planning + * @param dist_tolerance Tolerance in meters to the goal position + * @param angle_tolerance Tolerance in radians to the goal orientation + * @param plan The computed plan by the plugin + * @param cost The computed costs for the corresponding plan + * @param message An optional message which should correspond with the returned outcome + * @return An outcome number, see also the action definition in the GetPath.action file + */ + virtual uint32_t makePlan( + const geometry_msgs::PoseStamped &start, + const geometry_msgs::PoseStamped &goal, + double dist_tolerance, double angle_tolerance, + std::vector &plan, + double &cost, + std::string &message); + + //! Shared pointer to the global planner costmap + const CostmapWrapper::Ptr &costmap_ptr_; + + //! Whether to lock costmap before calling the planner (see issue #4 for details) + bool lock_costmap_; + + //! Name of the planner assigned by the class loader + std::string planner_name_; +}; + +} /* namespace mbf_costmap_nav */ + +#endif /* MBF_COSTMAP_NAV__COSTMAP_PLANNER_EXECUTION_H_ */ diff --git a/navigations/move_base_flex/mbf_costmap_nav/include/mbf_costmap_nav/costmap_recovery_execution.h b/navigations/move_base_flex/mbf_costmap_nav/include/mbf_costmap_nav/costmap_recovery_execution.h new file mode 100755 index 0000000..558cfb0 --- /dev/null +++ b/navigations/move_base_flex/mbf_costmap_nav/include/mbf_costmap_nav/costmap_recovery_execution.h @@ -0,0 +1,120 @@ +/* + * Copyright 2018, Magazino GmbH, Sebastian Pütz, Jorge Santos Simón + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * costmap_recovery_execution.h + * + * authors: + * Sebastian Pütz + * Jorge Santos Simón + * + */ + +#ifndef MBF_COSTMAP_NAV__COSTMAP_RECOVERY_EXECUTION_H_ +#define MBF_COSTMAP_NAV__COSTMAP_RECOVERY_EXECUTION_H_ + +#include +#include + +#include "mbf_costmap_nav/MoveBaseFlexConfig.h" +#include "mbf_costmap_nav/costmap_wrapper.h" + + +namespace mbf_costmap_nav +{ +/** + * @brief The CostmapRecoveryExecution binds a local and a global costmap to the AbstractRecoveryExecution and uses the + * nav_core/CostmapRecovery class as base plugin interface. + * This class makes move_base_flex compatible to the old move_base. + * + * @ingroup recovery_execution move_base_server + */ +class CostmapRecoveryExecution : public mbf_abstract_nav::AbstractRecoveryExecution +{ + +public: + typedef boost::shared_ptr Ptr; + + /** + * @brief Constructor. + * @param recovery_name Name of the recovery behavior to run. + * @param recovery_ptr Shared pointer to the plugin to use. + * @param tf_listener_ptr Shared pointer to a common tf listener + * @param global_costmap Shared pointer to the global costmap. + * @param local_costmap Shared pointer to the local costmap. + * @param config Current server configuration (dynamic). + */ + CostmapRecoveryExecution( + const std::string &recovery_name, + const mbf_costmap_core::CostmapRecovery::Ptr &recovery_ptr, + const TFPtr &tf_listener_ptr, + const CostmapWrapper::Ptr &global_costmap, + const CostmapWrapper::Ptr &local_costmap, + const MoveBaseFlexConfig &config); + + /** + * Destructor + */ + virtual ~CostmapRecoveryExecution(); + +private: + /** + * @brief Implementation-specific setup function, called right before execution. + * This method overrides abstract execution empty implementation with underlying map-specific setup code. + */ + void preRun() + { + local_costmap_->checkActivate(); + global_costmap_->checkActivate(); + }; + + /** + * @brief Implementation-specific cleanup function, called right after execution. + * This method overrides abstract execution empty implementation with underlying map-specific cleanup code. + */ + void postRun() + { + local_costmap_->checkDeactivate(); + global_costmap_->checkDeactivate(); + }; + + mbf_abstract_nav::MoveBaseFlexConfig toAbstract(const MoveBaseFlexConfig &config); + + //! Shared pointer to the global costmap + const CostmapWrapper::Ptr &global_costmap_; + + //! Shared pointer to thr local costmap + const CostmapWrapper::Ptr &local_costmap_; +}; + +} /* namespace mbf_costmap_nav */ + +#endif /* MBF_COSTMAP_NAV__COSTMAP_RECOVERY_EXECUTION_H_ */ diff --git a/navigations/move_base_flex/mbf_costmap_nav/include/mbf_costmap_nav/costmap_wrapper.h b/navigations/move_base_flex/mbf_costmap_nav/include/mbf_costmap_nav/costmap_wrapper.h new file mode 100755 index 0000000..49f890c --- /dev/null +++ b/navigations/move_base_flex/mbf_costmap_nav/include/mbf_costmap_nav/costmap_wrapper.h @@ -0,0 +1,120 @@ +/* + * Copyright 2019, Magazino GmbH, Sebastian Pütz, Jorge Santos Simón + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * costmap_wrapper.h + * + * authors: + * Sebastian Pütz + * Jorge Santos Simón + * + */ + +#ifndef MBF_COSTMAP_NAV__COSTMAP_WRAPPER_H_ +#define MBF_COSTMAP_NAV__COSTMAP_WRAPPER_H_ + +#include + +#include + + +namespace mbf_costmap_nav +{ +/** + * @defgroup move_base_server Move Base Server + * @brief Classes belonging to the Move Base Server level. + */ + + +/** + * @brief The CostmapWrapper class manages access to a costmap by locking/unlocking its mutex and handles + * (de)activation. + * + * @ingroup navigation_server move_base_server + */ +class CostmapWrapper : public costmap_2d::Costmap2DROS +{ +public: + typedef boost::shared_ptr Ptr; + + /** + * @brief Constructor + * @param tf_listener_ptr Shared pointer to a common TransformListener + */ + CostmapWrapper(const std::string &name, const TFPtr &tf_listener_ptr); + + /** + * @brief Destructor + */ + virtual ~CostmapWrapper(); + + /** + * @brief Reconfiguration method called by dynamic reconfigure. + * @param shutdown_costmap Determines whether or not to shutdown the costmap when move_base_flex is inactive. + * @param shutdown_costmap_delay How long in seconds to wait after last action before shutting down the costmap. + */ + void reconfigure(double shutdown_costmap, double shutdown_costmap_delay); + + /** + * @brief Clear costmap. + */ + void clear(); + + /** + * @brief Check whether the costmap should be activated. + */ + void checkActivate(); + + /** + * @brief Check whether the costmap should and could be deactivated. + */ + void checkDeactivate(); + +private: + /** + * @brief Timer-triggered deactivation of the costmap. + */ + void deactivate(const ros::TimerEvent &event); + + //! Private node handle + ros::NodeHandle private_nh_; + + boost::mutex check_costmap_mutex_; //!< Start/stop costmap mutex; concurrent calls to start can lead to segfault + bool shutdown_costmap_; //!< don't update costmap when not using it + bool clear_on_shutdown_; //!< clear the costmap, when shutting down + int16_t costmap_users_; //!< keep track of plugins using costmap + ros::Timer shutdown_costmap_timer_; //!< costmap delayed shutdown timer + ros::Duration shutdown_costmap_delay_; //!< costmap delayed shutdown delay +}; + +} /* namespace mbf_costmap_nav */ + +#endif /* MBF_COSTMAP_NAV__COSTMAP_WRAPPER_H_ */ diff --git a/navigations/move_base_flex/mbf_costmap_nav/include/mbf_costmap_nav/footprint_helper.h b/navigations/move_base_flex/mbf_costmap_nav/include/mbf_costmap_nav/footprint_helper.h new file mode 100755 index 0000000..5d934e0 --- /dev/null +++ b/navigations/move_base_flex/mbf_costmap_nav/include/mbf_costmap_nav/footprint_helper.h @@ -0,0 +1,89 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2008, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: TKruse + *********************************************************************/ + +#ifndef FOOTPRINT_HELPER_H_ +#define FOOTPRINT_HELPER_H_ + +#include + +#include +#include + +namespace mbf_costmap_nav +{ + +struct Cell +{ + unsigned int x, y; +}; + +class FootprintHelper +{ +public: + /** + * @brief Used to get the cells that make up the footprint of the robot + * @param x The x position of the robot + * @param y The y position of the robot + * @param theta The orientation of the robot + * @param fill If true: returns all cells in the footprint of the robot. If false: returns only the cells that make up the outline of the footprint. + * @return The cells that make up either the outline or entire footprint of the robot depending on fill + */ + static std::vector getFootprintCells( + double x, double y, double theta, + std::vector footprint_spec, + const costmap_2d::Costmap2D&, + bool fill); + + /** + * @brief Use Bresenham's algorithm to trace a line between two points in a grid + * @param x0 The x coordinate of the first point + * @param x1 The x coordinate of the second point + * @param y0 The y coordinate of the first point + * @param y1 The y coordinate of the second point + * @param pts Will be filled with the cells that lie on the line in the grid + */ + static void getLineCells(int x0, int x1, int y0, int y1, std::vector& pts); + + /** + * @brief Fill the outline of a polygon, in this case the robot footprint, in a grid + * @param footprint The list of cells making up the footprint in the grid, will be modified to include all cells inside the footprint + */ + static void getFillCells(std::vector& footprint); +}; + +} /* namespace mbf_costmap_nav */ +#endif /* FOOTPRINT_HELPER_H_ */ diff --git a/navigations/move_base_flex/mbf_costmap_nav/include/nav_core_wrapper/wrapper_global_planner.h b/navigations/move_base_flex/mbf_costmap_nav/include/nav_core_wrapper/wrapper_global_planner.h new file mode 100755 index 0000000..ae8e469 --- /dev/null +++ b/navigations/move_base_flex/mbf_costmap_nav/include/nav_core_wrapper/wrapper_global_planner.h @@ -0,0 +1,105 @@ +/* + * Copyright 2018, Magazino GmbH, Sebastian Pütz, Jorge Santos Simón + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * wrapper_global_planner.cpp + * + * authors: + * Sebastian Pütz + * Jorge Santos Simón + * + */ + +#ifndef MBF_COSTMAP_NAV__WRAPPER_GLOBAL_PLANNER_H_ +#define MBF_COSTMAP_NAV__WRAPPER_GLOBAL_PLANNER_H_ + +#include +#include "mbf_costmap_core/costmap_planner.h" + +namespace mbf_nav_core_wrapper { + /** + * @class CostmapPlanner + * @brief Provides an interface for global planners used in navigation. + * All global planners written to work as MBF plugins must adhere to this interface. Alternatively, this + * class can also operate as a wrapper for old API nav_core-based plugins, providing backward compatibility. + */ + class WrapperGlobalPlanner : public mbf_costmap_core::CostmapPlanner{ + public: + + /** + * @brief Given a goal pose in the world, compute a plan + * The final pose of the path must be within tolerance range (position and orientation) + * for this method to return a success outcome. + * @param start The start pose + * @param goal The goal pose + * @param dist_tolerance Tolerance in meters to the goal position + * @param angle_tolerance Tolerance in radians to the goal orientation + * @param plan The plan... filled by the planner + * @param cost The cost for the the plan + * @param message Optional more detailed outcome as a string + * @return Result code as described on GetPath action result, As this is a wrapper to the nav_core, + * only 0 (SUCCESS) and 50 (FAILURE) are supported + */ + virtual uint32_t makePlan(const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal, + double dist_tolerance, double angle_tolerance, + std::vector &plan, double &cost, std::string &message); + + /** + * @brief Requests the planner to cancel, e.g. if it takes too much time. + * @remark New on MBF API + * @return True if a cancel has been successfully requested, false if not implemented. + */ + virtual bool cancel(); + + /** + * @brief Initialization function for the CostmapPlanner + * @param name The name of this planner + * @param costmap_ros A pointer to the ROS wrapper of the costmap to use for planning + */ + virtual void initialize(std::string name, costmap_2d::Costmap2DROS *costmap_ros); + + /** + * @brief Public constructor used for handling a nav_core-based plugin + * @param plugin Backward compatible plugin + */ + WrapperGlobalPlanner(boost::shared_ptr< nav_core::BaseGlobalPlanner > plugin); + + /** + * @brief Virtual destructor for the interface + */ + virtual ~WrapperGlobalPlanner(); + + private: + boost::shared_ptr< nav_core::BaseGlobalPlanner > nav_core_plugin_; + }; +} /* namespace mbf_nav_core_wrapper */ + +#endif /* MBF_COSTMAP_NAV__WRAPPER_GLOBAL_PLANNER_H_ */ diff --git a/navigations/move_base_flex/mbf_costmap_nav/include/nav_core_wrapper/wrapper_local_planner.h b/navigations/move_base_flex/mbf_costmap_nav/include/nav_core_wrapper/wrapper_local_planner.h new file mode 100755 index 0000000..aceb691 --- /dev/null +++ b/navigations/move_base_flex/mbf_costmap_nav/include/nav_core_wrapper/wrapper_local_planner.h @@ -0,0 +1,127 @@ +/* + * Copyright 2018, Magazino GmbH, Sebastian Pütz, Jorge Santos Simón + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * wrapper_local_planner.cpp + * + * authors: + * Sebastian Pütz + * Jorge Santos Simón + * + */ + +#ifndef MBF_COSTMAP_NAV__WRAPPER_LOCAL_PLANNER_H_ +#define MBF_COSTMAP_NAV__WRAPPER_LOCAL_PLANNER_H_ + +#include +#include "mbf_costmap_core/costmap_controller.h" + +#include + +namespace mbf_nav_core_wrapper { + /** + * @class LocalPlanner + * @brief Provides an interface for local planners used in navigation. + * All local planners written to work as MBF plugins must adhere to this interface. Alternatively, this + * class can also operate as a wrapper for old API nav_core-based plugins, providing backward compatibility. + */ + class WrapperLocalPlanner : public mbf_costmap_core::CostmapController{ + public: + + /** + * @brief Given the current position, orientation, and velocity of the robot, + * compute velocity commands to send to the base + * @remark New on MBF API; replaces version without output code and message + * @param cmd_vel Will be filled with the velocity command to be passed to the robot base + * @param message Optional more detailed outcome as a string + * @return Result code as described on ExePath action result, as this is a wrapper to the nav_core, + * only 0 (SUCCESS) and 100 (FAILURE) are supported. + */ + virtual uint32_t computeVelocityCommands( + const geometry_msgs::PoseStamped &robot_pose, + const geometry_msgs::TwistStamped &robot_velocity, + geometry_msgs::TwistStamped &cmd_vel, + std::string &message); + + /** + * @brief Check if the goal pose has been achieved by the local planner + * @return True if achieved, false otherwise + */ + virtual bool isGoalReached(); + + /** + * @brief Check if the goal pose has been achieved by the local planner within tolerance limits + * @remark New on MBF API + * @param xy_tolerance Distance tolerance in meters + * @param yaw_tolerance Heading tolerance in radians + * @return True if achieved, false otherwise + */ + virtual bool isGoalReached(double xy_tolerance, double yaw_tolerance); + + /** + * @brief Set the plan that the local planner is following + * @param plan The plan to pass to the local planner + * @return True if the plan was updated successfully, false otherwise + */ + virtual bool setPlan(const std::vector &plan); + + /** + * @brief Requests the planner to cancel, e.g. if it takes too much time + * @remark New on MBF API + * @return True if a cancel has been successfully requested, false if not implemented. + */ + virtual bool cancel(); + + /** + * @brief Constructs the local planner + * @param name The name to give this instance of the local planner + * @param tf A pointer to a transform listener + * @param costmap_ros The cost map to use for assigning costs to local plans + */ + virtual void initialize(std::string name, TF *tf, costmap_2d::Costmap2DROS *costmap_ros); + + /** + * @brief Public constructor used for handling a nav_core-based plugin + * @param plugin Backward compatible plugin + */ + WrapperLocalPlanner(boost::shared_ptr< nav_core::BaseLocalPlanner >plugin); + + /** + * @brief Virtual destructor for the interface + */ + virtual ~WrapperLocalPlanner(); + + private: + boost::shared_ptr< nav_core::BaseLocalPlanner > nav_core_plugin_; + }; +} /* namespace mbf_nav_core_wrapper */ + +#endif /* MBF_COSTMAP_NAV__WRAPPER_LOCAL_PLANNER_H_ */ diff --git a/navigations/move_base_flex/mbf_costmap_nav/include/nav_core_wrapper/wrapper_recovery_behavior.h b/navigations/move_base_flex/mbf_costmap_nav/include/nav_core_wrapper/wrapper_recovery_behavior.h new file mode 100755 index 0000000..5929c57 --- /dev/null +++ b/navigations/move_base_flex/mbf_costmap_nav/include/nav_core_wrapper/wrapper_recovery_behavior.h @@ -0,0 +1,96 @@ +/* + * Copyright 2018, Magazino GmbH, Sebastian Pütz, Jorge Santos Simón + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * wrapper_recovery_behavior.cpp + * + * authors: + * Sebastian Pütz + * Jorge Santos Simón + * + */ + +#ifndef MBF_COSTMAP_NAV__WRAPPER_RECOVERY_BEHAVIOR_H_ +#define MBF_COSTMAP_NAV__WRAPPER_RECOVERY_BEHAVIOR_H_ + +#include +#include "mbf_costmap_core/costmap_recovery.h" + +#include +namespace mbf_nav_core_wrapper { + /** + * @class CostmapRecovery + * @brief Provides an interface for recovery behaviors used in navigation. + * All recovery behaviors written to work as MBF plugins must adhere to this interface. Alternatively, this + * class can also operate as a wrapper for old API nav_core-based plugins, providing backward compatibility. + */ + class WrapperRecoveryBehavior : public mbf_costmap_core::CostmapRecovery{ + public: + + /** + * @brief Initialization function for the CostmapRecovery + * @param tf A pointer to a transform listener + * @param global_costmap A pointer to the global_costmap used by the navigation stack + * @param local_costmap A pointer to the local_costmap used by the navigation stack + */ + virtual void initialize(std::string name, TF* tf, + costmap_2d::Costmap2DROS* global_costmap, + costmap_2d::Costmap2DROS* local_costmap); + + /** + * @brief Runs the CostmapRecovery + */ + virtual uint32_t runBehavior(std::string &message); + + /** + * @brief Requests the planner to cancel, e.g. if it takes too much time + * @remark New on MBF API + * @return True if a cancel has been successfully requested, false if not implemented. + */ + virtual bool cancel(); + + /** + * @brief Public constructor used for handling a nav_core-based plugin + * @param plugin Backward compatible plugin + */ + WrapperRecoveryBehavior(boost::shared_ptr< nav_core::RecoveryBehavior > plugin); + + /** + * @brief Virtual destructor for the interface + */ + virtual ~WrapperRecoveryBehavior(); + + private: + boost::shared_ptr< nav_core::RecoveryBehavior > nav_core_plugin_; + }; +}; /* namespace mbf_nav_core_wrapper */ + +#endif /* MBF_COSTMAP_NAV__WRAPPER_RECOVERY_BEHAVIOR_H_ */ diff --git a/navigations/move_base_flex/mbf_costmap_nav/package.xml b/navigations/move_base_flex/mbf_costmap_nav/package.xml new file mode 100755 index 0000000..c86607f --- /dev/null +++ b/navigations/move_base_flex/mbf_costmap_nav/package.xml @@ -0,0 +1,41 @@ + + mbf_costmap_nav + 0.3.2 + + The mbf_costmap_nav package contains the costmap navigation server implementation of Move Base Flex (MBF). The costmap navigation server is bound to the costmap_2d representation. It provides the Actions for planning, controlling and recovering. At the time of start MBF loads all defined plugins. Therefor, it loads all plugins which are defined in the lists *planners*, *controllers* and *recovery_behaviors*. Each list holds a pair of a *name* and a *type*. The *type* defines which kind of plugin to load. The *name* defines under which name the plugin should be callable by the actions. + + Additionally the mbf_costmap_nav package comes with a wrapper for the old navigation stack and the plugins which inherits from the nav_core base classes. Preferably it tries to load plugins for the new API. However, plugins could even support both move_base and move_base_flex by inheriting both base class interfaces located in the nav_core package and in the mbf_costmap_core package. + + http://wiki.ros.org/move_base_flex + Sebastian Pütz + Sebastian Pütz + Jorge Santos + BSD-3 + + catkin + + actionlib + actionlib_msgs + costmap_2d + dynamic_reconfigure + geometry_msgs + mbf_abstract_nav + mbf_costmap_core + mbf_msgs + mbf_utility + nav_core + nav_msgs + pluginlib + roscpp + std_msgs + std_srvs + tf + + + move_base + move_base_msgs + + + + + diff --git a/navigations/move_base_flex/mbf_costmap_nav/rosdoc.yaml b/navigations/move_base_flex/mbf_costmap_nav/rosdoc.yaml new file mode 100755 index 0000000..772ff48 --- /dev/null +++ b/navigations/move_base_flex/mbf_costmap_nav/rosdoc.yaml @@ -0,0 +1,4 @@ + - builder: doxygen + name: Move Base Flex + homepage: http://wiki.ros.org/move_base_flex + file_patterns: '*.c *.cpp *.h *.cc *.hh *.py *.md' diff --git a/navigations/move_base_flex/mbf_costmap_nav/scripts/move_base_legacy_relay.py b/navigations/move_base_flex/mbf_costmap_nav/scripts/move_base_legacy_relay.py new file mode 100755 index 0000000..ea64b63 --- /dev/null +++ b/navigations/move_base_flex/mbf_costmap_nav/scripts/move_base_legacy_relay.py @@ -0,0 +1,144 @@ +#!/usr/bin/env python +# +# @author Jorge Santos +# License: 3-Clause BSD + +import actionlib +import copy + +import rospy +import nav_msgs.srv as nav_srvs +import mbf_msgs.msg as mbf_msgs +import move_base_msgs.msg as mb_msgs +from dynamic_reconfigure.client import Client +from dynamic_reconfigure.server import Server +from geometry_msgs.msg import PoseStamped +from move_base.cfg import MoveBaseConfig + + +""" +move_base legacy relay node: +Relays old move_base actions to the new mbf move_base action, similar but with richer result and feedback. +We also relay the simple goal topic published by RViz, the make_plan service and dynamic reconfiguration +calls (note that some parameters have changed names; see http://wiki.ros.org/move_base_flex for details) +""" + +# keep configured base local and global planners to send to MBF +bgp = None +blp = None + + +def simple_goal_cb(msg): + mbf_mb_ac.send_goal(mbf_msgs.MoveBaseGoal(target_pose=msg, planner=bgp, controller=blp)) + rospy.logdebug("Relaying move_base_simple/goal pose to mbf") + + +def mb_execute_cb(msg): + mbf_mb_ac.send_goal(mbf_msgs.MoveBaseGoal(target_pose=msg.target_pose, planner=bgp, controller=blp), + feedback_cb=mbf_feedback_cb) + rospy.logdebug("Relaying legacy move_base goal to mbf") + mbf_mb_ac.wait_for_result() + + status = mbf_mb_ac.get_state() + result = mbf_mb_ac.get_result() + + rospy.logdebug("MBF execution completed with result [%d]: %s", result.outcome, result.message) + if result.outcome == mbf_msgs.MoveBaseResult.SUCCESS: + mb_as.set_succeeded(mb_msgs.MoveBaseResult(), "Goal reached.") + else: + mb_as.set_aborted(mb_msgs.MoveBaseResult(), result.message) + + +def make_plan_cb(request): + mbf_gp_ac.send_goal(mbf_msgs.GetPathGoal(start_pose=request.start, target_pose=request.goal, + use_start_pose=bool(request.start.header.frame_id), planner=bgp, + dist_tolerance=request.tolerance, angle_tolerance=request.tolerance, + tolerance_from_action=bool(request.tolerance > 0.0))) + rospy.logdebug("Relaying legacy make_plan service to mbf get_path action server") + mbf_gp_ac.wait_for_result() + + status = mbf_gp_ac.get_state() + result = mbf_gp_ac.get_result() + + rospy.logdebug("MBF get_path execution completed with result [%d]: %s", result.outcome, result.message) + if result.outcome == mbf_msgs.GetPathResult.SUCCESS: + return nav_srvs.GetPlanResponse(plan=result.path) + + +def mbf_feedback_cb(feedback): + mb_as.publish_feedback(mb_msgs.MoveBaseFeedback(base_position=feedback.current_pose)) + + +def mb_reconf_cb(config, level): + rospy.logdebug("Relaying legacy move_base reconfigure request to mbf") + + if not hasattr(mb_reconf_cb, "default_config"): + mb_reconf_cb.default_config = copy.deepcopy(config) + + if config.get('restore_defaults'): + config = mb_reconf_cb.default_config + + mbf_config = copy.deepcopy(config) + + # Map move_base legacy parameters to new mbf ones, and drop those not supported + # mbf doesn't allow changing plugins dynamically, but we can provide them in the + # action goal, so we keep both base_local_planner and base_global_planner + if 'base_local_planner' in mbf_config: + global blp + blp = mbf_config.pop('base_local_planner') + if 'controller_frequency' in mbf_config: + mbf_config['controller_frequency'] = mbf_config.pop('controller_frequency') + if 'controller_patience' in mbf_config: + mbf_config['controller_patience'] = mbf_config.pop('controller_patience') + if 'max_controller_retries' in mbf_config: + mbf_config['controller_max_retries'] = mbf_config.pop('max_controller_retries') + if 'base_global_planner' in mbf_config: + global bgp + bgp = mbf_config.pop('base_global_planner') + if 'planner_frequency' in mbf_config: + mbf_config['planner_frequency'] = mbf_config.pop('planner_frequency') + if 'planner_patience' in mbf_config: + mbf_config['planner_patience'] = mbf_config.pop('planner_patience') + if 'max_planning_retries' in mbf_config: + mbf_config['planner_max_retries'] = mbf_config.pop('max_planning_retries') + if 'recovery_behavior_enabled' in mbf_config: + mbf_config['recovery_enabled'] = mbf_config.pop('recovery_behavior_enabled') + if 'conservative_reset_dist' in mbf_config: + mbf_config.pop('conservative_reset_dist') # no mbf equivalent for this! + if 'clearing_rotation_allowed' in mbf_config: + mbf_config.pop('clearing_rotation_allowed') # no mbf equivalent for this! + if 'make_plan_add_unreachable_goal' in mbf_config: + mbf_config.pop('make_plan_add_unreachable_goal') # no mbf equivalent for this! + if 'make_plan_clear_costmap' in mbf_config: + mbf_config.pop('make_plan_clear_costmap') # no mbf equivalent for this! + mbf_drc.update_configuration(mbf_config) + return config + + +if __name__ == '__main__': + rospy.init_node("move_base") + + # TODO what happens with malformed target goal??? FAILURE or INVALID_POSE + # txt must be: "Aborting on goal because it was sent with an invalid quaternion" + + # move_base_flex get_path and move_base action clients + mbf_mb_ac = actionlib.SimpleActionClient("move_base_flex/move_base", mbf_msgs.MoveBaseAction) + mbf_gp_ac = actionlib.SimpleActionClient("move_base_flex/get_path", mbf_msgs.GetPathAction) + mbf_mb_ac.wait_for_server(rospy.Duration(20)) + mbf_gp_ac.wait_for_server(rospy.Duration(10)) + + # move_base_flex dynamic reconfigure client + mbf_drc = Client("move_base_flex", timeout=10) + + # move_base simple topic and action server + mb_sg = rospy.Subscriber('move_base_simple/goal', PoseStamped, simple_goal_cb) + mb_as = actionlib.SimpleActionServer('move_base', mb_msgs.MoveBaseAction, mb_execute_cb, auto_start=False) + mb_as.start() + + # move_base make_plan service + mb_mps = rospy.Service('~make_plan', nav_srvs.GetPlan, make_plan_cb) + + # move_base dynamic reconfigure server + mb_drs = Server(MoveBaseConfig, mb_reconf_cb) + + rospy.spin() diff --git a/navigations/move_base_flex/mbf_costmap_nav/src/mbf_costmap_nav/costmap_controller_execution.cpp b/navigations/move_base_flex/mbf_costmap_nav/src/mbf_costmap_nav/costmap_controller_execution.cpp new file mode 100755 index 0000000..3e5547b --- /dev/null +++ b/navigations/move_base_flex/mbf_costmap_nav/src/mbf_costmap_nav/costmap_controller_execution.cpp @@ -0,0 +1,103 @@ +/* + * Copyright 2018, Magazino GmbH, Sebastian Pütz, Jorge Santos Simón + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * costmap_controller_execution.cpp + * + * authors: + * Sebastian Pütz + * Jorge Santos Simón + * + */ +#include "mbf_costmap_nav/costmap_controller_execution.h" + +namespace mbf_costmap_nav +{ + +CostmapControllerExecution::CostmapControllerExecution( + const std::string &controller_name, + const mbf_costmap_core::CostmapController::Ptr &controller_ptr, + const ros::Publisher &vel_pub, + const ros::Publisher &goal_pub, + const TFPtr &tf_listener_ptr, + const CostmapWrapper::Ptr &costmap_ptr, + const MoveBaseFlexConfig &config) + : AbstractControllerExecution(controller_name, controller_ptr, vel_pub, goal_pub, + tf_listener_ptr, toAbstract(config)), + costmap_ptr_(costmap_ptr) +{ + ros::NodeHandle private_nh("~"); + private_nh.param("controller_lock_costmap", lock_costmap_, true); +} + +CostmapControllerExecution::~CostmapControllerExecution() +{ +} + +mbf_abstract_nav::MoveBaseFlexConfig CostmapControllerExecution::toAbstract(const MoveBaseFlexConfig &config) +{ + // copy the controller-related abstract configuration common to all MBF-based navigation + mbf_abstract_nav::MoveBaseFlexConfig abstract_config; + abstract_config.controller_frequency = config.controller_frequency; + abstract_config.controller_patience = config.controller_patience; + abstract_config.controller_max_retries = config.controller_max_retries; + abstract_config.oscillation_timeout = config.oscillation_timeout; + abstract_config.oscillation_distance = config.oscillation_distance; + return abstract_config; +} + +uint32_t CostmapControllerExecution::computeVelocityCmd( + const geometry_msgs::PoseStamped &robot_pose, + const geometry_msgs::TwistStamped &robot_velocity, + geometry_msgs::TwistStamped &vel_cmd, + std::string &message) +{ + // Lock the costmap while planning, but following issue #4, we allow to move the responsibility to the planner itself + if (lock_costmap_) + { + boost::lock_guard lock(*(costmap_ptr_->getCostmap()->getMutex())); + return controller_->computeVelocityCommands(robot_pose, robot_velocity, vel_cmd, message); + } + return controller_->computeVelocityCommands(robot_pose, robot_velocity, vel_cmd, message); +} + +bool CostmapControllerExecution::safetyCheck() +{ + // Check that the observation buffers for the costmap are current, we don't want to drive blind + if (!costmap_ptr_->isCurrent()) + { + ROS_WARN("Sensor data is out of date, we're not going to allow commanding of the base for safety"); + return false; + } + return true; +} + +} /* namespace mbf_costmap_nav */ diff --git a/navigations/move_base_flex/mbf_costmap_nav/src/mbf_costmap_nav/costmap_navigation_server.cpp b/navigations/move_base_flex/mbf_costmap_nav/src/mbf_costmap_nav/costmap_navigation_server.cpp new file mode 100755 index 0000000..8417e4c --- /dev/null +++ b/navigations/move_base_flex/mbf_costmap_nav/src/mbf_costmap_nav/costmap_navigation_server.cpp @@ -0,0 +1,718 @@ +/* + * Copyright 2018, Magazino GmbH, Sebastian Pütz, Jorge Santos Simón + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * costmap_navigation_server.cpp + * + * authors: + * Sebastian Pütz + * Jorge Santos Simón + * + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "mbf_costmap_nav/footprint_helper.h" +#include "mbf_costmap_nav/costmap_navigation_server.h" + +namespace mbf_costmap_nav +{ + + +CostmapNavigationServer::CostmapNavigationServer(const TFPtr &tf_listener_ptr) : + AbstractNavigationServer(tf_listener_ptr), + recovery_plugin_loader_("mbf_costmap_core", "mbf_costmap_core::CostmapRecovery"), + nav_core_recovery_plugin_loader_("nav_core", "nav_core::RecoveryBehavior"), + controller_plugin_loader_("mbf_costmap_core", "mbf_costmap_core::CostmapController"), + nav_core_controller_plugin_loader_("nav_core", "nav_core::BaseLocalPlanner"), + planner_plugin_loader_("mbf_costmap_core", "mbf_costmap_core::CostmapPlanner"), + nav_core_planner_plugin_loader_("nav_core", "nav_core::BaseGlobalPlanner"), + global_costmap_ptr_(new CostmapWrapper("global_costmap", tf_listener_ptr_)), + local_costmap_ptr_(new CostmapWrapper("local_costmap", tf_listener_ptr_)), + setup_reconfigure_(false) +{ + // advertise services and current goal topic + check_point_cost_srv_ = private_nh_.advertiseService("check_point_cost", + &CostmapNavigationServer::callServiceCheckPointCost, this); + check_pose_cost_srv_ = private_nh_.advertiseService("check_pose_cost", + &CostmapNavigationServer::callServiceCheckPoseCost, this); + check_path_cost_srv_ = private_nh_.advertiseService("check_path_cost", + &CostmapNavigationServer::callServiceCheckPathCost, this); + clear_costmaps_srv_ = private_nh_.advertiseService("clear_costmaps", + &CostmapNavigationServer::callServiceClearCostmaps, this); + + // dynamic reconfigure server for mbf_costmap_nav configuration; also include abstract server parameters + dsrv_costmap_ = boost::make_shared >(private_nh_); + dsrv_costmap_->setCallback(boost::bind(&CostmapNavigationServer::reconfigure, this, _1, _2)); + + // initialize all plugins + initializeServerComponents(); + + // start all action servers + startActionServers(); +} + +CostmapNavigationServer::~CostmapNavigationServer() +{ + // remove every plugin before its classLoader goes out of scope. + controller_plugin_manager_.clearPlugins(); + planner_plugin_manager_.clearPlugins(); + recovery_plugin_manager_.clearPlugins(); + + action_server_recovery_ptr_.reset(); + action_server_exe_path_ptr_.reset(); + action_server_get_path_ptr_.reset(); + action_server_move_base_ptr_.reset(); +} + +mbf_abstract_nav::AbstractPlannerExecution::Ptr CostmapNavigationServer::newPlannerExecution( + const std::string &plugin_name, + const mbf_abstract_core::AbstractPlanner::Ptr plugin_ptr) +{ + return boost::make_shared( + plugin_name, + boost::static_pointer_cast(plugin_ptr), + global_costmap_ptr_, + last_config_); +} + +mbf_abstract_nav::AbstractControllerExecution::Ptr CostmapNavigationServer::newControllerExecution( + const std::string &plugin_name, + const mbf_abstract_core::AbstractController::Ptr plugin_ptr) +{ + return boost::make_shared( + plugin_name, + boost::static_pointer_cast(plugin_ptr), + vel_pub_, + goal_pub_, + tf_listener_ptr_, + local_costmap_ptr_, + last_config_); +} + +mbf_abstract_nav::AbstractRecoveryExecution::Ptr CostmapNavigationServer::newRecoveryExecution( + const std::string &plugin_name, + const mbf_abstract_core::AbstractRecovery::Ptr plugin_ptr) +{ + return boost::make_shared( + plugin_name, + boost::static_pointer_cast(plugin_ptr), + tf_listener_ptr_, + global_costmap_ptr_, + local_costmap_ptr_, + last_config_); +} + +mbf_abstract_core::AbstractPlanner::Ptr CostmapNavigationServer::loadPlannerPlugin(const std::string &planner_type) +{ + mbf_abstract_core::AbstractPlanner::Ptr planner_ptr; + try + { + planner_ptr = boost::static_pointer_cast( + planner_plugin_loader_.createInstance(planner_type)); + std::string planner_name = planner_plugin_loader_.getName(planner_type); + ROS_DEBUG_STREAM("mbf_costmap_core-based planner plugin " << planner_name << " loaded."); + } + catch (const pluginlib::PluginlibException &ex_mbf_core) + { + ROS_DEBUG_STREAM("Failed to load the " << planner_type << " planner as a mbf_costmap_core-based plugin." + << " Try to load as a nav_core-based plugin. " << ex_mbf_core.what()); + try + { + // For plugins still based on old nav_core API, we load them and pass to a new MBF API that will act as wrapper + boost::shared_ptr nav_core_planner_ptr = nav_core_planner_plugin_loader_.createInstance(planner_type); + planner_ptr = boost::make_shared(nav_core_planner_ptr); + std::string planner_name = nav_core_planner_plugin_loader_.getName(planner_type); + ROS_DEBUG_STREAM("nav_core-based planner plugin " << planner_name << " loaded"); + } + catch (const pluginlib::PluginlibException &ex_nav_core) + { + ROS_FATAL_STREAM("Failed to load the " << planner_type << " planner, are you sure it's properly registered" + << " and that the containing library is built? " << ex_mbf_core.what() << " " << ex_nav_core.what()); + } + } + + return planner_ptr; +} + +bool CostmapNavigationServer::initializePlannerPlugin( + const std::string &name, + const mbf_abstract_core::AbstractPlanner::Ptr &planner_ptr +) +{ + mbf_costmap_core::CostmapPlanner::Ptr costmap_planner_ptr + = boost::static_pointer_cast(planner_ptr); + ROS_DEBUG_STREAM("Initialize planner \"" << name << "\"."); + + if (!global_costmap_ptr_) + { + ROS_FATAL_STREAM("The costmap pointer has not been initialized!"); + return false; + } + + costmap_planner_ptr->initialize(name, global_costmap_ptr_.get()); + ROS_DEBUG("Planner plugin initialized."); + return true; +} + + +mbf_abstract_core::AbstractController::Ptr CostmapNavigationServer::loadControllerPlugin(const std::string &controller_type) +{ + mbf_abstract_core::AbstractController::Ptr controller_ptr; + try + { + controller_ptr = controller_plugin_loader_.createInstance(controller_type); + std::string controller_name = controller_plugin_loader_.getName(controller_type); + ROS_DEBUG_STREAM("mbf_costmap_core-based controller plugin " << controller_name << " loaded."); + } + catch (const pluginlib::PluginlibException &ex_mbf_core) + { + ROS_DEBUG_STREAM("Failed to load the " << controller_type << " controller as a mbf_costmap_core-based plugin;" + << " we will retry to load as a nav_core-based plugin. " << ex_mbf_core.what()); + try + { + // For plugins still based on old nav_core API, we load them and pass to a new MBF API that will act as wrapper + boost::shared_ptr nav_core_controller_ptr + = nav_core_controller_plugin_loader_.createInstance(controller_type); + controller_ptr = boost::make_shared(nav_core_controller_ptr); + std::string controller_name = nav_core_controller_plugin_loader_.getName(controller_type); + ROS_DEBUG_STREAM("nav_core-based controller plugin " << controller_name << " loaded."); + } + catch (const pluginlib::PluginlibException &ex_nav_core) + { + ROS_FATAL_STREAM("Failed to load the " << controller_type << " controller, are you sure it's properly registered" + << " and that the containing library is built? " << ex_mbf_core.what() << " " << ex_nav_core.what()); + } + } + return controller_ptr; +} + +bool CostmapNavigationServer::initializeControllerPlugin( + const std::string &name, + const mbf_abstract_core::AbstractController::Ptr &controller_ptr) +{ + ROS_DEBUG_STREAM("Initialize controller \"" << name << "\"."); + + if (!tf_listener_ptr_) + { + ROS_FATAL_STREAM("The tf listener pointer has not been initialized!"); + return false; + } + + if (!local_costmap_ptr_) + { + ROS_FATAL_STREAM("The costmap pointer has not been initialized!"); + return false; + } + + mbf_costmap_core::CostmapController::Ptr costmap_controller_ptr + = boost::static_pointer_cast(controller_ptr); + costmap_controller_ptr->initialize(name, tf_listener_ptr_.get(), local_costmap_ptr_.get()); + ROS_DEBUG_STREAM("Controller plugin \"" << name << "\" initialized."); + return true; +} + +mbf_abstract_core::AbstractRecovery::Ptr CostmapNavigationServer::loadRecoveryPlugin( + const std::string &recovery_type) +{ + mbf_abstract_core::AbstractRecovery::Ptr recovery_ptr; + + try + { + recovery_ptr = boost::static_pointer_cast( + recovery_plugin_loader_.createInstance(recovery_type)); + std::string recovery_name = recovery_plugin_loader_.getName(recovery_type); + ROS_DEBUG_STREAM("mbf_costmap_core-based recovery behavior plugin " << recovery_name << " loaded."); + } + catch (pluginlib::PluginlibException &ex_mbf_core) + { + ROS_DEBUG_STREAM("Failed to load the " << recovery_type << " recovery behavior as a mbf_costmap_core-based plugin;" + << " Retry to load as a nav_core-based plugin. " << ex_mbf_core.what()); + try + { + // For plugins still based on old nav_core API, we load them and pass to a new MBF API that will act as wrapper + boost::shared_ptr nav_core_recovery_ptr = + nav_core_recovery_plugin_loader_.createInstance(recovery_type); + + recovery_ptr = boost::make_shared(nav_core_recovery_ptr); + std::string recovery_name = recovery_plugin_loader_.getName(recovery_type); + ROS_DEBUG_STREAM("nav_core-based recovery behavior plugin " << recovery_name << " loaded."); + + } + catch (const pluginlib::PluginlibException &ex_nav_core) + { + ROS_FATAL_STREAM("Failed to load the " << recovery_type << " recovery behavior, are you sure it's properly registered" + << " and that the containing library is built? " << ex_mbf_core.what() << " " << ex_nav_core.what()); + } + } + + return recovery_ptr; +} + +bool CostmapNavigationServer::initializeRecoveryPlugin( + const std::string &name, + const mbf_abstract_core::AbstractRecovery::Ptr &behavior_ptr) +{ + ROS_DEBUG_STREAM("Initialize recovery behavior \"" << name << "\"."); + + if (!tf_listener_ptr_) + { + ROS_FATAL_STREAM("The tf listener pointer has not been initialized!"); + return false; + } + + if (!local_costmap_ptr_) + { + ROS_FATAL_STREAM("The local costmap pointer has not been initialized!"); + return false; + } + + if (!global_costmap_ptr_) + { + ROS_FATAL_STREAM("The global costmap pointer has not been initialized!"); + return false; + } + + mbf_costmap_core::CostmapRecovery::Ptr behavior = + boost::static_pointer_cast(behavior_ptr); + behavior->initialize(name, tf_listener_ptr_.get(), global_costmap_ptr_.get(), local_costmap_ptr_.get()); + ROS_DEBUG_STREAM("Recovery behavior plugin \"" << name << "\" initialized."); + return true; +} + + +void CostmapNavigationServer::stop() +{ + AbstractNavigationServer::stop(); + ROS_INFO_STREAM_NAMED("mbf_costmap_nav", "Stopping local and global costmap for shutdown"); + local_costmap_ptr_->stop(); + global_costmap_ptr_->stop(); +} + +void CostmapNavigationServer::reconfigure(mbf_costmap_nav::MoveBaseFlexConfig &config, uint32_t level) +{ + // Make sure we have the original configuration the first time we're called, so we can restore it if needed + if (!setup_reconfigure_) + { + default_config_ = config; + setup_reconfigure_ = true; + } + + if (config.restore_defaults) + { + config = default_config_; + // if someone sets restore defaults on the parameter server, prevent looping + config.restore_defaults = false; + } + + // fill the abstract configuration common to all MBF-based navigation + mbf_abstract_nav::MoveBaseFlexConfig abstract_config; + abstract_config.planner_frequency = config.planner_frequency; + abstract_config.planner_patience = config.planner_patience; + abstract_config.planner_max_retries = config.planner_max_retries; + abstract_config.controller_frequency = config.controller_frequency; + abstract_config.controller_patience = config.controller_patience; + abstract_config.controller_max_retries = config.controller_max_retries; + abstract_config.recovery_enabled = config.recovery_enabled; + abstract_config.recovery_patience = config.recovery_patience; + abstract_config.oscillation_timeout = config.oscillation_timeout; + abstract_config.oscillation_distance = config.oscillation_distance; + abstract_config.restore_defaults = config.restore_defaults; + mbf_abstract_nav::AbstractNavigationServer::reconfigure(abstract_config, level); + + // also reconfigure costmaps + local_costmap_ptr_->reconfigure(config.shutdown_costmaps, config.shutdown_costmaps_delay); + global_costmap_ptr_->reconfigure(config.shutdown_costmaps, config.shutdown_costmaps_delay); + + last_config_ = config; +} + +bool CostmapNavigationServer::callServiceCheckPointCost(mbf_msgs::CheckPoint::Request &request, + mbf_msgs::CheckPoint::Response &response) +{ + // selecting the requested costmap + CostmapWrapper::Ptr costmap; + std::string costmap_name; + switch (request.costmap) + { + case mbf_msgs::CheckPoint::Request::LOCAL_COSTMAP: + costmap = local_costmap_ptr_; + costmap_name = "local costmap"; + break; + case mbf_msgs::CheckPoint::Request::GLOBAL_COSTMAP: + costmap = global_costmap_ptr_; + costmap_name = "global costmap"; + break; + default: + ROS_ERROR_STREAM("No valid costmap provided; options are " + << mbf_msgs::CheckPoint::Request::LOCAL_COSTMAP << ": local costmap, " + << mbf_msgs::CheckPoint::Request::GLOBAL_COSTMAP << ": global costmap"); + return false; + } + + // get target point as x, y coordinates + std::string costmap_frame = costmap->getGlobalFrameID(); + + geometry_msgs::PointStamped point; + if (!mbf_utility::transformPoint(*tf_listener_ptr_, costmap_frame, ros::Duration(0.5), request.point, point)) + { + ROS_ERROR_STREAM("Transform target point to " << costmap_name << " frame '" << costmap_frame << "' failed"); + return false; + } + + double x = point.point.x; + double y = point.point.y; + + // ensure costmap is active so cost reflects latest sensor readings + costmap->checkActivate(); + unsigned int mx, my; + if (!costmap->getCostmap()->worldToMap(x, y, mx, my)) + { + // point is outside of the map + response.state = static_cast(mbf_msgs::CheckPoint::Response::OUTSIDE); + ROS_DEBUG_STREAM("Point [" << x << ", " << y << "] is outside the map (cost = " << response.cost << ")"); + } + else + { + // lock costmap so content doesn't change while checking cell costs + boost::unique_lock lock(*(costmap->getCostmap()->getMutex())); + + // get cost of cell under point and classify as one of the states: UNKNOWN, LETHAL, INSCRIBED, FREE + response.cost = costmap->getCostmap()->getCost(mx, my); + switch (response.cost) + { + case costmap_2d::NO_INFORMATION: + response.state = static_cast(mbf_msgs::CheckPoint::Response::UNKNOWN); + ROS_DEBUG_STREAM("Point [" << x << ", " << y << "] is in unknown space! (cost = " << response.cost << ")"); + break; + case costmap_2d::LETHAL_OBSTACLE: + response.state = static_cast(mbf_msgs::CheckPoint::Response::LETHAL); + ROS_DEBUG_STREAM("Point [" << x << ", " << y << "] is in collision! (cost = " << response.cost << ")"); + break; + case costmap_2d::INSCRIBED_INFLATED_OBSTACLE: + response.state = static_cast(mbf_msgs::CheckPoint::Response::INSCRIBED); + ROS_DEBUG_STREAM("Point [" << x << ", " << y << "] is near an obstacle (cost = " << response.cost << ")"); + break; + default: + response.state = static_cast(mbf_msgs::CheckPoint::Response::FREE); + ROS_DEBUG_STREAM("Point [" << x << ", " << y << "] is free (cost = " << response.cost << ")"); + break; + } + } + + costmap->checkDeactivate(); + return true; +} + +bool CostmapNavigationServer::callServiceCheckPoseCost(mbf_msgs::CheckPose::Request &request, + mbf_msgs::CheckPose::Response &response) +{ + // selecting the requested costmap + CostmapWrapper::Ptr costmap; + std::string costmap_name; + switch (request.costmap) + { + case mbf_msgs::CheckPose::Request::LOCAL_COSTMAP: + costmap = local_costmap_ptr_; + costmap_name = "local costmap"; + break; + case mbf_msgs::CheckPose::Request::GLOBAL_COSTMAP: + costmap = global_costmap_ptr_; + costmap_name = "global costmap"; + break; + default: + ROS_ERROR_STREAM("No valid costmap provided; options are " + << mbf_msgs::CheckPose::Request::LOCAL_COSTMAP << ": local costmap, " + << mbf_msgs::CheckPose::Request::GLOBAL_COSTMAP << ": global costmap"); + return false; + } + + // get target pose or current robot pose as x, y, yaw coordinates + std::string costmap_frame = costmap->getGlobalFrameID(); + + geometry_msgs::PoseStamped pose; + if (request.current_pose) + { + if (!mbf_utility::getRobotPose(*tf_listener_ptr_, robot_frame_, costmap_frame, ros::Duration(0.5), pose)) + { + ROS_ERROR_STREAM("Get robot pose on " << costmap_name << " frame '" << costmap_frame << "' failed"); + return false; + } + } + else + { + if (!mbf_utility::transformPose(*tf_listener_ptr_, costmap_frame, ros::Duration(0.5), request.pose, pose)) + { + ROS_ERROR_STREAM("Transform target pose to " << costmap_name << " frame '" << costmap_frame << "' failed"); + return false; + } + } + + double x = pose.pose.position.x; + double y = pose.pose.position.y; + double yaw = tf::getYaw(pose.pose.orientation); + + // ensure costmap is active so cost reflects latest sensor readings + costmap->checkActivate(); + + // pad raw footprint to the requested safety distance; note that we discard footprint_padding parameter effect + std::vector footprint = costmap->getUnpaddedRobotFootprint(); + costmap_2d::padFootprint(footprint, request.safety_dist); + + // use footprint helper to get all the cells totally or partially within footprint polygon + std::vector footprint_cells = + FootprintHelper::getFootprintCells(x, y, yaw, footprint, *costmap->getCostmap(), true); + response.state = mbf_msgs::CheckPose::Response::FREE; + if (footprint_cells.empty()) + { + // no cells within footprint polygon must mean that robot is completely outside of the map + response.state = std::max(response.state, static_cast(mbf_msgs::CheckPose::Response::OUTSIDE)); + } + else + { + // lock costmap so content doesn't change while adding cell costs + boost::unique_lock lock(*(costmap->getCostmap()->getMutex())); + + // integrate the cost of all cells; state value precedence is UNKNOWN > LETHAL > INSCRIBED > FREE + for (int i = 0; i < footprint_cells.size(); ++i) + { + unsigned char cost = costmap->getCostmap()->getCost(footprint_cells[i].x, footprint_cells[i].y); + switch (cost) + { + case costmap_2d::NO_INFORMATION: + response.state = std::max(response.state, static_cast(mbf_msgs::CheckPose::Response::UNKNOWN)); + response.cost += cost * (request.unknown_cost_mult ? request.unknown_cost_mult : 1.0); + break; + case costmap_2d::LETHAL_OBSTACLE: + response.state = std::max(response.state, static_cast(mbf_msgs::CheckPose::Response::LETHAL)); + response.cost += cost * (request.lethal_cost_mult ? request.lethal_cost_mult : 1.0); + break; + case costmap_2d::INSCRIBED_INFLATED_OBSTACLE: + response.state = std::max(response.state, static_cast(mbf_msgs::CheckPose::Response::INSCRIBED)); + response.cost += cost * (request.inscrib_cost_mult ? request.inscrib_cost_mult : 1.0); + break; + default: + response.cost += cost; + break; + } + } + } + + // Provide some details of the outcome + switch (response.state) + { + case mbf_msgs::CheckPose::Response::OUTSIDE: + ROS_DEBUG_STREAM("Pose [" << x << ", " << y << ", " << yaw << "] is outside the map (cost = " << response.cost + << "; safety distance = " << request.safety_dist << ")"); + break; + case mbf_msgs::CheckPose::Response::UNKNOWN: + ROS_DEBUG_STREAM("Pose [" << x << ", " << y << ", " << yaw << "] is in unknown space! (cost = " << response.cost + << "; safety distance = " << request.safety_dist << ")"); + break; + case mbf_msgs::CheckPose::Response::LETHAL: + ROS_DEBUG_STREAM("Pose [" << x << ", " << y << ", " << yaw << "] is in collision! (cost = " << response.cost + << "; safety distance = " << request.safety_dist << ")"); + break; + case mbf_msgs::CheckPose::Response::INSCRIBED: + ROS_DEBUG_STREAM("Pose [" << x << ", " << y << ", " << yaw << "] is near an obstacle (cost = " << response.cost + << "; safety distance = " << request.safety_dist << ")"); + break; + case mbf_msgs::CheckPose::Response::FREE: + ROS_DEBUG_STREAM("Pose [" << x << ", " << y << ", " << yaw << "] is free (cost = " << response.cost + << "; safety distance = " << request.safety_dist << ")"); + break; + } + + costmap->checkDeactivate(); + return true; +} + +bool CostmapNavigationServer::callServiceCheckPathCost(mbf_msgs::CheckPath::Request &request, + mbf_msgs::CheckPath::Response &response) +{ + // selecting the requested costmap + CostmapWrapper::Ptr costmap; + std::string costmap_name; + switch (request.costmap) + { + case mbf_msgs::CheckPath::Request::LOCAL_COSTMAP: + costmap = local_costmap_ptr_; + costmap_name = "local costmap"; + break; + case mbf_msgs::CheckPath::Request::GLOBAL_COSTMAP: + costmap = global_costmap_ptr_; + costmap_name = "global costmap"; + break; + default: + ROS_ERROR_STREAM("No valid costmap provided; options are " + << mbf_msgs::CheckPath::Request::LOCAL_COSTMAP << ": local costmap, " + << mbf_msgs::CheckPath::Request::GLOBAL_COSTMAP << ": global costmap"); + return false; + } + + // ensure costmap is active so cost reflects latest sensor readings + costmap->checkActivate(); + + // get target pose or current robot pose as x, y, yaw coordinates + std::string costmap_frame = costmap->getGlobalFrameID(); + + std::vector footprint; + if (!request.path_cells_only) + { + // unless we want to check just the cells directly traversed by the path, pad raw footprint + // to the requested safety distance; note that we discard footprint_padding parameter effect + footprint = costmap->getUnpaddedRobotFootprint(); + costmap_2d::padFootprint(footprint, request.safety_dist); + } + + // lock costmap so content doesn't change while adding cell costs + boost::unique_lock lock(*(costmap->getCostmap()->getMutex())); + + geometry_msgs::PoseStamped pose; + + response.state = mbf_msgs::CheckPath::Response::FREE; + + for (int i = 0; i < request.path.poses.size(); ++i) + { + response.last_checked = i; + + if (!mbf_utility::transformPose(*tf_listener_ptr_, costmap_frame, ros::Duration(0.5), request.path.poses[i], pose)) + { + ROS_ERROR_STREAM("Transform target pose to " << costmap_name << " frame '" << costmap_frame << "' failed"); + return false; + } + + double x = pose.pose.position.x; + double y = pose.pose.position.y; + double yaw = tf::getYaw(pose.pose.orientation); + std::vector cells_to_check; + if (request.path_cells_only) + { + Cell cell; + if (costmap->getCostmap()->worldToMap(x, y, cell.x, cell.y)) + { + cells_to_check.push_back(cell); // out of map if false; cells_to_check will be empty + } + } + else + { + // use footprint helper to get all the cells totally or partially within footprint polygon + cells_to_check = FootprintHelper::getFootprintCells(x, y, yaw, footprint, *costmap->getCostmap(), true); + } + + if (cells_to_check.empty()) + { + // if path_cells_only is true, this means that current path's pose is outside the map + // if not, no cells within footprint polygon means that robot is completely outside of the map + response.state = std::max(response.state, static_cast(mbf_msgs::CheckPath::Response::OUTSIDE)); + } + else + { + // integrate the cost of all cells; state value precedence is UNKNOWN > LETHAL > INSCRIBED > FREE + // we apply the requested cost multipliers if different from zero (default value) + for (int j = 0; j < cells_to_check.size(); ++j) + { + unsigned char cost = costmap->getCostmap()->getCost(cells_to_check[j].x, cells_to_check[j].y); + switch (cost) + { + case costmap_2d::NO_INFORMATION: + response.state = std::max(response.state, static_cast(mbf_msgs::CheckPose::Response::UNKNOWN)); + response.cost += cost * (request.unknown_cost_mult ? request.unknown_cost_mult : 1.0); + break; + case costmap_2d::LETHAL_OBSTACLE: + response.state = std::max(response.state, static_cast(mbf_msgs::CheckPath::Response::LETHAL)); + response.cost += cost * (request.lethal_cost_mult ? request.lethal_cost_mult : 1.0); + break; + case costmap_2d::INSCRIBED_INFLATED_OBSTACLE: + response.state = std::max(response.state, static_cast(mbf_msgs::CheckPath::Response::INSCRIBED)); + response.cost += cost * (request.inscrib_cost_mult ? request.inscrib_cost_mult : 1.0); + break; + default:response.cost += cost; + break; + } + } + } + + if (request.return_on && response.state >= request.return_on) + { + // i-th pose state is bad enough for the client, so provide some details of the outcome and abort checking + switch (response.state) + { + case mbf_msgs::CheckPath::Response::OUTSIDE: + ROS_DEBUG_STREAM("At pose " << i << " [" << x << ", " << y << ", " << yaw << "] path goes outside the map " + << "(cost = " << response.cost << "; safety distance = " << request.safety_dist << ")"); + break; + case mbf_msgs::CheckPath::Response::UNKNOWN: + ROS_DEBUG_STREAM("At pose " << i << " [" << x << ", " << y << ", " << yaw << "] path goes in unknown space! " + << "(cost = " << response.cost << "; safety distance = " << request.safety_dist << ")"); + break; + case mbf_msgs::CheckPath::Response::LETHAL: + ROS_DEBUG_STREAM("At pose " << i << " [" << x << ", " << y << ", " << yaw << "] path goes in collision! " + << "(cost = " << response.cost << "; safety distance = " << request.safety_dist << ")"); + break; + case mbf_msgs::CheckPath::Response::INSCRIBED: + ROS_DEBUG_STREAM("At pose " << i << " [" << x << ", " << y << ", " << yaw << "] path goes near an obstacle " + << "(cost = " << response.cost << "; safety distance = " << request.safety_dist << ")"); + break; + case mbf_msgs::CheckPath::Response::FREE: + ROS_DEBUG_STREAM("Path is entirely free (maximum cost = " + << response.cost << "; safety distance = " << request.safety_dist << ")"); + break; + } + + break; + } + + i += request.skip_poses; // skip some poses to speedup processing (disabled by default) + } + + costmap->checkDeactivate(); + return true; +} + +bool CostmapNavigationServer::callServiceClearCostmaps(std_srvs::Empty::Request &request, + std_srvs::Empty::Response &response) +{ + // clear both costmaps + local_costmap_ptr_->clear(); + global_costmap_ptr_->clear(); + return true; +} + +} /* namespace mbf_costmap_nav */ diff --git a/navigations/move_base_flex/mbf_costmap_nav/src/mbf_costmap_nav/costmap_planner_execution.cpp b/navigations/move_base_flex/mbf_costmap_nav/src/mbf_costmap_nav/costmap_planner_execution.cpp new file mode 100755 index 0000000..1f9c533 --- /dev/null +++ b/navigations/move_base_flex/mbf_costmap_nav/src/mbf_costmap_nav/costmap_planner_execution.cpp @@ -0,0 +1,88 @@ +/* + * Copyright 2018, Magazino GmbH, Sebastian Pütz, Jorge Santos Simón + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * costmap_planner_execution.cpp + * + * authors: + * Sebastian Pütz + * Jorge Santos Simón + * + */ +#include + +#include "mbf_costmap_nav/costmap_planner_execution.h" + +namespace mbf_costmap_nav +{ + +CostmapPlannerExecution::CostmapPlannerExecution( + const std::string &planner_name, + const mbf_costmap_core::CostmapPlanner::Ptr &planner_ptr, + const CostmapWrapper::Ptr &costmap_ptr, + const MoveBaseFlexConfig &config) + : AbstractPlannerExecution(planner_name, planner_ptr, toAbstract(config)), + costmap_ptr_(costmap_ptr) +{ + ros::NodeHandle private_nh("~"); + private_nh.param("planner_lock_costmap", lock_costmap_, true); +} + +CostmapPlannerExecution::~CostmapPlannerExecution() +{ +} + +mbf_abstract_nav::MoveBaseFlexConfig CostmapPlannerExecution::toAbstract(const MoveBaseFlexConfig &config) +{ + // copy the planner-related abstract configuration common to all MBF-based navigation + mbf_abstract_nav::MoveBaseFlexConfig abstract_config; + abstract_config.planner_frequency = config.planner_frequency; + abstract_config.planner_patience = config.planner_patience; + abstract_config.planner_max_retries = config.planner_max_retries; + return abstract_config; +} + +uint32_t CostmapPlannerExecution::makePlan(const geometry_msgs::PoseStamped &start, + const geometry_msgs::PoseStamped &goal, + double dist_tolerance, double angle_tolerance, + std::vector &plan, + double &cost, + std::string &message) +{ + if (lock_costmap_) + { + boost::unique_lock lock(*(costmap_ptr_->getCostmap()->getMutex())); + return planner_->makePlan(start, goal, dist_tolerance, angle_tolerance, plan, cost, message); + } + return planner_->makePlan(start, goal, dist_tolerance, angle_tolerance, plan, cost, message); +} + +} /* namespace mbf_costmap_nav */ diff --git a/navigations/move_base_flex/mbf_costmap_nav/src/mbf_costmap_nav/costmap_recovery_execution.cpp b/navigations/move_base_flex/mbf_costmap_nav/src/mbf_costmap_nav/costmap_recovery_execution.cpp new file mode 100755 index 0000000..059a863 --- /dev/null +++ b/navigations/move_base_flex/mbf_costmap_nav/src/mbf_costmap_nav/costmap_recovery_execution.cpp @@ -0,0 +1,72 @@ +/* + * Copyright 2018, Magazino GmbH, Sebastian Pütz, Jorge Santos Simón + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * costmap_recovery_execution.cpp + * + * authors: + * Sebastian Pütz + * Jorge Santos Simón + * + */ +#include +#include "nav_core_wrapper/wrapper_recovery_behavior.h" +#include "mbf_costmap_nav/costmap_recovery_execution.h" + +namespace mbf_costmap_nav +{ + +CostmapRecoveryExecution::CostmapRecoveryExecution( + const std::string &recovery_name, + const mbf_costmap_core::CostmapRecovery::Ptr &recovery_ptr, + const TFPtr &tf_listener_ptr, + const CostmapWrapper::Ptr &global_costmap, + const CostmapWrapper::Ptr &local_costmap, + const MoveBaseFlexConfig &config) + : AbstractRecoveryExecution(recovery_name, recovery_ptr, tf_listener_ptr, toAbstract(config)), + global_costmap_(global_costmap), local_costmap_(local_costmap) +{ +} + +CostmapRecoveryExecution::~CostmapRecoveryExecution() +{ +} + +mbf_abstract_nav::MoveBaseFlexConfig CostmapRecoveryExecution::toAbstract(const MoveBaseFlexConfig &config) +{ + // copy the recovery-related abstract configuration common to all MBF-based navigation + mbf_abstract_nav::MoveBaseFlexConfig abstract_config; + abstract_config.recovery_enabled = config.recovery_enabled; + abstract_config.recovery_patience = config.recovery_patience; + return abstract_config; +} + +} /* namespace mbf_costmap_nav */ diff --git a/navigations/move_base_flex/mbf_costmap_nav/src/mbf_costmap_nav/costmap_wrapper.cpp b/navigations/move_base_flex/mbf_costmap_nav/src/mbf_costmap_nav/costmap_wrapper.cpp new file mode 100755 index 0000000..bbbb6ec --- /dev/null +++ b/navigations/move_base_flex/mbf_costmap_nav/src/mbf_costmap_nav/costmap_wrapper.cpp @@ -0,0 +1,139 @@ +/* + * Copyright 2019, Magazino GmbH, Sebastian Pütz, Jorge Santos Simón + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * costmap_wrapper.cpp + * + * authors: + * Sebastian Pütz + * Jorge Santos Simón + * + */ + +#include "mbf_costmap_nav/costmap_wrapper.h" + + +namespace mbf_costmap_nav +{ + + +CostmapWrapper::CostmapWrapper(const std::string &name, const TFPtr &tf_listener_ptr) : + costmap_2d::Costmap2DROS(name, *tf_listener_ptr), + shutdown_costmap_(false), costmap_users_(0), private_nh_("~") +{ + // even if shutdown_costmaps is a dynamically reconfigurable parameter, we + // need it here to decide whether to start or not the costmap on starting up + private_nh_.param("shutdown_costmaps", shutdown_costmap_, false); + private_nh_.param("clear_on_shutdown", clear_on_shutdown_, false); + + if (shutdown_costmap_) + // initialize costmap stopped if shutdown_costmaps parameter is true + stop(); + else + // otherwise costmap_users_ is at least 1, as costmap is always active + ++costmap_users_; +} + +CostmapWrapper::~CostmapWrapper() +{ + shutdown_costmap_timer_.stop(); +} + + +void CostmapWrapper::reconfigure(double shutdown_costmap, double shutdown_costmap_delay) +{ + shutdown_costmap_delay_ = ros::Duration(shutdown_costmap_delay); + if (shutdown_costmap_delay_.isZero()) + ROS_WARN("Zero shutdown costmaps delay is not recommended, as it forces us to enable costmaps on each action"); + + if (shutdown_costmap_ && !shutdown_costmap) + { + checkActivate(); + shutdown_costmap_ = shutdown_costmap; + } + if (!shutdown_costmap_ && shutdown_costmap) + { + shutdown_costmap_ = shutdown_costmap; + checkDeactivate(); + } +} + +void CostmapWrapper::clear() +{ + // lock and clear costmap + boost::unique_lock lock(*getCostmap()->getMutex()); + resetLayers(); +} + +void CostmapWrapper::checkActivate() +{ + boost::mutex::scoped_lock sl(check_costmap_mutex_); + + shutdown_costmap_timer_.stop(); + + // Activate costmap if we shutdown them when not moving and they are not already active. This method must be + // synchronized because start costmap can take up to 1/update freq., and concurrent calls to it can lead to segfaults + if (shutdown_costmap_ && !costmap_users_) + { + start(); + ROS_DEBUG_STREAM("" << name_ << " activated"); + } + ++costmap_users_; +} + +void CostmapWrapper::checkDeactivate() +{ + boost::mutex::scoped_lock sl(check_costmap_mutex_); + + --costmap_users_; + ROS_ASSERT_MSG(costmap_users_ >= 0, "Negative number (%d) of active users count!", costmap_users_); + if (shutdown_costmap_ && !costmap_users_) + { + // Delay costmap shutdown by shutdown_costmap_delay so we don't need to enable at each step of a normal + // navigation sequence, what is terribly inefficient; the timer is stopped on costmap re-activation and + // reset after every new call to deactivate + shutdown_costmap_timer_ = + private_nh_.createTimer(shutdown_costmap_delay_, &CostmapWrapper::deactivate, this, true); + } +} + +void CostmapWrapper::deactivate(const ros::TimerEvent &event) +{ + boost::mutex::scoped_lock sl(check_costmap_mutex_); + + ROS_ASSERT_MSG(!costmap_users_, "Deactivating costmap with %d active users!", costmap_users_); + if (clear_on_shutdown_) + clear(); // do before stop, as some layers (e.g. obstacle and voxel) reactivate their subscribers on reset + stop(); + ROS_DEBUG_STREAM("" << name_ << " deactivated"); +} + +} /* namespace mbf_costmap_nav */ diff --git a/navigations/move_base_flex/mbf_costmap_nav/src/mbf_costmap_nav/footprint_helper.cpp b/navigations/move_base_flex/mbf_costmap_nav/src/mbf_costmap_nav/footprint_helper.cpp new file mode 100755 index 0000000..6ee25e9 --- /dev/null +++ b/navigations/move_base_flex/mbf_costmap_nav/src/mbf_costmap_nav/footprint_helper.cpp @@ -0,0 +1,237 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2008, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: TKruse + *********************************************************************/ + +#include "mbf_costmap_nav/footprint_helper.h" + +namespace mbf_costmap_nav +{ + +void FootprintHelper::getLineCells(int x0, int x1, int y0, int y1, std::vector& pts) { + //Bresenham Ray-Tracing + int deltax = abs(x1 - x0); // The difference between the x's + int deltay = abs(y1 - y0); // The difference between the y's + int x = x0; // Start x off at the first pixel + int y = y0; // Start y off at the first pixel + + int xinc1, xinc2, yinc1, yinc2; + int den, num, numadd, numpixels; + + Cell pt; + + if (x1 >= x0) // The x-values are increasing + { + xinc1 = 1; + xinc2 = 1; + } + else // The x-values are decreasing + { + xinc1 = -1; + xinc2 = -1; + } + + if (y1 >= y0) // The y-values are increasing + { + yinc1 = 1; + yinc2 = 1; + } + else // The y-values are decreasing + { + yinc1 = -1; + yinc2 = -1; + } + + if (deltax >= deltay) // There is at least one x-value for every y-value + { + xinc1 = 0; // Don't change the x when numerator >= denominator + yinc2 = 0; // Don't change the y for every iteration + den = deltax; + num = deltax / 2; + numadd = deltay; + numpixels = deltax; // There are more x-values than y-values + } + else // There is at least one y-value for every x-value + { + xinc2 = 0; // Don't change the x for every iteration + yinc1 = 0; // Don't change the y when numerator >= denominator + den = deltay; + num = deltay / 2; + numadd = deltax; + numpixels = deltay; // There are more y-values than x-values + } + + for (int curpixel = 0; curpixel <= numpixels; curpixel++) + { + pt.x = x; //Draw the current pixel + pt.y = y; + pts.push_back(pt); + + num += numadd; // Increase the numerator by the top of the fraction + if (num >= den) // Check if numerator >= denominator + { + num -= den; // Calculate the new numerator value + x += xinc1; // Change the x as appropriate + y += yinc1; // Change the y as appropriate + } + x += xinc2; // Change the x as appropriate + y += yinc2; // Change the y as appropriate + } +} + + +void FootprintHelper::getFillCells(std::vector& footprint){ + //quick bubble sort to sort pts by x + Cell swap, pt; + unsigned int i = 0; + while (i < footprint.size() - 1) { + if (footprint[i].x > footprint[i + 1].x) { + swap = footprint[i]; + footprint[i] = footprint[i + 1]; + footprint[i + 1] = swap; + if(i > 0) { + --i; + } + } else { + ++i; + } + } + + i = 0; + Cell min_pt; + Cell max_pt; + unsigned int min_x = footprint[0].x; + unsigned int max_x = footprint[footprint.size() -1].x; + //walk through each column and mark cells inside the footprint + for (unsigned int x = min_x; x <= max_x; ++x) { + if (i >= footprint.size() - 1) { + break; + } + if (footprint[i].y < footprint[i + 1].y) { + min_pt = footprint[i]; + max_pt = footprint[i + 1]; + } else { + min_pt = footprint[i + 1]; + max_pt = footprint[i]; + } + + i += 2; + while (i < footprint.size() && footprint[i].x == x) { + if(footprint[i].y < min_pt.y) { + min_pt = footprint[i]; + } else if(footprint[i].y > max_pt.y) { + max_pt = footprint[i]; + } + ++i; + } + + //loop though cells in the column + for (unsigned int y = min_pt.y; y < max_pt.y; ++y) { + pt.x = x; + pt.y = y; + footprint.push_back(pt); + } + } +} + +/** + * get the cells of a footprint at a given position + */ +std::vector FootprintHelper::getFootprintCells( + double x, double y, double theta, + std::vector footprint_spec, + const costmap_2d::Costmap2D& costmap, + bool fill){ + std::vector footprint_cells; + + //if we have no footprint... do nothing + if (footprint_spec.size() <= 1) { + unsigned int mx, my; + if (costmap.worldToMap(x, y, mx, my)) { + Cell center; + center.x = mx; + center.y = my; + footprint_cells.push_back(center); + } + return footprint_cells; + } + + //pre-compute cos and sin values + double cos_th = cos(theta); + double sin_th = sin(theta); + double new_x, new_y; + unsigned int x0, y0, x1, y1; + unsigned int last_index = footprint_spec.size() - 1; + + for (unsigned int i = 0; i < last_index; ++i) { + //find the cell coordinates of the first segment point + new_x = x + (footprint_spec[i].x * cos_th - footprint_spec[i].y * sin_th); + new_y = y + (footprint_spec[i].x * sin_th + footprint_spec[i].y * cos_th); + if(!costmap.worldToMap(new_x, new_y, x0, y0)) { + return footprint_cells; + } + + //find the cell coordinates of the second segment point + new_x = x + (footprint_spec[i + 1].x * cos_th - footprint_spec[i + 1].y * sin_th); + new_y = y + (footprint_spec[i + 1].x * sin_th + footprint_spec[i + 1].y * cos_th); + if (!costmap.worldToMap(new_x, new_y, x1, y1)) { + return footprint_cells; + } + + getLineCells(x0, x1, y0, y1, footprint_cells); + } + + //we need to close the loop, so we also have to raytrace from the last pt to first pt + new_x = x + (footprint_spec[last_index].x * cos_th - footprint_spec[last_index].y * sin_th); + new_y = y + (footprint_spec[last_index].x * sin_th + footprint_spec[last_index].y * cos_th); + if (!costmap.worldToMap(new_x, new_y, x0, y0)) { + return footprint_cells; + } + new_x = x + (footprint_spec[0].x * cos_th - footprint_spec[0].y * sin_th); + new_y = y + (footprint_spec[0].x * sin_th + footprint_spec[0].y * cos_th); + if(!costmap.worldToMap(new_x, new_y, x1, y1)) { + return footprint_cells; + } + + getLineCells(x0, x1, y0, y1, footprint_cells); + + if(fill) { + getFillCells(footprint_cells); + } + + return footprint_cells; +} + +} /* namespace mbf_costmap_nav */ diff --git a/navigations/move_base_flex/mbf_costmap_nav/src/move_base_server_node.cpp b/navigations/move_base_flex/mbf_costmap_nav/src/move_base_server_node.cpp new file mode 100755 index 0000000..668b5b4 --- /dev/null +++ b/navigations/move_base_flex/mbf_costmap_nav/src/move_base_server_node.cpp @@ -0,0 +1,83 @@ +/* + * Copyright 2018, Magazino GmbH, Sebastian Pütz, Jorge Santos Simón + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * move_base_server_node.cpp + * + * authors: + * Sebastian Pütz + * Jorge Santos Simón + * + */ + +#include "mbf_costmap_nav/costmap_navigation_server.h" +#include +#include +#include + +typedef boost::shared_ptr CostmapNavigationServerPtr; +mbf_costmap_nav::CostmapNavigationServer::Ptr costmap_nav_srv_ptr; + +void sigintHandler(int sig) +{ + ROS_INFO_STREAM("Shutdown costmap navigation server."); + if(costmap_nav_srv_ptr) + { + costmap_nav_srv_ptr->stop(); + } + ros::shutdown(); +} + +int main(int argc, char **argv) +{ + ros::init(argc, argv, "mbf_2d_nav_server", ros::init_options::NoSigintHandler); + + ros::NodeHandle nh; + ros::NodeHandle private_nh("~"); + + double cache_time; + private_nh.param("tf_cache_time", cache_time, 10.0); + + signal(SIGINT, sigintHandler); +#ifdef USE_OLD_TF + TFPtr tf_listener_ptr(new TF(nh, ros::Duration(cache_time), true)); +#else + TFPtr tf_listener_ptr(new TF(ros::Duration(cache_time))); + tf2_ros::TransformListener tf_listener(*tf_listener_ptr); +#endif + costmap_nav_srv_ptr = boost::make_shared(tf_listener_ptr); + ros::spin(); + + // explicitly call destructor here, otherwise costmap_nav_srv_ptr will be + // destructed after tearing down internally allocated static variables + costmap_nav_srv_ptr.reset(); + return EXIT_SUCCESS; +} diff --git a/navigations/move_base_flex/mbf_costmap_nav/src/nav_core_wrapper/wrapper_global_planner.cpp b/navigations/move_base_flex/mbf_costmap_nav/src/nav_core_wrapper/wrapper_global_planner.cpp new file mode 100755 index 0000000..765a1f1 --- /dev/null +++ b/navigations/move_base_flex/mbf_costmap_nav/src/nav_core_wrapper/wrapper_global_planner.cpp @@ -0,0 +1,82 @@ +/* + * Copyright 2018, Magazino GmbH, Sebastian Pütz, Jorge Santos Simón + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * wrapper_global_planner.cpp + * + * authors: + * Sebastian Pütz + * Jorge Santos Simón + * + */ + +#include "nav_core_wrapper/wrapper_global_planner.h" + +namespace mbf_nav_core_wrapper +{ + +uint32_t WrapperGlobalPlanner::makePlan(const geometry_msgs::PoseStamped &start, + const geometry_msgs::PoseStamped &goal, + double dist_tolerance, double angle_tolerance, + std::vector &plan, + double &cost, + std::string &message) +{ +#if ROS_VERSION_MINIMUM(1, 12, 0) // if current ros version is >= 1.12.0 + // Kinetic and beyond + bool success = nav_core_plugin_->makePlan(start, goal, plan, cost); +#else + // Indigo + bool success = nav_core_plugin_->makePlan(start, goal, plan); + cost = 0; +#endif + message = success ? "Plan found" : "Planner failed"; + return success ? 0 : 50; // SUCCESS | FAILURE +} + +bool WrapperGlobalPlanner::cancel() +{ + return false; +} + +void WrapperGlobalPlanner::initialize(std::string name, costmap_2d::Costmap2DROS *costmap_ros) +{ + nav_core_plugin_->initialize(name, costmap_ros); +} + +WrapperGlobalPlanner::WrapperGlobalPlanner(boost::shared_ptr plugin) + : nav_core_plugin_(plugin) +{} + +WrapperGlobalPlanner::~WrapperGlobalPlanner() +{} + +}; /* namespace mbf_abstract_core */ diff --git a/navigations/move_base_flex/mbf_costmap_nav/src/nav_core_wrapper/wrapper_local_planner.cpp b/navigations/move_base_flex/mbf_costmap_nav/src/nav_core_wrapper/wrapper_local_planner.cpp new file mode 100755 index 0000000..8c9c0d4 --- /dev/null +++ b/navigations/move_base_flex/mbf_costmap_nav/src/nav_core_wrapper/wrapper_local_planner.cpp @@ -0,0 +1,94 @@ +/* + * Copyright 2018, Magazino GmbH, Sebastian Pütz, Jorge Santos Simón + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * wrapper_local_planner.cpp + * + * authors: + * Sebastian Pütz + * Jorge Santos Simón + * + */ + +#include "nav_core_wrapper/wrapper_local_planner.h" + +namespace mbf_nav_core_wrapper +{ + +uint32_t WrapperLocalPlanner::computeVelocityCommands( + const geometry_msgs::PoseStamped &robot_pose, + const geometry_msgs::TwistStamped &robot_velocity, + geometry_msgs::TwistStamped &cmd_vel, + std::string &message) +{ + bool success = nav_core_plugin_->computeVelocityCommands(cmd_vel.twist); + message = success ? "Goal reached" : "Controller failed"; + return success ? 0 : 100; // SUCCESS | FAILURE +} + +bool WrapperLocalPlanner::isGoalReached() +{ + return nav_core_plugin_->isGoalReached(); +} + +bool WrapperLocalPlanner::isGoalReached(double xy_tolerance, double yaw_tolerance) +{ + return isGoalReached(); +} + +bool WrapperLocalPlanner::setPlan(const std::vector &plan) +{ + return nav_core_plugin_->setPlan(plan); +} + +bool WrapperLocalPlanner::cancel() +{ + ROS_WARN_STREAM("The cancel method is not implemented. " + "Note: you are running a nav_core based plugin, " + "which is wrapped into the MBF interface."); + return false; +} + +void WrapperLocalPlanner::initialize(std::string name, + TF *tf, + costmap_2d::Costmap2DROS *costmap_ros) +{ + nav_core_plugin_->initialize(name, tf, costmap_ros); +} + +WrapperLocalPlanner::WrapperLocalPlanner(boost::shared_ptr plugin) + : nav_core_plugin_(plugin) +{} + +WrapperLocalPlanner::~WrapperLocalPlanner() +{} + +}; /* namespace mbf_abstract_core */ diff --git a/navigations/move_base_flex/mbf_costmap_nav/src/nav_core_wrapper/wrapper_recovery_behavior.cpp b/navigations/move_base_flex/mbf_costmap_nav/src/nav_core_wrapper/wrapper_recovery_behavior.cpp new file mode 100755 index 0000000..7816b39 --- /dev/null +++ b/navigations/move_base_flex/mbf_costmap_nav/src/nav_core_wrapper/wrapper_recovery_behavior.cpp @@ -0,0 +1,72 @@ +/* + * Copyright 2018, Magazino GmbH, Sebastian Pütz, Jorge Santos Simón + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * wrapper_recovery_behavior.cpp + * + * authors: + * Sebastian Pütz + * Jorge Santos Simón + * + */ + +#include +#include "nav_core_wrapper/wrapper_recovery_behavior.h" + +namespace mbf_nav_core_wrapper +{ +void WrapperRecoveryBehavior::initialize(std::string name, TF *tf, + costmap_2d::Costmap2DROS *global_costmap, + costmap_2d::Costmap2DROS *local_costmap) +{ + nav_core_plugin_->initialize(name, tf, global_costmap, local_costmap); +} + +uint32_t WrapperRecoveryBehavior::runBehavior(std::string &message) +{ + nav_core_plugin_->runBehavior(); + // TODO return a code for old API + return mbf_msgs::RecoveryResult::SUCCESS; +} + +bool WrapperRecoveryBehavior::cancel() +{ + return false; +} + +WrapperRecoveryBehavior::WrapperRecoveryBehavior(boost::shared_ptr plugin) + : nav_core_plugin_(plugin) +{} + +WrapperRecoveryBehavior::~WrapperRecoveryBehavior() +{} + +}; /* namespace mbf_abstract_core */ diff --git a/navigations/move_base_flex/mbf_msgs/CHANGELOG.rst b/navigations/move_base_flex/mbf_msgs/CHANGELOG.rst new file mode 100755 index 0000000..a727239 --- /dev/null +++ b/navigations/move_base_flex/mbf_msgs/CHANGELOG.rst @@ -0,0 +1,41 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package mbf_msgs +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +0.3.2 (2020-05-25) +------------------ +* add impassable outcome code for recovery behaviors +* enable different goal tolerance values for each action + +0.3.1 (2020-04-07) +------------------ + +0.3.0 (2020-03-31) +------------------ +* add some more error codes, e.g. out of map, or map error +* unify license declaration to BSD-3 + +0.2.5 (2019-10-11) +------------------ + +0.2.4 (2019-06-16) +------------------ +* Add check_point_cost service +* Change current_twist for last_cmd_vel on exe_path/feedback + +0.2.3 (2018-11-14) +------------------ +* Add outcome and message to the action's feedback in ExePath and MoveBase + +0.2.1 (2018-10-03) +------------------ + +0.2.0 (2018-09-11) +------------------ +* Concurrency for planners, controllers and recovery behaviors +* Adds concurrency slots to actions + +0.1.0 (2018-03-22) +------------------ +* First release of move_base_flex for kinetic and lunar +ca \ No newline at end of file diff --git a/navigations/move_base_flex/mbf_msgs/CMakeLists.txt b/navigations/move_base_flex/mbf_msgs/CMakeLists.txt new file mode 100755 index 0000000..dd7659e --- /dev/null +++ b/navigations/move_base_flex/mbf_msgs/CMakeLists.txt @@ -0,0 +1,49 @@ +cmake_minimum_required(VERSION 2.8.3) +project(mbf_msgs) + +find_package(catkin REQUIRED + COMPONENTS + actionlib_msgs + genmsg + geometry_msgs + message_generation + message_runtime + nav_msgs + std_msgs +) + +add_service_files( + DIRECTORY + srv + FILES + CheckPoint.srv + CheckPose.srv + CheckPath.srv +) + +add_action_files( + DIRECTORY + action + FILES + GetPath.action + ExePath.action + Recovery.action + MoveBase.action +) + +generate_messages( + DEPENDENCIES + actionlib_msgs + geometry_msgs + nav_msgs + std_msgs +) + +catkin_package( + CATKIN_DEPENDS + actionlib_msgs + geometry_msgs + message_runtime + nav_msgs + std_msgs +) diff --git a/navigations/move_base_flex/mbf_msgs/README.md b/navigations/move_base_flex/mbf_msgs/README.md new file mode 100755 index 0000000..536cce6 --- /dev/null +++ b/navigations/move_base_flex/mbf_msgs/README.md @@ -0,0 +1,3 @@ +# Move Base Flex Messages, Services and Actions {#mainpage} + +This move_base_flex messages package provides the action definition files for the actions GetPath, ExePath, Recovery and MoveBase. The action servers providing these actions are implemented in [mbf_abstract_nav](wiki.ros.org/mbf_abstract_nav). \ No newline at end of file diff --git a/navigations/move_base_flex/mbf_msgs/action/ExePath.action b/navigations/move_base_flex/mbf_msgs/action/ExePath.action new file mode 100755 index 0000000..dde382c --- /dev/null +++ b/navigations/move_base_flex/mbf_msgs/action/ExePath.action @@ -0,0 +1,60 @@ +# Follow the given path until completion or failure + +nav_msgs/Path path + +# Controller to use; defaults to the first one specified on "controllers" parameter +string controller + +# use different slots for concurrency +uint8 concurrency_slot + +# Optionally overrule goal tolerances +bool tolerance_from_action +float32 dist_tolerance +float32 angle_tolerance + +--- + +# Predefined success codes: +uint8 SUCCESS = 0 +# 1..9 are reserved as plugin specific non-error results + +# Predefined error codes: +uint8 FAILURE = 100 # Unspecified failure, only used for old, non-mfb_core based plugins +uint8 CANCELED = 101 +uint8 NO_VALID_CMD = 102 +uint8 PAT_EXCEEDED = 103 +uint8 COLLISION = 104 +uint8 OSCILLATION = 105 +uint8 ROBOT_STUCK = 106 +uint8 MISSED_GOAL = 107 +uint8 MISSED_PATH = 108 +uint8 BLOCKED_PATH = 109 +uint8 INVALID_PATH = 110 +uint8 TF_ERROR = 111 +uint8 NOT_INITIALIZED = 112 +uint8 INVALID_PLUGIN = 113 +uint8 INTERNAL_ERROR = 114 +uint8 OUT_OF_MAP = 115 # The start and / or the goal are outside the map +uint8 MAP_ERROR = 116 # The map is not running properly +uint8 STOPPED = 117 # The controller execution has been stopped rigorously. + +# 121..149 are reserved as plugin specific errors + +uint32 outcome +string message + +geometry_msgs/PoseStamped final_pose +float32 dist_to_goal +float32 angle_to_goal + +--- + +# Outcome of most recent controller cycle. Same values as in result +uint32 outcome +string message + +float32 dist_to_goal +float32 angle_to_goal +geometry_msgs/PoseStamped current_pose +geometry_msgs/TwistStamped last_cmd_vel # last command calculated by the controller diff --git a/navigations/move_base_flex/mbf_msgs/action/GetPath.action b/navigations/move_base_flex/mbf_msgs/action/GetPath.action new file mode 100755 index 0000000..13d91ed --- /dev/null +++ b/navigations/move_base_flex/mbf_msgs/action/GetPath.action @@ -0,0 +1,55 @@ +# Get a path from start_pose or current position to the target pose + +# Use start_pose or current position as the beginning of the path +bool use_start_pose + +# The start pose for the path; optional, used if use_start_pose is true +geometry_msgs/PoseStamped start_pose + +# The pose to achieve with the path +geometry_msgs/PoseStamped target_pose + +# Planner to use; defaults to the first one specified on "planners" parameter +string planner + +# use different slots for concurrency +uint8 concurrency_slot + +# Optional: how many meters/radians away from the goal can end the created path. The final pose of the +# path must be within tolerance range (position and orientation) for MBF to return a success outcome. +bool tolerance_from_action +float32 dist_tolerance +float32 angle_tolerance + +--- + +# Predefined success codes: +uint8 SUCCESS = 0 +# 1..9 are reserved as plugin specific non-error results + +# Possible error codes: +uint8 FAILURE = 50 # Unspecified failure, only used for old, non-mfb_core based plugins +uint8 CANCELED = 51 # The action has been canceled by a action client +uint8 INVALID_START = 52 # +uint8 INVALID_GOAL = 53 +uint8 NO_PATH_FOUND = 54 +uint8 PAT_EXCEEDED = 55 +uint8 EMPTY_PATH = 56 +uint8 TF_ERROR = 57 +uint8 NOT_INITIALIZED = 58 +uint8 INVALID_PLUGIN = 59 +uint8 INTERNAL_ERROR = 60 +uint8 OUT_OF_MAP = 61 +uint8 MAP_ERROR = 62 +uint8 STOPPED = 63 # The planner execution has been stopped rigorously. + +# 71..99 are reserved as plugin specific errors + +uint32 outcome +string message + +nav_msgs/Path path + +float64 cost + +--- diff --git a/navigations/move_base_flex/mbf_msgs/action/MoveBase.action b/navigations/move_base_flex/mbf_msgs/action/MoveBase.action new file mode 100755 index 0000000..fcf71bd --- /dev/null +++ b/navigations/move_base_flex/mbf_msgs/action/MoveBase.action @@ -0,0 +1,60 @@ +# Extension of move_base_msgs/MoveBase action, with more detailed result +# and feedback and the possibility to specify lists of applicable plugins + +geometry_msgs/PoseStamped target_pose + +# Controller to use; defaults to the first one specified on "controllers" parameter +string controller + +# Planner to use; defaults to the first one specified on "planners" parameter +string planner + +# Recovery behaviors to try on case of failure; defaults to the "recovery_behaviors" parameter value +string[] recovery_behaviors + +# Optionally overrule controller's goal tolerances +bool tolerance_from_action +float32 dist_tolerance +float32 angle_tolerance + +--- + +# Predefined success codes: +uint8 SUCCESS = 0 + +# Predefined general error codes: +uint8 FAILURE = 10 +uint8 CANCELED = 11 +uint8 COLLISION = 12 +uint8 OSCILLATION = 13 +uint8 START_BLOCKED = 14 +uint8 GOAL_BLOCKED = 15 +uint8 TF_ERROR = 16 +uint8 INTERNAL_ERROR = 17 +# 21..49 are reserved for future general error codes + +# Planning/controlling failures: +uint8 PLAN_FAILURE = 50 +# 51..99 are reserved as planner specific errors + +uint8 CTRL_FAILURE = 100 +# 101..149 are reserved as controller specific errors + +uint32 outcome +string message + +# Configuration upon action completion +float32 dist_to_goal +float32 angle_to_goal +geometry_msgs/PoseStamped final_pose + +--- + +# Outcome of most recent controller cycle. Same values as in MoveBase or ExePath result. +uint32 outcome +string message + +float32 dist_to_goal +float32 angle_to_goal +geometry_msgs/PoseStamped current_pose +geometry_msgs/TwistStamped last_cmd_vel # last command calculated by the controller diff --git a/navigations/move_base_flex/mbf_msgs/action/Recovery.action b/navigations/move_base_flex/mbf_msgs/action/Recovery.action new file mode 100755 index 0000000..ea43cce --- /dev/null +++ b/navigations/move_base_flex/mbf_msgs/action/Recovery.action @@ -0,0 +1,30 @@ +# Run one of the recovery behavior listed on recovery_behaviors parameter + +string behavior + +# use different slots for concurrency +uint8 concurrency_slot + +--- + +# Predefined success codes: +uint8 SUCCESS = 0 + +# Possible server codes: +uint8 FAILURE = 150 +uint8 CANCELED = 151 +uint8 PAT_EXCEEDED = 152 +uint8 TF_ERROR = 153 +uint8 NOT_INITIALIZED = 154 +uint8 INVALID_PLUGIN = 155 +uint8 INTERNAL_ERROR = 156 +uint8 STOPPED = 157 # The recovery behaviour execution has been stopped rigorously. +uint8 IMPASSABLE = 158 # Further execution would lead to a collision + +# 171..199 are reserved as plugin specific errors + +uint32 outcome +string message +string used_plugin + +--- diff --git a/navigations/move_base_flex/mbf_msgs/package.xml b/navigations/move_base_flex/mbf_msgs/package.xml new file mode 100755 index 0000000..f59d964 --- /dev/null +++ b/navigations/move_base_flex/mbf_msgs/package.xml @@ -0,0 +1,29 @@ + + mbf_msgs + 0.3.2 + + The move_base_flex messages package providing the action definition files for the action GetPath, ExePath, Recovery and MoveBase. The action servers providing these action are implemented in mbf_abstract_nav. + + Jorge Santos + Sebastian Pütz + Jorge Santos + Sebastian Pütz + BSD-3 + + catkin + + std_msgs + nav_msgs + geometry_msgs + actionlib_msgs + genmsg + message_runtime + message_generation + + std_msgs + nav_msgs + geometry_msgs + actionlib_msgs + message_runtime + + diff --git a/navigations/move_base_flex/mbf_msgs/srv/CheckPath.srv b/navigations/move_base_flex/mbf_msgs/srv/CheckPath.srv new file mode 100755 index 0000000..6454253 --- /dev/null +++ b/navigations/move_base_flex/mbf_msgs/srv/CheckPath.srv @@ -0,0 +1,24 @@ +uint8 LOCAL_COSTMAP = 1 +uint8 GLOBAL_COSTMAP = 2 + +nav_msgs/Path path # the path to be checked after transforming to costmap frame +float32 safety_dist # minimum distance allowed to the closest obstacle (footprint padding) +float32 lethal_cost_mult # cost multiplier for cells marked as lethal obstacle (zero is ignored) +float32 inscrib_cost_mult # cost multiplier for cells marked as inscribed obstacle (zero is ignored) +float32 unknown_cost_mult # cost multiplier for cells marked as unknown space (zero is ignored) +uint8 costmap # costmap in which to check the pose +uint8 return_on # abort check on finding a pose with this state or worse (zero is ignored) +uint8 skip_poses # skip this number of poses between checks, to speedup processing +bool path_cells_only # check only cells directly traversed by the path, ignoring robot footprint + # (if true, safety_dist is ignored) +--- +uint8 FREE = 0 # robot is completely in traversable space +uint8 INSCRIBED = 1 # robot is partially in inscribed space +uint8 LETHAL = 2 # robot is partially in collision +uint8 UNKNOWN = 3 # robot is partially in unknown space +uint8 OUTSIDE = 4 # robot is completely outside the map + +uint32 last_checked # index of the first pose along the path with return_on state or worse +uint8 state # path worst state (until last_checked): FREE, INFLATED, LETHAL, UNKNOWN... +uint32 cost # cost of all cells traversed by path within footprint padded by safety_dist + # or just by the path if path_cells_only is true diff --git a/navigations/move_base_flex/mbf_msgs/srv/CheckPoint.srv b/navigations/move_base_flex/mbf_msgs/srv/CheckPoint.srv new file mode 100755 index 0000000..06205d7 --- /dev/null +++ b/navigations/move_base_flex/mbf_msgs/srv/CheckPoint.srv @@ -0,0 +1,14 @@ +uint8 LOCAL_COSTMAP = 1 +uint8 GLOBAL_COSTMAP = 2 + +geometry_msgs/PointStamped point # the point to be checked after transforming to costmap frame +uint8 costmap # costmap in which to check the point +--- +uint8 FREE = 0 # point is in traversable space +uint8 INSCRIBED = 1 # point is in inscribed space +uint8 LETHAL = 2 # point is in collision +uint8 UNKNOWN = 3 # point is in unknown space +uint8 OUTSIDE = 4 # point is outside the map + +uint8 state # point state: FREE, INFLATED, LETHAL, UNKNOWN or OUTSIDE +uint32 cost # cost of the cell at point diff --git a/navigations/move_base_flex/mbf_msgs/srv/CheckPose.srv b/navigations/move_base_flex/mbf_msgs/srv/CheckPose.srv new file mode 100755 index 0000000..749e4a5 --- /dev/null +++ b/navigations/move_base_flex/mbf_msgs/srv/CheckPose.srv @@ -0,0 +1,19 @@ +uint8 LOCAL_COSTMAP = 1 +uint8 GLOBAL_COSTMAP = 2 + +geometry_msgs/PoseStamped pose # the pose to be checked after transforming to costmap frame +float32 safety_dist # minimum distance allowed to the closest obstacle +float32 lethal_cost_mult # cost multiplier for cells marked as lethal obstacle (zero is ignored) +float32 inscrib_cost_mult # cost multiplier for cells marked as inscribed obstacle (zero is ignored) +float32 unknown_cost_mult # cost multiplier for cells marked as unknown space (zero is ignored) +uint8 costmap # costmap in which to check the pose +bool current_pose # check current robot pose instead (ignores pose field) +--- +uint8 FREE = 0 # robot is completely in traversable space +uint8 INSCRIBED = 1 # robot is partially in inscribed space +uint8 LETHAL = 2 # robot is partially in collision +uint8 UNKNOWN = 3 # robot is partially in unknown space +uint8 OUTSIDE = 4 # robot is completely outside the map + +uint8 state # pose state: FREE, INFLATED, LETHAL, UNKNOWN or OUTSIDE +uint32 cost # total cost of all cells within footprint padded by safety_dist diff --git a/navigations/move_base_flex/mbf_simple_nav/CHANGELOG.rst b/navigations/move_base_flex/mbf_simple_nav/CHANGELOG.rst new file mode 100755 index 0000000..3d2d9cc --- /dev/null +++ b/navigations/move_base_flex/mbf_simple_nav/CHANGELOG.rst @@ -0,0 +1,39 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package mbf_simple_nav +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +0.3.2 (2020-05-25) +------------------ + +0.3.1 (2020-04-07) +------------------ + +0.3.0 (2020-03-31) +------------------ +* unify license declaration to BSD-3 + +0.2.5 (2019-10-11) +------------------ + +0.2.4 (2019-06-16) +------------------ + +0.2.3 (2018-11-14) +------------------ + +0.2.2 (2018-10-10) +------------------ + +0.2.1 (2018-10-03) +------------------ +* Make MBF melodic and indigo compatible +* Fix GoalHandle references bug in callbacks + +0.2.0 (2018-09-11) +------------------ +* Update copyright and 3-clause-BSD license +* Concurrency for planners, controllers and recovery behaviors + +0.1.0 (2018-03-22) +------------------ +* First release of move_base_flex for kinetic and lunar diff --git a/navigations/move_base_flex/mbf_simple_nav/CMakeLists.txt b/navigations/move_base_flex/mbf_simple_nav/CMakeLists.txt new file mode 100755 index 0000000..d635270 --- /dev/null +++ b/navigations/move_base_flex/mbf_simple_nav/CMakeLists.txt @@ -0,0 +1,82 @@ +cmake_minimum_required(VERSION 2.8.3) +project(mbf_simple_nav) + +find_package(catkin REQUIRED + COMPONENTS + actionlib + actionlib_msgs + dynamic_reconfigure + geometry_msgs + mbf_abstract_nav + mbf_msgs + mbf_abstract_core + nav_msgs + pluginlib + roscpp + std_msgs + std_srvs + tf + tf2 + tf2_ros + ) + +find_package(Boost COMPONENTS thread chrono REQUIRED) + +set(MBF_SIMPLE_SERVER_LIB mbf_simple_server) +set(MBF_SIMPLE_SERVER_NODE mbf_simple_nav) + +catkin_package( + INCLUDE_DIRS include + LIBRARIES ${MBF_SIMPLE_SERVER_LIB} + CATKIN_DEPENDS + actionlib + actionlib_msgs + dynamic_reconfigure + geometry_msgs + mbf_abstract_nav + mbf_msgs + mbf_abstract_core + nav_msgs + pluginlib + roscpp + std_msgs + std_srvs + tf + tf2 + tf2_ros + DEPENDS Boost +) + +include_directories( + include + ${catkin_INCLUDE_DIRS} + ${Boost_INCLUDE_DIRS} +) + +add_library(${MBF_SIMPLE_SERVER_LIB} + src/simple_navigation_server.cpp +) + +add_dependencies(${MBF_SIMPLE_SERVER_LIB} ${catkin_EXPORTED_TARGETS}) +target_link_libraries(${MBF_SIMPLE_SERVER_LIB} + ${catkin_LIBRARIES} + ${Boost_LIBRARIES} +) + +add_executable(${MBF_SIMPLE_SERVER_NODE} src/simple_server_node.cpp) +add_dependencies(${MBF_SIMPLE_SERVER_NODE} ${MBF_SIMPLE_SERVER_LIB}) +target_link_libraries(${MBF_SIMPLE_SERVER_NODE} + ${MBF_SIMPLE_SERVER_LIB} + ${catkin_LIBRARIES}) + +install(TARGETS + ${MBF_SIMPLE_SERVER_LIB} ${MBF_SIMPLE_SERVER_NODE} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) + +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} +) + diff --git a/navigations/move_base_flex/mbf_simple_nav/README.md b/navigations/move_base_flex/mbf_simple_nav/README.md new file mode 100755 index 0000000..198539e --- /dev/null +++ b/navigations/move_base_flex/mbf_simple_nav/README.md @@ -0,0 +1,6 @@ +# Move Base Flex Simple Navigation Server {#mainpage} + + +The mbf_simple_nav package contains a simple navigation server implementation of Move Base Flex (MBF). The simple navigation server is bound to no map representation. It provides actions for planning, controlling and recovering. MBF loads all defined plugins which are defined in the lists *planners*, *controllers* and *recovery_behaviors*. Each list holds a pair of a *name* and a *type*. The *type* defines which kind of plugin to load. The *name* defines under which name the plugin should be callable by the actions. + +It tries to load the defined plugins which implements the defined interfaces in [mbf_abstract_core](wiki.ros.org/mbf_abstract_core). \ No newline at end of file diff --git a/navigations/move_base_flex/mbf_simple_nav/include/mbf_simple_nav/simple_navigation_server.h b/navigations/move_base_flex/mbf_simple_nav/include/mbf_simple_nav/simple_navigation_server.h new file mode 100755 index 0000000..29283ad --- /dev/null +++ b/navigations/move_base_flex/mbf_simple_nav/include/mbf_simple_nav/simple_navigation_server.h @@ -0,0 +1,142 @@ +/* + * Copyright 2018, Magazino GmbH, Sebastian Pütz, Jorge Santos Simón + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * simple_navigation_server.h + * + * authors: + * Sebastian Pütz + * Jorge Santos Simón + * + */ + +#ifndef MBF_SIMPLE_NAV__SIMPLE_NAVIGATION_SERVER_H_ +#define MBF_SIMPLE_NAV__SIMPLE_NAVIGATION_SERVER_H_ + +#include +#include +#include + +namespace mbf_simple_nav +{ +/** + * @defgroup simple_server Simple Server + * @brief Classes belonging to the Simple Server level. + */ + +/** + * @brief The SimpleNavigationServer provides a simple navigation server, which does not bind a map representation to + * Move Base Flex. It combines the execution classes which use the mbf_abstract_core/AbstractController, + * mbf_abstract_core/AbstractPlanner and the mbf_abstract_core/AbstractRecovery base classes + * as plugin interfaces. + * + * @ingroup navigation_server simple_server + */ +class SimpleNavigationServer : public mbf_abstract_nav::AbstractNavigationServer +{ +public: + + /** + * @brief Constructor + * @param tf_listener_ptr Shared pointer to a common TransformListener + */ + SimpleNavigationServer(const TFPtr &tf_listener_ptr); + + /** + * @brief Destructor + */ + virtual ~SimpleNavigationServer(); + + /** + * @brief Loads the plugin associated with the given controller type parameter + * @param controller_type The type of the controller plugin + * @return A shared pointer to a new loaded controller, if the controller plugin was loaded successfully, + * an empty pointer otherwise. + */ + virtual mbf_abstract_core::AbstractController::Ptr loadControllerPlugin(const std::string& controller_type); + + /** + * @brief Empty init method. Nothing to initialize. + * @param name The name of the controller + * @param controller_ptr pointer to the controller object which corresponds to the name param + * @return true always + */ + virtual bool initializeControllerPlugin( + const std::string& name, + const mbf_abstract_core::AbstractController::Ptr& controller_ptr + ); + + /** + * @brief Loads the plugin associated with the given planner_type parameter. + * @param planner_type The type of the planner plugin to load. + * @return true, if the local planner plugin was successfully loaded. + */ + virtual mbf_abstract_core::AbstractPlanner::Ptr loadPlannerPlugin(const std::string& planner_type); + + /** + * @brief Empty init method. Nothing to initialize. + * @param name The name of the planner + * @param planner_ptr pointer to the planner object which corresponds to the name param + * @return true always + */ + virtual bool initializePlannerPlugin( + const std::string& name, + const mbf_abstract_core::AbstractPlanner::Ptr& planner_ptr + ); + + /** + * @brief Loads a Recovery plugin associated with given recovery type parameter + * @param recovery_name The name of the Recovery plugin + * @return A shared pointer to a Recovery plugin, if the plugin was loaded successfully, an empty pointer otherwise. + */ + virtual mbf_abstract_core::AbstractRecovery::Ptr loadRecoveryPlugin(const std::string& recovery_type); + + /** + * @brief Pure virtual method, the derived class has to implement. Depending on the plugin base class, + * some plugins need to be initialized! + * @param name The name of the recovery behavior + * @param behavior_ptr pointer to the recovery behavior object which corresponds to the name param + * @return true always + */ + virtual bool initializeRecoveryPlugin( + const std::string& name, + const mbf_abstract_core::AbstractRecovery::Ptr& behavior_ptr + ); + + private: + pluginlib::ClassLoader planner_plugin_loader_; + pluginlib::ClassLoader controller_plugin_loader_; + pluginlib::ClassLoader recovery_plugin_loader_; +}; + +} /* namespace mbf_simple_nav */ + +#endif /* MBF_SIMPLE_NAV__SIMPLE_NAVIGATION_SERVER_H_ */ diff --git a/navigations/move_base_flex/mbf_simple_nav/package.xml b/navigations/move_base_flex/mbf_simple_nav/package.xml new file mode 100755 index 0000000..b7926ef --- /dev/null +++ b/navigations/move_base_flex/mbf_simple_nav/package.xml @@ -0,0 +1,36 @@ + + mbf_simple_nav + 0.3.2 + + The mbf_simple_nav package contains a simple navigation server implementation of Move Base Flex (MBF). The simple navigation server is bound to no map representation. It provides actions for planning, controlling and recovering. MBF loads all defined plugins which are defined in the lists *planners*, *controllers* and *recovery_behaviors*. Each list holds a pair of a *name* and a *type*. The *type* defines which kind of plugin to load. The *name* defines under which name the plugin should be callable by the actions. + + It tries to load the defined plugins which implements the defined interfaces in mbf_abstract_core. + + http://wiki.ros.org/move_base_flex + Sebastian Pütz + Sebastian Pütz + Jorge Santos + BSD-3 + + catkin + + tf + roscpp + pluginlib + actionlib + actionlib_msgs + dynamic_reconfigure + std_msgs + std_srvs + nav_msgs + geometry_msgs + mbf_abstract_nav + mbf_abstract_core + mbf_msgs + + tf2 + tf2_ros + + + + diff --git a/navigations/move_base_flex/mbf_simple_nav/rosdoc.yaml b/navigations/move_base_flex/mbf_simple_nav/rosdoc.yaml new file mode 100755 index 0000000..de641ca --- /dev/null +++ b/navigations/move_base_flex/mbf_simple_nav/rosdoc.yaml @@ -0,0 +1,5 @@ + - builder: doxygen + name: Move Base Flex + homepage: http://wiki.ros.org/move_base_flex + file_patterns: '*.c *.cpp *.h *.cc *.hh *.py *.md' + use_mdfile_as_mainpage: README.md diff --git a/navigations/move_base_flex/mbf_simple_nav/src/simple_navigation_server.cpp b/navigations/move_base_flex/mbf_simple_nav/src/simple_navigation_server.cpp new file mode 100755 index 0000000..d8e3906 --- /dev/null +++ b/navigations/move_base_flex/mbf_simple_nav/src/simple_navigation_server.cpp @@ -0,0 +1,142 @@ +/* + * Copyright 2018, Magazino GmbH, Sebastian Pütz, Jorge Santos Simón + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * simple_navigation_server.cpp + * + * authors: + * Sebastian Pütz + * Jorge Santos Simón + * + */ + +#include "mbf_simple_nav/simple_navigation_server.h" + +namespace mbf_simple_nav +{ + +SimpleNavigationServer::SimpleNavigationServer(const TFPtr &tf_listener_ptr) : + mbf_abstract_nav::AbstractNavigationServer(tf_listener_ptr), + planner_plugin_loader_("mbf_abstract_core", "mbf_abstract_core::AbstractPlanner"), + controller_plugin_loader_("mbf_abstract_core", "mbf_abstract_core::AbstractController"), + recovery_plugin_loader_("mbf_abstract_core", "mbf_abstract_core::AbstractRecovery") +{ + // initialize all plugins + initializeServerComponents(); + + // start all action servers + startActionServers(); +} + +mbf_abstract_core::AbstractPlanner::Ptr SimpleNavigationServer::loadPlannerPlugin(const std::string& planner_type) +{ + mbf_abstract_core::AbstractPlanner::Ptr planner_ptr; + ROS_INFO("Load global planner plugin."); + try + { + planner_ptr = planner_plugin_loader_.createInstance(planner_type); + } + catch (const pluginlib::PluginlibException &ex) + { + ROS_FATAL_STREAM("Failed to load the " << planner_type << " planner, are you sure it is properly registered" + << " and that the containing library is built? Exception: " << ex.what()); + } + ROS_INFO("Global planner plugin loaded."); + + return planner_ptr; +} + +bool SimpleNavigationServer::initializePlannerPlugin( + const std::string& name, + const mbf_abstract_core::AbstractPlanner::Ptr& planner_ptr +) +{ + return true; +} + + +mbf_abstract_core::AbstractController::Ptr SimpleNavigationServer::loadControllerPlugin( + const std::string& controller_type) +{ + mbf_abstract_core::AbstractController::Ptr controller_ptr; + ROS_DEBUG("Load controller plugin."); + try + { + controller_ptr = controller_plugin_loader_.createInstance(controller_type); + ROS_INFO_STREAM("MBF_core-based local planner plugin " << controller_type << " loaded"); + } + catch (const pluginlib::PluginlibException &ex) + { + ROS_FATAL_STREAM("Failed to load the " << controller_type + << " local planner, are you sure it's properly registered" + << " and that the containing library is built? Exception: " << ex.what()); + } + return controller_ptr; +} + +bool SimpleNavigationServer::initializeControllerPlugin( + const std::string& name, + const mbf_abstract_core::AbstractController::Ptr& controller_ptr) +{ + return true; +} + +mbf_abstract_core::AbstractRecovery::Ptr SimpleNavigationServer::loadRecoveryPlugin( + const std::string& recovery_type) +{ + mbf_abstract_core::AbstractRecovery::Ptr recovery_ptr; + + try + { + recovery_ptr = boost::static_pointer_cast( + recovery_plugin_loader_.createInstance(recovery_type)); + } + catch (pluginlib::PluginlibException &ex) + { + ROS_FATAL_STREAM("Failed to load the " << recovery_type << " recovery behavior, are you sure it's properly registered" + << " and that the containing library is built? Exception: " << ex.what()); + } + return recovery_ptr; +} + +bool SimpleNavigationServer::initializeRecoveryPlugin( + const std::string& name, + const mbf_abstract_core::AbstractRecovery::Ptr& behavior_ptr) +{ + return true; +} + + +SimpleNavigationServer::~SimpleNavigationServer() +{ +} + +} /* namespace mbf_simple_nav */ diff --git a/navigations/move_base_flex/mbf_simple_nav/src/simple_server_node.cpp b/navigations/move_base_flex/mbf_simple_nav/src/simple_server_node.cpp new file mode 100755 index 0000000..0193cac --- /dev/null +++ b/navigations/move_base_flex/mbf_simple_nav/src/simple_server_node.cpp @@ -0,0 +1,69 @@ +/* + * Copyright 2018, Magazino GmbH, Sebastian Pütz, Jorge Santos Simón + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * simple_server_node.cpp + * + * authors: + * Sebastian Pütz + * Jorge Santos Simón + * + */ + +#include "mbf_simple_nav/simple_navigation_server.h" +#include +#include + +int main(int argc, char **argv) +{ + ros::init(argc, argv, "mbf_simple_server"); + + typedef boost::shared_ptr SimpleNavigationServerPtr; + + ros::NodeHandle nh; + ros::NodeHandle private_nh("~"); + + double cache_time; + private_nh.param("tf_cache_time", cache_time, 10.0); + +#ifdef USE_OLD_TF + TFPtr tf_listener_ptr(new TF(nh, ros::Duration(cache_time), true)); +#else + TFPtr tf_listener_ptr(new TF(ros::Duration(cache_time))); + tf2_ros::TransformListener tf_listener(*tf_listener_ptr); +#endif + + SimpleNavigationServerPtr controller_ptr( + new mbf_simple_nav::SimpleNavigationServer(tf_listener_ptr)); + + ros::spin(); + return EXIT_SUCCESS; +} diff --git a/navigations/move_base_flex/mbf_utility/CHANGELOG.rst b/navigations/move_base_flex/mbf_utility/CHANGELOG.rst new file mode 100755 index 0000000..5f6ba6b --- /dev/null +++ b/navigations/move_base_flex/mbf_utility/CHANGELOG.rst @@ -0,0 +1,42 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package mbf_utility +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +0.3.2 (2020-05-25) +------------------ +* Remove dependency on base_local_planner and move FootprintHelper class to mbf_costmap_nav and make it static + +0.3.1 (2020-04-07) +------------------ + +0.3.0 (2020-03-31) +------------------ +* Add exception classes for get_path, exe_path and recovery +* unify license declaration to BSD-3 + +0.2.5 (2019-10-11) +------------------ + +0.2.4 (2019-06-16) +------------------ +* Add check_point_cost service + +0.2.3 (2018-11-14) +------------------ +* Fix getRobotPose in melodic + +0.2.2 (2018-10-10) +------------------ + +0.2.1 (2018-10-03) +------------------ +* Make MBF melodic and indigo compatible +* Fix GoalHandle references bug in callbacks + +0.2.0 (2018-09-11) +------------------ +* Update copyright and 3-clause-BSD license + +0.1.0 (2018-03-22) +------------------ +* First release of move_base_flex for kinetic and lunar diff --git a/navigations/move_base_flex/mbf_utility/CMakeLists.txt b/navigations/move_base_flex/mbf_utility/CMakeLists.txt new file mode 100755 index 0000000..d7569aa --- /dev/null +++ b/navigations/move_base_flex/mbf_utility/CMakeLists.txt @@ -0,0 +1,42 @@ +cmake_minimum_required(VERSION 2.8.3) +project(mbf_utility) + +find_package(catkin REQUIRED COMPONENTS + geometry_msgs + roscpp + tf + tf2 + tf2_ros + tf2_geometry_msgs +) + +catkin_package( + INCLUDE_DIRS include + LIBRARIES mbf_utility + CATKIN_DEPENDS geometry_msgs roscpp tf tf2 tf2_ros tf2_geometry_msgs +) + +include_directories( + include + ${catkin_INCLUDE_DIRS} +) + +add_library(${PROJECT_NAME} + src/navigation_utility.cpp + src/robot_information.cpp +) + +add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) + +target_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES}) + +install(TARGETS ${PROJECT_NAME} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) + +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} + FILES_MATCHING PATTERN "*.h" +) diff --git a/navigations/move_base_flex/mbf_utility/include/mbf_utility/exe_path_exception.h b/navigations/move_base_flex/mbf_utility/include/mbf_utility/exe_path_exception.h new file mode 100755 index 0000000..9ebe487 --- /dev/null +++ b/navigations/move_base_flex/mbf_utility/include/mbf_utility/exe_path_exception.h @@ -0,0 +1,43 @@ +#ifndef MBF_UTILITY__EXE_PATH_EXCEPTION_H_ +#define MBF_UTILITY__EXE_PATH_EXCEPTION_H_ + +#include +#include + +namespace mbf_utility +{ + +struct ExePathException : public std::exception +{ + ExePathException(unsigned int error_code) : outcome(error_code){} + + const char * what () const throw () { + switch(outcome) + { + case mbf_msgs::ExePathResult::FAILURE: return "Failure"; + case mbf_msgs::ExePathResult::CANCELED: return "Canceled"; + case mbf_msgs::ExePathResult::NO_VALID_CMD: return "No valid command"; + case mbf_msgs::ExePathResult::PAT_EXCEEDED: return "Patience exceeded"; + case mbf_msgs::ExePathResult::COLLISION: return "Collision"; + case mbf_msgs::ExePathResult::OSCILLATION: return "Oscillation"; + case mbf_msgs::ExePathResult::ROBOT_STUCK: return "Robot stuck"; + case mbf_msgs::ExePathResult::MISSED_GOAL: return "Missed Goal"; + case mbf_msgs::ExePathResult::MISSED_PATH: return "Missed Path"; + case mbf_msgs::ExePathResult::BLOCKED_PATH: return "Blocked Path"; + case mbf_msgs::ExePathResult::INVALID_PATH: return "Invalid Path"; + case mbf_msgs::ExePathResult::TF_ERROR: return "TF Error"; + case mbf_msgs::ExePathResult::NOT_INITIALIZED: return "Not initialized"; + case mbf_msgs::ExePathResult::INVALID_PLUGIN: return "Invalid Plugin"; + case mbf_msgs::ExePathResult::INTERNAL_ERROR: return "Internal Error"; + case mbf_msgs::ExePathResult::STOPPED: return "Stopped"; + case mbf_msgs::ExePathResult::OUT_OF_MAP: return "Out of map"; + case mbf_msgs::ExePathResult::MAP_ERROR: return "Map error"; + default: return "unknown error code: " + outcome; + } + } + unsigned int outcome; +}; + +} /* namespace mbf_utility */ + +#endif // MBF_UTILITY__EXE_PATH_EXCEPTION_H_ diff --git a/navigations/move_base_flex/mbf_utility/include/mbf_utility/get_path_exception.h b/navigations/move_base_flex/mbf_utility/include/mbf_utility/get_path_exception.h new file mode 100755 index 0000000..75c1379 --- /dev/null +++ b/navigations/move_base_flex/mbf_utility/include/mbf_utility/get_path_exception.h @@ -0,0 +1,39 @@ +#ifndef MBF_UTILITY__GET_PATH_EXCEPTION_H_ +#define MBF_UTILITY__GET_PATH_EXCEPTION_H_ + +#include +#include + +namespace mbf_utility +{ + +struct GetPathException : public std::exception +{ + GetPathException(unsigned int error_code) : outcome(error_code){} + + const char * what () const throw () { + switch(outcome) + { + case mbf_msgs::GetPathResult::FAILURE: return "Failure"; + case mbf_msgs::GetPathResult::CANCELED: return "Canceled"; + case mbf_msgs::GetPathResult::INVALID_START: return "Invalid start" + case mbf_msgs::GetPathResult::INVALID_GOAL: return "Invalid goal" + case mbf_msgs::GetPathResult::NO_PATH_FOUND: return "No path found"; + case mbf_msgs::GetPathResult::PAT_EXCEEDED: return "Patience exceeded"; + case mbf_msgs::GetPathResult::EMPTY_PATH return "Empty Path"; + case mbf_msgs::GetPathResult::TF_ERROR: return "TF Error"; + case mbf_msgs::GetPathResult::NOT_INITIALIZED: return "Not initialized"; + case mbf_msgs::GetPathResult::INVALID_PLUGIN: return "Invalid Plugin"; + case mbf_msgs::GetPathResult::INTERNAL_ERROR: return "Internal Error"; + case mbf_msgs::GetPathResult::STOPPED: return "Stopped"; + case mbf_msgs::GetPathResult::OUT_OF_MAP: return "Out of map"; + case mbf_msgs::GetPathResult::MAP_ERROR: return "Map error"; + default: return "unknown error code: " + outcome; + } + } + unsigned int outcome; +}; + +} /* namespace mbf_utility */ + +#endif // MBF_UTILITY__GET_PATH_EXCEPTION_H_ diff --git a/navigations/move_base_flex/mbf_utility/include/mbf_utility/navigation_utility.h b/navigations/move_base_flex/mbf_utility/include/mbf_utility/navigation_utility.h new file mode 100755 index 0000000..179f20f --- /dev/null +++ b/navigations/move_base_flex/mbf_utility/include/mbf_utility/navigation_utility.h @@ -0,0 +1,119 @@ +/* + * Copyright 2018, Magazino GmbH, Sebastian Pütz, Jorge Santos Simón + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * navigation_utility.h + * + * authors: + * Sebastian Pütz + * Jorge Santos Simón + * + */ + +#ifndef MBF_UTILITY__NAVIGATION_UTILITY_H_ +#define MBF_UTILITY__NAVIGATION_UTILITY_H_ + +#include +#include +#include +#include +#include +#include +#include + +#include "mbf_utility/types.h" + +namespace mbf_utility +{ + +/** + * @brief Transforms a point from one frame into another. + * @param tf_listener TransformListener. + * @param target_frame Target frame for the point. + * @param timeout Timeout for looking up the transformation. + * @param in Point to transform. + * @param out Transformed point. + * @return true, if the transformation succeeded. + */ +bool transformPoint(const TF &tf, + const std::string &target_frame, + const ros::Duration &timeout, + const geometry_msgs::PointStamped &in, + geometry_msgs::PointStamped &out); + +/** + * @brief Transforms a pose from one frame into another. + * @param tf_listener TransformListener. + * @param target_frame Target frame for the pose. + * @param timeout Timeout for looking up the transformation. + * @param in Pose to transform. + * @param out Transformed pose. + * @return true, if the transformation succeeded. + */ +bool transformPose(const TF &tf, + const std::string &target_frame, + const ros::Duration &timeout, + const geometry_msgs::PoseStamped &in, + geometry_msgs::PoseStamped &out); + +/** + * @brief Computes the robot pose. + * @param tf_listener TransformListener. + * @param robot_frame frame of the robot. + * @param global_frame global frame in which the robot is located. + * @param timeout Timeout for looking up the transformation. + * @param robot_pose the computed rebot pose in the global frame. + * @return true, if succeeded, false otherwise. + */ +bool getRobotPose(const TF &tf, + const std::string &robot_frame, + const std::string &global_frame, + const ros::Duration &timeout, + geometry_msgs::PoseStamped &robot_pose); +/** + * @brief Computes the Euclidean-distance between two poses. + * @param pose1 pose 1 + * @param pose2 pose 2 + * @return Euclidean distance between pose 1 and pose 2. + */ +double distance(const geometry_msgs::PoseStamped &pose1, const geometry_msgs::PoseStamped &pose2); + +/** + * @brief computes the smallest angle between two poses. + * @param pose1 pose 1 + * @param pose2 pose 2 + * @return smallest angle between pose 1 and pose 2. + */ +double angle(const geometry_msgs::PoseStamped &pose1, const geometry_msgs::PoseStamped &pose2); + +} /* namespace mbf_utility */ + +#endif /* navigation_utility.h */ diff --git a/navigations/move_base_flex/mbf_utility/include/mbf_utility/recovery_exception.h b/navigations/move_base_flex/mbf_utility/include/mbf_utility/recovery_exception.h new file mode 100755 index 0000000..b79bbde --- /dev/null +++ b/navigations/move_base_flex/mbf_utility/include/mbf_utility/recovery_exception.h @@ -0,0 +1,33 @@ +#ifndef MBF_UTILITY__RECOVERY_EXCEPTION_H_ +#define MBF_UTILITY__RECOVERY_EXCEPTION_H_ + +#include +#include + +namespace mbf_utility +{ + +struct RecoveryException : public std::exception +{ + RecoveryException(unsigned int error_code) : outcome(error_code){} + + const char * what () const throw () { + switch(outcome) + { + case mbf_msgs::RecoveryResult::FAILURE: return "Failure"; + case mbf_msgs::RecoveryResult::CANCELED: return "Canceled"; + case mbf_msgs::RecoveryResult::PAT_EXCEEDED: return "Patience exceeded"; + case mbf_msgs::RecoveryResult::TF_ERROR: return "TF Error"; + case mbf_msgs::RecoveryResult::NOT_INITIALIZED: return "Not initialized"; + case mbf_msgs::RecoveryResult::INVALID_PLUGIN: return "Invalid Plugin"; + case mbf_msgs::RecoveryResult::INTERNAL_ERROR: return "Internal Error"; + case mbf_msgs::RecoveryResult::STOPPED: return "Stopped"; + default: return "unknown error code: " + outcome; + } + } + unsigned int outcome; +}; + +} /* namespace mbf_utility */ + +#endif // MBF_UTILITY__RECOVERY_EXCEPTION_H_ diff --git a/navigations/move_base_flex/mbf_utility/include/mbf_utility/robot_information.h b/navigations/move_base_flex/mbf_utility/include/mbf_utility/robot_information.h new file mode 100755 index 0000000..82d3960 --- /dev/null +++ b/navigations/move_base_flex/mbf_utility/include/mbf_utility/robot_information.h @@ -0,0 +1,95 @@ +/* + * Copyright 2018, Sebastian Pütz + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * robot_information.h + * + * author: Sebastian Pütz + * + */ + +#ifndef MBF_UTILITY__ROBOT_INFORMATION_H_ +#define MBF_UTILITY__ROBOT_INFORMATION_H_ + +#include +#include +#include +#include +#include + +#include "mbf_utility/types.h" + +namespace mbf_utility +{ + +class RobotInformation +{ + public: + + typedef boost::shared_ptr Ptr; + + RobotInformation( + TF &tf_listener, + const std::string &global_frame, + const std::string &robot_frame, + const ros::Duration &tf_timeout); + + /** + * @brief Computes the current robot pose (robot_frame_) in the global frame (global_frame_). + * @param robot_pose Reference to the robot_pose message object to be filled. + * @return true, if the current robot pose could be computed, false otherwise. + */ + bool getRobotPose(geometry_msgs::PoseStamped &robot_pose) const; + + bool getRobotVelocity(geometry_msgs::TwistStamped &robot_velocity, ros::Duration look_back_duration) const; + + const std::string& getGlobalFrame() const; + + const std::string& getRobotFrame() const; + + const TF& getTransformListener() const; + + const ros::Duration& getTfTimeout() const; + + private: + const TF& tf_listener_; + + const std::string &global_frame_; + + const std::string &robot_frame_; + + const ros::Duration &tf_timeout_; + +}; + +} /* mbf_utility */ + +#endif /* MBF_UTILITY__ROBOT_INFORMATION_H_ */ diff --git a/navigations/move_base_flex/mbf_utility/include/mbf_utility/types.h b/navigations/move_base_flex/mbf_utility/include/mbf_utility/types.h new file mode 100755 index 0000000..1e4046f --- /dev/null +++ b/navigations/move_base_flex/mbf_utility/include/mbf_utility/types.h @@ -0,0 +1,60 @@ +/* + * Copyright 2018, Sebastian Pütz + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * abstract_planner.h + * + * author: Jannik Abbenseth + * + */ + +#ifndef MBF_UTILITY__TYPES_H_ +#define MBF_UTILITY__TYPES_H_ + +#include +#include + +#if ROS_VERSION_MINIMUM (1, 14, 0) // if current ros version is >= 1.14.0 + // Melodic uses TF2 + #include + typedef boost::shared_ptr TFPtr; + typedef tf2_ros::Buffer TF; + typedef tf2::TransformException TFException; +#else + // Previous versions still using TF + #define USE_OLD_TF + #include + typedef boost::shared_ptr TFPtr; + typedef tf::TransformListener TF; + typedef tf::TransformException TFException; +#endif + +#endif diff --git a/navigations/move_base_flex/mbf_utility/package.xml b/navigations/move_base_flex/mbf_utility/package.xml new file mode 100755 index 0000000..95913c4 --- /dev/null +++ b/navigations/move_base_flex/mbf_utility/package.xml @@ -0,0 +1,21 @@ + + + mbf_utility + 0.3.2 + The mbf_utility package + + Sebastian Pütz + + BSD-3 + http://wiki.ros.org/move_base_flex/mbf_utility + Sebastian Pütz + + catkin + + geometry_msgs + roscpp + tf + tf2 + tf2_ros + tf2_geometry_msgs + diff --git a/navigations/move_base_flex/mbf_utility/src/navigation_utility.cpp b/navigations/move_base_flex/mbf_utility/src/navigation_utility.cpp new file mode 100755 index 0000000..740d5ac --- /dev/null +++ b/navigations/move_base_flex/mbf_utility/src/navigation_utility.cpp @@ -0,0 +1,186 @@ +/* + * Copyright 2018, Magazino GmbH, Sebastian Pütz, Jorge Santos Simón + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * navigation_utility.cpp + * + * authors: + * Sebastian Pütz + * Jorge Santos Simón + * + */ + +#include + +#include "mbf_utility/navigation_utility.h" + +namespace mbf_utility +{ + +bool getRobotPose(const TF &tf, + const std::string &robot_frame, + const std::string &global_frame, + const ros::Duration &timeout, + geometry_msgs::PoseStamped &robot_pose) +{ + geometry_msgs::PoseStamped local_pose; + local_pose.header.frame_id = robot_frame; + local_pose.header.stamp = ros::Time(0); // most recent available + local_pose.pose.orientation.w = 1.0; + bool success = transformPose(tf, + global_frame, + timeout, + local_pose, + robot_pose); + if (success && ros::Time::now() - robot_pose.header.stamp > timeout) + { + ROS_WARN("Most recent robot pose is %gs old (tolerance %gs)", + (ros::Time::now() - robot_pose.header.stamp).toSec(), timeout.toSec()); + return false; + } + return success; +} + +bool transformPose(const TF &tf, + const std::string &target_frame, + const ros::Duration &timeout, + const geometry_msgs::PoseStamped &in, + geometry_msgs::PoseStamped &out) +{ + std::string error_msg; + +#ifdef USE_OLD_TF + bool success = tf.waitForTransform(target_frame, + in.header.frame_id, + in.header.stamp, + timeout, + ros::Duration(0.01), + &error_msg); +#else + bool success = tf.canTransform(target_frame, + in.header.frame_id, + in.header.stamp, + timeout, + &error_msg); +#endif + + if (!success) + { + ROS_WARN_STREAM("Failed to look up transform from frame '" << in.header.frame_id << "' into frame '" << target_frame + << "': " << error_msg); + return false; + } + + try + { +#ifdef USE_OLD_TF + tf.transformPose(target_frame, in, out); +#else + tf.transform(in, out, target_frame); +#endif + } + catch (const TFException &ex) + { + ROS_WARN_STREAM("Failed to transform pose from frame '" << in.header.frame_id << " ' into frame '" + << target_frame << "' with exception: " << ex.what()); + return false; + } + return true; +} + +bool transformPoint(const TF &tf, + const std::string &target_frame, + const ros::Duration &timeout, + const geometry_msgs::PointStamped &in, + geometry_msgs::PointStamped &out) +{ + std::string error_msg; + +#ifdef USE_OLD_TF + bool success = tf.waitForTransform(target_frame, + in.header.frame_id, + in.header.stamp, + timeout, + ros::Duration(0.01), + &error_msg); +#else + bool success = tf.canTransform(target_frame, + in.header.frame_id, + in.header.stamp, + timeout, + &error_msg); +#endif + + if (!success) + { + ROS_WARN_STREAM("Failed to look up transform from frame '" << in.header.frame_id << "' into frame '" << target_frame + << "': " << error_msg); + return false; + } + + try + { +#ifdef USE_OLD_TF + tf.transformPoint(target_frame, in, out); +#else + tf.transform(in, out, target_frame); +#endif + } + catch (const TFException &ex) + { + ROS_WARN_STREAM("Failed to transform point from frame '" << in.header.frame_id << " ' into frame '" + << target_frame << "' with exception: " << ex.what()); + return false; + } + return true; +} + +double distance(const geometry_msgs::PoseStamped &pose1, const geometry_msgs::PoseStamped &pose2) +{ + const geometry_msgs::Point &p1 = pose1.pose.position; + const geometry_msgs::Point &p2 = pose2.pose.position; + const double dx = p1.x - p2.x; + const double dy = p1.y - p2.y; + const double dz = p1.z - p2.z; + return sqrt(dx * dx + dy * dy + dz * dz); +} + +double angle(const geometry_msgs::PoseStamped &pose1, const geometry_msgs::PoseStamped &pose2) +{ + const geometry_msgs::Quaternion &q1 = pose1.pose.orientation; + const geometry_msgs::Quaternion &q2 = pose2.pose.orientation; + tf::Quaternion rot1, rot2; + tf::quaternionMsgToTF(q1, rot1); + tf::quaternionMsgToTF(q2, rot2); + return rot1.angleShortestPath(rot2); +} + +} /* namespace mbf_utility */ diff --git a/navigations/move_base_flex/mbf_utility/src/robot_information.cpp b/navigations/move_base_flex/mbf_utility/src/robot_information.cpp new file mode 100755 index 0000000..97322c3 --- /dev/null +++ b/navigations/move_base_flex/mbf_utility/src/robot_information.cpp @@ -0,0 +1,82 @@ +/* + * Copyright 2018, Sebastian Pütz + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * robot_information.cpp + * + * author: Sebastian Pütz + * + */ + +#include "mbf_utility/robot_information.h" +#include "mbf_utility/navigation_utility.h" + +namespace mbf_utility +{ + +RobotInformation::RobotInformation(TF &tf_listener, + const std::string &global_frame, + const std::string &robot_frame, + const ros::Duration &tf_timeout) + : tf_listener_(tf_listener), global_frame_(global_frame), robot_frame_(robot_frame), tf_timeout_(tf_timeout) +{ + +} + + +bool RobotInformation::getRobotPose(geometry_msgs::PoseStamped &robot_pose) const +{ + bool tf_success = mbf_utility::getRobotPose(tf_listener_, robot_frame_, global_frame_, + ros::Duration(tf_timeout_), robot_pose); + if (!tf_success) + { + ROS_ERROR_STREAM("Can not get the robot pose in the global frame. - robot frame: \"" + << robot_frame_ << "\" global frame: \"" << global_frame_ << std::endl); + return false; + } + return true; +} + +bool RobotInformation::getRobotVelocity(geometry_msgs::TwistStamped &robot_velocity, ros::Duration look_back_duration) const +{ + // TODO implement and filter tf data to compute velocity. + return false; +} + +const std::string& RobotInformation::getGlobalFrame() const {return global_frame_;}; + +const std::string& RobotInformation::getRobotFrame() const {return robot_frame_;}; + +const TF& RobotInformation::getTransformListener() const {return tf_listener_;}; + +const ros::Duration& RobotInformation::getTfTimeout() const {return tf_timeout_;} + +} /* namespace mbf_utility */ diff --git a/navigations/move_base_flex/move_base_flex/CHANGELOG.rst b/navigations/move_base_flex/move_base_flex/CHANGELOG.rst new file mode 100755 index 0000000..5401dc1 --- /dev/null +++ b/navigations/move_base_flex/move_base_flex/CHANGELOG.rst @@ -0,0 +1,39 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package move_base_flex +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +0.3.2 (2020-05-25) +------------------ + +0.3.1 (2020-04-07) +------------------ + +0.3.0 (2020-03-31) +------------------ +* unify license declaration to BSD-3 + +0.2.5 (2019-10-11) +------------------ + +0.2.4 (2019-06-16) +------------------ + +0.2.3 (2018-11-14) +------------------ + +0.2.2 (2018-10-10) +------------------ + +0.2.1 (2018-10-03) +------------------ + +0.2.0 (2018-09-11) +------------------ +* Update copyright and 3-clause-BSD license of the Move Base Flex stack +* Concurrency for planners, controllers and recovery behaviors +* New class structure, allowing multiple executoin instances +* Fixes minor bugs + +0.1.0 (2018-03-22) +------------------ +* First release of move_base_flex for kinetic and lunar diff --git a/navigations/move_base_flex/move_base_flex/CMakeLists.txt b/navigations/move_base_flex/move_base_flex/CMakeLists.txt new file mode 100755 index 0000000..eb9de7a --- /dev/null +++ b/navigations/move_base_flex/move_base_flex/CMakeLists.txt @@ -0,0 +1,4 @@ +cmake_minimum_required(VERSION 2.8.3) +project(move_base_flex) +find_package(catkin REQUIRED) +catkin_metapackage() diff --git a/navigations/move_base_flex/move_base_flex/package.xml b/navigations/move_base_flex/move_base_flex/package.xml new file mode 100755 index 0000000..eef2d6e --- /dev/null +++ b/navigations/move_base_flex/move_base_flex/package.xml @@ -0,0 +1,28 @@ + + + move_base_flex + 0.3.2 + + Move Base Flex (MBF) is a backwards-compatible replacement for move_base. MBF can use existing plugins for move_base, and provides an enhanced version of the planner, controller and recovery plugin ROS interfaces. It exposes action servers for planning, controlling and recovering, providing detailed information of the current state and the plugin’s feedback. An external executive logic can use MBF and its actions to perform smart and flexible navigation strategies. Furthermore, MBF enables the use of other map representations, e.g. meshes or grid_map + + This package is a meta package and refers to the Move Base Flex stack packages.The abstract core of MBF – without any binding to a map representation – is represented by the mbf_abstract_nav and the mbf_abstract_core. For navigation on costmaps see mbf_costmap_nav and mbf_costmap_core. + + + Sebastian Pütz + BSD-3 + http://wiki.ros.org/move_base_flex + Sebastian Pütz + + catkin + mbf_abstract_core + mbf_abstract_nav + mbf_costmap_core + mbf_costmap_nav + mbf_msgs + mbf_simple_nav + mbf_utility + + + + + diff --git a/navigations/move_base_msgs/CHANGELOG.rst b/navigations/move_base_msgs/CHANGELOG.rst new file mode 100755 index 0000000..c9487f8 --- /dev/null +++ b/navigations/move_base_msgs/CHANGELOG.rst @@ -0,0 +1,20 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package move_base_msgs +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +1.14.1 (2020-11-02) +------------------- +* Merge pull request `#19 `_ from ros-planning/recovery_behavior_msg + Recovery behavior msg +* Contributors: David V. Lu, David V. Lu!!, Peter Mitrano + +1.14.0 (2020-03-10) +------------------- +* Bump CMake version to avoid CMP0048 + Signed-off-by: Shane Loretz +* Contributors: Shane Loretz + +1.13.0 (2015-03-16) +------------------- +* initial release from new repository +* Contributors: Michael Ferguson diff --git a/navigations/move_base_msgs/CMakeLists.txt b/navigations/move_base_msgs/CMakeLists.txt new file mode 100755 index 0000000..a67fe1b --- /dev/null +++ b/navigations/move_base_msgs/CMakeLists.txt @@ -0,0 +1,35 @@ +cmake_minimum_required(VERSION 3.0.2) +project(move_base_msgs) + +find_package(catkin REQUIRED + COMPONENTS + actionlib_msgs + geometry_msgs + message_generation +) + +# msgs +add_message_files( + DIRECTORY + msg + FILES + RecoveryStatus.msg +) + +# actions +add_action_files( + DIRECTORY + action + FILES + MoveBase.action +) + +generate_messages( + DEPENDENCIES + actionlib_msgs + geometry_msgs +) + +catkin_package( + CATKIN_DEPENDS actionlib_msgs geometry_msgs message_runtime +) diff --git a/navigations/move_base_msgs/action/MoveBase.action b/navigations/move_base_msgs/action/MoveBase.action new file mode 100755 index 0000000..49a6cab --- /dev/null +++ b/navigations/move_base_msgs/action/MoveBase.action @@ -0,0 +1,4 @@ +geometry_msgs/PoseStamped target_pose +--- +--- +geometry_msgs/PoseStamped base_position diff --git a/navigations/move_base_msgs/msg/RecoveryStatus.msg b/navigations/move_base_msgs/msg/RecoveryStatus.msg new file mode 100755 index 0000000..9c6fb7a --- /dev/null +++ b/navigations/move_base_msgs/msg/RecoveryStatus.msg @@ -0,0 +1,4 @@ +geometry_msgs/PoseStamped pose_stamped # The robot's pose when the recovery was triggered +uint16 current_recovery_number # 0-based index of current recovery number +uint16 total_number_of_recoveries # Total number of recoveries configured +string recovery_behavior_name # Namespace of the recovery being executed diff --git a/navigations/move_base_msgs/package.xml b/navigations/move_base_msgs/package.xml new file mode 100755 index 0000000..6f3f78c --- /dev/null +++ b/navigations/move_base_msgs/package.xml @@ -0,0 +1,28 @@ + + move_base_msgs + 1.14.1 + + + Holds the action description and relevant messages for the move_base package. + + + Eitan Marder-Eppstein + contradict@gmail.com + David V. Lu!! + Michael Ferguson + BSD + http://wiki.ros.org/move_base_msgs + https://github.com/ros-planning/navigation_msgs/issues + + catkin + + actionlib_msgs + geometry_msgs + message_generation + + actionlib_msgs + geometry_msgs + message_runtime + + + diff --git a/navigations/move_slow_and_clear/CHANGELOG.rst b/navigations/move_slow_and_clear/CHANGELOG.rst new file mode 100755 index 0000000..137c381 --- /dev/null +++ b/navigations/move_slow_and_clear/CHANGELOG.rst @@ -0,0 +1,150 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package move_slow_and_clear +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +1.17.3 (2023-01-10) +------------------- +* [ROS-O] various patches (`#1225 `_) + * do not specify obsolete c++11 standard + this breaks with current versions of log4cxx. + * update pluginlib include paths + the non-hpp headers have been deprecated since kinetic + * use lambdas in favor of boost::bind + Using boost's _1 as a global system is deprecated since C++11. + The ROS packages in Debian removed the implicit support for the global symbols, + so this code fails to compile there without the patch. +* Contributors: Michael Görner + +1.17.2 (2022-06-20) +------------------- +* [move_slow_and_clear] Add rosparam representing max vel rosparam name (`#1039 `_) +* Contributors: Naoya Yamaguchi + +1.17.1 (2020-08-27) +------------------- + +1.17.0 (2020-04-02) +------------------- +* Merge pull request `#982 `_ from ros-planning/noetic_prep + Noetic Migration +* increase required cmake version +* Contributors: Michael Ferguson + +1.16.6 (2020-03-18) +------------------- + +1.16.5 (2020-03-15) +------------------- +* [melodic] updated install for better portability. (`#973 `_) +* Contributors: Sean Yen + +1.16.4 (2020-03-04) +------------------- +* [Windows][melodic] Navigation (except for map_server and amcl) Windows build bring up (`#851 `_) +* Merge pull request `#955 `_ from isjfk/melodic-devel + Fix move_slow_and_clear sending obsolete params to dwa_local_planner +* Fix move_slow_and_clear sending obsolete params to dwa_local_planner + issue. +* Contributors: Jimmy F. Klarke, Michael Ferguson, Sean Yen + +1.16.3 (2019-11-15) +------------------- + +1.16.2 (2018-07-31) +------------------- + +1.16.1 (2018-07-28) +------------------- + +1.16.0 (2018-07-25) +------------------- +* Switch to TF2 `#755 `_ +* Contributors: Michael Ferguson, Vincent Rabaud + +1.15.2 (2018-03-22) +------------------- +* Merge pull request `#673 `_ from ros-planning/email_update_lunar + update maintainer email (lunar) +* Merge pull request `#649 `_ from aaronhoy/lunar_add_ahoy + Add myself as a maintainer. +* Rebase PRs from Indigo/Kinetic (`#637 `_) + * Respect planner_frequency intended behavior (`#622 `_) + * Only do a getRobotPose when no start pose is given (`#628 `_) + Omit the unnecessary call to getRobotPose when the start pose was + already given, so that move_base can also generate a path in + situations where getRobotPose would fail. + This is actually to work around an issue of getRobotPose randomly + failing. + * Update gradient_path.cpp (`#576 `_) + * Update gradient_path.cpp + * Update navfn.cpp + * update to use non deprecated pluginlib macro (`#630 `_) + * update to use non deprecated pluginlib macro + * multiline version as well + * Print SDL error on IMG_Load failure in server_map (`#631 `_) +* Contributors: Aaron Hoy, David V. Lu!!, Michael Ferguson + +1.15.1 (2017-08-14) +------------------- + +1.15.0 (2017-08-07) +------------------- +* convert packages to format2 +* Fix CMakeLists + package.xmls (`#548 `_) +* import only PCL common +* address gcc6 build error +* remove GCC warnings +* Fix CMake warnings +* Contributors: Lukas Bulwahn, Martin Günther, Mikael Arguedas, Vincent Rabaud + +1.14.0 (2016-05-20) +------------------- + +1.13.1 (2015-10-29) +------------------- + +1.13.0 (2015-03-17) +------------------- + +1.12.0 (2015-02-04) +------------------- +* update maintainer email +* Contributors: Michael Ferguson + +1.11.15 (2015-02-03) +-------------------- +* Add ARCHIVE_DESTINATION for static builds +* Contributors: Gary Servin + +1.11.14 (2014-12-05) +-------------------- + +1.11.13 (2014-10-02) +-------------------- + +1.11.12 (2014-10-01) +-------------------- + +1.11.11 (2014-07-23) +-------------------- +* Use service call, rather than system call, to call dynamic + reconfigure when decreasing move_base speed. +* Contributors: Ryohei Ueda + +1.11.10 (2014-06-25) +-------------------- + +1.11.9 (2014-06-10) +------------------- + +1.11.8 (2014-05-21) +------------------- + +1.11.7 (2014-05-21) +------------------- +* update build to find eigen using cmake_modules +* Contributors: Michael Ferguson + +1.11.4 (2013-09-27) +------------------- +* Package URL Updates diff --git a/navigations/move_slow_and_clear/CMakeLists.txt b/navigations/move_slow_and_clear/CMakeLists.txt new file mode 100755 index 0000000..1ae6779 --- /dev/null +++ b/navigations/move_slow_and_clear/CMakeLists.txt @@ -0,0 +1,58 @@ +cmake_minimum_required(VERSION 3.0.2) +project(move_slow_and_clear) + +find_package(catkin REQUIRED + COMPONENTS + cmake_modules + costmap_2d + geometry_msgs + nav_core + pluginlib + roscpp + ) + + +find_package(Eigen3 REQUIRED) +remove_definitions(-DDISABLE_LIBUSB-1.0) +find_package(Boost REQUIRED COMPONENTS thread) +include_directories( + include + ${catkin_INCLUDE_DIRS} + ${EIGEN3_INCLUDE_DIRS} +) +add_definitions(${EIGEN3_DEFINITIONS}) + +catkin_package( + INCLUDE_DIRS include + LIBRARIES move_slow_and_clear + CATKIN_DEPENDS + geometry_msgs + nav_core + pluginlib + roscpp +) + +add_library(${PROJECT_NAME} src/move_slow_and_clear.cpp) +add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) +target_link_libraries(${PROJECT_NAME} + ${Boost_LIBRARIES} + ${catkin_LIBRARIES} + ) + +## Install project namespaced headers +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} + FILES_MATCHING PATTERN "*.h" + PATTERN ".svn" EXCLUDE) + +install(TARGETS move_slow_and_clear + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} + ) + +install(FILES recovery_plugin.xml + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) + + diff --git a/navigations/move_slow_and_clear/include/move_slow_and_clear/move_slow_and_clear.h b/navigations/move_slow_and_clear/include/move_slow_and_clear/move_slow_and_clear.h new file mode 100755 index 0000000..4c43e7e --- /dev/null +++ b/navigations/move_slow_and_clear/include/move_slow_and_clear/move_slow_and_clear.h @@ -0,0 +1,85 @@ +/********************************************************************* +* +* Software License Agreement (BSD License) +* +* Copyright (c) 2009, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of Willow Garage, Inc. nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* +* Author: Eitan Marder-Eppstein +*********************************************************************/ +#ifndef MOVE_SLOW_AND_CLEAR_MOVE_SLOW_AND_CLEAR_H_ +#define MOVE_SLOW_AND_CLEAR_MOVE_SLOW_AND_CLEAR_H_ + +#include +#include +#include +#include +#include + +namespace move_slow_and_clear +{ + class MoveSlowAndClear : public nav_core::RecoveryBehavior + { + public: + MoveSlowAndClear(); + ~MoveSlowAndClear(); + + /// Initialize the parameters of the behavior + void initialize (std::string n, tf2_ros::Buffer* tf, + costmap_2d::Costmap2DROS* global_costmap, + costmap_2d::Costmap2DROS* local_costmap); + + /// Run the behavior + void runBehavior(); + + private: + void setRobotSpeed(double trans_speed, double rot_speed); + void distanceCheck(const ros::TimerEvent& e); + double getSqDistance(); + + void removeSpeedLimit(); + + ros::NodeHandle private_nh_, planner_nh_; + costmap_2d::Costmap2DROS* global_costmap_; + costmap_2d::Costmap2DROS* local_costmap_; + bool initialized_; + double clearing_distance_, limited_distance_; + double limited_trans_speed_, limited_rot_speed_, old_trans_speed_, old_rot_speed_; + std::string max_trans_param_name_, max_rot_param_name_; + ros::Timer distance_check_timer_; + geometry_msgs::PoseStamped speed_limit_pose_; + boost::thread* remove_limit_thread_; + boost::mutex mutex_; + bool limit_set_; + ros::ServiceClient planner_dynamic_reconfigure_service_; + }; +}; + +#endif diff --git a/navigations/move_slow_and_clear/package.xml b/navigations/move_slow_and_clear/package.xml new file mode 100755 index 0000000..eddf751 --- /dev/null +++ b/navigations/move_slow_and_clear/package.xml @@ -0,0 +1,35 @@ + + + + move_slow_and_clear + 1.17.3 + + + move_slow_and_clear + + + Eitan Marder-Eppstein + contradict@gmail.com + David V. Lu!! + Michael Ferguson + Aaron Hoy + BSD + http://wiki.ros.org/move_slow_and_clear + + catkin + + cmake_modules + + costmap_2d + geometry_msgs + nav_core + pluginlib + roscpp + + + + + + + + diff --git a/navigations/move_slow_and_clear/recovery_plugin.xml b/navigations/move_slow_and_clear/recovery_plugin.xml new file mode 100755 index 0000000..71776ee --- /dev/null +++ b/navigations/move_slow_and_clear/recovery_plugin.xml @@ -0,0 +1,7 @@ + + + + A recovery behavior that clears information in the costmap within the circumscribed radius of the robot and then limits the speed of the robot. Note, this recovery behavior is not truly safe, the robot may hit things, it'll just happen at a user-specified speed. Also, this recovery behavior is only compatible with local planners that allow maximum speeds to be set via dynamic reconfigure. + + + diff --git a/navigations/move_slow_and_clear/src/move_slow_and_clear.cpp b/navigations/move_slow_and_clear/src/move_slow_and_clear.cpp new file mode 100755 index 0000000..53b9ae6 --- /dev/null +++ b/navigations/move_slow_and_clear/src/move_slow_and_clear.cpp @@ -0,0 +1,225 @@ +/********************************************************************* +* +* Software License Agreement (BSD License) +* +* Copyright (c) 2009, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of Willow Garage, Inc. nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* +* Author: Eitan Marder-Eppstein +*********************************************************************/ +#include +#include +#include + +PLUGINLIB_EXPORT_CLASS(move_slow_and_clear::MoveSlowAndClear, nav_core::RecoveryBehavior) + +namespace move_slow_and_clear +{ + MoveSlowAndClear::MoveSlowAndClear():global_costmap_(NULL), local_costmap_(NULL), + initialized_(false), remove_limit_thread_(NULL), limit_set_(false){} + + MoveSlowAndClear::~MoveSlowAndClear() + { + delete remove_limit_thread_; + } + + void MoveSlowAndClear::initialize (std::string n, tf2_ros::Buffer* tf, + costmap_2d::Costmap2DROS* global_costmap, + costmap_2d::Costmap2DROS* local_costmap) + { + global_costmap_ = global_costmap; + local_costmap_ = local_costmap; + + ros::NodeHandle private_nh_("~/" + n); + private_nh_.param("clearing_distance", clearing_distance_, 0.5); + private_nh_.param("limited_trans_speed", limited_trans_speed_, 0.25); + private_nh_.param("limited_rot_speed", limited_rot_speed_, 0.45); + private_nh_.param("limited_distance", limited_distance_, 0.3); + private_nh_.param("max_trans_param_name", max_trans_param_name_, std::string("max_trans_vel")); + private_nh_.param("max_rot_param_name", max_rot_param_name_, std::string("max_rot_vel")); + + std::string planner_namespace; + private_nh_.param("planner_namespace", planner_namespace, std::string("DWAPlannerROS")); + planner_nh_ = ros::NodeHandle("~/" + planner_namespace); + planner_dynamic_reconfigure_service_ = planner_nh_.serviceClient("set_parameters", true); + initialized_ = true; + } + + void MoveSlowAndClear::runBehavior() + { + if(!initialized_) + { + ROS_ERROR("This recovery behavior has not been initialized, doing nothing."); + return; + } + ROS_WARN("Move slow and clear recovery behavior started."); + geometry_msgs::PoseStamped global_pose, local_pose; + global_costmap_->getRobotPose(global_pose); + local_costmap_->getRobotPose(local_pose); + + std::vector global_poly, local_poly; + geometry_msgs::Point pt; + + for(int i = -1; i <= 1; i+=2) + { + pt.x = global_pose.pose.position.x + i * clearing_distance_; + pt.y = global_pose.pose.position.y + i * clearing_distance_; + global_poly.push_back(pt); + + pt.x = global_pose.pose.position.x + i * clearing_distance_; + pt.y = global_pose.pose.position.y + -1.0 * i * clearing_distance_; + global_poly.push_back(pt); + + pt.x = local_pose.pose.position.x + i * clearing_distance_; + pt.y = local_pose.pose.position.y + i * clearing_distance_; + local_poly.push_back(pt); + + pt.x = local_pose.pose.position.x + i * clearing_distance_; + pt.y = local_pose.pose.position.y + -1.0 * i * clearing_distance_; + local_poly.push_back(pt); + } + + //clear the desired space in the costmaps + std::vector >* plugins = global_costmap_->getLayeredCostmap()->getPlugins(); + for (std::vector >::iterator pluginp = plugins->begin(); pluginp != plugins->end(); ++pluginp) { + boost::shared_ptr plugin = *pluginp; + if(plugin->getName().find("obstacles")!=std::string::npos){ + boost::shared_ptr costmap; + costmap = boost::static_pointer_cast(plugin); + costmap->setConvexPolygonCost(global_poly, costmap_2d::FREE_SPACE); + } + } + + plugins = local_costmap_->getLayeredCostmap()->getPlugins(); + for (std::vector >::iterator pluginp = plugins->begin(); pluginp != plugins->end(); ++pluginp) { + boost::shared_ptr plugin = *pluginp; + if(plugin->getName().find("obstacles")!=std::string::npos){ + boost::shared_ptr costmap; + costmap = boost::static_pointer_cast(plugin); + costmap->setConvexPolygonCost(local_poly, costmap_2d::FREE_SPACE); + } + } + + //lock... just in case we're already speed limited + boost::mutex::scoped_lock l(mutex_); + + //get the old maximum speed for the robot... we'll want to set it back + if(!limit_set_) + { + if(!planner_nh_.getParam(max_trans_param_name_, old_trans_speed_)) + { + ROS_ERROR("The planner %s, does not have the parameter %s", planner_nh_.getNamespace().c_str(), max_trans_param_name_.c_str()); + } + + if(!planner_nh_.getParam(max_rot_param_name_, old_rot_speed_)) + { + ROS_ERROR("The planner %s, does not have the parameter %s", planner_nh_.getNamespace().c_str(), max_rot_param_name_.c_str()); + } + } + + //we also want to save our current position so that we can remove the speed limit we impose later on + speed_limit_pose_ = global_pose; + + //limit the speed of the robot until it moves a certain distance + setRobotSpeed(limited_trans_speed_, limited_rot_speed_); + limit_set_ = true; + distance_check_timer_ = private_nh_.createTimer(ros::Duration(0.1), &MoveSlowAndClear::distanceCheck, this); + } + + double MoveSlowAndClear::getSqDistance() + { + geometry_msgs::PoseStamped global_pose; + global_costmap_->getRobotPose(global_pose); + double x1 = global_pose.pose.position.x; + double y1 = global_pose.pose.position.y; + + double x2 = speed_limit_pose_.pose.position.x; + double y2 = speed_limit_pose_.pose.position.y; + + return (x2 - x1) * (x2 - x1) + (y2 - y1) * (y2 - y1); + } + + void MoveSlowAndClear::distanceCheck(const ros::TimerEvent& e) + { + if(limited_distance_ * limited_distance_ <= getSqDistance()) + { + ROS_INFO("Moved far enough, removing speed limit."); + //have to do this because a system call within a timer cb does not seem to play nice + if(remove_limit_thread_) + { + remove_limit_thread_->join(); + delete remove_limit_thread_; + } + remove_limit_thread_ = new boost::thread(boost::bind(&MoveSlowAndClear::removeSpeedLimit, this)); + + distance_check_timer_.stop(); + } + } + + void MoveSlowAndClear::removeSpeedLimit() + { + boost::mutex::scoped_lock l(mutex_); + setRobotSpeed(old_trans_speed_, old_rot_speed_); + limit_set_ = false; + } + + void MoveSlowAndClear::setRobotSpeed(double trans_speed, double rot_speed) + { + + { + dynamic_reconfigure::Reconfigure vel_reconfigure; + dynamic_reconfigure::DoubleParameter new_trans; + new_trans.name = max_trans_param_name_; + new_trans.value = trans_speed; + vel_reconfigure.request.config.doubles.push_back(new_trans); + try { + planner_dynamic_reconfigure_service_.call(vel_reconfigure); + ROS_INFO_STREAM("Recovery setting trans vel: " << trans_speed); + } + catch(...) { + ROS_ERROR("Something went wrong in the service call to dynamic_reconfigure"); + } + } + { + dynamic_reconfigure::Reconfigure rot_reconfigure; + dynamic_reconfigure::DoubleParameter new_rot; + new_rot.name = max_rot_param_name_; + new_rot.value = rot_speed; + rot_reconfigure.request.config.doubles.push_back(new_rot); + try { + planner_dynamic_reconfigure_service_.call(rot_reconfigure); + ROS_INFO_STREAM("Recovery setting rot vel: " << rot_speed); + } + catch(...) { + ROS_ERROR("Something went wrong in the service call to dynamic_reconfigure"); + } + } + } +}; diff --git a/navigations/nav_2d_msgs/CMakeLists.txt b/navigations/nav_2d_msgs/CMakeLists.txt new file mode 100755 index 0000000..f001fe8 --- /dev/null +++ b/navigations/nav_2d_msgs/CMakeLists.txt @@ -0,0 +1,36 @@ +cmake_minimum_required(VERSION 3.0.2) +project(nav_2d_msgs) + +find_package(catkin REQUIRED COMPONENTS + geometry_msgs + message_generation + std_msgs +) + +add_message_files(FILES + ComplexPolygon2D.msg + NavGridInfo.msg + NavGridOfChars.msg + NavGridOfCharsUpdate.msg + NavGridOfDoubles.msg + NavGridOfDoublesUpdate.msg + Path2D.msg + Point2D.msg + Polygon2D.msg + Polygon2DCollection.msg + Polygon2DStamped.msg + Pose2D32.msg + Pose2DStamped.msg + Twist2D.msg + Twist2D32.msg + Twist2DStamped.msg + UIntBounds.msg +) + +add_service_files(FILES SwitchPlugin.srv) + +generate_messages(DEPENDENCIES geometry_msgs std_msgs) + +catkin_package( + CATKIN_DEPENDS geometry_msgs message_runtime std_msgs +) diff --git a/navigations/nav_2d_msgs/README.md b/navigations/nav_2d_msgs/README.md new file mode 100755 index 0000000..c9366b1 --- /dev/null +++ b/navigations/nav_2d_msgs/README.md @@ -0,0 +1,30 @@ +# nav_2d_msgs + +This package has basic message types for two dimensional navigation. Many of the messages are similar to those in `geometry_msgs` or `nav_msgs` but are streamlined to only be concerned with 2.5 dimensional `(x, y, theta)` navigation. This eliminates quaternions from the messages in many places, which make calculations faster and avoids that particular headache when only one orientation value is needed for 2.5D navigation. + +## Points and Poses + * [`Point2D`](msg/Point2D.msg) - like `geometry_msgs::Point` but just `x` and `y` (no `z`) + * [`Pose2DStamped`](msg/Pose2DStamped.msg) - `geometry_msgs::Pose2D` with a header + * [`Pose2D32`](msg/Pose2D32.msg) - `(x, y, theta)` with only 32bit floating point precision. + * [`Path2D`](msg/Path2D.msg) - An array of `Pose2D` with a header. Similar to `nav_msgs::Path` but without redundant headers. + +## Polygons + * [`Polygon2D`](msg/Polygon2D.msg) - Like `geometry_msgs::Polygon` but with 64 bit precision and no `z` coordinate. + * [`Polygon2DStamped`](msg/Polygon2DStamped.msg) - above with a header + * [`ComplexPolygon2D`](msg/ComplexPolygon2D.msg) - Non-simple Polygon2D, i.e. polygon with inner holes + * [`Polygon2DCollection`](msg/Polygon2DCollection.msg) - A list of complex polygons, with a header and an optional parallel list of colors. + +## Twists + * [`Twist2D`](msg/Twist2D.msg) - Like `geometry_msgs::Twist` but only `(x, y, theta)` (and not separated into linear and angular) + * [`Twist2DStamped`](msg/Twist2DStamped.msg) - above with a header + * [`Twist2D32`](msg/Twist2D32.msg) - `(x, y, theta)` with only 32bit floating point precision. + +## NavGrids + * [`NavGridInfo`](msg/NavGridInfo.msg) - Same data as `nav_grid::NavGridInfo`. Similar to `nav_msgs::MapMetadata` + * [`NavGridOfChars`](msg/NavGridOfChars.msg) - Data for `nav_grid::NavGrid`. Similar to `nav_msgs::OccupancyGrid` + * [`NavGridOfDoubles`](msg/NavGridOfDoubles.msg) - Data for `nav_grid::NavGrid` + * [`NavGridOfCharsUpdate`](msg/NavGridOfCharsUpdate.msg) and [`NavGridOfDoublesUpdate`](msg/NavGridOfDoublesUpdate.msg) - Similar to `map_msgs::OccupancyGridUpdate` + * [`UIntBounds`](msg/UIntBounds.msg) - Same data as `nav_core2::UIntBounds`. Used in both `Update` messages. + +## Service + * [`SwitchPlugin`](srv/SwitchPlugin.srv) - A simple service equivalent to [SetString.srv](https://discourse.ros.org/t/suggestions-for-std-srvs/1079) use by the PluginMux. \ No newline at end of file diff --git a/navigations/nav_2d_msgs/msg/ComplexPolygon2D.msg b/navigations/nav_2d_msgs/msg/ComplexPolygon2D.msg new file mode 100755 index 0000000..dd7641c --- /dev/null +++ b/navigations/nav_2d_msgs/msg/ComplexPolygon2D.msg @@ -0,0 +1,3 @@ +# Representation for a non-simple polygon, i.e. one with holes +Polygon2D outer # The outer perimeter +Polygon2D[] inner # The perimeter of any inner holes diff --git a/navigations/nav_2d_msgs/msg/NavGridInfo.msg b/navigations/nav_2d_msgs/msg/NavGridInfo.msg new file mode 100755 index 0000000..66dc167 --- /dev/null +++ b/navigations/nav_2d_msgs/msg/NavGridInfo.msg @@ -0,0 +1,6 @@ +uint32 width +uint32 height +float64 resolution +string frame_id +float64 origin_x +float64 origin_y diff --git a/navigations/nav_2d_msgs/msg/NavGridOfChars.msg b/navigations/nav_2d_msgs/msg/NavGridOfChars.msg new file mode 100755 index 0000000..08060e9 --- /dev/null +++ b/navigations/nav_2d_msgs/msg/NavGridOfChars.msg @@ -0,0 +1,5 @@ +time stamp +NavGridInfo info +# The map data, in row-major order, starting with (0,0). +# Unlike nav_msgs/OccupancyGrid, the values are [0, 256), not [-1, 100] +uint8[] data diff --git a/navigations/nav_2d_msgs/msg/NavGridOfCharsUpdate.msg b/navigations/nav_2d_msgs/msg/NavGridOfCharsUpdate.msg new file mode 100755 index 0000000..f190444 --- /dev/null +++ b/navigations/nav_2d_msgs/msg/NavGridOfCharsUpdate.msg @@ -0,0 +1,3 @@ +time stamp +UIntBounds bounds +uint8[] data diff --git a/navigations/nav_2d_msgs/msg/NavGridOfDoubles.msg b/navigations/nav_2d_msgs/msg/NavGridOfDoubles.msg new file mode 100755 index 0000000..d52c737 --- /dev/null +++ b/navigations/nav_2d_msgs/msg/NavGridOfDoubles.msg @@ -0,0 +1,4 @@ +time stamp +NavGridInfo info +# The map data, in row-major order, starting with (0,0). +float64[] data diff --git a/navigations/nav_2d_msgs/msg/NavGridOfDoublesUpdate.msg b/navigations/nav_2d_msgs/msg/NavGridOfDoublesUpdate.msg new file mode 100755 index 0000000..ab1742d --- /dev/null +++ b/navigations/nav_2d_msgs/msg/NavGridOfDoublesUpdate.msg @@ -0,0 +1,3 @@ +time stamp +UIntBounds bounds +float64[] data diff --git a/navigations/nav_2d_msgs/msg/Path2D.msg b/navigations/nav_2d_msgs/msg/Path2D.msg new file mode 100755 index 0000000..a4dad9e --- /dev/null +++ b/navigations/nav_2d_msgs/msg/Path2D.msg @@ -0,0 +1,2 @@ +Header header +geometry_msgs/Pose2D[] poses diff --git a/navigations/nav_2d_msgs/msg/Point2D.msg b/navigations/nav_2d_msgs/msg/Point2D.msg new file mode 100755 index 0000000..cbcc0fa --- /dev/null +++ b/navigations/nav_2d_msgs/msg/Point2D.msg @@ -0,0 +1,2 @@ +float64 x +float64 y diff --git a/navigations/nav_2d_msgs/msg/Polygon2D.msg b/navigations/nav_2d_msgs/msg/Polygon2D.msg new file mode 100755 index 0000000..b5127a0 --- /dev/null +++ b/navigations/nav_2d_msgs/msg/Polygon2D.msg @@ -0,0 +1 @@ +Point2D[] points diff --git a/navigations/nav_2d_msgs/msg/Polygon2DCollection.msg b/navigations/nav_2d_msgs/msg/Polygon2DCollection.msg new file mode 100755 index 0000000..caa5f5c --- /dev/null +++ b/navigations/nav_2d_msgs/msg/Polygon2DCollection.msg @@ -0,0 +1,5 @@ +# Primarily used for visualization +# Colors are optional +std_msgs/Header header +ComplexPolygon2D[] polygons +std_msgs/ColorRGBA[] colors diff --git a/navigations/nav_2d_msgs/msg/Polygon2DStamped.msg b/navigations/nav_2d_msgs/msg/Polygon2DStamped.msg new file mode 100755 index 0000000..f0bf41f --- /dev/null +++ b/navigations/nav_2d_msgs/msg/Polygon2DStamped.msg @@ -0,0 +1,2 @@ +std_msgs/Header header +Polygon2D polygon diff --git a/navigations/nav_2d_msgs/msg/Pose2D32.msg b/navigations/nav_2d_msgs/msg/Pose2D32.msg new file mode 100755 index 0000000..cf0e9b9 --- /dev/null +++ b/navigations/nav_2d_msgs/msg/Pose2D32.msg @@ -0,0 +1,3 @@ +float32 x +float32 y +float32 theta diff --git a/navigations/nav_2d_msgs/msg/Pose2DStamped.msg b/navigations/nav_2d_msgs/msg/Pose2DStamped.msg new file mode 100755 index 0000000..c485040 --- /dev/null +++ b/navigations/nav_2d_msgs/msg/Pose2DStamped.msg @@ -0,0 +1,2 @@ +Header header +geometry_msgs/Pose2D pose diff --git a/navigations/nav_2d_msgs/msg/Twist2D.msg b/navigations/nav_2d_msgs/msg/Twist2D.msg new file mode 100755 index 0000000..3acb858 --- /dev/null +++ b/navigations/nav_2d_msgs/msg/Twist2D.msg @@ -0,0 +1,3 @@ +float64 x +float64 y +float64 theta diff --git a/navigations/nav_2d_msgs/msg/Twist2D32.msg b/navigations/nav_2d_msgs/msg/Twist2D32.msg new file mode 100755 index 0000000..cf0e9b9 --- /dev/null +++ b/navigations/nav_2d_msgs/msg/Twist2D32.msg @@ -0,0 +1,3 @@ +float32 x +float32 y +float32 theta diff --git a/navigations/nav_2d_msgs/msg/Twist2DStamped.msg b/navigations/nav_2d_msgs/msg/Twist2DStamped.msg new file mode 100755 index 0000000..8eaea96 --- /dev/null +++ b/navigations/nav_2d_msgs/msg/Twist2DStamped.msg @@ -0,0 +1,2 @@ +std_msgs/Header header +Twist2D velocity diff --git a/navigations/nav_2d_msgs/msg/UIntBounds.msg b/navigations/nav_2d_msgs/msg/UIntBounds.msg new file mode 100755 index 0000000..a454824 --- /dev/null +++ b/navigations/nav_2d_msgs/msg/UIntBounds.msg @@ -0,0 +1,5 @@ +# Bounds are inclusive +uint32 min_x +uint32 min_y +uint32 max_x +uint32 max_y diff --git a/navigations/nav_2d_msgs/package.xml b/navigations/nav_2d_msgs/package.xml new file mode 100755 index 0000000..9e343cc --- /dev/null +++ b/navigations/nav_2d_msgs/package.xml @@ -0,0 +1,16 @@ + + + nav_2d_msgs + 0.3.0 + Basic message types for two dimensional navigation, extending from geometry_msgs::Pose2D. + David V. Lu!! + BSD + + catkin + geometry_msgs + std_msgs + message_generation + message_runtime + message_runtime + + diff --git a/navigations/nav_2d_msgs/srv/SwitchPlugin.srv b/navigations/nav_2d_msgs/srv/SwitchPlugin.srv new file mode 100755 index 0000000..ee12674 --- /dev/null +++ b/navigations/nav_2d_msgs/srv/SwitchPlugin.srv @@ -0,0 +1,4 @@ +string new_plugin +--- +bool success +string message diff --git a/navigations/nav_2d_utils/CMakeLists.txt b/navigations/nav_2d_utils/CMakeLists.txt new file mode 100755 index 0000000..c68ef84 --- /dev/null +++ b/navigations/nav_2d_utils/CMakeLists.txt @@ -0,0 +1,92 @@ +cmake_minimum_required(VERSION 3.0.2) +project(nav_2d_utils) + +set_directory_properties(PROPERTIES COMPILE_OPTIONS "-std=c++11;-Wall;-Werror") + +find_package(catkin REQUIRED + COMPONENTS + geometry_msgs + nav_2d_msgs + nav_core2 + nav_grid + nav_msgs + pluginlib + roscpp + std_msgs + tf + tf2_ros + tf2_geometry_msgs + xmlrpcpp +) +catkin_python_setup() + +catkin_package( + CATKIN_DEPENDS + geometry_msgs + nav_2d_msgs + nav_core2 + nav_grid + nav_msgs + pluginlib + roscpp + std_msgs + tf + tf2_ros + tf2_geometry_msgs + xmlrpcpp + INCLUDE_DIRS include + LIBRARIES bounds conversions path_ops polygons tf_help +) + +include_directories( + include ${catkin_INCLUDE_DIRS} +) + +add_library(conversions src/conversions.cpp) +target_link_libraries(conversions ${catkin_LIBRARIES}) +add_dependencies(conversions ${catkin_EXPORTED_TARGETS}) + +add_library(path_ops src/path_ops.cpp) +target_link_libraries(path_ops ${catkin_LIBRARIES}) +add_dependencies(path_ops ${catkin_EXPORTED_TARGETS}) + +add_library(polygons src/polygons.cpp src/footprint.cpp) +target_link_libraries(polygons ${catkin_LIBRARIES}) + +add_library(bounds src/bounds.cpp) +target_link_libraries(bounds ${catkin_LIBRARIES}) + +add_library(tf_help src/tf_help.cpp) +target_link_libraries(tf_help ${catkin_LIBRARIES}) + +if(CATKIN_ENABLE_TESTING) + find_package(rostest REQUIRED) + find_package(roslint REQUIRED) + roslint_cpp() + roslint_add_test() + roslint_python() + + catkin_add_gtest(polygon_tests test/polygon_tests.cpp) + target_link_libraries(polygon_tests polygons ${catkin_LIBRARIES}) + + catkin_add_gtest(compress_test test/compress_test.cpp) + target_link_libraries(compress_test path_ops ${catkin_LIBRARIES}) + + catkin_add_gtest(resolution_test test/resolution_test.cpp) + target_link_libraries(resolution_test path_ops ${catkin_LIBRARIES}) + + catkin_add_gtest(bounds_utils_test test/bounds_test.cpp) + target_link_libraries(bounds_utils_test bounds ${catkin_LIBRARIES}) + + add_rostest_gtest(param_tests test/param_tests.launch test/param_tests.cpp) + target_link_libraries(param_tests polygons ${catkin_LIBRARIES} ${GTEST_LIBRARIES}) +endif() + +install(TARGETS bounds conversions path_ops polygons tf_help + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} +) +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} +) diff --git a/navigations/nav_2d_utils/README.md b/navigations/nav_2d_utils/README.md new file mode 100755 index 0000000..c71f8a7 --- /dev/null +++ b/navigations/nav_2d_utils/README.md @@ -0,0 +1,10 @@ +# nav_2d_utils +A handful of useful utility functions for nav_core2 packages. + * Bounds - Utilities for `nav_core2::Bounds` objects interacting with other messages/types and for dividing a `UIntBounds` into multiple smaller bounds. + * [Conversions](doc/Conversions.md) - Tools for converting between `nav_2d_msgs` and other types. + * OdomSubscriber - subscribes to the standard `nav_msgs::Odometry` message and provides access to the velocity component as a `nav_2d_msgs::Twist` + * Parameters - a couple ROS parameter patterns + * PathOps - functions for working with `nav_2d_msgs::Path2D` objects (beyond strict conversion) + * [Plugin Mux](doc/PluginMux.md) - tool for switching between multiple `pluginlib` plugins + * [Polygons and Footprints](doc/PolygonsAndFootprints.md) - functions for working with `Polygon2D` objects + * TF Help - Tools for transforming `nav_2d_msgs` and other common operations. diff --git a/navigations/nav_2d_utils/doc/Conversions.md b/navigations/nav_2d_utils/doc/Conversions.md new file mode 100755 index 0000000..d8b0060 --- /dev/null +++ b/navigations/nav_2d_utils/doc/Conversions.md @@ -0,0 +1,54 @@ +# nav_2d_utils Conversions + +(note: exact syntax differs from below for conciseness, leaving out `const` and `&`) + +## Twist Transformations +| to `nav_2d_msgs` | from `nav_2d_msgs` | +| -- | -- | +| `Twist2D twist3Dto2D(geometry_msgs::Twist)` | `geometry_msgs::Twist twist2Dto3D(Twist2D cmd_vel_2d)` + +## Point Transformations +| to `nav_2d_msgs` | from `nav_2d_msgs` | +| -- | -- | +| `Point2D pointToPoint2D(geometry_msgs::Point)` | `geometry_msgs::Point pointToPoint3D(Point2D)` +| `Point2D pointToPoint2D(geometry_msgs::Point32)` | `geometry_msgs::Point32 pointToPoint32(Point2D)` + +## Pose Transformations +| to `nav_2d_msgs` | from `nav_2d_msgs` | +| -- | -- | +| `Pose2DStamped poseStampedToPose2D(geometry_msgs::PoseStamped)` | `geometry_msgs::PoseStamped pose2DToPoseStamped(Pose2DStamped)` +||`geometry_msgs::PoseStamped pose2DToPoseStamped(geometry_msgs::Pose2D, std::string, ros::Time)`| +||`geometry_msgs::Pose pose2DToPose(geometry_msgs::Pose2D)`| +| `Pose2DStamped stampedPoseToPose2D(tf::Stamped)` | | + +## Path Transformations +| to `nav_2d_msgs` | from `nav_2d_msgs` | +| -- | -- | +| `Path2D pathToPath(nav_msgs::Path)` |`nav_msgs::Path pathToPath(Path2D)` +| `Path2D posesToPath2D(std::vector)` | `nav_msgs::Path poses2DToPath(std::vector, std::string, ros::Time)` + +Also, `nav_msgs::Path posesToPath(std::vector)` + +## Polygon Transformations +| to `nav_2d_msgs` | from `nav_2d_msgs` | +| -- | -- | +| `Polygon2D polygon3Dto2D(geometry_msgs::Polygon)` |`geometry_msgs::Polygon polygon2Dto3D(Polygon2D)` +| `Polygon2DStamped polygon3Dto2D(geometry_msgs::PolygonStamped)` | `geometry_msgs::PolygonStamped polygon2Dto3D(Polygon2DStamped)` + +## Info Transformations +| to `nav_2d_msgs` | from `nav_2d_msgs` | +| -- | -- | +|`nav_2d_msgs::NavGridInfo toMsg(nav_grid::NavGridInfo)`|`nav_grid::NavGridInfo fromMsg(nav_2d_msgs::NavGridInfo)`| + +| to `nav_grid` info | from `nav_grid` info | +| -- | -- | +|`nav_grid::NavGridInfo infoToInfo(nav_msgs::MapMetaData, std::string)` | `nav_msgs::MapMetaData infoToInfo(nav_grid::NavGridInfo)` + +| to two dimensional pose | to three dimensional pose | +| -- | -- | +| `Pose2D getOrigin2D(nav_grid::NavGridInfo)` | `geometry_msgs::Pose getOrigin3D(nav_grid::NavGridInfo)`| + +## Bounds Transformations +| to `nav_2d_msgs` | from `nav_2d_msgs` | +| -- | -- | +|`nav_2d_msgs::UIntBounds toMsg(nav_core2::UIntBounds)`|`nav_core2::UIntBounds fromMsg(nav_2d_msgs::UIntBounds)`| diff --git a/navigations/nav_2d_utils/doc/PluginMux.md b/navigations/nav_2d_utils/doc/PluginMux.md new file mode 100755 index 0000000..6872fbe --- /dev/null +++ b/navigations/nav_2d_utils/doc/PluginMux.md @@ -0,0 +1,39 @@ + +# Plugin Mux +`PluginMux` is an organizer for switching between multiple different plugins of the same type. It may be easiest to see how it operates through an example. Let's say we have multiple global planners we would like to use at different times, with only one being active at a given time. + +This means we have multiple `pluginlib` plugins to load that extend the `BaseGlobalPlanner` interface from the `nav_core` package. We define multiple namespaces in the `global_planner_namespaces` and load each of them. Here's an example parameter config. + +``` +global_planner_namespaces: + - boring_nav_fn + - wacky_global_planner +boring_nav_fn: + allow_unknown: true + plugin_class: navfn/NavfnROS +wacky_global_planner: + allow_unknown: false + # default value commented out + # plugin_class: global_planner/GlobalPlanner +``` + +The namespaces are arbitrary strings, and need not reflect the name of the planner. The package and class name for the plugin will be specified by the `plugin_class` parameter. By default, the first namespace will be loaded as the current plugin. + +To advertise which plugin is active, we publish the namespace on a latched topic and set a parameter with the same name (`~/current_global_planner`). We can then switch among them with a `SetString` ROS service call, or the `usePlugin` C++ method. + +This configuration is all created by creating a plugin mux with the following parameters (parameter names shown for convenience): +``` +PluginMux(plugin_package = "nav_core", + plugin_class = "BaseGlobalPlanner", + parameter_name = "global_planner_namespaces", + default_value = "global_planner/GlobalPlanner", + ros_name = "current_global_planner", + switch_service_name = "switch_global_planner"); +``` + +If the parameter is not set or is an empty list, a namespace will be derived from the `default_value` and be loaded as the only plugin available. +``` +global_planner_namespaces: [] +GlobalPlanner: + allow_unknown: true +``` diff --git a/navigations/nav_2d_utils/doc/PolygonsAndFootprints.md b/navigations/nav_2d_utils/doc/PolygonsAndFootprints.md new file mode 100755 index 0000000..a8a4ac5 --- /dev/null +++ b/navigations/nav_2d_utils/doc/PolygonsAndFootprints.md @@ -0,0 +1,52 @@ +# nav_2d_utils Polygons and Footprints +This library represents a replacement for [costmap_2d/footprint.h](https://github.com/ros-planning/navigation/blob/a2837b5a9dc6dd4b4da176fca7d899d6a3722bf8/costmap_2d/include/costmap_2d/footprint.h) and deals with manipulating polygons. Note that implicitly all polygons here are assumed to be [simple polygons](https://en.wikipedia.org/wiki/Simple_polygon) without "holes." + +## Polygons and the Parameter Server +There have historically been three primary ways to specify a polygon/footprint on the parameter server. The first is to simply specify a radius which is converted to a hexadecagon, i.e. polygon with sixteen sides. This can be read with +``` +nav_2d_msgs::Polygon2D polygonFromRadius(const double radius, const unsigned int num_points = 16); +``` + +The second two ways involve specifying the points of the polygon individually. This can be done with either a string representing a bracketed array of arrays of doubles, `"[[1.0, 2.2], [3.3, 4.2], ...]"`. This can be read with + +``` +nav_2d_msgs::Polygon2D polygonFromString(const std::string& polygon_string); +``` + +Alternatively, with ROS, you can read the points directly from the parameter server in the form of an `XmlRpcValue`, which should be an array of arrays of doubles, which is read with + +``` +nav_2d_msgs::Polygon2D polygonFromXMLRPC(XmlRpc::XmlRpcValue& polygon_xmlrpc); +``` + +If the `XmlRpcValue` is a string, it will call the `polygonFromString` method. + +The above are the traditional methods that were supported by the original `costmap_2d` code. However, we add a fourth method that requires two parallel arrays of x and y coordinates. + +``` +nav_2d_msgs::Polygon2D polygonFromParallelArrays(const std::vector& xs, const std::vector& ys); +``` + +All of the above methods (except the radius one) can be loaded as appropriate from the parameter server with +``` +nav_2d_msgs::Polygon2D polygonFromParams(const ros::NodeHandle& nh, const std::string parameter_name, + bool search = true); +``` +to include the radius, use the logic in `footprint.h` which either uses "footprint" or "robot_radius" +``` +nav_2d_msgs::Polygon2D footprintFromParams(ros::NodeHandle& nh, bool write = true); +``` + +Polygons can be written to parameters with +``` +void polygontoParams(const nav_2d_msgs::Polygon2D& polygon, const ros::NodeHandle& nh, const std::string parameter_name, + bool array_of_arrays = true); +``` + +## Polygon Operations +There are also a handful of methods for examining/manipulating polygons + * `equals` - check if two polygons are equal + * `movePolygonToPose` - translate and rotate a polygon + * `isInside` - check if a point is inside a polygon + * `calculateMinAndMaxDistances` - Calculate the minimum and maximum distance from the origin of a polygon + * `triangulate` - Decompose a polygon into a set of non-overlapping triangles using an open source implementation of the [earcut algorithm](https://github.com/mapbox/earcut.hpp) diff --git a/navigations/nav_2d_utils/include/mapbox/LICENSE b/navigations/nav_2d_utils/include/mapbox/LICENSE new file mode 100755 index 0000000..8bafb57 --- /dev/null +++ b/navigations/nav_2d_utils/include/mapbox/LICENSE @@ -0,0 +1,15 @@ +ISC License + +Copyright (c) 2015, Mapbox + +Permission to use, copy, modify, and/or distribute this software for any purpose +with or without fee is hereby granted, provided that the above copyright notice +and this permission notice appear in all copies. + +THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES WITH +REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF MERCHANTABILITY AND +FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY SPECIAL, DIRECT, +INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES WHATSOEVER RESULTING FROM LOSS +OF USE, DATA OR PROFITS, WHETHER IN AN ACTION OF CONTRACT, NEGLIGENCE OR OTHER +TORTIOUS ACTION, ARISING OUT OF OR IN CONNECTION WITH THE USE OR PERFORMANCE OF +THIS SOFTWARE. diff --git a/navigations/nav_2d_utils/include/mapbox/NOTES b/navigations/nav_2d_utils/include/mapbox/NOTES new file mode 100755 index 0000000..5c1e99a --- /dev/null +++ b/navigations/nav_2d_utils/include/mapbox/NOTES @@ -0,0 +1,2 @@ +A C++ port of earcut.js, a fast, header-only polygon triangulation library. +https://github.com/mapbox/earcut.hpp diff --git a/navigations/nav_2d_utils/include/mapbox/earcut.hpp b/navigations/nav_2d_utils/include/mapbox/earcut.hpp new file mode 100755 index 0000000..68319c1 --- /dev/null +++ b/navigations/nav_2d_utils/include/mapbox/earcut.hpp @@ -0,0 +1,776 @@ +#pragma once + +#include +#include +#include +#include +#include + +namespace mapbox { + +namespace util { + +template struct nth { + inline static typename std::tuple_element::type + get(const T& t) { return std::get(t); }; +}; + +} + +namespace detail { + +template +class Earcut { +public: + std::vector indices; + std::size_t vertices = 0; + + template + void operator()(const Polygon& points); + +private: + struct Node { + Node(N index, double x_, double y_) : i(index), x(x_), y(y_) {} + Node(const Node&) = delete; + Node& operator=(const Node&) = delete; + Node(Node&&) = delete; + Node& operator=(Node&&) = delete; + + const N i; + const double x; + const double y; + + // previous and next vertice nodes in a polygon ring + Node* prev = nullptr; + Node* next = nullptr; + + // z-order curve value + int32_t z = 0; + + // previous and next nodes in z-order + Node* prevZ = nullptr; + Node* nextZ = nullptr; + + // indicates whether this is a steiner point + bool steiner = false; + }; + + template Node* linkedList(const Ring& points, const bool clockwise); + Node* filterPoints(Node* start, Node* end = nullptr); + void earcutLinked(Node* ear, int pass = 0); + bool isEar(Node* ear); + bool isEarHashed(Node* ear); + Node* cureLocalIntersections(Node* start); + void splitEarcut(Node* start); + template Node* eliminateHoles(const Polygon& points, Node* outerNode); + void eliminateHole(Node* hole, Node* outerNode); + Node* findHoleBridge(Node* hole, Node* outerNode); + void indexCurve(Node* start); + Node* sortLinked(Node* list); + int32_t zOrder(const double x_, const double y_); + Node* getLeftmost(Node* start); + bool pointInTriangle(double ax, double ay, double bx, double by, double cx, double cy, double px, double py) const; + bool isValidDiagonal(Node* a, Node* b); + double area(const Node* p, const Node* q, const Node* r) const; + bool equals(const Node* p1, const Node* p2); + bool intersects(const Node* p1, const Node* q1, const Node* p2, const Node* q2); + bool intersectsPolygon(const Node* a, const Node* b); + bool locallyInside(const Node* a, const Node* b); + bool middleInside(const Node* a, const Node* b); + Node* splitPolygon(Node* a, Node* b); + template Node* insertNode(std::size_t i, const Point& p, Node* last); + void removeNode(Node* p); + + bool hashing; + double minX, maxX; + double minY, maxY; + double inv_size = 0; + + template > + class ObjectPool { + public: + ObjectPool() { } + ObjectPool(std::size_t blockSize_) { + reset(blockSize_); + } + ~ObjectPool() { + clear(); + } + template + T* construct(Args&&... args) { + if (currentIndex >= blockSize) { + currentBlock = alloc_traits::allocate(alloc, blockSize); + allocations.emplace_back(currentBlock); + currentIndex = 0; + } + T* object = ¤tBlock[currentIndex++]; + alloc_traits::construct(alloc, object, std::forward(args)...); + return object; + } + void reset(std::size_t newBlockSize) { + for (auto allocation : allocations) { + alloc_traits::deallocate(alloc, allocation, blockSize); + } + allocations.clear(); + blockSize = std::max(1, newBlockSize); + currentBlock = nullptr; + currentIndex = blockSize; + } + void clear() { reset(blockSize); } + private: + T* currentBlock = nullptr; + std::size_t currentIndex = 1; + std::size_t blockSize = 1; + std::vector allocations; + Alloc alloc; + typedef typename std::allocator_traits alloc_traits; + }; + ObjectPool nodes; +}; + +template template +void Earcut::operator()(const Polygon& points) { + // reset + indices.clear(); + vertices = 0; + + if (points.empty()) return; + + double x; + double y; + int threshold = 80; + std::size_t len = 0; + + for (size_t i = 0; threshold >= 0 && i < points.size(); i++) { + threshold -= static_cast(points[i].size()); + len += points[i].size(); + } + + //estimate size of nodes and indices + nodes.reset(len * 3 / 2); + indices.reserve(len + points[0].size()); + + Node* outerNode = linkedList(points[0], true); + if (!outerNode || outerNode->prev == outerNode->next) return; + + if (points.size() > 1) outerNode = eliminateHoles(points, outerNode); + + // if the shape is not too simple, we'll use z-order curve hash later; calculate polygon bbox + hashing = threshold < 0; + if (hashing) { + Node* p = outerNode->next; + minX = maxX = outerNode->x; + minY = maxY = outerNode->y; + do { + x = p->x; + y = p->y; + minX = std::min(minX, x); + minY = std::min(minY, y); + maxX = std::max(maxX, x); + maxY = std::max(maxY, y); + p = p->next; + } while (p != outerNode); + + // minX, minY and size are later used to transform coords into integers for z-order calculation + inv_size = std::max(maxX - minX, maxY - minY); + inv_size = inv_size != .0 ? (1. / inv_size) : .0; + } + + earcutLinked(outerNode); + + nodes.clear(); +} + +// create a circular doubly linked list from polygon points in the specified winding order +template template +typename Earcut::Node* +Earcut::linkedList(const Ring& points, const bool clockwise) { + using Point = typename Ring::value_type; + double sum = 0; + const std::size_t len = points.size(); + std::size_t i, j; + Node* last = nullptr; + + // calculate original winding order of a polygon ring + for (i = 0, j = len > 0 ? len - 1 : 0; i < len; j = i++) { + const auto& p1 = points[i]; + const auto& p2 = points[j]; + const double p20 = util::nth<0, Point>::get(p2); + const double p10 = util::nth<0, Point>::get(p1); + const double p11 = util::nth<1, Point>::get(p1); + const double p21 = util::nth<1, Point>::get(p2); + sum += (p20 - p10) * (p11 + p21); + } + + // link points into circular doubly-linked list in the specified winding order + if (clockwise == (sum > 0)) { + for (i = 0; i < len; i++) last = insertNode(vertices + i, points[i], last); + } else { + for (i = len; i-- > 0;) last = insertNode(vertices + i, points[i], last); + } + + if (last && equals(last, last->next)) { + removeNode(last); + last = last->next; + } + + vertices += len; + + return last; +} + +// eliminate colinear or duplicate points +template +typename Earcut::Node* +Earcut::filterPoints(Node* start, Node* end) { + if (!end) end = start; + + Node* p = start; + bool again; + do { + again = false; + + if (!p->steiner && (equals(p, p->next) || area(p->prev, p, p->next) == 0)) { + removeNode(p); + p = end = p->prev; + + if (p == p->next) break; + again = true; + + } else { + p = p->next; + } + } while (again || p != end); + + return end; +} + +// main ear slicing loop which triangulates a polygon (given as a linked list) +template +void Earcut::earcutLinked(Node* ear, int pass) { + if (!ear) return; + + // interlink polygon nodes in z-order + if (!pass && hashing) indexCurve(ear); + + Node* stop = ear; + Node* prev; + Node* next; + + int iterations = 0; + + // iterate through ears, slicing them one by one + while (ear->prev != ear->next) { + iterations++; + prev = ear->prev; + next = ear->next; + + if (hashing ? isEarHashed(ear) : isEar(ear)) { + // cut off the triangle + indices.emplace_back(prev->i); + indices.emplace_back(ear->i); + indices.emplace_back(next->i); + + removeNode(ear); + + // skipping the next vertice leads to less sliver triangles + ear = next->next; + stop = next->next; + + continue; + } + + ear = next; + + // if we looped through the whole remaining polygon and can't find any more ears + if (ear == stop) { + // try filtering points and slicing again + if (!pass) earcutLinked(filterPoints(ear), 1); + + // if this didn't work, try curing all small self-intersections locally + else if (pass == 1) { + ear = cureLocalIntersections(ear); + earcutLinked(ear, 2); + + // as a last resort, try splitting the remaining polygon into two + } else if (pass == 2) splitEarcut(ear); + + break; + } + } +} + +// check whether a polygon node forms a valid ear with adjacent nodes +template +bool Earcut::isEar(Node* ear) { + const Node* a = ear->prev; + const Node* b = ear; + const Node* c = ear->next; + + if (area(a, b, c) >= 0) return false; // reflex, can't be an ear + + // now make sure we don't have other points inside the potential ear + Node* p = ear->next->next; + + while (p != ear->prev) { + if (pointInTriangle(a->x, a->y, b->x, b->y, c->x, c->y, p->x, p->y) && + area(p->prev, p, p->next) >= 0) return false; + p = p->next; + } + + return true; +} + +template +bool Earcut::isEarHashed(Node* ear) { + const Node* a = ear->prev; + const Node* b = ear; + const Node* c = ear->next; + + if (area(a, b, c) >= 0) return false; // reflex, can't be an ear + + // triangle bbox; min & max are calculated like this for speed + const double minTX = std::min(a->x, std::min(b->x, c->x)); + const double minTY = std::min(a->y, std::min(b->y, c->y)); + const double maxTX = std::max(a->x, std::max(b->x, c->x)); + const double maxTY = std::max(a->y, std::max(b->y, c->y)); + + // z-order range for the current triangle bbox; + const int32_t minZ = zOrder(minTX, minTY); + const int32_t maxZ = zOrder(maxTX, maxTY); + + // first look for points inside the triangle in increasing z-order + Node* p = ear->nextZ; + + while (p && p->z <= maxZ) { + if (p != ear->prev && p != ear->next && + pointInTriangle(a->x, a->y, b->x, b->y, c->x, c->y, p->x, p->y) && + area(p->prev, p, p->next) >= 0) return false; + p = p->nextZ; + } + + // then look for points in decreasing z-order + p = ear->prevZ; + + while (p && p->z >= minZ) { + if (p != ear->prev && p != ear->next && + pointInTriangle(a->x, a->y, b->x, b->y, c->x, c->y, p->x, p->y) && + area(p->prev, p, p->next) >= 0) return false; + p = p->prevZ; + } + + return true; +} + +// go through all polygon nodes and cure small local self-intersections +template +typename Earcut::Node* +Earcut::cureLocalIntersections(Node* start) { + Node* p = start; + do { + Node* a = p->prev; + Node* b = p->next->next; + + // a self-intersection where edge (v[i-1],v[i]) intersects (v[i+1],v[i+2]) + if (!equals(a, b) && intersects(a, p, p->next, b) && locallyInside(a, b) && locallyInside(b, a)) { + indices.emplace_back(a->i); + indices.emplace_back(p->i); + indices.emplace_back(b->i); + + // remove two nodes involved + removeNode(p); + removeNode(p->next); + + p = start = b; + } + p = p->next; + } while (p != start); + + return p; +} + +// try splitting polygon into two and triangulate them independently +template +void Earcut::splitEarcut(Node* start) { + // look for a valid diagonal that divides the polygon into two + Node* a = start; + do { + Node* b = a->next->next; + while (b != a->prev) { + if (a->i != b->i && isValidDiagonal(a, b)) { + // split the polygon in two by the diagonal + Node* c = splitPolygon(a, b); + + // filter colinear points around the cuts + a = filterPoints(a, a->next); + c = filterPoints(c, c->next); + + // run earcut on each half + earcutLinked(a); + earcutLinked(c); + return; + } + b = b->next; + } + a = a->next; + } while (a != start); +} + +// link every hole into the outer loop, producing a single-ring polygon without holes +template template +typename Earcut::Node* +Earcut::eliminateHoles(const Polygon& points, Node* outerNode) { + const size_t len = points.size(); + + std::vector queue; + for (size_t i = 1; i < len; i++) { + Node* list = linkedList(points[i], false); + if (list) { + if (list == list->next) list->steiner = true; + queue.push_back(getLeftmost(list)); + } + } + std::sort(queue.begin(), queue.end(), [](const Node* a, const Node* b) { + return a->x < b->x; + }); + + // process holes from left to right + for (size_t i = 0; i < queue.size(); i++) { + eliminateHole(queue[i], outerNode); + outerNode = filterPoints(outerNode, outerNode->next); + } + + return outerNode; +} + +// find a bridge between vertices that connects hole with an outer ring and and link it +template +void Earcut::eliminateHole(Node* hole, Node* outerNode) { + outerNode = findHoleBridge(hole, outerNode); + if (outerNode) { + Node* b = splitPolygon(outerNode, hole); + filterPoints(b, b->next); + } +} + +// David Eberly's algorithm for finding a bridge between hole and outer polygon +template +typename Earcut::Node* +Earcut::findHoleBridge(Node* hole, Node* outerNode) { + Node* p = outerNode; + double hx = hole->x; + double hy = hole->y; + double qx = -std::numeric_limits::infinity(); + Node* m = nullptr; + + // find a segment intersected by a ray from the hole's leftmost Vertex to the left; + // segment's endpoint with lesser x will be potential connection Vertex + do { + if (hy <= p->y && hy >= p->next->y && p->next->y != p->y) { + double x = p->x + (hy - p->y) * (p->next->x - p->x) / (p->next->y - p->y); + if (x <= hx && x > qx) { + qx = x; + if (x == hx) { + if (hy == p->y) return p; + if (hy == p->next->y) return p->next; + } + m = p->x < p->next->x ? p : p->next; + } + } + p = p->next; + } while (p != outerNode); + + if (!m) return 0; + + if (hx == qx) return m->prev; + + // look for points inside the triangle of hole Vertex, segment intersection and endpoint; + // if there are no points found, we have a valid connection; + // otherwise choose the Vertex of the minimum angle with the ray as connection Vertex + + const Node* stop = m; + double tanMin = std::numeric_limits::infinity(); + double tanCur = 0; + + p = m->next; + double mx = m->x; + double my = m->y; + + while (p != stop) { + if (hx >= p->x && p->x >= mx && hx != p->x && + pointInTriangle(hy < my ? hx : qx, hy, mx, my, hy < my ? qx : hx, hy, p->x, p->y)) { + + tanCur = std::abs(hy - p->y) / (hx - p->x); // tangential + + if ((tanCur < tanMin || (tanCur == tanMin && p->x > m->x)) && locallyInside(p, hole)) { + m = p; + tanMin = tanCur; + } + } + + p = p->next; + } + + return m; +} + +// interlink polygon nodes in z-order +template +void Earcut::indexCurve(Node* start) { + assert(start); + Node* p = start; + + do { + p->z = p->z ? p->z : zOrder(p->x, p->y); + p->prevZ = p->prev; + p->nextZ = p->next; + p = p->next; + } while (p != start); + + p->prevZ->nextZ = nullptr; + p->prevZ = nullptr; + + sortLinked(p); +} + +// Simon Tatham's linked list merge sort algorithm +// http://www.chiark.greenend.org.uk/~sgtatham/algorithms/listsort.html +template +typename Earcut::Node* +Earcut::sortLinked(Node* list) { + assert(list); + Node* p; + Node* q; + Node* e; + Node* tail; + int i, numMerges, pSize, qSize; + int inSize = 1; + + for (;;) { + p = list; + list = nullptr; + tail = nullptr; + numMerges = 0; + + while (p) { + numMerges++; + q = p; + pSize = 0; + for (i = 0; i < inSize; i++) { + pSize++; + q = q->nextZ; + if (!q) break; + } + + qSize = inSize; + + while (pSize > 0 || (qSize > 0 && q)) { + + if (pSize == 0) { + e = q; + q = q->nextZ; + qSize--; + } else if (qSize == 0 || !q) { + e = p; + p = p->nextZ; + pSize--; + } else if (p->z <= q->z) { + e = p; + p = p->nextZ; + pSize--; + } else { + e = q; + q = q->nextZ; + qSize--; + } + + if (tail) tail->nextZ = e; + else list = e; + + e->prevZ = tail; + tail = e; + } + + p = q; + } + + tail->nextZ = nullptr; + + if (numMerges <= 1) return list; + + inSize *= 2; + } +} + +// z-order of a Vertex given coords and size of the data bounding box +template +int32_t Earcut::zOrder(const double x_, const double y_) { + // coords are transformed into non-negative 15-bit integer range + int32_t x = static_cast(32767.0 * (x_ - minX) * inv_size); + int32_t y = static_cast(32767.0 * (y_ - minY) * inv_size); + + x = (x | (x << 8)) & 0x00FF00FF; + x = (x | (x << 4)) & 0x0F0F0F0F; + x = (x | (x << 2)) & 0x33333333; + x = (x | (x << 1)) & 0x55555555; + + y = (y | (y << 8)) & 0x00FF00FF; + y = (y | (y << 4)) & 0x0F0F0F0F; + y = (y | (y << 2)) & 0x33333333; + y = (y | (y << 1)) & 0x55555555; + + return x | (y << 1); +} + +// find the leftmost node of a polygon ring +template +typename Earcut::Node* +Earcut::getLeftmost(Node* start) { + Node* p = start; + Node* leftmost = start; + do { + if (p->x < leftmost->x || (p->x == leftmost->x && p->y < leftmost->y)) + leftmost = p; + p = p->next; + } while (p != start); + + return leftmost; +} + +// check if a point lies within a convex triangle +template +bool Earcut::pointInTriangle(double ax, double ay, double bx, double by, double cx, double cy, double px, double py) const { + return (cx - px) * (ay - py) - (ax - px) * (cy - py) >= 0 && + (ax - px) * (by - py) - (bx - px) * (ay - py) >= 0 && + (bx - px) * (cy - py) - (cx - px) * (by - py) >= 0; +} + +// check if a diagonal between two polygon nodes is valid (lies in polygon interior) +template +bool Earcut::isValidDiagonal(Node* a, Node* b) { + return a->next->i != b->i && a->prev->i != b->i && !intersectsPolygon(a, b) && + locallyInside(a, b) && locallyInside(b, a) && middleInside(a, b); +} + +// signed area of a triangle +template +double Earcut::area(const Node* p, const Node* q, const Node* r) const { + return (q->y - p->y) * (r->x - q->x) - (q->x - p->x) * (r->y - q->y); +} + +// check if two points are equal +template +bool Earcut::equals(const Node* p1, const Node* p2) { + return p1->x == p2->x && p1->y == p2->y; +} + +// check if two segments intersect +template +bool Earcut::intersects(const Node* p1, const Node* q1, const Node* p2, const Node* q2) { + if ((equals(p1, q1) && equals(p2, q2)) || + (equals(p1, q2) && equals(p2, q1))) return true; + return (area(p1, q1, p2) > 0) != (area(p1, q1, q2) > 0) && + (area(p2, q2, p1) > 0) != (area(p2, q2, q1) > 0); +} + +// check if a polygon diagonal intersects any polygon segments +template +bool Earcut::intersectsPolygon(const Node* a, const Node* b) { + const Node* p = a; + do { + if (p->i != a->i && p->next->i != a->i && p->i != b->i && p->next->i != b->i && + intersects(p, p->next, a, b)) return true; + p = p->next; + } while (p != a); + + return false; +} + +// check if a polygon diagonal is locally inside the polygon +template +bool Earcut::locallyInside(const Node* a, const Node* b) { + return area(a->prev, a, a->next) < 0 ? + area(a, b, a->next) >= 0 && area(a, a->prev, b) >= 0 : + area(a, b, a->prev) < 0 || area(a, a->next, b) < 0; +} + +// check if the middle Vertex of a polygon diagonal is inside the polygon +template +bool Earcut::middleInside(const Node* a, const Node* b) { + const Node* p = a; + bool inside = false; + double px = (a->x + b->x) / 2; + double py = (a->y + b->y) / 2; + do { + if (((p->y > py) != (p->next->y > py)) && p->next->y != p->y && + (px < (p->next->x - p->x) * (py - p->y) / (p->next->y - p->y) + p->x)) + inside = !inside; + p = p->next; + } while (p != a); + + return inside; +} + +// link two polygon vertices with a bridge; if the vertices belong to the same ring, it splits +// polygon into two; if one belongs to the outer ring and another to a hole, it merges it into a +// single ring +template +typename Earcut::Node* +Earcut::splitPolygon(Node* a, Node* b) { + Node* a2 = nodes.construct(a->i, a->x, a->y); + Node* b2 = nodes.construct(b->i, b->x, b->y); + Node* an = a->next; + Node* bp = b->prev; + + a->next = b; + b->prev = a; + + a2->next = an; + an->prev = a2; + + b2->next = a2; + a2->prev = b2; + + bp->next = b2; + b2->prev = bp; + + return b2; +} + +// create a node and util::optionally link it with previous one (in a circular doubly linked list) +template template +typename Earcut::Node* +Earcut::insertNode(std::size_t i, const Point& pt, Node* last) { + Node* p = nodes.construct(static_cast(i), util::nth<0, Point>::get(pt), util::nth<1, Point>::get(pt)); + + if (!last) { + p->prev = p; + p->next = p; + + } else { + assert(last); + p->next = last->next; + p->prev = last; + last->next->prev = p; + last->next = p; + } + return p; +} + +template +void Earcut::removeNode(Node* p) { + p->next->prev = p->prev; + p->prev->next = p->next; + + if (p->prevZ) p->prevZ->nextZ = p->nextZ; + if (p->nextZ) p->nextZ->prevZ = p->prevZ; +} +} + +template +std::vector earcut(const Polygon& poly) { + mapbox::detail::Earcut earcut; + earcut(poly); + return std::move(earcut.indices); +} +} diff --git a/navigations/nav_2d_utils/include/nav_2d_utils/bounds.h b/navigations/nav_2d_utils/include/nav_2d_utils/bounds.h new file mode 100755 index 0000000..6c95c26 --- /dev/null +++ b/navigations/nav_2d_utils/include/nav_2d_utils/bounds.h @@ -0,0 +1,91 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2020, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef NAV_2D_UTILS_BOUNDS_H +#define NAV_2D_UTILS_BOUNDS_H + +#include +#include +#include + +/** + * @brief A set of utility functions for Bounds objects interacting with other messages/types + */ +namespace nav_2d_utils +{ + +/** + * @brief return a floating point bounds that covers the entire NavGrid + * @param info Info for the NavGrid + * @return bounds covering the entire NavGrid + */ +nav_core2::Bounds getFullBounds(const nav_grid::NavGridInfo& info); + +/** + * @brief return an integral bounds that covers the entire NavGrid + * @param info Info for the NavGrid + * @return bounds covering the entire NavGrid + */ +nav_core2::UIntBounds getFullUIntBounds(const nav_grid::NavGridInfo& info); + +/** + * @brief Translate real-valued bounds to uint coordinates based on nav_grid info + * @param info Information used when converting the coordinates + * @param bounds floating point bounds object + * @returns corresponding UIntBounds for parameter + */ +nav_core2::UIntBounds translateBounds(const nav_grid::NavGridInfo& info, const nav_core2::Bounds& bounds); + +/** + * @brief Translate uint bounds to real-valued coordinates based on nav_grid info + * @param info Information used when converting the coordinates + * @param bounds UIntBounds object + * @returns corresponding floating point bounds for parameter + */ +nav_core2::Bounds translateBounds(const nav_grid::NavGridInfo& info, const nav_core2::UIntBounds& bounds); + +/** + * @brief divide the given bounds up into sub-bounds of roughly equal size + * @param original_bounds The original bounds to divide + * @param n_cols Positive number of columns to divide the bounds into + * @param n_rows Positive number of rows to divide the bounds into + * @return vector of a maximum of n_cols*n_rows nonempty bounds + * @throws std::invalid_argument when n_cols or n_rows is zero + */ +std::vector divideBounds(const nav_core2::UIntBounds& original_bounds, + unsigned int n_cols, unsigned int n_rows); + +} // namespace nav_2d_utils + +#endif // NAV_2D_UTILS_BOUNDS_H diff --git a/navigations/nav_2d_utils/include/nav_2d_utils/conversions.h b/navigations/nav_2d_utils/include/nav_2d_utils/conversions.h new file mode 100755 index 0000000..f6bbee4 --- /dev/null +++ b/navigations/nav_2d_utils/include/nav_2d_utils/conversions.h @@ -0,0 +1,107 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef NAV_2D_UTILS_CONVERSIONS_H +#define NAV_2D_UTILS_CONVERSIONS_H + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +namespace nav_2d_utils +{ +// Twist Transformations +geometry_msgs::Twist twist2Dto3D(const nav_2d_msgs::Twist2D& cmd_vel_2d); +nav_2d_msgs::Twist2D twist3Dto2D(const geometry_msgs::Twist& cmd_vel); + +// Point Transformations +nav_2d_msgs::Point2D pointToPoint2D(const geometry_msgs::Point& point); +nav_2d_msgs::Point2D pointToPoint2D(const geometry_msgs::Point32& point); +geometry_msgs::Point pointToPoint3D(const nav_2d_msgs::Point2D& point); +geometry_msgs::Point32 pointToPoint32(const nav_2d_msgs::Point2D& point); + +// Pose Transformations +nav_2d_msgs::Pose2DStamped stampedPoseToPose2D(const tf::Stamped& pose); +nav_2d_msgs::Pose2DStamped poseStampedToPose2D(const geometry_msgs::PoseStamped& pose); +geometry_msgs::Pose pose2DToPose(const geometry_msgs::Pose2D& pose2d); +geometry_msgs::PoseStamped pose2DToPoseStamped(const nav_2d_msgs::Pose2DStamped& pose2d); +geometry_msgs::PoseStamped pose2DToPoseStamped(const geometry_msgs::Pose2D& pose2d, + const std::string& frame, const ros::Time& stamp); + +// Path Transformations +nav_2d_msgs::Path2D pathToPath(const nav_msgs::Path& path); +nav_msgs::Path posesToPath(const std::vector& poses); +nav_2d_msgs::Path2D posesToPath2D(const std::vector& poses); +nav_msgs::Path poses2DToPath(const std::vector& poses, + const std::string& frame, const ros::Time& stamp); +nav_msgs::Path pathToPath(const nav_2d_msgs::Path2D& path2d); + +// Polygon Transformations +geometry_msgs::Polygon polygon2Dto3D(const nav_2d_msgs::Polygon2D& polygon_2d); +nav_2d_msgs::Polygon2D polygon3Dto2D(const geometry_msgs::Polygon& polygon_3d); +geometry_msgs::PolygonStamped polygon2Dto3D(const nav_2d_msgs::Polygon2DStamped& polygon_2d); +nav_2d_msgs::Polygon2DStamped polygon3Dto2D(const geometry_msgs::PolygonStamped& polygon_3d); + +// Info Transformations +nav_2d_msgs::NavGridInfo toMsg(const nav_grid::NavGridInfo& info); +nav_grid::NavGridInfo fromMsg(const nav_2d_msgs::NavGridInfo& msg); +geometry_msgs::Pose getOrigin3D(const nav_grid::NavGridInfo& info); +geometry_msgs::Pose2D getOrigin2D(const nav_grid::NavGridInfo& info); +nav_grid::NavGridInfo infoToInfo(const nav_msgs::MapMetaData& metadata, const std::string& frame); +nav_msgs::MapMetaData infoToInfo(const nav_grid::NavGridInfo & info); + +// Bounds Transformations +nav_2d_msgs::UIntBounds toMsg(const nav_core2::UIntBounds& bounds); +nav_core2::UIntBounds fromMsg(const nav_2d_msgs::UIntBounds& msg); + +} // namespace nav_2d_utils + +#endif // NAV_2D_UTILS_CONVERSIONS_H diff --git a/navigations/nav_2d_utils/include/nav_2d_utils/footprint.h b/navigations/nav_2d_utils/include/nav_2d_utils/footprint.h new file mode 100755 index 0000000..f3de873 --- /dev/null +++ b/navigations/nav_2d_utils/include/nav_2d_utils/footprint.h @@ -0,0 +1,54 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef NAV_2D_UTILS_FOOTPRINT_H +#define NAV_2D_UTILS_FOOTPRINT_H + +#include +#include + +namespace nav_2d_utils +{ + +/** + * @brief Load the robot footprint either as a polygon from the footprint parameter or from robot_radius + * + * Analagous to costmap_2d::makeFootprintFromParams in that it will return an empty polygon if neither parameter + * is present. + */ +nav_2d_msgs::Polygon2D footprintFromParams(ros::NodeHandle& nh, bool write = true); + +} // namespace nav_2d_utils + +#endif // NAV_2D_UTILS_FOOTPRINT_H diff --git a/navigations/nav_2d_utils/include/nav_2d_utils/geometry_help.h b/navigations/nav_2d_utils/include/nav_2d_utils/geometry_help.h new file mode 100755 index 0000000..3afae5a --- /dev/null +++ b/navigations/nav_2d_utils/include/nav_2d_utils/geometry_help.h @@ -0,0 +1,85 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef NAV_2D_UTILS_GEOMETRY_HELP_H +#define NAV_2D_UTILS_GEOMETRY_HELP_H + +#include + +namespace nav_2d_utils +{ +/** + * @brief Distance from point (pX, pY) to closest point on line from (x0, y0) to (x1, y1) + * @param pX + * @param pY + * @param x0 + * @param y0 + * @param x1 + * @param y1 + * @return shortest distance from point to line + */ +inline double distanceToLine(double pX, double pY, double x0, double y0, double x1, double y1) +{ + double A = pX - x0; + double B = pY - y0; + double C = x1 - x0; + double D = y1 - y0; + + double dot = A * C + B * D; + double len_sq = C * C + D * D; + double param = dot / len_sq; + + double xx, yy; + + if (param < 0) + { + xx = x0; + yy = y0; + } + else if (param > 1) + { + xx = x1; + yy = y1; + } + else + { + xx = x0 + param * C; + yy = y0 + param * D; + } + + return hypot(pX - xx, pY - yy); +} +} // namespace nav_2d_utils + +#endif // NAV_2D_UTILS_GEOMETRY_HELP_H diff --git a/navigations/nav_2d_utils/include/nav_2d_utils/odom_subscriber.h b/navigations/nav_2d_utils/include/nav_2d_utils/odom_subscriber.h new file mode 100755 index 0000000..c0974a6 --- /dev/null +++ b/navigations/nav_2d_utils/include/nav_2d_utils/odom_subscriber.h @@ -0,0 +1,87 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef NAV_2D_UTILS_ODOM_SUBSCRIBER_H +#define NAV_2D_UTILS_ODOM_SUBSCRIBER_H + +#include +#include +#include +#include +#include +#include + +namespace nav_2d_utils +{ + +/** + * @class OdomSubscriber + * Wrapper for some common odometry operations. Subscribes to the topic with a mutex. + */ +class OdomSubscriber +{ +public: + /** + * @brief Constructor that subscribes to an Odometry topic + * + * @param nh NodeHandle for creating subscriber + * @param default_topic Name of the topic that will be loaded of the odom_topic param is not set. + */ + explicit OdomSubscriber(ros::NodeHandle& nh, std::string default_topic = "odom") + { + std::string odom_topic; + nh.param("odom_topic", odom_topic, default_topic); + odom_sub_ = nh.subscribe(odom_topic, 1, boost::bind(&OdomSubscriber::odomCallback, this, _1)); + } + + inline nav_2d_msgs::Twist2D getTwist() { return odom_vel_.velocity; } + inline nav_2d_msgs::Twist2DStamped getTwistStamped() { return odom_vel_; } + +protected: + void odomCallback(const nav_msgs::Odometry::ConstPtr& msg) + { + ROS_INFO_ONCE("odom received!"); + boost::mutex::scoped_lock lock(odom_mutex_); + odom_vel_.header = msg->header; + odom_vel_.velocity = twist3Dto2D(msg->twist.twist); + } + + ros::Subscriber odom_sub_; + nav_2d_msgs::Twist2DStamped odom_vel_; + boost::mutex odom_mutex_; +}; + +} // namespace nav_2d_utils + +#endif // NAV_2D_UTILS_ODOM_SUBSCRIBER_H diff --git a/navigations/nav_2d_utils/include/nav_2d_utils/parameters.h b/navigations/nav_2d_utils/include/nav_2d_utils/parameters.h new file mode 100755 index 0000000..7b5871b --- /dev/null +++ b/navigations/nav_2d_utils/include/nav_2d_utils/parameters.h @@ -0,0 +1,150 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef NAV_2D_UTILS_PARAMETERS_H +#define NAV_2D_UTILS_PARAMETERS_H + +#include +#include + +namespace nav_2d_utils +{ + +/** + * @brief Search for a parameter and load it, or use the default value + * + * This templated function shortens a commonly used ROS pattern in which you + * search for a parameter and get its value if it exists, otherwise returning a default value. + * + * @param nh NodeHandle to start the parameter search from + * @param param_name Name of the parameter to search for + * @param default_value Value to return if not found + * @return Value of parameter if found, otherwise the default_value + */ +template +param_t searchAndGetParam(const ros::NodeHandle& nh, const std::string& param_name, const param_t& default_value) +{ + std::string resolved_name; + if (nh.searchParam(param_name, resolved_name)) + { + param_t value = default_value; + nh.param(resolved_name, value, default_value); + return value; + } + return default_value; +} + +/** + * @brief Load a parameter from one of two namespaces. Complain if it uses the old name. + * @param nh NodeHandle to look for the parameter in + * @param current_name Parameter name that is current, i.e. not deprecated + * @param old_name Deprecated parameter name + * @param default_value If neither parameter is present, return this value + * @return The value of the parameter or the default value + */ +template +param_t loadParameterWithDeprecation(const ros::NodeHandle& nh, const std::string current_name, + const std::string old_name, const param_t& default_value) +{ + param_t value; + if (nh.hasParam(current_name)) + { + nh.getParam(current_name, value); + return value; + } + if (nh.hasParam(old_name)) + { + ROS_WARN("Parameter %s is deprecated. Please use the name %s instead.", old_name.c_str(), current_name.c_str()); + nh.getParam(old_name, value); + return value; + } + return default_value; +} + +/** + * @brief If a deprecated parameter exists, complain and move to its new location + * @param nh NodeHandle to look for the parameter in + * @param current_name Parameter name that is current, i.e. not deprecated + * @param old_name Deprecated parameter name + */ +template +void moveDeprecatedParameter(const ros::NodeHandle& nh, const std::string current_name, const std::string old_name) +{ + if (!nh.hasParam(old_name)) return; + + param_t value; + ROS_WARN("Parameter %s is deprecated. Please use the name %s instead.", old_name.c_str(), current_name.c_str()); + nh.getParam(old_name, value); + nh.setParam(current_name, value); +} + +/** + * @brief Move a parameter from one place to another + * + * For use loading old parameter structures into new places. + * + * If the new name already has a value, don't move the old value there. + * + * @param nh NodeHandle for loading/saving params + * @param old_name Parameter name to move/remove + * @param current_name Destination parameter name + * @param default_value Value to save in the new name if old parameter is not found. + * @param should_delete If true, whether to delete the parameter from the old name + */ +template +void moveParameter(const ros::NodeHandle& nh, std::string old_name, + std::string current_name, param_t default_value, bool should_delete = true) +{ + if (nh.hasParam(current_name)) + { + if (should_delete) + nh.deleteParam(old_name); + return; + } + XmlRpc::XmlRpcValue value; + if (nh.hasParam(old_name)) + { + nh.getParam(old_name, value); + if (should_delete) nh.deleteParam(old_name); + } + else + value = default_value; + + nh.setParam(current_name, value); +} + + +} // namespace nav_2d_utils + +#endif // NAV_2D_UTILS_PARAMETERS_H diff --git a/navigations/nav_2d_utils/include/nav_2d_utils/path_ops.h b/navigations/nav_2d_utils/include/nav_2d_utils/path_ops.h new file mode 100755 index 0000000..187b762 --- /dev/null +++ b/navigations/nav_2d_utils/include/nav_2d_utils/path_ops.h @@ -0,0 +1,88 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef NAV_2D_UTILS_PATH_OPS_H +#define NAV_2D_UTILS_PATH_OPS_H + +#include + +namespace nav_2d_utils +{ +/** + * @brief Calculate the linear distance between two poses + */ +double poseDistance(const geometry_msgs::Pose2D& pose0, const geometry_msgs::Pose2D& pose1); + +/** + * @brief Calculate the length of the plan, starting from the given index + */ +double getPlanLength(const nav_2d_msgs::Path2D& plan, const unsigned int start_index = 0); + +/** + * @brief Calculate the length of the plan from the pose on the plan closest to the given pose + */ +double getPlanLength(const nav_2d_msgs::Path2D& plan, const geometry_msgs::Pose2D& query_pose); + +/** + * @brief Increase plan resolution to match that of the costmap by adding points linearly between points + * + * @param global_plan_in input plan + * @param resolution desired distance between waypoints + * @return Higher resolution plan + */ +nav_2d_msgs::Path2D adjustPlanResolution(const nav_2d_msgs::Path2D& global_plan_in, double resolution); + +/** + * @brief Decrease the length of the plan by eliminating colinear points + * + * Uses the Ramer Douglas Peucker algorithm. Ignores theta values + * + * @param input_path Path to compress + * @param epsilon maximum allowable error. Increase for greater compression. + * @return Path2D with possibly fewer poses + */ +nav_2d_msgs::Path2D compressPlan(const nav_2d_msgs::Path2D& input_path, double epsilon = 0.1); + +/** + * @brief Convenience function to add a pose to a path in one line. + * @param path Path to add to + * @param x x-coordinate + * @param y y-coordinate + * @param theta theta (if needed) + */ +void addPose(nav_2d_msgs::Path2D& path, double x, double y, double theta = 0.0); + +} // namespace nav_2d_utils + +#endif // NAV_2D_UTILS_PATH_OPS_H diff --git a/navigations/nav_2d_utils/include/nav_2d_utils/plugin_mux.h b/navigations/nav_2d_utils/include/nav_2d_utils/plugin_mux.h new file mode 100755 index 0000000..f775582 --- /dev/null +++ b/navigations/nav_2d_utils/include/nav_2d_utils/plugin_mux.h @@ -0,0 +1,274 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef NAV_2D_UTILS_PLUGIN_MUX_H +#define NAV_2D_UTILS_PLUGIN_MUX_H + +#include +#include +#include +#include +#include +#include +#include + +namespace nav_2d_utils +{ +/** + * @class PluginMux + * @brief An organizer for switching between multiple different plugins of the same type + * + * The different plugins are specified using a list of strings on the parameter server, each of which is a namespace. + * The specific type and additional parameters for each plugin are specified on the parameter server in that namespace. + * All the plugins are loaded initially, but only one is the "current" plugin at any particular time, which is published + * on a latched topic AND stored on the ROS parameter server. You can switch which plugin is current either through a + * C++ or ROS interface. + */ +template +class PluginMux +{ +public: + /** + * @brief Main Constructor - Loads plugin(s) and sets up ROS interfaces + * + * @param plugin_package The package of the plugin type + * @param plugin_class The class name for the plugin type + * @param parameter_name Name of parameter for the namespaces. + * @param default_value If class name is not specified, which plugin should be loaded + * @param ros_name ROS name for setting up topic and parameter + * @param switch_service_name ROS name for setting up the ROS service + */ + PluginMux(const std::string& plugin_package, const std::string& plugin_class, + const std::string& parameter_name, const std::string& default_value, + const std::string& ros_name = "current_plugin", const std::string& switch_service_name = "switch_plugin"); + + /** + * @brief Create an instance of the given plugin_class_name and save it with the given plugin_name + * @param plugin_name Namespace for the new plugin + * @param plugin_class_name Class type name for the new plugin + */ + void addPlugin(const std::string& plugin_name, const std::string& plugin_class_name); + + /** + * @brief C++ Interface for switching to a given plugin + * + * @param name Namespace to set current plugin to + * @return true if that namespace exists and is loaded properly + */ + bool usePlugin(const std::string& name) + { + // If plugin with given name doesn't exist, return false + if (plugins_.count(name) == 0) return false; + + if (switch_callback_) + { + switch_callback_(current_plugin_, name); + } + + // Switch Mux + current_plugin_ = name; + + // Update ROS info + std_msgs::String str_msg; + str_msg.data = current_plugin_; + current_plugin_pub_.publish(str_msg); + private_nh_.setParam(ros_name_, current_plugin_); + + return true; + } + + /** + * @brief Get the Current Plugin Name + * @return Name of the current plugin + */ + std::string getCurrentPluginName() const + { + return current_plugin_; + } + + /** + * @brief Check to see if a plugin exists + * @param name Namespace to set current plugin to + * @return True if the plugin exists + */ + bool hasPlugin(const std::string& name) const + { + return plugins_.find(name) != plugins_.end(); + } + + /** + * @brief Get the Specified Plugin + * @param name Name of plugin to get + * @return Reference to specified plugin + */ + T& getPlugin(const std::string& name) + { + if (!hasPlugin(name)) + throw std::invalid_argument("Plugin not found"); + return *plugins_[name]; + } + + /** + * @brief Get the Current Plugin + * @return Reference to current plugin + */ + T& getCurrentPlugin() + { + return getPlugin(current_plugin_); + } + + /** + * @brief Get the current list of plugin names + */ + std::vector getPluginNames() const + { + std::vector names; + for (auto& kv : plugins_) + { + names.push_back(kv.first); + } + return names; + } + + /** + * @brief alias for the function-type of the callback fired when the plugin switches. + * + * The first parameter will be the namespace of the plugin that was previously used. + * The second parameter will be the namespace of the plugin that is being switched to. + */ + using SwitchCallback = std::function; + + /** + * @brief Set the callback fired when the plugin switches + * + * In addition to switching which plugin is being used via directly calling `usePlugin` + * a switch can also be triggered externally via ROS service. In such a case, other classes + * may want to know when this happens. This is accomplished using the SwitchCallback, which + * will be called regardless of how the plugin is switched. + */ + void setSwitchCallback(SwitchCallback switch_callback) { switch_callback_ = switch_callback; } + +protected: + /** + * @brief ROS Interface for Switching Plugins + */ + bool switchPluginService(nav_2d_msgs::SwitchPlugin::Request &req, nav_2d_msgs::SwitchPlugin::Response &resp) + { + std::string name = req.new_plugin; + if (usePlugin(name)) + { + resp.success = true; + resp.message = "Loaded plugin namespace " + name + "."; + } + else + { + resp.success = false; + resp.message = "Namespace " + name + " not configured!"; + } + return true; + } + + // Plugin Management + pluginlib::ClassLoader plugin_loader_; + std::map> plugins_; + std::string current_plugin_; + + // ROS Interface + ros::ServiceServer switch_plugin_srv_; + ros::Publisher current_plugin_pub_; + ros::NodeHandle private_nh_; + std::string ros_name_; + + // Switch Callback + SwitchCallback switch_callback_; +}; + +// ********************************************************************************************************************* +// ****************** Implementation of Templated Methods ************************************************************** +// ********************************************************************************************************************* +template +PluginMux::PluginMux(const std::string& plugin_package, const std::string& plugin_class, + const std::string& parameter_name, const std::string& default_value, + const std::string& ros_name, const std::string& switch_service_name) + : plugin_loader_(plugin_package, plugin_class), private_nh_("~"), ros_name_(ros_name), switch_callback_(nullptr) +{ + // Create the latched publisher + current_plugin_pub_ = private_nh_.advertise(ros_name_, 1, true); + + // Load Plugins + std::string plugin_class_name; + std::vector plugin_namespaces; + private_nh_.getParam(parameter_name, plugin_namespaces); + if (plugin_namespaces.size() == 0) + { + // If no namespaces are listed, use the name of the default class as the singular namespace. + std::string plugin_name = plugin_loader_.getName(default_value); + plugin_namespaces.push_back(plugin_name); + } + + for (const std::string& the_namespace : plugin_namespaces) + { + // Load the class name from namespace/plugin_class, or use default value + private_nh_.param(std::string(the_namespace + "/plugin_class"), plugin_class_name, default_value); + addPlugin(the_namespace, plugin_class_name); + } + + // By default, use the first one as current + usePlugin(plugin_namespaces[0]); + + // Now that the plugins are created, advertise the service if there are multiple + if (plugin_namespaces.size() > 1) + { + switch_plugin_srv_ = private_nh_.advertiseService(switch_service_name, &PluginMux::switchPluginService, this); + } +} + +template +void PluginMux::addPlugin(const std::string& plugin_name, const std::string& plugin_class_name) +{ + try + { + plugins_[plugin_name] = plugin_loader_.createInstance(plugin_class_name); + } + catch (const pluginlib::PluginlibException& ex) + { + ROS_FATAL_NAMED("PluginMux", + "Failed to load the plugin: %s. Exception: %s", plugin_name.c_str(), ex.what()); + exit(EXIT_FAILURE); + } +} + +} // namespace nav_2d_utils + +#endif // NAV_2D_UTILS_PLUGIN_MUX_H diff --git a/navigations/nav_2d_utils/include/nav_2d_utils/polygons.h b/navigations/nav_2d_utils/include/nav_2d_utils/polygons.h new file mode 100755 index 0000000..7d1ee0c --- /dev/null +++ b/navigations/nav_2d_utils/include/nav_2d_utils/polygons.h @@ -0,0 +1,199 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef NAV_2D_UTILS_POLYGONS_H +#define NAV_2D_UTILS_POLYGONS_H + +#include +#include +#include +#include +#include +#include + +namespace nav_2d_utils +{ + +/** + * @class PolygonParseException + * @brief Exception to throw when Polygon doesn't load correctly + */ +class PolygonParseException: public std::runtime_error +{ +public: + explicit PolygonParseException(const std::string& description) : std::runtime_error(description) {} +}; + +/** + * @brief Parse a vector of vectors of doubles from a string. + * Syntax is [[1.0, 2.0], [3.3, 4.4, 5.5], ...] + * + * @param input The string to parse + * @return a vector of vectors of doubles + */ +std::vector > parseVVD(const std::string& input); + +/** + * @brief Create a "circular" polygon from a given radius + * + * @param radius Radius of the polygon + * @param num_points Number of points in the resulting polygon + * @return A rotationally symmetric polygon with the specified number of vertices + */ +nav_2d_msgs::Polygon2D polygonFromRadius(const double radius, const unsigned int num_points = 16); + +/** + * @brief Make a polygon from the given string. + * Format should be bracketed array of arrays of doubles, like so: [[1.0, 2.2], [3.3, 4.2], ...] + * + * @param polygon_string The string to parse + * @return Polygon2D + */ +nav_2d_msgs::Polygon2D polygonFromString(const std::string& polygon_string); + +/** + * @brief Load a polygon from a parameter, whether it is a string or array, or two arrays + * @param nh Node handle to load parameter from + * @param parameter_name Name of the parameter + * @param search Whether to search up the namespace for the parameter name + * @return Loaded polygon + */ +nav_2d_msgs::Polygon2D polygonFromParams(const ros::NodeHandle& nh, const std::string parameter_name, + bool search = true); + +/** + * @brief Create a polygon from the given XmlRpcValue. + * + * @param polygon_xmlrpc should be an array of arrays, where the top-level array should have + * 3 or more elements, and the sub-arrays should all have exactly 2 elements + * (x and y coordinates). + */ +nav_2d_msgs::Polygon2D polygonFromXMLRPC(XmlRpc::XmlRpcValue& polygon_xmlrpc); + +/** + * @brief Create XMLRPC Value for writing the polygon to the parameter server + * @param polygon Polygon to convert + * @param array_of_arrays If true, write an array of arrays. Otherwise, write two parallel arrays + * @return XmlRpcValue + */ +XmlRpc::XmlRpcValue polygonToXMLRPC(const nav_2d_msgs::Polygon2D& polygon, bool array_of_arrays = true); + +/** + * @brief Save a polygon to a parameter + * @param polygon The Polygon + * @param nh Node handle to save the parameter to + * @param parameter_name Name of the parameter + * @param array_of_arrays If true, write an array of arrays. Otherwise, write two parallel arrays + */ +void polygonToParams(const nav_2d_msgs::Polygon2D& polygon, const ros::NodeHandle& nh, const std::string parameter_name, + bool array_of_arrays = true); + +/** + * @brief Create a polygon from two parallel arrays + * + * @param xs Array of doubles representing x coordinates, at least three elements long + * @param ys Array of doubles representing y coordinates, matching length of xs + */ +nav_2d_msgs::Polygon2D polygonFromParallelArrays(const std::vector& xs, const std::vector& ys); + +/** + * @brief Create two parallel arrays from a polygon + * + * @param[in] polygon + * @param[out] xs Array of doubles representing x coordinates, to be populated + * @param[out] ys Array of doubles representing y coordinates, to be populated + */ +void polygonToParallelArrays(const nav_2d_msgs::Polygon2D polygon, std::vector& xs, std::vector& ys); + +/** + * @brief check if two polygons are equal. Used in testing + */ +bool equals(const nav_2d_msgs::Polygon2D& polygon0, const nav_2d_msgs::Polygon2D& polygon1); + +/** + * @brief Translate and rotate a polygon to a new pose + * @param polygon The polygon + * @param pose The x, y and theta to use when moving the polygon + * @return A new moved polygon + */ +nav_2d_msgs::Polygon2D movePolygonToPose(const nav_2d_msgs::Polygon2D& polygon, + const geometry_msgs::Pose2D& pose); + +/** + * @brief Check if a given point is inside of a polygon + * + * Borders are considered outside. + * + * @param polygon Polygon to check + * @param x x coordinate + * @param y y coordinate + * @return true if point is inside polygon + */ +bool isInside(const nav_2d_msgs::Polygon2D& polygon, const double x, const double y); + +/** + * @brief Calculate the minimum and maximum distance from (0, 0) to any point on the polygon + * @param[in] polygon polygon to analyze + * @param[out] min_dist + * @param[out] max_dist + */ +void calculateMinAndMaxDistances(const nav_2d_msgs::Polygon2D& polygon, double& min_dist, double& max_dist); + +/** + * @brief Decompose a complex polygon into a set of triangles. + * + * See https://en.wikipedia.org/wiki/Polygon_triangulation + * + * Implementation from https://github.com/mapbox/earcut.hpp + * + * @param polygon The complex polygon to deconstruct + * @return A vector of points where each set of three points represents a triangle + */ +std::vector triangulate(const nav_2d_msgs::ComplexPolygon2D& polygon); + +/** + * @brief Decompose a simple polygon into a set of triangles. + * + * See https://en.wikipedia.org/wiki/Polygon_triangulation + * + * Implementation from https://github.com/mapbox/earcut.hpp + * + * @param polygon The polygon to deconstruct + * @return A vector of points where each set of three points represents a triangle + */ +std::vector triangulate(const nav_2d_msgs::Polygon2D& polygon); + +} // namespace nav_2d_utils + +#endif // NAV_2D_UTILS_POLYGONS_H diff --git a/navigations/nav_2d_utils/include/nav_2d_utils/tf_help.h b/navigations/nav_2d_utils/include/nav_2d_utils/tf_help.h new file mode 100755 index 0000000..a76ad43 --- /dev/null +++ b/navigations/nav_2d_utils/include/nav_2d_utils/tf_help.h @@ -0,0 +1,91 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef NAV_2D_UTILS_TF_HELP_H +#define NAV_2D_UTILS_TF_HELP_H + +#include +#include +#include +#include + +namespace nav_2d_utils +{ +/** + * @brief Transform a PoseStamped from one frame to another while catching exceptions + * + * Also returns immediately if the frames are equal. + * @param tf Smart pointer to TFListener + * @param frame Frame to transform the pose into + * @param in_pose Pose to transform + * @param out_pose Place to store the resulting transformed pose + * @param extrapolation_fallback If true, if there is an ExtrapolationException, allow looking up the latest timestamp instead. + * @return True if successful transform + */ +bool transformPose(const TFListenerPtr tf, const std::string frame, + const geometry_msgs::PoseStamped& in_pose, geometry_msgs::PoseStamped& out_pose, + const bool extrapolation_fallback = true); + +/** + * @brief Transform a Pose2DStamped from one frame to another while catching exceptions + * + * Also returns immediately if the frames are equal. + * @param tf Smart pointer to TFListener + * @param frame Frame to transform the pose into + * @param in_pose Pose to transform + * @param out_pose Place to store the resulting transformed pose + * @param extrapolation_fallback If true, if there is an ExtrapolationException, allow looking up the latest timestamp instead. + * @return True if successful transform + */ +bool transformPose(const TFListenerPtr tf, const std::string frame, + const nav_2d_msgs::Pose2DStamped& in_pose, nav_2d_msgs::Pose2DStamped& out_pose, + const bool extrapolation_fallback = true); + +/** + * @brief Transform a Pose2DStamped into another frame + * + * Note that this returns a transformed pose + * regardless of whether the transform was successfully performed. + * + * @param tf Smart pointer to TFListener + * @param pose Pose to transform + * @param frame_id Frame to transform the pose into + * @return The resulting transformed pose + */ +geometry_msgs::Pose2D transformStampedPose(const TFListenerPtr tf, const nav_2d_msgs::Pose2DStamped& pose, + const std::string& frame_id); + +} // namespace nav_2d_utils + +#endif // NAV_2D_UTILS_TF_HELP_H diff --git a/navigations/nav_2d_utils/package.xml b/navigations/nav_2d_utils/package.xml new file mode 100755 index 0000000..2910be7 --- /dev/null +++ b/navigations/nav_2d_utils/package.xml @@ -0,0 +1,27 @@ + + + nav_2d_utils + 0.3.0 + A handful of useful utility functions for nav_core2 packages. + + David V. Lu!! + + BSD + + catkin + geometry_msgs + nav_2d_msgs + nav_core2 + nav_grid + nav_msgs + pluginlib + roscpp + std_msgs + tf + tf2_ros + tf2_geometry_msgs + xmlrpcpp + roslint + rostest + rosunit + diff --git a/navigations/nav_2d_utils/setup.py b/navigations/nav_2d_utils/setup.py new file mode 100755 index 0000000..77852f4 --- /dev/null +++ b/navigations/nav_2d_utils/setup.py @@ -0,0 +1,11 @@ +#!/usr/bin/env python + +from distutils.core import setup +from catkin_pkg.python_setup import generate_distutils_setup + +package_info = generate_distutils_setup( + packages=['nav_2d_utils'], + package_dir={'': 'src'} +) + +setup(**package_info) diff --git a/navigations/nav_2d_utils/src/bounds.cpp b/navigations/nav_2d_utils/src/bounds.cpp new file mode 100755 index 0000000..4a0ea72 --- /dev/null +++ b/navigations/nav_2d_utils/src/bounds.cpp @@ -0,0 +1,102 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2020, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include +#include +#include +#include + +namespace nav_2d_utils +{ +nav_core2::Bounds getFullBounds(const nav_grid::NavGridInfo& info) +{ + return nav_core2::Bounds(info.origin_x, info.origin_y, + info.origin_x + info.resolution * info.width, info.origin_y + info.resolution * info.height); +} + +nav_core2::UIntBounds getFullUIntBounds(const nav_grid::NavGridInfo& info) +{ + // bounds are inclusive, so we subtract one + return nav_core2::UIntBounds(0, 0, info.width - 1, info.height - 1); +} + +nav_core2::UIntBounds translateBounds(const nav_grid::NavGridInfo& info, const nav_core2::Bounds& bounds) +{ + unsigned int g_min_x, g_min_y, g_max_x, g_max_y; + worldToGridBounded(info, bounds.getMinX(), bounds.getMinY(), g_min_x, g_min_y); + worldToGridBounded(info, bounds.getMaxX(), bounds.getMaxY(), g_max_x, g_max_y); + return nav_core2::UIntBounds(g_min_x, g_min_y, g_max_x, g_max_y); +} + +nav_core2::Bounds translateBounds(const nav_grid::NavGridInfo& info, const nav_core2::UIntBounds& bounds) +{ + double min_x, min_y, max_x, max_y; + gridToWorld(info, bounds.getMinX(), bounds.getMinY(), min_x, min_y); + gridToWorld(info, bounds.getMaxX(), bounds.getMaxY(), max_x, max_y); + return nav_core2::Bounds(min_x, min_y, max_x, max_y); +} + +std::vector divideBounds(const nav_core2::UIntBounds& original_bounds, + unsigned int n_cols, unsigned int n_rows) +{ + if (n_cols * n_rows == 0) + { + throw std::invalid_argument("Number of rows and columns must be positive (not zero)"); + } + unsigned int full_width = original_bounds.getWidth(), + full_height = original_bounds.getHeight(); + + unsigned int small_width = static_cast(ceil(static_cast(full_width) / n_cols)), + small_height = static_cast(ceil(static_cast(full_height) / n_rows)); + + std::vector divided; + + for (unsigned int row = 0; row < n_rows; row++) + { + unsigned int min_y = original_bounds.getMinY() + small_height * row; + unsigned int max_y = std::min(min_y + small_height - 1, original_bounds.getMaxY()); + + for (unsigned int col = 0; col < n_cols; col++) + { + unsigned int min_x = original_bounds.getMinX() + small_width * col; + unsigned int max_x = std::min(min_x + small_width - 1, original_bounds.getMaxX()); + nav_core2::UIntBounds sub(min_x, min_y, max_x, max_y); + if (!sub.isEmpty()) + divided.push_back(sub); + } + } + return divided; +} +} // namespace nav_2d_utils diff --git a/navigations/nav_2d_utils/src/conversions.cpp b/navigations/nav_2d_utils/src/conversions.cpp new file mode 100755 index 0000000..d8ca973 --- /dev/null +++ b/navigations/nav_2d_utils/src/conversions.cpp @@ -0,0 +1,340 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ +#include +#include +#include + +namespace nav_2d_utils +{ + +geometry_msgs::Twist twist2Dto3D(const nav_2d_msgs::Twist2D& cmd_vel_2d) +{ + geometry_msgs::Twist cmd_vel; + cmd_vel.linear.x = cmd_vel_2d.x; + cmd_vel.linear.y = cmd_vel_2d.y; + cmd_vel.angular.z = cmd_vel_2d.theta; + return cmd_vel; +} + + +nav_2d_msgs::Twist2D twist3Dto2D(const geometry_msgs::Twist& cmd_vel) +{ + nav_2d_msgs::Twist2D cmd_vel_2d; + cmd_vel_2d.x = cmd_vel.linear.x; + cmd_vel_2d.y = cmd_vel.linear.y; + cmd_vel_2d.theta = cmd_vel.angular.z; + return cmd_vel_2d; +} + +nav_2d_msgs::Point2D pointToPoint2D(const geometry_msgs::Point& point) +{ + nav_2d_msgs::Point2D output; + output.x = point.x; + output.y = point.y; + return output; +} + +nav_2d_msgs::Point2D pointToPoint2D(const geometry_msgs::Point32& point) +{ + nav_2d_msgs::Point2D output; + output.x = point.x; + output.y = point.y; + return output; +} + +geometry_msgs::Point pointToPoint3D(const nav_2d_msgs::Point2D& point) +{ + geometry_msgs::Point output; + output.x = point.x; + output.y = point.y; + return output; +} + +geometry_msgs::Point32 pointToPoint32(const nav_2d_msgs::Point2D& point) +{ + geometry_msgs::Point32 output; + output.x = point.x; + output.y = point.y; + return output; +} + +nav_2d_msgs::Pose2DStamped stampedPoseToPose2D(const tf::Stamped& pose) +{ + nav_2d_msgs::Pose2DStamped pose2d; + pose2d.header.stamp = pose.stamp_; + pose2d.header.frame_id = pose.frame_id_; + pose2d.pose.x = pose.getOrigin().getX(); + pose2d.pose.y = pose.getOrigin().getY(); + pose2d.pose.theta = tf::getYaw(pose.getRotation()); + return pose2d; +} + +nav_2d_msgs::Pose2DStamped poseStampedToPose2D(const geometry_msgs::PoseStamped& pose) +{ + nav_2d_msgs::Pose2DStamped pose2d; + pose2d.header = pose.header; + pose2d.pose.x = pose.pose.position.x; + pose2d.pose.y = pose.pose.position.y; + pose2d.pose.theta = tf::getYaw(pose.pose.orientation); + return pose2d; +} + +geometry_msgs::Pose pose2DToPose(const geometry_msgs::Pose2D& pose2d) +{ + geometry_msgs::Pose pose; + pose.position.x = pose2d.x; + pose.position.y = pose2d.y; + pose.orientation = tf::createQuaternionMsgFromYaw(pose2d.theta); + return pose; +} + +geometry_msgs::PoseStamped pose2DToPoseStamped(const nav_2d_msgs::Pose2DStamped& pose2d) +{ + geometry_msgs::PoseStamped pose; + pose.header = pose2d.header; + pose.pose = pose2DToPose(pose2d.pose); + return pose; +} + +geometry_msgs::PoseStamped pose2DToPoseStamped(const geometry_msgs::Pose2D& pose2d, + const std::string& frame, const ros::Time& stamp) +{ + geometry_msgs::PoseStamped pose; + pose.header.frame_id = frame; + pose.header.stamp = stamp; + pose.pose.position.x = pose2d.x; + pose.pose.position.y = pose2d.y; + pose.pose.orientation = tf::createQuaternionMsgFromYaw(pose2d.theta); + return pose; +} + +nav_2d_msgs::Path2D pathToPath(const nav_msgs::Path& path) +{ + nav_2d_msgs::Path2D path2d; + path2d.header = path.header; + nav_2d_msgs::Pose2DStamped stamped_2d; + path2d.poses.resize(path.poses.size()); + for (unsigned int i = 0; i < path.poses.size(); i++) + { + stamped_2d = poseStampedToPose2D(path.poses[i]); + path2d.poses[i] = stamped_2d.pose; + } + return path2d; +} + +nav_msgs::Path posesToPath(const std::vector& poses) +{ + nav_msgs::Path path; + if (poses.empty()) + return path; + + path.poses.resize(poses.size()); + path.header.frame_id = poses[0].header.frame_id; + path.header.stamp = poses[0].header.stamp; + for (unsigned int i = 0; i < poses.size(); i++) + { + path.poses[i] = poses[i]; + } + return path; +} + +nav_2d_msgs::Path2D posesToPath2D(const std::vector& poses) +{ + nav_2d_msgs::Path2D path; + if (poses.empty()) + return path; + + nav_2d_msgs::Pose2DStamped pose; + path.poses.resize(poses.size()); + path.header.frame_id = poses[0].header.frame_id; + path.header.stamp = poses[0].header.stamp; + for (unsigned int i = 0; i < poses.size(); i++) + { + pose = poseStampedToPose2D(poses[i]); + path.poses[i] = pose.pose; + } + return path; +} + + +nav_msgs::Path poses2DToPath(const std::vector& poses, + const std::string& frame, const ros::Time& stamp) +{ + nav_msgs::Path path; + path.poses.resize(poses.size()); + path.header.frame_id = frame; + path.header.stamp = stamp; + for (unsigned int i = 0; i < poses.size(); i++) + { + path.poses[i] = pose2DToPoseStamped(poses[i], frame, stamp); + } + return path; +} + +nav_msgs::Path pathToPath(const nav_2d_msgs::Path2D& path2d) +{ + nav_msgs::Path path; + path.header = path2d.header; + path.poses.resize(path2d.poses.size()); + for (unsigned int i = 0; i < path.poses.size(); i++) + { + path.poses[i].header = path2d.header; + path.poses[i].pose = pose2DToPose(path2d.poses[i]); + } + return path; +} + +geometry_msgs::Polygon polygon2Dto3D(const nav_2d_msgs::Polygon2D& polygon_2d) +{ + geometry_msgs::Polygon polygon; + polygon.points.reserve(polygon_2d.points.size()); + for (const auto& pt : polygon_2d.points) + { + polygon.points.push_back(pointToPoint32(pt)); + } + return polygon; +} + +nav_2d_msgs::Polygon2D polygon3Dto2D(const geometry_msgs::Polygon& polygon_3d) +{ + nav_2d_msgs::Polygon2D polygon; + polygon.points.reserve(polygon_3d.points.size()); + for (const auto& pt : polygon_3d.points) + { + polygon.points.push_back(pointToPoint2D(pt)); + } + return polygon; +} + +geometry_msgs::PolygonStamped polygon2Dto3D(const nav_2d_msgs::Polygon2DStamped& polygon_2d) +{ + geometry_msgs::PolygonStamped polygon; + polygon.header = polygon_2d.header; + polygon.polygon = polygon2Dto3D(polygon_2d.polygon); + return polygon; +} + +nav_2d_msgs::Polygon2DStamped polygon3Dto2D(const geometry_msgs::PolygonStamped& polygon_3d) +{ + nav_2d_msgs::Polygon2DStamped polygon; + polygon.header = polygon_3d.header; + polygon.polygon = polygon3Dto2D(polygon_3d.polygon); + return polygon; +} + +nav_2d_msgs::NavGridInfo toMsg(const nav_grid::NavGridInfo& info) +{ + nav_2d_msgs::NavGridInfo msg; + msg.width = info.width; + msg.height = info.height; + msg.resolution = info.resolution; + msg.frame_id = info.frame_id; + msg.origin_x = info.origin_x; + msg.origin_y = info.origin_y; + return msg; +} + +nav_grid::NavGridInfo fromMsg(const nav_2d_msgs::NavGridInfo& msg) +{ + nav_grid::NavGridInfo info; + info.width = msg.width; + info.height = msg.height; + info.resolution = msg.resolution; + info.frame_id = msg.frame_id; + info.origin_x = msg.origin_x; + info.origin_y = msg.origin_y; + return info; +} + +nav_grid::NavGridInfo infoToInfo(const nav_msgs::MapMetaData& metadata, const std::string& frame) +{ + nav_grid::NavGridInfo info; + info.frame_id = frame; + info.resolution = metadata.resolution; + info.width = metadata.width; + info.height = metadata.height; + info.origin_x = metadata.origin.position.x; + info.origin_y = metadata.origin.position.y; + if (std::abs(tf::getYaw(metadata.origin.orientation)) > 1e-5) + { + ROS_WARN_NAMED("nav_2d_utils", + "Conversion from MapMetaData to NavGridInfo encountered a non-zero rotation. Ignoring."); + } + return info; +} + +geometry_msgs::Pose getOrigin3D(const nav_grid::NavGridInfo& info) +{ + geometry_msgs::Pose origin; + origin.position.x = info.origin_x; + origin.position.y = info.origin_y; + origin.orientation.w = 1.0; + return origin; +} + +geometry_msgs::Pose2D getOrigin2D(const nav_grid::NavGridInfo& info) +{ + geometry_msgs::Pose2D origin; + origin.x = info.origin_x; + origin.y = info.origin_y; + return origin; +} + +nav_msgs::MapMetaData infoToInfo(const nav_grid::NavGridInfo & info) +{ + nav_msgs::MapMetaData metadata; + metadata.resolution = info.resolution; + metadata.width = info.width; + metadata.height = info.height; + metadata.origin = getOrigin3D(info); + return metadata; +} + +nav_2d_msgs::UIntBounds toMsg(const nav_core2::UIntBounds& bounds) +{ + nav_2d_msgs::UIntBounds msg; + msg.min_x = bounds.getMinX(); + msg.min_y = bounds.getMinY(); + msg.max_x = bounds.getMaxX(); + msg.max_y = bounds.getMaxY(); + return msg; +} + +nav_core2::UIntBounds fromMsg(const nav_2d_msgs::UIntBounds& msg) +{ + return nav_core2::UIntBounds(msg.min_x, msg.min_y, msg.max_x, msg.max_y); +} + + +} // namespace nav_2d_utils diff --git a/navigations/nav_2d_utils/src/footprint.cpp b/navigations/nav_2d_utils/src/footprint.cpp new file mode 100755 index 0000000..8d0699b --- /dev/null +++ b/navigations/nav_2d_utils/src/footprint.cpp @@ -0,0 +1,67 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include +#include + +namespace nav_2d_utils +{ +nav_2d_msgs::Polygon2D footprintFromParams(ros::NodeHandle& nh, bool write) +{ + std::string full_param_name; + nav_2d_msgs::Polygon2D footprint; + + if (nh.searchParam("footprint", full_param_name)) + { + footprint = polygonFromParams(nh, full_param_name, false); + if (write) + { + nh.setParam("footprint", polygonToXMLRPC(footprint)); + } + } + else if (nh.searchParam("robot_radius", full_param_name)) + { + double robot_radius = 0.0; + nh.getParam(full_param_name, robot_radius); + footprint = polygonFromRadius(robot_radius); + if (write) + { + nh.setParam("robot_radius", robot_radius); + } + } + return footprint; +} + +} // namespace nav_2d_utils diff --git a/navigations/nav_2d_utils/src/nav_2d_utils/__init__.py b/navigations/nav_2d_utils/src/nav_2d_utils/__init__.py new file mode 100755 index 0000000..e69de29 diff --git a/navigations/nav_2d_utils/src/nav_2d_utils/conversions.py b/navigations/nav_2d_utils/src/nav_2d_utils/conversions.py new file mode 100755 index 0000000..0f05402 --- /dev/null +++ b/navigations/nav_2d_utils/src/nav_2d_utils/conversions.py @@ -0,0 +1,131 @@ +from geometry_msgs.msg import Pose, Pose2D, Quaternion, Point +from nav_2d_msgs.msg import Twist2D, Path2D, Pose2DStamped, Point2D +from nav_msgs.msg import Path +from geometry_msgs.msg import Twist, PoseStamped + +try: + from tf.transformations import euler_from_quaternion, quaternion_from_euler + + def get_yaw(orientation): + rpy = euler_from_quaternion((orientation.x, orientation.y, orientation.z, orientation.w)) + return rpy[2] + + def from_yaw(yaw): + q = Quaternion() + q.x, q.y, q.z, q.w = quaternion_from_euler(0, 0, yaw) + return q +except ImportError: + from math import sin, cos, atan2 + # From https://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles + + def from_yaw(yaw): + q = Quaternion() + q.z = sin(yaw * 0.5) + q.w = cos(yaw * 0.5) + return q + + def get_yaw(q): + siny_cosp = +2.0 * (q.w * q.z + q.x * q.y) + cosy_cosp = +1.0 - 2.0 * (q.y * q.y + q.z * q.z) + return atan2(siny_cosp, cosy_cosp) + + +def twist2Dto3D(cmd_vel_2d): + cmd_vel = Twist() + cmd_vel.linear.x = cmd_vel_2d.x + cmd_vel.linear.y = cmd_vel_2d.y + cmd_vel.angular.z = cmd_vel_2d.theta + return cmd_vel + + +def twist3Dto2D(cmd_vel): + cmd_vel_2d = Twist2D() + cmd_vel_2d.x = cmd_vel.linear.x + cmd_vel_2d.y = cmd_vel.linear.y + cmd_vel_2d.theta = cmd_vel.angular.z + return cmd_vel_2d + + +def pointToPoint3D(point_2d): + point = Point() + point.x = point_2d.x + point.y = point_2d.y + return point + + +def pointToPoint2D(point): + point_2d = Point2D() + point_2d.x = point.x + point_2d.y = point.y + return point_2d + + +def poseToPose2D(pose): + pose2d = Pose2D() + pose2d.x = pose.position.x + pose2d.y = pose.position.y + pose2d.theta = get_yaw(pose.orientation) + return pose2d + + +def poseStampedToPose2DStamped(pose): + pose2d = Pose2DStamped() + pose2d.header = pose.header + pose2d.pose = poseToPose2D(pose.pose) + return pose2d + + +def poseToPose2DStamped(pose, frame, stamp): + pose2d = Pose2DStamped() + pose2d.header.frame_id = frame + pose2d.header.stamp = stamp + pose2d.pose = poseToPose2D(pose) + return pose2d + + +def pose2DToPose(pose2d): + pose = Pose() + pose.position.x = pose2d.x + pose.position.y = pose2d.y + pose.orientation = from_yaw(pose2d.theta) + return pose + + +def pose2DStampedToPoseStamped(pose2d): + pose = PoseStamped() + pose.header = pose2d.header + pose.pose = pose2DToPose(pose2d.pose) + return pose + + +def pose2DToPoseStamped(pose2d, frame, stamp): + pose = PoseStamped() + pose.header.frame_id = frame + pose.header.stamp = stamp + pose.pose.position.x = pose2d.x + pose.pose.position.y = pose2d.y + pose.pose.orientation = from_yaw(pose2d.theta) + return pose + + +def pathToPath2D(path): + path2d = Path2D() + if len(path.poses) == 0: + return path + path2d.header.frame_id = path.poses[0].header.frame_id + path2d.header.stamp = path.poses[0].header.stamp + for pose in path.poses: + stamped = poseStampedToPose2DStamped(pose) + path2d.poses.append(stamped.pose) + return path2d + + +def path2DToPath(path2d): + path = Path() + path.header = path2d.header + for pose2d in path2d.poses: + pose = PoseStamped() + pose.header = path2d.header + pose.pose = pose2DToPose(pose2d) + path.poses.append(pose) + return path diff --git a/navigations/nav_2d_utils/src/path_ops.cpp b/navigations/nav_2d_utils/src/path_ops.cpp new file mode 100755 index 0000000..a91283a --- /dev/null +++ b/navigations/nav_2d_utils/src/path_ops.cpp @@ -0,0 +1,192 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include +#include +#include + +namespace nav_2d_utils +{ + +double poseDistance(const geometry_msgs::Pose2D& pose0, const geometry_msgs::Pose2D& pose1) +{ + return hypot(pose0.x - pose1.x, pose0.y - pose1.y); +} + +double getPlanLength(const nav_2d_msgs::Path2D& plan, const unsigned int start_index) +{ + double length = 0.0; + for (unsigned int i = start_index + 1; i < plan.poses.size(); i++) + { + length += poseDistance(plan.poses[i - 1], plan.poses[i]); + } + return length; +} + +double getPlanLength(const nav_2d_msgs::Path2D& plan, const geometry_msgs::Pose2D& query_pose) +{ + if (plan.poses.size() == 0) return 0.0; + + unsigned int closest_index = 0; + double closest_distance = poseDistance(plan.poses[0], query_pose); + for (unsigned int i = 1; i < plan.poses.size(); i++) + { + double distance = poseDistance(plan.poses[i], query_pose); + if (closest_distance > distance) + { + closest_index = i; + closest_distance = distance; + } + } + return getPlanLength(plan, closest_index); +} + +nav_2d_msgs::Path2D adjustPlanResolution(const nav_2d_msgs::Path2D& global_plan_in, double resolution) +{ + nav_2d_msgs::Path2D global_plan_out; + global_plan_out.header = global_plan_in.header; + if (global_plan_in.poses.size() == 0) + { + return global_plan_out; + } + + geometry_msgs::Pose2D last = global_plan_in.poses[0]; + global_plan_out.poses.push_back(last); + + double sq_resolution = resolution * resolution; + + for (unsigned int i = 1; i < global_plan_in.poses.size(); ++i) + { + geometry_msgs::Pose2D loop = global_plan_in.poses[i]; + double sq_dist = (loop.x - last.x) * (loop.x - last.x) + (loop.y - last.y) * (loop.y - last.y); + if (sq_dist > sq_resolution) + { + // add points in-between + double diff = sqrt(sq_dist) - resolution; + double steps_double = ceil(diff / resolution) + 1.0; + int steps = static_cast(steps_double); + + double delta_x = (loop.x - last.x) / steps_double; + double delta_y = (loop.y - last.y) / steps_double; + double delta_t = (loop.theta - last.theta) / steps_double; + + for (int j = 1; j < steps; ++j) + { + geometry_msgs::Pose2D pose; + pose.x = last.x + j * delta_x; + pose.y = last.y + j * delta_y; + pose.theta = last.theta + j * delta_t; + global_plan_out.poses.push_back(pose); + } + } + global_plan_out.poses.push_back(global_plan_in.poses[i]); + last.x = loop.x; + last.y = loop.y; + } + return global_plan_out; +} + +using PoseList = std::vector; + +/** + * @brief Helper function for other version of compressPlan. + * + * Uses the Ramer Douglas Peucker algorithm. Ignores theta values + * + * @param input Full list of poses + * @param start_index Index of first pose (inclusive) + * @param end_index Index of last pose (inclusive) + * @param epsilon maximum allowable error. Increase for greater compression. + * @param list of poses possibly compressed for the poses[start_index, end_index] + */ +PoseList compressPlan(const PoseList& input, unsigned int start_index, unsigned int end_index, double epsilon) +{ + // Skip if only two points + if (end_index - start_index <= 1) + { + PoseList::const_iterator first = input.begin() + start_index; + PoseList::const_iterator last = input.begin() + end_index + 1; + return PoseList(first, last); + } + + // Find the point with the maximum distance to the line from start to end + const geometry_msgs::Pose2D& start = input[start_index], + end = input[end_index]; + double max_distance = 0.0; + unsigned int max_index = 0; + for (unsigned int i = start_index + 1; i < end_index; i++) + { + const geometry_msgs::Pose2D& pose = input[i]; + double d = distanceToLine(pose.x, pose.y, start.x, start.y, end.x, end.y); + if (d > max_distance) + { + max_index = i; + max_distance = d; + } + } + + // If max distance is less than epsilon, eliminate all the points between start and end + if (max_distance <= epsilon) + { + PoseList outer; + outer.push_back(start); + outer.push_back(end); + return outer; + } + + // If max distance is greater than epsilon, recursively simplify + PoseList first_part = compressPlan(input, start_index, max_index, epsilon); + PoseList second_part = compressPlan(input, max_index, end_index, epsilon); + first_part.insert(first_part.end(), second_part.begin() + 1, second_part.end()); + return first_part; +} + +nav_2d_msgs::Path2D compressPlan(const nav_2d_msgs::Path2D& input_path, double epsilon) +{ + nav_2d_msgs::Path2D results; + results.header = input_path.header; + results.poses = compressPlan(input_path.poses, 0, input_path.poses.size() - 1, epsilon); + return results; +} + +void addPose(nav_2d_msgs::Path2D& path, double x, double y, double theta) +{ + geometry_msgs::Pose2D pose; + pose.x = x; + pose.y = y; + pose.theta = theta; + path.poses.push_back(pose); +} +} // namespace nav_2d_utils diff --git a/navigations/nav_2d_utils/src/polygons.cpp b/navigations/nav_2d_utils/src/polygons.cpp new file mode 100755 index 0000000..559f287 --- /dev/null +++ b/navigations/nav_2d_utils/src/polygons.cpp @@ -0,0 +1,502 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include +#include +#include +#include +#include +#include + +namespace nav_2d_utils +{ + +using nav_2d_msgs::Point2D; +using nav_2d_msgs::Polygon2D; + +std::vector > parseVVD(const std::string& input) +{ + std::vector > result; + + std::stringstream input_ss(input); + int depth = 0; + std::vector current_vector; + while (input_ss.good()) + { + switch (input_ss.peek()) + { + case EOF: + break; + case '[': + depth++; + if (depth > 2) + { + throw PolygonParseException("Array depth greater than 2"); + } + input_ss.get(); + current_vector.clear(); + break; + case ']': + depth--; + if (depth < 0) + { + throw PolygonParseException("More close ] than open ["); + } + input_ss.get(); + if (depth == 1) + { + result.push_back(current_vector); + } + break; + case ',': + case ' ': + case '\t': + input_ss.get(); + break; + default: // All other characters should be part of the numbers. + if (depth != 2) + { + std::stringstream err_ss; + err_ss << "Numbers at depth other than 2. Char was '" << char(input_ss.peek()) << "'."; + throw PolygonParseException(err_ss.str()); + } + double value; + if (input_ss >> value) + { + current_vector.push_back(value); + } + break; + } + } + + if (depth != 0) + { + throw PolygonParseException("Unterminated vector string."); + } + + return result; +} + +Polygon2D polygonFromRadius(const double radius, const unsigned int num_points) +{ + Polygon2D polygon; + Point2D pt; + for (unsigned int i = 0; i < num_points; ++i) + { + double angle = i * 2 * M_PI / num_points; + pt.x = cos(angle) * radius; + pt.y = sin(angle) * radius; + polygon.points.push_back(pt); + } + + return polygon; +} + +Polygon2D polygonFromString(const std::string& polygon_string) +{ + Polygon2D polygon; + // Will throw PolygonParseException if problematic + std::vector > vvd = parseVVD(polygon_string); + + // convert vvd into points. + if (vvd.size() < 3) + { + throw PolygonParseException("You must specify at least three points for the polygon."); + } + + polygon.points.resize(vvd.size()); + for (unsigned int i = 0; i < vvd.size(); i++) + { + if (vvd[ i ].size() != 2) + { + std::stringstream err_ss; + err_ss << "Points in the polygon specification must be pairs of numbers. Point index " << i << " had "; + err_ss << int(vvd[ i ].size()) << " numbers."; + throw PolygonParseException(err_ss.str()); + } + + polygon.points[i].x = vvd[i][0]; + polygon.points[i].y = vvd[i][1]; + } + + return polygon; +} + + +/** + * @brief Helper function. Convert value to double + */ +double getNumberFromXMLRPC(XmlRpc::XmlRpcValue& value) +{ + if (value.getType() == XmlRpc::XmlRpcValue::TypeInt) + { + return static_cast(static_cast(value)); + } + else if (value.getType() == XmlRpc::XmlRpcValue::TypeDouble) + { + return static_cast(value); + } + + std::stringstream err_ss; + err_ss << "Values in the polygon specification must be numbers. Found value: " << value.toXml(); + throw PolygonParseException(err_ss.str()); +} + +/** + * @brief Helper function. Convert value to double array + */ +std::vector getNumberVectorFromXMLRPC(XmlRpc::XmlRpcValue& value) +{ + if (value.getType() != XmlRpc::XmlRpcValue::TypeArray) + { + throw PolygonParseException("Subarray must have type list."); + } + std::vector array; + for (int i = 0; i < value.size(); i++) + { + array.push_back(getNumberFromXMLRPC(value[i])); + } + return array; +} + +Polygon2D polygonFromXMLRPC(XmlRpc::XmlRpcValue& polygon_xmlrpc) +{ + if (polygon_xmlrpc.getType() == XmlRpc::XmlRpcValue::TypeString && + polygon_xmlrpc != "" && polygon_xmlrpc != "[]") + { + return polygonFromString(std::string(polygon_xmlrpc)); + } + + if (polygon_xmlrpc.getType() == XmlRpc::XmlRpcValue::TypeStruct) + { + if (!polygon_xmlrpc.hasMember("x") || !polygon_xmlrpc.hasMember("y")) + { + throw PolygonParseException("Dict-like Polygon must specify members x and y."); + } + std::vector xs = getNumberVectorFromXMLRPC(polygon_xmlrpc["x"]); + std::vector ys = getNumberVectorFromXMLRPC(polygon_xmlrpc["y"]); + return polygonFromParallelArrays(xs, ys); + } + + // Make sure we have an array of at least 3 elements. + if (polygon_xmlrpc.getType() != XmlRpc::XmlRpcValue::TypeArray) + { + std::stringstream err_ss; + err_ss << "Polygon must be specified as a list of lists. Found object of type " << polygon_xmlrpc.getType() + << " instead."; + throw PolygonParseException(err_ss.str()); + } + else if (polygon_xmlrpc.size() < 3) + { + throw PolygonParseException("You must specify at least three points for the polygon."); + } + + Polygon2D polygon; + Point2D pt; + for (int i = 0; i < polygon_xmlrpc.size(); ++i) + { + // Make sure each element of the list is an array of size 2. (x and y coordinates) + XmlRpc::XmlRpcValue& point_xml = polygon_xmlrpc[i]; + if (point_xml.getType() != XmlRpc::XmlRpcValue::TypeArray) + { + std::stringstream err_ss; + err_ss << "Each point must be specified as a list. Found object of type " << point_xml.getType() << " instead."; + throw PolygonParseException(err_ss.str()); + } + else if (point_xml.size() != 2) + { + throw PolygonParseException("Each point must have two numbers (x and y)."); + } + + pt.x = getNumberFromXMLRPC(point_xml[0]); + pt.y = getNumberFromXMLRPC(point_xml[1]); + polygon.points.push_back(pt); + } + return polygon; +} + +Polygon2D polygonFromParams(const ros::NodeHandle& nh, const std::string parameter_name, bool search) +{ + std::string full_param_name; + if (search) + { + nh.searchParam(parameter_name, full_param_name); + } + else + { + full_param_name = parameter_name; + } + + if (!nh.hasParam(full_param_name)) + { + std::stringstream err_ss; + err_ss << "Parameter " << parameter_name << "(" + nh.resolveName(parameter_name) << ") not found."; + throw PolygonParseException(err_ss.str()); + } + XmlRpc::XmlRpcValue polygon_xmlrpc; + nh.getParam(full_param_name, polygon_xmlrpc); + return polygonFromXMLRPC(polygon_xmlrpc); +} + +/** + * @brief Helper method to convert a vector of doubles + */ +XmlRpc::XmlRpcValue vectorToXMLRPC(const std::vector& array) +{ + XmlRpc::XmlRpcValue xml; + xml.setSize(array.size()); + for (unsigned int i = 0; i < array.size(); ++i) + { + xml[i] = array[i]; + } + return xml; +} + +XmlRpc::XmlRpcValue polygonToXMLRPC(const nav_2d_msgs::Polygon2D& polygon, bool array_of_arrays) +{ + XmlRpc::XmlRpcValue xml; + if (array_of_arrays) + { + xml.setSize(polygon.points.size()); + for (unsigned int i = 0; i < polygon.points.size(); ++i) + { + xml[i].setSize(2); + const Point2D& p = polygon.points[i]; + xml[i][0] = p.x; + xml[i][1] = p.y; + } + } + else + { + std::vector xs, ys; + polygonToParallelArrays(polygon, xs, ys); + xml["x"] = vectorToXMLRPC(xs); + xml["y"] = vectorToXMLRPC(ys); + } + return xml; +} + +void polygonToParams(const nav_2d_msgs::Polygon2D& polygon, const ros::NodeHandle& nh, const std::string parameter_name, + bool array_of_arrays) +{ + nh.setParam(parameter_name, polygonToXMLRPC(polygon, array_of_arrays)); +} + +nav_2d_msgs::Polygon2D polygonFromParallelArrays(const std::vector& xs, const std::vector& ys) +{ + if (xs.size() < 3) + { + throw PolygonParseException("You must specify at least three points for the polygon."); + } + else if (xs.size() != ys.size()) + { + throw PolygonParseException("Length of x array does not match length of y array."); + } + + Polygon2D polygon; + polygon.points.resize(xs.size()); + for (unsigned int i = 0; i < xs.size(); i++) + { + Point2D& pt = polygon.points[i]; + pt.x = xs[i]; + pt.y = ys[i]; + } + return polygon; +} + +void polygonToParallelArrays(const nav_2d_msgs::Polygon2D polygon, std::vector& xs, std::vector& ys) +{ + xs.clear(); + ys.clear(); + for (const Point2D& pt : polygon.points) + { + xs.push_back(pt.x); + ys.push_back(pt.y); + } +} + +bool equals(const nav_2d_msgs::Polygon2D& polygon0, const nav_2d_msgs::Polygon2D& polygon1) +{ + if (polygon0.points.size() != polygon1.points.size()) + { + return false; + } + for (unsigned int i=0; i < polygon0.points.size(); i++) + { + if (polygon0.points[i].x != polygon1.points[i].x ||polygon0.points[i].y != polygon1.points[i].y) + { + return false; + } + } + return true; +} + +nav_2d_msgs::Polygon2D movePolygonToPose(const nav_2d_msgs::Polygon2D& polygon, + const geometry_msgs::Pose2D& pose) +{ + nav_2d_msgs::Polygon2D new_polygon; + new_polygon.points.resize(polygon.points.size()); + double cos_th = cos(pose.theta); + double sin_th = sin(pose.theta); + for (unsigned int i = 0; i < polygon.points.size(); ++i) + { + nav_2d_msgs::Point2D& new_pt = new_polygon.points[i]; + new_pt.x = pose.x + polygon.points[i].x * cos_th - polygon.points[i].y * sin_th; + new_pt.y = pose.y + polygon.points[i].x * sin_th + polygon.points[i].y * cos_th; + } + return new_polygon; +} + +bool isInside(const nav_2d_msgs::Polygon2D& polygon, const double x, const double y) +{ + // Determine if the given point is inside the polygon using the number of crossings method + // https://wrf.ecse.rpi.edu//Research/Short_Notes/pnpoly.html + int n = polygon.points.size(); + int cross = 0; + // Loop from i = [0 ... n - 1] and j = [n - 1, 0 ... n - 2] + // Ensures first point connects to last point + for (int i = 0, j = n - 1; i < n; j = i++) + { + // Check if the line to x,y crosses this edge + if ( ((polygon.points[i].y > y) != (polygon.points[j].y > y)) + && (x < (polygon.points[j].x - polygon.points[i].x) * (y - polygon.points[i].y) / + (polygon.points[j].y - polygon.points[i].y) + polygon.points[i].x) ) + { + cross++; + } + } + // Return true if the number of crossings is odd + return cross % 2 > 0; +} + +void calculateMinAndMaxDistances(const nav_2d_msgs::Polygon2D& polygon, double& min_dist, double& max_dist) +{ + min_dist = std::numeric_limits::max(); + max_dist = 0.0; + auto& points = polygon.points; + if (points.size() == 0) + { + return; + } + + for (unsigned int i = 0; i < points.size() - 1; ++i) + { + // check the distance from the robot center point to the first vertex + double vertex_dist = hypot(points[i].x, points[i].y); + double edge_dist = distanceToLine(0.0, 0.0, points[i].x, points[i].y, + points[i + 1].x, points[i + 1].y); + min_dist = std::min(min_dist, std::min(vertex_dist, edge_dist)); + max_dist = std::max(max_dist, std::max(vertex_dist, edge_dist)); + } + + // we also need to do the last vertex and the first vertex + double vertex_dist = hypot(points.back().x, points.back().y); + double edge_dist = distanceToLine(0.0, 0.0, points.back().x, points.back().y, + points.front().x, points.front().y); + min_dist = std::min(min_dist, std::min(vertex_dist, edge_dist)); + max_dist = std::max(max_dist, std::max(vertex_dist, edge_dist)); +} +} // namespace nav_2d_utils + +// Adapt Point2D for use with the triangulation library +namespace mapbox +{ +namespace util +{ +template <> +struct nth<0, nav_2d_msgs::Point2D> +{ + inline static double get(const nav_2d_msgs::Point2D& point) + { + return point.x; + }; +}; + +template <> +struct nth<1, nav_2d_msgs::Point2D> +{ + inline static double get(const nav_2d_msgs::Point2D& point) + { + return point.y; + }; +}; + +} // namespace util +} // namespace mapbox + + +namespace nav_2d_utils +{ +std::vector triangulate(const nav_2d_msgs::ComplexPolygon2D& polygon) +{ + // Compute the triangulation + std::vector> rings; + rings.reserve(1 + polygon.inner.size()); + rings.push_back(polygon.outer.points); + for (const nav_2d_msgs::Polygon2D& inner : polygon.inner) + { + rings.push_back(inner.points); + } + std::vector indices = mapbox::earcut(rings); + + // Create a sequential point index. The triangulation results are indices in this vector. + std::vector points; + for (const auto& ring : rings) + { + for (const nav_2d_msgs::Point2D& point : ring) + { + points.push_back(point); + } + } + + // Construct the output triangles + std::vector result; + result.reserve(indices.size()); + for (unsigned int index : indices) + { + result.push_back(points[index]); + } + return result; +} + +std::vector triangulate(const nav_2d_msgs::Polygon2D& polygon) +{ + nav_2d_msgs::ComplexPolygon2D complex; + complex.outer = polygon; + return triangulate(complex); +} + + +} // namespace nav_2d_utils diff --git a/navigations/nav_2d_utils/src/tf_help.cpp b/navigations/nav_2d_utils/src/tf_help.cpp new file mode 100755 index 0000000..b1364f6 --- /dev/null +++ b/navigations/nav_2d_utils/src/tf_help.cpp @@ -0,0 +1,100 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * 2022, Metro Robots + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include +#include +#include +#include + +namespace nav_2d_utils +{ +bool transformPose(const TFListenerPtr tf, const std::string frame, + const geometry_msgs::PoseStamped& in_pose, geometry_msgs::PoseStamped& out_pose, + const bool extrapolation_fallback) +{ + if (in_pose.header.frame_id == frame) + { + out_pose = in_pose; + return true; + } + + try + { + tf->transform(in_pose, out_pose, frame); + return true; + } + catch (tf::ExtrapolationException& ex) + { + if (!extrapolation_fallback) + throw; + geometry_msgs::PoseStamped latest_in_pose; + latest_in_pose.header.frame_id = in_pose.header.frame_id; + latest_in_pose.pose = in_pose.pose; + tf->transform(latest_in_pose, out_pose, frame); + return true; + } + catch (tf::TransformException& ex) + { + ROS_ERROR("Exception in transformPose: %s", ex.what()); + return false; + } + return false; +} + +bool transformPose(const TFListenerPtr tf, const std::string frame, + const nav_2d_msgs::Pose2DStamped& in_pose, nav_2d_msgs::Pose2DStamped& out_pose, + const bool extrapolation_fallback) +{ + geometry_msgs::PoseStamped in_3d_pose = pose2DToPoseStamped(in_pose); + geometry_msgs::PoseStamped out_3d_pose; + + bool ret = transformPose(tf, frame, in_3d_pose, out_3d_pose, extrapolation_fallback); + if (ret) + { + out_pose = poseStampedToPose2D(out_3d_pose); + } + return ret; +} + +geometry_msgs::Pose2D transformStampedPose(const TFListenerPtr tf, const nav_2d_msgs::Pose2DStamped& pose, + const std::string& frame_id) +{ + nav_2d_msgs::Pose2DStamped local_pose; + nav_2d_utils::transformPose(tf, frame_id, pose, local_pose); + return local_pose.pose; +} + +} // namespace nav_2d_utils diff --git a/navigations/nav_2d_utils/test/bounds_test.cpp b/navigations/nav_2d_utils/test/bounds_test.cpp new file mode 100755 index 0000000..58f840b --- /dev/null +++ b/navigations/nav_2d_utils/test/bounds_test.cpp @@ -0,0 +1,199 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2020, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ +#include +#include +#include +#include + +using nav_2d_utils::divideBounds; +using nav_core2::UIntBounds; + +/** + * @brief Count the values in a grid. + * @param[in] The grid + * @param[out] match Number of values == 1 + * @param[out] missed Number of values == 0 + * @param[out] multiple Number of other values + */ +void countValues(const nav_grid::VectorNavGrid& grid, + unsigned int& match, unsigned int& missed, unsigned int& multiple) +{ + match = 0; + missed = 0; + multiple = 0; + + nav_grid::NavGridInfo info = grid.getInfo(); + + // No iterator to avoid tricky depenencies + for (unsigned int x = 0; x < info.width; x++) + { + for (unsigned int y = 0; y < info.height; y++) + { + switch (grid(x, y)) + { + case 0: + missed++; + break; + case 1: + match++; + break; + default: + multiple++; + break; + } + } + } +} + +TEST(DivideBounds, zeroes) +{ + UIntBounds bounds(2, 2, 5, 5); + // Number of rows/cols has to be positive + EXPECT_THROW(divideBounds(bounds, 0, 2), std::invalid_argument); + EXPECT_THROW(divideBounds(bounds, 2, 0), std::invalid_argument); + EXPECT_THROW(divideBounds(bounds, 0, 0), std::invalid_argument); + EXPECT_NO_THROW(divideBounds(bounds, 2, 2)); + + bounds.reset(); + // check for errors with empty bounds + EXPECT_NO_THROW(divideBounds(bounds, 2, 2)); +} + +/** + * This test is for the divideBounds method and takes grids of various sizes + * (cycled through with the outer two loops) and tries to divide them into subgrids of + * various sizes (cycled through with the next two loops). The resulting vector of + * bounds should cover every cell in the original grid, so each of the divided bounds is + * iterated over, adding one to each grid cell. If everything works perfectly, each cell + * should be touched exactly once. + */ +TEST(DivideBounds, iterative_tests) +{ + nav_grid::VectorNavGrid full_grid; + nav_grid::NavGridInfo info; + + // count variables + unsigned int match, missed, multiple; + + for (info.width = 1; info.width < 15; info.width++) + { + for (info.height = 1; info.height < 15; info.height++) + { + full_grid.setInfo(info); + UIntBounds full_bounds = nav_2d_utils::getFullUIntBounds(info); + for (unsigned int rows = 1; rows < 11u; rows++) + { + for (unsigned int cols = 1; cols < 11u; cols++) + { + full_grid.reset(); + std::vector divided = divideBounds(full_bounds, cols, rows); + ASSERT_LE(divided.size(), rows * cols) << info.width << "x" << info.height << " " << rows << "x" << cols; + for (const UIntBounds& sub : divided) + { + EXPECT_FALSE(sub.isEmpty()); + // Can't use nav_grid_iterator for circular dependencies + for (unsigned int x = sub.getMinX(); x <= sub.getMaxX(); x++) + { + for (unsigned int y = sub.getMinY(); y <= sub.getMaxY(); y++) + { + full_grid.setValue(x, y, full_grid(x, y) + 1); + } + } + } + + countValues(full_grid, match, missed, multiple); + ASSERT_EQ(match, info.width * info.height) << "Full grid: " << info.width << "x" << info.height + << " Requested divisions: " << rows << "x" << cols; + EXPECT_EQ(missed, 0u); + EXPECT_EQ(multiple, 0u); + } + } + } + } +} + +/** + * This test is for the divideBounds method and calls it recursively to + * ensure that the method works when the minimum values in the original bounds + * are not zero. + */ +TEST(DivideBounds, recursive_tests) +{ + nav_grid::VectorNavGrid full_grid; + nav_grid::NavGridInfo info; + info.width = 100; + info.height = 100; + full_grid.setInfo(info); + + UIntBounds full_bounds = nav_2d_utils::getFullUIntBounds(info); + + std::vector level_one = divideBounds(full_bounds, 2, 2); + ASSERT_EQ(level_one.size(), 4u); + for (const UIntBounds& sub : level_one) + { + std::vector level_two = divideBounds(sub, 2, 2); + ASSERT_EQ(level_two.size(), 4u); + for (const UIntBounds& subsub : level_two) + { + EXPECT_GE(subsub.getMinX(), sub.getMinX()); + EXPECT_LE(subsub.getMaxX(), sub.getMaxX()); + EXPECT_GE(subsub.getMinY(), sub.getMinY()); + EXPECT_LE(subsub.getMaxY(), sub.getMaxY()); + // Can't use nav_grid_iterator for circular dependencies + for (unsigned int x = subsub.getMinX(); x <= subsub.getMaxX(); x++) + { + for (unsigned int y = subsub.getMinY(); y <= subsub.getMaxY(); y++) + { + full_grid.setValue(x, y, full_grid(x, y) + 1); + } + } + } + } + + // Count values + unsigned int match = 0, + missed = 0, + multiple = 0; + countValues(full_grid, match, missed, multiple); + ASSERT_EQ(match, info.width * info.height); + EXPECT_EQ(missed, 0u); + EXPECT_EQ(multiple, 0u); +} + + +int main(int argc, char** argv) +{ + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/navigations/nav_2d_utils/test/compress_test.cpp b/navigations/nav_2d_utils/test/compress_test.cpp new file mode 100755 index 0000000..41d5760 --- /dev/null +++ b/navigations/nav_2d_utils/test/compress_test.cpp @@ -0,0 +1,97 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ +#include +#include + +using nav_2d_utils::compressPlan; +using nav_2d_utils::addPose; + +TEST(CompressTest, compress_test) +{ + nav_2d_msgs::Path2D path; + // Dataset borrowed from https://karthaus.nl/rdp/ + addPose(path, 24, 173); + addPose(path, 26, 170); + addPose(path, 24, 166); + addPose(path, 27, 162); + addPose(path, 37, 161); + addPose(path, 45, 157); + addPose(path, 48, 152); + addPose(path, 46, 143); + addPose(path, 40, 140); + addPose(path, 34, 137); + addPose(path, 26, 134); + addPose(path, 24, 130); + addPose(path, 24, 125); + addPose(path, 28, 121); + addPose(path, 36, 118); + addPose(path, 46, 117); + addPose(path, 63, 121); + addPose(path, 76, 125); + addPose(path, 82, 120); + addPose(path, 86, 111); + addPose(path, 88, 103); + addPose(path, 90, 91); + addPose(path, 95, 87); + addPose(path, 107, 89); + addPose(path, 107, 104); + addPose(path, 106, 117); + addPose(path, 109, 129); + addPose(path, 119, 131); + addPose(path, 131, 131); + addPose(path, 139, 134); + addPose(path, 138, 143); + addPose(path, 131, 152); + addPose(path, 119, 154); + addPose(path, 111, 149); + addPose(path, 105, 143); + addPose(path, 91, 139); + addPose(path, 80, 142); + addPose(path, 81, 152); + addPose(path, 76, 163); + addPose(path, 67, 161); + addPose(path, 59, 149); + addPose(path, 63, 138); + + EXPECT_EQ(41U, compressPlan(path, 0.1).poses.size()); + EXPECT_EQ(34U, compressPlan(path, 1.3).poses.size()); + EXPECT_EQ(12U, compressPlan(path, 9.5).poses.size()); + EXPECT_EQ(8U, compressPlan(path, 19.9).poses.size()); +} + +int main(int argc, char** argv) +{ + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/navigations/nav_2d_utils/test/param_tests.cpp b/navigations/nav_2d_utils/test/param_tests.cpp new file mode 100755 index 0000000..724e186 --- /dev/null +++ b/navigations/nav_2d_utils/test/param_tests.cpp @@ -0,0 +1,146 @@ +/********************************************************************* +* +* Software License Agreement (BSD License) +* +* Copyright (c) 2009, Willow Garage, Inc. +* 2018, Locus Robotics +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of Willow Garage, Inc. nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* +* Author: Dave Hershberger +* David V. Lu!! (nav_2d_utils version) +*********************************************************************/ +#include +#include +#include + +using nav_2d_utils::polygonFromParams; +using nav_2d_msgs::Polygon2D; + +TEST(Polygon2D, unpadded_footprint_from_string_param) +{ + ros::NodeHandle nh("~unpadded"); + Polygon2D footprint = polygonFromParams(nh, "footprint"); + ASSERT_EQ(3U, footprint.points.size()); + + EXPECT_EQ(1.0f, footprint.points[ 0 ].x); + EXPECT_EQ(1.0f, footprint.points[ 0 ].y); + + EXPECT_EQ(-1.0f, footprint.points[ 1 ].x); + EXPECT_EQ(1.0f, footprint.points[ 1 ].y); + + EXPECT_EQ(-1.0f, footprint.points[ 2 ].x); + EXPECT_EQ(-1.0f, footprint.points[ 2 ].y); +} + +TEST(Polygon2D, check_search_capabilities) +{ + ros::NodeHandle nh("~unpadded/unneccessarily/long_namespace"); + Polygon2D footprint = polygonFromParams(nh, "footprint"); + ASSERT_EQ(3U, footprint.points.size()); + EXPECT_THROW(polygonFromParams(nh, "footprint", false), nav_2d_utils::PolygonParseException); +} + +TEST(Polygon2D, footprint_from_xmlrpc_param) +{ + ros::NodeHandle nh("~xmlrpc"); + Polygon2D footprint = polygonFromParams(nh, "footprint"); + ASSERT_EQ(4U, footprint.points.size()); + + EXPECT_FLOAT_EQ(0.1f, footprint.points[ 0 ].x); + EXPECT_FLOAT_EQ(0.1f, footprint.points[ 0 ].y); + + EXPECT_FLOAT_EQ(-0.1f, footprint.points[ 1 ].x); + EXPECT_FLOAT_EQ(0.1f, footprint.points[ 1 ].y); + + EXPECT_FLOAT_EQ(-0.1f, footprint.points[ 2 ].x); + EXPECT_FLOAT_EQ(-0.1f, footprint.points[ 2 ].y); + + EXPECT_FLOAT_EQ(0.1f, footprint.points[ 3 ].x); + EXPECT_FLOAT_EQ(-0.1f, footprint.points[ 3 ].y); + + Polygon2D footprint2 = polygonFromParams(nh, "footprint2"); + ASSERT_TRUE(nav_2d_utils::equals(footprint, footprint2)); +} + +TEST(Polygon2D, footprint_from_same_level_param) +{ + ros::NodeHandle nh("~same_level"); + Polygon2D footprint = polygonFromParams(nh, "footprint"); + ASSERT_EQ(3U, footprint.points.size()); + + EXPECT_EQ(1.0f, footprint.points[ 0 ].x); + EXPECT_EQ(2.0f, footprint.points[ 0 ].y); + + EXPECT_EQ(3.0f, footprint.points[ 1 ].x); + EXPECT_EQ(4.0f, footprint.points[ 1 ].y); + + EXPECT_EQ(5.0f, footprint.points[ 2 ].x); + EXPECT_EQ(6.0f, footprint.points[ 2 ].y); +} + +TEST(Polygon2D, footprint_from_xmlrpc_param_failure) +{ + ros::NodeHandle nh("~xmlrpc_fail"); + EXPECT_THROW(polygonFromParams(nh, "footprint"), nav_2d_utils::PolygonParseException); + EXPECT_THROW(polygonFromParams(nh, "footprint2"), nav_2d_utils::PolygonParseException); + EXPECT_THROW(polygonFromParams(nh, "footprint3"), nav_2d_utils::PolygonParseException); + EXPECT_THROW(polygonFromParams(nh, "footprint4"), nav_2d_utils::PolygonParseException); + EXPECT_THROW(polygonFromParams(nh, "footprint5"), nav_2d_utils::PolygonParseException); + EXPECT_THROW(polygonFromParams(nh, "footprint6"), nav_2d_utils::PolygonParseException); + EXPECT_THROW(polygonFromParams(nh, "footprint7"), nav_2d_utils::PolygonParseException); + EXPECT_THROW(polygonFromParams(nh, "footprint8"), nav_2d_utils::PolygonParseException); + EXPECT_THROW(polygonFromParams(nh, "footprint9"), nav_2d_utils::PolygonParseException); +} + +TEST(Polygon2D, footprint_empty) +{ + ros::NodeHandle nh("~empty"); + EXPECT_THROW(polygonFromParams(nh, "footprint"), nav_2d_utils::PolygonParseException); +} + +TEST(Polygon2D, test_write) +{ + ros::NodeHandle nh("~unpadded"); + Polygon2D footprint = polygonFromParams(nh, "footprint"); + nh.setParam("another_footprint", nav_2d_utils::polygonToXMLRPC(footprint)); + Polygon2D another_footprint = polygonFromParams(nh, "another_footprint"); + EXPECT_TRUE(nav_2d_utils::equals(footprint, another_footprint)); + + nh.setParam("third_footprint", nav_2d_utils::polygonToXMLRPC(footprint, false)); + another_footprint = polygonFromParams(nh, "third_footprint"); + EXPECT_TRUE(nav_2d_utils::equals(footprint, another_footprint)); +} + +int main(int argc, char** argv) +{ + ros::init(argc, argv, "param_tests"); + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/navigations/nav_2d_utils/test/param_tests.launch b/navigations/nav_2d_utils/test/param_tests.launch new file mode 100755 index 0000000..ead5813 --- /dev/null +++ b/navigations/nav_2d_utils/test/param_tests.launch @@ -0,0 +1,34 @@ + + + + + + footprint: [[0.1, 0.1], [-0.1, 0.1], [-0.1, -0.1], [0.1, -0.1]] + footprint2: + x: [0.1, -0.1, -0.1, 0.1] + y: [0.1, 0.1, -0.1, -0.1] + + + + footprint: [[0.1, 0.1], [-0.1, 0.1, 77.0], [-0.1, -0.1], [0.1, -0.1]] + footprint2: 1.0 + footprint3: false + footprint4: [[0.1, 0.1], [0.1, 0.1]] + footprint5: ['x', 'y', 'z'] + footprint6: [['x', 'y'], ['a', 'b'], ['c'], ['d']] + footprint7: + x: [0.1, -0.1, -0.1, 0.1] + footprint8: + x: 0 + y: 0 + footprint9: + x: ['a', 'b', 'c'] + y: [d, e, f] + + + + + + + + diff --git a/navigations/nav_2d_utils/test/polygon_tests.cpp b/navigations/nav_2d_utils/test/polygon_tests.cpp new file mode 100755 index 0000000..9bbc220 --- /dev/null +++ b/navigations/nav_2d_utils/test/polygon_tests.cpp @@ -0,0 +1,185 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ +#include +#include +#include + +using nav_2d_utils::parseVVD; +using nav_2d_msgs::Polygon2D; +using nav_2d_utils::polygonFromString; +using nav_2d_utils::polygonFromParallelArrays; + +TEST(array_parser, basic_operation) +{ + std::vector > vvd; + vvd = parseVVD("[[1, 2.2], [.3, -4e4]]"); + EXPECT_DOUBLE_EQ(2U, vvd.size()); + EXPECT_DOUBLE_EQ(2U, vvd[0].size()); + EXPECT_DOUBLE_EQ(2U, vvd[1].size()); + EXPECT_DOUBLE_EQ(1.0, vvd[0][0]); + EXPECT_DOUBLE_EQ(2.2, vvd[0][1]); + EXPECT_DOUBLE_EQ(0.3, vvd[1][0]); + EXPECT_DOUBLE_EQ(-40000.0, vvd[1][1]); +} + +TEST(array_parser, missing_open) +{ + EXPECT_THROW(parseVVD("[1, 2.2], [.3, -4e4]]"), nav_2d_utils::PolygonParseException); +} + +TEST(array_parser, missing_close) +{ + EXPECT_THROW(parseVVD("[[1, 2.2], [.3, -4e4]"), nav_2d_utils::PolygonParseException); +} + +TEST(array_parser, wrong_depth) +{ + EXPECT_THROW(parseVVD("[1, 2.2], [.3, -4e4]"), nav_2d_utils::PolygonParseException); +} + +TEST(Polygon2D, radius_param) +{ + Polygon2D footprint = nav_2d_utils::polygonFromRadius(10.0); + // Circular robot has 16-point footprint auto-generated. + ASSERT_EQ(16U, footprint.points.size()); + + // Check the first point + EXPECT_EQ(10.0, footprint.points[0].x); + EXPECT_EQ(0.0, footprint.points[0].y); + + // Check the 4th point, which should be 90 degrees around the circle from the first. + EXPECT_NEAR(0.0, footprint.points[4].x, 0.0001); + EXPECT_NEAR(10.0, footprint.points[4].y, 0.0001); +} + +TEST(Polygon2D, string_param) +{ + Polygon2D footprint = polygonFromString("[[1, 1], [-1, 1], [-1, -1]]"); + ASSERT_EQ(3U, footprint.points.size()); + + EXPECT_EQ(1.0, footprint.points[ 0 ].x); + EXPECT_EQ(1.0, footprint.points[ 0 ].y); + + EXPECT_EQ(-1.0, footprint.points[ 1 ].x); + EXPECT_EQ(1.0, footprint.points[ 1 ].y); + + EXPECT_EQ(-1.0, footprint.points[ 2 ].x); + EXPECT_EQ(-1.0, footprint.points[ 2 ].y); +} + +TEST(Polygon2D, broken_string_param) +{ + // Not enough points + EXPECT_THROW(polygonFromString("[[1, 1], [-1, 1]]"), nav_2d_utils::PolygonParseException); + + // Too many numbers in point + EXPECT_THROW(polygonFromString("[[1, 1, 1], [-1, 1], [-1, -1]]"), nav_2d_utils::PolygonParseException); + + // Unexpected character + EXPECT_THROW(polygonFromString("[[x, 1], [-1, 1], [-1, -1]]"), nav_2d_utils::PolygonParseException); + + // Empty String + EXPECT_THROW(polygonFromString(""), nav_2d_utils::PolygonParseException); + + // Empty List + EXPECT_THROW(polygonFromString("[]"), nav_2d_utils::PolygonParseException); + + // Empty Point + EXPECT_THROW(polygonFromString("[[]]"), nav_2d_utils::PolygonParseException); +} + +TEST(Polygon2D, arrays) +{ + std::vector xs = {1, -1, -1}; + std::vector ys = {1, 1, -1}; + Polygon2D footprint = polygonFromParallelArrays(xs, ys); + ASSERT_EQ(3U, footprint.points.size()); + + EXPECT_EQ(1.0, footprint.points[ 0 ].x); + EXPECT_EQ(1.0, footprint.points[ 0 ].y); + + EXPECT_EQ(-1.0, footprint.points[ 1 ].x); + EXPECT_EQ(1.0, footprint.points[ 1 ].y); + + EXPECT_EQ(-1.0, footprint.points[ 2 ].x); + EXPECT_EQ(-1.0, footprint.points[ 2 ].y); +} + +TEST(Polygon2D, broken_arrays) +{ + std::vector shorty = {1, -1}; + std::vector three = {1, 1, -1}; + std::vector four = {1, 1, -1, -1}; + EXPECT_THROW(polygonFromParallelArrays(shorty, shorty), nav_2d_utils::PolygonParseException); + EXPECT_THROW(polygonFromParallelArrays(three, four), nav_2d_utils::PolygonParseException); +} + +TEST(Polygon2D, test_move) +{ + Polygon2D square = polygonFromString("[[0.5, 0.5], [0.5, -0.5], [-0.5, -0.5], [-0.5, 0.5]]"); + geometry_msgs::Pose2D pose; + Polygon2D square2 = nav_2d_utils::movePolygonToPose(square, pose); + EXPECT_TRUE(nav_2d_utils::equals(square, square2)); + pose.x = 15; + pose.y = -10; + pose.theta = M_PI / 4; + Polygon2D diamond = nav_2d_utils::movePolygonToPose(square, pose); + ASSERT_EQ(4U, diamond.points.size()); + double side = 1.0 / sqrt(2); + + EXPECT_DOUBLE_EQ(pose.x, diamond.points[ 0 ].x); + EXPECT_DOUBLE_EQ(pose.y + side, diamond.points[ 0 ].y); + EXPECT_DOUBLE_EQ(pose.x + side, diamond.points[ 1 ].x); + EXPECT_DOUBLE_EQ(pose.y, diamond.points[ 1 ].y); + EXPECT_DOUBLE_EQ(pose.x, diamond.points[ 2 ].x); + EXPECT_DOUBLE_EQ(pose.y - side, diamond.points[ 2 ].y); + EXPECT_DOUBLE_EQ(pose.x - side, diamond.points[ 3 ].x); + EXPECT_DOUBLE_EQ(pose.y, diamond.points[ 3 ].y); +} + +TEST(Polygon2D, inside) +{ + Polygon2D square = polygonFromString("[[0.5, 0.5], [0.5, -0.5], [-0.5, -0.5], [-0.5, 0.5]]"); + EXPECT_TRUE(nav_2d_utils::isInside(square, 0.00, 0.00)); + EXPECT_TRUE(nav_2d_utils::isInside(square, 0.45, 0.45)); + EXPECT_FALSE(nav_2d_utils::isInside(square, 0.50, 0.50)); + EXPECT_FALSE(nav_2d_utils::isInside(square, 0.00, 0.50)); + EXPECT_FALSE(nav_2d_utils::isInside(square, 0.55, 0.55)); +} + +int main(int argc, char** argv) +{ + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/navigations/nav_2d_utils/test/resolution_test.cpp b/navigations/nav_2d_utils/test/resolution_test.cpp new file mode 100755 index 0000000..1a676b5 --- /dev/null +++ b/navigations/nav_2d_utils/test/resolution_test.cpp @@ -0,0 +1,78 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ +#include +#include + +using nav_2d_utils::adjustPlanResolution; +using nav_2d_utils::addPose; + +TEST(ResolutionTest, simple_example) +{ + nav_2d_msgs::Path2D path; + // Space between points is one meter + addPose(path, 0.0, 0.0); + addPose(path, 0.0, 1.0); + + // resolution>=1, path won't change + EXPECT_EQ(2U, adjustPlanResolution(path, 2.0).poses.size()); + EXPECT_EQ(2U, adjustPlanResolution(path, 1.0).poses.size()); + + // 0.5 <= resolution < 1.0, one point should be added in the middle + EXPECT_EQ(3U, adjustPlanResolution(path, 0.8).poses.size()); + EXPECT_EQ(3U, adjustPlanResolution(path, 0.5).poses.size()); + + // 0.333 <= resolution < 0.5, two points need to be added + EXPECT_EQ(4U, adjustPlanResolution(path, 0.34).poses.size()); + + // 0.25 <= resolution < 0.333, three points need to be added + EXPECT_EQ(5U, adjustPlanResolution(path, 0.32).poses.size()); +} + +TEST(ResolutionTest, real_example) +{ + // This test is based on a real-world example + nav_2d_msgs::Path2D path; + addPose(path, 17.779193, -0.972024); + addPose(path, 17.799171, -0.950775); + addPose(path, 17.851942, -0.903709); + EXPECT_EQ(3U, adjustPlanResolution(path, 0.2).poses.size()); + EXPECT_EQ(4U, adjustPlanResolution(path, 0.05).poses.size()); +} + + +int main(int argc, char** argv) +{ + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/navigations/nav_core/CHANGELOG.rst b/navigations/nav_core/CHANGELOG.rst new file mode 100755 index 0000000..1817763 --- /dev/null +++ b/navigations/nav_core/CHANGELOG.rst @@ -0,0 +1,112 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package nav_core +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +1.17.3 (2023-01-10) +------------------- + +1.17.2 (2022-06-20) +------------------- + +1.17.1 (2020-08-27) +------------------- + +1.17.0 (2020-04-02) +------------------- +* Merge pull request `#982 `_ from ros-planning/noetic_prep + Noetic Migration +* increase required cmake version +* Contributors: Michael Ferguson + +1.16.6 (2020-03-18) +------------------- + +1.16.5 (2020-03-15) +------------------- + +1.16.4 (2020-03-04) +------------------- + +1.16.3 (2019-11-15) +------------------- + +1.16.2 (2018-07-31) +------------------- + +1.16.1 (2018-07-28) +------------------- + +1.16.0 (2018-07-25) +------------------- +* Switch to TF2 `#755 `_ +* unify parameter names between base_local_planner and dwa_local_planner + addresses parts of `#90 `_ +* fix param names of RotateRecovery, closes `#706 `_ +* Contributors: David V. Lu, Michael Ferguson, Vincent Rabaud + +1.15.2 (2018-03-22) +------------------- +* Merge pull request `#673 `_ from ros-planning/email_update_lunar + update maintainer email (lunar) +* Merge pull request `#649 `_ from aaronhoy/lunar_add_ahoy + Add myself as a maintainer. +* Contributors: Aaron Hoy, Michael Ferguson + +1.15.1 (2017-08-14) +------------------- + +1.15.0 (2017-08-07) +------------------- +* convert packages to format2 +* makePlan overload must return. +* Contributors: Eric Tappan, Mikael Arguedas + +1.14.0 (2016-05-20) +------------------- + +1.13.1 (2015-10-29) +------------------- +* Merge pull request `#338 `_ from mikeferguson/planner_review +* fix doxygen, couple style fixes +* Contributors: Michael Ferguson + +1.13.0 (2015-03-17) +------------------- +* adding makePlan function with returned cost to base_global_planner +* Contributors: phil0stine + +1.12.0 (2015-02-04) +------------------- +* update maintainer email +* Contributors: Michael Ferguson + +1.11.15 (2015-02-03) +-------------------- + +1.11.14 (2014-12-05) +-------------------- + +1.11.13 (2014-10-02) +-------------------- + +1.11.12 (2014-10-01) +-------------------- + +1.11.11 (2014-07-23) +-------------------- + +1.11.10 (2014-06-25) +-------------------- + +1.11.9 (2014-06-10) +------------------- + +1.11.8 (2014-05-21) +------------------- + +1.11.7 (2014-05-21) +------------------- + +1.11.4 (2013-09-27) +------------------- +* Package URL Updates diff --git a/navigations/nav_core/CMakeLists.txt b/navigations/nav_core/CMakeLists.txt new file mode 100755 index 0000000..9cb0500 --- /dev/null +++ b/navigations/nav_core/CMakeLists.txt @@ -0,0 +1,27 @@ +cmake_minimum_required(VERSION 3.0.2) +project(nav_core) + +find_package(catkin REQUIRED + COMPONENTS + std_msgs + geometry_msgs + tf2_ros + costmap_2d + ) + +catkin_package( + INCLUDE_DIRS + include + CATKIN_DEPENDS + std_msgs + geometry_msgs + tf2_ros + costmap_2d +) + + +## Install project namespaced headers +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} + FILES_MATCHING PATTERN "*.h" + PATTERN ".svn" EXCLUDE) diff --git a/navigations/nav_core/include/nav_core/base_global_planner.h b/navigations/nav_core/include/nav_core/base_global_planner.h new file mode 100755 index 0000000..a863ca5 --- /dev/null +++ b/navigations/nav_core/include/nav_core/base_global_planner.h @@ -0,0 +1,93 @@ +/********************************************************************* +* +* Software License Agreement (BSD License) +* +* Copyright (c) 2008, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of Willow Garage, Inc. nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* +* Author: Eitan Marder-Eppstein +*********************************************************************/ +#ifndef NAV_CORE_BASE_GLOBAL_PLANNER_H +#define NAV_CORE_BASE_GLOBAL_PLANNER_H + +#include +#include + +namespace nav_core { + /** + * @class BaseGlobalPlanner + * @brief Provides an interface for global planners used in navigation. All global planners written as plugins for the navigation stack must adhere to this interface. + */ + class BaseGlobalPlanner{ + public: + /** + * @brief Given a goal pose in the world, compute a plan + * @param start The start pose + * @param goal The goal pose + * @param plan The plan... filled by the planner + * @return True if a valid plan was found, false otherwise + */ + virtual bool makePlan(const geometry_msgs::PoseStamped& start, + const geometry_msgs::PoseStamped& goal, std::vector& plan) = 0; + + /** + * @brief Given a goal pose in the world, compute a plan + * @param start The start pose + * @param goal The goal pose + * @param plan The plan... filled by the planner + * @param cost The plans calculated cost + * @return True if a valid plan was found, false otherwise + */ + virtual bool makePlan(const geometry_msgs::PoseStamped& start, + const geometry_msgs::PoseStamped& goal, std::vector& plan, + double& cost) + { + cost = 0; + return makePlan(start, goal, plan); + } + + /** + * @brief Initialization function for the BaseGlobalPlanner + * @param name The name of this planner + * @param costmap_ros A pointer to the ROS wrapper of the costmap to use for planning + */ + virtual void initialize(std::string name, costmap_2d::Costmap2DROS* costmap_ros) = 0; + + /** + * @brief Virtual destructor for the interface + */ + virtual ~BaseGlobalPlanner(){} + + protected: + BaseGlobalPlanner(){} + }; +}; // namespace nav_core + +#endif // NAV_CORE_BASE_GLOBAL_PLANNER_H \ No newline at end of file diff --git a/navigations/nav_core/include/nav_core/base_local_planner.h b/navigations/nav_core/include/nav_core/base_local_planner.h new file mode 100755 index 0000000..1f13dd1 --- /dev/null +++ b/navigations/nav_core/include/nav_core/base_local_planner.h @@ -0,0 +1,90 @@ +/********************************************************************* +* +* Software License Agreement (BSD License) +* +* Copyright (c) 2008, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of Willow Garage, Inc. nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* +* Author: Eitan Marder-Eppstein +*********************************************************************/ +#ifndef NAV_CORE_BASE_LOCAL_PLANNER_H +#define NAV_CORE_BASE_LOCAL_PLANNER_H + +#include +#include +#include +#include + +namespace nav_core { + /** + * @class BaseLocalPlanner + * @brief Provides an interface for local planners used in navigation. All local planners written as plugins for the navigation stack must adhere to this interface. + */ + class BaseLocalPlanner{ + public: + /** + * @brief Given the current position, orientation, and velocity of the robot, compute velocity commands to send to the base + * @param cmd_vel Will be filled with the velocity command to be passed to the robot base + * @return True if a valid velocity command was found, false otherwise + */ + virtual bool computeVelocityCommands(geometry_msgs::Twist& cmd_vel) = 0; + + /** + * @brief Check if the goal pose has been achieved by the local planner + * @return True if achieved, false otherwise + */ + virtual bool isGoalReached() = 0; + + /** + * @brief Set the plan that the local planner is following + * @param plan The plan to pass to the local planner + * @return True if the plan was updated successfully, false otherwise + */ + virtual bool setPlan(const std::vector& plan) = 0; + + /** + * @brief Constructs the local planner + * @param name The name to give this instance of the local planner + * @param tf A pointer to a transform listener + * @param costmap_ros The cost map to use for assigning costs to local plans + */ + virtual void initialize(std::string name, tf2_ros::Buffer* tf, costmap_2d::Costmap2DROS* costmap_ros) = 0; + + /** + * @brief Virtual destructor for the interface + */ + virtual ~BaseLocalPlanner(){} + + protected: + BaseLocalPlanner(){} + }; +}; // namespace nav_core + +#endif // NAV_CORE_BASE_LOCAL_PLANNER_H diff --git a/navigations/nav_core/include/nav_core/parameter_magic.h b/navigations/nav_core/include/nav_core/parameter_magic.h new file mode 100755 index 0000000..a318fd7 --- /dev/null +++ b/navigations/nav_core/include/nav_core/parameter_magic.h @@ -0,0 +1,86 @@ +/********************************************************************* +* +* Software License Agreement (BSD License) +* +* Copyright (c) 2018, Open Source Robotics Foundation +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of OSRF nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* +* Author: David Lu +*********************************************************************/ + +#ifndef NAV_CORE_PARAMETER_MAGIC_H +#define NAV_CORE_PARAMETER_MAGIC_H + +namespace nav_core +{ + +/** + * @brief Load a parameter from one of two namespaces. Complain if it uses the old name. + * @param nh NodeHandle to look for the parameter in + * @param current_name Parameter name that is current, i.e. not deprecated + * @param old_name Deprecated parameter name + * @param default_value If neither parameter is present, return this value + * @return The value of the parameter or the default value + */ +template +param_t loadParameterWithDeprecation(const ros::NodeHandle& nh, const std::string current_name, + const std::string old_name, const param_t& default_value) +{ + param_t value; + if (nh.hasParam(current_name)) + { + nh.getParam(current_name, value); + return value; + } + if (nh.hasParam(old_name)) + { + ROS_WARN("Parameter %s is deprecated. Please use the name %s instead.", old_name.c_str(), current_name.c_str()); + nh.getParam(old_name, value); + return value; + } + return default_value; +} + +/** + * @brief Warn if a parameter exists under a deprecated (and unsupported) name. + * + * Parameters loaded exclusively through dynamic reconfigure can't really use loadParamWithDeprecation. + */ +void warnRenamedParameter(const ros::NodeHandle& nh, const std::string current_name, const std::string old_name) +{ + if (nh.hasParam(old_name)) + { + ROS_WARN("Parameter %s is deprecated (and will not load properly). Use %s instead.", old_name.c_str(), current_name.c_str()); + } +} + +} // namespace nav_core + +#endif // NAV_CORE_PARAMETER_MAGIC_H diff --git a/navigations/nav_core/include/nav_core/recovery_behavior.h b/navigations/nav_core/include/nav_core/recovery_behavior.h new file mode 100755 index 0000000..07fd299 --- /dev/null +++ b/navigations/nav_core/include/nav_core/recovery_behavior.h @@ -0,0 +1,73 @@ +/********************************************************************* +* +* Software License Agreement (BSD License) +* +* Copyright (c) 2009, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of Willow Garage, Inc. nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* +* Author: Eitan Marder-Eppstein +*********************************************************************/ +#ifndef NAV_CORE_RECOVERY_BEHAVIOR_H +#define NAV_CORE_RECOVERY_BEHAVIOR_H + +#include +#include + +namespace nav_core { + /** + * @class RecoveryBehavior + * @brief Provides an interface for recovery behaviors used in navigation. All recovery behaviors written as plugins for the navigation stack must adhere to this interface. + */ + class RecoveryBehavior{ + public: + /** + * @brief Initialization function for the RecoveryBehavior + * @param tf A pointer to a transform listener + * @param global_costmap A pointer to the global_costmap used by the navigation stack + * @param local_costmap A pointer to the local_costmap used by the navigation stack + */ + virtual void initialize(std::string name, tf2_ros::Buffer* tf, costmap_2d::Costmap2DROS* global_costmap, costmap_2d::Costmap2DROS* local_costmap) = 0; + + /** + * @brief Runs the RecoveryBehavior + */ + virtual void runBehavior() = 0; + + /** + * @brief Virtual destructor for the interface + */ + virtual ~RecoveryBehavior(){} + + protected: + RecoveryBehavior(){} + }; +}; // namespace nav_core + +#endif // NAV_CORE_RECOVERY_BEHAVIOR_H diff --git a/navigations/nav_core/package.xml b/navigations/nav_core/package.xml new file mode 100755 index 0000000..866276a --- /dev/null +++ b/navigations/nav_core/package.xml @@ -0,0 +1,26 @@ + + + + nav_core + 1.17.3 + + + This package provides common interfaces for navigation specific robot actions. Currently, this package provides the BaseGlobalPlanner, BaseLocalPlanner, and RecoveryBehavior interfaces, which can be used to build actions that can easily swap their planner, local controller, or recovery behavior for new versions adhering to the same interface. + + + Eitan Marder-Eppstein + contradict@gmail.com + David V. Lu!! + Michael Ferguson + Aaron Hoy + BSD + http://wiki.ros.org/nav_core + + catkin + + costmap_2d + geometry_msgs + std_msgs + tf2_ros + + diff --git a/navigations/nav_core2/CMakeLists.txt b/navigations/nav_core2/CMakeLists.txt new file mode 100755 index 0000000..3d692ff --- /dev/null +++ b/navigations/nav_core2/CMakeLists.txt @@ -0,0 +1,41 @@ +cmake_minimum_required(VERSION 3.0.2) +project(nav_core2) +set_directory_properties(PROPERTIES COMPILE_OPTIONS "-std=c++11") + +find_package(catkin REQUIRED + COMPONENTS nav_2d_msgs nav_grid tf2_ros +) + +catkin_package( + CATKIN_DEPENDS nav_2d_msgs nav_grid tf2_ros + INCLUDE_DIRS include + LIBRARIES basic_costmap +) + +add_library(basic_costmap src/basic_costmap.cpp) +target_link_libraries( + basic_costmap ${catkin_LIBRARIES} +) + +include_directories( + include ${catkin_INCLUDE_DIRS} +) + +if(CATKIN_ENABLE_TESTING) + find_package(roslint REQUIRED) + roslint_cpp() + roslint_add_test() + + catkin_add_gtest(bounds_test test/bounds_test.cpp) + catkin_add_gtest(exception_test test/exception_test.cpp) +endif() + +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} +) +install( + TARGETS basic_costmap + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} +) diff --git a/navigations/nav_core2/README.md b/navigations/nav_core2/README.md new file mode 100755 index 0000000..42118a8 --- /dev/null +++ b/navigations/nav_core2/README.md @@ -0,0 +1,52 @@ +# nav_core2 +A replacement interface for [nav_core](https://github.com/ros-planning/navigation/tree/a2837b5a9dc6dd4b4da176fca7d899d6a3722bf8/nav_core/include/nav_core) that defines basic two dimensional planner interfaces. + +There were a few key reasons for creating new interfaces rather than extending the old ones. + * Use `nav_2d_msgs` to eliminate unused data fields + * Use a new `Costmap` interface as a plugin rather that forcing all implementations of the interfaces to use `costmap_2d::Costmap2DROS`. + * Provide more data in the interfaces for easier testing. + * Use Exceptions rather than booleans to provide more information about the types of errors encountered. + +## `Costmap` +`costmap_2d::Costmap2DROS` has been a vital part of the navigation stack for years, but it was not without its flaws. + * Initialization required a transform be available from the global frame to the base frame, which was later used to move rolling costmaps around (and a few other things). This made doing simple testing of any planner or other `Costmap2DROS`-based behavior annoying, because transforms had to be set up, often outside of the immediate code that was being tested. + * Initialization also started an update thread, which is also not always needed in testing. + * Using `Costmap2DROS` locked users into a layered costmap based approach, which made some tasks much easier, but didn't give users the freedom to change the implementation. + +The [`nav_core2::Costmap`](include/nav_core2/costmap.h) interface extends the `nav_grid::NavGrid` for abstracting away the data storage and coordinate manipulation, and provides a few other key methods for costmap functioning such as + * a mutex + * a way to potentially track changes to the costmap + * a public `update` method that can be called in whatever thread you please + +The `Costmap` can be loaded using `pluginlib`, allowing for arbitrary implementations of underlying update algorithms, include the layered costmap approach. + +One basic implementation is provided in [`BasicCostmap`](include/nav_core2/basic_costmap.h). You can also use the `nav_core_adapter::CostmapAdapter` class which implements the `Costmap` interface while allowing you to still use `Costmap2DROS`. + +Note: One could also imagine the `Costmap` interface being templatized itself like `NavGrid` instead of forcing use of `unsigned char`. While this may be possible, it was decided that it was a bit ambitious and the use of templates would force all of the implementation into headers, and would ultimately obfuscate the operation of algorithms. + +## Global Planner +Let us compare the old [nav_core::BaseGlobalPlanner](https://github.com/ros-planning/navigation/blob/a2837b5a9dc6dd4b4da176fca7d899d6a3722bf8/nav_core/include/nav_core/base_global_planner.h) to the new [nav_core2/GlobalPlanner](include/nav_core2/global_planner.h). + +| `nav_core` | `nav_core2` | comments | +|---|--|---| +|`void initialize(std::string, costmap_2d::Costmap2DROS*)`|`void initialize(const ros::NodeHandle& parent, const std::string&, TFListenerPtr, Costmap::Ptr)`|Uses modern pointers instead of raw pointers, and provides a TFListener| +|`bool makePlan(const geometry_msgs::PoseStamped&, const geometry_msgs::PoseStamped&, std::vector&)`|`nav_2d_msgs::Path2D makePlan(const nav_2d_msgs::Pose2DStamped&, const nav_2d_msgs::Pose2DStamped&)`|Uses exceptions for errors instead of returning a bool, which frees up the return for the actual path.| + +## Local Planner +Now let's compare the old [nav_core::BaseLocalPlanner](https://github.com/ros-planning/navigation/blob/a2837b5a9dc6dd4b4da176fca7d899d6a3722bf8/nav_core/include/nav_core/base_local_planner.h) to the new [nav_core2/LocalPlanner](include/nav_core2/local_planner.h). + +| `nav_core` | `nav_core2` | comments | +|---|--|---| +|`void initialize(std::string, tf::TransformListener*, costmap_2d::Costmap2DROS*)`|`void initialize(const ros::NodeHandle& parent, const std::string&, TFListenerPtr, Costmap::Ptr)`|Uses modern pointers instead of raw pointers| +|(no equivalent)|`void setGoalPose(const nav_2d_msgs::Pose2DStamped&)`|Explicitly set the new goal location, rather than using the last pose of the global plan` +|`bool setPlan(const std::vector&)`|`setPlan(const nav_2d_msgs::Path2D&)`|| +|`bool computeVelocityCommands(geometry_msgs::Twist&)`|`nav_2d_msgs::Twist2DStamped computeVelocityCommands(const nav_2d_msgs::Pose2DStamped&, const nav_2d_msgs::Twist2D&)`|Explicitly provides the current pose and velocity for more explicit data control and easier testing. Uses exceptions for errors instead of returning a bool, which frees up the return for the actual command.| +|`bool isGoalReached()` | `bool isGoalReached(const nav_2d_msgs::Pose2DStamped&, const nav_2d_msgs::Twist2D&)` | Explicitly provide the current pose and velocity for more explicit data control and easier testing. | + +## Exceptions +A hierarchical collection of [exceptions](include/nav_core2/exceptions.h) is provided to allow for reacting to navigation failures in a more robust and contextual way. +![exception hierarchy tree](doc/exceptions.png) +Each exception has a corresponding integer "result code" that can be used in ROS interfaces where passing the C++ object is infeasible. Note that due to the hierarchy, the result_code will be for the child-most exception. For example, if you throw a `StartBoundsException` which has a corresponding result code of `6`, it could also be seen as a `InvalidStartPoseException`, `GlobalPlannerException`, `PlannerException` or `NavCore2Exception`, all of which would also have the result code of `6`. + +## Bounds +For use in tracking `Costmap` changes and more, this package also provides an implementation of [bounding boxes](include/nav_core2/bounds.h). These are represented with the ranges `[min_x, max_x]` and `[min_y, max_y]` (inclusive). diff --git a/navigations/nav_core2/doc/exceptions.png b/navigations/nav_core2/doc/exceptions.png new file mode 100755 index 0000000..83f31e4 Binary files /dev/null and b/navigations/nav_core2/doc/exceptions.png differ diff --git a/navigations/nav_core2/include/nav_core2/basic_costmap.h b/navigations/nav_core2/include/nav_core2/basic_costmap.h new file mode 100755 index 0000000..5018438 --- /dev/null +++ b/navigations/nav_core2/include/nav_core2/basic_costmap.h @@ -0,0 +1,68 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef NAV_CORE2_BASIC_COSTMAP_H +#define NAV_CORE2_BASIC_COSTMAP_H + +#include +#include +#include + +namespace nav_core2 +{ +class BasicCostmap : public nav_core2::Costmap +{ +public: + // Standard Costmap Interface + mutex_t* getMutex() override { return &my_mutex_; } + + // NavGrid Interface + void reset() override; + void setValue(const unsigned int x, const unsigned int y, const unsigned char& value) override; + unsigned char getValue(const unsigned int x, const unsigned int y) const override; + void setInfo(const nav_grid::NavGridInfo& new_info) override + { + info_ = new_info; + reset(); + } + + // Index Conversion + unsigned int getIndex(const unsigned int x, const unsigned int y) const; +protected: + mutex_t my_mutex_; + std::vector data_; +}; +} // namespace nav_core2 + +#endif // NAV_CORE2_BASIC_COSTMAP_H diff --git a/navigations/nav_core2/include/nav_core2/bounds.h b/navigations/nav_core2/include/nav_core2/bounds.h new file mode 100755 index 0000000..c3fcbaf --- /dev/null +++ b/navigations/nav_core2/include/nav_core2/bounds.h @@ -0,0 +1,209 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef NAV_CORE2_BOUNDS_H +#define NAV_CORE2_BOUNDS_H + +#include +#include +#include + +namespace nav_core2 +{ +/** + * @brief Templatized method for checking if a value falls inside a one-dimensional range + * @param value The value to check + * @param min_value The minimum value of the range + * @param max_value The maximum value of the range + * @return True if the value is within the range + */ +template +inline bool inRange(const NumericType value, const NumericType min_value, const NumericType max_value) +{ + return min_value <= value && value <= max_value; +} + +/** + * @class GenericBounds + * @brief Templatized class that represents a two dimensional bounds with ranges [min_x, max_x] [min_y, max_y] inclusive + */ +template +struct GenericBounds +{ +public: + /** + * @brief Constructor for an empty bounds + */ + GenericBounds() + { + reset(); + } + + /** + * @brief Constructor for a non-empty initial bounds + * @param x0 Initial min x + * @param y0 Initial min y + * @param x1 Initial max x + * @param y1 Initial max y + */ + GenericBounds(NumericType x0, NumericType y0, NumericType x1, NumericType y1) + : min_x_(x0), min_y_(y0), max_x_(x1), max_y_(y1) {} + + /** + * @brief Reset the bounds to be empty + */ + void reset() + { + min_x_ = min_y_ = std::numeric_limits::max(); + max_x_ = max_y_ = std::numeric_limits::lowest(); // -max + } + + /** + * @brief Update the bounds to include the point (x, y) + */ + void touch(NumericType x, NumericType y) + { + min_x_ = std::min(x, min_x_); + min_y_ = std::min(y, min_y_); + max_x_ = std::max(x, max_x_); + max_y_ = std::max(y, max_y_); + } + + /** + * @brief Update the bounds to include points (x0, y0) and (x1, y1) + * @param x0 smaller of two x values + * @param y0 smaller of two y values + * @param x1 larger of two x values + * @param y1 larger of two y values + */ + void update(NumericType x0, NumericType y0, NumericType x1, NumericType y1) + { + min_x_ = std::min(x0, min_x_); + min_y_ = std::min(y0, min_y_); + max_x_ = std::max(x1, max_x_); + max_y_ = std::max(y1, max_y_); + } + + /** + * @brief Update the bounds to include the entirety of another bounds object + * @param other Another bounds object + */ + void merge(const GenericBounds& other) + { + update(other.min_x_, other.min_y_, other.max_x_, other.max_y_); + } + + /** + * @brief Returns true if the range is empty + */ + bool isEmpty() const + { + return min_x_ > max_x_ && min_y_ > max_y_; + } + + /** + * @brief Returns true if the point is inside this range + */ + bool contains(NumericType x, NumericType y) const + { + return inRange(x, min_x_, max_x_) && inRange(y, min_y_, max_y_); + } + + /** + * @brief returns true if the two bounds overlap each other + */ + bool overlaps(const GenericBounds& other) const + { + return !isEmpty() && !other.isEmpty() + && max_y_ >= other.min_y_ && min_y_ <= other.max_y_ + && max_x_ >= other.min_x_ && min_x_ <= other.max_x_; + } + + /** + * @brief comparison operator that requires all fields are equal + */ + bool operator==(const GenericBounds& other) const + { + return min_x_ == other.min_x_ && min_y_ == other.min_y_ && + max_x_ == other.max_x_ && max_y_ == other.max_y_; + } + + bool operator!=(const GenericBounds& other) const + { + return !operator==(other); + } + + /** + * @brief Returns a string representation of the bounds + */ + std::string toString() const + { + if (!isEmpty()) + { + return "(" + std::to_string(min_x_) + "," + std::to_string(min_y_) + "):(" + + std::to_string(max_x_) + "," + std::to_string(max_y_) + ")"; + } + else + { + return "(empty bounds)"; + } + } + + NumericType getMinX() const { return min_x_; } + NumericType getMinY() const { return min_y_; } + NumericType getMaxX() const { return max_x_; } + NumericType getMaxY() const { return max_y_; } + +protected: + NumericType min_x_, min_y_, max_x_, max_y_; +}; + +using Bounds = GenericBounds; + +inline unsigned int getDimension(unsigned int min_v, unsigned int max_v) +{ + return (min_v > max_v) ? 0 : max_v - min_v + 1; +} + +class UIntBounds : public GenericBounds +{ +public: + using GenericBounds::GenericBounds; + unsigned int getWidth() const { return getDimension(min_x_, max_x_); } + unsigned int getHeight() const { return getDimension(min_y_, max_y_); } +}; + +} // namespace nav_core2 + +#endif // NAV_CORE2_BOUNDS_H diff --git a/navigations/nav_core2/include/nav_core2/common.h b/navigations/nav_core2/include/nav_core2/common.h new file mode 100755 index 0000000..9391892 --- /dev/null +++ b/navigations/nav_core2/include/nav_core2/common.h @@ -0,0 +1,42 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ +#ifndef NAV_CORE2_COMMON_H +#define NAV_CORE2_COMMON_H + +#include +#include + +using TFListenerPtr = std::shared_ptr; + +#endif // NAV_CORE2_COMMON_H diff --git a/navigations/nav_core2/include/nav_core2/costmap.h b/navigations/nav_core2/include/nav_core2/costmap.h new file mode 100755 index 0000000..bbae720 --- /dev/null +++ b/navigations/nav_core2/include/nav_core2/costmap.h @@ -0,0 +1,156 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef NAV_CORE2_COSTMAP_H +#define NAV_CORE2_COSTMAP_H + +#include +#include +#include +#include +#include +#include + +namespace nav_core2 +{ + +class Costmap : public nav_grid::NavGrid +{ +public: + static const unsigned char NO_INFORMATION = 255; + static const unsigned char LETHAL_OBSTACLE = 254; + static const unsigned char INSCRIBED_INFLATED_OBSTACLE = 253; + static const unsigned char FREE_SPACE = 0; + + using Ptr = std::shared_ptr; + + /** + * @brief Virtual Destructor + */ + virtual ~Costmap() {} + + /** + * @brief Initialization function for the Costmap + * + * ROS parameters/topics are expected to be in the parent/name namespace. + * It is suggested that all NodeHandles in the costmap use the parent NodeHandle's callback queue. + * + * @param parent NodeHandle to derive other NodeHandles from + * @param name The namespace for the costmap + * @param tf A pointer to a transform listener + */ + virtual void initialize(const ros::NodeHandle& parent, const std::string& name, TFListenerPtr tf) {} + + inline unsigned char getCost(const unsigned int x, const unsigned int y) + { + return getValue(x, y); + } + + inline unsigned char getCost(const nav_grid::Index& index) + { + return getValue(index.x, index.y); + } + + inline void setCost(const unsigned int x, const unsigned int y, const unsigned char cost) + { + setValue(x, y, cost); + } + + inline void setCost(const nav_grid::Index& index, const unsigned char cost) + { + setValue(index, cost); + } + + /** + * @brief Update the values in the costmap + * + * Note that this method can throw CostmapExceptions to indicate problems, like when it would be unsafe to navigate. + * e.g. If the costmap expects laser data at a given rate, but laser data hasn't shown up in a while, this method + * might throw a CostmapDataLagException. + */ + virtual void update() {} + + using mutex_t = boost::recursive_mutex; + /** + * @brief Accessor for boost mutex + */ + virtual mutex_t* getMutex() = 0; + + /** + * @brief Flag to indicate whether this costmap is able to track how much has changed + */ + virtual bool canTrackChanges() { return false; } + + /** + * @brief If canTrackChanges, get the bounding box for how much of the costmap has changed + * + * Rather than querying based on time stamps (which can require an arbitrary amount of storage) + * we instead query based on a namespace. The return bounding box reports how much of the costmap + * has changed since the last time this method was called with a particular namespace. If a namespace + * is new, then it returns a bounding box for the whole costmap. The max values are inclusive. + * + * Example Sequence with a 5x5 costmap: (results listed (min_x,min_y):(max_x, max_y)) + * 0) getChangeBounds("A") --> (0,0):(4,4) + * 1) getChangeBounds("B") --> (0,0):(4,4) + * 2) update cell 1, 1 + * 3) getChangeBounds("C") --> (0,0):(4,4) + * 4) getChangeBounds("A") --> (1,1):(1,1) + * 5) getChangeBounds("A") --> (empty bounds) (i.e. nothing was updated since last call) + * 6) updateCell 2, 4 + * 7) getChangeBounds("A") --> (2,4):(2,4) + * 8) getChangeBounds("B") --> (1,1):(2,4) + * + * @param ns The namespace + * @return Updated bounds + * @throws std::runtime_error If canTrackChanges is false, the returned bounds would be meaningless + */ + virtual UIntBounds getChangeBounds(const std::string& ns) + { + if (!canTrackChanges()) + { + throw std::runtime_error("You called 'getChangeBounds()' on a derived Costmap type that is not capable of " + "tracking changes (i.e. canTrackChanges() returns false). You shouldn't do that."); + } + else + { + throw std::runtime_error("You called 'getChangeBounds()' on a derived Costmap type that is capable of tracking " + "changes but has not properly implemented this function. You should yell at the author " + "of the derived Costmap."); + } + return UIntBounds(); + } +}; +} // namespace nav_core2 + +#endif // NAV_CORE2_COSTMAP_H diff --git a/navigations/nav_core2/include/nav_core2/exceptions.h b/navigations/nav_core2/include/nav_core2/exceptions.h new file mode 100755 index 0000000..df01ac3 --- /dev/null +++ b/navigations/nav_core2/include/nav_core2/exceptions.h @@ -0,0 +1,321 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ +#ifndef NAV_CORE2_EXCEPTIONS_H +#define NAV_CORE2_EXCEPTIONS_H + +#include +#include +#include +#include +#include + +/************************************************** + * The nav_core2 Planning Exception Hierarchy!! + * (with arbitrary integer result codes) + ************************************************** + * NavCore2Exception + * 0 CostmapException + * 1 CostmapSafetyException + * 2 CostmapDataLagException + * 3 PlannerException + * 4 GlobalPlannerException + * 5 InvalidStartPoseException + * 6 StartBoundsException + * 7 OccupiedStartException + * 8 InvalidGoalPoseException + * 9 GoalBoundsException + * 10 OccupiedGoalException + * 11 NoGlobalPathException + * 12 GlobalPlannerTimeoutException + * 13 LocalPlannerException + * 14 IllegalTrajectoryException + * 15 NoLegalTrajectoriesException + * 16 PlannerTFException + * + * -1 Unknown + **************************************************/ + +namespace nav_core2 +{ + +inline std::string poseToString(const nav_2d_msgs::Pose2DStamped& pose) +{ + return "(" + std::to_string(pose.pose.x) + ", " + std::to_string(pose.pose.y) + ", " + std::to_string(pose.pose.theta) + + " : " + pose.header.frame_id + ")"; +} + +class NavCore2Exception: public std::runtime_error +{ +public: + explicit NavCore2Exception(const std::string& description, int result_code) + : std::runtime_error(description), result_code_(result_code) {} + int getResultCode() const { return result_code_; } +protected: + int result_code_; +}; + +using NavCore2ExceptionPtr = std::exception_ptr; + +/** + * @brief Handy function for getting the result code + */ +inline int getResultCode(const NavCore2ExceptionPtr& e_ptr) +{ + if (e_ptr == nullptr) + { + return -1; + } + try + { + std::rethrow_exception(e_ptr); + } + catch (const NavCore2Exception& e) + { + return e.getResultCode(); + } + catch (...) + { + // Will end up here if current_exception returned a non-NavCore2Exception + return -1; + } +} + +/** + * @class CostmapException + * @brief Extensible exception class for all costmap-related problems + */ +class CostmapException: public NavCore2Exception +{ +public: + explicit CostmapException(const std::string& description, int result_code = 0) + : NavCore2Exception(description, result_code) {} +}; + +/** + * @class CostmapSafetyException + * @brief General container for exceptions thrown when the costmap thinks any movement would be unsafe + */ +class CostmapSafetyException: public CostmapException +{ +public: + explicit CostmapSafetyException(const std::string& description, int result_code = 1) + : CostmapException(description, result_code) {} +}; + +/** + * @class CostmapDataLagException + * @brief Indicates costmap is out of date because data in not up to date. + * + * Functions similarly to `!Costmap2DROS::isCurrent()` + */ +class CostmapDataLagException: public CostmapSafetyException +{ +public: + explicit CostmapDataLagException(const std::string& description, int result_code = 2) + : CostmapSafetyException(description, result_code) {} +}; + +/** + * @class PlannerException + * @brief Parent type of all exceptions defined within + */ +class PlannerException: public NavCore2Exception +{ +public: + explicit PlannerException(const std::string& description, int result_code = 3) + : NavCore2Exception(description, result_code) {} +}; + +/** + * @class GlobalPlannerException + * @brief General container for exceptions thrown from the Global Planner + */ +class GlobalPlannerException: public PlannerException +{ +public: + explicit GlobalPlannerException(const std::string& description, int result_code = 4) + : PlannerException(description, result_code) {} +}; + +/** + * @class LocalPlannerException + * @brief General container for exceptions thrown from the Local Planner + */ +class LocalPlannerException: public PlannerException +{ +public: + explicit LocalPlannerException(const std::string& description, int result_code = 13) + : PlannerException(description, result_code) {} +}; + +/** + * @class PlannerTFException + * @brief Thrown when either the global or local planner cannot complete its operation due to TF errors + */ +class PlannerTFException: public PlannerException +{ +public: + explicit PlannerTFException(const std::string& description, int result_code = 16) + : PlannerException(description, result_code) {} +}; + +/** + * @class InvalidStartPoseException + * @brief Exception thrown when there is a problem at the start location for the global planner + */ +class InvalidStartPoseException: public GlobalPlannerException +{ +public: + explicit InvalidStartPoseException(const std::string& description, int result_code = 5) + : GlobalPlannerException(description, result_code) {} + InvalidStartPoseException(const nav_2d_msgs::Pose2DStamped& pose, const std::string& problem, int result_code = 5) : + InvalidStartPoseException("The starting pose " + poseToString(pose) + " is " + problem, result_code) {} +}; + +/** + * @class StartBoundsException + * @brief Exception thrown when the start location of the global planner is out of the expected bounds + */ +class StartBoundsException: public InvalidStartPoseException +{ +public: + explicit StartBoundsException(const std::string& description, int result_code = 6) + : InvalidStartPoseException(description, result_code) {} + explicit StartBoundsException(const nav_2d_msgs::Pose2DStamped& pose) : + InvalidStartPoseException(pose, "out of bounds", 6) {} +}; + +/** + * @class OccupiedStartException + * @brief Exception thrown when the start location of the global planner is occupied in the costmap + */ +class OccupiedStartException: public InvalidStartPoseException +{ +public: + explicit OccupiedStartException(const std::string& description, int result_code = 7) + : InvalidStartPoseException(description, result_code) {} + explicit OccupiedStartException(const nav_2d_msgs::Pose2DStamped& pose) : + InvalidStartPoseException(pose, "occupied", 7) {} +}; + +/** + * @class InvalidGoalPoseException + * @brief Exception thrown when there is a problem at the goal location for the global planner + */ +class InvalidGoalPoseException: public GlobalPlannerException +{ +public: + explicit InvalidGoalPoseException(const std::string& description, int result_code = 8) + : GlobalPlannerException(description, result_code) {} + InvalidGoalPoseException(const nav_2d_msgs::Pose2DStamped& pose, const std::string& problem, int result_code = 8) : + GlobalPlannerException("The goal pose " + poseToString(pose) + " is " + problem, result_code) {} +}; + +/** + * @class GoalBoundsException + * @brief Exception thrown when the goal location of the global planner is out of the expected bounds + */ +class GoalBoundsException: public InvalidGoalPoseException +{ +public: + explicit GoalBoundsException(const std::string& description, int result_code = 9) + : InvalidGoalPoseException(description, result_code) {} + explicit GoalBoundsException(const nav_2d_msgs::Pose2DStamped& pose) : + InvalidGoalPoseException(pose, "out of bounds", 9) {} +}; + +/** + * @class OccupiedGoalException + * @brief Exception thrown when the goal location of the global planner is occupied in the costmap + */ +class OccupiedGoalException: public InvalidGoalPoseException +{ +public: + explicit OccupiedGoalException(const std::string& description, int result_code = 10) + : InvalidGoalPoseException(description, result_code) {} + explicit OccupiedGoalException(const nav_2d_msgs::Pose2DStamped& pose) : + InvalidGoalPoseException(pose, "occupied", 10) {} +}; + +/** + * @class NoGlobalPathException + * @brief Exception thrown when the global planner cannot find a path from the start to the goal + */ +class NoGlobalPathException: public GlobalPlannerException +{ +public: + explicit NoGlobalPathException(const std::string& description, int result_code = 11) + : GlobalPlannerException(description, result_code) {} + NoGlobalPathException() : GlobalPlannerException("No global path found.") {} +}; + +/** + * @class GlobalPlannerTimeoutException + * @brief Exception thrown when the global planner has spent too long looking for a path + */ +class GlobalPlannerTimeoutException: public GlobalPlannerException +{ +public: + explicit GlobalPlannerTimeoutException(const std::string& description, int result_code = 12) + : GlobalPlannerException(description, result_code) {} +}; + +/** + * @class IllegalTrajectoryException + * @brief Thrown when one of the critics encountered a fatal error + */ +class IllegalTrajectoryException: public LocalPlannerException +{ +public: + IllegalTrajectoryException(const std::string& critic_name, const std::string& description, int result_code = 14) + : LocalPlannerException(description, result_code), critic_name_(critic_name) {} + std::string getCriticName() const { return critic_name_; } +protected: + std::string critic_name_; +}; + +/** + * @class NoLegalTrajectoriesException + * @brief Thrown when all the trajectories explored are illegal + */ +class NoLegalTrajectoriesException: public LocalPlannerException +{ +public: + explicit NoLegalTrajectoriesException(const std::string& description, int result_code = 15) + : LocalPlannerException(description, result_code) {} +}; + +} // namespace nav_core2 + +#endif // NAV_CORE2_EXCEPTIONS_H diff --git a/navigations/nav_core2/include/nav_core2/global_planner.h b/navigations/nav_core2/include/nav_core2/global_planner.h new file mode 100755 index 0000000..9eb548c --- /dev/null +++ b/navigations/nav_core2/include/nav_core2/global_planner.h @@ -0,0 +1,83 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ +#ifndef NAV_CORE2_GLOBAL_PLANNER_H +#define NAV_CORE2_GLOBAL_PLANNER_H + +#include +#include +#include +#include +#include + +namespace nav_core2 +{ + +/** + * @class GlobalPlanner + * @brief Provides an interface for global planners used in navigation. + */ +class GlobalPlanner +{ +public: + /** + * @brief Virtual Destructor + */ + virtual ~GlobalPlanner() {} + + /** + * @brief Initialization function for the GlobalPlanner + * + * ROS parameters/topics are expected to be in the parent/name namespace. + * It is suggested that all NodeHandles in the planner use the parent NodeHandle's callback queue. + * + * @param parent NodeHandle to derive other NodeHandles from + * @param name The name of this planner + * @param tf A pointer to a transform listener + * @param costmap A pointer to the costmap + */ + virtual void initialize(const ros::NodeHandle& parent, const std::string& name, + TFListenerPtr tf, Costmap::Ptr costmap) = 0; + + /** + * @brief Run the global planner to make a plan starting at the start and ending at the goal. + * @param start The starting pose of the robot + * @param goal The goal pose of the robot + * @return The sequence of poses to get from start to goal, if any + */ + virtual nav_2d_msgs::Path2D makePlan(const nav_2d_msgs::Pose2DStamped& start, + const nav_2d_msgs::Pose2DStamped& goal) = 0; +}; +} // namespace nav_core2 + +#endif // NAV_CORE2_GLOBAL_PLANNER_H diff --git a/navigations/nav_core2/include/nav_core2/local_planner.h b/navigations/nav_core2/include/nav_core2/local_planner.h new file mode 100755 index 0000000..be2329a --- /dev/null +++ b/navigations/nav_core2/include/nav_core2/local_planner.h @@ -0,0 +1,113 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ +#ifndef NAV_CORE2_LOCAL_PLANNER_H +#define NAV_CORE2_LOCAL_PLANNER_H + +#include +#include +#include +#include +#include +#include +#include + +namespace nav_core2 +{ + +/** + * @class LocalPlanner + * @brief Provides an interface for local planners used in navigation. + */ +class LocalPlanner +{ +public: + /** + * @brief Virtual Destructor + */ + virtual ~LocalPlanner() {} + + /** + * @brief Constructs the local planner + * + * ROS parameters/topics are expected to be in the parent/name namespace. + * It is suggested that all NodeHandles in the planner use the parent NodeHandle's callback queue. + * + * @param parent NodeHandle to derive other NodeHandles from + * @param name The name to give this instance of the local planner + * @param tf A pointer to a transform listener + * @param costmap A pointer to the costmap + */ + virtual void initialize(const ros::NodeHandle& parent, const std::string& name, + TFListenerPtr tf, Costmap::Ptr costmap) = 0; + + /** + * @brief Sets the global goal for this local planner. + * @param goal_pose The Goal Pose + */ + virtual void setGoalPose(const nav_2d_msgs::Pose2DStamped& goal_pose) = 0; + + /** + * @brief Sets the global plan for this local planner. + * + * @param path The global plan + */ + virtual void setPlan(const nav_2d_msgs::Path2D& path) = 0; + + /** + * @brief Compute the best command given the current pose, velocity and goal + * + * Get the local plan, given an initial pose, velocity and goal pose. + * It is presumed that the global plan is already set. + * + * @param pose Current robot pose + * @param velocity Current robot velocity + * @return The best computed velocity + */ + virtual nav_2d_msgs::Twist2DStamped computeVelocityCommands(const nav_2d_msgs::Pose2DStamped& pose, + const nav_2d_msgs::Twist2D& velocity) = 0; + + /** + * @brief Check to see whether the robot has reached its goal + * + * This tests whether the robot has fully reached the goal, given the current pose and velocity. + * + * @param query_pose The pose to check, in local costmap coordinates. + * @param velocity Velocity to check + * @return True if the goal conditions have been met + */ + virtual bool isGoalReached(const nav_2d_msgs::Pose2DStamped& pose, const nav_2d_msgs::Twist2D& velocity) = 0; +}; +} // namespace nav_core2 + +#endif // NAV_CORE2_LOCAL_PLANNER_H diff --git a/navigations/nav_core2/package.xml b/navigations/nav_core2/package.xml new file mode 100755 index 0000000..71aae5c --- /dev/null +++ b/navigations/nav_core2/package.xml @@ -0,0 +1,17 @@ + + + nav_core2 + 0.3.0 + + Interfaces for Costmap, LocalPlanner and GlobalPlanner. Replaces nav_core. + + David V. Lu!! + BSD + + catkin + nav_2d_msgs + nav_grid + tf2_ros + roslint + rosunit + diff --git a/navigations/nav_core2/src/basic_costmap.cpp b/navigations/nav_core2/src/basic_costmap.cpp new file mode 100755 index 0000000..64a272a --- /dev/null +++ b/navigations/nav_core2/src/basic_costmap.cpp @@ -0,0 +1,60 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include + +namespace nav_core2 +{ + +void BasicCostmap::reset() +{ + data_.assign(info_.width * info_.height, this->default_value_); +} + +unsigned int BasicCostmap::getIndex(const unsigned int x, const unsigned int y) const +{ + return y * info_.width + x; +} + +unsigned char BasicCostmap::getValue(const unsigned int x, const unsigned int y) const +{ + return data_[getIndex(x, y)]; +} + +void BasicCostmap::setValue(const unsigned int x, const unsigned int y, const unsigned char& value) +{ + data_[getIndex(x, y)] = value; +} + +} // namespace nav_core2 diff --git a/navigations/nav_core2/test/bounds_test.cpp b/navigations/nav_core2/test/bounds_test.cpp new file mode 100755 index 0000000..c9f19fa --- /dev/null +++ b/navigations/nav_core2/test/bounds_test.cpp @@ -0,0 +1,124 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ +#include +#include + +using nav_core2::Bounds; +using nav_core2::UIntBounds; + +TEST(Bounds, test_bounds_simple) +{ + Bounds b; + EXPECT_TRUE(b.isEmpty()); + + b.touch(5.0, 6.0); + EXPECT_EQ(5.0, b.getMinX()); + EXPECT_EQ(5.0, b.getMinX()); + EXPECT_EQ(5.0, b.getMaxX()); + EXPECT_EQ(6.0, b.getMinY()); + EXPECT_EQ(6.0, b.getMaxY()); + EXPECT_TRUE(b.contains(5.0, 6.0)); + EXPECT_FALSE(b.contains(5.5, 6.0)); + EXPECT_FALSE(b.contains(5.5, 4.0)); + EXPECT_FALSE(b.isEmpty()); + + Bounds b2 = b; + EXPECT_EQ(5.0, b2.getMinX()); + EXPECT_EQ(5.0, b2.getMaxX()); + EXPECT_EQ(6.0, b2.getMinY()); + EXPECT_EQ(6.0, b2.getMaxY()); + + b.reset(); + EXPECT_EQ(5.0, b2.getMinX()); + EXPECT_EQ(5.0, b2.getMaxX()); + EXPECT_EQ(6.0, b2.getMinY()); + EXPECT_EQ(6.0, b2.getMaxY()); + EXPECT_FALSE(b.contains(5.0, 6.0)); + EXPECT_FALSE(b.contains(5.5, 6.0)); + EXPECT_TRUE(b2.contains(5.0, 6.0)); + EXPECT_FALSE(b.contains(5.5, 6.0)); + EXPECT_TRUE(b.isEmpty()); + + Bounds b3; + b3.touch(1.0, 5.0); + b3.touch(4.0, 2.0); + EXPECT_TRUE(b3.contains(3.0, 3.0)); + EXPECT_FALSE(b3.contains(0.0, 3.0)); + EXPECT_FALSE(b3.contains(5.0, 3.0)); + EXPECT_FALSE(b3.contains(3.0, 6.0)); + EXPECT_FALSE(b3.contains(3.0, 1.0)); +} + +TEST(Bounds, test_dimensions) +{ + UIntBounds empty; + UIntBounds square(0, 0, 5, 5); + UIntBounds rectangle(1, 4, 3, 15); + EXPECT_EQ(empty.getWidth(), 0u); + EXPECT_EQ(empty.getHeight(), 0u); + + EXPECT_EQ(square.getWidth(), 6u); + EXPECT_EQ(square.getHeight(), 6u); + + EXPECT_EQ(rectangle.getWidth(), 3u); + EXPECT_EQ(rectangle.getHeight(), 12u); +} + +TEST(Bounds, test_bounds_overlap) +{ + UIntBounds b0(0, 0, 5, 5); + UIntBounds b1(0, 0, 5, 5); + UIntBounds b2(0, 0, 3, 3); + UIntBounds b3(3, 0, 4, 4); + UIntBounds b4(4, 0, 4, 4); + UIntBounds b5(1, 4, 3, 15); + UIntBounds b6(10, 10, 10, 10); + EXPECT_TRUE(b0.overlaps(b0)); + EXPECT_TRUE(b0.overlaps(b1)); + EXPECT_TRUE(b0.overlaps(b2)); + EXPECT_TRUE(b2.overlaps(b0)); + EXPECT_TRUE(b0.overlaps(b3)); + EXPECT_TRUE(b2.overlaps(b3)); + EXPECT_FALSE(b2.overlaps(b4)); + EXPECT_TRUE(b0.overlaps(b5)); + EXPECT_TRUE(b5.overlaps(b0)); + EXPECT_FALSE(b0.overlaps(b6)); + EXPECT_FALSE(b6.overlaps(b0)); +} + +int main(int argc, char **argv) +{ + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/navigations/nav_core2/test/exception_test.cpp b/navigations/nav_core2/test/exception_test.cpp new file mode 100755 index 0000000..26c3ef2 --- /dev/null +++ b/navigations/nav_core2/test/exception_test.cpp @@ -0,0 +1,133 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2019, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ +#include +#include +#include + +TEST(Exceptions, direct_code_access) +{ + // Make sure the caught exceptions have the same types as the thrown exception + // (This version does not create any copies of the exception) + try + { + throw nav_core2::GlobalPlannerTimeoutException("test case"); + } + catch (nav_core2::GlobalPlannerTimeoutException& x) + { + EXPECT_EQ(x.getResultCode(), 12); + } + + try + { + throw nav_core2::GlobalPlannerTimeoutException("test case"); + } + catch (nav_core2::PlannerException& x) + { + EXPECT_EQ(x.getResultCode(), 12); + } +} + +TEST(Exceptions, indirect_code_access) +{ + // Make sure the caught exceptions have the same types as the thrown exception + // (This version copies the exception to a new object with the parent type) + nav_core2::PlannerException e(""); + try + { + throw nav_core2::GlobalPlannerTimeoutException("test case"); + } + catch (nav_core2::GlobalPlannerTimeoutException& x) + { + e = x; + } + EXPECT_EQ(e.getResultCode(), 12); +} + +TEST(Exceptions, rethrow) +{ + // This version tests the ability to catch specific exceptions when rethrown + // A copy of the exception is made and rethrown, with the goal being able to catch the specific type + // and not the parent type. + nav_core2::NavCore2ExceptionPtr e; + try + { + throw nav_core2::GlobalPlannerTimeoutException("test case"); + } + catch (nav_core2::GlobalPlannerTimeoutException& x) + { + e = std::current_exception(); + } + + EXPECT_EQ(nav_core2::getResultCode(e), 12); + + try + { + std::rethrow_exception(e); + } + catch (nav_core2::GlobalPlannerTimeoutException& x) + { + EXPECT_EQ(x.getResultCode(), 12); + SUCCEED(); + } + catch (nav_core2::PlannerException& x) + { + FAIL() << "PlannerException caught instead of specific exception"; + } +} + +TEST(Exceptions, weird_exception) +{ + nav_core2::NavCore2ExceptionPtr e; + + // Check what happens with no exception + EXPECT_EQ(nav_core2::getResultCode(e), -1); + + // Check what happens with a non NavCore2Exception + try + { + std::string().at(1); // this generates an std::out_of_range + } + catch (...) + { + e = std::current_exception(); + } + + EXPECT_EQ(nav_core2::getResultCode(e), -1); +} + +int main(int argc, char **argv) +{ + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/navigations/nav_core_adapter/CMakeLists.txt b/navigations/nav_core_adapter/CMakeLists.txt new file mode 100755 index 0000000..0024a37 --- /dev/null +++ b/navigations/nav_core_adapter/CMakeLists.txt @@ -0,0 +1,76 @@ +cmake_minimum_required(VERSION 3.0.2) +project(nav_core_adapter) + +set_directory_properties(PROPERTIES COMPILE_OPTIONS "-std=c++11;-Wall;-Werror") + +find_package(catkin REQUIRED COMPONENTS + costmap_2d + geometry_msgs + nav_2d_msgs + nav_2d_utils + nav_core + nav_core2 + nav_grid + nav_msgs + pluginlib + tf + visualization_msgs +) + +catkin_package( + CATKIN_DEPENDS + costmap_2d + geometry_msgs + nav_2d_msgs + nav_2d_utils + nav_core + nav_core2 + nav_grid + nav_msgs + pluginlib + tf + visualization_msgs + INCLUDE_DIRS include + LIBRARIES local_planner_adapter global_planner_adapter costmap_adapter global_planner_adapter2 +) + +add_library(costmap_adapter src/costmap_adapter.cpp) +target_link_libraries(costmap_adapter ${catkin_LIBRARIES}) + +add_library(local_planner_adapter src/local_planner_adapter.cpp) +add_dependencies(local_planner_adapter ${catkin_EXPORTED_TARGETS}) +target_link_libraries(local_planner_adapter costmap_adapter ${catkin_LIBRARIES}) + +add_library(global_planner_adapter src/global_planner_adapter.cpp) +add_dependencies(global_planner_adapter ${catkin_EXPORTED_TARGETS}) +target_link_libraries(global_planner_adapter costmap_adapter ${catkin_LIBRARIES}) + +add_library(global_planner_adapter2 src/global_planner_adapter2.cpp) +add_dependencies(global_planner_adapter2 ${catkin_EXPORTED_TARGETS}) +target_link_libraries(global_planner_adapter2 ${catkin_LIBRARIES}) + +include_directories( + include ${catkin_INCLUDE_DIRS} +) + +if(CATKIN_ENABLE_TESTING) + find_package(rostest REQUIRED) + find_package(roslint REQUIRED) + roslint_cpp() + roslint_add_test() + + add_rostest_gtest(unload_test test/unload_test.launch test/unload_test.cpp) + target_link_libraries(unload_test local_planner_adapter ${catkin_LIBRARIES} ${GTEST_LIBRARIES}) +endif() + +install(TARGETS local_planner_adapter global_planner_adapter costmap_adapter global_planner_adapter2 + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} +) +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} +) +install(FILES nav_core2_plugins.xml nav_core_plugins.xml + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) diff --git a/navigations/nav_core_adapter/README.md b/navigations/nav_core_adapter/README.md new file mode 100755 index 0000000..38c067c --- /dev/null +++ b/navigations/nav_core_adapter/README.md @@ -0,0 +1,48 @@ +# nav_core_adapter +This package contains adapters for using `nav_core` plugins as `nav_core2` plugins and vice versa (more or less). In general, the adaptation process involves + * Converting between 2d and 3d datatypes. + * Converting between returning false and throwing exceptions on failure. + +We also provide an adapter for using a `costmap_2d::Costmap2DROS` as a plugin for the `nav_core2::Costmap` interface. + +## Adapter Classes + * Global Planner Adapters + * `GlobalPlannerAdapter` is used for employing a `nav_core2` global planner interface (such as `dlux_global_planner`) as a `nav_core` plugin, like in `move_base`. + * `GlobalPlannerAdapter2` is used for employing a `nav_core` global planner interface (such as `navfn`) +as a `nav_core2` plugin, like in `locomotor`. + * Local Planner Adapter + * `LocalPlannerAdapter` is used for employing a `nav_core2` local planner interface (such as `dwb_local_planner`) as a `nav_core` plugin, like in `move_base`. In addition to the standard adaptation steps listed above, the local planner adapter also uses the costmap to grab the global pose and subscribes to the odometry in order to get the current velocity. + * There is no `LocalPlannerAdapter2`. The `nav_core2` interfaces use additional information (like velocity) in the `local_planner` interface than its `nav_core` counterpart. This information would be ignored by a `nav_core` planner, so no adapter is provided. + * `CostmapAdapter` provides most of the functionality from `nav_core2::Costmap` and also provides a raw pointer to the `Costmap2DROS` object. It is not a perfect adaptation, because + * `Costmap2DROS` starts its own update thread and updates on its own schedule, so calling `update()` does not actually cause the costmap to update. It does update some of the metadata though. + * `setInfo` is not implemented. + +## Parameter Setup +Let's look at a practical example of how to use `dwb_local_planner` in `move_base`. + +If you were using `DWA` you would probably have parameters set up like this: +``` +base_local_planner: dwa_local_planner/DWALocalPlanner +DWALocalPlanner: + acc_lim_x: 0.42 + ... +``` +i.e. you specify + * The name of the planner + * A bunch of additional parameters within the planner's namespace + +To use the adapter, you have to provide additional information. +``` +base_local_planner: nav_core_adapter::LocalPlannerAdapter +LocalPlannerAdapter: + planner_name: dwb_local_planner::DWBLocalPlanner +DWBLocalPlanner: + acc_lim_x: 0.42 + ... +``` +i.e. + * The name of the planner now points at the adapter + * The name of the actual planner loaded into the adapter's namespace + * The planner's parameters still in the planner's namespace. + +The process for the global planners is similar. diff --git a/navigations/nav_core_adapter/include/nav_core_adapter/costmap_adapter.h b/navigations/nav_core_adapter/include/nav_core_adapter/costmap_adapter.h new file mode 100755 index 0000000..e5e7858 --- /dev/null +++ b/navigations/nav_core_adapter/include/nav_core_adapter/costmap_adapter.h @@ -0,0 +1,85 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef NAV_CORE_ADAPTER_COSTMAP_ADAPTER_H +#define NAV_CORE_ADAPTER_COSTMAP_ADAPTER_H + +#include +#include +#include +#include + +namespace nav_core_adapter +{ +nav_grid::NavGridInfo infoFromCostmap(costmap_2d::Costmap2DROS* costmap_ros); + +class CostmapAdapter : public nav_core2::Costmap +{ +public: + /** + * @brief Deconstructor for possibly freeing the costmap_ros_ object + */ + virtual ~CostmapAdapter(); + + /** + * @brief Initialize from an existing Costmap2DROS object + * @param costmap_ros A Costmap2DROS object + * @param needs_destruction Whether to free the costmap_ros object when this class is destroyed + */ + void initialize(costmap_2d::Costmap2DROS* costmap_ros, bool needs_destruction = false); + + // Standard Costmap Interface + void initialize(const ros::NodeHandle& parent, const std::string& name, TFListenerPtr tf) override; + nav_core2::Costmap::mutex_t* getMutex() override; + + // NavGrid Interface + void reset() override; + void update() override; + void setValue(const unsigned int x, const unsigned int y, const unsigned char& value) override; + unsigned char getValue(const unsigned int x, const unsigned int y) const override; + void setInfo(const nav_grid::NavGridInfo& new_info) override; + void updateInfo(const nav_grid::NavGridInfo& new_info) override; + + // Get Costmap Pointer for Backwards Compatibility + costmap_2d::Costmap2DROS* getCostmap2DROS() const { return costmap_ros_; } + +protected: + costmap_2d::Costmap2DROS* costmap_ros_; + costmap_2d::Costmap2D* costmap_; + bool needs_destruction_; +}; + +} // namespace nav_core_adapter + +#endif // NAV_CORE_ADAPTER_COSTMAP_ADAPTER_H diff --git a/navigations/nav_core_adapter/include/nav_core_adapter/global_planner_adapter.h b/navigations/nav_core_adapter/include/nav_core_adapter/global_planner_adapter.h new file mode 100755 index 0000000..5af07e2 --- /dev/null +++ b/navigations/nav_core_adapter/include/nav_core_adapter/global_planner_adapter.h @@ -0,0 +1,77 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef NAV_CORE_ADAPTER_GLOBAL_PLANNER_ADAPTER_H +#define NAV_CORE_ADAPTER_GLOBAL_PLANNER_ADAPTER_H + +#include +#include +#include +#include +#include +#include +#include + +namespace nav_core_adapter +{ + +/** + * @class GlobalPlannerAdapter + * @brief used for employing a `nav_core2` global planner interface as a `nav_core` plugin, like in `move_base`. + */ +class GlobalPlannerAdapter: public nav_core::BaseGlobalPlanner +{ +public: + GlobalPlannerAdapter(); + + // Standard ROS Global Planner Interface + void initialize(std::string name, costmap_2d::Costmap2DROS* costmap_ros) override; + bool makePlan(const geometry_msgs::PoseStamped& start, + const geometry_msgs::PoseStamped& goal, std::vector& plan) override; + +protected: + // Plugin handling + pluginlib::ClassLoader planner_loader_; + boost::shared_ptr planner_; + ros::Publisher path_pub_; + + TFListenerPtr tf_; + + std::shared_ptr costmap_adapter_; + costmap_2d::Costmap2DROS* costmap_ros_; +}; + +} // namespace nav_core_adapter + +#endif // NAV_CORE_ADAPTER_GLOBAL_PLANNER_ADAPTER_H diff --git a/navigations/nav_core_adapter/include/nav_core_adapter/global_planner_adapter2.h b/navigations/nav_core_adapter/include/nav_core_adapter/global_planner_adapter2.h new file mode 100755 index 0000000..18a05a9 --- /dev/null +++ b/navigations/nav_core_adapter/include/nav_core_adapter/global_planner_adapter2.h @@ -0,0 +1,73 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef NAV_CORE_ADAPTER_GLOBAL_PLANNER_ADAPTER2_H +#define NAV_CORE_ADAPTER_GLOBAL_PLANNER_ADAPTER2_H + +#include +#include +#include +#include +#include + +namespace nav_core_adapter +{ + +/** + * @class GlobalPlannerAdapter2 + * @brief used for employing a `nav_core` global planner (such as `navfn`) as a `nav_core2` plugin, like in `locomotor`. + */ +class GlobalPlannerAdapter2: public nav_core2::GlobalPlanner +{ +public: + GlobalPlannerAdapter2(); + + // Nav Core 2 Global Planner Interface + void initialize(const ros::NodeHandle& parent, const std::string& name, + TFListenerPtr tf, nav_core2::Costmap::Ptr costmap) override; + nav_2d_msgs::Path2D makePlan(const nav_2d_msgs::Pose2DStamped& start, + const nav_2d_msgs::Pose2DStamped& goal) override; + +protected: + // Plugin handling + pluginlib::ClassLoader planner_loader_; + boost::shared_ptr planner_; + + costmap_2d::Costmap2DROS* costmap_ros_; + nav_core2::Costmap::Ptr costmap_; +}; + +} // namespace nav_core_adapter + +#endif // NAV_CORE_ADAPTER_GLOBAL_PLANNER_ADAPTER2_H diff --git a/navigations/nav_core_adapter/include/nav_core_adapter/local_planner_adapter.h b/navigations/nav_core_adapter/include/nav_core_adapter/local_planner_adapter.h new file mode 100755 index 0000000..05e11f7 --- /dev/null +++ b/navigations/nav_core_adapter/include/nav_core_adapter/local_planner_adapter.h @@ -0,0 +1,99 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef NAV_CORE_ADAPTER_LOCAL_PLANNER_ADAPTER_H +#define NAV_CORE_ADAPTER_LOCAL_PLANNER_ADAPTER_H + +#include +#include +#include +#include +#include +#include +#include +#include + +namespace nav_core_adapter +{ + +/** + * @class LocalPlannerAdapter + * @brief used for employing a nav_core2 local planner (such as dwb) as a nav_core plugin, like in move_base. + */ +class LocalPlannerAdapter: public nav_core::BaseLocalPlanner +{ +public: + LocalPlannerAdapter(); + + // Standard ROS Local Planner Interface + void initialize(std::string name, tf2_ros::Buffer* tf, costmap_2d::Costmap2DROS* costmap_ros) override; + bool computeVelocityCommands(geometry_msgs::Twist& cmd_vel) override; + bool isGoalReached() override; + bool setPlan(const std::vector& plan) override; + +protected: + /** + * @brief Get the robot pose from the costmap and store as Pose2DStamped + */ + bool getRobotPose(nav_2d_msgs::Pose2DStamped& pose2d); + + /** + * @brief See if the back of the global plan matches the most recent goal pose + * @return True if the plan has changed + */ + bool hasGoalChanged(const nav_2d_msgs::Pose2DStamped& new_goal); + + // The most recent goal pose + nav_2d_msgs::Pose2DStamped last_goal_; + bool has_active_goal_; + + /** + * @brief helper class for subscribing to odometry + */ + std::shared_ptr odom_sub_; + + // Plugin handling + pluginlib::ClassLoader planner_loader_; + boost::shared_ptr planner_; + + // Pointer Copies + TFListenerPtr tf_; + + std::shared_ptr costmap_adapter_; + costmap_2d::Costmap2DROS* costmap_ros_; +}; + +} // namespace nav_core_adapter + +#endif // NAV_CORE_ADAPTER_LOCAL_PLANNER_ADAPTER_H diff --git a/navigations/nav_core_adapter/include/nav_core_adapter/shared_pointers.h b/navigations/nav_core_adapter/include/nav_core_adapter/shared_pointers.h new file mode 100755 index 0000000..d7b4d52 --- /dev/null +++ b/navigations/nav_core_adapter/include/nav_core_adapter/shared_pointers.h @@ -0,0 +1,67 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef NAV_CORE_ADAPTER_SHARED_POINTERS_H +#define NAV_CORE_ADAPTER_SHARED_POINTERS_H + +#include +#include + +namespace nav_core_adapter +{ + +template +void null_deleter(T* raw_ptr) {} + +/** + * @brief Custom Constructor for creating a shared pointer to an existing object that doesn't delete the ptr when done + * + * @note This is considered bad form, and is only done here for backwards compatibility purposes. The nav_core2 + * interfaces require shared pointers, but the creation of the shared pointer from a raw pointer takes ownership + * of the object such that when the object containing the shared pointer is freed, the object pointed at by the + * shared pointer is also freed. This presents a problem, for instance, when switching from one planner to another + * if the costmap is freed by one planner. + * + * @param raw_ptr The raw pointer to an object + * @return A Shared pointer pointing at the raw_ptr, but when it is freed, the raw_ptr remains valid + */ +template +std::shared_ptr createSharedPointerWithNoDelete(T* raw_ptr) +{ + return std::shared_ptr(raw_ptr, null_deleter); +} + +} // namespace nav_core_adapter + +#endif // NAV_CORE_ADAPTER_SHARED_POINTERS_H diff --git a/navigations/nav_core_adapter/nav_core2_plugins.xml b/navigations/nav_core_adapter/nav_core2_plugins.xml new file mode 100755 index 0000000..5b56e99 --- /dev/null +++ b/navigations/nav_core_adapter/nav_core2_plugins.xml @@ -0,0 +1,12 @@ + + + + + + + + + + + + diff --git a/navigations/nav_core_adapter/nav_core_plugins.xml b/navigations/nav_core_adapter/nav_core_plugins.xml new file mode 100755 index 0000000..a53cdb5 --- /dev/null +++ b/navigations/nav_core_adapter/nav_core_plugins.xml @@ -0,0 +1,12 @@ + + + + + + + + + + + + diff --git a/navigations/nav_core_adapter/package.xml b/navigations/nav_core_adapter/package.xml new file mode 100755 index 0000000..d6200ca --- /dev/null +++ b/navigations/nav_core_adapter/package.xml @@ -0,0 +1,38 @@ + + + nav_core_adapter + 0.3.0 + + This package contains adapters for using `nav_core` plugins as `nav_core2` plugins and vice versa (more or less). + See README.md for more information. + + + David V. Lu!! + + BSD + + catkin + costmap_2d + geometry_msgs + nav_2d_msgs + nav_2d_utils + nav_core + nav_core2 + nav_grid + nav_msgs + pluginlib + tf + visualization_msgs + roslint + rostest + + + dwb_local_planner + dwb_plugins + dwb_critics + + + + + + diff --git a/navigations/nav_core_adapter/src/costmap_adapter.cpp b/navigations/nav_core_adapter/src/costmap_adapter.cpp new file mode 100755 index 0000000..cbf5681 --- /dev/null +++ b/navigations/nav_core_adapter/src/costmap_adapter.cpp @@ -0,0 +1,117 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include +#include +#include + +PLUGINLIB_EXPORT_CLASS(nav_core_adapter::CostmapAdapter, nav_core2::Costmap) + +namespace nav_core_adapter +{ + +nav_grid::NavGridInfo infoFromCostmap(costmap_2d::Costmap2DROS* costmap_ros) +{ + nav_grid::NavGridInfo info; + costmap_2d::Costmap2D* costmap = costmap_ros->getCostmap(); + info.width = costmap->getSizeInCellsX(); + info.height = costmap->getSizeInCellsY(); + info.resolution = costmap->getResolution(); + info.frame_id = costmap_ros->getGlobalFrameID(); + info.origin_x = costmap->getOriginX(); + info.origin_y = costmap->getOriginY(); + return info; +} + +CostmapAdapter::~CostmapAdapter() +{ + if (needs_destruction_) + { + delete costmap_ros_; + } +} + +void CostmapAdapter::initialize(costmap_2d::Costmap2DROS* costmap_ros, bool needs_destruction) +{ + costmap_ros_ = costmap_ros; + needs_destruction_ = needs_destruction; + info_ = infoFromCostmap(costmap_ros_); + costmap_ = costmap_ros_->getCostmap(); +} + +void CostmapAdapter::initialize(const ros::NodeHandle& parent, const std::string& name, TFListenerPtr tf) +{ + initialize(new costmap_2d::Costmap2DROS(name, *tf), true); +} + +nav_core2::Costmap::mutex_t* CostmapAdapter::getMutex() +{ + return costmap_->getMutex(); +} + +void CostmapAdapter::reset() +{ + costmap_ros_->resetLayers(); +} + +void CostmapAdapter::update() +{ + info_ = infoFromCostmap(costmap_ros_); + if (!costmap_ros_->isCurrent()) + throw nav_core2::CostmapDataLagException("Costmap2DROS is out of date somehow."); +} + +void CostmapAdapter::setValue(const unsigned int x, const unsigned int y, const unsigned char& value) +{ + costmap_->setCost(x, y, value); +} + +unsigned char CostmapAdapter::getValue(const unsigned int x, const unsigned int y) const +{ + unsigned int index = costmap_->getIndex(x, y); + return costmap_->getCharMap()[index]; +} + +void CostmapAdapter::setInfo(const nav_grid::NavGridInfo& new_info) +{ + throw nav_core2::CostmapException("setInfo not implemented on CostmapAdapter"); +} + +void CostmapAdapter::updateInfo(const nav_grid::NavGridInfo& new_info) +{ + costmap_->updateOrigin(new_info.origin_x, new_info.origin_y); +} + +} // namespace nav_core_adapter diff --git a/navigations/nav_core_adapter/src/global_planner_adapter.cpp b/navigations/nav_core_adapter/src/global_planner_adapter.cpp new file mode 100755 index 0000000..06ba0c0 --- /dev/null +++ b/navigations/nav_core_adapter/src/global_planner_adapter.cpp @@ -0,0 +1,97 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +namespace nav_core_adapter +{ + +GlobalPlannerAdapter::GlobalPlannerAdapter() : + planner_loader_("nav_core2", "nav_core2::GlobalPlanner") +{ +} + +/** + * @brief Load the nav_core2 global planner and initialize it + */ +void GlobalPlannerAdapter::initialize(std::string name, costmap_2d::Costmap2DROS* costmap_ros) +{ + costmap_ros_ = costmap_ros; + costmap_adapter_ = std::make_shared(); + costmap_adapter_->initialize(costmap_ros); + + ros::NodeHandle private_nh("~"); + ros::NodeHandle adapter_nh("~/" + name); + std::string planner_name; + adapter_nh.param("planner_name", planner_name, std::string("dlux_global_planner::DluxGlobalPlanner")); + ROS_WARN("%s ,GlobalPlannerAdapter::initialize", name.c_str()); + ROS_INFO_NAMED("GlobalPlannerAdapter", "Loading plugin %s", planner_name.c_str()); + planner_ = planner_loader_.createInstance(planner_name); + planner_->initialize(private_nh, planner_loader_.getName(planner_name), tf_, costmap_adapter_); + path_pub_ = private_nh.advertise("plan", 1); +} + +bool GlobalPlannerAdapter::makePlan(const geometry_msgs::PoseStamped& start, + const geometry_msgs::PoseStamped& goal, + std::vector& plan) +{ + nav_2d_msgs::Pose2DStamped start2d = nav_2d_utils::poseStampedToPose2D(start), + goal2d = nav_2d_utils::poseStampedToPose2D(goal); + try + { + nav_2d_msgs::Path2D path2d = planner_->makePlan(start2d, goal2d); + nav_msgs::Path path = nav_2d_utils::pathToPath(path2d); + plan = path.poses; + path_pub_.publish(path); + return true; + } + catch (nav_core2::PlannerException& e) + { + ROS_ERROR_NAMED("GlobalPlannerAdapter", "makePlan Exception: %s", e.what()); + return false; + } +} +} // namespace nav_core_adapter + + +// register this planner as a BaseGlobalPlanner plugin +PLUGINLIB_EXPORT_CLASS(nav_core_adapter::GlobalPlannerAdapter, nav_core::BaseGlobalPlanner) diff --git a/navigations/nav_core_adapter/src/global_planner_adapter2.cpp b/navigations/nav_core_adapter/src/global_planner_adapter2.cpp new file mode 100755 index 0000000..7d4f1ab --- /dev/null +++ b/navigations/nav_core_adapter/src/global_planner_adapter2.cpp @@ -0,0 +1,95 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +namespace nav_core_adapter +{ + +GlobalPlannerAdapter2::GlobalPlannerAdapter2() : + planner_loader_("nav_core", "nav_core::BaseGlobalPlanner") +{ +} + +/** + * @brief Load the nav_core global planner and initialize it + */ +void GlobalPlannerAdapter2::initialize(const ros::NodeHandle& parent, const std::string& name, + TFListenerPtr tf, nav_core2::Costmap::Ptr costmap) +{ + costmap_ = costmap; + std::shared_ptr ptr = std::static_pointer_cast(costmap); + + if (!ptr) + { + ROS_FATAL_NAMED("GlobalPlannerAdapter2", + "GlobalPlannerAdapter2 can only be used with the CostmapAdapter, not other Costmaps!"); + exit(EXIT_FAILURE); + } + costmap_ros_ = ptr->getCostmap2DROS(); + + ros::NodeHandle planner_nh(parent, name); + std::string planner_name; + planner_nh.param("planner_name", planner_name, std::string("global_planner/GlobalPlanner")); + ROS_INFO_NAMED("GlobalPlannerAdapter2", "Loading plugin %s", planner_name.c_str()); + planner_ = planner_loader_.createInstance(planner_name); + planner_->initialize(planner_loader_.getName(planner_name), costmap_ros_); +} + +nav_2d_msgs::Path2D GlobalPlannerAdapter2::makePlan(const nav_2d_msgs::Pose2DStamped& start, + const nav_2d_msgs::Pose2DStamped& goal) +{ + geometry_msgs::PoseStamped start3d = nav_2d_utils::pose2DToPoseStamped(start), + goal3d = nav_2d_utils::pose2DToPoseStamped(goal); + std::vector plan; + bool ret = planner_->makePlan(start3d, goal3d, plan); + if (!ret) + { + throw nav_core2::PlannerException("Generic Global Planner Error"); + } + return nav_2d_utils::posesToPath2D(plan); +} +} // namespace nav_core_adapter + + +// register this planner as a GlobalPlanner plugin +PLUGINLIB_EXPORT_CLASS(nav_core_adapter::GlobalPlannerAdapter2, nav_core2::GlobalPlanner) diff --git a/navigations/nav_core_adapter/src/local_planner_adapter.cpp b/navigations/nav_core_adapter/src/local_planner_adapter.cpp new file mode 100755 index 0000000..a8015e5 --- /dev/null +++ b/navigations/nav_core_adapter/src/local_planner_adapter.cpp @@ -0,0 +1,190 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +namespace nav_core_adapter +{ + +LocalPlannerAdapter::LocalPlannerAdapter() : + planner_loader_("nav_core2", "nav_core2::LocalPlanner") +{ +} + +/** + * @brief Load the nav_core2 local planner and initialize it + */ +void LocalPlannerAdapter::initialize(std::string name, tf2_ros::Buffer* tf, costmap_2d::Costmap2DROS* costmap_ros) +{ + // ROS_WARN("LocalPlannerAdapter::initialize"); + tf_ = createSharedPointerWithNoDelete(tf); + costmap_ros_ = costmap_ros; + costmap_adapter_ = std::make_shared(); + costmap_adapter_->initialize(costmap_ros); + + ros::NodeHandle nh; + ros::NodeHandle private_nh("~"); + ros::NodeHandle adapter_nh("~/" + name); + std::string planner_name; + adapter_nh.param("planner_name", planner_name, std::string("dwb_local_planner::DWBLocalPlanner")); + ROS_INFO_NAMED("LocalPlannerAdapter", "Loading plugin %s", planner_name.c_str()); + planner_ = planner_loader_.createInstance(planner_name); + // From void DWBLocalPlanner::initialize(const ros::NodeHandle& parent, const std::string& name, + // TFListenerPtr tf, nav_core2::Costmap::Ptr costmap) + planner_->initialize(private_nh, planner_loader_.getName(planner_name), tf_, costmap_adapter_); + has_active_goal_ = false; + + odom_sub_ = std::make_shared(nh); +} + +/** + * @brief Collect the additional information needed by nav_core2 and call the child computeVelocityCommands + */ +bool LocalPlannerAdapter::computeVelocityCommands(geometry_msgs::Twist& cmd_vel) +{ + if (!has_active_goal_) + { + return false; + } + + // Get the Pose + nav_2d_msgs::Pose2DStamped pose2d; + if (!getRobotPose(pose2d)) + { + return false; + } + + // Get the Velocity + nav_2d_msgs::Twist2D velocity = odom_sub_->getTwist(); + nav_2d_msgs::Twist2DStamped cmd_vel_2d; + try + { // to -> DWBLocalPlanner::computeVelocityCommands() + cmd_vel_2d = planner_->computeVelocityCommands(pose2d, velocity); + } + catch (const nav_core2::PlannerException& e) + { + ROS_ERROR_NAMED("LocalPlannerAdapter", "computeVelocityCommands exception: %s", e.what()); + return false; + } + cmd_vel = nav_2d_utils::twist2Dto3D(cmd_vel_2d.velocity); + return true; +} + +/** + * @brief Collect the additional information needed by nav_core2 and call the child isGoalReached + */ +bool LocalPlannerAdapter::isGoalReached() +{ + // Get the Pose + nav_2d_msgs::Pose2DStamped pose2d; + if (!getRobotPose(pose2d)) + return false; + + nav_2d_msgs::Twist2D velocity = odom_sub_->getTwist(); + bool ret = planner_->isGoalReached(pose2d, velocity); + if (ret) + { + has_active_goal_ = false; + } + return ret; +} + +/** + * @brief Convert from 2d to 3d and call child setPlan + */ +bool LocalPlannerAdapter::setPlan(const std::vector& orig_global_plan) +{ + nav_2d_msgs::Path2D path = nav_2d_utils::posesToPath2D(orig_global_plan); + try + { + if (path.poses.size() > 0) + { + nav_2d_msgs::Pose2DStamped goal_pose; + goal_pose.header = path.header; + goal_pose.pose = path.poses.back(); + + if (!has_active_goal_ || hasGoalChanged(goal_pose)) + { + last_goal_ = goal_pose; + has_active_goal_ = true; + planner_->setGoalPose(goal_pose); + } + } + + planner_->setPlan(path); + return true; + } + catch (const nav_core2::PlannerException& e) + { + ROS_ERROR_NAMED("LocalPlannerAdapter", "setPlan Exception: %s", e.what()); + return false; + } +} + +bool LocalPlannerAdapter::hasGoalChanged(const nav_2d_msgs::Pose2DStamped& new_goal) +{ + if (last_goal_.header.frame_id != new_goal.header.frame_id) + { + return true; + } + + return last_goal_.pose.x != new_goal.pose.x || last_goal_.pose.y != new_goal.pose.y || + last_goal_.pose.theta != new_goal.pose.theta; +} + +bool LocalPlannerAdapter::getRobotPose(nav_2d_msgs::Pose2DStamped& pose2d) +{ + geometry_msgs::PoseStamped current_pose; + if (!costmap_ros_->getRobotPose(current_pose)) + { + ROS_ERROR_NAMED("LocalPlannerAdapter", "Could not get robot pose"); + return false; + } + pose2d = nav_2d_utils::poseStampedToPose2D(current_pose); + return true; +} + +} // namespace nav_core_adapter + +// register this planner as a BaseLocalPlanner plugin +PLUGINLIB_EXPORT_CLASS(nav_core_adapter::LocalPlannerAdapter, nav_core::BaseLocalPlanner) diff --git a/navigations/nav_core_adapter/test/unload_test.cpp b/navigations/nav_core_adapter/test/unload_test.cpp new file mode 100755 index 0000000..aa5118d --- /dev/null +++ b/navigations/nav_core_adapter/test/unload_test.cpp @@ -0,0 +1,69 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ +#include +#include + + +TEST(LocalPlannerAdapter, unload_local_planner) +{ + tf2_ros::Buffer tf; + tf.setUsingDedicatedThread(true); + + // This empty transform is added to satisfy the constructor of + // Costmap2DROS, which waits for the transform from map to base_link + // to become available. + geometry_msgs::TransformStamped base_rel_map; + base_rel_map.child_frame_id = "/base_link"; + base_rel_map.header.frame_id = "/map"; + base_rel_map.transform.rotation.w = 1.0; + tf.setTransform(base_rel_map, "unload", true); + + nav_core_adapter::LocalPlannerAdapter* lpa = new nav_core_adapter::LocalPlannerAdapter(); + + costmap_2d::Costmap2DROS costmap_ros("local_costmap", tf); + lpa->initialize("lpa", &tf, &costmap_ros); + + delete lpa; + + // Simple test to make sure costmap hasn't been deleted + EXPECT_EQ("map", costmap_ros.getGlobalFrameID()); +} + + +int main(int argc, char** argv) +{ + ros::init(argc, argv, "unload_test"); + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/navigations/nav_core_adapter/test/unload_test.launch b/navigations/nav_core_adapter/test/unload_test.launch new file mode 100755 index 0000000..c1ddad8 --- /dev/null +++ b/navigations/nav_core_adapter/test/unload_test.launch @@ -0,0 +1,3 @@ + + + diff --git a/navigations/nav_grid/CMakeLists.txt b/navigations/nav_grid/CMakeLists.txt new file mode 100755 index 0000000..818a090 --- /dev/null +++ b/navigations/nav_grid/CMakeLists.txt @@ -0,0 +1,21 @@ +cmake_minimum_required(VERSION 3.0.2) +project(nav_grid) +set_directory_properties(PROPERTIES COMPILE_OPTIONS "-std=c++11") + +find_package(catkin REQUIRED) + +catkin_package( + INCLUDE_DIRS include +) + +if (CATKIN_ENABLE_TESTING) + find_package(roslint REQUIRED) + include_directories(include ${catkin_INCLUDE_DIRS}) + roslint_cpp() + roslint_add_test() + catkin_add_gtest(${PROJECT_NAME}_utest test/utest.cpp) +endif (CATKIN_ENABLE_TESTING) + +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} +) diff --git a/navigations/nav_grid/README.md b/navigations/nav_grid/README.md new file mode 100755 index 0000000..7ec1957 --- /dev/null +++ b/navigations/nav_grid/README.md @@ -0,0 +1,39 @@ +# nav_grid + +Many navigation algorithms rely on the concept of a two dimensional grid being overlaid on the world, with a value being assigned to each grid cell. In the original navigation stack, `Costmap2DROS` associated an `unsigned char` with grid cells, global planners cache distance to the goal as `float`s and local planners would cache various metrics in a grid to quickly calculate the strength of different trajectories. + +![nav_grid diagram](doc/nav_grid.png) + +## `NavGridInfo` + +Where the grid exists in the world is defined by six parameters. + * `width` and `height` (which together define the number of cells in the grid) + * `resolution` which is the dimension of each cell in meters (square cells only) + * `frame_id` which is the TF frame the grid is defined relative to. + * `origin_x` and `origin_y` which define the offset in meters from the root of the TF frame to the minimum corner of the (0, 0) cell. + +Together, these components make a [`nav_grid::NavGridInfo`](include/nav_grid/nav_grid_info.h) struct. It evolved from the [`nav_msgs::MapMetaData` message](http://docs.ros.org/melodic/api/nav_msgs/html/msg/MapMetaData.html) but without `map_load_time`, simplified origin geometry and the `frame_id` added. Note: for general efficiency of computation (particularly moving the grid while retaining some of the values) there is no rotation component to the origin. Each grid is locked to the orientation of its TF frame. + +The default values are `width=0, height=0, resolution=1.0, frame_id="map", origin_x=0.0, origin_y=0.0`. + +## Coordinate Conversion +One of the most common operations is to want to convert between the real world coordinates and the grid coordinates. These operations can be done with a `NavGridInfo` object and the methods in [`coordinate_conversion.h`](include/nav_grid/coordinate_conversion.h). They are derived from methods in [`costmap_2d.h`](https://github.com/ros-planning/navigation/blob/a2837b5a9dc6dd4b4da176fca7d899d6a3722bf8/costmap_2d/include/costmap_2d/costmap_2d.h#L126), but with some key differences (beyond replacing `map` with `grid`). + * `gridToWorld` is the same as `mapToWorld`, as both return the world coordinates of the center of the specified cell. + * `worldToGrid` works like `worldToMapNoBounds`, but it results in either `int` or `double` coordinates depending on the output parameter types. As the result are not bounded by the grid, the results are signed. + * `worldToGridBounded` is a combination of `worldToMap` and `worldToMapEnforceBounds`. It returns a bool for whether the input coordinates are within the grid AND the output coordinates are forced to be within the grid. The output coordinates are therefore `unsigned int`. + * There's also `isWithinGrid` that returns whether a given point is within the grid (i.e. will match the return value of `worldToGridBounded` but saves some of the computation associated with calculating the actual values of the coordinates. + +![example coordinate conversion](doc/coords.png) + +## `NavGrid` +Of course, we also want to associate a value with each cell in the grid. For that, we define the templatized [`nav_grid::NavGrid`](include/nav_grid/nav_grid.h) abstract class. The template allows for storing arbitrary data types associated with each grid cell. The actual storage mechanism for the data is not part of the base class to allow for possibly more efficient methods. A default implementation where the data is simply stored in row-major order in a one-dimensional vector is provided in [`nav_grid::VectorNavGrid`](include/nav_grid/vector_nav_grid.h>) + +The constructor for `NavGrid` takes a default value for each cell which is 0 by default. The grid's initial info matches the default info above, so the grid is initially `0x0`. + +The `NavGrid` class provides handy methods for accessing values via their grid indexes. You can use `grid(x, y)` or `grid.getValue(x, y)` to access each value, and use `grid.setValue(x, y, value)` to write each value. There is also the helper class [`nav_grid::Index`](include/nav_grid/index.h) that can be used to store the two coordinates and used in accessing the data as well a la `grid(index)` and `grid.setValue(index, value)`. + +There are two methods for changing the `info` associated with the grid: `setInfo` and `updateInfo`. `setInfo` changes the `info` while maintaining the data associated with each grid coordinate. `updateInfo` will change the info but instead maintain the data associated with the world coordinates. + +For instance, imagine a 5x5 grid with 0.5 meter resolution with the cell (2, 0) set to red which represents a cell at (1.25, 0.25) in the world. If we change the origin to be 0.5 meters to the right, the grids will have different values according to the method we use. With `setInfo`, cell (2, 0) is still red, but it is associated with a cell at (1.75, 0.25) in the world. With `updateInfo`, the cell at (1.25, 0.25) is still red, but it is now associated with cell (1, 0). The exact mechanism for how this data is preserved is left to the implementing class. + +![illustration of grid update](doc/change_info.png) diff --git a/navigations/nav_grid/doc/change_info.png b/navigations/nav_grid/doc/change_info.png new file mode 100755 index 0000000..1e0e9c5 Binary files /dev/null and b/navigations/nav_grid/doc/change_info.png differ diff --git a/navigations/nav_grid/doc/coords.png b/navigations/nav_grid/doc/coords.png new file mode 100755 index 0000000..dfa40bf Binary files /dev/null and b/navigations/nav_grid/doc/coords.png differ diff --git a/navigations/nav_grid/doc/nav_grid.png b/navigations/nav_grid/doc/nav_grid.png new file mode 100755 index 0000000..c43cda0 Binary files /dev/null and b/navigations/nav_grid/doc/nav_grid.png differ diff --git a/navigations/nav_grid/include/nav_grid/coordinate_conversion.h b/navigations/nav_grid/include/nav_grid/coordinate_conversion.h new file mode 100755 index 0000000..4eb06fe --- /dev/null +++ b/navigations/nav_grid/include/nav_grid/coordinate_conversion.h @@ -0,0 +1,168 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef NAV_GRID_COORDINATE_CONVERSION_H +#define NAV_GRID_COORDINATE_CONVERSION_H + +#include +#include + +namespace nav_grid +{ +/** + * @brief Convert from grid coordinates to world coordinates of the center of the cell + * + * The resulting coordinates are for the center of the grid cell. + * + * @param[in] mx The x grid coordinate + * @param[in] my The y grid coordinate + * @param[out] wx Set to the associated x world coordinate + * @param[out] wy Set to the associated y world coordinate + */ +inline void gridToWorld(const NavGridInfo& info, int mx, int my, double& wx, double& wy) +{ + wx = info.origin_x + (mx + 0.5) * info.resolution; + wy = info.origin_y + (my + 0.5) * info.resolution; +} + +/** + * @brief Convert from world coordinates to the precise (double) grid coordinates + * + * The results are not rounded, so that the values can be used for locating a position within a cell + * + * @param[in] wx The x world coordinate + * @param[in] wy The y world coordinate + * @param[out] mx Set to the associated x grid coordinate + * @param[out] my Set to the associated y grid coordinate + */ +inline void worldToGrid(const NavGridInfo& info, double wx, double wy, double& mx, double& my) +{ + mx = (wx - info.origin_x) / info.resolution; + my = (wy - info.origin_y) / info.resolution; +} + +/** + * @brief Convert from world coordinates to grid coordinates without checking for legal bounds + * @param[in] wx The x world coordinate + * @param[in] wy The y world coordinate + * @param[out] mx Set to the associated x grid coordinate + * @param[out] my Set to the associated y grid coordinate + * @note The returned grid coordinates are not guaranteed to lie within the grid. + */ +inline void worldToGrid(const NavGridInfo& info, double wx, double wy, int& mx, int& my) +{ + double dmx, dmy; + worldToGrid(info, wx, wy, dmx, dmy); + mx = static_cast(floor(dmx)); + my = static_cast(floor(dmy)); +} + +/** + * @brief Convert from world coordinates to grid coordinates + * + * Combined functionality from costmap_2d::worldToMap and costmap_2d::worldToMapEnforceBounds. + * The output parameters are set to grid indexes within the grid, even if the function returns false, + * meaning the coordinates are outside the grid. + * + * @param[in] wx The x world coordinate + * @param[in] wy The y world coordinate + * @param[out] mx Set to the associated (bounds-enforced) x grid coordinate + * @param[out] my Set to the associated (bounds-enforced) y grid coordinate + * @return True if the input coordinates were within the grid + */ +inline bool worldToGridBounded(const NavGridInfo& info, double wx, double wy, unsigned int& mx, unsigned int& my) +{ + double dmx, dmy; + worldToGrid(info, wx, wy, dmx, dmy); + + bool valid = true; + + if (dmx < 0.0) + { + mx = 0; + valid = false; + } + else if (dmx >= info.width) + { + mx = info.width - 1; + valid = false; + } + else + { + mx = static_cast(dmx); + } + + if (dmy < 0.0) + { + my = 0; + valid = false; + } + else if (dmy >= info.height) + { + my = info.height - 1; + valid = false; + } + else + { + my = static_cast(dmy); + } + + return valid; +} + +/** + * @brief Check to see if the world coordinates are within the grid. + * + * This should only be used if the caller does not need the associated grid coordinates. Otherwise it would + * be more efficient to call worldToGridBounded. + * + * @param[in] wx The x world coordinate + * @param[in] wy The y world coordinate + * @return True if the input coordinates were within the grid + */ +inline bool isWithinGrid(const NavGridInfo& info, double wx, double wy) +{ + wx -= info.origin_x; + wy -= info.origin_y; + return wx >= 0.0 && + wy >= 0.0 && + wx < info.width * info.resolution && + wy < info.height * info.resolution; +} + + + +} // namespace nav_grid + +#endif // NAV_GRID_COORDINATE_CONVERSION_H diff --git a/navigations/nav_grid/include/nav_grid/index.h b/navigations/nav_grid/include/nav_grid/index.h new file mode 100755 index 0000000..e6be03d --- /dev/null +++ b/navigations/nav_grid/include/nav_grid/index.h @@ -0,0 +1,99 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef NAV_GRID_INDEX_H +#define NAV_GRID_INDEX_H + +#include + +namespace nav_grid +{ +/** + * @class GenericIndex + * @brief A simple pair of x/y coordinates + */ +template +struct GenericIndex +{ + NumericType x, y; + explicit GenericIndex(const NumericType& x = 0, const NumericType& y = 0) : x(x), y(y) {} + + /** + * @brief comparison operator that requires equal x and y + */ + bool operator == (const GenericIndex& other) const + { + return x == other.x && y == other.y; + } + + bool operator != (const GenericIndex& other) const + { + return !operator==(other); + } + + /** + * @brief less than operator so object can be used in sets + */ + bool operator < (const GenericIndex& other) const + { + return x < other.x || (x == other.x && y < other.y); + } + + // Derived Comparators + bool operator > (const GenericIndex& other) const { return other < *this; } + bool operator <= (const GenericIndex& other) const { return !(*this > other); } + bool operator >= (const GenericIndex& other) const { return !(*this < other); } + + /** + * @brief String representation of this object + */ + std::string toString() const + { + return "(" + std::to_string(x) + ", " + std::to_string(y) + ")"; + } +}; + +template +inline std::ostream& operator<<(std::ostream& stream, const GenericIndex& index) +{ + stream << index.toString(); + return stream; +} + +using SignedIndex = GenericIndex; +using Index = GenericIndex; + +} // namespace nav_grid + +#endif // NAV_GRID_INDEX_H diff --git a/navigations/nav_grid/include/nav_grid/nav_grid.h b/navigations/nav_grid/include/nav_grid/nav_grid.h new file mode 100755 index 0000000..7dfe7f8 --- /dev/null +++ b/navigations/nav_grid/include/nav_grid/nav_grid.h @@ -0,0 +1,157 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef NAV_GRID_NAV_GRID_H +#define NAV_GRID_NAV_GRID_H + +#include +#include +#include + +namespace nav_grid +{ +/** + * @class NavGrid + * This class is a spiritual successor to the costmap_2d::Costmap2D class, with the key differences being that + * the datatype and data storage methods are not specified, and the frame_id is specified. + * + * The templatized nature of the class allows you to store whatever you like at each grid location, including + * unsigned chars if emulating Costmap2D or floating point numbers if emulating the grid_map package, or whatever + * else. + * + * The VectorNavGrid class in this package implements this class with a straight-forward single-dimensional vector + * representing the two dimensional grid. Other classes could implement the data storage differently. + * + * Getting data from the grid can be done either through the getValue methods or the parenthetical operators (which call + * getValue internally). Implementing classes must implement getValue. + * x = grid(0, 0) + grid.getValue(0, 1); + * + * Writing data to the grid must be done through the setValue method (which implementing classes must implement) + * grid.setValue(0, 0, x); + * + * You can also use nav_grid::Index objects + * nav_grid::Index index(0, 0); + * x = grid(index) + grid.getValue(index); + * index.y = 3; + * grid.setCost(index, x); + * The Index methods also internally call setValue/getValue + * + * The geometry of the grid is specified by the NavGridInfo. Borrowing an idea from the grid_map package, two + * separate methods are defined for changing the info. setInfo will change the info without changing the grid values. + * updateInfo will change the info while trying to preserve the contents of the grid. + * + * The final component is a collection of methods inspired by Costmap2D for converting coordinates of different types. + */ +template class NavGrid +{ +public: + explicit NavGrid(const T default_value = T{}) : default_value_(default_value) {} + + /** + * @brief Reset the contents of the grid + */ + virtual void reset() = 0; + + /** + * @brief get the value of the grid at (x,y) + * @param x[in] Valid x coordinate + * @param y[in] Valid y coordinate + * @return value at (x,y) + */ + virtual T getValue(const unsigned int x, const unsigned int y) const = 0; + + /** + * @brief set the value of the grid at (x,y) + * @param x[in] Valid x coordinate + * @param y[in] Valid y coordinate + * @param value[in] New Value + */ + virtual void setValue(const unsigned int x, const unsigned int y, const T& value) = 0; + + /**@name Convenience Aliases */ + // Note: You may not be able to use these unless your deriving class declares using NavGrid::operator() or + // using NavGrid::getValue + /**@{*/ + T getValue(const Index& index) { return getValue(index.x, index.y); } + T operator() (const unsigned int x, const unsigned int y) const { return getValue(x, y); } + T operator() (const Index& index) const { return getValue(index.x, index.y); } + void setValue(const Index& index, const T& value) { setValue(index.x, index.y, value); } + + /**@}*/ + + /** + * @brief Change the info while attempting to keep the values associated with the grid coordinates + * @param[in] new_info New grid info + */ + virtual void setInfo(const NavGridInfo& new_info) = 0; + + /** + * @brief Change the info while attempting to keep the values associated with the world coordinates + * + * For example, if the only change to the info is to the origin's x coordinate (increasing by an amount equal to the + * resolution), then all the values should be shifted one grid cell to the left. + * + * @param[in] new_info New grid info + */ + virtual void updateInfo(const NavGridInfo& new_info) { setInfo(new_info); } + + inline NavGridInfo getInfo() const { return info_; } + + /** + * @brief Set the default value + * @param[in] new_value New Default Value + */ + void setDefaultValue(const T new_value) + { + default_value_ = new_value; + } + + /***************************************************************************************************** + * NavGridInfo accessor methods + *****************************************************************************************************/ + inline unsigned int getWidth() const { return info_.width; } + inline unsigned int getHeight() const { return info_.height; } + inline double getResolution() const { return info_.resolution; } + inline std::string getFrameId() const { return info_.frame_id; } + inline double getOriginX() const { return info_.origin_x; } + inline double getOriginY() const { return info_.origin_y; } + +protected: + NavGridInfo info_; + T default_value_; +}; + +} // namespace nav_grid + +#endif // NAV_GRID_NAV_GRID_H diff --git a/navigations/nav_grid/include/nav_grid/nav_grid_info.h b/navigations/nav_grid/include/nav_grid/nav_grid_info.h new file mode 100755 index 0000000..8addf08 --- /dev/null +++ b/navigations/nav_grid/include/nav_grid/nav_grid_info.h @@ -0,0 +1,92 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef NAV_GRID_NAV_GRID_INFO_H +#define NAV_GRID_NAV_GRID_INFO_H + +#include + +namespace nav_grid +{ +/** + * @struct NavGridInfo + * This class defines a way to discretize a finite section of the world into a grid. + * It contains similar information to the ROS msg nav_msgs/MapMetaData (aka the info field of nav_msgs/OccupancyGrid) + * except the map_load_time is removed, the geometry is simplified from a Pose to xy coordinates, and the frame_id + * is added. + */ +struct NavGridInfo +{ +public: + /* All data is publically accessible */ + unsigned int width = 0; + unsigned int height = 0; + double resolution = 1.0; + std::string frame_id = "map"; + double origin_x = 0.0; ///< The origin defines the coordinates of minimum corner of cell (0,0) in the grid + double origin_y = 0.0; + + /** + * @brief comparison operator that requires all fields are equal + */ + bool operator == (const NavGridInfo& info) const + { + return width == info.width && height == info.height && resolution == info.resolution && + origin_x == info.origin_x && origin_y == info.origin_y && frame_id == info.frame_id; + } + + bool operator != (const NavGridInfo& info) const + { + return !operator==(info); + } + + /** + * @brief String representation of this object + */ + std::string toString() const + { + return std::to_string(width) + "x" + std::to_string(height) + " (" + std::to_string(resolution) + "res) " + + frame_id + " " + std::to_string(origin_x) + " " + std::to_string(origin_y); + } +}; + +inline std::ostream& operator<<(std::ostream& stream, const NavGridInfo& info) +{ + stream << info.toString(); + return stream; +} + +} // namespace nav_grid + +#endif // NAV_GRID_NAV_GRID_INFO_H diff --git a/navigations/nav_grid/include/nav_grid/vector_nav_grid.h b/navigations/nav_grid/include/nav_grid/vector_nav_grid.h new file mode 100755 index 0000000..ea7c4a9 --- /dev/null +++ b/navigations/nav_grid/include/nav_grid/vector_nav_grid.h @@ -0,0 +1,239 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef NAV_GRID_VECTOR_NAV_GRID_H +#define NAV_GRID_VECTOR_NAV_GRID_H + +#include +#include +#include +#include + +namespace nav_grid +{ +/** + * @class VectorNavGrid + * A straight-forward implementation of the NavGrid class where the data for cell (x, y) is stored in a std::vector + * with index (y * info.width + x). + */ +template class VectorNavGrid : public NavGrid +{ +public: + using NavGrid::NavGrid; + + /** + * @brief Reset the contents of the grid to the default value + */ + void reset() override + { + data_.assign(this->info_.width * this->info_.height, this->default_value_); + } + + /** + * @brief Change the info while attempting to keep the values associated with the grid coordinates + * + * If the width changes, we need to move each row to its new location + * + * If just the height changes, then we can resize the vector without having to move elements + * + * We just overwrite the rest of the grid info + */ + void setInfo(const NavGridInfo& new_info) override + { + if (this->info_.width != new_info.width) + { + std::vector new_vector(new_info.width * new_info.height, this->default_value_); + unsigned int cols_to_move = std::min(this->info_.width, new_info.width); + auto old_it = data_.begin(); + auto new_it = new_vector.begin(); + unsigned int max_row = std::min(this->info_.height, new_info.height); + for (unsigned int row = 0; row < max_row; row++) + { + std::copy(old_it, old_it + cols_to_move, new_it); + old_it += this->info_.width; + new_it += new_info.width; + } + data_.swap(new_vector); + } + else if (this->info_.height != new_info.height) + { + data_.resize(new_info.width * new_info.height, this->default_value_); + } + + this->info_ = new_info; + } + + /** + * @brief Update the info while keeping the data geometrically in tact + * + * If the resolution or frame_id changes, reset all the data. + * + * Otherwise, adjust the new_info so the grid stays aligned (The grid's new info will be within a + * resolution-length of the original new_info). Then copy the common values into the new grid. + * + * @param[in] new_info New information to update the grid with + */ + void updateInfo(const NavGridInfo& new_info) override + { + // If the info is the same, make no changes + if (this->info_ == new_info) + { + return; + } + + // If the resolution or frame changes, reset the whole grid + if (this->info_.resolution != new_info.resolution || this->info_.frame_id != new_info.frame_id) + { + setInfo(new_info); + return; + } + + // project the new origin into the grid + int cell_ox, cell_oy; + worldToGrid(this->info_, new_info.origin_x, new_info.origin_y, cell_ox, cell_oy); + + // To save casting from unsigned int to int a bunch of times + int old_size_x = static_cast(this->info_.width); + int old_size_y = static_cast(this->info_.height); + + // we need to compute the overlap of the new and existing windows + int lower_left_x = std::min(std::max(cell_ox, 0), old_size_x); + int lower_left_y = std::min(std::max(cell_oy, 0), old_size_y); + int upper_right_x = std::min(std::max(cell_ox + static_cast(new_info.width), 0), old_size_x); + int upper_right_y = std::min(std::max(cell_oy + static_cast(new_info.height), 0), old_size_y); + + unsigned int cell_size_x = upper_right_x - lower_left_x; + unsigned int cell_size_y = upper_right_y - lower_left_y; + + // we need a vector to store the new contents in the window temporarily + std::vector new_data(new_info.width * new_info.height, this->default_value_); + + // compute the starting cell location for copying data back in + int start_x = lower_left_x - cell_ox; + int start_y = lower_left_y - cell_oy; + + // now we want to copy the overlapping information into the new vector, but in its new location + // we'll first need to compute the starting points for each vector + auto src_index = data_.begin() + (lower_left_y * old_size_x + lower_left_x); + auto dest_index = new_data.begin() + (start_y * new_info.width + start_x); + + // now, we'll copy the source vector into the destination vector + for (unsigned int i = 0; i < cell_size_y; ++i) + { + std::copy(src_index, src_index + cell_size_x, dest_index); + src_index += this->info_.width; + dest_index += new_info.width; + } + + data_.swap(new_data); + + // update the dimensions + this->info_.width = new_info.width; + this->info_.height = new_info.height; + + // update the origin. Recomputed instead of using new_info.origin + // because we want to keep things grid-aligned + this->info_.origin_x += cell_ox * this->info_.resolution; + this->info_.origin_y += cell_oy * this->info_.resolution; + } + + void setValue(const unsigned int x, const unsigned int y, const T& value) override + { + data_[getIndex(x, y)] = value; + } + + T getValue(const unsigned int x, const unsigned int y) const override + { + return data_[getIndex(x, y)]; + } + + using NavGrid::operator(); + using NavGrid::getValue; + using NavGrid::setValue; + + /** + * Overloading the [] operator so that the data can be accessed directly with vector_nav_grid[i] + */ + T operator[] (unsigned int i) const {return data_[i];} + T& operator[] (unsigned int i) {return data_[i];} + + /** + * @brief Return the size of the vector. Equivalent to width * height. + * @return size of the vector + */ + unsigned int size() const { return data_.size(); } + + /** + * @brief Given two grid coordinates... compute the associated index + * @param[in] mx The x coordinate + * @param[in] my The y coordinate + * @return The associated index + */ + inline unsigned int getIndex(unsigned int mx, unsigned int my) const + { + return my * this->info_.width + mx; + } + + /** + * @brief Given two world coordinates... compute the associated index + * @param[in] mx The x coordinate + * @param[in] my The y coordinate + * @return The associated index + */ + inline unsigned int getIndex(double x, double y) const + { + unsigned int mx, my; + worldToGridBounded(this->info_, x, y, mx, my); + return getIndex(mx, my); + } + + /** + * @brief Given an index... compute the associated grid coordinates + * @param[in] index The index + * @param[out] mx Set to the associated x grid coordinate + * @param[out] my Set to the associated y grid coordinate + */ + inline void indexToCells(unsigned int index, unsigned int& mx, unsigned int& my) const + { + unsigned int w = this->info_.width; + my = index / w; + mx = index - my * w; + } + +protected: + std::vector data_; +}; +} // namespace nav_grid + +#endif // NAV_GRID_VECTOR_NAV_GRID_H diff --git a/navigations/nav_grid/package.xml b/navigations/nav_grid/package.xml new file mode 100755 index 0000000..56936ba --- /dev/null +++ b/navigations/nav_grid/package.xml @@ -0,0 +1,13 @@ + + + nav_grid + 0.3.0 + + A templatized interface for overlaying a two dimensional grid on the world. + + David V. Lu!! + BSD + catkin + roslint + rosunit + diff --git a/navigations/nav_grid/test/utest.cpp b/navigations/nav_grid/test/utest.cpp new file mode 100755 index 0000000..c9463cf --- /dev/null +++ b/navigations/nav_grid/test/utest.cpp @@ -0,0 +1,522 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ +#include +#include +#include +#include + +TEST(VectorNavGrid, info_equality) +{ + nav_grid::NavGridInfo info0; + nav_grid::NavGridInfo info1; + nav_grid::NavGridInfo width_info; + width_info.width = 3; + + nav_grid::NavGridInfo height_info; + height_info.height = 3; + + nav_grid::NavGridInfo res_info; + res_info.resolution = 3.0; + + nav_grid::NavGridInfo frame_info; + frame_info.frame_id = "foobar"; + + nav_grid::NavGridInfo originx_info; + originx_info.origin_x = 3.0; + + nav_grid::NavGridInfo originy_info; + originy_info.origin_y = 3.0; + + + EXPECT_EQ(info0, info0); + EXPECT_EQ(info0, info1); + EXPECT_NE(info0, width_info); + EXPECT_NE(info0, height_info); + EXPECT_NE(info0, res_info); + EXPECT_NE(info0, frame_info); + EXPECT_NE(info0, originx_info); + EXPECT_NE(info0, originy_info); +} + +TEST(VectorNavGrid, basic_test) +{ + nav_grid::VectorNavGrid grid(-3); + nav_grid::NavGridInfo info; + info.width = 2; + info.height = 3; + grid.setInfo(info); + EXPECT_EQ(grid(0, 0), -3); + grid.setValue(1, 1, 10); + EXPECT_EQ(grid(0, 0), -3); + EXPECT_EQ(grid(1, 1), 10); +} + +TEST(VectorNavGrid, basic_index_test) +{ + nav_grid::VectorNavGrid grid(-3); + nav_grid::NavGridInfo info; + info.width = 2; + info.height = 3; + grid.setInfo(info); + + nav_grid::Index index0(0, 0), index1(1, 1); + EXPECT_EQ(grid(index0), -3); + grid.setValue(index1, 10); + EXPECT_EQ(grid(index0), -3); + EXPECT_EQ(grid(index1), 10); + EXPECT_EQ(grid(0, 0), -3); + EXPECT_EQ(grid(1, 1), 10); +} + +TEST(VectorNavGrid, easy_coordinates_test) +{ + nav_grid::NavGridInfo info; + info.width = 2; + info.height = 3; + + double wx, wy; + gridToWorld(info, 0, 0, wx, wy); + EXPECT_DOUBLE_EQ(wx, 0.5); + EXPECT_DOUBLE_EQ(wy, 0.5); + gridToWorld(info, 1, 2, wx, wy); + EXPECT_DOUBLE_EQ(wx, 1.5); + EXPECT_DOUBLE_EQ(wy, 2.5); + + unsigned int umx, umy; + int mx, my; + double dmx, dmy; + ASSERT_TRUE(worldToGridBounded(info, wx, wy, umx, umy)); + EXPECT_EQ(umx, 1); + EXPECT_EQ(umy, 2); + worldToGrid(info, wx, wy, mx, my); + EXPECT_EQ(mx, 1); + EXPECT_EQ(my, 2); + worldToGrid(info, wx, wy, dmx, dmy); + EXPECT_DOUBLE_EQ(dmx, wx); + EXPECT_DOUBLE_EQ(dmy, wy); + + // Invalid Coordinate + wx = 2.5; + EXPECT_FALSE(worldToGridBounded(info, wx, wy, umx, umy)); + EXPECT_EQ(umx, 1); + EXPECT_EQ(umy, 2); + worldToGrid(info, wx, wy, mx, my); + EXPECT_EQ(mx, 2); + EXPECT_EQ(my, 2); + + // Border Cases + EXPECT_TRUE(worldToGridBounded(info, 0.0, wy, umx, umy)); + EXPECT_EQ(umx, 0); + EXPECT_TRUE(worldToGridBounded(info, 0.25, wy, umx, umy)); + EXPECT_EQ(umx, 0); + EXPECT_TRUE(worldToGridBounded(info, 0.75, wy, umx, umy)); + EXPECT_EQ(umx, 0); + EXPECT_TRUE(worldToGridBounded(info, 0.9999, wy, umx, umy)); + EXPECT_EQ(umx, 0); + EXPECT_TRUE(worldToGridBounded(info, 1.0, wy, umx, umy)); + EXPECT_EQ(umx, 1); + EXPECT_TRUE(worldToGridBounded(info, 1.25, wy, umx, umy)); + EXPECT_EQ(umx, 1); + EXPECT_TRUE(worldToGridBounded(info, 1.75, wy, umx, umy)); + EXPECT_EQ(umx, 1); + EXPECT_TRUE(worldToGridBounded(info, 1.9999, wy, umx, umy)); + EXPECT_EQ(umx, 1); + EXPECT_FALSE(worldToGridBounded(info, 2.0, wy, umx, umy)); + EXPECT_EQ(umx, 1); +} + +TEST(VectorNavGrid, hard_coordinates_test) +{ + nav_grid::NavGridInfo info; + info.width = 2; + info.height = 3; + info.resolution = 0.1; + info.origin_x = -0.2; + info.origin_y = 0.2; + + double wx, wy; + gridToWorld(info, 0, 0, wx, wy); + EXPECT_DOUBLE_EQ(wx, -0.15); + EXPECT_DOUBLE_EQ(wy, 0.25); + gridToWorld(info, 1, 2, wx, wy); + EXPECT_DOUBLE_EQ(wx, -0.05); + EXPECT_DOUBLE_EQ(wy, 0.45); + + unsigned int umx, umy; + int mx, my; + double dmx, dmy; + EXPECT_TRUE(worldToGridBounded(info, wx, wy, umx, umy)); + EXPECT_EQ(umx, 1); + EXPECT_EQ(umy, 2); + worldToGrid(info, wx, wy, mx, my); + EXPECT_EQ(mx, 1); + EXPECT_EQ(my, 2); + worldToGrid(info, wx, wy, dmx, dmy); + EXPECT_DOUBLE_EQ(dmx, 1.5); + EXPECT_DOUBLE_EQ(dmy, 2.5); + + // Invalid Coordinate + wx = 2.5; + EXPECT_FALSE(worldToGridBounded(info, wx, wy, umx, umy)); + EXPECT_EQ(umx, 1); + EXPECT_EQ(umy, 2); + worldToGrid(info, wx, wy, mx, my); + EXPECT_EQ(mx, 27); + EXPECT_EQ(my, 2); +} + + +TEST(VectorNavGrid, speed_test) +{ + nav_grid::NavGridInfo info; + + const int N = 1000; + const int EXTRA = 300; + + info.width = N; + info.height = N; + + double wx, wy; + unsigned int umx, umy; + int mx, my; + double dmx, dmy; + + for (int x = -EXTRA; x < N + EXTRA; x++) + { + for (int y = -EXTRA; y < N + EXTRA; y++) + { + gridToWorld(info, x, y, wx, wy); + if (x < 0 || y < 0 || x >= N || y >= N) + { + EXPECT_FALSE(isWithinGrid(info, wx, wy)); + EXPECT_FALSE(worldToGridBounded(info, wx, wy, umx, umy)); + EXPECT_EQ(umx, std::min(std::max(0, x), N - 1)); + EXPECT_EQ(umy, std::min(std::max(0, y), N - 1)); + } + else + { + EXPECT_TRUE(isWithinGrid(info, wx, wy)); + EXPECT_TRUE(worldToGridBounded(info, wx, wy, umx, umy)); + EXPECT_EQ(umx, x); + EXPECT_EQ(umy, y); + } + worldToGrid(info, wx, wy, mx, my); + EXPECT_EQ(mx, x); + EXPECT_EQ(my, y); + worldToGrid(info, wx, wy, dmx, dmy); + EXPECT_DOUBLE_EQ(dmx, x + 0.5); + EXPECT_DOUBLE_EQ(dmy, y + 0.5); + } + } +} + +int testGridValue(double x, double y) +{ + return static_cast(100 * floor(x) + floor(y)); +} + +/** + * Initialize Grid Values with values based on the grid/world coordinates + * which are initially the same + * + * x --> + * 000 100 200 300 400 500 600 700 800 900 y + * 001 101 201 301 401 501 601 701 801 901 | + * 002 102 202 302 402 502 602 702 802 902 | + * 003 103 203 303 403 503 603 703 803 903 V + * 004 104 204 304 404 504 604 704 804 904 + + */ +void initializeTestGrid(nav_grid::VectorNavGrid& grid) +{ + grid.setDefaultValue(-10); + nav_grid::NavGridInfo info; + info.width = 10; + info.height = 5; + grid.setInfo(info); + double mx, my; + for (unsigned int j = 0; j < info.height; j++) + { + for (unsigned int i = 0; i < info.width; i++) + { + gridToWorld(info, i, j, mx, my); + grid.setValue(i, j, testGridValue(mx, my)); + } + } +} + +/** + * Check to make sure all the grid values are now the same based on their grid coordinates + */ +void checkSetGridValues(const nav_grid::VectorNavGrid& grid, + unsigned int x0, unsigned int x1, unsigned int y0, unsigned int y1) +{ + for (unsigned int x = 0; x < grid.getWidth(); x++) + { + for (unsigned int y = 0; y < grid.getHeight(); y++) + { + if (x >= x0 && x < x1 && y >= y0 && y < y1) + { + EXPECT_EQ(grid(x, y), testGridValue(x, y)); // testGridValue based on Grid Coordinates + } + else + { + EXPECT_EQ(grid(x, y), -10); + } + } + } +} + +/** + * Check to make sure all the grid values are now the same based on their world coordinates + */ +void checkUpdateGridValues(const nav_grid::VectorNavGrid& grid, + unsigned int x0, unsigned int x1, unsigned int y0, unsigned int y1) +{ + double mx, my; + for (unsigned int x = 0; x < grid.getWidth(); x++) + { + for (unsigned int y = 0; y < grid.getHeight(); y++) + { + if (x >= x0 && x < x1 && y >= y0 && y < y1) + { + gridToWorld(grid.getInfo(), x, y, mx, my); + EXPECT_EQ(grid(x, y), testGridValue(mx, my)); // testGridValue based on World Coordinates + } + else + { + EXPECT_EQ(grid(x, y), -10); + } + } + } +} + +void debugGridValues(const nav_grid::VectorNavGrid& grid) +{ + for (unsigned int j = 0; j < grid.getHeight(); j++) + { + for (unsigned int i = 0; i < grid.getWidth(); i++) + { + printf("%d ", grid(i, j)); + } + printf("\n"); + } + printf("\n"); +} + +TEST(VectorNavGrid, resizing_grid_with_set) +{ + nav_grid::VectorNavGrid grid; + initializeTestGrid(grid); + checkSetGridValues(grid, 0, grid.getWidth(), 0, grid.getHeight()); + + nav_grid::NavGridInfo decreased_width_info = grid.getInfo(); + decreased_width_info.width = 5; + grid.setInfo(decreased_width_info); + checkSetGridValues(grid, 0, grid.getWidth(), 0, grid.getHeight()); + + nav_grid::NavGridInfo increased_width_info = grid.getInfo(); + increased_width_info.width = 9; + grid.setInfo(increased_width_info); + checkSetGridValues(grid, 0, 5, 0, grid.getHeight()); + + initializeTestGrid(grid); + checkSetGridValues(grid, 0, grid.getWidth(), 0, grid.getHeight()); + + nav_grid::NavGridInfo increased_height_info = grid.getInfo(); + increased_height_info.height = 9; + grid.setInfo(increased_height_info); + checkSetGridValues(grid, 0, grid.getWidth(), 0, 5); + + nav_grid::NavGridInfo decreased_height_info = grid.getInfo(); + decreased_height_info.height = 4; + grid.setInfo(decreased_height_info); + checkSetGridValues(grid, 0, grid.getWidth(), 0, 4); +} + +TEST(VectorNavGrid, resizing_grid_with_update) +{ + nav_grid::VectorNavGrid grid; + initializeTestGrid(grid); + checkUpdateGridValues(grid, 0, grid.getWidth(), 0, grid.getHeight()); + + nav_grid::NavGridInfo decreased_width_info = grid.getInfo(); + decreased_width_info.width = 5; + grid.updateInfo(decreased_width_info); + checkUpdateGridValues(grid, 0, grid.getWidth(), 0, grid.getHeight()); + + nav_grid::NavGridInfo increased_width_info = grid.getInfo(); + increased_width_info.width = 9; + grid.updateInfo(increased_width_info); + checkUpdateGridValues(grid, 0, 5, 0, grid.getHeight()); + + initializeTestGrid(grid); + checkUpdateGridValues(grid, 0, grid.getWidth(), 0, grid.getHeight()); + + nav_grid::NavGridInfo increased_height_info = grid.getInfo(); + increased_height_info.height = 9; + grid.updateInfo(increased_height_info); + checkUpdateGridValues(grid, 0, grid.getWidth(), 0, 5); + + nav_grid::NavGridInfo decreased_height_info = grid.getInfo(); + decreased_height_info.height = 4; + grid.updateInfo(decreased_height_info); + checkUpdateGridValues(grid, 0, grid.getWidth(), 0, 4); +} + +TEST(VectorNavGrid, change_origin) +{ + nav_grid::VectorNavGrid grid; + initializeTestGrid(grid); + + nav_grid::NavGridInfo bump_right_info = grid.getInfo(); + bump_right_info.origin_x = 3; + grid.updateInfo(bump_right_info); + checkUpdateGridValues(grid, 0, 7, 0, grid.getHeight()); + + nav_grid::NavGridInfo bump_up_info = grid.getInfo(); + bump_up_info.origin_y = 2; + grid.updateInfo(bump_up_info); + checkUpdateGridValues(grid, 0, 7, 0, 3); + + nav_grid::NavGridInfo bump_left_info = grid.getInfo(); + bump_left_info.origin_x = -1; + grid.updateInfo(bump_left_info); + checkUpdateGridValues(grid, 4, grid.getWidth(), 0, 3); + + nav_grid::NavGridInfo bump_down_info = grid.getInfo(); + bump_down_info.origin_y = 0; + grid.updateInfo(bump_down_info); + checkUpdateGridValues(grid, 4, grid.getWidth(), 2, grid.getHeight()); + + + initializeTestGrid(grid); + nav_grid::NavGridInfo bump_far_right_info = grid.getInfo(); + bump_far_right_info.origin_x = 30; + grid.updateInfo(bump_far_right_info); + checkUpdateGridValues(grid, 0, 0, 0, 0); +} + +TEST(VectorNavGrid, combined_changes) +{ + // This is not a complete set of possible combined changes, just enough to satisfy my curiousity + nav_grid::VectorNavGrid grid; + initializeTestGrid(grid); + checkUpdateGridValues(grid, 0, grid.getWidth(), 0, grid.getHeight()); + + nav_grid::NavGridInfo info1 = grid.getInfo(); + info1.width = 15; + info1.origin_x = -5.0; + grid.updateInfo(info1); + checkUpdateGridValues(grid, 5, grid.getWidth(), 0, grid.getHeight()); + + initializeTestGrid(grid); + nav_grid::NavGridInfo info2 = grid.getInfo(); + info2.width = 17; + info2.origin_x = -5.0; + grid.updateInfo(info2); + checkUpdateGridValues(grid, 5, grid.getWidth() - 2, 0, grid.getHeight()); + + initializeTestGrid(grid); + nav_grid::NavGridInfo info3 = grid.getInfo(); + info3.width = 2; + info3.origin_x = 2.0; + grid.updateInfo(info3); + checkUpdateGridValues(grid, 0, grid.getWidth(), 0, grid.getHeight()); + + initializeTestGrid(grid); + nav_grid::NavGridInfo info4 = grid.getInfo(); + info4.width = 20; + info4.height = 20; + info4.origin_x = -2.0; + info4.origin_y = -5.0; + grid.updateInfo(info4); + checkUpdateGridValues(grid, 2, 12, 5, 10); +} + +TEST(Index, comparison_tests) +{ + unsigned int N = 5; + for (unsigned int x0 = 0; x0 < N; ++x0) + { + for (unsigned int y0 = 0; y0 < N; ++y0) + { + nav_grid::Index index0(x0, y0); + + for (unsigned int x1 = 0; x1 < N; ++x1) + { + for (unsigned int y1 = 0; y1 < N; ++y1) + { + nav_grid::Index index1(x1, y1); + // Check equality and the test for equality that sets use + // See https://stackoverflow.com/a/1114862 + if (x0 == x1 && y0 == y1) + { + EXPECT_EQ(index0, index1); + EXPECT_TRUE(!(index0 < index1) && !(index1 < index0)); + EXPECT_GE(index0, index1); + EXPECT_LE(index0, index1); + EXPECT_GE(index1, index0); + EXPECT_LE(index1, index0); + } + else + { + EXPECT_NE(index0, index1); + EXPECT_FALSE(!(index0 < index1) && !(index1 < index0)); + if (x0 < x1 || (x0 == x1 && y0 < y1)) + { + EXPECT_LT(index0, index1); + EXPECT_GT(index1, index0); + EXPECT_LE(index0, index1); + EXPECT_GE(index1, index0); + } + else + { + EXPECT_GT(index0, index1); + EXPECT_LT(index1, index0); + EXPECT_GE(index0, index1); + EXPECT_LE(index1, index0); + } + } + } + } + } + } +} + +int main(int argc, char **argv) +{ + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/navigations/nav_grid_iterators/CMakeLists.txt b/navigations/nav_grid_iterators/CMakeLists.txt new file mode 100755 index 0000000..baba8c3 --- /dev/null +++ b/navigations/nav_grid_iterators/CMakeLists.txt @@ -0,0 +1,58 @@ +cmake_minimum_required(VERSION 3.0.2) +project(nav_grid_iterators) +set_directory_properties(PROPERTIES COMPILE_OPTIONS "-std=c++11;-Wall;-Werror") + +find_package(catkin REQUIRED COMPONENTS + nav_grid nav_2d_msgs nav_2d_utils nav_msgs roscpp +) + +catkin_package( + CATKIN_DEPENDS nav_grid nav_2d_msgs nav_2d_utils nav_msgs roscpp + INCLUDE_DIRS include + LIBRARIES nav_grid_iterators +) + +add_library(nav_grid_iterators + src/whole_grid.cpp + src/sub_grid.cpp + src/circle_fill.cpp + src/circle_outline.cpp + src/spiral.cpp + src/bresenham.cpp + src/ray_trace.cpp + src/line.cpp + src/polygon_outline.cpp + src/polygon_fill.cpp +) + +target_link_libraries( + nav_grid_iterators ${catkin_LIBRARIES} +) + +add_executable(demo demo/demo.cpp) +add_dependencies(demo ${catkin_EXPORTED_TARGETS}) +target_link_libraries(demo nav_grid_iterators ${catkin_LIBRARIES}) + +include_directories( + include ${catkin_INCLUDE_DIRS} +) + +if (CATKIN_ENABLE_TESTING) + find_package(roslint REQUIRED) + roslint_cpp() + roslint_add_test() + + catkin_add_gtest(line_tests test/line_tests.cpp) + target_link_libraries(line_tests nav_grid_iterators) + catkin_add_gtest(${PROJECT_NAME}_utest test/utest.cpp) + target_link_libraries(${PROJECT_NAME}_utest nav_grid_iterators) +endif (CATKIN_ENABLE_TESTING) + +install(TARGETS nav_grid_iterators + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} +) +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} +) diff --git a/navigations/nav_grid_iterators/README.md b/navigations/nav_grid_iterators/README.md new file mode 100755 index 0000000..9d27024 --- /dev/null +++ b/navigations/nav_grid_iterators/README.md @@ -0,0 +1,32 @@ +# nav_grid_iterators + +This package provides C++ iterators for iterating over some portion of a `NavGrid`. There are two sets. The first are signed line iterators which are not constrained to valid `NavGrid` indexes. Second, are the general iterators which are constrained to valid `NavGrid` indexes. + +## Signed Line Iteration +As a building block for the general iterators, we provide two line iterators that iterate over `int` coordinates. Both take two pairs of coordinates for start and end points, as well as a boolean for whether to include the coordinates of the end point in the iteration. + * [`Bresenham`](include/nav_grid_iterators/line/bresenham.h) takes integer coordinates as input and implements [Bresenham's line algorithm](https://en.wikipedia.org/wiki/Bresenham%27s_line_algorithm), which means that there is either only one cell per column or one cell per row. + * [`RayTrace`](include/nav_grid_iterators/line/ray_trace.h) takes double coordinates as input and implements [Ray tracing](https://en.wikipedia.org/wiki/Ray_tracing_(graphics)), which means that it iterates over all cells that the line passes through, even if only briefly. + +## General Iterators + * [`WholeGrid`](include/nav_grid_iterators/whole_grid.h) iterates over every cell in the grid in row major order. + * [`SubGrid`](include/nav_grid_iterators/sub_grid.h) iterates over a rectangular subportion of the grid in row major order. + * [`Line`](include/nav_grid_iterators/line.h) iterates over a line, using either of the above algorithms, but the coordinates are constrained to the grid. + * [`PolygonFill`](include/nav_grid_iterators/polygon_fill.h) iterates over all the cells whose centers fall within a `nav_2d_msgs::Polygon2D` + * [`PolygonOutline`](include/nav_grid_iterators/polygon_outline.h) iterates over the outline of a `nav_2d_msgs::Polygon2D` using either of the two above line iterators. + * [`CircleFill`](include/nav_grid_iterators/circle_fill.h) iterates over all the cells whose centers fall within a given circle, iterating in row major order. + * [`Spiral`](include/nav_grid_iterators/spiral.h) iterates over the same cells as `CircleFill` but from the center of the circle outward. + * [`CircleOutline`](include/nav_grid_iterators/circle_outline.h) iterates around the outline of a circle. + +# Demo +A demonstration of all the general iterators can be seen by running `roslaunch nav_grid_iterators demo.launch` or by looking at [this video](demo/demo.mp4). + * The purple iterator is `WholeGrid` + * The bottom row, left to right, are + * `SubGrid` (green) + * `PolygonFill` (yellow) + * `PolygonOutline+Bresenham` (blue) + * `PolygonOutline+RayTrace` (blue) + * In the middle are a `Line+Bresenham` (bottom) and a `Line+RayTrace` (top) + * The top row, left to right, are + * `CircleFill` (grey) + * `Spiral` (green) + * `CircleOutline` (cyan) diff --git a/navigations/nav_grid_iterators/demo/demo.cpp b/navigations/nav_grid_iterators/demo/demo.cpp new file mode 100755 index 0000000..ffa0ae3 --- /dev/null +++ b/navigations/nav_grid_iterators/demo/demo.cpp @@ -0,0 +1,160 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include +#include +#include +#include +#include + +template +class InfiniteIterator +{ +public: + InfiniteIterator(Iterator it, unsigned char active_value, unsigned char seen_value) + : it_(it), active_(active_value), seen_(seen_value) + { + } + + void iterate(nav_grid::NavGrid& grid) + { + // Note that this demo assumes that each iterator has at least one point on the grid + grid.setValue(*it_, seen_); + ++it_; + if (it_ == it_.end()) + { + it_ = it_.begin(); + } + grid.setValue(*it_, active_); + } + +private: + Iterator it_; + unsigned char active_, seen_; +}; + +int main(int argc, char** argv) +{ + ros::init(argc, argv, "iterator_demo"); + nav_grid::VectorNavGrid grid; + nav_grid::NavGridInfo info; + sleep(5.0); + info.width = 75; + info.height = 60; + info.resolution = 0.1; + grid.setInfo(info); + + ros::NodeHandle nh("~"); + ros::Publisher pub = nh.advertise("/map", 1); + ros::Rate r(33); + + nav_2d_msgs::Polygon2D triangle; + triangle.points.resize(3); + triangle.points[0].x = 1.9; + triangle.points[0].y = 0.5; + triangle.points[1].x = 3.5; + triangle.points[1].y = 1.0; + triangle.points[2].x = 2.0; + triangle.points[2].y = 2.4; + + nav_2d_msgs::Polygon2D diamond; + diamond.points.resize(4); + diamond.points[0].x = 4.5; + diamond.points[0].y = 0.0; + diamond.points[1].x = 5.3; + diamond.points[1].y = 1.25; + diamond.points[2].x = 4.5; + diamond.points[2].y = 2.5; + diamond.points[3].x = 3.7; + diamond.points[3].y = 1.25; + + nav_2d_msgs::Polygon2D diamond2; + diamond2.points.resize(4); + diamond2.points[0].x = 6.5; + diamond2.points[0].y = 0.0; + diamond2.points[1].x = 7.3; + diamond2.points[1].y = 1.25; + diamond2.points[2].x = 6.5; + diamond2.points[2].y = 2.5; + diamond2.points[3].x = 5.7; + diamond2.points[3].y = 1.25; + + InfiniteIterator whole_grid(nav_grid_iterators::WholeGrid(&info), 100, 50); + InfiniteIterator sub_grid(nav_grid_iterators::SubGrid(&info, 3, 5, 14, 15), 99, 101); + InfiniteIterator line(nav_grid_iterators::Line(&info, 7.3, 2.8, 0.2, 2.5), 126, 200); + InfiniteIterator line2(nav_grid_iterators::Line(&info, 7.3, 3.3, 0.2, 3.0, true, false), + 126, 200); + InfiniteIterator circle_fill(nav_grid_iterators::CircleFill(&info, 1.25, 4.8, 1.0), + 254, 255); + InfiniteIterator spiral(nav_grid_iterators::Spiral(&info, 3.75, 4.8, 1.0), 254, 126); + InfiniteIterator circle_o(nav_grid_iterators::CircleOutline(&info, 6.25, 4.8, 1.0), + 254, 99); + InfiniteIterator poly_f(nav_grid_iterators::PolygonFill(&info, triangle), 126, 254); + InfiniteIterator poly_o(nav_grid_iterators::PolygonOutline(&info, diamond), 0, 1); + InfiniteIterator poly_r(nav_grid_iterators::PolygonOutline(&info, diamond2, 0), + 0, 1); + + nav_msgs::OccupancyGrid ogrid; + ogrid.header.frame_id = info.frame_id; + ogrid.info = nav_2d_utils::infoToInfo(info); + ogrid.data.resize(info.width * info.height); + + while (ros::ok()) + { + whole_grid.iterate(grid); + sub_grid.iterate(grid); + line.iterate(grid); + line2.iterate(grid); + circle_fill.iterate(grid); + spiral.iterate(grid); + circle_o.iterate(grid); + poly_f.iterate(grid); + poly_o.iterate(grid); + poly_r.iterate(grid); + + // Manaully creating OccupancyGrid (rather than use nav_grid_pub_sub) to avoid circular dependency + ogrid.header.stamp = ros::Time::now(); + + unsigned int data_index = 0; + for (const nav_grid::Index& index : nav_grid_iterators::WholeGrid(info)) + { + ogrid.data[data_index++] = grid(index); + } + pub.publish(ogrid); + r.sleep(); + } + + return 0; +} diff --git a/navigations/nav_grid_iterators/demo/demo.launch b/navigations/nav_grid_iterators/demo/demo.launch new file mode 100755 index 0000000..a88c413 --- /dev/null +++ b/navigations/nav_grid_iterators/demo/demo.launch @@ -0,0 +1,4 @@ + + + + diff --git a/navigations/nav_grid_iterators/demo/demo.mp4 b/navigations/nav_grid_iterators/demo/demo.mp4 new file mode 100755 index 0000000..5fe880a Binary files /dev/null and b/navigations/nav_grid_iterators/demo/demo.mp4 differ diff --git a/navigations/nav_grid_iterators/demo/demo.rviz b/navigations/nav_grid_iterators/demo/demo.rviz new file mode 100755 index 0000000..ba2c32a --- /dev/null +++ b/navigations/nav_grid_iterators/demo/demo.rviz @@ -0,0 +1,19 @@ +Visualization Manager: + Displays: + - Class: rviz/Map + Color Scheme: costmap + Enabled: true + Name: Map + Topic: /map + Views: + Current: + Angle: 0 + Class: rviz/TopDownOrtho + Name: Current View + Scale: 100 + Value: TopDownOrtho (rviz) + X: 3.5 + Y: 2.5 +Window Geometry: + Height: 1400 + Width: 2500 diff --git a/navigations/nav_grid_iterators/include/nav_grid_iterators/base_iterator.h b/navigations/nav_grid_iterators/include/nav_grid_iterators/base_iterator.h new file mode 100755 index 0000000..874a20f --- /dev/null +++ b/navigations/nav_grid_iterators/include/nav_grid_iterators/base_iterator.h @@ -0,0 +1,139 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef NAV_GRID_ITERATORS_BASE_ITERATOR_H +#define NAV_GRID_ITERATORS_BASE_ITERATOR_H + +#include +#include + +namespace nav_grid_iterators +{ +template +class BaseIterator +{ +public: + /** + * @brief Public Constructor. Takes in a pointer to the info and starts at the minimum index + * @param info NavGridInfo for the grid to iterate over + */ + explicit BaseIterator(const nav_grid::NavGridInfo* info) : BaseIterator(info, nav_grid::Index(0, 0)) {} + + /** + * @brief Public Constructor. Takes in a reference to the info and starts at the minimum index + * @param info NavGridInfo for the grid to iterate over + */ + explicit BaseIterator(const nav_grid::NavGridInfo& info) : BaseIterator(&info, nav_grid::Index(0, 0)) {} + + /** + * @brief Destructor + */ + virtual ~BaseIterator() = default; + + /** + * @brief Helper function for range-style iteration + * Equivalent to the above constructor + * @return Iterator representing beginning of the iteration + */ + virtual Derived begin() const = 0; + + /** + * @brief Helper function for range-style iteration + * @return Iterator representing end of the iteration, with an invalid index + */ + virtual Derived end() const = 0; + + /** + * @brief Test if two iterators are equivalent + * + * Derived classes may want to implement the fieldsEqual function + * for checking if additional fields beyond the index and info are equal. + */ + bool operator==(const Derived& other) { return info_ == other.info_ && index_ == other.index_ && fieldsEqual(other); } + + /** + * @brief Test if two iterators are not equivalent - required for testing if iterator is at the end + */ + bool operator!=(const Derived& other) { return !(*this == other); } + + /** + * @brief Additional check for whether fields of derived iterators are equal. + * + * Helps make overriding the == operator easy. + */ + virtual bool fieldsEqual(const Derived& other) { return true; } + + /** + * @brief Dereference the iterator + * @return the index to which the iterator is pointing. + */ + const nav_grid::Index& operator*() const { return index_; } + + /** + * @brief Increase the iterator to the next element. + * @return a reference to the updated iterator. + */ + Derived& operator++() + { + increment(); + return *static_cast(this); + } + + /** + * @brief Increase the iterator to the next element. + */ + virtual void increment() = 0; + + using self_type = Derived; + using value_type = nav_grid::Index; + using reference = nav_grid::Index&; + using pointer = nav_grid::Index*; + using iterator_category = std::input_iterator_tag; + using difference_type = int; + + +protected: + /** + * @brief Protected constructor that takes in an arbitrary index + * @param info NavGridInfo for the grid to iterate over + * @param index Initial index + */ + BaseIterator(const nav_grid::NavGridInfo* info, const nav_grid::Index& index) : info_(info), index_(index) {} + + const nav_grid::NavGridInfo* info_; + nav_grid::Index index_; +}; +} // namespace nav_grid_iterators + +#endif // NAV_GRID_ITERATORS_BASE_ITERATOR_H diff --git a/navigations/nav_grid_iterators/include/nav_grid_iterators/circle_fill.h b/navigations/nav_grid_iterators/include/nav_grid_iterators/circle_fill.h new file mode 100755 index 0000000..be6c5e9 --- /dev/null +++ b/navigations/nav_grid_iterators/include/nav_grid_iterators/circle_fill.h @@ -0,0 +1,113 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef NAV_GRID_ITERATORS_CIRCLE_FILL_H +#define NAV_GRID_ITERATORS_CIRCLE_FILL_H + +#include +#include +#include + +namespace nav_grid_iterators +{ +/** + * @class CircleFill + * @brief Iterates over all of the valid indexes that lie within a circle in row major order + */ +class CircleFill : public BaseIterator +{ +public: + /** + * @brief Public Constructor. + * @param info NavGridInfo for the grid to iterate over + * @param center_x Center of the circle (x coordinate) + * @param center_y Center of the circle (y coordinate) + * @param radius Size of the circle + */ + CircleFill(const nav_grid::NavGridInfo* info, double center_x, double center_y, double radius); + + /** + * @brief Copy Constructor + * Required to ensure unique_ptr is set properly + */ + CircleFill(const CircleFill& other); + + /** + * @brief Assignment Operator + * Required to ensure unique_ptr is set properly + */ + CircleFill& operator=(const CircleFill& other); + + /**@name Standard BaseIterator Interface */ + /**@{*/ + CircleFill begin() const override; + CircleFill end() const override; + void increment() override; + bool fieldsEqual(const CircleFill& other) override; + /**@}*/ + +protected: + /** + * @brief Protected constructor that takes in an arbitrary index and other internal parameters + * @param info NavGridInfo for the grid to iterate over + * @param index Initial index + * @param center_x Center of the circle (x coordinate) + * @param center_y Center of the circle (y coordinate) + * @param radius_sq Square of the size of the circle + * @param min_x Minimum valid index that is within the circle (x coordinate) + * @param min_y Minimum valid index that is within the circle (y coordinate) + * @param width Maximum number of valid indexes in a row of the circle + * @param height Maximum number of of valid indexes in a column of the circle + * @param start_index The first valid index in the minimum row + */ + CircleFill(const nav_grid::NavGridInfo* info, const nav_grid::Index& index, double center_x, double center_y, + double radius_sq, unsigned int min_x, unsigned int min_y, unsigned int width, unsigned int height, + const nav_grid::Index& start_index); + + + /** + * @brief Check if coordinates are inside the circle. + * @return true if inside, false otherwise. + */ + bool isInside(unsigned int x, unsigned int y) const; + + double center_x_, center_y_, radius_sq_; + unsigned int min_x_, min_y_, width_, height_; + nav_grid::Index start_index_; + std::unique_ptr internal_iterator_; +}; +} // namespace nav_grid_iterators + + +#endif // NAV_GRID_ITERATORS_CIRCLE_FILL_H diff --git a/navigations/nav_grid_iterators/include/nav_grid_iterators/circle_outline.h b/navigations/nav_grid_iterators/include/nav_grid_iterators/circle_outline.h new file mode 100755 index 0000000..a5a943d --- /dev/null +++ b/navigations/nav_grid_iterators/include/nav_grid_iterators/circle_outline.h @@ -0,0 +1,124 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef NAV_GRID_ITERATORS_CIRCLE_OUTLINE_H +#define NAV_GRID_ITERATORS_CIRCLE_OUTLINE_H + +#include + +namespace nav_grid_iterators +{ + +/** + * @brief returns the sign of a number + * @param val number + * @return 1 if positive, 0 if 0, -1 if negative + */ +inline int signum(const int val) +{ + return (0 < val) - (val < 0); +} + +/** + * @class CircleOutline + * @brief Iterates over the valid indexes that lie on the outline of a circle + */ +class CircleOutline : public BaseIterator +{ +public: + /** + * @brief Public Constructor. + * @param info NavGridInfo for the grid to iterate over + * @param center_x Center of the circle (x coordinate) + * @param center_y Center of the circle (y coordinate) + * @param radius Size of the circle + */ + CircleOutline(const nav_grid::NavGridInfo* info, double center_x, double center_y, double radius); + + + /** + * @brief Public Constructor with integer radius. + * @param info NavGridInfo for the grid to iterate over + * @param center_x Center of the circle (x coordinate) + * @param center_y Center of the circle (y coordinate) + * @param radius Size of the circle + */ + CircleOutline(const nav_grid::NavGridInfo* info, double center_x, double center_y, unsigned int radius); + + /**@name Standard BaseIterator Interface */ + /**@{*/ + CircleOutline begin() const override; + CircleOutline end() const override; + void increment() override; + bool fieldsEqual(const CircleOutline& other) override; + /**@}*/ + +protected: + /** + * @brief Protected constructor that takes in an arbitrary index and other internal parameters + * @param info NavGridInfo for the grid to iterate over + * @param index Initial index + * @param center_index_x Index of the center of the circle (x coordinate) + * @param center_index_y Index of the center of the circle (y coordinate) + * @param distance The number of cells in the radius of the circle + * @param init Whether the first cell has been visited or not + * @param start_index The first valid index in the minimum row + */ + CircleOutline(const nav_grid::NavGridInfo* info, const nav_grid::Index& index, int center_index_x, int center_index_y, + unsigned int distance, bool init, const nav_grid::Index& start_index); + + + /** + * @brief Check if arbitrary coordinates are within the grid + * @return true if inside grid, false otherwise. + */ + bool isValidIndex(int x, int y) const; + + /** + * @brief Check if a cell with the given distance from the center of the circle is on the outline of the circle + * @return true if the distance to the cell when rounded to an integer is equal to the distance_ + */ + bool isOnOutline(int dx, int dy) const; + + int center_index_x_, center_index_y_; + unsigned int distance_; + bool init_; + int signed_width_, signed_height_; + int point_x_, point_y_; + nav_grid::Index start_index_; +}; +} // namespace nav_grid_iterators + + +#endif // NAV_GRID_ITERATORS_CIRCLE_OUTLINE_H diff --git a/navigations/nav_grid_iterators/include/nav_grid_iterators/iterators.h b/navigations/nav_grid_iterators/include/nav_grid_iterators/iterators.h new file mode 100755 index 0000000..efe8448 --- /dev/null +++ b/navigations/nav_grid_iterators/include/nav_grid_iterators/iterators.h @@ -0,0 +1,47 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef NAV_GRID_ITERATORS_ITERATORS_H +#define NAV_GRID_ITERATORS_ITERATORS_H + +#include +#include +#include +#include +#include +#include +#include +#include + +#endif // NAV_GRID_ITERATORS_ITERATORS_H diff --git a/navigations/nav_grid_iterators/include/nav_grid_iterators/line.h b/navigations/nav_grid_iterators/include/nav_grid_iterators/line.h new file mode 100755 index 0000000..4df194d --- /dev/null +++ b/navigations/nav_grid_iterators/include/nav_grid_iterators/line.h @@ -0,0 +1,115 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef NAV_GRID_ITERATORS_LINE_H +#define NAV_GRID_ITERATORS_LINE_H + +#include +#include +#include + +namespace nav_grid_iterators +{ +/** + * @class Line + * @brief Iterates over all of the valid indexes of a line + */ +class Line : public BaseIterator +{ +public: + /** + * @brief Public Constructor. + * @param info NavGridInfo for the grid to iterate over + * @param x0 Start x coordinate + * @param y0 Start y coordinate + * @param x1 End x coordinate + * @param y1 End y coordinate + * @param include_last_index If true, will include the end coordinates. + */ + Line(const nav_grid::NavGridInfo* info, double x0, double y0, double x1, double y1, + bool include_last_index = true, bool bresenham = true); + + /** + * @brief Copy Constructor + * Required to ensure unique_ptr is set properly + */ + Line(const Line& other); + + /** + * @brief Assignment Operator + * Required to ensure unique_ptr is set properly + */ + Line& operator=(const Line& other); + + /**@name Standard BaseIterator Interface */ + /**@{*/ + Line begin() const override; + Line end() const override; + void increment() override; + bool fieldsEqual(const Line& other) override; + /**@}*/ + +protected: + /** + * @brief Protected constructor that takes in an arbitrary index and other internal parameters + * @param info NavGridInfo for the grid to iterate over + * @param index Initial index + * @param x0 Start x coordinate + * @param y0 Start y coordinate + * @param x1 End x coordinate + * @param y1 End y coordinate + * @param include_last_index If true, will include the end coordinates. + * @param start_index The first valid index + * @param end_index The first invalid index + */ + Line(const nav_grid::NavGridInfo* info, const nav_grid::Index& index, double x0, double y0, double x1, double y1, + bool include_last_index, bool bresenham, nav_grid::Index start_index, nav_grid::Index end_index); + + void constructIterator(); + + /** + * @brief Check if a SignedIndex is within the bounds of the NavGrid + */ + bool inBounds(const nav_grid::SignedIndex& sindex); + + std::unique_ptr internal_iterator_; + double x0_, y0_, x1_, y1_; + bool include_last_index_; + bool bresenham_; + int signed_width_, signed_height_; + nav_grid::Index start_index_, end_index_; +}; +} // namespace nav_grid_iterators + +#endif // NAV_GRID_ITERATORS_LINE_H diff --git a/navigations/nav_grid_iterators/include/nav_grid_iterators/line/abstract_line_iterator.h b/navigations/nav_grid_iterators/include/nav_grid_iterators/line/abstract_line_iterator.h new file mode 100755 index 0000000..883ede9 --- /dev/null +++ b/navigations/nav_grid_iterators/include/nav_grid_iterators/line/abstract_line_iterator.h @@ -0,0 +1,89 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef NAV_GRID_ITERATORS_LINE_ABSTRACT_LINE_ITERATOR_H +#define NAV_GRID_ITERATORS_LINE_ABSTRACT_LINE_ITERATOR_H + +#include + +namespace nav_grid_iterators +{ +/** + * @class AbstractLineIterator + * @brief Abstract class for iterating over lines. + * + * Not constrained by a bounding box from NavGridInfo, i.e. can include positive and negative indexes + */ +class AbstractLineIterator +{ +public: + /** + * @brief Public Constructor + */ + AbstractLineIterator() {} + + /** + * @brief Public Destructor + */ + virtual ~AbstractLineIterator() = default; + + /** + * @brief Dereference the iterator + * @return the index to which the iterator is pointing. + */ + const nav_grid::SignedIndex& operator*() const { return index_; } + + virtual nav_grid::SignedIndex getFinalIndex() const = 0; + + bool isFinished() + { + return getFinalIndex() == index_; + } + + /** + * @brief Increase the iterator to the next element. + */ + virtual void increment() = 0; + +protected: + /** + * @brief Protected Constructor - takes arbitrary index + */ + explicit AbstractLineIterator(nav_grid::SignedIndex index) : index_(index) {} + nav_grid::SignedIndex index_; +}; + +} // namespace nav_grid_iterators + +#endif // NAV_GRID_ITERATORS_LINE_ABSTRACT_LINE_ITERATOR_H diff --git a/navigations/nav_grid_iterators/include/nav_grid_iterators/line/bresenham.h b/navigations/nav_grid_iterators/include/nav_grid_iterators/line/bresenham.h new file mode 100755 index 0000000..03c38ff --- /dev/null +++ b/navigations/nav_grid_iterators/include/nav_grid_iterators/line/bresenham.h @@ -0,0 +1,136 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef NAV_GRID_ITERATORS_LINE_BRESENHAM_H +#define NAV_GRID_ITERATORS_LINE_BRESENHAM_H + +#include + +namespace nav_grid_iterators +{ +/** + * @class Bresenham + * @brief Line Iterator using Bresenham's algorithm (no subpixel precision) + */ +class Bresenham : public AbstractLineIterator +{ +public: + /** + * @brief Public constructor + * @param x0 Start x coordinate + * @param y0 Start y coordinate + * @param x1 End x coordinate + * @param y1 End y coordinate + * @param include_last_index If true, will include the end coordinates. + */ + Bresenham(int x0, int y0, int x1, int y1, bool include_last_index = true); + + /** + * @brief Test if two iterators are equivalent + */ + bool operator==(const Bresenham& other) + { + return x0_ == other.x0_ && y0_ == other.y0_ && x1_ == other.x1_ && y1_ == other.y1_ && index_ == other.index_; + } + + /** + * @brief Test if two iterators are not equivalent - required for testing if iterator is at the end + */ + bool operator!=(const Bresenham& other) { return !(*this == other); } + + /** + * @brief Helper function for range-style iteration + * @return Iterator representing beginning of the iteration + */ + Bresenham begin() const; + + /** + * @brief Helper function for range-style iteration + * @return Iterator representing end of the iteration, with an invalid index + */ + Bresenham end() const; + + nav_grid::SignedIndex getFinalIndex() const override; + void increment() override; + + /** + * @brief Increase the iterator to the next element. + * @return a reference to the updated iterator. + */ + Bresenham& operator++() + { + increment(); + return *this; + } + + using self_type = Bresenham; + using value_type = nav_grid::SignedIndex; + using reference = nav_grid::SignedIndex&; + using pointer = nav_grid::SignedIndex*; + using iterator_category = std::input_iterator_tag; + using difference_type = int; + +protected: + /** + * @brief Protected constructor that takes in an arbitrary index and other internal parameters + * @param index Initial index + * @param x0 Start x coordinate + * @param y0 Start y coordinate + * @param x1 End x coordinate + * @param y1 End y coordinate + * @param include_last_index If true, will include the end coordinates. + * @param error_inc_x + * @param loop_inc_x + * @param error_inc_y + * @param loop_inc_y + * @param denominator + * @param numerator + * @param numerator_inc + */ + Bresenham(const nav_grid::SignedIndex& index, + int x0, int y0, int x1, int y1, bool include_last_index, + int error_inc_x, int loop_inc_x, int error_inc_y, int loop_inc_y, + int denominator, int numerator, int numerator_inc); + + + int x0_, y0_, x1_, y1_; + bool include_last_index_; + int error_inc_x_, loop_inc_x_, error_inc_y_, loop_inc_y_; + int denominator_, numerator_, numerator_inc_; +}; + + +} // namespace nav_grid_iterators + +#endif // NAV_GRID_ITERATORS_LINE_BRESENHAM_H diff --git a/navigations/nav_grid_iterators/include/nav_grid_iterators/line/ray_trace.h b/navigations/nav_grid_iterators/include/nav_grid_iterators/line/ray_trace.h new file mode 100755 index 0000000..5a87a93 --- /dev/null +++ b/navigations/nav_grid_iterators/include/nav_grid_iterators/line/ray_trace.h @@ -0,0 +1,132 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef NAV_GRID_ITERATORS_LINE_RAY_TRACE_H +#define NAV_GRID_ITERATORS_LINE_RAY_TRACE_H + +#include + +namespace nav_grid_iterators +{ +/** + * @class RayTrace + * @brief Line Iterator with Ray Tracing (subpixel accuracy) + */ +class RayTrace : public AbstractLineIterator +{ +public: + /** + * @brief Public constructor + * @param x0 Start x coordinate + * @param y0 Start y coordinate + * @param x1 End x coordinate + * @param y1 End y coordinate + * @param include_last_index If true, will include the end coordinates. + */ + RayTrace(double x0, double y0, double x1, double y1, bool include_last_index = true); + + /** + * @brief Test if two iterators are equivalent + */ + bool operator==(const RayTrace& other) + { + return x0_ == other.x0_ && y0_ == other.y0_ && x1_ == other.x1_ && y1_ == other.y1_ && index_ == other.index_; + } + + /** + * @brief Test if two iterators are not equivalent - required for testing if iterator is at the end + */ + bool operator!=(const RayTrace& other) { return !(*this == other); } + + /** + * @brief Helper function for range-style iteration + * @return Iterator representing beginning of the iteration + */ + RayTrace begin() const; + + /** + * @brief Helper function for range-style iteration + * @return Iterator representing end of the iteration, with an invalid index + */ + RayTrace end() const; + + nav_grid::SignedIndex getFinalIndex() const override; + void increment() override; + + /** + * @brief Increase the iterator to the next element. + * @return a reference to the updated iterator. + */ + RayTrace& operator++() + { + increment(); + return *this; + } + + using self_type = RayTrace; + using value_type = nav_grid::SignedIndex; + using reference = nav_grid::SignedIndex&; + using pointer = nav_grid::SignedIndex*; + using iterator_category = std::input_iterator_tag; + using difference_type = int; + +protected: + /** + * @brief Protected constructor that takes in an arbitrary index and other internal parameters + * @param index Initial index + * @param x0 Start x coordinate + * @param y0 Start y coordinate + * @param x1 End x coordinate + * @param y1 End y coordinate + * @param include_last_index If true, will include the end coordinates. + * @param dx + * @param dy + * @param initial_error + * @param loop_inc_x + * @param loop_inc_y + */ + RayTrace(const nav_grid::SignedIndex& index, + double x0, double y0, double x1, double y1, bool include_last_index, + double dx, double dy, double initial_error, int loop_inc_x, int loop_inc_y); + + + double x0_, y0_, x1_, y1_; + bool include_last_index_; + double dx_, dy_, error_, initial_error_; + int loop_inc_x_, loop_inc_y_; +}; + +} // namespace nav_grid_iterators + +#endif // NAV_GRID_ITERATORS_LINE_RAY_TRACE_H diff --git a/navigations/nav_grid_iterators/include/nav_grid_iterators/polygon_fill.h b/navigations/nav_grid_iterators/include/nav_grid_iterators/polygon_fill.h new file mode 100755 index 0000000..7c094c6 --- /dev/null +++ b/navigations/nav_grid_iterators/include/nav_grid_iterators/polygon_fill.h @@ -0,0 +1,109 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef NAV_GRID_ITERATORS_POLYGON_FILL_H +#define NAV_GRID_ITERATORS_POLYGON_FILL_H + +#include +#include +#include +#include + +namespace nav_grid_iterators +{ +/** + * @class PolygonFill + * @brief Iterates over all of the valid indexes that lie within an arbitrary polygon in row major order + */ +class PolygonFill : public BaseIterator +{ +public: + /** + * @brief Public Constructor. + * @param info NavGridInfo for the grid to iterate over + * @param polygon Polygon to iterate over + */ + PolygonFill(const nav_grid::NavGridInfo* info, nav_2d_msgs::Polygon2D polygon); + + /** + * @brief Copy Constructor + * Required to ensure unique_ptr is set properly + */ + PolygonFill(const PolygonFill& other); + + /** + * @brief Assignment Operator + * Required to ensure unique_ptr is set properly + */ + PolygonFill& operator=(const PolygonFill& other); + + /**@name Standard BaseIterator Interface */ + /**@{*/ + PolygonFill begin() const override; + PolygonFill end() const override; + void increment() override; + bool fieldsEqual(const PolygonFill& other) override; + /**@}*/ + +protected: + /** + * @brief Protected constructor that takes in an arbitrary index and other internal parameters + * @param info NavGridInfo for the grid to iterate over + * @param index Initial index + * @param polygon Polygon to iterate over + * @param min_x Minimum valid index that is within the polygon (x coordinate) + * @param min_y Minimum valid index that is within the polygon (y coordinate) + * @param width Maximum number of valid indexes in a row of the polygon + * @param height Maximum number of of valid indexes in a column of the polygon + * @param start_index The first valid index in the minimum row + */ + PolygonFill(const nav_grid::NavGridInfo* info, const nav_grid::Index& index, nav_2d_msgs::Polygon2D polygon, + unsigned int min_x, unsigned int min_y, unsigned int width, unsigned int height, + const nav_grid::Index& start_index); + + + /** + * @brief Check if given index is inside the polygon. + * @return true if inside, false otherwise. + */ + bool isInside(unsigned int x, unsigned int y) const; + + nav_2d_msgs::Polygon2D polygon_; + unsigned int min_x_, min_y_, width_, height_; + nav_grid::Index start_index_; + std::unique_ptr internal_iterator_; +}; +} // namespace nav_grid_iterators + +#endif // NAV_GRID_ITERATORS_POLYGON_FILL_H diff --git a/navigations/nav_grid_iterators/include/nav_grid_iterators/polygon_outline.h b/navigations/nav_grid_iterators/include/nav_grid_iterators/polygon_outline.h new file mode 100755 index 0000000..357aada --- /dev/null +++ b/navigations/nav_grid_iterators/include/nav_grid_iterators/polygon_outline.h @@ -0,0 +1,104 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef NAV_GRID_ITERATORS_POLYGON_OUTLINE_H +#define NAV_GRID_ITERATORS_POLYGON_OUTLINE_H + +#include +#include +#include +#include + +namespace nav_grid_iterators +{ +/** + * @class PolygonOutline + * @brief Iterates over all of the valid indexes on the outline of a polygon + */ +class PolygonOutline : public BaseIterator +{ +public: + /** + * @brief Public Constructor. + * @param info NavGridInfo for the grid to iterate over + * @param polygon Polygon to iterate over + */ + PolygonOutline(const nav_grid::NavGridInfo* info, nav_2d_msgs::Polygon2D polygon, bool bresenham = true); + + /** + * @brief Copy Constructor + * Required to ensure unique_ptr is set properly + */ + PolygonOutline(const PolygonOutline& other); + + /** + * @brief Assignment Operator + * Required to ensure unique_ptr is set properly + */ + PolygonOutline& operator=(const PolygonOutline& other); + + /**@name Standard BaseIterator Interface */ + /**@{*/ + PolygonOutline begin() const override; + PolygonOutline end() const override; + void increment() override; + bool fieldsEqual(const PolygonOutline& other) override; + /**@}*/ + +protected: + /** + * @brief Protected constructor that takes in an arbitrary index and other internal parameters + * @param info NavGridInfo for the grid to iterate over + * @param index Initial index + * @param polygon Polygon to iterate over + * @param side_index Which side we are currently iterating over + */ + PolygonOutline(const nav_grid::NavGridInfo* info, const nav_grid::Index& index, nav_2d_msgs::Polygon2D polygon, + bool bresenham, unsigned int side_index); + + /** + * @brief Given a new side index, loads the internal iterator. + * If there are no valid values in the internal iterator, increases the side index. + */ + void loadSide(); + + std::unique_ptr internal_iterator_; + nav_2d_msgs::Polygon2D polygon_; + nav_grid::Index start_index_; + bool bresenham_; + unsigned int side_index_; +}; +} // namespace nav_grid_iterators + +#endif // NAV_GRID_ITERATORS_POLYGON_OUTLINE_H diff --git a/navigations/nav_grid_iterators/include/nav_grid_iterators/spiral.h b/navigations/nav_grid_iterators/include/nav_grid_iterators/spiral.h new file mode 100755 index 0000000..666391a --- /dev/null +++ b/navigations/nav_grid_iterators/include/nav_grid_iterators/spiral.h @@ -0,0 +1,116 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef NAV_GRID_ITERATORS_SPIRAL_H +#define NAV_GRID_ITERATORS_SPIRAL_H + +#include +#include +#include + +namespace nav_grid_iterators +{ +/** + * @class Spiral + * @brief Iterates over all of the valid indexes that lie within a circle from the center out + */ +class Spiral : public BaseIterator +{ +public: + /** + * @brief Public Constructor. + * @param info NavGridInfo for the grid to iterate over + * @param center_x Center of the circle (x coordinate) + * @param center_y Center of the circle (y coordinate) + * @param radius Size of the circle + */ + Spiral(const nav_grid::NavGridInfo* info, double center_x, double center_y, double radius); + + /** + * @brief Copy Constructor + * Required to ensure unique_ptr is set properly + */ + Spiral(const Spiral& other); + + /** + * @brief Assignment Operator + * Required to ensure unique_ptr is set properly + */ + Spiral& operator=(const Spiral& other); + + /**@name Standard BaseIterator Interface */ + /**@{*/ + Spiral begin() const override; + Spiral end() const override; + void increment() override; + bool fieldsEqual(const Spiral& other) override; + /**@}*/ + +protected: + /** + * @brief Protected constructor that takes in an arbitrary index and other internal parameters + * @param info NavGridInfo for the grid to iterate over + * @param index Initial index + * @param center_x Center of the circle (x coordinate) + * @param center_y Center of the circle (y coordinate) + * @param radius_sq Square of the size of the circle + * @param distance Which ring of the spiral to start on + * @param max_distance The maximum valid ring + * @param start_index The first valid index in the spiral + */ + Spiral(const nav_grid::NavGridInfo* info, const nav_grid::Index& index, double center_x, double center_y, + double radius_sq, unsigned int distance, unsigned int max_distance, + const nav_grid::Index& start_index); + + /** + * @brief Given a new distance value, loads the internal iterator. + * If there are no valid values in the internal iterator, increases the distance. + */ + void loadRing(); + + /** + * @brief Check if the center of the given index is within the circle + * @return true if inside + */ + bool isInside(unsigned int x, unsigned int y) const; + + double center_x_, center_y_, radius_sq_; + unsigned int distance_, max_distance_; + nav_grid::Index start_index_; + std::unique_ptr internal_iterator_; +}; +} // namespace nav_grid_iterators + + +#endif // NAV_GRID_ITERATORS_SPIRAL_H diff --git a/navigations/nav_grid_iterators/include/nav_grid_iterators/sub_grid.h b/navigations/nav_grid_iterators/include/nav_grid_iterators/sub_grid.h new file mode 100755 index 0000000..60d195d --- /dev/null +++ b/navigations/nav_grid_iterators/include/nav_grid_iterators/sub_grid.h @@ -0,0 +1,104 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef NAV_GRID_ITERATORS_SUB_GRID_H +#define NAV_GRID_ITERATORS_SUB_GRID_H + +#include +#include + +namespace nav_grid_iterators +{ +/** + * @class SubGrid + * @brief Iterator for looping through every index within an aligned rectangular portion of the grid + */ +class SubGrid : public BaseIterator +{ +public: + /** + * @brief Public Constructor + * @param info NavGridInfo for the grid to iterate over + * @param min_x Minimum index (x coordinate) + * @param min_y Minimum index (y coordinate) + * @param width Number of indexes in the x direction + * @param height Number of indexes in the y direction + */ + SubGrid(const nav_grid::NavGridInfo* info, unsigned int min_x, unsigned int min_y, + unsigned int width, unsigned int height) + : SubGrid(info, nav_grid::Index(min_x, min_y), min_x, min_y, width, height) {} + + /** + * @brief Public Constructor using UIntBounds object + * @param info NavGridInfo for the grid to iterate over + * @param bounds UIntBounds + */ + SubGrid(const nav_grid::NavGridInfo* info, const nav_core2::UIntBounds& bounds) + : SubGrid(info, bounds.getMinX(), bounds.getMinY(), bounds.getWidth(), bounds.getHeight()) {} + + /** + * @brief Public constructor that takes in an arbitrary index + * @param info NavGridInfo for the grid to iterate over + * @param index Initial index + * @param min_x Minimum index (x coordinate) + * @param min_y Minimum index (y coordinate) + * @param width Number of indexes in the x direction + * @param height Number of indexes in the y direction + */ + SubGrid(const nav_grid::NavGridInfo* info, const nav_grid::Index& index, unsigned int min_x, unsigned int min_y, + unsigned int width, unsigned int height); + + /** + * @brief Public constructor using UIntBounds object that takes in an arbitrary index + * @param info NavGridInfo for the grid to iterate over + * @param index Initial index + * @param bounds UIntBounds + */ + SubGrid(const nav_grid::NavGridInfo* info, const nav_grid::Index& index, const nav_core2::UIntBounds& bounds) + : SubGrid(info, index, bounds.getMinX(), bounds.getMinY(), bounds.getWidth(), bounds.getHeight()) {} + + /**@name Standard BaseIterator Interface */ + /**@{*/ + SubGrid begin() const override; + SubGrid end() const override; + void increment() override; + bool fieldsEqual(const SubGrid& other) override; + /**@}*/ + +protected: + unsigned int min_x_, min_y_, width_, height_; +}; +} // namespace nav_grid_iterators + +#endif // NAV_GRID_ITERATORS_SUB_GRID_H diff --git a/navigations/nav_grid_iterators/include/nav_grid_iterators/whole_grid.h b/navigations/nav_grid_iterators/include/nav_grid_iterators/whole_grid.h new file mode 100755 index 0000000..3702d89 --- /dev/null +++ b/navigations/nav_grid_iterators/include/nav_grid_iterators/whole_grid.h @@ -0,0 +1,60 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef NAV_GRID_ITERATORS_WHOLE_GRID_H +#define NAV_GRID_ITERATORS_WHOLE_GRID_H + +#include + +namespace nav_grid_iterators +{ +/** + * @class WholeGrid + * An iterator that will iterate through all the cells of a grid in row-major order + */ +class WholeGrid : public BaseIterator +{ +public: + using BaseIterator::BaseIterator; + + /**@name Standard BaseIterator Interface */ + /**@{*/ + WholeGrid begin() const override; + WholeGrid end() const override; + void increment() override; + /**@}*/ +}; +} // namespace nav_grid_iterators + +#endif // NAV_GRID_ITERATORS_WHOLE_GRID_H diff --git a/navigations/nav_grid_iterators/package.xml b/navigations/nav_grid_iterators/package.xml new file mode 100755 index 0000000..542f49f --- /dev/null +++ b/navigations/nav_grid_iterators/package.xml @@ -0,0 +1,21 @@ + + + nav_grid_iterators + 0.3.0 + + Iterator implementations for moving around the cells of a nav_grid in a number of common patterns. + + + David V. Lu!! + + BSD + + catkin + nav_2d_msgs + nav_2d_utils + nav_grid + nav_msgs + roscpp + roslint + rosunit + diff --git a/navigations/nav_grid_iterators/src/bresenham.cpp b/navigations/nav_grid_iterators/src/bresenham.cpp new file mode 100755 index 0000000..511812c --- /dev/null +++ b/navigations/nav_grid_iterators/src/bresenham.cpp @@ -0,0 +1,120 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include + +namespace nav_grid_iterators +{ + +Bresenham::Bresenham(int x0, int y0, int x1, int y1, bool include_last_index) + : AbstractLineIterator(nav_grid::SignedIndex(x0, y0)), x0_(x0), y0_(y0), x1_(x1), y1_(y1), + include_last_index_(include_last_index) +{ + int dx = std::abs(x1_ - x0_); + int dy = std::abs(y1_ - y0_); + int xsign = x1_ >= x0_ ? 1 : -1; + int ysign = y1_ >= y0_ ? 1 : -1; + + if (dx >= dy) // There is at least one x-value for every y-value + { + loop_inc_x_ = xsign; + error_inc_x_ = 0; // Don't change the x when numerator >= denominator + loop_inc_y_ = 0; // Don't change the y for every iteration + error_inc_y_ = ysign; + + denominator_ = dx; + numerator_ = dx / 2; + numerator_inc_ = dy; + } + else // There is at least one y-value for every x-value + { + loop_inc_x_ = 0; // Don't change the x for every iteration + error_inc_x_ = xsign; + loop_inc_y_ = ysign; + error_inc_y_ = 0; // Don't change the y when numerator >= denominator + + denominator_ = dy; + numerator_ = dy / 2; + numerator_inc_ = dx; + } +} + +Bresenham::Bresenham(const nav_grid::SignedIndex& index, + int x0, int y0, int x1, int y1, bool include_last_index, + int error_inc_x, int loop_inc_x, int error_inc_y, int loop_inc_y, + int denominator, int numerator, int numerator_inc) + : AbstractLineIterator(index), x0_(x0), y0_(y0), x1_(x1), y1_(y1), include_last_index_(include_last_index), + error_inc_x_(error_inc_x), loop_inc_x_(loop_inc_x), error_inc_y_(error_inc_y), loop_inc_y_(loop_inc_y), + denominator_(denominator), numerator_(numerator), numerator_inc_(numerator_inc) +{ +} + +Bresenham Bresenham::begin() const +{ + return Bresenham(nav_grid::SignedIndex(x0_, y0_), x0_, y0_, x1_, y1_, include_last_index_, + error_inc_x_, loop_inc_x_, error_inc_y_, loop_inc_y_, + denominator_, numerator_, numerator_inc_); +} + +Bresenham Bresenham::end() const +{ + Bresenham end(nav_grid::SignedIndex(x1_, y1_), x0_, y0_, x1_, y1_, include_last_index_, + error_inc_x_, loop_inc_x_, error_inc_y_, loop_inc_y_, + denominator_, numerator_, numerator_inc_); + + // If we want the last_index, return an iterator that is whatever is one-past the end coordinates + if (include_last_index_) + end.increment(); + return end; +} + +void Bresenham::increment() +{ + numerator_ += numerator_inc_; // Increase the numerator by the top of the fraction + if (numerator_ >= denominator_) // Check if numerator >= denominator + { + numerator_ -= denominator_; // Calculate the new numerator value + index_.x += error_inc_x_; // Change the x as appropriate + index_.y += error_inc_y_; // Change the y as appropriate + } + index_.x += loop_inc_x_; // Change the x as appropriate + index_.y += loop_inc_y_; // Change the y as appropriate +} + +nav_grid::SignedIndex Bresenham::getFinalIndex() const +{ + return end().index_; +} +} // namespace nav_grid_iterators diff --git a/navigations/nav_grid_iterators/src/circle_fill.cpp b/navigations/nav_grid_iterators/src/circle_fill.cpp new file mode 100755 index 0000000..5190dfd --- /dev/null +++ b/navigations/nav_grid_iterators/src/circle_fill.cpp @@ -0,0 +1,141 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include + +namespace nav_grid_iterators +{ +CircleFill::CircleFill(const nav_grid::NavGridInfo* info, double center_x, double center_y, double radius) + : BaseIterator(info), center_x_(center_x), center_y_(center_y), start_index_(0, 0) +{ + radius_sq_ = radius * radius; + + double min_x = center_x_ - radius; + double max_x = center_x_ + radius; + double min_y = center_y_ - radius; + double max_y = center_y_ + radius; + + // Calculate and save the minimum coordinates + worldToGridBounded(*info_, min_x, min_y, min_x_, min_y_); + + // Calculate the max coordinates, and save the width/height + unsigned int max_x_grid, max_y_grid; + worldToGridBounded(*info_, max_x, max_y, max_x_grid, max_y_grid); + + width_ = max_x_grid - min_x_ + 1; + height_ = max_y_grid - min_y_ + 1; + + // Initialize internal iterator + internal_iterator_.reset(new SubGrid(info_, min_x_, min_y_, width_, height_)); + index_.x = min_x_; + index_.y = min_y_; + + // Iterate to first valid index + if (!isInside(min_x_, min_y_)) ++(*this); + start_index_ = **internal_iterator_; + index_ = start_index_; +} + +CircleFill::CircleFill(const nav_grid_iterators::CircleFill& other) + : CircleFill(other.info_, other.index_, other.center_x_, other.center_y_, other.radius_sq_, + other.min_x_, other.min_y_, other.width_, other.height_, other.start_index_) +{ +} + +CircleFill::CircleFill(const nav_grid::NavGridInfo* info, const nav_grid::Index& index, double center_x, + double center_y, double radius_sq, unsigned int min_x, unsigned int min_y, unsigned int width, + unsigned int height, const nav_grid::Index& start_index) + : BaseIterator(info, index), center_x_(center_x), center_y_(center_y), radius_sq_(radius_sq), + min_x_(min_x), min_y_(min_y), width_(width), height_(height), start_index_(start_index) +{ + internal_iterator_.reset(new SubGrid(info_, index_, min_x_, min_y_, width_, height_)); +} + +CircleFill& CircleFill::operator=(const CircleFill& other) +{ + info_ = other.info_; + index_ = other.index_; + center_x_ = other.center_x_; + center_y_ = other.center_y_; + radius_sq_ = other.radius_sq_; + min_x_ = other.min_x_; + min_y_ = other.min_y_; + width_ = other.width_; + height_ = other.height_; + start_index_ = other.start_index_; + internal_iterator_.reset(new SubGrid(info_, index_, min_x_, min_y_, width_, height_)); + return *this; +} + +bool CircleFill::isInside(unsigned int x, unsigned int y) const +{ + double wx, wy; + gridToWorld(*info_, x, y, wx, wy); + double dx = wx - center_x_; + double dy = wy - center_y_; + return (dx * dx + dy * dy) < radius_sq_; +} + +CircleFill CircleFill::begin() const +{ + return CircleFill(info_, start_index_, center_x_, center_y_, radius_sq_, min_x_, min_y_, width_, height_, + start_index_); +} + +CircleFill CircleFill::end() const +{ + return CircleFill(info_, *internal_iterator_->end(), center_x_, center_y_, radius_sq_, min_x_, min_y_, + width_, height_, start_index_); +} + +void CircleFill::increment() +{ + ++(*internal_iterator_); + index_ = **internal_iterator_; + while (*internal_iterator_ != internal_iterator_->end()) + { + if (isInside(index_.x, index_.y)) + break; + ++(*internal_iterator_); + index_ = **internal_iterator_; + } +} + +bool CircleFill::fieldsEqual(const CircleFill& other) +{ + return center_x_ == other.center_x_ && center_y_ == other.center_y_ && radius_sq_ == other.radius_sq_; +} + +} // namespace nav_grid_iterators diff --git a/navigations/nav_grid_iterators/src/circle_outline.cpp b/navigations/nav_grid_iterators/src/circle_outline.cpp new file mode 100755 index 0000000..a02d14b --- /dev/null +++ b/navigations/nav_grid_iterators/src/circle_outline.cpp @@ -0,0 +1,143 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include + +namespace nav_grid_iterators +{ +CircleOutline::CircleOutline(const nav_grid::NavGridInfo* info, double center_x, double center_y, double radius) + : CircleOutline(info, center_x, center_y, static_cast(ceil(radius / info->resolution))) +{ +} + +CircleOutline::CircleOutline(const nav_grid::NavGridInfo* info, double center_x, double center_y, unsigned int radius) + : BaseIterator(info), distance_(radius), init_(false) +{ + signed_width_ = static_cast(info->width); + signed_height_ = static_cast(info->height); + + // Calculate and save the center coordinates + worldToGrid(*info_, center_x, center_y, center_index_x_, center_index_y_); + + point_x_ = distance_; + point_y_ = 0; + + if (!isValidIndex(center_index_x_ + point_x_, center_index_y_ + point_y_)) + { + increment(); + init_ = !isValidIndex(center_index_x_ + point_x_, center_index_y_ + point_y_); + } + index_.x = center_index_x_ + point_x_; + index_.y = center_index_y_ + point_y_; + start_index_ = index_; +} + +CircleOutline::CircleOutline(const nav_grid::NavGridInfo* info, const nav_grid::Index& index, + int center_index_x, int center_index_y, unsigned int distance, + bool init, const nav_grid::Index& start_index) + : BaseIterator(info, index), + center_index_x_(center_index_x), center_index_y_(center_index_y), distance_(distance), init_(init), + start_index_(start_index) +{ + signed_width_ = static_cast(info->width); + signed_height_ = static_cast(info->height); + point_x_ = distance_; + point_y_ = 0; +} + +CircleOutline CircleOutline::begin() const +{ + return CircleOutline(info_, start_index_, center_index_x_, center_index_y_, + distance_, false, start_index_); +} + +CircleOutline CircleOutline::end() const +{ + return CircleOutline(info_, start_index_, center_index_x_, center_index_y_, + distance_, true, start_index_); +} + +void CircleOutline::increment() +{ + init_ = true; + while (true) + { + int nx = -signum(point_y_); + int ny = signum(point_x_); + if (nx != 0 && isOnOutline(point_x_ + nx, point_y_)) + { + point_x_ += nx; + } + else if (ny != 0 && isOnOutline(point_x_, point_y_ + ny)) + { + point_y_ += ny; + } + else + { + point_x_ += nx; + point_y_ += ny; + } + + if (isValidIndex(center_index_x_ + point_x_, center_index_y_ + point_y_)) + { + break; + } + if (point_x_ == static_cast(distance_) && point_y_ == 0) + { + index_ = start_index_; + return; + } + } + index_.x = center_index_x_ + point_x_; + index_.y = center_index_y_ + point_y_; +} + +bool CircleOutline::fieldsEqual(const CircleOutline& other) +{ + return center_index_x_ == other.center_index_x_ && center_index_y_ == other.center_index_y_ && + distance_ == other.distance_ && init_ == other.init_; +} + +bool CircleOutline::isValidIndex(int x, int y) const +{ + return x >= 0 && y >= 0 && x < signed_width_ && y < signed_height_; +} + +bool CircleOutline::isOnOutline(int dx, int dy) const +{ + return static_cast(hypot(dx, dy)) == distance_; +} + +} // namespace nav_grid_iterators diff --git a/navigations/nav_grid_iterators/src/line.cpp b/navigations/nav_grid_iterators/src/line.cpp new file mode 100755 index 0000000..4c992aa --- /dev/null +++ b/navigations/nav_grid_iterators/src/line.cpp @@ -0,0 +1,167 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include +#include +#include + +namespace nav_grid_iterators +{ +Line::Line(const nav_grid::NavGridInfo* info, double x0, double y0, double x1, double y1, + bool include_last_index, bool bresenham) + : BaseIterator(info), x0_(x0), y0_(y0), x1_(x1), y1_(y1), include_last_index_(include_last_index), + bresenham_(bresenham), start_index_(0, 0), end_index_(0, 0) +{ + constructIterator(); + + // Convenience variables to avoid mismatched comparisons + signed_width_ = static_cast(info->width); + signed_height_ = static_cast(info->height); + + // Cache the end index + nav_grid::SignedIndex end = internal_iterator_->getFinalIndex(); + end_index_.x = end.x; + end_index_.y = end.y; + + // Iterate to first valid index + nav_grid::SignedIndex sindex = **internal_iterator_; + while (!internal_iterator_->isFinished() && !inBounds(sindex)) + { + internal_iterator_->increment(); + sindex = **internal_iterator_; + } + + // If all the indices are invalid, explicitly set the start index to be invalid + if (internal_iterator_->isFinished()) + { + start_index_ = end_index_; + } + else + { + start_index_.x = sindex.x; + start_index_.y = sindex.y; + } + + index_ = start_index_; +} + +Line::Line(const Line& other) + : Line(other.info_, other.index_, other.x0_, other.y0_, other.x1_, other.y1_, other.include_last_index_, + other.bresenham_, other.start_index_, other.end_index_) +{ +} + +Line::Line(const nav_grid::NavGridInfo* info, const nav_grid::Index& index, double x0, double y0, double x1, double y1, + bool include_last_index, bool bresenham, nav_grid::Index start_index, nav_grid::Index end_index) + : BaseIterator(info, index), x0_(x0), y0_(y0), x1_(x1), y1_(y1), include_last_index_(include_last_index), + bresenham_(bresenham), start_index_(start_index), end_index_(end_index) +{ + constructIterator(); + signed_width_ = static_cast(info->width); + signed_height_ = static_cast(info->height); +} + +Line& Line::operator=(const Line& other) +{ + info_ = other.info_; + index_ = other.index_; + x0_ = other.x0_; + y0_ = other.y0_; + x1_ = other.x1_; + y1_ = other.y1_; + include_last_index_ = other.include_last_index_; + bresenham_ = other.bresenham_; + start_index_ = other.start_index_; + end_index_ = other.end_index_; + signed_width_ = other.signed_width_; + signed_height_ = other.signed_height_; + constructIterator(); + return *this; +} + +void Line::constructIterator() +{ + // translate coordinates into grid coordinates + double local_x0, local_y0, local_x1, local_y1; + worldToGrid(*info_, x0_, y0_, local_x0, local_y0); + worldToGrid(*info_, x1_, y1_, local_x1, local_y1); + + if (bresenham_) + { + internal_iterator_.reset(new Bresenham(local_x0, local_y0, local_x1, local_y1, include_last_index_)); + } + else + { + internal_iterator_.reset(new RayTrace(local_x0, local_y0, local_x1, local_y1, include_last_index_)); + } +} + +bool Line::inBounds(const nav_grid::SignedIndex& sindex) +{ + return sindex.x >= 0 && sindex.y >= 0 && sindex.x < signed_width_ && sindex.y < signed_height_; +} + +Line Line::begin() const +{ + return Line(info_, start_index_, x0_, y0_, x1_, y1_, include_last_index_, bresenham_, start_index_, end_index_); +} + +Line Line::end() const +{ + return Line(info_, end_index_, x0_, y0_, x1_, y1_, include_last_index_, bresenham_, start_index_, end_index_); +} + +void Line::increment() +{ + internal_iterator_->increment(); + nav_grid::SignedIndex sindex = **internal_iterator_; + if (!internal_iterator_->isFinished() && !inBounds(sindex)) + { + index_ = end_index_; + } + else + { + index_.x = sindex.x; + index_.y = sindex.y; + } +} + +bool Line::fieldsEqual(const Line& other) +{ + return x0_ == other.x0_ && y0_ == other.y0_ && x1_ == other.x1_ && y1_ == other.y1_ && + include_last_index_ == other.include_last_index_ && bresenham_ == other.bresenham_; +} + +} // namespace nav_grid_iterators diff --git a/navigations/nav_grid_iterators/src/polygon_fill.cpp b/navigations/nav_grid_iterators/src/polygon_fill.cpp new file mode 100755 index 0000000..0a28acd --- /dev/null +++ b/navigations/nav_grid_iterators/src/polygon_fill.cpp @@ -0,0 +1,153 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include +#include +#include + +namespace nav_grid_iterators +{ +PolygonFill::PolygonFill(const nav_grid::NavGridInfo* info, nav_2d_msgs::Polygon2D polygon) + : BaseIterator(info), polygon_(polygon), start_index_(0, 0) +{ + if (polygon.points.size() == 0) + { + internal_iterator_.reset(new SubGrid(info_, 0, 0, 0, 0)); + start_index_ = **internal_iterator_; + index_ = start_index_; + return; + } + + // Find the minimum and maximum coordinates of the vertices + double min_x = polygon_.points[0].x; + double max_x = min_x; + double min_y = polygon_.points[0].y; + double max_y = min_y; + for (const auto& vertex : polygon_.points) + { + min_x = std::min(min_x, vertex.x); + min_y = std::min(min_y, vertex.y); + max_x = std::max(max_x, vertex.x); + max_y = std::max(max_y, vertex.y); + } + + // Save the minimum in grid coordinates + worldToGridBounded(*info_, min_x, min_y, min_x_, min_y_); + + // Calculate the maximum in grid coordinates and then save the width/height + unsigned int max_x_grid, max_y_grid; + worldToGridBounded(*info_, max_x, max_y, max_x_grid, max_y_grid); + width_ = max_x_grid - min_x_ + 1; + height_ = max_y_grid - min_y_ + 1; + + // Initialize internal iterator + internal_iterator_.reset(new SubGrid(info_, min_x_, min_y_, width_, height_)); + index_.x = min_x_; + index_.y = min_y_; + + // Iterate to first valid index + if (!isInside(index_.x, index_.y)) ++(*this); + start_index_ = **internal_iterator_; + index_ = start_index_; +} + +PolygonFill::PolygonFill(const PolygonFill& other) + : PolygonFill(other.info_, other.index_, other.polygon_, other.min_x_, other.min_y_, other.width_, other.height_, + other.start_index_) +{ +} + +PolygonFill::PolygonFill(const nav_grid::NavGridInfo* info, const nav_grid::Index& index, + nav_2d_msgs::Polygon2D polygon, + unsigned int min_x, unsigned int min_y, unsigned int width, unsigned int height, + const nav_grid::Index& start_index) + : BaseIterator(info, index), polygon_(polygon), + min_x_(min_x), min_y_(min_y), width_(width), height_(height), start_index_(start_index) +{ + internal_iterator_.reset(new SubGrid(info_, min_x_, min_y_, width_, height_)); +} + +PolygonFill& PolygonFill::operator=(const PolygonFill& other) +{ + info_ = other.info_; + index_ = other.index_; + polygon_ = other.polygon_; + min_x_ = other.min_x_; + min_y_ = other.min_y_; + width_ = other.width_; + height_ = other.height_; + start_index_ = other.start_index_; + internal_iterator_.reset(new SubGrid(info_, index_, min_x_, min_y_, width_, height_)); + return *this; +} + +bool PolygonFill::isInside(unsigned int x, unsigned int y) const +{ + // Determine if the current index is inside the polygon using the number of crossings method + double wx, wy; + gridToWorld(*info_, x, y, wx, wy); + return nav_2d_utils::isInside(polygon_, wx, wy); +} + +PolygonFill PolygonFill::begin() const +{ + return PolygonFill(info_, start_index_, polygon_, min_x_, min_y_, width_, height_, start_index_); +} + +PolygonFill PolygonFill::end() const +{ + return PolygonFill(info_, *internal_iterator_->end(), polygon_, min_x_, min_y_, width_, height_, + start_index_); +} + +void PolygonFill::increment() +{ + ++(*internal_iterator_); + index_ = **internal_iterator_; + while (*internal_iterator_ != internal_iterator_->end()) + { + if (isInside(index_.x, index_.y)) + break; + ++(*internal_iterator_); + index_ = **internal_iterator_; + } +} + +bool PolygonFill::fieldsEqual(const PolygonFill& other) +{ + return nav_2d_utils::equals(polygon_, other.polygon_); +} + +} // namespace nav_grid_iterators diff --git a/navigations/nav_grid_iterators/src/polygon_outline.cpp b/navigations/nav_grid_iterators/src/polygon_outline.cpp new file mode 100755 index 0000000..912890c --- /dev/null +++ b/navigations/nav_grid_iterators/src/polygon_outline.cpp @@ -0,0 +1,135 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include +#include + +namespace nav_grid_iterators +{ +PolygonOutline::PolygonOutline(const nav_grid::NavGridInfo* info, nav_2d_msgs::Polygon2D polygon, bool bresenham) + : BaseIterator(info), polygon_(polygon), start_index_(0, 0), bresenham_(bresenham), side_index_(0) +{ + if (polygon.points.size() == 0) + { + internal_iterator_.reset(new Line(info_, 0.0, 0.0, 0.0, 0.0, false, bresenham_)); + index_ = **internal_iterator_; + start_index_ = index_; + return; + } + loadSide(); + index_ = **internal_iterator_; + start_index_ = index_; +} + +PolygonOutline::PolygonOutline(const PolygonOutline& other) + : PolygonOutline(other.info_, other.index_, other.polygon_, other.bresenham_, other.side_index_) +{ +} + +PolygonOutline::PolygonOutline(const nav_grid::NavGridInfo* info, const nav_grid::Index& index, + nav_2d_msgs::Polygon2D polygon, bool bresenham, unsigned int side_index) + : BaseIterator(info, index), polygon_(polygon), start_index_(index), bresenham_(bresenham), side_index_(side_index) +{ + loadSide(); +} + +PolygonOutline& PolygonOutline::operator=(const PolygonOutline& other) +{ + info_ = other.info_; + index_ = other.index_; + polygon_ = other.polygon_; + bresenham_ = other.bresenham_; + side_index_ = other.side_index_; + loadSide(); + return *this; +} + +void PolygonOutline::loadSide() +{ + while (side_index_ < polygon_.points.size()) + { + // The next index loops around to the first index + unsigned int next_index = side_index_ + 1; + if (next_index == polygon_.points.size()) + { + next_index = 0; + } + + internal_iterator_.reset(new Line(info_, + polygon_.points[side_index_].x, polygon_.points[side_index_].y, + polygon_.points[next_index].x, polygon_.points[next_index].y, + false, bresenham_)); + + if (*internal_iterator_ != internal_iterator_->end()) + break; + ++side_index_; + } +} + +PolygonOutline PolygonOutline::begin() const +{ + return PolygonOutline(info_, start_index_, polygon_, bresenham_, 0); +} + +PolygonOutline PolygonOutline::end() const +{ + // Since the polygon outline loops around to the original index when it is complete + // the end iterator is represented by having the current side to be the invalid + return PolygonOutline(info_, start_index_, polygon_, bresenham_, polygon_.points.size()); +} + +void PolygonOutline::increment() +{ + ++(*internal_iterator_); + if (*internal_iterator_ == internal_iterator_->end()) + { + ++side_index_; + if (side_index_ == polygon_.points.size()) + { + index_ = start_index_; + return; + } + loadSide(); + } + index_ = **internal_iterator_; +} + +bool PolygonOutline::fieldsEqual(const PolygonOutline& other) +{ + return side_index_ == other.side_index_ && nav_2d_utils::equals(polygon_, other.polygon_) && + bresenham_ == other.bresenham_; +} + +} // namespace nav_grid_iterators diff --git a/navigations/nav_grid_iterators/src/ray_trace.cpp b/navigations/nav_grid_iterators/src/ray_trace.cpp new file mode 100755 index 0000000..1d5628a --- /dev/null +++ b/navigations/nav_grid_iterators/src/ray_trace.cpp @@ -0,0 +1,146 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include +#include + +namespace nav_grid_iterators +{ +RayTrace::RayTrace(double x0, double y0, double x1, double y1, bool include_last_index) + : AbstractLineIterator(), x0_(x0), y0_(y0), x1_(x1), y1_(y1), include_last_index_(include_last_index) +{ + dx_ = std::abs(x1 - x0); + dy_ = std::abs(y1 - y0); + index_.x = static_cast(floor(x0)); + index_.y = static_cast(floor(y0)); + + if (dx_ == 0) + { + loop_inc_x_ = 0; + error_ = std::numeric_limits::max(); + } + else if (x1 > x0) + { + loop_inc_x_ = 1; + error_ = (floor(x0) + 1 - x0) * dy_; + } + else + { + loop_inc_x_ = -1; + error_ = (x0 - floor(x0)) * dy_; + } + + if (dy_ == 0) + { + loop_inc_y_ = 0; + error_ -= std::numeric_limits::max(); + } + else if (y1 > y0) + { + loop_inc_y_ = 1; + error_ -= (floor(y0) + 1 - y0) * dx_; + } + else + { + loop_inc_y_ = -1; + error_ -= (y0 - floor(y0)) * dx_; + } + + /* Since we check if the index is equal to the second point in the line, + * we have to check for this one edge case to ensure we don't get into a rounding + * problem, resulting in an off-by-one error. + */ + if (!include_last_index && x1 < x0 && y1 - floor(y1) == 0.0) + { + error_ += 1e-10; + } + + initial_error_ = error_; + + // Special use case when start and end point are the same AND we want to include that point + if (include_last_index && loop_inc_x_ == 0 && loop_inc_y_ == 0) + { + loop_inc_x_ = 1; + } +} + +RayTrace::RayTrace(const nav_grid::SignedIndex& index, + double x0, double y0, double x1, double y1, bool include_last_index, + double dx, double dy, double initial_error, int loop_inc_x, int loop_inc_y) + : AbstractLineIterator(index), x0_(x0), y0_(y0), x1_(x1), y1_(y1), include_last_index_(include_last_index), + dx_(dx), dy_(dy), error_(initial_error), initial_error_(initial_error), + loop_inc_x_(loop_inc_x), loop_inc_y_(loop_inc_y) +{ +} + +RayTrace RayTrace::begin() const +{ + return RayTrace(nav_grid::SignedIndex(x0_, y0_), x0_, y0_, x1_, y1_, include_last_index_, + dx_, dy_, initial_error_, loop_inc_x_, loop_inc_y_); +} + +RayTrace RayTrace::end() const +{ + int x_diff = abs(static_cast(x0_) - static_cast(x1_)); + int y_diff = abs(static_cast(y0_) - static_cast(y1_)); + double final_error = initial_error_ - dx_ * y_diff + dy_ * x_diff; + RayTrace end(nav_grid::SignedIndex(x1_, y1_), x0_, y0_, x1_, y1_, include_last_index_, + dx_, dy_, final_error, loop_inc_x_, loop_inc_y_); + + // If we want the last_index, return an iterator that is whatever is one-past the end coordinates + if (include_last_index_) + end.increment(); + return end; +} + +void RayTrace::increment() +{ + if (error_ > 0.0) + { + index_.y += loop_inc_y_; + error_ -= dx_; + } + else + { + index_.x += loop_inc_x_; + error_ += dy_; + } +} + +nav_grid::SignedIndex RayTrace::getFinalIndex() const +{ + return end().index_; +} +} // namespace nav_grid_iterators diff --git a/navigations/nav_grid_iterators/src/spiral.cpp b/navigations/nav_grid_iterators/src/spiral.cpp new file mode 100755 index 0000000..32fd9d8 --- /dev/null +++ b/navigations/nav_grid_iterators/src/spiral.cpp @@ -0,0 +1,154 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include + +namespace nav_grid_iterators +{ +Spiral::Spiral(const nav_grid::NavGridInfo* info, double center_x, double center_y, double radius) + : BaseIterator(info), center_x_(center_x), center_y_(center_y), distance_(0), start_index_(0, 0) +{ + radius_sq_ = radius * radius; + max_distance_ = ceil(radius / info->resolution); + loadRing(); + index_ = **internal_iterator_; + start_index_ = index_; +} + +Spiral::Spiral(const Spiral& other) + : Spiral(other.info_, other.index_, other.center_x_, other.center_y_, other.radius_sq_, + other.distance_, other.max_distance_, other.start_index_) +{ +} + +Spiral::Spiral(const nav_grid::NavGridInfo* info, const nav_grid::Index& index, double center_x, double center_y, + double radius_sq, unsigned int distance, unsigned int max_distance, + const nav_grid::Index& start_index) + : BaseIterator(info, index), center_x_(center_x), center_y_(center_y), radius_sq_(radius_sq), + distance_(distance), max_distance_(max_distance), start_index_(start_index) +{ + loadRing(); + if (distance_ < max_distance_) + { + index_ = **internal_iterator_; + start_index_ = index_; + } +} + +Spiral& Spiral::operator=(const Spiral& other) +{ + info_ = other.info_; + index_ = other.index_; + center_x_ = other.center_x_; + center_y_ = other.center_y_; + radius_sq_ = other.radius_sq_; + distance_ = other.distance_; + max_distance_ = other.max_distance_; + start_index_ = other.start_index_; + loadRing(); + if (distance_ < max_distance_) + { + index_ = **internal_iterator_; + start_index_ = index_; + } + return *this; +} + +Spiral Spiral::begin() const +{ + return Spiral(info_, start_index_, center_x_, center_y_, radius_sq_, 0, max_distance_, start_index_); +} + +Spiral Spiral::end() const +{ + return Spiral(info_, start_index_, center_x_, center_y_, radius_sq_, max_distance_ + 1, max_distance_, + start_index_); +} + +void Spiral::increment() +{ + while (distance_ <= max_distance_) + { + ++(*internal_iterator_); + if (*internal_iterator_ == internal_iterator_->end()) + { + ++distance_; + if (distance_ > max_distance_) + { + index_ = start_index_; + return; + } + loadRing(); + } + index_ = **internal_iterator_; + if (isInside(index_.x, index_.y)) + { + break; + } + } + if (distance_ > max_distance_) + { + index_ = start_index_; + } +} + +bool Spiral::fieldsEqual(const Spiral& other) +{ + return center_x_ == other.center_x_ && center_y_ == other.center_y_ && + radius_sq_ == other.radius_sq_ && distance_ == other.distance_; +} + +void Spiral::loadRing() +{ + while (distance_ <= max_distance_) + { + internal_iterator_.reset(new CircleOutline(info_, center_x_, center_y_, distance_)); + + if (*internal_iterator_ != internal_iterator_->end()) + break; + ++distance_; + } +} + +bool Spiral::isInside(unsigned int x, unsigned int y) const +{ + double wx, wy; + gridToWorld(*info_, x, y, wx, wy); + double dx = wx - center_x_; + double dy = wy - center_y_; + return (dx * dx + dy * dy) < radius_sq_; +} + +} // namespace nav_grid_iterators diff --git a/navigations/nav_grid_iterators/src/sub_grid.cpp b/navigations/nav_grid_iterators/src/sub_grid.cpp new file mode 100755 index 0000000..0b61c65 --- /dev/null +++ b/navigations/nav_grid_iterators/src/sub_grid.cpp @@ -0,0 +1,93 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include + +namespace nav_grid_iterators +{ +SubGrid::SubGrid(const nav_grid::NavGridInfo* info, const nav_grid::Index& index, + unsigned int min_x, unsigned int min_y, + unsigned int width, unsigned int height) + : BaseIterator(info, index), min_x_(min_x), min_y_(min_y), width_(width), height_(height) +{ + // If the start coordinate is entirely off the grid or the size is 0 + // we invalidate the entire iterator and give up immediately + if (min_x_ >= info->width || min_y_ >= info->height || width_ == 0 || height_ == 0) + { + index_ = nav_grid::Index(0, 0); + width_ = 0; + height_ = 0; + min_x_ = 0; + min_y_ = 0; + return; + } + + // If the end coordinate is off the grid, we shorten the dimensions to + // cover the on-grid potion + if (min_x_ + width_ > info->width) + { + width_ = info->width - min_x_; + } + if (min_y_ + height_ > info->height) + { + height_ = info->height - min_y_; + } +} + +SubGrid SubGrid::begin() const +{ + return SubGrid(info_, min_x_, min_y_, width_, height_); +} + +SubGrid SubGrid::end() const +{ + return SubGrid(info_, nav_grid::Index(min_x_, min_y_ + height_), min_x_, min_y_, width_, height_); +} + +void SubGrid::increment() +{ + ++index_.x; + if (index_.x >= min_x_ + width_) + { + index_.x = min_x_; + ++index_.y; + } +} + +bool SubGrid::fieldsEqual(const SubGrid& other) +{ + return min_x_ == other.min_x_ && min_y_ == other.min_y_ && width_ == other.width_ && height_ == other.height_; +} + +} // namespace nav_grid_iterators diff --git a/navigations/nav_grid_iterators/src/whole_grid.cpp b/navigations/nav_grid_iterators/src/whole_grid.cpp new file mode 100755 index 0000000..b0cf752 --- /dev/null +++ b/navigations/nav_grid_iterators/src/whole_grid.cpp @@ -0,0 +1,60 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include + +namespace nav_grid_iterators +{ + +WholeGrid WholeGrid::begin() const +{ + return WholeGrid(info_); +} + +WholeGrid WholeGrid::end() const +{ + return WholeGrid(info_, nav_grid::Index(0, info_->height)); +} + +void WholeGrid::increment() +{ + ++index_.x; + if (index_.x >= info_->width) + { + index_.x = 0; + ++index_.y; + } +} + +} // namespace nav_grid_iterators diff --git a/navigations/nav_grid_iterators/test/line_tests.cpp b/navigations/nav_grid_iterators/test/line_tests.cpp new file mode 100755 index 0000000..52aa397 --- /dev/null +++ b/navigations/nav_grid_iterators/test/line_tests.cpp @@ -0,0 +1,138 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ +#include +#include +#include + +template +int countIterations(iterator_type it, int max_iterations = 1000) +{ + int count = 0; + iterator_type end = it.end(); + for ( ; it != end; ++it) + { + ++count; + if (count >= max_iterations) break; + } + return count; +} + +TEST(Lines, line) +{ + for (int i = 0; i <= 1; i++) + { + bool include_last_point = i == 0; + EXPECT_EQ(countIterations(nav_grid_iterators::Bresenham(0, 0, 0, 0, include_last_point)), 1 - i); + EXPECT_EQ(countIterations(nav_grid_iterators::Bresenham(0, 0, 3, 0, include_last_point)), 4 - i); + EXPECT_EQ(countIterations(nav_grid_iterators::Bresenham(0, 0, -3, 0, include_last_point)), 4 - i); + EXPECT_EQ(countIterations(nav_grid_iterators::Bresenham(3, 0, 0, 0, include_last_point)), 4 - i); + EXPECT_EQ(countIterations(nav_grid_iterators::Bresenham(-3, 0, 0, 0, include_last_point)), 4 - i); + EXPECT_EQ(countIterations(nav_grid_iterators::Bresenham(0, 0, 0, 3, include_last_point)), 4 - i); + EXPECT_EQ(countIterations(nav_grid_iterators::Bresenham(0, 0, 0, -3, include_last_point)), 4 - i); + EXPECT_EQ(countIterations(nav_grid_iterators::Bresenham(0, 3, 0, 0, include_last_point)), 4 - i); + EXPECT_EQ(countIterations(nav_grid_iterators::Bresenham(0, -3, 0, 0, include_last_point)), 4 - i); + EXPECT_EQ(countIterations(nav_grid_iterators::Bresenham(0, 0, 1, 9, include_last_point)), 10 - i); + EXPECT_EQ(countIterations(nav_grid_iterators::Bresenham(0, 0, -1, -9, include_last_point)), 10 - i); + EXPECT_EQ(countIterations(nav_grid_iterators::Bresenham(1, 9, 0, 0, include_last_point)), 10 - i); + EXPECT_EQ(countIterations(nav_grid_iterators::Bresenham(-1, -9, 0, 0, include_last_point)), 10 - i); + EXPECT_EQ(countIterations(nav_grid_iterators::Bresenham(9, 1, 0, 0, include_last_point)), 10 - i); + EXPECT_EQ(countIterations(nav_grid_iterators::Bresenham(0, 0, 9, 1, include_last_point)), 10 - i); + EXPECT_EQ(countIterations(nav_grid_iterators::Bresenham(-5, -5, 5, 5, include_last_point)), 11 - i); + EXPECT_EQ(countIterations(nav_grid_iterators::Bresenham(-5, 5, 15, 5, include_last_point)), 21 - i); + EXPECT_EQ(countIterations(nav_grid_iterators::Bresenham(15, 5, -5, 5, include_last_point)), 21 - i); + EXPECT_EQ(countIterations(nav_grid_iterators::Bresenham(15, 5, 15, 7, include_last_point)), 3 - i); + + EXPECT_EQ(countIterations(nav_grid_iterators::RayTrace(0, 0, 0, 0, include_last_point)), 1 - i); + EXPECT_EQ(countIterations(nav_grid_iterators::RayTrace(0, 0, 3, 0, include_last_point)), 4 - i); + EXPECT_EQ(countIterations(nav_grid_iterators::RayTrace(0, 0, -3, 0, include_last_point)), 4 - i); + EXPECT_EQ(countIterations(nav_grid_iterators::RayTrace(3, 0, 0, 0, include_last_point)), 4 - i); + EXPECT_EQ(countIterations(nav_grid_iterators::RayTrace(-3, 0, 0, 0, include_last_point)), 4 - i); + EXPECT_EQ(countIterations(nav_grid_iterators::RayTrace(0, 0, 0, 3, include_last_point)), 4 - i); + EXPECT_EQ(countIterations(nav_grid_iterators::RayTrace(0, 0, 0, -3, include_last_point)), 4 - i); + EXPECT_EQ(countIterations(nav_grid_iterators::RayTrace(0, 3, 0, 0, include_last_point)), 4 - i); + EXPECT_EQ(countIterations(nav_grid_iterators::RayTrace(0, -3, 0, 0, include_last_point)), 4 - i); + EXPECT_EQ(countIterations(nav_grid_iterators::RayTrace(0, 0, 1, 9, include_last_point)), 11 - i); + EXPECT_EQ(countIterations(nav_grid_iterators::RayTrace(0, 0, -1, -9, include_last_point)), 11 - i); + EXPECT_EQ(countIterations(nav_grid_iterators::RayTrace(1, 9, 0, 0, include_last_point)), 11 - i); + EXPECT_EQ(countIterations(nav_grid_iterators::RayTrace(-1, -9, 0, 0, include_last_point)), 11 - i); + EXPECT_EQ(countIterations(nav_grid_iterators::RayTrace(9, 1, 0, 0, include_last_point)), 11 - i); + EXPECT_EQ(countIterations(nav_grid_iterators::RayTrace(0, 0, 9, 1, include_last_point)), 11 - i); + EXPECT_EQ(countIterations(nav_grid_iterators::RayTrace(-5, -5, 5, 5, include_last_point)), 21 - i); + EXPECT_EQ(countIterations(nav_grid_iterators::RayTrace(-5, 5, 15, 5, include_last_point)), 21 - i); + EXPECT_EQ(countIterations(nav_grid_iterators::RayTrace(15, 5, -5, 5, include_last_point)), 21 - i); + EXPECT_EQ(countIterations(nav_grid_iterators::RayTrace(15, 5, 15, 7, include_last_point)), 3 - i); + } +} + +TEST(Lines, border_conditions) +{ + int N = 100; + int N2 = N / 2; + for (int include_last_point = 0; include_last_point <= 1; ++include_last_point) + { + for (int i=0; i < N; ++i) + { + EXPECT_LT(countIterations(nav_grid_iterators::Bresenham(0, 0, N2, i - N2, include_last_point)), N*3); + EXPECT_LT(countIterations(nav_grid_iterators::Bresenham(0, 0, -N2, i - N2, include_last_point)), N*3); + EXPECT_LT(countIterations(nav_grid_iterators::Bresenham(0, 0, i - N2, N2, include_last_point)), N*3); + EXPECT_LT(countIterations(nav_grid_iterators::Bresenham(0, 0, i - N2, -N2, include_last_point)), N*3); + EXPECT_LT(countIterations(nav_grid_iterators::RayTrace(0, 0, N2, i - N2, include_last_point)), N*3); + EXPECT_LT(countIterations(nav_grid_iterators::RayTrace(0, 0, -N2, i - N2, include_last_point)), N*3); + EXPECT_LT(countIterations(nav_grid_iterators::RayTrace(0, 0, i - N2, N2, include_last_point)), N*3); + EXPECT_LT(countIterations(nav_grid_iterators::RayTrace(0, 0, i - N2, -N2, include_last_point)), N*3); + } + } +} + +TEST(Lines, equality) +{ + nav_grid_iterators::Bresenham it1(0, 0, 5, 5); + nav_grid_iterators::Bresenham it2(0, 0, 1, 1); + ASSERT_FALSE(it1 == it2); +} + +TEST(Lines, test_copy) +{ + // This test will fail to compile if you cannot use the copy operator + nav_grid_iterators::Bresenham bres(0, 0, 0, 0); + bres = bres.begin(); + nav_grid_iterators::RayTrace rt(0, 0, 0, 0); + rt = rt.begin(); +} + +int main(int argc, char **argv) +{ + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/navigations/nav_grid_iterators/test/utest.cpp b/navigations/nav_grid_iterators/test/utest.cpp new file mode 100755 index 0000000..9c8dab9 --- /dev/null +++ b/navigations/nav_grid_iterators/test/utest.cpp @@ -0,0 +1,466 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2018, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ +#include +#include +#include +#include + +using nav_grid::Index; + +template +int countIterations(iterator_type it, int max_iterations = 1000) +{ + int count = 0; + iterator_type end = it.end(); + for ( ; it != end; ++it) + { + ++count; + if (count >= max_iterations) break; + } + return count; +} + +TEST(WholeGrid, whole_grid) +{ + nav_grid::NavGridInfo info; + info.width = 5; + info.height = 8; + int count = 0; + for (nav_grid_iterators::WholeGrid it(info); it != it.end(); ++it) + { + Index i = *it; + ASSERT_EQ(i.x, count % info.width); + ASSERT_EQ(i.y, count / info.width); + ++count; + } + ASSERT_EQ(count, 40); +} + +TEST(WholeGrid, whole_grid_range) +{ + nav_grid::NavGridInfo info; + info.width = 3; + info.height = 6; + int count = 0; + for (Index i : nav_grid_iterators::WholeGrid(info)) + { + ASSERT_EQ(i.x, count % info.width); + ASSERT_EQ(i.y, count / info.width); + ++count; + } + ASSERT_EQ(count, 18); +} + +TEST(WholeGrid, std_stuff) +{ + nav_grid::NavGridInfo info; + info.width = 8; + info.height = 2; + nav_grid_iterators::WholeGrid wg(info); + + std::vector vec; + std::copy(wg.begin(), wg.end(), std::back_inserter(vec)); + for (int count = 0; count < 16; ++count) + { + Index& i = vec[count]; + ASSERT_EQ(i.x, count % info.width); + ASSERT_EQ(i.y, count / info.width); + } +} + +TEST(SubGrid, sub_grid) +{ + nav_grid::NavGridInfo info; + info.width = 5; + info.height = 8; + int count = 0; + for (Index i : nav_grid_iterators::SubGrid(&info, 1, 2, 2, 3)) + { + ASSERT_EQ(i.x, static_cast(1 + count % 2)); + ASSERT_EQ(i.y, static_cast(2 + count / 2)); + ++count; + } + ASSERT_EQ(count, 6); + + ASSERT_EQ(countIterations(nav_grid_iterators::SubGrid(&info, 1, 3, 4, 1)), 4); + ASSERT_EQ(countIterations(nav_grid_iterators::SubGrid(&info, 1, 3, 2, 2)), 4); + nav_core2::UIntBounds bounds(1, 3, 4, 3); + ASSERT_EQ(countIterations(nav_grid_iterators::SubGrid(&info, bounds)), 4); + + // Empty Bounds + bounds.reset(); + ASSERT_EQ(countIterations(nav_grid_iterators::SubGrid(&info, bounds)), 0); + + // Partially Overlapping Bounds + bounds.touch(3, 2); + bounds.touch(6, 3); + ASSERT_EQ(countIterations(nav_grid_iterators::SubGrid(&info, bounds)), 4); + + bounds.reset(); + bounds.touch(1, 6); + bounds.touch(3, 9); + ASSERT_EQ(countIterations(nav_grid_iterators::SubGrid(&info, bounds)), 6); + + // Different empty bounds + nav_core2::UIntBounds empty(1, 0, 0, 0); + ASSERT_EQ(countIterations(nav_grid_iterators::SubGrid(&info, empty)), 0); +} + +TEST(SubGrid, equality) +{ + nav_grid::NavGridInfo info; + info.width = 5; + info.height = 8; + nav_grid_iterators::SubGrid it1(&info, 1, 2, 2, 3); + nav_grid_iterators::SubGrid it2(&info, 1, 2, 1, 1); + ASSERT_FALSE(it1 == it2); +} + +TEST(CircleFill, circle) +{ + nav_grid::NavGridInfo info; + info.width = 8; + info.height = 8; + info.resolution = 1.0; + + ASSERT_EQ(countIterations(nav_grid_iterators::CircleFill(&info, 4.0, 4.0, 3.0)), 32); + ASSERT_EQ(countIterations(nav_grid_iterators::CircleFill(&info, 4.3, 4.0, 3.0)), 28); + ASSERT_EQ(countIterations(nav_grid_iterators::CircleFill(&info, 4.0, 4.0, 8.0)), 64); + ASSERT_EQ(countIterations(nav_grid_iterators::CircleFill(&info, 14.0, 4.0, 1.0)), 0); + ASSERT_EQ(countIterations(nav_grid_iterators::CircleFill(&info, 0.0, 4.0, 4.0)), 26); + ASSERT_EQ(countIterations(nav_grid_iterators::CircleFill(&info, 4.0, 4.0, 3.0).begin()), 32); +} + +TEST(CircleFill, equality) +{ + nav_grid::NavGridInfo info; + info.width = 5; + info.height = 8; + nav_grid_iterators::CircleFill it1(&info, 4.0, 4.0, 8.0); + nav_grid_iterators::CircleFill it2(&info, 1.0, 1.0, 100.0); + ASSERT_FALSE(it1 == it2); +} + +TEST(CircleOutline, circle_outline) +{ + nav_grid::NavGridInfo info; + info.width = 8; + info.height = 8; + info.resolution = 1.0; + + unsigned int size = 0; + EXPECT_EQ(countIterations(nav_grid_iterators::CircleOutline(&info, 4.0, 4.0, size++)), 1); + EXPECT_EQ(countIterations(nav_grid_iterators::CircleOutline(&info, 4.0, 4.0, size++)), 8); + EXPECT_EQ(countIterations(nav_grid_iterators::CircleOutline(&info, 4.0, 4.0, size++)), 16); + EXPECT_EQ(countIterations(nav_grid_iterators::CircleOutline(&info, 4.0, 4.0, size++)), 20); + EXPECT_EQ(countIterations(nav_grid_iterators::CircleOutline(&info, 4.0, 4.0, size++)), 14); + EXPECT_EQ(countIterations(nav_grid_iterators::CircleOutline(&info, 4.0, 4.0, size++)), 5); + EXPECT_EQ(countIterations(nav_grid_iterators::CircleOutline(&info, 4.0, 4.0, size++)), 0); + EXPECT_EQ(countIterations(nav_grid_iterators::CircleOutline(&info, 4.0, 4.0, size++)), 0); +} + +TEST(CircleOutline, equality) +{ + nav_grid::NavGridInfo info; + info.width = 5; + info.height = 8; + nav_grid_iterators::CircleOutline it1(&info, 3.0, 1.0, 1.0); + nav_grid_iterators::CircleOutline it2(&info, 1.0, 1.0, 3.0); + ASSERT_FALSE(it1 == it2); +} + +TEST(Spiral, spiral) +{ + nav_grid::NavGridInfo info; + info.width = 8; + info.height = 8; + info.resolution = 1.0; + info.origin_x = 0.0; + info.origin_y = 0.0; + ASSERT_EQ(countIterations(nav_grid_iterators::Spiral(&info, 4.0, 4.0, 3.0)), 32); + ASSERT_EQ(countIterations(nav_grid_iterators::Spiral(&info, 4.3, 4.0, 3.0)), 28); + ASSERT_EQ(countIterations(nav_grid_iterators::Spiral(&info, 4.0, 4.0, 8.0)), 64); + ASSERT_EQ(countIterations(nav_grid_iterators::Spiral(&info, 14.0, 4.0, 1.0)), 0); + ASSERT_EQ(countIterations(nav_grid_iterators::Spiral(&info, 0.0, 4.0, 4.0)), 26); +} + +TEST(Spiral, equality) +{ + nav_grid::NavGridInfo info; + info.width = 5; + info.height = 8; + nav_grid_iterators::Spiral it1(&info, 1.0, 1.0, 1.0); + nav_grid_iterators::Spiral it2(&info, 1.0, 1.0, 3.0); + ASSERT_FALSE(it1 == it2); +} + +TEST(Line, signed_line) +{ + nav_grid::NavGridInfo info; + info.width = 10; + info.height = 10; + info.resolution = 1.0; + EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, 0, 0, 0, 0)), 1); + EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, 0, 0, 3, 0)), 4); + EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, 0, 0, -3, 0)), 1); + EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, 3, 0, 0, 0)), 4); + EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, -3, 0, 0, 0)), 1); + EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, -3, 0, 0, 0, false)), 0); + EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, 0, 0, 0, 3)), 4); + EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, 0, 0, 0, -3)), 1); + EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, 0, 3, 0, 0)), 4); + EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, 0, -3, 0, 0)), 1); + EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, 0, 0, 1, 9)), 10); + EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, 1, 9, 0, 0)), 10); + EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, 9, 1, 0, 0)), 10); + EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, 0, 0, 9, 1)), 10); + + EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, -5, 5, 15, 5)), 10); + EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, 15, 5, -5, 5)), 10); + EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, 15, 5, 15, 7)), 0); + + EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, -1, -5, -1, -7)), 0); +} + +TEST(Line, signed_line_diff_res) +{ + // This is the same test as above with a reduced resolution. Most of the coordinates are divided by 10 + // (with an additional 0.05 in some places to avoid floating point errors) + nav_grid::NavGridInfo info; + info.width = 10; + info.height = 10; + info.resolution = 0.1; + EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, 0, 0, 0, 0)), 1); + EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, 0, 0, 0.35, 0)), 4); + EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, 0, 0, -0.35, 0)), 1); + EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, 0.35, 0, 0, 0)), 4); + EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, -0.35, 0, 0, 0)), 1); + EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, -0.35, 0, 0, 0, false)), 0); + EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, 0, 0, 0, 0.35)), 4); + EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, 0, 0, 0, -0.35)), 1); + EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, 0, 0.35, 0, 0)), 4); + EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, 0, -0.35, 0, 0)), 1); + EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, 0, 0, 0.15, 0.95)), 10); + EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, 0.15, 0.95, 0, 0)), 10); + EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, 0.95, 0.15, 0, 0)), 10); + EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, 0, 0, 0.95, 0.15)), 10); + + EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, -0.5, 0.5, 1.5, 0.5)), 10); + EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, 1.5, 0.5, -0.55, 0.55)), 10); + EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, 1.5, 0.5, 1.5, 0.75)), 0); + + EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, -0.1, -0.5, -0.1, -0.7)), 0); +} + +TEST(Line, random_test_case) +{ + nav_grid::NavGridInfo info; + info.width = 795; + info.height = 925; + info.resolution = 0.05; + EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, 6.2402, 30.651832, 2.805347, 22.8941, false, false)), 224); + EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, 6.2402, 30.651832, 2.805347, 22.8941, true, false)), 225); +} + +TEST(Line, equality) +{ + nav_grid::NavGridInfo info; + info.width = 5; + info.height = 8; + nav_grid_iterators::Line it1(&info, 0, 0, 5, 5); + nav_grid_iterators::Line it2(&info, 0, 0, 1, 1); + ASSERT_FALSE(it1 == it2); +} + +nav_2d_msgs::Point2D make_point(double x, double y) +{ + nav_2d_msgs::Point2D pt; + pt.x = x; + pt.y = y; + return pt; +} + +TEST(Polygon, polygon) +{ + nav_grid::NavGridInfo info; + // First check to make sure it works when the polygon is completely on the grid + info.width = 10; + info.height = 10; + info.resolution = 1.0; + nav_2d_msgs::Polygon2D simple_square; + simple_square.points.push_back(make_point(1.4, 1.4)); + simple_square.points.push_back(make_point(1.4, 3.6)); + simple_square.points.push_back(make_point(3.6, 3.6)); + simple_square.points.push_back(make_point(3.6, 1.4)); + + EXPECT_EQ(countIterations(nav_grid_iterators::PolygonOutline(&info, simple_square)), 8); + EXPECT_EQ(countIterations(nav_grid_iterators::PolygonFill(&info, simple_square)), 9); + + // Then do it again when it is only partially on the grid + info.height = 3; + EXPECT_EQ(countIterations(nav_grid_iterators::PolygonOutline(&info, simple_square)), 5); + EXPECT_EQ(countIterations(nav_grid_iterators::PolygonFill(&info, simple_square)), 6); + + // Then check when it is completely off the grid + info.resolution = 0.1; + EXPECT_EQ(countIterations(nav_grid_iterators::PolygonOutline(&info, simple_square)), 0); + EXPECT_EQ(countIterations(nav_grid_iterators::PolygonFill(&info, simple_square)), 0); +} + +TEST(Polygon, empty_polygon) +{ + nav_grid::NavGridInfo info; + info.width = 10; + info.height = 10; + info.resolution = 1.0; + nav_2d_msgs::Polygon2D empty_polygon; + + EXPECT_EQ(countIterations(nav_grid_iterators::PolygonOutline(&info, empty_polygon)), 0); + EXPECT_EQ(countIterations(nav_grid_iterators::PolygonFill(&info, empty_polygon)), 0); +} + +TEST(Polygon, equality) +{ + nav_grid::NavGridInfo info; + info.width = 10; + info.height = 10; + info.resolution = 1.0; + nav_2d_msgs::Polygon2D simple_square; + simple_square.points.push_back(make_point(1.4, 1.4)); + simple_square.points.push_back(make_point(1.4, 3.6)); + simple_square.points.push_back(make_point(3.6, 3.6)); + simple_square.points.push_back(make_point(3.6, 1.4)); + + nav_2d_msgs::Polygon2D triangle; + triangle.points.push_back(make_point(1.4, 1.4)); + triangle.points.push_back(make_point(1.4, 3.6)); + triangle.points.push_back(make_point(3.6, 3.6)); + + + nav_grid_iterators::PolygonOutline it1(&info, simple_square); + nav_grid_iterators::PolygonOutline it2(&info, triangle); + ASSERT_FALSE(it1 == it2); + + nav_grid_iterators::PolygonFill it3(&info, simple_square); + nav_grid_iterators::PolygonFill it4(&info, triangle); + ASSERT_FALSE(it3 == it4); +} + +TEST(Iterators, test_copy) +{ + // This test will fail to compile if you cannot use the copy operator + nav_grid::NavGridInfo info; + info.width = 10; + info.height = 10; + info.resolution = 1.0; + + nav_2d_msgs::Polygon2D simple_square; + simple_square.points.push_back(make_point(1.4, 1.4)); + simple_square.points.push_back(make_point(1.4, 3.6)); + simple_square.points.push_back(make_point(3.6, 3.6)); + simple_square.points.push_back(make_point(3.6, 1.4)); + + nav_grid_iterators::WholeGrid whole_grid(info); + whole_grid = whole_grid.begin(); + nav_grid_iterators::SubGrid sub_grid(&info, 1, 2, 2, 3); + sub_grid = sub_grid.begin(); + nav_grid_iterators::CircleFill cf(&info, 4.0, 4.0, 3.0); + cf = cf.begin(); + nav_grid_iterators::CircleOutline co(&info, 4.0, 4.0, 3.0); + co = co.begin(); + nav_grid_iterators::Spiral spiral(&info, 4.0, 4.0, 3.0); + spiral = spiral.begin(); + nav_grid_iterators::Line line(&info, 0, 0, 0, 0); + line = line.begin(); + nav_grid_iterators::PolygonOutline po(&info, simple_square); + po = po.begin(); + nav_grid_iterators::PolygonFill pf(&info, simple_square); + pf = pf.begin(); +} + +TEST(Iterators, test_assignment) +{ + nav_grid::NavGridInfo info; + info.width = 10; + info.height = 10; + info.resolution = 1.0; + nav_grid_iterators::CircleFill iter1(&info, 3.0, 3.0, 1.0); + // Sequence should be (2, 2) (3, 2) (2, 3) (3, 3) + EXPECT_EQ((*iter1).x, 2U); + EXPECT_EQ((*iter1).y, 2U); + + nav_grid_iterators::CircleFill iter2 = iter1; + + // Effective Copy + EXPECT_EQ((*iter1).x, 2U); + EXPECT_EQ((*iter1).y, 2U); + EXPECT_EQ((*iter2).x, 2U); + EXPECT_EQ((*iter2).y, 2U); + + // Increment only iter2 + ++iter2; + EXPECT_EQ((*iter1).x, 2U); + EXPECT_EQ((*iter1).y, 2U); + EXPECT_EQ((*iter2).x, 3U); + EXPECT_EQ((*iter2).y, 2U); + + // Increment first to match + ++iter1; + EXPECT_EQ((*iter1).x, 3U); + EXPECT_EQ((*iter1).y, 2U); + EXPECT_EQ((*iter2).x, 3U); + EXPECT_EQ((*iter2).y, 2U); + + // Increment only iter2 + ++iter2; + EXPECT_EQ((*iter1).x, 3U); + EXPECT_EQ((*iter1).y, 2U); + EXPECT_EQ((*iter2).x, 2U); + EXPECT_EQ((*iter2).y, 3U); + + // Check copy when not at the start + nav_grid_iterators::CircleFill iter3 = iter1; + EXPECT_EQ((*iter1).x, 3U); + EXPECT_EQ((*iter1).y, 2U); + EXPECT_EQ((*iter2).x, 2U); + EXPECT_EQ((*iter2).y, 3U); + EXPECT_EQ((*iter3).x, 3U); + EXPECT_EQ((*iter3).y, 2U); +} + +int main(int argc, char **argv) +{ + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/navigations/nav_msgs/CHANGELOG.rst b/navigations/nav_msgs/CHANGELOG.rst new file mode 100755 index 0000000..41c70f2 --- /dev/null +++ b/navigations/nav_msgs/CHANGELOG.rst @@ -0,0 +1,267 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package nav_msgs +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +1.13.1 (2021-01-11) +------------------- +* Update package maintainers (`#168 `_) +* Add LoadMap service (`#164 `_) +* Contributors: David V. Lu!!, Michel Hidalgo + +1.13.0 (2020-05-21) +------------------- +* Bump CMake version to avoid CMP0048 warning (`#158 `_) +* Contributors: Shane Loretz + +1.12.7 (2018-11-06) +------------------- + +1.12.6 (2018-05-03) +------------------- + +1.12.5 (2016-09-30) +------------------- + +1.12.4 (2016-02-22) +------------------- + +1.12.3 (2015-04-20) +------------------- + +1.12.2 (2015-03-21) +------------------- +* change type of initial_pose in SetMap service to PoseWithCovarianceStamped +* Contributors: Stephan Wirth + +1.12.1 (2015-03-17) +------------------- +* updating outdated urls. fixes `#52 `_. +* Adds a SetMap service message to support swap maps functionality in amcl +* Contributors: Tully Foote, liz-murphy + +1.12.0 (2014-12-29) +------------------- + +1.11.6 (2014-11-04) +------------------- + +1.11.5 (2014-10-27) +------------------- + +1.11.4 (2014-06-19) +------------------- + +1.11.3 (2014-05-07) +------------------- +* Export architecture_independent flag in package.xml +* Contributors: Scott K Logan + +1.11.2 (2014-04-24) +------------------- + +1.11.1 (2014-04-16) +------------------- + +1.11.0 (2014-03-04) +------------------- + +1.10.6 (2014-02-27) +------------------- + +1.10.5 (2014-02-25) +------------------- + +1.10.4 (2014-02-18) +------------------- + +1.10.3 (2014-01-07) +------------------- + +1.10.2 (2013-08-19) +------------------- + +1.10.1 (2013-08-16) +------------------- + +1.10.0 (2013-07-13) +------------------- + +1.9.16 (2013-05-21) +------------------- +* added action definition for getting maps +* update email in package.xml + +1.9.15 (2013-03-08) +------------------- + +1.9.14 (2013-01-19) +------------------- + +1.9.13 (2013-01-13) +------------------- + +1.9.12 (2013-01-02) +------------------- + +1.9.11 (2012-12-17) +------------------- +* modified dep type of catkin + +1.9.10 (2012-12-13) +------------------- +* add missing downstream depend +* switched from langs to message_* packages + +1.9.9 (2012-11-22) +------------------ + +1.9.8 (2012-11-14) +------------------ + +1.9.7 (2012-10-30) +------------------ +* fix catkin function order + +1.9.6 (2012-10-18) +------------------ +* updated cmake min version to 2.8.3, use cmake_parse_arguments instead of custom macro + +1.9.5 (2012-09-28) +------------------ + +1.9.4 (2012-09-27 18:06) +------------------------ + +1.9.3 (2012-09-27 17:39) +------------------------ +* cleanup +* cleaned up package.xml files +* updated to latest catkin +* fixed dependencies and more +* updated to latest catkin: created package.xmls, updated CmakeLists.txt + +1.9.2 (2012-09-05) +------------------ +* updated pkg-config in manifest.xml + +1.9.1 (2012-09-04) +------------------ +* use install destination variables, removed manual installation of manifests + +1.9.0 (2012-08-29) +------------------ +* updated to current catkin + +1.8.13 (2012-07-26 18:34:15 +0000) +---------------------------------- + +1.8.8 (2012-06-12 22:36) +------------------------ +* make find_package REQUIRED +* removed obsolete catkin tag from manifest files +* fixed package dependencies for several common messages (fixed `#3956 `_) +* adding manifest exports +* removed depend, added catkin +* stripping depend and export tags from common_msgs manifests as msg dependencies are now declared in cmake and stack.yaml. Also removed bag migration exports +* common_msgs: removing migration rules as all are over a year old +* bye bye vestigial MSG_DIRS +* nav_msgs: getting rid of other build files and cleaning up +* common_msgs: starting catkin conversion +* adios rosbuild2 in manifest.xml +* catkin updates +* catkin_project +* Updated to work with new message generation macros +* More tweaking for standalone message generation +* Getting standalone message generation working... w/o munging rosbuild2 +* more rosbuild2 hacking +* missing dependencies +* updating bagmigration exports +* rosbuild2 taking shape +* removing old exports ros`#2292 `_ +* Added Ubuntu platform tags to manifest +* Adding a start pose to the GetPlan service +* Remove use of deprecated rosbuild macros +* Fixing migration rules for nav_msgs. +* Changed byte to int8, in response to map_server doc review +* changing review status +* adding documentation for `#2997 `_ +* removing redundant range statements as per ticket:2997 +* Adding documentation to the Odometry message to make things more clear +* manifest update +* updated description and url +* full migration rules +* adding child_frame_id as per discussion about odometry message +* Adding a header to Path +* Adding a header to the GridCells message +* Adding a new GridCells message for displaying obstacles in nav_view and rviz +* clearing API reviews for they've been through a bunch of them recently. +* fixing stack name +* Adding comments to path +* documenting messages +* Making odometry migration fail until we have worked out appropriate way to handle covariances. +* Changing naming of bag migration rules. +* Modifying migration rules for Odometry and WrenchStamped change of field names. +* Adding actual migration rules for all of the tested common_msgs migrations. +* `#2250 `_ getting rid of _with_covariance in Odometry fields +* nav_msgs: added missing srv export +* Adding migration rules to get migration tests to pass. +* removing last of robot_msgs and all dependencies on it +* moving Path from robot_msgs to nav_msgs `#2281 `_ +* adding header to OccupancyGrid `#1906 `_ +* First half of the change from deprecated_msgs::RobotBase2DOdom to nav_msgs::Odometry, I think all the c++ compiles, can't speak for functionality yet, also... the python has yet to be run... this may break some things +* moving PoseArray into geometry_msgs `#1907 `_ +* fixing names +* Removing header since there's already one in the pose and fixing message definition to have variable names +* adding Odometry message as per API review and ticket:2250 +* merging in the changes to messages see ros-users email. THis is about half the common_msgs API changes +* Forgot to check in the services I added.... shoot +* Moving StaticMap.srv to GetMap.srv and moving Plan.srv to GetPlan.srv, also moving them to nav_msgs and removing the nav_srvs package +* Merging tha actionlib branch back into trunk + r29135@att (orig r19792): eitanme | 2009-07-27 18:30:30 -0700 + Creating a branch for actionlib.... hopefully for the last time + r29137@att (orig r19794): eitanme | 2009-07-27 18:32:49 -0700 + Changing ParticleCloud to PoseArray + r29139@att (orig r19796): eitanme | 2009-07-27 18:33:42 -0700 + Adding action definition to the rep + r29148@att (orig r19805): eitanme | 2009-07-27 18:47:39 -0700 + Some fixes... almost compiling + r29165@att (orig r19822): eitanme | 2009-07-27 20:41:07 -0700 + Macro version of the typedefs that compiles + r29213@att (orig r19869): eitanme | 2009-07-28 11:49:10 -0700 + Compling version of the ActionServer re-write complete with garbage collection, be default it will keep goals without goal handles for 5 seconds + r29220@att (orig r19876): eitanme | 2009-07-28 12:06:06 -0700 + Fix to make sure that transitions into preempting and recalling states actually happen + r29254@att (orig r19888): eitanme | 2009-07-28 13:27:40 -0700 + Forgot to actually call the cancel callback... addind a subscriber on the cancel topic + r29267@att (orig r19901): eitanme | 2009-07-28 14:41:09 -0700 + Adding text field to GoalStatus to allow users to throw some debugging information into the GoalStatus messages + r29275@att (orig r19909): eitanme | 2009-07-28 15:43:49 -0700 + Using tf remapping as I should've been doing for awhile + r29277@att (orig r19911): eitanme | 2009-07-28 15:48:48 -0700 + The navigation stack can now handle goals that aren't in the global frame. However, these goals will be transformed to the global frame at the time of reception, so for achieving them accurately the global frame of move_base should really be set to match the goals. + r29299@att (orig r19933): stuglaser | 2009-07-28 17:08:10 -0700 + Created genaction.py script to create the various messages that an action needs + r29376@att (orig r20003): vijaypradeep | 2009-07-29 02:45:24 -0700 + ActionClient is running. MoveBase ActionServer seems to be crashing + r29409@att (orig r20033): vijaypradeep | 2009-07-29 11:57:54 -0700 + Fixing bug with adding status trackers + r29410@att (orig r20034): vijaypradeep | 2009-07-29 11:58:18 -0700 + Changing from Release to Debug + r29432@att (orig r20056): vijaypradeep | 2009-07-29 14:07:30 -0700 + No longer building goal_manager_test.cpp + r29472@att (orig r20090): vijaypradeep | 2009-07-29 17:04:14 -0700 + Lots of Client-Side doxygen + r29484@att (orig r20101): vijaypradeep | 2009-07-29 18:35:01 -0700 + Adding to mainpage.dox + r29487@att (orig r20104): eitanme | 2009-07-29 18:55:06 -0700 + Removing file to help resolve merge I hope + r29489@att (orig r20106): eitanme | 2009-07-29 19:00:07 -0700 + Removing another file to try to resolve the branch + r29492@att (orig r20108): eitanme | 2009-07-29 19:14:25 -0700 + Again removing a file to get the merge working + r29493@att (orig r20109): eitanme | 2009-07-29 19:34:45 -0700 + Removing yet another file on which ssl negotiation fails + r29500@att (orig r20116): eitanme | 2009-07-29 19:54:18 -0700 + Fixing bug in genaction +* moving MapMetaData and OccGrid into nav_msgs `#1303 `_ +* created nav_msgs and moved ParticleCloud there `#1300 `_ diff --git a/navigations/nav_msgs/CMakeLists.txt b/navigations/nav_msgs/CMakeLists.txt new file mode 100755 index 0000000..b475181 --- /dev/null +++ b/navigations/nav_msgs/CMakeLists.txt @@ -0,0 +1,29 @@ +cmake_minimum_required(VERSION 3.0.2) +project(nav_msgs) + +find_package(catkin REQUIRED COMPONENTS geometry_msgs message_generation std_msgs actionlib_msgs) + +add_message_files( + DIRECTORY msg + FILES + GridCells.msg + MapMetaData.msg + OccupancyGrid.msg + Odometry.msg + Path.msg) + +add_service_files( + DIRECTORY srv + FILES + GetMap.srv + GetPlan.srv + SetMap.srv + LoadMap.srv) + +add_action_files( + FILES + GetMap.action) + +generate_messages(DEPENDENCIES geometry_msgs std_msgs actionlib_msgs) + +catkin_package(CATKIN_DEPENDS geometry_msgs message_runtime std_msgs actionlib_msgs) diff --git a/navigations/nav_msgs/action/GetMap.action b/navigations/nav_msgs/action/GetMap.action new file mode 100755 index 0000000..080e54f --- /dev/null +++ b/navigations/nav_msgs/action/GetMap.action @@ -0,0 +1,5 @@ +# Get the map as a nav_msgs/OccupancyGrid +--- +nav_msgs/OccupancyGrid map +--- +# no feedback \ No newline at end of file diff --git a/navigations/nav_msgs/msg/GridCells.msg b/navigations/nav_msgs/msg/GridCells.msg new file mode 100755 index 0000000..2c92894 --- /dev/null +++ b/navigations/nav_msgs/msg/GridCells.msg @@ -0,0 +1,5 @@ +#an array of cells in a 2D grid +Header header +float32 cell_width +float32 cell_height +geometry_msgs/Point[] cells diff --git a/navigations/nav_msgs/msg/MapMetaData.msg b/navigations/nav_msgs/msg/MapMetaData.msg new file mode 100755 index 0000000..398fbdd --- /dev/null +++ b/navigations/nav_msgs/msg/MapMetaData.msg @@ -0,0 +1,13 @@ +# This hold basic information about the characterists of the OccupancyGrid + +# The time at which the map was loaded +time map_load_time +# The map resolution [m/cell] +float32 resolution +# Map width [cells] +uint32 width +# Map height [cells] +uint32 height +# The origin of the map [m, m, rad]. This is the real-world pose of the +# cell (0,0) in the map. +geometry_msgs/Pose origin \ No newline at end of file diff --git a/navigations/nav_msgs/msg/OccupancyGrid.msg b/navigations/nav_msgs/msg/OccupancyGrid.msg new file mode 100755 index 0000000..f2e79bd --- /dev/null +++ b/navigations/nav_msgs/msg/OccupancyGrid.msg @@ -0,0 +1,11 @@ +# This represents a 2-D grid map, in which each cell represents the probability of +# occupancy. + +Header header + +#MetaData for the map +MapMetaData info + +# The map data, in row-major order, starting with (0,0). Occupancy +# probabilities are in the range [0,100]. Unknown is -1. +int8[] data diff --git a/navigations/nav_msgs/msg/Odometry.msg b/navigations/nav_msgs/msg/Odometry.msg new file mode 100755 index 0000000..73578ed --- /dev/null +++ b/navigations/nav_msgs/msg/Odometry.msg @@ -0,0 +1,7 @@ +# This represents an estimate of a position and velocity in free space. +# The pose in this message should be specified in the coordinate frame given by header.frame_id. +# The twist in this message should be specified in the coordinate frame given by the child_frame_id +Header header +string child_frame_id +geometry_msgs/PoseWithCovariance pose +geometry_msgs/TwistWithCovariance twist diff --git a/navigations/nav_msgs/msg/Path.msg b/navigations/nav_msgs/msg/Path.msg new file mode 100755 index 0000000..979cb7d --- /dev/null +++ b/navigations/nav_msgs/msg/Path.msg @@ -0,0 +1,3 @@ +#An array of poses that represents a Path for a robot to follow +Header header +geometry_msgs/PoseStamped[] poses diff --git a/navigations/nav_msgs/package.xml b/navigations/nav_msgs/package.xml new file mode 100755 index 0000000..f379061 --- /dev/null +++ b/navigations/nav_msgs/package.xml @@ -0,0 +1,29 @@ + + nav_msgs + 1.13.1 + + nav_msgs defines the common messages used to interact with the + navigation stack. + + Michel Hidalgo + BSD + + http://wiki.ros.org/nav_msgs + Tully Foote + + catkin + + geometry_msgs + message_generation + std_msgs + actionlib_msgs + + geometry_msgs + message_runtime + std_msgs + actionlib_msgs + + + + + diff --git a/navigations/nav_msgs/srv/GetMap.srv b/navigations/nav_msgs/srv/GetMap.srv new file mode 100755 index 0000000..6bd8e4a --- /dev/null +++ b/navigations/nav_msgs/srv/GetMap.srv @@ -0,0 +1,3 @@ +# Get the map as a nav_msgs/OccupancyGrid +--- +nav_msgs/OccupancyGrid map diff --git a/navigations/nav_msgs/srv/GetPlan.srv b/navigations/nav_msgs/srv/GetPlan.srv new file mode 100755 index 0000000..f5c23ed --- /dev/null +++ b/navigations/nav_msgs/srv/GetPlan.srv @@ -0,0 +1,13 @@ +# Get a plan from the current position to the goal Pose + +# The start pose for the plan +geometry_msgs/PoseStamped start + +# The final pose of the goal position +geometry_msgs/PoseStamped goal + +# If the goal is obstructed, how many meters the planner can +# relax the constraint in x and y before failing. +float32 tolerance +--- +nav_msgs/Path plan diff --git a/navigations/nav_msgs/srv/LoadMap.srv b/navigations/nav_msgs/srv/LoadMap.srv new file mode 100755 index 0000000..3b9caaa --- /dev/null +++ b/navigations/nav_msgs/srv/LoadMap.srv @@ -0,0 +1,15 @@ +# URL of map resource +# Can be an absolute path to a file: file:///path/to/maps/floor1.yaml +# Or, relative to a ROS package: package://my_ros_package/maps/floor2.yaml +string map_url +--- +# Result code defintions +uint8 RESULT_SUCCESS=0 +uint8 RESULT_MAP_DOES_NOT_EXIST=1 +uint8 RESULT_INVALID_MAP_DATA=2 +uint8 RESULT_INVALID_MAP_METADATA=3 +uint8 RESULT_UNDEFINED_FAILURE=255 + +# Returned map is only valid if result equals RESULT_SUCCESS +nav_msgs/OccupancyGrid map +uint8 result diff --git a/navigations/nav_msgs/srv/SetMap.srv b/navigations/nav_msgs/srv/SetMap.srv new file mode 100755 index 0000000..55d3c24 --- /dev/null +++ b/navigations/nav_msgs/srv/SetMap.srv @@ -0,0 +1,6 @@ +# Set a new map together with an initial pose +nav_msgs/OccupancyGrid map +geometry_msgs/PoseWithCovarianceStamped initial_pose +--- +bool success + diff --git a/navigations/navfn/CHANGELOG.rst b/navigations/navfn/CHANGELOG.rst new file mode 100755 index 0000000..a34edb5 --- /dev/null +++ b/navigations/navfn/CHANGELOG.rst @@ -0,0 +1,192 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package navfn +^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +1.17.3 (2023-01-10) +------------------- +* [ROS-O] various patches (`#1225 `_) + * do not specify obsolete c++11 standard + this breaks with current versions of log4cxx. + * update pluginlib include paths + the non-hpp headers have been deprecated since kinetic + * use lambdas in favor of boost::bind + Using boost's _1 as a global system is deprecated since C++11. + The ROS packages in Debian removed the implicit support for the global symbols, + so this code fails to compile there without the patch. +* Contributors: Michael Görner + +1.17.2 (2022-06-20) +------------------- +* navfn: stop installing test headers (`#1085 `_) + The navtest executable is only built if FLTK is installed. However, the + header it uses is installed regardless, and requires FLTK. Nothing else + uses this header, and navfn doesn't depend upon FLTK, so stop installing + the header. Also fix navtest to actually build when FLTK is installed. +* Contributors: Kyle Fazzari + +1.17.1 (2020-08-27) +------------------- + +1.17.0 (2020-04-02) +------------------- +* Merge pull request `#982 `_ from ros-planning/noetic_prep + Noetic Migration +* increase required cmake version +* Contributors: Michael Ferguson + +1.16.6 (2020-03-18) +------------------- +* Fix Unknown CMake command check_include_file (navfn & base_local_planner) (`#975 `_) +* Contributors: Sam Pfeiffer + +1.16.5 (2020-03-15) +------------------- +* [melodic] updated install for better portability. (`#973 `_) +* Contributors: Sean Yen + +1.16.4 (2020-03-04) +------------------- +* [Windows][melodic] Navigation (except for map_server and amcl) Windows build bring up (`#851 `_) +* Add frame ID to empty NavFn paths (`#964 `_) + * Don't publish empty paths + RViz will complain about not being able to transform the path if it doesn't have a frame ID, so we'll just drop these + Closes `#963 `_ + * Publish empty paths with a valid frame + * Fix indexing into empty plan for timestamp +* Contributors: Nick Walker, Sean Yen + +1.16.3 (2019-11-15) +------------------- +* Merge pull request `#831 `_ from ros-planning/feature/remove_slashes + [melodic] Remove leading slashes from default frame_id parameters +* Remove leading slashes from default frame_id parameters +* Merge pull request `#789 `_ from ipa-fez/fix/astar_const_melodic + Remove const from create_nav_plan_astar +* remove const from create_nav_plan_astar +* Contributors: David V. Lu, Felix, Michael Ferguson + +1.16.2 (2018-07-31) +------------------- + +1.16.1 (2018-07-28) +------------------- + +1.16.0 (2018-07-25) +------------------- +* Remove dependency on PCL +* Switch to TF2 `#755 `_ +* Merge pull request `#737 `_ from marting87/minor_comment_fixes + Minor comment corrections +* Contributors: David V. Lu, Martin Ganeff, Michael Ferguson, Vincent Rabaud + +1.15.2 (2018-03-22) +------------------- +* Merge pull request `#673 `_ from ros-planning/email_update_lunar + update maintainer email (lunar) +* Remove Dead Code [Lunar] (`#646 `_) + * Clean up navfn + * Cleanup amcl +* Merge pull request `#649 `_ from aaronhoy/lunar_add_ahoy + Add myself as a maintainer. +* Rebase PRs from Indigo/Kinetic (`#637 `_) + * Respect planner_frequency intended behavior (`#622 `_) + * Only do a getRobotPose when no start pose is given (`#628 `_) + Omit the unnecessary call to getRobotPose when the start pose was + already given, so that move_base can also generate a path in + situations where getRobotPose would fail. + This is actually to work around an issue of getRobotPose randomly + failing. + * Update gradient_path.cpp (`#576 `_) + * Update gradient_path.cpp + * Update navfn.cpp + * update to use non deprecated pluginlib macro (`#630 `_) + * update to use non deprecated pluginlib macro + * multiline version as well + * Print SDL error on IMG_Load failure in server_map (`#631 `_) +* Contributors: Aaron Hoy, David V. Lu!!, Michael Ferguson + +1.15.1 (2017-08-14) +------------------- + +1.15.0 (2017-08-07) +------------------- +* convert packages to format2 +* Fix CMakeLists + package.xmls (`#548 `_) +* import only PCL common +* port `#549 `_ (in alphabetical order) +* address gcc6 build error +* remove GCC warnings +* Contributors: Lukas Bulwahn, Martin Günther, Michael Ferguson, Mikael Arguedas, Vincent Rabaud + +1.14.0 (2016-05-20) +------------------- +* navfn: make independent on costmap implementation + navfn::NavfnROS: + * remove direct dependency on costmap_2d::Costmap2DROS + * add constructor for barebone costmap_2d::Costmap2D (user must provide also global_frame) + * NavfnROS::initialize() follows constructor semantics + nav_core::BaseGlobalPlanner interface unchanged +* Contributors: Jiri Horner + +1.13.1 (2015-10-29) +------------------- +* Fix for `#337 `_ +* Contributors: David V. Lu!! + +1.13.0 (2015-03-17) +------------------- + +1.12.0 (2015-02-04) +------------------- +* update maintainer email +* Contributors: Michael Ferguson + +1.11.15 (2015-02-03) +-------------------- +* Add ARCHIVE_DESTINATION for static builds +* Contributors: Gary Servin + +1.11.14 (2014-12-05) +-------------------- + +1.11.13 (2014-10-02) +-------------------- + +1.11.12 (2014-10-01) +-------------------- + +1.11.11 (2014-07-23) +-------------------- +* removes unused param planner_costmap_publish_frequency +* Contributors: Enrique Fernández Perdomo + +1.11.10 (2014-06-25) +-------------------- +* Remove unnecessary colons +* Contributors: David Lu!! + +1.11.9 (2014-06-10) +------------------- +* uses ::hypot(x, y) instead of sqrt(x*x, y*y) +* Contributors: Enrique Fernández Perdomo + +1.11.8 (2014-05-21) +------------------- + +1.11.7 (2014-05-21) +------------------- +* update build to find eigen using cmake_modules +* Contributors: Michael Ferguson + +1.11.5 (2014-01-30) +------------------- +* navfn: fix parallel build error from missing dep +* fixed header installation directory +* check for CATKIN_ENABLE_TESTING +* Change maintainer from Hersh to Lu + +1.11.4 (2013-09-27) +------------------- +* Package URL Updates +* fixed `#103 `_, navfn_node not installed +* Potential missing dependency diff --git a/navigations/navfn/CMakeLists.txt b/navigations/navfn/CMakeLists.txt new file mode 100755 index 0000000..e49357a --- /dev/null +++ b/navigations/navfn/CMakeLists.txt @@ -0,0 +1,141 @@ +cmake_minimum_required(VERSION 3.0.2) +project(navfn) + +include(CheckIncludeFile) + +find_package(catkin REQUIRED + COMPONENTS + cmake_modules + costmap_2d + geometry_msgs + message_generation + nav_core + nav_msgs + pluginlib + rosconsole + roscpp + tf2_ros + sensor_msgs + visualization_msgs + ) + +find_package(Eigen3 REQUIRED) +include_directories( + include + ${catkin_INCLUDE_DIRS} + ${EIGEN3_INCLUDE_DIRS} +) +add_definitions(${EIGEN3_DEFINITIONS}) + + +# services +add_service_files( + DIRECTORY srv + FILES + MakeNavPlan.srv + SetCostmap.srv +) + +generate_messages( + DEPENDENCIES + geometry_msgs +) + +catkin_package( + INCLUDE_DIRS + include + LIBRARIES + navfn + CATKIN_DEPENDS + geometry_msgs + message_runtime + nav_core + nav_msgs + pluginlib + roscpp + sensor_msgs + visualization_msgs +) + +check_include_file(sys/time.h HAVE_SYS_TIME_H) +if (HAVE_SYS_TIME_H) + add_definitions(-DHAVE_SYS_TIME_H) +endif (HAVE_SYS_TIME_H) + +add_library (navfn src/navfn.cpp src/navfn_ros.cpp) +target_link_libraries(navfn + ${catkin_LIBRARIES} + ) +add_dependencies(navfn ${PROJECT_NAME}_generate_messages_cpp ${catkin_EXPORTED_TARGETS}) + +add_executable(navfn_node src/navfn_node.cpp) +target_link_libraries(navfn_node + navfn + ) + +install(TARGETS navfn_node + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} + ) + +install(TARGETS navfn + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} + ) + +install(DIRECTORY include/navfn/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} +) + +install(FILES bgp_plugin.xml + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) + +### The problem with FindFLTK is that it only reports success if *all* +### fltk components are installed, but we only need the core library. +# include (FindFLTK) +include (CheckIncludeFileCXX) +check_include_file_cxx (FL/Fl.H NAVFN_HAVE_FLTK) +check_include_file_cxx (pgm.h NAVFN_HAVE_NETPBM) +message (STATUS "NAVFN_HAVE_FLTK: ${NAVFN_HAVE_FLTK}, NETPBM: ${NAVFN_HAVE_NETPBM}") +# Just linking -lfltk is not sufficient on OS X +if (NAVFN_HAVE_FLTK AND NAVFN_HAVE_NETPBM AND NOT APPLE) + message (STATUS "FLTK found: adding navtest to build") + add_executable (navtest src/navtest/navtest.cpp src/navtest/navwin.cpp) + set (FLTK_SKIP_FLUID 1) + set (FLTK_SKIP_FORMS 1) + set (FLTK_SKIP_IMAGES 1) + find_package(FLTK) + if(FLTK_FOUND) + target_link_libraries (navtest navfn netpbm ${FLTK_LIBRARIES}) + else (FLTK_FOUND) + target_link_libraries (navtest navfn netpbm fltk) + endif (FLTK_FOUND) +else (NAVFN_HAVE_FLTK) + message (STATUS "FLTK orf NETPBM not found: cannot build navtest") +endif (NAVFN_HAVE_FLTK AND NAVFN_HAVE_NETPBM AND NOT APPLE) + +### For some reason (on cmake-2.4.7 at least) the "check" for pgm.h +### always succeeds, even if pgm.h is not installed. It seems to be +### caused by a bug in the rule that attempts to build the C source: +### instead of directly calling e.g. 'gcc -c +### /CMakeFiles/CMakeTmp/CheckIncludeFile.c' it goes through some make +### infrastructure, which reports "Nothing to be done for +### `CMakeFiles/cmTryCompileExec.dir/build'" and calls that a success. +### +### As a workaround we simply force everyone to install libnetpbm +# +# include (CheckIncludeFile) +# check_include_file (pgm.h NAVFN_HAVE_NETPBM) +# message (STATUS "NAVFN_HAVE_NETPBM: ${NAVFN_HAVE_NETPBM}") +# if (NAVFN_HAVE_NETPBM) +# message (STATUS "found pgm.h") +# add_definitions (-DNAVFN_HAVE_NETPBM) +#target_link_libraries (navfn -lnetpbm) +# else (NAVFN_HAVE_NETPBM) +# message (STATUS "pgm.h not found (optional)") +# endif (NAVFN_HAVE_NETPBM) + +if(CATKIN_ENABLE_TESTING) + add_subdirectory(test) +endif() diff --git a/navigations/navfn/Makefile.orig b/navigations/navfn/Makefile.orig new file mode 100755 index 0000000..95abc9c --- /dev/null +++ b/navigations/navfn/Makefile.orig @@ -0,0 +1,39 @@ +# +# Makefile for navigation function planner +# + +CC = g++ +CXX = g++ +LD = g++ +CPPFLAGS = -Wall -g -O3 -Iinclude -I/usr/local/include -I/usr/local/include/opencv +CFLAGS = -DGCC -msse2 -mpreferred-stack-boundary=4 -O3 -Wall -Iinclude -I/usr/local/include +GCC = g++ +LDFLAGS = -Lbin +SHAREDFLAGS = -shared -Wl,-soname, +LIBS = -lfltk -lnetpbm + +OBJECTS = navfn navwin + +all: bin/navtest + +bin/navtest: obj/navtest.o $(OBJECTS:%=obj/%.o) + $(LD) $(LDFLAGS) -o $@ $(OBJECTS:%=obj/%.o) obj/navtest.o $(LIBS) + +# general cpp command from src->obj +obj/%.o:src/%.cpp + $(GCC) $(CPPFLAGS) -c $< -o $@ + +# general c command from src->obj +obj/%.o:src/%.c + $(GCC) $(CFLAGS) -c $< -o $@ + +obj/navfn.o: include/navfn/navfn.h + +clean: + - rm obj/*.o + - rm bin/navtest + +dist: + + + diff --git a/navigations/navfn/bgp_plugin.xml b/navigations/navfn/bgp_plugin.xml new file mode 100755 index 0000000..86f3ad6 --- /dev/null +++ b/navigations/navfn/bgp_plugin.xml @@ -0,0 +1,7 @@ + + + + A implementation of a grid based planner using Dijkstra + + + diff --git a/navigations/navfn/include/navfn/navfn.h b/navigations/navfn/include/navfn/navfn.h new file mode 100755 index 0000000..7edc3a4 --- /dev/null +++ b/navigations/navfn/include/navfn/navfn.h @@ -0,0 +1,267 @@ +/********************************************************************* +* Software License Agreement (BSD License) +* +* Copyright (c) 2008, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of the Willow Garage nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +*********************************************************************/ + +// +// Navigation function computation +// Uses Dijkstra's method +// Modified for Euclidean-distance computation +// + +#ifndef _NAVFN_H +#define _NAVFN_H + +#include +#include +#include +#include + +// cost defs +#define COST_UNKNOWN_ROS 255 // 255 is unknown cost +#define COST_OBS 254 // 254 for forbidden regions +#define COST_OBS_ROS 253 // ROS values of 253 are obstacles + +// navfn cost values are set to +// COST_NEUTRAL + COST_FACTOR * costmap_cost_value. +// Incoming costmap cost values are in the range 0 to 252. +// With COST_NEUTRAL of 50, the COST_FACTOR needs to be about 0.8 to +// ensure the input values are spread evenly over the output range, 50 +// to 253. If COST_FACTOR is higher, cost values will have a plateau +// around obstacles and the planner will then treat (for example) the +// whole width of a narrow hallway as equally undesirable and thus +// will not plan paths down the center. + +#define COST_NEUTRAL 50 // Set this to "open space" value +#define COST_FACTOR 0.8 // Used for translating costs in NavFn::setCostmap() + +// Define the cost type in the case that it is not set. However, this allows +// clients to modify it without changing the file. Arguably, it is better to require it to +// be defined by a user explicitly +#ifndef COSTTYPE +#define COSTTYPE unsigned char // Whatever is used... +#endif + +// potential defs +#define POT_HIGH 1.0e10 // unassigned cell potential + +// priority buffers +#define PRIORITYBUFSIZE 10000 + + +namespace navfn { + /** + Navigation function call. + \param costmap Cost map array, of type COSTTYPE; origin is upper left +NOTE: will be modified to have a border of obstacle costs +\param nx Width of map in cells +\param ny Height of map in cells +\param goal X,Y position of goal cell +\param start X,Y position of start cell + +Returns length of plan if found, and fills an array with x,y interpolated +positions at about 1/2 cell resolution; else returns 0. + +*/ + + int create_nav_plan_astar(COSTTYPE *costmap, int nx, int ny, + int* goal, int* start, + float *plan, int nplan); + + + + /** + * @class NavFn + * @brief Navigation function class. Holds buffers for costmap, navfn map. Maps are pixel-based. Origin is upper left, x is right, y is down. + */ + class NavFn + { + public: + /** + * @brief Constructs the planner + * @param nx The x size of the map + * @param ny The y size of the map + */ + NavFn(int nx, int ny); // size of map + + ~NavFn(); + + /** + * @brief Sets or resets the size of the map + * @param nx The x size of the map + * @param ny The y size of the map + */ + void setNavArr(int nx, int ny); /**< sets or resets the size of the map */ + int nx, ny, ns; /**< size of grid, in pixels */ + + /** + * @brief Set up the cost array for the planner, usually from ROS + * @param cmap The costmap + * @param isROS Whether or not the costmap is coming in in ROS format + * @param allow_unknown Whether or not the planner should be allowed to plan through unknown space + */ + void setCostmap(const COSTTYPE *cmap, bool isROS=true, bool allow_unknown = true); /**< sets up the cost map */ + + /** + * @brief Calculates a plan using the A* heuristic, returns true if one is found + * @return True if a plan is found, false otherwise + */ + bool calcNavFnAstar(); /**< calculates a plan, returns true if found */ + + /** + * @brief Caclulates the full navigation function using Dijkstra + */ + bool calcNavFnDijkstra(bool atStart = false); /**< calculates the full navigation function */ + + /** + * @brief Accessor for the x-coordinates of a path + * @return The x-coordinates of a path + */ + float *getPathX(); /**< x-coordinates of path */ + + /** + * @brief Accessor for the y-coordinates of a path + * @return The y-coordinates of a path + */ + float *getPathY(); /**< y-coordinates of path */ + + /** + * @brief Accessor for the length of a path + * @return The length of a path + */ + int getPathLen(); /**< length of path, 0 if not found */ + + /** + * @brief Gets the cost of the path found the last time a navigation function was computed + * @return The cost of the last path found + */ + float getLastPathCost(); /**< Return cost of path found the last time A* was called */ + + /** cell arrays */ + COSTTYPE *costarr; /**< cost array in 2D configuration space */ + float *potarr; /**< potential array, navigation function potential */ + bool *pending; /**< pending cells during propagation */ + int nobs; /**< number of obstacle cells */ + + /** block priority buffers */ + int *pb1, *pb2, *pb3; /**< storage buffers for priority blocks */ + int *curP, *nextP, *overP; /**< priority buffer block ptrs */ + int curPe, nextPe, overPe; /**< end points of arrays */ + + /** block priority thresholds */ + float curT; /**< current threshold */ + float priInc; /**< priority threshold increment */ + + /** goal and start positions */ + /** + * @brief Sets the goal position for the planner. Note: the navigation cost field computed gives the cost to get to a given point from the goal, not from the start. + * @param goal the goal position + */ + void setGoal(int *goal); + + /** + * @brief Sets the start position for the planner. Note: the navigation cost field computed gives the cost to get to a given point from the goal, not from the start. + * @param start the start position + */ + void setStart(int *start); + + int goal[2]; + int start[2]; + /** + * @brief Initialize cell k with cost v for propagation + * @param k the cell to initialize + * @param v the cost to give to the cell + */ + void initCost(int k, float v); /**< initialize cell with cost , for propagation */ + + /** propagation */ + + /** + * @brief Updates the cell at index n + * @param n The index to update + */ + void updateCell(int n); /**< updates the cell at index */ + + /** + * @brief Updates the cell at index n using the A* heuristic + * @param n The index to update + */ + void updateCellAstar(int n); /**< updates the cell at index , uses A* heuristic */ + + void setupNavFn(bool keepit = false); /**< resets all nav fn arrays for propagation */ + + /** + * @brief Run propagation for iterations, or until start is reached using breadth-first Dijkstra method + * @param cycles The maximum number of iterations to run for + * @param atStart Whether or not to stop when the start point is reached + * @return true if the start point is reached + */ + bool propNavFnDijkstra(int cycles, bool atStart = false); /**< returns true if start point found or full prop */ + /** + * @brief Run propagation for iterations, or until start is reached using the best-first A* method with Euclidean distance heuristic + * @param cycles The maximum number of iterations to run for + * @return true if the start point is reached + */ + bool propNavFnAstar(int cycles); /**< returns true if start point found */ + + /** gradient and paths */ + float *gradx, *grady; /**< gradient arrays, size of potential array */ + float *pathx, *pathy; /**< path points, as subpixel cell coordinates */ + int npath; /**< number of path points */ + int npathbuf; /**< size of pathx, pathy buffers */ + + float last_path_cost_; /**< Holds the cost of the path found the last time A* was called */ + + + /** + * @brief Calculates the path for at mose cycles + * @param n The maximum number of cycles to run for + * @return The length of the path found + */ + int calcPath(int n, int *st = NULL); /**< calculates path for at most cycles, returns path length, 0 if none */ + + float gradCell(int n); /**< calculates gradient at cell , returns norm */ + float pathStep; /**< step size for following gradient */ + + /** display callback */ + void display(void fn(NavFn *nav), int n = 100); /**< is the number of cycles between updates */ + int displayInt; /**< save second argument of display() above */ + void (*displayFn)(NavFn *nav); /**< display function itself */ + + /** save costmap */ + void savemap(const char *fname); /**< write out costmap and start/goal states as fname.pgm and fname.txt */ + + }; +}; + + +#endif // NAVFN diff --git a/navigations/navfn/include/navfn/navfn_ros.h b/navigations/navfn/include/navfn/navfn_ros.h new file mode 100755 index 0000000..9438007 --- /dev/null +++ b/navigations/navfn/include/navfn/navfn_ros.h @@ -0,0 +1,188 @@ +/********************************************************************* +* +* Software License Agreement (BSD License) +* +* Copyright (c) 2008, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of the Willow Garage nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* +* Author: Eitan Marder-Eppstein +*********************************************************************/ +#ifndef NAVFN_NAVFN_ROS_H_ +#define NAVFN_NAVFN_ROS_H_ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +namespace navfn { + /** + * @class NavfnROS + * @brief Provides a ROS wrapper for the navfn planner which runs a fast, interpolated navigation function on a costmap. + */ + class NavfnROS : public nav_core::BaseGlobalPlanner { + public: + /** + * @brief Default constructor for the NavFnROS object + */ + NavfnROS(); + + /** + * @brief Constructor for the NavFnROS object + * @param name The name of this planner + * @param costmap A pointer to the ROS wrapper of the costmap to use + */ + NavfnROS(std::string name, costmap_2d::Costmap2DROS* costmap_ros); + + /** + * @brief Constructor for the NavFnROS object + * @param name The name of this planner + * @param costmap A pointer to the costmap to use + * @param global_frame The global frame of the costmap + */ + NavfnROS(std::string name, costmap_2d::Costmap2D* costmap, std::string global_frame); + + /** + * @brief Initialization function for the NavFnROS object + * @param name The name of this planner + * @param costmap A pointer to the ROS wrapper of the costmap to use for planning + */ + void initialize(std::string name, costmap_2d::Costmap2DROS* costmap_ros); + + /** + * @brief Initialization function for the NavFnROS object + * @param name The name of this planner + * @param costmap A pointer to the costmap to use for planning + * @param global_frame The global frame of the costmap + */ + void initialize(std::string name, costmap_2d::Costmap2D* costmap, std::string global_frame); + + /** + * @brief Given a goal pose in the world, compute a plan + * @param start The start pose + * @param goal The goal pose + * @param plan The plan... filled by the planner + * @return True if a valid plan was found, false otherwise + */ + bool makePlan(const geometry_msgs::PoseStamped& start, + const geometry_msgs::PoseStamped& goal, std::vector& plan); + + /** + * @brief Given a goal pose in the world, compute a plan + * @param start The start pose + * @param goal The goal pose + * @param tolerance The tolerance on the goal point for the planner + * @param plan The plan... filled by the planner + * @return True if a valid plan was found, false otherwise + */ + bool makePlan(const geometry_msgs::PoseStamped& start, + const geometry_msgs::PoseStamped& goal, double tolerance, std::vector& plan); + + /** + * @brief Computes the full navigation function for the map given a point in the world to start from + * @param world_point The point to use for seeding the navigation function + * @return True if the navigation function was computed successfully, false otherwise + */ + bool computePotential(const geometry_msgs::Point& world_point); + + /** + * @brief Compute a plan to a goal after the potential for a start point has already been computed (Note: You should call computePotential first) + * @param goal The goal pose to create a plan to + * @param plan The plan... filled by the planner + * @return True if a valid plan was found, false otherwise + */ + bool getPlanFromPotential(const geometry_msgs::PoseStamped& goal, std::vector& plan); + + /** + * @brief Get the potential, or naviagation cost, at a given point in the world (Note: You should call computePotential first) + * @param world_point The point to get the potential for + * @return The navigation function's value at that point in the world + */ + double getPointPotential(const geometry_msgs::Point& world_point); + + /** + * @brief Check for a valid potential value at a given point in the world (Note: You should call computePotential first) + * @param world_point The point to get the potential for + * @return True if the navigation function is valid at that point in the world, false otherwise + */ + bool validPointPotential(const geometry_msgs::Point& world_point); + + /** + * @brief Check for a valid potential value at a given point in the world (Note: You should call computePotential first) + * @param world_point The point to get the potential for + * @param tolerance The tolerance on searching around the world_point specified + * @return True if the navigation function is valid at that point in the world, false otherwise + */ + bool validPointPotential(const geometry_msgs::Point& world_point, double tolerance); + + /** + * @brief Publish a path for visualization purposes + */ + void publishPlan(const std::vector& path, double r, double g, double b, double a); + + ~NavfnROS(){} + + bool makePlanService(nav_msgs::GetPlan::Request& req, nav_msgs::GetPlan::Response& resp); + + protected: + + /** + * @brief Store a copy of the current costmap in \a costmap. Called by makePlan. + */ + costmap_2d::Costmap2D* costmap_; + boost::shared_ptr planner_; + ros::Publisher plan_pub_; + ros::Publisher potarr_pub_; + bool initialized_, allow_unknown_, visualize_potential_; + + + private: + inline double sq_distance(const geometry_msgs::PoseStamped& p1, const geometry_msgs::PoseStamped& p2){ + double dx = p1.pose.position.x - p2.pose.position.x; + double dy = p1.pose.position.y - p2.pose.position.y; + return dx*dx +dy*dy; + } + + void mapToWorld(double mx, double my, double& wx, double& wy); + void clearRobotCell(const geometry_msgs::PoseStamped& global_pose, unsigned int mx, unsigned int my); + double planner_window_x_, planner_window_y_, default_tolerance_; + boost::mutex mutex_; + ros::ServiceServer make_plan_srv_; + std::string global_frame_; + }; +}; + +#endif diff --git a/navigations/navfn/include/navfn/potarr_point.h b/navigations/navfn/include/navfn/potarr_point.h new file mode 100755 index 0000000..957e991 --- /dev/null +++ b/navigations/navfn/include/navfn/potarr_point.h @@ -0,0 +1,50 @@ +/********************************************************************* +* +* Software License Agreement (BSD License) +* +* Copyright (c) 2008, (Simon) Ye Cheng +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of the Willow Garage nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* +*********************************************************************/ + +#ifndef POTARR_POINT_H_ +#define POTARR_POINT_H_ + +namespace navfn { + struct PotarrPoint { + float x; + float y; + float z; + float pot_value; + }; +} + +#endif + diff --git a/navigations/navfn/include/navfn/read_pgm_costmap.h b/navigations/navfn/include/navfn/read_pgm_costmap.h new file mode 100755 index 0000000..37bfe68 --- /dev/null +++ b/navigations/navfn/include/navfn/read_pgm_costmap.h @@ -0,0 +1,35 @@ +/* + * Copyright (c) 2012, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ +#ifndef READ_PGM_COSTMAP_H +#define READ_PGM_COSTMAP_H + +// is true for ROS-generated raw cost maps +COSTTYPE *readPGM(const char *fname, int *width, int *height, bool raw = false); + +#endif // READ_PGM_COSTMAP_H diff --git a/navigations/navfn/package.xml b/navigations/navfn/package.xml new file mode 100755 index 0000000..49b6cd0 --- /dev/null +++ b/navigations/navfn/package.xml @@ -0,0 +1,49 @@ + + + + navfn + 1.17.3 + + + navfn provides a fast interpolated navigation function that can be used to create plans for + a mobile base. The planner assumes a circular robot and operates on a costmap to find a + minimum cost plan from a start point to an end point in a grid. The navigation function is + computed with Dijkstra's algorithm, but support for an A* heuristic may also be added in the + near future. navfn also provides a ROS wrapper for the navfn planner that adheres to the + nav_core::BaseGlobalPlanner interface specified in nav_core. + + + Kurt Konolige + Eitan Marder-Eppstein + contradict@gmail.com + David V. Lu!! + Michael Ferguson + Aaron Hoy + BSD + http://wiki.ros.org/navfn + + catkin + + cmake_modules + message_generation + netpbm + + costmap_2d + geometry_msgs + nav_core + nav_msgs + pluginlib + rosconsole + roscpp + sensor_msgs + tf2_ros + visualization_msgs + + message_runtime + + rosunit + + + + + diff --git a/navigations/navfn/src/navfn.cpp b/navigations/navfn/src/navfn.cpp new file mode 100755 index 0000000..8b1fffc --- /dev/null +++ b/navigations/navfn/src/navfn.cpp @@ -0,0 +1,1056 @@ +/********************************************************************* +* Software License Agreement (BSD License) +* +* Copyright (c) 2008, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of the Willow Garage nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +*********************************************************************/ +// +// Navigation function computation +// Uses Dijkstra's method +// Modified for Euclidean-distance computation +// +// Path calculation uses no interpolation when pot field is at max in +// nearby cells +// +// Path calc has sanity check that it succeeded +// + + +#include +#include + +namespace navfn { + + // + // function to perform nav fn calculation + // keeps track of internal buffers, will be more efficient + // if the size of the environment does not change + // + + int + create_nav_plan_astar(COSTTYPE *costmap, int nx, int ny, + int* goal, int* start, + float *plan, int nplan) + { + static NavFn *nav = NULL; + + if (nav == NULL) + nav = new NavFn(nx,ny); + + if (nav->nx != nx || nav->ny != ny) // check for compatibility with previous call + { + delete nav; + nav = new NavFn(nx,ny); + } + + nav->setGoal(goal); + nav->setStart(start); + + nav->costarr = costmap; + nav->setupNavFn(true); + + // calculate the nav fn and path + nav->priInc = 2*COST_NEUTRAL; + nav->propNavFnAstar(std::max(nx*ny/20,nx+ny)); + + // path + int len = nav->calcPath(nplan); + + if (len > 0) // found plan + ROS_DEBUG("[NavFn] Path found, %d steps\n", len); + else + ROS_DEBUG("[NavFn] No path found\n"); + + if (len > 0) + { + for (int i=0; ipathx[i]; + plan[i*2+1] = nav->pathy[i]; + } + } + + return len; + } + + + + + // + // create nav fn buffers + // + + NavFn::NavFn(int xs, int ys) + { + // create cell arrays + costarr = NULL; + potarr = NULL; + pending = NULL; + gradx = grady = NULL; + setNavArr(xs,ys); + + // priority buffers + pb1 = new int[PRIORITYBUFSIZE]; + pb2 = new int[PRIORITYBUFSIZE]; + pb3 = new int[PRIORITYBUFSIZE]; + + // for Dijkstra (breadth-first), set to COST_NEUTRAL + // for A* (best-first), set to COST_NEUTRAL + priInc = 2*COST_NEUTRAL; + + // goal and start + goal[0] = goal[1] = 0; + start[0] = start[1] = 0; + + // display function + displayFn = NULL; + displayInt = 0; + + // path buffers + npathbuf = npath = 0; + pathx = pathy = NULL; + pathStep = 0.5; + } + + + NavFn::~NavFn() + { + if(costarr) + delete[] costarr; + if(potarr) + delete[] potarr; + if(pending) + delete[] pending; + if(gradx) + delete[] gradx; + if(grady) + delete[] grady; + if(pathx) + delete[] pathx; + if(pathy) + delete[] pathy; + if(pb1) + delete[] pb1; + if(pb2) + delete[] pb2; + if(pb3) + delete[] pb3; + } + + + // + // set goal, start positions for the nav fn + // + + void + NavFn::setGoal(int *g) + { + goal[0] = g[0]; + goal[1] = g[1]; + ROS_DEBUG("[NavFn] Setting goal to %d,%d\n", goal[0], goal[1]); + } + + void + NavFn::setStart(int *g) + { + start[0] = g[0]; + start[1] = g[1]; + ROS_DEBUG("[NavFn] Setting start to %d,%d\n", start[0], start[1]); + } + + // + // Set/Reset map size + // + + void + NavFn::setNavArr(int xs, int ys) + { + ROS_DEBUG("[NavFn] Array is %d x %d\n", xs, ys); + + nx = xs; + ny = ys; + ns = nx*ny; + + if(costarr) + delete[] costarr; + if(potarr) + delete[] potarr; + if(pending) + delete[] pending; + + if(gradx) + delete[] gradx; + if(grady) + delete[] grady; + + costarr = new COSTTYPE[ns]; // cost array, 2d config space + memset(costarr, 0, ns*sizeof(COSTTYPE)); + potarr = new float[ns]; // navigation potential array + pending = new bool[ns]; + memset(pending, 0, ns*sizeof(bool)); + gradx = new float[ns]; + grady = new float[ns]; + } + + + // + // set up cost array, usually from ROS + // + + void + NavFn::setCostmap(const COSTTYPE *cmap, bool isROS, bool allow_unknown) + { + COSTTYPE *cm = costarr; + if (isROS) // ROS-type cost array + { + for (int i=0; i COST_OBS (incoming "lethal obstacle") + // COST_OBS_ROS -> COST_OBS (incoming "inscribed inflated obstacle") + // values in range 0 to 252 -> values from COST_NEUTRAL to COST_OBS_ROS. + *cm = COST_OBS; + int v = *cmap; + if (v < COST_OBS_ROS) + { + v = COST_NEUTRAL+COST_FACTOR*v; + if (v >= COST_OBS) + v = COST_OBS-1; + *cm = v; + } + else if(v == COST_UNKNOWN_ROS && allow_unknown) + { + v = COST_OBS-1; + *cm = v; + } + } + } + } + + else // not a ROS map, just a PGM + { + for (int i=0; i ny-8 || j<7 || j > nx-8) + continue; // don't do borders + int v = *cmap; + if (v < COST_OBS_ROS) + { + v = COST_NEUTRAL+COST_FACTOR*v; + if (v >= COST_OBS) + v = COST_OBS-1; + *cm = v; + } + else if(v == COST_UNKNOWN_ROS) + { + v = COST_OBS-1; + *cm = v; + } + } + } + + } + } + + bool + NavFn::calcNavFnDijkstra(bool atStart) + { + setupNavFn(true); + + // calculate the nav fn and path + propNavFnDijkstra(std::max(nx*ny/20,nx+ny),atStart); + + // path + int len = calcPath(nx*ny/2); + + if (len > 0) // found plan + { + ROS_DEBUG("[NavFn] Path found, %d steps\n", len); + return true; + } + else + { + ROS_DEBUG("[NavFn] No path found\n"); + return false; + } + + } + + + // + // calculate navigation function, given a costmap, goal, and start + // + + bool + NavFn::calcNavFnAstar() + { + setupNavFn(true); + + // calculate the nav fn and path + propNavFnAstar(std::max(nx*ny/20,nx+ny)); + + // path + int len = calcPath(nx*4); + + if (len > 0) // found plan + { + ROS_DEBUG("[NavFn] Path found, %d steps\n", len); + return true; + } + else + { + ROS_DEBUG("[NavFn] No path found\n"); + return false; + } + } + + + // + // returning values + // + + float *NavFn::getPathX() { return pathx; } + float *NavFn::getPathY() { return pathy; } + int NavFn::getPathLen() { return npath; } + + // inserting onto the priority blocks +#define push_cur(n) { if (n>=0 && n=0 && n=0 && n= COST_OBS) + ntot++; // number of cells that are obstacles + } + nobs = ntot; + } + + + // initialize a goal-type cost for starting propagation + + void + NavFn::initCost(int k, float v) + { + potarr[k] = v; + push_cur(k+1); + push_cur(k-1); + push_cur(k-nx); + push_cur(k+nx); + } + + + // + // Critical function: calculate updated potential value of a cell, + // given its neighbors' values + // Planar-wave update calculation from two lowest neighbors in a 4-grid + // Quadratic approximation to the interpolated value + // No checking of bounds here, this function should be fast + // + +#define INVSQRT2 0.707106781 + + inline void + NavFn::updateCell(int n) + { + // get neighbors + float u,d,l,r; + l = potarr[n-1]; + r = potarr[n+1]; + u = potarr[n-nx]; + d = potarr[n+nx]; + // ROS_INFO("[Update] c: %0.1f l: %0.1f r: %0.1f u: %0.1f d: %0.1f\n", + // potarr[n], l, r, u, d); + // ROS_INFO("[Update] cost: %d\n", costarr[n]); + + // find lowest, and its lowest neighbor + float ta, tc; + if (l= hf) // if too large, use ta-only update + pot = ta+hf; + else // two-neighbor interpolation update + { + // use quadratic approximation + // might speed this up through table lookup, but still have to + // do the divide + float d = dc/hf; + float v = -0.2301*d*d + 0.5307*d + 0.7040; + pot = ta + hf*v; + } + + // ROS_INFO("[Update] new pot: %d\n", costarr[n]); + + // now add affected neighbors to priority blocks + if (pot < potarr[n]) + { + float le = INVSQRT2*(float)costarr[n-1]; + float re = INVSQRT2*(float)costarr[n+1]; + float ue = INVSQRT2*(float)costarr[n-nx]; + float de = INVSQRT2*(float)costarr[n+nx]; + potarr[n] = pot; + if (pot < curT) // low-cost buffer block + { + if (l > pot+le) push_next(n-1); + if (r > pot+re) push_next(n+1); + if (u > pot+ue) push_next(n-nx); + if (d > pot+de) push_next(n+nx); + } + else // overflow block + { + if (l > pot+le) push_over(n-1); + if (r > pot+re) push_over(n+1); + if (u > pot+ue) push_over(n-nx); + if (d > pot+de) push_over(n+nx); + } + } + + } + + } + + + // + // Use A* method for setting priorities + // Critical function: calculate updated potential value of a cell, + // given its neighbors' values + // Planar-wave update calculation from two lowest neighbors in a 4-grid + // Quadratic approximation to the interpolated value + // No checking of bounds here, this function should be fast + // + +#define INVSQRT2 0.707106781 + + inline void + NavFn::updateCellAstar(int n) + { + // get neighbors + float u,d,l,r; + l = potarr[n-1]; + r = potarr[n+1]; + u = potarr[n-nx]; + d = potarr[n+nx]; + //ROS_INFO("[Update] c: %0.1f l: %0.1f r: %0.1f u: %0.1f d: %0.1f\n", + // potarr[n], l, r, u, d); + // ROS_INFO("[Update] cost of %d: %d\n", n, costarr[n]); + + // find lowest, and its lowest neighbor + float ta, tc; + if (l= hf) // if too large, use ta-only update + pot = ta+hf; + else // two-neighbor interpolation update + { + // use quadratic approximation + // might speed this up through table lookup, but still have to + // do the divide + float d = dc/hf; + float v = -0.2301*d*d + 0.5307*d + 0.7040; + pot = ta + hf*v; + } + + //ROS_INFO("[Update] new pot: %d\n", costarr[n]); + + // now add affected neighbors to priority blocks + if (pot < potarr[n]) + { + float le = INVSQRT2*(float)costarr[n-1]; + float re = INVSQRT2*(float)costarr[n+1]; + float ue = INVSQRT2*(float)costarr[n-nx]; + float de = INVSQRT2*(float)costarr[n+nx]; + + // calculate distance + int x = n%nx; + int y = n/nx; + float dist = hypot(x-start[0], y-start[1])*(float)COST_NEUTRAL; + + potarr[n] = pot; + pot += dist; + if (pot < curT) // low-cost buffer block + { + if (l > pot+le) push_next(n-1); + if (r > pot+re) push_next(n+1); + if (u > pot+ue) push_next(n-nx); + if (d > pot+de) push_next(n+nx); + } + else + { + if (l > pot+le) push_over(n-1); + if (r > pot+re) push_over(n+1); + if (u > pot+ue) push_over(n-nx); + if (d > pot+de) push_over(n+nx); + } + } + + } + + } + + + + // + // main propagation function + // Dijkstra method, breadth-first + // runs for a specified number of cycles, + // or until it runs out of cells to update, + // or until the Start cell is found (atStart = true) + // + + bool + NavFn::propNavFnDijkstra(int cycles, bool atStart) + { + int nwv = 0; // max priority block size + int nc = 0; // number of cells put into priority blocks + int cycle = 0; // which cycle we're on + + // set up start cell + int startCell = start[1]*nx + start[0]; + + for (; cycle < cycles; cycle++) // go for this many cycles, unless interrupted + { + // + if (curPe == 0 && nextPe == 0) // priority blocks empty + break; + + // stats + nc += curPe; + if (curPe > nwv) + nwv = curPe; + + // reset pending flags on current priority buffer + int *pb = curP; + int i = curPe; + while (i-- > 0) + pending[*(pb++)] = false; + + // process current priority buffer + pb = curP; + i = curPe; + while (i-- > 0) + updateCell(*pb++); + + if (displayInt > 0 && (cycle % displayInt) == 0) + displayFn(this); + + // swap priority blocks curP <=> nextP + curPe = nextPe; + nextPe = 0; + pb = curP; // swap buffers + curP = nextP; + nextP = pb; + + // see if we're done with this priority level + if (curPe == 0) + { + curT += priInc; // increment priority threshold + curPe = overPe; // set current to overflow block + overPe = 0; + pb = curP; // swap buffers + curP = overP; + overP = pb; + } + + // check if we've hit the Start cell + if (atStart) + if (potarr[startCell] < POT_HIGH) + break; + } + + ROS_DEBUG("[NavFn] Used %d cycles, %d cells visited (%d%%), priority buf max %d\n", + cycle,nc,(int)((nc*100.0)/(ns-nobs)),nwv); + + if (cycle < cycles) return true; // finished up here + else return false; + } + + + // + // main propagation function + // A* method, best-first + // uses Euclidean distance heuristic + // runs for a specified number of cycles, + // or until it runs out of cells to update, + // or until the Start cell is found (atStart = true) + // + + bool + NavFn::propNavFnAstar(int cycles) + { + int nwv = 0; // max priority block size + int nc = 0; // number of cells put into priority blocks + int cycle = 0; // which cycle we're on + + // set initial threshold, based on distance + float dist = hypot(goal[0]-start[0], goal[1]-start[1])*(float)COST_NEUTRAL; + curT = dist + curT; + + // set up start cell + int startCell = start[1]*nx + start[0]; + + // do main cycle + for (; cycle < cycles; cycle++) // go for this many cycles, unless interrupted + { + // + if (curPe == 0 && nextPe == 0) // priority blocks empty + break; + + // stats + nc += curPe; + if (curPe > nwv) + nwv = curPe; + + // reset pending flags on current priority buffer + int *pb = curP; + int i = curPe; + while (i-- > 0) + pending[*(pb++)] = false; + + // process current priority buffer + pb = curP; + i = curPe; + while (i-- > 0) + updateCellAstar(*pb++); + + if (displayInt > 0 && (cycle % displayInt) == 0) + displayFn(this); + + // swap priority blocks curP <=> nextP + curPe = nextPe; + nextPe = 0; + pb = curP; // swap buffers + curP = nextP; + nextP = pb; + + // see if we're done with this priority level + if (curPe == 0) + { + curT += priInc; // increment priority threshold + curPe = overPe; // set current to overflow block + overPe = 0; + pb = curP; // swap buffers + curP = overP; + overP = pb; + } + + // check if we've hit the Start cell + if (potarr[startCell] < POT_HIGH) + break; + + } + + last_path_cost_ = potarr[startCell]; + + ROS_DEBUG("[NavFn] Used %d cycles, %d cells visited (%d%%), priority buf max %d\n", + cycle,nc,(int)((nc*100.0)/(ns-nobs)),nwv); + + + if (potarr[startCell] < POT_HIGH) return true; // finished up here + else return false; + } + + + float NavFn::getLastPathCost() + { + return last_path_cost_; + } + + + // + // Path construction + // Find gradient at array points, interpolate path + // Use step size of pathStep, usually 0.5 pixel + // + // Some sanity checks: + // 1. Stuck at same index position + // 2. Doesn't get near goal + // 3. Surrounded by high potentials + // + + int + NavFn::calcPath(int n, int *st) + { + // test write + //savemap("test"); + + // check path arrays + if (npathbuf < n) + { + if (pathx) delete [] pathx; + if (pathy) delete [] pathy; + pathx = new float[n]; + pathy = new float[n]; + npathbuf = n; + } + + // set up start position at cell + // st is always upper left corner for 4-point bilinear interpolation + if (st == NULL) st = start; + int stc = st[1]*nx + st[0]; + + // set up offset + float dx=0; + float dy=0; + npath = 0; + + // go for cycles at most + for (int i=0; i ns-nx) // would be out of bounds + { + ROS_DEBUG("[PathCalc] Out of bounds"); + return 0; + } + + // add to path + pathx[npath] = stc%nx + dx; + pathy[npath] = stc/nx + dy; + npath++; + + bool oscillation_detected = false; + if( npath > 2 && + pathx[npath-1] == pathx[npath-3] && + pathy[npath-1] == pathy[npath-3] ) + { + ROS_DEBUG("[PathCalc] oscillation detected, attempting fix."); + oscillation_detected = true; + } + + int stcnx = stc+nx; + int stcpx = stc-nx; + + // check for potentials at eight positions near cell + if (potarr[stc] >= POT_HIGH || + potarr[stc+1] >= POT_HIGH || + potarr[stc-1] >= POT_HIGH || + potarr[stcnx] >= POT_HIGH || + potarr[stcnx+1] >= POT_HIGH || + potarr[stcnx-1] >= POT_HIGH || + potarr[stcpx] >= POT_HIGH || + potarr[stcpx+1] >= POT_HIGH || + potarr[stcpx-1] >= POT_HIGH || + oscillation_detected) + { + ROS_DEBUG("[Path] Pot fn boundary, following grid (%0.1f/%d)", potarr[stc], npath); + // check eight neighbors to find the lowest + int minc = stc; + int minp = potarr[stc]; + int st = stcpx - 1; + if (potarr[st] < minp) {minp = potarr[st]; minc = st; } + st++; + if (potarr[st] < minp) {minp = potarr[st]; minc = st; } + st++; + if (potarr[st] < minp) {minp = potarr[st]; minc = st; } + st = stc-1; + if (potarr[st] < minp) {minp = potarr[st]; minc = st; } + st = stc+1; + if (potarr[st] < minp) {minp = potarr[st]; minc = st; } + st = stcnx-1; + if (potarr[st] < minp) {minp = potarr[st]; minc = st; } + st++; + if (potarr[st] < minp) {minp = potarr[st]; minc = st; } + st++; + if (potarr[st] < minp) {minp = potarr[st]; minc = st; } + stc = minc; + dx = 0; + dy = 0; + + ROS_DEBUG("[Path] Pot: %0.1f pos: %0.1f,%0.1f", + potarr[stc], pathx[npath-1], pathy[npath-1]); + + if (potarr[stc] >= POT_HIGH) + { + ROS_DEBUG("[PathCalc] No path found, high potential"); + //savemap("navfn_highpot"); + return 0; + } + } + + // have a good gradient here + else + { + + // get grad at four positions near cell + gradCell(stc); + gradCell(stc+1); + gradCell(stcnx); + gradCell(stcnx+1); + + + // get interpolated gradient + float x1 = (1.0-dx)*gradx[stc] + dx*gradx[stc+1]; + float x2 = (1.0-dx)*gradx[stcnx] + dx*gradx[stcnx+1]; + float x = (1.0-dy)*x1 + dy*x2; // interpolated x + float y1 = (1.0-dx)*grady[stc] + dx*grady[stc+1]; + float y2 = (1.0-dx)*grady[stcnx] + dx*grady[stcnx+1]; + float y = (1.0-dy)*y1 + dy*y2; // interpolated y + + // show gradients + ROS_DEBUG("[Path] %0.2f,%0.2f %0.2f,%0.2f %0.2f,%0.2f %0.2f,%0.2f; final x=%.3f, y=%.3f\n", + gradx[stc], grady[stc], gradx[stc+1], grady[stc+1], + gradx[stcnx], grady[stcnx], gradx[stcnx+1], grady[stcnx+1], + x, y); + + // check for zero gradient, failed + if (x == 0.0 && y == 0.0) + { + ROS_DEBUG("[PathCalc] Zero gradient"); + return 0; + } + + // move in the right direction + float ss = pathStep/hypot(x, y); + dx += x*ss; + dy += y*ss; + + // check for overflow + if (dx > 1.0) { stc++; dx -= 1.0; } + if (dx < -1.0) { stc--; dx += 1.0; } + if (dy > 1.0) { stc+=nx; dy -= 1.0; } + if (dy < -1.0) { stc-=nx; dy += 1.0; } + + } + + // ROS_INFO("[Path] Pot: %0.1f grad: %0.1f,%0.1f pos: %0.1f,%0.1f\n", + // potarr[stc], x, y, pathx[npath-1], pathy[npath-1]); + } + + // return npath; // out of cycles, return failure + ROS_DEBUG("[PathCalc] No path found, path too long"); + //savemap("navfn_pathlong"); + return 0; // out of cycles, return failure + } + + + // + // gradient calculations + // + + // calculate gradient at a cell + // positive value are to the right and down + float + NavFn::gradCell(int n) + { + if (gradx[n]+grady[n] > 0.0) // check this cell + return 1.0; + + if (n < nx || n > ns-nx) // would be out of bounds + return 0.0; + + float cv = potarr[n]; + float dx = 0.0; + float dy = 0.0; + + // check for in an obstacle + if (cv >= POT_HIGH) + { + if (potarr[n-1] < POT_HIGH) + dx = -COST_OBS; + else if (potarr[n+1] < POT_HIGH) + dx = COST_OBS; + + if (potarr[n-nx] < POT_HIGH) + dy = -COST_OBS; + else if (potarr[n+nx] < POT_HIGH) + dy = COST_OBS; + } + + else // not in an obstacle + { + // dx calc, average to sides + if (potarr[n-1] < POT_HIGH) + dx += potarr[n-1]- cv; + if (potarr[n+1] < POT_HIGH) + dx += cv - potarr[n+1]; + + // dy calc, average to sides + if (potarr[n-nx] < POT_HIGH) + dy += potarr[n-nx]- cv; + if (potarr[n+nx] < POT_HIGH) + dy += cv - potarr[n+nx]; + } + + // normalize + float norm = hypot(dx, dy); + if (norm > 0) + { + norm = 1.0/norm; + gradx[n] = norm*dx; + grady[n] = norm*dy; + } + return norm; + } + + + // + // display function setup + // is the number of cycles to wait before displaying, + // use 0 to turn it off + + void + NavFn::display(void fn(NavFn *nav), int n) + { + displayFn = fn; + displayInt = n; + } + + + // + // debug writes + // saves costmap and start/goal + // + + void + NavFn::savemap(const char *fname) + { + char fn[4096]; + + ROS_DEBUG("[NavFn] Saving costmap and start/goal points"); + // write start and goal points + sprintf(fn,"%s.txt",fname); + FILE *fp = fopen(fn,"w"); + if (!fp) + { + ROS_WARN("Can't open file %s", fn); + return; + } + fprintf(fp,"Goal: %d %d\nStart: %d %d\n",goal[0],goal[1],start[0],start[1]); + fclose(fp); + + // write cost array + if (!costarr) return; + sprintf(fn,"%s.pgm",fname); + fp = fopen(fn,"wb"); + if (!fp) + { + ROS_WARN("Can't open file %s", fn); + return; + } + fprintf(fp,"P5\n%d\n%d\n%d\n", nx, ny, 0xff); + fwrite(costarr,1,nx*ny,fp); + fclose(fp); + } +}; diff --git a/navigations/navfn/src/navfn_node.cpp b/navigations/navfn/src/navfn_node.cpp new file mode 100755 index 0000000..4843997 --- /dev/null +++ b/navigations/navfn/src/navfn_node.cpp @@ -0,0 +1,131 @@ +/********************************************************************* +* +* Software License Agreement (BSD License) +* +* Copyright (c) 2008, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of the Willow Garage nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* +* Author: Bhaskara Marthi +*********************************************************************/ +#include +#include +#include +#include +#include + +namespace cm=costmap_2d; +namespace rm=geometry_msgs; + +using std::vector; +using rm::PoseStamped; +using std::string; +using cm::Costmap2D; +using cm::Costmap2DROS; + +namespace navfn { + +class NavfnWithCostmap : public NavfnROS +{ +public: + NavfnWithCostmap(string name, Costmap2DROS* cmap); + bool makePlanService(MakeNavPlan::Request& req, MakeNavPlan::Response& resp); + +private: + void poseCallback(const rm::PoseStamped::ConstPtr& goal); + Costmap2DROS* cmap_; + ros::ServiceServer make_plan_service_; + ros::Subscriber pose_sub_; +}; + + +bool NavfnWithCostmap::makePlanService(MakeNavPlan::Request& req, MakeNavPlan::Response& resp) +{ + vector path; + + req.start.header.frame_id = "map"; + req.goal.header.frame_id = "map"; + bool success = makePlan(req.start, req.goal, path); + resp.plan_found = success; + if (success) { + resp.path = path; + } + + return true; +} + +void NavfnWithCostmap::poseCallback(const rm::PoseStamped::ConstPtr& goal) { + geometry_msgs::PoseStamped global_pose; + cmap_->getRobotPose(global_pose); + vector path; + makePlan(global_pose, *goal, path); +} + + +NavfnWithCostmap::NavfnWithCostmap(string name, Costmap2DROS* cmap) : + NavfnROS(name, cmap) +{ + ros::NodeHandle private_nh("~"); + cmap_ = cmap; + make_plan_service_ = private_nh.advertiseService("make_plan", &NavfnWithCostmap::makePlanService, this); + pose_sub_ = private_nh.subscribe("goal", 1, &NavfnWithCostmap::poseCallback, this); +} + +} // namespace + +int main (int argc, char** argv) +{ + ros::init(argc, argv, "global_planner"); + + tf2_ros::Buffer buffer(ros::Duration(10)); + tf2_ros::TransformListener tf(buffer); + + costmap_2d::Costmap2DROS lcr("costmap", buffer); + + navfn::NavfnWithCostmap navfn("navfn_planner", &lcr); + + ros::spin(); + return 0; +} + + + + + + + + + + + + + + + + diff --git a/navigations/navfn/src/navfn_ros.cpp b/navigations/navfn/src/navfn_ros.cpp new file mode 100755 index 0000000..2a4cbbb --- /dev/null +++ b/navigations/navfn/src/navfn_ros.cpp @@ -0,0 +1,432 @@ +/********************************************************************* +* +* Software License Agreement (BSD License) +* +* Copyright (c) 2008, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of the Willow Garage nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* +* Author: Eitan Marder-Eppstein +*********************************************************************/ +#include +#include +#include +#include +#include + +//register this planner as a BaseGlobalPlanner plugin +PLUGINLIB_EXPORT_CLASS(navfn::NavfnROS, nav_core::BaseGlobalPlanner) + +namespace navfn { + + NavfnROS::NavfnROS() + : costmap_(NULL), planner_(), initialized_(false), allow_unknown_(true) {} + + NavfnROS::NavfnROS(std::string name, costmap_2d::Costmap2DROS* costmap_ros) + : costmap_(NULL), planner_(), initialized_(false), allow_unknown_(true) { + //initialize the planner + initialize(name, costmap_ros); + } + + NavfnROS::NavfnROS(std::string name, costmap_2d::Costmap2D* costmap, std::string global_frame) + : costmap_(NULL), planner_(), initialized_(false), allow_unknown_(true) { + //initialize the planner + initialize(name, costmap, global_frame); + } + + void NavfnROS::initialize(std::string name, costmap_2d::Costmap2D* costmap, std::string global_frame){ + if(!initialized_){ + costmap_ = costmap; + global_frame_ = global_frame; + planner_ = boost::shared_ptr(new NavFn(costmap_->getSizeInCellsX(), costmap_->getSizeInCellsY())); + + ros::NodeHandle private_nh("~/" + name); + + plan_pub_ = private_nh.advertise("plan", 1); + + private_nh.param("visualize_potential", visualize_potential_, false); + + //if we're going to visualize the potential array we need to advertise + if(visualize_potential_) + potarr_pub_ = private_nh.advertise("potential", 1); + + private_nh.param("allow_unknown", allow_unknown_, true); + private_nh.param("planner_window_x", planner_window_x_, 0.0); + private_nh.param("planner_window_y", planner_window_y_, 0.0); + private_nh.param("default_tolerance", default_tolerance_, 0.0); + + make_plan_srv_ = private_nh.advertiseService("make_plan", &NavfnROS::makePlanService, this); + + initialized_ = true; + } + else + ROS_WARN("This planner has already been initialized, you can't call it twice, doing nothing"); + } + + void NavfnROS::initialize(std::string name, costmap_2d::Costmap2DROS* costmap_ros){ + initialize(name, costmap_ros->getCostmap(), costmap_ros->getGlobalFrameID()); + } + + bool NavfnROS::validPointPotential(const geometry_msgs::Point& world_point){ + return validPointPotential(world_point, default_tolerance_); + } + + bool NavfnROS::validPointPotential(const geometry_msgs::Point& world_point, double tolerance){ + if(!initialized_){ + ROS_ERROR("This planner has not been initialized yet, but it is being used, please call initialize() before use"); + return false; + } + + double resolution = costmap_->getResolution(); + geometry_msgs::Point p; + p = world_point; + + p.y = world_point.y - tolerance; + + while(p.y <= world_point.y + tolerance){ + p.x = world_point.x - tolerance; + while(p.x <= world_point.x + tolerance){ + double potential = getPointPotential(p); + if(potential < POT_HIGH){ + return true; + } + p.x += resolution; + } + p.y += resolution; + } + + return false; + } + + double NavfnROS::getPointPotential(const geometry_msgs::Point& world_point){ + if(!initialized_){ + ROS_ERROR("This planner has not been initialized yet, but it is being used, please call initialize() before use"); + return -1.0; + } + + unsigned int mx, my; + if(!costmap_->worldToMap(world_point.x, world_point.y, mx, my)) + return DBL_MAX; + + unsigned int index = my * planner_->nx + mx; + return planner_->potarr[index]; + } + + bool NavfnROS::computePotential(const geometry_msgs::Point& world_point){ + if(!initialized_){ + ROS_ERROR("This planner has not been initialized yet, but it is being used, please call initialize() before use"); + return false; + } + + //make sure to resize the underlying array that Navfn uses + planner_->setNavArr(costmap_->getSizeInCellsX(), costmap_->getSizeInCellsY()); + planner_->setCostmap(costmap_->getCharMap(), true, allow_unknown_); + + unsigned int mx, my; + if(!costmap_->worldToMap(world_point.x, world_point.y, mx, my)) + return false; + + int map_start[2]; + map_start[0] = 0; + map_start[1] = 0; + + int map_goal[2]; + map_goal[0] = mx; + map_goal[1] = my; + + planner_->setStart(map_start); + planner_->setGoal(map_goal); + + return planner_->calcNavFnDijkstra(); + } + + void NavfnROS::clearRobotCell(const geometry_msgs::PoseStamped& global_pose, unsigned int mx, unsigned int my){ + if(!initialized_){ + ROS_ERROR("This planner has not been initialized yet, but it is being used, please call initialize() before use"); + return; + } + + //set the associated costs in the cost map to be free + costmap_->setCost(mx, my, costmap_2d::FREE_SPACE); + } + + bool NavfnROS::makePlanService(nav_msgs::GetPlan::Request& req, nav_msgs::GetPlan::Response& resp){ + makePlan(req.start, req.goal, resp.plan.poses); + + resp.plan.header.stamp = ros::Time::now(); + resp.plan.header.frame_id = global_frame_; + + return true; + } + + void NavfnROS::mapToWorld(double mx, double my, double& wx, double& wy) { + wx = costmap_->getOriginX() + mx * costmap_->getResolution(); + wy = costmap_->getOriginY() + my * costmap_->getResolution(); + } + + bool NavfnROS::makePlan(const geometry_msgs::PoseStamped& start, + const geometry_msgs::PoseStamped& goal, std::vector& plan){ + return makePlan(start, goal, default_tolerance_, plan); + } + + bool NavfnROS::makePlan(const geometry_msgs::PoseStamped& start, + const geometry_msgs::PoseStamped& goal, double tolerance, std::vector& plan){ + boost::mutex::scoped_lock lock(mutex_); + if(!initialized_){ + ROS_ERROR("This planner has not been initialized yet, but it is being used, please call initialize() before use"); + return false; + } + + //clear the plan, just in case + plan.clear(); + + ros::NodeHandle n; + + //until tf can handle transforming things that are way in the past... we'll require the goal to be in our global frame + if(goal.header.frame_id != global_frame_){ + ROS_ERROR("The goal pose passed to this planner must be in the %s frame. It is instead in the %s frame.", + global_frame_.c_str(), goal.header.frame_id.c_str()); + return false; + } + + if(start.header.frame_id != global_frame_){ + ROS_ERROR("The start pose passed to this planner must be in the %s frame. It is instead in the %s frame.", + global_frame_.c_str(), start.header.frame_id.c_str()); + return false; + } + + double wx = start.pose.position.x; + double wy = start.pose.position.y; + + unsigned int mx, my; + if(!costmap_->worldToMap(wx, wy, mx, my)){ + ROS_WARN_THROTTLE(1.0, "The robot's start position is off the global costmap. Planning will always fail, are you sure the robot has been properly localized?"); + return false; + } + + //clear the starting cell within the costmap because we know it can't be an obstacle + clearRobotCell(start, mx, my); + + //make sure to resize the underlying array that Navfn uses + planner_->setNavArr(costmap_->getSizeInCellsX(), costmap_->getSizeInCellsY()); + planner_->setCostmap(costmap_->getCharMap(), true, allow_unknown_); + + int map_start[2]; + map_start[0] = mx; + map_start[1] = my; + + wx = goal.pose.position.x; + wy = goal.pose.position.y; + + if(!costmap_->worldToMap(wx, wy, mx, my)){ + if(tolerance <= 0.0){ + ROS_WARN_THROTTLE(1.0, "The goal sent to the navfn planner is off the global costmap. Planning will always fail to this goal."); + return false; + } + mx = 0; + my = 0; + } + + int map_goal[2]; + map_goal[0] = mx; + map_goal[1] = my; + + planner_->setStart(map_goal); + planner_->setGoal(map_start); + + //bool success = planner_->calcNavFnAstar(); + planner_->calcNavFnDijkstra(true); + + double resolution = costmap_->getResolution(); + geometry_msgs::PoseStamped p, best_pose; + p = goal; + + bool found_legal = false; + double best_sdist = DBL_MAX; + + p.pose.position.y = goal.pose.position.y - tolerance; + + while(p.pose.position.y <= goal.pose.position.y + tolerance){ + p.pose.position.x = goal.pose.position.x - tolerance; + while(p.pose.position.x <= goal.pose.position.x + tolerance){ + double potential = getPointPotential(p.pose.position); + double sdist = sq_distance(p, goal); + if(potential < POT_HIGH && sdist < best_sdist){ + best_sdist = sdist; + best_pose = p; + found_legal = true; + } + p.pose.position.x += resolution; + } + p.pose.position.y += resolution; + } + + if(found_legal){ + //extract the plan + if(getPlanFromPotential(best_pose, plan)){ + //make sure the goal we push on has the same timestamp as the rest of the plan + geometry_msgs::PoseStamped goal_copy = best_pose; + goal_copy.header.stamp = ros::Time::now(); + plan.push_back(goal_copy); + } + else{ + ROS_ERROR("Failed to get a plan from potential when a legal potential was found. This shouldn't happen."); + } + } + + if (visualize_potential_) + { + // Publish the potentials as a PointCloud2 + sensor_msgs::PointCloud2 cloud; + cloud.width = 0; + cloud.height = 0; + cloud.header.stamp = ros::Time::now(); + cloud.header.frame_id = global_frame_; + sensor_msgs::PointCloud2Modifier cloud_mod(cloud); + cloud_mod.setPointCloud2Fields(4, "x", 1, sensor_msgs::PointField::FLOAT32, + "y", 1, sensor_msgs::PointField::FLOAT32, + "z", 1, sensor_msgs::PointField::FLOAT32, + "pot", 1, sensor_msgs::PointField::FLOAT32); + cloud_mod.resize(planner_->ny * planner_->nx); + sensor_msgs::PointCloud2Iterator iter_x(cloud, "x"); + + PotarrPoint pt; + float *pp = planner_->potarr; + double pot_x, pot_y; + for (unsigned int i = 0; i < (unsigned int)planner_->ny*planner_->nx ; i++) + { + if (pp[i] < 10e7) + { + mapToWorld(i%planner_->nx, i/planner_->nx, pot_x, pot_y); + iter_x[0] = pot_x; + iter_x[1] = pot_y; + iter_x[2] = pp[i]/pp[planner_->start[1]*planner_->nx + planner_->start[0]]*20; + iter_x[3] = pp[i]; + ++iter_x; + } + } + potarr_pub_.publish(cloud); + } + + //publish the plan for visualization purposes + publishPlan(plan, 0.0, 1.0, 0.0, 0.0); + + return !plan.empty(); + } + + void NavfnROS::publishPlan(const std::vector& path, double r, double g, double b, double a){ + if(!initialized_){ + ROS_ERROR("This planner has not been initialized yet, but it is being used, please call initialize() before use"); + return; + } + + //create a message for the plan + nav_msgs::Path gui_path; + gui_path.poses.resize(path.size()); + + if(path.empty()) { + //still set a valid frame so visualization won't hit transform issues + gui_path.header.frame_id = global_frame_; + gui_path.header.stamp = ros::Time::now(); + } else { + gui_path.header.frame_id = path[0].header.frame_id; + gui_path.header.stamp = path[0].header.stamp; + } + + // Extract the plan in world co-ordinates, we assume the path is all in the same frame + for(unsigned int i=0; i < path.size(); i++){ + gui_path.poses[i] = path[i]; + } + + plan_pub_.publish(gui_path); + } + + bool NavfnROS::getPlanFromPotential(const geometry_msgs::PoseStamped& goal, std::vector& plan){ + if(!initialized_){ + ROS_ERROR("This planner has not been initialized yet, but it is being used, please call initialize() before use"); + return false; + } + + //clear the plan, just in case + plan.clear(); + + //until tf can handle transforming things that are way in the past... we'll require the goal to be in our global frame + if(goal.header.frame_id != global_frame_){ + ROS_ERROR("The goal pose passed to this planner must be in the %s frame. It is instead in the %s frame.", + global_frame_.c_str(), goal.header.frame_id.c_str()); + return false; + } + + double wx = goal.pose.position.x; + double wy = goal.pose.position.y; + + //the potential has already been computed, so we won't update our copy of the costmap + unsigned int mx, my; + if(!costmap_->worldToMap(wx, wy, mx, my)){ + ROS_WARN_THROTTLE(1.0, "The goal sent to the navfn planner is off the global costmap. Planning will always fail to this goal."); + return false; + } + + int map_goal[2]; + map_goal[0] = mx; + map_goal[1] = my; + + planner_->setStart(map_goal); + + planner_->calcPath(costmap_->getSizeInCellsX() * 4); + + //extract the plan + float *x = planner_->getPathX(); + float *y = planner_->getPathY(); + int len = planner_->getPathLen(); + ros::Time plan_time = ros::Time::now(); + + for(int i = len - 1; i >= 0; --i){ + //convert the plan to world coordinates + double world_x, world_y; + mapToWorld(x[i], y[i], world_x, world_y); + + geometry_msgs::PoseStamped pose; + pose.header.stamp = plan_time; + pose.header.frame_id = global_frame_; + pose.pose.position.x = world_x; + pose.pose.position.y = world_y; + pose.pose.position.z = 0.0; + pose.pose.orientation.x = 0.0; + pose.pose.orientation.y = 0.0; + pose.pose.orientation.z = 0.0; + pose.pose.orientation.w = 1.0; + plan.push_back(pose); + } + + //publish the plan for visualization purposes + publishPlan(plan, 0.0, 1.0, 0.0, 0.0); + return !plan.empty(); + } +}; diff --git a/navigations/navfn/src/navtest/navtest.cpp b/navigations/navfn/src/navtest/navtest.cpp new file mode 100755 index 0000000..266d23d --- /dev/null +++ b/navigations/navfn/src/navtest/navtest.cpp @@ -0,0 +1,309 @@ +// +// simple timing test of the nav fn planner +// expects a cost map in maps/willow-full-0.05.pgm +// + +#include +#ifdef HAVE_SYS_TIME_H +#include +#endif +#include +#include +#include + +#include +#include + +#include "navwin.h" + +using namespace navfn; + +#ifdef __APPLE__ +# include +#else +extern "C" { +#include +// pgm.h is not very friendly with system headers... need to undef max() and min() afterwards +#include +#undef max +#undef min +} +#endif + +int goal[2]; +int start[2]; + +double get_ms() +{ + struct timeval t0; + gettimeofday(&t0,NULL); + double ret = t0.tv_sec * 1000.0; + ret += ((double)t0.tv_usec)*0.001; + return ret; +} + +NavWin *nwin; + +void +dispPot(NavFn *nav) +{ + nwin->drawPot(nav); + Fl::check(); +} + + +// is true for ROS-generated raw cost maps +COSTTYPE *readPGM(const char *fname, int *width, int *height, bool raw = false); + +int main(int argc, char **argv) +{ + int dispn = 0; + + int res = 50; // 50 mm resolution + double size = 40.0; // 40 m on a side + int inc = 2*COST_NEUTRAL; // thin wavefront + bool got_start_goal = false; + std::string pgm_file_name; + + start[0] = 420; + start[1] = 420; + + goal[0] = 580; + goal[1] = 400; + + if (argc > 1) + { + pgm_file_name = std::string( argv[ 1 ]) + ".pgm"; + std::string txt_file_name = std::string( argv[ 1 ]) + ".txt"; + + std::ifstream txt_stream( txt_file_name.c_str() ); + if( txt_stream ) + { + std::string name; + int x, y; + for( int i = 0; i < 2; i++ ) + { + txt_stream >> name >> x >> y; + if( txt_stream && name == "Goal:" ) + { + goal[0] = x; + goal[1] = y; + } + else if( txt_stream && name == "Start:" ) + { + start[0] = x; + start[1] = y; + } + } + got_start_goal = true; + printf( "start is %d, %d, goal is %d, %d.\n", start[ 0 ], start[ 1 ], goal[ 0 ], goal[ 1 ]); + } + else + { + printf( "Failed to open file %s, assuming you didn't want to open a file.\n", txt_file_name.c_str() ); + } + } + + // get resolution (mm) and perhaps size (m) + if( !got_start_goal ) + { + if (argc > 1) + res = atoi(argv[1]); + + if (argc > 2) + size = atoi(argv[2]); + + if (argc > 3) + inc = atoi(argv[3]); + + if (argc > 4) + dispn = atoi(argv[4]); + } + NavFn *nav; + + // try reading in a file + int sx,sy; + COSTTYPE *cmap = NULL; + cmap = readPGM( pgm_file_name.c_str(),&sx,&sy,true); + if (cmap) + { + nav = new NavFn(sx,sy); + + + } + else + { + sx = (int)((.001 + size) / (res*.001)); + sy = sx; + nav = new NavFn(sx,sy); // size in pixels + goal[0] = sx-10; + goal[1] = sy/2; + start[0] = 20; + start[1] = sy/2; + } + + // display + nwin = new NavWin(sx,sy,"Potential Field"); + nwin->maxval = 2*sx*COST_NEUTRAL; + Fl::visual(FL_RGB); + nwin->show(); + + + // set goal and robot poses + int *gg = goal; + nav->setGoal(gg); + int *ss = start; + nav->setStart(ss); + + // set display function + nav->display(dispPot,dispn); + + + nav->priInc = inc; + printf("[NavTest] priority increment: %d\n", inc); + + double t0 = get_ms(); + // set up cost map from file, if it exists + if (cmap) + { + // nav->setCostMap(cmap); + memcpy(nav->costarr,cmap,sx*sy); + nav->setupNavFn(true); + } + else + { + nav->setupNavFn(false); + } + double t1 = get_ms(); + // nav->calcNavFnAstar(); + nav->calcNavFnDijkstra(true); + double t2 = get_ms(); + printf("Setup: %d ms Plan: %d ms Total: %d ms\n", + (int)(t1-t0), (int)(t2-t1), (int)(t2-t0)); + + // draw potential field + float mmax = 0.0; + float *pp = nav->potarr; + int ntot = 0; + for (int i=0; iny*nav->nx; i++, pp++) + { + if (*pp < 10e7 && *pp > mmax) + mmax = *pp; + if (*pp > 10e7) + ntot++; // number of uncalculated cells + } + printf("[NavFn] Cells not touched: %d/%d\n", ntot, nav->nx*nav->ny); + nwin->maxval = 4*mmax/3/15; + dispPot(nav); + while (Fl::check()) { + if( Fl::event_key( 'q' )) + { + break; + } + } + + return 0; +} + + +// read in a PGM file for obstacles +// no expansion yet... + +static int CS; + +void +setcostobs(COSTTYPE *cmap, int n, int w) +{ + CS = 11; + for (int i=-CS/2; i= 0; --jj) + { + int v = row[jj]; + cmap[ii*ncols+jj] = v; + if (v >= COST_OBS_ROS) + otot++; + if (v == 0) + ftot++; + } + } + else + { + ftot = ncols*nrows; + for (int jj(ncols - 1); jj >= 0; --jj) + { + if (row[jj] < unknown_gray && ii < nrows-7 && ii > 7) + { + setcostobs(cmap,ii*ncols+jj,ncols); + otot++; + ftot--; + } + else if (row[jj] <= unknown_gray) + { + setcostunk(cmap,ii*ncols+jj,ncols); + utot++; + ftot--; + } + } + } + } + printf("[NavTest] Found %d obstacle cells, %d free cells, %d unknown cells\n", otot, ftot, utot); + pgm_freerow(row); + *width = ncols; + *height = nrows; + return cmap; +} diff --git a/navigations/navfn/src/navtest/navwin.cpp b/navigations/navfn/src/navtest/navwin.cpp new file mode 100755 index 0000000..a6c49eb --- /dev/null +++ b/navigations/navfn/src/navtest/navwin.cpp @@ -0,0 +1,292 @@ +// +// simple timing test of the nav fn planner +// + +#include +#include "navwin.h" + +namespace navfn { +NavWin::NavWin(int w, int h, const char *name) + : Fl_Double_Window(w,h,name) +{ + nw = w; + nh = h; + dec = 1; + maxval = 90*1000; + im = NULL; + pw = w; + ph = h; + pce = pne = poe = 0; + pc = pn = po = NULL; + pathlen = pathbuflen = 0; + path = NULL; +} + +NavWin::~NavWin() +{ +} + +void +NavWin::drawPot(NavFn *nav) +{ + float *pot = nav->potarr; + COSTTYPE *cst = nav->costarr; + int width = nav->nx; + int height = nav->ny; + + // params + pw = width; + ph = height; + + // figure out decimation or expansion to fit + dec = 1; + inc = 1; + + if (width >= nw/2) + { + int ww = width; + while (ww > nw) + { + dec++; + ww = width/dec; + } + + int hh = height/dec; + while (hh > nh) + { + dec++; + hh = height/dec; + } + + if (im == NULL) + im = new uchar[nw*nh*3]; + + + // draw potential + for (int i=0; i= COST_OBS) + { + *ii = 120; + *(ii+1) = 60; + *(ii+2) = 60; + } + } + } + + } + + else // expand + { + int ww = width; + while (ww < nw/2) + { + inc++; + ww = width*inc; + } + + int hh = height*inc; + while (hh < nh/2) + { + inc++; + hh = height*inc; + } + + if (im == NULL) + im = new uchar[nw*nh*3]; + + for (int i=0; i maxval) + v = 255; + else + v = (int)((*pp/maxval) * 255.0); + for (int k=0; kcurPe; + pc = new int[pce]; + memcpy(pc, nav->curP, pce*sizeof(int)); + + if (pn) + delete [] pn; + pne = nav->nextPe; + pn = new int[pne]; + memcpy(pn, nav->nextP, pne*sizeof(int)); + + if (po) + delete [] po; + poe = nav->overPe; + po = new int[poe]; + memcpy(po, nav->overP, poe*sizeof(int)); + + // start and goal + goal[0] = nav->goal[0]; + goal[1] = nav->goal[1]; + start[0] = nav->start[0]; + start[1] = nav->start[1]; + + // path + if (nav->npath > 0) + { + pathlen = nav->npath; + if (pathbuflen < pathlen) + { + pathbuflen = pathlen; + if (path) delete [] path; + path = new int[pathbuflen]; + } + for (int i=0; ipathy[i])+(int)(nav->pathx[i]); + } + + drawOverlay(); + + redraw(); +} + + +void +NavWin::drawOverlay() +{ + if (inc == 1) // decimation + { + fl_color(255,0,0); + if (pce > 0) + for (int i=0; i 0) + for (int i=0; i 0) + for (int i=0; i 0) + for (int i=0; i 0) + for (int i=0; i 0) + for (int i=0; i 0) // decimation or equal pixels + { + int y = path[0]/pw; + int x = path[0]%pw; + for (int i=1; i +#include +#include + +#include +#include +#include +#include +#include + +#include + +namespace navfn { + class NavWin + : public Fl_Double_Window + { + public: + NavWin(int w, int h, const char *name); + ~NavWin(); + + int nw,nh; // width and height of image + int pw,ph; // width and height of pot field + int dec, inc; // decimation or expansion for display + + float maxval; // max potential value + void drawPot(NavFn *nav); // draw everything... + + void drawOverlay(); + + uchar *im; // image for drawing + int *pc, *pn, *po; // priority buffers + int pce, pne, poe; // buffer sizes + int goal[2]; + int start[2]; + int *path; // path buffer, cell indices + int pathlen; // how many we have + int pathbuflen; // how big the path buffer is + + void draw(); // draw the image + }; +}; diff --git a/navigations/navfn/src/read_pgm_costmap.cpp b/navigations/navfn/src/read_pgm_costmap.cpp new file mode 100755 index 0000000..27f861a --- /dev/null +++ b/navigations/navfn/src/read_pgm_costmap.cpp @@ -0,0 +1,141 @@ +/* + * Copyright (c) 2012, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include +#include + +#ifdef __APPLE__ +# include +#else +extern "C" { +#include +// pgm.h is not very friendly with system headers... need to undef max() and min() afterwards +#include +#undef max +#undef min +} +#endif + +void +setcostobs(COSTTYPE *cmap, int n, int w) +{ + int CS = 11; + for (int i=-CS/2; i= 0; --jj) + { + int v = row[jj]; + cmap[ii*ncols+jj] = v; + if (v >= COST_OBS_ROS) + otot++; + if (v == 0) + ftot++; + } + } + else + { + ftot = ncols*nrows; + for (int jj(ncols - 1); jj >= 0; --jj) + { + if (row[jj] < unknown_gray && ii < nrows-7 && ii > 7) + { + setcostobs(cmap,ii*ncols+jj,ncols); + otot++; + ftot--; + } + else if (row[jj] <= unknown_gray) + { + setcostunk(cmap,ii*ncols+jj,ncols); + utot++; + ftot--; + } + } + } + } + printf("readPGM() Found %d obstacle cells, %d free cells, %d unknown cells\n", otot, ftot, utot); + pgm_freerow(row); + *width = ncols; + *height = nrows; + return cmap; +} diff --git a/navigations/navfn/srv/MakeNavPlan.srv b/navigations/navfn/srv/MakeNavPlan.srv new file mode 100755 index 0000000..244600b --- /dev/null +++ b/navigations/navfn/srv/MakeNavPlan.srv @@ -0,0 +1,9 @@ +geometry_msgs/PoseStamped start +geometry_msgs/PoseStamped goal +--- + +uint8 plan_found +string error_message + +# if plan_found is true, this is an array of waypoints from start to goal, where the first one equals start and the last one equals goal +geometry_msgs/PoseStamped[] path diff --git a/navigations/navfn/srv/SetCostmap.srv b/navigations/navfn/srv/SetCostmap.srv new file mode 100755 index 0000000..27299b8 --- /dev/null +++ b/navigations/navfn/srv/SetCostmap.srv @@ -0,0 +1,4 @@ +uint8[] costs +uint16 height +uint16 width +--- \ No newline at end of file diff --git a/navigations/navfn/test/CMakeLists.txt b/navigations/navfn/test/CMakeLists.txt new file mode 100755 index 0000000..1bc039f --- /dev/null +++ b/navigations/navfn/test/CMakeLists.txt @@ -0,0 +1,2 @@ +catkin_add_gtest(path_calc_test path_calc_test.cpp ../src/read_pgm_costmap.cpp) +target_link_libraries(path_calc_test navfn netpbm) diff --git a/navigations/navfn/test/path_calc_test.cpp b/navigations/navfn/test/path_calc_test.cpp new file mode 100755 index 0000000..067ff02 --- /dev/null +++ b/navigations/navfn/test/path_calc_test.cpp @@ -0,0 +1,160 @@ +/* + * Copyright (c) 2012, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include +#include +#include +#include + +// Load a willow garage costmap and return a NavFn instance using it. +// If the costmap file fails to load, returns NULL. +navfn::NavFn* make_willow_nav() +{ + int sx,sy; + std::string path = ros::package::getPath( ROS_PACKAGE_NAME ) + "/test/willow_costmap.pgm"; + + COSTTYPE *cmap = readPGM( path.c_str(), &sx, &sy, true ); + if( cmap == NULL ) + { + return NULL; + } + navfn::NavFn* nav = new navfn::NavFn(sx,sy); + + nav->priInc = 2*COST_NEUTRAL; // thin wavefront + + memcpy( nav->costarr, cmap, sx*sy ); + + return nav; +} + +void print_neighborhood_of_last_path_entry( navfn::NavFn* nav ) +{ + printf("last path entries:\n"); + for( int i = nav->npath - 4; i < nav->npath; i++ ) + { + printf("%.3f, %.3f\n", nav->pathx[ i ], nav->pathy[ i ]); + } + printf("potential field neighborhood of last entry:\n"); + int xf = nav->pathx[ nav->npath-1 ]; + int yf = nav->pathy[ nav->npath-1 ]; + + printf( " " ); + for( int x = xf - 2; x <= xf + 2; x++ ) + { + printf( " %6d", x ); + } + printf( "\n" ); + + for( int y = yf - 2; y <= yf + 2; y++ ) + { + printf( "%5d:", y ); + for( int x = xf - 2; x <= xf + 2; x++ ) + { + printf( " %5.1f", nav->potarr[ y * nav->nx + x ] ); + } + printf( "\n" ); + } + + printf("gradient neighborhood of last entry:\n"); + printf( " " ); + for( int x = xf - 2; x <= xf + 2; x++ ) + { + printf( " %6d", x ); + } + printf( "\n" ); + + for( int y = yf - 2; y <= yf + 2; y++ ) + { + printf( "%5d x:", y ); + for( int x = xf - 2; x <= xf + 2; x++ ) + { + printf( " %5.1f", nav->gradx[ y * nav->nx + x ] ); + } + printf( "\n" ); + + printf( " y:" ); + for( int x = xf - 2; x <= xf + 2; x++ ) + { + printf( " %5.1f", nav->grady[ y * nav->nx + x ] ); + } + printf( "\n" ); + } +} + +TEST(PathCalc, oscillate_in_pinch_point) +{ + navfn::NavFn* nav = make_willow_nav(); + ASSERT_TRUE( nav != NULL ); + + int goal[2]; + int start[2]; + + start[0] = 428; + start[1] = 746; + + goal[0] = 350; + goal[1] = 450; + + nav->setGoal( goal ); + nav->setStart( start ); + + bool plan_success = nav->calcNavFnDijkstra( true ); + EXPECT_TRUE( plan_success ); + if( !plan_success ) + { + print_neighborhood_of_last_path_entry( nav ); + } +} + +TEST(PathCalc, easy_nav_should_always_work) +{ + navfn::NavFn* nav = make_willow_nav(); + ASSERT_TRUE( nav != NULL ); + + int goal[2]; + int start[2]; + + start[0] = 350; + start[1] = 400; + + goal[0] = 350; + goal[1] = 450; + + nav->setGoal( goal ); + nav->setStart( start ); + + EXPECT_TRUE( nav->calcNavFnDijkstra( true )); +} + +int main(int argc, char **argv) +{ + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/navigations/navfn/test/willow_costmap.pgm b/navigations/navfn/test/willow_costmap.pgm new file mode 100755 index 0000000..9be6775 --- /dev/null +++ b/navigations/navfn/test/willow_costmap.pgm @@ -0,0 +1,5 @@ +P5 +1132 +1217 +255 +22222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222222 \ No newline at end of file diff --git a/navigations/pluginlib/CHANGELOG.rst b/navigations/pluginlib/CHANGELOG.rst new file mode 100755 index 0000000..bad160d --- /dev/null +++ b/navigations/pluginlib/CHANGELOG.rst @@ -0,0 +1,325 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package pluginlib +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +1.13.0 (2020-05-21) +------------------- +* Declare specific boost dependencies (`#171 `_) +* Contributors: Mikael Arguedas + +1.12.2 (2020-02-14) +------------------- +* Add bin to library search path on Windows. (`#145 `_) +* Bump minimum CMake version to avoid CMP0048 warning. (`#173 `_) +* Check for NULL in XMLElement::Attribute. (`#163 `_) +* Check for NULL in XMLElement::GetText. (`#159 `_) +* Check for NULL in XMLNode::Value. (`#158 `_) +* Update header migration script for Python 3. (`#148 `_) +* Make Steven! Ragnarok the maintainer. (`#129 `_) +* Fix spelling Attirbute=>Attribute. (`#128 `_) +* Link test_plugins against class_loader for Windows compilation. (`#125 `_) +* Fix build issue when build on Windows (`#123 `_) +* Contributors: James Xu, Jeremie Deray, Johnson Shih, Markus Grimm, Mikael Arguedas, Shane Loretz, josch + +1.12.1 (2018-04-27) +------------------- +* [warning fix] remove deprecation warning until users are required to change code (`#115 `_) +* [warning fix] move catkinFindLib implementation from anonymous namespace to getCatkinLibraryPaths (`#113 `_) +* Contributors: Mikael Arguedas + +1.12.0 (2018-03-14) +------------------- +* [warning fix]Cherry-pick `#103 `_ to melodic-devel (`#105 `_) +* [migration helper] provide a script to convert include statements to use new headers (`#104 `_) +* [migration] use new class_loader headers and fix deprecation warnings (`#101 `_) +* [bugfix] Continue loading classes on error (`#85 `_) (`#88 `_) +* [style] Fix cpplint and lint_cmake errors (`#84 `_) +* move pluginlib in its own folder (`#83 `_) +* Contributors: Mikael Arguedas + +1.11.0 (2017-07-27) +------------------- +* Switch to Tinyxml2 (`#59 `_) +* do not use popen to solve catkin_path. (`#49 `_) +* switch to package format 2 (`#55 `_) +* remove trailing whitespaces (`#54 `_) +* Contributors: Dmitry Rozhkov, Koji Terada, Mikael Arguedas + +1.10.5 (2017-03-27) +------------------- +* Merge pull request `#47 `_ from ros/fix_conversion + fix size_t to int conversion +* fix int conversion +* Contributors: Mikael Arguedas + +1.10.4 (2016-09-20) +------------------- +* Merge pull request `#42 `_ from delftrobotics-forks/unique-ptr + Add std::unique_ptr API +* Add unit test for unique_ptr API. +* Simplify unit tests with ASSERT_THROW. +* Add ClassLoader::createUniqueInstance. +* Wrap long comment on createInstance and friend. +* Throw exception if plugin.xml is broken (`#41 `_) + * added test case for broken xml files with missing attributes of class tag + * added checks if all needed attributes of the class tag are existing + * removed comment and empty line +* Contributors: Maarten de Vries, Mikael Arguedas, cwecht + +1.10.3 (2016-06-22) +------------------- +* Merge pull request `#40 `_ from ros/fix_warnings + fix deprecated warnings in unit tests +* fix deprecated warnings in unit tests +* removed merge messages and redundant commits +* Contributors: Mikael Arguedas + +1.10.2 (2016-03-14) +------------------- +* Remove Boost Software License from license tag `#35 `_ +* Throw an exception if ClassLoader can't be instantiated due to an invalid package name `#34 `_ +* Add ":" to split function within getName. `#33 `_ +* Contributors: Esteve Fernandez, Jochen Sprickerhof, Mikael Arguedas, Mike O'Driscoll + +1.10.1 (2014-12-23) +------------------- +* Remove GTEST_FOUND from CMakeLists.txt +* Check that GTest is installed before running tests. +* Moved plugin_macro_update script to scripts directory. Made plugin_macro_update rosrunnable and removed it from global PATH `#29 `_ +* Contributors: Esteve Fernandez + +1.10.0 (2014-05-08 14:56) +------------------------- + +1.9.25 (2014-05-08 20:37) +------------------------- +* Use cmake_modules to find TinyXML `#26 `_ +* Check for release libraries in debug builds `#25 `_ +* update refreshDeclaredClasses to force recrawl (fix `#23 `_) +* Contributors: Dirk Thomas, Esteve Fernandez + +1.9.24 (2014-03-11) +------------------- +* Remove invalid exception when no plugins are found `#22 `_ +* Update maintainer field +* Contributors: Dirk Thomas, Esteve Fernandez + +1.9.23 (2013-10-04) +------------------- +* expose plugin paths in ClassLoader `#21 `_ +* Contributors: Dirk Thomas, Mirza Shah + +1.9.22 (2013-08-21) +------------------- +* Fixed use of __FILE_\_ macro in deprecation warning +* Added libdl to plugin_tool link args...temporary fix +* Contributors: Mirza Shah + +1.9.21 (2013-07-14) +------------------- +* Added file hint for deprecated warnings. `#16 `_ +* check for CATKIN_ENABLE_TESTING +* remove mainpage.dox +* Contributors: Dane Powell, Dirk Thomas, Mirza Shah + +1.9.20 (2013-04-18) +------------------- +* Added another unit test for managed instance case. +* Fixed a regression that broke unload call. Added a unit test for this case. +* Contributors: Mirza Shah + +1.9.19 (2013-03-23) +------------------- +* Converted ROS_DEBUG and ROS_WARN calls to ROS_DEBUG_NAMED and ROS_WARN_NAMED calls `#13 `_ +* Contributors: Dave Coleman, Mirza Shah + +1.9.18 (2013-01-28) +------------------- +* Support for boost filesystem v2 `#11 `_ +* Added more debug information +* Contributors: Mario Prats, Mirza Shah + +1.9.17 (2012-12-27) +------------------- +* More useful debug messages +* Fixed incorrect debug message in plugin description XML parsing +* Contributors: Mirza Shah + +1.9.16 (2012-12-21) +------------------- +* Removed old file +* Annotated deprecation warning with more info +* Made python script global installable +* Added a script to recursively update deprecated pluginlib macro +* added missing license header +* modified dep type of catkin +* Contributors: Aaron Blasdel, Dirk Thomas, Mirza Shah + +1.9.15 (2012-12-13 17:22) +------------------------- +* Updated registration macros to be easier and deprecated older ones. Also cleaned up code violating standard +* Added wg copyright notice +* Contributors: Mirza Shah + +1.9.14 (2012-12-13 15:20) +------------------------- +* lookup name (i.e. magic name) is now optional. Further cleanup...alphabetized methods, broke up some. +* Contributors: Mirza Shah + +1.9.13 (2012-12-11) +------------------- +* Made robust to plugin package having different name from the folder it came from. ```#6 `_ +* Contributors: Mirza Shah + +1.9.2 (2012-10-25) +------------------ +* fixed deps for downstream packages +* Contributors: Dirk Thomas + +1.9.1 (2012-10-24 22:02) +------------------------ +* fix missing and redundant deps for downstream projects +* Contributors: Dirk Thomas + +1.9.0 (2012-10-24 18:31) +------------------------ +* renamed test target +* remove obsolete files +* Fixed dependency in package.xml and minor touchups +* Broke up code into further files +* Catkinized pluginlib and completed integration more or less with class_loader. Heavy mods to pluginlib::ClassLoader to handle constraints of Catkin as well as delegate housekeeping to class_loader::ClassLoader +* Updated to utilize newly renamed class_loader (formerly plugins) library with new file names, functions, identifiers, etc +* Removed explicit dependency that should have been automatically imported from dependent package in CMakeLists.txt +* Fixed unhandled exception to make all unit tests pass +* Removed mention of console bridge in CMakeLists.txt, plugins now probably exports +* Finished mods to utilize lower level plugins library. One test still failing, will get to that soon, but basics seem to be ok +* Modding pluginlib to use new plugins library. Not done, but just doing it tosync with my laptop +* Removed Poco and updated CMake and manifest files to depend on lower level plugins library +* Contributors: Dirk Thomas, Mirza Shah, mirzashah + +1.8.6 (2012-10-09) +------------------ +* added missing boost include dirs and runtime dependency +* updated cmake min version to 2.8.3 +* Contributors: Dirk Thomas, Vincent Rabaud + +1.8.5 (2012-10-01) +------------------ +* add missing roslib dependency that happens in class_loader_imp.h +* Contributors: Vincent Rabaud + +1.8.4 (2012-09-30) +------------------ +* updated to latest catkin +* Contributors: Dirk Thomas + +1.8.3 (2012-09-07) +------------------ +* added tinyxml to project depends +* Contributors: Dirk Thomas + +1.8.2 (2012-09-06) +------------------ +* updated pkg-config in manifest.xml +* updated catkin variables +* Contributors: Dirk Thomas + +1.8.1 (2012-09-04) +------------------ +* Missing LIBRARIES and DEPENDS specifiers from CMakeLists.txt, now added. +* catkin-ized +* updated api doc for load/create/unload methods +* renamed new methods using shorter name for encouraged method +* added cmake macro for hiding plugin symbols and respective rosbuild export +* updated class loader according to updated REP 121 +* add auto-unload for libraries using boost shared pointer +* pluginlib: added a pure-virtual base class for ClassLoader called ClassLoaderBase, which is not templated. Only one function of ClassLoader is actually templated. This allows client code to not be templated where it doesn't need to be. +* patch 4 for `#4887 `_ +* ignore bin +* accepting patch from ticket `#4887 `_ REP 116 implementation +* add explicit link against tinyxml, because users of our libraries will need to link against it +* link poco_lite with tinyxml +* remove namespace to be compatible with tinyxml sysdep +* removing back depend on common +* removing rosdep.yaml, rule is in ros/rosdep.yaml +* fixed tinyxml +* converting to unary stack (separated from common) +* applied patch from 4923, to support boost 1.46 +* patch from Nick Butko osx compatability +* adding unittest melonee forgot to commit +* adding pluginlib tests +* patch for osx linking `#4094 `_ +* Fixed exception comments +* Added Ubuntu platform tags to manifest +* Fixing bug where the incorrect library path was passed to dlopen from pluginlib... oops. +* fix in latest for `#4013 `_ to isolate boost filesystem calls into a library +* patch from Wim `#3346 `_ reviewed by Eitan and I +* Adding getName and isClassAvailable function calls to the class loader +* inlining to avoid multiple definitions +* macro deprecation +* adding warning about deprecated macro PLUGINLIB_REGISTER_CLASS +* pluginlib now takes pkg/type arguments, new macro PLUGINLIB_DECLARE_CLASS +* pluginlib now robust to malformed manifests +* Adding more descriptive error messages when libaries fail to load +* Remove use of deprecated rosbuild macros +* doc review completed http://www.ros.org/wiki/pluginlib/Reviews/2009-10-06_Doc_Review +* fixing documentation link +* fixing `#2894 `_ +* Removing ROS_ERRORS in favor of adding information to the exceptions thrown +* migration part 1 +* Contributors: Dave Hershberger, Dirk Thomas, Ken Conley, Mirza Shah, Tully Foote, eitan, gerkey, kwc, mwise, rusu, tfoote, vpradeep, wheeler diff --git a/navigations/pluginlib/CMakeLists.txt b/navigations/pluginlib/CMakeLists.txt new file mode 100755 index 0000000..289c5af --- /dev/null +++ b/navigations/pluginlib/CMakeLists.txt @@ -0,0 +1,43 @@ +cmake_minimum_required(VERSION 3.0.2) +project(pluginlib) + +find_package(catkin REQUIRED COMPONENTS class_loader rosconsole roslib cmake_modules) +find_package(Boost REQUIRED COMPONENTS filesystem) +find_package(TinyXML2 REQUIRED) + +catkin_package( + INCLUDE_DIRS include + CATKIN_DEPENDS class_loader rosconsole roslib + DEPENDS Boost TinyXML2 +) + +if(CATKIN_ENABLE_TESTING) + include_directories(include ${catkin_INCLUDE_DIRS} ${Boost_INCLUDE_DIRS} ${TinyXML2_INCLUDE_DIRS}) + + add_library(test_plugins EXCLUDE_FROM_ALL SHARED test/test_plugins.cpp) + target_link_libraries(test_plugins ${class_loader_LIBRARIES}) + + catkin_add_gtest(${PROJECT_NAME}_utest test/utest.cpp) + if(TARGET ${PROJECT_NAME}_utest) + target_link_libraries(${PROJECT_NAME}_utest ${TinyXML2_LIBRARIES} ${catkin_LIBRARIES} ${Boost_LIBRARIES}) + add_dependencies(${PROJECT_NAME}_utest test_plugins) + endif() + + include(CheckCXXCompilerFlag) + check_cxx_compiler_flag("-std=c++11" COMPILER_SUPPORTS_CXX11) + if(COMPILER_SUPPORTS_CXX11) + catkin_add_gtest(${PROJECT_NAME}_unique_ptr_test test/unique_ptr_test.cpp) + if(TARGET ${PROJECT_NAME}_unique_ptr_test) + target_link_libraries(${PROJECT_NAME}_unique_ptr_test ${TinyXML2_LIBRARIES} ${catkin_LIBRARIES} ${Boost_LIBRARIES}) + set_target_properties(${PROJECT_NAME}_unique_ptr_test PROPERTIES COMPILE_FLAGS -std=c++11 LINK_FLAGS -std=c++11) + add_dependencies(${PROJECT_NAME}_unique_ptr_test test_plugins) + endif() + endif() + +endif() + +install(DIRECTORY include/pluginlib/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}) + +install(PROGRAMS scripts/pluginlib_headers_migration.py + DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) diff --git a/navigations/pluginlib/include/pluginlib/class_desc.h b/navigations/pluginlib/include/pluginlib/class_desc.h new file mode 100755 index 0000000..f52e2bd --- /dev/null +++ b/navigations/pluginlib/include/pluginlib/class_desc.h @@ -0,0 +1,37 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Open Source Robotics Foundation, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the copyright holders nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef PLUGINLIB__CLASS_DESC_H_ +#define PLUGINLIB__CLASS_DESC_H_ + +#include "./class_desc.hpp" + +#endif // PLUGINLIB__CLASS_DESC_H_ diff --git a/navigations/pluginlib/include/pluginlib/class_desc.hpp b/navigations/pluginlib/include/pluginlib/class_desc.hpp new file mode 100755 index 0000000..8a1ea12 --- /dev/null +++ b/navigations/pluginlib/include/pluginlib/class_desc.hpp @@ -0,0 +1,84 @@ +/********************************************************************* +* +* Software License Agreement (BSD License) +* +* Copyright (c) 2008, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of Willow Garage, Inc. nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* +*********************************************************************/ + +#ifndef PLUGINLIB__CLASS_DESC_HPP_ +#define PLUGINLIB__CLASS_DESC_HPP_ + +#include + +namespace pluginlib +{ + +/// Storage for information about a given class. +class ClassDesc +{ +public: + /** + * \param lookup_name The lookup name of the class + * \param derived_class The type of the derived class of the class + * \param base_class The type of the class, corresponds to the type of the base class + * \param package The package the class lives in + * \param description A description for the class + * \param library_name The name of the containing library for the class (not a full path!) + * \param plugin_manifest_path The path to the plugin manifest file + */ + ClassDesc( + const std::string & lookup_name, const std::string & derived_class, + const std::string & base_class, const std::string & package, + const std::string & description, const std::string & library_name, + const std::string & plugin_manifest_path) + : lookup_name_(lookup_name), + derived_class_(derived_class), + base_class_(base_class), + package_(package), + description_(description), + library_name_(library_name), + resolved_library_path_("UNRESOLVED"), + plugin_manifest_path_(plugin_manifest_path) {} + + std::string lookup_name_; + std::string derived_class_; + std::string base_class_; + std::string package_; + std::string description_; + std::string library_name_; + std::string resolved_library_path_; // This is set by pluginlib::ClassLoader at load time. + std::string plugin_manifest_path_; +}; + +} // namespace pluginlib + +#endif // PLUGINLIB__CLASS_DESC_HPP_ diff --git a/navigations/pluginlib/include/pluginlib/class_list_macros.h b/navigations/pluginlib/include/pluginlib/class_list_macros.h new file mode 100755 index 0000000..a7f7b95 --- /dev/null +++ b/navigations/pluginlib/include/pluginlib/class_list_macros.h @@ -0,0 +1,37 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Open Source Robotics Foundation, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the copyright holders nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef PLUGINLIB__CLASS_LIST_MACROS_H_ +#define PLUGINLIB__CLASS_LIST_MACROS_H_ + +#include "./class_list_macros.hpp" + +#endif // PLUGINLIB__CLASS_LIST_MACROS_H_ diff --git a/navigations/pluginlib/include/pluginlib/class_list_macros.hpp b/navigations/pluginlib/include/pluginlib/class_list_macros.hpp new file mode 100755 index 0000000..9691052 --- /dev/null +++ b/navigations/pluginlib/include/pluginlib/class_list_macros.hpp @@ -0,0 +1,51 @@ +/********************************************************************* +* +* Software License Agreement (BSD License) +* +* Copyright (c) 2008, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of Willow Garage, Inc. nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* +*********************************************************************/ + +#ifndef PLUGINLIB__CLASS_LIST_MACROS_HPP_ +#define PLUGINLIB__CLASS_LIST_MACROS_HPP_ + +#include + +/// Register a class with class loader to effectively export it for plugin loading later. +/** + * \def PLUGINLIB_EXPORT_CLASS(class_type, base_class_type) + * \param class_type The real class name with namespace qualifier (e.g. Animals::Lion) + * \param base_class_type The real base class type from which class_type inherits + */ +#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type) \ + CLASS_LOADER_REGISTER_CLASS(class_type, base_class_type) + +#endif // PLUGINLIB__CLASS_LIST_MACROS_HPP_ diff --git a/navigations/pluginlib/include/pluginlib/class_loader.h b/navigations/pluginlib/include/pluginlib/class_loader.h new file mode 100755 index 0000000..f2458a2 --- /dev/null +++ b/navigations/pluginlib/include/pluginlib/class_loader.h @@ -0,0 +1,37 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Open Source Robotics Foundation, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the copyright holders nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef PLUGINLIB__CLASS_LOADER_H_ +#define PLUGINLIB__CLASS_LOADER_H_ + +#include "./class_loader.hpp" + +#endif // PLUGINLIB__CLASS_LOADER_H_ diff --git a/navigations/pluginlib/include/pluginlib/class_loader.hpp b/navigations/pluginlib/include/pluginlib/class_loader.hpp new file mode 100755 index 0000000..7aaa044 --- /dev/null +++ b/navigations/pluginlib/include/pluginlib/class_loader.hpp @@ -0,0 +1,352 @@ +/* + * Copyright (c) 2009, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef PLUGINLIB__CLASS_LOADER_HPP_ +#define PLUGINLIB__CLASS_LOADER_HPP_ + +#include +#include +#include + +#include "boost/algorithm/string.hpp" +#include "class_loader/multi_library_class_loader.hpp" +#include "pluginlib/class_desc.hpp" +#include "pluginlib/class_loader_base.hpp" +#include "pluginlib/exceptions.hpp" +#include "ros/console.h" +#include "ros/package.h" +#include "tinyxml2.h" // NOLINT + +// Note: pluginlib has traditionally utilized a "lookup name" for classes that does not match its +// real C++ name. +// This was done due to limitations of how pluginlib was implemented. +// As of version 1.9, a lookup name is no longer necessary and an attempt to the merge two concepts +// is underway. + +namespace pluginlib +{ + +#if __cplusplus >= 201103L +template +using UniquePtr = class_loader::ClassLoader::UniquePtr; +#endif +/// A class to help manage and load classes. +template +class ClassLoader : public ClassLoaderBase +{ +public: + typedef typename std::map::iterator ClassMapIterator; + +public: + /** + * \param package The package containing the base class + * \param base_class The type of the base class for classes to be loaded + * \param attrib_name The attribute to search for in manifext.xml files, defaults to "plugin" + * \param plugin_xml_paths The list of paths of plugin.xml files, defaults to be crawled via + * ros::package::getPlugins() + * \throws pluginlib::ClassLoaderException if package manifest cannot be found + */ + ClassLoader( + std::string package, std::string base_class, + std::string attrib_name = std::string("plugin"), + std::vector plugin_xml_paths = std::vector()); + + ~ClassLoader(); + + /// Create an instance of a desired class, optionally loading the associated library too. + /** + * \param lookup_name The name of the class to load + * \param auto_load Specifies whether or not to automatically load the + * library containing the class, set to true by default. + * \throws pluginlib::LibraryLoadException when the library associated + * with the class cannot be loaded + * \throws pluginlib::CreateClassException when the class cannot be instantiated + * \return An instance of the class + * \deprecated use either createInstance() or createUnmanagedInstance() + */ + [[deprecated]] T * createClassInstance( + const std::string & lookup_name, + bool auto_load = true); + + /// Create an instance of a desired class. + /** + * Implicitly calls loadLibraryForClass() to increment the library counter. + * + * Deleting the instance and calling unloadLibraryForClass() is automatically + * handled by the shared pointer. + * \param lookup_name The name of the class to load + * \throws pluginlib::LibraryLoadException when the library associated with + * the class cannot be loaded + * \throws pluginlib::CreateClassException when the class cannot be instantiated + * \return An instance of the class + */ + boost::shared_ptr createInstance(const std::string & lookup_name); + +#if __cplusplus >= 201103L + /// Create an instance of a desired class. + /** + * Implicitly calls loadLibraryForClass() to increment the library counter. + * + * Deleting the instance and calling unloadLibraryForClass() is automatically + * handled by the unique pointer. + * + * If you release the wrapped pointer you must manually call the original + * deleter when you want to destroy the released pointer. + * + * \param lookup_name The name of the class to load. + * \throws pluginlib::LibraryLoadException when the library associated with + * the class cannot be loaded. + * \throws pluginlib::CreateClassException when the class cannot be instantiated + * \return An instance of the class + */ + UniquePtr createUniqueInstance(const std::string & lookup_name); +#endif + + /// Create an instance of a desired class. + /** + * Implicitly calls loadLibraryForClass() to increment the library counter. + * + * \attention The ownership is transfered to the caller, which is responsible + * for deleting the instance and calling unloadLibraryForClass() + * (in order to decrement the associated library counter and unloading it + * if it is no more used). + * \param lookup_name The name of the class to load + * \throws pluginlib::LibraryLoadException when the library associated with + * the class cannot be loaded + * \throws pluginlib::CreateClassException when the class cannot be instantiated + * \return An instance of the class + */ + T * createUnmanagedInstance(const std::string & lookup_name); + + /// Return a list of all available plugin manifest paths for this ClassLoader's base class type. + /** + * \return A vector of strings corresponding to the paths of all available plugin manifests + */ + std::vector getPluginXmlPaths(); + + /// Return a list of all available classes for this ClassLoader's base class type. + /** + * \return A vector of strings corresponding to the names of all available classes + */ + std::vector getDeclaredClasses(); + + /// Strip the package name off of a lookup name. + /** + * \param lookup_name The name of the plugin + * \return The name of the plugin stripped of the package name + */ + virtual std::string getName(const std::string & lookup_name); + + /// Given the lookup name of a class, return the type of the associated base class. + /** + * \return The type of the associated base class + */ + virtual std::string getBaseClassType() const; + + /// Given the lookup name of a class, return the type of the derived class associated with it. + /** + * \param lookup_name The name of the class + * \return The name of the associated derived class + */ + virtual std::string getClassType(const std::string & lookup_name); + + /// Given the lookup name of a class, return its description. + /** + * \param lookup_name The lookup name of the class + * \return The description of the class + */ + virtual std::string getClassDescription(const std::string & lookup_name); + + /// Given the name of a class, return the path to its associated library. + /** + * \param lookup_name The name of the class + * \return The path to the associated library + */ + virtual std::string getClassLibraryPath(const std::string & lookup_name); + + /// Given the name of a class, return name of the containing package. + /** + * \param lookup_name The name of the class + * \return The name of the containing package + */ + virtual std::string getClassPackage(const std::string & lookup_name); + + /// Given the name of a class, return the path of the associated plugin manifest. + /** + * \param lookup_name The name of the class + * \return The path of the associated plugin manifest + */ + virtual std::string getPluginManifestPath(const std::string & lookup_name); + + /// Return the libraries that are registered and can be loaded. + /** + * \return A vector of strings corresponding to the names of registered libraries + */ + virtual std::vector getRegisteredLibraries(); + + /// Check if the library for a given class is currently loaded. + /** + * \param lookup_name The lookup name of the class to query + * \return True if the class is loaded, false otherwise + */ + bool isClassLoaded(const std::string & lookup_name); + + /// Check if the class associated with a plugin name is available to be loaded. + /** + * \param lookup_name The name of the plugin + * \return true if the plugin is available, false otherwise + */ + virtual bool isClassAvailable(const std::string & lookup_name); + + /// Attempt to load the library containing a class with a given name. + /** + * The counter for the library uses (refcount) is also incremented. + * + * \param lookup_name The lookup name of the class to load + * \throws pluginlib::LibraryLoadException if the library for the + * class cannot be loaded + */ + virtual void loadLibraryForClass(const std::string & lookup_name); + + /// Refresh the list of all available classes for this ClassLoader's base class type. + /** + * \throws pluginlib::LibraryLoadException if package manifest cannot be found + */ + virtual void refreshDeclaredClasses(); + + /// Decrement the counter for the library containing a class with a given name. + /** + * Also try to unload the library, If the counter reaches zero. + * + * \param lookup_name The lookup name of the class to unload + * \throws pluginlib::LibraryUnloadException if the library for the + * class cannot be unloaded + * \return The number of pending unloads until the library is removed from memory + */ + virtual int unloadLibraryForClass(const std::string & lookup_name); + +private: + /// Return the paths to plugin.xml files. + /** + * \throws pluginlib::LibraryLoadException if package manifest cannot be found + * \return A vector of paths + */ + std::vector getPluginXmlPaths( + const std::string & package, + const std::string & attrib_name, + bool force_recrawl = false); + + /// Return the available classes. + /** + * \param plugin_xml_paths The vector of paths of plugin.xml files + * \throws pluginlib::LibraryLoadException if package manifest cannot be found + * \return A map of class names and the corresponding descriptions + */ + std::map determineAvailableClasses( + const std::vector & plugin_xml_paths); + + /// Open a package.xml file and extract the package name (i.e. contents of tag). + /** + * \param package_xml_path The path to the package.xml file + * \return The name of the package if successful, otherwise an empty string + */ + std::string extractPackageNameFromPackageXML(const std::string & package_xml_path); + + /// Get a list of paths to try to find a library. + /** + * As we transition from rosbuild to Catkin build systems, plugins can be + * found in the old rosbuild place (pkg_name/lib usually) or somewhere in the + * Catkin build space. + */ + std::vector getAllLibraryPathsToTry( + const std::string & library_name, + const std::string & exporting_package_name); + + /// Return the paths where libraries are installed according to the Catkin build system. + std::vector getCatkinLibraryPaths(); + + /// Return an error message for an unknown class. + /** + * \param lookup_name The name of the class + * \return The error message + */ + std::string getErrorStringForUnknownClass(const std::string & lookup_name); + + /// Get the standard path separator for the native OS (e.g. "/" on *nix, "\" on Windows). + std::string getPathSeparator(); + + /// Given a package name, return the path where rosbuild thinks plugins are installed. + std::string getROSBuildLibraryPath(const std::string & exporting_package_name); + + /// Get the package name from a path to a plugin XML file. + std::string getPackageFromPluginXMLFilePath(const std::string & path); + + /// Join two filesystem paths together utilzing appropriate path separator. + std::string joinPaths(const std::string & path1, const std::string & path2); + + /// Parse a plugin XML file. + /** + * Also insert the appropriate ClassDesc entries into the passes + * classes_available map. + */ + void processSingleXMLPluginFile( + const std::string & xml_file, std::map & class_available); + + /// Strip all but the filename from an explicit file path. + /** + * \param path The path to strip + * \return The basename of the path + */ + std::string stripAllButFileFromPath(const std::string & path); + + + /// Helper function for unloading a shared library. + /** + * \param library_path The exact path to the library to unload + * \return The number of pending unloads until the library is removed from memory + */ + int unloadClassLibraryInternal(const std::string & library_path); + +private: + std::vector plugin_xml_paths_; + // Map from library to class's descriptions described in XML. + std::map classes_available_; + std::string package_; + std::string base_class_; + std::string attrib_name_; + class_loader::MultiLibraryClassLoader lowlevel_class_loader_; // The underlying classloader +}; + +} // namespace pluginlib + +// Note: The implementation of the methods is in a separate file for clarity. +#include "./class_loader_imp.hpp" + +#endif // PLUGINLIB__CLASS_LOADER_HPP_ diff --git a/navigations/pluginlib/include/pluginlib/class_loader_base.h b/navigations/pluginlib/include/pluginlib/class_loader_base.h new file mode 100755 index 0000000..985a87a --- /dev/null +++ b/navigations/pluginlib/include/pluginlib/class_loader_base.h @@ -0,0 +1,37 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Open Source Robotics Foundation, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the copyright holders nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef PLUGINLIB__CLASS_LOADER_BASE_H_ +#define PLUGINLIB__CLASS_LOADER_BASE_H_ + +#include "./class_loader_base.hpp" + +#endif // PLUGINLIB__CLASS_LOADER_BASE_H_ diff --git a/navigations/pluginlib/include/pluginlib/class_loader_base.hpp b/navigations/pluginlib/include/pluginlib/class_loader_base.hpp new file mode 100755 index 0000000..c8f5af0 --- /dev/null +++ b/navigations/pluginlib/include/pluginlib/class_loader_base.hpp @@ -0,0 +1,156 @@ +/* + * Copyright (c) 2012, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef PLUGINLIB__CLASS_LOADER_BASE_HPP_ +#define PLUGINLIB__CLASS_LOADER_BASE_HPP_ + +#include +#include + +namespace pluginlib +{ +/// Pure virtual base class of pluginlib::ClassLoader which is not templated. +/** + * This allows the writing of non-templated manager code + * which can call all the administrative functions of ClassLoaders - + * everything except createClassInstance(), createInstance() + * and createUnmanagedInstance(). + */ +class ClassLoaderBase +{ +public: + /// Empty virtual destructor. + virtual ~ClassLoaderBase() {} + + /// Return a list of all available plugin manifest paths. + /** + * \return A vector of strings corresponding to the paths of all available plugin manifests + */ + virtual std::vector getPluginXmlPaths() = 0; + + /// Return a list of all available classes for this ClassLoader's base class type. + /** + * \return A vector of strings corresponding to the names of all available classes + */ + virtual std::vector getDeclaredClasses() = 0; + + /// Refresh the list of all available classes for this ClassLoader's base class type. + /** + * \throws pluginlib::LibraryLoadException if package manifest cannot be found + */ + virtual void refreshDeclaredClasses() = 0; + + /// Strip the package name off of a lookup name. + /** + * \param lookup_name The name of the plugin + * \return The name of the plugin stripped of the package name + */ + virtual std::string getName(const std::string & lookup_name) = 0; + + /// Check if the class associated with a plugin name is available to be loaded. + /** + * \param lookup_name The name of the plugin + * \return True if the plugin is available, false otherwise + */ + virtual bool isClassAvailable(const std::string & lookup_name) = 0; + + /// Given the lookup name of a class, return the type of the derived class associated with it. + /** + * \param lookup_name The name of the class + * \return The name of the associated derived class + */ + virtual std::string getClassType(const std::string & lookup_name) = 0; + + /// Given the lookup name of a class, return its description. + /** + * \param lookup_name The lookup name of the class + * \return The description of the class + */ + virtual std::string getClassDescription(const std::string & lookup_name) = 0; + + /// Given the lookup name of a class, return the type of the associated base class. + /** + * \return The type of the associated base class + */ + virtual std::string getBaseClassType() const = 0; + + /// Given the name of a class, return name of the containing package. + /** + * \param lookup_name The name of the class + * \return The name of the containing package + */ + virtual std::string getClassPackage(const std::string & lookup_name) = 0; + + /// Given the name of a class, return the path of the associated plugin manifest. + /** + * \param lookup_name The name of the class + * \return The path of the associated plugin manifest + */ + virtual std::string getPluginManifestPath(const std::string & lookup_name) = 0; + + /// Check if a given class is currently loaded. + /** + * \param lookup_name The lookup name of the class to query + * \return True if the class is loaded, false otherwise + */ + virtual bool isClassLoaded(const std::string & lookup_name) = 0; + + /// Attempt to load a class with a given name. + /** + * \param lookup_name The lookup name of the class to load + * \throws pluginlib::LibraryLoadException if the library for the + * class cannot be loaded + */ + virtual void loadLibraryForClass(const std::string & lookup_name) = 0; + + /// Attempt to unload a class with a given name. + /** + * \param lookup_name The lookup name of the class to unload + * \throws pluginlib::LibraryUnloadException if the library for the class + * cannot be unloaded + * \return The number of pending unloads until the library is removed from memory + */ + virtual int unloadLibraryForClass(const std::string & lookup_name) = 0; + + /// Return the libraries that are registered and can be loaded. + /** + * \return A vector of strings corresponding to the names of registered libraries + */ + virtual std::vector getRegisteredLibraries() = 0; + + /// Given the name of a class, return the path to its associated library. + /** + * \param lookup_name The name of the class + * \return The path to the associated library + */ + virtual std::string getClassLibraryPath(const std::string & lookup_name) = 0; +}; +} // namespace pluginlib + +#endif // PLUGINLIB__CLASS_LOADER_BASE_HPP_ diff --git a/navigations/pluginlib/include/pluginlib/class_loader_imp.h b/navigations/pluginlib/include/pluginlib/class_loader_imp.h new file mode 100755 index 0000000..38260ed --- /dev/null +++ b/navigations/pluginlib/include/pluginlib/class_loader_imp.h @@ -0,0 +1,39 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Open Source Robotics Foundation, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the copyright holders nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef PLUGINLIB__CLASS_LOADER_IMP_H_ +#define PLUGINLIB__CLASS_LOADER_IMP_H_ + +// *INDENT-OFF* (prevent uncrustify from adding indention below) +#error Header is deprecated, \ +but this file should never be included directly, include instead. + +#endif // PLUGINLIB__CLASS_LOADER_IMP_H_ diff --git a/navigations/pluginlib/include/pluginlib/class_loader_imp.hpp b/navigations/pluginlib/include/pluginlib/class_loader_imp.hpp new file mode 100755 index 0000000..8951b9f --- /dev/null +++ b/navigations/pluginlib/include/pluginlib/class_loader_imp.hpp @@ -0,0 +1,836 @@ +/********************************************************************* +* +* Software License Agreement (BSD License) +* +* Copyright (c) 2008, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of Willow Garage, Inc. nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* +*********************************************************************/ + +#ifndef PLUGINLIB__CLASS_LOADER_IMP_HPP_ +#define PLUGINLIB__CLASS_LOADER_IMP_HPP_ + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "boost/algorithm/string.hpp" +#include "boost/bind.hpp" +#include "boost/filesystem.hpp" +#include "boost/foreach.hpp" +#include "class_loader/class_loader.hpp" + +#include "ros/package.h" + +#include "./class_loader.hpp" + +#ifdef _WIN32 +const std::string os_pathsep(";"); // NOLINT +#else +const std::string os_pathsep(":"); // NOLINT +#endif + +namespace pluginlib +{ +template +ClassLoader::ClassLoader( + std::string package, std::string base_class, std::string attrib_name, + std::vector plugin_xml_paths) +: plugin_xml_paths_(plugin_xml_paths), + package_(package), + base_class_(base_class), + attrib_name_(attrib_name), + // NOTE: The parameter to the class loader enables/disables on-demand class + // loading/unloading. + // Leaving it off for now... libraries will be loaded immediately and won't + // be unloaded until class loader is destroyed or force unload. + lowlevel_class_loader_(false) + /***************************************************************************/ +{ + ROS_DEBUG_NAMED("pluginlib.ClassLoader", "Creating ClassLoader, base = %s, address = %p", + base_class.c_str(), this); + if (ros::package::getPath(package_).empty()) { + throw pluginlib::ClassLoaderException("Unable to find package: " + package_); + } + + if (0 == plugin_xml_paths_.size()) { + plugin_xml_paths_ = getPluginXmlPaths(package_, attrib_name_); + } + classes_available_ = determineAvailableClasses(plugin_xml_paths_); + ROS_DEBUG_NAMED("pluginlib.ClassLoader", + "Finished constructring ClassLoader, base = %s, address = %p", + base_class.c_str(), this); +} + +template +ClassLoader::~ClassLoader() +/***************************************************************************/ +{ + ROS_DEBUG_NAMED("pluginlib.ClassLoader", "Destroying ClassLoader, base = %s, address = %p", + getBaseClassType().c_str(), this); +} + + +template +T * ClassLoader::createClassInstance(const std::string & lookup_name, bool auto_load) +/***************************************************************************/ +{ + // Note: This method is deprecated + ROS_DEBUG_NAMED("pluginlib.ClassLoader", + "In deprecated call createClassInstance(), lookup_name = %s, auto_load = %i.", + (lookup_name.c_str()), auto_load); + + if (auto_load && !isClassLoaded(lookup_name)) { + ROS_DEBUG_NAMED("pluginlib.ClassLoader", + "Autoloading class library before attempting to create instance."); + loadLibraryForClass(lookup_name); + } + + try { + ROS_DEBUG_NAMED("pluginlib.ClassLoader", + "Attempting to create instance through low-level MultiLibraryClassLoader..."); + T * obj = lowlevel_class_loader_.createUnmanagedInstance(getClassType(lookup_name)); + ROS_DEBUG_NAMED("pluginlib.ClassLoader", "Instance created with object pointer = %p", obj); + + return obj; + } catch (const class_loader::CreateClassException & ex) { + ROS_DEBUG_NAMED("pluginlib.ClassLoader", "CreateClassException about to be raised for class %s", + lookup_name.c_str()); + throw pluginlib::CreateClassException(ex.what()); + } +} + +template +boost::shared_ptr ClassLoader::createInstance(const std::string & lookup_name) +/***************************************************************************/ +{ + ROS_DEBUG_NAMED("pluginlib.ClassLoader", "Attempting to create managed instance for class %s.", + lookup_name.c_str()); + + if (!isClassLoaded(lookup_name)) { + loadLibraryForClass(lookup_name); + } + + try { + std::string class_type = getClassType(lookup_name); + ROS_DEBUG_NAMED("pluginlib.ClassLoader", "%s maps to real class type %s", + lookup_name.c_str(), class_type.c_str()); + + boost::shared_ptr obj = lowlevel_class_loader_.createInstance(class_type); + + ROS_DEBUG_NAMED("pluginlib.ClassLoader", "boost::shared_ptr to object of real type %s created.", + class_type.c_str()); + + return obj; + } catch (const class_loader::CreateClassException & ex) { + ROS_DEBUG_NAMED("pluginlib.ClassLoader", + "Exception raised by low-level multi-library class loader when attempting " + "to create instance of class %s.", + lookup_name.c_str()); + throw pluginlib::CreateClassException(ex.what()); + } +} + +#if __cplusplus >= 201103L +template +UniquePtr ClassLoader::createUniqueInstance(const std::string & lookup_name) +{ + ROS_DEBUG_NAMED("pluginlib.ClassLoader", + "Attempting to create managed (unique) instance for class %s.", + lookup_name.c_str()); + + if (!isClassLoaded(lookup_name)) { + loadLibraryForClass(lookup_name); + } + + try { + std::string class_type = getClassType(lookup_name); + ROS_DEBUG_NAMED("pluginlib.ClassLoader", "%s maps to real class type %s", + lookup_name.c_str(), class_type.c_str()); + + UniquePtr obj = lowlevel_class_loader_.createUniqueInstance(class_type); + + ROS_DEBUG_NAMED("pluginlib.ClassLoader", "std::unique_ptr to object of real type %s created.", + class_type.c_str()); + + return obj; + } catch (const class_loader::CreateClassException & ex) { + ROS_DEBUG_NAMED("pluginlib.ClassLoader", + "Exception raised by low-level multi-library class loader when attempting " + "to create instance of class %s.", + lookup_name.c_str()); + throw pluginlib::CreateClassException(ex.what()); + } +} +#endif + +template +T * ClassLoader::createUnmanagedInstance(const std::string & lookup_name) +/***************************************************************************/ +{ + ROS_DEBUG_NAMED("pluginlib.ClassLoader", "Attempting to create UNMANAGED instance for class %s.", + lookup_name.c_str()); + + if (!isClassLoaded(lookup_name)) { + loadLibraryForClass(lookup_name); + } + + T * instance = 0; + try { + ROS_DEBUG_NAMED("pluginlib.ClassLoader", + "Attempting to create instance through low level multi-library class loader."); + std::string class_type = getClassType(lookup_name); + ROS_DEBUG_NAMED("pluginlib.ClassLoader", "%s maps to real class type %s", + lookup_name.c_str(), class_type.c_str()); + instance = lowlevel_class_loader_.createUnmanagedInstance(class_type); + ROS_DEBUG_NAMED("pluginlib.ClassLoader", "Instance of type %s created.", class_type.c_str()); + } catch (const class_loader::CreateClassException & ex) { + ROS_DEBUG_NAMED("pluginlib.ClassLoader", + "Exception raised by low-level multi-library class loader when attempting " + "to create UNMANAGED instance of class %s.", + lookup_name.c_str()); + throw pluginlib::CreateClassException(ex.what()); + } + return instance; +} + +template +std::vector ClassLoader::getPluginXmlPaths( + const std::string & package, + const std::string & attrib_name, + bool force_recrawl) +/***************************************************************************/ +{ + // Pull possible files from manifests of packages which depend on this package and export class + std::vector paths; + ros::package::getPlugins(package, attrib_name, paths, force_recrawl); + return paths; +} + +template +std::map ClassLoader::determineAvailableClasses( + const std::vector & plugin_xml_paths) +/***************************************************************************/ +{ + // mas - This method requires major refactoring... + // not only is it really long and confusing but a lot of the comments do not + // seem to be correct. + // With time I keep correcting small things, but a good rewrite is needed. + + ROS_DEBUG_NAMED("pluginlib.ClassLoader", "Entering determineAvailableClasses()..."); + std::map classes_available; + + // Walk the list of all plugin XML files (variable "paths") that are exported by the build system + for (std::vector::const_iterator it = plugin_xml_paths.begin(); + it != plugin_xml_paths.end(); ++it) + { + try { + processSingleXMLPluginFile(*it, classes_available); + } catch (const pluginlib::InvalidXMLException & e) { + ROS_ERROR_NAMED("pluginlib.ClassLoader", + "Skipped loading plugin with error: %s.", + e.what()); + } + } + + ROS_DEBUG_NAMED("pluginlib.ClassLoader", "Exiting determineAvailableClasses()..."); + return classes_available; +} + +template +std::string ClassLoader::extractPackageNameFromPackageXML(const std::string & package_xml_path) +/***************************************************************************/ +{ + tinyxml2::XMLDocument document; + document.LoadFile(package_xml_path.c_str()); + tinyxml2::XMLElement * doc_root_node = document.FirstChildElement("package"); + if (NULL == doc_root_node) { + ROS_ERROR_NAMED("pluginlib.ClassLoader", + "Could not find a root element for package manifest at %s.", + package_xml_path.c_str()); + return ""; + } + + assert(document.RootElement() == doc_root_node); + + tinyxml2::XMLElement * package_name_node = doc_root_node->FirstChildElement("name"); + if (NULL == package_name_node) { + ROS_ERROR_NAMED("pluginlib.ClassLoader", + "package.xml at %s does not have a tag! Cannot determine package " + "which exports plugin.", + package_xml_path.c_str()); + return ""; + } + + const char* package_name_node_txt = package_name_node->GetText(); + if (NULL == package_name_node_txt) { + ROS_ERROR_NAMED("pluginlib.ClassLoader", + "package.xml at %s has an invalid tag! Cannot determine package " + "which exports plugin.", + package_xml_path.c_str()); + return ""; + } + + return package_name_node_txt; +} + +template +std::vector ClassLoader::getCatkinLibraryPaths() +/***************************************************************************/ +{ + std::vector lib_paths; + const char * env = std::getenv("CMAKE_PREFIX_PATH"); + if (env) { + std::string env_catkin_prefix_paths(env); + std::vector catkin_prefix_paths; + boost::split(catkin_prefix_paths, env_catkin_prefix_paths, boost::is_any_of(os_pathsep)); + BOOST_FOREACH(std::string catkin_prefix_path, catkin_prefix_paths) { + boost::filesystem::path path(catkin_prefix_path); +#ifdef _WIN32 + boost::filesystem::path bin("bin"); + lib_paths.push_back((path / bin).string()); +#endif + boost::filesystem::path lib("lib"); + lib_paths.push_back((path / lib).string()); + } + } + return lib_paths; +} + +template +std::vector ClassLoader::getAllLibraryPathsToTry( + const std::string & library_name, + const std::string & exporting_package_name) +/***************************************************************************/ +{ + // Catkin-rosbuild Backwards Compatability Rules - Note library_name may be prefixed with + // relative path (e.g. "/lib/libFoo") + // 1. Try catkin library paths (catkin_find --libs) + library_name + extension + // 2. Try catkin library paths + // (catkin_find -- libs) + stripAllButFileFromPath(library_name) + extension + // 3. Try export_pkg/library_name + extension + + std::vector all_paths; + std::vector all_paths_without_extension = getCatkinLibraryPaths(); + all_paths_without_extension.push_back(getROSBuildLibraryPath(exporting_package_name)); + bool debug_library_suffix = (0 == class_loader::systemLibrarySuffix().compare(0, 1, "d")); + std::string non_debug_suffix; + if (debug_library_suffix) { + non_debug_suffix = class_loader::systemLibrarySuffix().substr(1); + } else { + non_debug_suffix = class_loader::systemLibrarySuffix(); + } + std::string library_name_with_extension = library_name + non_debug_suffix; + std::string stripped_library_name = stripAllButFileFromPath(library_name); + std::string stripped_library_name_with_extension = stripped_library_name + non_debug_suffix; + + const std::string path_separator = getPathSeparator(); + + for (unsigned int c = 0; c < all_paths_without_extension.size(); c++) { + std::string current_path = all_paths_without_extension.at(c); + all_paths.push_back(current_path + path_separator + library_name_with_extension); + all_paths.push_back(current_path + path_separator + stripped_library_name_with_extension); + // We're in debug mode, try debug libraries as well + if (debug_library_suffix) { + all_paths.push_back( + current_path + path_separator + library_name + class_loader::systemLibrarySuffix()); + all_paths.push_back( + current_path + path_separator + stripped_library_name + + class_loader::systemLibrarySuffix()); + } + } + + return all_paths; +} + +template +bool ClassLoader::isClassLoaded(const std::string & lookup_name) +/***************************************************************************/ +{ + return lowlevel_class_loader_.isClassAvailable(getClassType(lookup_name)); +} + +template +std::string ClassLoader::getBaseClassType() const +/***************************************************************************/ +{ + return base_class_; +} + +template +std::string ClassLoader::getClassDescription(const std::string & lookup_name) +/***************************************************************************/ +{ + ClassMapIterator it = classes_available_.find(lookup_name); + if (it != classes_available_.end()) { + return it->second.description_; + } + return ""; +} + +template +std::string ClassLoader::getClassType(const std::string & lookup_name) +/***************************************************************************/ +{ + ClassMapIterator it = classes_available_.find(lookup_name); + if (it != classes_available_.end()) { + return it->second.derived_class_; + } + return ""; +} + +template +std::string ClassLoader::getClassLibraryPath(const std::string & lookup_name) +/***************************************************************************/ +{ + if (classes_available_.find(lookup_name) == classes_available_.end()) { + ROS_DEBUG_NAMED("pluginlib.ClassLoader", "Class %s has no mapping in classes_available_.", + lookup_name.c_str()); + return ""; + } + ClassMapIterator it = classes_available_.find(lookup_name); + std::string library_name = it->second.library_name_; + ROS_DEBUG_NAMED("pluginlib.ClassLoader", "Class %s maps to library %s in classes_available_.", + lookup_name.c_str(), library_name.c_str()); + + std::vector paths_to_try = + getAllLibraryPathsToTry(library_name, it->second.package_); + + ROS_DEBUG_NAMED("pluginlib.ClassLoader", + "Iterating through all possible paths where %s could be located...", + library_name.c_str()); + for (std::vector::const_iterator it = paths_to_try.begin(); it != paths_to_try.end(); + it++) + { + ROS_DEBUG_NAMED("pluginlib.ClassLoader", "Checking path %s ", it->c_str()); + if (boost::filesystem::exists(*it)) { + ROS_DEBUG_NAMED("pluginlib.ClassLoader", "Library %s found at explicit path %s.", + library_name.c_str(), it->c_str()); + return *it; + } + } + return ""; +} + +template +std::string ClassLoader::getClassPackage(const std::string & lookup_name) +/***************************************************************************/ +{ + ClassMapIterator it = classes_available_.find(lookup_name); + if (it != classes_available_.end()) { + return it->second.package_; + } + return ""; +} + +template +std::vector ClassLoader::getPluginXmlPaths() +/***************************************************************************/ +{ + return plugin_xml_paths_; +} + +template +std::vector ClassLoader::getDeclaredClasses() +/***************************************************************************/ +{ + std::vector lookup_names; + for (ClassMapIterator it = classes_available_.begin(); it != classes_available_.end(); ++it) { + lookup_names.push_back(it->first); + } + + return lookup_names; +} + +template +std::string ClassLoader::getErrorStringForUnknownClass(const std::string & lookup_name) +/***************************************************************************/ +{ + std::string declared_types; + std::vector types = getDeclaredClasses(); + for (unsigned int i = 0; i < types.size(); i++) { + declared_types = declared_types + std::string(" ") + types[i]; + } + return "According to the loaded plugin descriptions the class " + lookup_name + + " with base class type " + base_class_ + " does not exist. Declared types are " + + declared_types; +} + +template +std::string ClassLoader::getName(const std::string & lookup_name) +/***************************************************************************/ +{ + // remove the package name to get the raw plugin name + std::vector split; + boost::split(split, lookup_name, boost::is_any_of("/:")); + return split.back(); +} + +template +std::string +ClassLoader::getPackageFromPluginXMLFilePath(const std::string & plugin_xml_file_path) +/***************************************************************************/ +{ + // Note: This method takes an input a path to a plugin xml file and must determine which + // package the XML file came from. This is not necessariliy the same thing as the member + // variable "package_". The plugin xml file can be located anywhere in the source tree for a + // package + + // rosbuild: + // 1. Find nearest encasing manifest.xml + // 2. Once found, the name of the folder containg the manifest should be the + // package name we are looking for + // 3. Confirm package is findable with rospack + + // catkin: + // 1. Find nearest encasing package.xml + // 2. Extract name of package from package.xml + + std::string package_name; + boost::filesystem::path p(plugin_xml_file_path); + boost::filesystem::path parent = p.parent_path(); + + // Figure out exactly which package the passed XML file is exported by. + while (true) { + if (boost::filesystem::exists(parent / "package.xml")) { + std::string package_file_path = (boost::filesystem::path(parent / "package.xml")).string(); + return extractPackageNameFromPackageXML(package_file_path); + } else if (boost::filesystem::exists(parent / "manifest.xml")) { +#if BOOST_FILESYSTEM_VERSION >= 3 + std::string package = parent.filename().string(); +#else + std::string package = parent.filename(); +#endif + std::string package_path = ros::package::getPath(package); + + // package_path is a substr of passed plugin xml path + if (0 == plugin_xml_file_path.find(package_path)) { + package_name = package; + break; + } + } + + // Recursive case - hop one folder up + parent = parent.parent_path().string(); + + // Base case - reached root and cannot find what we're looking for + if (parent.string().empty()) { + return ""; + } + } + + return package_name; +} + +template +std::string ClassLoader::getPathSeparator() +/***************************************************************************/ +{ +#if BOOST_FILESYSTEM_VERSION >= 3 +# ifdef _WIN32 + return boost::filesystem::path("/").string(); +# else + return boost::filesystem::path("/").native(); +# endif +#else + return boost::filesystem::path("/").external_file_string(); +#endif +} + + +template +std::string ClassLoader::getPluginManifestPath(const std::string & lookup_name) +/***************************************************************************/ +{ + ClassMapIterator it = classes_available_.find(lookup_name); + if (it != classes_available_.end()) { + return it->second.plugin_manifest_path_; + } + return ""; +} + + +template +std::vector ClassLoader::getRegisteredLibraries() +/***************************************************************************/ +{ + return lowlevel_class_loader_.getRegisteredLibraries(); +} + +template +std::string ClassLoader::getROSBuildLibraryPath(const std::string & exporting_package_name) +/***************************************************************************/ +{ + return ros::package::getPath(exporting_package_name); +} + +template +bool ClassLoader::isClassAvailable(const std::string & lookup_name) +/***************************************************************************/ +{ + return classes_available_.find(lookup_name) != classes_available_.end(); +} + +template +std::string ClassLoader::joinPaths(const std::string & path1, const std::string & path2) +/***************************************************************************/ +{ + boost::filesystem::path p1(path1); + return (p1 / path2).string(); +} + +template +void ClassLoader::loadLibraryForClass(const std::string & lookup_name) +/***************************************************************************/ +{ + ClassMapIterator it = classes_available_.find(lookup_name); + if (it == classes_available_.end()) { + ROS_DEBUG_NAMED("pluginlib.ClassLoader", "Class %s has no mapping in classes_available_.", + lookup_name.c_str()); + throw pluginlib::LibraryLoadException(getErrorStringForUnknownClass(lookup_name)); + } + + std::string library_path = getClassLibraryPath(lookup_name); + if ("" == library_path) { + ROS_DEBUG_NAMED("pluginlib.ClassLoader", "No path could be found to the library containing %s.", + lookup_name.c_str()); + std::ostringstream error_msg; + error_msg << "Could not find library corresponding to plugin " << lookup_name << + ". Make sure the plugin description XML file has the correct name of the " + "library and that the library actually exists."; + throw pluginlib::LibraryLoadException(error_msg.str()); + } + + try { + lowlevel_class_loader_.loadLibrary(library_path); + it->second.resolved_library_path_ = library_path; + } catch (const class_loader::LibraryLoadException & ex) { + std::string error_string = + "Failed to load library " + library_path + ". " + "Make sure that you are calling the PLUGINLIB_EXPORT_CLASS macro in the " + "library code, and that names are consistent between this macro and your XML. " + "Error string: " + ex.what(); + throw pluginlib::LibraryLoadException(error_string); + } +} + +template +void ClassLoader::processSingleXMLPluginFile( + const std::string & xml_file, std::map & classes_available) +/***************************************************************************/ +{ + ROS_DEBUG_NAMED("pluginlib.ClassLoader", "Processing xml file %s...", xml_file.c_str()); + tinyxml2::XMLDocument document; + document.LoadFile(xml_file.c_str()); + tinyxml2::XMLElement * config = document.RootElement(); + if (NULL == config) { + throw pluginlib::InvalidXMLException( + "XML Document '" + xml_file + + "' has no Root Element. This likely means the XML is malformed or missing."); + return; + } + const char* config_value = config->Value(); + if (NULL == config_value) { + throw pluginlib::InvalidXMLException( + "XML Document '" + xml_file + + "' has an invalid Root Element. This likely means the XML is malformed or missing."); + return; + } + if (!(strcmp(config_value, "library") == 0 || + strcmp(config_value, "class_libraries") == 0)) + { + throw pluginlib::InvalidXMLException( + "The XML document '" + xml_file + "' given to add must have either \"library\" or " + "\"class_libraries\" as the root tag"); + return; + } + // Step into the filter list if necessary + if (strcmp(config_value, "class_libraries") == 0) { + config = config->FirstChildElement("library"); + } + + tinyxml2::XMLElement * library = config; + while (library != NULL) { + const char* path = library->Attribute("path"); + if (NULL == path) { + ROS_ERROR_NAMED("pluginlib.ClassLoader", + "Attribute 'path' in 'library' tag is missing in %s.", xml_file.c_str()); + continue; + } + std::string library_path(path); + if (0 == library_path.size()) { + ROS_ERROR_NAMED("pluginlib.ClassLoader", + "Attribute 'path' in 'library' tag is missing in %s.", xml_file.c_str()); + continue; + } + + std::string package_name = getPackageFromPluginXMLFilePath(xml_file); + if ("" == package_name) { + ROS_ERROR_NAMED("pluginlib.ClassLoader", + "Could not find package manifest (neither package.xml or deprecated " + "manifest.xml) at same directory level as the plugin XML file %s. " + "Plugins will likely not be exported properly.\n)", + xml_file.c_str()); + } + + tinyxml2::XMLElement * class_element = library->FirstChildElement("class"); + while (class_element) { + std::string derived_class; + if (class_element->Attribute("type") != NULL) { + derived_class = std::string(class_element->Attribute("type")); + } else { + throw pluginlib::ClassLoaderException( + "Class could not be loaded. Attribute 'type' in class tag is missing."); + } + + std::string base_class_type; + if (class_element->Attribute("base_class_type") != NULL) { + base_class_type = std::string(class_element->Attribute("base_class_type")); + } else { + throw pluginlib::ClassLoaderException( + "Class could not be loaded. Attribute 'base_class_type' in class tag is missing."); + } + + std::string lookup_name; + if (class_element->Attribute("name") != NULL) { + lookup_name = class_element->Attribute("name"); + ROS_DEBUG_NAMED("pluginlib.ClassLoader", + "XML file specifies lookup name (i.e. magic name) = %s.", + lookup_name.c_str()); + } else { + ROS_DEBUG_NAMED("pluginlib.ClassLoader", + "XML file has no lookup name (i.e. magic name) for class %s, " + "assuming lookup_name == real class name.", + derived_class.c_str()); + lookup_name = derived_class; + } + + // make sure that this class is of the right type before registering it + if (base_class_type == base_class_) { + // register class here + tinyxml2::XMLElement * description = class_element->FirstChildElement("description"); + std::string description_str; + if (description) { + description_str = description->GetText() ? description->GetText() : ""; + } else { + description_str = "No 'description' tag for this plugin in plugin description file."; + } + + classes_available.insert(std::pair(lookup_name, + ClassDesc(lookup_name, derived_class, base_class_type, package_name, description_str, + library_path, xml_file))); + } + + // step to next class_element + class_element = class_element->NextSiblingElement("class"); + } + library = library->NextSiblingElement("library"); + } +} + +template +void ClassLoader::refreshDeclaredClasses() +/***************************************************************************/ +{ + ROS_DEBUG_NAMED("pluginlib.ClassLoader", "Refreshing declared classes."); + // determine classes not currently loaded for removal + std::list remove_classes; + for (std::map::const_iterator it = classes_available_.begin(); + it != classes_available_.end(); it++) + { + std::string resolved_library_path = it->second.resolved_library_path_; + std::vector open_libs = lowlevel_class_loader_.getRegisteredLibraries(); + if (std::find(open_libs.begin(), open_libs.end(), resolved_library_path) != open_libs.end()) { + remove_classes.push_back(it->first); + } + } + + while (!remove_classes.empty()) { + classes_available_.erase(remove_classes.front()); + remove_classes.pop_front(); + } + + // add new classes + plugin_xml_paths_ = getPluginXmlPaths(package_, attrib_name_, true); + std::map updated_classes = determineAvailableClasses(plugin_xml_paths_); + for (std::map::const_iterator it = updated_classes.begin(); + it != updated_classes.end(); it++) + { + if (classes_available_.find(it->first) == classes_available_.end()) { + classes_available_.insert(std::pair(it->first, it->second)); + } + } +} + +template +std::string ClassLoader::stripAllButFileFromPath(const std::string & path) +/***************************************************************************/ +{ + std::string only_file; + size_t c = path.find_last_of(getPathSeparator()); + if (std::string::npos == c) { + return path; + } else { + return path.substr(c, path.size()); + } +} + +template +int ClassLoader::unloadLibraryForClass(const std::string & lookup_name) +/***************************************************************************/ +{ + ClassMapIterator it = classes_available_.find(lookup_name); + if (it != classes_available_.end() && it->second.resolved_library_path_ != "UNRESOLVED") { + std::string library_path = it->second.resolved_library_path_; + ROS_DEBUG_NAMED("pluginlib.ClassLoader", "Attempting to unload library %s for class %s", + library_path.c_str(), lookup_name.c_str()); + return unloadClassLibraryInternal(library_path); + } else { + throw pluginlib::LibraryUnloadException(getErrorStringForUnknownClass(lookup_name)); + } +} + +template +int ClassLoader::unloadClassLibraryInternal(const std::string & library_path) +/***************************************************************************/ +{ + return lowlevel_class_loader_.unloadLibrary(library_path); +} + +} // namespace pluginlib + +#endif // PLUGINLIB__CLASS_LOADER_IMP_HPP_ diff --git a/navigations/pluginlib/include/pluginlib/exceptions.hpp b/navigations/pluginlib/include/pluginlib/exceptions.hpp new file mode 100755 index 0000000..4733d85 --- /dev/null +++ b/navigations/pluginlib/include/pluginlib/exceptions.hpp @@ -0,0 +1,107 @@ +/* + * Copyright (c) 2012, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef PLUGINLIB__EXCEPTIONS_HPP_ +#define PLUGINLIB__EXCEPTIONS_HPP_ + +#include +#include + +namespace pluginlib +{ + +/// A base class for all pluginlib exceptions that inherits from std::runtime_exception. +/** + * \class PluginlibException + */ +class PluginlibException : public std::runtime_error +{ +public: + explicit PluginlibException(const std::string & error_desc) + : std::runtime_error(error_desc) {} +}; + +/// Thrown when pluginlib is unable to load a plugin XML file. +/** + * \class InvalidXMLException + */ +class InvalidXMLException : public PluginlibException +{ +public: + explicit InvalidXMLException(const std::string & error_desc) + : PluginlibException(error_desc) {} +}; + +/// Thrown when pluginlib is unable to load the library associated with a given plugin. +/** + * \class LibraryLoadException + */ +class LibraryLoadException : public PluginlibException +{ +public: + explicit LibraryLoadException(const std::string & error_desc) + : PluginlibException(error_desc) {} +}; + +/// Thrown when pluginlib is unable to instantiate a class loader. +/** + * \class ClassLoaderException + */ +class ClassLoaderException : public PluginlibException +{ +public: + explicit ClassLoaderException(const std::string & error_desc) + : PluginlibException(error_desc) {} +}; + +/// Thrown when pluginlib is unable to unload the library associated with a given plugin. +/** + * \class LibraryUnloadException + */ +class LibraryUnloadException : public PluginlibException +{ +public: + explicit LibraryUnloadException(const std::string & error_desc) + : PluginlibException(error_desc) {} +}; + +/// Thrown when pluginlib is unable to create the class associated with a given plugin. +/** + * \class CreateClassException + */ +class CreateClassException : public PluginlibException +{ +public: + explicit CreateClassException(const std::string & error_desc) + : PluginlibException(error_desc) {} +}; + +} // namespace pluginlib + +#endif // PLUGINLIB__EXCEPTIONS_HPP_ diff --git a/navigations/pluginlib/include/pluginlib/pluginlib_exceptions.h b/navigations/pluginlib/include/pluginlib/pluginlib_exceptions.h new file mode 100755 index 0000000..a98d5fa --- /dev/null +++ b/navigations/pluginlib/include/pluginlib/pluginlib_exceptions.h @@ -0,0 +1,37 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, Open Source Robotics Foundation, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the copyright holders nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef PLUGINLIB__PLUGINLIB_EXCEPTIONS_H_ +#define PLUGINLIB__PLUGINLIB_EXCEPTIONS_H_ + +#include "./exceptions.hpp" + +#endif // PLUGINLIB__PLUGINLIB_EXCEPTIONS_H_ diff --git a/navigations/pluginlib/package.xml b/navigations/pluginlib/package.xml new file mode 100755 index 0000000..a64b54f --- /dev/null +++ b/navigations/pluginlib/package.xml @@ -0,0 +1,42 @@ + + + + pluginlib + 1.13.0 + + The pluginlib package provides tools for writing and dynamically loading plugins using the ROS build infrastructure. + To work, these tools require plugin providers to register their plugins in the package.xml of their package. + + Steven! Ragnarök + BSD + + http://www.ros.org/wiki/pluginlib + https://github.com/ros/pluginlib/issues + https://github.com/ros/pluginlib + Eitan Marder-Eppstein + Tully Foote + Dirk Thomas + Mirza Shah + + catkin + + cmake_modules + libboost-dev + libboost-filesystem-dev + class_loader + rosconsole + roslib + tinyxml2 + + libboost-dev + libboost-filesystem-dev + class_loader + rosconsole + roslib + tinyxml2 + + + + + + diff --git a/navigations/pluginlib/scripts/pluginlib_headers_migration.py b/navigations/pluginlib/scripts/pluginlib_headers_migration.py new file mode 100755 index 0000000..2b5dece --- /dev/null +++ b/navigations/pluginlib/scripts/pluginlib_headers_migration.py @@ -0,0 +1,74 @@ +#!/usr/bin/env python +# Software License Agreement (BSD License) +# +# Copyright (c) 2018, Open Source Robotics Foundation, Inc. +# All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# * Redistributions in binary form must reproduce the above +# copyright notice, this list of conditions and the following +# disclaimer in the documentation and/or other materials provided +# with the distribution. +# * Neither the name of the copyright holders nor the names of its +# contributors may be used to endorse or promote products derived +# from this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. + +# Run this script to update legacy pluginlib include statements +# to utilize the new pluginlib headers. + + +import subprocess + +cmd = "find . -type f ! -name '*.svn-base' -a ! -name '*.hg' -a ! -name '*.git' -a " \ + "\( -name '*.c*' -o -name '*.h*' \)" + +header_mappings = { + 'pluginlib/class_desc.h': 'pluginlib/class_desc.hpp', + 'pluginlib/class_list_macros.h': 'pluginlib/class_list_macros.hpp', + 'pluginlib/class_loader_base.h': 'pluginlib/class_loader_base.hpp', + 'pluginlib/class_loader.h': 'pluginlib/class_loader.hpp', + 'pluginlib/class_loader_imp.h': 'pluginlib/class_loader_imp.hpp', + 'pluginlib/pluginlib_exceptions.h': 'pluginlib/exceptions.hpp', +} +include_tokens = { + '"': '"', + '<': '>', +} +include_prefix = '#include ' +sed_cmd_prefix = ' -exec sed -i \' s' +sed_cmd_suffix = ' {} \; ' +sed_separator = '@' +full_cmd = cmd +for old_header, new_header in header_mappings.items(): + for leading_token, ending_token in include_tokens.items(): + full_cmd += \ + sed_cmd_prefix + sed_separator + \ + include_prefix + leading_token + old_header + ending_token + sed_separator + \ + include_prefix + leading_token + new_header + ending_token + sed_separator + \ + "g'" + sed_cmd_suffix + print("Looking for '%s' to replace with '%s'" % (old_header, new_header)) + +print('Running %s' % full_cmd) +ret_code = subprocess.call(full_cmd, shell=True) +if ret_code == 0: + print('success') +else: + print('failure') diff --git a/navigations/pluginlib/test/test_base.h b/navigations/pluginlib/test/test_base.h new file mode 100755 index 0000000..33340cf --- /dev/null +++ b/navigations/pluginlib/test/test_base.h @@ -0,0 +1,46 @@ +/* + * Copyright (c) 2012, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef TEST_BASE_H_ +#define TEST_BASE_H_ + +namespace test_base +{ +class Fubar +{ +public: + virtual void initialize(double foo) = 0; + virtual double result() = 0; + virtual ~Fubar() {} + +protected: + Fubar() {} +}; +} // namespace test_base +#endif // TEST_BASE_H_ diff --git a/navigations/pluginlib/test/test_plugins.cpp b/navigations/pluginlib/test/test_plugins.cpp new file mode 100755 index 0000000..70edd2c --- /dev/null +++ b/navigations/pluginlib/test/test_plugins.cpp @@ -0,0 +1,35 @@ +/* + * Copyright (c) 2012, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include "./test_base.h" +#include "test_plugins.h" // NOLINT + +PLUGINLIB_EXPORT_CLASS(test_plugins::Foo, test_base::Fubar) +PLUGINLIB_EXPORT_CLASS(test_plugins::Bar, test_base::Fubar) diff --git a/navigations/pluginlib/test/test_plugins.h b/navigations/pluginlib/test/test_plugins.h new file mode 100755 index 0000000..fca0bdd --- /dev/null +++ b/navigations/pluginlib/test/test_plugins.h @@ -0,0 +1,82 @@ +/* + * Copyright (c) 2012, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef TEST_PLUGINS_H_ +#define TEST_PLUGINS_H_ + +#include + +#include "./test_base.h" + +namespace test_plugins +{ +class Bar : public test_base::Fubar +{ +public: + Bar() {} + + void initialize(double foo) + { + foo_ = foo; + } + + double result() + { + return 0.5 * foo_ * getBar(); + } + + double getBar() + { + return sqrt((foo_ * foo_) - ((foo_ / 2) * (foo_ / 2))); + } + +private: + double foo_; +}; + +class Foo : public test_base::Fubar +{ +public: + Foo() {} + + void initialize(double foo) + { + foo_ = foo; + } + + double result() + { + return foo_ * foo_; + } + +private: + double foo_; +}; +} // namespace test_plugins +#endif // TEST_PLUGINS_H_ diff --git a/navigations/pluginlib/test/test_plugins.xml b/navigations/pluginlib/test/test_plugins.xml new file mode 100755 index 0000000..54972be --- /dev/null +++ b/navigations/pluginlib/test/test_plugins.xml @@ -0,0 +1,11 @@ + + + This is a foo plugin. + + + This is a bar plugin. + + + This is a broken none plugin. + + diff --git a/navigations/pluginlib/test/test_plugins_broken.xml b/navigations/pluginlib/test/test_plugins_broken.xml new file mode 100755 index 0000000..f28243c --- /dev/null +++ b/navigations/pluginlib/test/test_plugins_broken.xml @@ -0,0 +1,5 @@ + + + This is a foo plugin. + + diff --git a/navigations/pluginlib/test/unique_ptr_test.cpp b/navigations/pluginlib/test/unique_ptr_test.cpp new file mode 100755 index 0000000..6aaaadf --- /dev/null +++ b/navigations/pluginlib/test/unique_ptr_test.cpp @@ -0,0 +1,99 @@ +/* + * Copyright (c) 2012, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include + +#include + +#include "./test_base.h" + +TEST(PluginlibUniquePtrTest, unknownPlugin) { + pluginlib::ClassLoader test_loader("pluginlib", "test_base::Fubar"); + ASSERT_THROW(test_loader.createUniqueInstance("pluginlib/foobar"), + pluginlib::LibraryLoadException); +} + + +TEST(PluginlibUniquePtrTest, misspelledPlugin) { + pluginlib::ClassLoader bad_test_loader("pluginlib", "test_base::Fuba"); + ASSERT_THROW(bad_test_loader.createUniqueInstance( + "pluginlib/foo"), pluginlib::LibraryLoadException); +} + +TEST(PluginlibTest, brokenPlugin) { + pluginlib::ClassLoader test_loader("pluginlib", "test_base::Fubar"); + ASSERT_THROW(test_loader.createUniqueInstance("pluginlib/none"), pluginlib::PluginlibException); +} + +TEST(PluginlibUniquePtrTest, workingPlugin) { + pluginlib::ClassLoader test_loader("pluginlib", "test_base::Fubar"); + + try { + pluginlib::UniquePtr foo = test_loader.createUniqueInstance("pluginlib/foo"); + foo->initialize(10.0); + EXPECT_EQ(100.0, foo->result()); + } catch (pluginlib::PluginlibException & ex) { + FAIL() << "Throwing exception: " << ex.what(); + return; + } catch (...) { + FAIL() << "Uncaught exception"; + } +} + +TEST(PluginlibUniquePtrTest, createUniqueInstanceAndUnloadLibrary) { + ROS_INFO("Making the ClassLoader..."); + pluginlib::ClassLoader pl("pluginlib", "test_base::Fubar"); + + ROS_INFO("Instantiating plugin..."); + { + pluginlib::UniquePtr inst = pl.createUniqueInstance("pluginlib/foo"); + } + + ROS_INFO("Checking if plugin is loaded with isClassLoaded..."); + if (pl.isClassLoaded("pluginlib/foo")) { + ROS_INFO("Class is loaded"); + } else { + FAIL() << "Library containing class should be loaded but isn't."; + } + + ROS_INFO("Trying to unload class with unloadLibraryForClass..."); + try { + pl.unloadLibraryForClass("pluginlib/foo"); + } catch (pluginlib::PluginlibException & e) { + FAIL() << "Could not unload library when I should be able to."; + } + ROS_INFO("Done."); +} + +// Run all the tests that were declared with TEST() +int main(int argc, char ** argv) +{ + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/navigations/pluginlib/test/utest.cpp b/navigations/pluginlib/test/utest.cpp new file mode 100755 index 0000000..4ca2c77 --- /dev/null +++ b/navigations/pluginlib/test/utest.cpp @@ -0,0 +1,140 @@ +/* + * Copyright (c) 2012, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include + +#include + +#include "./test_base.h" + +TEST(PluginlibTest, unknownPlugin) { + pluginlib::ClassLoader test_loader("pluginlib", "test_base::Fubar"); + ASSERT_THROW(test_loader.createInstance("pluginlib/foobar"), pluginlib::LibraryLoadException); +} + +TEST(PluginlibTest, misspelledPlugin) { + pluginlib::ClassLoader bad_test_loader("pluginlib", "test_base::Fuba"); + ASSERT_THROW(bad_test_loader.createInstance("pluginlib/foo"), pluginlib::LibraryLoadException); +} + +TEST(PluginlibTest, invalidPackage) { + ASSERT_THROW(pluginlib::ClassLoader("pluginlib_bad", + "test_base::Fubar"), + pluginlib::ClassLoaderException); +} + +TEST(PluginlibTest, brokenPlugin) { + pluginlib::ClassLoader test_loader("pluginlib", "test_base::Fubar"); + ASSERT_THROW(test_loader.createInstance("pluginlib/none"), pluginlib::PluginlibException); +} + +TEST(PluginlibTest, workingPlugin) { + pluginlib::ClassLoader test_loader("pluginlib", "test_base::Fubar"); + + try { + boost::shared_ptr foo = test_loader.createInstance("pluginlib/foo"); + foo->initialize(10.0); + EXPECT_EQ(100.0, foo->result()); + } catch (pluginlib::PluginlibException & ex) { + FAIL() << "Throwing exception: " << ex.what(); + return; + } catch (...) { + FAIL() << "Uncaught exception"; + } +} + +TEST(PluginlibTest, createUnmanagedInstanceAndUnloadLibrary) { + ROS_INFO("Making the ClassLoader..."); + pluginlib::ClassLoader pl("pluginlib", "test_base::Fubar"); + + ROS_INFO("Instantiating plugin..."); + test_base::Fubar * inst = pl.createUnmanagedInstance("pluginlib/foo"); + + ROS_INFO("Deleting plugin..."); + delete inst; + + ROS_INFO("Checking if plugin is loaded with isClassLoaded..."); + if (pl.isClassLoaded("pluginlib/foo")) { + ROS_INFO("Class is loaded"); + } else { + FAIL() << "Library containing class should be loaded but isn't."; + } + ROS_INFO("Trying to unload class with unloadLibraryForClass..."); + try { + pl.unloadLibraryForClass("pluginlib/foo"); + } catch (pluginlib::PluginlibException & e) { + FAIL() << "Could not unload library when I should be able to."; + } + ROS_INFO("Done."); +} + +TEST(PluginlibTest, createManagedInstanceAndUnloadLibrary) { + ROS_INFO("Making the ClassLoader..."); + pluginlib::ClassLoader pl("pluginlib", "test_base::Fubar"); + + ROS_INFO("Instantiating plugin..."); + { + boost::shared_ptr inst = pl.createInstance("pluginlib/foo"); + } + + ROS_INFO("Checking if plugin is loaded with isClassLoaded..."); + if (pl.isClassLoaded("pluginlib/foo")) { + ROS_INFO("Class is loaded"); + } else { + FAIL() << "Library containing class should be loaded but isn't."; + } + + ROS_INFO("Trying to unload class with unloadLibraryForClass..."); + try { + pl.unloadLibraryForClass("pluginlib/foo"); + } catch (pluginlib::PluginlibException & e) { + FAIL() << "Could not unload library when I should be able to."; + } + ROS_INFO("Done."); +} + +TEST(PluginlibTest, brokenXML) { + try { + pluginlib::ClassLoader test_loader("pluginlib", "test_base::Fubar", + "plugin_test"); + test_loader.createInstance("pluginlib/foo"); + } catch (pluginlib::PluginlibException & ex) { + SUCCEED(); + return; + } + + ADD_FAILURE() << "Didn't throw exception as expected"; +} + +// Run all the tests that were declared with TEST() +int main(int argc, char ** argv) +{ + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/navigations/pose_follower/CHANGELOG.rst b/navigations/pose_follower/CHANGELOG.rst new file mode 100755 index 0000000..78a819f --- /dev/null +++ b/navigations/pose_follower/CHANGELOG.rst @@ -0,0 +1,46 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package pose_follower +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +0.4.1 (2022-08-24) +------------------ + +0.4.0 (2022-03-07) +------------------ + +0.3.4 (2020-06-19) +------------------ +* Initial release into noetic * Set cmake_policy CMP0048 to fix warning +* Contributors: Martin Günther + +0.3.3 (2019-10-15) +------------------ +* Add dynamic reconfigure to pose_follower (`#40 `_) + Similar to the other available local planners, this commit adds dynamic reconfigure to pose_follower. In addition to this, the collision_planner parameters (used for detecting illegal trajectory) have been moved to the `PoseFollower/collision_planner` namespace. + Major ROS API changes: + * all internal TrajectoryPlannerROS parameters moved into the collision_planner namespace + * all internal TrajectoryPlannerROS publishers (cost_cloud, global_plan, local_plan) moved into the collision_planner namespace + * there is still a global_plan topic without namespace, which is now only published by the pose_follower itself and no longer shared with the internal TrajectoryPlannerROS. +* unused publisher removed (`#41 `_) +* Add READMEs +* Contributors: Martin Günther, Pavel Shumejko + +0.3.2 (2019-01-16) +------------------ +* max rotation vel in in-place rotation limited (`#27 `_) +* pose_follower: Add visualization of global plan (`#26 `_) +* Contributors: Martin Günther, Pavel, sumejko92 + +0.3.1 (2018-09-05) +------------------ + +0.3.0 (2018-09-04) +------------------ +* Convert to TF2 + new navigation API (for melodic) +* Use non deprecated pluginlib macro + headers +* Contributors: Martin Günther + +0.2.0 (2018-09-03) +------------------ +* Initial release into indigo, kinetic, lunar and melodic +* Contributors: Martin Günther, David V. Lu!!, Dave Hershberger, Howard Cochran, Jon Binney, Kaijen Hsiao, Michael Ferguson, cratliff, Eitan Marder-Eppstein, Wim Meeussen diff --git a/navigations/pose_follower/CMakeLists.txt b/navigations/pose_follower/CMakeLists.txt new file mode 100755 index 0000000..3f55bb7 --- /dev/null +++ b/navigations/pose_follower/CMakeLists.txt @@ -0,0 +1,37 @@ +cmake_minimum_required(VERSION 3.5.1) +cmake_policy(SET CMP0048 NEW) +project(pose_follower) +set(pose_follower_ROS_DEPS nav_core base_local_planner costmap_2d roscpp tf2_geometry_msgs tf2_ros nav_msgs pluginlib dynamic_reconfigure) + +find_package(catkin REQUIRED COMPONENTS ${pose_follower_ROS_DEPS}) + +generate_dynamic_reconfigure_options( + cfg/PoseFollower.cfg +) + +catkin_package( + INCLUDE_DIRS include + LIBRARIES pose_follower + CATKIN_DEPENDS ${pose_follower_ROS_DEPS} +) + +include_directories(include ${catkin_INCLUDE_DIRS}) + +add_library(pose_follower src/pose_follower.cpp) +add_dependencies(pose_follower ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) +target_link_libraries(pose_follower ${catkin_LIBRARIES}) + +install(TARGETS pose_follower + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) + +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} + FILES_MATCHING PATTERN "*.h" +) + +install(FILES blp_plugin.xml + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) diff --git a/navigations/pose_follower/README.md b/navigations/pose_follower/README.md new file mode 100755 index 0000000..5991eec --- /dev/null +++ b/navigations/pose_follower/README.md @@ -0,0 +1,5 @@ +pose_follower +============= + +A implementation of a local planner that attempts to follow a plan as closely +as possible. diff --git a/navigations/pose_follower/blp_plugin.xml b/navigations/pose_follower/blp_plugin.xml new file mode 100755 index 0000000..31bc8ab --- /dev/null +++ b/navigations/pose_follower/blp_plugin.xml @@ -0,0 +1,7 @@ + + + + A implementation of a local planner that attempts to follow a plan as closely as possible. + + + diff --git a/navigations/pose_follower/cfg/PoseFollower.cfg b/navigations/pose_follower/cfg/PoseFollower.cfg new file mode 100755 index 0000000..8a640e1 --- /dev/null +++ b/navigations/pose_follower/cfg/PoseFollower.cfg @@ -0,0 +1,33 @@ +#!/usr/bin/env python + +PACKAGE = 'pose_follower' + +from math import pi + +from dynamic_reconfigure.parameter_generator_catkin import ParameterGenerator, double_t, int_t, bool_t, str_t + +gen = ParameterGenerator() + +gen.add("max_vel_lin", double_t, 0, "Maximum linear velocity in m/s", 0.9, 0.0, 10.0) +gen.add("max_vel_th", double_t, 0, "Maximum angular velocity in rad/s", 1.4, 0.0, 10.0) +gen.add("min_vel_lin", double_t, 0, "Minimum linear velocity for the robot in m/s", 0.1, 0, 10.0) +gen.add("min_vel_th", double_t, 0, "Minimum angular velocity for the robot in rad/s", 0.0, 0, 10.0) +gen.add("min_in_place_vel_th", double_t, 0, "If we're rotating in place, go at least this fast to avoid getting stuck", 0.0, 0, 10.0) +gen.add("in_place_trans_vel", double_t, 0, "When we're near the end and would be trying to go no faster than this translationally, just rotate in place instead", 0.0, 0, 10.0) +gen.add("trans_stopped_velocity", double_t, 0, "The robot is stopped if the velocities are lower than this", 1e-4, 0, 10.0) +gen.add("rot_stopped_velocity", double_t, 0, "The robot is stopped if the velocities are lower than this", 1e-4, 0, 10.0) + +gen.add("tolerance_trans", double_t, 0, "Translational tolerance for the goal", 0.02, 0, 10.0) +gen.add("tolerance_rot", double_t, 0, "Angular tolerance for the goal", 0.04, 0, pi) +gen.add("tolerance_timeout", double_t, 0, "We've reached our goal only if we're within range for this long and stopped", 0.5, 0, 20.0) + +gen.add("samples", int_t, 0, "Number of samples (scaling factors of our current desired twist)", 10, 0, 20) +gen.add("allow_backwards", bool_t, 0, "Allow backwards movement", False) +gen.add("turn_in_place_first", bool_t, 0, "If true, turn in place to face the new goal instead of arching towards it", False) +gen.add("max_heading_diff_before_moving", double_t, 0, "If turn_in_place_first is true, turn in place if our heading is more than this far from facing the goal location", 0.17, 0, pi) + + +gen.add("k_trans", double_t, 0, "Gain factor for translation component of output velocities", 2.0, 0.0, 20.0) +gen.add("k_rot", double_t, 0, "Gain factor for rotation component of output velocities", 2.0, 0.0, 20.0) + +exit(gen.generate(PACKAGE, "pose_follower", "PoseFollower")) diff --git a/navigations/pose_follower/include/pose_follower/pose_follower.h b/navigations/pose_follower/include/pose_follower/pose_follower.h new file mode 100755 index 0000000..2dcad38 --- /dev/null +++ b/navigations/pose_follower/include/pose_follower/pose_follower.h @@ -0,0 +1,109 @@ +/********************************************************************* +* +* Software License Agreement (BSD License) +* +* Copyright (c) 2009, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of Willow Garage, Inc. nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* +* Author: Eitan Marder-Eppstein +*********************************************************************/ +#ifndef POSE_FOLLOWER_POSE_FOLLOWER_H_ +#define POSE_FOLLOWER_POSE_FOLLOWER_H_ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +namespace pose_follower { + class PoseFollower : public nav_core::BaseLocalPlanner { + public: + PoseFollower(); + ~PoseFollower(); + void initialize(std::string name, tf2_ros::Buffer* tf, costmap_2d::Costmap2DROS* costmap_ros); + bool isGoalReached(); + bool setPlan(const std::vector& global_plan); + bool computeVelocityCommands(geometry_msgs::Twist& cmd_vel); + + private: + inline double sign(double n){ + return n < 0.0 ? -1.0 : 1.0; + } + + geometry_msgs::Twist diff2D(const geometry_msgs::Pose& pose1, const geometry_msgs::Pose& pose2); + geometry_msgs::Twist limitTwist(const geometry_msgs::Twist& twist); + double headingDiff(double pt_x, double pt_y, double x, double y, double heading); + + bool transformGlobalPlan(const tf2_ros::Buffer& tf, const std::vector& global_plan, + const costmap_2d::Costmap2DROS& costmap, const std::string& global_frame, + std::vector& transformed_plan); + + void odomCallback(const nav_msgs::Odometry::ConstPtr& msg); + bool stopped(); + void publishPlan(const std::vector &path, const ros::Publisher &pub); + void reconfigureCB(pose_follower::PoseFollowerConfig &config, uint32_t level); + + tf2_ros::Buffer *tf_; + costmap_2d::Costmap2DROS *costmap_ros_; + ros::Publisher global_plan_pub_; + boost::mutex odom_lock_; + ros::Subscriber odom_sub_; + nav_msgs::Odometry base_odom_; + ros::Time goal_reached_time_; + unsigned int current_waypoint_; + std::vector global_plan_; + base_local_planner::TrajectoryPlannerROS collision_planner_; + dynamic_reconfigure::Server *dsrv_; + + // Parameters + double max_vel_lin_, max_vel_th_; + double min_vel_lin_, min_vel_th_; + double min_in_place_vel_th_, in_place_trans_vel_; + double trans_stopped_velocity_, rot_stopped_velocity_; + double K_trans_, K_rot_, tolerance_trans_, tolerance_rot_; + double tolerance_timeout_; + int samples_; + bool allow_backwards_; + bool turn_in_place_first_; + double max_heading_diff_before_moving_; + bool holonomic_; + }; +}; +#endif diff --git a/navigations/pose_follower/package.xml b/navigations/pose_follower/package.xml new file mode 100755 index 0000000..6031d6e --- /dev/null +++ b/navigations/pose_follower/package.xml @@ -0,0 +1,30 @@ + + + pose_follower + 0.4.1 + + A implementation of a local planner that attempts to follow a plan as closely as possible. + + Martin Günther + Eitan Marder-Eppstein + BSD + http://wiki.ros.org/pose_follower + https://github.com/ros-planning/navigation_experimental.git + https://github.com/ros-planning/navigation_experimental/issues + + catkin + + base_local_planner + costmap_2d + dynamic_reconfigure + nav_core + nav_msgs + pluginlib + roscpp + tf2_geometry_msgs + tf2_ros + + + + + diff --git a/navigations/pose_follower/src/pose_follower.cpp b/navigations/pose_follower/src/pose_follower.cpp new file mode 100755 index 0000000..c8d1940 --- /dev/null +++ b/navigations/pose_follower/src/pose_follower.cpp @@ -0,0 +1,416 @@ +/********************************************************************* +* +* Software License Agreement (BSD License) +* +* Copyright (c) 2009, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of Willow Garage, Inc. nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* +* Author: Eitan Marder-Eppstein +*********************************************************************/ +#include +#include +#include + +PLUGINLIB_EXPORT_CLASS(pose_follower::PoseFollower, nav_core::BaseLocalPlanner) + +namespace pose_follower { + PoseFollower::PoseFollower(): tf_(NULL), costmap_ros_(NULL) {} + + PoseFollower::~PoseFollower() { + if (dsrv_) + delete dsrv_; + } + + void PoseFollower::initialize(std::string name, tf2_ros::Buffer* tf, costmap_2d::Costmap2DROS* costmap_ros){ + tf_ = tf; + costmap_ros_ = costmap_ros; + current_waypoint_ = 0; + goal_reached_time_ = ros::Time::now(); + ros::NodeHandle node_private("~/" + name); + + collision_planner_.initialize(name + "/collision_planner", tf_, costmap_ros_); + + //set this to true if you're using a holonomic robot + node_private.param("holonomic", holonomic_, true); + + global_plan_pub_ = node_private.advertise("global_plan", 1); + + ros::NodeHandle node; + odom_sub_ = node.subscribe("odom", 1, boost::bind(&PoseFollower::odomCallback, this, _1)); + + dsrv_ = new dynamic_reconfigure::Server( + ros::NodeHandle(node_private)); + dynamic_reconfigure::Server::CallbackType cb = + boost::bind(&PoseFollower::reconfigureCB, this, _1, _2); + dsrv_->setCallback(cb); + + ROS_DEBUG("Initialized"); + } + + void PoseFollower::reconfigureCB(pose_follower::PoseFollowerConfig &config, uint32_t level) { + max_vel_lin_ = config.max_vel_lin; + max_vel_th_ = config.max_vel_th; + min_vel_lin_ = config.min_vel_lin; + min_vel_th_ = config.min_vel_th; + min_in_place_vel_th_ = config.min_in_place_vel_th; + in_place_trans_vel_ = config.in_place_trans_vel; + trans_stopped_velocity_ = config.trans_stopped_velocity; + rot_stopped_velocity_ = config.rot_stopped_velocity; + + tolerance_trans_ = config.tolerance_trans; + tolerance_rot_ = config.tolerance_rot; + tolerance_timeout_ = config.tolerance_timeout; + + samples_ = config.samples; + allow_backwards_ = config.allow_backwards; + turn_in_place_first_ = config.turn_in_place_first; + max_heading_diff_before_moving_ = config.max_heading_diff_before_moving; + + K_trans_ = config.k_trans; + K_rot_ = config.k_rot; + } + + void PoseFollower::odomCallback(const nav_msgs::Odometry::ConstPtr& msg){ + //we assume that the odometry is published in the frame of the base + boost::mutex::scoped_lock lock(odom_lock_); + base_odom_.twist.twist.linear.x = msg->twist.twist.linear.x; + base_odom_.twist.twist.linear.y = msg->twist.twist.linear.y; + base_odom_.twist.twist.angular.z = msg->twist.twist.angular.z; + ROS_DEBUG("In the odometry callback with velocity values: (%.2f, %.2f, %.2f)", + base_odom_.twist.twist.linear.x, base_odom_.twist.twist.linear.y, base_odom_.twist.twist.angular.z); + } + + double PoseFollower::headingDiff(double x, double y, double pt_x, double pt_y, double heading) + { + double v1_x = x - pt_x; + double v1_y = y - pt_y; + double v2_x = cos(heading); + double v2_y = sin(heading); + + double perp_dot = v1_x * v2_y - v1_y * v2_x; + double dot = v1_x * v2_x + v1_y * v2_y; + + //get the signed angle + double vector_angle = atan2(perp_dot, dot); + + return -1.0 * vector_angle; + } + + bool PoseFollower::stopped(){ + //copy over the odometry information + nav_msgs::Odometry base_odom; + { + boost::mutex::scoped_lock lock(odom_lock_); + base_odom = base_odom_; + } + + return fabs(base_odom.twist.twist.angular.z) <= rot_stopped_velocity_ + && fabs(base_odom.twist.twist.linear.x) <= trans_stopped_velocity_ + && fabs(base_odom.twist.twist.linear.y) <= trans_stopped_velocity_; + } + + void PoseFollower::publishPlan(const std::vector &path, + const ros::Publisher &pub) { + // given an empty path we won't do anything + if (path.empty()) + return; + + // create a path message + nav_msgs::Path gui_path; + gui_path.poses.resize(path.size()); + gui_path.header.frame_id = path[0].header.frame_id; + gui_path.header.stamp = path[0].header.stamp; + + // Extract the plan in world co-ordinates, we assume the path is all in the same frame + for (unsigned int i = 0; i < path.size(); i++) { + gui_path.poses[i] = path[i]; + } + pub.publish(gui_path); + } + + bool PoseFollower::computeVelocityCommands(geometry_msgs::Twist& cmd_vel){ + //get the current pose of the robot in the fixed frame + geometry_msgs::PoseStamped robot_pose; + if(!costmap_ros_->getRobotPose(robot_pose)){ + ROS_ERROR("Can't get robot pose"); + geometry_msgs::Twist empty_twist; + cmd_vel = empty_twist; + return false; + } + + //we want to compute a velocity command based on our current waypoint + geometry_msgs::PoseStamped target_pose = global_plan_[current_waypoint_]; + ROS_DEBUG("PoseFollower: current robot pose %f %f ==> %f", robot_pose.pose.position.x, robot_pose.pose.position.y, tf2::getYaw(robot_pose.pose.orientation)); + ROS_DEBUG("PoseFollower: target robot pose %f %f ==> %f", target_pose.pose.position.x, target_pose.pose.position.y, tf2::getYaw(target_pose.pose.orientation)); + + //get the difference between the two poses + geometry_msgs::Twist diff = diff2D(target_pose.pose, robot_pose.pose); + ROS_DEBUG("PoseFollower: diff %f %f ==> %f", diff.linear.x, diff.linear.y, diff.angular.z); + + geometry_msgs::Twist limit_vel = limitTwist(diff); + + geometry_msgs::Twist test_vel = limit_vel; + bool legal_traj = collision_planner_.checkTrajectory(test_vel.linear.x, test_vel.linear.y, test_vel.angular.z, true); + + double scaling_factor = 1.0; + double ds = scaling_factor / samples_; + + //let's make sure that the velocity command is legal... and if not, scale down + if(!legal_traj){ + for(int i = 0; i < samples_; ++i){ + test_vel.linear.x = limit_vel.linear.x * scaling_factor; + test_vel.linear.y = limit_vel.linear.y * scaling_factor; + test_vel.angular.z = limit_vel.angular.z * scaling_factor; + test_vel = limitTwist(test_vel); + if(collision_planner_.checkTrajectory(test_vel.linear.x, test_vel.linear.y, test_vel.angular.z, false)){ + legal_traj = true; + break; + } + scaling_factor -= ds; + } + } + + if(!legal_traj){ + ROS_ERROR("Not legal (%.2f, %.2f, %.2f)", limit_vel.linear.x, limit_vel.linear.y, limit_vel.angular.z); + geometry_msgs::Twist empty_twist; + cmd_vel = empty_twist; + return false; + } + + //if it is legal... we'll pass it on + cmd_vel = test_vel; + + bool in_goal_position = false; + while(fabs(diff.linear.x) <= tolerance_trans_ && + fabs(diff.linear.y) <= tolerance_trans_ && + fabs(diff.angular.z) <= tolerance_rot_) + { + if(current_waypoint_ < global_plan_.size() - 1) + { + current_waypoint_++; + target_pose = global_plan_[current_waypoint_]; + diff = diff2D(target_pose.pose, robot_pose.pose); + } + else + { + ROS_INFO("Reached goal: %d", current_waypoint_); + in_goal_position = true; + break; + } + } + + //if we're not in the goal position, we need to update time + if(!in_goal_position) + goal_reached_time_ = ros::Time::now(); + + //check if we've reached our goal for long enough to succeed + if(goal_reached_time_ + ros::Duration(tolerance_timeout_) < ros::Time::now()){ + geometry_msgs::Twist empty_twist; + cmd_vel = empty_twist; + } + + return true; + } + + bool PoseFollower::setPlan(const std::vector& global_plan){ + current_waypoint_ = 0; + goal_reached_time_ = ros::Time::now(); + if(!transformGlobalPlan(*tf_, global_plan, *costmap_ros_, costmap_ros_->getGlobalFrameID(), global_plan_)){ + ROS_ERROR("Could not transform the global plan to the frame of the controller"); + return false; + } + + ROS_DEBUG("global plan size: %lu", global_plan_.size()); + publishPlan(global_plan_, global_plan_pub_); + return true; + } + + bool PoseFollower::isGoalReached(){ + return goal_reached_time_ + ros::Duration(tolerance_timeout_) < ros::Time::now() && stopped(); + } + + geometry_msgs::Twist PoseFollower::diff2D(const geometry_msgs::Pose& pose1_msg, + const geometry_msgs::Pose& pose2_msg) + { + tf2::Transform pose1, pose2; + tf2::convert(pose1_msg, pose1); + tf2::convert(pose2_msg, pose2); + geometry_msgs::Twist res; + tf2::Transform diff = pose2.inverse() * pose1; + res.linear.x = diff.getOrigin().x(); + res.linear.y = diff.getOrigin().y(); + res.angular.z = tf2::getYaw(diff.getRotation()); + + if(holonomic_ || (fabs(res.linear.x) <= tolerance_trans_ && fabs(res.linear.y) <= tolerance_trans_)) + return res; + + //in the case that we're not rotating to our goal position and we have a non-holonomic robot + //we'll need to command a rotational velocity that will help us reach our desired heading + + //we want to compute a goal based on the heading difference between our pose and the target + double yaw_diff = headingDiff(pose1.getOrigin().x(), pose1.getOrigin().y(), + pose2.getOrigin().x(), pose2.getOrigin().y(), tf2::getYaw(pose2.getRotation())); + + //we'll also check if we can move more effectively backwards + if (allow_backwards_) + { + double neg_yaw_diff = headingDiff(pose1.getOrigin().x(), pose1.getOrigin().y(), + pose2.getOrigin().x(), pose2.getOrigin().y(), M_PI + tf2::getYaw(pose2.getRotation())); + + //check if its faster to just back up + if(fabs(neg_yaw_diff) < fabs(yaw_diff)){ + ROS_DEBUG("Negative is better: %.2f", neg_yaw_diff); + yaw_diff = neg_yaw_diff; + } + } + + //compute the desired quaterion + tf2::Quaternion rot_diff; + rot_diff.setRPY(0.0, 0.0, yaw_diff); + tf2::Quaternion rot = pose2.getRotation() * rot_diff; + tf2::Transform new_pose = pose1; + new_pose.setRotation(rot); + + diff = pose2.inverse() * new_pose; + res.linear.x = diff.getOrigin().x(); + res.linear.y = diff.getOrigin().y(); + res.angular.z = tf2::getYaw(diff.getRotation()); + return res; + } + + + geometry_msgs::Twist PoseFollower::limitTwist(const geometry_msgs::Twist& twist) + { + geometry_msgs::Twist res = twist; + res.linear.x *= K_trans_; + if(!holonomic_) + res.linear.y = 0.0; + else + res.linear.y *= K_trans_; + res.angular.z *= K_rot_; + + //if turn_in_place_first is true, see if we need to rotate in place to face our goal first + if (turn_in_place_first_ && fabs(twist.angular.z) > max_heading_diff_before_moving_) + { + res.linear.x = 0; + res.linear.y = 0; + if (fabs(res.angular.z) > max_vel_th_) res.angular.z = max_vel_th_ * sign(res.angular.z); + if (fabs(res.angular.z) < min_in_place_vel_th_) res.angular.z = min_in_place_vel_th_ * sign(res.angular.z); + return res; + } + + //make sure to bound things by our velocity limits + double lin_overshoot = sqrt(res.linear.x * res.linear.x + res.linear.y * res.linear.y) / max_vel_lin_; + double lin_undershoot = min_vel_lin_ / sqrt(res.linear.x * res.linear.x + res.linear.y * res.linear.y); + if (lin_overshoot > 1.0) + { + res.linear.x /= lin_overshoot; + res.linear.y /= lin_overshoot; + } + + //we only want to enforce a minimum velocity if we're not rotating in place + if(lin_undershoot > 1.0) + { + res.linear.x *= lin_undershoot; + res.linear.y *= lin_undershoot; + } + + if (fabs(res.angular.z) > max_vel_th_) res.angular.z = max_vel_th_ * sign(res.angular.z); + if (fabs(res.angular.z) < min_vel_th_) res.angular.z = min_vel_th_ * sign(res.angular.z); + if (std::isnan(res.linear.x)) + res.linear.x = 0.0; + if (std::isnan(res.linear.y)) + res.linear.y = 0.0; + + //we want to check for whether or not we're desired to rotate in place + if(sqrt(twist.linear.x * twist.linear.x + twist.linear.y * twist.linear.y) < in_place_trans_vel_){ + if (fabs(res.angular.z) < min_in_place_vel_th_) res.angular.z = min_in_place_vel_th_ * sign(res.angular.z); + res.linear.x = 0.0; + res.linear.y = 0.0; + } + + ROS_DEBUG("Angular command %f", res.angular.z); + return res; + } + + bool PoseFollower::transformGlobalPlan(const tf2_ros::Buffer& tf, const std::vector& global_plan, + const costmap_2d::Costmap2DROS& costmap, const std::string& global_frame, + std::vector& transformed_plan){ + const geometry_msgs::PoseStamped& plan_pose = global_plan[0]; + + transformed_plan.clear(); + + try{ + if (global_plan.empty()) + { + ROS_ERROR("Recieved plan with zero length"); + return false; + } + + geometry_msgs::TransformStamped transform; + transform = tf.lookupTransform(global_frame, ros::Time(), + plan_pose.header.frame_id, plan_pose.header.stamp, + plan_pose.header.frame_id); + tf2::Stamped tf_transform; + tf2::convert(transform, tf_transform); + + tf2::Stamped tf_pose; + geometry_msgs::PoseStamped newer_pose; + //now we'll transform until points are outside of our distance threshold + for(unsigned int i = 0; i < global_plan.size(); ++i){ + const geometry_msgs::PoseStamped& pose = global_plan[i]; + tf2::convert(pose, tf_pose); + tf_pose.setData(tf_transform * tf_pose); + tf_pose.stamp_ = tf_transform.stamp_; + tf_pose.frame_id_ = global_frame; + tf2::toMsg(tf_pose, newer_pose); + + transformed_plan.push_back(newer_pose); + } + } + catch(tf2::LookupException& ex) { + ROS_ERROR("No Transform available Error: %s\n", ex.what()); + return false; + } + catch(tf2::ConnectivityException& ex) { + ROS_ERROR("Connectivity Error: %s\n", ex.what()); + return false; + } + catch(tf2::ExtrapolationException& ex) { + ROS_ERROR("Extrapolation Error: %s\n", ex.what()); + if (!global_plan.empty()) + ROS_ERROR("Global Frame: %s Plan Frame size %d: %s\n", global_frame.c_str(), (unsigned int)global_plan.size(), global_plan[0].header.frame_id.c_str()); + + return false; + } + + return true; + } +}; diff --git a/navigations/robot_localization/.github/ISSUE_TEMPLATE/bug_report.md b/navigations/robot_localization/.github/ISSUE_TEMPLATE/bug_report.md new file mode 100755 index 0000000..85d1156 --- /dev/null +++ b/navigations/robot_localization/.github/ISSUE_TEMPLATE/bug_report.md @@ -0,0 +1,30 @@ +--- +name: Bug report +about: For filing confirmed bugs +title: '' +labels: bug +assignees: ayrton04 + +--- + + + +## Bug report + +**Required Info:** + +- Operating System: + - +- Installation type: + - +- Version or commit hash: + - + +#### Steps to reproduce issue + + +#### Expected behavior + +#### Actual behavior + +#### Additional information diff --git a/navigations/robot_localization/.github/ISSUE_TEMPLATE/feature_request.md b/navigations/robot_localization/.github/ISSUE_TEMPLATE/feature_request.md new file mode 100755 index 0000000..00937ff --- /dev/null +++ b/navigations/robot_localization/.github/ISSUE_TEMPLATE/feature_request.md @@ -0,0 +1,16 @@ +--- +name: Feature request +about: For requesting new features +title: '' +labels: feature request +assignees: ayrton04 + +--- + +## Feature request + +#### Feature description + + +#### Implementation considerations + diff --git a/navigations/robot_localization/.gitignore b/navigations/robot_localization/.gitignore new file mode 100755 index 0000000..581b015 --- /dev/null +++ b/navigations/robot_localization/.gitignore @@ -0,0 +1,4 @@ +doc/html +*.cproject +*.project +*.settings diff --git a/navigations/robot_localization/CHANGELOG.rst b/navigations/robot_localization/CHANGELOG.rst new file mode 100755 index 0000000..e028973 --- /dev/null +++ b/navigations/robot_localization/CHANGELOG.rst @@ -0,0 +1,311 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package robot_localization +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +2.7.4 (2022-07-27) +------------------ +* Fix odometry and acceleration processing pipeline (`#753 `_) +* Use default CXX, need to specify boost::placeholders::_1 instead of just _1 (`#750 `_) +* Fix odometry msgs with child frame other than baseLink (`#728 `_) +* update documentation (`#723 `_) +* Fix unused-parameter warning (`#721 `_) +* Fix tf lookup timestamp during map->odom publication (`#719 `_) +* UKF cleanup (`#671 `_) +* Added geographiclib to catkin exported depends (`#709 `_) +* Make the navsat tf frame name parametric (`#699 `_) +* Propagate the suppression of tf warnings (`#705 `_) +* Fix typo in base_link_frame_output name. (`#701 `_) +* Contributors: AR Dabbour, Carlos Agüero, Haoguang Yang, J.P.S, Joshua Owen, Leonardo Hemerly, Lucas Walter, Marcus Scheunemann, Stephen Williams, Tom Moore + +2.7.3 (2021-07-23) +------------------ +* Prevent node from crashing on invalid UTM zone, but throw ROS_ERROR to notify user (`#682 `_) +* changed geographiclib to tag (`#684 `_) +* Small formatting and content change (`#677 `_) +* Fixed state transition for sigma points. The state transition function for each sigma point now uses its sigma point's posteriori state instead of always the posteriori state. (`#628 `_) + Co-authored-by: jola6897 +* Contributors: John Stechschulte, Jonas, MCFurry, Vivek Mhatre + +2.7.2 (2021-06-03) +------------------ +* Also test for gamma conversion (`#647 `_) +* fix: Transform gravitation vector to IMU frame before removing acceleration (`#639 `_) +* Fixed a typo in validate filter output error message. (`#646 `_) +* Stick to the global utm_zone\_ when transforming gps to UTM (`#627 `_) + * Stick to the global utm_zone\_ when transforming gps to UTM +* UTM conversions using geographiclib (`#626 `_) + * Use GeographicLib for UTMtoLL conversions +* SHARED linking for Geographiclib (`#624 `_) + * remove GeographicLib specific linking option +* Fixing lat-long to UTM conversion (`#620 `_) + Thanks again for the report. I'll get this into `noetic-devel` and the relevant ROS2 branches. +* Removing xmlrpcpp dependency +* yaml-cpp using find_package as backup (`#618 `_) +* Add ${GeographicLib_LIBRARIES} to navsat_transform (`#617 `_) +* Contributors: Achmad Fathoni, Leonardo Hemerly, Paul Verhoeckx, Tim Clephas, Tobias Fischer, Tom Moore + +2.7.0 (2020-12-17) +------------------ +* Making repeated state publication optional (`#595 `_) +* Fix sign error in dFY_dP part of transferFunctionJacobian\_ (`#592 `_) +* Fix typo in navsat_transform_node.rst (`#588 `_) +* Fix issue caused by starting on uneven terrain (`#582 `_) +* Local Cartesian Option (`#575 `_) +* Fix frame id of imu in differential mode, closes `#482 `_. (`#522 `_) +* navsat_transform diagram to address `#550 `_ (`#570 `_) +* Increasing the minimum CMake version (`#573 `_) +* Contributors: Aleksander Bojda, David Jensen, James Baxter, Jeffrey Kane Johnson, Mabel Zhang, Ronald Ensing, Tom Moore + +2.6.8 (2020-06-03) +------------------ +* Adding conditional build dependencies (`#572 `_) +* Contributors: Tom Moore + +2.6.7 (2020-06-01) +------------------ +* Parameterizing transform failure warnings +* [melodic] Fix Windows build break. (`#557 `_) +* Contributors: Sean Yen, Tom Moore, florianspy + +2.6.5 (2019-08-08) +------------------ +* fix: wall time used when `use_sim_time` is true +* Created service for converting to / from lat long +* Fix bug with tf_prefix +* Adding new contribution to doc +* Add missing undocumented params +* Update wiki location +* Contributors: Andrew Grindstaff, Axel Mousset, Charles Brian Quinn, Oswin So, Tom Moore + +2.6.4 (2019-02-15) +------------------ +* Meridian convergence adjustment added to navsat_transform. +* Documentation changes +* Add broadcast_utm_transform_as_parent_frame +* Enable build optimisations if no build type configured. +* Contributors: G.A. vd. Hoorn, Pavlo Kolomiiets, diasdm + +2.6.3 (2019-01-14) +------------------ +* Rename odomBaseLinkTrans to baseLinkOdomTrans + Adhere to the naming convention Trans used for worldBaseLinkTrans and mapOdomTrans. +* Add const& to catch values to prevent the error: catching polymorphic type ‘class tf2::TransformException’ by value + And ZoneNumber by 0x3fU to prevent error: directive output may be truncated writing between 1 and 11 bytes into a region of size 4 +* Enabling the user to override the output child_frame_id +* Fixing Euler body-to-world transformations +* Whitespace +* fixing no datum service in melodic +* Contributors: Alexis schad, Matthew Jones, Tom Moore, thallerod + +2.6.2 (2018-10-25) +------------------ +* Fixing tests +* Contributors: Tom Moore + +2.6.1 (2018-10-25) +------------------ +* Adding more output for measurement history failures +* Adding filter processing toggle service +* Waiting for valid ROS time before starting navsat_transform_node +* Contributors: Tom Moore, stevemacenski + +2.6.0 (2018-07-27) +------------------ +* Moving to C++14, adding error flags, and fixing all warnings +* Contributors: Tom Moore + +2.5.2 (2018-04-11) +------------------ +* Add published accel topic to documentation +* adding log statements for nans in the invertable matrix +* Fixing issue with potential seg fault +* Contributors: Oleg Kalachev, Tom Moore, stevemacenski + +2.5.1 (2018-01-03) +------------------ +* Fixing CMakeLists +* Contributors: Tom Moore + +2.5.0 (2017-12-15) +------------------ +* Fixing datum precision +* Fixing timing variable +* Fixing state history reversion +* Fixing critical bug with dynamic process noise covariance +* Fix typo in reading Mahalanobis thresholds. +* Zero out rotation in GPS to base_link transform +* Update xmlrpcpp includes for Indigo support +* Removing lastUpdateTime +* Fixing timestamps in map->odom transform +* Simplify enabledAtStartup logic +* Add std_srvs dependency +* Add enabling service +* Ensure all raw sensor input orientations are normalized even if messages are not +* Install params directory. +* Add robot localization estimator +* Adding nodelet support +* Contributors: Jacob Perron, Jacob Seibert, Jiri Hubacek, Mike Purvis, Miquel Massot, Pavlo Kolomiiets, Rein Appeldoorn, Rokus Ottervanger, Simon Gene Gottlieb, Tom Moore, stevemacenski + +2.4.0 (2017-06-12) +------------------ +* Updated documentation +* Added reset_on_time_jump option +* Added feature to optionally publish utm frame as parent in navsat_transform_node +* Moved global callback queue reset +* Added initial_state parameter and documentation +* Fixed ac/deceleration gains default logic +* Added gravity parameter +* Added delay and throttle if tf lookup fails +* Fixed UKF IMUTwistBasicIO test +* Added transform_timeout parameter +* Set gps_odom timestamp before tf2 lookuptransform +* Removed non-portable sincos calls +* Simplified logic to account for correlated error +* Added dynamic process noise covariance calculation +* Fixed catkin_package Eigen warning +* Added optional publication of acceleration state +* Contributors: Brian Gerkey, Enrique Fernandez, Jochen Sprickerhof, Rein Appeldoorn, Simon Gene Gottlieb, Tom Moore + +2.3.1 (2016-10-27) +------------------ +* Adding gitignore +* Adding remaining wiki pages +* Adding config and prep pages +* Adding navsat_transform_node documentation +* use_odometry_yaw fix for n_t_n +* Fixing issue with manual pose reset when history is not empty +* Getting inverse transform when looking up robot's pose. +* Sphinx documentation +* Removing forward slashes from navsat_transform input topics for template launch file +* Adding example launch and parameter files for a two-level EKF setup with navsat_transform_node +* Adding yaml file for navsat_transform_node, and moving parameter documentation to it. +* Updating EKF and UKF parameter templates with usage comments +* Contributors: Tom Moore, asimay + +2.3.0 (2016-07-28) +------------------ +* Fixed issues with datum usage and frame_ids +* Fixed comment for wait_for_datum +* Fixing issue with non-zero navsat sensor orientation offsets +* Fixing issue with base_link->gps transform wrecking the 'true' UTM position computation +* Using correct covariance for filtered GPS +* Fixed unitialized odometry covariance bug +* Added filter history and measurement queue behavior +* Changing output timestamp to more accurately use the time stamp of the most recently-processed measurement +* Added TcpNoDelay() +* Added parameter to make transform publishing optional +* Fixed differential handling for pose data so that it doesn't care about the message's frame_id +* Updated UKF config and launch +* Added a test case for the timestamp diagnostics +* Added reporting of bad timestamps via diagnostics +* Updated tests to match new method signatures +* Added control term +* Added smoothing capability for delayed measurements +* Making variables in navsat_transform conform to ROS coding standards +* Contributors: Adel Fakih, Ivor Wanders, Marc Essinger, Tobias Tueylue, Tom Moore + +2.2.3 (2016-04-24) +------------------ +* Cleaning up callback data structure and callbacks and updating doxygen comments in headers +* Removing MessageFilters +* Removing deprecated parameters +* Adding the ability to handle GPS offsets from the vehicle's origin +* Cleaning up navsat_transform.h +* Making variables in navsat_transform conform to ROS coding standards + +2.2.2 (2016-02-04) +------------------ +* Updating trig functions to use sincos for efficiency +* Updating licensing information and adding Eigen MPL-only flag +* Added state to imu frame transformation +* Using state orientation if imu orientation is missing +* Manually adding second spin for odometry and IMU data that is passed to message filters +* Reducing delay between measurement reception and filter output +* Zero altitute in intital transform too, when zero altitude param is set +* Fixing regression with conversion back to GPS coordinates +* Switched cropping of orientation data in inovationSubset with mahalanobis check to prevent excluding measurements with orientations bigger/smaller than ± PI +* Fix Jacobian for EKF. +* Removing warning about orientation variables when only their velocities are measured +* Checking for -1 in IMU covariances and ignoring relevant message data +* roslint and catkin_lint applied +* Adding base_link to datum specification, and fixing bug with order of measurement handling when a datum is specified. Also added check to make sure IMU data is transformable before using it. +* Contributors: Adnan Ademovic, Jit Ray Chowdhury, Philipp Tscholl, Tom Moore, ayrton04, kphil + +2.2.1 (2015-05-27) +------------------ +* Fixed handling of IMU data w.r.t. differential mode and relative mode + +2.2.0 (2015-05-22) +------------------ +* Added tf2-friendly tf_prefix appending +* Corrected for IMU orientation in navsat_transform +* Fixed issue with out-of-order measurements and pose resets +* Nodes now assume ENU standard for yaw data +* Removed gps_common dependency +* Adding option to navsat_transform_node that enables the use of the heading from the odometry message instead of an IMU. +* Changed frame_id used in setPoseCallback to be the world_frame +* Optimized Eigen arithmetic for signficiant performance boost +* Migrated to tf2 +* Code refactoring and reorganization +* Removed roll and pitch from navsat_transform calculations +* Fixed transform for IMU data to better support mounting IMUs in non-standard orientations +* Added feature to navsat_transform_node whereby filtered odometry data can be coverted back into navsat data +* Added a parameter to allow future dating the world_frame->base_link_frame transform. +* Removed deprecated differential setting handler +* Added relative mode +* Updated and improved tests +* Fixing source frame_id in pose data handling +* Added initial covariance parameter +* Fixed bug in covariance copyinh +* Added parameters for topic queue sizes +* Improved motion model's handling of angular velocities when robot has non-zero roll and pitch +* Changed the way differential measurements are handled +* Added diagnostics + +2.1.7 (2015-01-05) +------------------ +* Added some checks to eliminate unnecessary callbacks +* Updated launch file templates +* Added measurement outlier rejection +* Added failure callbacks for tf message filters +* Added optional broadcast of world_frame->utm transform for navsat_transform_node +* Bug fixes for differential mode and handling of Z acceleration in 2D mode + +2.1.6 (2014-11-06) +------------------ +* Added unscented Kalman filter (UKF) localization node +* Fixed map->odom tf calculation +* Acceleration data from IMUs is now used in computing the state estimate +* Added 2D mode + +2.1.5 (2014-10-07) +------------------ +* Changed initial estimate error covariance to be much smaller +* Fixed some debug output +* Added test suite +* Better compliance with REP-105 +* Fixed differential measurement handling +* Implemented message filters +* Added navsat_transform_node + +2.1.4 (2014-08-22) +------------------ +* Adding utm_transform_node to install targets + +2.1.3 (2014-06-22) +------------------ +* Some changes to ease GPS integration +* Addition of differential integration of pose data +* Some documentation cleanup +* Added UTM transform node and launch file +* Bug fixes + +2.1.2 (2014-04-11) +------------------ +* Updated covariance correction formulation to "Joseph form" to improve filter stability. +* Implemented new versioning scheme. + +2.1.1 (2014-04-11) +------------------ +* Added cmake_modules dependency for Eigen support, and added include to silence boost::signals warning from tf include + diff --git a/navigations/robot_localization/CMakeLists.txt b/navigations/robot_localization/CMakeLists.txt new file mode 100755 index 0000000..cc7f334 --- /dev/null +++ b/navigations/robot_localization/CMakeLists.txt @@ -0,0 +1,354 @@ +cmake_minimum_required(VERSION 3.0.2) +project(robot_localization) + +if(NOT CMAKE_CONFIGURATION_TYPES AND NOT CMAKE_BUILD_TYPE) + message("${PROJECT_NAME}: You did not request a specific build type: selecting 'RelWithDebInfo'.") + set(CMAKE_BUILD_TYPE RelWithDebInfo) +endif() + +find_package(catkin REQUIRED COMPONENTS + angles + diagnostic_msgs + diagnostic_updater + eigen_conversions + geographic_msgs + geometry_msgs + message_filters + message_generation + nav_msgs + nodelet + roscpp + roslint + sensor_msgs + std_msgs + std_srvs + tf2 + tf2_geometry_msgs + tf2_ros) + +find_package(PkgConfig REQUIRED) +pkg_check_modules(YAML_CPP yaml-cpp) +if(NOT YAML_CPP_FOUND) + find_package(yaml-cpp REQUIRED) +endif() + + +# Geographiclib installs FindGeographicLib.cmake to this non-standard location +set(CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH} "/usr/share/cmake/geographiclib/") +find_package(GeographicLib REQUIRED) + +# Attempt to find Eigen using its own CMake module. +# If that fails, fall back to cmake_modules package. +find_package(Eigen3) +set(EIGEN_PACKAGE EIGEN3) +if(NOT EIGEN3_FOUND) + find_package(cmake_modules REQUIRED) + find_package(Eigen REQUIRED) + set(EIGEN3_INCLUDE_DIRS ${EIGEN_INCLUDE_DIRS}) + set(EIGEN3_LIBRARIES ${EIGEN_LIBRARIES}) + set(EIGEN_PACKAGE Eigen) +endif() + +if(NOT MSVC) + set_directory_properties(PROPERTIES COMPILE_OPTIONS "-Wall;-Werror") +endif() +add_definitions(-DEIGEN_NO_DEBUG -DEIGEN_MPL2_ONLY) + +set(ROSLINT_CPP_OPTS "--filter=-build/c++11,-runtime/references") +roslint_cpp() + +################################### +## catkin specific configuration ## +################################### +add_service_files( + FILES + GetState.srv + SetDatum.srv + SetPose.srv + SetUTMZone.srv + ToggleFilterProcessing.srv + FromLL.srv + ToLL.srv +) + +generate_messages( + DEPENDENCIES + geographic_msgs + geometry_msgs + std_msgs +) + +catkin_package( + INCLUDE_DIRS + include + LIBRARIES + ekf + ekf_localization_nodelet + filter_base + filter_utilities + navsat_transform + navsat_transform_nodelet + ros_filter + ros_filter_utilities + robot_localization_estimator + ros_robot_localization_listener + ukf + ukf_localization_nodelet + CATKIN_DEPENDS + angles + cmake_modules + diagnostic_msgs + diagnostic_updater + eigen_conversions + geographic_msgs + geometry_msgs + message_filters + message_runtime + nav_msgs + roscpp + sensor_msgs + std_msgs + std_srvs + tf2 + tf2_geometry_msgs + tf2_ros + DEPENDS + ${EIGEN_PACKAGE} + GeographicLib + YAML_CPP +) + +########### +## Build ## +########### + +include_directories( + include + ${catkin_INCLUDE_DIRS} + ${EIGEN3_INCLUDE_DIRS} + ${YAML_CPP_INCLUDE_DIRS}) + +link_directories(${YAML_CPP_LIBRARY_DIRS}) + +# Library definitions +add_library(filter_utilities src/filter_utilities.cpp) +add_library(filter_base src/filter_base.cpp) +add_library(ekf src/ekf.cpp) +add_library(ukf src/ukf.cpp) +add_library(robot_localization_estimator src/robot_localization_estimator.cpp) +add_library(ros_robot_localization_listener src/ros_robot_localization_listener.cpp) +add_library(ros_filter_utilities src/ros_filter_utilities.cpp) +add_library(ros_filter src/ros_filter.cpp) +add_library(navsat_transform src/navsat_transform.cpp) +add_library(ekf_localization_nodelet src/ekf_localization_nodelet.cpp) +add_library(ukf_localization_nodelet src/ukf_localization_nodelet.cpp) +add_library(navsat_transform_nodelet src/navsat_transform_nodelet.cpp) + +# Executables +add_executable(ekf_localization_node src/ekf_localization_node.cpp) +add_executable(ukf_localization_node src/ukf_localization_node.cpp) +add_executable(navsat_transform_node src/navsat_transform_node.cpp) +add_executable(robot_localization_listener_node src/robot_localization_listener_node.cpp) + +# Dependencies +add_dependencies(filter_base ${PROJECT_NAME}_gencpp) +add_dependencies(navsat_transform ${PROJECT_NAME}_gencpp) +add_dependencies(robot_localization_listener_node ${PROJECT_NAME}_gencpp) + +# Linking +target_link_libraries(ros_filter_utilities ${catkin_LIBRARIES} ${EIGEN3_LIBRARIES}) +target_link_libraries(filter_utilities ${catkin_LIBRARIES} ${EIGEN3_LIBRARIES}) +target_link_libraries(filter_base filter_utilities ${catkin_LIBRARIES} ${EIGEN3_LIBRARIES}) +target_link_libraries(ekf filter_base ${catkin_LIBRARIES} ${EIGEN3_LIBRARIES}) +target_link_libraries(ukf filter_base ${catkin_LIBRARIES} ${EIGEN3_LIBRARIES}) +target_link_libraries(ros_filter ekf ukf ros_filter_utilities ${catkin_LIBRARIES} ${EIGEN3_LIBRARIES}) +target_link_libraries(robot_localization_estimator filter_utilities filter_base ekf ukf ${EIGEN3_LIBRARIES}) +target_link_libraries(ros_robot_localization_listener robot_localization_estimator ros_filter_utilities + ${catkin_LIBRARIES} ${EIGEN3_LIBRARIES} ${YAML_CPP_LIBRARIES}) +target_link_libraries(robot_localization_listener_node ros_robot_localization_listener ${catkin_LIBRARIES}) +target_link_libraries(ekf_localization_node ros_filter ${catkin_LIBRARIES}) +target_link_libraries(ekf_localization_nodelet ros_filter ${catkin_LIBRARIES}) +target_link_libraries(ukf_localization_node ros_filter ${catkin_LIBRARIES}) +target_link_libraries(ukf_localization_nodelet ros_filter ${catkin_LIBRARIES}) +target_link_libraries(navsat_transform filter_utilities ros_filter_utilities ${catkin_LIBRARIES} ${EIGEN3_LIBRARIES} ${GeographicLib_LIBRARIES}) +target_link_libraries(navsat_transform_node navsat_transform ${catkin_LIBRARIES} ${GeographicLib_LIBRARIES}) +target_link_libraries(navsat_transform_nodelet navsat_transform ${catkin_LIBRARIES} ${GeographicLib_LIBRARIES}) + +############# +## Install ## +############# + +## Mark executables and/or libraries for installation +install(TARGETS + ekf + ekf_localization_nodelet + filter_base + filter_utilities + navsat_transform + navsat_transform_nodelet + ros_filter + ros_filter_utilities + robot_localization_estimator + ros_robot_localization_listener + ukf + ukf_localization_nodelet + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) + +install(TARGETS + ekf_localization_node + navsat_transform_node + robot_localization_listener_node + ukf_localization_node + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) + +## Mark cpp header files for installation +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} + FILES_MATCHING PATTERN "*.h" + PATTERN ".svn" EXCLUDE) + +install(DIRECTORY launch/ + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch + FILES_MATCHING PATTERN "*.launch") + +install(DIRECTORY params/ + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/params) + +install(FILES + LICENSE + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) +install(FILES nodelet_plugins.xml + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) + +############# +## Testing ## +############# + +if (CATKIN_ENABLE_TESTING) + + roslint_add_test() + + # Not really necessary, but it will cause the build to fail if it's + # missing, rather than failing once the tests are being executed + find_package(rosbag REQUIRED) + find_package(rostest REQUIRED) + + #### FILTER BASE TESTS #### + catkin_add_gtest(filter_base-test test/test_filter_base.cpp) + target_link_libraries(filter_base-test filter_base ${catkin_LIBRARIES}) + + # This test uses ekf_localization node for convenience. + add_rostest_gtest(test_filter_base_diagnostics_timestamps + test/test_filter_base_diagnostics_timestamps.test + test/test_filter_base_diagnostics_timestamps.cpp) + target_link_libraries(test_filter_base_diagnostics_timestamps ${catkin_LIBRARIES} ${rostest_LIBRARIES}) + add_dependencies(test_filter_base_diagnostics_timestamps ekf_localization_node) + + #### EKF TESTS ##### + add_rostest_gtest(test_ekf + test/test_ekf.test + test/test_ekf.cpp) + target_link_libraries(test_ekf ros_filter ekf ${catkin_LIBRARIES} ${rostest_LIBRARIES}) + + add_rostest_gtest(test_ekf_localization_node_interfaces + test/test_ekf_localization_node_interfaces.test + test/test_ekf_localization_node_interfaces.cpp) + target_link_libraries(test_ekf_localization_node_interfaces ros_filter ekf ${catkin_LIBRARIES} ${rostest_LIBRARIES}) + add_dependencies(test_ekf_localization_node_interfaces ekf_localization_node) + + add_rostest_gtest(test_ekf_localization_node_bag1 + test/test_ekf_localization_node_bag1.test + test/test_localization_node_bag_pose_tester.cpp) + target_link_libraries(test_ekf_localization_node_bag1 ${catkin_LIBRARIES} ${rostest_LIBRARIES}) + add_dependencies(test_ekf_localization_node_bag1 ekf_localization_node) + + add_rostest_gtest(test_ekf_localization_node_bag2 + test/test_ekf_localization_node_bag2.test + test/test_localization_node_bag_pose_tester.cpp) + target_link_libraries(test_ekf_localization_node_bag2 ${catkin_LIBRARIES} ${rostest_LIBRARIES}) + add_dependencies(test_ekf_localization_node_bag2 ekf_localization_node) + + add_rostest_gtest(test_ekf_localization_node_bag3 + test/test_ekf_localization_node_bag3.test + test/test_localization_node_bag_pose_tester.cpp) + target_link_libraries(test_ekf_localization_node_bag3 ${catkin_LIBRARIES} ${rostest_LIBRARIES}) + add_dependencies(test_ekf_localization_node_bag3 ekf_localization_node) + + add_rostest_gtest(test_ekf_localization_nodelet_bag1 + test/test_ekf_localization_nodelet_bag1.test + test/test_localization_node_bag_pose_tester.cpp) + target_link_libraries(test_ekf_localization_nodelet_bag1 ${catkin_LIBRARIES} ${rostest_LIBRARIES}) + add_dependencies(test_ekf_localization_nodelet_bag1 ekf_localization_nodelet) + + #### UKF TESTS ##### + add_rostest_gtest(test_ukf + test/test_ukf.test + test/test_ukf.cpp) + target_link_libraries(test_ukf ros_filter ukf ${catkin_LIBRARIES} ${rostest_LIBRARIES}) + + add_rostest_gtest(test_ukf_localization_node_interfaces + test/test_ukf_localization_node_interfaces.test + test/test_ukf_localization_node_interfaces.cpp) + target_link_libraries(test_ukf_localization_node_interfaces ${catkin_LIBRARIES} ${rostest_LIBRARIES}) + add_dependencies(test_ukf_localization_node_interfaces ukf_localization_node) + + add_rostest_gtest(test_ukf_localization_node_bag1 + test/test_ukf_localization_node_bag1.test + test/test_localization_node_bag_pose_tester.cpp) + target_link_libraries(test_ukf_localization_node_bag1 ${catkin_LIBRARIES} ${rostest_LIBRARIES}) + add_dependencies(test_ukf_localization_node_bag1 ukf_localization_node) + + add_rostest_gtest(test_ukf_localization_node_bag2 + test/test_ukf_localization_node_bag2.test + test/test_localization_node_bag_pose_tester.cpp) + target_link_libraries(test_ukf_localization_node_bag2 ${catkin_LIBRARIES} ${rostest_LIBRARIES}) + add_dependencies(test_ukf_localization_node_bag2 ukf_localization_node) + + add_rostest_gtest(test_ukf_localization_node_bag3 + test/test_ukf_localization_node_bag3.test + test/test_localization_node_bag_pose_tester.cpp) + target_link_libraries(test_ukf_localization_node_bag3 ${catkin_LIBRARIES} ${rostest_LIBRARIES}) + add_dependencies(test_ukf_localization_node_bag3 ukf_localization_node) + + add_rostest_gtest(test_ukf_localization_nodelet_bag1 + test/test_ukf_localization_nodelet_bag1.test + test/test_localization_node_bag_pose_tester.cpp) + target_link_libraries(test_ukf_localization_nodelet_bag1 ${catkin_LIBRARIES} ${rostest_LIBRARIES}) + add_dependencies(test_ukf_localization_nodelet_bag1 ukf_localization_nodelet) + + #### RLE/RLL TESTS ##### + add_rostest_gtest(test_robot_localization_estimator + test/test_robot_localization_estimator.test + test/test_robot_localization_estimator.cpp) + target_link_libraries(test_robot_localization_estimator + robot_localization_estimator + ${catkin_LIBRARIES} + ${rostest_LIBRARIES}) + + add_executable(test_ros_robot_localization_listener_publisher test/test_ros_robot_localization_listener_publisher.cpp) + target_link_libraries(test_ros_robot_localization_listener_publisher + ${catkin_LIBRARIES}) + + add_rostest_gtest(test_ros_robot_localization_listener + test/test_ros_robot_localization_listener.test + test/test_ros_robot_localization_listener.cpp) + target_link_libraries(test_ros_robot_localization_listener + ros_robot_localization_listener + ${catkin_LIBRARIES} + ${rostest_LIBRARIES}) + + #### NAVSAT CONVERSION TESTS #### + catkin_add_gtest(navsat_conversions-test test/test_navsat_conversions.cpp) + target_link_libraries(navsat_conversions-test navsat_transform ${catkin_LIBRARIES}) + + #### NAVSAT TRANSFORM TESTS #### + add_rostest_gtest(test_navsat_transform + test/test_navsat_transform.test + test/test_navsat_transform.cpp) + target_link_libraries(test_navsat_transform ${catkin_LIBRARIES} ${rostest_LIBRARIES}) + +endif() diff --git a/navigations/robot_localization/LICENSE b/navigations/robot_localization/LICENSE new file mode 100755 index 0000000..45521a4 --- /dev/null +++ b/navigations/robot_localization/LICENSE @@ -0,0 +1,68 @@ +All code within the robot_localization package that was developed by Charles +River Analytics is released under the BSD license: + +Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc. +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name of the {organization} nor the names of its + contributors may be used to endorse or promote products derived from + this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +========================================================================== + +The robot_localization package also makes use of code written by The University +of Texas at Austin. This code is released under a modified BSD license: + +Copyright (C) 2010 Austin Robot Technology, and others +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions +are met: + +* Redistributions of source code must retain the above copyright + notice, this list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above + copyright notice, this list of conditions and the following + disclaimer in the documentation and/or other materials provided + with the distribution. + +* Neither the names of the University of Texas at Austin, nor + Austin Robot Technology, nor the names of other contributors may + be used to endorse or promote products derived from this + software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +"AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +POSSIBILITY OF SUCH DAMAGE. diff --git a/navigations/robot_localization/README.md b/navigations/robot_localization/README.md new file mode 100755 index 0000000..2220d2f --- /dev/null +++ b/navigations/robot_localization/README.md @@ -0,0 +1,6 @@ +robot_localization +================== + +robot_localization is a package of nonlinear state estimation nodes. The package was developed by Charles River Analytics, Inc. + +Please see documentation here: http://docs.ros.org/noetic/api/robot_localization/html/index.html diff --git a/navigations/robot_localization/doc/.templates/full_globaltoc.html b/navigations/robot_localization/doc/.templates/full_globaltoc.html new file mode 100755 index 0000000..ba7226e --- /dev/null +++ b/navigations/robot_localization/doc/.templates/full_globaltoc.html @@ -0,0 +1,10 @@ +

{{ _('Table Of Contents') }}

+{{ toctree(includehidden=True) }} + +

{{ _('Further Documentation') }}

+ + + diff --git a/navigations/robot_localization/doc/CHANGELOG.rst b/navigations/robot_localization/doc/CHANGELOG.rst new file mode 100755 index 0000000..e028973 --- /dev/null +++ b/navigations/robot_localization/doc/CHANGELOG.rst @@ -0,0 +1,311 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package robot_localization +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +2.7.4 (2022-07-27) +------------------ +* Fix odometry and acceleration processing pipeline (`#753 `_) +* Use default CXX, need to specify boost::placeholders::_1 instead of just _1 (`#750 `_) +* Fix odometry msgs with child frame other than baseLink (`#728 `_) +* update documentation (`#723 `_) +* Fix unused-parameter warning (`#721 `_) +* Fix tf lookup timestamp during map->odom publication (`#719 `_) +* UKF cleanup (`#671 `_) +* Added geographiclib to catkin exported depends (`#709 `_) +* Make the navsat tf frame name parametric (`#699 `_) +* Propagate the suppression of tf warnings (`#705 `_) +* Fix typo in base_link_frame_output name. (`#701 `_) +* Contributors: AR Dabbour, Carlos Agüero, Haoguang Yang, J.P.S, Joshua Owen, Leonardo Hemerly, Lucas Walter, Marcus Scheunemann, Stephen Williams, Tom Moore + +2.7.3 (2021-07-23) +------------------ +* Prevent node from crashing on invalid UTM zone, but throw ROS_ERROR to notify user (`#682 `_) +* changed geographiclib to tag (`#684 `_) +* Small formatting and content change (`#677 `_) +* Fixed state transition for sigma points. The state transition function for each sigma point now uses its sigma point's posteriori state instead of always the posteriori state. (`#628 `_) + Co-authored-by: jola6897 +* Contributors: John Stechschulte, Jonas, MCFurry, Vivek Mhatre + +2.7.2 (2021-06-03) +------------------ +* Also test for gamma conversion (`#647 `_) +* fix: Transform gravitation vector to IMU frame before removing acceleration (`#639 `_) +* Fixed a typo in validate filter output error message. (`#646 `_) +* Stick to the global utm_zone\_ when transforming gps to UTM (`#627 `_) + * Stick to the global utm_zone\_ when transforming gps to UTM +* UTM conversions using geographiclib (`#626 `_) + * Use GeographicLib for UTMtoLL conversions +* SHARED linking for Geographiclib (`#624 `_) + * remove GeographicLib specific linking option +* Fixing lat-long to UTM conversion (`#620 `_) + Thanks again for the report. I'll get this into `noetic-devel` and the relevant ROS2 branches. +* Removing xmlrpcpp dependency +* yaml-cpp using find_package as backup (`#618 `_) +* Add ${GeographicLib_LIBRARIES} to navsat_transform (`#617 `_) +* Contributors: Achmad Fathoni, Leonardo Hemerly, Paul Verhoeckx, Tim Clephas, Tobias Fischer, Tom Moore + +2.7.0 (2020-12-17) +------------------ +* Making repeated state publication optional (`#595 `_) +* Fix sign error in dFY_dP part of transferFunctionJacobian\_ (`#592 `_) +* Fix typo in navsat_transform_node.rst (`#588 `_) +* Fix issue caused by starting on uneven terrain (`#582 `_) +* Local Cartesian Option (`#575 `_) +* Fix frame id of imu in differential mode, closes `#482 `_. (`#522 `_) +* navsat_transform diagram to address `#550 `_ (`#570 `_) +* Increasing the minimum CMake version (`#573 `_) +* Contributors: Aleksander Bojda, David Jensen, James Baxter, Jeffrey Kane Johnson, Mabel Zhang, Ronald Ensing, Tom Moore + +2.6.8 (2020-06-03) +------------------ +* Adding conditional build dependencies (`#572 `_) +* Contributors: Tom Moore + +2.6.7 (2020-06-01) +------------------ +* Parameterizing transform failure warnings +* [melodic] Fix Windows build break. (`#557 `_) +* Contributors: Sean Yen, Tom Moore, florianspy + +2.6.5 (2019-08-08) +------------------ +* fix: wall time used when `use_sim_time` is true +* Created service for converting to / from lat long +* Fix bug with tf_prefix +* Adding new contribution to doc +* Add missing undocumented params +* Update wiki location +* Contributors: Andrew Grindstaff, Axel Mousset, Charles Brian Quinn, Oswin So, Tom Moore + +2.6.4 (2019-02-15) +------------------ +* Meridian convergence adjustment added to navsat_transform. +* Documentation changes +* Add broadcast_utm_transform_as_parent_frame +* Enable build optimisations if no build type configured. +* Contributors: G.A. vd. Hoorn, Pavlo Kolomiiets, diasdm + +2.6.3 (2019-01-14) +------------------ +* Rename odomBaseLinkTrans to baseLinkOdomTrans + Adhere to the naming convention Trans used for worldBaseLinkTrans and mapOdomTrans. +* Add const& to catch values to prevent the error: catching polymorphic type ‘class tf2::TransformException’ by value + And ZoneNumber by 0x3fU to prevent error: directive output may be truncated writing between 1 and 11 bytes into a region of size 4 +* Enabling the user to override the output child_frame_id +* Fixing Euler body-to-world transformations +* Whitespace +* fixing no datum service in melodic +* Contributors: Alexis schad, Matthew Jones, Tom Moore, thallerod + +2.6.2 (2018-10-25) +------------------ +* Fixing tests +* Contributors: Tom Moore + +2.6.1 (2018-10-25) +------------------ +* Adding more output for measurement history failures +* Adding filter processing toggle service +* Waiting for valid ROS time before starting navsat_transform_node +* Contributors: Tom Moore, stevemacenski + +2.6.0 (2018-07-27) +------------------ +* Moving to C++14, adding error flags, and fixing all warnings +* Contributors: Tom Moore + +2.5.2 (2018-04-11) +------------------ +* Add published accel topic to documentation +* adding log statements for nans in the invertable matrix +* Fixing issue with potential seg fault +* Contributors: Oleg Kalachev, Tom Moore, stevemacenski + +2.5.1 (2018-01-03) +------------------ +* Fixing CMakeLists +* Contributors: Tom Moore + +2.5.0 (2017-12-15) +------------------ +* Fixing datum precision +* Fixing timing variable +* Fixing state history reversion +* Fixing critical bug with dynamic process noise covariance +* Fix typo in reading Mahalanobis thresholds. +* Zero out rotation in GPS to base_link transform +* Update xmlrpcpp includes for Indigo support +* Removing lastUpdateTime +* Fixing timestamps in map->odom transform +* Simplify enabledAtStartup logic +* Add std_srvs dependency +* Add enabling service +* Ensure all raw sensor input orientations are normalized even if messages are not +* Install params directory. +* Add robot localization estimator +* Adding nodelet support +* Contributors: Jacob Perron, Jacob Seibert, Jiri Hubacek, Mike Purvis, Miquel Massot, Pavlo Kolomiiets, Rein Appeldoorn, Rokus Ottervanger, Simon Gene Gottlieb, Tom Moore, stevemacenski + +2.4.0 (2017-06-12) +------------------ +* Updated documentation +* Added reset_on_time_jump option +* Added feature to optionally publish utm frame as parent in navsat_transform_node +* Moved global callback queue reset +* Added initial_state parameter and documentation +* Fixed ac/deceleration gains default logic +* Added gravity parameter +* Added delay and throttle if tf lookup fails +* Fixed UKF IMUTwistBasicIO test +* Added transform_timeout parameter +* Set gps_odom timestamp before tf2 lookuptransform +* Removed non-portable sincos calls +* Simplified logic to account for correlated error +* Added dynamic process noise covariance calculation +* Fixed catkin_package Eigen warning +* Added optional publication of acceleration state +* Contributors: Brian Gerkey, Enrique Fernandez, Jochen Sprickerhof, Rein Appeldoorn, Simon Gene Gottlieb, Tom Moore + +2.3.1 (2016-10-27) +------------------ +* Adding gitignore +* Adding remaining wiki pages +* Adding config and prep pages +* Adding navsat_transform_node documentation +* use_odometry_yaw fix for n_t_n +* Fixing issue with manual pose reset when history is not empty +* Getting inverse transform when looking up robot's pose. +* Sphinx documentation +* Removing forward slashes from navsat_transform input topics for template launch file +* Adding example launch and parameter files for a two-level EKF setup with navsat_transform_node +* Adding yaml file for navsat_transform_node, and moving parameter documentation to it. +* Updating EKF and UKF parameter templates with usage comments +* Contributors: Tom Moore, asimay + +2.3.0 (2016-07-28) +------------------ +* Fixed issues with datum usage and frame_ids +* Fixed comment for wait_for_datum +* Fixing issue with non-zero navsat sensor orientation offsets +* Fixing issue with base_link->gps transform wrecking the 'true' UTM position computation +* Using correct covariance for filtered GPS +* Fixed unitialized odometry covariance bug +* Added filter history and measurement queue behavior +* Changing output timestamp to more accurately use the time stamp of the most recently-processed measurement +* Added TcpNoDelay() +* Added parameter to make transform publishing optional +* Fixed differential handling for pose data so that it doesn't care about the message's frame_id +* Updated UKF config and launch +* Added a test case for the timestamp diagnostics +* Added reporting of bad timestamps via diagnostics +* Updated tests to match new method signatures +* Added control term +* Added smoothing capability for delayed measurements +* Making variables in navsat_transform conform to ROS coding standards +* Contributors: Adel Fakih, Ivor Wanders, Marc Essinger, Tobias Tueylue, Tom Moore + +2.2.3 (2016-04-24) +------------------ +* Cleaning up callback data structure and callbacks and updating doxygen comments in headers +* Removing MessageFilters +* Removing deprecated parameters +* Adding the ability to handle GPS offsets from the vehicle's origin +* Cleaning up navsat_transform.h +* Making variables in navsat_transform conform to ROS coding standards + +2.2.2 (2016-02-04) +------------------ +* Updating trig functions to use sincos for efficiency +* Updating licensing information and adding Eigen MPL-only flag +* Added state to imu frame transformation +* Using state orientation if imu orientation is missing +* Manually adding second spin for odometry and IMU data that is passed to message filters +* Reducing delay between measurement reception and filter output +* Zero altitute in intital transform too, when zero altitude param is set +* Fixing regression with conversion back to GPS coordinates +* Switched cropping of orientation data in inovationSubset with mahalanobis check to prevent excluding measurements with orientations bigger/smaller than ± PI +* Fix Jacobian for EKF. +* Removing warning about orientation variables when only their velocities are measured +* Checking for -1 in IMU covariances and ignoring relevant message data +* roslint and catkin_lint applied +* Adding base_link to datum specification, and fixing bug with order of measurement handling when a datum is specified. Also added check to make sure IMU data is transformable before using it. +* Contributors: Adnan Ademovic, Jit Ray Chowdhury, Philipp Tscholl, Tom Moore, ayrton04, kphil + +2.2.1 (2015-05-27) +------------------ +* Fixed handling of IMU data w.r.t. differential mode and relative mode + +2.2.0 (2015-05-22) +------------------ +* Added tf2-friendly tf_prefix appending +* Corrected for IMU orientation in navsat_transform +* Fixed issue with out-of-order measurements and pose resets +* Nodes now assume ENU standard for yaw data +* Removed gps_common dependency +* Adding option to navsat_transform_node that enables the use of the heading from the odometry message instead of an IMU. +* Changed frame_id used in setPoseCallback to be the world_frame +* Optimized Eigen arithmetic for signficiant performance boost +* Migrated to tf2 +* Code refactoring and reorganization +* Removed roll and pitch from navsat_transform calculations +* Fixed transform for IMU data to better support mounting IMUs in non-standard orientations +* Added feature to navsat_transform_node whereby filtered odometry data can be coverted back into navsat data +* Added a parameter to allow future dating the world_frame->base_link_frame transform. +* Removed deprecated differential setting handler +* Added relative mode +* Updated and improved tests +* Fixing source frame_id in pose data handling +* Added initial covariance parameter +* Fixed bug in covariance copyinh +* Added parameters for topic queue sizes +* Improved motion model's handling of angular velocities when robot has non-zero roll and pitch +* Changed the way differential measurements are handled +* Added diagnostics + +2.1.7 (2015-01-05) +------------------ +* Added some checks to eliminate unnecessary callbacks +* Updated launch file templates +* Added measurement outlier rejection +* Added failure callbacks for tf message filters +* Added optional broadcast of world_frame->utm transform for navsat_transform_node +* Bug fixes for differential mode and handling of Z acceleration in 2D mode + +2.1.6 (2014-11-06) +------------------ +* Added unscented Kalman filter (UKF) localization node +* Fixed map->odom tf calculation +* Acceleration data from IMUs is now used in computing the state estimate +* Added 2D mode + +2.1.5 (2014-10-07) +------------------ +* Changed initial estimate error covariance to be much smaller +* Fixed some debug output +* Added test suite +* Better compliance with REP-105 +* Fixed differential measurement handling +* Implemented message filters +* Added navsat_transform_node + +2.1.4 (2014-08-22) +------------------ +* Adding utm_transform_node to install targets + +2.1.3 (2014-06-22) +------------------ +* Some changes to ease GPS integration +* Addition of differential integration of pose data +* Some documentation cleanup +* Added UTM transform node and launch file +* Bug fixes + +2.1.2 (2014-04-11) +------------------ +* Updated covariance correction formulation to "Joseph form" to improve filter stability. +* Implemented new versioning scheme. + +2.1.1 (2014-04-11) +------------------ +* Added cmake_modules dependency for Eigen support, and added include to silence boost::signals warning from tf include + diff --git a/navigations/robot_localization/doc/Makefile b/navigations/robot_localization/doc/Makefile new file mode 100755 index 0000000..642efcf --- /dev/null +++ b/navigations/robot_localization/doc/Makefile @@ -0,0 +1,216 @@ +# Makefile for Sphinx documentation +# + +# You can set these variables from the command line. +SPHINXOPTS = +SPHINXBUILD = sphinx-build +PAPER = +BUILDDIR = .build + +# User-friendly check for sphinx-build +ifeq ($(shell which $(SPHINXBUILD) >/dev/null 2>&1; echo $$?), 1) +$(error The '$(SPHINXBUILD)' command was not found. Make sure you have Sphinx installed, then set the SPHINXBUILD environment variable to point to the full path of the '$(SPHINXBUILD)' executable. Alternatively you can add the directory with the executable to your PATH. If you don't have Sphinx installed, grab it from http://sphinx-doc.org/) +endif + +# Internal variables. +PAPEROPT_a4 = -D latex_paper_size=a4 +PAPEROPT_letter = -D latex_paper_size=letter +ALLSPHINXOPTS = -d $(BUILDDIR)/doctrees $(PAPEROPT_$(PAPER)) $(SPHINXOPTS) . +# the i18n builder cannot share the environment and doctrees with the others +I18NSPHINXOPTS = $(PAPEROPT_$(PAPER)) $(SPHINXOPTS) . + +.PHONY: help +help: + @echo "Please use \`make ' where is one of" + @echo " html to make standalone HTML files" + @echo " dirhtml to make HTML files named index.html in directories" + @echo " singlehtml to make a single large HTML file" + @echo " pickle to make pickle files" + @echo " json to make JSON files" + @echo " htmlhelp to make HTML files and a HTML help project" + @echo " qthelp to make HTML files and a qthelp project" + @echo " applehelp to make an Apple Help Book" + @echo " devhelp to make HTML files and a Devhelp project" + @echo " epub to make an epub" + @echo " latex to make LaTeX files, you can set PAPER=a4 or PAPER=letter" + @echo " latexpdf to make LaTeX files and run them through pdflatex" + @echo " latexpdfja to make LaTeX files and run them through platex/dvipdfmx" + @echo " text to make text files" + @echo " man to make manual pages" + @echo " texinfo to make Texinfo files" + @echo " info to make Texinfo files and run them through makeinfo" + @echo " gettext to make PO message catalogs" + @echo " changes to make an overview of all changed/added/deprecated items" + @echo " xml to make Docutils-native XML files" + @echo " pseudoxml to make pseudoxml-XML files for display purposes" + @echo " linkcheck to check all external links for integrity" + @echo " doctest to run all doctests embedded in the documentation (if enabled)" + @echo " coverage to run coverage check of the documentation (if enabled)" + +.PHONY: clean +clean: + rm -rf $(BUILDDIR)/* + +.PHONY: html +html: + $(SPHINXBUILD) -b html $(ALLSPHINXOPTS) $(BUILDDIR)/html + @echo + @echo "Build finished. The HTML pages are in $(BUILDDIR)/html." + +.PHONY: dirhtml +dirhtml: + $(SPHINXBUILD) -b dirhtml $(ALLSPHINXOPTS) $(BUILDDIR)/dirhtml + @echo + @echo "Build finished. The HTML pages are in $(BUILDDIR)/dirhtml." + +.PHONY: singlehtml +singlehtml: + $(SPHINXBUILD) -b singlehtml $(ALLSPHINXOPTS) $(BUILDDIR)/singlehtml + @echo + @echo "Build finished. The HTML page is in $(BUILDDIR)/singlehtml." + +.PHONY: pickle +pickle: + $(SPHINXBUILD) -b pickle $(ALLSPHINXOPTS) $(BUILDDIR)/pickle + @echo + @echo "Build finished; now you can process the pickle files." + +.PHONY: json +json: + $(SPHINXBUILD) -b json $(ALLSPHINXOPTS) $(BUILDDIR)/json + @echo + @echo "Build finished; now you can process the JSON files." + +.PHONY: htmlhelp +htmlhelp: + $(SPHINXBUILD) -b htmlhelp $(ALLSPHINXOPTS) $(BUILDDIR)/htmlhelp + @echo + @echo "Build finished; now you can run HTML Help Workshop with the" \ + ".hhp project file in $(BUILDDIR)/htmlhelp." + +.PHONY: qthelp +qthelp: + $(SPHINXBUILD) -b qthelp $(ALLSPHINXOPTS) $(BUILDDIR)/qthelp + @echo + @echo "Build finished; now you can run "qcollectiongenerator" with the" \ + ".qhcp project file in $(BUILDDIR)/qthelp, like this:" + @echo "# qcollectiongenerator $(BUILDDIR)/qthelp/robot_localization.qhcp" + @echo "To view the help file:" + @echo "# assistant -collectionFile $(BUILDDIR)/qthelp/robot_localization.qhc" + +.PHONY: applehelp +applehelp: + $(SPHINXBUILD) -b applehelp $(ALLSPHINXOPTS) $(BUILDDIR)/applehelp + @echo + @echo "Build finished. The help book is in $(BUILDDIR)/applehelp." + @echo "N.B. You won't be able to view it unless you put it in" \ + "~/Library/Documentation/Help or install it in your application" \ + "bundle." + +.PHONY: devhelp +devhelp: + $(SPHINXBUILD) -b devhelp $(ALLSPHINXOPTS) $(BUILDDIR)/devhelp + @echo + @echo "Build finished." + @echo "To view the help file:" + @echo "# mkdir -p $$HOME/.local/share/devhelp/robot_localization" + @echo "# ln -s $(BUILDDIR)/devhelp $$HOME/.local/share/devhelp/robot_localization" + @echo "# devhelp" + +.PHONY: epub +epub: + $(SPHINXBUILD) -b epub $(ALLSPHINXOPTS) $(BUILDDIR)/epub + @echo + @echo "Build finished. The epub file is in $(BUILDDIR)/epub." + +.PHONY: latex +latex: + $(SPHINXBUILD) -b latex $(ALLSPHINXOPTS) $(BUILDDIR)/latex + @echo + @echo "Build finished; the LaTeX files are in $(BUILDDIR)/latex." + @echo "Run \`make' in that directory to run these through (pdf)latex" \ + "(use \`make latexpdf' here to do that automatically)." + +.PHONY: latexpdf +latexpdf: + $(SPHINXBUILD) -b latex $(ALLSPHINXOPTS) $(BUILDDIR)/latex + @echo "Running LaTeX files through pdflatex..." + $(MAKE) -C $(BUILDDIR)/latex all-pdf + @echo "pdflatex finished; the PDF files are in $(BUILDDIR)/latex." + +.PHONY: latexpdfja +latexpdfja: + $(SPHINXBUILD) -b latex $(ALLSPHINXOPTS) $(BUILDDIR)/latex + @echo "Running LaTeX files through platex and dvipdfmx..." + $(MAKE) -C $(BUILDDIR)/latex all-pdf-ja + @echo "pdflatex finished; the PDF files are in $(BUILDDIR)/latex." + +.PHONY: text +text: + $(SPHINXBUILD) -b text $(ALLSPHINXOPTS) $(BUILDDIR)/text + @echo + @echo "Build finished. The text files are in $(BUILDDIR)/text." + +.PHONY: man +man: + $(SPHINXBUILD) -b man $(ALLSPHINXOPTS) $(BUILDDIR)/man + @echo + @echo "Build finished. The manual pages are in $(BUILDDIR)/man." + +.PHONY: texinfo +texinfo: + $(SPHINXBUILD) -b texinfo $(ALLSPHINXOPTS) $(BUILDDIR)/texinfo + @echo + @echo "Build finished. The Texinfo files are in $(BUILDDIR)/texinfo." + @echo "Run \`make' in that directory to run these through makeinfo" \ + "(use \`make info' here to do that automatically)." + +.PHONY: info +info: + $(SPHINXBUILD) -b texinfo $(ALLSPHINXOPTS) $(BUILDDIR)/texinfo + @echo "Running Texinfo files through makeinfo..." + make -C $(BUILDDIR)/texinfo info + @echo "makeinfo finished; the Info files are in $(BUILDDIR)/texinfo." + +.PHONY: gettext +gettext: + $(SPHINXBUILD) -b gettext $(I18NSPHINXOPTS) $(BUILDDIR)/locale + @echo + @echo "Build finished. The message catalogs are in $(BUILDDIR)/locale." + +.PHONY: changes +changes: + $(SPHINXBUILD) -b changes $(ALLSPHINXOPTS) $(BUILDDIR)/changes + @echo + @echo "The overview file is in $(BUILDDIR)/changes." + +.PHONY: linkcheck +linkcheck: + $(SPHINXBUILD) -b linkcheck $(ALLSPHINXOPTS) $(BUILDDIR)/linkcheck + @echo + @echo "Link check complete; look for any errors in the above output " \ + "or in $(BUILDDIR)/linkcheck/output.txt." + +.PHONY: doctest +doctest: + $(SPHINXBUILD) -b doctest $(ALLSPHINXOPTS) $(BUILDDIR)/doctest + @echo "Testing of doctests in the sources finished, look at the " \ + "results in $(BUILDDIR)/doctest/output.txt." + +.PHONY: coverage +coverage: + $(SPHINXBUILD) -b coverage $(ALLSPHINXOPTS) $(BUILDDIR)/coverage + @echo "Testing of coverage in the sources finished, look at the " \ + "results in $(BUILDDIR)/coverage/python.txt." + +.PHONY: xml +xml: + $(SPHINXBUILD) -b xml $(ALLSPHINXOPTS) $(BUILDDIR)/xml + @echo + @echo "Build finished. The XML files are in $(BUILDDIR)/xml." + +.PHONY: pseudoxml +pseudoxml: + $(SPHINXBUILD) -b pseudoxml $(ALLSPHINXOPTS) $(BUILDDIR)/pseudoxml + @echo + @echo "Build finished. The pseudo-XML files are in $(BUILDDIR)/pseudoxml." diff --git a/navigations/robot_localization/doc/conf.py b/navigations/robot_localization/doc/conf.py new file mode 100755 index 0000000..b8aad58 --- /dev/null +++ b/navigations/robot_localization/doc/conf.py @@ -0,0 +1,197 @@ +import sys +import os + +import catkin_pkg.package +catkin_dir = os.path.dirname(os.path.dirname(os.path.abspath(__file__))) +catkin_package = catkin_pkg.package.parse_package(os.path.join(catkin_dir, catkin_pkg.package.PACKAGE_MANIFEST_FILENAME)) + +extensions = [ + 'sphinx.ext.autodoc', + 'sphinx.ext.doctest', + 'sphinx.ext.intersphinx', + 'sphinx.ext.todo', + 'sphinx.ext.coverage', + 'sphinx.ext.mathjax', +] + +templates_path = ['.templates'] +source_suffix = '.rst' +master_doc = 'index' + +project = u'robot_localization' +copyright = u'2016, Tom Moore' +author = u'Tom Moore' +version = catkin_package.version +release = catkin_package.version + +language = None +exclude_patterns = ['.build'] +pygments_style = 'sphinx' +todo_include_todos = True + +html_theme = 'nature' + +html_theme_options = { + "sidebarwidth": "350" +} + +# The name of an image file (relative to this directory) to place at the top +# of the sidebar. +html_logo = 'images/rl_small.png' + +# The name of an image file (relative to this directory) to use as a favicon of +# the docs. This file should be a Windows icon file (.ico) being 16x16 or 32x32 +# pixels large. +#html_favicon = None + +# Add any paths that contain custom static files (such as style sheets) here, +# relative to this directory. They are copied after the builtin static files, +# so a file named "default.css" will overwrite the builtin "default.css". +#html_static_path = ['.static'] + +# Add any extra paths that contain custom files (such as robots.txt or +# .htaccess) here, relative to this directory. These files are copied +# directly to the root of the documentation. +#html_extra_path = [] + +# If not '', a 'Last updated on:' timestamp is inserted at every page bottom, +# using the given strftime format. +#html_last_updated_fmt = '%b %d, %Y' + +# If true, SmartyPants will be used to convert quotes and dashes to +# typographically correct entities. +#html_use_smartypants = True + +# Custom sidebar templates, maps document names to template names. +html_sidebars = { '**': ['full_globaltoc.html', 'sourcelink.html', 'searchbox.html'], } + +# Additional templates that should be rendered to pages, maps page names to +# template names. +#html_additional_pages = {} + +# If false, no module index is generated. +#html_domain_indices = True + +# If false, no index is generated. +#html_use_index = True + +# If true, the index is split into individual pages for each letter. +#html_split_index = False + +# If true, links to the reST sources are added to the pages. +#html_show_sourcelink = True + +# If true, "Created using Sphinx" is shown in the HTML footer. Default is True. +#html_show_sphinx = True + +# If true, "(C) Copyright ..." is shown in the HTML footer. Default is True. +#html_show_copyright = True + +# If true, an OpenSearch description file will be output, and all pages will +# contain a tag referring to it. The value of this option must be the +# base URL from which the finished HTML is served. +#html_use_opensearch = '' + +# This is the file name suffix for HTML files (e.g. ".xhtml"). +#html_file_suffix = None + +# Language to be used for generating the HTML full-text search index. +# Sphinx supports the following languages: +# 'da', 'de', 'en', 'es', 'fi', 'fr', 'hu', 'it', 'ja' +# 'nl', 'no', 'pt', 'ro', 'ru', 'sv', 'tr' +#html_search_language = 'en' + +# A dictionary with options for the search language support, empty by default. +# Now only 'ja' uses this config value +#html_search_options = {'type': 'default'} + +# The name of a javascript file (relative to the configuration directory) that +# implements a search results scorer. If empty, the default will be used. +#html_search_scorer = 'scorer.js' + +# Output file base name for HTML help builder. +htmlhelp_basename = 'robot_localizationdoc' + +# -- Options for LaTeX output --------------------------------------------- + +latex_elements = { +# The paper size ('letterpaper' or 'a4paper'). +#'papersize': 'letterpaper', + +# The font size ('10pt', '11pt' or '12pt'). +#'pointsize': '10pt', + +# Additional stuff for the LaTeX preamble. +#'preamble': '', + +# Latex figure (float) alignment +#'figure_align': 'htbp', +} + +# Grouping the document tree into LaTeX files. List of tuples +# (source start file, target name, title, +# author, documentclass [howto, manual, or own class]). +latex_documents = [ + (master_doc, 'robot_localization.tex', u'robot\\_localization Documentation', + u'Tom Moore', 'manual'), +] + +# The name of an image file (relative to this directory) to place at the top of +# the title page. +#latex_logo = None + +# For "manual" documents, if this is true, then toplevel headings are parts, +# not chapters. +#latex_use_parts = False + +# If true, show page references after internal links. +#latex_show_pagerefs = False + +# If true, show URL addresses after external links. +#latex_show_urls = False + +# Documents to append as an appendix to all manuals. +#latex_appendices = [] + +# If false, no module index is generated. +#latex_domain_indices = True + + +# -- Options for manual page output --------------------------------------- + +# One entry per manual page. List of tuples +# (source start file, name, description, authors, manual section). +man_pages = [ + (master_doc, 'robot_localization', u'robot_localization Documentation', + [author], 1) +] + +# If true, show URL addresses after external links. +#man_show_urls = False + + +# -- Options for Texinfo output ------------------------------------------- + +# Grouping the document tree into Texinfo files. List of tuples +# (source start file, target name, title, author, +# dir menu entry, description, category) +texinfo_documents = [ + (master_doc, 'robot_localization', u'robot_localization Documentation', + author, 'robot_localization', 'One line description of project.', + 'Miscellaneous'), +] + +# Documents to append as an appendix to all manuals. +#texinfo_appendices = [] + +# If false, no module index is generated. +#texinfo_domain_indices = True + +# How to display URL addresses: 'footnote', 'no', or 'inline'. +#texinfo_show_urls = 'footnote' + +# If true, do not generate a @detailmenu in the "Top" node's menu. +#texinfo_no_detailmenu = False + +# Example configuration for intersphinx: refer to the Python standard library. +intersphinx_mapping = {'https://docs.python.org/': None} diff --git a/navigations/robot_localization/doc/configuring_robot_localization.rst b/navigations/robot_localization/doc/configuring_robot_localization.rst new file mode 100755 index 0000000..5db5385 --- /dev/null +++ b/navigations/robot_localization/doc/configuring_robot_localization.rst @@ -0,0 +1,117 @@ +.. _configuring_robot_localization: + +Configuring robot_localization +############################## + + +When incorporating sensor data into the position estimate of any of ``robot_localization``'s state estimation nodes, it is important to extract as much information as possible. This tutorial details the best practices for sensor integration. + +For additional information, users are encouraged to watch this `presentation `_ from ROSCon 2015. + +Sensor Configuration +******************** + +The configuration vector format is the same for all sensors, even if the message type in question doesn't contain some of the variables in the configuration vector (e.g., a <> lacks any pose data, but the configuration vector still has values for pose variables). Unused variables are simply ignored. + +Note that the configuration vector is given in the ``frame_id`` of the input message. For example, consider a velocity sensor that produces a `geometry_msgs/TwistWithCovarianceStamped `_ message with a ``frame_id`` of *velocity_sensor_frame*. In this example, we'll assume that a transform exists from *velocity_sensor_frame* to your robot's ``base_link_frame`` (e.g., *base_link*), and that the transform would convert :math:`X` velocity in the *velocity_sensor_frame* to :math:`Z` velocity in the ``base_link_frame``. To include the :math:`X` velocity data from the sensor into the filter, the configuration vector should set the :math:`X` velocity value to *true*, and **not** the :math:`\dot{Z}` velocity value: + +.. code-block:: xml + + [false, false, false, + false, false, false, + true, false, false, + false, false, false, + false, false, false] + +.. note:: The order of the boolean values are :math:`(X, Y, Z, roll, pitch, yaw, \dot{X}, \dot{Y}, \dot{Z}, \dot{roll}, \dot{pitch}, \dot{yaw}, \ddot{X}, \ddot{Y}, \ddot{Z})`. + +Operating in 2D? +**************** + +The first decision to make when configuring your sensors is whether or not your robot is operating in a planar environment, and you're comfortable with ignoring subtle effects of variations in the ground plane as might be reported from an IMU. If so, please set the ``two_d_mode`` parameter to *true*. This effectively zeros out the 3D pose variables in every measurement and forces them to be fused in the state estimate. + +Fusing Unmeasured Variables +*************************** + +Let's start with an example. Let's say you have a wheeled, nonholonomic robot that works in a planar environment. Your robot has some wheel encoders that are used to estimate instantaneous X velocity as well as absolute pose information. This information is reported in an `nav_msgs/Odometry `_ message. Additionally, your robot has an IMU that measures rotational velocity, vehicle attitude, and linear acceleration. Its data is reported in a `sensor_msgs/Imu `_ message. As we are operating in a planar environment, we set the ``two_d_mode`` parameter to *true*. This will automatically zero out all 3D variables, such as :math:`Z`, :math:`roll`, :math:`pitch`, their respective velocities, and :math:`Z` acceleration. We start with this configuration: + +.. code-block:: xml + + [true, true, false, + false, false, true, + true, false, false, + false, false, true, + false, false, false] + + [false, false, false, + false, false, true, + false, false, false, + false, false, true, + true, false, false] + +As a first pass, this makes sense, as a planar robot only needs to concern itself with :math:`X`, :math:`Y`, :math:`\dot{X}`, :math:`\dot{Y}`, :math:`\ddot{X}`, :math:`\ddot{Y}`, :math:`yaw`, and :math:`\dot{yaw}`. However, there are a few things to note here. + +1. For ``odom0``, we are including :math:`X` and :math:`Y` (reported in a world coordinate frame), :math:`yaw`, :math:`\dot{X}` (reported in the body frame), and :math:`\dot{yaw}`. However, unless your robot is internally using an IMU, it is most likely simply using wheel encoder data to generate the values in its measurements. Therefore, its velocity, heading, and position data are all generated from the same source. In that instance, we don't want to use all the values, as you're feeding duplicate information into the filter. Instead, it's best to just use the velocities: + +.. code-block:: xml + + [false, false, false, + false, false, false, + true, false, false, + false, false, true, + false, false, false] + + [false, false, false, + false, false, true, + false, false, false, + false, false, true, + true, false, false] + +2. Next, we note that we are not fusing :math:`\dot{Y}`. At first glance, this is the right choice, as our robot cannot move instantaneously sideways. However, if the `nav_msgs/Odometry `_ message reports a :math:`0` value for :math:`\dot{Y}` (and the :math:`\dot{Y}` covariance is NOT inflated to a large value), it's best to feed that value to the filter. As a :math:`0` measurement in this case indicates that the robot cannot ever move in that direction, it serves as a perfectly valid measurement: + +.. code-block:: xml + + [false, false, false, + false, false, false, + true, true, false, + false, false, true, + false, false, false] + + [false, false, false, + false, false, true, + false, false, false, + false, false, true, + true, false, false] + +You may wonder why did we not fuse :math:`\dot{Z}` velocity for the same reason. The answer is that we did when we set ``two_d_mode`` to *false*. If we hadn't, we could, in fact, fuse the :math:`0` measurement for :math:`\dot{Z}` velocity into the filter. + +3. Last, we come to the IMU. You may notice that we have set the :math:`\ddot{Y}` to *false*. This is due to the fact that many systems, including the hypothetical one we are discussing here, will not undergo instantaneous :math:`Y` acceleration. However, the IMU will likely report non-zero, noisy values for Y acceleration, which can cause your estimate to drift rapidly. + +The *differential* Parameters +***************************** + +The state estimation nodes in ''robot_localization'' allow users to fuse as many sensors as they like. This allows users to measure certain state vector variables - in particular, pose variables - using more than one source. For example, your robot may obtain absolute orientation information from multiple IMUs, or it may have multiple data sources providing an estimate its absolute position. In this case, users have two options: + +1. Fuse all the absolute position/orientation data as-is, e.g., + +.. code-block:: xml + + [false, false, false, + true, true, true, + false, false, false, + false, false, false, + false, false, false] + + [false, false, false, + true, true, true, + false, false, false, + false, false, false, + false, false, false] + +In this case, users should be **very** careful and ensure that the covariances on each measured orientation variable are set correctly. If each IMU advertises a yaw variance of, for example, :math:`0.1`, yet the delta between the IMUs' yaw measurements is :math:`> 0.1`, then the output of the filter will oscillate back and forth between the values provided by each sensor. Users should make sure that the noise distributions around each measurement overlap. + +2. Alternatively, users can make use of the ``_differential`` parameter. By setting this to *true* for a given sensor, all pose (position and orientation) data is converted to a velocity by calculating the change in the measurement value between two consecutive time steps. The data is then fused as a velocity. Again, though, users should take care: when measurements are fused absolutely (especially IMUs), if the measurement has a static or non-increasing variance for a given variable, then the variance in the estimate's covariance matrix will be bounded. If that information is converted to a velocity, then at each time step, the estimate will gain some small amount of error, and the variance for the variable in question will grow without bound. For position :math:`(X, Y, Z)` information, this isn't an issue, but for orientation data, it is a problem. For example, it is acceptable for a robot to move around its environment and accumulate :math:`1.5` meters of error in the :math:`X` direction after some time. If that same robot moves around and accumulates :math:`1.5` radians of error in yaw, then when the robot next drives forward, its position error will explode. + +The general rule of thumb for the ``_differential`` parameter is that if a give robot has only one source of orientation data, then the differential parameter should be set to *false*. If there are :math:`N` sources, users can set the ``_differential`` parameter to *true* for :math:`N-1` of them, or simply ensure that the covariance values are large enough to eliminate oscillations. + + diff --git a/navigations/robot_localization/doc/images/figure2.png b/navigations/robot_localization/doc/images/figure2.png new file mode 100755 index 0000000..0224d29 Binary files /dev/null and b/navigations/robot_localization/doc/images/figure2.png differ diff --git a/navigations/robot_localization/doc/images/navsat_transform_workflow.png b/navigations/robot_localization/doc/images/navsat_transform_workflow.png new file mode 100755 index 0000000..450bcf2 Binary files /dev/null and b/navigations/robot_localization/doc/images/navsat_transform_workflow.png differ diff --git a/navigations/robot_localization/doc/images/navsat_transform_workflow.tex b/navigations/robot_localization/doc/images/navsat_transform_workflow.tex new file mode 100755 index 0000000..2dd0ab0 --- /dev/null +++ b/navigations/robot_localization/doc/images/navsat_transform_workflow.tex @@ -0,0 +1,49 @@ +\documentclass{standalone} +\usepackage{tikz} +\usetikzlibrary{positioning} + +\begin{document} + +\sffamily + +\begin{tikzpicture}[>=stealth, + node distance = 3cm, + box/.style={shape=rectangle,draw,rounded corners},] + % Nodes + \node (wheel) [box] {Wheel Odometry}; + \node (imu) [box, right =of wheel]{IMU}; + \node (ekfLocal) [box, below =of wheel]{EKF Local}; + \node (ekfGlobal) [box, below =of imu]{EKF Global}; + \node (navsat) [box, right =7cm of ekfGlobal]{navsat\_transform}; + \node (gps) [box, above =of navsat]{GPS}; + % Coordinates for edges pointing to empty space + \node (gpsF) [right =of navsat]{}; + \node (tfLocal) [below =of ekfLocal]{}; + \node (odomLocal) [left =of ekfLocal]{}; + \node (tfGlobal) [below =of ekfGlobal]{}; + % Edges + \draw[->] (wheel.270) -- (ekfLocal.90); + \draw[->] (wheel.315) -- (ekfGlobal.135) + node [fill=white, pos=0.2, align=center] {\ttfamily"/wheel/odometry"\\nav\_msgs/Odometry}; + \draw[->] (imu.225) -- (ekfLocal.45); + \draw[->] (imu.315) -- (navsat.135); + \draw[->] (imu.270) -- (ekfGlobal.90) + node [fill=white, pos=0.2, align=center] {\ttfamily"/imu/data"\\sensor\_msgs/Imu}; + \draw[->] (gps.270) -- (navsat.90) + node [fill=white, pos=0.2, align=center] {\ttfamily"/gps/fix"\\sensor\_msgs/NavSatFix}; + \draw[->, transform canvas={yshift=1mm}] (ekfGlobal) -- (navsat) + node [fill=white, above=1mm, pos=0.5, align=center] {\ttfamily"/odometry/filtered/global"\\nav\_msgs/Odometry}; + \draw[->, transform canvas={yshift=-1mm}] (navsat) -- (ekfGlobal) + node [fill=white, below=1mm, pos=0.5, align=center] {\ttfamily"/odometry/gps"\\nav\_msgs/Odometry}; + % Outputs not cycled back into the graph + \draw[->, dashed] (navsat) -- (gpsF) + node [fill=white, above=1mm, pos=1.0, align=center] {\ttfamily"/gps/filtered"\\sensor\_msgs/NavSatFix}; + \draw[->, dashed] (ekfLocal) -- (tfLocal) + node [fill=white, pos=0.7, align=center] {\ttfamily"/tf" odom -> base\\tf2\_msgs/TFMessage}; + \draw[->, dashed] (ekfLocal) -- (odomLocal) + node [fill=white, above=1mm, pos=1.0, align=center] {\ttfamily"/odometry/filtered/local"\\nav\_msgs/Odometry}; + \draw[->, dashed] (ekfGlobal) -- (tfGlobal) + node [fill=white, pos=0.7, align=center] {\ttfamily"/tf" map -> odom\\tf2\_msgs/TFMessage}; +\end{tikzpicture} + +\end{document} diff --git a/navigations/robot_localization/doc/images/rl_small.png b/navigations/robot_localization/doc/images/rl_small.png new file mode 100755 index 0000000..33a4d59 Binary files /dev/null and b/navigations/robot_localization/doc/images/rl_small.png differ diff --git a/navigations/robot_localization/doc/index.rst b/navigations/robot_localization/doc/index.rst new file mode 100755 index 0000000..b6c6aee --- /dev/null +++ b/navigations/robot_localization/doc/index.rst @@ -0,0 +1,55 @@ +.. _index: + +robot_localization wiki +*********************** + +``robot_localization`` is a collection of state estimation nodes, each of which is an implementation of a nonlinear state estimator for robots moving in 3D space. It contains two state estimation nodes, ``ekf_localization_node`` and ``ukf_localization_node``. In addition, ``robot_localization`` provides ``navsat_transform_node``, which aids in the integration of GPS data. + +.. toctree:: + :hidden: + + state_estimation_nodes + navsat_transform_node + preparing_sensor_data + configuring_robot_localization + migrating_from_robot_pose_ekf + integrating_gps + CHANGELOG + user_contributed_tutorials + +Features +======== + +All the state estimation nodes in ``robot_localization`` share common features, namely: + +* Fusion of an arbitrary number of sensors. The nodes do not restrict the number of input sources. If, for example, your robot has multiple IMUs or multiple sources of odometry information, the state estimation nodes within ``robot_localization`` can support all of them. +* Support for multiple ROS message types. All state estimation nodes in ``robot_localization`` can take in `nav_msgs/Odometry `_, `sensor_msgs/Imu `_, `geometry_msgs/PoseWithCovarianceStamped `_, or `geometry_msgs/TwistWithCovarianceStamped `_ messages. +* Per-sensor input customization. If a given sensor message contains data that you don't want to include in your state estimate, the state estimation nodes in ``robot_localization`` allow you to exclude that data on a per-sensor basis. +* Continuous estimation. Each state estimation node in ``robot_localization`` begins estimating the vehicle's state as soon as it receives a single measurement. If there is a holiday in the sensor data (i.e., a long period in which no data is received), the filter will continue to estimate the robot's state via an internal motion model. + +All state estimation nodes track the 15-dimensional state of the vehicle: :math:`(X, Y, Z, roll, pitch, yaw, \dot{X}, \dot{Y}, \dot{Z}, \dot{roll}, \dot{pitch}, \dot{yaw}, \ddot{X}, \ddot{Y}, \ddot{Z})`. + +Other Resources +=============== + +If you're new to ``robot_localization``, check out the `2015 ROSCon talk `_ for some pointers on getting started. + +Further details can be found in :download:`this paper `: + +.. code-block:: none + + @inproceedings{MooreStouchKeneralizedEkf2014, + author = {T. Moore and D. Stouch}, + title = {A Generalized Extended Kalman Filter Implementation for the Robot Operating System}, + year = {2014}, + month = {July}, + booktitle = {Proceedings of the 13th International Conference on Intelligent Autonomous Systems (IAS-13)}, + publisher = {Springer} + } + +Indices and tables +================== + +* :ref:`genindex` +* :ref:`search` + diff --git a/navigations/robot_localization/doc/integrating_gps.rst b/navigations/robot_localization/doc/integrating_gps.rst new file mode 100755 index 0000000..65a7850 --- /dev/null +++ b/navigations/robot_localization/doc/integrating_gps.rst @@ -0,0 +1,165 @@ +Integrating GPS Data +#################### + +Integration of GPS data is a common request from users. ``robot_localization`` contains a node, ``navsat_transform_node``, that transforms GPS data into a frame that is consistent with your robot's starting pose (position and orientation) in its world frame. This greatly simplifies fusion of GPS data. This tutorial explains how to use ``navsat_transform_node``, and delves into some of the math behind it. + +For additional information, users are encouraged to watch this `presentation `_ from ROSCon 2015. + +Notes on Fusing GPS Data +************************ + +Before beginning this tutorial, users should be sure to familiarize themselves with `REP-105 `_. It is important for users to realize that using a position estimate that includes GPS data will likely be unfit for use by navigation modules, owing to the fact that GPS data is subject to discrete discontinuities ("jumps"). If you want to fuse data from a GPS into your position estimate, one potential solution is to do the following: + +1. Run one instance of a ``robot_localization`` state estimation node that fuses only continuous data, such as odometry and IMU data. Set the ``world_frame`` parameter for this instance to the same value as the ``odom_frame`` parameter. Execute local path plans and motions in this frame. +2. Run another instance of a ``robot_localization`` state estimation node that fuses all sources of data, including the GPS. Set the ``world_frame`` parameter for this instance to the same value as the ``map_frame`` parameter. + +This is just a suggestion, however, and users are free to fuse the GPS data into a single instance of a ``robot_localization`` state estimation node. + +Using navsat_transform_node +*************************** + +The diagram below illustrates an example setup: + +.. image:: images/navsat_transform_workflow.png + :width: 800px + :align: center + :alt: navsat_transform workflow + + +Required Inputs +=============== + +``navsat_transform_node`` requires three sources of information: the robot's current pose estimate in its world frame, an earth-referenced heading, and a geographic coordinate expressed as a latitude/longitude pair (with optional altitude). + +These data can be obtained in three different ways: + +1. (Default behavior) The data can come entirely from the robot's sensors and pose estimation software. To enable this mode, make sure the ``wait_for_datum`` parameter is set to *false* (its default value). The required messages are: + + * A `sensor_msgs/NavSatFix `_ message with raw GPS coordinates in it. + * A `sensor_msgs/Imu `_ message with an absolute (earth-referenced) heading. + * A `nav_msgs/Odometry `_ message that contains the robot's current position estimate in the frame specified by its start location (typically the output of a ``robot_localization`` state estimation node). + +2. The datum (global frame origin) can be specified via the ``datum`` parameter. + + .. note:: In order to use this mode, the ``wait_for_datum`` parameter must be set to *true*. + + The ``datum`` parameter takes this form: + + .. code-block:: xml + + [55.944904, -3.186693, 0.0, map, base_link] + + The parameter order is ``latitude`` in decimal degrees, ``longitude`` in decimal degrees, ``heading`` in radians) the ``frame_id`` of your robot's world frame (i.e., the value of the ``world_frame`` parameter in a ``robot_localization`` state estimation node), and the ``frame_id`` of your robot's body frame (i.e., the value of the ``base_link_frame`` parameter in a ``robot_localization`` state estimation node). When this mode is used, the robot assumes that your robot's world frame origin is at the specified latitude and longitude and with a heading of :math:`0` (east). + +3. The datum can be set manually via the ``set_datum`` service and using the `robot_localization/SetDatum `_ service message. + + +GPS Data +^^^^^^^^ + +Please note that all development of ``navsat_transform_node`` was done using a Garmin 18x GPS unit, so there may be intricacies of the data generated by other units that need to be handled. + +The excellent `nmea_navsat_driver `_ package provides the required `sensor_msgs/NavSatFix `_ message. Here is the ``nmea_navsat_driver`` launch file we'll use for this tutorial: + + .. code-block:: xml + + + + + + +This information is only relevant if the user is not manually specifying the origin via the ``datum`` parameter or the ``set_datum`` service. + +IMU Data +^^^^^^^^ + +.. note:: Since version 2.2.1, ``navsat_transform_node`` has moved to a standard wherein all heading data is assumed to start with its zero point facing east. If your IMU does not conform to this standard and instead reports zero when facing north, you can still use the ``yaw_offset`` parameter to correct this. In this case, the value for ``yaw_offset`` would be :math:`\pi / 2` (approximately :math:`1.5707963`). + +Users should make sure their IMUs conform to `REP-105 `_. In particular, check that the signs of your orientation angles increase in the right direction. In addition, users should look up the `magnetic declination `_ for their robot's operating area, convert it to radians, and then use that value for the ``magnetic_declination_radians`` parameter. + +This information is only relevant if the user is not manually specifying the origin via the ``datum`` parameter or the ``set_datum`` service. + +Odometry Data +^^^^^^^^^^^^^ + +This should just be the output of whichever ``robot_localization`` state estimation node instance you are using to fuse GPS data. + +Configuring navsat_transform_node +================================= + +Below is the ``navsat_transform_node`` launch file we'll use for this tutorial: + +.. code-block:: xml + + + + + + + + + + + + + + + + + +These parameters are discussed on the :ref:`main page `. + +Configuring robot_localization +============================== + +Integration with ``robot_localization`` is straightforward at this point. Simply add this block to your state estimation node launch file: + +.. code-block:: xml + + + + [true, true, false, + false, false, false, + false, false, false, + false, false, false, + false, false, false] + + +Make sure to change ``odomN`` to whatever your odometry input values is (e.g., *odom1*, *odom2*, etc.). Also, if you wish to include altitude data, set ``odomN_config``'s third value to ``true``. + +.. note:: If you are operating in 2D don't have any sensor measuring Z or Z velocity, you can either: + + * Set ``navsat_transform_node's`` ``zero_altitude`` parameter to *true*, and then set ``odomN_config``'s third value to *true* + * Set ``two_d_mode`` to *true* in your ``robot_localization`` state estimation node + +You should have no need to modify the ``_differential`` setting within the state estimation node. The GPS is an absolute position sensor, and enabling differential integration defeats the purpose of using it. + +Details +======= + +We'll start with a picture. Consider a robot that starts at some latitude and longitude and with some heading. We assume in this tutorial that the heading comes from an IMU that reads 0 when facing east, and increases according to the ROS spec (i.e., counter-clockwise). The remainder of this tutorial will refer to Figure 2: + +.. image:: images/figure2.png + :width: 800px + :align: center + :alt: Figure 2 + + +`REP-105 `_ suggests four coordinate frames: *base_link*, *odom*, *map*, and *earth*. *base_link* is the coordinate frame that is rigidly attached to the vehicle. The *odom* and *map* frames are world-fixed frames and generally have their origins at the vehicle's start position and orientation. The *earth* frame is used as a common reference frame for multiple map frames, and is not yet supported by ``navsat_transform_node``. Note that in Figure 2, the robot has just started (``t = 0``), and so its *base_link*, *odom*, and *map* frames are aligned. We can also define a coordinate frame for the UTM grid, which we will call *utm*. For the purposes of this tutorial, we will refer to the UTM grid coordinate frame as *utm*. Therefore, what we want to do is create a *utm*->*map* transform. + +Referring to Figure 2, these ideas are (hopefully) made clear. The UTM origin is the :math:`(0_{UTM}, 0_{UTM})` point of the UTM zone that is associated with the robot's GPS location. The robot begins somewhere within the UTM zone at location :math:`(x_{UTM}, y_{UTM})`. The robot's initial orientation is some angle :math:`\theta` above the UTM grid's :math:`X`-axis. Our transform will therefore require that we know :math:`x_{UTM}, y_{UTM}` and :math:`\theta`. + +We now need to convert our latitude and longitude to UTM coordinates. The UTM grid assumes that the :math:`X`-axis faces east, the :math:`Y`-axis faces (true) north, and the :math:`Z`-axis points up out of the ground. This complies with the right-handed coordinate frame as dictated by `REP-105 `_. The REP also states that a yaw angle of :math:`0` means that we are facing straight down the :math:`X`-axis, and that the yaw increases counter-clockwise. ``navsat_transform_node`` assumes your heading data conforms to this standard. However, there are two factors that need to be considered: + +1. The IMU driver may not allow the user to apply the magnetic declination correction factor +2. The IMU driver may incorrectly report :math:`0` when facing north, and not when facing east (even though its headings increase and decrease correctly). Fortunately, ``navsat_transform_node`` exposes two parameters to adddress these possible shortcomings in IMU data: ``magnetic_declination_radians`` and ``yaw_offset``. Referring to Figure 2, for an IMU that is currently measuring a yaw value of ``imu_yaw``, + + :math:`yaw_{imu} = -\omega - offset_{yaw} + \theta` + + :math:`\theta = yaw_{imu} + \omega + offset_{yaw}` + +We now have a translation :math:`(x_{UTM}, y_{UTM})` and rotation :math:`\theta`, which we can use to create the required *utm* -> *map* transform. We use the transform to convert all future GPS positions into the robot's local coordinate frame. ``navsat_transform_node`` will also broadcast this transform if the ``broadcast_utm_transform`` parameter is set to *true*. + +If you have any questions about this tutorial, please feel free to ask questions on `answers.ros.org `_. + + diff --git a/navigations/robot_localization/doc/manifest.yaml b/navigations/robot_localization/doc/manifest.yaml new file mode 100755 index 0000000..a0dc0c4 --- /dev/null +++ b/navigations/robot_localization/doc/manifest.yaml @@ -0,0 +1,38 @@ +actions: [] +authors: Tom Moore +brief: '' +bugtracker: '' +depends: +- catkin +- eigen +- diagnostic_updater +- cmake_modules +- tf2 +- nav_msgs +- roscpp +- rostest +- tf2_ros +- message_generation +- message_filters +- tf2_geometry_msgs +- sensor_msgs +- message_runtime +- std_msgs +- roslint +- rosunit +- diagnostic_msgs +- geographic_msgs +- python-catkin-pkg +- geometry_msgs +- rosbag +description: The robot_localization package provides nonlinear state estimation through + sensor fusion of an abritrary number of sensors. +license: BSD +maintainers: Tom Moore +msgs: [] +package_type: package +repo_url: '' +srvs: +- SetPose +- SetDatum +url: http://ros.org/wiki/robot_localization diff --git a/navigations/robot_localization/doc/migrating_from_robot_pose_ekf.rst b/navigations/robot_localization/doc/migrating_from_robot_pose_ekf.rst new file mode 100755 index 0000000..8ffba57 --- /dev/null +++ b/navigations/robot_localization/doc/migrating_from_robot_pose_ekf.rst @@ -0,0 +1,29 @@ +.. _migrating_from_robot_pose_ekf: + +Migrating from robot_pose_ekf +############################# + +Migration from ``robot_pose_ekf`` is fairly straightforward. This page is meant to highlight relevant differences between the packages to facilitate rapid transitions. + +Covariances in Source Messages +============================== + +For ``robot_pose_ekf``, a common means of getting the filter to ignore measurements is to give it a massively inflated covariance, often on the order of 10^3. However, the state estimation nodes in ``robot_localization`` allow users to specify *which* variables from the measurement should be fused with the current state. If your sensor reports zero for a given variable and you don't want to fuse that value with your filter, or if the sensor is known to produce poor data for that field, then simply set its ``xxxx_config`` parameter value to false for the variable in question (see the main page for a description of this parameter). + +However, users should take care: sometimes platform constraints create implicit :math:`0` measurements of variables. For example, a differential drive robot that cannot move instantaneously in the :math:`Y` direction can safely fuse a :math:`0` measurement for :math:`\dot{Y}` with a small covariance value. + +The ''differential'' Parameter +============================== + +By default, ``robot_pose_ekf`` will take a pose measurement at time :math:`t`, determine the difference between it and the measurement at time :math:`t-1`, transform that difference into the current frame, and then integrate that measurement. This cleverly aids in cases where two sensors are measuring the same pose variable: as time progresses, the values reported by each sensor will start to diverge. If the covariances on at least one of these measurements do not grow appopriately, the filter will eventually start to oscillate between the measured values. By carrying out differential integration, this situation is avoided and measurements are always consistent with the current state. + +This situation can be avoided using three different methods for the ``robot_localization`` state estimation nodes: + +1. If fusing two different sources for the same pose data (e.g., two different sensors measuring :math:`Z` position), ensure that those sources accurately report their covariances. If the two sources begin to diverge, then their covariances should refect the growing error that must be occurring in at least one of them. + +2. If available, fuse velocity data instead of pose data. If you have two separate data sources measuring the same variable, fuse the most accurate one as pose data and the other as velocity. + +3. As an alternative to (2), if velocity data is unavailable for a given pose measurement, enable the ``_differential`` parameter for one of the sensors. This will cause it to be differentiated and fused as a velocity. + + + diff --git a/navigations/robot_localization/doc/navsat_transform_node.rst b/navigations/robot_localization/doc/navsat_transform_node.rst new file mode 100755 index 0000000..28f0359 --- /dev/null +++ b/navigations/robot_localization/doc/navsat_transform_node.rst @@ -0,0 +1,75 @@ +navsat_transform_node +********************* + +``navsat_transform_node`` takes as input a `nav_msgs/Odometry `_ message (usually the output of ``ekf_localization_node`` or ``ukf_localization_node``), a `sensor_msgs/Imu `_ containing an accurate estimate of your robot's heading, and a `sensor_msgs/NavSatFix `_ message containing GPS data. It produces an odometry message in coordinates that are consistent with your robot's world frame. This value can be directly fused into your state estimate. + +.. note:: If you fuse the output of this node with any of the state estimation nodes in ``robot_localization``, you should make sure that the ``odomN_differential`` setting is *false* for that input. + +Parameters +========== + +~frequency +^^^^^^^^^^ +The real-valued frequency, in Hz, at which ``navsat_transform_node`` checks for new `sensor_msgs/NavSatFix `_ messages, and publishes filtered `sensor_msgs/NavSatFix `_ when ``publish_filtered_gps`` is set to *true*. + +~delay +^^^^^^ +The time, in seconds, to wait before calculating the transform from GPS coordinates to your robot's world frame. + +~magnetic_declination_radians +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Enter the magnetic declination for your location. If you don't know it, see `http://www.ngdc.noaa.gov/geomag-web `_ (make sure to convert the value to radians). This parameter is needed if your IMU provides its orientation with respect to the magnetic north. + +~yaw_offset +^^^^^^^^^^^ +Your IMU should read 0 for yaw when facing east. If it doesn't, enter the offset here (desired_value = offset + sensor_raw_value). For example, if your IMU reports 0 when facing north, as most of them do, this parameter would be ``pi/2`` (~1.5707963). This parameter changed in version ``2.2.1``. Previously, ``navsat_transform_node`` assumed that IMUs read 0 when facing north, so yaw_offset was used acordingly. + +~zero_altitude +^^^^^^^^^^^^^^ +If this is *true*, the `nav_msgs/Odometry `_ message produced by this node has its pose Z value set to 0. + +~publish_filtered_gps +^^^^^^^^^^^^^^^^^^^^^ +If *true*, ``navsat_transform_node`` will also transform your robot's world frame (e.g., *map*) position back to GPS coordinates, and publish a `sensor_msgs/NavSatFix `_ message on the ``/gps/filtered`` topic. + +~broadcast_utm_transform +^^^^^^^^^^^^^^^^^^^^^^^^ +If this is *true*, ``navsat_transform_node`` will broadcast the transform between the UTM grid and the frame of the input odometry data. See Published Transforms below for more information. + +~use_odometry_yaw +^^^^^^^^^^^^^^^^^ +If *true*, ``navsat_transform_node`` will not get its heading from the IMU data, but from the input odometry message. Users should take care to only set this to true if your odometry message has orientation data specified in an earth-referenced frame, e.g., as produced by a magnetometer. Additionally, if the odometry source is one of the state estimation nodes in ``robot_localization``, the user should have at least one source of absolute orientation data being fed into the node, with the ``_differential`` and ``_relative`` parameters set to *false*. + +~wait_for_datum +^^^^^^^^^^^^^^^ +If *true*, ``navsat_transform_node`` will wait to get a datum from either: + +* The ``datum`` parameter +* The ``set_datum`` service + +~broadcast_utm_transform_as_parent_frame +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +If *true*, ``navsat_transform_node`` will publish the utm->world_frame transform instead of the world_frame->utm transform. +Note that for the transform to be published ``broadcast_utm_transform`` also has to be set to *true*. + +~transform_timeout +^^^^^^^^^^^^^^^^^^ +This parameter specifies how long we would like to wait if a transformation is not available yet. Defaults to 0 if not set. The value 0 means we just get us the latest available (see ``tf2`` implementation) transform. + +Subscribed Topics +================= +* ``imu/data`` A `sensor_msgs/Imu `_ message with orientation data + +* ``odometry/filtered`` A `nav_msgs/Odometry `_ message of your robot's current position. This is needed in the event that your first GPS reading comes after your robot has attained some non-zero pose. + +* ``gps/fix`` A `sensor_msgs/NavSatFix `_ message containing your robot's GPS coordinates + +Published Topics +================ +* ``odometry/gps`` A `nav_msgs/Odometry `_ message containing the GPS coordinates of your robot, transformed into its world coordinate frame. This message can be directly fused into ``robot_localization``'s state estimation nodes. + +* ``gps/filtered`` (optional) A `sensor_msgs/NavSatFix `_ message containing your robot's world frame position, transformed into GPS coordinates + +Published Transforms +==================== +* ``world_frame->utm`` (optional) - If the ``broadcast_utm_transform`` parameter is set to *true*, ``navsat_transform_node`` calculates a transform from the *utm* frame to the ``frame_id`` of the input odometry data. By default, the *utm* frame is published as a child of the odometry frame by using the inverse transform. With use of the ``broadcast_utm_transform_as_parent_frame`` parameter, the *utm* frame will be published as a parent of the odometry frame. This is useful if you have multiple robots within one TF tree. diff --git a/navigations/robot_localization/doc/preparing_sensor_data.rst b/navigations/robot_localization/doc/preparing_sensor_data.rst new file mode 100755 index 0000000..2d67e6c --- /dev/null +++ b/navigations/robot_localization/doc/preparing_sensor_data.rst @@ -0,0 +1,104 @@ +Preparing Your Data for Use with robot_localization +################################################### + +Before getting started with the state estimation nodes in ``robot_localization``, it is important that users ensure that their sensor data well-formed. There are various considerations for each class of sensor data, and users are encouraged to read this tutorial in its entirety before attempting to use ``robot_localization``. + +For additional information, users are encouraged to watch this `presentation `_ from ROSCon 2015. + +Adherence to ROS Standards +************************** + +The two most important ROS REPs to consider are: + +* `REP-103 `_ (Standard Units of Measure and Coordinate Conventions) +* `REP-105 `_ (Coordinate Frame Conventions). + +Users who are new to ROS or state estimation are encouraged to read over both REPs, as it will almost certainly aid you in preparing your sensor data. ``robot_localization`` attempts to adhere to these standards as much as possible. + +Also, it will likely benefit users to look over the specifications for each of the supported ROS message types: + +* `nav_msgs/Odometry `_ + +* `geometry_msgs/PoseWithCovarianceStamped `_ + +* `geometry_msgs/TwistWithCovarianceStamped `_ + +* `sensor_msgs/Imu `_ + +Coordinate Frames and Transforming Sensor Data +********************************************** + +`REP-105 `_ specifies four principal coordinate frames: *base_link*, *odom*, *map*, and *earth*. The *base_link* frame is rigidly affixed to the robot. The *map* and *odom* frames are world-fixed frames whose origins are typically aligned with the robot's start position. The *earth* frame is used to provide a common reference frame for multiple *map* frames (e.g., for robots distributed over a large area). The *earth* frame is not relevant to this tutorial. + +The state estimation nodes of ``robot_localization`` produce a state estimate whose pose is given in the *map* or *odom* frame and whose velocity is given in the *base_link* frame. All incoming data is transformed into one of these coordinate frames before being fused with the state. The data in each message type is transformed as follows: + +* `nav_msgs/Odometry `_ - All pose data (position and orientation) is transformed from the message header's ``frame_id`` into the coordinate frame specified by the ``world_frame`` parameter (typically *map* or *odom*). In the message itself, this specifically refers to everything contained within the ``pose`` property. All twist data (linear and angular velocity) is transformed from the ``child_frame_id`` of the message into the coordinate frame specified by the ``base_link_frame`` parameter (typically *base_link*). +* `geometry_msgs/PoseWithCovarianceStamped `_ - Handled in the same fashion as the pose data in the Odometry message. +* `geometry_msgs/TwistWithCovarianceStamped `_ - Handled in the same fashion as the twist data in the Odometry message. +* `sensor_msgs/Imu `_ - The IMU message is currently subject to some ambiguity, though this is being addressed by the ROS community. Most IMUs natively report orientation data in a world-fixed frame whose :math:`X` and :math:`Z` axes are defined by the vectors pointing to magnetic north and the center of the earth, respectively, with the Y axis facing east (90 degrees offset from the magnetic north vector). This frame is often referred to as NED (North, East, Down). However, `REP-103 `_ specifies an ENU (East, North, Up) coordinate frame for outdoor navigation. As of this writing, ``robot_localization`` assumes an ENU frame for all IMU data, and does not work with NED frame data. This may change in the future, but for now, users should ensure that data is transformed to the ENU frame before using it with any node in ``robot_localization``. + +The IMU may also be oriented on the robot in a position other than its "neutral" position. For example, the user may mount the IMU on its side, or rotate it so that it faces a direction other than the front of the robot. This offset is typically specified by a static transform from the ``base_link_frame`` parameter to the IMU message's ``frame_id``. The state estimation nodes in ``robot_localization`` will automatically correct for the orientation of the sensor so that its data aligns with the frame specified by the ``base_link_frame`` parameter. + +Handling tf_prefix +****************** + +With the migration to `tf2 `_ as of ROS Indigo, ``robot_localization`` still allows for the use of the ``tf_prefix`` parameter, but, in accordance with `tf2 `_, all ``frame_id`` values will have any leading '/' stripped. + +Considerations for Each Sensor Message Type +******************************************* + +Odometry +======== + +Many robot platforms come equipped with wheel encoders that provide instantaneous translational and rotational velocity. Many also internally integrate these velocities to generate a position estimate. If you are responsible for this data, or can edit it, keep the following in mind: + +1. **Velocities/Poses:** `robot_localization` can integrate velocities or absolute pose information. In general, the best practice is: + + * If the odometry provides both position and linear velocity, fuse the linear velocity. + * If the odometry provides both orientation and angular velocity, fuse the orientation. + + .. note:: If you have two sources of orientation data, then you'll want to be careful. If both produce orientations with accurate covariance matrices, it's safe to fuse the orientations. If, however, one or both under-reports its covariance, then you should only fuse the orientation data from the more accurate sensor. For the other sensor, use the angular velocity (if it's provided), or continue to fuse the absolute orientation data, but turn `_differential` mode on for that sensor. + +2. **frame_id:** See the section on coordinate frames and transforms above. + +3. **Covariance:** Covariance values **matter** to ``robot_localization``. `robot_pose_ekf `_ attempts to fuse all pose variables in an odometry message. Some robots' drivers have been written to accommodate its requirements. This means that if a given sensor does not produce a certain variable (e.g., a robot that doesn't report :math:`Z` position), then the only way to get ``robot_pose_ekf`` to ignore it is to inflate its variance to a very large value (on the order of :math:`1e3`) so that the variable in question is effectively ignored. This practice is both unnecessary and even detrimental to the performance of ``robot_localization``. The exception is the case where you have a second input source measuring the variable in question, in which case inflated covariances will work. + + .. note:: See :ref:`configuring_robot_localization` and :ref:`migrating_from_robot_pose_ekf` for more information. + +4. **Signs:** Adherence to `REP-103 `_ means that you need to ensure that the **signs** of your data are correct. For example, if you have a ground robot and turn it counter-clockwise, then its yaw angle should *increase*, and its yaw velocity should be *positive*. If you drive it *forward*, its X-position should *increase* and its X-velocity should be *positive*. + +5. **Transforms:** Broadcast of the *odom*->*base_link* transform. When the ``world_frame`` parameter is set to the value of the ``odom_frame`` parameter in the configuration file, ``robot_localization``'s state estimation nodes output both a position estimate in a `nav_msgs/Odometry `_ message and a transform from the frame specified by its ``odom_frame`` parameter to its ``base_link_frame`` parameter. However, some robot drivers also broadcast this transform along with their odometry message. If users want ``robot_localization`` to be responsible for this transform, then they need to disable the broadcast of that transform by their robot's driver. This is often exposed as a parameter. + +IMU +=== + +In addition to the following, be sure to read the above section regarding coordinate frames and transforms for IMU data. + +1. **Adherence to specifications:** As with odometry, be sure your data adheres to `REP-103 `_ and the `sensor_msgs/Imu `_ specification. Double-check the signs of your data, and make sure the ``frame_id`` values are correct. + +2. **Covariance:** Echoing the advice for odometry, make sure your covariances make sense. Do not use large values to get the filter to ignore a given variable. Set the configuration for the variable you'd like to ignore to *false*. + +3. **Acceleration:** Be careful with acceleration data. The state estimation nodes in ``robot_localization`` assume that an IMU that is placed in its neutral *right-side-up* position on a flat surface will: + + * Measure **+**:math:`9.81` meters per second squared for the :math:`Z` axis. + * If the sensor is rolled **+**:math:`90` degrees (left side up), the acceleration should be **+**:math:`9.81` meters per second squared for the :math:`Y` axis. + * If the sensor is pitched **+**:math:`90` degrees (front side down), it should read **-**:math:`9.81` meters per second squared for the :math:`X` axis. + +PoseWithCovarianceStamped +========================= + +See the section on odometry. + +TwistWithCovarianceStamped +========================== + +See the section on odometry. + +Common errors +************* + +* Input data doesn't adhere to `REP-103 `_. Make sure that all values (especially orientation angles) increase and decrease in the correct directions. +* Incorrect ``frame_id`` values. Velocity data should be reported in the frame given by the ``base_link_frame`` parameter, or a transform should exist between the ``frame_id`` of the velocity data and the ``base_link_frame``. +* Inflated covariances. The preferred method for ignoring variables in measurements is through the ``odomN_config`` parameter. +* Missing covariances. If you have configured a given sensor to fuse a given variable into the state estimation node, then the variance for that value (i.e., the covariance matrix value at position :math:`(i, i)`, where :math:`i` is the index of that variable) should **not** be :math:`0`. If a :math:`0` variance value is encountered for a variable that is being fused, the state estimation nodes will add a small epsilon value (:math:`1e^{-6}`) to that value. A better solution is for users to set covariances appropriately. + diff --git a/navigations/robot_localization/doc/robot_localization_ias13_revised.pdf b/navigations/robot_localization/doc/robot_localization_ias13_revised.pdf new file mode 100755 index 0000000..4387137 Binary files /dev/null and b/navigations/robot_localization/doc/robot_localization_ias13_revised.pdf differ diff --git a/navigations/robot_localization/doc/state_estimation_nodes.rst b/navigations/robot_localization/doc/state_estimation_nodes.rst new file mode 100755 index 0000000..a913803 --- /dev/null +++ b/navigations/robot_localization/doc/state_estimation_nodes.rst @@ -0,0 +1,336 @@ +State Estimation Nodes +###################### + +ekf_localization_node +********************* +``ekf_localization_node`` is an implementation of an `extended Kalman filter `_. It uses an omnidirectional motion model to project the state forward in time, and corrects that projected estimate using perceived sensor data. + +ukf_localization_node +********************* +``ukf_localization_node`` is an implementation of an `unscented Kalman filter `_. It uses a set of carefully selected sigma points to project the state through the same motion model that is used in the EKF, and then uses those projected sigma points to recover the state estimate and covariance. This eliminates the use of Jacobian matrices and makes the filter more stable. However, it is also more computationally taxing than ``ekf_localization_node``. + +Parameters +********** + +``ekf_localization_node`` and ``ukf_localization_node`` share the vast majority of their parameters, as most of the parameters control how data is treated before being fused with the core filters. + +The relatively large number of parameters available to the state estimation nodes make launch and configuration files the preferred method for starting any of its nodes. The package contains template launch and configuration files to help get users started. + +Parameters Common to *ekf_localization_node* and *ukf_localization_node* +======================================================================== + +Standard Parameters +------------------- + +~frequency +^^^^^^^^^^ +The real-valued frequency, in Hz, at which the filter produces a state estimate. + +.. note:: The filter will not begin computation until it receives at least one message from one of the inputs. + +~sensor_timeout +^^^^^^^^^^^^^^^ +The real-valued period, in seconds, after which we consider any sensor to have timed out. In this event, we carry out a predict cycle on the EKF without correcting it. This parameter can be thought of as the inverse of the minimum frequency at which the filter will generate *new* output. + +~two_d_mode +^^^^^^^^^^^ +If your robot is operating in a planar environment and you're comfortable with ignoring the subtle variations in the ground (as reported by an IMU), then set this to true. It will fuse 0 values for all 3D variables (Z, roll, pitch, and their respective velocities and accelerations). This keeps the covariances for those values from exploding while ensuring that your robot's state estimate remains affixed to the X-Y plane. + +~[frame] +^^^^^^^^^ +Specific parameters: + +* ``~map_frame`` +* ``~odom_frame`` +* ``~base_link_frame`` +* ``~base_link_frame_output`` +* ``~world_frame`` + +These parameters define the operating "mode" for ``robot_localization``. `REP-105 `_ specifies three principal coordinate frames: *map*, *odom*, and *base_link*. *base_link* is the coordinate frame that is affixed to the robot. The robot's position in the *odom* frame will drift over time, but is accurate in the short term and should be continuous. The *map* frame, like the *odom* frame, is a world-fixed coordinate frame, and while it contains the most globally accurate position estimate for your robot, it is subject to discrete jumps, e.g., due to the fusion of GPS data. Here is how to use these parameters: + +1. Set the ``map_frame``, ``odom_frame``, and ``base_link_frame`` parameters to the appropriate frame names for your system. + + .. note:: If your system does not have a ``map_frame``, just remove it, and make sure ``world_frame`` is set to the value of ``odom_frame``. + .. note:: If you are running multiple EKF instances and would like to "override" the output transform and message to have this frame for its ``child_frame_id``, you may set this. The ``base_link_frame_output`` is optional and will default to the ``base_link_frame``. This helps to enable disconnected TF trees when multiple EKF instances are being run. When the final state is computed, we "override" the output transform and message to have this frame for its ``child_frame_id``. + +2. If you are only fusing continuous position data such as wheel encoder odometry, visual odometry, or IMU data, set ``world_frame`` to your ``odom_frame`` value. This is the default behavior for the state estimation nodes in ``robot_localization``, and the most common use for it. +3. If you are fusing global absolute position data that is subject to discrete jumps (e.g., GPS or position updates from landmark observations) then: + + i. Set your ``world_frame`` to your ``map_frame`` value + ii. **Make sure** something else is generating the *odom->base_link* transform. This can even be another instance of a ``robot_localization`` state estimation node. However, that instance should *not* fuse the global data. + +The default values for ``map_frame``, ``odom_frame``, and ``base_link_frame`` are *map*, *odom,* and *base_link,* respectively. The ``base_link_frame_output`` parameter defaults to the value of ``base_link_frame``. The ``world_frame`` parameter defaults to the value of ``odom_frame``. + +~transform_time_offset +^^^^^^^^^^^^^^^^^^^^^^ +Some packages require that your transforms are future-dated by a small time offset. The value of this parameter will be added to the timestamp of *map->odom* or *odom->base_link* transform being generated by the state estimation nodes in ``robot_localization``. + +~transform_timeout +^^^^^^^^^^^^^^^^^^ +The ``robot_localization`` package uses ``tf2``'s ``lookupTransform`` method to request transformations. This parameter specifies how long we would like to wait if a transformation is not available yet. Defaults to 0 if not set. The value 0 means we just get us the latest available (see ``tf2`` implementation) transform so we are not blocking the filter. Specifying a non-zero `transform_timeout` affects the filter's timing since it waits for a maximum of the `transform_timeout` for a transform to become available. This directly implies that mostly the specified desired output rate is not met since the filter has to wait for transforms when updating. + +~[sensor] +^^^^^^^^^ +For each sensor, users need to define this parameter based on the message type. For example, if we define one source of Imu messages and two sources of Odometry messages, the configuration would look like this: + +.. code-block:: xml + + + + + +The index for each parameter name is 0-based (e.g., ``odom0``, ``odom1``, etc.) and must be defined sequentially (e.g., do *not* use ``pose0`` and ``pose2`` if you have not defined ``pose1``). The values for each parameter are the topic name for that sensor. + +~[sensor]_config +^^^^^^^^^^^^^^^^ + +Specific parameters: + +* ``~odomN_config`` +* ``~twistN_config`` +* ``~imuN_config`` +* ``~poseN_config`` + +For each of the sensor messages defined above, users must specify what variables of those messages should be fused into the final state estimate. An example odometry configuration might look like this: + +.. code-block:: xml + + [true, true, false, + false, false, true, + true, false, false, + false, false, true, + false, false, false] + + +The order of the boolean values are :math:`X, Y, Z, roll, pitch, yaw, \dot{X}, \dot{Y}, \dot{Z}, \dot{roll}, \dot{pitch}, \dot{yaw}, \ddot{X}, \ddot{Y}, \ddot{Z}`. In this example, we are fusing :math:`X` and :math:`Y` position, :math:`yaw`, :math:`\dot{X}`, and :math:`\dot{yaw}`. + +.. note:: The specification is done in the ``frame_id`` of the **sensor**, *not* in the ``world_frame`` or ``base_link_frame``. Please see the :doc:`coniguration tutorial ` for more information. + +~[sensor]_queue_size +^^^^^^^^^^^^^^^^^^^^ + +Specific parameters: + +* ``~odomN_queue_size`` +* ``~twistN_queue_size`` +* ``~imuN_queue_size`` +* ``~poseN_queue_size`` + +Users can use these parameters to adjust the callback queue sizes for each sensor. This is useful if your ``frequency`` parameter value is much lower than your sensor's frequency, as it allows the filter to incorporate all measurements that arrived in between update cycles. + +~[sensor]_differential +^^^^^^^^^^^^^^^^^^^^^^ + +Specific parameters: + +* ``~odomN_differential`` +* ``~imuN_differential`` +* ``~poseN_differential`` + +For each of the sensor messages defined above *that contain pose information*, users can specify whether the pose variables should be integrated differentially. If a given value is set to *true*, then for a measurement at time :math:`t` from the sensor in question, we first subtract the measurement at time :math:`t-1`, and convert the resulting value to a velocity. This setting is especially useful if your robot has two sources of absolute pose information, e.g., yaw measurements from odometry and an IMU. In that case, if the variances on the input sources are not configured correctly, these measurements may get out of sync with one another and cause oscillations in the filter, but by integrating one or both of them differentially, we avoid this scenario. + +Users should take care when using this parameter for orientation data, as the conversion to velocity means that the covariance for orientation state variables will grow without bound (unless another source of absolute orientation data is being fused). If you simply want all of your pose variables to start at :math:`0`, then please use the ``_relative`` parameter. + +.. note:: If you are fusing GPS information via ``navsat_transform_node`` or ``utm_transform_node``, you should make sure that the ``_differential`` setting is *false.* + +~[sensor]_relative +^^^^^^^^^^^^^^^^^^ + +Specific parameters: + +* ``~odomN_relative`` +* ``~imuN_relative`` +* ``~poseN_relative`` + +If this parameter is set to ``true``, then any measurements from this sensor will be fused relative to the first measurement received from that sensor. This is useful if, for example, you want your state estimate to always start at :math:`(0, 0, 0)` and with :math:`roll, pitch,` and :math:`yaw` values of :math:`(0, 0, 0)`. It is similar to the ``_differential`` parameter, but instead of removing the measurement at time :math:`t-1`, we always remove the measurement at time :math:`0`, and the measurement is not converted to a velocity. + +~imuN_remove_gravitational_acceleration +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +If fusing accelerometer data from IMUs, this parameter determines whether or not acceleration due to gravity is removed from the acceleration measurement before fusing it. + +.. note:: This assumes that the IMU that is providing the acceleration data is also producing an absolute orientation. The orientation data is required to correctly remove gravitational acceleration. + +~gravitational_acceleration +^^^^^^^^^^^^^^^^^^^^^^^^^^^ +If ``imuN_remove_gravitational_acceleration`` is set to ``true``, then this parameter determines the acceleration in Z due to gravity that will be removed from the IMU's linear acceleration data. Default is 9.80665 (m/s^2). + +~initial_state +^^^^^^^^^^^^^^ +Starts the filter with the specified state. The state is given as a 15-D vector of doubles, in the same order as the sensor configurations. For example, to start your robot at a position of :math:`(5.0, 4.0, 3.0)`, a :math:`yaw` of :math:`1.57`, and a linear velocity of :math:`(0.1, 0.2, 0.3)`, you would use: + +.. code-block:: xml + + [5.0, 4.0, 3.0, + 0.0, 0.0, 1.57, + 0.1, 0.2, 0.3, + 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0] + +~publish_tf +^^^^^^^^^^^ +If *true*, the state estimation node will publish the transform from the frame specified by the ``world_frame`` parameter to the frame specified by the ``base_link_frame`` parameter. Defaults to *true*. + +~publish_acceleration +^^^^^^^^^^^^^^^^^^^^^ +If *true*, the state estimation node will publish the linear acceleration state. Defaults to *false*. + +~permit_corrected_publication +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +When the state estimation nodes publish the state at time `t`, but then receive a measurement with a timestamp < `t`, they re-publish the corrected state, with the same time stamp as the previous publication. Setting this parameter to *false* disables that behavior. Defaults to *false*. + +~print_diagnostics +^^^^^^^^^^^^^^^^^^ +If true, the state estimation node will publish diagnostic messages to the ``/diagnostics`` topic. This is useful for debugging your configuration and sensor data. + +Advanced Parameters +------------------- + +~use_control +^^^^^^^^^^^^ +If *true*, the state estimation node will listen to the `cmd_vel` topic for a `geometry_msgs/Twist `_ message, and use that to generate an acceleration term. This term is then used in the robot's state prediction. This is especially useful in situations where even small amounts of lag in convergence for a given state variable cause problems in your application (e.g., LIDAR shifting during rotations). Defaults to *false*. + +.. note:: The presence and inclusion of linear acceleration data from an IMU will currently "override" the predicted linear acceleration value. + +~stamped_control +^^^^^^^^^^^^^^^^ +If *true* and ``use_control`` is also *true*, looks for a `geometry_msgs/TwistStamped `_ message instead of a `geometry_msgs/Twist `_ message. + +~control_timeout +^^^^^^^^^^^^^^^^ +If ``use_control`` is set to *true* and no control command is received in this amount of time, given in seconds, the control-based acceleration term ceases to be applied. + +~control_config +^^^^^^^^^^^^^^^ +Controls which variables in the ``cmd_vel`` message are used in state prediction. The order of the values is :math:`\dot{X}, \dot{Y}, \dot{Z}, \dot{roll}, \dot{pitch}, \dot{yaw}`. Only used if ``use_control`` is set to *true*. + +.. code-block:: xml + + [true, false, false, + false, false, true] + +~acceleration_limits +^^^^^^^^^^^^^^^^^^^^ +How rapidly your robot can accelerate for each dimension. Matches the parameter order in ``control_config``. Only used if ``use_control`` is set to *true*. + +.. code-block:: xml + + [1.3, 0.0, 0.0, + 0.0, 0.0, 3.2] + +~deceleration_limits +^^^^^^^^^^^^^^^^^^^^ +How rapidly your robot can decelerate for each dimension. Matches the parameter order in ``control_config``. Only used if ``use_control`` is set to *true*. + +~acceleration_gains +^^^^^^^^^^^^^^^^^^^ +If your robot cannot instantaneously reach its acceleration limit, the permitted change can be controlled with these gains. Only used if ``use_control`` is set to *true*. + +.. code-block:: xml + + [0.8, 0.0, 0.0, + 0.0, 0.0, 0.9] + +~deceleration_gains +^^^^^^^^^^^^^^^^^^^ +If your robot cannot instantaneously reach its deceleration limit, the permitted change can be controlled with these gains. Only used if ``use_control`` is set to *true*. + +~smooth_lagged_data +^^^^^^^^^^^^^^^^^^^ +If any of your sensors produce data with timestamps that are older than the most recent filter update (more plainly, if you have a source of lagged sensor data), setting this parameter to *true* will enable the filter, upon reception of lagged data, to revert to the last state prior to the lagged measurement, then process all measurements until the current time. This is especially useful for measurements that come from nodes that require heavy CPU usage to generate pose estimates (e.g., laser scan matchers), as they are frequently lagged behind the current time. + +~history_length +^^^^^^^^^^^^^^^ +If ``smooth_lagged_data`` is set to *true*, this parameter specifies the number of seconds for which the filter will retain its state and measurement history. This value should be at least as large as the time delta between your lagged measurements and the current time. + +~[sensor]_nodelay +^^^^^^^^^^^^^^^^^ + +Specific parameters: + +* ``~odomN_nodelay`` +* ``~twistN_nodelay`` +* ``~imuN_nodelay`` +* ``~poseN_nodelay`` + +If *true*, sets the `tcpNoDelay` `transport hint `_. There is some evidence that Nagle's algorithm intereferes with the timely reception of large message types, such as the `nav_msgs/Odometry `_ message. Setting this to *true* for an input disables Nagle's algorithm for that subscriber. Defaults to *false*. + +~[sensor]_threshold +^^^^^^^^^^^^^^^^^^^ +Specific parameters: + +* ``~odomN_pose_rejection_threshold`` +* ``odomN_twist_rejection_threshold`` +* ``poseN_rejection_threshold`` +* ``twistN_rejection_threshold`` +* ``imuN_pose_rejection_threshold`` +* ``imuN_angular_velocity_rejection_threshold`` +* ``imuN_linear_acceleration_rejection_threshold`` + +If your data is subject to outliers, use these threshold settings, expressed as `Mahalanobis distances `_, to control how far away from the current vehicle state a sensor measurement is permitted to be. Each defaults to ``numeric_limits::max()`` if unspecified. + +~debug +^^^^^^ +Boolean flag that specifies whether or not to run in debug mode. WARNING: setting this to true will generate a massive amount of data. The data is written to the value of the ``debug_out_file`` parameter. Defaults to *false*. + +~debug_out_file +^^^^^^^^^^^^^^^^ +If ``debug`` is *true*, the file to which debug output is written. + +~process_noise_covariance +^^^^^^^^^^^^^^^^^^^^^^^^^ +The process noise covariance, commonly denoted *Q*, is used to model uncertainty in the prediction stage of the filtering algorithms. It can be difficult to tune, and has been exposed as a parameter for easier customization. This parameter can be left alone, but you will achieve superior results by tuning it. In general, the larger the value for *Q* relative to the variance for a given variable in an input message, the faster the filter will converge to the value in the measurement. + +~dynamic_process_noise_covariance +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +If *true*, will dynamically scale the ``process_noise_covariance`` based on the robot's velocity. This is useful, e.g., when you want your robot's estimate error covariance to stop growing when the robot is stationary. Defaults to *false*. + +~initial_estimate_covariance +^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +The estimate covariance, commonly denoted *P*, defines the error in the current state estimate. The parameter allows users to set the initial value for the matrix, which will affect how quickly the filter converges. For example, if users set the value at position :math:`[0, 0]` to a very small value, e.g., `1e-12`, and then attempt to fuse measurements of X position with a high variance value for :math:`X`, then the filter will be very slow to "trust" those measurements, and the time required for convergence will increase. Again, users should take care with this parameter. When only fusing velocity data (e.g., no absolute pose information), users will likely *not* want to set the initial covariance values for the absolute pose variables to large numbers. This is because those errors are going to grow without bound (owing to the lack of absolute pose measurements to reduce the error), and starting them with large values will not benefit the state estimate. + +~reset_on_time_jump +^^^^^^^^^^^^^^^^^^^ +If set to *true* and ``ros::Time::isSimTime()`` is *true*, the filter will reset to its uninitialized state when a jump back in time is detected on a topic. This is useful when working with bag data, in that the bag can be restarted without restarting the node. + +~predict_to_current_time +^^^^^^^^^^^^^^^^^^^^^^^^ +If set to *true*, the filter predicts and corrects up to the time of the latest measurement (by default) but will now also predict up to the current time step. + +~disabled_at_startup +^^^^^^^^^^^^^^^^^^^^ +If set to *true* will not run the filter on start. + +Node-specific Parameters +------------------------ +The standard and advanced parameters are common to all state estimation nodes in ``robot_localization``. This section details parameters that are unique to their respective state estimation nodes. + +ukf_localization_node +^^^^^^^^^^^^^^^^^^^^^ + +The parameters for ``ukf_localization_node`` follow the nomenclature of the `original paper `_ and `wiki article `_. + +* **~alpha** - Controls the spread of sigma points. Unless you are familiar with unscented Kalman filters, it's probably best for this setting to remain at its default value (0.001). + +* **~kappa** - Also control the spread of sigma points. Unless you are familiar with unscented Kalman filters, it's probably best for this setting to remain at its default value (0). + +* **~beta** - Relates to the distribution of the state vector. The default value of 2 implies that the distribution is Gaussian. Like the other parameters, this should remain unchanged unless the user is familiar with unscented Kalman filters. + +Published Topics +================ + +* ``odometry/filtered`` (`nav_msgs/Odometry `_) +* ``accel/filtered`` (`geometry_msgs/AccelWithCovarianceStamped `_) (if enabled) + +Published Transforms +==================== + +* If the user's ``world_frame`` parameter is set to the value of ``odom_frame``, a transform is published from the frame given by the ``odom_frame`` parameter to the frame given by the ``base_link_frame`` parameter. + +* If the user's ``world_frame`` parameter is set to the value of ``map_frame``, a transform is published from the frame given by the ``map_frame`` parameter to the frame given by the ``odom_frame`` parameter. + + .. note:: This mode assumes that another node is broadcasting the transform from the frame given by the ``odom_frame`` parameter to the frame given by the ``base_link_frame`` parameter. This can be another instance of a ``robot_localization`` state estimation node. + +Services +======== + +* ``set_pose`` - By issuing a `geometry_msgs/PoseWithCovarianceStamped `_ message to the ``set_pose`` topic, users can manually set the state of the filter. This is useful for resetting the filter during testing, and allows for interaction with ``rviz``. Alternatively, the state estimation nodes advertise a ``SetPose`` service, whose type is `robot_localization/SetPose `_. diff --git a/navigations/robot_localization/doc/user_contributed_tutorials.rst b/navigations/robot_localization/doc/user_contributed_tutorials.rst new file mode 100755 index 0000000..0cbe609 --- /dev/null +++ b/navigations/robot_localization/doc/user_contributed_tutorials.rst @@ -0,0 +1,13 @@ +User-Contributed Tutorials +########################## + +Here's a list of user-contributed tutorials for robot_localization! + +Tutorials +========= + +* `ros-sensor-fusion-tutorial `_ + A comprehensive end-to-end tutorial for setting up robot_localization for sensor fusion, as well as running through the necessary concepts. (Includes a practical example of setting it up with ultrasonic beacons!) + +* `Kapernikov: The ROS robot_localization package `_ + The documentation of the robot_localization package is quite clear once you know how it works. However, it lacks a hands-on tutorial to help you with your first steps. There are some great examples on how to set up the robot_localization package, but they require good working hardware. This tutorial tries to bridge the gap, using the turtlesim package as a virtual robot. diff --git a/navigations/robot_localization/include/robot_localization/ekf.h b/navigations/robot_localization/include/robot_localization/ekf.h new file mode 100755 index 0000000..80218e9 --- /dev/null +++ b/navigations/robot_localization/include/robot_localization/ekf.h @@ -0,0 +1,87 @@ +/* + * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef ROBOT_LOCALIZATION_EKF_H +#define ROBOT_LOCALIZATION_EKF_H + +#include "robot_localization/filter_base.h" + +#include +#include +#include +#include + +namespace RobotLocalization +{ + +//! @brief Extended Kalman filter class +//! +//! Implementation of an extended Kalman filter (EKF). This +//! class derives from FilterBase and overrides the predict() +//! and correct() methods in keeping with the discrete time +//! EKF algorithm. +//! +class Ekf: public FilterBase +{ + public: + //! @brief Constructor for the Ekf class + //! + //! @param[in] args - Generic argument container (not used here, but + //! needed so that the ROS filters can pass arbitrary arguments to + //! templated filter types). + //! + explicit Ekf(std::vector args = std::vector()); + + //! @brief Destructor for the Ekf class + //! + ~Ekf(); + + //! @brief Carries out the correct step in the predict/update cycle. + //! + //! @param[in] measurement - The measurement to fuse with our estimate + //! + void correct(const Measurement &measurement); + + //! @brief Carries out the predict step in the predict/update cycle. + //! + //! Projects the state and error matrices forward using a model of + //! the vehicle's motion. + //! + //! @param[in] referenceTime - The time at which the prediction is being made + //! @param[in] delta - The time step over which to predict. + //! + void predict(const double referenceTime, const double delta); +}; + +} // namespace RobotLocalization + +#endif // ROBOT_LOCALIZATION_EKF_H diff --git a/navigations/robot_localization/include/robot_localization/filter_base.h b/navigations/robot_localization/include/robot_localization/filter_base.h new file mode 100755 index 0000000..825b14c --- /dev/null +++ b/navigations/robot_localization/include/robot_localization/filter_base.h @@ -0,0 +1,534 @@ +/* + * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef ROBOT_LOCALIZATION_FILTER_BASE_H +#define ROBOT_LOCALIZATION_FILTER_BASE_H + +#include "robot_localization/filter_utilities.h" +#include "robot_localization/filter_common.h" + +#include + +#include +#include +#include +#include +#include +#include +#include +#include + +#include + +namespace RobotLocalization +{ + +//! @brief Structure used for storing and comparing measurements +//! (for priority queues) +//! +//! Measurement units are assumed to be in meters and radians. +//! Times are real-valued and measured in seconds. +//! +struct Measurement +{ + // The time stamp of the most recent control term (needed for lagged data) + double latestControlTime_; + + // The Mahalanobis distance threshold in number of sigmas + double mahalanobisThresh_; + + // The real-valued time, in seconds, since some epoch + // (presumably the start of execution, but any will do) + double time_; + + // The topic name for this measurement. Needed + // for capturing previous state values for new + // measurements. + std::string topicName_; + + // This defines which variables within this measurement + // actually get passed into the filter. std::vector + // is generally frowned upon, so we use ints. + std::vector updateVector_; + + // The most recent control vector (needed for lagged data) + Eigen::VectorXd latestControl_; + + // The measurement and its associated covariance + Eigen::VectorXd measurement_; + Eigen::MatrixXd covariance_; + + // We want earlier times to have greater priority + bool operator()(const boost::shared_ptr &a, const boost::shared_ptr &b) + { + return (*this)(*(a.get()), *(b.get())); + } + + bool operator()(const Measurement &a, const Measurement &b) + { + return a.time_ > b.time_; + } + + Measurement() : + latestControlTime_(0.0), + mahalanobisThresh_(std::numeric_limits::max()), + time_(0.0), + topicName_("") + { + } +}; +typedef boost::shared_ptr MeasurementPtr; + +//! @brief Structure used for storing and comparing filter states +//! +//! This structure is useful when higher-level classes need to remember filter history. +//! Measurement units are assumed to be in meters and radians. +//! Times are real-valued and measured in seconds. +//! +struct FilterState +{ + // The time stamp of the most recent measurement for the filter + double lastMeasurementTime_; + + // The time stamp of the most recent control term + double latestControlTime_; + + // The most recent control vector + Eigen::VectorXd latestControl_; + + // The filter state vector + Eigen::VectorXd state_; + + // The filter error covariance matrix + Eigen::MatrixXd estimateErrorCovariance_; + + // We want the queue to be sorted from latest to earliest timestamps. + bool operator()(const FilterState &a, const FilterState &b) + { + return a.lastMeasurementTime_ < b.lastMeasurementTime_; + } + + FilterState() : + lastMeasurementTime_(0.0), + latestControlTime_(0.0) + {} +}; +typedef boost::shared_ptr FilterStatePtr; + +class FilterBase +{ + public: + //! @brief Constructor for the FilterBase class + //! + FilterBase(); + + //! @brief Destructor for the FilterBase class + //! + virtual ~FilterBase(); + + //! @brief Resets filter to its unintialized state + //! + void reset(); + + //! @brief Computes a dynamic process noise covariance matrix using the parameterized state + //! + //! This allows us to, e.g., not increase the pose covariance values when the vehicle is not moving + //! + //! @param[in] state - The STATE_SIZE state vector that is used to generate the dynamic process noise covariance + //! + void computeDynamicProcessNoiseCovariance(const Eigen::VectorXd &state, const double delta); + + //! @brief Carries out the correct step in the predict/update cycle. This method + //! must be implemented by subclasses. + //! + //! @param[in] measurement - The measurement to fuse with the state estimate + //! + virtual void correct(const Measurement &measurement) = 0; + + //! @brief Returns the control vector currently being used + //! + //! @return The control vector + //! + const Eigen::VectorXd& getControl(); + + //! @brief Returns the time at which the control term was issued + //! + //! @return The time the control vector was issued + //! + double getControlTime(); + + //! @brief Gets the value of the debug_ variable. + //! + //! @return True if in debug mode, false otherwise + //! + bool getDebug(); + + //! @brief Gets the estimate error covariance + //! + //! @return A copy of the estimate error covariance matrix + //! + const Eigen::MatrixXd& getEstimateErrorCovariance(); + + //! @brief Gets the filter's initialized status + //! + //! @return True if we've received our first measurement, false otherwise + //! + bool getInitializedStatus(); + + //! @brief Gets the most recent measurement time + //! + //! @return The time at which we last received a measurement + //! + double getLastMeasurementTime(); + + //! @brief Gets the filter's predicted state, i.e., the + //! state estimate before correct() is called. + //! + //! @return A constant reference to the predicted state + //! + const Eigen::VectorXd& getPredictedState(); + + //! @brief Gets the filter's process noise covariance + //! + //! @return A constant reference to the process noise covariance + //! + const Eigen::MatrixXd& getProcessNoiseCovariance(); + + //! @brief Gets the sensor timeout value (in seconds) + //! + //! @return The sensor timeout value + //! + double getSensorTimeout(); + + //! @brief Gets the filter state + //! + //! @return A constant reference to the current state + //! + const Eigen::VectorXd& getState(); + + //! @brief Carries out the predict step in the predict/update cycle. + //! Projects the state and error matrices forward using a model of + //! the vehicle's motion. This method must be implemented by subclasses. + //! + //! @param[in] referenceTime - The time at which the prediction is being made + //! @param[in] delta - The time step over which to predict. + //! + virtual void predict(const double referenceTime, const double delta) = 0; + + //! @brief Does some final preprocessing, carries out the predict/update cycle + //! + //! @param[in] measurement - The measurement object to fuse into the filter + //! + virtual void processMeasurement(const Measurement &measurement); + + //! @brief Sets the most recent control term + //! + //! @param[in] control - The control term to be applied + //! @param[in] controlTime - The time at which the control in question was received + //! + void setControl(const Eigen::VectorXd &control, const double controlTime); + + //! @brief Sets the control update vector and acceleration limits + //! + //! @param[in] updateVector - The values the control term affects + //! @param[in] controlTimeout - Timeout value, in seconds, after which a control is considered stale + //! @param[in] accelerationLimits - The acceleration limits for the control variables + //! @param[in] accelerationGains - Gains applied to the control term-derived acceleration + //! @param[in] decelerationLimits - The deceleration limits for the control variables + //! @param[in] decelerationGains - Gains applied to the control term-derived deceleration + //! + void setControlParams(const std::vector &updateVector, const double controlTimeout, + const std::vector &accelerationLimits, const std::vector &accelerationGains, + const std::vector &decelerationLimits, const std::vector &decelerationGains); + + //! @brief Sets the filter into debug mode + //! + //! NOTE: this will generates a lot of debug output to the provided stream. + //! The value must be a pointer to a valid ostream object. + //! + //! @param[in] debug - Whether or not to place the filter in debug mode + //! @param[in] outStream - If debug is true, then this must have a valid pointer. + //! If the pointer is invalid, the filter will not enter debug mode. If debug is + //! false, outStream is ignored. + //! + void setDebug(const bool debug, std::ostream *outStream = NULL); + + //! @brief Enables dynamic process noise covariance calculation + //! + //! @param[in] dynamicProcessNoiseCovariance - Whether or not to compute dynamic process noise covariance matrices + //! + void setUseDynamicProcessNoiseCovariance(const bool dynamicProcessNoiseCovariance); + + //! @brief Manually sets the filter's estimate error covariance + //! + //! @param[in] estimateErrorCovariance - The state to set as the filter's current state + //! + void setEstimateErrorCovariance(const Eigen::MatrixXd &estimateErrorCovariance); + + //! @brief Sets the filter's last measurement time. + //! + //! @param[in] lastMeasurementTime - The last measurement time of the filter + //! + void setLastMeasurementTime(const double lastMeasurementTime); + + //! @brief Sets the process noise covariance for the filter. + //! + //! This enables external initialization, which is important, as this + //! matrix can be difficult to tune for a given implementation. + //! + //! @param[in] processNoiseCovariance - The STATE_SIZExSTATE_SIZE process noise covariance matrix + //! to use for the filter + //! + void setProcessNoiseCovariance(const Eigen::MatrixXd &processNoiseCovariance); + + //! @brief Sets the sensor timeout + //! + //! @param[in] sensorTimeout - The time, in seconds, for a sensor to be + //! considered having timed out + //! + void setSensorTimeout(const double sensorTimeout); + + //! @brief Manually sets the filter's state + //! + //! @param[in] state - The state to set as the filter's current state + //! + void setState(const Eigen::VectorXd &state); + + //! @brief Ensures a given time delta is valid (helps with bag file playback issues) + //! + //! @param[in] delta - The time delta, in seconds, to validate + //! + void validateDelta(double &delta); + + protected: + //! @brief Method for settings bounds on acceleration values derived from controls + //! @param[in] state - The current state variable (e.g., linear X velocity) + //! @param[in] control - The current control commanded velocity corresponding to the state variable + //! @param[in] accelerationLimit - Limit for acceleration (regardless of driving direction) + //! @param[in] accelerationGain - Gain applied to acceleration control error + //! @param[in] decelerationLimit - Limit for deceleration (moving towards zero, regardless of driving direction) + //! @param[in] decelerationGain - Gain applied to deceleration control error + //! @return a usable acceleration estimate for the control vector + //! + inline double computeControlAcceleration(const double state, const double control, const double accelerationLimit, + const double accelerationGain, const double decelerationLimit, const double decelerationGain) + { + FB_DEBUG("---------- FilterBase::computeControlAcceleration ----------\n"); + + const double error = control - state; + const bool sameSign = (::fabs(error) <= ::fabs(control) + 0.01); + const double setPoint = (sameSign ? control : 0.0); + const bool decelerating = ::fabs(setPoint) < ::fabs(state); + double limit = accelerationLimit; + double gain = accelerationGain; + + if (decelerating) + { + limit = decelerationLimit; + gain = decelerationGain; + } + + const double finalAccel = std::min(std::max(gain * error, -limit), limit); + + FB_DEBUG("Control value: " << control << "\n" << + "State value: " << state << "\n" << + "Error: " << error << "\n" << + "Same sign: " << (sameSign ? "true" : "false") << "\n" << + "Set point: " << setPoint << "\n" << + "Decelerating: " << (decelerating ? "true" : "false") << "\n" << + "Limit: " << limit << "\n" << + "Gain: " << gain << "\n" << + "Final is " << finalAccel << "\n"); + + return finalAccel; + } + + //! @brief Keeps the state Euler angles in the range [-pi, pi] + //! + virtual void wrapStateAngles(); + + //! @brief Tests if innovation is within N-sigmas of covariance. Returns true if passed the test. + //! @param[in] innovation - The difference between the measurement and the state + //! @param[in] invCovariance - The innovation error + //! @param[in] nsigmas - Number of standard deviations that are considered acceptable + //! + virtual bool checkMahalanobisThreshold(const Eigen::VectorXd &innovation, + const Eigen::MatrixXd &invCovariance, + const double nsigmas); + + //! @brief Converts the control term to an acceleration to be applied in the prediction step + //! @param[in] referenceTime - The time of the update (measurement used in the prediction step) + //! @param[in] predictionDelta - The amount of time over which we are carrying out our prediction + //! + void prepareControl(const double referenceTime, const double predictionDelta); + + //! @brief Whether or not we've received any measurements + //! + bool initialized_; + + //! @brief Whether or not we apply the control term + //! + bool useControl_; + + //! @brief If true, uses the robot's vehicle state and the static process noise covariance matrix to generate a + //! dynamic process noise covariance matrix + //! + bool useDynamicProcessNoiseCovariance_; + + //! @brief Tracks the time the filter was last updated using a measurement. + //! + //! This value is used to monitor sensor readings with respect to the sensorTimeout_. + //! We also use it to compute the time delta values for our prediction step. + //! + double lastMeasurementTime_; + + //! @brief The time of reception of the most recent control term + //! + double latestControlTime_; + + //! @brief Timeout value, in seconds, after which a control is considered stale + //! + double controlTimeout_; + + //! @brief The updates to the filter - both predict and correct - are driven + //! by measurements. If we get a gap in measurements for some reason, we want + //! the filter to continue estimating. When this gap occurs, as specified by + //! this timeout, we will continue to call predict() at the filter's frequency. + //! + double sensorTimeout_; + + //! @brief Which control variables are being used (e.g., not every vehicle is controllable in Y or Z) + //! + std::vector controlUpdateVector_; + + //! @brief Gains applied to acceleration derived from control term + //! + std::vector accelerationGains_; + + //! @brief Caps the acceleration we apply from control input + //! + std::vector accelerationLimits_; + + //! @brief Gains applied to deceleration derived from control term + //! + std::vector decelerationGains_; + + //! @brief Caps the deceleration we apply from control input + //! + std::vector decelerationLimits_; + + //! @brief Variable that gets updated every time we process a measurement and we have a valid control + //! + Eigen::VectorXd controlAcceleration_; + + //! @brief Latest control term + //! + Eigen::VectorXd latestControl_; + + //! @brief Holds the last predicted state of the filter + //! + Eigen::VectorXd predictedState_; + + //! @brief This is the robot's state vector, which is what we are trying to + //! filter. The values in this vector are what get reported by the node. + //! + Eigen::VectorXd state_; + + //! @brief Covariance matrices can be incredibly unstable. We can + //! add a small value to it at each iteration to help maintain its + //! positive-definite property. + //! + Eigen::MatrixXd covarianceEpsilon_; + + //! @brief Gets updated when useDynamicProcessNoise_ is true + //! + Eigen::MatrixXd dynamicProcessNoiseCovariance_; + + //! @brief This matrix stores the total error in our position + //! estimate (the state_ variable). + //! + Eigen::MatrixXd estimateErrorCovariance_; + + //! @brief We need the identity for a few operations. Better to store it. + //! + Eigen::MatrixXd identity_; + + //! @brief As we move through the world, we follow a predict/update + //! cycle. If one were to imagine a scenario where all we did was make + //! predictions without correcting, the error in our position estimate + //! would grow without bound. This error is stored in the + //! stateEstimateCovariance_ matrix. However, this matrix doesn't answer + //! the question of *how much* our error should grow for each time step. + //! That's where the processNoiseCovariance matrix comes in. When we + //! make a prediction using the transfer function, we add this matrix + //! (times deltaT) to the state estimate covariance matrix. + //! + Eigen::MatrixXd processNoiseCovariance_; + + //! @brief The Kalman filter transfer function + //! + //! Kalman filters and extended Kalman filters project the current + //! state forward in time. This is the "predict" part of the predict/correct + //! cycle. A Kalman filter has a (typically constant) matrix A that defines + //! how to turn the current state, x, into the predicted next state. For an + //! EKF, this matrix becomes a function f(x). However, this function can still + //! be expressed as a matrix to make the math a little cleaner, which is what + //! we do here. Technically, each row in the matrix is actually a function. + //! Some rows will contain many trigonometric functions, which are of course + //! non-linear. In any case, you can think of this as the 'A' matrix in the + //! Kalman filter formulation. + //! + Eigen::MatrixXd transferFunction_; + + //! @brief The Kalman filter transfer function Jacobian + //! + //! The transfer function is allowed to be non-linear in an EKF, but + //! for propagating (predicting) the covariance matrix, we need to linearize + //! it about the current mean (i.e., state). This is done via a Jacobian, + //! which calculates partial derivatives of each row of the transfer function + //! matrix with respect to each state variable. + //! + Eigen::MatrixXd transferFunctionJacobian_; + + //! @brief Used for outputting debug messages + //! + std::ostream *debugStream_; + + private: + //! @brief Whether or not the filter is in debug mode + //! + bool debug_; +}; + +} // namespace RobotLocalization + +#endif // ROBOT_LOCALIZATION_FILTER_BASE_H diff --git a/navigations/robot_localization/include/robot_localization/filter_common.h b/navigations/robot_localization/include/robot_localization/filter_common.h new file mode 100755 index 0000000..30d1c54 --- /dev/null +++ b/navigations/robot_localization/include/robot_localization/filter_common.h @@ -0,0 +1,97 @@ +/* + * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef ROBOT_LOCALIZATION_FILTER_COMMON_H +#define ROBOT_LOCALIZATION_FILTER_COMMON_H + +namespace RobotLocalization +{ + +//! @brief Enumeration that defines the state vector +//! +enum StateMembers +{ + StateMemberX = 0, + StateMemberY, + StateMemberZ, + StateMemberRoll, + StateMemberPitch, + StateMemberYaw, + StateMemberVx, + StateMemberVy, + StateMemberVz, + StateMemberVroll, + StateMemberVpitch, + StateMemberVyaw, + StateMemberAx, + StateMemberAy, + StateMemberAz +}; + +//! @brief Enumeration that defines the control vector +//! +enum ControlMembers +{ + ControlMemberVx, + ControlMemberVy, + ControlMemberVz, + ControlMemberVroll, + ControlMemberVpitch, + ControlMemberVyaw +}; + +//! @brief Global constants that define our state +//! vector size and offsets to groups of values +//! within that state. +const int STATE_SIZE = 15; +const int POSITION_OFFSET = StateMemberX; +const int ORIENTATION_OFFSET = StateMemberRoll; +const int POSITION_V_OFFSET = StateMemberVx; +const int ORIENTATION_V_OFFSET = StateMemberVroll; +const int POSITION_A_OFFSET = StateMemberAx; + +//! @brief Pose and twist messages each +//! contain six variables +const int POSE_SIZE = 6; +const int TWIST_SIZE = 6; +const int POSITION_SIZE = 3; +const int ORIENTATION_SIZE = 3; +const int LINEAR_VELOCITY_SIZE = 3; +const int ACCELERATION_SIZE = 3; + +//! @brief Common variables +const double PI = 3.141592653589793; +const double TAU = 6.283185307179587; + +} // namespace RobotLocalization + +#endif // ROBOT_LOCALIZATION_FILTER_COMMON_H diff --git a/navigations/robot_localization/include/robot_localization/filter_utilities.h b/navigations/robot_localization/include/robot_localization/filter_utilities.h new file mode 100755 index 0000000..61e93c9 --- /dev/null +++ b/navigations/robot_localization/include/robot_localization/filter_utilities.h @@ -0,0 +1,71 @@ +/* + * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef ROBOT_LOCALIZATION_FILTER_UTILITIES_H +#define ROBOT_LOCALIZATION_FILTER_UTILITIES_H + +#include + +#include +#include +#include +#include + +#define FB_DEBUG(msg) if (getDebug()) { *debugStream_ << msg; } + +// Handy methods for debug output +std::ostream& operator<<(std::ostream& os, const Eigen::MatrixXd &mat); +std::ostream& operator<<(std::ostream& os, const Eigen::VectorXd &vec); +std::ostream& operator<<(std::ostream& os, const std::vector &vec); +std::ostream& operator<<(std::ostream& os, const std::vector &vec); + +namespace RobotLocalization +{ +namespace FilterUtilities +{ + + //! @brief Utility method keeping RPY angles in the range [-pi, pi] + //! @param[in] rotation - The rotation to bind + //! @return the bounded value + //! + double clampRotation(double rotation); + + //! @brief Utility method for appending tf2 prefixes cleanly + //! @param[in] tfPrefix - the tf2 prefix to append + //! @param[in, out] frameId - the resulting frame_id value + //! + void appendPrefix(std::string tfPrefix, std::string &frameId); + +} // namespace FilterUtilities +} // namespace RobotLocalization + +#endif // ROBOT_LOCALIZATION_FILTER_UTILITIES_H diff --git a/navigations/robot_localization/include/robot_localization/navsat_conversions.h b/navigations/robot_localization/include/robot_localization/navsat_conversions.h new file mode 100755 index 0000000..6c7ad59 --- /dev/null +++ b/navigations/robot_localization/include/robot_localization/navsat_conversions.h @@ -0,0 +1,216 @@ +/* +* Copyright (C) 2010 Austin Robot Technology, and others +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* 1. Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* 2. Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* 3. Neither the names of the University of Texas at Austin, nor +* Austin Robot Technology, nor the names of other contributors may +* be used to endorse or promote products derived from this +* software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* +* This file contains code from multiple files in the original +* source. The originals can be found here: +* +* https://github.com/austin-robot/utexas-art-ros-pkg/blob/afd147a1eb944fc3dbd138574c39699813f797bf/stacks/art_vehicle/art_common/include/art/UTM.h +* https://github.com/austin-robot/utexas-art-ros-pkg/blob/afd147a1eb944fc3dbd138574c39699813f797bf/stacks/art_vehicle/art_common/include/art/conversions.h +*/ + +#ifndef ROBOT_LOCALIZATION_NAVSAT_CONVERSIONS_H +#define ROBOT_LOCALIZATION_NAVSAT_CONVERSIONS_H + +/** @file + + @brief Universal Transverse Mercator transforms. + Functions to convert (spherical) latitude and longitude to and + from (Euclidean) UTM coordinates. + @author Chuck Gantz- chuck.gantz@globalstar.com + */ + +#include +#include + +#include +#include + +#include +#include + +namespace RobotLocalization +{ +namespace NavsatConversions +{ + +const double RADIANS_PER_DEGREE = M_PI/180.0; +const double DEGREES_PER_RADIAN = 180.0/M_PI; + +// Grid granularity for rounding UTM coordinates to generate MapXY. +const double grid_size = 100000.0; // 100 km grid + +// WGS84 Parameters +#define WGS84_A 6378137.0 // major axis +#define WGS84_B 6356752.31424518 // minor axis +#define WGS84_F 0.0033528107 // ellipsoid flattening +#define WGS84_E 0.0818191908 // first eccentricity +#define WGS84_EP 0.0820944379 // second eccentricity + +// UTM Parameters +#define UTM_K0 0.9996 // scale factor +#define UTM_FE 500000.0 // false easting +#define UTM_FN_N 0.0 // false northing, northern hemisphere +#define UTM_FN_S 10000000.0 // false northing, southern hemisphere +#define UTM_E2 (WGS84_E*WGS84_E) // e^2 +#define UTM_E4 (UTM_E2*UTM_E2) // e^4 +#define UTM_E6 (UTM_E4*UTM_E2) // e^6 +#define UTM_EP2 (UTM_E2/(1-UTM_E2)) // e'^2 + +/** + * Utility function to convert geodetic to UTM position + * + * Units in are floating point degrees (sign for east/west) + * + * Units out are meters + * + * @todo deprecate this interface in favor of LLtoUTM() + */ +static inline void UTM(double lat, double lon, double *x, double *y) +{ + // constants + static const double m0 = (1 - UTM_E2/4 - 3*UTM_E4/64 - 5*UTM_E6/256); + static const double m1 = -(3*UTM_E2/8 + 3*UTM_E4/32 + 45*UTM_E6/1024); + static const double m2 = (15*UTM_E4/256 + 45*UTM_E6/1024); + static const double m3 = -(35*UTM_E6/3072); + + // compute the central meridian + int cm = ((lon >= 0.0) + ? (static_cast(lon) - (static_cast(lon)) % 6 + 3) + : (static_cast(lon) - (static_cast(lon)) % 6 - 3)); + + // convert degrees into radians + double rlat = lat * RADIANS_PER_DEGREE; + double rlon = lon * RADIANS_PER_DEGREE; + double rlon0 = cm * RADIANS_PER_DEGREE; + + // compute trigonometric functions + double slat = sin(rlat); + double clat = cos(rlat); + double tlat = tan(rlat); + + // decide the false northing at origin + double fn = (lat > 0) ? UTM_FN_N : UTM_FN_S; + + double T = tlat * tlat; + double C = UTM_EP2 * clat * clat; + double A = (rlon - rlon0) * clat; + double M = WGS84_A * (m0*rlat + m1*sin(2*rlat) + + m2*sin(4*rlat) + m3*sin(6*rlat)); + double V = WGS84_A / sqrt(1 - UTM_E2*slat*slat); + + // compute the easting-northing coordinates + *x = UTM_FE + UTM_K0 * V * (A + (1-T+C)*pow(A, 3)/6 + + (5-18*T+T*T+72*C-58*UTM_EP2)*pow(A, 5)/120); + *y = fn + UTM_K0 * (M + V * tlat * (A*A/2 + + (5-T+9*C+4*C*C)*pow(A, 4)/24 + + ((61-58*T+T*T+600*C-330*UTM_EP2) + * pow(A, 6)/720))); + + return; +} + +/** + * Convert lat/long to UTM coords. + * + * East Longitudes are positive, West longitudes are negative. + * North latitudes are positive, South latitudes are negative + * Lat and Long are in fractional degrees + * + * @param[out] gamma meridian convergence at point (degrees). + */ +static inline void LLtoUTM(const double Lat, const double Long, + double &UTMNorthing, double &UTMEasting, + std::string &UTMZone, double &gamma) +{ + int zone; + bool northp; + double k_unused; + GeographicLib::UTMUPS::Forward(Lat, Long, zone, northp, UTMEasting, UTMNorthing, gamma, + k_unused, GeographicLib::UTMUPS::zonespec::MATCH); + GeographicLib::MGRS::Forward(zone, northp, UTMEasting, UTMNorthing, -1, UTMZone); +} + +/** + * Convert lat/long to UTM coords. + * + * East Longitudes are positive, West longitudes are negative. + * North latitudes are positive, South latitudes are negative + * Lat and Long are in fractional degrees + */ +static inline void LLtoUTM(const double Lat, const double Long, + double &UTMNorthing, double &UTMEasting, + std::string &UTMZone) +{ + double gamma = 0.0; + LLtoUTM(Lat, Long, UTMNorthing, UTMEasting, UTMZone, gamma); +} + +/** + * Converts UTM coords to lat/long. + * + * East Longitudes are positive, West longitudes are negative. + * North latitudes are positive, South latitudes are negative + * Lat and Long are in fractional degrees. + * + * @param[out] gamma meridian convergence at point (degrees). + */ +static inline void UTMtoLL(const double UTMNorthing, const double UTMEasting, + const std::string &UTMZone, double& Lat, double& Long, + double& /*gamma*/) +{ + int zone; + bool northp; + double x_unused; + double y_unused; + int prec_unused; + GeographicLib::MGRS::Reverse(UTMZone, zone, northp, x_unused, y_unused, prec_unused, true); + GeographicLib::UTMUPS::Reverse(zone, northp, UTMEasting, UTMNorthing, Lat, Long); +} + +/** + * Converts UTM coords to lat/long. + * + * East Longitudes are positive, West longitudes are negative. + * North latitudes are positive, South latitudes are negative + * Lat and Long are in fractional degrees. + */ +static inline void UTMtoLL(const double UTMNorthing, const double UTMEasting, + const std::string &UTMZone, double& Lat, double& Long) +{ + double gamma; + UTMtoLL(UTMNorthing, UTMEasting, UTMZone, Lat, Long, gamma); +} + +} // namespace NavsatConversions +} // namespace RobotLocalization + +#endif // ROBOT_LOCALIZATION_NAVSAT_CONVERSIONS_H diff --git a/navigations/robot_localization/include/robot_localization/navsat_transform.h b/navigations/robot_localization/include/robot_localization/navsat_transform.h new file mode 100755 index 0000000..eb50e26 --- /dev/null +++ b/navigations/robot_localization/include/robot_localization/navsat_transform.h @@ -0,0 +1,382 @@ +/* + * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef ROBOT_LOCALIZATION_NAVSAT_TRANSFORM_H +#define ROBOT_LOCALIZATION_NAVSAT_TRANSFORM_H + +#include +#include +#include +#include + +#include + +#include +#include +#include + +#include +#include +#include +#include + +#include + +#include +#include +#include +#include + +#include + +namespace RobotLocalization +{ + +class NavSatTransform +{ + public: + //! @brief Constructor + //! + NavSatTransform(ros::NodeHandle nh, ros::NodeHandle nh_priv); + + //! @brief Destructor + //! + ~NavSatTransform(); + + private: + //! @brief callback function which is called for periodic updates + //! + void periodicUpdate(const ros::TimerEvent& event); + + //! @brief Computes the transform from the UTM frame to the odom frame + //! + void computeTransform(); + + //! @brief Callback for the datum service + //! + bool datumCallback(robot_localization::SetDatum::Request& request, robot_localization::SetDatum::Response&); + + //! @brief Callback for the to Lat Long service + //! + bool toLLCallback(robot_localization::ToLL::Request& request, robot_localization::ToLL::Response& response); + + //! @brief Callback for the from Lat Long service + //! + bool fromLLCallback(robot_localization::FromLL::Request& request, robot_localization::FromLL::Response& response); + + //! @brief Callback for the UTM zone service + //! + bool setUTMZoneCallback(robot_localization::SetUTMZone::Request& request, + robot_localization::SetUTMZone::Response& response); + + //! @brief Given the pose of the navsat sensor in the cartesian frame, removes the offset from the vehicle's + //! centroid and returns the cartesian-frame pose of said centroid. + //! + void getRobotOriginCartesianPose(const tf2::Transform &gps_cartesian_pose, + tf2::Transform &robot_cartesian_pose, + const ros::Time &transform_time); + + //! @brief Given the pose of the navsat sensor in the world frame, removes the offset from the vehicle's centroid + //! and returns the world-frame pose of said centroid. + //! + void getRobotOriginWorldPose(const tf2::Transform &gps_odom_pose, + tf2::Transform &robot_odom_pose, + const ros::Time &transform_time); + + //! @brief Callback for the GPS fix data + //! @param[in] msg The NavSatFix message to process + //! + void gpsFixCallback(const sensor_msgs::NavSatFixConstPtr& msg); + + //! @brief Callback for the IMU data + //! @param[in] msg The IMU message to process + //! + void imuCallback(const sensor_msgs::ImuConstPtr& msg); + + //! @brief Callback for the odom data + //! @param[in] msg The odometry message to process + //! + void odomCallback(const nav_msgs::OdometryConstPtr& msg); + + //! @brief Converts the odometry data back to GPS and broadcasts it + //! @param[out] filtered_gps The NavSatFix message to prepare + //! + bool prepareFilteredGps(sensor_msgs::NavSatFix &filtered_gps); + + //! @brief Prepares the GPS odometry message before sending + //! @param[out] gps_odom The odometry message to prepare + //! + bool prepareGpsOdometry(nav_msgs::Odometry &gps_odom); + + //! @brief Used for setting the GPS data that will be used to compute the transform + //! @param[in] msg The NavSatFix message to use in the transform + //! + void setTransformGps(const sensor_msgs::NavSatFixConstPtr& msg); + + //! @brief Used for setting the odometry data that will be used to compute the transform + //! @param[in] msg The odometry message to use in the transform + //! + void setTransformOdometry(const nav_msgs::OdometryConstPtr& msg); + + //! @brief Transforms the passed in pose from utm to map frame + //! @param[in] cartesian_pose the pose in cartesian frame to use to transform + //! + nav_msgs::Odometry cartesianToMap(const tf2::Transform& cartesian_pose) const; + + //! @brief Transforms the passed in point from map frame to lat/long + //! @param[in] point the point in map frame to use to transform + //! + void mapToLL(const tf2::Vector3& point, double& latitude, double& longitude, double& altitude) const; + + //! @brief Whether or not we broadcast the cartesian transform + //! + bool broadcast_cartesian_transform_; + + //! @brief Whether to broadcast the cartesian transform as parent frame, default as child + //! + bool broadcast_cartesian_transform_as_parent_frame_; + + //! @brief Whether or not we have new GPS data + //! + //! We only want to compute and broadcast our transformed GPS data if it's new. This variable keeps track of that. + //! + bool gps_updated_; + + //! @brief Whether or not the GPS fix is usable + //! + bool has_transform_gps_; + + //! @brief Signifies that we have received a usable IMU message + //! + bool has_transform_imu_; + + //! @brief Signifies that we have received a usable odometry message + //! + bool has_transform_odom_; + + //! @brief Whether or not we have new odometry data + //! + //! If we're creating filtered GPS messages, then we only want to broadcast them when new odometry data arrives. + //! + bool odom_updated_; + + //! @brief Whether or not we publish filtered GPS messages + //! + bool publish_gps_; + + //! @brief Whether or not we've computed a good heading + //! + bool transform_good_; + + //! @brief Whether we get our datum from the first GPS message or from the set_datum + //! service/parameter + //! + bool use_manual_datum_; + + //! @brief Whether we get the transform's yaw from the odometry or IMU source + //! + bool use_odometry_yaw_; + + //! @brief Whether we use a Local Cartesian (tangent plane ENU) or the UTM coordinates as our cartesian + //! + bool use_local_cartesian_; + + //! @brief When true, do not print warnings for tf lookup failures. + //! + bool tf_silent_failure_; + + //! @brief Local Cartesian projection around gps origin + //! + GeographicLib::LocalCartesian gps_local_cartesian_; + + //! @brief Whether or not to report 0 altitude + //! + //! If this parameter is true, we always report 0 for the altitude of the converted GPS odometry message. + //! + bool zero_altitude_; + + //! @brief Parameter that specifies the magnetic declination for the robot's environment. + //! + double magnetic_declination_; + + //! @brief UTM's meridian convergence + //! + //! Angle between projected meridian (True North) and UTM's grid Y-axis. + //! For UTM projection (Ellipsoidal Transverse Mercator) it is zero on the equator and non-zero everywhere else. + //! It increases as the poles are approached or as we're getting farther from central meridian. + //! + double utm_meridian_convergence_; + + //! @brief IMU's yaw offset + //! + //! Your IMU should read 0 when facing *magnetic* north. If it doesn't, this (parameterized) value gives the offset + //! (NOTE: if you have a magenetic declination, use the parameter setting for that). + //! + double yaw_offset_; + + //! @brief Frame ID of the robot's body frame + //! + //! This is needed for obtaining transforms from the robot's body frame to the frames of sensors (IMU and GPS) + //! + std::string base_link_frame_id_; + + //! @brief The cartesian frame ID, default as 'local_enu' if using Local Cartesian or 'utm' if using the UTM + //! coordinates as our cartesian. + //! + std::string cartesian_frame_id_; + + //! @brief The frame_id of the GPS message (specifies mounting location) + //! + std::string gps_frame_id_; + + //! @brief the UTM zone (zero means UPS) + //! + int utm_zone_; + + //! @brief hemisphere (true means north, false means south) + //! + bool northp_; + + //! @brief Frame ID of the GPS odometry output + //! + //! This will just match whatever your odometry message has + //! + std::string world_frame_id_; + + //! @brief Covariance for most recent odometry data + //! + Eigen::MatrixXd latest_odom_covariance_; + + //! @brief Covariance for most recent GPS/UTM/LocalCartesian data + //! + Eigen::MatrixXd latest_cartesian_covariance_; + + //! @brief Timestamp of the latest good GPS message + //! + //! We assign this value to the timestamp of the odometry message that we output + //! + ros::Time gps_update_time_; + + //! @brief Timestamp of the latest good odometry message + //! + //! We assign this value to the timestamp of the odometry message that we output + //! + ros::Time odom_update_time_; + + //! @brief Parameter that specifies the how long we wait for a transform to become available. + //! + ros::Duration transform_timeout_; + + //! @brief timer calling periodicUpdate + //! + ros::Timer periodicUpdateTimer_; + + //! @brief Latest IMU orientation + //! + tf2::Quaternion transform_orientation_; + + //! @brief Latest GPS data, stored as Cartesian coords + //! + tf2::Transform latest_cartesian_pose_; + + //! @brief Latest odometry pose data + //! + tf2::Transform latest_world_pose_; + + //! @brief Holds the cartesian (UTM or local ENU) pose that is used to compute the transform + //! + tf2::Transform transform_cartesian_pose_; + + //! @brief Latest IMU orientation + //! + tf2::Transform transform_world_pose_; + + //! @brief Holds the Cartesian->odom transform + //! + tf2::Transform cartesian_world_transform_; + + //! @brief Holds the odom->UTM transform for filtered GPS broadcast + //! + tf2::Transform cartesian_world_trans_inverse_; + + //! @brief Publiser for filtered gps data + //! + ros::Publisher filtered_gps_pub_; + + //! @brief GPS subscriber + //! + ros::Subscriber gps_sub_; + + //! @brief Subscribes to imu topic + //! + ros::Subscriber imu_sub_; + + //! @brief Odometry subscriber + //! + ros::Subscriber odom_sub_; + + //! @brief Publisher for gps data + //! + ros::Publisher gps_odom_pub_; + + //! @brief Service for set datum + //! + ros::ServiceServer datum_srv_; + + //! @brief Service for to Lat Long + //! + ros::ServiceServer to_ll_srv_; + + //! @brief Service for from Lat Long + //! + ros::ServiceServer from_ll_srv_; + + //! @brief Service for set UTM zone + //! + ros::ServiceServer set_utm_zone_srv_; + + //! @brief Transform buffer for managing coordinate transforms + //! + tf2_ros::Buffer tf_buffer_; + + //! @brief Transform listener for receiving transforms + //! + tf2_ros::TransformListener tf_listener_; + + //! @brief Used for publishing the static world_frame->cartesian transform + //! + tf2_ros::StaticTransformBroadcaster cartesian_broadcaster_; +}; + +} // namespace RobotLocalization + +#endif // ROBOT_LOCALIZATION_NAVSAT_TRANSFORM_H diff --git a/navigations/robot_localization/include/robot_localization/robot_localization_estimator.h b/navigations/robot_localization/include/robot_localization/robot_localization_estimator.h new file mode 100755 index 0000000..ef862f4 --- /dev/null +++ b/navigations/robot_localization/include/robot_localization/robot_localization_estimator.h @@ -0,0 +1,222 @@ +/* + * Copyright (c) 2016, TNO IVS Helmond. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef ROBOT_LOCALIZATION_ROBOT_LOCALIZATION_ESTIMATOR_H +#define ROBOT_LOCALIZATION_ROBOT_LOCALIZATION_ESTIMATOR_H + +#include +#include +#include +#include + +#include "robot_localization/filter_base.h" +#include "robot_localization/filter_utilities.h" +#include "robot_localization/filter_common.h" + +namespace RobotLocalization +{ + +struct Twist +{ + Eigen::Vector3d linear; + Eigen::Vector3d angular; +}; + +//! @brief Robot Localization Estimator State +//! +//! The Estimator State data structure bundles the state information of the estimator. +//! +struct EstimatorState +{ + EstimatorState(): + time_stamp(0.0), + state(STATE_SIZE), + covariance(STATE_SIZE, STATE_SIZE) + { + state.setZero(); + covariance.setZero(); + } + + //! @brief Time at which this state is/was achieved + double time_stamp; + + //! @brief System state at time = time_stamp + Eigen::VectorXd state; + + //! @brief System state covariance at time = time_stamp + Eigen::MatrixXd covariance; + + friend std::ostream& operator<<(std::ostream &os, const EstimatorState& state) + { + return os << "state:\n - time_stamp: " << state.time_stamp << + "\n - state: \n" << state.state << + " - covariance: \n" << state.covariance; + } +}; + +namespace EstimatorResults +{ +enum EstimatorResult +{ + ExtrapolationIntoFuture = 0, + Interpolation, + ExtrapolationIntoPast, + Exact, + EmptyBuffer, + Failed +}; +} // namespace EstimatorResults +typedef EstimatorResults::EstimatorResult EstimatorResult; + +namespace FilterTypes +{ +enum FilterType +{ + EKF = 0, + UKF, + NotDefined +}; +} // namespace FilterTypes +typedef FilterTypes::FilterType FilterType; + +//! @brief Robot Localization Listener class +//! +//! The Robot Localization Estimator class buffers states of and inputs to a system and can interpolate and extrapolate +//! based on a given system model. +//! +class RobotLocalizationEstimator +{ +public: + //! @brief Constructor for the RobotLocalizationListener class + //! + //! @param[in] args - Generic argument container (not used here, but needed so that the ROS filters can pass arbitrary + //! arguments to templated filter types). + //! + explicit RobotLocalizationEstimator(unsigned int buffer_capacity, + FilterType filter_type, + const Eigen::MatrixXd& process_noise_covariance, + const std::vector& filter_args = std::vector()); + + //! @brief Destructor for the RobotLocalizationListener class + //! + virtual ~RobotLocalizationEstimator(); + + //! @brief Sets the current internal state of the listener. + //! + //! @param[in] state - The new state vector to set the internal state to + //! + void setState(const EstimatorState& state); + + //! @brief Returns the state at a given time + //! + //! Projects the current state and error matrices forward using a model of the robot's motion. + //! + //! @param[in] time - The time to which the prediction is being made + //! @param[out] state - The returned state at the given time + //! + //! @return GetStateResult enum + //! + EstimatorResult getState(const double time, EstimatorState &state) const; + + //! @brief Clears the internal state buffer + //! + void clearBuffer(); + + //! @brief Sets the buffer capacity + //! + //! @param[in] capacity - The new buffer capacity + //! + void setBufferCapacity(const int capacity); + + //! @brief Returns the buffer capacity + //! + //! Returns the number of EstimatorState objects that can be pushed to the buffer before old ones are dropped. (The + //! capacity of the buffer). + //! + //! @return buffer capacity + //! + unsigned int getBufferCapacity() const; + + //! @brief Returns the current buffer size + //! + //! Returns the number of EstimatorState objects currently in the buffer. + //! + //! @return current buffer size + //! + unsigned int getSize() const; + +private: + friend std::ostream& operator<<(std::ostream &os, const RobotLocalizationEstimator& rle) + { + for ( boost::circular_buffer::const_iterator it = rle.state_buffer_.begin(); + it != rle.state_buffer_.end(); ++it ) + { + os << *it << "\n"; + } + return os; + } + + //! @brief Extrapolates the given state to a requested time stamp + //! + //! @param[in] boundary_state - state from which to extrapolate + //! @param[in] requested_time - time stamp to extrapolate to + //! @param[out] state_at_req_time - predicted state at requested time + //! + void extrapolate(const EstimatorState& boundary_state, + const double requested_time, + EstimatorState& state_at_req_time) const; + + //! @brief Interpolates the given state to a requested time stamp + //! + //! @param[in] given_state_1 - last state update before requested time + //! @param[in] given_state_2 - next state update after requested time + //! @param[in] requested_time - time stamp to extrapolate to + //! @param[out] state_at_req_time - predicted state at requested time + //! + void interpolate(const EstimatorState& given_state_1, const EstimatorState& given_state_2, + const double requested_time, EstimatorState& state_at_req_time) const; + + //! + //! @brief The buffer holding the system states that have come in. Interpolation and extrapolation is done starting + //! from these states. + //! + boost::circular_buffer state_buffer_; + + //! + //! @brief A pointer to the filter instance that is used for extrapolation + //! + FilterBase* filter_; +}; + +} // namespace RobotLocalization + +#endif // ROBOT_LOCALIZATION_ROBOT_LOCALIZATION_ESTIMATOR_H diff --git a/navigations/robot_localization/include/robot_localization/ros_filter.h b/navigations/robot_localization/include/robot_localization/ros_filter.h new file mode 100755 index 0000000..9eb6bf7 --- /dev/null +++ b/navigations/robot_localization/include/robot_localization/ros_filter.h @@ -0,0 +1,767 @@ +/* + * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef ROBOT_LOCALIZATION_ROS_FILTER_H +#define ROBOT_LOCALIZATION_ROS_FILTER_H + +#include "robot_localization/ros_filter_utilities.h" +#include "robot_localization/filter_common.h" +#include "robot_localization/filter_base.h" + +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include + +#include + +#include +#include +#include +#include +#include +#include +#include +#include + +namespace RobotLocalization +{ + +struct CallbackData +{ + CallbackData(const std::string &topicName, + const std::vector &updateVector, + const int updateSum, + const bool differential, + const bool relative, + const bool pose_use_child_frame, + const double rejectionThreshold) : + topicName_(topicName), + updateVector_(updateVector), + updateSum_(updateSum), + differential_(differential), + relative_(relative), + pose_use_child_frame_(pose_use_child_frame), + rejectionThreshold_(rejectionThreshold) + { + } + + std::string topicName_; + std::vector updateVector_; + int updateSum_; + bool differential_; + bool relative_; + bool pose_use_child_frame_; + double rejectionThreshold_; +}; + +typedef std::priority_queue, Measurement> MeasurementQueue; +typedef std::deque MeasurementHistoryDeque; +typedef std::deque FilterStateHistoryDeque; + +template class RosFilter +{ + public: + //! @brief Constructor + //! + //! The RosFilter constructor makes sure that anyone using + //! this template is doing so with the correct object type + //! + explicit RosFilter(ros::NodeHandle nh, + ros::NodeHandle nh_priv, + std::string node_name, + std::vector args = std::vector()); + + //! @brief Constructor + //! + //! The RosFilter constructor makes sure that anyone using + //! this template is doing so with the correct object type + //! + explicit RosFilter(ros::NodeHandle nh, ros::NodeHandle nh_priv, std::vector args = std::vector()); + + //! @brief Destructor + //! + //! Clears out the message filters and topic subscribers. + //! + ~RosFilter(); + + //! @brief Initialize filter + // + void initialize(); + + //! @brief Resets the filter to its initial state + //! + void reset(); + + //! @brief Service callback to toggle processing measurements for a standby mode but continuing to publish + //! @param[in] request - The state requested, on (True) or off (False) + //! @param[out] response - status if upon success + //! @return boolean true if successful, false if not + bool toggleFilterProcessingCallback(robot_localization::ToggleFilterProcessing::Request&, + robot_localization::ToggleFilterProcessing::Response&); + + //! @brief Callback method for receiving all acceleration (IMU) messages + //! @param[in] msg - The ROS IMU message to take in. + //! @param[in] callbackData - Relevant static callback data + //! @param[in] targetFrame - The target frame_id into which to transform the data + //! + void accelerationCallback(const sensor_msgs::Imu::ConstPtr &msg, + const CallbackData &callbackData, + const std::string &targetFrame); + + //! @brief Callback method for receiving non-stamped control input + //! @param[in] msg - The ROS twist message to take in + //! + void controlCallback(const geometry_msgs::Twist::ConstPtr &msg); + + //! @brief Callback method for receiving stamped control input + //! @param[in] msg - The ROS stamped twist message to take in + //! + void controlCallback(const geometry_msgs::TwistStamped::ConstPtr &msg); + + //! @brief Adds a measurement to the queue of measurements to be processed + //! + //! @param[in] topicName - The name of the measurement source (only used for debugging) + //! @param[in] measurement - The measurement to enqueue + //! @param[in] measurementCovariance - The covariance of the measurement + //! @param[in] updateVector - The boolean vector that specifies which variables to update from this measurement + //! @param[in] mahalanobisThresh - Threshold, expressed as a Mahalanobis distance, for outlier rejection + //! @param[in] time - The time of arrival (in seconds) + //! + void enqueueMeasurement(const std::string &topicName, + const Eigen::VectorXd &measurement, + const Eigen::MatrixXd &measurementCovariance, + const std::vector &updateVector, + const double mahalanobisThresh, + const ros::Time &time); + + //! @brief Method for zeroing out 3D variables within measurements + //! @param[out] measurement - The measurement whose 3D variables will be zeroed out + //! @param[out] measurementCovariance - The covariance of the measurement + //! @param[out] updateVector - The boolean update vector of the measurement + //! + //! If we're in 2D mode, then for every measurement from every sensor, we call this. + //! It sets the 3D variables to 0, gives those variables tiny variances, and sets + //! their updateVector values to 1. + //! + void forceTwoD(Eigen::VectorXd &measurement, + Eigen::MatrixXd &measurementCovariance, + std::vector &updateVector); + + //! @brief Retrieves the EKF's output for broadcasting + //! @param[out] message - The standard ROS odometry message to be filled + //! @return true if the filter is initialized, false otherwise + //! + bool getFilteredOdometryMessage(nav_msgs::Odometry &message); + + //! @brief Retrieves the EKF's acceleration output for broadcasting + //! @param[out] message - The standard ROS acceleration message to be filled + //! @return true if the filter is initialized, false otherwise + //! + bool getFilteredAccelMessage(geometry_msgs::AccelWithCovarianceStamped &message); + + //! @brief Callback method for receiving all IMU messages + //! @param[in] msg - The ROS IMU message to take in. + //! @param[in] topicName - The topic name for the IMU message (only used for debug output) + //! @param[in] poseCallbackData - Relevant static callback data for orientation variables + //! @param[in] twistCallbackData - Relevant static callback data for angular velocity variables + //! @param[in] accelCallbackData - Relevant static callback data for linear acceleration variables + //! + //! This method separates out the orientation, angular velocity, and linear acceleration data and + //! passed each on to its respective callback. + //! + void imuCallback(const sensor_msgs::Imu::ConstPtr &msg, const std::string &topicName, + const CallbackData &poseCallbackData, const CallbackData &twistCallbackData, + const CallbackData &accelCallbackData); + + //! @brief Processes all measurements in the measurement queue, in temporal order + //! + //! @param[in] currentTime - The time at which to carry out integration (the current time) + //! + void integrateMeasurements(const ros::Time ¤tTime); + + //! @brief Differentiate angular velocity for angular acceleration + //! + //! @param[in] currentTime - The time at which to carry out differentiation (the current time) + //! + //! Maybe more state variables can be time-differentiated to estimate higher-order states, + //! but now we only focus on obtaining the angular acceleration. It implements a backward- + //! Euler differentiation. + //! + void differentiateMeasurements(const ros::Time ¤tTime); + + //! @brief Loads all parameters from file + //! + void loadParams(); + + //! @brief Callback method for receiving all odometry messages + //! @param[in] msg - The ROS odometry message to take in. + //! @param[in] topicName - The topic name for the odometry message (only used for debug output) + //! @param[in] poseCallbackData - Relevant static callback data for pose variables + //! @param[in] twistCallbackData - Relevant static callback data for twist variables + //! + //! This method simply separates out the pose and twist data into two new messages, and passes them into their + //! respective callbacks + //! + void odometryCallback(const nav_msgs::Odometry::ConstPtr &msg, const std::string &topicName, + const CallbackData &poseCallbackData, const CallbackData &twistCallbackData); + + //! @brief Callback method for receiving all pose messages + //! @param[in] msg - The ROS stamped pose with covariance message to take in + //! @param[in] callbackData - Relevant static callback data + //! @param[in] targetFrame - The target frame_id into which to transform the data + //! @param[in] poseSourceFrame - The source frame_id from which to transform the data + //! @param[in] imuData - Whether this data comes from an IMU + //! + void poseCallback(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &msg, + const CallbackData &callbackData, + const std::string &targetFrame, + const std::string &poseSourceFrame, + const bool imuData); + + //! @brief Callback method for manually setting/resetting the internal pose estimate + //! @param[in] msg - The ROS stamped pose with covariance message to take in + //! + void setPoseCallback(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &msg); + + //! @brief Service callback for manually setting/resetting the internal pose estimate + //! + //! @param[in] request - Custom service request with pose information + //! @return true if successful, false if not + bool setPoseSrvCallback(robot_localization::SetPose::Request& request, + robot_localization::SetPose::Response&); + + //! @brief Service callback for manually enable the filter + //! @param[in] request - N/A + //! @param[out] response - N/A + //! @return boolean true if successful, false if not + bool enableFilterSrvCallback(std_srvs::Empty::Request&, + std_srvs::Empty::Response&); + + //! @brief Callback method for receiving all twist messages + //! @param[in] msg - The ROS stamped twist with covariance message to take in. + //! @param[in] callbackData - Relevant static callback data + //! @param[in] targetFrame - The target frame_id into which to transform the data + //! + void twistCallback(const geometry_msgs::TwistWithCovarianceStamped::ConstPtr &msg, + const CallbackData &callbackData, + const std::string &targetFrame); + + //! @brief Validates filter outputs for NaNs and Infinite values + //! @param[out] message - The standard ROS odometry message to be validated + //! @return true if the filter output is valid, false otherwise + //! + bool validateFilterOutput(const nav_msgs::Odometry &message); + + protected: + //! @brief Finds the latest filter state before the given timestamp and makes it the current state again. + //! + //! This method also inserts all measurements between the older filter timestamp and now into the measurements + //! queue. + //! + //! @param[in] time - The time to which the filter state should revert + //! @return True if restoring the filter succeeded. False if not. + //! + bool revertTo(const double time); + + //! @brief Saves the current filter state in the queue of previous filter states + //! + //! These measurements will be used in backwards smoothing in the event that older measurements come in. + //! @param[in] filter - The filter base object whose state we want to save + //! + void saveFilterState(FilterBase &filter); + + //! @brief Removes measurements and filter states older than the given cutoff time. + //! @param[in] cutoffTime - Measurements and states older than this time will be dropped. + //! + void clearExpiredHistory(const double cutoffTime); + + //! @brief Clears measurement queue + //! + void clearMeasurementQueue(); + + //! @brief Adds a diagnostic message to the accumulating map and updates the error level + //! @param[in] errLevel - The error level of the diagnostic + //! @param[in] topicAndClass - The sensor topic (if relevant) and class of diagnostic + //! @param[in] message - Details of the diagnostic + //! @param[in] staticDiag - Whether or not this diagnostic information is static + //! + void addDiagnostic(const int errLevel, + const std::string &topicAndClass, + const std::string &message, + const bool staticDiag); + + //! @brief Aggregates all diagnostics so they can be published + //! @param[in] wrapper - The diagnostic status wrapper to update + //! + void aggregateDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &wrapper); + + //! @brief Utility method for copying covariances from ROS covariance arrays + //! to Eigen matrices + //! + //! This method copies the covariances and also does some data validation, which is + //! why it requires more parameters than just the covariance containers. + //! @param[in] arr - The source array for the covariance data + //! @param[in] covariance - The destination matrix for the covariance data + //! @param[in] topicName - The name of the source data topic (for debug purposes) + //! @param[in] updateVector - The update vector for the source topic + //! @param[in] offset - The "starting" location within the array/update vector + //! @param[in] dimension - The number of values to copy, starting at the offset + //! + void copyCovariance(const double *arr, + Eigen::MatrixXd &covariance, + const std::string &topicName, + const std::vector &updateVector, + const size_t offset, + const size_t dimension); + + //! @brief Utility method for copying covariances from Eigen matrices to ROS + //! covariance arrays + //! + //! @param[in] covariance - The source matrix for the covariance data + //! @param[in] arr - The destination array + //! @param[in] dimension - The number of values to copy + //! + void copyCovariance(const Eigen::MatrixXd &covariance, + double *arr, + const size_t dimension); + + //! @brief Loads fusion settings from the config file + //! @param[in] topicName - The name of the topic for which to load settings + //! @return The boolean vector of update settings for each variable for this topic + //! + std::vector loadUpdateConfig(const std::string &topicName); + + //! @brief Prepares an IMU message's linear acceleration for integration into the filter + //! @param[in] msg - The IMU message to prepare + //! @param[in] topicName - The name of the topic over which this message was received + //! @param[in] targetFrame - The target tf frame + //! @param[in] updateVector - The update vector for the data source + //! @param[in] measurement - The twist data converted to a measurement + //! @param[in] measurementCovariance - The covariance of the converted measurement + //! + bool prepareAcceleration(const sensor_msgs::Imu::ConstPtr &msg, + const std::string &topicName, + const std::string &targetFrame, + const bool relative, + std::vector &updateVector, + Eigen::VectorXd &measurement, + Eigen::MatrixXd &measurementCovariance); + + //! @brief Prepares a pose message for integration into the filter + //! @param[in] msg - The pose message to prepare + //! @param[in] topicName - The name of the topic over which this message was received + //! @param[in] targetFrame - The target tf frame + //! @param[in] sourceFrame - The source tf frame + //! @param[in] differential - Whether we're carrying out differential integration + //! @param[in] relative - Whether this measurement is processed relative to the first + //! @param[in] imuData - Whether this measurement is from an IMU + //! @param[in,out] updateVector - The update vector for the data source + //! @param[out] measurement - The pose data converted to a measurement + //! @param[out] measurementCovariance - The covariance of the converted measurement + //! @return true indicates that the measurement was successfully prepared, false otherwise + //! + bool preparePose(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &msg, + const std::string &topicName, + const std::string &targetFrame, + const std::string &sourceFrame, + const bool differential, + const bool relative, + const bool imuData, + std::vector &updateVector, + Eigen::VectorXd &measurement, + Eigen::MatrixXd &measurementCovariance); + + //! @brief Prepares a twist message for integration into the filter + //! @param[in] msg - The twist message to prepare + //! @param[in] topicName - The name of the topic over which this message was received + //! @param[in] targetFrame - The target tf frame + //! @param[in,out] updateVector - The update vector for the data source + //! @param[out] measurement - The twist data converted to a measurement + //! @param[out] measurementCovariance - The covariance of the converted measurement + //! @return true indicates that the measurement was successfully prepared, false otherwise + //! + bool prepareTwist(const geometry_msgs::TwistWithCovarianceStamped::ConstPtr &msg, + const std::string &topicName, + const std::string &targetFrame, + std::vector &updateVector, + Eigen::VectorXd &measurement, + Eigen::MatrixXd &measurementCovariance); + + + //! @brief callback function which is called for periodic updates + //! + void periodicUpdate(const ros::TimerEvent& event); + + //! @brief Start the Filter disabled at startup + //! + //! If this is true, the filter reads parameters and prepares publishers and subscribes + //! but does not integrate new messages into the state vector. + //! The filter can be enabled later using a service. + bool disabledAtStartup_; + + //! @brief Whether the filter is enabled or not. See disabledAtStartup_. + bool enabled_; + + //! Whether we'll allow old measurements to cause a re-publication of the updated state + bool permitCorrectedPublication_; + + //! @brief By default, the filter predicts and corrects up to the time of the latest measurement. If this is set + //! to true, the filter does the same, but then also predicts up to the current time step. + //! + bool predictToCurrentTime_; + + //! @brief Whether or not we print diagnostic messages to the /diagnostics topic + //! + bool printDiagnostics_; + + //! @brief Whether we publish the acceleration + //! + bool publishAcceleration_; + + //! @brief Whether we publish the transform from the world_frame to the base_link_frame + //! + bool publishTransform_; + + //! @brief Whether to reset the filters when backwards jump in time is detected + //! + //! This is usually the case when logs are being used and a jump in the logi + //! is done or if a log files restarts from the beginning. + //! + bool resetOnTimeJump_; + + //! @brief Whether or not we use smoothing + //! + bool smoothLaggedData_; + + //! @brief Whether the filter should process new measurements or not. + bool toggledOn_; + + //! @brief Whether or not we're in 2D mode + //! + //! If this is true, the filter binds all 3D variables (Z, + //! roll, pitch, and their respective velocities) to 0 for + //! every measurement. + //! + bool twoDMode_; + + //! @brief Whether or not we use a control term + //! + bool useControl_; + + //! @brief When true, do not print warnings for tf lookup failures. + //! + bool tfSilentFailure_; + + //! @brief The max (worst) dynamic diagnostic level. + //! + int dynamicDiagErrorLevel_; + + //! @brief The max (worst) static diagnostic level. + //! + int staticDiagErrorLevel_; + + //! @brief The frequency of the run loop + //! + double frequency_; + + //! @brief What is the acceleration in Z due to gravity (m/s^2)? Default is +9.80665. + //! + double gravitationalAcc_; + + //! @brief The depth of the history we track for smoothing/delayed measurement processing + //! + //! This is the guaranteed minimum buffer size for which previous states and measurements are kept. + //! + double historyLength_; + + //! @brief minimal frequency + //! + double minFrequency_; + + //! @brief maximal frequency + double maxFrequency_; + + //! @brief tf frame name for the robot's body frame + //! + std::string baseLinkFrameId_; + + //! @brief tf frame name for the robot's body frame + //! + //! When the final state is computed, we "override" the output transform and message to have this frame for its + //! child_frame_id. This helps to enable disconnected TF trees when multiple EKF instances are being run. + //! + std::string baseLinkOutputFrameId_; + + //! @brief tf frame name for the robot's map (world-fixed) frame + //! + std::string mapFrameId_; + + //! @brief tf frame name for the robot's odometry (world-fixed) frame + //! + std::string odomFrameId_; + + //! @brief tf frame name that is the parent frame of the transform that this node will calculate and broadcast. + //! + std::string worldFrameId_; + + //! @brief Used for outputting debug messages + //! + std::ofstream debugStream_; + + //! @brief Contains the state vector variable names in string format + //! + std::vector stateVariableNames_; + + //! @brief Vector to hold our subscribers until they go out of scope + //! + std::vector topicSubs_; + + //! @brief This object accumulates dynamic diagnostics, e.g., diagnostics relating + //! to sensor data. + //! + //! The values are considered transient and are cleared at every iteration. + //! + std::map dynamicDiagnostics_; + + //! @brief Stores the first measurement from each topic for relative measurements + //! + //! When a given sensor is being integrated in relative mode, its first measurement + //! is effectively treated as an offset, and future measurements have this first + //! measurement removed before they are fused. This variable stores the initial + //! measurements. Note that this is different from using differential mode, as in + //! differential mode, pose data is converted to twist data, resulting in boundless + //! error growth for the variables being fused. With relative measurements, the + //! vehicle will start with a 0 heading and position, but the measurements are still + //! fused absolutely. + std::map initialMeasurements_; + + //! @brief Store the last time a message from each topic was received + //! + //! If we're getting messages rapidly, we may accidentally get + //! an older message arriving after a newer one. This variable keeps + //! track of the most recent message time for each subscribed message + //! topic. We also use it when listening to odometry messages to + //! determine if we should be using messages from that topic. + //! + std::map lastMessageTimes_; + + //! @brief We also need the previous covariance matrix for differential data + //! + std::map previousMeasurementCovariances_; + + //! @brief Stores the last measurement from a given topic for differential integration + //! + //! To carry out differential integration, we have to (1) transform + //! that into the target frame (probably the frame specified by + //! @p odomFrameId_), (2) "subtract" the previous measurement from + //! the current measurement, and then (3) transform it again by the previous + //! state estimate. This holds the measurements used for step (2). + //! + std::map previousMeasurements_; + + //! @brief If including acceleration for each IMU input, whether or not we remove acceleration due to gravity + //! + std::map removeGravitationalAcc_; + + //! @brief This object accumulates static diagnostics, e.g., diagnostics relating + //! to the configuration parameters. + //! + //! The values are treated as static and always reported (i.e., this object is never cleared) + //! + std::map staticDiagnostics_; + + //! @brief Last time mark that time-differentiation is calculated + //! + ros::Time lastDiffTime_; + + //! @brief Last record of filtered angular velocity + //! + tf2::Vector3 lastStateTwistRot_; + + //! @brief Calculated angular acceleration from time-differencing + //! + tf2::Vector3 angular_acceleration_; + + //! @brief Covariance of the calculated angular acceleration + //! + Eigen::MatrixXd angular_acceleration_cov_; + + //! @brief The most recent control input + //! + Eigen::VectorXd latestControl_; + + //! @brief Message that contains our latest transform (i.e., state) + //! + //! We use the vehicle's latest state in a number of places, and often + //! use it as a transform, so this is the most convenient variable to + //! use as our global "current state" object + //! + geometry_msgs::TransformStamped worldBaseLinkTransMsg_; + + //! @brief last call of periodicUpdate + //! + ros::Time lastDiagTime_; + + //! @brief The time of the most recent published state + //! + ros::Time lastPublishedStamp_; + + //! @brief Store the last time set pose message was received + //! + //! If we receive a setPose message to reset the filter, we can get in + //! strange situations wherein we process the pose reset, but then even + //! after another spin cycle or two, we can get a new message with a time + //! stamp that is *older* than the setPose message's time stamp. This means + //! we have to check the message's time stamp against the lastSetPoseTime_. + ros::Time lastSetPoseTime_; + + //! @brief The time of the most recent control input + //! + ros::Time latestControlTime_; + + //! @brief For future (or past) dating the world_frame->base_link_frame transform + //! + ros::Duration tfTimeOffset_; + + //! @brief Parameter that specifies the how long we wait for a transform to become available. + //! + ros::Duration tfTimeout_; + + //! @brief Service that allows another node to toggle on/off filter processing while still publishing. + //! Uses a robot_localization ToggleFilterProcessing service. + //! + ros::ServiceServer toggleFilterProcessingSrv_; + + //! @brief timer calling periodicUpdate + //! + ros::Timer periodicUpdateTimer_; + + //! @brief An implicitly time ordered queue of past filter states used for smoothing. + // + // front() refers to the filter state with the earliest timestamp. + // back() refers to the filter state with the latest timestamp. + FilterStateHistoryDeque filterStateHistory_; + + //! @brief A deque of previous measurements which is implicitly ordered from earliest to latest measurement. + // when popped from the measurement priority queue. + // front() refers to the measurement with the earliest timestamp. + // back() refers to the measurement with the latest timestamp. + MeasurementHistoryDeque measurementHistory_; + + //! @brief We process measurements by queueing them up in + //! callbacks and processing them all at once within each + //! iteration + //! + MeasurementQueue measurementQueue_; + + //! @brief Our filter (EKF, UKF, etc.) + //! + T filter_; + + //! @brief Node handle + //! + ros::NodeHandle nh_; + + //! @brief Local node handle (for params) + //! + ros::NodeHandle nhLocal_; + + //! @brief optional acceleration publisher + //! + ros::Publisher accelPub_; + + //! @brief position publisher + //! + ros::Publisher positionPub_; + + //! @brief Subscribes to the control input topic + //! + ros::Subscriber controlSub_; + + //! @brief Subscribes to the set_pose topic (usually published from rviz). Message + //! type is geometry_msgs/PoseWithCovarianceStamped. + //! + ros::Subscriber setPoseSub_; + + //! @brief Service that allows another node to enable the filter. Uses a standard Empty service. + //! + ros::ServiceServer enableFilterSrv_; + + //! @brief Service that allows another node to change the current state and recieve a confirmation. Uses + //! a custom SetPose service. + //! + ros::ServiceServer setPoseSrv_; + + //! @brief Used for updating the diagnostics + //! + diagnostic_updater::Updater diagnosticUpdater_; + + //! @brief Transform buffer for managing coordinate transforms + //! + tf2_ros::Buffer tfBuffer_; + + //! @brief Transform listener for receiving transforms + //! + tf2_ros::TransformListener tfListener_; + + //! @brief broadcaster of worldTransform tfs + //! + tf2_ros::TransformBroadcaster worldTransformBroadcaster_; + + //! @brief optional signaling diagnostic frequency + //! + std::unique_ptr freqDiag_; +}; + +} // namespace RobotLocalization + +#endif // ROBOT_LOCALIZATION_ROS_FILTER_H diff --git a/navigations/robot_localization/include/robot_localization/ros_filter_types.h b/navigations/robot_localization/include/robot_localization/ros_filter_types.h new file mode 100755 index 0000000..635572b --- /dev/null +++ b/navigations/robot_localization/include/robot_localization/ros_filter_types.h @@ -0,0 +1,48 @@ +/* + * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef ROBOT_LOCALIZATION_ROS_FILTER_TYPES_H +#define ROBOT_LOCALIZATION_ROS_FILTER_TYPES_H + +#include "robot_localization/ros_filter.h" +#include "robot_localization/ekf.h" +#include "robot_localization/ukf.h" + +namespace RobotLocalization +{ + +typedef RosFilter RosEkf; +typedef RosFilter RosUkf; + +} + +#endif // ROBOT_LOCALIZATION_ROS_FILTER_TYPES_H diff --git a/navigations/robot_localization/include/robot_localization/ros_filter_utilities.h b/navigations/robot_localization/include/robot_localization/ros_filter_utilities.h new file mode 100755 index 0000000..16346e3 --- /dev/null +++ b/navigations/robot_localization/include/robot_localization/ros_filter_utilities.h @@ -0,0 +1,135 @@ +/* + * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef ROBOT_LOCALIZATION_ROS_FILTER_UTILITIES_H +#define ROBOT_LOCALIZATION_ROS_FILTER_UTILITIES_H + +#include +#include +#include + +#include + +#include +#include +#include +#include + +#define RF_DEBUG(msg) if (filter_.getDebug()) { debugStream_ << msg; } + +// Handy methods for debug output +std::ostream& operator<<(std::ostream& os, const tf2::Vector3 &vec); +std::ostream& operator<<(std::ostream& os, const tf2::Quaternion &quat); +std::ostream& operator<<(std::ostream& os, const tf2::Transform &trans); +std::ostream& operator<<(std::ostream& os, const std::vector &vec); + +namespace RobotLocalization +{ +namespace RosFilterUtilities +{ + +double getYaw(const tf2::Quaternion quat); + +//! @brief Method for safely obtaining transforms. +//! @param[in] buffer - tf buffer object to use for looking up the transform +//! @param[in] targetFrame - The target frame of the desired transform +//! @param[in] sourceFrame - The source frame of the desired transform +//! @param[in] time - The time at which we want the transform +//! @param[in] timeout - How long to block before falling back to last transform +//! @param[out] targetFrameTrans - The resulting transform object +//! @param[in] silent - Whether or not to print transform warnings +//! @return Sets the value of @p targetFrameTrans and returns true if successful, +//! false otherwise. +//! +//! This method attempts to obtain a transform from the @p sourceFrame to the @p +//! targetFrame at the specific @p time. If no transform is available at that time, +//! it attempts to simply obtain the latest transform. If that still fails, then the +//! method checks to see if the transform is going from a given frame_id to itself. +//! If any of these checks succeed, the method sets the value of @p targetFrameTrans +//! and returns true, otherwise it returns false. +//! +bool lookupTransformSafe(const tf2_ros::Buffer &buffer, + const std::string &targetFrame, + const std::string &sourceFrame, + const ros::Time &time, + const ros::Duration &timeout, + tf2::Transform &targetFrameTrans, + const bool silent = false); + +//! @brief Method for safely obtaining transforms. +//! @param[in] buffer - tf buffer object to use for looking up the transform +//! @param[in] targetFrame - The target frame of the desired transform +//! @param[in] sourceFrame - The source frame of the desired transform +//! @param[in] time - The time at which we want the transform +//! @param[out] targetFrameTrans - The resulting transform object +//! @param[in] silent - Whether or not to print transform warnings +//! @return Sets the value of @p targetFrameTrans and returns true if successful, +//! false otherwise. +//! +//! This method attempts to obtain a transform from the @p sourceFrame to the @p +//! targetFrame at the specific @p time. If no transform is available at that time, +//! it attempts to simply obtain the latest transform. If that still fails, then the +//! method checks to see if the transform is going from a given frame_id to itself. +//! If any of these checks succeed, the method sets the value of @p targetFrameTrans +//! and returns true, otherwise it returns false. +//! +bool lookupTransformSafe(const tf2_ros::Buffer &buffer, + const std::string &targetFrame, + const std::string &sourceFrame, + const ros::Time &time, + tf2::Transform &targetFrameTrans, + const bool silent = false); + +//! @brief Utility method for converting quaternion to RPY +//! @param[in] quat - The quaternion to convert +//! @param[out] roll - The converted roll +//! @param[out] pitch - The converted pitch +//! @param[out] yaw - The converted yaw +//! +void quatToRPY(const tf2::Quaternion &quat, double &roll, double &pitch, double &yaw); + +//! @brief Converts our Eigen state vector into a TF transform/pose +//! @param[in] state - The state to convert +//! @param[out] stateTF - The converted state +//! +void stateToTF(const Eigen::VectorXd &state, tf2::Transform &stateTF); + +//! @brief Converts a TF transform/pose into our Eigen state vector +//! @param[in] stateTF - The state to convert +//! @param[out] state - The converted state +//! +void TFtoState(const tf2::Transform &stateTF, Eigen::VectorXd &state); + +} // namespace RosFilterUtilities +} // namespace RobotLocalization + +#endif // ROBOT_LOCALIZATION_ROS_FILTER_UTILITIES_H diff --git a/navigations/robot_localization/include/robot_localization/ros_robot_localization_listener.h b/navigations/robot_localization/include/robot_localization/ros_robot_localization_listener.h new file mode 100755 index 0000000..d0d8ccc --- /dev/null +++ b/navigations/robot_localization/include/robot_localization/ros_robot_localization_listener.h @@ -0,0 +1,171 @@ +/* + * Copyright (c) 2016, TNO IVS Helmond. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef ROBOT_LOCALIZATION_ROS_ROBOT_LOCALIZATION_LISTENER_H +#define ROBOT_LOCALIZATION_ROS_ROBOT_LOCALIZATION_LISTENER_H + +#include "robot_localization/robot_localization_estimator.h" + +#include + +#include +#include +#include +#include +#include +#include + +namespace RobotLocalization +{ + +//! @brief RosRobotLocalizationListener class +//! +//! This class wraps the RobotLocalizationEstimator. It listens to topics over which the (filtered) robot state is +//! published (odom and accel) and pushes them into its instance of the RobotLocalizationEstimator. It exposes a +//! getState method to offer the user the estimated state at a requested time. This class offers the option to run this +//! listener without the need to run a separate node. If you do wish to run this functionality in a separate node, +//! consider the robot localization listener node. +//! +class RosRobotLocalizationListener +{ +public: + //! @brief Constructor + //! + //! The RosRobotLocalizationListener constructor initializes nodehandles, subscribers, a filter for synchronized + //! listening to the topics it subscribes to, and an instance of the RobotLocalizationEstimator. + //! + RosRobotLocalizationListener(); + + //! @brief Destructor + //! + //! Empty destructor + //! + ~RosRobotLocalizationListener(); + + //! @brief Get a state from the localization estimator + //! + //! Requests the predicted state and covariance at a given time from the Robot Localization Estimator. + //! + //! @param[in] time - time of the requested state + //! @param[in] frame_id - frame id of which the state is requested. + //! @param[out] state - state at the requested time + //! @param[out] covariance - covariance at the requested time + //! + //! @return false if buffer is empty, true otherwise + //! + bool getState(const double time, const std::string& frame_id, + Eigen::VectorXd& state, Eigen::MatrixXd& covariance, + std::string world_frame_id = "") const; + + //! @brief Get a state from the localization estimator + //! + //! Overload of getState method for using ros::Time. + //! + //! @param[in] ros_time - ros time of the requested state + //! @param[in] frame_id - frame id of which the state is requested. + //! @param[out] state - state at the requested time + //! @param[out] covariance - covariance at the requested time + //! + //! @return false if buffer is empty, true otherwise + //! + bool getState(const ros::Time& ros_time, const std::string& frame_id, + Eigen::VectorXd& state, Eigen::MatrixXd& covariance, + const std::string& world_frame_id = "") const; + + //! + //! \brief getBaseFrameId Returns the base frame id of the localization listener + //! \return The base frame id + //! + const std::string& getBaseFrameId() const; + + //! + //! \brief getWorldFrameId Returns the world frame id of the localization listener + //! \return The world frame id + //! + const std::string& getWorldFrameId() const; + +private: + //! @brief Callback for odom and accel + //! + //! Puts the information from the odom and accel messages in a Robot Localization Estimator state and sets the most + //! recent state of the estimator. + //! + //! @param[in] odometry message + //! @param[in] accel message + //! + void odomAndAccelCallback(const nav_msgs::Odometry& odom, const geometry_msgs::AccelWithCovarianceStamped& accel); + + //! @brief The core state estimator that facilitates inter- and + //! extrapolation between buffered states. + //! + RobotLocalizationEstimator* estimator_; + + //! @brief A public handle to the ROS node + //! + ros::NodeHandle nh_; + + //! @brief A private handle to the ROS node + //! + ros::NodeHandle nh_p_; + + //! @brief Subscriber to the odometry state topic (output of a filter node) + //! + message_filters::Subscriber odom_sub_; + + //! @brief Subscriber to the acceleration state topic (output of a filter node) + //! + message_filters::Subscriber accel_sub_; + + //! @brief Waits for both an Odometry and an Accel message before calling a single callback function + //! + message_filters::TimeSynchronizer sync_; + + //! @brief Child frame id received from the Odometry message + //! + std::string base_frame_id_; + + //! @brief Frame id received from the odometry message + //! + std::string world_frame_id_; + + //! @brief Tf buffer for looking up transforms + //! + tf2_ros::Buffer tf_buffer_; + + //! @brief Transform listener to fill the tf_buffer + //! + tf2_ros::TransformListener tf_listener_; +}; + +} // namespace RobotLocalization + +#endif // ROBOT_LOCALIZATION_ROS_ROBOT_LOCALIZATION_LISTENER_H diff --git a/navigations/robot_localization/include/robot_localization/ukf.h b/navigations/robot_localization/include/robot_localization/ukf.h new file mode 100755 index 0000000..8f5bb63 --- /dev/null +++ b/navigations/robot_localization/include/robot_localization/ukf.h @@ -0,0 +1,139 @@ +/* + * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef ROBOT_LOCALIZATION_UKF_H +#define ROBOT_LOCALIZATION_UKF_H + +#include "robot_localization/filter_base.h" + +#include +#include +#include +#include + +namespace RobotLocalization +{ + +//! @brief Unscented Kalman filter class +//! +//! Implementation of an unscenter Kalman filter (UKF). This +//! class derives from FilterBase and overrides the predict() +//! and correct() methods in keeping with the discrete time +//! UKF algorithm. The algorithm was derived from the UKF +//! Wikipedia article at +//! (http://en.wikipedia.org/wiki/Kalman_filter#Unscented_Kalman_filter) +//! ...and this paper: +//! J. J. LaViola, Jr., “A comparison of unscented and extended Kalman +//! filtering for estimating quaternion motion,” in Proc. American Control +//! Conf., Denver, CO, June 4–6, 2003, pp. 2435–2440 +//! Obtained here: http://www.cs.ucf.edu/~jjl/pubs/laviola_acc2003.pdf +//! +class Ukf: public FilterBase +{ + public: + //! @brief Constructor for the Ukf class + //! + //! @param[in] args - Generic argument container. It is assumed + //! that args[0] constains the alpha parameter, args[1] contains + //! the kappa parameter, and args[2] contains the beta parameter. + //! + explicit Ukf(std::vector args); + + //! @brief Destructor for the Ukf class + //! + ~Ukf(); + + //! @brief Carries out the correct step in the predict/update cycle. + //! + //! @param[in] measurement - The measurement to fuse with our estimate + //! + void correct(const Measurement &measurement); + + //! @brief Carries out the predict step in the predict/update cycle. + //! + //! Projects the state and error matrices forward using a model of + //! the vehicle's motion. + //! + //! @param[in] referenceTime - The time at which the prediction is being made + //! @param[in] delta - The time step over which to predict. + //! + void predict(const double referenceTime, const double delta); + + protected: + //! @brief Computes the weighted covariance and sigma points + //! + void generateSigmaPoints(); + + //! @brief Carries out the predict step for the posteriori state of a sigma + //! point. + //! + //! Projects the state and error matrices forward using a model of + //! the vehicle's motion. + //! + //! @param[in,out] sigmaPoint - The sigma point (state vector) to project + //! @param[in] delta - The time step over which to project + //! + void projectSigmaPoint(Eigen::VectorXd& sigmaPoint, double delta); + + //! @brief The UKF sigma points + //! + //! Used to sample possible next states during prediction. + //! + std::vector sigmaPoints_; + + //! @brief This matrix is used to generate the sigmaPoints_ + //! + Eigen::MatrixXd weightedCovarSqrt_; + + //! @brief The weights associated with each sigma point when generating + //! a new state + //! + std::vector stateWeights_; + + //! @brief The weights associated with each sigma point when calculating + //! a predicted estimateErrorCovariance_ + //! + std::vector covarWeights_; + + //! @brief Used in weight generation for the sigma points + //! + double lambda_; + + //! @brief Used to determine if we need to re-compute the sigma + //! points when carrying out multiple corrections + //! + bool uncorrected_; +}; + +} // namespace RobotLocalization + +#endif // ROBOT_LOCALIZATION_UKF_H diff --git a/navigations/robot_localization/launch/dual_ekf_navsat_example.launch b/navigations/robot_localization/launch/dual_ekf_navsat_example.launch new file mode 100755 index 0000000..bec3c16 --- /dev/null +++ b/navigations/robot_localization/launch/dual_ekf_navsat_example.launch @@ -0,0 +1,27 @@ + + + + + + + + + + + + + + + + + diff --git a/navigations/robot_localization/launch/ekf_nodelet_template.launch b/navigations/robot_localization/launch/ekf_nodelet_template.launch new file mode 100755 index 0000000..f4f74ea --- /dev/null +++ b/navigations/robot_localization/launch/ekf_nodelet_template.launch @@ -0,0 +1,38 @@ + + + + + + + + + + + + + + + + + + diff --git a/navigations/robot_localization/launch/ekf_template.launch b/navigations/robot_localization/launch/ekf_template.launch new file mode 100755 index 0000000..c5c2bbd --- /dev/null +++ b/navigations/robot_localization/launch/ekf_template.launch @@ -0,0 +1,11 @@ + + + + + + + + diff --git a/navigations/robot_localization/launch/navsat_transform_template.launch b/navigations/robot_localization/launch/navsat_transform_template.launch new file mode 100755 index 0000000..9c2a458 --- /dev/null +++ b/navigations/robot_localization/launch/navsat_transform_template.launch @@ -0,0 +1,51 @@ + + + + + + + + + + + diff --git a/navigations/robot_localization/launch/ukf_template.launch b/navigations/robot_localization/launch/ukf_template.launch new file mode 100755 index 0000000..9d2b0b2 --- /dev/null +++ b/navigations/robot_localization/launch/ukf_template.launch @@ -0,0 +1,11 @@ + + + + + + + + diff --git a/navigations/robot_localization/nodelet_plugins.xml b/navigations/robot_localization/nodelet_plugins.xml new file mode 100755 index 0000000..56b98ef --- /dev/null +++ b/navigations/robot_localization/nodelet_plugins.xml @@ -0,0 +1,27 @@ + + + + ekf_localization_node as nodelet + + + + + + + ukf_localization_node as nodelet + + + + + + + navsat_transform_node as nodelet + + + diff --git a/navigations/robot_localization/package.xml b/navigations/robot_localization/package.xml new file mode 100755 index 0000000..3602e6f --- /dev/null +++ b/navigations/robot_localization/package.xml @@ -0,0 +1,54 @@ + + + robot_localization + 2.7.4 + Provides nonlinear state estimation through sensor fusion of an abritrary number of sensors. + + Tom Moore + + BSD + + http://ros.org/wiki/robot_localization + + Tom Moore + + catkin + + angles + cmake_modules + diagnostic_msgs + diagnostic_updater + eigen + eigen_conversions + geographiclib + geographic_msgs + geometry_msgs + message_filters + nav_msgs + nodelet + roscpp + sensor_msgs + std_msgs + std_srvs + tf2 + tf2_geometry_msgs + tf2_ros + yaml-cpp + + message_generation + python-catkin-pkg + python3-catkin-pkg + roslint + + message_runtime + + rosbag + rostest + rosunit + + + + + + + diff --git a/navigations/robot_localization/params/dual_ekf_navsat_example.yaml b/navigations/robot_localization/params/dual_ekf_navsat_example.yaml new file mode 100755 index 0000000..c6d749d --- /dev/null +++ b/navigations/robot_localization/params/dual_ekf_navsat_example.yaml @@ -0,0 +1,166 @@ +# For parameter descriptions, please refer to the template parameter files for each node. + +ekf_se_odom: + frequency: 30 + sensor_timeout: 0.1 + two_d_mode: false + transform_time_offset: 0.0 + transform_timeout: 0.0 + print_diagnostics: true + debug: false + + map_frame: map + odom_frame: odom + base_link_frame: base_link + world_frame: odom + + odom0: odometry/wheel + odom0_config: [false, false, false, + false, false, false, + true, true, true, + false, false, true, + false, false, false] + odom0_queue_size: 10 + odom0_nodelay: true + odom0_differential: false + odom0_relative: false + + imu0: imu/data + imu0_config: [false, false, false, + true, true, false, + false, false, false, + true, true, true, + true, true, true] + imu0_nodelay: false + imu0_differential: false + imu0_relative: false + imu0_queue_size: 10 + imu0_remove_gravitational_acceleration: true + + use_control: false + + process_noise_covariance: [1e-3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 1e-3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1e-3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0.3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0.3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0.5, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0.5, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0.1, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.3, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.3, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.3, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.3, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.3] + + initial_estimate_covariance: [1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 1.0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1.0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 1.0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 1.0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 1.0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 1.0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1.0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1.0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1.0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1.0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1.0] + +ekf_se_map: + frequency: 30 + sensor_timeout: 0.1 + two_d_mode: false + transform_time_offset: 0.0 + transform_timeout: 0.0 + print_diagnostics: true + debug: false + + map_frame: map + odom_frame: odom + base_link_frame: base_link + world_frame: map + + odom0: odometry/wheel + odom0_config: [false, false, false, + false, false, false, + true, true, true, + false, false, true, + false, false, false] + odom0_queue_size: 10 + odom0_nodelay: true + odom0_differential: false + odom0_relative: false + + odom1: odometry/gps + odom1_config: [true, true, false, + false, false, false, + false, false, false, + false, false, false, + false, false, false] + odom1_queue_size: 10 + odom1_nodelay: true + odom1_differential: false + odom1_relative: false + + imu0: imu/data + imu0_config: [false, false, false, + true, true, false, + false, false, false, + true, true, true, + true, true, true] + imu0_nodelay: true + imu0_differential: false + imu0_relative: false + imu0_queue_size: 10 + imu0_remove_gravitational_acceleration: true + + use_control: false + + process_noise_covariance: [1.0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 1.0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1e-3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0.3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0.3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0.5, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0.5, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0.1, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.3, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.3, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.3, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.3, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.3] + + initial_estimate_covariance: [1.0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 1.0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 1.0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1.0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 1.0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 1.0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 1.0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 1.0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1.0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1.0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1.0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1.0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1.0] + +navsat_transform: + frequency: 30 + delay: 3.0 + magnetic_declination_radians: 0.0429351 # For lat/long 55.944831, -3.186998 + yaw_offset: 1.570796327 # IMU reads 0 facing magnetic north, not east + zero_altitude: false + broadcast_utm_transform: true + publish_filtered_gps: true + use_odometry_yaw: false + wait_for_datum: false + diff --git a/navigations/robot_localization/params/ekf_template.yaml b/navigations/robot_localization/params/ekf_template.yaml new file mode 100755 index 0000000..06e722e --- /dev/null +++ b/navigations/robot_localization/params/ekf_template.yaml @@ -0,0 +1,255 @@ +# The frequency, in Hz, at which the filter will output a position estimate. Note that the filter will not begin +# computation until it receives at least one message from one of the inputs. It will then run continuously at the +# frequency specified here, regardless of whether it receives more measurements. Defaults to 30 if unspecified. +frequency: 30 + +silent_tf_failure: false +# The period, in seconds, after which we consider a sensor to have timed out. In this event, we carry out a predict +# cycle on the EKF without correcting it. This parameter can be thought of as the minimum frequency with which the +# filter will generate new output. Defaults to 1 / frequency if not specified. +sensor_timeout: 0.1 + +# ekf_localization_node and ukf_localization_node both use a 3D omnidirectional motion model. If this parameter is +# set to true, no 3D information will be used in your state estimate. Use this if you are operating in a planar +# environment and want to ignore the effect of small variations in the ground plane that might otherwise be detected +# by, for example, an IMU. Defaults to false if unspecified. +two_d_mode: false + +# Use this parameter to provide an offset to the transform generated by ekf_localization_node. This can be used for +# future dating the transform, which is required for interaction with some other packages. Defaults to 0.0 if +# unspecified. +transform_time_offset: 0.0 + +# Use this parameter to provide specify how long the tf listener should wait for a transform to become available. +# Defaults to 0.0 if unspecified. +transform_timeout: 0.0 + +# If you're having trouble, try setting this to true, and then echo the /diagnostics_agg topic to see if the node is +# unhappy with any settings or data. +print_diagnostics: true + +# Debug settings. Not for the faint of heart. Outputs a ludicrous amount of information to the file specified by +# debug_out_file. I hope you like matrices! Please note that setting this to true will have strongly deleterious +# effects on the performance of the node. Defaults to false if unspecified. +debug: false + +# Defaults to "robot_localization_debug.txt" if unspecified. Please specify the full path. +debug_out_file: /path/to/debug/file.txt + +# Whether to broadcast the transformation over the /tf topic. Defaults to true if unspecified. +publish_tf: true + +# Whether to publish the acceleration state. Defaults to false if unspecified. +publish_acceleration: false + +# Whether we'll allow old measurements to cause a re-publication of the updated state +permit_corrected_publication: false + +# REP-105 (http://www.ros.org/reps/rep-0105.html) specifies four principal coordinate frames: base_link, odom, map, and +# earth. base_link is the coordinate frame that is affixed to the robot. Both odom and map are world-fixed frames. +# The robot's position in the odom frame will drift over time, but is accurate in the short term and should be +# continuous. The odom frame is therefore the best frame for executing local motion plans. The map frame, like the odom +# frame, is a world-fixed coordinate frame, and while it contains the most globally accurate position estimate for your +# robot, it is subject to discrete jumps, e.g., due to the fusion of GPS data or a correction from a map-based +# localization node. The earth frame is used to relate multiple map frames by giving them a common reference frame. +# ekf_localization_node and ukf_localization_node are not concerned with the earth frame. +# Here is how to use the following settings: +# 1. Set the map_frame, odom_frame, and base_link frames to the appropriate frame names for your system. +# 1a. If your system does not have a map_frame, just remove it, and make sure "world_frame" is set to the value of +# odom_frame. +# 2. If you are fusing continuous position data such as wheel encoder odometry, visual odometry, or IMU data, set +# "world_frame" to your odom_frame value. This is the default behavior for robot_localization's state estimation nodes. +# 3. If you are fusing global absolute position data that is subject to discrete jumps (e.g., GPS or position updates +# from landmark observations) then: +# 3a. Set your "world_frame" to your map_frame value +# 3b. MAKE SURE something else is generating the odom->base_link transform. Note that this can even be another state +# estimation node from robot_localization! However, that instance should *not* fuse the global data. +map_frame: map # Defaults to "map" if unspecified +odom_frame: odom # Defaults to "odom" if unspecified +base_link_frame: base_link # Defaults to "base_link" if unspecified +world_frame: odom # Defaults to the value of odom_frame if unspecified + +# The filter accepts an arbitrary number of inputs from each input message type (nav_msgs/Odometry, +# geometry_msgs/PoseWithCovarianceStamped, geometry_msgs/TwistWithCovarianceStamped, +# sensor_msgs/Imu). To add an input, simply append the next number in the sequence to its "base" name, e.g., odom0, +# odom1, twist0, twist1, imu0, imu1, imu2, etc. The value should be the topic name. These parameters obviously have no +# default values, and must be specified. +odom0: example/odom + +# Each sensor reading updates some or all of the filter's state. These options give you greater control over which +# values from each measurement are fed to the filter. For example, if you have an odometry message as input, but only +# want to use its Z position value, then set the entire vector to false, except for the third entry. The order of the +# values is x, y, z, roll, pitch, yaw, vx, vy, vz, vroll, vpitch, vyaw, ax, ay, az. Note that not some message types +# do not provide some of the state variables estimated by the filter. For example, a TwistWithCovarianceStamped message +# has no pose information, so the first six values would be meaningless in that case. Each vector defaults to all false +# if unspecified, effectively making this parameter required for each sensor. +odom0_config: [true, true, false, + false, false, false, + false, false, false, + false, false, true, + false, false, false] + +# If you have high-frequency data or are running with a low frequency parameter value, then you may want to increase +# the size of the subscription queue so that more measurements are fused. +odom0_queue_size: 2 + +# [ADVANCED] Large messages in ROS can exhibit strange behavior when they arrive at a high frequency. This is a result +# of Nagle's algorithm. This option tells the ROS subscriber to use the tcpNoDelay option, which disables Nagle's +# algorithm. +odom0_nodelay: false + +# [ADVANCED] When measuring one pose variable with two sensors, a situation can arise in which both sensors under- +# report their covariances. This can lead to the filter rapidly jumping back and forth between each measurement as they +# arrive. In these cases, it often makes sense to (a) correct the measurement covariances, or (b) if velocity is also +# measured by one of the sensors, let one sensor measure pose, and the other velocity. However, doing (a) or (b) isn't +# always feasible, and so we expose the differential parameter. When differential mode is enabled, all absolute pose +# data is converted to velocity data by differentiating the absolute pose measurements. These velocities are then +# integrated as usual. NOTE: this only applies to sensors that provide pose measurements; setting differential to true +# for twist measurements has no effect. +odom0_differential: false + +# [ADVANCED] When the node starts, if this parameter is true, then the first measurement is treated as a "zero point" +# for all future measurements. While you can achieve the same effect with the differential paremeter, the key +# difference is that the relative parameter doesn't cause the measurement to be converted to a velocity before +# integrating it. If you simply want your measurements to start at 0 for a given sensor, set this to true. +odom0_relative: false + +# [ADVANCED] If your data is subject to outliers, use these threshold settings, expressed as Mahalanobis distances, to +# control how far away from the current vehicle state a sensor measurement is permitted to be. Each defaults to +# numeric_limits::max() if unspecified. It is strongly recommended that these parameters be removed if not +# required. Data is specified at the level of pose and twist variables, rather than for each variable in isolation. +# For messages that have both pose and twist data, the parameter specifies to which part of the message we are applying +# the thresholds. +odom0_pose_rejection_threshold: 5 +odom0_twist_rejection_threshold: 1 + +# Further input parameter examples +odom1: example/another_odom +odom1_config: [false, false, true, + false, false, false, + false, false, false, + false, false, true, + false, false, false] +odom1_differential: false +odom1_relative: true +odom1_queue_size: 2 +odom1_pose_rejection_threshold: 2 +odom1_twist_rejection_threshold: 0.2 +odom1_nodelay: false + +pose0: example/pose +pose0_config: [true, true, false, + false, false, false, + false, false, false, + false, false, false, + false, false, false] +pose0_differential: true +pose0_relative: false +pose0_queue_size: 5 +pose0_rejection_threshold: 2 # Note the difference in parameter name +pose0_nodelay: false + +twist0: example/twist +twist0_config: [false, false, false, + false, false, false, + true, true, true, + false, false, false, + false, false, false] +twist0_queue_size: 3 +twist0_rejection_threshold: 2 +twist0_nodelay: false + +imu0: example/imu +imu0_config: [false, false, false, + true, true, true, + false, false, false, + true, true, true, + true, true, true] +imu0_nodelay: false +imu0_differential: false +imu0_relative: true +imu0_queue_size: 5 +imu0_pose_rejection_threshold: 0.8 # Note the difference in parameter names +imu0_twist_rejection_threshold: 0.8 # +imu0_linear_acceleration_rejection_threshold: 0.8 # + +# [ADVANCED] Some IMUs automatically remove acceleration due to gravity, and others don't. If yours doesn't, please set +# this to true, and *make sure* your data conforms to REP-103, specifically, that the data is in ENU frame. +imu0_remove_gravitational_acceleration: true + +# [ADVANCED] The EKF and UKF models follow a standard predict/correct cycle. During prediction, if there is no +# acceleration reference, the velocity at time t+1 is simply predicted to be the same as the velocity at time t. During +# correction, this predicted value is fused with the measured value to produce the new velocity estimate. This can be +# problematic, as the final velocity will effectively be a weighted average of the old velocity and the new one. When +# this velocity is the integrated into a new pose, the result can be sluggish covergence. This effect is especially +# noticeable with LIDAR data during rotations. To get around it, users can try inflating the process_noise_covariance +# for the velocity variable in question, or decrease the variance of the variable in question in the measurement +# itself. In addition, users can also take advantage of the control command being issued to the robot at the time we +# make the prediction. If control is used, it will get converted into an acceleration term, which will be used during +# predicition. Note that if an acceleration measurement for the variable in question is available from one of the +# inputs, the control term will be ignored. +# Whether or not we use the control input during predicition. Defaults to false. +use_control: true +# Whether the input (assumed to be cmd_vel) is a geometry_msgs/Twist or geometry_msgs/TwistStamped message. Defaults to +# false. +stamped_control: false +# The last issued control command will be used in prediction for this period. Defaults to 0.2. +control_timeout: 0.2 +# Which velocities are being controlled. Order is vx, vy, vz, vroll, vpitch, vyaw. +control_config: [true, false, false, false, false, true] +# Places limits on how large the acceleration term will be. Should match your robot's kinematics. +acceleration_limits: [1.3, 0.0, 0.0, 0.0, 0.0, 3.4] +# Acceleration and deceleration limits are not always the same for robots. +deceleration_limits: [1.3, 0.0, 0.0, 0.0, 0.0, 4.5] +# If your robot cannot instantaneously reach its acceleration limit, the permitted change can be controlled with these +# gains +acceleration_gains: [0.8, 0.0, 0.0, 0.0, 0.0, 0.9] +# If your robot cannot instantaneously reach its deceleration limit, the permitted change can be controlled with these +# gains +deceleration_gains: [1.0, 0.0, 0.0, 0.0, 0.0, 1.0] + +# [ADVANCED] The process noise covariance matrix can be difficult to tune, and can vary for each application, so it is +# exposed as a configuration parameter. This matrix represents the noise we add to the total error after each +# prediction step. The better the omnidirectional motion model matches your system, the smaller these values can be. +# However, if users find that a given variable is slow to converge, one approach is to increase the +# process_noise_covariance diagonal value for the variable in question, which will cause the filter's predicted error +# to be larger, which will cause the filter to trust the incoming measurement more during correction. The values are +# ordered as x, y, z, roll, pitch, yaw, vx, vy, vz, vroll, vpitch, vyaw, ax, ay, az. Defaults to the matrix below if +# unspecified. +process_noise_covariance: [0.05, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0.05, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0.06, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0.03, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0.03, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0.06, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0.025, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0.025, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0.04, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.02, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.015] + +# [ADVANCED] This represents the initial value for the state estimate error covariance matrix. Setting a diagonal +# value (variance) to a large value will result in rapid convergence for initial measurements of the variable in +# question. Users should take care not to use large values for variables that will not be measured directly. The values +# are ordered as x, y, z, roll, pitch, yaw, vx, vy, vz, vroll, vpitch, vyaw, ax, ay, az. Defaults to the matrix below +#if unspecified. +initial_estimate_covariance: [1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9] + diff --git a/navigations/robot_localization/params/navsat_transform_template.yaml b/navigations/robot_localization/params/navsat_transform_template.yaml new file mode 100755 index 0000000..5571720 --- /dev/null +++ b/navigations/robot_localization/params/navsat_transform_template.yaml @@ -0,0 +1,48 @@ +# Frequency of the main run loop +frequency: 30 + +# Delay time, in seconds, before we calculate the transform from the UTM frame to your world frame. This is especially +# important if you have use_odometry_yaw set to true. Defaults to 0. +delay: 3.0 + +# PLEASE READ: Like all nodes in robot_localization, this node assumes that your IMU data is reported in the ENU frame. +# Many IMUs report data in the NED frame, so you'll want to verify that your data is in the correct frame before using +# it. + +# If your IMU does not account for magnetic declination, enter the value for your location here. If you don't know it, +# see http://www.ngdc.noaa.gov/geomag-web/ (make sure to convert the value to radians). This parameter is mandatory. +magnetic_declination_radians: 0 + +# Your IMU's yaw, once the magentic_declination_radians value is added to it, should report 0 when facing east. If it +# doesn't, enter the offset here. Defaults to 0. +yaw_offset: 0.0 + +# If this is true, the altitude is set to 0 in the output odometry message. Defaults to false. +zero_altitude: false + +# If this is true, the transform world_frame->utm transform is broadcast for use by other nodes. Defaults to false. +broadcast_utm_transform: false + +# If this is true, the utm->world_frame transform will be published instead of the world_frame->utm transform. +# Note that broadcast_utm_transform still has to be enabled. Defaults to false. +broadcast_utm_transform_as_parent_frame: false + +# If this is true, all received odometry data is converted back to a lat/lon and published as a NavSatFix message as +# /gps/filtered. Defaults to false. +publish_filtered_gps: false + +# If this is true, the node ignores the IMU data and gets its heading from the odometry source (typically the +# /odometry/filtered topic coming from one of robot_localization's state estimation nodes). BE CAREFUL when using this! +# The yaw value in your odometry source *must* be world-referenced, e.g., you cannot use your odometry source for yaw +# if your yaw data is based purely on integrated velocities. Defaults to false. +use_odometry_yaw: false + +# If true, will retrieve the datum from the 'datum' parameter below, if available. If no 'datum' parameter exists, +# navsat_transform_node will wait until the user calls the 'datum' service with the SetDatum service message. +wait_for_datum: false + +# Instead of using the first GPS location and IMU-based heading for the local-frame origin, users can specify the +# origin (datum) using this parameter. The fields in the parameter represent latitude and longitude in decimal degrees, +# and heading in radians. As navsat_transform_node assumes an ENU standard, a 0 heading corresponds to east. +datum: [55.944904, -3.186693, 0.0] + diff --git a/navigations/robot_localization/params/ukf_template.yaml b/navigations/robot_localization/params/ukf_template.yaml new file mode 100755 index 0000000..683313f --- /dev/null +++ b/navigations/robot_localization/params/ukf_template.yaml @@ -0,0 +1,267 @@ +# The frequency, in Hz, at which the filter will output a position estimate. Note that the filter will not begin +# computation until it receives at least one message from one of the inputs. It will then run continuously at the +# frequency specified here, regardless of whether it receives more measurements. Defaults to 30 if unspecified. +frequency: 30 + +# The period, in seconds, after which we consider a sensor to have timed out. In this event, we carry out a predict +# cycle on the EKF without correcting it. This parameter can be thought of as the minimum frequency with which the +# filter will generate new output. Defaults to 1 / frequency if not specified. +sensor_timeout: 0.1 + +# ekf_localization_node and ukf_localization_node both use a 3D omnidirectional motion model. If this parameter is +# set to true, no 3D information will be used in your state estimate. Use this if you are operating in a planar +# environment and want to ignore the effect of small variations in the ground plane that might otherwise be detected +# by, for example, an IMU. Defaults to false if unspecified. +two_d_mode: false + +# Use this parameter to provide an offset to the transform generated by ekf_localization_node. This can be used for +# future dating the transform, which is required for interaction with some other packages. Defaults to 0.0 if +# unspecified. +transform_time_offset: 0.0 + +# Use this parameter to provide specify how long the tf listener should wait for a transform to become available. +# Defaults to 0.0 if unspecified. +transform_timeout: 0.0 + +# If you're having trouble, try setting this to true, and then echo the /diagnostics_agg topic to see if the node is +# unhappy with any settings or data. +print_diagnostics: true + +# Whether we'll allow old measurements to cause a re-publication of the updated state +permit_corrected_publication: false + +# Debug settings. Not for the faint of heart. Outputs a ludicrous amount of information to the file specified by +# debug_out_file. I hope you like matrices! Please note that setting this to true will have strongly deleterious +# effects on the performance of the node. Defaults to false if unspecified. +debug: false + +# Defaults to "robot_localization_debug.txt" if unspecified. Please specify the full path. +debug_out_file: /path/to/debug/file.txt + +# Whether to broadcast the transformation over the /tf topic. Defaults to true if unspecified. +publish_tf: true + +# Whether to publish the acceleration state. Defaults to false if unspecified. +publish_acceleration: false + +# Whether we'll allow old measurements to cause a re-publication of the updated state +permit_corrected_publication: false + +# REP-105 (http://www.ros.org/reps/rep-0105.html) specifies four principal coordinate frames: base_link, odom, map, and +# earth. base_link is the coordinate frame that is affixed to the robot. Both odom and map are world-fixed frames. +# The robot's position in the odom frame will drift over time, but is accurate in the short term and should be +# continuous. The odom frame is therefore the best frame for executing local motion plans. The map frame, like the odom +# frame, is a world-fixed coordinate frame, and while it contains the most globally accurate position estimate for your +# robot, it is subject to discrete jumps, e.g., due to the fusion of GPS data or a correction from a map-based +# localization node. The earth frame is used to relate multiple map frames by giving them a common reference frame. +# ekf_localization_node and ukf_localization_node are not concerned with the earth frame. +# Here is how to use the following settings: +# 1. Set the map_frame, odom_frame, and base_link frames to the appropriate frame names for your system. +# 1a. If your system does not have a map_frame, just remove it, and make sure "world_frame" is set to the value of +# odom_frame. +# 2. If you are fusing continuous position data such as wheel encoder odometry, visual odometry, or IMU data, set +# "world_frame" to your odom_frame value. This is the default behavior for robot_localization's state estimation nodes. +# 3. If you are fusing global absolute position data that is subject to discrete jumps (e.g., GPS or position updates +# from landmark observations) then: +# 3a. Set your "world_frame" to your map_frame value +# 3b. MAKE SURE something else is generating the odom->base_link transform. Note that this can even be another state +# estimation node from robot_localization! However, that instance should *not* fuse the global data. +map_frame: map # Defaults to "map" if unspecified +odom_frame: odom # Defaults to "odom" if unspecified +base_link_frame: base_link # Defaults to "base_link" if unspecified +world_frame: odom # Defaults to the value of odom_frame if unspecified + +# The filter accepts an arbitrary number of inputs from each input message type (nav_msgs/Odometry, +# geometry_msgs/PoseWithCovarianceStamped, geometry_msgs/TwistWithCovarianceStamped, +# sensor_msgs/Imu). To add an input, simply append the next number in the sequence to its "base" name, e.g., odom0, +# odom1, twist0, twist1, imu0, imu1, imu2, etc. The value should be the topic name. These parameters obviously have no +# default values, and must be specified. +odom0: example/odom + +# Each sensor reading updates some or all of the filter's state. These options give you greater control over which +# values from each measurement are fed to the filter. For example, if you have an odometry message as input, but only +# want to use its Z position value, then set the entire vector to false, except for the third entry. The order of the +# values is x, y, z, roll, pitch, yaw, vx, vy, vz, vroll, vpitch, vyaw, ax, ay, az. Note that not some message types +# do not provide some of the state variables estimated by the filter. For example, a TwistWithCovarianceStamped message +# has no pose information, so the first six values would be meaningless in that case. Each vector defaults to all false +# if unspecified, effectively making this parameter required for each sensor. +odom0_config: [true, true, false, + false, false, false, + false, false, false, + false, false, true, + false, false, false] + +# If you have high-frequency data or are running with a low frequency parameter value, then you may want to increase +# the size of the subscription queue so that more measurements are fused. +odom0_queue_size: 2 + +# [ADVANCED] Large messages in ROS can exhibit strange behavior when they arrive at a high frequency. This is a result +# of Nagle's algorithm. This option tells the ROS subscriber to use the tcpNoDelay option, which disables Nagle's +# algorithm. +odom0_nodelay: false + +# [ADVANCED] When measuring one pose variable with two sensors, a situation can arise in which both sensors under- +# report their covariances. This can lead to the filter rapidly jumping back and forth between each measurement as they +# arrive. In these cases, it often makes sense to (a) correct the measurement covariances, or (b) if velocity is also +# measured by one of the sensors, let one sensor measure pose, and the other velocity. However, doing (a) or (b) isn't +# always feasible, and so we expose the differential parameter. When differential mode is enabled, all absolute pose +# data is converted to velocity data by differentiating the absolute pose measurements. These velocities are then +# integrated as usual. NOTE: this only applies to sensors that provide pose measurements; setting differential to true +# for twist measurements has no effect. +odom0_differential: false + +# [ADVANCED] When the node starts, if this parameter is true, then the first measurement is treated as a "zero point" +# for all future measurements. While you can achieve the same effect with the differential paremeter, the key +# difference is that the relative parameter doesn't cause the measurement to be converted to a velocity before +# integrating it. If you simply want your measurements to start at 0 for a given sensor, set this to true. +odom0_relative: false + +# [ADVANCED] If your data is subject to outliers, use these threshold settings, expressed as Mahalanobis distances, to +# control how far away from the current vehicle state a sensor measurement is permitted to be. Each defaults to +# numeric_limits::max() if unspecified. It is strongly recommended that these parameters be removed if not +# required. Data is specified at the level of pose and twist variables, rather than for each variable in isolation. +# For messages that have both pose and twist data, the parameter specifies to which part of the message we are applying +# the thresholds. +odom0_pose_rejection_threshold: 5 +odom0_twist_rejection_threshold: 1 + +# Further input parameter examples +odom1: example/another_odom +odom1_config: [false, false, true, + false, false, false, + false, false, false, + false, false, true, + false, false, false] +odom1_differential: false +odom1_relative: true +odom1_queue_size: 2 +odom1_pose_rejection_threshold: 2 +odom1_twist_rejection_threshold: 0.2 +odom1_nodelay: false + +pose0: example/pose +pose0_config: [true, true, false, + false, false, false, + false, false, false, + false, false, false, + false, false, false] +pose0_differential: true +pose0_relative: false +pose0_queue_size: 5 +pose0_rejection_threshold: 2 # Note the difference in parameter name +pose0_nodelay: false + +twist0: example/twist +twist0_config: [false, false, false, + false, false, false, + true, true, true, + false, false, false, + false, false, false] +twist0_queue_size: 3 +twist0_rejection_threshold: 2 +twist0_nodelay: false + +imu0: example/imu +imu0_config: [false, false, false, + true, true, true, + false, false, false, + true, true, true, + true, true, true] +imu0_nodelay: false +imu0_differential: false +imu0_relative: true +imu0_queue_size: 5 +imu0_pose_rejection_threshold: 0.8 # Note the difference in parameter names +imu0_twist_rejection_threshold: 0.8 # +imu0_linear_acceleration_rejection_threshold: 0.8 # + +# [ADVANCED] Some IMUs automatically remove acceleration due to gravity, and others don't. If yours doesn't, please set +# this to true, and *make sure* your data conforms to REP-103, specifically, that the data is in ENU frame. +imu0_remove_gravitational_acceleration: true + +# [ADVANCED] The EKF and UKF models follow a standard predict/correct cycle. During prediction, if there is no +# acceleration reference, the velocity at time t+1 is simply predicted to be the same as the velocity at time t. During +# correction, this predicted value is fused with the measured value to produce the new velocity estimate. This can be +# problematic, as the final velocity will effectively be a weighted average of the old velocity and the new one. When +# this velocity is the integrated into a new pose, the result can be sluggish covergence. This effect is especially +# noticeable with LIDAR data during rotations. To get around it, users can try inflating the process_noise_covariance +# for the velocity variable in question, or decrease the variance of the variable in question in the measurement +# itself. In addition, users can also take advantage of the control command being issued to the robot at the time we +# make the prediction. If control is used, it will get converted into an acceleration term, which will be used during +# predicition. Note that if an acceleration measurement for the variable in question is available from one of the +# inputs, the control term will be ignored. +# Whether or not we use the control input during predicition. Defaults to false. +use_control: true +# Whether the input (assumed to be cmd_vel) is a geometry_msgs/Twist or geometry_msgs/TwistStamped message. Defaults to +# false. +stamped_control: false +# The last issued control command will be used in prediction for this period. Defaults to 0.2. +control_timeout: 0.2 +# Which velocities are being controlled. Order is vx, vy, vz, vroll, vpitch, vyaw. +control_config: [true, false, false, false, false, true] +# Places limits on how large the acceleration term will be. Should match your robot's kinematics. +acceleration_limits: [1.3, 0.0, 0.0, 0.0, 0.0, 3.4] +# Acceleration and deceleration limits are not always the same for robots. +deceleration_limits: [1.3, 0.0, 0.0, 0.0, 0.0, 4.5] +# If your robot cannot instantaneously reach its acceleration limit, the permitted change can be controlled with these +# gains +acceleration_gains: [0.8, 0.0, 0.0, 0.0, 0.0, 0.9] +# If your robot cannot instantaneously reach its deceleration limit, the permitted change can be controlled with these +# gains +deceleration_gains: [1.0, 0.0, 0.0, 0.0, 0.0, 1.0] + +# [ADVANCED] The process noise covariance matrix can be difficult to tune, and can vary for each application, so it is +# exposed as a configuration parameter. This matrix represents the noise we add to the total error after each +# prediction step. The better the omnidirectional motion model matches your system, the smaller these values can be. +# However, if users find that a given variable is slow to converge, one approach is to increase the +# process_noise_covariance diagonal value for the variable in question, which will cause the filter's predicted error +# to be larger, which will cause the filter to trust the incoming measurement more during correction. The values are +# ordered as x, y, z, roll, pitch, yaw, vx, vy, vz, vroll, vpitch, vyaw, ax, ay, az. Defaults to the matrix below if +# unspecified. +process_noise_covariance: [0.05, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0.05, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0.06, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0.03, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0.03, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0.06, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0.025, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0.025, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0.04, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.02, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.015] + +# [ADVANCED] This represents the initial value for the state estimate error covariance matrix. Setting a diagonal +# value (variance) to a large value will result in rapid convergence for initial measurements of the variable in +# question. Users should take care not to use large values for variables that will not be measured directly. The values +# are ordered as x, y, z, roll, pitch, yaw, vx, vy, vz, vroll, vpitch, vyaw, ax, ay, az. Defaults to the matrix below +#if unspecified. +initial_estimate_covariance: [1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9] + +# [ADVANCED, UKF ONLY] The alpha and kappa variables control the spread of the sigma points. Unless you are familiar +# with UKFs, it's probably a good idea to leave these alone. +# Defaults to 0.001 if unspecified. +alpha: 0.001 +# Defaults to 0 if unspecified. +kappa: 0 + +# [ADVANCED, UKF ONLY] The beta variable relates to the distribution of the state vector. Again, it's probably best to +# leave this alone if you're uncertain. Defaults to 2 if unspecified. +beta: 2 diff --git a/navigations/robot_localization/rosdoc.yaml b/navigations/robot_localization/rosdoc.yaml new file mode 100755 index 0000000..c9c76e3 --- /dev/null +++ b/navigations/robot_localization/rosdoc.yaml @@ -0,0 +1,6 @@ + - builder: sphinx + sphinx_root_dir: doc + - builder: doxygen + output_dir: api + file_patterns: '*.cpp *.h *.dox *.md' + exclude_patterns: '*/test/*' diff --git a/navigations/robot_localization/src/ekf.cpp b/navigations/robot_localization/src/ekf.cpp new file mode 100755 index 0000000..2076028 --- /dev/null +++ b/navigations/robot_localization/src/ekf.cpp @@ -0,0 +1,389 @@ +/* + * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include "robot_localization/ekf.h" +#include "robot_localization/filter_common.h" + +#include + +#include +#include +#include +#include + + +namespace RobotLocalization +{ + Ekf::Ekf(std::vector) : + FilterBase() // Must initialize filter base! + { + } + + Ekf::~Ekf() + { + } + + void Ekf::correct(const Measurement &measurement) + { + FB_DEBUG("---------------------- Ekf::correct ----------------------\n" << + "State is:\n" << state_ << "\n" + "Topic is:\n" << measurement.topicName_ << "\n" + "Measurement is:\n" << measurement.measurement_ << "\n" + "Measurement topic name is:\n" << measurement.topicName_ << "\n\n" + "Measurement covariance is:\n" << measurement.covariance_ << "\n"); + + // We don't want to update everything, so we need to build matrices that only update + // the measured parts of our state vector. Throughout prediction and correction, we + // attempt to maximize efficiency in Eigen. + + // First, determine how many state vector values we're updating + std::vector updateIndices; + for (size_t i = 0; i < measurement.updateVector_.size(); ++i) + { + if (measurement.updateVector_[i]) + { + // Handle nan and inf values in measurements + if (std::isnan(measurement.measurement_(i))) + { + FB_DEBUG("Value at index " << i << " was nan. Excluding from update.\n"); + } + else if (std::isinf(measurement.measurement_(i))) + { + FB_DEBUG("Value at index " << i << " was inf. Excluding from update.\n"); + } + else + { + updateIndices.push_back(i); + } + } + } + + FB_DEBUG("Update indices are:\n" << updateIndices << "\n"); + + size_t updateSize = updateIndices.size(); + + // Now set up the relevant matrices + Eigen::VectorXd stateSubset(updateSize); // x (in most literature) + Eigen::VectorXd measurementSubset(updateSize); // z + Eigen::MatrixXd measurementCovarianceSubset(updateSize, updateSize); // R + Eigen::MatrixXd stateToMeasurementSubset(updateSize, state_.rows()); // H + Eigen::MatrixXd kalmanGainSubset(state_.rows(), updateSize); // K + Eigen::VectorXd innovationSubset(updateSize); // z - Hx + + stateSubset.setZero(); + measurementSubset.setZero(); + measurementCovarianceSubset.setZero(); + stateToMeasurementSubset.setZero(); + kalmanGainSubset.setZero(); + innovationSubset.setZero(); + + // Now build the sub-matrices from the full-sized matrices + for (size_t i = 0; i < updateSize; ++i) + { + measurementSubset(i) = measurement.measurement_(updateIndices[i]); + stateSubset(i) = state_(updateIndices[i]); + + for (size_t j = 0; j < updateSize; ++j) + { + measurementCovarianceSubset(i, j) = measurement.covariance_(updateIndices[i], updateIndices[j]); + } + + // Handle negative (read: bad) covariances in the measurement. Rather + // than exclude the measurement or make up a covariance, just take + // the absolute value. + if (measurementCovarianceSubset(i, i) < 0) + { + FB_DEBUG("WARNING: Negative covariance for index " << i << + " of measurement (value is" << measurementCovarianceSubset(i, i) << + "). Using absolute value...\n"); + + measurementCovarianceSubset(i, i) = ::fabs(measurementCovarianceSubset(i, i)); + } + + // If the measurement variance for a given variable is very + // near 0 (as in e-50 or so) and the variance for that + // variable in the covariance matrix is also near zero, then + // the Kalman gain computation will blow up. Really, no + // measurement can be completely without error, so add a small + // amount in that case. + if (measurementCovarianceSubset(i, i) < 1e-9) + { + FB_DEBUG("WARNING: measurement had very small error covariance for index " << updateIndices[i] << + ". Adding some noise to maintain filter stability.\n"); + + measurementCovarianceSubset(i, i) = 1e-9; + } + } + + // The state-to-measurement function, h, will now be a measurement_size x full_state_size + // matrix, with ones in the (i, i) locations of the values to be updated + for (size_t i = 0; i < updateSize; ++i) + { + stateToMeasurementSubset(i, updateIndices[i]) = 1; + } + + FB_DEBUG("Current state subset is:\n" << stateSubset << + "\nMeasurement subset is:\n" << measurementSubset << + "\nMeasurement covariance subset is:\n" << measurementCovarianceSubset << + "\nState-to-measurement subset is:\n" << stateToMeasurementSubset << "\n"); + + // (1) Compute the Kalman gain: K = (PH') / (HPH' + R) + Eigen::MatrixXd pht = estimateErrorCovariance_ * stateToMeasurementSubset.transpose(); + Eigen::MatrixXd hphrInv = (stateToMeasurementSubset * pht + measurementCovarianceSubset).inverse(); + kalmanGainSubset.noalias() = pht * hphrInv; + + innovationSubset = (measurementSubset - stateSubset); + + // Wrap angles in the innovation + for (size_t i = 0; i < updateSize; ++i) + { + if (updateIndices[i] == StateMemberRoll || + updateIndices[i] == StateMemberPitch || + updateIndices[i] == StateMemberYaw) + { + while (innovationSubset(i) < -PI) + { + innovationSubset(i) += TAU; + } + + while (innovationSubset(i) > PI) + { + innovationSubset(i) -= TAU; + } + } + } + + // (2) Check Mahalanobis distance between mapped measurement and state. + if (checkMahalanobisThreshold(innovationSubset, hphrInv, measurement.mahalanobisThresh_)) + { + // (3) Apply the gain to the difference between the state and measurement: x = x + K(z - Hx) + state_.noalias() += kalmanGainSubset * innovationSubset; + + // (4) Update the estimate error covariance using the Joseph form: (I - KH)P(I - KH)' + KRK' + Eigen::MatrixXd gainResidual = identity_; + gainResidual.noalias() -= kalmanGainSubset * stateToMeasurementSubset; + estimateErrorCovariance_ = gainResidual * estimateErrorCovariance_ * gainResidual.transpose(); + estimateErrorCovariance_.noalias() += kalmanGainSubset * + measurementCovarianceSubset * + kalmanGainSubset.transpose(); + + // Handle wrapping of angles + wrapStateAngles(); + + FB_DEBUG("Kalman gain subset is:\n" << kalmanGainSubset << + "\nInnovation is:\n" << innovationSubset << + "\nCorrected full state is:\n" << state_ << + "\nCorrected full estimate error covariance is:\n" << estimateErrorCovariance_ << + "\n\n---------------------- /Ekf::correct ----------------------\n"); + } + } + + void Ekf::predict(const double referenceTime, const double delta) + { + FB_DEBUG("---------------------- Ekf::predict ----------------------\n" << + "delta is " << delta << "\n" << + "state is " << state_ << "\n"); + + double roll = state_(StateMemberRoll); + double pitch = state_(StateMemberPitch); + double yaw = state_(StateMemberYaw); + double xVel = state_(StateMemberVx); + double yVel = state_(StateMemberVy); + double zVel = state_(StateMemberVz); + double pitchVel = state_(StateMemberVpitch); + double yawVel = state_(StateMemberVyaw); + double xAcc = state_(StateMemberAx); + double yAcc = state_(StateMemberAy); + double zAcc = state_(StateMemberAz); + + // We'll need these trig calculations a lot. + double sp = ::sin(pitch); + double cp = ::cos(pitch); + double cpi = 1.0 / cp; + double tp = sp * cpi; + + double sr = ::sin(roll); + double cr = ::cos(roll); + + double sy = ::sin(yaw); + double cy = ::cos(yaw); + + prepareControl(referenceTime, delta); + + // Prepare the transfer function + transferFunction_(StateMemberX, StateMemberVx) = cy * cp * delta; + transferFunction_(StateMemberX, StateMemberVy) = (cy * sp * sr - sy * cr) * delta; + transferFunction_(StateMemberX, StateMemberVz) = (cy * sp * cr + sy * sr) * delta; + transferFunction_(StateMemberX, StateMemberAx) = 0.5 * transferFunction_(StateMemberX, StateMemberVx) * delta; + transferFunction_(StateMemberX, StateMemberAy) = 0.5 * transferFunction_(StateMemberX, StateMemberVy) * delta; + transferFunction_(StateMemberX, StateMemberAz) = 0.5 * transferFunction_(StateMemberX, StateMemberVz) * delta; + transferFunction_(StateMemberY, StateMemberVx) = sy * cp * delta; + transferFunction_(StateMemberY, StateMemberVy) = (sy * sp * sr + cy * cr) * delta; + transferFunction_(StateMemberY, StateMemberVz) = (sy * sp * cr - cy * sr) * delta; + transferFunction_(StateMemberY, StateMemberAx) = 0.5 * transferFunction_(StateMemberY, StateMemberVx) * delta; + transferFunction_(StateMemberY, StateMemberAy) = 0.5 * transferFunction_(StateMemberY, StateMemberVy) * delta; + transferFunction_(StateMemberY, StateMemberAz) = 0.5 * transferFunction_(StateMemberY, StateMemberVz) * delta; + transferFunction_(StateMemberZ, StateMemberVx) = -sp * delta; + transferFunction_(StateMemberZ, StateMemberVy) = cp * sr * delta; + transferFunction_(StateMemberZ, StateMemberVz) = cp * cr * delta; + transferFunction_(StateMemberZ, StateMemberAx) = 0.5 * transferFunction_(StateMemberZ, StateMemberVx) * delta; + transferFunction_(StateMemberZ, StateMemberAy) = 0.5 * transferFunction_(StateMemberZ, StateMemberVy) * delta; + transferFunction_(StateMemberZ, StateMemberAz) = 0.5 * transferFunction_(StateMemberZ, StateMemberVz) * delta; + transferFunction_(StateMemberRoll, StateMemberVroll) = delta; + transferFunction_(StateMemberRoll, StateMemberVpitch) = sr * tp * delta; + transferFunction_(StateMemberRoll, StateMemberVyaw) = cr * tp * delta; + transferFunction_(StateMemberPitch, StateMemberVpitch) = cr * delta; + transferFunction_(StateMemberPitch, StateMemberVyaw) = -sr * delta; + transferFunction_(StateMemberYaw, StateMemberVpitch) = sr * cpi * delta; + transferFunction_(StateMemberYaw, StateMemberVyaw) = cr * cpi * delta; + transferFunction_(StateMemberVx, StateMemberAx) = delta; + transferFunction_(StateMemberVy, StateMemberAy) = delta; + transferFunction_(StateMemberVz, StateMemberAz) = delta; + + // Prepare the transfer function Jacobian. This function is analytically derived from the + // transfer function. + double xCoeff = 0.0; + double yCoeff = 0.0; + double zCoeff = 0.0; + double oneHalfATSquared = 0.5 * delta * delta; + + yCoeff = cy * sp * cr + sy * sr; + zCoeff = -cy * sp * sr + sy * cr; + double dFx_dR = (yCoeff * yVel + zCoeff * zVel) * delta + + (yCoeff * yAcc + zCoeff * zAcc) * oneHalfATSquared; + double dFR_dR = 1.0 + (cr * tp * pitchVel - sr * tp * yawVel) * delta; + + xCoeff = -cy * sp; + yCoeff = cy * cp * sr; + zCoeff = cy * cp * cr; + double dFx_dP = (xCoeff * xVel + yCoeff * yVel + zCoeff * zVel) * delta + + (xCoeff * xAcc + yCoeff * yAcc + zCoeff * zAcc) * oneHalfATSquared; + double dFR_dP = (cpi * cpi * sr * pitchVel + cpi * cpi * cr * yawVel) * delta; + + xCoeff = -sy * cp; + yCoeff = -sy * sp * sr - cy * cr; + zCoeff = -sy * sp * cr + cy * sr; + double dFx_dY = (xCoeff * xVel + yCoeff * yVel + zCoeff * zVel) * delta + + (xCoeff * xAcc + yCoeff * yAcc + zCoeff * zAcc) * oneHalfATSquared; + + yCoeff = sy * sp * cr - cy * sr; + zCoeff = -sy * sp * sr - cy * cr; + double dFy_dR = (yCoeff * yVel + zCoeff * zVel) * delta + + (yCoeff * yAcc + zCoeff * zAcc) * oneHalfATSquared; + double dFP_dR = (-sr * pitchVel - cr * yawVel) * delta; + + xCoeff = -sy * sp; + yCoeff = sy * cp * sr; + zCoeff = sy * cp * cr; + double dFy_dP = (xCoeff * xVel + yCoeff * yVel + zCoeff * zVel) * delta + + (xCoeff * xAcc + yCoeff * yAcc + zCoeff * zAcc) * oneHalfATSquared; + + xCoeff = cy * cp; + yCoeff = cy * sp * sr - sy * cr; + zCoeff = cy * sp * cr + sy * sr; + double dFy_dY = (xCoeff * xVel + yCoeff * yVel + zCoeff * zVel) * delta + + (xCoeff * xAcc + yCoeff * yAcc + zCoeff * zAcc) * oneHalfATSquared; + + yCoeff = cp * cr; + zCoeff = -cp * sr; + double dFz_dR = (yCoeff * yVel + zCoeff * zVel) * delta + + (yCoeff * yAcc + zCoeff * zAcc) * oneHalfATSquared; + double dFY_dR = (cr * cpi * pitchVel - sr * cpi * yawVel) * delta; + + xCoeff = -cp; + yCoeff = -sp * sr; + zCoeff = -sp * cr; + double dFz_dP = (xCoeff * xVel + yCoeff * yVel + zCoeff * zVel) * delta + + (xCoeff * xAcc + yCoeff * yAcc + zCoeff * zAcc) * oneHalfATSquared; + double dFY_dP = (sr * tp * cpi * pitchVel + cr * tp * cpi * yawVel) * delta; + + // Much of the transfer function Jacobian is identical to the transfer function + transferFunctionJacobian_ = transferFunction_; + transferFunctionJacobian_(StateMemberX, StateMemberRoll) = dFx_dR; + transferFunctionJacobian_(StateMemberX, StateMemberPitch) = dFx_dP; + transferFunctionJacobian_(StateMemberX, StateMemberYaw) = dFx_dY; + transferFunctionJacobian_(StateMemberY, StateMemberRoll) = dFy_dR; + transferFunctionJacobian_(StateMemberY, StateMemberPitch) = dFy_dP; + transferFunctionJacobian_(StateMemberY, StateMemberYaw) = dFy_dY; + transferFunctionJacobian_(StateMemberZ, StateMemberRoll) = dFz_dR; + transferFunctionJacobian_(StateMemberZ, StateMemberPitch) = dFz_dP; + transferFunctionJacobian_(StateMemberRoll, StateMemberRoll) = dFR_dR; + transferFunctionJacobian_(StateMemberRoll, StateMemberPitch) = dFR_dP; + transferFunctionJacobian_(StateMemberPitch, StateMemberRoll) = dFP_dR; + transferFunctionJacobian_(StateMemberYaw, StateMemberRoll) = dFY_dR; + transferFunctionJacobian_(StateMemberYaw, StateMemberPitch) = dFY_dP; + + FB_DEBUG("Transfer function is:\n" << transferFunction_ << + "\nTransfer function Jacobian is:\n" << transferFunctionJacobian_ << + "\nProcess noise covariance is:\n" << processNoiseCovariance_ << + "\nCurrent state is:\n" << state_ << "\n"); + + Eigen::MatrixXd *processNoiseCovariance = &processNoiseCovariance_; + + if (useDynamicProcessNoiseCovariance_) + { + computeDynamicProcessNoiseCovariance(state_, delta); + processNoiseCovariance = &dynamicProcessNoiseCovariance_; + } + + // (1) Apply control terms, which are actually accelerations + state_(StateMemberVroll) += controlAcceleration_(ControlMemberVroll) * delta; + state_(StateMemberVpitch) += controlAcceleration_(ControlMemberVpitch) * delta; + state_(StateMemberVyaw) += controlAcceleration_(ControlMemberVyaw) * delta; + + state_(StateMemberAx) = (controlUpdateVector_[ControlMemberVx] ? + controlAcceleration_(ControlMemberVx) : state_(StateMemberAx)); + state_(StateMemberAy) = (controlUpdateVector_[ControlMemberVy] ? + controlAcceleration_(ControlMemberVy) : state_(StateMemberAy)); + state_(StateMemberAz) = (controlUpdateVector_[ControlMemberVz] ? + controlAcceleration_(ControlMemberVz) : state_(StateMemberAz)); + + // (2) Project the state forward: x = Ax + Bu (really, x = f(x, u)) + state_ = transferFunction_ * state_; + + // Handle wrapping + wrapStateAngles(); + + FB_DEBUG("Predicted state is:\n" << state_ << + "\nCurrent estimate error covariance is:\n" << estimateErrorCovariance_ << "\n"); + + // (3) Project the error forward: P = J * P * J' + Q + estimateErrorCovariance_ = (transferFunctionJacobian_ * + estimateErrorCovariance_ * + transferFunctionJacobian_.transpose()); + estimateErrorCovariance_.noalias() += delta * (*processNoiseCovariance); + + FB_DEBUG("Predicted estimate error covariance is:\n" << estimateErrorCovariance_ << + "\n\n--------------------- /Ekf::predict ----------------------\n"); + } + +} // namespace RobotLocalization diff --git a/navigations/robot_localization/src/ekf_localization_node.cpp b/navigations/robot_localization/src/ekf_localization_node.cpp new file mode 100755 index 0000000..797bbe9 --- /dev/null +++ b/navigations/robot_localization/src/ekf_localization_node.cpp @@ -0,0 +1,51 @@ +/* + * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include "robot_localization/ros_filter_types.h" + +#include + +#include + +int main(int argc, char **argv) +{ + ros::init(argc, argv, "ekf_navigation_node"); + + ros::NodeHandle nh; + ros::NodeHandle nh_priv("~"); + + RobotLocalization::RosEkf ekf(nh, nh_priv); + ekf.initialize(); + ros::spin(); + + return EXIT_SUCCESS; +} diff --git a/navigations/robot_localization/src/ekf_localization_nodelet.cpp b/navigations/robot_localization/src/ekf_localization_nodelet.cpp new file mode 100755 index 0000000..337fa52 --- /dev/null +++ b/navigations/robot_localization/src/ekf_localization_nodelet.cpp @@ -0,0 +1,64 @@ +/* + * Copyright (c) 2017 Simon Gene Gottlieb + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include "robot_localization/ros_filter_types.h" + +#include +#include +#include + +#include + +namespace RobotLocalization +{ + +class EkfNodelet : public nodelet::Nodelet +{ +private: + std::unique_ptr ekf; + +public: + virtual void onInit() + { + NODELET_DEBUG("Initializing nodelet..."); + + ros::NodeHandle nh = getNodeHandle(); + ros::NodeHandle nh_priv = getPrivateNodeHandle(); + + ekf = std::make_unique(nh, nh_priv, getName()); + ekf->initialize(); + } +}; + +} // namespace RobotLocalization + +PLUGINLIB_EXPORT_CLASS(RobotLocalization::EkfNodelet, nodelet::Nodelet); diff --git a/navigations/robot_localization/src/filter_base.cpp b/navigations/robot_localization/src/filter_base.cpp new file mode 100755 index 0000000..efd181f --- /dev/null +++ b/navigations/robot_localization/src/filter_base.cpp @@ -0,0 +1,403 @@ +/* + * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include "robot_localization/filter_base.h" +#include "robot_localization/filter_common.h" + +#include +#include +#include +#include +#include + +namespace RobotLocalization +{ + FilterBase::FilterBase() : + initialized_(false), + useControl_(false), + useDynamicProcessNoiseCovariance_(false), + lastMeasurementTime_(0.0), + latestControlTime_(0.0), + controlTimeout_(0.0), + sensorTimeout_(0.0), + controlUpdateVector_(TWIST_SIZE, 0), + accelerationGains_(TWIST_SIZE, 0.0), + accelerationLimits_(TWIST_SIZE, 0.0), + decelerationGains_(TWIST_SIZE, 0.0), + decelerationLimits_(TWIST_SIZE, 0.0), + controlAcceleration_(TWIST_SIZE), + latestControl_(TWIST_SIZE), + predictedState_(STATE_SIZE), + state_(STATE_SIZE), + covarianceEpsilon_(STATE_SIZE, STATE_SIZE), + dynamicProcessNoiseCovariance_(STATE_SIZE, STATE_SIZE), + estimateErrorCovariance_(STATE_SIZE, STATE_SIZE), + identity_(STATE_SIZE, STATE_SIZE), + processNoiseCovariance_(STATE_SIZE, STATE_SIZE), + transferFunction_(STATE_SIZE, STATE_SIZE), + transferFunctionJacobian_(STATE_SIZE, STATE_SIZE), + debugStream_(NULL), + debug_(false) + { + reset(); + } + + FilterBase::~FilterBase() + { + } + + void FilterBase::reset() + { + initialized_ = false; + + // Clear the state and predicted state + state_.setZero(); + predictedState_.setZero(); + controlAcceleration_.setZero(); + + // Prepare the invariant parts of the transfer + // function + transferFunction_.setIdentity(); + + // Clear the Jacobian + transferFunctionJacobian_.setZero(); + + // Set the estimate error covariance. We want our measurements + // to be accepted rapidly when the filter starts, so we should + // initialize the state's covariance with large values. + estimateErrorCovariance_.setIdentity(); + estimateErrorCovariance_ *= 1e-9; + + // We need the identity for the update equations + identity_.setIdentity(); + + // Set the epsilon matrix to be a matrix with small values on the diagonal + // It is used to maintain the positive-definite property of the covariance + covarianceEpsilon_.setIdentity(); + covarianceEpsilon_ *= 0.001; + + // Assume 30Hz from sensor data (configurable) + sensorTimeout_ = 0.033333333; + + // Initialize our measurement time + lastMeasurementTime_ = 0; + + // These can be overridden via the launch parameters, + // but we need default values. + processNoiseCovariance_.setZero(); + processNoiseCovariance_(StateMemberX, StateMemberX) = 0.05; + processNoiseCovariance_(StateMemberY, StateMemberY) = 0.05; + processNoiseCovariance_(StateMemberZ, StateMemberZ) = 0.06; + processNoiseCovariance_(StateMemberRoll, StateMemberRoll) = 0.03; + processNoiseCovariance_(StateMemberPitch, StateMemberPitch) = 0.03; + processNoiseCovariance_(StateMemberYaw, StateMemberYaw) = 0.06; + processNoiseCovariance_(StateMemberVx, StateMemberVx) = 0.025; + processNoiseCovariance_(StateMemberVy, StateMemberVy) = 0.025; + processNoiseCovariance_(StateMemberVz, StateMemberVz) = 0.04; + processNoiseCovariance_(StateMemberVroll, StateMemberVroll) = 0.01; + processNoiseCovariance_(StateMemberVpitch, StateMemberVpitch) = 0.01; + processNoiseCovariance_(StateMemberVyaw, StateMemberVyaw) = 0.02; + processNoiseCovariance_(StateMemberAx, StateMemberAx) = 0.01; + processNoiseCovariance_(StateMemberAy, StateMemberAy) = 0.01; + processNoiseCovariance_(StateMemberAz, StateMemberAz) = 0.015; + + dynamicProcessNoiseCovariance_ = processNoiseCovariance_; + } + + void FilterBase::computeDynamicProcessNoiseCovariance(const Eigen::VectorXd &state, const double delta) + { + // A more principled approach would be to get the current velocity from the state, make a diagonal matrix from it, + // and then rotate it to be in the world frame (i.e., the same frame as the pose data). We could then use this + // rotated velocity matrix to scale the process noise covariance for the pose variables as + // rotatedVelocityMatrix * poseCovariance * rotatedVelocityMatrix' + // However, this presents trouble for robots that may incur rotational error as a result of linear motion (and + // vice-versa). Instead, we create a diagonal matrix whose diagonal values are the vector norm of the state's + // velocity. We use that to scale the process noise covariance. + Eigen::MatrixXd velocityMatrix(TWIST_SIZE, TWIST_SIZE); + velocityMatrix.setIdentity(); + velocityMatrix.diagonal() *= state.segment(POSITION_V_OFFSET, TWIST_SIZE).norm(); + + dynamicProcessNoiseCovariance_.block(POSITION_OFFSET, POSITION_OFFSET) = + velocityMatrix * + processNoiseCovariance_.block(POSITION_OFFSET, POSITION_OFFSET) * + velocityMatrix.transpose(); + } + + const Eigen::VectorXd& FilterBase::getControl() + { + return latestControl_; + } + + double FilterBase::getControlTime() + { + return latestControlTime_; + } + + bool FilterBase::getDebug() + { + return debug_; + } + + const Eigen::MatrixXd& FilterBase::getEstimateErrorCovariance() + { + return estimateErrorCovariance_; + } + + bool FilterBase::getInitializedStatus() + { + return initialized_; + } + + double FilterBase::getLastMeasurementTime() + { + return lastMeasurementTime_; + } + + const Eigen::VectorXd& FilterBase::getPredictedState() + { + return predictedState_; + } + + const Eigen::MatrixXd& FilterBase::getProcessNoiseCovariance() + { + return processNoiseCovariance_; + } + + double FilterBase::getSensorTimeout() + { + return sensorTimeout_; + } + + const Eigen::VectorXd& FilterBase::getState() + { + return state_; + } + + void FilterBase::processMeasurement(const Measurement &measurement) + { + FB_DEBUG("------ FilterBase::processMeasurement (" << measurement.topicName_ << ") ------\n"); + + double delta = 0.0; + + // If we've had a previous reading, then go through the predict/update + // cycle. Otherwise, set our state and covariance to whatever we get + // from this measurement. + if (initialized_) + { + // Determine how much time has passed since our last measurement + delta = measurement.time_ - lastMeasurementTime_; + + FB_DEBUG("Filter is already initialized. Carrying out predict/correct loop...\n" + "Measurement time is " << std::setprecision(20) << measurement.time_ << + ", last measurement time is " << lastMeasurementTime_ << ", delta is " << delta << "\n"); + + // Only want to carry out a prediction if it's + // forward in time. Otherwise, just correct. + if (delta > 0) + { + validateDelta(delta); + predict(measurement.time_, delta); + + // Return this to the user + predictedState_ = state_; + } + + correct(measurement); + } + else + { + FB_DEBUG("First measurement. Initializing filter.\n"); + + // Initialize the filter, but only with the values we're using + size_t measurementLength = measurement.updateVector_.size(); + for (size_t i = 0; i < measurementLength; ++i) + { + state_[i] = (measurement.updateVector_[i] ? measurement.measurement_[i] : state_[i]); + } + + // Same for covariance + for (size_t i = 0; i < measurementLength; ++i) + { + for (size_t j = 0; j < measurementLength; ++j) + { + estimateErrorCovariance_(i, j) = (measurement.updateVector_[i] && measurement.updateVector_[j] ? + measurement.covariance_(i, j) : + estimateErrorCovariance_(i, j)); + } + } + + initialized_ = true; + } + + if (delta >= 0.0) + { + lastMeasurementTime_ = measurement.time_; + } + + FB_DEBUG("------ /FilterBase::processMeasurement (" << measurement.topicName_ << ") ------\n"); + } + + void FilterBase::setControl(const Eigen::VectorXd &control, const double controlTime) + { + latestControl_ = control; + latestControlTime_ = controlTime; + } + + void FilterBase::setControlParams(const std::vector &updateVector, const double controlTimeout, + const std::vector &accelerationLimits, const std::vector &accelerationGains, + const std::vector &decelerationLimits, const std::vector &decelerationGains) + { + useControl_ = true; + controlUpdateVector_ = updateVector; + controlTimeout_ = controlTimeout; + accelerationLimits_ = accelerationLimits; + accelerationGains_ = accelerationGains; + decelerationLimits_ = decelerationLimits; + decelerationGains_ = decelerationGains; + } + + void FilterBase::setDebug(const bool debug, std::ostream *outStream) + { + if (debug) + { + if (outStream != NULL) + { + debugStream_ = outStream; + debug_ = true; + } + else + { + debug_ = false; + } + } + else + { + debug_ = false; + } + } + + void FilterBase::setUseDynamicProcessNoiseCovariance(const bool useDynamicProcessNoiseCovariance) + { + useDynamicProcessNoiseCovariance_ = useDynamicProcessNoiseCovariance; + } + + void FilterBase::setEstimateErrorCovariance(const Eigen::MatrixXd &estimateErrorCovariance) + { + estimateErrorCovariance_ = estimateErrorCovariance; + } + + void FilterBase::setLastMeasurementTime(const double lastMeasurementTime) + { + lastMeasurementTime_ = lastMeasurementTime; + } + + void FilterBase::setProcessNoiseCovariance(const Eigen::MatrixXd &processNoiseCovariance) + { + processNoiseCovariance_ = processNoiseCovariance; + dynamicProcessNoiseCovariance_ = processNoiseCovariance_; + } + + void FilterBase::setSensorTimeout(const double sensorTimeout) + { + sensorTimeout_ = sensorTimeout; + } + + void FilterBase::setState(const Eigen::VectorXd &state) + { + state_ = state; + } + + void FilterBase::validateDelta(double &delta) + { + // This handles issues with ROS time when use_sim_time is on and we're playing from bags. + if (delta > 100000.0) + { + FB_DEBUG("Delta was very large. Suspect playing from bag file. Setting to 0.01\n"); + + delta = 0.01; + } + } + + + void FilterBase::prepareControl(const double referenceTime, const double predictionDelta) + { + controlAcceleration_.setZero(); + + if (useControl_) + { + bool timedOut = ::fabs(referenceTime - latestControlTime_) >= controlTimeout_; + + if (timedOut) + { + FB_DEBUG("Control timed out. Reference time was " << referenceTime << ", latest control time was " << + latestControlTime_ << ", control timeout was " << controlTimeout_ << "\n"); + } + + for (size_t controlInd = 0; controlInd < TWIST_SIZE; ++controlInd) + { + if (controlUpdateVector_[controlInd]) + { + controlAcceleration_(controlInd) = computeControlAcceleration(state_(controlInd + POSITION_V_OFFSET), + (timedOut ? 0.0 : latestControl_(controlInd)), accelerationLimits_[controlInd], + accelerationGains_[controlInd], decelerationLimits_[controlInd], decelerationGains_[controlInd]); + } + } + } + } + + void FilterBase::wrapStateAngles() + { + state_(StateMemberRoll) = FilterUtilities::clampRotation(state_(StateMemberRoll)); + state_(StateMemberPitch) = FilterUtilities::clampRotation(state_(StateMemberPitch)); + state_(StateMemberYaw) = FilterUtilities::clampRotation(state_(StateMemberYaw)); + } + + bool FilterBase::checkMahalanobisThreshold(const Eigen::VectorXd &innovation, + const Eigen::MatrixXd &invCovariance, + const double nsigmas) + { + double sqMahalanobis = innovation.dot(invCovariance * innovation); + double threshold = nsigmas * nsigmas; + + if (sqMahalanobis >= threshold) + { + FB_DEBUG("Innovation mahalanobis distance test failed. Squared Mahalanobis is: " << sqMahalanobis << "\n" << + "Threshold is: " << threshold << "\n" << + "Innovation is: " << innovation << "\n" << + "Innovation covariance is:\n" << invCovariance << "\n"); + + return false; + } + + return true; + } +} // namespace RobotLocalization diff --git a/navigations/robot_localization/src/filter_utilities.cpp b/navigations/robot_localization/src/filter_utilities.cpp new file mode 100755 index 0000000..259644d --- /dev/null +++ b/navigations/robot_localization/src/filter_utilities.cpp @@ -0,0 +1,146 @@ +/* + * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include "robot_localization/filter_utilities.h" +#include "robot_localization/filter_common.h" + +#include +#include + +std::ostream& operator<<(std::ostream& os, const Eigen::MatrixXd &mat) +{ + os << "["; + + int rowCount = static_cast(mat.rows()); + + for (int row = 0; row < rowCount; ++row) + { + if (row > 0) + { + os << " "; + } + + for (int col = 0; col < mat.cols(); ++col) + { + os << std::setiosflags(std::ios::left) << std::setw(12) << std::setprecision(5) << mat(row, col); + } + + if (row < rowCount - 1) + { + os << "\n"; + } + } + + os << "]\n"; + + return os; +} + +std::ostream& operator<<(std::ostream& os, const Eigen::VectorXd &vec) +{ + os << "["; + for (int dim = 0; dim < vec.rows(); ++dim) + { + os << std::setiosflags(std::ios::left) << std::setw(12) << std::setprecision(5) << vec(dim); + } + os << "]\n"; + + return os; +} + +std::ostream& operator<<(std::ostream& os, const std::vector &vec) +{ + os << "["; + for (size_t dim = 0; dim < vec.size(); ++dim) + { + os << std::setiosflags(std::ios::left) << std::setw(12) << std::setprecision(5) << vec[dim]; + } + os << "]\n"; + + return os; +} + +std::ostream& operator<<(std::ostream& os, const std::vector &vec) +{ + os << "["; + for (size_t dim = 0; dim < vec.size(); ++dim) + { + os << std::setiosflags(std::ios::left) << std::setw(3) << (vec[dim] ? "t" : "f"); + } + os << "]\n"; + + return os; +} + +namespace RobotLocalization +{ + +namespace FilterUtilities +{ + void appendPrefix(std::string tfPrefix, std::string &frameId) + { + // Strip all leading slashes for tf2 compliance + if (!frameId.empty() && frameId.at(0) == '/') + { + frameId = frameId.substr(1); + } + + if (!tfPrefix.empty() && tfPrefix.at(0) == '/') + { + tfPrefix = tfPrefix.substr(1); + } + + // If we do have a tf prefix, then put a slash in between + if (!tfPrefix.empty()) + { + frameId = tfPrefix + "/" + frameId; + } + } + + double clampRotation(double rotation) + { + while (rotation > PI) + { + rotation -= TAU; + } + + while (rotation < -PI) + { + rotation += TAU; + } + + return rotation; + } + +} // namespace FilterUtilities + +} // namespace RobotLocalization diff --git a/navigations/robot_localization/src/navsat_transform.cpp b/navigations/robot_localization/src/navsat_transform.cpp new file mode 100755 index 0000000..5ec9f1b --- /dev/null +++ b/navigations/robot_localization/src/navsat_transform.cpp @@ -0,0 +1,915 @@ +/* + * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include "robot_localization/navsat_transform.h" +#include "robot_localization/filter_common.h" +#include "robot_localization/filter_utilities.h" +#include "robot_localization/navsat_conversions.h" +#include "robot_localization/ros_filter_utilities.h" + +#include +#include + +#include + +namespace RobotLocalization +{ + NavSatTransform::NavSatTransform(ros::NodeHandle nh, ros::NodeHandle nh_priv) : + broadcast_cartesian_transform_(false), + broadcast_cartesian_transform_as_parent_frame_(false), + gps_updated_(false), + has_transform_gps_(false), + has_transform_imu_(false), + has_transform_odom_(false), + odom_updated_(false), + publish_gps_(false), + transform_good_(false), + use_manual_datum_(false), + use_odometry_yaw_(false), + use_local_cartesian_(false), + zero_altitude_(false), + magnetic_declination_(0.0), + yaw_offset_(0.0), + base_link_frame_id_("base_link"), + gps_frame_id_(""), + utm_zone_(0), + world_frame_id_("odom"), + transform_timeout_(ros::Duration(0)), + tf_listener_(tf_buffer_) + { + ROS_INFO("Waiting for valid clock time..."); + ros::Time::waitForValid(); + ROS_INFO("Valid clock time received. Starting node."); + + latest_cartesian_covariance_.resize(POSE_SIZE, POSE_SIZE); + latest_odom_covariance_.resize(POSE_SIZE, POSE_SIZE); + + double frequency; + double delay = 0.0; + double transform_timeout = 0.0; + + // Load the parameters we need + nh_priv.getParam("magnetic_declination_radians", magnetic_declination_); + nh_priv.param("yaw_offset", yaw_offset_, 0.0); + nh_priv.param("broadcast_cartesian_transform", broadcast_cartesian_transform_, false); + nh_priv.param("broadcast_cartesian_transform_as_parent_frame", + broadcast_cartesian_transform_as_parent_frame_, false); + nh_priv.param("zero_altitude", zero_altitude_, false); + nh_priv.param("publish_filtered_gps", publish_gps_, false); + nh_priv.param("use_odometry_yaw", use_odometry_yaw_, false); + nh_priv.param("wait_for_datum", use_manual_datum_, false); + nh_priv.param("use_local_cartesian", use_local_cartesian_, false); + nh_priv.param("frequency", frequency, 10.0); + nh_priv.param("delay", delay, 0.0); + nh_priv.param("transform_timeout", transform_timeout, 0.0); + nh_priv.param("cartesian_frame_id", cartesian_frame_id_, std::string(use_local_cartesian_ ? "local_enu" : "utm")); + transform_timeout_.fromSec(transform_timeout); + + // Check for deprecated parameters + if (nh_priv.getParam("broadcast_utm_transform", broadcast_cartesian_transform_)) + { + ROS_WARN("navsat_transform, Parameter 'broadcast_utm_transform' has been deprecated. Please use" + "'broadcast_cartesian_transform' instead."); + } + if (nh_priv.getParam("broadcast_utm_transform_as_parent_frame", broadcast_cartesian_transform_as_parent_frame_)) + { + ROS_WARN("navsat_transform, Parameter 'broadcast_utm_transform_as_parent_frame' has been deprecated. Please use" + "'broadcast_cartesian_transform_as_parent_frame' instead."); + } + + // Check if tf warnings should be suppressed + nh.getParam("/silent_tf_failure", tf_silent_failure_); + + // Subscribe to the messages and services we need + datum_srv_ = nh.advertiseService("datum", &NavSatTransform::datumCallback, this); + + to_ll_srv_ = nh.advertiseService("toLL", &NavSatTransform::toLLCallback, this); + from_ll_srv_ = nh.advertiseService("fromLL", &NavSatTransform::fromLLCallback, this); + set_utm_zone_srv_ = nh.advertiseService("setUTMZone", &NavSatTransform::setUTMZoneCallback, this); + + if (use_manual_datum_ && nh_priv.hasParam("datum")) + { + XmlRpc::XmlRpcValue datum_config; + + try + { + double datum_lat; + double datum_lon; + double datum_yaw; + + nh_priv.getParam("datum", datum_config); + + // Handle datum specification. Users should always specify a baseLinkFrameId_ in the + // datum config, but we had a release where it wasn't used, so we'll maintain compatibility. + ROS_ASSERT(datum_config.getType() == XmlRpc::XmlRpcValue::TypeArray); + ROS_ASSERT(datum_config.size() >= 3); + + if (datum_config.size() > 3) + { + ROS_WARN_STREAM("Deprecated datum parameter configuration detected. Only the first three parameters " + "(latitude, longitude, yaw) will be used. frame_ids will be derived from odometry and navsat inputs."); + } + + std::ostringstream ostr; + ostr << std::setprecision(20) << datum_config[0] << " " << datum_config[1] << " " << datum_config[2]; + std::istringstream istr(ostr.str()); + istr >> datum_lat >> datum_lon >> datum_yaw; + + // Try to resolve tf_prefix + std::string tf_prefix = ""; + std::string tf_prefix_path = ""; + if (nh_priv.searchParam("tf_prefix", tf_prefix_path)) + { + nh_priv.getParam(tf_prefix_path, tf_prefix); + } + + // Append the tf prefix in a tf2-friendly manner + FilterUtilities::appendPrefix(tf_prefix, world_frame_id_); + FilterUtilities::appendPrefix(tf_prefix, base_link_frame_id_); + + robot_localization::SetDatum::Request request; + request.geo_pose.position.latitude = datum_lat; + request.geo_pose.position.longitude = datum_lon; + request.geo_pose.position.altitude = 0.0; + tf2::Quaternion quat; + quat.setRPY(0.0, 0.0, datum_yaw); + request.geo_pose.orientation = tf2::toMsg(quat); + robot_localization::SetDatum::Response response; + datumCallback(request, response); + } + catch (XmlRpc::XmlRpcException &e) + { + ROS_ERROR_STREAM("ERROR reading sensor config: " << e.getMessage() << + " for process_noise_covariance (type: " << datum_config.getType() << ")"); + } + } + + odom_sub_ = nh.subscribe("odometry/filtered", 1, &NavSatTransform::odomCallback, this); + gps_sub_ = nh.subscribe("gps/fix", 1, &NavSatTransform::gpsFixCallback, this); + + if (!use_odometry_yaw_ && !use_manual_datum_) + { + imu_sub_ = nh.subscribe("imu/data", 1, &NavSatTransform::imuCallback, this); + } + + gps_odom_pub_ = nh.advertise("odometry/gps", 10); + + if (publish_gps_) + { + filtered_gps_pub_ = nh.advertise("gps/filtered", 10); + } + + // Sleep for the parameterized amount of time, to give + // other nodes time to start up (not always necessary) + ros::Duration start_delay(delay); + start_delay.sleep(); + + periodicUpdateTimer_ = nh.createTimer(ros::Duration(1./frequency), &NavSatTransform::periodicUpdate, this); + } + + NavSatTransform::~NavSatTransform() + { + } + +// void NavSatTransform::run() + void NavSatTransform::periodicUpdate(const ros::TimerEvent& event) + { + if (!transform_good_) + { + computeTransform(); + + if (transform_good_ && !use_odometry_yaw_ && !use_manual_datum_) + { + // Once we have the transform, we don't need the IMU + imu_sub_.shutdown(); + } + } + else + { + nav_msgs::Odometry gps_odom; + if (prepareGpsOdometry(gps_odom)) + { + gps_odom_pub_.publish(gps_odom); + } + + if (publish_gps_) + { + sensor_msgs::NavSatFix odom_gps; + if (prepareFilteredGps(odom_gps)) + { + filtered_gps_pub_.publish(odom_gps); + } + } + } + } + + void NavSatTransform::computeTransform() + { + // Only do this if: + // 1. We haven't computed the odom_frame->cartesian_frame transform before + // 2. We've received the data we need + if (!transform_good_ && + has_transform_odom_ && + has_transform_gps_ && + has_transform_imu_) + { + // The cartesian pose we have is given at the location of the GPS sensor on the robot. We need to get the + // cartesian pose of the robot's origin. + tf2::Transform transform_cartesian_pose_corrected; + if (!use_manual_datum_) + { + getRobotOriginCartesianPose(transform_cartesian_pose_, transform_cartesian_pose_corrected, ros::Time(0)); + } + else + { + transform_cartesian_pose_corrected = transform_cartesian_pose_; + } + + // Get the IMU's current RPY values. Need the raw values (for yaw, anyway). + tf2::Matrix3x3 mat(transform_orientation_); + + // Convert to RPY + double imu_roll; + double imu_pitch; + double imu_yaw; + mat.getRPY(imu_roll, imu_pitch, imu_yaw); + + /* The IMU's heading was likely originally reported w.r.t. magnetic north. + * However, all the nodes in robot_localization assume that orientation data, + * including that reported by IMUs, is reported in an ENU frame, with a 0 yaw + * value being reported when facing east and increasing counter-clockwise (i.e., + * towards north). To make the world frame ENU aligned, where X is east + * and Y is north, we have to take into account three additional considerations: + * 1. The IMU may have its non-ENU frame data transformed to ENU, but there's + * a possibility that its data has not been corrected for magnetic + * declination. We need to account for this. A positive magnetic + * declination is counter-clockwise in an ENU frame. Therefore, if + * we have a magnetic declination of N radians, then when the sensor + * is facing a heading of N, it reports 0. Therefore, we need to add + * the declination angle. + * 2. To account for any other offsets that may not be accounted for by the + * IMU driver or any interim processing node, we expose a yaw offset that + * lets users work with navsat_transform_node. + * 3. UTM grid isn't aligned with True East\North. To account for the difference + * we need to add meridian convergence angle when using UTM. This value will be + * 0.0 when use_local_cartesian is TRUE. + */ + imu_yaw += (magnetic_declination_ + yaw_offset_ + utm_meridian_convergence_); + + ROS_INFO_STREAM("Corrected for magnetic declination of " << std::fixed << magnetic_declination_ << + ", user-specified offset of " << yaw_offset_ << + " and meridian convergence of " << utm_meridian_convergence_ << "." << + " Transform heading factor is now " << imu_yaw); + + // Convert to tf-friendly structures + tf2::Quaternion imu_quat; + imu_quat.setRPY(0.0, 0.0, imu_yaw); + + // The transform order will be orig_odom_pos * orig_cartesian_pos_inverse * cur_cartesian_pos. + // Doing it this way will allow us to cope with having non-zero odometry position + // when we get our first GPS message. + tf2::Transform cartesian_pose_with_orientation; + cartesian_pose_with_orientation.setOrigin(transform_cartesian_pose_corrected.getOrigin()); + cartesian_pose_with_orientation.setRotation(imu_quat); + + // Remove roll and pitch from odometry pose + // Must be done because roll and pitch is removed from cartesian_pose_with_orientation + double odom_roll, odom_pitch, odom_yaw; + tf2::Matrix3x3(transform_world_pose_.getRotation()).getRPY(odom_roll, odom_pitch, odom_yaw); + tf2::Quaternion odom_quat; + odom_quat.setRPY(0.0, 0.0, odom_yaw); + tf2::Transform transform_world_pose_yaw_only(transform_world_pose_); + transform_world_pose_yaw_only.setRotation(odom_quat); + + cartesian_world_transform_.mult(transform_world_pose_yaw_only, cartesian_pose_with_orientation.inverse()); + + cartesian_world_trans_inverse_ = cartesian_world_transform_.inverse(); + + ROS_INFO_STREAM("Transform world frame pose is: " << transform_world_pose_); + ROS_INFO_STREAM("World frame->cartesian transform is " << cartesian_world_transform_); + + transform_good_ = true; + + // Send out the (static) Cartesian transform in case anyone else would like to use it. + if (broadcast_cartesian_transform_) + { + geometry_msgs::TransformStamped cartesian_transform_stamped; + cartesian_transform_stamped.header.stamp = ros::Time::now(); + cartesian_transform_stamped.header.frame_id = (broadcast_cartesian_transform_as_parent_frame_ ? + cartesian_frame_id_ : world_frame_id_); + cartesian_transform_stamped.child_frame_id = (broadcast_cartesian_transform_as_parent_frame_ ? + world_frame_id_ : cartesian_frame_id_); + cartesian_transform_stamped.transform = (broadcast_cartesian_transform_as_parent_frame_ ? + tf2::toMsg(cartesian_world_trans_inverse_) : + tf2::toMsg(cartesian_world_transform_)); + cartesian_transform_stamped.transform.translation.z = (zero_altitude_ ? + 0.0 : cartesian_transform_stamped.transform.translation.z); + cartesian_broadcaster_.sendTransform(cartesian_transform_stamped); + } + } + } + + bool NavSatTransform::datumCallback(robot_localization::SetDatum::Request& request, + robot_localization::SetDatum::Response&) + { + // If we get a service call with a manual datum, even if we already computed the transform using the robot's + // initial pose, then we want to assume that we are using a datum from now on, and we want other methods to + // not attempt to transform the values we are specifying here. + use_manual_datum_ = true; + + transform_good_ = false; + + sensor_msgs::NavSatFix *fix = new sensor_msgs::NavSatFix(); + fix->latitude = request.geo_pose.position.latitude; + fix->longitude = request.geo_pose.position.longitude; + fix->altitude = request.geo_pose.position.altitude; + fix->header.stamp = ros::Time::now(); + fix->position_covariance[0] = 0.1; + fix->position_covariance[4] = 0.1; + fix->position_covariance[8] = 0.1; + fix->position_covariance_type = sensor_msgs::NavSatStatus::STATUS_FIX; + sensor_msgs::NavSatFixConstPtr fix_ptr(fix); + setTransformGps(fix_ptr); + + nav_msgs::Odometry *odom = new nav_msgs::Odometry(); + odom->pose.pose.orientation.x = 0; + odom->pose.pose.orientation.y = 0; + odom->pose.pose.orientation.z = 0; + odom->pose.pose.orientation.w = 1; + odom->pose.pose.position.x = 0; + odom->pose.pose.position.y = 0; + odom->pose.pose.position.z = 0; + odom->header.frame_id = world_frame_id_; + odom->child_frame_id = base_link_frame_id_; + nav_msgs::OdometryConstPtr odom_ptr(odom); + setTransformOdometry(odom_ptr); + + sensor_msgs::Imu *imu = new sensor_msgs::Imu(); + imu->orientation = request.geo_pose.orientation; + imu->header.frame_id = base_link_frame_id_; + sensor_msgs::ImuConstPtr imu_ptr(imu); + imuCallback(imu_ptr); + + return true; + } + + bool NavSatTransform::toLLCallback(robot_localization::ToLL::Request& request, + robot_localization::ToLL::Response& response) + { + if (!transform_good_) + { + ROS_ERROR("No transform available (yet)"); + return false; + } + tf2::Vector3 point; + tf2::fromMsg(request.map_point, point); + mapToLL(point, response.ll_point.latitude, response.ll_point.longitude, response.ll_point.altitude); + + return true; + } + + bool NavSatTransform::fromLLCallback(robot_localization::FromLL::Request& request, + robot_localization::FromLL::Response& response) + { + double altitude = request.ll_point.altitude; + double longitude = request.ll_point.longitude; + double latitude = request.ll_point.latitude; + + tf2::Transform cartesian_pose; + + double cartesian_x; + double cartesian_y; + double cartesian_z; + + if (use_local_cartesian_) + { + gps_local_cartesian_.Forward(latitude, longitude, altitude, cartesian_x, cartesian_y, cartesian_z); + } + else + { + int zone_tmp; + bool nortp_tmp; + try + { + GeographicLib::UTMUPS::Forward(latitude, longitude, zone_tmp, nortp_tmp, cartesian_x, cartesian_y, utm_zone_); + } + catch (const GeographicLib::GeographicErr& e) + { + ROS_ERROR_STREAM_THROTTLE(1.0, e.what()); + return false; + } + } + + cartesian_pose.setOrigin(tf2::Vector3(cartesian_x, cartesian_y, altitude)); + + nav_msgs::Odometry gps_odom; + + if (!transform_good_) + { + ROS_ERROR("No transform available (yet)"); + return false; + } + + response.map_point = cartesianToMap(cartesian_pose).pose.pose.position; + + return true; + } + + bool NavSatTransform::setUTMZoneCallback(robot_localization::SetUTMZone::Request& request, + robot_localization::SetUTMZone::Response& response) + { + double x_unused; + double y_unused; + int prec_unused; + GeographicLib::MGRS::Reverse(request.utm_zone, utm_zone_, northp_, x_unused, y_unused, prec_unused, true); + ROS_INFO("UTM zone set to %d %s", utm_zone_, northp_ ? "north" : "south"); + return true; + } + + nav_msgs::Odometry NavSatTransform::cartesianToMap(const tf2::Transform& cartesian_pose) const + { + nav_msgs::Odometry gps_odom{}; + + tf2::Transform transformed_cartesian_gps{}; + + transformed_cartesian_gps.mult(cartesian_world_transform_, cartesian_pose); + transformed_cartesian_gps.setRotation(tf2::Quaternion::getIdentity()); + + // Set header information stamp because we would like to know the robot's position at that timestamp + gps_odom.header.frame_id = world_frame_id_; + gps_odom.header.stamp = gps_update_time_; + + // Now fill out the message. Set the orientation to the identity. + tf2::toMsg(transformed_cartesian_gps, gps_odom.pose.pose); + gps_odom.pose.pose.position.z = (zero_altitude_ ? 0.0 : gps_odom.pose.pose.position.z); + + return gps_odom; + } + + void NavSatTransform::mapToLL(const tf2::Vector3& point, double& latitude, double& longitude, double& altitude) const + { + tf2::Transform odom_as_cartesian{}; + + tf2::Transform pose{}; + pose.setOrigin(point); + pose.setRotation(tf2::Quaternion::getIdentity()); + + odom_as_cartesian.mult(cartesian_world_trans_inverse_, pose); + odom_as_cartesian.setRotation(tf2::Quaternion::getIdentity()); + + if (use_local_cartesian_) + { + double altitude_tmp = 0.0; + gps_local_cartesian_.Reverse(odom_as_cartesian.getOrigin().getX(), + odom_as_cartesian.getOrigin().getY(), + 0.0, + latitude, + longitude, + altitude_tmp); + altitude = odom_as_cartesian.getOrigin().getZ(); + } + else + { + GeographicLib::UTMUPS::Reverse(utm_zone_, + northp_, + odom_as_cartesian.getOrigin().getX(), + odom_as_cartesian.getOrigin().getY(), + latitude, + longitude); + altitude = odom_as_cartesian.getOrigin().getZ(); + } + } + + void NavSatTransform::getRobotOriginCartesianPose(const tf2::Transform &gps_cartesian_pose, + tf2::Transform &robot_cartesian_pose, + const ros::Time &transform_time) + { + robot_cartesian_pose.setIdentity(); + + // Get linear offset from origin for the GPS + tf2::Transform offset; + bool can_transform = RosFilterUtilities::lookupTransformSafe(tf_buffer_, + base_link_frame_id_, + gps_frame_id_, + transform_time, + ros::Duration(transform_timeout_), + offset, + tf_silent_failure_); + + if (can_transform) + { + // Get the orientation we'll use for our Cartesian->world transform + tf2::Quaternion cartesian_orientation = transform_orientation_; + tf2::Matrix3x3 mat(cartesian_orientation); + + // Add the offsets + double roll; + double pitch; + double yaw; + mat.getRPY(roll, pitch, yaw); + yaw += (magnetic_declination_ + yaw_offset_ + utm_meridian_convergence_); + cartesian_orientation.setRPY(roll, pitch, yaw); + + // Rotate the GPS linear offset by the orientation + // Zero out the orientation, because the GPS orientation is meaningless, and if it's non-zero, it will make the + // the computation of robot_cartesian_pose erroneous. + offset.setOrigin(tf2::quatRotate(cartesian_orientation, offset.getOrigin())); + offset.setRotation(tf2::Quaternion::getIdentity()); + + // Update the initial pose + robot_cartesian_pose = offset.inverse() * gps_cartesian_pose; + } + else + { + if (gps_frame_id_ != "") + { + ROS_WARN_STREAM_ONCE("Unable to obtain " << base_link_frame_id_ << "->" << gps_frame_id_ << + " transform. Will assume navsat device is mounted at robot's origin"); + } + + robot_cartesian_pose = gps_cartesian_pose; + } + } + + void NavSatTransform::getRobotOriginWorldPose(const tf2::Transform &gps_odom_pose, + tf2::Transform &robot_odom_pose, + const ros::Time &transform_time) + { + robot_odom_pose.setIdentity(); + + // Remove the offset from base_link + tf2::Transform gps_offset_rotated; + bool can_transform = RosFilterUtilities::lookupTransformSafe(tf_buffer_, + base_link_frame_id_, + gps_frame_id_, + transform_time, + transform_timeout_, + gps_offset_rotated, + tf_silent_failure_); + + if (can_transform) + { + tf2::Transform robot_orientation; + can_transform = RosFilterUtilities::lookupTransformSafe(tf_buffer_, + world_frame_id_, + base_link_frame_id_, + transform_time, + transform_timeout_, + robot_orientation, + tf_silent_failure_); + + if (can_transform) + { + // Zero out rotation because we don't care about the orientation of the + // GPS receiver relative to base_link + gps_offset_rotated.setOrigin(tf2::quatRotate(robot_orientation.getRotation(), gps_offset_rotated.getOrigin())); + gps_offset_rotated.setRotation(tf2::Quaternion::getIdentity()); + robot_odom_pose = gps_offset_rotated.inverse() * gps_odom_pose; + } + else + { + ROS_WARN_STREAM_THROTTLE(5.0, "Could not obtain " << world_frame_id_ << "->" << base_link_frame_id_ << + " transform. Will not remove offset of navsat device from robot's origin."); + } + } + else + { + ROS_WARN_STREAM_THROTTLE(5.0, "Could not obtain " << base_link_frame_id_ << "->" << gps_frame_id_ << + " transform. Will not remove offset of navsat device from robot's origin."); + } + } + + void NavSatTransform::gpsFixCallback(const sensor_msgs::NavSatFixConstPtr& msg) + { + gps_frame_id_ = msg->header.frame_id; + + if (gps_frame_id_.empty()) + { + ROS_WARN_STREAM_ONCE("NavSatFix message has empty frame_id. Will assume navsat device is mounted at robot's " + "origin."); + } + + // Make sure the GPS data is usable + bool good_gps = (msg->status.status != sensor_msgs::NavSatStatus::STATUS_NO_FIX && + !std::isnan(msg->altitude) && + !std::isnan(msg->latitude) && + !std::isnan(msg->longitude)); + + if (good_gps) + { + // If we haven't computed the transform yet, then + // store this message as the initial GPS data to use + if (!transform_good_ && !use_manual_datum_) + { + setTransformGps(msg); + } + + double cartesian_x = 0.0; + double cartesian_y = 0.0; + double cartesian_z = 0.0; + if (use_local_cartesian_) + { + gps_local_cartesian_.Forward(msg->latitude, msg->longitude, msg->altitude, + cartesian_x, cartesian_y, cartesian_z); + } + else + { + // Transform to UTM using the fixed utm_zone_ + int zone_tmp; + bool northp_tmp; + try + { + GeographicLib::UTMUPS::Forward(msg->latitude, msg->longitude, + zone_tmp, northp_tmp, cartesian_x, cartesian_y, utm_zone_); + } + catch (const GeographicLib::GeographicErr& e) + { + ROS_ERROR_STREAM_THROTTLE(1.0, e.what()); + return; + } + } + latest_cartesian_pose_.setOrigin(tf2::Vector3(cartesian_x, cartesian_y, msg->altitude)); + latest_cartesian_covariance_.setZero(); + + // Copy the measurement's covariance matrix so that we can rotate it later + for (size_t i = 0; i < POSITION_SIZE; i++) + { + for (size_t j = 0; j < POSITION_SIZE; j++) + { + latest_cartesian_covariance_(i, j) = msg->position_covariance[POSITION_SIZE * i + j]; + } + } + + gps_update_time_ = msg->header.stamp; + gps_updated_ = true; + } + } + + void NavSatTransform::imuCallback(const sensor_msgs::ImuConstPtr& msg) + { + // We need the baseLinkFrameId_ from the odometry message, so + // we need to wait until we receive it. + if (has_transform_odom_) + { + /* This method only gets called if we don't yet have the + * IMU data (the subscriber gets shut down once we compute + * the transform), so we can assumed that every IMU message + * that comes here is meant to be used for that purpose. */ + tf2::fromMsg(msg->orientation, transform_orientation_); + + // Correct for the IMU's orientation w.r.t. base_link + tf2::Transform target_frame_trans; + bool can_transform = RosFilterUtilities::lookupTransformSafe(tf_buffer_, + base_link_frame_id_, + msg->header.frame_id, + msg->header.stamp, + transform_timeout_, + target_frame_trans, + tf_silent_failure_); + + if (can_transform) + { + double roll_offset = 0; + double pitch_offset = 0; + double yaw_offset = 0; + double roll = 0; + double pitch = 0; + double yaw = 0; + RosFilterUtilities::quatToRPY(target_frame_trans.getRotation(), roll_offset, pitch_offset, yaw_offset); + RosFilterUtilities::quatToRPY(transform_orientation_, roll, pitch, yaw); + + ROS_DEBUG_STREAM("Initial orientation is " << transform_orientation_); + + // Apply the offset (making sure to bound them), and throw them in a vector + tf2::Vector3 rpy_angles(FilterUtilities::clampRotation(roll - roll_offset), + FilterUtilities::clampRotation(pitch - pitch_offset), + FilterUtilities::clampRotation(yaw - yaw_offset)); + + // Now we need to rotate the roll and pitch by the yaw offset value. + // Imagine a case where an IMU is mounted facing sideways. In that case + // pitch for the IMU's world frame is roll for the robot. + tf2::Matrix3x3 mat; + mat.setRPY(0.0, 0.0, yaw_offset); + rpy_angles = mat * rpy_angles; + transform_orientation_.setRPY(rpy_angles.getX(), rpy_angles.getY(), rpy_angles.getZ()); + + ROS_DEBUG_STREAM("Initial corrected orientation roll, pitch, yaw is (" << + rpy_angles.getX() << ", " << rpy_angles.getY() << ", " << rpy_angles.getZ() << ")"); + + has_transform_imu_ = true; + } + } + } + + void NavSatTransform::odomCallback(const nav_msgs::OdometryConstPtr& msg) + { + world_frame_id_ = msg->header.frame_id; + base_link_frame_id_ = msg->child_frame_id; + + if (!transform_good_ && !use_manual_datum_) + { + setTransformOdometry(msg); + } + + tf2::fromMsg(msg->pose.pose, latest_world_pose_); + latest_odom_covariance_.setZero(); + for (size_t row = 0; row < POSE_SIZE; ++row) + { + for (size_t col = 0; col < POSE_SIZE; ++col) + { + latest_odom_covariance_(row, col) = msg->pose.covariance[row * POSE_SIZE + col]; + } + } + + odom_update_time_ = msg->header.stamp; + odom_updated_ = true; + } + + + bool NavSatTransform::prepareFilteredGps(sensor_msgs::NavSatFix &filtered_gps) + { + bool new_data = false; + + if (transform_good_ && odom_updated_) + { + mapToLL(latest_world_pose_.getOrigin(), filtered_gps.latitude, filtered_gps.longitude, filtered_gps.altitude); + + // Rotate the covariance as well + tf2::Matrix3x3 rot(cartesian_world_trans_inverse_.getRotation()); + Eigen::MatrixXd rot_6d(POSE_SIZE, POSE_SIZE); + rot_6d.setIdentity(); + + for (size_t rInd = 0; rInd < POSITION_SIZE; ++rInd) + { + rot_6d(rInd, 0) = rot.getRow(rInd).getX(); + rot_6d(rInd, 1) = rot.getRow(rInd).getY(); + rot_6d(rInd, 2) = rot.getRow(rInd).getZ(); + rot_6d(rInd+POSITION_SIZE, 3) = rot.getRow(rInd).getX(); + rot_6d(rInd+POSITION_SIZE, 4) = rot.getRow(rInd).getY(); + rot_6d(rInd+POSITION_SIZE, 5) = rot.getRow(rInd).getZ(); + } + + // Rotate the covariance + latest_odom_covariance_ = rot_6d * latest_odom_covariance_.eval() * rot_6d.transpose(); + + // Copy the measurement's covariance matrix back + for (size_t i = 0; i < POSITION_SIZE; i++) + { + for (size_t j = 0; j < POSITION_SIZE; j++) + { + filtered_gps.position_covariance[POSITION_SIZE * i + j] = latest_odom_covariance_(i, j); + } + } + + filtered_gps.position_covariance_type = sensor_msgs::NavSatFix::COVARIANCE_TYPE_KNOWN; + filtered_gps.status.status = sensor_msgs::NavSatStatus::STATUS_GBAS_FIX; + filtered_gps.header.frame_id = base_link_frame_id_; + filtered_gps.header.stamp = odom_update_time_; + + // Mark this GPS as used + odom_updated_ = false; + new_data = true; + } + + return new_data; + } + + bool NavSatTransform::prepareGpsOdometry(nav_msgs::Odometry &gps_odom) + { + bool new_data = false; + + if (transform_good_ && gps_updated_ && odom_updated_) + { + gps_odom = cartesianToMap(latest_cartesian_pose_); + + tf2::Transform transformed_cartesian_gps; + tf2::fromMsg(gps_odom.pose.pose, transformed_cartesian_gps); + + // Want the pose of the vehicle origin, not the GPS + tf2::Transform transformed_cartesian_robot; + getRobotOriginWorldPose(transformed_cartesian_gps, transformed_cartesian_robot, gps_odom.header.stamp); + + // Rotate the covariance as well + tf2::Matrix3x3 rot(cartesian_world_transform_.getRotation()); + Eigen::MatrixXd rot_6d(POSE_SIZE, POSE_SIZE); + rot_6d.setIdentity(); + + for (size_t rInd = 0; rInd < POSITION_SIZE; ++rInd) + { + rot_6d(rInd, 0) = rot.getRow(rInd).getX(); + rot_6d(rInd, 1) = rot.getRow(rInd).getY(); + rot_6d(rInd, 2) = rot.getRow(rInd).getZ(); + rot_6d(rInd+POSITION_SIZE, 3) = rot.getRow(rInd).getX(); + rot_6d(rInd+POSITION_SIZE, 4) = rot.getRow(rInd).getY(); + rot_6d(rInd+POSITION_SIZE, 5) = rot.getRow(rInd).getZ(); + } + + // Rotate the covariance + latest_cartesian_covariance_ = rot_6d * latest_cartesian_covariance_.eval() * rot_6d.transpose(); + + // Now fill out the message. Set the orientation to the identity. + tf2::toMsg(transformed_cartesian_robot, gps_odom.pose.pose); + gps_odom.pose.pose.position.z = (zero_altitude_ ? 0.0 : gps_odom.pose.pose.position.z); + + // Copy the measurement's covariance matrix so that we can rotate it later + for (size_t i = 0; i < POSE_SIZE; i++) + { + for (size_t j = 0; j < POSE_SIZE; j++) + { + gps_odom.pose.covariance[POSE_SIZE * i + j] = latest_cartesian_covariance_(i, j); + } + } + + // Mark this GPS as used + gps_updated_ = false; + new_data = true; + } + + return new_data; + } + + void NavSatTransform::setTransformGps(const sensor_msgs::NavSatFixConstPtr& msg) + { + double cartesian_x = 0; + double cartesian_y = 0; + double cartesian_z = 0; + if (use_local_cartesian_) + { + const double hae_altitude = 0.0; + gps_local_cartesian_.Reset(msg->latitude, msg->longitude, hae_altitude); + gps_local_cartesian_.Forward(msg->latitude, msg->longitude, msg->altitude, cartesian_x, cartesian_y, cartesian_z); + + // UTM meridian convergence is not meaningful when using local cartesian, so set it to 0.0 + utm_meridian_convergence_ = 0.0; + } + else + { + double k_tmp; + double utm_meridian_convergence_degrees; + GeographicLib::UTMUPS::Forward(msg->latitude, msg->longitude, utm_zone_, northp_, + cartesian_x, cartesian_y, utm_meridian_convergence_degrees, k_tmp); + utm_meridian_convergence_ = utm_meridian_convergence_degrees * NavsatConversions::RADIANS_PER_DEGREE; + } + + ROS_INFO_STREAM("Datum (latitude, longitude, altitude) is (" << std::fixed << msg->latitude << ", " << + msg->longitude << ", " << msg->altitude << ")"); + ROS_INFO_STREAM("Datum " << ((use_local_cartesian_)? "Local Cartesian" : "UTM") << + " coordinate is (" << std::fixed << cartesian_x << ", " << cartesian_y << ") zone " << utm_zone_); + + transform_cartesian_pose_.setOrigin(tf2::Vector3(cartesian_x, cartesian_y, msg->altitude)); + transform_cartesian_pose_.setRotation(tf2::Quaternion::getIdentity()); + has_transform_gps_ = true; + } + + void NavSatTransform::setTransformOdometry(const nav_msgs::OdometryConstPtr& msg) + { + tf2::fromMsg(msg->pose.pose, transform_world_pose_); + has_transform_odom_ = true; + + ROS_INFO_STREAM_ONCE("Initial odometry pose is " << transform_world_pose_); + + // Users can optionally use the (potentially fused) heading from + // the odometry source, which may have multiple fused sources of + // heading data, and so would act as a better heading for the + // Cartesian->world_frame transform. + if (!transform_good_ && use_odometry_yaw_ && !use_manual_datum_) + { + sensor_msgs::Imu *imu = new sensor_msgs::Imu(); + imu->orientation = msg->pose.pose.orientation; + imu->header.frame_id = msg->child_frame_id; + imu->header.stamp = msg->header.stamp; + sensor_msgs::ImuConstPtr imuPtr(imu); + imuCallback(imuPtr); + } + } + +} // namespace RobotLocalization diff --git a/navigations/robot_localization/src/navsat_transform_node.cpp b/navigations/robot_localization/src/navsat_transform_node.cpp new file mode 100755 index 0000000..16023fa --- /dev/null +++ b/navigations/robot_localization/src/navsat_transform_node.cpp @@ -0,0 +1,51 @@ +/* + * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include "robot_localization/navsat_transform.h" + +#include + +int main(int argc, char **argv) +{ + ros::init(argc, argv, "navsat_transform_node"); + + ros::NodeHandle nh; + ros::NodeHandle nh_priv("~"); + + + RobotLocalization::NavSatTransform trans(nh, nh_priv); + ros::spin(); + + return EXIT_SUCCESS; +} + + diff --git a/navigations/robot_localization/src/navsat_transform_nodelet.cpp b/navigations/robot_localization/src/navsat_transform_nodelet.cpp new file mode 100755 index 0000000..994ddc1 --- /dev/null +++ b/navigations/robot_localization/src/navsat_transform_nodelet.cpp @@ -0,0 +1,63 @@ +/* + * Copyright (c) 2017 Simon Gene Gottlieb + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include "robot_localization/navsat_transform.h" + +#include +#include +#include + +#include + +namespace RobotLocalization +{ + +class NavSatTransformNodelet : public nodelet::Nodelet +{ +private: + std::unique_ptr trans; + +public: + virtual void onInit() + { + NODELET_DEBUG("Initializing nodelet..."); + + ros::NodeHandle nh = getNodeHandle(); + ros::NodeHandle nh_priv = getPrivateNodeHandle(); + + trans = std::make_unique(nh, nh_priv); + } +}; + +} // namespace RobotLocalization + +PLUGINLIB_EXPORT_CLASS(RobotLocalization::NavSatTransformNodelet, nodelet::Nodelet); diff --git a/navigations/robot_localization/src/robot_localization_estimator.cpp b/navigations/robot_localization/src/robot_localization_estimator.cpp new file mode 100755 index 0000000..9de64c3 --- /dev/null +++ b/navigations/robot_localization/src/robot_localization_estimator.cpp @@ -0,0 +1,212 @@ +/* + * Copyright (c) 2016, TNO IVS Helmond. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include "robot_localization/robot_localization_estimator.h" +#include "robot_localization/ekf.h" +#include "robot_localization/ukf.h" + +#include + +namespace RobotLocalization +{ +RobotLocalizationEstimator::RobotLocalizationEstimator(unsigned int buffer_capacity, + FilterType filter_type, + const Eigen::MatrixXd& process_noise_covariance, + const std::vector& filter_args) +{ + state_buffer_.set_capacity(buffer_capacity); + + // Set up the filter that is used for predictions + if ( filter_type == FilterTypes::EKF ) + { + filter_ = new Ekf; + } + else if ( filter_type == FilterTypes::UKF ) + { + filter_ = new Ukf(filter_args); + } + + filter_->setProcessNoiseCovariance(process_noise_covariance); +} + +RobotLocalizationEstimator::~RobotLocalizationEstimator() +{ + delete filter_; +} + +void RobotLocalizationEstimator::setState(const EstimatorState& state) +{ + // If newly received state is newer than any in the buffer, push back + if ( state_buffer_.empty() || state.time_stamp > state_buffer_.back().time_stamp ) + { + state_buffer_.push_back(state); + } + // If it is older, put it in the right position + else + { + for ( boost::circular_buffer::iterator it = state_buffer_.begin(); it != state_buffer_.end(); ++it ) + { + if ( state.time_stamp < it->time_stamp ) + { + state_buffer_.insert(it, state); + return; + } + } + } +} + +EstimatorResult RobotLocalizationEstimator::getState(const double time, + EstimatorState& state) const +{ + // If there's nothing in the buffer, there's nothing to give. + if ( state_buffer_.size() == 0 ) + { + return EstimatorResults::EmptyBuffer; + } + + // Set state to the most recent one for now + state = state_buffer_.back(); + + // Go through buffer from new to old + EstimatorState last_state_before_time = state_buffer_.front(); + EstimatorState next_state_after_time = state_buffer_.back(); + bool previous_state_found = false; + bool next_state_found = false; + + for (boost::circular_buffer::const_reverse_iterator it = state_buffer_.rbegin(); + it != state_buffer_.rend(); ++it) + { + /* If the time stamp of the current state from the buffer is + * older than the requested time, store it as the last state + * before the requested time. If it is younger, save it as the + * next one after, and go on to find the last one before. + */ + if ( it->time_stamp == time ) + { + state = *it; + return EstimatorResults::Exact; + } + else if ( it->time_stamp <= time ) + { + last_state_before_time = *it; + previous_state_found = true; + break; + } + else + { + next_state_after_time = *it; + next_state_found = true; + } + } + + // If we found a previous state and a next state, we can do interpolation + if ( previous_state_found && next_state_found ) + { + interpolate(last_state_before_time, next_state_after_time, time, state); + return EstimatorResults::Interpolation; + } + + // If only a previous state is found, we can do extrapolation into the future + else if ( previous_state_found ) + { + extrapolate(last_state_before_time, time, state); + return EstimatorResults::ExtrapolationIntoFuture; + } + + // If only a next state is found, we'll have to extrapolate into the past. + else if ( next_state_found ) + { + extrapolate(next_state_after_time, time, state); + return EstimatorResults::ExtrapolationIntoPast; + } + + else + { + return EstimatorResults::Failed; + } +} + +void RobotLocalizationEstimator::setBufferCapacity(const int capacity) +{ + state_buffer_.set_capacity(capacity); +} + +void RobotLocalizationEstimator::clearBuffer() +{ + state_buffer_.clear(); +} + +unsigned int RobotLocalizationEstimator::getBufferCapacity() const +{ + return state_buffer_.capacity(); +} + +unsigned int RobotLocalizationEstimator::getSize() const +{ + return state_buffer_.size(); +} + +void RobotLocalizationEstimator::extrapolate(const EstimatorState& boundary_state, + const double requested_time, + EstimatorState& state_at_req_time) const +{ + // Set up the filter with the boundary state + filter_->setState(boundary_state.state); + filter_->setEstimateErrorCovariance(boundary_state.covariance); + + // Calculate how much time we need to extrapolate into the future + double delta = requested_time - boundary_state.time_stamp; + + // Use the filter to predict + filter_->predict(boundary_state.time_stamp, delta); + + state_at_req_time.time_stamp = requested_time; + state_at_req_time.state = filter_->getState(); + state_at_req_time.covariance = filter_->getEstimateErrorCovariance(); + + return; +} + +void RobotLocalizationEstimator::interpolate(const EstimatorState& given_state_1, + const EstimatorState& given_state_2, + const double requested_time, + EstimatorState& state_at_req_time) const +{ + /* + * TODO: Right now, we only extrapolate from the last known state before the requested time. But as the state after + * the requested time is also known, we may want to perform interpolation between states. + */ + extrapolate(given_state_1, requested_time, state_at_req_time); + return; +} + +} // namespace RobotLocalization diff --git a/navigations/robot_localization/src/robot_localization_listener_node.cpp b/navigations/robot_localization/src/robot_localization_listener_node.cpp new file mode 100755 index 0000000..697070c --- /dev/null +++ b/navigations/robot_localization/src/robot_localization_listener_node.cpp @@ -0,0 +1,98 @@ +/* + * Copyright (c) 2016, TNO IVS Helmond. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include "robot_localization/ros_robot_localization_listener.h" +#include "robot_localization/GetState.h" + +#include + +namespace RobotLocalization +{ + +class RobotLocalizationListenerNode +{ +public: + RobotLocalizationListenerNode() + { + service_ = n_.advertiseService("get_state", &RobotLocalizationListenerNode::getStateCallback, this); + } + + std::string getService() + { + return service_.getService(); + } + +private: + RosRobotLocalizationListener rll_; + ros::NodeHandle n_; + ros::ServiceServer service_; + + bool getStateCallback(robot_localization::GetState::Request &req, + robot_localization::GetState::Response &res) + { + Eigen::VectorXd state(STATE_SIZE); + Eigen::MatrixXd covariance(STATE_SIZE, STATE_SIZE); + + if ( !rll_.getState(req.time_stamp, req.frame_id, state, covariance) ) + { + ROS_ERROR("Robot Localization Listener Node: Listener instance returned false at getState call."); + return false; + } + + for (size_t i = 0; i < STATE_SIZE; i++) + { + res.state[i] = (*(state.data() + i)); + } + + for (size_t i = 0; i < STATE_SIZE * STATE_SIZE; i++) + { + res.covariance[i] = (*(covariance.data() + i)); + } + + ROS_DEBUG("Robot Localization Listener Node: Listener responded with state and covariance at the requested time."); + return true; + } +}; + +} // namespace RobotLocalization + +int main(int argc, char **argv) +{ + ros::init(argc, argv, "robot_localization_listener_node"); + + RobotLocalization::RobotLocalizationListenerNode rlln; + ROS_INFO_STREAM("Robot Localization Listener Node: Ready to handle GetState requests at " << rlln.getService()); + + ros::spin(); + + return 0; +} diff --git a/navigations/robot_localization/src/ros_filter.cpp b/navigations/robot_localization/src/ros_filter.cpp new file mode 100755 index 0000000..4cacacf --- /dev/null +++ b/navigations/robot_localization/src/ros_filter.cpp @@ -0,0 +1,3361 @@ +/* + * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include "robot_localization/ros_filter.h" +#include "robot_localization/filter_utilities.h" +#include "robot_localization/ekf.h" +#include "robot_localization/ukf.h" + +#include + +#include +#include +#include +#include +#include +#include +#include +#include + +#if defined(_WIN32) && defined(ERROR) + #undef ERROR +#endif + +namespace RobotLocalization +{ + template + RosFilter::RosFilter(ros::NodeHandle nh, + ros::NodeHandle nh_priv, + std::string node_name, + std::vector args) : + disabledAtStartup_(false), + enabled_(false), + predictToCurrentTime_(false), + printDiagnostics_(true), + publishAcceleration_(false), + publishTransform_(true), + resetOnTimeJump_(false), + smoothLaggedData_(false), + toggledOn_(true), + twoDMode_(false), + useControl_(false), + dynamicDiagErrorLevel_(diagnostic_msgs::DiagnosticStatus::OK), + staticDiagErrorLevel_(diagnostic_msgs::DiagnosticStatus::OK), + frequency_(30.0), + gravitationalAcc_(9.80665), + historyLength_(0), + minFrequency_(frequency_ - 2.0), + maxFrequency_(frequency_ + 2.0), + baseLinkFrameId_("base_link"), + mapFrameId_("map"), + odomFrameId_("odom"), + worldFrameId_(odomFrameId_), + lastDiagTime_(0), + lastSetPoseTime_(0), + latestControlTime_(0), + tfTimeOffset_(ros::Duration(0)), + tfTimeout_(ros::Duration(0)), + filter_(args), + nh_(nh), + nhLocal_(nh_priv), + diagnosticUpdater_(nh, nh_priv, node_name), + tfListener_(tfBuffer_) + { + stateVariableNames_.push_back("X"); + stateVariableNames_.push_back("Y"); + stateVariableNames_.push_back("Z"); + stateVariableNames_.push_back("ROLL"); + stateVariableNames_.push_back("PITCH"); + stateVariableNames_.push_back("YAW"); + stateVariableNames_.push_back("X_VELOCITY"); + stateVariableNames_.push_back("Y_VELOCITY"); + stateVariableNames_.push_back("Z_VELOCITY"); + stateVariableNames_.push_back("ROLL_VELOCITY"); + stateVariableNames_.push_back("PITCH_VELOCITY"); + stateVariableNames_.push_back("YAW_VELOCITY"); + stateVariableNames_.push_back("X_ACCELERATION"); + stateVariableNames_.push_back("Y_ACCELERATION"); + stateVariableNames_.push_back("Z_ACCELERATION"); + + diagnosticUpdater_.setHardwareID("none"); + } + + template + RosFilter::RosFilter(ros::NodeHandle nh, ros::NodeHandle nh_priv, std::vector args) : + RosFilter::RosFilter(nh, nh_priv, ros::this_node::getName(), args) + {} + + template + RosFilter::~RosFilter() + { + topicSubs_.clear(); + } + + template + void RosFilter::initialize() + { + loadParams(); + + if (printDiagnostics_) + { + diagnosticUpdater_.add("Filter diagnostic updater", this, &RosFilter::aggregateDiagnostics); + } + + // Set up the frequency diagnostic + minFrequency_ = frequency_ - 2; + maxFrequency_ = frequency_ + 2; + freqDiag_ = std::make_unique( + "odometry/filtered", + diagnosticUpdater_, + diagnostic_updater::FrequencyStatusParam( + &minFrequency_, + &maxFrequency_, + 0.1, + 10)); + + // Publisher + positionPub_ = nh_.advertise("odometry/filtered", 20); + + // Optional acceleration publisher + if (publishAcceleration_) + { + accelPub_ = nh_.advertise("accel/filtered", 20); + } + + lastDiagTime_ = ros::Time::now(); + + periodicUpdateTimer_ = nh_.createTimer(ros::Duration(1./frequency_), &RosFilter::periodicUpdate, this); + } + + template + void RosFilter::reset() + { + // Get rid of any initial poses (pretend we've never had a measurement) + initialMeasurements_.clear(); + previousMeasurements_.clear(); + previousMeasurementCovariances_.clear(); + + clearMeasurementQueue(); + + filterStateHistory_.clear(); + measurementHistory_.clear(); + + // Also set the last set pose time, so we ignore all messages + // that occur before it + lastSetPoseTime_ = ros::Time(0); + + // clear tf buffer to avoid TF_OLD_DATA errors + tfBuffer_.clear(); + + // clear last message timestamp, so older messages will be accepted + lastMessageTimes_.clear(); + + // reset filter to uninitialized state + filter_.reset(); + + // clear all waiting callbacks + ros::getGlobalCallbackQueue()->clear(); + } + + template + bool RosFilter::toggleFilterProcessingCallback(robot_localization::ToggleFilterProcessing::Request& req, + robot_localization::ToggleFilterProcessing::Response& resp) + { + if (req.on == toggledOn_) + { + ROS_WARN_STREAM("Service was called to toggle filter processing but state was already as requested."); + resp.status = false; + } + else + { + ROS_INFO("Toggling filter measurement filtering to %s.", req.on ? "On" : "Off"); + toggledOn_ = req.on; + resp.status = true; + } + return true; + } + + // @todo: Replace with AccelWithCovarianceStamped + template + void RosFilter::accelerationCallback(const sensor_msgs::Imu::ConstPtr &msg, const CallbackData &callbackData, + const std::string &targetFrame) + { + // If we've just reset the filter, then we want to ignore any messages + // that arrive with an older timestamp + if (msg->header.stamp <= lastSetPoseTime_) + { + return; + } + + const std::string &topicName = callbackData.topicName_; + + RF_DEBUG("------ RosFilter::accelerationCallback (" << topicName << ") ------\n" + "Twist message:\n" << *msg); + + if (lastMessageTimes_.count(topicName) == 0) + { + lastMessageTimes_.insert(std::pair(topicName, msg->header.stamp)); + } + + // Make sure this message is newer than the last one + if (msg->header.stamp >= lastMessageTimes_[topicName]) + { + RF_DEBUG("Update vector for " << topicName << " is:\n" << topicName); + + Eigen::VectorXd measurement(STATE_SIZE); + Eigen::MatrixXd measurementCovariance(STATE_SIZE, STATE_SIZE); + + measurement.setZero(); + measurementCovariance.setZero(); + + // Make sure we're actually updating at least one of these variables + std::vector updateVectorCorrected = callbackData.updateVector_; + + // Prepare the twist data for inclusion in the filter + if (prepareAcceleration(msg, topicName, targetFrame, callbackData.relative_, updateVectorCorrected, measurement, + measurementCovariance)) + { + // Store the measurement. Add an "acceleration" suffix so we know what kind of measurement + // we're dealing with when we debug the core filter logic. + enqueueMeasurement(topicName, + measurement, + measurementCovariance, + updateVectorCorrected, + callbackData.rejectionThreshold_, + msg->header.stamp); + + RF_DEBUG("Enqueued new measurement for " << topicName << "_acceleration\n"); + } + else + { + RF_DEBUG("Did *not* enqueue measurement for " << topicName << "_acceleration\n"); + } + + lastMessageTimes_[topicName] = msg->header.stamp; + + RF_DEBUG("Last message time for " << topicName << " is now " << + lastMessageTimes_[topicName] << "\n"); + } + else if (resetOnTimeJump_ && ros::Time::isSimTime()) + { + reset(); + } + else + { + std::stringstream stream; + stream << "The " << topicName << " message has a timestamp before that of the previous message received," << + " this message will be ignored. This may indicate a bad timestamp. (message time: " << + msg->header.stamp.toSec() << ")"; + addDiagnostic(diagnostic_msgs::DiagnosticStatus::WARN, + topicName + "_timestamp", + stream.str(), + false); + + RF_DEBUG("Message is too old. Last message time for " << topicName << + " is " << lastMessageTimes_[topicName] << ", current message time is " << + msg->header.stamp << ".\n"); + } + + RF_DEBUG("\n----- /RosFilter::accelerationCallback (" << topicName << ") ------\n"); + } + + template + void RosFilter::controlCallback(const geometry_msgs::Twist::ConstPtr &msg) + { + geometry_msgs::TwistStampedPtr twistStampedPtr = geometry_msgs::TwistStampedPtr(new geometry_msgs::TwistStamped()); + twistStampedPtr->twist = *msg; + twistStampedPtr->header.frame_id = baseLinkFrameId_; + twistStampedPtr->header.stamp = ros::Time::now(); + controlCallback(twistStampedPtr); + } + + template + void RosFilter::controlCallback(const geometry_msgs::TwistStamped::ConstPtr &msg) + { + if (msg->header.frame_id == baseLinkFrameId_ || msg->header.frame_id == "") + { + latestControl_(ControlMemberVx) = msg->twist.linear.x; + latestControl_(ControlMemberVy) = msg->twist.linear.y; + latestControl_(ControlMemberVz) = msg->twist.linear.z; + latestControl_(ControlMemberVroll) = msg->twist.angular.x; + latestControl_(ControlMemberVpitch) = msg->twist.angular.y; + latestControl_(ControlMemberVyaw) = msg->twist.angular.z; + latestControlTime_ = msg->header.stamp; + + // Update the filter with this control term + filter_.setControl(latestControl_, msg->header.stamp.toSec()); + } + else + { + ROS_WARN_STREAM_THROTTLE(5.0, "Commanded velocities must be given in the robot's body frame (" << + baseLinkFrameId_ << "). Message frame was " << msg->header.frame_id); + } + } + + template + void RosFilter::enqueueMeasurement(const std::string &topicName, + const Eigen::VectorXd &measurement, + const Eigen::MatrixXd &measurementCovariance, + const std::vector &updateVector, + const double mahalanobisThresh, + const ros::Time &time) + { + MeasurementPtr meas = MeasurementPtr(new Measurement()); + + meas->topicName_ = topicName; + meas->measurement_ = measurement; + meas->covariance_ = measurementCovariance; + meas->updateVector_ = updateVector; + meas->time_ = time.toSec(); + meas->mahalanobisThresh_ = mahalanobisThresh; + meas->latestControl_ = latestControl_; + meas->latestControlTime_ = latestControlTime_.toSec(); + measurementQueue_.push(meas); + } + + template + void RosFilter::forceTwoD(Eigen::VectorXd &measurement, + Eigen::MatrixXd &measurementCovariance, + std::vector &updateVector) + { + measurement(StateMemberZ) = 0.0; + measurement(StateMemberRoll) = 0.0; + measurement(StateMemberPitch) = 0.0; + measurement(StateMemberVz) = 0.0; + measurement(StateMemberVroll) = 0.0; + measurement(StateMemberVpitch) = 0.0; + measurement(StateMemberAz) = 0.0; + + measurementCovariance(StateMemberZ, StateMemberZ) = 1e-6; + measurementCovariance(StateMemberRoll, StateMemberRoll) = 1e-6; + measurementCovariance(StateMemberPitch, StateMemberPitch) = 1e-6; + measurementCovariance(StateMemberVz, StateMemberVz) = 1e-6; + measurementCovariance(StateMemberVroll, StateMemberVroll) = 1e-6; + measurementCovariance(StateMemberVpitch, StateMemberVpitch) = 1e-6; + measurementCovariance(StateMemberAz, StateMemberAz) = 1e-6; + + updateVector[StateMemberZ] = 1; + updateVector[StateMemberRoll] = 1; + updateVector[StateMemberPitch] = 1; + updateVector[StateMemberVz] = 1; + updateVector[StateMemberVroll] = 1; + updateVector[StateMemberVpitch] = 1; + updateVector[StateMemberAz] = 1; + } + + template + bool RosFilter::getFilteredOdometryMessage(nav_msgs::Odometry &message) + { + // If the filter has received a measurement at some point... + if (filter_.getInitializedStatus()) + { + // Grab our current state and covariance estimates + const Eigen::VectorXd &state = filter_.getState(); + const Eigen::MatrixXd &estimateErrorCovariance = filter_.getEstimateErrorCovariance(); + + // Convert from roll, pitch, and yaw back to quaternion for + // orientation values + tf2::Quaternion quat; + quat.setRPY(state(StateMemberRoll), state(StateMemberPitch), state(StateMemberYaw)); + + // Fill out the message + message.pose.pose.position.x = state(StateMemberX); + message.pose.pose.position.y = state(StateMemberY); + message.pose.pose.position.z = state(StateMemberZ); + message.pose.pose.orientation.x = quat.x(); + message.pose.pose.orientation.y = quat.y(); + message.pose.pose.orientation.z = quat.z(); + message.pose.pose.orientation.w = quat.w(); + message.twist.twist.linear.x = state(StateMemberVx); + message.twist.twist.linear.y = state(StateMemberVy); + message.twist.twist.linear.z = state(StateMemberVz); + message.twist.twist.angular.x = state(StateMemberVroll); + message.twist.twist.angular.y = state(StateMemberVpitch); + message.twist.twist.angular.z = state(StateMemberVyaw); + + // Our covariance matrix layout doesn't quite match + for (size_t i = 0; i < POSE_SIZE; i++) + { + for (size_t j = 0; j < POSE_SIZE; j++) + { + message.pose.covariance[POSE_SIZE * i + j] = estimateErrorCovariance(i, j); + } + } + + // POSE_SIZE and TWIST_SIZE are currently the same size, but we can spare a few + // cycles to be meticulous and not index a twist covariance array on the size of + // a pose covariance array + for (size_t i = 0; i < TWIST_SIZE; i++) + { + for (size_t j = 0; j < TWIST_SIZE; j++) + { + message.twist.covariance[TWIST_SIZE * i + j] = + estimateErrorCovariance(i + POSITION_V_OFFSET, j + POSITION_V_OFFSET); + } + } + + message.header.stamp = ros::Time(filter_.getLastMeasurementTime()); + message.header.frame_id = worldFrameId_; + message.child_frame_id = baseLinkOutputFrameId_; + } + + return filter_.getInitializedStatus(); + } + + template + bool RosFilter::getFilteredAccelMessage(geometry_msgs::AccelWithCovarianceStamped &message) + { + // If the filter has received a measurement at some point... + if (filter_.getInitializedStatus()) + { + // Grab our current state and covariance estimates + const Eigen::VectorXd &state = filter_.getState(); + const Eigen::MatrixXd &estimateErrorCovariance = filter_.getEstimateErrorCovariance(); + + //! Fill out the accel_msg + message.accel.accel.linear.x = state(StateMemberAx); + message.accel.accel.linear.y = state(StateMemberAy); + message.accel.accel.linear.z = state(StateMemberAz); + message.accel.accel.angular.x = angular_acceleration_.x(); + message.accel.accel.angular.y = angular_acceleration_.y(); + message.accel.accel.angular.z = angular_acceleration_.z(); + // Fill the covariance (only the left-upper matrix since we are not estimating + // the rotational accelerations arround the axes + for (size_t i = 0; i < ACCELERATION_SIZE; i++) + { + for (size_t j = 0; j < ACCELERATION_SIZE; j++) + { + // We use the POSE_SIZE since the accel cov matrix of ROS is 6x6 + message.accel.covariance[POSE_SIZE * i + j] = + estimateErrorCovariance(i + POSITION_A_OFFSET, j + POSITION_A_OFFSET); + } + } + for (size_t i = ACCELERATION_SIZE; i < POSE_SIZE; i++) + { + for (size_t j = ACCELERATION_SIZE; j < POSE_SIZE; j++) + { + // fill out the angular portion. We assume the linear and angular portions are independent. + message.accel.covariance[POSE_SIZE * i + j] = + angular_acceleration_cov_(i - ACCELERATION_SIZE, j - ACCELERATION_SIZE); + } + } + + // Fill header information + message.header.stamp = ros::Time(filter_.getLastMeasurementTime()); + message.header.frame_id = baseLinkOutputFrameId_; + } + + return filter_.getInitializedStatus(); + } + + template + void RosFilter::imuCallback(const sensor_msgs::Imu::ConstPtr &msg, + const std::string &topicName, + const CallbackData &poseCallbackData, + const CallbackData &twistCallbackData, + const CallbackData &accelCallbackData) + { + RF_DEBUG("------ RosFilter::imuCallback (" << topicName << ") ------\n" << "IMU message:\n" << *msg); + + // If we've just reset the filter, then we want to ignore any messages + // that arrive with an older timestamp + if (msg->header.stamp <= lastSetPoseTime_) + { + std::stringstream stream; + stream << "The " << topicName << " message has a timestamp equal to or before the last filter reset, " << + "this message will be ignored. This may indicate an empty or bad timestamp. (message time: " << + msg->header.stamp.toSec() << ")"; + addDiagnostic(diagnostic_msgs::DiagnosticStatus::WARN, + topicName + "_timestamp", + stream.str(), + false); + RF_DEBUG("Received message that preceded the most recent pose reset. Ignoring..."); + + return; + } + + // As with the odometry message, we can separate out the pose- and twist-related variables + // in the IMU message and pass them to the pose and twist callbacks (filters) + if (poseCallbackData.updateSum_ > 0) + { + // Per the IMU message specification, if the IMU does not provide orientation, + // then its first covariance value should be set to -1, and we should ignore + // that portion of the message. robot_localization allows users to explicitly + // ignore data using its parameters, but we should also be compliant with + // message specs. + if (::fabs(msg->orientation_covariance[0] + 1) < 1e-9) + { + RF_DEBUG("Received IMU message with -1 as its first covariance value for orientation. " + "Ignoring orientation..."); + } + else + { + // Extract the pose (orientation) data, pass it to its filter + geometry_msgs::PoseWithCovarianceStamped *posPtr = new geometry_msgs::PoseWithCovarianceStamped(); + posPtr->header = msg->header; + posPtr->pose.pose.orientation = msg->orientation; + + // Copy the covariance for roll, pitch, and yaw + for (size_t i = 0; i < ORIENTATION_SIZE; i++) + { + for (size_t j = 0; j < ORIENTATION_SIZE; j++) + { + posPtr->pose.covariance[POSE_SIZE * (i + ORIENTATION_SIZE) + (j + ORIENTATION_SIZE)] = + msg->orientation_covariance[ORIENTATION_SIZE * i + j]; + } + } + + // IMU data gets handled a bit differently, since the message is ambiguous and has only a single frame_id, + // even though the data in it is reported in two different frames. As we assume users will specify a base_link + // to imu transform, we make the target and child frame baseLinkFrameId_ and tell the poseCallback that it is + // working with IMU data. This will cause it to apply different logic to the data. + geometry_msgs::PoseWithCovarianceStampedConstPtr pptr(posPtr); + poseCallback(pptr, poseCallbackData, baseLinkFrameId_, + baseLinkFrameId_, true); + } + } + + if (twistCallbackData.updateSum_ > 0) + { + // Ignore rotational velocity if the first covariance value is -1 + if (::fabs(msg->angular_velocity_covariance[0] + 1) < 1e-9) + { + RF_DEBUG("Received IMU message with -1 as its first covariance value for angular " + "velocity. Ignoring angular velocity..."); + } + else + { + // Repeat for velocity + geometry_msgs::TwistWithCovarianceStamped *twistPtr = new geometry_msgs::TwistWithCovarianceStamped(); + twistPtr->header = msg->header; + twistPtr->twist.twist.angular = msg->angular_velocity; + + // Copy the covariance + for (size_t i = 0; i < ORIENTATION_SIZE; i++) + { + for (size_t j = 0; j < ORIENTATION_SIZE; j++) + { + twistPtr->twist.covariance[TWIST_SIZE * (i + ORIENTATION_SIZE) + (j + ORIENTATION_SIZE)] = + msg->angular_velocity_covariance[ORIENTATION_SIZE * i + j]; + } + } + + geometry_msgs::TwistWithCovarianceStampedConstPtr tptr(twistPtr); + twistCallback(tptr, twistCallbackData, baseLinkFrameId_); + } + } + + if (accelCallbackData.updateSum_ > 0) + { + // Ignore linear acceleration if the first covariance value is -1 + if (::fabs(msg->linear_acceleration_covariance[0] + 1) < 1e-9) + { + RF_DEBUG("Received IMU message with -1 as its first covariance value for linear " + "acceleration. Ignoring linear acceleration..."); + } + else + { + // Pass the message on + accelerationCallback(msg, accelCallbackData, baseLinkFrameId_); + } + } + + RF_DEBUG("\n----- /RosFilter::imuCallback (" << topicName << ") ------\n"); + } + + template + void RosFilter::integrateMeasurements(const ros::Time ¤tTime) + { + const double currentTimeSec = currentTime.toSec(); + + RF_DEBUG("------ RosFilter::integrateMeasurements ------\n\n" + "Integration time is " << std::setprecision(20) << currentTimeSec << "\n" + << measurementQueue_.size() << " measurements in queue.\n"); + + bool predictToCurrentTime = predictToCurrentTime_; + + // If we have any measurements in the queue, process them + if (!measurementQueue_.empty()) + { + // Check if the first measurement we're going to process is older than the filter's last measurement. + // This means we have received an out-of-sequence message (one with an old timestamp), and we need to + // revert both the filter state and measurement queue to the first state that preceded the time stamp + // of our first measurement. + const MeasurementPtr& firstMeasurement = measurementQueue_.top(); + int restoredMeasurementCount = 0; + if (smoothLaggedData_ && firstMeasurement->time_ < filter_.getLastMeasurementTime()) + { + RF_DEBUG("Received a measurement that was " << filter_.getLastMeasurementTime() - firstMeasurement->time_ << + " seconds in the past. Reverting filter state and measurement queue..."); + + int originalCount = static_cast(measurementQueue_.size()); + const double firstMeasurementTime = firstMeasurement->time_; + const std::string firstMeasurementTopic = firstMeasurement->topicName_; + if (!revertTo(firstMeasurementTime - 1e-9)) // revertTo may invalidate firstMeasurement + { + RF_DEBUG("ERROR: history interval is too small to revert to time " << firstMeasurementTime << "\n"); + ROS_WARN_STREAM_DELAYED_THROTTLE(historyLength_, "Received old measurement for topic " << + firstMeasurementTopic << ", but history interval is insufficiently sized. Measurement time is " << + std::setprecision(20) << firstMeasurementTime << ", current time is " << currentTime.toSec() << + ", history length is " << historyLength_ << "."); + restoredMeasurementCount = 0; + } + + restoredMeasurementCount = static_cast(measurementQueue_.size()) - originalCount; + } + + while (!measurementQueue_.empty() && ros::ok()) + { + MeasurementPtr measurement = measurementQueue_.top(); + + // If we've reached a measurement that has a time later than now, it should wait until a future iteration. + // Since measurements are stored in a priority queue, all remaining measurements will be in the future. + if (measurement->time_ > currentTime.toSec()) + { + break; + } + + measurementQueue_.pop(); + + // When we receive control messages, we call this directly in the control callback. However, we also associate + // a control with each sensor message so that we can support lagged smoothing. As we cannot guarantee that the + // new control callback will fire before a new measurement, we should only perform this operation if we are + // processing messages from the history. Otherwise, we may get a new measurement, store the "old" latest + // control, then receive a control, call setControl, and then overwrite that value with this one (i.e., with + // the "old" control we associated with the measurement). + if (useControl_ && restoredMeasurementCount > 0) + { + filter_.setControl(measurement->latestControl_, measurement->latestControlTime_); + restoredMeasurementCount--; + } + + // This will call predict and, if necessary, correct + filter_.processMeasurement(*(measurement.get())); + + // Store old states and measurements if we're smoothing + if (smoothLaggedData_) + { + // Invariant still holds: measurementHistoryDeque_.back().time_ < measurementQueue_.top().time_ + measurementHistory_.push_back(measurement); + + // We should only save the filter state once per unique timstamp + if (measurementQueue_.empty() || + ::fabs(measurementQueue_.top()->time_ - filter_.getLastMeasurementTime()) > 1e-9) + { + saveFilterState(filter_); + } + } + } + } + else if (filter_.getInitializedStatus()) + { + // In the event that we don't get any measurements for a long time, + // we still need to continue to estimate our state. Therefore, we + // should project the state forward here. + double lastUpdateDelta = currentTimeSec - filter_.getLastMeasurementTime(); + + // If we get a large delta, then continuously predict until + if (lastUpdateDelta >= filter_.getSensorTimeout()) + { + predictToCurrentTime = true; + + RF_DEBUG("Sensor timeout! Last measurement time was " << filter_.getLastMeasurementTime() << + ", current time is " << currentTimeSec << + ", delta is " << lastUpdateDelta << "\n"); + } + } + else + { + RF_DEBUG("Filter not yet initialized.\n"); + } + + if (filter_.getInitializedStatus() && predictToCurrentTime) + { + double lastUpdateDelta = currentTimeSec - filter_.getLastMeasurementTime(); + + filter_.validateDelta(lastUpdateDelta); + filter_.predict(currentTimeSec, lastUpdateDelta); + + // Update the last measurement time and last update time + filter_.setLastMeasurementTime(filter_.getLastMeasurementTime() + lastUpdateDelta); + } + + RF_DEBUG("\n----- /RosFilter::integrateMeasurements ------\n"); + } + + template + void RosFilter::differentiateMeasurements(const ros::Time ¤tTime) + { + if (filter_.getInitializedStatus()) + { + const double dt = (currentTime - lastDiffTime_).toSec(); + const Eigen::VectorXd &state = filter_.getState(); + // Specific to angular acceleration for now... + tf2::Vector3 newStateTwistRot(state(StateMemberVroll), + state(StateMemberVpitch), + state(StateMemberVyaw)); + angular_acceleration_ = (newStateTwistRot - lastStateTwistRot_)/dt; + const Eigen::MatrixXd &cov = filter_.getEstimateErrorCovariance(); + for (size_t i = 0; i < 3; i ++) + { + for (size_t j = 0; j < 3; j ++) + { + angular_acceleration_cov_(i, j) = cov(i+ORIENTATION_V_OFFSET, j+ORIENTATION_V_OFFSET) + * 2. / (dt * dt); + } + } + lastStateTwistRot_ = newStateTwistRot; + lastDiffTime_ = currentTime; + } + } + + template + void RosFilter::loadParams() + { + /* For diagnostic purposes, collect information about how many different + * sources are measuring each absolute pose variable and do not have + * differential integration enabled. + */ + std::map absPoseVarCounts; + absPoseVarCounts[StateMemberX] = 0; + absPoseVarCounts[StateMemberY] = 0; + absPoseVarCounts[StateMemberZ] = 0; + absPoseVarCounts[StateMemberRoll] = 0; + absPoseVarCounts[StateMemberPitch] = 0; + absPoseVarCounts[StateMemberYaw] = 0; + + // Same for twist variables + std::map twistVarCounts; + twistVarCounts[StateMemberVx] = 0; + twistVarCounts[StateMemberVy] = 0; + twistVarCounts[StateMemberVz] = 0; + twistVarCounts[StateMemberVroll] = 0; + twistVarCounts[StateMemberVpitch] = 0; + twistVarCounts[StateMemberVyaw] = 0; + + // Determine if we'll be printing diagnostic information + nhLocal_.param("print_diagnostics", printDiagnostics_, true); + + // Check for custom gravitational acceleration value + nhLocal_.param("gravitational_acceleration", gravitationalAcc_, 9.80665); + + // Grab the debug param. If true, the node will produce a LOT of output. + bool debug; + nhLocal_.param("debug", debug, false); + + if (debug) + { + std::string debugOutFile; + + try + { + nhLocal_.param("debug_out_file", debugOutFile, std::string("robot_localization_debug.txt")); + debugStream_.open(debugOutFile.c_str()); + + // Make sure we succeeded + if (debugStream_.is_open()) + { + filter_.setDebug(debug, &debugStream_); + } + else + { + ROS_WARN_STREAM("RosFilter::loadParams() - unable to create debug output file " << debugOutFile); + } + } + catch(const std::exception &e) + { + ROS_WARN_STREAM("RosFilter::loadParams() - unable to create debug output file" << debugOutFile + << ". Error was " << e.what() << "\n"); + } + } + + // These params specify the name of the robot's body frame (typically + // base_link) and odometry frame (typically odom) + nhLocal_.param("map_frame", mapFrameId_, std::string("map")); + nhLocal_.param("odom_frame", odomFrameId_, std::string("odom")); + nhLocal_.param("base_link_frame", baseLinkFrameId_, std::string("base_link")); + nhLocal_.param("base_link_frame_output", baseLinkOutputFrameId_, baseLinkFrameId_); + + /* + * These parameters are designed to enforce compliance with REP-105: + * http://www.ros.org/reps/rep-0105.html + * When fusing absolute position data from sensors such as GPS, the state + * estimate can undergo discrete jumps. According to REP-105, we want three + * coordinate frames: map, odom, and base_link. The map frame can have + * discontinuities, but is the frame with the most accurate position estimate + * for the robot and should not suffer from drift. The odom frame drifts over + * time, but is guaranteed to be continuous and is accurate enough for local + * planning and navigation. The base_link frame is affixed to the robot. The + * intention is that some odometry source broadcasts the odom->base_link + * transform. The localization software should broadcast map->base_link. + * However, tf does not allow multiple parents for a coordinate frame, so + * we must *compute* map->base_link, but then use the existing odom->base_link + * transform to compute *and broadcast* map->odom. + * + * The state estimation nodes in robot_localization therefore have two "modes." + * If your world_frame parameter value matches the odom_frame parameter value, + * then robot_localization will assume someone else is broadcasting a transform + * from odom_frame->base_link_frame, and it will compute the + * map_frame->odom_frame transform. Otherwise, it will simply compute the + * odom_frame->base_link_frame transform. + * + * The default is the latter behavior (broadcast of odom->base_link). + */ + nhLocal_.param("world_frame", worldFrameId_, odomFrameId_); + + ROS_FATAL_COND(mapFrameId_ == odomFrameId_ || + odomFrameId_ == baseLinkFrameId_ || + mapFrameId_ == baseLinkFrameId_ || + odomFrameId_ == baseLinkOutputFrameId_ || + mapFrameId_ == baseLinkOutputFrameId_, + "Invalid frame configuration! The values for map_frame, odom_frame, " + "and base_link_frame must be unique. If using a base_link_frame_output values, it " + "must not match the map_frame or odom_frame."); + + // Try to resolve tf_prefix + std::string tfPrefix = ""; + std::string tfPrefixPath = ""; + if (nhLocal_.searchParam("tf_prefix", tfPrefixPath)) + { + nhLocal_.getParam(tfPrefixPath, tfPrefix); + } + + // Append the tf prefix in a tf2-friendly manner + FilterUtilities::appendPrefix(tfPrefix, mapFrameId_); + FilterUtilities::appendPrefix(tfPrefix, odomFrameId_); + FilterUtilities::appendPrefix(tfPrefix, baseLinkFrameId_); + FilterUtilities::appendPrefix(tfPrefix, baseLinkOutputFrameId_); + FilterUtilities::appendPrefix(tfPrefix, worldFrameId_); + + // Whether we're publshing the world_frame->base_link_frame transform + nhLocal_.param("publish_tf", publishTransform_, true); + + // Whether we're publishing the acceleration state transform + nhLocal_.param("publish_acceleration", publishAcceleration_, false); + + // Whether we'll allow old measurements to cause a re-publication of the updated state + nhLocal_.param("permit_corrected_publication", permitCorrectedPublication_, false); + + // Transform future dating + double offsetTmp; + nhLocal_.param("transform_time_offset", offsetTmp, 0.0); + tfTimeOffset_.fromSec(offsetTmp); + + // Transform timeout + double timeoutTmp; + nhLocal_.param("transform_timeout", timeoutTmp, 0.0); + tfTimeout_.fromSec(timeoutTmp); + + // Update frequency and sensor timeout + double sensorTimeout; + nhLocal_.param("frequency", frequency_, 30.0); + nhLocal_.param("sensor_timeout", sensorTimeout, 1.0 / frequency_); + filter_.setSensorTimeout(sensorTimeout); + + // Determine if we're in 2D mode + nhLocal_.param("two_d_mode", twoDMode_, false); + + // Smoothing window size + nhLocal_.param("smooth_lagged_data", smoothLaggedData_, false); + nhLocal_.param("history_length", historyLength_, 0.0); + + // Wether we reset filter on jump back in time + nhLocal_.param("reset_on_time_jump", resetOnTimeJump_, false); + + if (!smoothLaggedData_ && ::fabs(historyLength_) > 1e-9) + { + ROS_WARN_STREAM("Filter history interval of " << historyLength_ << + " specified, but smooth_lagged_data is set to false. Lagged data will not be smoothed."); + } + + if (smoothLaggedData_ && historyLength_ < -1e9) + { + ROS_WARN_STREAM("Negative history interval of " << historyLength_ << + " specified. Absolute value will be assumed."); + } + + historyLength_ = ::fabs(historyLength_); + + nhLocal_.param("predict_to_current_time", predictToCurrentTime_, false); + + // Determine if we're using a control term + bool stampedControl = false; + double controlTimeout = sensorTimeout; + std::vector controlUpdateVector(TWIST_SIZE, 0); + std::vector accelerationLimits(TWIST_SIZE, 1.0); + std::vector accelerationGains(TWIST_SIZE, 1.0); + std::vector decelerationLimits(TWIST_SIZE, 1.0); + std::vector decelerationGains(TWIST_SIZE, 1.0); + + nhLocal_.param("use_control", useControl_, false); + nhLocal_.param("stamped_control", stampedControl, false); + nhLocal_.param("control_timeout", controlTimeout, sensorTimeout); + + if (useControl_) + { + if (nhLocal_.getParam("control_config", controlUpdateVector)) + { + if (controlUpdateVector.size() != TWIST_SIZE) + { + ROS_ERROR_STREAM("Control configuration must be of size " << TWIST_SIZE << ". Provided config was of " + "size " << controlUpdateVector.size() << ". No control term will be used."); + useControl_ = false; + } + } + else + { + ROS_ERROR_STREAM("use_control is set to true, but control_config is missing. No control term will be used."); + useControl_ = false; + } + + if (nhLocal_.getParam("acceleration_limits", accelerationLimits)) + { + if (accelerationLimits.size() != TWIST_SIZE) + { + ROS_ERROR_STREAM("Acceleration configuration must be of size " << TWIST_SIZE << ". Provided config was of " + "size " << accelerationLimits.size() << ". No control term will be used."); + useControl_ = false; + } + } + else + { + ROS_WARN_STREAM("use_control is set to true, but acceleration_limits is missing. Will use default values."); + } + + if (nhLocal_.getParam("acceleration_gains", accelerationGains)) + { + const int size = accelerationGains.size(); + if (size != TWIST_SIZE) + { + ROS_ERROR_STREAM("Acceleration gain configuration must be of size " << TWIST_SIZE << + ". Provided config was of size " << size << ". All gains will be assumed to be 1."); + std::fill_n(accelerationGains.begin(), std::min(size, TWIST_SIZE), 1.0); + accelerationGains.resize(TWIST_SIZE, 1.0); + } + } + + if (nhLocal_.getParam("deceleration_limits", decelerationLimits)) + { + if (decelerationLimits.size() != TWIST_SIZE) + { + ROS_ERROR_STREAM("Deceleration configuration must be of size " << TWIST_SIZE << + ". Provided config was of size " << decelerationLimits.size() << ". No control term will be used."); + useControl_ = false; + } + } + else + { + ROS_INFO_STREAM("use_control is set to true, but no deceleration_limits specified. Will use acceleration " + "limits."); + decelerationLimits = accelerationLimits; + } + + if (nhLocal_.getParam("deceleration_gains", decelerationGains)) + { + const int size = decelerationGains.size(); + if (size != TWIST_SIZE) + { + ROS_ERROR_STREAM("Deceleration gain configuration must be of size " << TWIST_SIZE << + ". Provided config was of size " << size << ". All gains will be assumed to be 1."); + std::fill_n(decelerationGains.begin(), std::min(size, TWIST_SIZE), 1.0); + decelerationGains.resize(TWIST_SIZE, 1.0); + } + } + else + { + ROS_INFO_STREAM("use_control is set to true, but no deceleration_gains specified. Will use acceleration " + "gains."); + decelerationGains = accelerationGains; + } + } + + bool dynamicProcessNoiseCovariance = false; + nhLocal_.param("dynamic_process_noise_covariance", dynamicProcessNoiseCovariance, false); + filter_.setUseDynamicProcessNoiseCovariance(dynamicProcessNoiseCovariance); + + std::vector initialState(STATE_SIZE, 0.0); + if (nhLocal_.getParam("initial_state", initialState)) + { + if (initialState.size() != STATE_SIZE) + { + ROS_ERROR_STREAM("Initial state must be of size " << STATE_SIZE << ". Provided config was of size " << + initialState.size() << ". The initial state will be ignored."); + } + else + { + Eigen::Map eigenState(initialState.data(), initialState.size()); + filter_.setState(eigenState); + } + } + + // Check if the filter should start or not + nhLocal_.param("disabled_at_startup", disabledAtStartup_, false); + enabled_ = !disabledAtStartup_; + + // Check if tf warnings should be suppressed + nh_.getParam("/silent_tf_failure", tfSilentFailure_); + + // Debugging writes to file + RF_DEBUG("tf_prefix is " << tfPrefix << + "\nmap_frame is " << mapFrameId_ << + "\nodom_frame is " << odomFrameId_ << + "\nbase_link_frame is " << baseLinkFrameId_ << + "\base_link_frame_output is " << baseLinkOutputFrameId_ << + "\nworld_frame is " << worldFrameId_ << + "\ntransform_time_offset is " << tfTimeOffset_.toSec() << + "\ntransform_timeout is " << tfTimeout_.toSec() << + "\nfrequency is " << frequency_ << + "\nsensor_timeout is " << filter_.getSensorTimeout() << + "\ntwo_d_mode is " << std::boolalpha << twoDMode_ << + "\nsmooth_lagged_data is " << std::boolalpha << smoothLaggedData_ << + "\nhistory_length is " << historyLength_ << + "\nuse_control is " << std::boolalpha << useControl_ << + "\nstamped_control is " << std::boolalpha << stampedControl << + "\ncontrol_config is " << controlUpdateVector << + "\ncontrol_timeout is " << controlTimeout << + "\nacceleration_limits are " << accelerationLimits << + "\nacceleration_gains are " << accelerationGains << + "\ndeceleration_limits are " << decelerationLimits << + "\ndeceleration_gains are " << decelerationGains << + "\ninitial state is " << filter_.getState() << + "\ndynamic_process_noise_covariance is " << std::boolalpha << dynamicProcessNoiseCovariance << + "\npermit_corrected_publication is " << std::boolalpha << permitCorrectedPublication_ << + "\nprint_diagnostics is " << std::boolalpha << printDiagnostics_ << + "\nsuppress tf warnings is " << std::boolalpha << tfSilentFailure_ << "\n" "\n"); + + // Create a subscriber for manually setting/resetting pose + setPoseSub_ = nh_.subscribe("set_pose", + 1, + &RosFilter::setPoseCallback, + this, ros::TransportHints().tcpNoDelay(false)); + + // Create a service for manually setting/resetting pose + setPoseSrv_ = nh_.advertiseService("set_pose", &RosFilter::setPoseSrvCallback, this); + + // Create a service for manually enabling the filter + enableFilterSrv_ = nhLocal_.advertiseService("enable", &RosFilter::enableFilterSrvCallback, this); + + // Create a service for toggling processing new measurements while still publishing + toggleFilterProcessingSrv_ = + nhLocal_.advertiseService("toggle", &RosFilter::toggleFilterProcessingCallback, this); + + // Init the last measurement time so we don't get a huge initial delta + filter_.setLastMeasurementTime(ros::Time::now().toSec()); + + // Now pull in each topic to which we want to subscribe. + // Start with odom. + size_t topicInd = 0; + bool moreParams = false; + do + { + // Build the string in the form of "odomX", where X is the odom topic number, + // then check if we have any parameters with that value. Users need to make + // sure they don't have gaps in their configs (e.g., odom0 and then odom2) + std::stringstream ss; + ss << "odom" << topicInd++; + std::string odomTopicName = ss.str(); + moreParams = nhLocal_.hasParam(odomTopicName); + + if (moreParams) + { + // Determine if we want to integrate this sensor differentially + bool differential; + nhLocal_.param(odomTopicName + std::string("_differential"), differential, false); + + // Determine if we want to integrate this sensor relatively + bool relative; + nhLocal_.param(odomTopicName + std::string("_relative"), relative, false); + + if (relative && differential) + { + ROS_WARN_STREAM("Both " << odomTopicName << "_differential" << " and " << odomTopicName << + "_relative were set to true. Using differential mode."); + + relative = false; + } + + // Consider odometry transformation from the child_frame_id instead of the base_link_frame_id + bool pose_use_child_frame; + nhLocal_.param(odomTopicName + std::string("_pose_use_child_frame"), pose_use_child_frame, false); + + std::string odomTopic; + nhLocal_.getParam(odomTopicName, odomTopic); + + // Check for pose rejection threshold + double poseMahalanobisThresh; + nhLocal_.param(odomTopicName + std::string("_pose_rejection_threshold"), + poseMahalanobisThresh, + std::numeric_limits::max()); + + // Check for twist rejection threshold + double twistMahalanobisThresh; + nhLocal_.param(odomTopicName + std::string("_twist_rejection_threshold"), + twistMahalanobisThresh, + std::numeric_limits::max()); + + // Now pull in its boolean update vector configuration. Create separate vectors for pose + // and twist data, and then zero out the opposite values in each vector (no pose data in + // the twist update vector and vice-versa). + std::vector updateVec = loadUpdateConfig(odomTopicName); + std::vector poseUpdateVec = updateVec; + std::fill(poseUpdateVec.begin() + POSITION_V_OFFSET, poseUpdateVec.begin() + POSITION_V_OFFSET + TWIST_SIZE, 0); + std::vector twistUpdateVec = updateVec; + std::fill(twistUpdateVec.begin() + POSITION_OFFSET, twistUpdateVec.begin() + POSITION_OFFSET + POSE_SIZE, 0); + + int poseUpdateSum = std::accumulate(poseUpdateVec.begin(), poseUpdateVec.end(), 0); + int twistUpdateSum = std::accumulate(twistUpdateVec.begin(), twistUpdateVec.end(), 0); + int odomQueueSize = 1; + nhLocal_.param(odomTopicName + "_queue_size", odomQueueSize, 1); + + const CallbackData poseCallbackData(odomTopicName + "_pose", poseUpdateVec, poseUpdateSum, differential, + relative, pose_use_child_frame, poseMahalanobisThresh); + const CallbackData twistCallbackData(odomTopicName + "_twist", twistUpdateVec, twistUpdateSum, false, false, + false, twistMahalanobisThresh); + + bool nodelayOdom = false; + nhLocal_.param(odomTopicName + "_nodelay", nodelayOdom, false); + + // Store the odometry topic subscribers so they don't go out of scope. + if (poseUpdateSum + twistUpdateSum > 0) + { + topicSubs_.push_back( + nh_.subscribe(odomTopic, odomQueueSize, + boost::bind(&RosFilter::odometryCallback, this, boost::placeholders::_1, + odomTopicName, poseCallbackData, twistCallbackData), + ros::VoidPtr(), ros::TransportHints().tcpNoDelay(nodelayOdom))); + } + else + { + std::stringstream stream; + stream << odomTopic << " is listed as an input topic, but all update variables are false"; + + addDiagnostic(diagnostic_msgs::DiagnosticStatus::WARN, + odomTopic + "_configuration", + stream.str(), + true); + } + + if (poseUpdateSum > 0) + { + if (differential) + { + twistVarCounts[StateMemberVx] += poseUpdateVec[StateMemberX]; + twistVarCounts[StateMemberVy] += poseUpdateVec[StateMemberY]; + twistVarCounts[StateMemberVz] += poseUpdateVec[StateMemberZ]; + twistVarCounts[StateMemberVroll] += poseUpdateVec[StateMemberRoll]; + twistVarCounts[StateMemberVpitch] += poseUpdateVec[StateMemberPitch]; + twistVarCounts[StateMemberVyaw] += poseUpdateVec[StateMemberYaw]; + } + else + { + absPoseVarCounts[StateMemberX] += poseUpdateVec[StateMemberX]; + absPoseVarCounts[StateMemberY] += poseUpdateVec[StateMemberY]; + absPoseVarCounts[StateMemberZ] += poseUpdateVec[StateMemberZ]; + absPoseVarCounts[StateMemberRoll] += poseUpdateVec[StateMemberRoll]; + absPoseVarCounts[StateMemberPitch] += poseUpdateVec[StateMemberPitch]; + absPoseVarCounts[StateMemberYaw] += poseUpdateVec[StateMemberYaw]; + } + } + + if (twistUpdateSum > 0) + { + twistVarCounts[StateMemberVx] += twistUpdateVec[StateMemberVx]; + twistVarCounts[StateMemberVy] += twistUpdateVec[StateMemberVx]; + twistVarCounts[StateMemberVz] += twistUpdateVec[StateMemberVz]; + twistVarCounts[StateMemberVroll] += twistUpdateVec[StateMemberVroll]; + twistVarCounts[StateMemberVpitch] += twistUpdateVec[StateMemberVpitch]; + twistVarCounts[StateMemberVyaw] += twistUpdateVec[StateMemberVyaw]; + } + + RF_DEBUG("Subscribed to " << odomTopic << " (" << odomTopicName << ")\n\t" << + odomTopicName << "_differential is " << (differential ? "true" : "false") << "\n\t" << + odomTopicName << "_pose_rejection_threshold is " << poseMahalanobisThresh << "\n\t" << + odomTopicName << "_twist_rejection_threshold is " << twistMahalanobisThresh << "\n\t" << + odomTopicName << "_queue_size is " << odomQueueSize << "\n\t" << + odomTopicName << " pose update vector is " << poseUpdateVec << "\t"<< + odomTopicName << " twist update vector is " << twistUpdateVec); + } + } + while (moreParams); + + // Repeat for pose + topicInd = 0; + moreParams = false; + do + { + std::stringstream ss; + ss << "pose" << topicInd++; + std::string poseTopicName = ss.str(); + moreParams = nhLocal_.hasParam(poseTopicName); + + if (moreParams) + { + bool differential; + nhLocal_.param(poseTopicName + std::string("_differential"), differential, false); + + // Determine if we want to integrate this sensor relatively + bool relative; + nhLocal_.param(poseTopicName + std::string("_relative"), relative, false); + + if (relative && differential) + { + ROS_WARN_STREAM("Both " << poseTopicName << "_differential" << " and " << poseTopicName << + "_relative were set to true. Using differential mode."); + + relative = false; + } + + std::string poseTopic; + nhLocal_.getParam(poseTopicName, poseTopic); + + // Check for pose rejection threshold + double poseMahalanobisThresh; + nhLocal_.param(poseTopicName + std::string("_rejection_threshold"), + poseMahalanobisThresh, + std::numeric_limits::max()); + + int poseQueueSize = 1; + nhLocal_.param(poseTopicName + "_queue_size", poseQueueSize, 1); + + bool nodelayPose = false; + nhLocal_.param(poseTopicName + "_nodelay", nodelayPose, false); + + // Pull in the sensor's config, zero out values that are invalid for the pose type + std::vector poseUpdateVec = loadUpdateConfig(poseTopicName); + std::fill(poseUpdateVec.begin() + POSITION_V_OFFSET, + poseUpdateVec.begin() + POSITION_V_OFFSET + TWIST_SIZE, + 0); + std::fill(poseUpdateVec.begin() + POSITION_A_OFFSET, + poseUpdateVec.begin() + POSITION_A_OFFSET + ACCELERATION_SIZE, + 0); + + int poseUpdateSum = std::accumulate(poseUpdateVec.begin(), poseUpdateVec.end(), 0); + + if (poseUpdateSum > 0) + { + const CallbackData callbackData(poseTopicName, poseUpdateVec, poseUpdateSum, differential, relative, + false, poseMahalanobisThresh); + + topicSubs_.push_back( + nh_.subscribe(poseTopic, poseQueueSize, + boost::bind(&RosFilter::poseCallback, this, boost::placeholders::_1, + callbackData, worldFrameId_, baseLinkFrameId_, false), + ros::VoidPtr(), ros::TransportHints().tcpNoDelay(nodelayPose))); + + if (differential) + { + twistVarCounts[StateMemberVx] += poseUpdateVec[StateMemberX]; + twistVarCounts[StateMemberVy] += poseUpdateVec[StateMemberY]; + twistVarCounts[StateMemberVz] += poseUpdateVec[StateMemberZ]; + twistVarCounts[StateMemberVroll] += poseUpdateVec[StateMemberRoll]; + twistVarCounts[StateMemberVpitch] += poseUpdateVec[StateMemberPitch]; + twistVarCounts[StateMemberVyaw] += poseUpdateVec[StateMemberYaw]; + } + else + { + absPoseVarCounts[StateMemberX] += poseUpdateVec[StateMemberX]; + absPoseVarCounts[StateMemberY] += poseUpdateVec[StateMemberY]; + absPoseVarCounts[StateMemberZ] += poseUpdateVec[StateMemberZ]; + absPoseVarCounts[StateMemberRoll] += poseUpdateVec[StateMemberRoll]; + absPoseVarCounts[StateMemberPitch] += poseUpdateVec[StateMemberPitch]; + absPoseVarCounts[StateMemberYaw] += poseUpdateVec[StateMemberYaw]; + } + } + else + { + ROS_WARN_STREAM("Warning: " << poseTopic << " is listed as an input topic, " + "but all pose update variables are false"); + } + + RF_DEBUG("Subscribed to " << poseTopic << " (" << poseTopicName << ")\n\t" << + poseTopicName << "_differential is " << (differential ? "true" : "false") << "\n\t" << + poseTopicName << "_rejection_threshold is " << poseMahalanobisThresh << "\n\t" << + poseTopicName << "_queue_size is " << poseQueueSize << "\n\t" << + poseTopicName << " update vector is " << poseUpdateVec); + } + } + while (moreParams); + + // Repeat for twist + topicInd = 0; + moreParams = false; + do + { + std::stringstream ss; + ss << "twist" << topicInd++; + std::string twistTopicName = ss.str(); + moreParams = nhLocal_.hasParam(twistTopicName); + + if (moreParams) + { + std::string twistTopic; + nhLocal_.getParam(twistTopicName, twistTopic); + + // Check for twist rejection threshold + double twistMahalanobisThresh; + nhLocal_.param(twistTopicName + std::string("_rejection_threshold"), + twistMahalanobisThresh, + std::numeric_limits::max()); + + int twistQueueSize = 1; + nhLocal_.param(twistTopicName + "_queue_size", twistQueueSize, 1); + + bool nodelayTwist = false; + nhLocal_.param(twistTopicName + "_nodelay", nodelayTwist, false); + + // Pull in the sensor's config, zero out values that are invalid for the twist type + std::vector twistUpdateVec = loadUpdateConfig(twistTopicName); + std::fill(twistUpdateVec.begin() + POSITION_OFFSET, twistUpdateVec.begin() + POSITION_OFFSET + POSE_SIZE, 0); + + int twistUpdateSum = std::accumulate(twistUpdateVec.begin(), twistUpdateVec.end(), 0); + + if (twistUpdateSum > 0) + { + const CallbackData callbackData(twistTopicName, twistUpdateVec, twistUpdateSum, false, false, + false, twistMahalanobisThresh); + + topicSubs_.push_back( + nh_.subscribe(twistTopic, twistQueueSize, + boost::bind(&RosFilter::twistCallback, this, boost::placeholders::_1, + callbackData, baseLinkFrameId_), + ros::VoidPtr(), ros::TransportHints().tcpNoDelay(nodelayTwist))); + + twistVarCounts[StateMemberVx] += twistUpdateVec[StateMemberVx]; + twistVarCounts[StateMemberVy] += twistUpdateVec[StateMemberVy]; + twistVarCounts[StateMemberVz] += twistUpdateVec[StateMemberVz]; + twistVarCounts[StateMemberVroll] += twistUpdateVec[StateMemberVroll]; + twistVarCounts[StateMemberVpitch] += twistUpdateVec[StateMemberVpitch]; + twistVarCounts[StateMemberVyaw] += twistUpdateVec[StateMemberVyaw]; + } + else + { + ROS_WARN_STREAM("Warning: " << twistTopic << " is listed as an input topic, " + "but all twist update variables are false"); + } + + RF_DEBUG("Subscribed to " << twistTopic << " (" << twistTopicName << ")\n\t" << + twistTopicName << "_rejection_threshold is " << twistMahalanobisThresh << "\n\t" << + twistTopicName << "_queue_size is " << twistQueueSize << "\n\t" << + twistTopicName << " update vector is " << twistUpdateVec); + } + } + while (moreParams); + + // Repeat for IMU + topicInd = 0; + moreParams = false; + do + { + std::stringstream ss; + ss << "imu" << topicInd++; + std::string imuTopicName = ss.str(); + moreParams = nhLocal_.hasParam(imuTopicName); + + if (moreParams) + { + bool differential; + nhLocal_.param(imuTopicName + std::string("_differential"), differential, false); + + // Determine if we want to integrate this sensor relatively + bool relative; + nhLocal_.param(imuTopicName + std::string("_relative"), relative, false); + + if (relative && differential) + { + ROS_WARN_STREAM("Both " << imuTopicName << "_differential" << " and " << imuTopicName << + "_relative were set to true. Using differential mode."); + + relative = false; + } + + std::string imuTopic; + nhLocal_.getParam(imuTopicName, imuTopic); + + // Check for pose rejection threshold + double poseMahalanobisThresh; + nhLocal_.param(imuTopicName + std::string("_pose_rejection_threshold"), + poseMahalanobisThresh, + std::numeric_limits::max()); + + // Check for angular velocity rejection threshold + double twistMahalanobisThresh; + std::string imuTwistRejectionName = + imuTopicName + std::string("_twist_rejection_threshold"); + nhLocal_.param(imuTwistRejectionName, twistMahalanobisThresh, std::numeric_limits::max()); + + // Check for acceleration rejection threshold + double accelMahalanobisThresh; + nhLocal_.param(imuTopicName + std::string("_linear_acceleration_rejection_threshold"), + accelMahalanobisThresh, + std::numeric_limits::max()); + + bool removeGravAcc = false; + nhLocal_.param(imuTopicName + "_remove_gravitational_acceleration", removeGravAcc, false); + removeGravitationalAcc_[imuTopicName + "_acceleration"] = removeGravAcc; + + // Now pull in its boolean update vector configuration and differential + // update configuration (as this contains pose information) + std::vector updateVec = loadUpdateConfig(imuTopicName); + + // sanity checks for update config settings + std::vector positionUpdateVec(updateVec.begin() + POSITION_OFFSET, + updateVec.begin() + POSITION_OFFSET + POSITION_SIZE); + int positionUpdateSum = std::accumulate(positionUpdateVec.begin(), positionUpdateVec.end(), 0); + if (positionUpdateSum > 0) + { + ROS_WARN_STREAM("Warning: Some position entries in parameter " << imuTopicName << "_config are listed true, " + "but sensor_msgs/Imu contains no information about position"); + } + std::vector linearVelocityUpdateVec(updateVec.begin() + POSITION_V_OFFSET, + updateVec.begin() + POSITION_V_OFFSET + LINEAR_VELOCITY_SIZE); + int linearVelocityUpdateSum = std::accumulate(linearVelocityUpdateVec.begin(), + linearVelocityUpdateVec.end(), + 0); + if (linearVelocityUpdateSum > 0) + { + ROS_WARN_STREAM("Warning: Some linear velocity entries in parameter " << imuTopicName << "_config are listed " + "true, but an sensor_msgs/Imu contains no information about linear velocities"); + } + + std::vector poseUpdateVec = updateVec; + // IMU message contains no information about position, filter everything except orientation + std::fill(poseUpdateVec.begin() + POSITION_OFFSET, + poseUpdateVec.begin() + POSITION_OFFSET + POSITION_SIZE, + 0); + std::fill(poseUpdateVec.begin() + POSITION_V_OFFSET, + poseUpdateVec.begin() + POSITION_V_OFFSET + TWIST_SIZE, + 0); + std::fill(poseUpdateVec.begin() + POSITION_A_OFFSET, + poseUpdateVec.begin() + POSITION_A_OFFSET + ACCELERATION_SIZE, + 0); + + std::vector twistUpdateVec = updateVec; + // IMU message contains no information about linear speeds, filter everything except angular velocity + std::fill(twistUpdateVec.begin() + POSITION_OFFSET, + twistUpdateVec.begin() + POSITION_OFFSET + POSE_SIZE, + 0); + std::fill(twistUpdateVec.begin() + POSITION_V_OFFSET, + twistUpdateVec.begin() + POSITION_V_OFFSET + LINEAR_VELOCITY_SIZE, + 0); + std::fill(twistUpdateVec.begin() + POSITION_A_OFFSET, + twistUpdateVec.begin() + POSITION_A_OFFSET + ACCELERATION_SIZE, + 0); + + std::vector accelUpdateVec = updateVec; + std::fill(accelUpdateVec.begin() + POSITION_OFFSET, + accelUpdateVec.begin() + POSITION_OFFSET + POSE_SIZE, + 0); + std::fill(accelUpdateVec.begin() + POSITION_V_OFFSET, + accelUpdateVec.begin() + POSITION_V_OFFSET + TWIST_SIZE, + 0); + + int poseUpdateSum = std::accumulate(poseUpdateVec.begin(), poseUpdateVec.end(), 0); + int twistUpdateSum = std::accumulate(twistUpdateVec.begin(), twistUpdateVec.end(), 0); + int accelUpdateSum = std::accumulate(accelUpdateVec.begin(), accelUpdateVec.end(), 0); + + // Check if we're using control input for any of the acceleration variables; turn off if so + if (static_cast(controlUpdateVector[ControlMemberVx]) && static_cast(accelUpdateVec[StateMemberAx])) + { + ROS_WARN_STREAM("X acceleration is being measured from IMU; X velocity control input is disabled"); + controlUpdateVector[ControlMemberVx] = 0; + } + if (static_cast(controlUpdateVector[ControlMemberVy]) && static_cast(accelUpdateVec[StateMemberAy])) + { + ROS_WARN_STREAM("Y acceleration is being measured from IMU; Y velocity control input is disabled"); + controlUpdateVector[ControlMemberVy] = 0; + } + if (static_cast(controlUpdateVector[ControlMemberVz]) && static_cast(accelUpdateVec[StateMemberAz])) + { + ROS_WARN_STREAM("Z acceleration is being measured from IMU; Z velocity control input is disabled"); + controlUpdateVector[ControlMemberVz] = 0; + } + + int imuQueueSize = 1; + nhLocal_.param(imuTopicName + "_queue_size", imuQueueSize, 1); + + bool nodelayImu = false; + nhLocal_.param(imuTopicName + "_nodelay", nodelayImu, false); + + if (poseUpdateSum + twistUpdateSum + accelUpdateSum > 0) + { + const CallbackData poseCallbackData(imuTopicName + "_pose", poseUpdateVec, poseUpdateSum, differential, + relative, false, poseMahalanobisThresh); + const CallbackData twistCallbackData(imuTopicName + "_twist", twistUpdateVec, twistUpdateSum, differential, + relative, false, twistMahalanobisThresh); + const CallbackData accelCallbackData(imuTopicName + "_acceleration", accelUpdateVec, accelUpdateSum, + differential, relative, false, accelMahalanobisThresh); + + topicSubs_.push_back( + nh_.subscribe(imuTopic, imuQueueSize, + boost::bind(&RosFilter::imuCallback, this, boost::placeholders::_1, + imuTopicName, poseCallbackData, twistCallbackData, + accelCallbackData), ros::VoidPtr(), ros::TransportHints().tcpNoDelay(nodelayImu))); + } + else + { + ROS_WARN_STREAM("Warning: " << imuTopic << " is listed as an input topic, " + "but all its update variables are false"); + } + + if (poseUpdateSum > 0) + { + if (differential) + { + twistVarCounts[StateMemberVroll] += poseUpdateVec[StateMemberRoll]; + twistVarCounts[StateMemberVpitch] += poseUpdateVec[StateMemberPitch]; + twistVarCounts[StateMemberVyaw] += poseUpdateVec[StateMemberYaw]; + } + else + { + absPoseVarCounts[StateMemberRoll] += poseUpdateVec[StateMemberRoll]; + absPoseVarCounts[StateMemberPitch] += poseUpdateVec[StateMemberPitch]; + absPoseVarCounts[StateMemberYaw] += poseUpdateVec[StateMemberYaw]; + } + } + + if (twistUpdateSum > 0) + { + twistVarCounts[StateMemberVroll] += twistUpdateVec[StateMemberVroll]; + twistVarCounts[StateMemberVpitch] += twistUpdateVec[StateMemberVpitch]; + twistVarCounts[StateMemberVyaw] += twistUpdateVec[StateMemberVyaw]; + } + + RF_DEBUG("Subscribed to " << imuTopic << " (" << imuTopicName << ")\n\t" << + imuTopicName << "_differential is " << (differential ? "true" : "false") << "\n\t" << + imuTopicName << "_pose_rejection_threshold is " << poseMahalanobisThresh << "\n\t" << + imuTopicName << "_twist_rejection_threshold is " << twistMahalanobisThresh << "\n\t" << + imuTopicName << "_linear_acceleration_rejection_threshold is " << accelMahalanobisThresh << "\n\t" << + imuTopicName << "_remove_gravitational_acceleration is " << + (removeGravAcc ? "true" : "false") << "\n\t" << + imuTopicName << "_queue_size is " << imuQueueSize << "\n\t" << + imuTopicName << " pose update vector is " << poseUpdateVec << "\t"<< + imuTopicName << " twist update vector is " << twistUpdateVec << "\t" << + imuTopicName << " acceleration update vector is " << accelUpdateVec); + } + } + while (moreParams); + angular_acceleration_cov_.resize(ORIENTATION_SIZE, ORIENTATION_SIZE); + angular_acceleration_cov_.setZero(); + + // Now that we've checked if IMU linear acceleration is being used, we can determine our final control parameters + if (useControl_ && std::accumulate(controlUpdateVector.begin(), controlUpdateVector.end(), 0) == 0) + { + ROS_ERROR_STREAM("use_control is set to true, but control_config has only false values. No control term " + "will be used."); + useControl_ = false; + } + + // If we're using control, set the parameters and create the necessary subscribers + if (useControl_) + { + latestControl_.resize(TWIST_SIZE); + latestControl_.setZero(); + + filter_.setControlParams(controlUpdateVector, controlTimeout, accelerationLimits, accelerationGains, + decelerationLimits, decelerationGains); + + if (stampedControl) + { + controlSub_ = nh_.subscribe("cmd_vel", 1, &RosFilter::controlCallback, this); + } + else + { + controlSub_ = nh_.subscribe("cmd_vel", 1, &RosFilter::controlCallback, this); + } + } + + /* Warn users about: + * 1. Multiple non-differential input sources + * 2. No absolute *or* velocity measurements for pose variables + */ + if (printDiagnostics_) + { + for (int stateVar = StateMemberX; stateVar <= StateMemberYaw; ++stateVar) + { + if (absPoseVarCounts[static_cast(stateVar)] > 1) + { + std::stringstream stream; + stream << absPoseVarCounts[static_cast(stateVar - POSITION_OFFSET)] << + " absolute pose inputs detected for " << stateVariableNames_[stateVar] << + ". This may result in oscillations. Please ensure that your variances for each " + "measured variable are set appropriately."; + + addDiagnostic(diagnostic_msgs::DiagnosticStatus::WARN, + stateVariableNames_[stateVar] + "_configuration", + stream.str(), + true); + } + else if (absPoseVarCounts[static_cast(stateVar)] == 0) + { + if ((static_cast(stateVar) == StateMemberX && + twistVarCounts[static_cast(StateMemberVx)] == 0) || + (static_cast(stateVar) == StateMemberY && + twistVarCounts[static_cast(StateMemberVy)] == 0) || + (static_cast(stateVar) == StateMemberZ && + twistVarCounts[static_cast(StateMemberVz)] == 0 && + twoDMode_ == false) || + (static_cast(stateVar) == StateMemberRoll && + twistVarCounts[static_cast(StateMemberVroll)] == 0 && + twoDMode_ == false) || + (static_cast(stateVar) == StateMemberPitch && + twistVarCounts[static_cast(StateMemberVpitch)] == 0 && + twoDMode_ == false) || + (static_cast(stateVar) == StateMemberYaw && + twistVarCounts[static_cast(StateMemberVyaw)] == 0)) + { + std::stringstream stream; + stream << "Neither " << stateVariableNames_[stateVar] << " nor its " + "velocity is being measured. This will result in unbounded " + "error growth and erratic filter behavior."; + + addDiagnostic(diagnostic_msgs::DiagnosticStatus::ERROR, + stateVariableNames_[stateVar] + "_configuration", + stream.str(), + true); + } + } + } + } + + // Load up the process noise covariance (from the launch file/parameter server) + Eigen::MatrixXd processNoiseCovariance(STATE_SIZE, STATE_SIZE); + processNoiseCovariance.setZero(); + XmlRpc::XmlRpcValue processNoiseCovarConfig; + + if (nhLocal_.hasParam("process_noise_covariance")) + { + try + { + nhLocal_.getParam("process_noise_covariance", processNoiseCovarConfig); + + ROS_ASSERT(processNoiseCovarConfig.getType() == XmlRpc::XmlRpcValue::TypeArray); + + int matSize = processNoiseCovariance.rows(); + + for (int i = 0; i < matSize; i++) + { + for (int j = 0; j < matSize; j++) + { + try + { + // These matrices can cause problems if all the types + // aren't specified with decimal points. Handle that + // using string streams. + std::ostringstream ostr; + ostr << processNoiseCovarConfig[matSize * i + j]; + std::istringstream istr(ostr.str()); + istr >> processNoiseCovariance(i, j); + } + catch(XmlRpc::XmlRpcException &e) + { + throw e; + } + catch(...) + { + throw; + } + } + } + + RF_DEBUG("Process noise covariance is:\n" << processNoiseCovariance << "\n"); + } + catch (XmlRpc::XmlRpcException &e) + { + ROS_ERROR_STREAM("ERROR reading sensor config: " << + e.getMessage() << + " for process_noise_covariance (type: " << + processNoiseCovarConfig.getType() << ")"); + } + + filter_.setProcessNoiseCovariance(processNoiseCovariance); + } + + // Load up the process noise covariance (from the launch file/parameter server) + Eigen::MatrixXd initialEstimateErrorCovariance(STATE_SIZE, STATE_SIZE); + initialEstimateErrorCovariance.setZero(); + XmlRpc::XmlRpcValue estimateErrorCovarConfig; + + if (nhLocal_.hasParam("initial_estimate_covariance")) + { + try + { + nhLocal_.getParam("initial_estimate_covariance", estimateErrorCovarConfig); + + ROS_ASSERT(estimateErrorCovarConfig.getType() == XmlRpc::XmlRpcValue::TypeArray); + + int matSize = initialEstimateErrorCovariance.rows(); + + for (int i = 0; i < matSize; i++) + { + for (int j = 0; j < matSize; j++) + { + try + { + // These matrices can cause problems if all the types + // aren't specified with decimal points. Handle that + // using string streams. + std::ostringstream ostr; + ostr << estimateErrorCovarConfig[matSize * i + j]; + std::istringstream istr(ostr.str()); + istr >> initialEstimateErrorCovariance(i, j); + } + catch(XmlRpc::XmlRpcException &e) + { + throw e; + } + catch(...) + { + throw; + } + } + } + + RF_DEBUG("Initial estimate error covariance is:\n" << initialEstimateErrorCovariance << "\n"); + } + catch (XmlRpc::XmlRpcException &e) + { + ROS_ERROR_STREAM("ERROR reading initial_estimate_covariance (type: " << + estimateErrorCovarConfig.getType() << + "): " << + e.getMessage()); + } + catch(...) + { + ROS_ERROR_STREAM( + "ERROR reading initial_estimate_covariance (type: " << estimateErrorCovarConfig.getType() << ")"); + } + + filter_.setEstimateErrorCovariance(initialEstimateErrorCovariance); + } + } + + template + void RosFilter::odometryCallback(const nav_msgs::Odometry::ConstPtr &msg, const std::string &topicName, + const CallbackData &poseCallbackData, const CallbackData &twistCallbackData) + { + // If we've just reset the filter, then we want to ignore any messages + // that arrive with an older timestamp + if (msg->header.stamp <= lastSetPoseTime_) + { + std::stringstream stream; + stream << "The " << topicName << " message has a timestamp equal to or before the last filter reset, " << + "this message will be ignored. This may indicate an empty or bad timestamp. (message time: " << + msg->header.stamp.toSec() << ")"; + addDiagnostic(diagnostic_msgs::DiagnosticStatus::WARN, + topicName + "_timestamp", + stream.str(), + false); + RF_DEBUG("Received message that preceded the most recent pose reset. Ignoring..."); + + return; + } + + RF_DEBUG("------ RosFilter::odometryCallback (" << topicName << ") ------\n" << "Odometry message:\n" << *msg); + + if (poseCallbackData.updateSum_ > 0) + { + // Grab the pose portion of the message and pass it to the poseCallback + geometry_msgs::PoseWithCovarianceStamped *posPtr = new geometry_msgs::PoseWithCovarianceStamped(); + posPtr->header = msg->header; + posPtr->pose = msg->pose; // Entire pose object, also copies covariance + + geometry_msgs::PoseWithCovarianceStampedConstPtr pptr(posPtr); + if (poseCallbackData.pose_use_child_frame_) + { + poseCallback(pptr, poseCallbackData, worldFrameId_, msg->child_frame_id, false); + } + else + { + poseCallback(pptr, poseCallbackData, worldFrameId_, baseLinkFrameId_, false); + } + } + + if (twistCallbackData.updateSum_ > 0) + { + // Grab the twist portion of the message and pass it to the twistCallback + geometry_msgs::TwistWithCovarianceStamped *twistPtr = new geometry_msgs::TwistWithCovarianceStamped(); + twistPtr->header = msg->header; + twistPtr->header.frame_id = msg->child_frame_id; + twistPtr->twist = msg->twist; // Entire twist object, also copies covariance + + geometry_msgs::TwistWithCovarianceStampedConstPtr tptr(twistPtr); + twistCallback(tptr, twistCallbackData, baseLinkFrameId_); + } + + RF_DEBUG("\n----- /RosFilter::odometryCallback (" << topicName << ") ------\n"); + } + + template + void RosFilter::poseCallback(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &msg, + const CallbackData &callbackData, + const std::string &targetFrame, + const std::string &poseSourceFrame, + const bool imuData) + { + const std::string &topicName = callbackData.topicName_; + + // If we've just reset the filter, then we want to ignore any messages + // that arrive with an older timestamp + if (msg->header.stamp <= lastSetPoseTime_) + { + std::stringstream stream; + stream << "The " << topicName << " message has a timestamp equal to or before the last filter reset, " << + "this message will be ignored. This may indicate an empty or bad timestamp. (message time: " << + msg->header.stamp.toSec() << ")"; + addDiagnostic(diagnostic_msgs::DiagnosticStatus::WARN, + topicName + "_timestamp", + stream.str(), + false); + return; + } + + RF_DEBUG("------ RosFilter::poseCallback (" << topicName << ") ------\n" << + "Pose message:\n" << *msg); + + // Put the initial value in the lastMessagTimes_ for this variable if it's empty + if (lastMessageTimes_.count(topicName) == 0) + { + lastMessageTimes_.insert(std::pair(topicName, msg->header.stamp)); + } + + // Make sure this message is newer than the last one + if (msg->header.stamp >= lastMessageTimes_[topicName]) + { + RF_DEBUG("Update vector for " << topicName << " is:\n" << callbackData.updateVector_); + + Eigen::VectorXd measurement(STATE_SIZE); + Eigen::MatrixXd measurementCovariance(STATE_SIZE, STATE_SIZE); + + measurement.setZero(); + measurementCovariance.setZero(); + + // Make sure we're actually updating at least one of these variables + std::vector updateVectorCorrected = callbackData.updateVector_; + + // Prepare the pose data for inclusion in the filter + if (preparePose(msg, + topicName, + targetFrame, + poseSourceFrame, + callbackData.differential_, + callbackData.relative_, + imuData, + updateVectorCorrected, + measurement, + measurementCovariance)) + { + // Store the measurement. Add a "pose" suffix so we know what kind of measurement + // we're dealing with when we debug the core filter logic. + enqueueMeasurement(topicName, + measurement, + measurementCovariance, + updateVectorCorrected, + callbackData.rejectionThreshold_, + msg->header.stamp); + + RF_DEBUG("Enqueued new measurement for " << topicName << "\n"); + } + else + { + RF_DEBUG("Did *not* enqueue measurement for " << topicName << "\n"); + } + + lastMessageTimes_[topicName] = msg->header.stamp; + + RF_DEBUG("Last message time for " << topicName << " is now " << + lastMessageTimes_[topicName] << "\n"); + } + else if (resetOnTimeJump_ && ros::Time::isSimTime()) + { + reset(); + } + else + { + std::stringstream stream; + stream << "The " << topicName << " message has a timestamp before that of the previous message received," << + " this message will be ignored. This may indicate a bad timestamp. (message time: " << + msg->header.stamp.toSec() << ")"; + addDiagnostic(diagnostic_msgs::DiagnosticStatus::WARN, + topicName + "_timestamp", + stream.str(), + false); + + RF_DEBUG("Message is too old. Last message time for " << topicName << " is " + << lastMessageTimes_[topicName] << ", current message time is " + << msg->header.stamp << ".\n"); + } + + RF_DEBUG("\n----- /RosFilter::poseCallback (" << topicName << ") ------\n"); + } + + template + void RosFilter::periodicUpdate(const ros::TimerEvent& event) + { + // Warn the user if the update took too long (> 2 cycles) + const double loop_elapsed = (event.current_real - event.last_expected).toSec(); + if (loop_elapsed > 2./frequency_) + { + ROS_WARN_STREAM("Failed to meet update rate! Took " << std::setprecision(20) << loop_elapsed); + } + + // Wait for the filter to be enabled + if (!enabled_) + { + ROS_INFO_STREAM_ONCE("Filter is disabled. To enable it call the " << enableFilterSrv_.getService() << + " service"); + return; + } + + ros::Time curTime = ros::Time::now(); + + if (toggledOn_) + { + // Now we'll integrate any measurements we've received if requested, and update angular acceleration. + integrateMeasurements(curTime); + differentiateMeasurements(curTime); + } + else + { + // clear out measurements since we're not currently processing new entries + clearMeasurementQueue(); + + // Reset last measurement time so we don't get a large time delta on toggle on + if (filter_.getInitializedStatus()) + { + filter_.setLastMeasurementTime(ros::Time::now().toSec()); + } + } + + // Get latest state and publish it + nav_msgs::Odometry filteredPosition; + + bool corrected_data = false; + + if (getFilteredOdometryMessage(filteredPosition)) + { + worldBaseLinkTransMsg_.transform = tf2::toMsg(tf2::Transform::getIdentity()); + worldBaseLinkTransMsg_.header.stamp = filteredPosition.header.stamp + tfTimeOffset_; + worldBaseLinkTransMsg_.header.frame_id = filteredPosition.header.frame_id; + worldBaseLinkTransMsg_.child_frame_id = filteredPosition.child_frame_id; + + worldBaseLinkTransMsg_.transform.translation.x = filteredPosition.pose.pose.position.x; + worldBaseLinkTransMsg_.transform.translation.y = filteredPosition.pose.pose.position.y; + worldBaseLinkTransMsg_.transform.translation.z = filteredPosition.pose.pose.position.z; + worldBaseLinkTransMsg_.transform.rotation = filteredPosition.pose.pose.orientation; + + // the filteredPosition is the message containing the state and covariances: nav_msgs Odometry + + if (!validateFilterOutput(filteredPosition)) + { + ROS_ERROR_STREAM("Critical Error, NaNs were detected in the output state of the filter." << + " This was likely due to poorly conditioned process, noise, or sensor covariances."); + } + + // If we're trying to publish with the same time stamp, it means that we had a measurement get inserted into the + // filter history, and our state estimate was updated after it was already published. As of ROS Noetic, TF2 will + // issue warnings whenever this occurs, so we make this behavior optional. + // Just for safety, we also check for the condition where the last published stamp is *later* than this stamp. + // This should never happen, but we should handle the case anyway. + corrected_data = (!permitCorrectedPublication_ && lastPublishedStamp_ >= filteredPosition.header.stamp); + + // If the worldFrameId_ is the odomFrameId_ frame, then we can just send the transform. If the + // worldFrameId_ is the mapFrameId_ frame, we'll have some work to do. + if (publishTransform_ && !corrected_data) + { + if (filteredPosition.header.frame_id == odomFrameId_) + { + worldTransformBroadcaster_.sendTransform(worldBaseLinkTransMsg_); + } + else if (filteredPosition.header.frame_id == mapFrameId_) + { + /* + * First, see these two references: + * http://wiki.ros.org/tf/Overview/Using%20Published%20Transforms#lookupTransform + * http://wiki.ros.org/geometry/CoordinateFrameConventions#Transform_Direction + * We have a transform from mapFrameId_->baseLinkFrameId_, but it would actually transform + * a given pose from baseLinkFrameId_->mapFrameId_. We then used lookupTransform, whose + * first two arguments are target frame and source frame, to get a transform from + * baseLinkFrameId_->odomFrameId_. However, this transform would actually transform data + * from odomFrameId_->baseLinkFrameId_. Now imagine that we have a position in the + * mapFrameId_ frame. First, we multiply it by the inverse of the + * mapFrameId_->baseLinkFrameId, which will transform that data from mapFrameId_ to + * baseLinkFrameId_. Now we want to go from baseLinkFrameId_->odomFrameId_, but the + * transform we have takes data from odomFrameId_->baseLinkFrameId_, so we need its + * inverse as well. We have now transformed our data from mapFrameId_ to odomFrameId_. + * However, if we want other users to be able to do the same, we need to broadcast + * the inverse of that entire transform. + */ + + tf2::Transform baseLinkOdomTrans; + if (RosFilterUtilities::lookupTransformSafe( + tfBuffer_, + baseLinkFrameId_, + odomFrameId_, + filteredPosition.header.stamp, + tfTimeout_, + baseLinkOdomTrans, + tfSilentFailure_)) + { + tf2::Transform worldBaseLinkTrans; + tf2::fromMsg(worldBaseLinkTransMsg_.transform, worldBaseLinkTrans); + + tf2::Transform mapOdomTrans; + mapOdomTrans.mult(worldBaseLinkTrans, baseLinkOdomTrans); + + geometry_msgs::TransformStamped mapOdomTransMsg; + mapOdomTransMsg.transform = tf2::toMsg(mapOdomTrans); + mapOdomTransMsg.header.stamp = filteredPosition.header.stamp + tfTimeOffset_; + mapOdomTransMsg.header.frame_id = mapFrameId_; + mapOdomTransMsg.child_frame_id = odomFrameId_; + + worldTransformBroadcaster_.sendTransform(mapOdomTransMsg); + } + else + { + ROS_ERROR_STREAM_DELAYED_THROTTLE(5.0, "Could not obtain transform from " << odomFrameId_ << + "->" << baseLinkFrameId_); + } + } + else + { + ROS_ERROR_STREAM("Odometry message frame_id was " << filteredPosition.header.frame_id << + ", expected " << mapFrameId_ << " or " << odomFrameId_); + } + } + + // Fire off the position and the transform + if (!corrected_data) + { + positionPub_.publish(filteredPosition); + } + + // Retain the last published stamp so we can detect repeated transforms in future cycles + lastPublishedStamp_ = filteredPosition.header.stamp; + + if (printDiagnostics_) + { + freqDiag_->tick(); + } + } + + // Publish the acceleration if desired and filter is initialized + geometry_msgs::AccelWithCovarianceStamped filteredAcceleration; + if (publishAcceleration_ && getFilteredAccelMessage(filteredAcceleration) && !corrected_data) + { + accelPub_.publish(filteredAcceleration); + } + + /* Diagnostics can behave strangely when playing back from bag + * files and using simulated time, so we have to check for + * time suddenly moving backwards as well as the standard + * timeout criterion before publishing. */ + double diagDuration = (curTime - lastDiagTime_).toSec(); + if (printDiagnostics_ && (diagDuration >= diagnosticUpdater_.getPeriod() || diagDuration < 0.0)) + { + diagnosticUpdater_.force_update(); + lastDiagTime_ = curTime; + } + + // Clear out expired history data + if (smoothLaggedData_) + { + clearExpiredHistory(filter_.getLastMeasurementTime() - historyLength_); + } + } + + template + void RosFilter::setPoseCallback(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &msg) + { + RF_DEBUG("------ RosFilter::setPoseCallback ------\nPose message:\n" << *msg); + + ROS_INFO_STREAM("Received set_pose request with value\n" << *msg); + + std::string topicName("setPose"); + + // Get rid of any initial poses (pretend we've never had a measurement) + initialMeasurements_.clear(); + previousMeasurements_.clear(); + previousMeasurementCovariances_.clear(); + + clearMeasurementQueue(); + + filterStateHistory_.clear(); + measurementHistory_.clear(); + + // Also set the last set pose time, so we ignore all messages + // that occur before it + lastSetPoseTime_ = msg->header.stamp; + + // Set the state vector to the reported pose + Eigen::VectorXd measurement(STATE_SIZE); + Eigen::MatrixXd measurementCovariance(STATE_SIZE, STATE_SIZE); + std::vector updateVector(STATE_SIZE, true); + + // We only measure pose variables, so initialize the vector to 0 + measurement.setZero(); + + // Set this to the identity and let the message reset it + measurementCovariance.setIdentity(); + measurementCovariance *= 1e-6; + + // Prepare the pose data (really just using this to transform it into the target frame). + // Twist data is going to get zeroed out. + // Since pose messages do not provide a child_frame_id, it defaults to baseLinkFrameId_ + preparePose(msg, topicName, worldFrameId_, baseLinkFrameId_, false, false, + false, updateVector, measurement, measurementCovariance); + + // For the state + filter_.setState(measurement); + filter_.setEstimateErrorCovariance(measurementCovariance); + + filter_.setLastMeasurementTime(ros::Time::now().toSec()); + + RF_DEBUG("\n------ /RosFilter::setPoseCallback ------\n"); + } + + template + bool RosFilter::setPoseSrvCallback(robot_localization::SetPose::Request& request, + robot_localization::SetPose::Response&) + { + geometry_msgs::PoseWithCovarianceStamped::Ptr msg; + msg = boost::make_shared(request.pose); + setPoseCallback(msg); + + return true; + } + + template + bool RosFilter::enableFilterSrvCallback(std_srvs::Empty::Request&, + std_srvs::Empty::Response&) + { + RF_DEBUG("\n[" << ros::this_node::getName() << ":]" << " ------ /RosFilter::enableFilterSrvCallback ------\n"); + if (enabled_) + { + ROS_WARN_STREAM("[" << ros::this_node::getName() << ":] Asking for enabling filter service, but the filter was " + "already enabled! Use param disabled_at_startup."); + } + else + { + ROS_INFO_STREAM("[" << ros::this_node::getName() << ":] Enabling filter..."); + enabled_ = true; + } + return true; + } + + template + void RosFilter::twistCallback(const geometry_msgs::TwistWithCovarianceStamped::ConstPtr &msg, + const CallbackData &callbackData, + const std::string &targetFrame) + { + const std::string &topicName = callbackData.topicName_; + + // If we've just reset the filter, then we want to ignore any messages + // that arrive with an older timestamp + if (msg->header.stamp <= lastSetPoseTime_) + { + std::stringstream stream; + stream << "The " << topicName << " message has a timestamp equal to or before the last filter reset, " << + "this message will be ignored. This may indicate an empty or bad timestamp. (message time: " << + msg->header.stamp.toSec() << ")"; + addDiagnostic(diagnostic_msgs::DiagnosticStatus::WARN, + topicName + "_timestamp", + stream.str(), + false); + return; + } + + RF_DEBUG("------ RosFilter::twistCallback (" << topicName << ") ------\n" + "Twist message:\n" << *msg); + + if (lastMessageTimes_.count(topicName) == 0) + { + lastMessageTimes_.insert(std::pair(topicName, msg->header.stamp)); + } + + // Make sure this message is newer than the last one + if (msg->header.stamp >= lastMessageTimes_[topicName]) + { + RF_DEBUG("Update vector for " << topicName << " is:\n" << callbackData.updateVector_); + + Eigen::VectorXd measurement(STATE_SIZE); + Eigen::MatrixXd measurementCovariance(STATE_SIZE, STATE_SIZE); + + measurement.setZero(); + measurementCovariance.setZero(); + + // Make sure we're actually updating at least one of these variables + std::vector updateVectorCorrected = callbackData.updateVector_; + + // Prepare the twist data for inclusion in the filter + if (prepareTwist(msg, topicName, targetFrame, updateVectorCorrected, measurement, measurementCovariance)) + { + // Store the measurement. Add a "twist" suffix so we know what kind of measurement + // we're dealing with when we debug the core filter logic. + enqueueMeasurement(topicName, + measurement, + measurementCovariance, + updateVectorCorrected, + callbackData.rejectionThreshold_, + msg->header.stamp); + + RF_DEBUG("Enqueued new measurement for " << topicName << "_twist\n"); + } + else + { + RF_DEBUG("Did *not* enqueue measurement for " << topicName << "_twist\n"); + } + + lastMessageTimes_[topicName] = msg->header.stamp; + + RF_DEBUG("Last message time for " << topicName << " is now " << + lastMessageTimes_[topicName] << "\n"); + } + else if (resetOnTimeJump_ && ros::Time::isSimTime()) + { + reset(); + } + else + { + std::stringstream stream; + stream << "The " << topicName << " message has a timestamp before that of the previous message received," << + " this message will be ignored. This may indicate a bad timestamp. (message time: " << + msg->header.stamp.toSec() << ")"; + addDiagnostic(diagnostic_msgs::DiagnosticStatus::WARN, + topicName + "_timestamp", + stream.str(), + false); + + RF_DEBUG("Message is too old. Last message time for " << topicName << " is " << lastMessageTimes_[topicName] << + ", current message time is " << msg->header.stamp << ".\n"); + } + + RF_DEBUG("\n----- /RosFilter::twistCallback (" << topicName << ") ------\n"); + } + + template + void RosFilter::addDiagnostic(const int errLevel, + const std::string &topicAndClass, + const std::string &message, + const bool staticDiag) + { + if (staticDiag) + { + staticDiagnostics_[topicAndClass] = message; + staticDiagErrorLevel_ = std::max(staticDiagErrorLevel_, errLevel); + } + else + { + dynamicDiagnostics_[topicAndClass] = message; + dynamicDiagErrorLevel_ = std::max(dynamicDiagErrorLevel_, errLevel); + } + } + + template + void RosFilter::aggregateDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &wrapper) + { + wrapper.clear(); + wrapper.clearSummary(); + + int maxErrLevel = std::max(staticDiagErrorLevel_, dynamicDiagErrorLevel_); + + // Report the overall status + switch (maxErrLevel) + { + case diagnostic_msgs::DiagnosticStatus::ERROR: + wrapper.summary(maxErrLevel, + "Erroneous data or settings detected for a robot_localization state estimation node."); + break; + case diagnostic_msgs::DiagnosticStatus::WARN: + wrapper.summary(maxErrLevel, + "Potentially erroneous data or settings detected for " + "a robot_localization state estimation node."); + break; + case diagnostic_msgs::DiagnosticStatus::STALE: + wrapper.summary(maxErrLevel, + "The state of the robot_localization state estimation node is stale."); + break; + case diagnostic_msgs::DiagnosticStatus::OK: + wrapper.summary(maxErrLevel, + "The robot_localization state estimation node appears to be functioning properly."); + break; + default: + break; + } + + // Aggregate all the static messages + for (std::map::iterator diagIt = staticDiagnostics_.begin(); + diagIt != staticDiagnostics_.end(); + ++diagIt) + { + wrapper.add(diagIt->first, diagIt->second); + } + + // Aggregate all the dynamic messages, then clear them + for (std::map::iterator diagIt = dynamicDiagnostics_.begin(); + diagIt != dynamicDiagnostics_.end(); + ++diagIt) + { + wrapper.add(diagIt->first, diagIt->second); + } + dynamicDiagnostics_.clear(); + + // Reset the warning level for the dynamic diagnostic messages + dynamicDiagErrorLevel_ = diagnostic_msgs::DiagnosticStatus::OK; + } + + template + void RosFilter::copyCovariance(const double *arr, + Eigen::MatrixXd &covariance, + const std::string &topicName, + const std::vector &updateVector, + const size_t offset, + const size_t dimension) + { + for (size_t i = 0; i < dimension; i++) + { + for (size_t j = 0; j < dimension; j++) + { + covariance(i, j) = arr[dimension * i + j]; + + if (printDiagnostics_) + { + std::string iVar = stateVariableNames_[offset + i]; + + if (covariance(i, j) > 1e3 && (updateVector[offset + i] || updateVector[offset + j])) + { + std::string jVar = stateVariableNames_[offset + j]; + + std::stringstream stream; + stream << "The covariance at position (" << dimension * i + j << "), which corresponds to " << + (i == j ? iVar + " variance" : iVar + " and " + jVar + " covariance") << + ", the value is extremely large (" << covariance(i, j) << "), but the update vector for " << + (i == j ? iVar : iVar + " and/or " + jVar) << " is set to true. This may produce undesirable results."; + + addDiagnostic(diagnostic_msgs::DiagnosticStatus::WARN, + topicName + "_covariance", + stream.str(), + false); + } + else if (updateVector[i] && i == j && covariance(i, j) == 0) + { + std::stringstream stream; + stream << "The covariance at position (" << dimension * i + j << "), which corresponds to " << + iVar << " variance, was zero. This will be replaced with a small value to maintain filter " + "stability, but should be corrected at the message origin node."; + + addDiagnostic(diagnostic_msgs::DiagnosticStatus::WARN, + topicName + "_covariance", + stream.str(), + false); + } + else if (updateVector[i] && i == j && covariance(i, j) < 0) + { + std::stringstream stream; + stream << "The covariance at position (" << dimension * i + j << + "), which corresponds to " << iVar << " variance, was negative. This will be replaced with a " + "small positive value to maintain filter stability, but should be corrected at the message " + "origin node."; + + addDiagnostic(diagnostic_msgs::DiagnosticStatus::WARN, + topicName + "_covariance", + stream.str(), + false); + } + } + } + } + } + + template + void RosFilter::copyCovariance(const Eigen::MatrixXd &covariance, + double *arr, + const size_t dimension) + { + for (size_t i = 0; i < dimension; i++) + { + for (size_t j = 0; j < dimension; j++) + { + arr[dimension * i + j] = covariance(i, j); + } + } + } + + template + std::vector RosFilter::loadUpdateConfig(const std::string &topicName) + { + XmlRpc::XmlRpcValue topicConfig; + std::vector updateVector(STATE_SIZE, 0); + std::string topicConfigName = topicName + "_config"; + + try + { + nhLocal_.getParam(topicConfigName, topicConfig); + + ROS_ASSERT(topicConfig.getType() == XmlRpc::XmlRpcValue::TypeArray); + + if (topicConfig.size() != STATE_SIZE) + { + ROS_WARN_STREAM("Configuration vector for " << topicConfigName << " should have 15 entries."); + } + + for (int i = 0; i < topicConfig.size(); i++) + { + // The double cast looks strange, but we'll get exceptions if we + // remove the cast to bool. vector is discouraged, so updateVector + // uses integers. + updateVector[i] = static_cast(static_cast(topicConfig[i])); + } + } + catch (XmlRpc::XmlRpcException &e) + { + ROS_FATAL_STREAM("Could not read sensor update configuration for topic " << topicName << + " (type: " << topicConfig.getType() << ", expected: " << XmlRpc::XmlRpcValue::TypeArray + << "). Error was " << e.getMessage() << "\n"); + } + + return updateVector; + } + + template + bool RosFilter::prepareAcceleration(const sensor_msgs::Imu::ConstPtr &msg, + const std::string &topicName, + const std::string &targetFrame, + const bool relative, + std::vector &updateVector, + Eigen::VectorXd &measurement, + Eigen::MatrixXd &measurementCovariance) + { + RF_DEBUG("------ RosFilter::prepareAcceleration (" << topicName << ") ------\n"); + + // 1. Get the measurement into a vector + tf2::Vector3 accTmp(msg->linear_acceleration.x, + msg->linear_acceleration.y, + msg->linear_acceleration.z); + + // Set relevant header info + std::string msgFrame = (msg->header.frame_id == "" ? baseLinkFrameId_ : msg->header.frame_id); + + // 2. robot_localization lets users configure which variables from the sensor should be + // fused with the filter. This is specified at the sensor level. However, the data + // may go through transforms before being fused with the state estimate. In that case, + // we need to know which of the transformed variables came from the pre-transformed + // "approved" variables (i.e., the ones that had "true" in their xxx_config parameter). + // To do this, we create a pose from the original upate vector, which contains only + // zeros and ones. This pose goes through the same transforms as the measurement. The + // non-zero values that result will be used to modify the updateVector. + tf2::Matrix3x3 maskAcc(updateVector[StateMemberAx], 0, 0, + 0, updateVector[StateMemberAy], 0, + 0, 0, updateVector[StateMemberAz]); + + // 3. We'll need to rotate the covariance as well + Eigen::MatrixXd covarianceRotated(ACCELERATION_SIZE, ACCELERATION_SIZE); + covarianceRotated.setZero(); + + this->copyCovariance(&(msg->linear_acceleration_covariance[0]), + covarianceRotated, + topicName, + updateVector, + POSITION_A_OFFSET, + ACCELERATION_SIZE); + + RF_DEBUG("Original measurement as tf object: " << accTmp << + "\nOriginal update vector:\n" << updateVector << + "\nOriginal covariance matrix:\n" << covarianceRotated << "\n"); + + // 4. We need to transform this into the target frame (probably base_link) + // It's unlikely that we'll get a velocity measurement in another frame, but + // we have to handle the situation. + tf2::Transform targetFrameTrans; + bool canTransform = RosFilterUtilities::lookupTransformSafe(tfBuffer_, + targetFrame, + msgFrame, + msg->header.stamp, + tfTimeout_, + targetFrameTrans, + tfSilentFailure_); + + if (canTransform) + { + const Eigen::VectorXd &state = filter_.getState(); + + // We don't know if the user has already handled the removal + // of normal forces, so we use a parameter + if (removeGravitationalAcc_[topicName]) + { + tf2::Vector3 normAcc(0, 0, gravitationalAcc_); + tf2::Transform trans; + tf2::Vector3 rotNorm; + + if (::fabs(msg->orientation_covariance[0] + 1) < 1e-9) + { + // Imu message contains no orientation, so we should use orientation + // from filter state to transform and remove acceleration + tf2::Matrix3x3 stateTmp; + stateTmp.setRPY(state(StateMemberRoll), + state(StateMemberPitch), + state(StateMemberYaw)); + + // transform state orientation to IMU frame + trans.setBasis(stateTmp * targetFrameTrans.getBasis()); + rotNorm = trans.getBasis().inverse() * normAcc; + } + else + { + tf2::Quaternion curAttitude; + tf2::fromMsg(msg->orientation, curAttitude); + if (fabs(curAttitude.length() - 1.0) > 0.01) + { + ROS_WARN_ONCE("An input was not normalized, this should NOT happen, but will normalize."); + curAttitude.normalize(); + } + trans.setRotation(curAttitude); + if (!relative) + { + // curAttitude is the true world-frame attitude of the sensor + rotNorm = trans.getBasis().inverse() * normAcc; + } + else + { + // curAttitude is relative to the initial pose of the sensor. + // Assumption: IMU sensor is rigidly attached to the base_link (but a static rotation is possible). + rotNorm = targetFrameTrans.getBasis().inverse() * trans.getBasis().inverse() * normAcc; + } + } + accTmp.setX(accTmp.getX() - rotNorm.getX()); + accTmp.setY(accTmp.getY() - rotNorm.getY()); + accTmp.setZ(accTmp.getZ() - rotNorm.getZ()); + + RF_DEBUG("Orientation is " << trans.getRotation() << + "Acceleration due to gravity is " << rotNorm << + "After removing acceleration due to gravity, acceleration is " << accTmp << "\n"); + } + + // Transform to correct frame + tf2::Vector3 stateTwistRot(state(StateMemberVroll), + state(StateMemberVpitch), + state(StateMemberVyaw)); + accTmp = targetFrameTrans.getBasis() * accTmp + targetFrameTrans.getOrigin().cross(angular_acceleration_) + - targetFrameTrans.getOrigin().cross(stateTwistRot).cross(stateTwistRot); + maskAcc = targetFrameTrans.getBasis() * maskAcc; + + // Now use the mask values to determine which update vector values should be true + updateVector[StateMemberAx] = static_cast( + maskAcc.getRow(StateMemberAx - POSITION_A_OFFSET).length() >= 1e-6); + updateVector[StateMemberAy] = static_cast( + maskAcc.getRow(StateMemberAy - POSITION_A_OFFSET).length() >= 1e-6); + updateVector[StateMemberAz] = static_cast( + maskAcc.getRow(StateMemberAz - POSITION_A_OFFSET).length() >= 1e-6); + + RF_DEBUG(msg->header.frame_id << "->" << targetFrame << " transform:\n" << targetFrameTrans << + "\nAfter applying transform to " << targetFrame << ", update vector is:\n" << updateVector << + "\nAfter applying transform to " << targetFrame << ", measurement is:\n" << accTmp << "\n"); + + // 5. Now rotate the covariance: create an augmented + // matrix that contains a 3D rotation matrix in the + // upper-left and lower-right quadrants, and zeros + // elsewhere + tf2::Matrix3x3 rot(targetFrameTrans.getRotation()); + Eigen::MatrixXd rot3d(ACCELERATION_SIZE, ACCELERATION_SIZE); + rot3d.setIdentity(); + + for (size_t rInd = 0; rInd < ACCELERATION_SIZE; ++rInd) + { + rot3d(rInd, 0) = rot.getRow(rInd).getX(); + rot3d(rInd, 1) = rot.getRow(rInd).getY(); + rot3d(rInd, 2) = rot.getRow(rInd).getZ(); + } + + // Carry out the rotation + covarianceRotated = rot3d * covarianceRotated.eval() * rot3d.transpose(); + + RF_DEBUG("Transformed covariance is \n" << covarianceRotated << "\n"); + + // 6. Store our corrected measurement and covariance + measurement(StateMemberAx) = accTmp.getX(); + measurement(StateMemberAy) = accTmp.getY(); + measurement(StateMemberAz) = accTmp.getZ(); + + // Copy the covariances + measurementCovariance.block(POSITION_A_OFFSET, POSITION_A_OFFSET, ACCELERATION_SIZE, ACCELERATION_SIZE) = + covarianceRotated.block(0, 0, ACCELERATION_SIZE, ACCELERATION_SIZE); + + // 7. Handle 2D mode + if (twoDMode_) + { + forceTwoD(measurement, measurementCovariance, updateVector); + } + } + else + { + RF_DEBUG("Could not transform measurement into " << targetFrame << ". Ignoring...\n"); + } + + RF_DEBUG("\n----- /RosFilter::prepareAcceleration(" << topicName << ") ------\n"); + + return canTransform; + } + + template + bool RosFilter::preparePose(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &msg, + const std::string &topicName, + const std::string &targetFrame, + const std::string &sourceFrame, + const bool differential, + const bool relative, + const bool imuData, + std::vector &updateVector, + Eigen::VectorXd &measurement, + Eigen::MatrixXd &measurementCovariance) + { + bool retVal = false; + + RF_DEBUG("------ RosFilter::preparePose (" << topicName << ") ------\n"); + + // 1. Get the measurement into a tf-friendly transform (pose) object + tf2::Stamped poseTmp; + + // We'll need this later for storing this measurement for differential integration + tf2::Transform curMeasurement; + + // Handle issues where frame_id data is not filled out properly + // @todo: verify that this is necessary still. New IMU handling may + // have rendered this obsolete. + std::string finalTargetFrame; + if (targetFrame == "") + { + if (msg->header.frame_id == "") + { + // Blank target and message frames mean we can just + // use our world_frame + finalTargetFrame = worldFrameId_; + poseTmp.frame_id_ = finalTargetFrame; + } + else + { // (targetFrame == "") + // A blank target frame means we shouldn't bother + // transforming the data + finalTargetFrame = msg->header.frame_id; + poseTmp.frame_id_ = finalTargetFrame; + } + } + else + { + // Otherwise, we should use our target frame + finalTargetFrame = targetFrame; + poseTmp.frame_id_ = (differential && !imuData ? finalTargetFrame : msg->header.frame_id); + } + + RF_DEBUG("Final target frame for " << topicName << " is " << finalTargetFrame << "\n"); + + poseTmp.stamp_ = msg->header.stamp; + + // Fill out the position data + poseTmp.setOrigin(tf2::Vector3(msg->pose.pose.position.x, + msg->pose.pose.position.y, + msg->pose.pose.position.z)); + + tf2::Quaternion orientation; + + // Handle bad (empty) quaternions + if (msg->pose.pose.orientation.x == 0 && msg->pose.pose.orientation.y == 0 && + msg->pose.pose.orientation.z == 0 && msg->pose.pose.orientation.w == 0) + { + orientation.setValue(0.0, 0.0, 0.0, 1.0); + + if (updateVector[StateMemberRoll] || updateVector[StateMemberPitch] || updateVector[StateMemberYaw]) + { + std::stringstream stream; + stream << "The " << topicName << " message contains an invalid orientation quaternion, " << + "but its configuration is such that orientation data is being used. Correcting..."; + + addDiagnostic(diagnostic_msgs::DiagnosticStatus::WARN, + topicName + "_orientation", + stream.str(), + false); + } + } + else + { + tf2::fromMsg(msg->pose.pose.orientation, orientation); + if (fabs(orientation.length() - 1.0) > 0.01) + { + ROS_WARN_ONCE("An input was not normalized, this should NOT happen, but will normalize."); + orientation.normalize(); + } + } + + // Fill out the orientation data + poseTmp.setRotation(orientation); + + // 2. Get the target frame transformation + tf2::Transform targetFrameTrans; + bool canTransform = RosFilterUtilities::lookupTransformSafe(tfBuffer_, + finalTargetFrame, + poseTmp.frame_id_, + poseTmp.stamp_, + tfTimeout_, + targetFrameTrans, + tfSilentFailure_); + + // handling multiple odometry origins: convert to the origin adherent to base_link. + // make pose refer to the baseLinkFrame as source + tf2::Transform sourceFrameTrans; + bool canSrcTransform = false; + if ( sourceFrame != baseLinkFrameId_ ) + { + canSrcTransform = RosFilterUtilities::lookupTransformSafe(tfBuffer_, + sourceFrame, + baseLinkFrameId_, + poseTmp.stamp_, + tfTimeout_, + sourceFrameTrans, + tfSilentFailure_); + } + + // 3. Make sure we can work with this data before carrying on + if (canTransform) + { + /* 4. robot_localization lets users configure which variables from the sensor should be + * fused with the filter. This is specified at the sensor level. However, the data + * may go through transforms before being fused with the state estimate. In that case, + * we need to know which of the transformed variables came from the pre-transformed + * "approved" variables (i.e., the ones that had "true" in their xxx_config parameter). + * To do this, we construct matrices using the update vector values on the diagonals, + * pass this matrix through the rotation, and use the length of each row to determine + * the transformed update vector. The process is slightly different for IMUs, as the + * coordinate frame transform is really the base_link->imu_frame transform, and not + * a transform from some other world-fixed frame (even though the IMU data itself *is* + * reported in a world fixed frame). */ + tf2::Matrix3x3 maskPosition(updateVector[StateMemberX], 0, 0, + 0, updateVector[StateMemberY], 0, + 0, 0, updateVector[StateMemberZ]); + + tf2::Matrix3x3 maskOrientation(updateVector[StateMemberRoll], 0, 0, + 0, updateVector[StateMemberPitch], 0, + 0, 0, updateVector[StateMemberYaw]); + + if (imuData) + { + /* We have to treat IMU orientation data differently. Even though we are dealing with pose + * data when we work with orientations, for IMUs, the frame_id is the frame in which the + * sensor is mounted, and not the coordinate frame of the IMU. Imagine an IMU that is mounted + * facing sideways. The pitch in the IMU frame becomes roll for the vehicle. This means that + * we need to rotate roll and pitch angles by the IMU's mounting yaw offset, and we must apply + * similar treatment to its update mask and covariance. */ + + double dummy, yaw; + targetFrameTrans.getBasis().getRPY(dummy, dummy, yaw); + tf2::Matrix3x3 transTmp; + transTmp.setRPY(0.0, 0.0, yaw); + + maskPosition = transTmp * maskPosition; + maskOrientation = transTmp * maskOrientation; + } + else + { + maskPosition = targetFrameTrans.getBasis() * maskPosition; + maskOrientation = targetFrameTrans.getBasis() * maskOrientation; + } + + // Now copy the mask values back into the update vector: any row with a significant vector length + // indicates that we want to set that variable to true in the update vector. + updateVector[StateMemberX] = static_cast( + maskPosition.getRow(StateMemberX - POSITION_OFFSET).length() >= 1e-6); + updateVector[StateMemberY] = static_cast( + maskPosition.getRow(StateMemberY - POSITION_OFFSET).length() >= 1e-6); + updateVector[StateMemberZ] = static_cast( + maskPosition.getRow(StateMemberZ - POSITION_OFFSET).length() >= 1e-6); + updateVector[StateMemberRoll] = static_cast( + maskOrientation.getRow(StateMemberRoll - ORIENTATION_OFFSET).length() >= 1e-6); + updateVector[StateMemberPitch] = static_cast( + maskOrientation.getRow(StateMemberPitch - ORIENTATION_OFFSET).length() >= 1e-6); + updateVector[StateMemberYaw] = static_cast( + maskOrientation.getRow(StateMemberYaw - ORIENTATION_OFFSET).length() >= 1e-6); + + // 5a. We'll need to rotate the covariance as well. Create a container and copy over the + // covariance data + Eigen::MatrixXd covariance(POSE_SIZE, POSE_SIZE); + covariance.setZero(); + copyCovariance(&(msg->pose.covariance[0]), covariance, topicName, updateVector, POSITION_OFFSET, POSE_SIZE); + + // 5b. Now rotate the covariance: create an augmented matrix that + // contains a 3D rotation matrix in the upper-left and lower-right + // quadrants, with zeros elsewhere. + tf2::Matrix3x3 rot; + Eigen::MatrixXd rot6d(POSE_SIZE, POSE_SIZE); + rot6d.setIdentity(); + Eigen::MatrixXd covarianceRotated; + + // Transform pose covariance due to a different pose source origin + if (canSrcTransform) + { + rot.setRotation(sourceFrameTrans.getRotation()); + for (size_t rInd = 0; rInd < POSITION_SIZE; ++rInd) + { + rot6d(rInd, 0) = rot.getRow(rInd).getX(); + rot6d(rInd, 1) = rot.getRow(rInd).getY(); + rot6d(rInd, 2) = rot.getRow(rInd).getZ(); + rot6d(rInd+POSITION_SIZE, 3) = rot.getRow(rInd).getX(); + rot6d(rInd+POSITION_SIZE, 4) = rot.getRow(rInd).getY(); + rot6d(rInd+POSITION_SIZE, 5) = rot.getRow(rInd).getZ(); + } + // since the transformation is a post-multiply + covariance = rot6d.transpose() * covariance.eval() * rot6d; + } + + rot6d.setIdentity(); + + if (imuData) + { + // Apply the same special logic to the IMU covariance rotation + double dummy, yaw; + targetFrameTrans.getBasis().getRPY(dummy, dummy, yaw); + rot.setRPY(0.0, 0.0, yaw); + } + else + { + rot.setRotation(targetFrameTrans.getRotation()); + } + + for (size_t rInd = 0; rInd < POSITION_SIZE; ++rInd) + { + rot6d(rInd, 0) = rot.getRow(rInd).getX(); + rot6d(rInd, 1) = rot.getRow(rInd).getY(); + rot6d(rInd, 2) = rot.getRow(rInd).getZ(); + rot6d(rInd+POSITION_SIZE, 3) = rot.getRow(rInd).getX(); + rot6d(rInd+POSITION_SIZE, 4) = rot.getRow(rInd).getY(); + rot6d(rInd+POSITION_SIZE, 5) = rot.getRow(rInd).getZ(); + } + + // Now carry out the rotation + covarianceRotated = rot6d * covariance * rot6d.transpose(); + + RF_DEBUG("After rotating into the " << finalTargetFrame << + " frame, covariance is \n" << covarianceRotated << "\n"); + + /* 6a. For IMU data, the transform that we get is the transform from the body + * frame of the robot (e.g., base_link) to the mounting frame of the robot. It + * is *not* the coordinate frame in which the IMU orientation data is reported. + * If the IMU is mounted in a non-neutral orientation, we need to remove those + * offsets, and then we need to potentially "swap" roll and pitch. + * Note that this transform does NOT handle NED->ENU conversions. Data is assumed + * to be in the ENU frame when it is received. + * */ + if (imuData) + { + // First, convert the transform and measurement rotation to RPY + // @todo: There must be a way to handle this with quaternions. Need to look into it. + double rollOffset = 0; + double pitchOffset = 0; + double yawOffset = 0; + double roll = 0; + double pitch = 0; + double yaw = 0; + RosFilterUtilities::quatToRPY(targetFrameTrans.getRotation(), rollOffset, pitchOffset, yawOffset); + RosFilterUtilities::quatToRPY(poseTmp.getRotation(), roll, pitch, yaw); + + // 6b. Apply the offset (making sure to bound them), and throw them in a vector + tf2::Vector3 rpyAngles(FilterUtilities::clampRotation(roll - rollOffset), + FilterUtilities::clampRotation(pitch - pitchOffset), + FilterUtilities::clampRotation(yaw - yawOffset)); + + // 6c. Now we need to rotate the roll and pitch by the yaw offset value. + // Imagine a case where an IMU is mounted facing sideways. In that case + // pitch for the IMU's world frame is roll for the robot. + tf2::Matrix3x3 mat; + mat.setRPY(0.0, 0.0, yawOffset); + rpyAngles = mat * rpyAngles; + poseTmp.getBasis().setRPY(rpyAngles.getX(), rpyAngles.getY(), rpyAngles.getZ()); + + // We will use this target transformation later on, but + // we've already transformed this data as if the IMU + // were mounted neutrall on the robot, so we can just + // make the transform the identity. + targetFrameTrans.setIdentity(); + } + + // 7. Two cases: if we're in differential mode, we need to generate a twist + // message. Otherwise, we just transform it to the target frame. + if (differential) + { + bool success = false; + + // We're going to be playing with poseTmp, so store it, + // as we'll need to save its current value for the next + // measurement. + curMeasurement = poseTmp; + + // Make sure we have previous measurements to work with + if (previousMeasurements_.count(topicName) > 0 && previousMeasurementCovariances_.count(topicName) > 0) + { + // 7a. If we are carrying out differential integration and + // we have a previous measurement for this sensor,then we + // need to apply the inverse of that measurement to this new + // measurement to produce a "delta" measurement between the two. + // Even if we're not using all of the variables from this sensor, + // we need to use the whole measurement to determine the delta + // to the new measurement + tf2::Transform prevMeasurement = previousMeasurements_[topicName]; + poseTmp.setData(prevMeasurement.inverseTimes(poseTmp)); + + RF_DEBUG("Previous measurement:\n" << previousMeasurements_[topicName] << + "\nAfter removing previous measurement, measurement delta is:\n" << poseTmp << "\n"); + + // 7b. Now we we have a measurement delta in the frame_id of the + // message, but we want that delta to be in the target frame, so + // we need to apply the rotation of the target frame transform. + targetFrameTrans.setOrigin(tf2::Vector3(0.0, 0.0, 0.0)); + poseTmp.mult(targetFrameTrans, poseTmp); + + RF_DEBUG("After rotating to the target frame, measurement delta is:\n" << poseTmp << "\n"); + + // 7c. Now use the time difference from the last message to compute + // translational and rotational velocities + double dt = msg->header.stamp.toSec() - lastMessageTimes_[topicName].toSec(); + double xVel = poseTmp.getOrigin().getX() / dt; + double yVel = poseTmp.getOrigin().getY() / dt; + double zVel = poseTmp.getOrigin().getZ() / dt; + + double rollVel = 0; + double pitchVel = 0; + double yawVel = 0; + + RosFilterUtilities::quatToRPY(poseTmp.getRotation(), rollVel, pitchVel, yawVel); + rollVel /= dt; + pitchVel /= dt; + yawVel /= dt; + + RF_DEBUG("Previous message time was " << lastMessageTimes_[topicName].toSec() << + ", current message time is " << msg->header.stamp.toSec() << ", delta is " << + dt << ", velocity is (vX, vY, vZ): (" << xVel << ", " << yVel << ", " << zVel << + ")\n" << "(vRoll, vPitch, vYaw): (" << rollVel << ", " << pitchVel << ", " << + yawVel << ")\n"); + + // 7d. Fill out the velocity data in the message + geometry_msgs::TwistWithCovarianceStamped *twistPtr = new geometry_msgs::TwistWithCovarianceStamped(); + twistPtr->header = msg->header; + twistPtr->header.frame_id = sourceFrame; + twistPtr->twist.twist.linear.x = xVel; + twistPtr->twist.twist.linear.y = yVel; + twistPtr->twist.twist.linear.z = zVel; + twistPtr->twist.twist.angular.x = rollVel; + twistPtr->twist.twist.angular.y = pitchVel; + twistPtr->twist.twist.angular.z = yawVel; + std::vector twistUpdateVec(STATE_SIZE, false); + std::copy(updateVector.begin() + POSITION_OFFSET, + updateVector.begin() + POSE_SIZE, + twistUpdateVec.begin() + POSITION_V_OFFSET); + std::copy(twistUpdateVec.begin(), twistUpdateVec.end(), updateVector.begin()); + geometry_msgs::TwistWithCovarianceStampedConstPtr ptr(twistPtr); + + // 7e. Now rotate the previous covariance for this measurement to get it + // into the target frame, and add the current measurement's rotated covariance + // to the previous measurement's rotated covariance, and multiply by the time delta. + Eigen::MatrixXd prevCovarRotated = rot6d * previousMeasurementCovariances_[topicName] * rot6d.transpose(); + covarianceRotated = (covarianceRotated.eval() + prevCovarRotated) * dt; + copyCovariance(covarianceRotated, &(twistPtr->twist.covariance[0]), POSE_SIZE); + + RF_DEBUG("Previous measurement covariance:\n" << previousMeasurementCovariances_[topicName] << + "\nPrevious measurement covariance rotated:\n" << prevCovarRotated << + "\nFinal twist covariance:\n" << covarianceRotated << "\n"); + + // Now pass this on to prepareTwist, which will convert it to the required frame + success = prepareTwist(ptr, + topicName + "_twist", + baseLinkFrameId_, + updateVector, + measurement, + measurementCovariance); + } + + // 7f. Update the previous measurement and measurement covariance + previousMeasurements_[topicName] = curMeasurement; + previousMeasurementCovariances_[topicName] = covariance; + + retVal = success; + } + else + { + // make pose refer to the baseLinkFrame as source + // canSrcTransform == true => ( sourceFrame != baseLinkFrameId_ ) + if (canSrcTransform) + { + poseTmp.setData(poseTmp * sourceFrameTrans); + } + + // 7g. If we're in relative mode, remove the initial measurement + if (relative) + { + if (initialMeasurements_.count(topicName) == 0) + { + initialMeasurements_.insert(std::pair(topicName, poseTmp)); + } + + tf2::Transform initialMeasurement = initialMeasurements_[topicName]; + poseTmp.setData(initialMeasurement.inverseTimes(poseTmp)); + } + + // 7h. Apply the target frame transformation to the pose object. + poseTmp.mult(targetFrameTrans, poseTmp); + poseTmp.frame_id_ = finalTargetFrame; + + // 7i. Finally, copy everything into our measurement and covariance objects + measurement(StateMemberX) = poseTmp.getOrigin().x(); + measurement(StateMemberY) = poseTmp.getOrigin().y(); + measurement(StateMemberZ) = poseTmp.getOrigin().z(); + + // The filter needs roll, pitch, and yaw values instead of quaternions + double roll, pitch, yaw; + RosFilterUtilities::quatToRPY(poseTmp.getRotation(), roll, pitch, yaw); + measurement(StateMemberRoll) = roll; + measurement(StateMemberPitch) = pitch; + measurement(StateMemberYaw) = yaw; + + measurementCovariance.block(0, 0, POSE_SIZE, POSE_SIZE) = covarianceRotated.block(0, 0, POSE_SIZE, POSE_SIZE); + + // 8. Handle 2D mode + if (twoDMode_) + { + forceTwoD(measurement, measurementCovariance, updateVector); + } + + retVal = true; + } + } + else + { + retVal = false; + + RF_DEBUG("Could not transform measurement into " << finalTargetFrame << ". Ignoring..."); + } + + RF_DEBUG("\n----- /RosFilter::preparePose (" << topicName << ") ------\n"); + + return retVal; + } + + template + bool RosFilter::prepareTwist(const geometry_msgs::TwistWithCovarianceStamped::ConstPtr &msg, + const std::string &topicName, + const std::string &targetFrame, + std::vector &updateVector, + Eigen::VectorXd &measurement, + Eigen::MatrixXd &measurementCovariance) + { + RF_DEBUG("------ RosFilter::prepareTwist (" << topicName << ") ------\n"); + + // 1. Get the measurement into two separate vector objects. + tf2::Vector3 twistLin(msg->twist.twist.linear.x, + msg->twist.twist.linear.y, + msg->twist.twist.linear.z); + tf2::Vector3 measTwistRot(msg->twist.twist.angular.x, + msg->twist.twist.angular.y, + msg->twist.twist.angular.z); + + // 1a. This sensor may or may not measure rotational velocity. Regardless, + // if it measures linear velocity, then later on, we'll need to remove "false" + // linear velocity resulting from angular velocity and the translational offset + // of the sensor from the vehicle origin. + const Eigen::VectorXd &state = filter_.getState(); + tf2::Vector3 stateTwistRot(state(StateMemberVroll), + state(StateMemberVpitch), + state(StateMemberVyaw)); + + // Determine the frame_id of the data + std::string msgFrame = (msg->header.frame_id == "" ? targetFrame : msg->header.frame_id); + + // 2. robot_localization lets users configure which variables from the sensor should be + // fused with the filter. This is specified at the sensor level. However, the data + // may go through transforms before being fused with the state estimate. In that case, + // we need to know which of the transformed variables came from the pre-transformed + // "approved" variables (i.e., the ones that had "true" in their xxx_config parameter). + // To do this, we construct matrices using the update vector values on the diagonals, + // pass this matrix through the rotation, and use the length of each row to determine + // the transformed update vector. + tf2::Matrix3x3 maskLin(updateVector[StateMemberVx], 0, 0, + 0, updateVector[StateMemberVy], 0, + 0, 0, updateVector[StateMemberVz]); + + tf2::Matrix3x3 maskRot(updateVector[StateMemberVroll], 0, 0, + 0, updateVector[StateMemberVpitch], 0, + 0, 0, updateVector[StateMemberVyaw]); + + // 3. We'll need to rotate the covariance as well + Eigen::MatrixXd covarianceRotated(TWIST_SIZE, TWIST_SIZE); + covarianceRotated.setZero(); + + copyCovariance(&(msg->twist.covariance[0]), + covarianceRotated, + topicName, + updateVector, + POSITION_V_OFFSET, + TWIST_SIZE); + + RF_DEBUG("Original measurement as tf object:\nLinear: " << twistLin << + "Rotational: " << measTwistRot << + "\nOriginal update vector:\n" << updateVector << + "\nOriginal covariance matrix:\n" << covarianceRotated << "\n"); + + // 4. We need to transform this into the target frame (probably base_link) + tf2::Transform targetFrameTrans; + bool canTransform = RosFilterUtilities::lookupTransformSafe(tfBuffer_, + targetFrame, + msgFrame, + msg->header.stamp, + tfTimeout_, + targetFrameTrans, + tfSilentFailure_); + + if (canTransform) + { + // Transform to correct frame. Note that we can get linear velocity + // as a result of the sensor offset and rotational velocity + measTwistRot = targetFrameTrans.getBasis() * measTwistRot; + twistLin = targetFrameTrans.getBasis() * twistLin + targetFrameTrans.getOrigin().cross(stateTwistRot); + maskLin = targetFrameTrans.getBasis() * maskLin; + maskRot = targetFrameTrans.getBasis() * maskRot; + + // Now copy the mask values back into the update vector + updateVector[StateMemberVx] = static_cast( + maskLin.getRow(StateMemberVx - POSITION_V_OFFSET).length() >= 1e-6); + updateVector[StateMemberVy] = static_cast( + maskLin.getRow(StateMemberVy - POSITION_V_OFFSET).length() >= 1e-6); + updateVector[StateMemberVz] = static_cast( + maskLin.getRow(StateMemberVz - POSITION_V_OFFSET).length() >= 1e-6); + updateVector[StateMemberVroll] = static_cast( + maskRot.getRow(StateMemberVroll - ORIENTATION_V_OFFSET).length() >= 1e-6); + updateVector[StateMemberVpitch] = static_cast( + maskRot.getRow(StateMemberVpitch - ORIENTATION_V_OFFSET).length() >= 1e-6); + updateVector[StateMemberVyaw] = static_cast( + maskRot.getRow(StateMemberVyaw - ORIENTATION_V_OFFSET).length() >= 1e-6); + + RF_DEBUG(msg->header.frame_id << "->" << targetFrame << " transform:\n" << targetFrameTrans << + "\nAfter applying transform to " << targetFrame << ", update vector is:\n" << updateVector << + "\nAfter applying transform to " << targetFrame << ", measurement is:\n" << + "Linear: " << twistLin << "Rotational: " << measTwistRot << "\n"); + + // 5. Now rotate the covariance: create an augmented + // matrix that contains a 3D rotation matrix in the + // upper-left and lower-right quadrants, and zeros + // elsewhere + tf2::Matrix3x3 rot(targetFrameTrans.getRotation()); + Eigen::MatrixXd rot6d(TWIST_SIZE, TWIST_SIZE); + rot6d.setIdentity(); + + for (size_t rInd = 0; rInd < POSITION_SIZE; ++rInd) + { + rot6d(rInd, 0) = rot.getRow(rInd).getX(); + rot6d(rInd, 1) = rot.getRow(rInd).getY(); + rot6d(rInd, 2) = rot.getRow(rInd).getZ(); + rot6d(rInd+POSITION_SIZE, 3) = rot.getRow(rInd).getX(); + rot6d(rInd+POSITION_SIZE, 4) = rot.getRow(rInd).getY(); + rot6d(rInd+POSITION_SIZE, 5) = rot.getRow(rInd).getZ(); + } + + // Carry out the rotation + covarianceRotated = rot6d * covarianceRotated.eval() * rot6d.transpose(); + + RF_DEBUG("Transformed covariance is \n" << covarianceRotated << "\n"); + + // 6. Store our corrected measurement and covariance + measurement(StateMemberVx) = twistLin.getX(); + measurement(StateMemberVy) = twistLin.getY(); + measurement(StateMemberVz) = twistLin.getZ(); + measurement(StateMemberVroll) = measTwistRot.getX(); + measurement(StateMemberVpitch) = measTwistRot.getY(); + measurement(StateMemberVyaw) = measTwistRot.getZ(); + + // Copy the covariances + measurementCovariance.block(POSITION_V_OFFSET, POSITION_V_OFFSET, TWIST_SIZE, TWIST_SIZE) = + covarianceRotated.block(0, 0, TWIST_SIZE, TWIST_SIZE); + + // 7. Handle 2D mode + if (twoDMode_) + { + forceTwoD(measurement, measurementCovariance, updateVector); + } + } + else + { + RF_DEBUG("Could not transform measurement into " << targetFrame << ". Ignoring..."); + } + + RF_DEBUG("\n----- /RosFilter::prepareTwist (" << topicName << ") ------\n"); + + return canTransform; + } + + template + void RosFilter::saveFilterState(FilterBase& filter) + { + FilterStatePtr state = FilterStatePtr(new FilterState()); + state->state_ = Eigen::VectorXd(filter.getState()); + state->estimateErrorCovariance_ = Eigen::MatrixXd(filter.getEstimateErrorCovariance()); + state->lastMeasurementTime_ = filter.getLastMeasurementTime(); + state->latestControl_ = Eigen::VectorXd(filter.getControl()); + state->latestControlTime_ = filter.getControlTime(); + filterStateHistory_.push_back(state); + RF_DEBUG("Saved state with timestamp " << std::setprecision(20) << state->lastMeasurementTime_ << + " to history. " << filterStateHistory_.size() << " measurements are in the queue.\n"); + } + + template + bool RosFilter::revertTo(const double time) + { + RF_DEBUG("\n----- RosFilter::revertTo -----\n"); + RF_DEBUG("\nRequested time was " << std::setprecision(20) << time << "\n") + + size_t history_size = filterStateHistory_.size(); + + // Walk back through the queue until we reach a filter state whose time stamp is less than or equal to the + // requested time. Since every saved state after that time will be overwritten/corrected, we can pop from + // the queue. If the history is insufficiently short, we just take the oldest state we have. + FilterStatePtr lastHistoryState; + while (!filterStateHistory_.empty() && filterStateHistory_.back()->lastMeasurementTime_ > time) + { + lastHistoryState = filterStateHistory_.back(); + filterStateHistory_.pop_back(); + } + + // If the state history is not empty at this point, it means that our history was large enough, and we + // should revert to the state at the back of the history deque. + bool retVal = false; + if (!filterStateHistory_.empty()) + { + retVal = true; + lastHistoryState = filterStateHistory_.back(); + } + else + { + RF_DEBUG("Insufficient history to revert to time " << time << "\n"); + + if (lastHistoryState) + { + RF_DEBUG("Will revert to oldest state at " << lastHistoryState->latestControlTime_ << ".\n"); + ROS_WARN_STREAM_DELAYED_THROTTLE(historyLength_, "Could not revert to state with time " << + std::setprecision(20) << time << ". Instead reverted to state with time " << + lastHistoryState->lastMeasurementTime_ << ". History size was " << history_size); + } + } + + // If we have a valid reversion state, revert + if (lastHistoryState) + { + // Reset filter to the latest state from the queue. + const FilterStatePtr &state = lastHistoryState; + filter_.setState(state->state_); + filter_.setEstimateErrorCovariance(state->estimateErrorCovariance_); + filter_.setLastMeasurementTime(state->lastMeasurementTime_); + + RF_DEBUG("Reverted to state with time " << std::setprecision(20) << state->lastMeasurementTime_ << "\n"); + + // Repeat for measurements, but push every measurement onto the measurement queue as we go + int restored_measurements = 0; + while (!measurementHistory_.empty() && measurementHistory_.back()->time_ > time) + { + // Don't need to restore measurements that predate our earliest state time + if (state->lastMeasurementTime_ <= measurementHistory_.back()->time_) + { + measurementQueue_.push(measurementHistory_.back()); + restored_measurements++; + } + + measurementHistory_.pop_back(); + } + + RF_DEBUG("Restored " << restored_measurements << " to measurement queue.\n"); + } + + RF_DEBUG("\n----- /RosFilter::revertTo\n"); + + return retVal; + } + + template + bool RosFilter::validateFilterOutput(const nav_msgs::Odometry &message) + { + return !std::isnan(message.pose.pose.position.x) && !std::isinf(message.pose.pose.position.x) && + !std::isnan(message.pose.pose.position.y) && !std::isinf(message.pose.pose.position.y) && + !std::isnan(message.pose.pose.position.z) && !std::isinf(message.pose.pose.position.z) && + !std::isnan(message.pose.pose.orientation.x) && !std::isinf(message.pose.pose.orientation.x) && + !std::isnan(message.pose.pose.orientation.y) && !std::isinf(message.pose.pose.orientation.y) && + !std::isnan(message.pose.pose.orientation.z) && !std::isinf(message.pose.pose.orientation.z) && + !std::isnan(message.pose.pose.orientation.w) && !std::isinf(message.pose.pose.orientation.w) && + !std::isnan(message.twist.twist.linear.x) && !std::isinf(message.twist.twist.linear.x) && + !std::isnan(message.twist.twist.linear.y) && !std::isinf(message.twist.twist.linear.y) && + !std::isnan(message.twist.twist.linear.z) && !std::isinf(message.twist.twist.linear.z) && + !std::isnan(message.twist.twist.angular.x) && !std::isinf(message.twist.twist.angular.x) && + !std::isnan(message.twist.twist.angular.y) && !std::isinf(message.twist.twist.angular.y) && + !std::isnan(message.twist.twist.angular.z) && !std::isinf(message.twist.twist.angular.z); + } + + template + void RosFilter::clearExpiredHistory(const double cutOffTime) + { + RF_DEBUG("\n----- RosFilter::clearExpiredHistory -----" << + "\nCutoff time is " << cutOffTime << "\n"); + + int poppedMeasurements = 0; + int poppedStates = 0; + + while (!measurementHistory_.empty() && measurementHistory_.front()->time_ < cutOffTime) + { + measurementHistory_.pop_front(); + poppedMeasurements++; + } + + while (!filterStateHistory_.empty() && filterStateHistory_.front()->lastMeasurementTime_ < cutOffTime) + { + filterStateHistory_.pop_front(); + poppedStates++; + } + + RF_DEBUG("\nPopped " << poppedMeasurements << " measurements and " << + poppedStates << " states from their respective queues." << + "\n---- /RosFilter::clearExpiredHistory ----\n"); + } + + template + void RosFilter::clearMeasurementQueue() + { + while (!measurementQueue_.empty() && ros::ok()) + { + measurementQueue_.pop(); + } + return; + } +} // namespace RobotLocalization + +// Instantiations of classes is required when template class code +// is placed in a .cpp file. +template class RobotLocalization::RosFilter; +template class RobotLocalization::RosFilter; diff --git a/navigations/robot_localization/src/ros_filter_utilities.cpp b/navigations/robot_localization/src/ros_filter_utilities.cpp new file mode 100755 index 0000000..e1a5bfb --- /dev/null +++ b/navigations/robot_localization/src/ros_filter_utilities.cpp @@ -0,0 +1,195 @@ +/* + * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include "robot_localization/ros_filter_utilities.h" +#include "robot_localization/filter_common.h" + +#include +#include + +#include +#include + +std::ostream& operator<<(std::ostream& os, const tf2::Vector3 &vec) +{ + os << "(" << std::setprecision(20) << vec.getX() << " " << vec.getY() << " " << vec.getZ() << ")\n"; + + return os; +} + +std::ostream& operator<<(std::ostream& os, const tf2::Quaternion &quat) +{ + double roll, pitch, yaw; + tf2::Matrix3x3 orTmp(quat); + orTmp.getRPY(roll, pitch, yaw); + + os << "(" << std::setprecision(20) << roll << ", " << pitch << ", " << yaw << ")\n"; + + return os; +} + +std::ostream& operator<<(std::ostream& os, const tf2::Transform &trans) +{ + os << "Origin: " << trans.getOrigin() << + "Rotation (RPY): " << trans.getRotation(); + + return os; +} + +std::ostream& operator<<(std::ostream& os, const std::vector &vec) +{ + os << "(" << std::setprecision(20); + + for (size_t i = 0; i < vec.size(); ++i) + { + os << vec[i] << " "; + } + + os << ")\n"; + + return os; +} + +namespace RobotLocalization +{ +namespace RosFilterUtilities +{ + + double getYaw(const tf2::Quaternion quat) + { + tf2::Matrix3x3 mat(quat); + + double dummy; + double yaw; + mat.getRPY(dummy, dummy, yaw); + + return yaw; + } + + bool lookupTransformSafe(const tf2_ros::Buffer &buffer, + const std::string &targetFrame, + const std::string &sourceFrame, + const ros::Time &time, + const ros::Duration &timeout, + tf2::Transform &targetFrameTrans, + const bool silent) + { + bool retVal = true; + + // First try to transform the data at the requested time + try + { + tf2::fromMsg(buffer.lookupTransform(targetFrame, sourceFrame, time, timeout).transform, + targetFrameTrans); + } + catch (tf2::TransformException &ex) + { + // The issue might be that the transforms that are available are not close + // enough temporally to be used. In that case, just use the latest available + // transform and warn the user. + try + { + tf2::fromMsg(buffer.lookupTransform(targetFrame, sourceFrame, ros::Time(0)).transform, + targetFrameTrans); + + if (!silent) + { + ROS_WARN_STREAM_THROTTLE(2.0, "Transform from " << sourceFrame << " to " << targetFrame << + " was unavailable for the time requested. Using latest instead.\n"); + } + } + catch(tf2::TransformException &ex) + { + if (!silent) + { + ROS_WARN_STREAM_THROTTLE(2.0, "Could not obtain transform from " << sourceFrame << + " to " << targetFrame << ". Error was " << ex.what() << "\n"); + } + + retVal = false; + } + } + + // Transforming from a frame id to itself can fail when the tf tree isn't + // being broadcast (e.g., for some bag files). This is the only failure that + // would throw an exception, so check for this situation before giving up. + if (!retVal) + { + if (targetFrame == sourceFrame) + { + targetFrameTrans.setIdentity(); + retVal = true; + } + } + + return retVal; + } + + bool lookupTransformSafe(const tf2_ros::Buffer &buffer, + const std::string &targetFrame, + const std::string &sourceFrame, + const ros::Time &time, + tf2::Transform &targetFrameTrans, + const bool silent) + { + return lookupTransformSafe(buffer, targetFrame, sourceFrame, time, ros::Duration(0), targetFrameTrans, silent); + } + + void quatToRPY(const tf2::Quaternion &quat, double &roll, double &pitch, double &yaw) + { + tf2::Matrix3x3 orTmp(quat); + orTmp.getRPY(roll, pitch, yaw); + } + + void stateToTF(const Eigen::VectorXd &state, tf2::Transform &stateTF) + { + stateTF.setOrigin(tf2::Vector3(state(StateMemberX), + state(StateMemberY), + state(StateMemberZ))); + tf2::Quaternion quat; + quat.setRPY(state(StateMemberRoll), + state(StateMemberPitch), + state(StateMemberYaw)); + + stateTF.setRotation(quat); + } + + void TFtoState(const tf2::Transform &stateTF, Eigen::VectorXd &state) + { + state(StateMemberX) = stateTF.getOrigin().getX(); + state(StateMemberY) = stateTF.getOrigin().getY(); + state(StateMemberZ) = stateTF.getOrigin().getZ(); + quatToRPY(stateTF.getRotation(), state(StateMemberRoll), state(StateMemberPitch), state(StateMemberYaw)); + } + +} // namespace RosFilterUtilities +} // namespace RobotLocalization diff --git a/navigations/robot_localization/src/ros_robot_localization_listener.cpp b/navigations/robot_localization/src/ros_robot_localization_listener.cpp new file mode 100755 index 0000000..85e5465 --- /dev/null +++ b/navigations/robot_localization/src/ros_robot_localization_listener.cpp @@ -0,0 +1,539 @@ +/* + * Copyright (c) 2016, TNO IVS Helmond. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include "robot_localization/ros_robot_localization_listener.h" +#include "robot_localization/ros_filter_utilities.h" + +#include +#include +#include + +#include +#include +#include +#include +#include +#include + +#include + +namespace RobotLocalization +{ + +FilterType filterTypeFromString(const std::string& filter_type_str) +{ + if ( filter_type_str == "ekf" ) + { + return FilterTypes::EKF; + } + else if ( filter_type_str == "ukf" ) + { + return FilterTypes::UKF; + } + else + { + return FilterTypes::NotDefined; + } +} + +RosRobotLocalizationListener::RosRobotLocalizationListener(): + nh_p_("robot_localization"), + odom_sub_(nh_, "odometry/filtered", 1), + accel_sub_(nh_, "accel/filtered", 1), + sync_(odom_sub_, accel_sub_, 10), + base_frame_id_(""), + world_frame_id_(""), + tf_listener_(tf_buffer_) +{ + int buffer_size; + nh_p_.param("buffer_size", buffer_size, 10); + + std::string param_ns; + nh_p_.param("parameter_namespace", param_ns, nh_p_.getNamespace()); + + ros::NodeHandle nh_param(param_ns); + + std::string filter_type_str; + nh_param.param("filter_type", filter_type_str, std::string("ekf")); + FilterType filter_type = filterTypeFromString(filter_type_str); + if ( filter_type == FilterTypes::NotDefined ) + { + ROS_ERROR("RosRobotLocalizationListener: Parameter filter_type invalid"); + return; + } + + // Load up the process noise covariance (from the launch file/parameter server) + // TODO(reinzor): this code is copied from ros_filter. In a refactor, this could be moved to a function in + // ros_filter_utilities + Eigen::MatrixXd process_noise_covariance(STATE_SIZE, STATE_SIZE); + process_noise_covariance.setZero(); + XmlRpc::XmlRpcValue process_noise_covar_config; + + if (!nh_param.hasParam("process_noise_covariance")) + { + ROS_FATAL_STREAM("Process noise covariance not found in the robot localization listener config (namespace " << + nh_param.getNamespace() << ")! Use the ~parameter_namespace to specify the parameter namespace."); + } + else + { + try + { + nh_param.getParam("process_noise_covariance", process_noise_covar_config); + + ROS_ASSERT(process_noise_covar_config.getType() == XmlRpc::XmlRpcValue::TypeArray); + + int mat_size = process_noise_covariance.rows(); + + for (int i = 0; i < mat_size; i++) + { + for (int j = 0; j < mat_size; j++) + { + try + { + // These matrices can cause problems if all the types + // aren't specified with decimal points. Handle that + // using string streams. + std::ostringstream ostr; + process_noise_covar_config[mat_size * i + j].write(ostr); + std::istringstream istr(ostr.str()); + istr >> process_noise_covariance(i, j); + } + catch(XmlRpc::XmlRpcException &e) + { + throw e; + } + catch(...) + { + throw; + } + } + } + + ROS_DEBUG_STREAM("Process noise covariance is:\n" << process_noise_covariance << "\n"); + } + catch (XmlRpc::XmlRpcException &e) + { + ROS_ERROR_STREAM("ERROR reading robot localization listener config: " << + e.getMessage() << + " for process_noise_covariance (type: " << + process_noise_covar_config.getType() << ")"); + } + } + + std::vector filter_args; + nh_param.param("filter_args", filter_args, std::vector()); + + estimator_ = new RobotLocalizationEstimator(buffer_size, filter_type, process_noise_covariance, filter_args); + + sync_.registerCallback(&RosRobotLocalizationListener::odomAndAccelCallback, this); + + ROS_INFO_STREAM("Ros Robot Localization Listener: Listening to topics " << + odom_sub_.getTopic() << " and " << accel_sub_.getTopic()); + + // Wait until the base and world frames are set by the incoming messages + while (ros::ok() && base_frame_id_.empty()) + { + ros::spinOnce(); + ROS_INFO_STREAM_THROTTLE(1.0, "Ros Robot Localization Listener: Waiting for incoming messages on topics " << + odom_sub_.getTopic() << " and " << accel_sub_.getTopic()); + ros::Duration(0.1).sleep(); + } +} + +RosRobotLocalizationListener::~RosRobotLocalizationListener() +{ + delete estimator_; +} + +void RosRobotLocalizationListener::odomAndAccelCallback(const nav_msgs::Odometry& odom, + const geometry_msgs::AccelWithCovarianceStamped& accel) +{ + // Instantiate a state that can be added to the robot localization estimator + EstimatorState state; + + // Set its time stamp and the state received from the messages + state.time_stamp = odom.header.stamp.toSec(); + + // Get the base frame id from the odom message + if ( base_frame_id_.empty() ) + base_frame_id_ = odom.child_frame_id; + + // Get the world frame id from the odom message + if ( world_frame_id_.empty() ) + world_frame_id_ = odom.header.frame_id; + + // Pose: Position + state.state(StateMemberX) = odom.pose.pose.position.x; + state.state(StateMemberY) = odom.pose.pose.position.y; + state.state(StateMemberZ) = odom.pose.pose.position.z; + + // Pose: Orientation + tf2::Quaternion orientation_quat; + tf2::fromMsg(odom.pose.pose.orientation, orientation_quat); + double roll, pitch, yaw; + RosFilterUtilities::quatToRPY(orientation_quat, roll, pitch, yaw); + + state.state(StateMemberRoll) = roll; + state.state(StateMemberPitch) = pitch; + state.state(StateMemberYaw) = yaw; + + // Pose: Covariance + for ( unsigned int i = 0; i < POSE_SIZE; i++ ) + { + for ( unsigned int j = 0; j < POSE_SIZE; j++ ) + { + state.covariance(POSITION_OFFSET + i, POSITION_OFFSET + j) = odom.pose.covariance[i*POSE_SIZE + j]; + } + } + + // Velocity: Linear + state.state(StateMemberVx) = odom.twist.twist.linear.x; + state.state(StateMemberVy) = odom.twist.twist.linear.y; + state.state(StateMemberVz) = odom.twist.twist.linear.z; + + // Velocity: Angular + state.state(StateMemberVroll) = odom.twist.twist.angular.x; + state.state(StateMemberVpitch) = odom.twist.twist.angular.y; + state.state(StateMemberVyaw) = odom.twist.twist.angular.z; + + // Velocity: Covariance + for ( unsigned int i = 0; i < TWIST_SIZE; i++ ) + { + for ( unsigned int j = 0; j < TWIST_SIZE; j++ ) + { + state.covariance(POSITION_V_OFFSET + i, POSITION_V_OFFSET + j) = odom.twist.covariance[i*TWIST_SIZE + j]; + } + } + + // Acceleration: Linear + state.state(StateMemberAx) = accel.accel.accel.linear.x; + state.state(StateMemberAy) = accel.accel.accel.linear.y; + state.state(StateMemberAz) = accel.accel.accel.linear.z; + + // Acceleration: Angular is not available in state + + // Acceleration: Covariance + for ( unsigned int i = 0; i < ACCELERATION_SIZE; i++ ) + { + for ( unsigned int j = 0; j < ACCELERATION_SIZE; j++ ) + { + state.covariance(POSITION_A_OFFSET + i, POSITION_A_OFFSET + j) = accel.accel.covariance[i*TWIST_SIZE + j]; + } + } + + // Add the state to the buffer, so that we can later interpolate between this and earlier states + estimator_->setState(state); + + return; +} + +bool findAncestorRecursiveYAML(YAML::Node& tree, const std::string& source_frame, const std::string& target_frame) +{ + if ( source_frame == target_frame ) + { + return true; + } + + std::string parent_frame = tree[source_frame]["parent"].Scalar(); + + if ( parent_frame.empty() ) + { + return false; + } + + return findAncestorRecursiveYAML(tree, parent_frame, target_frame); +} + +// Cache, assumption that the tree parent child order does not change over time +static std::map > ancestor_map; +static std::map > descendant_map; +bool findAncestor(const tf2_ros::Buffer& buffer, const std::string& source_frame, const std::string& target_frame) +{ + // Check cache + const std::vector& ancestors = ancestor_map[source_frame]; + if (std::find(ancestors.begin(), ancestors.end(), target_frame) != ancestors.end()) + { + return true; + } + const std::vector& descendants = descendant_map[source_frame]; + if (std::find(descendants.begin(), descendants.end(), target_frame) != descendants.end()) + { + return false; + } + + std::stringstream frames_stream(buffer.allFramesAsYAML()); + YAML::Node frames_yaml = YAML::Load(frames_stream); + + bool target_frame_is_ancestor = findAncestorRecursiveYAML(frames_yaml, source_frame, target_frame); + bool target_frame_is_descendant = findAncestorRecursiveYAML(frames_yaml, target_frame, source_frame); + + // Caching + if (target_frame_is_ancestor) + { + ancestor_map[source_frame].push_back(target_frame); + } + if (target_frame_is_descendant) + { + descendant_map[source_frame].push_back(target_frame); + } + + return target_frame_is_ancestor; +} + + +bool RosRobotLocalizationListener::getState(const double time, + const std::string& frame_id, + Eigen::VectorXd& state, + Eigen::MatrixXd& covariance, + std::string world_frame_id) const +{ + EstimatorState estimator_state; + state.resize(STATE_SIZE); + state.setZero(); + covariance.resize(STATE_SIZE, STATE_SIZE); + covariance.setZero(); + + if ( base_frame_id_.empty() || world_frame_id_.empty() ) + { + if ( estimator_->getSize() == 0 ) + { + ROS_WARN("Ros Robot Localization Listener: The base or world frame id is not set. " + "No odom/accel messages have come in."); + } + else + { + ROS_ERROR("Ros Robot Localization Listener: The base or world frame id is not set. " + "Are the child_frame_id and the header.frame_id in the odom messages set?"); + } + + return false; + } + + if ( estimator_->getState(time, estimator_state) == EstimatorResults::ExtrapolationIntoPast ) + { + ROS_WARN("Ros Robot Localization Listener: A state is requested at a time stamp older than the oldest in the " + "estimator buffer. The result is an extrapolation into the past. Maybe you should increase the buffer " + "size?"); + } + + // If no world_frame_id is specified, we will default to the world frame_id of the received odometry message + if (world_frame_id.empty()) + { + world_frame_id = world_frame_id_; + } + + if ( frame_id == base_frame_id_ && world_frame_id == world_frame_id_ ) + { + // If the state of the base frame is requested and the world frame equals the world frame of the robot_localization + // estimator, we can simply return the state we got from the state estimator + state = estimator_state.state; + covariance = estimator_state.covariance; + return true; + } + + // - - - - - - - - - - - - - - - - - - + // Get the transformation between the requested world frame and the world_frame of the estimator + // - - - - - - - - - - - - - - - - - - + Eigen::Affine3d world_pose_requested_frame; + + // If the requested frame is the same as the tracker, set to identity + if (world_frame_id == world_frame_id_) + { + world_pose_requested_frame.setIdentity(); + } + else + { + geometry_msgs::TransformStamped world_requested_to_world_transform; + try + { + // TODO(reinzor): magic number + world_requested_to_world_transform = tf_buffer_.lookupTransform(world_frame_id, + world_frame_id_, + ros::Time(time), + ros::Duration(0.1)); + + if ( findAncestor(tf_buffer_, world_frame_id, base_frame_id_) ) + { + ROS_ERROR_STREAM("You are trying to get the state with respect to world frame " << world_frame_id << + ", but this frame is a child of robot base frame " << base_frame_id_ << + ", so this doesn't make sense."); + return false; + } + } + catch ( const tf2::TransformException &e ) + { + ROS_WARN_STREAM("Ros Robot Localization Listener: Could not look up transform: " << e.what()); + return false; + } + + // Convert to pose + tf::transformMsgToEigen(world_requested_to_world_transform.transform, world_pose_requested_frame); + } + + // - - - - - - - - - - - - - - - - - - + // Calculate the state of the requested frame from the state of the base frame. + // - - - - - - - - - - - - - - - - - - + + // First get the transform from base to target + geometry_msgs::TransformStamped base_to_target_transform; + try + { + base_to_target_transform = tf_buffer_.lookupTransform(base_frame_id_, + frame_id, + ros::Time(time), + ros::Duration(0.1)); // TODO(reinzor): magic number + + // Check that frame_id is a child of the base frame. If it is not, it does not make sense to request its state. + // Do this after tf lookup, so we know that there is a connection. + if ( !findAncestor(tf_buffer_, frame_id, base_frame_id_) ) + { + ROS_ERROR_STREAM("You are trying to get the state of " << frame_id << ", but this frame is not a child of the " + "base frame: " << base_frame_id_ << "."); + return false; + } + } + catch ( const tf2::TransformException &e ) + { + ROS_WARN_STREAM("Ros Robot Localization Listener: Could not look up transform: " << e.what()); + return false; + } + + // And convert it to an eigen Affine transformation + Eigen::Affine3d target_pose_base; + tf::transformMsgToEigen(base_to_target_transform.transform, target_pose_base); + + // Then convert the base pose to an Eigen Affine transformation + Eigen::Vector3d base_position(estimator_state.state(StateMemberX), + estimator_state.state(StateMemberY), + estimator_state.state(StateMemberZ)); + + Eigen::AngleAxisd roll_angle(estimator_state.state(StateMemberRoll), Eigen::Vector3d::UnitX()); + Eigen::AngleAxisd pitch_angle(estimator_state.state(StateMemberPitch), Eigen::Vector3d::UnitY()); + Eigen::AngleAxisd yaw_angle(estimator_state.state(StateMemberYaw), Eigen::Vector3d::UnitZ()); + + Eigen::Quaterniond base_orientation(yaw_angle * pitch_angle * roll_angle); + + Eigen::Affine3d base_pose(Eigen::Translation3d(base_position) * base_orientation); + + // Now we can calculate the transform from odom to the requested frame (target)... + Eigen::Affine3d target_pose_odom = world_pose_requested_frame * base_pose * target_pose_base; + + // ... and put it in the output state + state(StateMemberX) = target_pose_odom.translation().x(); + state(StateMemberY) = target_pose_odom.translation().y(); + state(StateMemberZ) = target_pose_odom.translation().z(); + + Eigen::Vector3d ypr = target_pose_odom.rotation().eulerAngles(2, 1, 0); + + state(StateMemberRoll) = ypr[2]; + state(StateMemberPitch) = ypr[1]; + state(StateMemberYaw) = ypr[0]; + + // Now let's calculate the twist of the target frame + // First get the base's twist + Twist base_velocity; + Twist target_velocity_base; + base_velocity.linear = Eigen::Vector3d(estimator_state.state(StateMemberVx), + estimator_state.state(StateMemberVy), + estimator_state.state(StateMemberVz)); + base_velocity.angular = Eigen::Vector3d(estimator_state.state(StateMemberVroll), + estimator_state.state(StateMemberVpitch), + estimator_state.state(StateMemberVyaw)); + + // Then calculate the target frame's twist as a result of the base's twist. + /* + * We first calculate the coordinates of the velocity vectors (linear and angular) in the base frame. We have to keep + * in mind that a rotation of the base frame, together with the translational offset of the target frame from the base + * frame, induces a translational velocity of the target frame. + */ + target_velocity_base.linear = base_velocity.linear + base_velocity.angular.cross(target_pose_base.translation()); + target_velocity_base.angular = base_velocity.angular; + + // Now we can transform that to the target frame + Twist target_velocity; + target_velocity.linear = target_pose_base.rotation().transpose() * target_velocity_base.linear; + target_velocity.angular = target_pose_base.rotation().transpose() * target_velocity_base.angular; + + state(StateMemberVx) = target_velocity.linear(0); + state(StateMemberVy) = target_velocity.linear(1); + state(StateMemberVz) = target_velocity.linear(2); + + state(StateMemberVroll) = target_velocity.angular(0); + state(StateMemberVpitch) = target_velocity.angular(1); + state(StateMemberVyaw) = target_velocity.angular(2); + + // Rotate the covariance as well + Eigen::MatrixXd rot_6d(POSE_SIZE, POSE_SIZE); + rot_6d.setIdentity(); + + rot_6d.block(POSITION_OFFSET, POSITION_OFFSET) = target_pose_base.rotation(); + rot_6d.block(ORIENTATION_OFFSET, ORIENTATION_OFFSET) = + target_pose_base.rotation(); + + // Rotate the covariance + covariance.block(POSITION_OFFSET, POSITION_OFFSET) = + rot_6d * estimator_state.covariance.block(POSITION_OFFSET, POSITION_OFFSET) * + rot_6d.transpose(); + + return true; +} + +bool RosRobotLocalizationListener::getState(const ros::Time& ros_time, const std::string& frame_id, + Eigen::VectorXd& state, Eigen::MatrixXd& covariance, + const std::string& world_frame_id) const +{ + double time; + if ( ros_time.isZero() ) + { + ROS_INFO("Ros Robot Localization Listener: State requested at time = zero, returning state at current time"); + time = ros::Time::now().toSec(); + } + else + { + time = ros_time.toSec(); + } + + return getState(time, frame_id, state, covariance, world_frame_id); +} + +const std::string& RosRobotLocalizationListener::getBaseFrameId() const +{ + return base_frame_id_; +} + +const std::string& RosRobotLocalizationListener::getWorldFrameId() const +{ + return world_frame_id_; +} + +} // namespace RobotLocalization + diff --git a/navigations/robot_localization/src/ukf.cpp b/navigations/robot_localization/src/ukf.cpp new file mode 100755 index 0000000..5b55a43 --- /dev/null +++ b/navigations/robot_localization/src/ukf.cpp @@ -0,0 +1,458 @@ +/* + * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include "robot_localization/ukf.h" +#include "robot_localization/filter_common.h" + +#include +#include +#include + +#include + + +namespace RobotLocalization +{ + Ukf::Ukf(std::vector args) : + FilterBase(), // Must initialize filter base! + uncorrected_(true) + { + assert(args.size() == 3); + + double alpha = args[0]; + double kappa = args[1]; + double beta = args[2]; + + size_t sigmaCount = (STATE_SIZE << 1) + 1; + sigmaPoints_.resize(sigmaCount, Eigen::VectorXd(STATE_SIZE)); + + // Prepare constants + lambda_ = alpha * alpha * (STATE_SIZE + kappa) - STATE_SIZE; + + stateWeights_.resize(sigmaCount); + covarWeights_.resize(sigmaCount); + + stateWeights_[0] = lambda_ / (STATE_SIZE + lambda_); + covarWeights_[0] = stateWeights_[0] + (1 - (alpha * alpha) + beta); + sigmaPoints_[0].setZero(); + for (size_t i = 1; i < sigmaCount; ++i) + { + sigmaPoints_[i].setZero(); + stateWeights_[i] = 1 / (2 * (STATE_SIZE + lambda_)); + covarWeights_[i] = stateWeights_[i]; + } + } + + Ukf::~Ukf() + { + } + + void Ukf::correct(const Measurement &measurement) + { + FB_DEBUG("---------------------- Ukf::correct ----------------------\n" << + "State is:\n" << state_ << + "\nMeasurement is:\n" << measurement.measurement_ << + "\nMeasurement covariance is:\n" << measurement.covariance_ << "\n"); + + // In our implementation, it may be that after we call predict once, we call correct + // several times in succession (multiple measurements with different time stamps). In + // that event, the sigma points need to be updated to reflect the current state. + // Throughout prediction and correction, we attempt to maximize efficiency in Eigen. + if (!uncorrected_) + { + generateSigmaPoints(); + } + + // We don't want to update everything, so we need to build matrices that only update + // the measured parts of our state vector + + // First, determine how many state vector values we're updating + std::vector updateIndices; + for (size_t i = 0; i < measurement.updateVector_.size(); ++i) + { + if (measurement.updateVector_[i]) + { + // Handle nan and inf values in measurements + if (std::isnan(measurement.measurement_(i))) + { + FB_DEBUG("Value at index " << i << " was nan. Excluding from update.\n"); + } + else if (std::isinf(measurement.measurement_(i))) + { + FB_DEBUG("Value at index " << i << " was inf. Excluding from update.\n"); + } + else + { + updateIndices.push_back(i); + } + } + } + + FB_DEBUG("Update indices are:\n" << updateIndices << "\n"); + + size_t updateSize = updateIndices.size(); + + // Now set up the relevant matrices + Eigen::VectorXd stateSubset(updateSize); // x (in most literature) + Eigen::VectorXd measurementSubset(updateSize); // z + Eigen::MatrixXd measurementCovarianceSubset(updateSize, updateSize); // R + Eigen::MatrixXd stateToMeasurementSubset(updateSize, STATE_SIZE); // H + Eigen::MatrixXd kalmanGainSubset(STATE_SIZE, updateSize); // K + Eigen::VectorXd innovationSubset(updateSize); // z - Hx + Eigen::VectorXd predictedMeasurement(updateSize); + Eigen::VectorXd sigmaDiff(updateSize); + Eigen::MatrixXd predictedMeasCovar(updateSize, updateSize); + Eigen::MatrixXd crossCovar(STATE_SIZE, updateSize); + + std::vector sigmaPointMeasurements(sigmaPoints_.size(), Eigen::VectorXd(updateSize)); + + stateSubset.setZero(); + measurementSubset.setZero(); + measurementCovarianceSubset.setZero(); + stateToMeasurementSubset.setZero(); + kalmanGainSubset.setZero(); + innovationSubset.setZero(); + predictedMeasurement.setZero(); + predictedMeasCovar.setZero(); + crossCovar.setZero(); + + // Now build the sub-matrices from the full-sized matrices + for (size_t i = 0; i < updateSize; ++i) + { + measurementSubset(i) = measurement.measurement_(updateIndices[i]); + stateSubset(i) = state_(updateIndices[i]); + + for (size_t j = 0; j < updateSize; ++j) + { + measurementCovarianceSubset(i, j) = measurement.covariance_(updateIndices[i], updateIndices[j]); + } + + // Handle negative (read: bad) covariances in the measurement. Rather + // than exclude the measurement or make up a covariance, just take + // the absolute value. + if (measurementCovarianceSubset(i, i) < 0) + { + FB_DEBUG("WARNING: Negative covariance for index " << i << + " of measurement (value is" << measurementCovarianceSubset(i, i) << + "). Using absolute value...\n"); + + measurementCovarianceSubset(i, i) = ::fabs(measurementCovarianceSubset(i, i)); + } + + // If the measurement variance for a given variable is very + // near 0 (as in e-50 or so) and the variance for that + // variable in the covariance matrix is also near zero, then + // the Kalman gain computation will blow up. Really, no + // measurement can be completely without error, so add a small + // amount in that case. + if (measurementCovarianceSubset(i, i) < 1e-9) + { + measurementCovarianceSubset(i, i) = 1e-9; + + FB_DEBUG("WARNING: measurement had very small error covariance for index " << + updateIndices[i] << + ". Adding some noise to maintain filter stability.\n"); + } + } + + // The state-to-measurement function, h, will now be a measurement_size x full_state_size + // matrix, with ones in the (i, i) locations of the values to be updated + for (size_t i = 0; i < updateSize; ++i) + { + stateToMeasurementSubset(i, updateIndices[i]) = 1; + } + + FB_DEBUG("Current state subset is:\n" << stateSubset << + "\nMeasurement subset is:\n" << measurementSubset << + "\nMeasurement covariance subset is:\n" << measurementCovarianceSubset << + "\nState-to-measurement subset is:\n" << stateToMeasurementSubset << "\n"); + + double roll_sum_x {}; + double roll_sum_y {}; + double pitch_sum_x {}; + double pitch_sum_y {}; + double yaw_sum_x {}; + double yaw_sum_y {}; + + // (1) Generate sigma points, use them to generate a predicted measurement + for (size_t sigmaInd = 0; sigmaInd < sigmaPoints_.size(); ++sigmaInd) + { + sigmaPointMeasurements[sigmaInd] = stateToMeasurementSubset * sigmaPoints_[sigmaInd]; + predictedMeasurement.noalias() += stateWeights_[sigmaInd] * sigmaPointMeasurements[sigmaInd]; + + // Euler angle averaging requires special care + for (size_t i = 0; i < updateSize; ++i) + { + if (updateIndices[i] == StateMemberRoll) + { + roll_sum_x += stateWeights_[sigmaInd] * ::cos(sigmaPointMeasurements[sigmaInd](i)); + roll_sum_y += stateWeights_[sigmaInd] * ::sin(sigmaPointMeasurements[sigmaInd](i)); + } + else if (updateIndices[i] == StateMemberPitch) + { + pitch_sum_x += stateWeights_[sigmaInd] * ::cos(sigmaPointMeasurements[sigmaInd](i)); + pitch_sum_y += stateWeights_[sigmaInd] * ::sin(sigmaPointMeasurements[sigmaInd](i)); + } + else if (updateIndices[i] == StateMemberYaw) + { + yaw_sum_x += stateWeights_[sigmaInd] * ::cos(sigmaPointMeasurements[sigmaInd](i)); + yaw_sum_y += stateWeights_[sigmaInd] * ::sin(sigmaPointMeasurements[sigmaInd](i)); + } + } + } + + // Wrap angles in the innovation + for (size_t i = 0; i < updateSize; ++i) + { + if (updateIndices[i] == StateMemberRoll) + { + predictedMeasurement(i) = ::atan2(roll_sum_y, roll_sum_x); + } + else if (updateIndices[i] == StateMemberPitch) + { + predictedMeasurement(i) = ::atan2(pitch_sum_y, pitch_sum_x); + } + else if (updateIndices[i] == StateMemberYaw) + { + predictedMeasurement(i) = ::atan2(yaw_sum_y, yaw_sum_x); + } + } + + // (2) Use the sigma point measurements and predicted measurement to compute a predicted + // measurement covariance matrix P_zz and a state/measurement cross-covariance matrix P_xz. + for (size_t sigmaInd = 0; sigmaInd < sigmaPoints_.size(); ++sigmaInd) + { + sigmaDiff = sigmaPointMeasurements[sigmaInd] - predictedMeasurement; + Eigen::VectorXd sigmaStateDiff = sigmaPoints_[sigmaInd] - state_; + + for (size_t i = 0; i < updateSize; ++i) + { + if (updateIndices[i] == StateMemberRoll || + updateIndices[i] == StateMemberPitch || + updateIndices[i] == StateMemberYaw) + { + sigmaDiff(i) = angles::normalize_angle(sigmaDiff(i)); + sigmaStateDiff(i) = angles::normalize_angle(sigmaStateDiff(i)); + } + } + + predictedMeasCovar.noalias() += covarWeights_[sigmaInd] * (sigmaDiff * sigmaDiff.transpose()); + crossCovar.noalias() += covarWeights_[sigmaInd] * (sigmaStateDiff * sigmaDiff.transpose()); + } + + // (3) Compute the Kalman gain, making sure to use the actual measurement covariance: K = P_xz * (P_zz + R)^-1 + Eigen::MatrixXd invInnovCov = (predictedMeasCovar + measurementCovarianceSubset).inverse(); + kalmanGainSubset = crossCovar * invInnovCov; + + // (4) Apply the gain to the difference between the actual and predicted measurements: x = x + K(z - z_hat) + innovationSubset = (measurementSubset - predictedMeasurement); + + // Wrap angles in the innovation + for (size_t i = 0; i < updateSize; ++i) + { + if (updateIndices[i] == StateMemberRoll || + updateIndices[i] == StateMemberPitch || + updateIndices[i] == StateMemberYaw) + { + innovationSubset(i) = angles::normalize_angle(innovationSubset(i)); + } + } + + // (5) Check Mahalanobis distance of innovation + if (checkMahalanobisThreshold(innovationSubset, invInnovCov, measurement.mahalanobisThresh_)) + { + state_.noalias() += kalmanGainSubset * innovationSubset; + + // (6) Compute the new estimate error covariance P = P - (K * P_zz * K') + estimateErrorCovariance_.noalias() -= (kalmanGainSubset * predictedMeasCovar * kalmanGainSubset.transpose()); + + wrapStateAngles(); + + // Mark that we need to re-compute sigma points for successive corrections + uncorrected_ = false; + + FB_DEBUG("Predicated measurement covariance is:\n" << predictedMeasCovar << + "\nCross covariance is:\n" << crossCovar << + "\nKalman gain subset is:\n" << kalmanGainSubset << + "\nInnovation:\n" << innovationSubset << + "\nCorrected full state is:\n" << state_ << + "\nCorrected full estimate error covariance is:\n" << estimateErrorCovariance_ << + "\n\n---------------------- /Ukf::correct ----------------------\n"); + } + } + + void Ukf::predict(const double referenceTime, const double delta) + { + FB_DEBUG("---------------------- Ukf::predict ----------------------\n" << + "delta is " << delta << + "\nstate is " << state_ << "\n"); + + prepareControl(referenceTime, delta); + + generateSigmaPoints(); + + double roll_sum_x {}; + double roll_sum_y {}; + double pitch_sum_x {}; + double pitch_sum_y {}; + double yaw_sum_x {}; + double yaw_sum_y {}; + + // Sum the weighted sigma points to generate a new state prediction + state_.setZero(); + for (size_t sigmaInd = 0; sigmaInd < sigmaPoints_.size(); ++sigmaInd) + { + // Apply the state transition function to this sigma point + projectSigmaPoint(sigmaPoints_[sigmaInd], delta); + state_.noalias() += stateWeights_[sigmaInd] * sigmaPoints_[sigmaInd]; + + // Euler angle averaging requires special care + roll_sum_x += stateWeights_[sigmaInd] * ::cos(sigmaPoints_[sigmaInd](StateMemberRoll)); + roll_sum_y += stateWeights_[sigmaInd] * ::sin(sigmaPoints_[sigmaInd](StateMemberRoll)); + pitch_sum_x += stateWeights_[sigmaInd] * ::cos(sigmaPoints_[sigmaInd](StateMemberPitch)); + pitch_sum_y += stateWeights_[sigmaInd] * ::sin(sigmaPoints_[sigmaInd](StateMemberPitch)); + yaw_sum_x += stateWeights_[sigmaInd] * ::cos(sigmaPoints_[sigmaInd](StateMemberYaw)); + yaw_sum_y += stateWeights_[sigmaInd] * ::sin(sigmaPoints_[sigmaInd](StateMemberYaw)); + } + + // Recover average Euler angles + state_(StateMemberRoll) = ::atan2(roll_sum_y, roll_sum_x); + state_(StateMemberPitch) = ::atan2(pitch_sum_y, pitch_sum_x); + state_(StateMemberYaw) = ::atan2(yaw_sum_y, yaw_sum_x); + + // Now use the sigma points and the predicted state to compute a predicted covariance + estimateErrorCovariance_.setZero(); + Eigen::VectorXd sigmaDiff(STATE_SIZE); + for (size_t sigmaInd = 0; sigmaInd < sigmaPoints_.size(); ++sigmaInd) + { + sigmaDiff = (sigmaPoints_[sigmaInd] - state_); + + sigmaDiff(StateMemberRoll) = angles::normalize_angle(sigmaDiff(StateMemberRoll)); + sigmaDiff(StateMemberPitch) = angles::normalize_angle(sigmaDiff(StateMemberPitch)); + sigmaDiff(StateMemberYaw) = angles::normalize_angle(sigmaDiff(StateMemberYaw)); + + estimateErrorCovariance_.noalias() += covarWeights_[sigmaInd] * (sigmaDiff * sigmaDiff.transpose()); + } + + // Not strictly in the theoretical UKF formulation, but necessary here + // to ensure that we actually incorporate the processNoiseCovariance_ + Eigen::MatrixXd *processNoiseCovariance = &processNoiseCovariance_; + + if (useDynamicProcessNoiseCovariance_) + { + computeDynamicProcessNoiseCovariance(state_, delta); + processNoiseCovariance = &dynamicProcessNoiseCovariance_; + } + + estimateErrorCovariance_.noalias() += delta * (*processNoiseCovariance); + + // Keep the angles bounded + wrapStateAngles(); + + // Mark that we can keep these sigma points + uncorrected_ = true; + + FB_DEBUG("Predicted state is:\n" << state_ << + "\nPredicted estimate error covariance is:\n" << estimateErrorCovariance_ << + "\n\n--------------------- /Ukf::predict ----------------------\n"); + } + + void Ukf::generateSigmaPoints() + { + // Take the square root of a small fraction of the estimateErrorCovariance_ using LL' decomposition + weightedCovarSqrt_ = ((static_cast(STATE_SIZE) + lambda_) * estimateErrorCovariance_).llt().matrixL(); + + // Compute sigma points + + // First sigma point is the current state + sigmaPoints_[0] = state_; + + // Next STATE_SIZE sigma points are state + weightedCovarSqrt_[ith column] + // STATE_SIZE sigma points after that are state - weightedCovarSqrt_[ith column] + for (size_t sigmaInd = 0; sigmaInd < STATE_SIZE; ++sigmaInd) + { + sigmaPoints_[sigmaInd + 1] = state_ + weightedCovarSqrt_.col(sigmaInd); + sigmaPoints_[sigmaInd + 1 + STATE_SIZE] = state_ - weightedCovarSqrt_.col(sigmaInd); + } + } + + void Ukf::projectSigmaPoint(Eigen::VectorXd& sigmaPoint, double delta) + { + double roll = sigmaPoint(StateMemberRoll); + double pitch = sigmaPoint(StateMemberPitch); + double yaw = sigmaPoint(StateMemberYaw); + + // We'll need these trig calculations a lot. + double sp = ::sin(pitch); + double cp = ::cos(pitch); + double cpi = 1.0 / cp; + double tp = sp * cpi; + + double sr = ::sin(roll); + double cr = ::cos(roll); + + double sy = ::sin(yaw); + double cy = ::cos(yaw); + + // Prepare the transfer function + transferFunction_(StateMemberX, StateMemberVx) = cy * cp * delta; + transferFunction_(StateMemberX, StateMemberVy) = (cy * sp * sr - sy * cr) * delta; + transferFunction_(StateMemberX, StateMemberVz) = (cy * sp * cr + sy * sr) * delta; + transferFunction_(StateMemberX, StateMemberAx) = 0.5 * transferFunction_(StateMemberX, StateMemberVx) * delta; + transferFunction_(StateMemberX, StateMemberAy) = 0.5 * transferFunction_(StateMemberX, StateMemberVy) * delta; + transferFunction_(StateMemberX, StateMemberAz) = 0.5 * transferFunction_(StateMemberX, StateMemberVz) * delta; + transferFunction_(StateMemberY, StateMemberVx) = sy * cp * delta; + transferFunction_(StateMemberY, StateMemberVy) = (sy * sp * sr + cy * cr) * delta; + transferFunction_(StateMemberY, StateMemberVz) = (sy * sp * cr - cy * sr) * delta; + transferFunction_(StateMemberY, StateMemberAx) = 0.5 * transferFunction_(StateMemberY, StateMemberVx) * delta; + transferFunction_(StateMemberY, StateMemberAy) = 0.5 * transferFunction_(StateMemberY, StateMemberVy) * delta; + transferFunction_(StateMemberY, StateMemberAz) = 0.5 * transferFunction_(StateMemberY, StateMemberVz) * delta; + transferFunction_(StateMemberZ, StateMemberVx) = -sp * delta; + transferFunction_(StateMemberZ, StateMemberVy) = cp * sr * delta; + transferFunction_(StateMemberZ, StateMemberVz) = cp * cr * delta; + transferFunction_(StateMemberZ, StateMemberAx) = 0.5 * transferFunction_(StateMemberZ, StateMemberVx) * delta; + transferFunction_(StateMemberZ, StateMemberAy) = 0.5 * transferFunction_(StateMemberZ, StateMemberVy) * delta; + transferFunction_(StateMemberZ, StateMemberAz) = 0.5 * transferFunction_(StateMemberZ, StateMemberVz) * delta; + transferFunction_(StateMemberRoll, StateMemberVroll) = delta; + transferFunction_(StateMemberRoll, StateMemberVpitch) = sr * tp * delta; + transferFunction_(StateMemberRoll, StateMemberVyaw) = cr * tp * delta; + transferFunction_(StateMemberPitch, StateMemberVpitch) = cr * delta; + transferFunction_(StateMemberPitch, StateMemberVyaw) = -sr * delta; + transferFunction_(StateMemberYaw, StateMemberVpitch) = sr * cpi * delta; + transferFunction_(StateMemberYaw, StateMemberVyaw) = cr * cpi * delta; + transferFunction_(StateMemberVx, StateMemberAx) = delta; + transferFunction_(StateMemberVy, StateMemberAy) = delta; + transferFunction_(StateMemberVz, StateMemberAz) = delta; + + sigmaPoint.applyOnTheLeft(transferFunction_); + } +} // namespace RobotLocalization diff --git a/navigations/robot_localization/src/ukf_localization_node.cpp b/navigations/robot_localization/src/ukf_localization_node.cpp new file mode 100755 index 0000000..6f1d99e --- /dev/null +++ b/navigations/robot_localization/src/ukf_localization_node.cpp @@ -0,0 +1,57 @@ +/* + * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include "robot_localization/ros_filter_types.h" + +#include + +#include +#include + +int main(int argc, char **argv) +{ + ros::init(argc, argv, "ukf_navigation_node"); + ros::NodeHandle nh; + ros::NodeHandle nhLocal("~"); + + std::vector args(3, 0); + + nhLocal.param("alpha", args[0], 0.001); + nhLocal.param("kappa", args[1], 0.0); + nhLocal.param("beta", args[2], 2.0); + + RobotLocalization::RosUkf ukf(nh, nhLocal, args); + ukf.initialize(); + ros::spin(); + + return EXIT_SUCCESS; +} diff --git a/navigations/robot_localization/src/ukf_localization_nodelet.cpp b/navigations/robot_localization/src/ukf_localization_nodelet.cpp new file mode 100755 index 0000000..f33e1fd --- /dev/null +++ b/navigations/robot_localization/src/ukf_localization_nodelet.cpp @@ -0,0 +1,71 @@ +/* + * Copyright (c) 2017 Simon Gene Gottlieb + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include "robot_localization/ros_filter_types.h" + +#include +#include +#include + +#include +#include + +namespace RobotLocalization +{ + +class UkfNodelet : public nodelet::Nodelet +{ +private: + std::unique_ptr ukf; + +public: + virtual void onInit() + { + NODELET_DEBUG("Initializing nodelet..."); + + ros::NodeHandle nh = getNodeHandle(); + ros::NodeHandle nh_priv = getPrivateNodeHandle(); + + std::vector args(3, 0); + + nh_priv.param("alpha", args[0], 0.001); + nh_priv.param("kappa", args[1], 0.0); + nh_priv.param("beta", args[2], 2.0); + + ukf = std::make_unique(nh, nh_priv, getName(), args); + ukf->initialize(); + } +}; + +} // namespace RobotLocalization + +PLUGINLIB_EXPORT_CLASS(RobotLocalization::UkfNodelet, nodelet::Nodelet); diff --git a/navigations/robot_localization/srv/FromLL.srv b/navigations/robot_localization/srv/FromLL.srv new file mode 100755 index 0000000..60c9d54 --- /dev/null +++ b/navigations/robot_localization/srv/FromLL.srv @@ -0,0 +1,3 @@ +geographic_msgs/GeoPoint ll_point +--- +geometry_msgs/Point map_point diff --git a/navigations/robot_localization/srv/GetState.srv b/navigations/robot_localization/srv/GetState.srv new file mode 100755 index 0000000..3d9bb86 --- /dev/null +++ b/navigations/robot_localization/srv/GetState.srv @@ -0,0 +1,8 @@ +time time_stamp +string frame_id +--- +# State vector: x, y, z, roll, pitch, yaw, vx, vy, vz, vroll, vpitch, vyaw, ax, ay, az +float64[15] state + +# Covariance matrix in row-major order +float64[225] covariance diff --git a/navigations/robot_localization/srv/SetDatum.srv b/navigations/robot_localization/srv/SetDatum.srv new file mode 100755 index 0000000..25cbe4a --- /dev/null +++ b/navigations/robot_localization/srv/SetDatum.srv @@ -0,0 +1,2 @@ +geographic_msgs/GeoPose geo_pose +--- diff --git a/navigations/robot_localization/srv/SetPose.srv b/navigations/robot_localization/srv/SetPose.srv new file mode 100755 index 0000000..7089d1a --- /dev/null +++ b/navigations/robot_localization/srv/SetPose.srv @@ -0,0 +1,2 @@ +geometry_msgs/PoseWithCovarianceStamped pose +--- diff --git a/navigations/robot_localization/srv/SetUTMZone.srv b/navigations/robot_localization/srv/SetUTMZone.srv new file mode 100755 index 0000000..c96c3c4 --- /dev/null +++ b/navigations/robot_localization/srv/SetUTMZone.srv @@ -0,0 +1,4 @@ +# Set an UTM zone navsat_transform should stick to. +# Example: 31U +string utm_zone +--- diff --git a/navigations/robot_localization/srv/ToLL.srv b/navigations/robot_localization/srv/ToLL.srv new file mode 100755 index 0000000..e99723d --- /dev/null +++ b/navigations/robot_localization/srv/ToLL.srv @@ -0,0 +1,3 @@ +geometry_msgs/Point map_point +--- +geographic_msgs/GeoPoint ll_point diff --git a/navigations/robot_localization/srv/ToggleFilterProcessing.srv b/navigations/robot_localization/srv/ToggleFilterProcessing.srv new file mode 100755 index 0000000..01f8bcd --- /dev/null +++ b/navigations/robot_localization/srv/ToggleFilterProcessing.srv @@ -0,0 +1,3 @@ +bool on +--- +bool status diff --git a/navigations/robot_localization/test/record_all_stats.sh b/navigations/robot_localization/test/record_all_stats.sh new file mode 100755 index 0000000..9a39760 --- /dev/null +++ b/navigations/robot_localization/test/record_all_stats.sh @@ -0,0 +1,9 @@ +#!/bin/bash + +./stat_recorder.sh test_ekf_localization_node_bag1.test $1/ekf1.txt +./stat_recorder.sh test_ekf_localization_node_bag2.test $1/ekf2.txt +./stat_recorder.sh test_ekf_localization_node_bag3.test $1/ekf3.txt + +./stat_recorder.sh test_ukf_localization_node_bag1.test $1/ukf1.txt +./stat_recorder.sh test_ukf_localization_node_bag2.test $1/ukf2.txt +./stat_recorder.sh test_ukf_localization_node_bag3.test $1/ukf3.txt diff --git a/navigations/robot_localization/test/stat_recorder.sh b/navigations/robot_localization/test/stat_recorder.sh new file mode 100755 index 0000000..afc236c --- /dev/null +++ b/navigations/robot_localization/test/stat_recorder.sh @@ -0,0 +1,18 @@ +#!/bin/bash + +rm $2 +echo "x = [" > $2 + +i="0" + +while [ $i -lt 30 ] +do +rostest robot_localization $1 output_final_position:=true output_location:=$2 +i=$[$i+1] +sleep 3 +done + +echo "]" >> $2 +echo "mean(x)" >> $2 +echo "sqrt(sum((4 * std(x)).^2))" >> $2 + diff --git a/navigations/robot_localization/test/test1.bag b/navigations/robot_localization/test/test1.bag new file mode 100755 index 0000000..565f14c Binary files /dev/null and b/navigations/robot_localization/test/test1.bag differ diff --git a/navigations/robot_localization/test/test2.bag b/navigations/robot_localization/test/test2.bag new file mode 100755 index 0000000..0559965 Binary files /dev/null and b/navigations/robot_localization/test/test2.bag differ diff --git a/navigations/robot_localization/test/test3.bag b/navigations/robot_localization/test/test3.bag new file mode 100755 index 0000000..6e139cb Binary files /dev/null and b/navigations/robot_localization/test/test3.bag differ diff --git a/navigations/robot_localization/test/test_ekf.cpp b/navigations/robot_localization/test/test_ekf.cpp new file mode 100755 index 0000000..63f8b67 --- /dev/null +++ b/navigations/robot_localization/test/test_ekf.cpp @@ -0,0 +1,135 @@ +/* + * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include "robot_localization/ros_filter_types.h" + +#include + +#include +#include + +using RobotLocalization::Ekf; +using RobotLocalization::RosEkf; +using RobotLocalization::STATE_SIZE; + +class RosEkfPassThrough : public RosEkf +{ + public: + RosEkfPassThrough() : RosEkf(ros::NodeHandle(), ros::NodeHandle("~")) + { + } + + Ekf &getFilter() + { + return filter_; + } +}; + +TEST(EkfTest, Measurements) +{ + RosEkfPassThrough ekf; + + Eigen::MatrixXd initialCovar(15, 15); + initialCovar.setIdentity(); + initialCovar *= 0.5; + ekf.getFilter().setEstimateErrorCovariance(initialCovar); + + Eigen::VectorXd measurement(STATE_SIZE); + measurement.setIdentity(); + for (size_t i = 0; i < STATE_SIZE; ++i) + { + measurement[i] = i * 0.01 * STATE_SIZE; + } + + Eigen::MatrixXd measurementCovariance(STATE_SIZE, STATE_SIZE); + measurementCovariance.setIdentity(); + for (size_t i = 0; i < STATE_SIZE; ++i) + { + measurementCovariance(i, i) = 1e-9; + } + + std::vector updateVector(STATE_SIZE, true); + + // Ensure that measurements are being placed in the queue correctly + ros::Time time; + time.fromSec(1000); + ekf.enqueueMeasurement("odom0", + measurement, + measurementCovariance, + updateVector, + std::numeric_limits::max(), + time); + + ekf.integrateMeasurements(ros::Time(1001)); + + EXPECT_EQ(ekf.getFilter().getState(), measurement); + EXPECT_EQ(ekf.getFilter().getEstimateErrorCovariance(), measurementCovariance); + + ekf.getFilter().setEstimateErrorCovariance(initialCovar); + + // Now fuse another measurement and check the output. + // We know what the filter's state should be when + // this is complete, so we'll check the difference and + // make sure it's suitably small. + Eigen::VectorXd measurement2 = measurement; + + measurement2 *= 2.0; + + for (size_t i = 0; i < STATE_SIZE; ++i) + { + measurementCovariance(i, i) = 1e-9; + } + + time.fromSec(1002); + ekf.enqueueMeasurement("odom0", + measurement2, + measurementCovariance, + updateVector, + std::numeric_limits::max(), + time); + + ekf.integrateMeasurements(ros::Time(1003)); + + measurement = measurement2.eval() - ekf.getFilter().getState(); + for (size_t i = 0; i < STATE_SIZE; ++i) + { + EXPECT_LT(::fabs(measurement[i]), 0.001); + } +} + +int main(int argc, char **argv) +{ + ros::init(argc, argv, "ekf"); + + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/navigations/robot_localization/test/test_ekf.test b/navigations/robot_localization/test/test_ekf.test new file mode 100755 index 0000000..92f8235 --- /dev/null +++ b/navigations/robot_localization/test/test_ekf.test @@ -0,0 +1,7 @@ + + + + + + + diff --git a/navigations/robot_localization/test/test_ekf_localization_node_bag1.test b/navigations/robot_localization/test/test_ekf_localization_node_bag1.test new file mode 100755 index 0000000..8d37e92 --- /dev/null +++ b/navigations/robot_localization/test/test_ekf_localization_node_bag1.test @@ -0,0 +1,105 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [false, false, false, + false, false, false, + true, true, true, + false, false, false, + false, false, false] + + [false, false, false, + true, true, true, + false, false, false, + true, true, false, + true, true, true] + + + + + + + + + + + + + + + + + + [0.05, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0.05, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0.06, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0.03, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0.03, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0.06, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0.025, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0.025, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0.04, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.02, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.015] + + [1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9] + + + + + + + + + + + + + diff --git a/navigations/robot_localization/test/test_ekf_localization_node_bag2.test b/navigations/robot_localization/test/test_ekf_localization_node_bag2.test new file mode 100755 index 0000000..5ea3285 --- /dev/null +++ b/navigations/robot_localization/test/test_ekf_localization_node_bag2.test @@ -0,0 +1,85 @@ + + + + + + + + + + + + + + + + + + + + + + + + + [false, false, false, + false, false, false, + true, true, true, + false, false, true, + false, false, false] + + [false, false, false, + true, true, true, + false, false, false, + true, true, true, + true, true, true] + + + + + + + [0.03, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0.03, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0.4, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0.03, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0.03, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0.06, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0.025, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0.025, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0.05, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.002, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.002, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.004, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01] + + [1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9] + + + + + + + + + + + + + diff --git a/navigations/robot_localization/test/test_ekf_localization_node_bag3.test b/navigations/robot_localization/test/test_ekf_localization_node_bag3.test new file mode 100755 index 0000000..eb0c6bf --- /dev/null +++ b/navigations/robot_localization/test/test_ekf_localization_node_bag3.test @@ -0,0 +1,69 @@ + + + + + + + + + + + + + + + + + + + + + + + + + [false, false, true, + false, false, false, + true, true, false, + false, false, true, + false, false, false] + + [false, false, false, + true, true, true, + false, false, false, + true, true, true, + false, false, false] + + + + + + + [0.03, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.03, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.4, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.03, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.03, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.025, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.025, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.002, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.002, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.004, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01] + + + + + + + + + + + + + diff --git a/navigations/robot_localization/test/test_ekf_localization_node_interfaces.cpp b/navigations/robot_localization/test/test_ekf_localization_node_interfaces.cpp new file mode 100755 index 0000000..bf501cd --- /dev/null +++ b/navigations/robot_localization/test/test_ekf_localization_node_interfaces.cpp @@ -0,0 +1,1075 @@ +/* + * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include "robot_localization/SetPose.h" + +#include +#include +#include +#include +#include + +#include +#include + +#include +#include + +nav_msgs::Odometry filtered_; + +bool stateUpdated_; + +void resetFilter() +{ + ros::NodeHandle nh; + ros::ServiceClient client = nh.serviceClient("/set_pose"); + + robot_localization::SetPose setPose; + setPose.request.pose.pose.pose.orientation.w = 1; + setPose.request.pose.header.frame_id = "odom"; + for (size_t ind = 0; ind < 36; ind+=7) + { + setPose.request.pose.pose.covariance[ind] = 1e-6; + } + + setPose.request.pose.header.stamp = ros::Time::now(); + client.call(setPose); + setPose.request.pose.header.seq++; + ros::spinOnce(); + ros::Duration(0.01).sleep(); + stateUpdated_ = false; + + double deltaX = 0.0; + double deltaY = 0.0; + double deltaZ = 0.0; + + while (!stateUpdated_ || ::sqrt(deltaX * deltaX + deltaY * deltaY + deltaZ * deltaZ) > 0.1) + { + ros::spinOnce(); + ros::Duration(0.01).sleep(); + + deltaX = filtered_.pose.pose.position.x - setPose.request.pose.pose.pose.position.x; + deltaY = filtered_.pose.pose.position.y - setPose.request.pose.pose.pose.position.y; + deltaZ = filtered_.pose.pose.position.z - setPose.request.pose.pose.pose.position.z; + } + + EXPECT_LT(::sqrt(deltaX * deltaX + deltaY * deltaY + deltaZ * deltaZ), 0.1); +} + +void filterCallback(const nav_msgs::OdometryConstPtr &msg) +{ + filtered_ = *msg; + stateUpdated_ = true; +} + +TEST(InterfacesTest, OdomPoseBasicIO) +{ + stateUpdated_ = false; + + ros::NodeHandle nh; + ros::Publisher odomPub = nh.advertise("/odom_input0", 5); + ros::Subscriber filteredSub = nh.subscribe("/odometry/filtered", 1, &filterCallback); + + nav_msgs::Odometry odom; + odom.pose.pose.position.x = 20.0; + odom.pose.pose.position.y = 10.0; + odom.pose.pose.position.z = -40.0; + + odom.pose.covariance[0] = 2.0; + odom.pose.covariance[7] = 2.0; + odom.pose.covariance[14] = 2.0; + + odom.header.frame_id = "odom"; + odom.child_frame_id = "base_link"; + + ros::Rate loopRate(50); + for (size_t i = 0; i < 50; ++i) + { + odom.header.stamp = ros::Time::now(); + odomPub.publish(odom); + ros::spinOnce(); + + loopRate.sleep(); + + odom.header.seq++; + } + + // Now check the values from the callback + EXPECT_LT(::fabs(filtered_.pose.pose.position.x - odom.pose.pose.position.x), 0.01); + EXPECT_LT(::fabs(filtered_.pose.pose.position.y), 0.01); // Configuration for this variable for this sensor is false + EXPECT_LT(::fabs(filtered_.pose.pose.position.z - odom.pose.pose.position.z), 0.01); + + EXPECT_LT(filtered_.pose.covariance[0], 0.5); + EXPECT_LT(filtered_.pose.covariance[7], 0.25); // Configuration for this variable for this sensor is false + EXPECT_LT(filtered_.pose.covariance[14], 0.5); + + resetFilter(); +} + +TEST(InterfacesTest, OdomTwistBasicIO) +{ + ros::NodeHandle nh; + ros::Publisher odomPub = nh.advertise("/odom_input2", 5); + ros::Subscriber filteredSub = nh.subscribe("/odometry/filtered", 1, &filterCallback); + + nav_msgs::Odometry odom; + odom.twist.twist.linear.x = 5.0; + odom.twist.twist.linear.y = 0.0; + odom.twist.twist.linear.z = 0.0; + odom.twist.twist.angular.x = 0.0; + odom.twist.twist.angular.y = 0.0; + odom.twist.twist.angular.z = 0.0; + + for (size_t ind = 0; ind < 36; ind+=7) + { + odom.twist.covariance[ind] = 1e-6; + } + + odom.header.frame_id = "odom"; + odom.child_frame_id = "base_link"; + + ros::Rate loopRate(20); + for (size_t i = 0; i < 400; ++i) + { + odom.header.stamp = ros::Time::now(); + odomPub.publish(odom); + ros::spinOnce(); + + loopRate.sleep(); + + odom.header.seq++; + } + ros::spinOnce(); + + EXPECT_LT(::fabs(filtered_.twist.twist.linear.x - odom.twist.twist.linear.x), 0.1); + EXPECT_LT(::fabs(filtered_.pose.pose.position.x - 100.0), 2.0); + + resetFilter(); + + odom.twist.twist.linear.x = 0.0; + odom.twist.twist.linear.y = 5.0; + + loopRate = ros::Rate(20); + for (size_t i = 0; i < 200; ++i) + { + odom.header.stamp = ros::Time::now(); + odomPub.publish(odom); + ros::spinOnce(); + + loopRate.sleep(); + + odom.header.seq++; + } + ros::spinOnce(); + + EXPECT_LT(::fabs(filtered_.twist.twist.linear.y - odom.twist.twist.linear.y), 0.1); + EXPECT_LT(::fabs(filtered_.pose.pose.position.y - 50.0), 1.0); + + resetFilter(); + + odom.twist.twist.linear.y = 0.0; + odom.twist.twist.linear.z = 5.0; + + loopRate = ros::Rate(20); + for (size_t i = 0; i < 100; ++i) + { + odom.header.stamp = ros::Time::now(); + odomPub.publish(odom); + ros::spinOnce(); + + loopRate.sleep(); + + odom.header.seq++; + } + ros::spinOnce(); + + EXPECT_LT(::fabs(filtered_.twist.twist.linear.z - odom.twist.twist.linear.z), 0.1); + EXPECT_LT(::fabs(filtered_.pose.pose.position.z - 25.0), 1.0); + + resetFilter(); + + odom.twist.twist.linear.z = 0.0; + odom.twist.twist.linear.x = 1.0; + odom.twist.twist.angular.z = (M_PI/2) / (100.0 * 0.05); + + loopRate = ros::Rate(20); + for (size_t i = 0; i < 100; ++i) + { + odom.header.stamp = ros::Time::now(); + odomPub.publish(odom); + ros::spinOnce(); + + loopRate.sleep(); + + odom.header.seq++; + } + ros::spinOnce(); + + EXPECT_LT(::fabs(filtered_.twist.twist.linear.x - odom.twist.twist.linear.x), 0.1); + EXPECT_LT(::fabs(filtered_.twist.twist.angular.z - odom.twist.twist.angular.z), 0.1); + EXPECT_LT(::fabs(filtered_.pose.pose.position.x - filtered_.pose.pose.position.y), 0.5); + + resetFilter(); + + odom.twist.twist.linear.x = 0.0; + odom.twist.twist.angular.z = 0.0; + odom.twist.twist.angular.x = -(M_PI/2) / (100.0 * 0.05); + + // First, roll the vehicle on its side + loopRate = ros::Rate(20); + for (size_t i = 0; i < 100; ++i) + { + odom.header.stamp = ros::Time::now(); + odomPub.publish(odom); + ros::spinOnce(); + + loopRate.sleep(); + + odom.header.seq++; + } + ros::spinOnce(); + + odom.twist.twist.angular.x = 0.0; + odom.twist.twist.angular.y = (M_PI/2) / (100.0 * 0.05); + + // Now, pitch it down (positive pitch velocity in vehicle frame) + loopRate = ros::Rate(20); + for (size_t i = 0; i < 100; ++i) + { + odom.header.stamp = ros::Time::now(); + odomPub.publish(odom); + ros::spinOnce(); + + loopRate.sleep(); + + odom.header.seq++; + } + ros::spinOnce(); + + odom.twist.twist.angular.y = 0.0; + odom.twist.twist.linear.x = 3.0; + + // We should now be on our side and facing -Y. Move forward in + // the vehicle frame X direction, and make sure Y decreases in + // the world frame. + loopRate = ros::Rate(20); + for (size_t i = 0; i < 100; ++i) + { + odom.header.stamp = ros::Time::now(); + odomPub.publish(odom); + ros::spinOnce(); + + loopRate.sleep(); + + odom.header.seq++; + } + ros::spinOnce(); + + EXPECT_LT(::fabs(filtered_.twist.twist.linear.x - odom.twist.twist.linear.x), 0.1); + EXPECT_LT(::fabs(filtered_.pose.pose.position.y + 15), 1.0); + + resetFilter(); +} + +TEST(InterfacesTest, PoseBasicIO) +{ + ros::NodeHandle nh; + ros::Publisher posePub = nh.advertise("/pose_input0", 5); + ros::Subscriber filteredSub = nh.subscribe("/odometry/filtered", 1, &filterCallback); + + geometry_msgs::PoseWithCovarianceStamped pose; + pose.pose.pose.position.x = 20.0; + pose.pose.pose.position.y = 10.0; + pose.pose.pose.position.z = -40.0; + pose.pose.pose.orientation.x = 0; + pose.pose.pose.orientation.y = 0; + pose.pose.pose.orientation.z = 0; + pose.pose.pose.orientation.w = 1; + + for (size_t ind = 0; ind < 36; ind+=7) + { + pose.pose.covariance[ind] = 1e-6; + } + + pose.header.frame_id = "odom"; + + ros::Rate loopRate = ros::Rate(50); + for (size_t i = 0; i < 50; ++i) + { + pose.header.stamp = ros::Time::now(); + posePub.publish(pose); + ros::spinOnce(); + + loopRate.sleep(); + + pose.header.seq++; + } + + // Now check the values from the callback + EXPECT_LT(::fabs(filtered_.pose.pose.position.x - pose.pose.pose.position.x), 0.1); + EXPECT_LT(::fabs(filtered_.pose.pose.position.y), 0.1); // Configuration for this variable for this sensor is false + EXPECT_LT(::fabs(filtered_.pose.pose.position.z - pose.pose.pose.position.z), 0.1); + + EXPECT_LT(filtered_.pose.covariance[0], 0.5); + EXPECT_LT(filtered_.pose.covariance[7], 0.25); // Configuration for this variable for this sensor is false + EXPECT_LT(filtered_.pose.covariance[14], 0.5); + + resetFilter(); +} + +TEST(InterfacesTest, TwistBasicIO) +{ + ros::NodeHandle nh; + ros::Publisher twistPub = nh.advertise("/twist_input0", 5); + ros::Subscriber filteredSub = nh.subscribe("/odometry/filtered", 1, &filterCallback); + + geometry_msgs::TwistWithCovarianceStamped twist; + twist.twist.twist.linear.x = 5.0; + twist.twist.twist.linear.y = 0; + twist.twist.twist.linear.z = 0; + twist.twist.twist.angular.x = 0; + twist.twist.twist.angular.y = 0; + twist.twist.twist.angular.z = 0; + + for (size_t ind = 0; ind < 36; ind+=7) + { + twist.twist.covariance[ind] = 1e-6; + } + + twist.header.frame_id = "base_link"; + + ros::Rate loopRate = ros::Rate(20); + for (size_t i = 0; i < 400; ++i) + { + twist.header.stamp = ros::Time::now(); + twistPub.publish(twist); + ros::spinOnce(); + + loopRate.sleep(); + + twist.header.seq++; + } + ros::spinOnce(); + + EXPECT_LT(::fabs(filtered_.twist.twist.linear.x - twist.twist.twist.linear.x), 0.1); + EXPECT_LT(::fabs(filtered_.pose.pose.position.x - 100.0), 2.0); + + resetFilter(); + + twist.twist.twist.linear.x = 0.0; + twist.twist.twist.linear.y = 5.0; + + loopRate = ros::Rate(20); + for (size_t i = 0; i < 200; ++i) + { + twist.header.stamp = ros::Time::now(); + twistPub.publish(twist); + ros::spinOnce(); + + loopRate.sleep(); + + twist.header.seq++; + } + ros::spinOnce(); + + EXPECT_LT(::fabs(filtered_.twist.twist.linear.y - twist.twist.twist.linear.y), 0.1); + EXPECT_LT(::fabs(filtered_.pose.pose.position.y - 50.0), 1.0); + + resetFilter(); + + twist.twist.twist.linear.y = 0.0; + twist.twist.twist.linear.z = 5.0; + + loopRate = ros::Rate(20); + for (size_t i = 0; i < 100; ++i) + { + twist.header.stamp = ros::Time::now(); + twistPub.publish(twist); + ros::spinOnce(); + + loopRate.sleep(); + + twist.header.seq++; + } + ros::spinOnce(); + + EXPECT_LT(::fabs(filtered_.twist.twist.linear.z - twist.twist.twist.linear.z), 0.1); + EXPECT_LT(::fabs(filtered_.pose.pose.position.z - 25.0), 1.0); + + resetFilter(); + + twist.twist.twist.linear.z = 0.0; + twist.twist.twist.linear.x = 1.0; + twist.twist.twist.angular.z = (M_PI/2) / (100.0 * 0.05); + + loopRate = ros::Rate(20); + for (size_t i = 0; i < 100; ++i) + { + twist.header.stamp = ros::Time::now(); + twistPub.publish(twist); + ros::spinOnce(); + + loopRate.sleep(); + + twist.header.seq++; + } + ros::spinOnce(); + + EXPECT_LT(::fabs(filtered_.twist.twist.linear.x - twist.twist.twist.linear.x), 0.1); + EXPECT_LT(::fabs(filtered_.twist.twist.angular.z - twist.twist.twist.angular.z), 0.1); + EXPECT_LT(::fabs(filtered_.pose.pose.position.x - filtered_.pose.pose.position.y), 0.5); + + resetFilter(); + + twist.twist.twist.linear.x = 0.0; + twist.twist.twist.angular.z = 0.0; + twist.twist.twist.angular.x = -(M_PI/2) / (100.0 * 0.05); + + // First, roll the vehicle on its side + loopRate = ros::Rate(20); + for (size_t i = 0; i < 100; ++i) + { + twist.header.stamp = ros::Time::now(); + twistPub.publish(twist); + ros::spinOnce(); + + loopRate.sleep(); + + twist.header.seq++; + } + ros::spinOnce(); + + twist.twist.twist.angular.x = 0.0; + twist.twist.twist.angular.y = (M_PI/2) / (100.0 * 0.05); + + // Now, pitch it down (positive pitch velocity in vehicle frame) + loopRate = ros::Rate(20); + for (size_t i = 0; i < 100; ++i) + { + twist.header.stamp = ros::Time::now(); + twistPub.publish(twist); + ros::spinOnce(); + + loopRate.sleep(); + + twist.header.seq++; + } + ros::spinOnce(); + + twist.twist.twist.angular.y = 0.0; + twist.twist.twist.linear.x = 3.0; + + // We should now be on our side and facing -Y. Move forward in + // the vehicle frame X direction, and make sure Y decreases in + // the world frame. + loopRate = ros::Rate(20); + for (size_t i = 0; i < 100; ++i) + { + twist.header.stamp = ros::Time::now(); + twistPub.publish(twist); + ros::spinOnce(); + + loopRate.sleep(); + + twist.header.seq++; + } + ros::spinOnce(); + + EXPECT_LT(::fabs(filtered_.twist.twist.linear.x - twist.twist.twist.linear.x), 0.1); + EXPECT_LT(::fabs(filtered_.pose.pose.position.y + 15), 1.0); + + resetFilter(); +} + +TEST(InterfacesTest, ImuPoseBasicIO) +{ + ros::NodeHandle nh; + ros::Publisher imuPub = nh.advertise("/imu_input0", 5); + ros::Subscriber filteredSub = nh.subscribe("/odometry/filtered", 1, &filterCallback); + + sensor_msgs::Imu imu; + tf2::Quaternion quat; + quat.setRPY(M_PI/4, -M_PI/4, M_PI/2); + imu.orientation = tf2::toMsg(quat); + + for (size_t ind = 0; ind < 9; ind+=4) + { + imu.orientation_covariance[ind] = 1e-6; + } + + imu.header.frame_id = "base_link"; + + // Make sure the pose reset worked. Test will timeout + // if this fails. + ros::Rate loopRate(50); + for (size_t i = 0; i < 50; ++i) + { + imu.header.stamp = ros::Time::now(); + imuPub.publish(imu); + ros::spinOnce(); + + loopRate.sleep(); + + imu.header.seq++; + } + + // Now check the values from the callback + tf2::fromMsg(filtered_.pose.pose.orientation, quat); + tf2::Matrix3x3 mat(quat); + double r, p, y; + mat.getRPY(r, p, y); + EXPECT_LT(::fabs(r - M_PI/4), 0.1); + EXPECT_LT(::fabs(p + M_PI/4), 0.1); + EXPECT_LT(::fabs(y - M_PI/2), 0.1); + + EXPECT_LT(filtered_.pose.covariance[21], 0.5); + EXPECT_LT(filtered_.pose.covariance[28], 0.25); + EXPECT_LT(filtered_.pose.covariance[35], 0.5); + + resetFilter(); + + // Test to see if the orientation data is ignored when we set the + // first covariance value to -1 + sensor_msgs::Imu imuIgnore; + imuIgnore.orientation.x = 0.1; + imuIgnore.orientation.y = 0.2; + imuIgnore.orientation.z = 0.3; + imuIgnore.orientation.w = 0.4; + imuIgnore.orientation_covariance[0] = -1; + + loopRate = ros::Rate(50); + for (size_t i = 0; i < 50; ++i) + { + imuIgnore.header.stamp = ros::Time::now(); + imuPub.publish(imuIgnore); + loopRate.sleep(); + ros::spinOnce(); + + imuIgnore.header.seq++; + } + + tf2::fromMsg(filtered_.pose.pose.orientation, quat); + mat.setRotation(quat); + mat.getRPY(r, p, y); + EXPECT_LT(::fabs(r), 1e-3); + EXPECT_LT(::fabs(p), 1e-3); + EXPECT_LT(::fabs(y), 1e-3); + + resetFilter(); +} + +TEST(InterfacesTest, ImuTwistBasicIO) +{ + ros::NodeHandle nh; + ros::Publisher imuPub = nh.advertise("/imu_input1", 5); + ros::Subscriber filteredSub = nh.subscribe("/odometry/filtered", 1, &filterCallback); + + sensor_msgs::Imu imu; + tf2::Quaternion quat; + imu.angular_velocity.x = (M_PI / 2.0); + + for (size_t ind = 0; ind < 9; ind+=4) + { + imu.angular_velocity_covariance[ind] = 1e-6; + } + + imu.header.frame_id = "base_link"; + + ros::Rate loopRate(50); + for (size_t i = 0; i < 50; ++i) + { + imu.header.stamp = ros::Time::now(); + imuPub.publish(imu); + loopRate.sleep(); + ros::spinOnce(); + + imu.header.seq++; + } + + // Now check the values from the callback + tf2::fromMsg(filtered_.pose.pose.orientation, quat); + tf2::Matrix3x3 mat(quat); + double r, p, y; + mat.getRPY(r, p, y); + + // Tolerances may seem loose, but the initial state covariances + // are tiny, so the filter is sluggish to accept velocity data + EXPECT_LT(::fabs(r - M_PI / 2.0), 0.7); + EXPECT_LT(::fabs(p), 0.1); + EXPECT_LT(::fabs(y), 0.1); + + EXPECT_LT(filtered_.twist.covariance[21], 1e-3); + EXPECT_LT(filtered_.pose.covariance[21], 0.1); + + resetFilter(); + + imu.angular_velocity.x = 0.0; + imu.angular_velocity.y = -(M_PI / 2.0); + + // Make sure the pose reset worked. Test will timeout + // if this fails. + loopRate = ros::Rate(50); + for (size_t i = 0; i < 50; ++i) + { + imu.header.stamp = ros::Time::now(); + imuPub.publish(imu); + loopRate.sleep(); + ros::spinOnce(); + + imu.header.seq++; + } + + // Now check the values from the callback + tf2::fromMsg(filtered_.pose.pose.orientation, quat); + mat.setRotation(quat); + mat.getRPY(r, p, y); + EXPECT_LT(::fabs(r), 0.1); + EXPECT_LT(::fabs(p + M_PI / 2.0), 0.7); + EXPECT_LT(::fabs(y), 0.1); + + EXPECT_LT(filtered_.twist.covariance[28], 1e-3); + EXPECT_LT(filtered_.pose.covariance[28], 0.1); + + resetFilter(); + + imu.angular_velocity.y = 0; + imu.angular_velocity.z = M_PI / 4.0; + + // Make sure the pose reset worked. Test will timeout + // if this fails. + loopRate = ros::Rate(50); + for (size_t i = 0; i < 50; ++i) + { + imu.header.stamp = ros::Time::now(); + imuPub.publish(imu); + loopRate.sleep(); + ros::spinOnce(); + + imu.header.seq++; + } + + // Now check the values from the callback + tf2::fromMsg(filtered_.pose.pose.orientation, quat); + mat.setRotation(quat); + mat.getRPY(r, p, y); + EXPECT_LT(::fabs(r), 0.1); + EXPECT_LT(::fabs(p), 0.1); + EXPECT_LT(::fabs(y - M_PI / 4.0), 0.7); + + EXPECT_LT(filtered_.twist.covariance[35], 1e-3); + EXPECT_LT(filtered_.pose.covariance[35], 0.1); + + resetFilter(); + + // Test to see if the angular velocity data is ignored when we set the + // first covariance value to -1 + sensor_msgs::Imu imuIgnore; + imuIgnore.angular_velocity.x = 100; + imuIgnore.angular_velocity.y = 100; + imuIgnore.angular_velocity.z = 100; + imuIgnore.angular_velocity_covariance[0] = -1; + + loopRate = ros::Rate(50); + for (size_t i = 0; i < 50; ++i) + { + imuIgnore.header.stamp = ros::Time::now(); + imuPub.publish(imuIgnore); + loopRate.sleep(); + ros::spinOnce(); + + imuIgnore.header.seq++; + } + + tf2::fromMsg(filtered_.pose.pose.orientation, quat); + mat.setRotation(quat); + mat.getRPY(r, p, y); + EXPECT_LT(::fabs(r), 1e-3); + EXPECT_LT(::fabs(p), 1e-3); + EXPECT_LT(::fabs(y), 1e-3); + + resetFilter(); +} + +TEST(InterfacesTest, ImuAccBasicIO) +{ + ros::NodeHandle nh; + ros::Publisher imuPub = nh.advertise("/imu_input2", 5); + ros::Subscriber filteredSub = nh.subscribe("/odometry/filtered", 1, &filterCallback); + + sensor_msgs::Imu imu; + imu.header.frame_id = "base_link"; + imu.linear_acceleration_covariance[0] = 1e-6; + imu.linear_acceleration_covariance[4] = 1e-6; + imu.linear_acceleration_covariance[8] = 1e-6; + + imu.linear_acceleration.x = 1; + imu.linear_acceleration.y = -1; + imu.linear_acceleration.z = 1; + + // Move with constant acceleration for 1 second, + // then check our velocity. + ros::Rate loopRate(50); + for (size_t i = 0; i < 50; ++i) + { + imu.header.stamp = ros::Time::now(); + imuPub.publish(imu); + loopRate.sleep(); + ros::spinOnce(); + + imu.header.seq++; + } + + EXPECT_LT(::fabs(filtered_.twist.twist.linear.x - 1.0), 0.4); + EXPECT_LT(::fabs(filtered_.twist.twist.linear.y + 1.0), 0.4); + EXPECT_LT(::fabs(filtered_.twist.twist.linear.z - 1.0), 0.4); + + imu.linear_acceleration.x = 0.0; + imu.linear_acceleration.y = 0.0; + imu.linear_acceleration.z = 0.0; + + // Now move for another second, and see where we + // end up + loopRate = ros::Rate(50); + for (size_t i = 0; i < 50; ++i) + { + imu.header.stamp = ros::Time::now(); + imuPub.publish(imu); + loopRate.sleep(); + ros::spinOnce(); + + imu.header.seq++; + } + + EXPECT_LT(::fabs(filtered_.pose.pose.position.x - 1.2), 0.4); + EXPECT_LT(::fabs(filtered_.pose.pose.position.y + 1.2), 0.4); + EXPECT_LT(::fabs(filtered_.pose.pose.position.z - 1.2), 0.4); + + resetFilter(); + + // Test to see if the linear acceleration data is ignored when we set the + // first covariance value to -1 + sensor_msgs::Imu imuIgnore; + imuIgnore.linear_acceleration.x = 1000; + imuIgnore.linear_acceleration.y = 1000; + imuIgnore.linear_acceleration.z = 1000; + imuIgnore.linear_acceleration_covariance[0] = -1; + + loopRate = ros::Rate(50); + for (size_t i = 0; i < 50; ++i) + { + imuIgnore.header.stamp = ros::Time::now(); + imuPub.publish(imuIgnore); + loopRate.sleep(); + ros::spinOnce(); + + imuIgnore.header.seq++; + } + + EXPECT_LT(::fabs(filtered_.pose.pose.position.x), 1e-3); + EXPECT_LT(::fabs(filtered_.pose.pose.position.y), 1e-3); + EXPECT_LT(::fabs(filtered_.pose.pose.position.z), 1e-3); + + resetFilter(); +} + +TEST(InterfacesTest, OdomDifferentialIO) +{ + ros::NodeHandle nh; + ros::Publisher odomPub = nh.advertise("/odom_input1", 5); + ros::Subscriber filteredSub = nh.subscribe("/odometry/filtered", 1, &filterCallback); + + nav_msgs::Odometry odom; + odom.pose.pose.position.x = 20.0; + odom.pose.pose.position.y = 10.0; + odom.pose.pose.position.z = -40.0; + + odom.pose.pose.orientation.w = 1; + + odom.pose.covariance[0] = 2.0; + odom.pose.covariance[7] = 2.0; + odom.pose.covariance[14] = 2.0; + odom.pose.covariance[21] = 0.2; + odom.pose.covariance[28] = 0.2; + odom.pose.covariance[35] = 0.2; + + odom.header.frame_id = "odom"; + odom.child_frame_id = "base_link"; + + // No guaranteeing that the zero state + // we're expecting to see here isn't just + // a result of zeroing it out previously, + // so check 10 times in succession. + size_t zeroCount = 0; + while (zeroCount++ < 10) + { + odom.header.stamp = ros::Time::now(); + odomPub.publish(odom); + ros::spinOnce(); + + EXPECT_LT(::fabs(filtered_.pose.pose.position.x), 0.01); + EXPECT_LT(::fabs(filtered_.pose.pose.position.y), 0.01); + EXPECT_LT(::fabs(filtered_.pose.pose.position.z), 0.01); + EXPECT_LT(::fabs(filtered_.pose.pose.orientation.x), 0.01); + EXPECT_LT(::fabs(filtered_.pose.pose.orientation.y), 0.01); + EXPECT_LT(::fabs(filtered_.pose.pose.orientation.z), 0.01); + EXPECT_LT(::fabs(filtered_.pose.pose.orientation.w - 1), 0.01); + + ros::Duration(0.1).sleep(); + + odom.header.seq++; + } + + for (size_t ind = 0; ind < 36; ind+=7) + { + odom.pose.covariance[ind] = 1e-6; + } + + // Slowly move the position, and hope that the + // differential position keeps up + ros::Rate loopRate(20); + for (size_t i = 0; i < 100; ++i) + { + odom.pose.pose.position.x += 0.01; + odom.pose.pose.position.y += 0.02; + odom.pose.pose.position.z -= 0.03; + + odom.header.stamp = ros::Time::now(); + odomPub.publish(odom); + ros::spinOnce(); + + loopRate.sleep(); + + odom.header.seq++; + } + ros::spinOnce(); + + EXPECT_LT(::fabs(filtered_.pose.pose.position.x - 1), 0.2); + EXPECT_LT(::fabs(filtered_.pose.pose.position.y - 2), 0.4); + EXPECT_LT(::fabs(filtered_.pose.pose.position.z + 3), 0.6); + + resetFilter(); +} + +TEST(InterfacesTest, PoseDifferentialIO) +{ + ros::NodeHandle nh; + ros::Publisher posePub = nh.advertise("/pose_input1", 5); + ros::Subscriber filteredSub = nh.subscribe("/odometry/filtered", 1, &filterCallback); + + geometry_msgs::PoseWithCovarianceStamped pose; + pose.pose.pose.position.x = 20.0; + pose.pose.pose.position.y = 10.0; + pose.pose.pose.position.z = -40.0; + + pose.pose.pose.orientation.w = 1; + + pose.pose.covariance[0] = 2.0; + pose.pose.covariance[7] = 2.0; + pose.pose.covariance[14] = 2.0; + pose.pose.covariance[21] = 0.2; + pose.pose.covariance[28] = 0.2; + pose.pose.covariance[35] = 0.2; + + pose.header.frame_id = "odom"; + + // No guaranteeing that the zero state + // we're expecting to see here isn't just + // a result of zeroing it out previously, + // so check 10 times in succession. + size_t zeroCount = 0; + while (zeroCount++ < 10) + { + pose.header.stamp = ros::Time::now(); + posePub.publish(pose); + ros::spinOnce(); + + EXPECT_LT(::fabs(filtered_.pose.pose.position.x), 0.01); + EXPECT_LT(::fabs(filtered_.pose.pose.position.y), 0.01); + EXPECT_LT(::fabs(filtered_.pose.pose.position.z), 0.01); + EXPECT_LT(::fabs(filtered_.pose.pose.orientation.x), 0.01); + EXPECT_LT(::fabs(filtered_.pose.pose.orientation.y), 0.01); + EXPECT_LT(::fabs(filtered_.pose.pose.orientation.z), 0.01); + EXPECT_LT(::fabs(filtered_.pose.pose.orientation.w - 1), 0.01); + + ros::Duration(0.1).sleep(); + + pose.header.seq++; + } + + // ...but only if we give the measurement a tiny covariance + for (size_t ind = 0; ind < 36; ind+=7) + { + pose.pose.covariance[ind] = 1e-6; + } + + // Issue this location repeatedly, and see if we get + // a final reported position of (1, 2, -3) + ros::Rate loopRate(20); + for (size_t i = 0; i < 100; ++i) + { + pose.pose.pose.position.x += 0.01; + pose.pose.pose.position.y += 0.02; + pose.pose.pose.position.z -= 0.03; + + pose.header.stamp = ros::Time::now(); + posePub.publish(pose); + ros::spinOnce(); + + loopRate.sleep(); + + pose.header.seq++; + } + ros::spinOnce(); + + EXPECT_LT(::fabs(filtered_.pose.pose.position.x - 1), 0.2); + EXPECT_LT(::fabs(filtered_.pose.pose.position.y - 2), 0.4); + EXPECT_LT(::fabs(filtered_.pose.pose.position.z + 3), 0.6); + + resetFilter(); +} + +TEST(InterfacesTest, ImuDifferentialIO) +{ + ros::NodeHandle nh; + ros::Publisher imu0Pub = nh.advertise("/imu_input0", 5); + ros::Publisher imu1Pub = nh.advertise("/imu_input1", 5); + ros::Publisher imuPub = nh.advertise("/imu_input3", 5); + ros::Subscriber filteredSub = nh.subscribe("/odometry/filtered", 1, &filterCallback); + + sensor_msgs::Imu imu; + imu.header.frame_id = "base_link"; + tf2::Quaternion quat; + const double roll = M_PI/2.0; + const double pitch = -M_PI; + const double yaw = -M_PI/4.0; + quat.setRPY(roll, pitch, yaw); + imu.orientation = tf2::toMsg(quat); + + imu.orientation_covariance[0] = 0.02; + imu.orientation_covariance[4] = 0.02; + imu.orientation_covariance[8] = 0.02; + + imu.angular_velocity_covariance[0] = 0.02; + imu.angular_velocity_covariance[4] = 0.02; + imu.angular_velocity_covariance[8] = 0.02; + + size_t setCount = 0; + while (setCount++ < 10) + { + imu.header.stamp = ros::Time::now(); + imu0Pub.publish(imu); // Use this to move the absolute orientation + imu1Pub.publish(imu); // Use this to keep velocities at 0 + ros::spinOnce(); + + ros::Duration(0.1).sleep(); + + imu.header.seq++; + } + + size_t zeroCount = 0; + while (zeroCount++ < 10) + { + imu.header.stamp = ros::Time::now(); + imuPub.publish(imu); + ros::spinOnce(); + + ros::Duration(0.1).sleep(); + + imu.header.seq++; + } + + double rollFinal = roll; + double pitchFinal = pitch; + double yawFinal = yaw; + + // Move the orientation slowly, and see if we + // can push it to 0 + ros::Rate loopRate(20); + for (size_t i = 0; i < 100; ++i) + { + yawFinal -= 0.01 * (3.0 * M_PI/4.0); + + quat.setRPY(rollFinal, pitchFinal, yawFinal); + + imu.orientation = tf2::toMsg(quat); + imu.header.stamp = ros::Time::now(); + imuPub.publish(imu); + ros::spinOnce(); + + loopRate.sleep(); + + imu.header.seq++; + } + ros::spinOnce(); + + // Move the orientation slowly, and see if we + // can push it to 0 + loopRate = ros::Rate(20); + for (size_t i = 0; i < 100; ++i) + { + rollFinal += 0.01 * (M_PI/2.0); + + quat.setRPY(rollFinal, pitchFinal, yawFinal); + + imu.orientation = tf2::toMsg(quat); + imu.header.stamp = ros::Time::now(); + imuPub.publish(imu); + ros::spinOnce(); + + loopRate.sleep(); + + imu.header.seq++; + } + ros::spinOnce(); + + tf2::fromMsg(filtered_.pose.pose.orientation, quat); + tf2::Matrix3x3 mat(quat); + mat.getRPY(rollFinal, pitchFinal, yawFinal); + EXPECT_LT(::fabs(rollFinal), 0.2); + EXPECT_LT(::fabs(pitchFinal), 0.2); + EXPECT_LT(::fabs(yawFinal), 0.2); + + resetFilter(); +} + +int main(int argc, char **argv) +{ + testing::InitGoogleTest(&argc, argv); + + ros::init(argc, argv, "ekf_navigation_node-test-interfaces"); + ros::Time::init(); + + // Give ekf_localization_node time to initialize + ros::Duration(2.0).sleep(); + + return RUN_ALL_TESTS(); +} diff --git a/navigations/robot_localization/test/test_ekf_localization_node_interfaces.test b/navigations/robot_localization/test/test_ekf_localization_node_interfaces.test new file mode 100755 index 0000000..f440b92 --- /dev/null +++ b/navigations/robot_localization/test/test_ekf_localization_node_interfaces.test @@ -0,0 +1,68 @@ + + + + + + + + + + + + + + + + + + + + + + + + + [true, false, true, false, false, false, false, false, false, false, false, false, false, false, false] + [true, true, true, true, true, true, false, false, false, false, false, false, false, false, false] + [false, false, false, false, false, false, true, true, true, true, true, true, false, false, false] + + [true, false, true, false, false, false, false, false, false, false, false, false, false, false, false] + [true, true, true, true, true, true, false, false, false, false, false, false, false, false, false] + + [false, false, false, false, false, false, true, true, true, true, true, true, false, false, false] + + [false, false, false, true, true, true, false, false, false, false, false, false, false, false, false] + [false, false, false, false, false, false, false, false, false, true, true, true, false, false, false] + [false, false, false, false, false, false, false, false, false, false, false, false, true, true, true] + [false, false, false, true, true, true, false, false, false, false, false, false, false, false, false] + + + + + + + + + + + [0.03, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.03, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.4, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.03, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.03, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.025, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.025, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.002, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.002, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.004, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01] + + + + + + diff --git a/navigations/robot_localization/test/test_ekf_localization_nodelet_bag1.test b/navigations/robot_localization/test/test_ekf_localization_nodelet_bag1.test new file mode 100755 index 0000000..b49c7fe --- /dev/null +++ b/navigations/robot_localization/test/test_ekf_localization_nodelet_bag1.test @@ -0,0 +1,104 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [false, false, false, + false, false, false, + true, true, true, + false, false, false, + false, false, false] + + [false, false, false, + true, true, true, + false, false, false, + true, true, false, + true, true, true] + + + + + + + + + + + + + + + + + + [0.05, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0.05, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0.06, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0.03, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0.03, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0.06, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0.025, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0.025, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0.04, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.02, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.015] + + [1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9] + + + + + + + + + + + + + diff --git a/navigations/robot_localization/test/test_filter_base.cpp b/navigations/robot_localization/test/test_filter_base.cpp new file mode 100755 index 0000000..8ae42f3 --- /dev/null +++ b/navigations/robot_localization/test/test_filter_base.cpp @@ -0,0 +1,216 @@ +/* + * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include "robot_localization/filter_base.h" +#include "robot_localization/filter_common.h" + +#include + +#include + +#include +#include +#include + +using RobotLocalization::STATE_SIZE; +using RobotLocalization::Measurement; + +namespace RobotLocalization +{ + +class FilterDerived : public FilterBase +{ + public: + double val; + + FilterDerived() : val(0) { } + + void correct(const Measurement &measurement) + { + EXPECT_EQ(val, measurement.time_); + EXPECT_EQ(measurement.topicName_, "topic"); + + EXPECT_EQ(measurement.updateVector_.size(), 10u); + for (size_t i = 0; i < measurement.updateVector_.size(); ++i) + { + EXPECT_EQ(measurement.updateVector_[i], true); + } + } + + void predict(const double refTime, const double delta) + { + val = delta; + } +}; + +class FilterDerived2 : public FilterBase +{ + public: + FilterDerived2() { } + + void correct(const Measurement &measurement) + { + } + + void predict(const double refTime, const double delta) + { + } + + void processMeasurement(const Measurement &measurement) + { + FilterBase::processMeasurement(measurement); + } +}; + +} // namespace RobotLocalization + +TEST(FilterBaseTest, MeasurementStruct) +{ + RobotLocalization::Measurement meas1; + RobotLocalization::Measurement meas2; + + EXPECT_EQ(meas1.topicName_, std::string("")); + EXPECT_EQ(meas1.time_, 0); + EXPECT_EQ(meas2.time_, 0); + + // Comparison test is true if the first + // argument is > the second, so should + // be false if they're equal. + EXPECT_EQ(meas1(meas1, meas2), false); + EXPECT_EQ(meas2(meas2, meas1), false); + + meas1.time_ = 100; + meas2.time_ = 200; + + EXPECT_EQ(meas1(meas1, meas2), false); + EXPECT_EQ(meas1(meas2, meas1), true); + EXPECT_EQ(meas2(meas1, meas2), false); + EXPECT_EQ(meas2(meas2, meas1), true); +} + +TEST(FilterBaseTest, DerivedFilterGetSet) +{ + using RobotLocalization::FilterDerived; + + FilterDerived derived; + + // With the ostream argument as NULL, + // the debug flag will remain false. + derived.setDebug(true); + + EXPECT_FALSE(derived.getDebug()); + + // Now set the stream and do it again + std::stringstream os; + derived.setDebug(true, &os); + + EXPECT_TRUE(derived.getDebug()); + + // Simple get/set checks + double timeout = 7.4; + derived.setSensorTimeout(timeout); + EXPECT_EQ(derived.getSensorTimeout(), timeout); + + double lastMeasTime = 3.83; + derived.setLastMeasurementTime(lastMeasTime); + EXPECT_EQ(derived.getLastMeasurementTime(), lastMeasTime); + + Eigen::MatrixXd pnCovar(STATE_SIZE, STATE_SIZE); + for (size_t i = 0; i < STATE_SIZE; ++i) + { + for (size_t j = 0; j < STATE_SIZE; ++j) + { + pnCovar(i, j) = static_cast(i * j); + } + } + derived.setProcessNoiseCovariance(pnCovar); + EXPECT_EQ(derived.getProcessNoiseCovariance(), pnCovar); + + Eigen::VectorXd state(STATE_SIZE); + state.setZero(); + derived.setState(state); + EXPECT_EQ(derived.getState(), state); + + EXPECT_EQ(derived.getInitializedStatus(), false); +} + +TEST(FilterBaseTest, MeasurementProcessing) +{ + using RobotLocalization::FilterDerived2; + + FilterDerived2 derived; + + Measurement meas; + + Eigen::VectorXd measurement(STATE_SIZE); + for (size_t i = 0; i < STATE_SIZE; ++i) + { + measurement[i] = 0.1 * static_cast(i); + } + + Eigen::MatrixXd measurementCovariance(STATE_SIZE, STATE_SIZE); + for (size_t i = 0; i < STATE_SIZE; ++i) + { + for (size_t j = 0; j < STATE_SIZE; ++j) + { + measurementCovariance(i, j) = 0.1 * static_cast(i * j); + } + } + + meas.topicName_ = "odomTest"; + meas.measurement_ = measurement; + meas.covariance_ = measurementCovariance; + meas.updateVector_.resize(STATE_SIZE, true); + meas.time_ = 1000; + + // The filter shouldn't be initializedyet + EXPECT_FALSE(derived.getInitializedStatus()); + + derived.processMeasurement(meas); + + // Now it's initialized, and the entire filter state + // should be equal to the first state + EXPECT_TRUE(derived.getInitializedStatus()); + EXPECT_EQ(derived.getState(), measurement); + + // Process a measurement and make sure it updates the + // lastMeasurementTime variable + meas.time_ = 1002; + derived.processMeasurement(meas); + EXPECT_EQ(derived.getLastMeasurementTime(), meas.time_); +} + +int main(int argc, char **argv) +{ + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/navigations/robot_localization/test/test_filter_base_diagnostics_timestamps.cpp b/navigations/robot_localization/test/test_filter_base_diagnostics_timestamps.cpp new file mode 100755 index 0000000..0fa6fda --- /dev/null +++ b/navigations/robot_localization/test/test_filter_base_diagnostics_timestamps.cpp @@ -0,0 +1,434 @@ +/* + * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include +#include +#include +#include + +#include "robot_localization/filter_base.h" +#include "robot_localization/filter_common.h" +#include "robot_localization/SetPose.h" + + +#include + +#include + +#include + +namespace RobotLocalization +{ + +/* + Convenience functions to get valid messages. +*/ + +geometry_msgs::PoseWithCovarianceStamped getValidPose() +{ + geometry_msgs::PoseWithCovarianceStamped pose_msg; + pose_msg.header.frame_id = "base_link"; + pose_msg.pose.pose.position.x = 1; + pose_msg.pose.pose.orientation.w = 1; + for (size_t i = 0; i < 6 ; i++) + { + pose_msg.pose.covariance[i*6 + i] = 1; + } + return pose_msg; +} + +geometry_msgs::TwistWithCovarianceStamped getValidTwist() +{ + geometry_msgs::TwistWithCovarianceStamped twist_msg; + twist_msg.header.frame_id = "base_link"; + for (size_t i = 0; i < 6 ; i++) + { + twist_msg.twist.covariance[i*6 + i] = 1; + } + return twist_msg; +} + + +sensor_msgs::Imu getValidImu() +{ + sensor_msgs::Imu imu_msg; + imu_msg.header.frame_id = "base_link"; + imu_msg.orientation.w = 1; + for (size_t i = 0; i < 3 ; i++) + { + imu_msg.orientation_covariance[i * 3 + i] = 1; + imu_msg.angular_velocity_covariance[i * 3 + i] = 1; + imu_msg.linear_acceleration_covariance[i * 3 + i] = 1; + } + return imu_msg; +} + +nav_msgs::Odometry getValidOdometry() +{ + nav_msgs::Odometry odom_msg; + odom_msg.header.frame_id = "odom"; + odom_msg.child_frame_id = "base_link"; + odom_msg.pose = getValidPose().pose; + odom_msg.twist = getValidTwist().twist; + return odom_msg; +} + +/* + Helper class to handle the setup and message publishing for the testcases. + + It provides convenience to send valid messages with a specified timestamp. + + All diagnostic messages are stored into the public diagnostics attribute. +*/ +class DiagnosticsHelper +{ + private: + ros::Publisher odom_pub_; + ros::Publisher pose_pub_; + ros::Publisher twist_pub_; + ros::Publisher imu_pub_; + + geometry_msgs::PoseWithCovarianceStamped pose_msg_; + geometry_msgs::TwistWithCovarianceStamped twist_msg_; + nav_msgs::Odometry odom_msg_; + sensor_msgs::Imu imu_msg_; + + ros::Subscriber diagnostic_sub_; + ros::ServiceClient set_pose_; + + public: + std::vector< diagnostic_msgs::DiagnosticArray > diagnostics; + + DiagnosticsHelper() + { + ros::NodeHandle nh; + ros::NodeHandle nhLocal("~"); + + // ready the valid messages. + pose_msg_ = getValidPose(); + twist_msg_ = getValidTwist(); + odom_msg_ = getValidOdometry(); + imu_msg_ = getValidImu(); + + // subscribe to diagnostics and create publishers for the odometry messages. + odom_pub_ = nh.advertise("example/odom", 10); + pose_pub_ = nh.advertise("example/pose", 10); + twist_pub_ = nh.advertise("example/twist", 10); + imu_pub_ = nh.advertise("example/imu/data", 10); + + diagnostic_sub_ = nh.subscribe("/diagnostics", 10, &DiagnosticsHelper::diagnosticCallback, this); + set_pose_ = nh.serviceClient("/set_pose"); + } + + void diagnosticCallback(const diagnostic_msgs::DiagnosticArrayPtr &msg) + { + diagnostics.push_back(*msg); + } + + void publishMessages(ros::Time t) + { + odom_msg_.header.stamp = t; + odom_msg_.header.seq++; + odom_pub_.publish(odom_msg_); + + pose_msg_.header.stamp = t; + pose_msg_.header.seq++; + pose_pub_.publish(pose_msg_); + + twist_msg_.header.stamp = t; + twist_msg_.header.seq++; + twist_pub_.publish(twist_msg_); + + imu_msg_.header.stamp = t; + imu_msg_.header.seq++; + imu_pub_.publish(imu_msg_); + } + + void setPose(ros::Time t) + { + robot_localization::SetPose pose_; + pose_.request.pose = getValidPose(); + pose_.request.pose.header.stamp = t; + set_pose_.call(pose_); + } +}; + +} // namespace RobotLocalization + +/* + First test; we run for a bit; then send messagse with an empty timestamp. + Then we check if the diagnostics showed a warning. +*/ +TEST(FilterBaseDiagnosticsTest, EmptyTimestamps) +{ + RobotLocalization::DiagnosticsHelper dh_; + + // keep track of which diagnostic messages are detected. + bool received_warning_imu = false; + bool received_warning_odom = false; + bool received_warning_twist = false; + bool received_warning_pose = false; + + // For about a second, send correct messages. + ros::Rate loopRate(10); + for (size_t i = 0; i < 10; ++i) + { + ros::spinOnce(); + dh_.publishMessages(ros::Time::now()); + loopRate.sleep(); + } + + ros::spinOnce(); + + // create an empty timestamp and send all messages with this empty timestamp. + ros::Time empty; + empty.fromSec(0); + + dh_.publishMessages(empty); + + ros::spinOnce(); + + // The filter runs and sends the diagnostics every second. + // Just run this for two seconds to ensure we get all the diagnostic message. + for (size_t i = 0; i < 20; ++i) + { + ros::spinOnce(); + loopRate.sleep(); + } + + /* + Now the diagnostic messages have to be investigated to see whether they contain our warning. + */ + for (size_t i=0; i < dh_.diagnostics.size(); i++) + { + for (size_t status_index=0; status_index < dh_.diagnostics[i].status.size(); status_index++) + { + for (size_t key=0; key < dh_.diagnostics[i].status[status_index].values.size(); key++) + { + diagnostic_msgs::KeyValue kv = dh_.diagnostics[i].status[status_index].values[key]; + // Now the keys can be checked to see whether we found our warning. + + if (kv.key == "imu0_timestamp") + { + received_warning_imu = true; + } + if (kv.key == "odom0_timestamp") + { + received_warning_odom = true; + } + if (kv.key == "twist0_timestamp") + { + received_warning_twist = true; + } + if (kv.key == "pose0_timestamp") + { + received_warning_pose = true; + } + } + } + } + EXPECT_TRUE(received_warning_imu); + EXPECT_TRUE(received_warning_odom); + EXPECT_TRUE(received_warning_twist); + EXPECT_TRUE(received_warning_pose); +} + +TEST(FilterBaseDiagnosticsTest, TimestampsBeforeSetPose) +{ + RobotLocalization::DiagnosticsHelper dh_; + + // keep track of which diagnostic messages are detected. + bool received_warning_imu = false; + bool received_warning_odom = false; + bool received_warning_twist = false; + bool received_warning_pose = false; + + // For about a second, send correct messages. + ros::Rate loopRate(10); + for (size_t i = 0; i < 10; ++i) + { + ros::spinOnce(); + dh_.publishMessages(ros::Time::now()); + loopRate.sleep(); + } + ros::spinOnce(); + + // Set the pose to the current timestamp. + dh_.setPose(ros::Time::now()); + ros::spinOnce(); + + // send messages from one second before that pose reset. + dh_.publishMessages(ros::Time::now() - ros::Duration(1)); + + // The filter runs and sends the diagnostics every second. + // Just run this for two seconds to ensure we get all the diagnostic message. + for (size_t i = 0; i < 20; ++i) + { + ros::spinOnce(); + loopRate.sleep(); + } + + /* + Now the diagnostic messages have to be investigated to see whether they contain our warning. + */ + for (size_t i=0; i < dh_.diagnostics.size(); i++) + { + for (size_t status_index=0; status_index < dh_.diagnostics[i].status.size(); status_index++) + { + for (size_t key=0; key < dh_.diagnostics[i].status[status_index].values.size(); key++) + { + diagnostic_msgs::KeyValue kv = dh_.diagnostics[i].status[status_index].values[key]; + // Now the keys can be checked to see whether we found our warning. + + if (kv.key == "imu0_timestamp") + { + received_warning_imu = true; + } + if (kv.key == "odom0_timestamp") + { + received_warning_odom = true; + } + if (kv.key == "twist0_timestamp") + { + received_warning_twist = true; + } + if (kv.key == "pose0_timestamp") + { + received_warning_pose = true; + } + } + } + } + EXPECT_TRUE(received_warning_imu); + EXPECT_TRUE(received_warning_odom); + EXPECT_TRUE(received_warning_twist); + EXPECT_TRUE(received_warning_pose); +} + +TEST(FilterBaseDiagnosticsTest, TimestampsBeforePrevious) +{ + RobotLocalization::DiagnosticsHelper dh_; + + // keep track of which diagnostic messages are detected. + // we have more things to check here because the messages get split over + // various callbacks if they pass the check if they predate the set_pose time. + bool received_warning_imu_accel = false; + bool received_warning_imu_pose = false; + bool received_warning_imu_twist = false; + bool received_warning_odom_twist = false; + bool received_warning_twist = false; + bool received_warning_pose = false; + + // For two seconds send correct messages. + ros::Rate loopRate(10); + for (size_t i = 0; i < 20; ++i) + { + ros::spinOnce(); + dh_.publishMessages(ros::Time::now()); + loopRate.sleep(); + } + ros::spinOnce(); + + // Send message that is one second in the past. + dh_.publishMessages(ros::Time::now() - ros::Duration(1)); + + // The filter runs and sends the diagnostics every second. + // Just run this for two seconds to ensure we get all the diagnostic message. + for (size_t i = 0; i < 20; ++i) + { + ros::spinOnce(); + loopRate.sleep(); + } + + /* + Now the diagnostic messages have to be investigated to see whether they contain our warning. + */ + for (size_t i=0; i < dh_.diagnostics.size(); i++) + { + for (size_t status_index=0; status_index < dh_.diagnostics[i].status.size(); status_index++) + { + for (size_t key=0; key < dh_.diagnostics[i].status[status_index].values.size(); key++) + { + diagnostic_msgs::KeyValue kv = dh_.diagnostics[i].status[status_index].values[key]; + // Now the keys can be checked to see whether we found our warning. + + if (kv.key == "imu0_acceleration_timestamp") + { + received_warning_imu_accel = true; + } + if (kv.key == "imu0_pose_timestamp") + { + received_warning_imu_pose = true; + } + if (kv.key == "imu0_twist_timestamp") + { + received_warning_imu_twist = true; + } + + if (kv.key == "odom0_twist_timestamp") + { + received_warning_twist = true; + } + + if (kv.key == "pose0_timestamp") + { + received_warning_pose = true; + } + if (kv.key == "twist0_timestamp") + { + received_warning_odom_twist = true; + } + } + } + } + + EXPECT_TRUE(received_warning_imu_accel); + EXPECT_TRUE(received_warning_imu_pose); + EXPECT_TRUE(received_warning_imu_twist); + EXPECT_TRUE(received_warning_odom_twist); + EXPECT_TRUE(received_warning_pose); + EXPECT_TRUE(received_warning_twist); +} + + +int main(int argc, char **argv) +{ + ros::init(argc, argv, "filter_base_diagnostics_timestamps-test-interfaces"); + ros::Time::init(); + + // Give ekf_localization_node time to initialize + ros::Duration(2.0).sleep(); + + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/navigations/robot_localization/test/test_filter_base_diagnostics_timestamps.test b/navigations/robot_localization/test/test_filter_base_diagnostics_timestamps.test new file mode 100755 index 0000000..40cf75b --- /dev/null +++ b/navigations/robot_localization/test/test_filter_base_diagnostics_timestamps.test @@ -0,0 +1,44 @@ + + + + + + + + + + + + [false, false, false, + false, false, false, + true, false, false, + false, false, false, + false, false, false] + + [true, true, false, + false, false, false, + false, false, false, + false, false, false, + false, false, false] + + [false, false, false, + false, false, false, + true, true, true, + true, true, true, + false, false, false] + + [false, false, false, + true, true, true, + false, false, false, + true, true, true, + true, true, true] + + + + + + + + diff --git a/navigations/robot_localization/test/test_localization_node_bag_pose_tester.cpp b/navigations/robot_localization/test/test_localization_node_bag_pose_tester.cpp new file mode 100755 index 0000000..a38fa58 --- /dev/null +++ b/navigations/robot_localization/test/test_localization_node_bag_pose_tester.cpp @@ -0,0 +1,111 @@ +/* + * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include + +#include + +#include +#include +#include + +nav_msgs::Odometry filtered_; + +void filterCallback(const nav_msgs::OdometryConstPtr &msg) +{ + filtered_ = *msg; +} + +TEST(BagTest, PoseCheck) +{ + ros::NodeHandle nh; + ros::NodeHandle nhLocal("~"); + + double finalX = 0; + double finalY = 0; + double finalZ = 0; + double tolerance = 0; + bool outputFinalPosition = false; + std::string finalPositionFile; + + nhLocal.getParam("final_x", finalX); + nhLocal.getParam("final_y", finalY); + nhLocal.getParam("final_z", finalZ); + nhLocal.getParam("tolerance", tolerance); + nhLocal.param("output_final_position", outputFinalPosition, false); + nhLocal.param("output_location", finalPositionFile, std::string("test.txt")); + + ros::Subscriber filteredSub = nh.subscribe("/odometry/filtered", 1, &filterCallback); + + while (ros::ok()) + { + ros::spinOnce(); + ros::Duration(0.0333333).sleep(); + } + + if (outputFinalPosition) + { + try + { + std::ofstream posOut; + posOut.open(finalPositionFile.c_str(), std::ofstream::app); + posOut << filtered_.pose.pose.position.x << " " << filtered_.pose.pose.position.y << " " << + filtered_.pose.pose.position.z << std::endl; + posOut.close(); + } + catch(...) + { + ROS_ERROR_STREAM("Unable to open output file.\n"); + } + } + + double xDiff = filtered_.pose.pose.position.x - finalX; + double yDiff = filtered_.pose.pose.position.y - finalY; + double zDiff = filtered_.pose.pose.position.z - finalZ; + + EXPECT_LT(::sqrt(xDiff*xDiff + yDiff*yDiff + zDiff*zDiff), tolerance); +} + +int main(int argc, char **argv) +{ + testing::InitGoogleTest(&argc, argv); + + ros::init(argc, argv, "localization_node-bag-pose-tester"); + ros::Time::init(); + + // Give ekf_localization_node time to initialize + ros::Duration(2.0).sleep(); + + return RUN_ALL_TESTS(); +} + diff --git a/navigations/robot_localization/test/test_navsat_conversions.cpp b/navigations/robot_localization/test/test_navsat_conversions.cpp new file mode 100755 index 0000000..15f85ab --- /dev/null +++ b/navigations/robot_localization/test/test_navsat_conversions.cpp @@ -0,0 +1,69 @@ +/* + * Copyright (c) 2021, Charles River Analytics, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include "robot_localization/navsat_conversions.h" + +#include + +#include + +void NavsatConversionsTest(const double lat, const double lon, + const double UTMNorthing, const double UTMEasting, + const std::string UTMZone, const double gamma) +{ + double UTMNorthing_new; + double UTMEasting_new; + std::string UTMZone_new; + double gamma_new; + RobotLocalization::NavsatConversions::LLtoUTM(lat, lon, UTMNorthing_new, UTMEasting_new, UTMZone_new, gamma_new); + EXPECT_NEAR(UTMNorthing, UTMNorthing_new, 1e-2); + EXPECT_NEAR(UTMEasting, UTMEasting_new, 1e-2); + EXPECT_EQ(UTMZone, UTMZone_new); + EXPECT_NEAR(gamma, gamma_new, 1e-2); + double lat_new; + double lon_new; + RobotLocalization::NavsatConversions::UTMtoLL(UTMNorthing, UTMEasting, UTMZone, lat_new, lon_new); + EXPECT_NEAR(lat_new, lat, 1e-5); + EXPECT_NEAR(lon_new, lon, 1e-5); +} + +TEST(NavsatConversionsTest, UtmTest) +{ + NavsatConversionsTest(51.423964, 5.494271, 5699924.709, 673409.989, "31U", 1.950); + NavsatConversionsTest(-43.530955, 172.636645, 5178919.718, 632246.802, "59G", -1.127); +} + +int main(int argc, char **argv) +{ + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/navigations/robot_localization/test/test_navsat_transform.cpp b/navigations/robot_localization/test/test_navsat_transform.cpp new file mode 100755 index 0000000..72db4e5 --- /dev/null +++ b/navigations/robot_localization/test/test_navsat_transform.cpp @@ -0,0 +1,91 @@ +/* + * Copyright (c) 2021, Charles River Analytics, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include "robot_localization/navsat_transform.h" +#include +#include +#include + +#include + +#include + +TEST(NavSatTransformUTMJumpTest, UtmTest) +{ + ros::NodeHandle nh; + ros::ServiceClient set_datum_client = nh.serviceClient("/datum"); + ros::ServiceClient from_ll_client = nh.serviceClient("/fromLL"); + + EXPECT_TRUE(set_datum_client.waitForExistence(ros::Duration(5))); + + // Initialise the navsat_transform node to a UTM zone + robot_localization::SetDatum set_datum_srv; + set_datum_srv.request.geo_pose.position.latitude = 1; + set_datum_srv.request.geo_pose.position.longitude = 4; + set_datum_srv.request.geo_pose.orientation.w = 1; + EXPECT_TRUE(set_datum_client.call(set_datum_srv)); + + // Let the node figure out its transforms + ros::Duration(0.2).sleep(); + + // Request the GPS point of said point: + robot_localization::FromLL from_ll_srv; + from_ll_srv.request.ll_point.latitude = 10; + from_ll_srv.request.ll_point.longitude = 4.5; + EXPECT_TRUE(from_ll_client.call(from_ll_srv)); + auto initial_response = from_ll_srv.response; + + // Request GPS point also in that zone + from_ll_srv.request.ll_point.longitude = 5.5; + EXPECT_TRUE(from_ll_client.call(from_ll_srv)); + auto same_zone_response = from_ll_srv.response; + + // 1° of longitude is about 111 kilometers in length + EXPECT_NEAR(initial_response.map_point.x, same_zone_response.map_point.x, 120e3); + EXPECT_NEAR(initial_response.map_point.y, same_zone_response.map_point.y, 120e3); + + // Request GPS point from neighboring zone (zone crossing is at 6 degrees) + from_ll_srv.request.ll_point.longitude = 6.5; + from_ll_client.call(from_ll_srv); + auto neighbour_zone_response = from_ll_srv.response; + + EXPECT_NEAR(initial_response.map_point.x, neighbour_zone_response.map_point.x, 2*120e3); + EXPECT_NEAR(initial_response.map_point.y, neighbour_zone_response.map_point.y, 2*120e3); +} + +int main(int argc, char **argv) +{ + ros::init(argc, argv, "test_navsat_transform"); + + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/navigations/robot_localization/test/test_navsat_transform.test b/navigations/robot_localization/test/test_navsat_transform.test new file mode 100755 index 0000000..d8873b2 --- /dev/null +++ b/navigations/robot_localization/test/test_navsat_transform.test @@ -0,0 +1,9 @@ + + + + + + + + + diff --git a/navigations/robot_localization/test/test_robot_localization_estimator.cpp b/navigations/robot_localization/test/test_robot_localization_estimator.cpp new file mode 100755 index 0000000..757423e --- /dev/null +++ b/navigations/robot_localization/test/test_robot_localization_estimator.cpp @@ -0,0 +1,169 @@ +/* + * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include "robot_localization/robot_localization_estimator.h" + +#include +#include + +#include + +TEST(RLETest, StateBuffer) +{ + // Generate a few estimator states + std::vector states; + + for ( int i = 0; i < 10; i++ ) + { + /* + * t = i s; + * x = i m; + * vx = 1.0 m/s; + */ + RobotLocalization::EstimatorState state; + state.time_stamp = i; + state.state(RobotLocalization::StateMemberX) = i; + state.state(RobotLocalization::StateMemberY) = 0; + state.state(RobotLocalization::StateMemberZ) = 0; + + state.state(RobotLocalization::StateMemberRoll) = 0; + state.state(RobotLocalization::StateMemberPitch) = 0; + state.state(RobotLocalization::StateMemberYaw) = 0; + + state.state(RobotLocalization::StateMemberVx) = 1; + state.state(RobotLocalization::StateMemberVy) = 0; + state.state(RobotLocalization::StateMemberVz) = 0; + + state.state(RobotLocalization::StateMemberVroll) = 0; + state.state(RobotLocalization::StateMemberVpitch) = 0; + state.state(RobotLocalization::StateMemberVyaw) = 0; + + state.state(RobotLocalization::StateMemberAx) = 0; + state.state(RobotLocalization::StateMemberAy) = 0; + state.state(RobotLocalization::StateMemberAz) = 0; + states.push_back(state); + } + + // Instantiate a robot localization estimator with a buffer capacity of 5 + int buffer_capacity = 5; + Eigen::MatrixXd process_noise_covariance = Eigen::MatrixXd::Identity(RobotLocalization::STATE_SIZE, + RobotLocalization::STATE_SIZE); + RobotLocalization::RobotLocalizationEstimator estimator(buffer_capacity, RobotLocalization::FilterTypes::EKF, + process_noise_covariance); + + RobotLocalization::EstimatorState state; + + // Add the states in chronological order + for ( int i = 0; i < 6; i++ ) + { + estimator.setState(states[i]); + + // Check that the state is added correctly + estimator.getState(states[i].time_stamp, state); + EXPECT_EQ(state.time_stamp, states[i].time_stamp); + } + + // We filled the buffer with more states that it can hold, so its size should now be equal to the capacity + EXPECT_EQ(static_cast(estimator.getSize()), buffer_capacity); + + // Clear the buffer and check if it's really empty afterwards + estimator.clearBuffer(); + EXPECT_EQ(estimator.getSize(), 0u); + + // Add states at time 1 through 3 inclusive to the buffer (buffer is not yet full) + for ( int i = 1; i < 4; i++ ) + { + estimator.setState(states[i]); + } + + // Now add a state at time 0, but let's change it a bit (set StateMemberY=12) so that we can inspect if it is + // correctly added to the buffer. + RobotLocalization::EstimatorState state_2 = states[0]; + state_2.state(RobotLocalization::StateMemberY) = 12; + estimator.setState(state_2); + EXPECT_EQ(RobotLocalization::EstimatorResults::Exact, + estimator.getState(states[0].time_stamp, state)); + + // Check if the state is correctly added + EXPECT_EQ(state.state, state_2.state); + + // Add some more states. State at t=0 should now be dropped, so we should get the prediction, which means y=0 + for ( int i = 5; i < 8; i++ ) + { + estimator.setState(states[i]); + } + EXPECT_EQ(RobotLocalization::EstimatorResults::ExtrapolationIntoPast, + estimator.getState(states[0].time_stamp, state)); + EXPECT_EQ(states[0].state, state.state); + + // Estimate a state that is not in the buffer, but can be determined by interpolation. The predicted state vector + // should be equal to the designed state at the requested time. + EXPECT_EQ(RobotLocalization::EstimatorResults::Interpolation, + estimator.getState(states[4].time_stamp, state)); + EXPECT_EQ(states[4].state, state.state); + + // Estimate a state that is not in the buffer, but can be determined by extrapolation into the future. The predicted + // state vector should be equal to the designed state at the requested time. + EXPECT_EQ(RobotLocalization::EstimatorResults::ExtrapolationIntoFuture, + estimator.getState(states[8].time_stamp, state)); + EXPECT_EQ(states[8].state, state.state); + + // Add missing state somewhere in the middle + estimator.setState(states[4]); + + // Overwrite state at t=3 (oldest state now in the buffer) and check if it's correctly overwritten. + state_2 = states[3]; + state_2.state(RobotLocalization::StateMemberVy) = -1.0; + estimator.setState(state_2); + EXPECT_EQ(RobotLocalization::EstimatorResults::Exact, + estimator.getState(states[3].time_stamp, state)); + EXPECT_EQ(state_2.state, state.state); + + // Add state that came too late + estimator.setState(states[0]); + + // Check if getState needed to do extrapolation into the past + EXPECT_EQ(estimator.getState(states[0].time_stamp, state), + RobotLocalization::EstimatorResults::ExtrapolationIntoPast); + + // Check state at t=0. This can only work correctly if the state at t=3 is + // overwritten and the state at zero is not in the buffer. + EXPECT_DOUBLE_EQ(3.0, state.state(RobotLocalization::StateMemberY)); +} + +int main(int argc, char **argv) +{ + ros::init(argc, argv, "test_robot_localization_estimator"); + + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/navigations/robot_localization/test/test_robot_localization_estimator.test b/navigations/robot_localization/test/test_robot_localization_estimator.test new file mode 100755 index 0000000..ebd8db5 --- /dev/null +++ b/navigations/robot_localization/test/test_robot_localization_estimator.test @@ -0,0 +1,7 @@ + + + + + + + diff --git a/navigations/robot_localization/test/test_ros_robot_localization_listener.cpp b/navigations/robot_localization/test/test_ros_robot_localization_listener.cpp new file mode 100755 index 0000000..00cfc88 --- /dev/null +++ b/navigations/robot_localization/test/test_ros_robot_localization_listener.cpp @@ -0,0 +1,132 @@ +/* + * Copyright (c) 2016, TNO IVS, Helmond + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include "robot_localization/ros_robot_localization_listener.h" +#include "robot_localization/filter_common.h" + +#include + +#include +#include + +#include + +RobotLocalization::RosRobotLocalizationListener* g_listener; + +TEST(LocalizationListenerTest, testGetStateOfBaseLink) +{ + ros::spinOnce(); + + ros::Time time2(1001); + + Eigen::VectorXd state(RobotLocalization::STATE_SIZE); + Eigen::MatrixXd covariance(RobotLocalization::STATE_SIZE, RobotLocalization::STATE_SIZE); + + std::string base_frame("base_link"); + g_listener->getState(time2, base_frame, state, covariance); + + EXPECT_DOUBLE_EQ(1.0, state(RobotLocalization::StateMemberX)); + EXPECT_DOUBLE_EQ(0.0, state(RobotLocalization::StateMemberY)); + EXPECT_DOUBLE_EQ(0.0, state(RobotLocalization::StateMemberZ)); + + EXPECT_FLOAT_EQ(M_PI/4, state(RobotLocalization::StateMemberRoll)); + EXPECT_FLOAT_EQ(0.0, state(RobotLocalization::StateMemberPitch)); + EXPECT_FLOAT_EQ(0.0, state(RobotLocalization::StateMemberYaw)); + + EXPECT_DOUBLE_EQ(M_PI/4.0, state(RobotLocalization::StateMemberVroll)); + EXPECT_DOUBLE_EQ(0.0, state(RobotLocalization::StateMemberVpitch)); + EXPECT_DOUBLE_EQ(0.0, state(RobotLocalization::StateMemberVyaw)); +} + +TEST(LocalizationListenerTest, GetStateOfRelatedFrame) +{ + ros::spinOnce(); + + Eigen::VectorXd state(RobotLocalization::STATE_SIZE); + Eigen::MatrixXd covariance(RobotLocalization::STATE_SIZE, RobotLocalization::STATE_SIZE); + + ros::Time time1(1000); + ros::Time time2(1001); + + std::string sensor_frame("sensor"); + + EXPECT_TRUE(g_listener->getState(time1, sensor_frame, state, covariance) ); + + EXPECT_FLOAT_EQ(0.0, state(RobotLocalization::StateMemberX)); + EXPECT_FLOAT_EQ(1.0, state(RobotLocalization::StateMemberY)); + EXPECT_FLOAT_EQ(0.0, state(RobotLocalization::StateMemberZ)); + + EXPECT_FLOAT_EQ(0.0, state(RobotLocalization::StateMemberRoll)); + EXPECT_FLOAT_EQ(0.0, state(RobotLocalization::StateMemberPitch)); + EXPECT_FLOAT_EQ(M_PI/2, state(RobotLocalization::StateMemberYaw)); + + EXPECT_TRUE(1e-12 > state(RobotLocalization::StateMemberVx)); + EXPECT_FLOAT_EQ(-1.0, state(RobotLocalization::StateMemberVy)); + EXPECT_FLOAT_EQ(M_PI/4.0, state(RobotLocalization::StateMemberVz)); + + EXPECT_TRUE(1e-12 > state(RobotLocalization::StateMemberVroll)); + EXPECT_FLOAT_EQ(-M_PI/4.0, state(RobotLocalization::StateMemberVpitch)); + EXPECT_FLOAT_EQ(0.0, state(RobotLocalization::StateMemberVyaw)); + + EXPECT_TRUE(g_listener->getState(time2, sensor_frame, state, covariance)); + + EXPECT_FLOAT_EQ(1.0, state(RobotLocalization::StateMemberX)); + EXPECT_FLOAT_EQ(sqrt(2)/2.0, state(RobotLocalization::StateMemberY)); + EXPECT_FLOAT_EQ(sqrt(2)/2.0, state(RobotLocalization::StateMemberZ)); + + EXPECT_TRUE(1e-12 > state(RobotLocalization::StateMemberRoll)); + EXPECT_TRUE(1e-12 > fabs(-M_PI/4.0 - state(RobotLocalization::StateMemberPitch))); + EXPECT_FLOAT_EQ(M_PI/2, state(RobotLocalization::StateMemberYaw)); + + EXPECT_TRUE(1e-12 > state(RobotLocalization::StateMemberVx)); + EXPECT_FLOAT_EQ(-1.0, state(RobotLocalization::StateMemberVy)); + EXPECT_FLOAT_EQ(M_PI/4, state(RobotLocalization::StateMemberVz)); + + EXPECT_TRUE(1e-12 > state(RobotLocalization::StateMemberVroll)); + EXPECT_FLOAT_EQ(-M_PI/4.0, state(RobotLocalization::StateMemberVpitch)); + EXPECT_FLOAT_EQ(0, state(RobotLocalization::StateMemberVyaw)); +} + +int main(int argc, char **argv) +{ + ros::init(argc, argv, "test_robot_localization_estimator"); + + g_listener = new RobotLocalization::RosRobotLocalizationListener(); + + testing::InitGoogleTest(&argc, argv); + + int res = RUN_ALL_TESTS(); + + delete g_listener; + + return res; +} diff --git a/navigations/robot_localization/test/test_ros_robot_localization_listener.test b/navigations/robot_localization/test/test_ros_robot_localization_listener.test new file mode 100755 index 0000000..e706abd --- /dev/null +++ b/navigations/robot_localization/test/test_ros_robot_localization_listener.test @@ -0,0 +1,68 @@ + + + + + + + + + + + + + + + + + + + + + + + + [true, false, true, false, false, false, false, false, false, false, false, false, false, false, false] + [true, true, true, true, true, true, false, false, false, false, false, false, false, false, false] + [false, false, false, false, false, false, true, true, true, true, true, true, false, false, false] + + [true, false, true, false, false, false, false, false, false, false, false, false, false, false, false] + [true, true, true, true, true, true, false, false, false, false, false, false, false, false, false] + + [false, false, false, false, false, false, true, true, true, true, true, true, false, false, false] + + [false, false, false, true, true, true, false, false, false, false, false, false, false, false, false] + [false, false, false, false, false, false, false, false, false, true, true, true, false, false, false] + [false, false, false, false, false, false, false, false, false, false, false, false, true, true, true] + [false, false, false, true, true, true, false, false, false, false, false, false, false, false, false] + + + + + + + + + + + [0.03, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.03, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.4, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.03, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.03, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.025, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.025, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.002, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.002, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.004, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01] + + + + + + + diff --git a/navigations/robot_localization/test/test_ros_robot_localization_listener_publisher.cpp b/navigations/robot_localization/test/test_ros_robot_localization_listener_publisher.cpp new file mode 100755 index 0000000..5dbff22 --- /dev/null +++ b/navigations/robot_localization/test/test_ros_robot_localization_listener_publisher.cpp @@ -0,0 +1,117 @@ +/* + * Copyright (c) 2016, TNO IVS, Helmond + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include +#include + +#include +#include +#include + +int main(int argc, char **argv) +{ + ros::init(argc, argv, "test_robot_localization_listener_publisher"); + + ros::NodeHandle nh; + ros::Publisher odom_pub = nh.advertise("odometry/filtered", 1); + ros::Publisher accel_pub = nh.advertise("accel/filtered", 1); + tf2_ros::StaticTransformBroadcaster transform_broadcaster; + + ros::Time end_time = ros::Time::now() + ros::Duration(10); + while (ros::ok() && ros::Time::now() < end_time) + { + ros::Time time1(1000); + double x, y, z, roll, pitch, yaw, vx, vy, vz, vroll, vpitch, vyaw, ax, ay, az; + x = y = z = roll = pitch = yaw = vy = vz = vroll = vpitch = vyaw = ax = ay = az = 0.0; + vx = 1.0; + vroll = M_PI/4.0; + + tf2::Quaternion q; + q.setRPY(0, 0, 0); + + nav_msgs::Odometry odom_msg; + odom_msg.header.stamp = time1; + odom_msg.header.frame_id = "map"; + odom_msg.child_frame_id = "base_link"; + odom_msg.pose.pose.position.x = x; + odom_msg.pose.pose.position.y = y; + odom_msg.pose.pose.position.y = z; + odom_msg.pose.pose.orientation.x = q.x(); + odom_msg.pose.pose.orientation.y = q.y(); + odom_msg.pose.pose.orientation.z = q.z(); + odom_msg.pose.pose.orientation.w = q.w(); + + odom_msg.twist.twist.linear.x = vx; + odom_msg.twist.twist.linear.y = vy; + odom_msg.twist.twist.linear.z = vz; + odom_msg.twist.twist.angular.x = vroll; + odom_msg.twist.twist.angular.y = vpitch; + odom_msg.twist.twist.angular.z = vyaw; + + geometry_msgs::AccelWithCovarianceStamped accel_msg; + accel_msg.header.stamp = time1; + accel_msg.header.frame_id = "base_link"; + accel_msg.accel.accel.linear.x = ax; + accel_msg.accel.accel.linear.y = ay; + accel_msg.accel.accel.linear.z = az; + accel_msg.accel.accel.angular.x = 0; + accel_msg.accel.accel.angular.y = 0; + accel_msg.accel.accel.angular.z = 0; + + odom_pub.publish(odom_msg); + accel_pub.publish(accel_msg); + + geometry_msgs::TransformStamped transformStamped; + + transformStamped.header.stamp = ros::Time::now(); + transformStamped.header.frame_id = "base_link"; + transformStamped.child_frame_id = "sensor"; + transformStamped.transform.translation.x = 0.0; + transformStamped.transform.translation.y = 1.0; + transformStamped.transform.translation.z = 0.0; + { + tf2::Quaternion q; + q.setRPY(0, 0, M_PI/2); + transformStamped.transform.rotation.x = q.x(); + transformStamped.transform.rotation.y = q.y(); + transformStamped.transform.rotation.z = q.z(); + transformStamped.transform.rotation.w = q.w(); + + transform_broadcaster.sendTransform(transformStamped); + } + + ros::Duration(0.1).sleep(); + } + + return 0; +} diff --git a/navigations/robot_localization/test/test_ukf.cpp b/navigations/robot_localization/test/test_ukf.cpp new file mode 100755 index 0000000..4348863 --- /dev/null +++ b/navigations/robot_localization/test/test_ukf.cpp @@ -0,0 +1,141 @@ +/* + * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include "robot_localization/ros_filter_types.h" + +#include + +#include +#include + +using RobotLocalization::Ukf; +using RobotLocalization::RosUkf; +using RobotLocalization::STATE_SIZE; + +class RosUkfPassThrough : public RosUkf +{ + public: + explicit RosUkfPassThrough(std::vector &args) : RosUkf(ros::NodeHandle(), ros::NodeHandle("~"), args) + { + } + + Ukf &getFilter() + { + return filter_; + } +}; + +TEST(UkfTest, Measurements) +{ + std::vector args; + args.push_back(0.001); + args.push_back(0); + args.push_back(2); + + RosUkfPassThrough ukf(args); + + Eigen::MatrixXd initialCovar(15, 15); + initialCovar.setIdentity(); + initialCovar *= 0.5; + ukf.getFilter().setEstimateErrorCovariance(initialCovar); + + EXPECT_EQ(ukf.getFilter().getEstimateErrorCovariance(), initialCovar); + + Eigen::VectorXd measurement(STATE_SIZE); + for (size_t i = 0; i < STATE_SIZE; ++i) + { + measurement[i] = i * 0.01 * STATE_SIZE; + } + + Eigen::MatrixXd measurementCovariance(STATE_SIZE, STATE_SIZE); + measurementCovariance.setIdentity(); + for (size_t i = 0; i < STATE_SIZE; ++i) + { + measurementCovariance(i, i) = 1e-9; + } + + std::vector updateVector(STATE_SIZE, true); + + // Ensure that measurements are being placed in the queue correctly + ros::Time time; + time.fromSec(1000); + ukf.enqueueMeasurement("odom0", + measurement, + measurementCovariance, + updateVector, + std::numeric_limits::max(), + time); + + ukf.integrateMeasurements(ros::Time(1001)); + + EXPECT_EQ(ukf.getFilter().getState(), measurement); + EXPECT_EQ(ukf.getFilter().getEstimateErrorCovariance(), measurementCovariance); + + ukf.getFilter().setEstimateErrorCovariance(initialCovar); + + // Now fuse another measurement and check the output. + // We know what the filter's state should be when + // this is complete, so we'll check the difference and + // make sure it's suitably small. + Eigen::VectorXd measurement2 = measurement; + + measurement2 *= 2.0; + + for (size_t i = 0; i < STATE_SIZE; ++i) + { + measurementCovariance(i, i) = 1e-9; + } + + time.fromSec(1002); + ukf.enqueueMeasurement("odom0", + measurement2, + measurementCovariance, + updateVector, + std::numeric_limits::max(), + time); + + ukf.integrateMeasurements(ros::Time(1003)); + + measurement = measurement2.eval() - ukf.getFilter().getState(); + for (size_t i = 0; i < STATE_SIZE; ++i) + { + EXPECT_LT(::fabs(measurement[i]), 0.001); + } +} + +int main(int argc, char **argv) +{ + ros::init(argc, argv, "ukf"); + + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/navigations/robot_localization/test/test_ukf.test b/navigations/robot_localization/test/test_ukf.test new file mode 100755 index 0000000..211480a --- /dev/null +++ b/navigations/robot_localization/test/test_ukf.test @@ -0,0 +1,7 @@ + + + + + + + diff --git a/navigations/robot_localization/test/test_ukf_localization_node_bag1.test b/navigations/robot_localization/test/test_ukf_localization_node_bag1.test new file mode 100755 index 0000000..1592c65 --- /dev/null +++ b/navigations/robot_localization/test/test_ukf_localization_node_bag1.test @@ -0,0 +1,110 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [false, false, false, + false, false, false, + true, true, true, + false, false, false, + false, false, false] + + [false, false, false, + true, true, true, + false, false, false, + true, true, false, + true, true, true] + + + + + + + + + + + + + + + + + + [0.05, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0.05, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0.06, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0.03, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0.03, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0.06, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0.025, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0.025, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0.04, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.02, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.015] + + [1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9] + + + + + + + + + + + + + + + + + diff --git a/navigations/robot_localization/test/test_ukf_localization_node_bag2.test b/navigations/robot_localization/test/test_ukf_localization_node_bag2.test new file mode 100755 index 0000000..5fbbe16 --- /dev/null +++ b/navigations/robot_localization/test/test_ukf_localization_node_bag2.test @@ -0,0 +1,91 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + [false, false, false, + false, false, false, + true, true, true, + false, false, true, + false, false, false] + + [false, false, false, + true, true, true, + false, false, false, + true, true, true, + true, true, true] + + + + + + + [0.03, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0.03, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0.4, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0.03, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0.03, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0.06, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0.025, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0.025, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0.05, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.002, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.002, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.004, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01] + + [1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9] + + + + + + + + + + + + + + + + + diff --git a/navigations/robot_localization/test/test_ukf_localization_node_bag3.test b/navigations/robot_localization/test/test_ukf_localization_node_bag3.test new file mode 100755 index 0000000..d2c0e6a --- /dev/null +++ b/navigations/robot_localization/test/test_ukf_localization_node_bag3.test @@ -0,0 +1,79 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + [false, false, true, + false, false, false, + true, true, false, + false, false, true, + false, false, false] + + [false, false, false, + true, true, true, + false, false, false, + true, true, true, + false, false, false] + + + + + + + + + + + + + + + [0.03, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.03, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.4, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.03, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.03, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.025, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.025, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.002, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.002, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.004, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01] + + + + + + + + + + + + + diff --git a/navigations/robot_localization/test/test_ukf_localization_node_interfaces.cpp b/navigations/robot_localization/test/test_ukf_localization_node_interfaces.cpp new file mode 100755 index 0000000..153acb0 --- /dev/null +++ b/navigations/robot_localization/test/test_ukf_localization_node_interfaces.cpp @@ -0,0 +1,1079 @@ +/* + * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include "robot_localization/SetPose.h" + +#include +#include +#include +#include +#include + +#include +#include + +#include + +#include + +nav_msgs::Odometry filtered_; + +bool stateUpdated_; + +void resetFilter() +{ + ros::NodeHandle nh; + ros::ServiceClient client = nh.serviceClient("/set_pose"); + + robot_localization::SetPose setPose; + setPose.request.pose.pose.pose.orientation.w = 1; + setPose.request.pose.header.frame_id = "odom"; + for (size_t ind = 0; ind < 36; ind+=7) + { + setPose.request.pose.pose.covariance[ind] = 1e-6; + } + + setPose.request.pose.header.stamp = ros::Time::now(); + client.call(setPose); + setPose.request.pose.header.seq++; + ros::spinOnce(); + ros::Duration(0.01).sleep(); + stateUpdated_ = false; + + double deltaX = 0.0; + double deltaY = 0.0; + double deltaZ = 0.0; + + while (!stateUpdated_ || ::sqrt(deltaX * deltaX + deltaY * deltaY + deltaZ * deltaZ) > 0.1) + { + ros::spinOnce(); + ros::Duration(0.01).sleep(); + + deltaX = filtered_.pose.pose.position.x - setPose.request.pose.pose.pose.position.x; + deltaY = filtered_.pose.pose.position.y - setPose.request.pose.pose.pose.position.y; + deltaZ = filtered_.pose.pose.position.z - setPose.request.pose.pose.pose.position.z; + } + + EXPECT_LT(::sqrt(deltaX * deltaX + deltaY * deltaY + deltaZ * deltaZ), 0.1); +} + +void filterCallback(const nav_msgs::OdometryConstPtr &msg) +{ + filtered_ = *msg; + stateUpdated_ = true; +} + +TEST(InterfacesTest, OdomPoseBasicIO) +{ + stateUpdated_ = false; + + ros::NodeHandle nh; + ros::Publisher odomPub = nh.advertise("/odom_input0", 5); + ros::Subscriber filteredSub = nh.subscribe("/odometry/filtered", 1, &filterCallback); + + nav_msgs::Odometry odom; + odom.pose.pose.position.x = 20.0; + odom.pose.pose.position.y = 10.0; + odom.pose.pose.position.z = -40.0; + + odom.pose.covariance[0] = 2.0; + odom.pose.covariance[7] = 2.0; + odom.pose.covariance[14] = 2.0; + + odom.header.frame_id = "odom"; + odom.child_frame_id = "base_link"; + + ros::Rate loopRate(50); + for (size_t i = 0; i < 50; ++i) + { + odom.header.stamp = ros::Time::now(); + odomPub.publish(odom); + ros::spinOnce(); + + loopRate.sleep(); + + odom.header.seq++; + } + + // Now check the values from the callback + EXPECT_LT(::fabs(filtered_.pose.pose.position.x - odom.pose.pose.position.x), 0.01); + EXPECT_LT(::fabs(filtered_.pose.pose.position.y), 0.01); // Configuration for this variable for this sensor is false + EXPECT_LT(::fabs(filtered_.pose.pose.position.z - odom.pose.pose.position.z), 0.01); + + EXPECT_LT(filtered_.pose.covariance[0], 0.5); + EXPECT_LT(filtered_.pose.covariance[7], 0.25); // Configuration for this variable for this sensor is false + EXPECT_LT(filtered_.pose.covariance[14], 0.6); + + resetFilter(); +} + +TEST(InterfacesTest, OdomTwistBasicIO) +{ + ros::NodeHandle nh; + ros::Publisher odomPub = nh.advertise("/odom_input2", 5); + ros::Subscriber filteredSub = nh.subscribe("/odometry/filtered", 1, &filterCallback); + + nav_msgs::Odometry odom; + odom.twist.twist.linear.x = 5.0; + odom.twist.twist.linear.y = 0.0; + odom.twist.twist.linear.z = 0.0; + odom.twist.twist.angular.x = 0.0; + odom.twist.twist.angular.y = 0.0; + odom.twist.twist.angular.z = 0.0; + + for (size_t ind = 0; ind < 36; ind+=7) + { + odom.twist.covariance[ind] = 1e-6; + } + + odom.header.frame_id = "odom"; + odom.child_frame_id = "base_link"; + + ros::Rate loopRate(20); + for (size_t i = 0; i < 400; ++i) + { + odom.header.stamp = ros::Time::now(); + odomPub.publish(odom); + ros::spinOnce(); + + loopRate.sleep(); + + odom.header.seq++; + } + ros::spinOnce(); + + EXPECT_LT(::fabs(filtered_.twist.twist.linear.x - odom.twist.twist.linear.x), 0.1); + EXPECT_LT(::fabs(filtered_.pose.pose.position.x - 100.0), 2.0); + + resetFilter(); + + odom.twist.twist.linear.x = 0.0; + odom.twist.twist.linear.y = 5.0; + + loopRate = ros::Rate(20); + for (size_t i = 0; i < 200; ++i) + { + odom.header.stamp = ros::Time::now(); + odomPub.publish(odom); + ros::spinOnce(); + + loopRate.sleep(); + + odom.header.seq++; + } + ros::spinOnce(); + + EXPECT_LT(::fabs(filtered_.twist.twist.linear.y - odom.twist.twist.linear.y), 0.1); + EXPECT_LT(::fabs(filtered_.pose.pose.position.y - 50.0), 1.0); + + resetFilter(); + + odom.twist.twist.linear.y = 0.0; + odom.twist.twist.linear.z = 5.0; + + loopRate = ros::Rate(20); + for (size_t i = 0; i < 100; ++i) + { + odom.header.stamp = ros::Time::now(); + odomPub.publish(odom); + ros::spinOnce(); + + loopRate.sleep(); + + odom.header.seq++; + } + ros::spinOnce(); + + EXPECT_LT(::fabs(filtered_.twist.twist.linear.z - odom.twist.twist.linear.z), 0.1); + EXPECT_LT(::fabs(filtered_.pose.pose.position.z - 25.0), 1.0); + + resetFilter(); + + odom.twist.twist.linear.z = 0.0; + odom.twist.twist.linear.x = 1.0; + odom.twist.twist.angular.z = (M_PI/2) / (100.0 * 0.05); + + loopRate = ros::Rate(20); + for (size_t i = 0; i < 100; ++i) + { + odom.header.stamp = ros::Time::now(); + odomPub.publish(odom); + ros::spinOnce(); + + loopRate.sleep(); + + odom.header.seq++; + } + ros::spinOnce(); + + EXPECT_LT(::fabs(filtered_.twist.twist.linear.x - odom.twist.twist.linear.x), 0.1); + EXPECT_LT(::fabs(filtered_.twist.twist.angular.z - odom.twist.twist.angular.z), 0.1); + EXPECT_LT(::fabs(filtered_.pose.pose.position.x - filtered_.pose.pose.position.y), 0.5); + + resetFilter(); + + odom.twist.twist.linear.x = 0.0; + odom.twist.twist.angular.z = 0.0; + odom.twist.twist.angular.x = -(M_PI/2) / (100.0 * 0.05); + + // First, roll the vehicle on its side + loopRate = ros::Rate(20); + for (size_t i = 0; i < 100; ++i) + { + odom.header.stamp = ros::Time::now(); + odomPub.publish(odom); + ros::spinOnce(); + + loopRate.sleep(); + + odom.header.seq++; + } + ros::spinOnce(); + + odom.twist.twist.angular.x = 0.0; + odom.twist.twist.angular.y = (M_PI/2) / (100.0 * 0.05); + + // Now, pitch it down (positive pitch velocity in vehicle frame) + loopRate = ros::Rate(20); + for (size_t i = 0; i < 100; ++i) + { + odom.header.stamp = ros::Time::now(); + odomPub.publish(odom); + ros::spinOnce(); + + loopRate.sleep(); + + odom.header.seq++; + } + ros::spinOnce(); + + odom.twist.twist.angular.y = 0.0; + odom.twist.twist.linear.x = 3.0; + + // We should now be on our side and facing -Y. Move forward in + // the vehicle frame X direction, and make sure Y decreases in + // the world frame. + loopRate = ros::Rate(20); + for (size_t i = 0; i < 100; ++i) + { + odom.header.stamp = ros::Time::now(); + odomPub.publish(odom); + ros::spinOnce(); + + loopRate.sleep(); + + odom.header.seq++; + } + ros::spinOnce(); + + EXPECT_LT(::fabs(filtered_.twist.twist.linear.x - odom.twist.twist.linear.x), 0.1); + EXPECT_LT(::fabs(filtered_.pose.pose.position.y + 15), 1.0); + + resetFilter(); +} + +TEST(InterfacesTest, PoseBasicIO) +{ + ros::NodeHandle nh; + ros::Publisher posePub = nh.advertise("/pose_input0", 5); + ros::Subscriber filteredSub = nh.subscribe("/odometry/filtered", 1, &filterCallback); + + geometry_msgs::PoseWithCovarianceStamped pose; + pose.pose.pose.position.x = 20.0; + pose.pose.pose.position.y = 10.0; + pose.pose.pose.position.z = -40.0; + pose.pose.pose.orientation.x = 0; + pose.pose.pose.orientation.y = 0; + pose.pose.pose.orientation.z = 0; + pose.pose.pose.orientation.w = 1; + + for (size_t ind = 0; ind < 36; ind+=7) + { + pose.pose.covariance[ind] = 1e-6; + } + + pose.header.frame_id = "odom"; + + ros::Rate loopRate = ros::Rate(50); + for (size_t i = 0; i < 50; ++i) + { + pose.header.stamp = ros::Time::now(); + posePub.publish(pose); + ros::spinOnce(); + + loopRate.sleep(); + + pose.header.seq++; + } + + // Now check the values from the callback + EXPECT_LT(::fabs(filtered_.pose.pose.position.x - pose.pose.pose.position.x), 0.1); + EXPECT_LT(::fabs(filtered_.pose.pose.position.y), 0.1); // Configuration for this variable for this sensor is false + EXPECT_LT(::fabs(filtered_.pose.pose.position.z - pose.pose.pose.position.z), 0.1); + + EXPECT_LT(filtered_.pose.covariance[0], 0.5); + EXPECT_LT(filtered_.pose.covariance[7], 0.25); // Configuration for this variable for this sensor is false + EXPECT_LT(filtered_.pose.covariance[14], 0.5); + + resetFilter(); +} + +TEST(InterfacesTest, TwistBasicIO) +{ + ros::NodeHandle nh; + ros::Publisher twistPub = nh.advertise("/twist_input0", 5); + ros::Subscriber filteredSub = nh.subscribe("/odometry/filtered", 1, &filterCallback); + + geometry_msgs::TwistWithCovarianceStamped twist; + twist.twist.twist.linear.x = 5.0; + twist.twist.twist.linear.y = 0; + twist.twist.twist.linear.z = 0; + twist.twist.twist.angular.x = 0; + twist.twist.twist.angular.y = 0; + twist.twist.twist.angular.z = 0; + + for (size_t ind = 0; ind < 36; ind+=7) + { + twist.twist.covariance[ind] = 1e-6; + } + + twist.header.frame_id = "base_link"; + + ros::Rate loopRate = ros::Rate(20); + for (size_t i = 0; i < 400; ++i) + { + twist.header.stamp = ros::Time::now(); + twistPub.publish(twist); + ros::spinOnce(); + + loopRate.sleep(); + + twist.header.seq++; + } + ros::spinOnce(); + + EXPECT_LT(::fabs(filtered_.twist.twist.linear.x - twist.twist.twist.linear.x), 0.1); + EXPECT_LT(::fabs(filtered_.pose.pose.position.x - 100.0), 2.0); + + resetFilter(); + + twist.twist.twist.linear.x = 0.0; + twist.twist.twist.linear.y = 5.0; + + loopRate = ros::Rate(20); + for (size_t i = 0; i < 200; ++i) + { + twist.header.stamp = ros::Time::now(); + twistPub.publish(twist); + ros::spinOnce(); + + loopRate.sleep(); + + twist.header.seq++; + } + ros::spinOnce(); + + EXPECT_LT(::fabs(filtered_.twist.twist.linear.y - twist.twist.twist.linear.y), 0.1); + EXPECT_LT(::fabs(filtered_.pose.pose.position.y - 50.0), 1.0); + + resetFilter(); + + twist.twist.twist.linear.y = 0.0; + twist.twist.twist.linear.z = 5.0; + + loopRate = ros::Rate(20); + for (size_t i = 0; i < 100; ++i) + { + twist.header.stamp = ros::Time::now(); + twistPub.publish(twist); + ros::spinOnce(); + + loopRate.sleep(); + + twist.header.seq++; + } + ros::spinOnce(); + + EXPECT_LT(::fabs(filtered_.twist.twist.linear.z - twist.twist.twist.linear.z), 0.1); + EXPECT_LT(::fabs(filtered_.pose.pose.position.z - 25.0), 1.0); + + resetFilter(); + + twist.twist.twist.linear.z = 0.0; + twist.twist.twist.linear.x = 1.0; + twist.twist.twist.angular.z = (M_PI/2) / (100.0 * 0.05); + + loopRate = ros::Rate(20); + for (size_t i = 0; i < 100; ++i) + { + twist.header.stamp = ros::Time::now(); + twistPub.publish(twist); + ros::spinOnce(); + + loopRate.sleep(); + + twist.header.seq++; + } + ros::spinOnce(); + + EXPECT_LT(::fabs(filtered_.twist.twist.linear.x - twist.twist.twist.linear.x), 0.1); + EXPECT_LT(::fabs(filtered_.twist.twist.angular.z - twist.twist.twist.angular.z), 0.1); + EXPECT_LT(::fabs(filtered_.pose.pose.position.x - filtered_.pose.pose.position.y), 0.5); + + resetFilter(); + + twist.twist.twist.linear.x = 0.0; + twist.twist.twist.angular.z = 0.0; + twist.twist.twist.angular.x = -(M_PI/2) / (100.0 * 0.05); + + // First, roll the vehicle on its side + loopRate = ros::Rate(20); + for (size_t i = 0; i < 100; ++i) + { + twist.header.stamp = ros::Time::now(); + twistPub.publish(twist); + ros::spinOnce(); + + loopRate.sleep(); + + twist.header.seq++; + } + ros::spinOnce(); + + twist.twist.twist.angular.x = 0.0; + twist.twist.twist.angular.y = (M_PI/2) / (100.0 * 0.05); + + // Now, pitch it down (positive pitch velocity in vehicle frame) + loopRate = ros::Rate(20); + for (size_t i = 0; i < 100; ++i) + { + twist.header.stamp = ros::Time::now(); + twistPub.publish(twist); + ros::spinOnce(); + + loopRate.sleep(); + + twist.header.seq++; + } + ros::spinOnce(); + + twist.twist.twist.angular.y = 0.0; + twist.twist.twist.linear.x = 3.0; + + // We should now be on our side and facing -Y. Move forward in + // the vehicle frame X direction, and make sure Y decreases in + // the world frame. + loopRate = ros::Rate(20); + for (size_t i = 0; i < 100; ++i) + { + twist.header.stamp = ros::Time::now(); + twistPub.publish(twist); + ros::spinOnce(); + + loopRate.sleep(); + + twist.header.seq++; + } + ros::spinOnce(); + + EXPECT_LT(::fabs(filtered_.twist.twist.linear.x - twist.twist.twist.linear.x), 0.1); + EXPECT_LT(::fabs(filtered_.pose.pose.position.y + 15), 1.0); + + resetFilter(); +} + +TEST(InterfacesTest, ImuPoseBasicIO) +{ + ros::NodeHandle nh; + ros::Publisher imuPub = nh.advertise("/imu_input0", 5); + ros::Subscriber filteredSub = nh.subscribe("/odometry/filtered", 1, &filterCallback); + + sensor_msgs::Imu imu; + tf2::Quaternion quat; + quat.setRPY(M_PI/4, -M_PI/4, M_PI/2); + imu.orientation = tf2::toMsg(quat); + + for (size_t ind = 0; ind < 9; ind+=4) + { + imu.orientation_covariance[ind] = 1e-6; + } + + imu.header.frame_id = "base_link"; + + // Make sure the pose reset worked. Test will timeout + // if this fails. + ros::Rate loopRate(50); + for (size_t i = 0; i < 50; ++i) + { + imu.header.stamp = ros::Time::now(); + imuPub.publish(imu); + ros::spinOnce(); + + loopRate.sleep(); + + imu.header.seq++; + } + + // Now check the values from the callback + tf2::fromMsg(filtered_.pose.pose.orientation, quat); + tf2::Matrix3x3 mat(quat); + double r, p, y; + mat.getRPY(r, p, y); + EXPECT_LT(::fabs(r - M_PI/4), 0.1); + EXPECT_LT(::fabs(p + M_PI/4), 0.1); + EXPECT_LT(::fabs(y - M_PI/2), 0.1); + + EXPECT_LT(filtered_.pose.covariance[21], 0.5); + EXPECT_LT(filtered_.pose.covariance[28], 0.25); + EXPECT_LT(filtered_.pose.covariance[35], 0.5); + + resetFilter(); + + // Test to see if the orientation data is ignored when we set the + // first covariance value to -1 + sensor_msgs::Imu imuIgnore; + imuIgnore.orientation.x = 0.1; + imuIgnore.orientation.y = 0.2; + imuIgnore.orientation.z = 0.3; + imuIgnore.orientation.w = 0.4; + imuIgnore.orientation_covariance[0] = -1; + + loopRate = ros::Rate(50); + for (size_t i = 0; i < 50; ++i) + { + imuIgnore.header.stamp = ros::Time::now(); + imuPub.publish(imuIgnore); + loopRate.sleep(); + ros::spinOnce(); + + imuIgnore.header.seq++; + } + + tf2::fromMsg(filtered_.pose.pose.orientation, quat); + mat.setRotation(quat); + mat.getRPY(r, p, y); + EXPECT_LT(::fabs(r), 1e-3); + EXPECT_LT(::fabs(p), 1e-3); + EXPECT_LT(::fabs(y), 1e-3); + + resetFilter(); +} + +TEST(InterfacesTest, ImuTwistBasicIO) +{ + ros::NodeHandle nh; + ros::Publisher imuPub = nh.advertise("/imu_input1", 5); + ros::Subscriber filteredSub = nh.subscribe("/odometry/filtered", 1, &filterCallback); + + sensor_msgs::Imu imu; + tf2::Quaternion quat; + imu.angular_velocity.x = (M_PI / 2.0); + + for (size_t ind = 0; ind < 9; ind+=4) + { + imu.angular_velocity_covariance[ind] = 1e-6; + } + + imu.header.frame_id = "base_link"; + + ros::Rate loopRate(50); + for (size_t i = 0; i < 50; ++i) + { + imu.header.stamp = ros::Time::now(); + imuPub.publish(imu); + loopRate.sleep(); + ros::spinOnce(); + + imu.header.seq++; + } + + // Now check the values from the callback + tf2::fromMsg(filtered_.pose.pose.orientation, quat); + tf2::Matrix3x3 mat(quat); + double r, p, y; + mat.getRPY(r, p, y); + + // Tolerances may seem loose, but the initial state covariances + // are tiny, so the filter is sluggish to accept velocity data + EXPECT_LT(::fabs(r - M_PI / 2.0), 0.7); + EXPECT_LT(::fabs(p), 0.1); + EXPECT_LT(::fabs(y), 0.1); + + EXPECT_LT(filtered_.twist.covariance[21], 1e-3); + EXPECT_LT(filtered_.pose.covariance[21], 0.1); + + resetFilter(); + + imu.angular_velocity.x = 0.0; + imu.angular_velocity.y = -(M_PI / 2.0); + + // Make sure the pose reset worked. Test will timeout + // if this fails. + loopRate = ros::Rate(50); + for (size_t i = 0; i < 50; ++i) + { + imu.header.stamp = ros::Time::now(); + imuPub.publish(imu); + loopRate.sleep(); + ros::spinOnce(); + + imu.header.seq++; + } + + // Now check the values from the callback + tf2::fromMsg(filtered_.pose.pose.orientation, quat); + + tf2::Quaternion expected_quat(tf2::Vector3(0., 1., 0.), -M_PI/2.0); + + EXPECT_LT(std::abs(tf2Angle(expected_quat.getAxis(), quat.getAxis())), 0.1); + EXPECT_LT(std::abs(expected_quat.getAngle() - quat.getAngle()), 0.7); + + EXPECT_LT(filtered_.twist.covariance[28], 1e-3); + EXPECT_LT(filtered_.pose.covariance[28], 0.1); + + resetFilter(); + + imu.angular_velocity.y = 0; + imu.angular_velocity.z = M_PI / 4.0; + + // Make sure the pose reset worked. Test will timeout + // if this fails. + loopRate = ros::Rate(50); + for (size_t i = 0; i < 50; ++i) + { + imu.header.stamp = ros::Time::now(); + imuPub.publish(imu); + loopRate.sleep(); + ros::spinOnce(); + + imu.header.seq++; + } + + // Now check the values from the callback + tf2::fromMsg(filtered_.pose.pose.orientation, quat); + mat.setRotation(quat); + mat.getRPY(r, p, y); + EXPECT_LT(::fabs(r), 0.1); + EXPECT_LT(::fabs(p), 0.1); + EXPECT_LT(::fabs(y - M_PI / 4.0), 0.7); + + EXPECT_LT(filtered_.twist.covariance[35], 1e-3); + EXPECT_LT(filtered_.pose.covariance[35], 0.1); + + resetFilter(); + + // Test to see if the angular velocity data is ignored when we set the + // first covariance value to -1 + sensor_msgs::Imu imuIgnore; + imuIgnore.angular_velocity.x = 100; + imuIgnore.angular_velocity.y = 100; + imuIgnore.angular_velocity.z = 100; + imuIgnore.angular_velocity_covariance[0] = -1; + + loopRate = ros::Rate(50); + for (size_t i = 0; i < 50; ++i) + { + imuIgnore.header.stamp = ros::Time::now(); + imuPub.publish(imuIgnore); + loopRate.sleep(); + ros::spinOnce(); + + imuIgnore.header.seq++; + } + + tf2::fromMsg(filtered_.pose.pose.orientation, quat); + mat.setRotation(quat); + mat.getRPY(r, p, y); + EXPECT_LT(::fabs(r), 1e-3); + EXPECT_LT(::fabs(p), 1e-3); + EXPECT_LT(::fabs(y), 1e-3); + + resetFilter(); +} + +TEST(InterfacesTest, ImuAccBasicIO) +{ + ros::NodeHandle nh; + ros::Publisher imuPub = nh.advertise("/imu_input2", 5); + ros::Subscriber filteredSub = nh.subscribe("/odometry/filtered", 1, &filterCallback); + + sensor_msgs::Imu imu; + imu.header.frame_id = "base_link"; + imu.linear_acceleration_covariance[0] = 1e-6; + imu.linear_acceleration_covariance[4] = 1e-6; + imu.linear_acceleration_covariance[8] = 1e-6; + + imu.linear_acceleration.x = 1; + imu.linear_acceleration.y = -1; + imu.linear_acceleration.z = 1; + + // Move with constant acceleration for 1 second, + // then check our velocity. + ros::Rate loopRate(50); + for (size_t i = 0; i < 50; ++i) + { + imu.header.stamp = ros::Time::now(); + imuPub.publish(imu); + loopRate.sleep(); + ros::spinOnce(); + + imu.header.seq++; + } + + EXPECT_LT(::fabs(filtered_.twist.twist.linear.x - 1.0), 0.4); + EXPECT_LT(::fabs(filtered_.twist.twist.linear.y + 1.0), 0.4); + EXPECT_LT(::fabs(filtered_.twist.twist.linear.z - 1.0), 0.4); + + imu.linear_acceleration.x = 0.0; + imu.linear_acceleration.y = 0.0; + imu.linear_acceleration.z = 0.0; + + // Now move for another second, and see where we + // end up + loopRate = ros::Rate(50); + for (size_t i = 0; i < 50; ++i) + { + imu.header.stamp = ros::Time::now(); + imuPub.publish(imu); + loopRate.sleep(); + ros::spinOnce(); + + imu.header.seq++; + } + + EXPECT_LT(::fabs(filtered_.pose.pose.position.x - 1.2), 0.4); + EXPECT_LT(::fabs(filtered_.pose.pose.position.y + 1.2), 0.4); + EXPECT_LT(::fabs(filtered_.pose.pose.position.z - 1.2), 0.4); + + resetFilter(); + + // Test to see if the linear acceleration data is ignored when we set the + // first covariance value to -1 + sensor_msgs::Imu imuIgnore; + imuIgnore.linear_acceleration.x = 1000; + imuIgnore.linear_acceleration.y = 1000; + imuIgnore.linear_acceleration.z = 1000; + imuIgnore.linear_acceleration_covariance[0] = -1; + + loopRate = ros::Rate(50); + for (size_t i = 0; i < 50; ++i) + { + imuIgnore.header.stamp = ros::Time::now(); + imuPub.publish(imuIgnore); + loopRate.sleep(); + ros::spinOnce(); + + imuIgnore.header.seq++; + } + + EXPECT_LT(::fabs(filtered_.pose.pose.position.x), 1e-3); + EXPECT_LT(::fabs(filtered_.pose.pose.position.y), 1e-3); + EXPECT_LT(::fabs(filtered_.pose.pose.position.z), 1e-3); + + resetFilter(); +} + +TEST(InterfacesTest, OdomDifferentialIO) +{ + ros::NodeHandle nh; + ros::Publisher odomPub = nh.advertise("/odom_input1", 5); + ros::Subscriber filteredSub = nh.subscribe("/odometry/filtered", 1, &filterCallback); + + nav_msgs::Odometry odom; + odom.pose.pose.position.x = 20.0; + odom.pose.pose.position.y = 10.0; + odom.pose.pose.position.z = -40.0; + + odom.pose.pose.orientation.w = 1; + + odom.pose.covariance[0] = 2.0; + odom.pose.covariance[7] = 2.0; + odom.pose.covariance[14] = 2.0; + odom.pose.covariance[21] = 0.2; + odom.pose.covariance[28] = 0.2; + odom.pose.covariance[35] = 0.2; + + odom.header.frame_id = "odom"; + odom.child_frame_id = "base_link"; + + // No guaranteeing that the zero state + // we're expecting to see here isn't just + // a result of zeroing it out previously, + // so check 10 times in succession. + size_t zeroCount = 0; + while (zeroCount++ < 10) + { + odom.header.stamp = ros::Time::now(); + odomPub.publish(odom); + ros::spinOnce(); + + EXPECT_LT(::fabs(filtered_.pose.pose.position.x), 0.01); + EXPECT_LT(::fabs(filtered_.pose.pose.position.y), 0.01); + EXPECT_LT(::fabs(filtered_.pose.pose.position.z), 0.01); + EXPECT_LT(::fabs(filtered_.pose.pose.orientation.x), 0.01); + EXPECT_LT(::fabs(filtered_.pose.pose.orientation.y), 0.01); + EXPECT_LT(::fabs(filtered_.pose.pose.orientation.z), 0.01); + EXPECT_LT(::fabs(filtered_.pose.pose.orientation.w - 1), 0.01); + + ros::Duration(0.1).sleep(); + + odom.header.seq++; + } + + for (size_t ind = 0; ind < 36; ind+=7) + { + odom.pose.covariance[ind] = 1e-6; + } + + // Slowly move the position, and hope that the + // differential position keeps up + ros::Rate loopRate(20); + for (size_t i = 0; i < 100; ++i) + { + odom.pose.pose.position.x += 0.01; + odom.pose.pose.position.y += 0.02; + odom.pose.pose.position.z -= 0.03; + + odom.header.stamp = ros::Time::now(); + odomPub.publish(odom); + ros::spinOnce(); + + loopRate.sleep(); + + odom.header.seq++; + } + ros::spinOnce(); + + EXPECT_LT(::fabs(filtered_.pose.pose.position.x - 1), 0.2); + EXPECT_LT(::fabs(filtered_.pose.pose.position.y - 2), 0.4); + EXPECT_LT(::fabs(filtered_.pose.pose.position.z + 3), 0.6); + + resetFilter(); +} + +TEST(InterfacesTest, PoseDifferentialIO) +{ + ros::NodeHandle nh; + ros::Publisher posePub = nh.advertise("/pose_input1", 5); + ros::Subscriber filteredSub = nh.subscribe("/odometry/filtered", 1, &filterCallback); + + geometry_msgs::PoseWithCovarianceStamped pose; + pose.pose.pose.position.x = 20.0; + pose.pose.pose.position.y = 10.0; + pose.pose.pose.position.z = -40.0; + + pose.pose.pose.orientation.w = 1; + + pose.pose.covariance[0] = 2.0; + pose.pose.covariance[7] = 2.0; + pose.pose.covariance[14] = 2.0; + pose.pose.covariance[21] = 0.2; + pose.pose.covariance[28] = 0.2; + pose.pose.covariance[35] = 0.2; + + pose.header.frame_id = "odom"; + + // No guaranteeing that the zero state + // we're expecting to see here isn't just + // a result of zeroing it out previously, + // so check 10 times in succession. + size_t zeroCount = 0; + while (zeroCount++ < 10) + { + pose.header.stamp = ros::Time::now(); + posePub.publish(pose); + ros::spinOnce(); + + EXPECT_LT(::fabs(filtered_.pose.pose.position.x), 0.01); + EXPECT_LT(::fabs(filtered_.pose.pose.position.y), 0.01); + EXPECT_LT(::fabs(filtered_.pose.pose.position.z), 0.01); + EXPECT_LT(::fabs(filtered_.pose.pose.orientation.x), 0.01); + EXPECT_LT(::fabs(filtered_.pose.pose.orientation.y), 0.01); + EXPECT_LT(::fabs(filtered_.pose.pose.orientation.z), 0.01); + EXPECT_LT(::fabs(filtered_.pose.pose.orientation.w - 1), 0.01); + + ros::Duration(0.1).sleep(); + + pose.header.seq++; + } + + // ...but only if we give the measurement a tiny covariance + for (size_t ind = 0; ind < 36; ind+=7) + { + pose.pose.covariance[ind] = 1e-6; + } + + // Issue this location repeatedly, and see if we get + // a final reported position of (1, 2, -3) + ros::Rate loopRate(20); + for (size_t i = 0; i < 100; ++i) + { + pose.pose.pose.position.x += 0.01; + pose.pose.pose.position.y += 0.02; + pose.pose.pose.position.z -= 0.03; + + pose.header.stamp = ros::Time::now(); + posePub.publish(pose); + ros::spinOnce(); + + loopRate.sleep(); + + pose.header.seq++; + } + ros::spinOnce(); + + EXPECT_LT(::fabs(filtered_.pose.pose.position.x - 1), 0.2); + EXPECT_LT(::fabs(filtered_.pose.pose.position.y - 2), 0.4); + EXPECT_LT(::fabs(filtered_.pose.pose.position.z + 3), 0.6); + + resetFilter(); +} + +TEST(InterfacesTest, ImuDifferentialIO) +{ + ros::NodeHandle nh; + ros::Publisher imu0Pub = nh.advertise("/imu_input0", 5); + ros::Publisher imu1Pub = nh.advertise("/imu_input1", 5); + ros::Publisher imuPub = nh.advertise("/imu_input3", 5); + ros::Subscriber filteredSub = nh.subscribe("/odometry/filtered", 1, &filterCallback); + + sensor_msgs::Imu imu; + imu.header.frame_id = "base_link"; + tf2::Quaternion quat; + const double roll = M_PI/2.0; + const double pitch = -M_PI; + const double yaw = -M_PI/4.0; + quat.setRPY(roll, pitch, yaw); + imu.orientation = tf2::toMsg(quat); + + imu.orientation_covariance[0] = 0.02; + imu.orientation_covariance[4] = 0.02; + imu.orientation_covariance[8] = 0.02; + + imu.angular_velocity_covariance[0] = 0.02; + imu.angular_velocity_covariance[4] = 0.02; + imu.angular_velocity_covariance[8] = 0.02; + + ros::Duration(0.1).sleep(); + ros::spinOnce(); + + size_t setCount = 0; + while (setCount++ < 1000) + { + imu.header.stamp = ros::Time::now(); + imu0Pub.publish(imu); // Use this to move the absolute orientation + imu1Pub.publish(imu); // Use this to keep velocities at 0 + ros::spinOnce(); + + ros::Duration(0.001).sleep(); + + imu.header.seq++; + } + + size_t zeroCount = 0; + while (zeroCount++ < 10) + { + imu.header.stamp = ros::Time::now(); + imuPub.publish(imu); + ros::spinOnce(); + + ros::Duration(0.1).sleep(); + + imu.header.seq++; + } + + double rollFinal = roll; + double pitchFinal = pitch; + double yawFinal = yaw; + + // Move the orientation slowly, and see if we + // can push it to 0 + ros::Rate loopRate(20); + for (size_t i = 0; i < 100; ++i) + { + yawFinal -= 0.01 * (3.0 * M_PI/4.0); + + quat.setRPY(rollFinal, pitchFinal, yawFinal); + + imu.orientation = tf2::toMsg(quat); + imu.header.stamp = ros::Time::now(); + imuPub.publish(imu); + ros::spinOnce(); + + loopRate.sleep(); + + imu.header.seq++; + } + ros::spinOnce(); + + // Move the orientation slowly, and see if we + // can push it to 0 + loopRate = ros::Rate(20); + for (size_t i = 0; i < 100; ++i) + { + rollFinal += 0.01 * (M_PI/2.0); + + quat.setRPY(rollFinal, pitchFinal, yawFinal); + + imu.orientation = tf2::toMsg(quat); + imu.header.stamp = ros::Time::now(); + imuPub.publish(imu); + ros::spinOnce(); + + loopRate.sleep(); + + imu.header.seq++; + } + ros::spinOnce(); + + tf2::fromMsg(filtered_.pose.pose.orientation, quat); + tf2::Matrix3x3 mat(quat); + mat.getRPY(rollFinal, pitchFinal, yawFinal); + EXPECT_LT(::fabs(rollFinal), 0.2); + EXPECT_LT(::fabs(pitchFinal), 0.2); + EXPECT_LT(::fabs(yawFinal), 0.2); + + resetFilter(); +} + +int main(int argc, char **argv) +{ + testing::InitGoogleTest(&argc, argv); + + ros::init(argc, argv, "ukf_navigation_node-test-interfaces"); + ros::Time::init(); + + // Give ukf_localization_node time to initialize + ros::Duration(2.0).sleep(); + + return RUN_ALL_TESTS(); +} diff --git a/navigations/robot_localization/test/test_ukf_localization_node_interfaces.test b/navigations/robot_localization/test/test_ukf_localization_node_interfaces.test new file mode 100755 index 0000000..8959361 --- /dev/null +++ b/navigations/robot_localization/test/test_ukf_localization_node_interfaces.test @@ -0,0 +1,73 @@ + + + + + + + + + + + + + + + + + + + + + + + + + [true, false, true, false, false, false, false, false, false, false, false, false, false, false, false] + [true, true, true, true, true, true, false, false, false, false, false, false, false, false, false] + [false, false, false, false, false, false, true, true, true, true, true, true, false, false, false] + + [true, false, true, false, false, false, false, false, false, false, false, false, false, false, false] + [true, true, true, true, true, true, false, false, false, false, false, false, false, false, false] + + [false, false, false, false, false, false, true, true, true, true, true, true, false, false, false] + + [false, false, false, true, true, true, false, false, false, false, false, false, false, false, false] + [false, false, false, false, false, false, false, false, false, true, true, true, false, false, false] + [false, false, false, false, false, false, false, false, false, false, false, false, true, true, true] + [false, false, false, true, true, true, false, false, false, false, false, false, false, false, false] + + + + + + + + + + + + [1e-6, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 1e-6, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 1e-6, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 1e-6, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 1e-6, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 1e-6, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.025, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.025, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.002, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.002, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.004, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01] + + + + + + + + + + diff --git a/navigations/robot_localization/test/test_ukf_localization_nodelet_bag1.test b/navigations/robot_localization/test/test_ukf_localization_nodelet_bag1.test new file mode 100755 index 0000000..546ad80 --- /dev/null +++ b/navigations/robot_localization/test/test_ukf_localization_nodelet_bag1.test @@ -0,0 +1,111 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [false, false, false, + false, false, false, + true, true, true, + false, false, false, + false, false, false] + + [false, false, false, + true, true, true, + false, false, false, + true, true, false, + true, true, true] + + + + + + + + + + + + + + + + + + [0.05, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0.05, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0.06, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0.03, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0.03, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0.06, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0.025, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0.025, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0.04, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.02, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.015] + + [1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1e-9] + + + + + + + + + + + + + + + + + diff --git a/navigations/rospy_message_converter/.flake8 b/navigations/rospy_message_converter/.flake8 new file mode 100755 index 0000000..1edf3cd --- /dev/null +++ b/navigations/rospy_message_converter/.flake8 @@ -0,0 +1,9 @@ +[flake8] +# The line length here has to match the black config in pyproject.toml +max-line-length = 120 +exclude = + .git, + __pycache__ +extend-ignore = + # See https://github.com/PyCQA/pycodestyle/issues/373 + E203, diff --git a/navigations/rospy_message_converter/.github/workflows/github-actions.yml b/navigations/rospy_message_converter/.github/workflows/github-actions.yml new file mode 100755 index 0000000..1e681c0 --- /dev/null +++ b/navigations/rospy_message_converter/.github/workflows/github-actions.yml @@ -0,0 +1,41 @@ +name: Build and run ROS tests +on: [push, pull_request] +jobs: + build: + strategy: + matrix: + rosdistro: [noetic] + runs-on: ubuntu-latest + container: + image: ros:${{ matrix.rosdistro }}-ros-core + steps: + - name: Install apt dependencies + run: | + sudo apt-get update + sudo apt-get install -y build-essential clang-format-10 file git python3-catkin-lint python3-pip python3-rosdep + - name: Install pip dependencies + run: pip install pre-commit + - name: Checkout repository + uses: actions/checkout@v3 + with: + path: src/rospy_message_converter + - name: Use rosdep to install remaining dependencies + run: | + sudo rosdep init + rosdep update + rosdep install --from-paths src -i -y --rosdistro ${{ matrix.rosdistro }} + - name: Build + run: | + . /opt/ros/${{ matrix.rosdistro }}/setup.sh + catkin_make install + - name: Run tests + run: | + . devel/setup.sh + CTEST_OUTPUT_ON_FAILURE=1 catkin_make test + cd src/rospy_message_converter + python3 src/rospy_message_converter/json_message_converter.py + python3 src/rospy_message_converter/message_converter.py + - name: Run pre-commit hooks + run: | + cd src/rospy_message_converter + pre-commit run -a diff --git a/navigations/rospy_message_converter/.gitignore b/navigations/rospy_message_converter/.gitignore new file mode 100755 index 0000000..ad1d299 --- /dev/null +++ b/navigations/rospy_message_converter/.gitignore @@ -0,0 +1,3 @@ +*.pyc +.idea +*.iml diff --git a/navigations/rospy_message_converter/.pre-commit-config.yaml b/navigations/rospy_message_converter/.pre-commit-config.yaml new file mode 100755 index 0000000..58e8641 --- /dev/null +++ b/navigations/rospy_message_converter/.pre-commit-config.yaml @@ -0,0 +1,55 @@ +# To use: +# +# pre-commit run -a +# +# Or: +# +# pre-commit install # (runs every time you commit in git) +# +# To update this file: +# +# pre-commit autoupdate +# +# See https://github.com/pre-commit/pre-commit + +repos: + # Standard hooks + - repo: https://github.com/pre-commit/pre-commit-hooks + rev: v4.1.0 + hooks: + - id: check-added-large-files + - id: check-case-conflict + - id: check-executables-have-shebangs + - id: check-docstring-first + - id: check-merge-conflict + - id: check-shebang-scripts-are-executable + - id: check-symlinks + - id: check-vcs-permalinks + - id: check-xml + - id: check-yaml + - id: debug-statements + - id: end-of-file-fixer + - id: fix-byte-order-marker + - id: mixed-line-ending + - id: trailing-whitespace + + - repo: https://github.com/psf/black + rev: 22.3.0 + hooks: + - id: black + + - repo: https://github.com/PyCQA/flake8.git + rev: 5.0.4 + hooks: + - id: flake8 + + - repo: local + hooks: + - id: catkin_lint + name: catkin_lint + description: Check package.xml and cmake files + entry: catkin_lint . + language: system + always_run: true + pass_filenames: false + args: [ "--strict" ] diff --git a/navigations/rospy_message_converter/CHANGELOG.rst b/navigations/rospy_message_converter/CHANGELOG.rst new file mode 100755 index 0000000..5fc4e38 --- /dev/null +++ b/navigations/rospy_message_converter/CHANGELOG.rst @@ -0,0 +1,161 @@ +Change Log +========== + +0.5.9 (2022-09-12) +------------------ +* Fix flake8 errors +* Re-format code using black +* package.xml: Add missing build_export_depend +* Fix EOF and trailing whitespace +* Add pre-commit config +* README: Add note about branches +* pass down log_level to helper functions (`#60 `_) +* Declare file encoding + This is necessary on ROS Melodic (Python2), because I have added a + non-ASCII character (u umlaut) in my last commit. +* Add LICENSE file and license headers +* Contributors: Martin Günther, Yuri Rocha + +0.5.8 (2022-03-03) +------------------ +* add option to change log level (`#58 `_) +* Contributors: Yuri Rocha + +0.5.7 (2021-09-08) +------------------ +* Handle None values in dictionary +* Add tests for None +* Dockerfile-kinetic: Add --include-eol-distros +* Contributors: Martin Günther + +0.5.6 (2021-03-01) +------------------ +* Propagate strict_mode, check_missing_fields in _convert_to_ros_type + Previously, _convert_to_ros_type dropped strict_mode and + check_missing_fields in nested messages. +* Add NestedUint8ArrayTestService tests +* propagate check_types in _convert_to_ros_type (`#51 `_) + Co-authored-by: Martin Günther +* Fix binary_array_as_bytes=False with nested msgs +* Add param binary_array_as_bytes + Closes `#45 `_. +* Contributors: Marc Bosch-Jorge, Martin Günther, Otacon5555 + +0.5.5 (2020-11-09) +------------------ +* Decode strings from ROS messages as UTF8 + This makes the python2 behavior equal to python3. +* python3 only: Validate base64 strings +* Add bytes to python3 string types + This means that `bytes` will now also be base64-decoded, which fixes the following tests on python3: + * test_dictionary_with_uint8_array_bytes + * test_dictionary_with_uint8_array_bytes_unencoded + * test_dictionary_with_3uint8_array_bytes + On python2, `bytes` is just an alias for `str`, which is why it worked + without this. +* Fix and add tests +* Contributors: Martin Günther + +0.5.4 (2020-10-13) +------------------ +* Avoid numpy dependency +* Contributors: Martin Günther, betaboon + +0.5.3 (2020-08-20) +------------------ +* Add check_types parameter to convert_dictionary_to_ros_message (`#42 `_) +* Allow numpy numeric types in numeric fields (`#41 `_) + Fixes `#39 `_. +* perf: Remove remaining regexes + This is only a small speedup of about 1.03x. +* perf: Avoid regex in _is_field_type_a_primitive_array + This makes the function almost 3x faster. +* perf: Reorder type checks + Perform the cheaper checks first. This results in a speedup of about + 1.2x. +* perf: Avoid regex in is_ros_binary_type + This makes is_ros_binary_type almost 5x faster and as a result the whole + convert_ros_message_to_dictionary function almost 2x faster. +* Compare types, not type names; improve error message + Old error message: + TypeError: Wrong type: '1.0' must be float64 + New error message: + TypeError: Field 'x' has wrong type (valid types: [, ]) +* Remove unused python_to_ros_type_map +* added test for convert_dictionary_to_ros_message with int8 array +* python 3 fix for _convert_to_ros_binary +* Contributors: Martin Günther, Steffen Rühl + +0.5.2 (2020-07-09) +------------------ +* Check for wrong field types when converting from dict to ros msg +* Check for missing fields when converting from dict to ros msg +* Contributors: Martin Günther, alecarnevale + +0.5.1 (2020-05-25) +------------------ +* Initial release into Noetic +* Decode base64-encoded byte arrays as unicode +* Make tests compatible with python3 +* add check for python3 str serializing `#33 `_ (`#34 `_) +* efficient conversion of primitive array to ros type (`#31 `_) +* efficient conversion of primitive array +* removed unused _convert_from_ros_primitive +* optionally ignore extra fields when deserializing (`#29 `_) +* Remove EOL distros indigo + lunar from CI +* travis CI: Use matrix to split ROS distros +* Update README (convert to md, add build status) +* Contributors: Martin Günther, George Hartt, Jannik Abbenseth, Omri Rozenzaft + +0.5.0 (2019-01-17) +------------------ +* Initial release into Lunar and Melodic +* Remove support for Jade (EOL) +* Change maintainer from Brandon Alexander to Martin Günther +* Move repo from baalexander to uos +* Add serialize_deserialize to unit tests, fix incorrect tests caught by this +* Remove dependency on ROS master in tests; all tests are now unit + tests (`#18 `_) +* Add service request/response support (`#17 `_) +* Fix fixed-size uint8 array conversion failure (`#15 `_) +* Fix unicode handling in string fields (`#13 `_) +* Enable testing only if CATKIN_ENABLE_TESTING is set (`#9 `_) +* Contributors: Martin Günther, Brandon Alexander, George Laurent, Jean-Baptiste Doyon, Viktor Schlegel, Rein Appeldoorn, Will Baker, neka-nat + +0.4.0 (2015-12-13) +------------------ +* Adds support for ROS Jade +* Removes support for ROS Groovy and Hydro (EOL) +* Uses single branch for all ROS versions +* Docker support for local development and Travis CI + +0.3.0 (2014-06-03) +------------------ +* Adds support for ROS Indigo + +0.2.0 (2013-07-15) +------------------ +* Updates to ROS Hydro +* Builds and runs tests with Travis CI +* Adds CHANGELOG + +0.1.4 (2013-04-16) +------------------ +* Documents Python functions +* Throws error if invalid JSON or dictionary + +0.1.3 (2013-03-04) +------------------ +* Adds rostest dependency + +0.1.2 (2013-03-04) +------------------ +* Adds missing build_depends and run_depends + +0.1.1 (2013-03-01) +------------------ +* Adds message_generation dependency to fix build + +0.1.0 (2013-02-27) +------------------ +* Initial release of rospy_message_converter diff --git a/navigations/rospy_message_converter/CMakeLists.txt b/navigations/rospy_message_converter/CMakeLists.txt new file mode 100755 index 0000000..977762b --- /dev/null +++ b/navigations/rospy_message_converter/CMakeLists.txt @@ -0,0 +1,37 @@ +cmake_minimum_required(VERSION 3.5.1) +cmake_policy(SET CMP0048 NEW) +project(rospy_message_converter) + +find_package(catkin REQUIRED COMPONENTS message_generation std_msgs) + +# Generate messages for testing (NOINSTALL) +add_message_files( + FILES + NestedUint8ArrayTestMessage.msg + TestArray.msg + Uint8Array3TestMessage.msg + Uint8ArrayTestMessage.msg + NOINSTALL +) + +add_service_files( + FILES + NestedUint8ArrayTestService.srv + NOINSTALL +) + +catkin_python_setup() + +# Generate added messages and services with any dependencies listed here +generate_messages( + DEPENDENCIES + std_msgs +) + +catkin_package(CATKIN_DEPENDS message_runtime std_msgs) + +# Testing +if(CATKIN_ENABLE_TESTING) + catkin_add_nosetests(test/test_json_message_converter.py) + catkin_add_nosetests(test/test_message_converter.py) +endif() diff --git a/navigations/rospy_message_converter/Dockerfile-kinetic b/navigations/rospy_message_converter/Dockerfile-kinetic new file mode 100755 index 0000000..fb93554 --- /dev/null +++ b/navigations/rospy_message_converter/Dockerfile-kinetic @@ -0,0 +1,18 @@ +FROM ros:kinetic-ros-core + +RUN apt-get update \ + && apt-get install -y build-essential python-rosdep cmake \ + && rm -rf /var/lib/apt/lists/{apt,dpkg,cache,log} /tmp/* /var/tmp/* + +RUN rosdep init && rosdep update --include-eol-distros + +# Create ROS workspace +COPY . /ws/src/rospy_message_converter +WORKDIR /ws + +# Install the package and its dependencies +RUN rosdep install --from-paths src --ignore-src --rosdistro kinetic -y + +# Set up the development environment +RUN /bin/bash -c "source /opt/ros/kinetic/setup.bash && \ + catkin_make install" diff --git a/navigations/rospy_message_converter/Dockerfile-melodic b/navigations/rospy_message_converter/Dockerfile-melodic new file mode 100755 index 0000000..bd4fb12 --- /dev/null +++ b/navigations/rospy_message_converter/Dockerfile-melodic @@ -0,0 +1,18 @@ +FROM ros:melodic-ros-core + +RUN apt-get update \ + && apt-get install -y build-essential python-rosdep cmake \ + && rm -rf /var/lib/apt/lists/{apt,dpkg,cache,log} /tmp/* /var/tmp/* + +RUN rosdep init && rosdep update + +# Create ROS workspace +COPY . /ws/src/rospy_message_converter +WORKDIR /ws + +# Install the package and its dependencies +RUN rosdep install --from-paths src --ignore-src --rosdistro melodic -y + +# Set up the development environment +RUN /bin/bash -c "source /opt/ros/melodic/setup.bash && \ + catkin_make install" diff --git a/navigations/rospy_message_converter/Dockerfile-noetic b/navigations/rospy_message_converter/Dockerfile-noetic new file mode 100755 index 0000000..7639001 --- /dev/null +++ b/navigations/rospy_message_converter/Dockerfile-noetic @@ -0,0 +1,18 @@ +FROM ros:noetic-ros-core + +RUN apt-get update \ + && apt-get install -y build-essential python3-rosdep cmake \ + && rm -rf /var/lib/apt/lists/{apt,dpkg,cache,log} /tmp/* /var/tmp/* + +RUN rosdep init && rosdep update + +# Create ROS workspace +COPY . /ws/src/rospy_message_converter +WORKDIR /ws + +# Install the package and its dependencies +RUN rosdep install --from-paths src --ignore-src --rosdistro noetic -y + +# Set up the development environment +RUN /bin/bash -c "source /opt/ros/noetic/setup.bash && \ + catkin_make install" diff --git a/navigations/rospy_message_converter/LICENSE b/navigations/rospy_message_converter/LICENSE new file mode 100755 index 0000000..f1486ba --- /dev/null +++ b/navigations/rospy_message_converter/LICENSE @@ -0,0 +1,28 @@ +Copyright (c) 2019-2022, Martin Günther (DFKI GmbH) and others +Copyright (c) 2013-2016, Brandon Alexander + +All rights reserved. + +Redistribution and use in source and binary forms, with or without modification, +are permitted provided that the following conditions are met: + + * Redistributions of source code must retain the above copyright notice, + this list of conditions and the following disclaimer. + * Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + * Neither the name of this project nor the names of its contributors + may be used to endorse or promote products derived from this software + without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +"AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR +A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR +CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, +EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, +PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. diff --git a/navigations/rospy_message_converter/README.md b/navigations/rospy_message_converter/README.md new file mode 100755 index 0000000..a004795 --- /dev/null +++ b/navigations/rospy_message_converter/README.md @@ -0,0 +1,104 @@ +rospy_message_converter +======================= + +Rospy_message_converter is a lightweight ROS package and Python library to +convert from Python dictionaries and JSON messages to rospy messages, and vice +versa. + +ROS 1 and ROS 2 branches +------------------------ + +ROS 1 users should use the `master` branch. ROS 2 users should use the appropriate +branch for their distro (`foxy`/`galactic`/`humble`/`rolling`/...). + +Usage +----- + +Convert a dictionary to a ROS message + +```python +from rospy_message_converter import message_converter +from std_msgs.msg import String +dictionary = { 'data': 'Howdy' } +message = message_converter.convert_dictionary_to_ros_message('std_msgs/String', dictionary) +``` + +Convert a ROS message to a dictionary + +```python +from rospy_message_converter import message_converter +from std_msgs.msg import String +message = String(data = 'Howdy') +dictionary = message_converter.convert_ros_message_to_dictionary(message) +``` + +Convert JSON to a ROS message + +```python +from rospy_message_converter import json_message_converter +from std_msgs.msg import String +json_str = '{"data": "Hello"}' +message = json_message_converter.convert_json_to_ros_message('std_msgs/String', json_str) +``` + +Convert a ROS message to JSON + +```python +from rospy_message_converter import json_message_converter +from std_msgs.msg import String +message = String(data = 'Hello') +json_str = json_message_converter.convert_ros_message_to_json(message) +``` + +Test +---- + +To run the tests: + +```bash +catkin_make test +``` + +pre-commit Formatting Checks +---------------------------- + +This repo has a [pre-commit](https://pre-commit.com/) check that runs in CI. +You can use this locally and set it up to run automatically before you commit +something. To install, use pip: + +```bash +pip3 install --user pre-commit +``` + +To run over all the files in the repo manually: + +```bash +pre-commit run -a +``` + +To run pre-commit automatically before committing in the local repo, install the git hooks: + +```bash +pre-commit install +``` + + +License +------- + +Project is released under the BSD license. + +GitHub actions - Continuous Integration +--------------------------------------- + +[![Build Status](https://github.com/DFKI-NI/rospy_message_converter/actions/workflows/github-actions.yml/badge.svg)](https://github.com/DFKI-NI/rospy_message_converter/actions/workflows/github-actions.yml/) + + +ROS Buildfarm +------------- + +| | binary deb | source deb | devel | doc | +|-----------|------------|------------|-------|-----| +| kinetic | [![Build Status](http://build.ros.org/buildStatus/icon?job=Kbin_uX64__rospy_message_converter__ubuntu_xenial_amd64__binary)](http://build.ros.org/job/Kbin_uX64__rospy_message_converter__ubuntu_xenial_amd64__binary/) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Ksrc_uX__rospy_message_converter__ubuntu_xenial__source)](http://build.ros.org/job/Ksrc_uX__rospy_message_converter__ubuntu_xenial__source/) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Kdev__rospy_message_converter__ubuntu_xenial_amd64)](http://build.ros.org/job/Kdev__rospy_message_converter__ubuntu_xenial_amd64) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Kdoc__rospy_message_converter__ubuntu_xenial_amd64)](http://build.ros.org/job/Kdoc__rospy_message_converter__ubuntu_xenial_amd64) | +| melodic | [![Build Status](http://build.ros.org/buildStatus/icon?job=Mbin_uB64__rospy_message_converter__ubuntu_bionic_amd64__binary)](http://build.ros.org/job/Mbin_uB64__rospy_message_converter__ubuntu_bionic_amd64__binary) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Msrc_uB__rospy_message_converter__ubuntu_bionic__source)](http://build.ros.org/job/Msrc_uB__rospy_message_converter__ubuntu_bionic__source/) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Mdev__rospy_message_converter__ubuntu_bionic_amd64)](http://build.ros.org/job/Mdev__rospy_message_converter__ubuntu_bionic_amd64) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Mdoc__rospy_message_converter__ubuntu_bionic_amd64)](http://build.ros.org/job/Mdoc__rospy_message_converter__ubuntu_bionic_amd64) | +| noetic | [![Build Status](http://build.ros.org/buildStatus/icon?job=Nbin_uF64__rospy_message_converter__ubuntu_focal_amd64__binary)](http://build.ros.org/job/Nbin_uF64__rospy_message_converter__ubuntu_focal_amd64__binary/) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Nsrc_uF__rospy_message_converter__ubuntu_focal__source)](http://build.ros.org/job/Nsrc_uF__rospy_message_converter__ubuntu_focal__source/) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Ndev__rospy_message_converter__ubuntu_focal_amd64)](http://build.ros.org/job/Ndev__rospy_message_converter__ubuntu_focal_amd64/) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Ndoc__rospy_message_converter__ubuntu_focal_amd64)](http://build.ros.org/job/Ndoc__rospy_message_converter__ubuntu_focal_amd64/) | diff --git a/navigations/rospy_message_converter/msg/NestedUint8ArrayTestMessage.msg b/navigations/rospy_message_converter/msg/NestedUint8ArrayTestMessage.msg new file mode 100755 index 0000000..cf7dbd6 --- /dev/null +++ b/navigations/rospy_message_converter/msg/NestedUint8ArrayTestMessage.msg @@ -0,0 +1,2 @@ +# array of arrays for testing purposes +Uint8ArrayTestMessage[] arrays diff --git a/navigations/rospy_message_converter/msg/TestArray.msg b/navigations/rospy_message_converter/msg/TestArray.msg new file mode 100755 index 0000000..922220f --- /dev/null +++ b/navigations/rospy_message_converter/msg/TestArray.msg @@ -0,0 +1 @@ +float64[] data diff --git a/navigations/rospy_message_converter/msg/Uint8Array3TestMessage.msg b/navigations/rospy_message_converter/msg/Uint8Array3TestMessage.msg new file mode 100755 index 0000000..e97c0cd --- /dev/null +++ b/navigations/rospy_message_converter/msg/Uint8Array3TestMessage.msg @@ -0,0 +1,2 @@ +# Fixed size uint8 array for testing purposes +uint8[3] data diff --git a/navigations/rospy_message_converter/msg/Uint8ArrayTestMessage.msg b/navigations/rospy_message_converter/msg/Uint8ArrayTestMessage.msg new file mode 100755 index 0000000..b66b73a --- /dev/null +++ b/navigations/rospy_message_converter/msg/Uint8ArrayTestMessage.msg @@ -0,0 +1,2 @@ +# Size-agnostic uint8 array for testing purposes +uint8[] data diff --git a/navigations/rospy_message_converter/package.xml b/navigations/rospy_message_converter/package.xml new file mode 100755 index 0000000..a7b218b --- /dev/null +++ b/navigations/rospy_message_converter/package.xml @@ -0,0 +1,28 @@ + + + rospy_message_converter + 0.5.9 + Converts between Python dictionaries and JSON to rospy messages. + Martin Günther + BSD + http://ros.org/wiki/rospy_message_converter + https://github.com/DFKI-NI/rospy_message_converter + https://github.com/DFKI-NI/rospy_message_converter/issues + Brandon Alexander + + catkin + + message_generation + std_msgs + std_msgs + + roslib + rospy + message_runtime + std_msgs + + rosunit + std_srvs + python-numpy + python3-numpy + diff --git a/navigations/rospy_message_converter/pyproject.toml b/navigations/rospy_message_converter/pyproject.toml new file mode 100755 index 0000000..9366856 --- /dev/null +++ b/navigations/rospy_message_converter/pyproject.toml @@ -0,0 +1,5 @@ +[tool.black] +# The line length here has to match the flake8 config in .flake8 +line-length = 120 +target-version = ['py38'] +skip-string-normalization = true diff --git a/navigations/rospy_message_converter/setup.py b/navigations/rospy_message_converter/setup.py new file mode 100755 index 0000000..bb8a9b3 --- /dev/null +++ b/navigations/rospy_message_converter/setup.py @@ -0,0 +1,11 @@ +# ! DO NOT MANUALLY INVOKE THIS setup.py, USE CATKIN INSTEAD + +from distutils.core import setup +from catkin_pkg.python_setup import generate_distutils_setup + +d = generate_distutils_setup( + packages=['rospy_message_converter'], + package_dir={'': 'src'}, +) + +setup(**d) diff --git a/navigations/rospy_message_converter/src/rospy_message_converter/__init__.py b/navigations/rospy_message_converter/src/rospy_message_converter/__init__.py new file mode 100755 index 0000000..e69de29 diff --git a/navigations/rospy_message_converter/src/rospy_message_converter/json_message_converter.py b/navigations/rospy_message_converter/src/rospy_message_converter/json_message_converter.py new file mode 100755 index 0000000..4d023b5 --- /dev/null +++ b/navigations/rospy_message_converter/src/rospy_message_converter/json_message_converter.py @@ -0,0 +1,97 @@ +# -*- coding: utf-8 -*- +# +# Software License Agreement (BSD License) +# +# Copyright (c) 2019-2022, Martin Günther (DFKI GmbH) and others +# Copyright (c) 2013-2016, Brandon Alexander +# +# All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# * Redistributions in binary form must reproduce the above +# copyright notice, this list of conditions and the following +# disclaimer in the documentation and/or other materials provided +# with the distribution. +# * Neither the name of this project nor the names of its +# contributors may be used to endorse or promote products derived +# from this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. + +import json + +from rospy_message_converter import message_converter + + +def convert_json_to_ros_message(message_type, json_message, strict_mode=True, log_level='error'): + """ + Takes in the message type and a JSON-formatted string and returns a ROS + message. + + :param message_type: The desired ROS message type of the result + :type message_type: str + :param json_message: A JSON-formatted string + :type json_message: str + :param strict_mode: If strict_mode is set, an exception will be thrown if the json message contains extra fields. + :type strict_mode: bool, optional + :param log_level: The log level to be used. Available levels: debug, info, warning, error, critical + :type log_level: str, optional + :return: A ROS message + :rtype: class:`genpy.Message` + + Example: + >>> msg_type = "std_msgs/String" + >>> json_msg = '{"data": "Hello, Robot"}' + >>> convert_json_to_ros_message(msg_type, json_msg) + data: "Hello, Robot" + """ + dictionary = json.loads(json_message) + return message_converter.convert_dictionary_to_ros_message( + message_type, dictionary, strict_mode=strict_mode, log_level=log_level + ) + + +def convert_ros_message_to_json(message, binary_array_as_bytes=True): + """ + Takes in a ROS message and returns a JSON-formatted string. + + :param message: A ROS message to convert + :type message: class:`genpy.Message` + :param binary_array_as_bytes: rospy treats `uint8[]` data as a `bytes`, which is the Python representation for byte + data. In Python 2, this is the same as `str`. If this parameter is `False`, all `uint8[]` fields will be + converted to `list(int)` instead. + :type binary_array_as_bytes: bool, optional + :return: A JSON-formatted string + :rtype: str + + Example: + >>> import std_msgs.msg + >>> ros_message = std_msgs.msg.String(data="Hello, Robot") + >>> convert_ros_message_to_json(ros_message) + '{"data": "Hello, Robot"}' + """ + dictionary = message_converter.convert_ros_message_to_dictionary(message, binary_array_as_bytes) + json_message = json.dumps(dictionary) + return json_message + + +if __name__ == "__main__": + import doctest + + doctest.testmod() diff --git a/navigations/rospy_message_converter/src/rospy_message_converter/message_converter.py b/navigations/rospy_message_converter/src/rospy_message_converter/message_converter.py new file mode 100755 index 0000000..4ac3e8a --- /dev/null +++ b/navigations/rospy_message_converter/src/rospy_message_converter/message_converter.py @@ -0,0 +1,397 @@ +# -*- coding: utf-8 -*- +# +# Software License Agreement (BSD License) +# +# Copyright (c) 2019-2022, Martin Günther (DFKI GmbH) and others +# Copyright (c) 2013-2016, Brandon Alexander +# +# All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# * Redistributions in binary form must reproduce the above +# copyright notice, this list of conditions and the following +# disclaimer in the documentation and/or other materials provided +# with the distribution. +# * Neither the name of this project nor the names of its +# contributors may be used to endorse or promote products derived +# from this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. + +import logging +import roslib.message +import rospy +import base64 +import sys +import copy +import collections + +python3 = sys.hexversion > 0x03000000 + +python_list_types = [list, tuple] + +if python3: + python_string_types = [str, bytes] + python_int_types = [int] +else: + python_string_types = [str, unicode] # noqa + python_int_types = [int, long] # noqa + +python_float_types = [float] + +ros_to_python_type_map = { + 'bool': [bool], + 'float32': copy.deepcopy(python_float_types + python_int_types), + 'float64': copy.deepcopy(python_float_types + python_int_types), + 'int8': copy.deepcopy(python_int_types), + 'int16': copy.deepcopy(python_int_types), + 'int32': copy.deepcopy(python_int_types), + 'int64': copy.deepcopy(python_int_types), + 'uint8': copy.deepcopy(python_int_types), + 'uint16': copy.deepcopy(python_int_types), + 'uint32': copy.deepcopy(python_int_types), + 'uint64': copy.deepcopy(python_int_types), + 'byte': copy.deepcopy(python_int_types), + 'char': copy.deepcopy(python_int_types), + 'string': copy.deepcopy(python_string_types), +} + +try: + import numpy as np + + _ros_to_numpy_type_map = { + 'float32': [np.float32, np.int8, np.int16, np.uint8, np.uint16], + # don't include int32, because conversion to float may change value: + # v = np.iinfo(np.int32).max; np.float32(v) != v + 'float64': [np.float32, np.float64, np.int8, np.int16, np.int32, np.uint8, np.uint16, np.uint32], + 'int8': [np.int8], + 'int16': [np.int8, np.int16, np.uint8], + 'int32': [np.int8, np.int16, np.int32, np.uint8, np.uint16], + 'int64': [np.int8, np.int16, np.int32, np.int64, np.uint8, np.uint16, np.uint32], + 'uint8': [np.uint8], + 'uint16': [np.uint8, np.uint16], + 'uint32': [np.uint8, np.uint16, np.uint32], + 'uint64': [np.uint8, np.uint16, np.uint32, np.uint64], + 'byte': [np.int8], + 'char': [np.uint8], + } + + # merge type_maps + merged = collections.defaultdict(list, ros_to_python_type_map) + for k, v in _ros_to_numpy_type_map.items(): + merged[k].extend(v) + ros_to_python_type_map = dict(merged) +except ImportError: + pass + + +ros_time_types = ['time', 'duration'] +ros_primitive_types = [ + 'bool', + 'byte', + 'char', + 'int8', + 'uint8', + 'int16', + 'uint16', + 'int32', + 'uint32', + 'int64', + 'uint64', + 'float32', + 'float64', + 'string', +] +ros_header_types = ['Header', 'std_msgs/Header', 'roslib/Header'] + + +def convert_dictionary_to_ros_message( + message_type, + dictionary, + kind='message', + strict_mode=True, + check_missing_fields=False, + check_types=True, + log_level='error', +): + """ + Takes in the message type and a Python dictionary and returns a ROS message. + + Example: + >>> msg_type = "std_msgs/String" + >>> dict_msg = { "data": "Hello, Robot" } + >>> convert_dictionary_to_ros_message(msg_type, dict_msg) + data: "Hello, Robot" + + >>> msg_type = "std_srvs/SetBool" + >>> dict_msg = { "data": True } + >>> kind = "request" + >>> convert_dictionary_to_ros_message(msg_type, dict_msg, kind) + data: True + """ + if kind == 'message': + message_class = roslib.message.get_message_class(message_type) + message = message_class() + elif kind == 'request': + service_class = roslib.message.get_service_class(message_type) + message = service_class._request_class() + elif kind == 'response': + service_class = roslib.message.get_service_class(message_type) + message = service_class._response_class() + else: + raise ValueError('Unknown kind "%s".' % kind) + message_fields = dict(_get_message_fields(message)) + + remaining_message_fields = copy.deepcopy(message_fields) + + if dictionary is None: + dictionary = {} + for field_name, field_value in dictionary.items(): + if field_name in message_fields: + field_type = message_fields[field_name] + if field_value is not None: + field_value = _convert_to_ros_type( + field_name, field_type, field_value, strict_mode, check_missing_fields, check_types, log_level + ) + setattr(message, field_name, field_value) + del remaining_message_fields[field_name] + else: + error_message = 'ROS message type "{0}" has no field named "{1}"'.format(message_type, field_name) + if strict_mode: + raise ValueError(error_message) + else: + if log_level not in ["debug", "info", "warning", "error", "critical"]: + log_level = "error" + logger = logging.getLogger('rosout') + log_func = getattr(logger, log_level) + + log_func('{}! It will be ignored.'.format(error_message)) + + if check_missing_fields and remaining_message_fields: + error_message = 'Missing fields "{0}"'.format(remaining_message_fields) + raise ValueError(error_message) + + return message + + +def _convert_to_ros_type( + field_name, + field_type, + field_value, + strict_mode=True, + check_missing_fields=False, + check_types=True, + log_level='error', +): + if _is_ros_binary_type(field_type): + field_value = _convert_to_ros_binary(field_type, field_value) + elif field_type in ros_time_types: + field_value = _convert_to_ros_time(field_type, field_value) + elif field_type in ros_primitive_types: + # Note: one could also use genpy.message.check_type() here, but: + # 1. check_type is "not designed to run fast and is meant only for error diagnosis" + # 2. it doesn't check floats (see ros/genpy#130) + # 3. it rejects numpy types, although they can be serialized + if check_types and type(field_value) not in ros_to_python_type_map[field_type]: + raise TypeError( + "Field '{0}' has wrong type {1} (valid types: {2})".format( + field_name, type(field_value), ros_to_python_type_map[field_type] + ) + ) + field_value = _convert_to_ros_primitive(field_type, field_value) + elif _is_field_type_a_primitive_array(field_type): + field_value = field_value + elif _is_field_type_an_array(field_type): + field_value = _convert_to_ros_array( + field_name, field_type, field_value, strict_mode, check_missing_fields, check_types, log_level + ) + else: + field_value = convert_dictionary_to_ros_message( + field_type, + field_value, + strict_mode=strict_mode, + check_missing_fields=check_missing_fields, + check_types=check_types, + log_level=log_level, + ) + return field_value + + +def _convert_to_ros_binary(field_type, field_value): + if type(field_value) in python_string_types: + if python3: + # base64 in python3 added the `validate` arg: + # If field_value is not properly base64 encoded and there are non-base64-alphabet characters in the input, + # a binascii.Error will be raised. + binary_value_as_string = base64.b64decode(field_value, validate=True) + else: + # base64 in python2 doesn't have the `validate` arg: characters that are not in the base-64 alphabet are + # silently discarded, resulting in garbage output. + binary_value_as_string = base64.b64decode(field_value) + else: + binary_value_as_string = bytes(bytearray(field_value)) + return binary_value_as_string + + +def _convert_to_ros_time(field_type, field_value): + time = None + + if field_type == 'time' and field_value == 'now': + time = rospy.get_rostime() + else: + if field_type == 'time': + time = rospy.rostime.Time() + elif field_type == 'duration': + time = rospy.rostime.Duration() + if 'secs' in field_value and field_value['secs'] is not None: + setattr(time, 'secs', field_value['secs']) + if 'nsecs' in field_value and field_value['nsecs'] is not None: + setattr(time, 'nsecs', field_value['nsecs']) + + return time + + +def _convert_to_ros_primitive(field_type, field_value): + # std_msgs/msg/_String.py always calls encode() on python3, so don't do it here + if field_type == "string" and not python3: + field_value = field_value.encode('utf-8') + return field_value + + +def _convert_to_ros_array( + field_name, + field_type, + list_value, + strict_mode=True, + check_missing_fields=False, + check_types=True, + log_level='error', +): + # use index to raise ValueError if '[' not present + list_type = field_type[: field_type.index('[')] + return [ + _convert_to_ros_type(field_name, list_type, value, strict_mode, check_missing_fields, check_types, log_level) + for value in list_value + ] + + +def convert_ros_message_to_dictionary(message, binary_array_as_bytes=True): + """ + Takes in a ROS message and returns a Python dictionary. + + Example: + >>> import std_msgs.msg + >>> ros_message = std_msgs.msg.UInt32(data=42) + >>> convert_ros_message_to_dictionary(ros_message) + {'data': 42} + """ + dictionary = {} + message_fields = _get_message_fields(message) + for field_name, field_type in message_fields: + field_value = getattr(message, field_name) + dictionary[field_name] = _convert_from_ros_type(field_type, field_value, binary_array_as_bytes) + + return dictionary + + +def _convert_from_ros_type(field_type, field_value, binary_array_as_bytes=True): + if field_type in ros_primitive_types: + field_value = _convert_from_ros_primitive(field_type, field_value) + elif field_type in ros_time_types: + field_value = _convert_from_ros_time(field_type, field_value) + elif _is_ros_binary_type(field_type): + if binary_array_as_bytes: + field_value = _convert_from_ros_binary(field_type, field_value) + elif type(field_value) == str: + field_value = [ord(v) for v in field_value] + else: + field_value = list(field_value) + elif _is_field_type_a_primitive_array(field_type): + field_value = list(field_value) + elif _is_field_type_an_array(field_type): + field_value = _convert_from_ros_array(field_type, field_value, binary_array_as_bytes) + else: + field_value = convert_ros_message_to_dictionary(field_value, binary_array_as_bytes) + + return field_value + + +def _is_ros_binary_type(field_type): + """Checks if the field is a binary array one, fixed size or not + + >>> _is_ros_binary_type("uint8") + False + >>> _is_ros_binary_type("uint8[]") + True + >>> _is_ros_binary_type("uint8[3]") + True + >>> _is_ros_binary_type("char") + False + >>> _is_ros_binary_type("char[]") + True + >>> _is_ros_binary_type("char[3]") + True + """ + return field_type.startswith('uint8[') or field_type.startswith('char[') + + +def _convert_from_ros_binary(field_type, field_value): + field_value = base64.b64encode(field_value).decode('utf-8') + return field_value + + +def _convert_from_ros_time(field_type, field_value): + field_value = {'secs': field_value.secs, 'nsecs': field_value.nsecs} + return field_value + + +def _convert_from_ros_primitive(field_type, field_value): + # std_msgs/msg/_String.py always calls decode() on python3, so don't do it here + if field_type == "string" and not python3: + field_value = field_value.decode('utf-8') + return field_value + + +def _convert_from_ros_array(field_type, field_value, binary_array_as_bytes=True): + # use index to raise ValueError if '[' not present + list_type = field_type[: field_type.index('[')] + return [_convert_from_ros_type(list_type, value, binary_array_as_bytes) for value in field_value] + + +def _get_message_fields(message): + return zip(message.__slots__, message._slot_types) + + +def _is_field_type_an_array(field_type): + return field_type.find('[') >= 0 + + +def _is_field_type_a_primitive_array(field_type): + bracket_index = field_type.find('[') + if bracket_index < 0: + return False + else: + list_type = field_type[:bracket_index] + return list_type in ros_primitive_types + + +if __name__ == "__main__": + import doctest + + doctest.testmod() diff --git a/navigations/rospy_message_converter/srv/NestedUint8ArrayTestService.srv b/navigations/rospy_message_converter/srv/NestedUint8ArrayTestService.srv new file mode 100755 index 0000000..d48997e --- /dev/null +++ b/navigations/rospy_message_converter/srv/NestedUint8ArrayTestService.srv @@ -0,0 +1,6 @@ +# service with nested types for testing purposes +NestedUint8ArrayTestMessage input + +--- + +NestedUint8ArrayTestMessage output diff --git a/navigations/rospy_message_converter/test/__init__.py b/navigations/rospy_message_converter/test/__init__.py new file mode 100755 index 0000000..e69de29 diff --git a/navigations/rospy_message_converter/test/test_json_message_converter.py b/navigations/rospy_message_converter/test/test_json_message_converter.py new file mode 100755 index 0000000..4442fad --- /dev/null +++ b/navigations/rospy_message_converter/test/test_json_message_converter.py @@ -0,0 +1,172 @@ +# -*- coding: utf-8 -*- +# +# Software License Agreement (BSD License) +# +# Copyright (c) 2019-2022, Martin Günther (DFKI GmbH) and others +# Copyright (c) 2013-2016, Brandon Alexander +# +# All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# * Redistributions in binary form must reproduce the above +# copyright notice, this list of conditions and the following +# disclaimer in the documentation and/or other materials provided +# with the distribution. +# * Neither the name of this project nor the names of its +# contributors may be used to endorse or promote products derived +# from this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. + +import unittest +import rospy +from rospy_message_converter import json_message_converter + + +class TestJsonMessageConverter(unittest.TestCase): + def test_ros_message_with_string(self): + from std_msgs.msg import String + + expected_json = '{"data": "Hello"}' + message = String(data='Hello') + message = serialize_deserialize(message) + returned_json = json_message_converter.convert_ros_message_to_json(message) + self.assertEqual(returned_json, expected_json) + + def test_ros_message_with_string_unicode(self): + from std_msgs.msg import String + + expected_json = '{"data": "Hello \\u00dcnicode"}' + message = String(data=u'Hello \u00dcnicode') + message = serialize_deserialize(message) + returned_json = json_message_converter.convert_ros_message_to_json(message) + self.assertEqual(returned_json, expected_json) + + def test_ros_message_with_header(self): + from std_msgs.msg import Header + from time import time + + now_time = rospy.Time(time()) + expected_json1 = '{{"stamp": {{"secs": {0}, "nsecs": {1}}}, "frame_id": "my_frame", "seq": 3}}'.format( + now_time.secs, now_time.nsecs + ) + expected_json2 = '{{"seq": 3, "stamp": {{"secs": {0}, "nsecs": {1}}}, "frame_id": "my_frame"}}'.format( + now_time.secs, now_time.nsecs + ) + expected_json3 = '{{"frame_id": "my_frame", "seq": 3, "stamp": {{"secs": {0}, "nsecs": {1}}}}}'.format( + now_time.secs, now_time.nsecs + ) + message = Header(stamp=now_time, frame_id='my_frame', seq=3) + message = serialize_deserialize(message) + returned_json = json_message_converter.convert_ros_message_to_json(message) + self.assertTrue( + returned_json == expected_json1 or returned_json == expected_json2 or returned_json == expected_json3 + ) + + def test_ros_message_with_uint8_array(self): + from rospy_message_converter.msg import Uint8ArrayTestMessage + + input_data = [97, 98, 99, 100] + expected_json = '{"data": "YWJjZA=="}' # base64.b64encode("abcd") is "YWJjZA==" + message = Uint8ArrayTestMessage(data=input_data) + message = serialize_deserialize(message) + returned_json = json_message_converter.convert_ros_message_to_json(message) + self.assertEqual(returned_json, expected_json) + + def test_ros_message_with_3uint8_array(self): + from rospy_message_converter.msg import Uint8Array3TestMessage + + input_data = [97, 98, 99] + expected_json = '{"data": "YWJj"}' # base64.b64encode("abc") is "YWJj" + message = Uint8Array3TestMessage(data=input_data) + message = serialize_deserialize(message) + returned_json = json_message_converter.convert_ros_message_to_json(message) + self.assertEqual(returned_json, expected_json) + + def test_json_with_string(self): + from std_msgs.msg import String + + expected_message = String(data='Hello') + json_str = '{"data": "Hello"}' + message = json_message_converter.convert_json_to_ros_message('std_msgs/String', json_str) + expected_message = serialize_deserialize(expected_message) + self.assertEqual(message, expected_message) + + def test_json_with_string_unicode(self): + from std_msgs.msg import String + + expected_message = String(data=u'Hello \u00dcnicode') + json_str = '{"data": "Hello \\u00dcnicode"}' + message = json_message_converter.convert_json_to_ros_message('std_msgs/String', json_str) + expected_message = serialize_deserialize(expected_message) + self.assertEqual(message, expected_message) + + def test_json_with_header(self): + from std_msgs.msg import Header + from time import time + + now_time = rospy.Time(time()) + expected_message = Header(stamp=now_time, frame_id='my_frame', seq=12) + json_str = '{{"stamp": {{"secs": {0}, "nsecs": {1}}}, "frame_id": "my_frame", "seq": 12}}'.format( + now_time.secs, now_time.nsecs + ) + message = json_message_converter.convert_json_to_ros_message('std_msgs/Header', json_str) + expected_message = serialize_deserialize(expected_message) + self.assertEqual(message, expected_message) + + def test_json_with_string_null(self): + from std_msgs.msg import String + + expected_message = String(data='') + json_str = '{"data": null}' + message = json_message_converter.convert_json_to_ros_message('std_msgs/String', json_str) + expected_message = serialize_deserialize(expected_message) + self.assertEqual(message, expected_message) + + def test_json_with_invalid_message_fields(self): + self.assertRaises( + ValueError, json_message_converter.convert_json_to_ros_message, 'std_msgs/String', '{"not_data": "Hello"}' + ) + + +def serialize_deserialize(message): + """ + Serialize and then deserialize a message. This simulates sending a message + between ROS nodes and makes sure that the ROS messages being tested are + actually serializable, and are in the same format as they would be received + over the network. In rospy, it is possible to assign an illegal data type + to a message field (for example, `message = String(data=42)`), but trying + to publish this message will throw `SerializationError: field data must be + of type str`. This method will expose such bugs. + """ + from io import BytesIO + + buff = BytesIO() + message.serialize(buff) + result = message.__class__() # create new instance of same class as message + result.deserialize(buff.getvalue()) + return result + + +PKG = 'rospy_message_converter' +NAME = 'test_json_message_converter' +if __name__ == '__main__': + import rosunit + + rosunit.unitrun(PKG, NAME, TestJsonMessageConverter) diff --git a/navigations/rospy_message_converter/test/test_message_converter.py b/navigations/rospy_message_converter/test/test_message_converter.py new file mode 100755 index 0000000..03dab47 --- /dev/null +++ b/navigations/rospy_message_converter/test/test_message_converter.py @@ -0,0 +1,1188 @@ +# -*- coding: utf-8 -*- +# +# Software License Agreement (BSD License) +# +# Copyright (c) 2019-2022, Martin Günther (DFKI GmbH) and others +# Copyright (c) 2013-2016, Brandon Alexander +# +# All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# * Redistributions in binary form must reproduce the above +# copyright notice, this list of conditions and the following +# disclaimer in the documentation and/or other materials provided +# with the distribution. +# * Neither the name of this project nor the names of its +# contributors may be used to endorse or promote products derived +# from this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. + +import numpy as np +import struct +import sys +import unittest + +import rospy +from rospy.exceptions import ROSInitException +from rospy_message_converter import message_converter + +python3 = sys.hexversion > 0x03000000 + + +class TestMessageConverter(unittest.TestCase): + def test_ros_message_with_array(self): + from rospy_message_converter.msg import TestArray + + expected_dictionary = {'data': [1.1, 2.2, 3.3]} + message = TestArray(data=expected_dictionary['data']) + message = serialize_deserialize(message) + dictionary = message_converter.convert_ros_message_to_dictionary(message) + self.assertEqual(dictionary, expected_dictionary) + + def test_ros_message_with_bool(self): + from std_msgs.msg import Bool + + expected_dictionary = {'data': True} + message = Bool(data=expected_dictionary['data']) + message = serialize_deserialize(message) + dictionary = message_converter.convert_ros_message_to_dictionary(message) + self.assertEqual(dictionary, expected_dictionary) + + def test_ros_message_with_byte(self): + from std_msgs.msg import Byte + + expected_dictionary = {'data': 5} + message = Byte(data=expected_dictionary['data']) + message = serialize_deserialize(message) + dictionary = message_converter.convert_ros_message_to_dictionary(message) + self.assertEqual(dictionary, expected_dictionary) + + def test_ros_message_with_char(self): + from std_msgs.msg import Char + + expected_dictionary = {'data': 99} + message = Char(data=expected_dictionary['data']) + message = serialize_deserialize(message) + dictionary = message_converter.convert_ros_message_to_dictionary(message) + self.assertEqual(dictionary, expected_dictionary) + + def test_ros_message_with_duration(self): + from std_msgs.msg import Duration + + duration = rospy.rostime.Duration(33, 25) + expected_dictionary = {'data': {'secs': duration.secs, 'nsecs': duration.nsecs}} + message = Duration(data=duration) + message = serialize_deserialize(message) + dictionary = message_converter.convert_ros_message_to_dictionary(message) + self.assertEqual(dictionary, expected_dictionary) + + def test_ros_message_with_empty(self): + from std_msgs.msg import Empty + + expected_dictionary = {} + message = Empty() + message = serialize_deserialize(message) + dictionary = message_converter.convert_ros_message_to_dictionary(message) + self.assertEqual(dictionary, expected_dictionary) + + def test_ros_message_with_float32(self): + from std_msgs.msg import Float32 + + expected_dictionary = {'data': struct.unpack('`_) + * do not specify obsolete c++11 standard + this breaks with current versions of log4cxx. + * update pluginlib include paths + the non-hpp headers have been deprecated since kinetic + * use lambdas in favor of boost::bind + Using boost's _1 as a global system is deprecated since C++11. + The ROS packages in Debian removed the implicit support for the global symbols, + so this code fails to compile there without the patch. +* Contributors: Michael Görner + +1.17.2 (2022-06-20) +------------------- + +1.17.1 (2020-08-27) +------------------- + +1.17.0 (2020-04-02) +------------------- +* Merge pull request `#982 `_ from ros-planning/noetic_prep + Noetic Migration +* increase required cmake version +* Contributors: Michael Ferguson + +1.16.6 (2020-03-18) +------------------- + +1.16.5 (2020-03-15) +------------------- +* [melodic] updated install for better portability. (`#973 `_) +* Contributors: Sean Yen + +1.16.4 (2020-03-04) +------------------- +* [Windows][melodic] Navigation (except for map_server and amcl) Windows build bring up (`#851 `_) +* Contributors: Sean Yen + +1.16.3 (2019-11-15) +------------------- +* Merge branch 'melodic-devel' into layer_clear_area-melodic +* Cherry pick `#914 `_ (`#919 `_) +* Contributors: David V. Lu!!, Steven Macenski + +1.16.2 (2018-07-31) +------------------- +* Merge pull request `#773 `_ from ros-planning/packaging_fixes + packaging fixes +* fix rotate_recovery debian build + * add depend on tf2_geometry_msgs (due to https://github.com/ros/geometry2/issues/275) + * add other hidden depends: angles, geometry_msgs, tf2 +* Contributors: Michael Ferguson + +1.16.1 (2018-07-28) +------------------- + +1.16.0 (2018-07-25) +------------------- +* Remove dependency on PCL +* Switch to TF2 `#755 `_ +* fix param names of RotateRecovery, closes `#706 `_ +* Contributors: David V. Lu, Michael Ferguson, Vincent Rabaud + +1.15.2 (2018-03-22) +------------------- +* Merge pull request `#673 `_ from ros-planning/email_update_lunar + update maintainer email (lunar) +* Merge pull request `#649 `_ from aaronhoy/lunar_add_ahoy + Add myself as a maintainer. +* Rebase PRs from Indigo/Kinetic (`#637 `_) + * Respect planner_frequency intended behavior (`#622 `_) + * Only do a getRobotPose when no start pose is given (`#628 `_) + Omit the unnecessary call to getRobotPose when the start pose was + already given, so that move_base can also generate a path in + situations where getRobotPose would fail. + This is actually to work around an issue of getRobotPose randomly + failing. + * Update gradient_path.cpp (`#576 `_) + * Update gradient_path.cpp + * Update navfn.cpp + * update to use non deprecated pluginlib macro (`#630 `_) + * update to use non deprecated pluginlib macro + * multiline version as well + * Print SDL error on IMG_Load failure in server_map (`#631 `_) +* Contributors: Aaron Hoy, David V. Lu!!, Michael Ferguson + +1.15.1 (2017-08-14) +------------------- + +1.15.0 (2017-08-07) +------------------- +* convert packages to format2 +* Fix CMakeLists + package.xmls (`#548 `_) +* Contributors: Martin Günther, Mikael Arguedas, Vincent Rabaud + +1.14.0 (2016-05-20) +------------------- + +1.13.1 (2015-10-29) +------------------- + +1.13.0 (2015-03-17) +------------------- + +1.12.0 (2015-02-04) +------------------- +* update maintainer email +* Contributors: Michael Ferguson + +1.11.15 (2015-02-03) +-------------------- +* Add ARCHIVE_DESTINATION for static builds +* Contributors: Gary Servin + +1.11.14 (2014-12-05) +-------------------- + +1.11.13 (2014-10-02) +-------------------- + +1.11.12 (2014-10-01) +-------------------- + +1.11.11 (2014-07-23) +-------------------- + +1.11.10 (2014-06-25) +-------------------- + +1.11.9 (2014-06-10) +------------------- + +1.11.8 (2014-05-21) +------------------- + +1.11.7 (2014-05-21) +------------------- +* update build to find eigen using cmake_modules +* Contributors: Michael Ferguson + +1.11.4 (2013-09-27) +------------------- +* Package URL Updates diff --git a/navigations/rotate_recovery/CMakeLists.txt b/navigations/rotate_recovery/CMakeLists.txt new file mode 100755 index 0000000..c41b5b6 --- /dev/null +++ b/navigations/rotate_recovery/CMakeLists.txt @@ -0,0 +1,58 @@ +cmake_minimum_required(VERSION 3.0.2) +project(rotate_recovery) + +find_package(catkin REQUIRED + COMPONENTS + angles + base_local_planner + cmake_modules + costmap_2d + geometry_msgs + nav_core + pluginlib + roscpp + tf2 + tf2_geometry_msgs + tf2_ros +) + +find_package(Eigen3 REQUIRED) +include_directories( + include + ${catkin_INCLUDE_DIRS} + ${EIGEN3_INCLUDE_DIRS} +) +add_definitions(${EIGEN3_DEFINITIONS}) + +catkin_package( + INCLUDE_DIRS include + LIBRARIES rotate_recovery + CATKIN_DEPENDS + costmap_2d + geometry_msgs + nav_core + pluginlib + roscpp + tf2 + tf2_ros +) + +add_library(rotate_recovery src/rotate_recovery.cpp) +add_dependencies(rotate_recovery ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) +target_link_libraries(rotate_recovery ${catkin_LIBRARIES}) + +install(TARGETS rotate_recovery + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} + ) + +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} + FILES_MATCHING PATTERN "*.h" +) + +install(FILES rotate_plugin.xml + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) + diff --git a/navigations/rotate_recovery/include/rotate_recovery/rotate_recovery.h b/navigations/rotate_recovery/include/rotate_recovery/rotate_recovery.h new file mode 100755 index 0000000..cbfdf2d --- /dev/null +++ b/navigations/rotate_recovery/include/rotate_recovery/rotate_recovery.h @@ -0,0 +1,86 @@ +/********************************************************************* +* +* Software License Agreement (BSD License) +* +* Copyright (c) 2009, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of Willow Garage, Inc. nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* +* Author: Eitan Marder-Eppstein +*********************************************************************/ +#ifndef ROTATE_RECOVERY_ROTATE_RECOVERY_H +#define ROTATE_RECOVERY_ROTATE_RECOVERY_H +#include +#include +#include +#include +#include + +namespace rotate_recovery +{ +/** + * @class RotateRecovery + * @brief A recovery behavior that rotates the robot in-place to attempt to clear out space + */ +class RotateRecovery : public nav_core::RecoveryBehavior +{ +public: + /** + * @brief Constructor, make sure to call initialize in addition to actually initialize the object + */ + RotateRecovery(); + + /** + * @brief Initialization function for the RotateRecovery recovery behavior + * @param name Namespace used in initialization + * @param tf (unused) + * @param global_costmap (unused) + * @param local_costmap A pointer to the local_costmap used by the navigation stack + */ + void initialize(std::string name, tf2_ros::Buffer*, + costmap_2d::Costmap2DROS*, costmap_2d::Costmap2DROS* local_costmap); + + /** + * @brief Run the RotateRecovery recovery behavior. + */ + void runBehavior(); + + /** + * @brief Destructor for the rotate recovery behavior + */ + ~RotateRecovery(); + +private: + costmap_2d::Costmap2DROS* local_costmap_; + bool initialized_; + double sim_granularity_, min_rotational_vel_, max_rotational_vel_, acc_lim_th_, tolerance_, frequency_; + base_local_planner::CostmapModel* world_model_; +}; +}; // namespace rotate_recovery +#endif // ROTATE_RECOVERY_ROTATE_RECOVERY_H diff --git a/navigations/rotate_recovery/package.xml b/navigations/rotate_recovery/package.xml new file mode 100755 index 0000000..cfec387 --- /dev/null +++ b/navigations/rotate_recovery/package.xml @@ -0,0 +1,39 @@ + + + + rotate_recovery + 1.17.3 + + + This package provides a recovery behavior for the navigation stack that attempts to clear space by performing a 360 degree rotation of the robot. + + + Eitan Marder-Eppstein + contradict@gmail.com + David V. Lu!! + Michael Ferguson + Aaron Hoy + BSD + http://wiki.ros.org/rotate_recovery + + catkin + + angles + base_local_planner + cmake_modules + + costmap_2d + eigen + geometry_msgs + nav_core + pluginlib + roscpp + tf2 + tf2_geometry_msgs + tf2_ros + + + + + + diff --git a/navigations/rotate_recovery/rotate_plugin.xml b/navigations/rotate_recovery/rotate_plugin.xml new file mode 100755 index 0000000..1b6cf3e --- /dev/null +++ b/navigations/rotate_recovery/rotate_plugin.xml @@ -0,0 +1,7 @@ + + + + A recovery behavior that performs a 360 degree in-place rotation to attempt to clear out space. + + + diff --git a/navigations/rotate_recovery/src/rotate_recovery.cpp b/navigations/rotate_recovery/src/rotate_recovery.cpp new file mode 100755 index 0000000..b144736 --- /dev/null +++ b/navigations/rotate_recovery/src/rotate_recovery.cpp @@ -0,0 +1,183 @@ +/********************************************************************* +* +* Software License Agreement (BSD License) +* +* Copyright (c) 2009, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of Willow Garage, Inc. nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* +* Author: Eitan Marder-Eppstein +*********************************************************************/ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + + +// register this planner as a RecoveryBehavior plugin +PLUGINLIB_EXPORT_CLASS(rotate_recovery::RotateRecovery, nav_core::RecoveryBehavior) + +namespace rotate_recovery +{ +RotateRecovery::RotateRecovery(): local_costmap_(NULL), initialized_(false), world_model_(NULL) +{ +} + +void RotateRecovery::initialize(std::string name, tf2_ros::Buffer*, + costmap_2d::Costmap2DROS*, costmap_2d::Costmap2DROS* local_costmap) +{ + if (!initialized_) + { + local_costmap_ = local_costmap; + + // get some parameters from the parameter server + ros::NodeHandle private_nh("~/" + name); + ros::NodeHandle blp_nh("~/TrajectoryPlannerROS"); + + // we'll simulate every degree by default + private_nh.param("sim_granularity", sim_granularity_, 0.017); + private_nh.param("frequency", frequency_, 20.0); + + acc_lim_th_ = nav_core::loadParameterWithDeprecation(blp_nh, "acc_lim_theta", "acc_lim_th", 3.2); + max_rotational_vel_ = nav_core::loadParameterWithDeprecation(blp_nh, "max_vel_theta", "max_rotational_vel", 1.0); + min_rotational_vel_ = nav_core::loadParameterWithDeprecation(blp_nh, "min_in_place_vel_theta", "min_in_place_rotational_vel", 0.4); + blp_nh.param("yaw_goal_tolerance", tolerance_, 0.10); + + world_model_ = new base_local_planner::CostmapModel(*local_costmap_->getCostmap()); + + initialized_ = true; + } + else + { + ROS_ERROR("You should not call initialize twice on this object, doing nothing"); + } +} + +RotateRecovery::~RotateRecovery() +{ + delete world_model_; +} + +void RotateRecovery::runBehavior() +{ + if (!initialized_) + { + ROS_ERROR("This object must be initialized before runBehavior is called"); + return; + } + + if (local_costmap_ == NULL) + { + ROS_ERROR("The costmap passed to the RotateRecovery object cannot be NULL. Doing nothing."); + return; + } + ROS_WARN("Rotate recovery behavior started."); + + ros::Rate r(frequency_); + ros::NodeHandle n; + ros::Publisher vel_pub = n.advertise("cmd_vel", 10); + + geometry_msgs::PoseStamped global_pose; + local_costmap_->getRobotPose(global_pose); + + double current_angle = tf2::getYaw(global_pose.pose.orientation); + double start_angle = current_angle; + + bool got_180 = false; + + while (n.ok() && + (!got_180 || + std::fabs(angles::shortest_angular_distance(current_angle, start_angle)) > tolerance_)) + { + // Update Current Angle + local_costmap_->getRobotPose(global_pose); + current_angle = tf2::getYaw(global_pose.pose.orientation); + + // compute the distance left to rotate + double dist_left; + if (!got_180) + { + // If we haven't hit 180 yet, we need to rotate a half circle plus the distance to the 180 point + double distance_to_180 = std::fabs(angles::shortest_angular_distance(current_angle, start_angle + M_PI)); + dist_left = M_PI + distance_to_180; + + if (distance_to_180 < tolerance_) + { + got_180 = true; + } + } + else + { + // If we have hit the 180, we just have the distance back to the start + dist_left = std::fabs(angles::shortest_angular_distance(current_angle, start_angle)); + } + + double x = global_pose.pose.position.x, y = global_pose.pose.position.y; + + // check if that velocity is legal by forward simulating + double sim_angle = 0.0; + while (sim_angle < dist_left) + { + double theta = current_angle + sim_angle; + + // make sure that the point is legal, if it isn't... we'll abort + double footprint_cost = world_model_->footprintCost(x, y, theta, local_costmap_->getRobotFootprint(), 0.0, 0.0); + if (footprint_cost < 0.0) + { + ROS_ERROR("Rotate recovery can't rotate in place because there is a potential collision. Cost: %.2f", + footprint_cost); + return; + } + + sim_angle += sim_granularity_; + } + + // compute the velocity that will let us stop by the time we reach the goal + double vel = sqrt(2 * acc_lim_th_ * dist_left); + + // make sure that this velocity falls within the specified limits + vel = std::min(std::max(vel, min_rotational_vel_), max_rotational_vel_); + + geometry_msgs::Twist cmd_vel; + cmd_vel.linear.x = 0.0; + cmd_vel.linear.y = 0.0; + cmd_vel.angular.z = vel; + + vel_pub.publish(cmd_vel); + + r.sleep(); + } +} +}; // namespace rotate_recovery diff --git a/navigations/sbpl/.gitignore b/navigations/sbpl/.gitignore new file mode 100755 index 0000000..051d772 --- /dev/null +++ b/navigations/sbpl/.gitignore @@ -0,0 +1,13 @@ +cmake_install.cmake + +envdebug.txt +debug.txt +sol.txt + +bin/* +lib/* +CMakeFiles/* +build/* + +.project +.cproject diff --git a/navigations/sbpl/CMakeLists.txt b/navigations/sbpl/CMakeLists.txt new file mode 100755 index 0000000..99723df --- /dev/null +++ b/navigations/sbpl/CMakeLists.txt @@ -0,0 +1,80 @@ +cmake_minimum_required(VERSION 2.8) +PROJECT( sbpl ) + +# version (e.g. for packaging) +set(SBPL_MAJOR_VERSION 1) +set(SBPL_MINOR_VERSION 3) +set(SBPL_PATCH_VERSION 1) +set(SBPL_VERSION ${SBPL_MAJOR_VERSION}.${SBPL_MINOR_VERSION}.${SBPL_PATCH_VERSION}) + +set(CMAKE_BUILD_TYPE Release) + +include_directories(src/include) + +add_library(sbpl SHARED + src/discrete_space_information/environment_nav2D.cpp + src/discrete_space_information/environment_navxythetalat.cpp + src/discrete_space_information/environment_navxythetamlevlat.cpp + src/discrete_space_information/environment_nav2Duu.cpp + src/discrete_space_information/environment_XXX.cpp + src/discrete_space_information/environment_robarm.cpp + src/heuristics/embedded_heuristic.cpp + src/planners/adplanner.cpp + src/planners/ANAplanner.cpp + src/planners/araplanner.cpp + src/planners/lazyARA.cpp + src/planners/mhaplanner.cpp + src/planners/ppcpplanner.cpp + src/planners/rstarplanner.cpp + src/planners/viplanner.cpp + src/utils/heap.cpp + src/utils/mdp.cpp + src/utils/utils.cpp + src/utils/2Dgridsearch.cpp + src/utils/config.cpp + ) + +set(SBPL_INCLUDE_DIR "${CMAKE_INSTALL_PREFIX}/include") +set(SBPL_LIB_DIR "${CMAKE_INSTALL_PREFIX}/lib") + +# support for pkg-config +set(PKG_NAME "sbpl") +set(PKG_DESC "The Search Based Planning Library") +set(PKG_SBPL_LIBS "-lsbpl") +set(pkg_conf_file_in "${CMAKE_CURRENT_SOURCE_DIR}/sbpl.pc.in") +set(pkg_conf_file "${PROJECT_BINARY_DIR}/InstallFiles/sbpl.pc") +configure_file("${pkg_conf_file_in}" "${pkg_conf_file}" @ONLY) +install(FILES ${pkg_conf_file} DESTINATION lib/pkgconfig/ COMPONENT pkgconfig) + +# support for cmake-config: +configure_file(sbpl-config.cmake.in + "${PROJECT_BINARY_DIR}/InstallFiles/sbpl-config.cmake" @ONLY) +configure_file(sbpl-config-version.cmake.in + "${PROJECT_BINARY_DIR}/InstallFiles/sbpl-config-version.cmake" @ONLY) +install(FILES + "${PROJECT_BINARY_DIR}/InstallFiles/sbpl-config.cmake" + "${PROJECT_BINARY_DIR}/InstallFiles/sbpl-config-version.cmake" +DESTINATION share/sbpl/) + +# support for build tree export +option(SBPL_BUILD_TREE_EXPORT "Enable build tree exports" OFF) +if (${SBPL_BUILD_TREE_EXPORT}) + export(TARGETS sbpl FILE sbpl-targets.cmake) + set(CONF_INCLUDE_DIRS "${PROJECT_SOURCE_DIR}/src/include") + configure_file( + sbpl-config-tree-export.cmake.in + "${PROJECT_BINARY_DIR}/sbpl-config.cmake" + @ONLY) + export(PACKAGE sbpl) +endif() + +install(DIRECTORY src/include/sbpl DESTINATION include + FILES_MATCHING PATTERN "*.h") +install(TARGETS sbpl + LIBRARY DESTINATION lib) + +add_executable(test_sbpl src/test/main.cpp) +target_link_libraries(test_sbpl sbpl) + +add_executable(test_adjacency_list src/test/test_adjacency_list.cpp) +target_link_libraries(test_adjacency_list sbpl) diff --git a/navigations/sbpl/Doxyfile b/navigations/sbpl/Doxyfile new file mode 100755 index 0000000..b513a4c --- /dev/null +++ b/navigations/sbpl/Doxyfile @@ -0,0 +1,207 @@ +PROJECT_NAME = "ROS SBPL Motion Planner Library" +PROJECT_NUMBER = +OUTPUT_DIRECTORY = . +OUTPUT_LANGUAGE = English +USE_WINDOWS_ENCODING = NO +BRIEF_MEMBER_DESC = YES +REPEAT_BRIEF = YES +ALWAYS_DETAILED_SEC = NO +INLINE_INHERITED_MEMB = NO +FULL_PATH_NAMES = NO +STRIP_FROM_PATH = +SHORT_NAMES = NO +JAVADOC_AUTOBRIEF = NO +MULTILINE_CPP_IS_BRIEF = NO +DETAILS_AT_TOP = NO +INHERIT_DOCS = YES +DISTRIBUTE_GROUP_DOC = NO +TAB_SIZE = 8 +ALIASES = +OPTIMIZE_OUTPUT_FOR_C = NO +OPTIMIZE_OUTPUT_JAVA = NO +SUBGROUPING = YES + +#--------------------------------------------------------------------------- +# Build related configuration options +#--------------------------------------------------------------------------- + +EXTRACT_ALL = YES +EXTRACT_PRIVATE = YES +EXTRACT_STATIC = YES +EXTRACT_LOCAL_CLASSES = YES +HIDE_UNDOC_MEMBERS = NO +HIDE_UNDOC_CLASSES = NO +HIDE_FRIEND_COMPOUNDS = NO +HIDE_IN_BODY_DOCS = NO +INTERNAL_DOCS = NO +CASE_SENSE_NAMES = YES +HIDE_SCOPE_NAMES = NO +SHOW_INCLUDE_FILES = YES +INLINE_INFO = YES +SORT_MEMBER_DOCS = YES +GENERATE_TODOLIST = YES +GENERATE_TESTLIST = YES +GENERATE_BUGLIST = YES +GENERATE_DEPRECATEDLIST= YES +ENABLED_SECTIONS = +MAX_INITIALIZER_LINES = 30 +SHOW_USED_FILES = YES + +#--------------------------------------------------------------------------- +# configuration options related to warning and progress messages +#--------------------------------------------------------------------------- + +QUIET = YES +WARNINGS = YES +WARN_IF_UNDOCUMENTED = NO +WARN_IF_DOC_ERROR = YES +WARN_FORMAT = "$file:$line: $text" +WARN_LOGFILE = + +#--------------------------------------------------------------------------- +# configuration options related to the input files +#--------------------------------------------------------------------------- + +INPUT = src +FILE_PATTERNS = *.h *.cpp +RECURSIVE = YES +EXCLUDE = +EXCLUDE_SYMLINKS = NO +EXCLUDE_PATTERNS = +EXAMPLE_PATH = +EXAMPLE_PATTERNS = +EXAMPLE_RECURSIVE = NO +IMAGE_PATH = +INPUT_FILTER = +FILTER_SOURCE_FILES = NO + +#--------------------------------------------------------------------------- +# configuration options related to source browsing +#--------------------------------------------------------------------------- + +SOURCE_BROWSER = NO +INLINE_SOURCES = NO +STRIP_CODE_COMMENTS = YES +REFERENCED_BY_RELATION = YES +REFERENCES_RELATION = YES +VERBATIM_HEADERS = YES + +#--------------------------------------------------------------------------- +# configuration options related to the alphabetical class index +#--------------------------------------------------------------------------- + +ALPHABETICAL_INDEX = NO +COLS_IN_ALPHA_INDEX = 5 +IGNORE_PREFIX = + +#--------------------------------------------------------------------------- +# configuration options related to the HTML output +#--------------------------------------------------------------------------- + +GENERATE_HTML = YES +HTML_OUTPUT = html +HTML_FILE_EXTENSION = .html +HTML_HEADER = +HTML_FOOTER = +HTML_STYLESHEET = +HTML_ALIGN_MEMBERS = YES +GENERATE_HTMLHELP = NO +CHM_FILE = +HHC_LOCATION = +GENERATE_CHI = NO +BINARY_TOC = NO +TOC_EXPAND = NO +DISABLE_INDEX = NO +ENUM_VALUES_PER_LINE = 4 +GENERATE_TREEVIEW = NO +TREEVIEW_WIDTH = 250 + +#--------------------------------------------------------------------------- +# configuration options related to the LaTeX output +#--------------------------------------------------------------------------- + +GENERATE_LATEX = NO + +#--------------------------------------------------------------------------- +# configuration options related to the RTF output +#--------------------------------------------------------------------------- + +GENERATE_RTF = NO + +#--------------------------------------------------------------------------- +# configuration options related to the man page output +#--------------------------------------------------------------------------- + +GENERATE_MAN = NO + +#--------------------------------------------------------------------------- +# configuration options related to the XML output +#--------------------------------------------------------------------------- + +GENERATE_XML = NO + +#--------------------------------------------------------------------------- +# configuration options for the AutoGen Definitions output +#--------------------------------------------------------------------------- + +GENERATE_AUTOGEN_DEF = NO + +#--------------------------------------------------------------------------- +# configuration options related to the Perl module output +#--------------------------------------------------------------------------- + +GENERATE_PERLMOD = NO + +#--------------------------------------------------------------------------- +# Configuration options related to the preprocessor +#--------------------------------------------------------------------------- + +ENABLE_PREPROCESSING = YES +MACRO_EXPANSION = NO +EXPAND_ONLY_PREDEF = NO +SEARCH_INCLUDES = YES +INCLUDE_PATH = +INCLUDE_FILE_PATTERNS = +PREDEFINED = +EXPAND_AS_DEFINED = +SKIP_FUNCTION_MACROS = YES + +#--------------------------------------------------------------------------- +# Configuration::addtions related to external references +#--------------------------------------------------------------------------- + +TAGFILES = +GENERATE_TAGFILE = +ALLEXTERNALS = NO +EXTERNAL_GROUPS = YES +PERL_PATH = /usr/bin/perl + +#--------------------------------------------------------------------------- +# Configuration options related to the dot tool +#--------------------------------------------------------------------------- + +CLASS_DIAGRAMS = YES +HIDE_UNDOC_RELATIONS = NO +HAVE_DOT = YES +CLASS_GRAPH = YES +COLLABORATION_GRAPH = YES +UML_LOOK = NO +TEMPLATE_RELATIONS = YES +INCLUDE_GRAPH = YES +INCLUDED_BY_GRAPH = YES +CALL_GRAPH = NO +GRAPHICAL_HIERARCHY = YES +DOT_IMAGE_FORMAT = png +DOT_PATH = +DOTFILE_DIRS = +MAX_DOT_GRAPH_WIDTH = 1024 +MAX_DOT_GRAPH_HEIGHT = 1024 +MAX_DOT_GRAPH_DEPTH = 0 +GENERATE_LEGEND = YES +DOT_CLEANUP = YES + +#--------------------------------------------------------------------------- +# Configuration::addtions related to the search engine +#--------------------------------------------------------------------------- + +SEARCHENGINE = NO diff --git a/navigations/sbpl/README.txt b/navigations/sbpl/README.txt new file mode 100755 index 0000000..b794ce0 --- /dev/null +++ b/navigations/sbpl/README.txt @@ -0,0 +1,173 @@ +I. Building, Installing, and Using SBPL + + SBPL is available as a standalone software library. SBPL itself has no + dependencies other than the C/C++ standard library. + + These build and install instructions are primarily for Linux. For other + operating systems, CMake can generate the platform-specific build and project + files necessary for building SBPL. + + Versions of ROS older than Fuerte may contain packages that depend on a ROS + package version of SBPL. The recommended method to install SBPL is to install + it as a standard system library. However, if you wish to use the old ROS + package version of SBPL, you may follow these instructions. + + 1. Building and Installing SBPL from source + + 1.1 Build SBPL + + SBPL uses git as its version control system. From the directory where + you want the SBPL source to reside, clone the latest source from + https://github.com/sbpl/sbpl: + + git clone https://github.com/sbpl/sbpl.git + + In the source directory, build the SBPL library using standard + CMake build conventions: + + mkdir build + cd build + cmake .. + make + + 1.2 Install SBPL + + Install the built library and headers onto your local system + (usually into /usr/local): + + sudo make install + + 2. Installing SBPL from pre-built binary package + + A pre-built Debian package exists on Linux for ROS distributions + Fuerte and newer. To install the Debian, run: + + sudo apt-get install ros-distro-sbpl + + where distro is the name of your ROS distribution. This will install + the SBPL library and associated development headers alongside other + ROS components (in /opt/ros/distro on Ubuntu distributions). A + pkg-config file is also included to allow you to locate the SBPL + library components in your build system. + + 3. Build your (ROS) package with SBPL as a dependency (CMake) + + In the CMakeLists.txt for your (ROS) package, the following lines are + needed to find the installed SBPL files: + + find_package(PkgConfig REQUIRED) + pkg_check_modules(SBPL REQUIRED sbpl) + include_directories(${SBPL_INCLUDE_DIRS}) + link_directories(${SBPL_LIBRARY_DIRS}) + + Then, after you've declared your binaries, you need to link them + against SBPL with the following line: + + target_link_libraries(your-binary-here ${SBPL_LIBRARIES}) + + 4. Installing and Using SBPL as a ROS package + + The ROS package version of SBPL was deprecated with the release of ROS + Fuerte. However, packages in ROS Electric may still require the ROS + package version of SBPL. + + 4.1 Install SBPL + + 4.1.1 Source install + + SBPL uses git as its version control system. From the + directory where you want the SBPL source to reside, clone the + latest source from https://github.com/sbpl/sbpl: + + git clone https://github.com/sbpl/sbpl.git + + In the source directory, checkout the electric branch of the + repository to revert to the old ROS package version: + + git checkout -b electric + + Ensure that SBPL is on your ROS_PACKAGE_PATH and type: + + rosmake sbpl + + 4.1.2 Binary install + + SBPL is also available as a pre-built Debian in ROS Electric. + To instal the Debian, run: + + sudo apt-get install ros-electric-arm-navigation + + 4.2 Build your ROS package with SBPL as a depency (rosbuild) + + In the manifest.xml for your package, you need to add the + following line to declare the SBPL package as a dependency: + + + +II. Usage + + Examples for how to use SBPL are in src/test/main.cpp. Please follow the + examples carefully. The library contains a number of planning problem + examples, stored as ascii files. These files (with extension .cfg) should + be passed in as arguments into the main function in main.cpp. The files + can be found in env_examples directory. + + Command-line usage for the test_sbpl program can be viewed by passing '-h' + as argument to the executable. + + Examples: + + The following can be run from the directory containing test_sbpl, + which we assume is a build directory in the root of this project. + + $ ./test_sbpl ../env_examples/nav3d/env1.cfg + Environment: xytheta; Planner: arastar; Search direction: backward + Initializing ARAPlanner... + start planning... + done planning + size of solution=16 + solution size=0 + Solution is found + + $ ./test_sbpl --env=2d ../env_examples/nav2d/env1.cfg #2d is needed here in order to use 2d config + Environment: 2d; Planner: arastar; Search direction: backward + Initializing ARAPlanner... + start planning... + done planning + size of solution=22 + Solution is found + + $ ./test_sbpl --env=robarm --search-dir=forward --planner=rstar ../env_examples/robarm/env1_6d.cfg + Environment: robarm; Planner: rstar; Search direction: forward + Initializing RSTARPlanner... + start planning... + done planning + size of solution=44 + Solution is found + + Motion primitives files can be found in sbpl/matlab/mprim directory. + + Finally, few visualization scripts can be found in + sbpl/matlab/visualization. In particular, plot_3Dpath.m function can be + used to visualize the path found by xytheta lattice planner. This + functions takes in .cfg file that specified environment and sol.txt file + that was generated within main.cpp by xythetalattice planners. + + Note: If you compile the library with the ROS symbol defined, all text + output will be redirected to ROS logging constructions. Without the ROS + symbol defined, SBPL will print messages to stdout and test_sbpl will + generate a solution file, sol.txt, as well as a debugging information + file, debug.txt + +III. Links + + These instructions and more tutorials can be found at www.sbpl.net + + For more information and documentation on SBPL visit: + + http://www.ros.org/wiki/sbpl + + For more information and documentation on using the x,y,theta environment + available in ROS visit: + + http://www.ros.org/wiki/sbpl_lattice_planner diff --git a/navigations/sbpl/env_examples/nav2d/env1.cfg b/navigations/sbpl/env_examples/nav2d/env1.cfg new file mode 100755 index 0000000..3f93f3a --- /dev/null +++ b/navigations/sbpl/env_examples/nav2d/env1.cfg @@ -0,0 +1,20 @@ +discretization(cells): 15 15 +obsthresh: 1 +start(cells): 0 0 +end(cells): 14 14 +environment: +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 1 1 1 1 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 +1 1 1 1 0 0 0 0 0 0 0 1 0 0 0 +1 1 1 1 0 0 0 0 0 0 0 1 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 diff --git a/navigations/sbpl/env_examples/nav2d/env2.cfg b/navigations/sbpl/env_examples/nav2d/env2.cfg new file mode 100755 index 0000000..0b4c3c8 --- /dev/null +++ b/navigations/sbpl/env_examples/nav2d/env2.cfg @@ -0,0 +1,1205 @@ +discretization(cells): 100 1200 +obsthresh: 1 +start(cells): 0 0 +end(cells): 99 999 +environment: +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 diff --git a/navigations/sbpl/env_examples/nav2duu/env1.cfg b/navigations/sbpl/env_examples/nav2duu/env1.cfg new file mode 100755 index 0000000..7a424f1 --- /dev/null +++ b/navigations/sbpl/env_examples/nav2duu/env1.cfg @@ -0,0 +1,20 @@ +discretization(cells): 15 15 +obsthresh: 1 +start(cells): 0 0 +end(cells): 14 14 +environment: +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 1 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 1 0 0 0 0 +0 0 0 0 0 0 1 1 1 0 1 1 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0.1 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 +1 1 1 1 0 0 0 0 0 0 0 1 0 0 0 +1 1 1 1 0 0 0 0 0 0 0 0.9 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0.5 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 diff --git a/navigations/sbpl/env_examples/nav3d/cubicle-25mm-inflated-env.cfg b/navigations/sbpl/env_examples/nav3d/cubicle-25mm-inflated-env.cfg new file mode 100755 index 0000000..5748e0e --- /dev/null +++ b/navigations/sbpl/env_examples/nav3d/cubicle-25mm-inflated-env.cfg @@ -0,0 +1,483 @@ +discretization(cells): 436 473 +obsthresh: 254 +cost_inscribed_thresh: 253 +cost_possibly_circumscribed_thresh: 128 +cellsize(meters): 0.025 +nominalvel(mpersecs): 1.0 +timetoturn45degsinplace(secs): 20.0 +start(meters,rads): 4.0 8.0 0 +end(meters,rads): 6.00 2.0 0 +environment: + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 2 2 2 2 2 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 2 5 9 12 15 17 18 17 15 12 9 5 2 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 3 9 16 24 32 40 46 49 51 49 46 40 32 24 16 9 3 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 8 18 30 44 59 72 84 93 99 101 99 93 84 72 59 44 30 18 8 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 4 13 28 46 66 87 108 128 144 157 165 168 165 157 144 128 108 87 66 46 28 13 4 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 17 35 59 86 115 144 173 199 221 238 248 252 248 238 221 199 173 144 115 86 59 35 17 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 67 101 137 176 215 252 253 253 253 253 253 253 253 253 253 252 215 176 137 101 67 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 5 19 40 71 108 152 199 248 253 253 253 253 253 253 253 253 253 253 253 253 253 248 199 152 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 4 17 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 13 35 67 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 8 28 59 101 152 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 4 18 46 86 137 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 13 35 67 115 176 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 8 28 59 101 152 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 4 18 46 86 137 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 13 35 67 115 176 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 8 28 59 101 152 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 4 18 46 86 137 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 13 35 67 115 176 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 8 28 59 101 152 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3 18 46 86 137 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 30 66 115 176 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 4 18 46 87 144 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 13 35 67 115 176 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 8 28 59 101 152 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 4 18 46 86 137 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 13 35 67 115 176 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 8 28 59 101 152 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 4 18 46 86 137 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 13 35 67 115 176 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 8 28 59 101 152 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 4 18 46 86 137 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 13 35 67 115 176 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 8 28 59 101 152 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 4 18 46 86 137 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 13 35 67 115 176 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 8 28 59 101 152 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 4 18 46 86 137 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 13 35 67 115 176 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 8 28 59 101 152 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 4 18 46 86 137 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 13 35 67 115 176 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 248 176 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 8 28 59 101 152 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 137 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3 18 46 86 137 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 152 101 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 30 66 115 176 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 248 176 115 67 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 4 18 46 87 144 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 137 86 46 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 13 35 67 115 176 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 152 101 59 28 8 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 8 28 59 101 152 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 248 176 115 67 35 13 2 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 4 18 46 86 137 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 137 86 46 18 4 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 13 35 67 115 176 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 152 101 59 28 8 1 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 8 28 59 101 152 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 248 176 115 67 35 13 2 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 4 18 46 86 137 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 137 86 46 18 4 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 13 35 67 115 176 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 152 101 59 28 8 1 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 8 28 59 101 152 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 248 176 115 67 35 13 2 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 4 18 46 86 137 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 137 86 46 18 4 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 13 35 67 115 176 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 152 101 59 28 8 1 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 8 28 59 101 152 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 248 176 115 67 35 13 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 4 18 46 86 137 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 137 86 46 18 4 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 13 35 67 115 176 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 152 101 59 28 8 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 8 28 59 101 152 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 252 176 115 67 35 13 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 4 18 46 86 137 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 144 87 46 18 4 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 13 35 67 115 176 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 248 176 115 66 30 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 8 28 59 101 152 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 137 86 46 18 3 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 8 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 4 18 46 86 137 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 152 101 59 28 8 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 46 28 13 4 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 13 35 67 115 176 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 248 176 115 67 35 13 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 115 86 59 35 17 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 8 28 59 101 152 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 137 86 46 18 4 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 176 137 101 67 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 4 18 46 86 137 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 152 101 59 28 8 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 248 199 152 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 13 35 67 115 176 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 248 176 115 67 35 13 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 8 28 59 101 152 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 137 86 46 18 4 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3 18 46 86 137 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 152 101 59 28 8 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 30 66 115 176 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 248 176 115 67 35 13 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 4 18 46 87 144 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 137 86 46 18 4 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 13 35 67 115 176 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 152 101 59 28 8 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 8 28 59 101 152 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 248 176 115 67 35 13 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 4 18 46 86 137 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 137 86 46 18 4 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 13 35 67 115 176 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 152 101 59 28 8 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 8 28 59 101 152 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 248 176 115 67 35 13 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 4 18 46 86 137 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 137 86 46 18 4 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 13 35 67 115 176 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 152 101 59 28 8 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 8 28 59 101 152 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 248 176 115 67 35 13 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 4 18 46 86 137 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 137 86 46 18 4 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 13 35 67 115 176 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 152 101 59 28 8 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 8 28 59 101 152 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 248 176 115 67 35 13 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 4 18 46 86 137 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 137 86 46 18 4 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 13 35 67 115 176 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 152 101 59 28 8 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 8 28 59 101 152 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 252 176 115 67 35 13 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 4 18 46 86 137 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 144 87 46 18 4 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 13 35 67 115 176 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 248 176 115 66 30 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 8 28 59 101 152 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 137 86 46 18 3 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 152 199 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 4 18 46 86 137 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 152 101 59 28 8 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 67 101 137 176 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 13 35 67 115 176 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 248 176 115 67 35 13 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 17 35 59 86 115 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 8 28 59 101 152 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 137 86 46 18 4 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 4 13 28 46 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3 18 46 86 137 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 152 101 59 28 8 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 8 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 30 66 115 176 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 248 176 115 67 35 13 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 4 18 46 87 144 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 137 86 46 18 4 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 13 35 67 115 176 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 152 101 59 28 8 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 8 28 59 101 152 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 248 176 115 67 35 13 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 4 18 46 86 137 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 137 86 46 18 4 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 13 35 67 115 176 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 152 101 59 28 8 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 8 28 59 101 152 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 248 176 115 67 35 13 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 4 18 46 86 137 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 137 86 46 18 4 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 13 35 67 115 176 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 152 101 59 28 8 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 8 28 59 101 152 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 248 176 115 67 35 13 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3 18 46 86 137 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 137 86 46 18 4 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 30 66 115 176 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 152 101 59 28 8 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3 18 46 87 144 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 248 176 115 67 35 13 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 30 66 115 176 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 137 86 46 18 4 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 16 44 87 144 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 152 101 59 28 8 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 5 24 59 108 173 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 252 176 115 67 35 13 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 9 32 72 128 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 144 87 46 18 4 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 12 40 84 144 221 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 248 176 115 66 30 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 15 46 93 157 238 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 137 86 46 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 17 49 99 165 248 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 17 49 99 165 248 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 15 46 93 157 238 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 12 40 84 144 221 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 9 32 72 128 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 5 24 59 108 173 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 17 4 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 16 44 87 144 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 67 35 13 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 30 66 115 176 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 152 101 59 28 8 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3 18 46 86 137 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 137 86 46 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 8 28 59 101 152 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 248 176 115 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 13 35 67 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 4 17 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 17 4 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 67 35 13 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 152 101 59 28 8 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 137 86 46 18 3 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 248 176 115 66 30 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 144 87 46 18 3 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 252 176 115 66 30 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 144 87 46 18 3 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 252 176 115 66 30 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 8 18 35 59 86 115 152 199 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 144 87 44 16 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 17 4 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 4 13 28 46 67 101 137 176 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 252 173 108 59 24 5 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 67 35 13 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 8 18 35 59 86 115 152 199 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 128 72 32 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 152 101 59 28 8 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 4 13 28 46 67 101 137 176 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 221 144 87 46 18 3 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 115 176 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 137 86 46 18 3 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 17 35 59 86 115 152 199 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 176 115 66 30 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 46 86 137 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 248 176 115 66 30 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 8 19 40 67 101 137 176 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 144 87 46 18 3 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 8 28 59 101 152 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 144 87 44 16 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 4 13 28 46 71 108 152 199 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 176 115 66 30 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 13 35 67 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 252 173 108 59 24 5 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 8 18 35 59 86 115 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 144 87 44 16 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 4 17 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 128 72 32 9 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 4 13 28 46 67 101 137 176 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 252 173 108 59 24 5 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 221 144 84 40 12 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 8 18 35 59 86 115 152 199 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 128 72 32 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 238 157 93 46 15 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 4 13 28 46 67 101 137 176 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 221 144 87 46 18 3 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 248 165 99 49 17 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 8 18 35 59 86 115 152 199 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 176 115 66 30 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 4 13 28 46 67 101 137 176 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 144 87 44 16 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 248 165 99 49 17 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 8 18 35 59 86 115 152 199 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 173 108 59 24 5 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 238 157 93 46 15 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 4 13 28 46 67 101 137 176 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 128 72 32 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 221 144 84 40 12 1 1 2 2 2 2 2 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 8 18 35 59 86 115 152 199 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 221 144 87 46 18 3 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 128 72 32 9 9 12 15 17 18 17 15 12 9 5 2 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 4 13 28 46 67 101 137 176 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 176 115 66 30 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 252 173 108 59 24 24 32 40 46 49 51 49 46 40 32 24 16 9 3 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 8 18 35 59 86 115 152 199 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 144 87 44 16 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 144 87 44 44 59 72 84 93 99 101 99 93 84 72 59 44 30 18 8 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 4 13 28 46 67 101 137 176 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 173 108 59 24 5 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 248 176 115 66 66 87 108 128 144 157 165 168 165 157 144 128 108 87 66 46 28 13 4 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 8 18 35 59 86 115 152 199 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 128 72 32 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 137 86 86 115 144 173 199 221 238 248 252 248 238 221 199 173 144 115 86 59 35 17 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 4 13 28 46 67 101 137 176 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 221 144 87 46 18 3 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 152 101 101 137 176 215 252 253 253 253 253 253 253 253 253 253 252 215 176 137 101 67 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 8 18 35 59 86 115 152 199 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 176 115 66 30 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 108 152 199 248 253 253 253 253 253 253 253 253 253 253 253 253 253 248 199 152 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 4 13 28 46 67 101 137 176 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 144 87 46 18 3 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 152 199 248 253 253 253 253 253 253 253 253 253 253 253 253 253 248 199 152 108 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 8 18 35 59 86 115 152 199 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 221 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 176 115 66 30 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 67 101 137 176 215 252 253 253 253 253 253 253 253 253 253 252 215 176 137 101 101 152 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 4 13 28 46 67 101 137 176 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 248 199 152 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 144 87 44 16 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 17 35 59 86 115 144 173 199 221 238 248 252 248 238 221 199 173 144 115 86 86 137 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 8 18 35 59 86 115 152 199 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 176 137 108 173 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 252 173 108 59 24 5 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 4 13 28 46 66 87 108 128 144 157 165 168 165 157 144 128 108 87 66 66 115 176 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 4 13 28 46 67 101 137 176 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 248 199 152 115 86 87 144 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 128 72 32 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 8 18 30 44 59 72 84 93 99 101 99 93 84 72 59 44 44 87 144 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 8 18 35 59 86 115 152 199 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 176 137 101 67 46 66 115 176 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 221 144 87 46 18 3 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 3 9 16 24 32 40 46 49 51 49 46 40 32 24 24 59 108 173 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 4 13 28 46 67 101 137 176 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 248 199 152 115 86 59 35 18 46 87 144 221 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 176 115 66 30 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 2 5 9 12 15 17 18 17 15 12 9 9 32 72 128 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 8 18 35 59 86 115 152 199 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 176 137 101 67 46 28 13 9 32 72 128 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 144 87 44 16 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 2 2 2 2 2 1 1 12 40 84 144 221 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 4 13 28 46 67 101 137 176 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 115 86 59 35 18 8 2 5 24 59 108 173 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 173 108 59 24 5 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 15 46 93 157 238 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 8 18 35 59 86 115 152 199 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 248 199 152 108 71 46 28 13 4 1 0 2 16 44 87 144 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 128 72 32 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 17 49 99 165 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 4 13 28 46 67 101 137 176 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 176 137 101 67 40 19 8 2 0 0 0 1 9 30 66 115 176 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 221 144 87 46 18 3 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 8 18 35 59 86 115 152 199 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 248 199 152 115 86 59 35 17 5 1 0 0 0 0 0 3 18 46 87 144 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 176 115 66 30 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 17 49 99 165 248 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 4 13 28 46 67 101 137 176 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 176 137 101 67 46 28 13 4 0 0 0 0 0 0 0 1 9 30 66 115 176 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 144 87 44 16 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 15 46 93 157 238 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 17 35 59 86 115 152 199 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 248 199 152 115 86 59 35 18 8 2 0 0 0 0 0 0 0 0 0 3 18 46 87 144 221 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 173 108 59 24 5 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 12 40 84 144 221 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 8 19 40 67 101 137 176 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 176 137 101 67 46 28 13 4 1 0 0 0 0 0 0 0 0 0 0 1 9 32 72 128 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 128 72 32 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 9 32 72 128 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 0 0 1 4 13 28 46 71 108 152 199 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 248 199 152 115 86 59 35 18 8 2 0 0 0 0 0 0 0 0 0 0 0 0 0 5 24 59 108 173 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 221 144 87 46 18 3 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 5 24 59 108 173 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 0 0 0 2 8 18 35 59 86 115 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 176 137 101 67 46 28 13 4 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 16 44 87 144 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 176 115 66 30 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 16 44 87 144 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 0 0 1 4 13 28 46 67 101 137 176 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 248 199 152 115 86 59 35 18 8 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 30 66 115 176 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 144 87 46 18 3 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 30 66 115 176 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 0 0 0 2 8 18 35 59 86 115 152 199 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 176 137 101 67 46 28 13 4 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3 18 46 87 144 221 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 176 115 66 30 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3 18 46 86 137 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 1 0 1 4 13 28 46 67 101 137 176 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 248 199 152 115 86 59 35 18 8 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 32 72 128 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 144 87 44 16 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 8 28 59 101 152 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 5 2 8 18 35 59 86 115 152 199 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 176 137 101 67 46 28 13 4 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 5 24 59 108 173 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 252 173 108 59 24 5 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 13 35 67 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 19 13 28 46 67 101 137 176 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 248 199 152 115 86 59 35 18 8 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 16 44 87 144 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 128 72 32 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 4 17 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 40 35 59 86 115 152 199 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 176 137 101 67 46 28 13 4 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 30 66 115 176 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 221 144 87 46 18 3 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 71 67 101 137 176 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 248 199 152 115 86 59 35 18 8 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3 18 46 87 144 221 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 176 115 66 30 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 115 152 199 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 176 137 101 67 46 28 13 4 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 32 72 128 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 144 87 44 16 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 176 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 248 199 152 115 86 59 35 18 8 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 5 24 59 108 173 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 173 108 59 24 5 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 176 137 101 67 46 28 13 4 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 16 44 87 144 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 128 72 32 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 248 199 152 115 86 59 35 18 8 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 30 66 115 176 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 221 144 87 46 18 3 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 176 137 101 67 46 28 13 4 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3 18 46 87 144 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 176 115 66 30 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 248 199 152 115 86 59 35 18 8 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 30 66 115 176 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 144 87 44 16 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 176 137 101 67 46 28 13 4 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3 18 46 87 144 221 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 173 108 59 24 5 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 248 199 152 115 86 59 35 18 8 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 32 72 128 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 128 72 32 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 176 137 101 67 46 28 13 4 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 5 24 59 108 173 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 221 144 87 46 18 3 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 248 199 152 115 86 59 35 18 8 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 16 44 87 144 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 176 115 66 30 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 176 137 101 67 46 28 13 4 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 30 66 115 176 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 144 87 46 18 3 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 248 199 152 115 86 59 35 18 8 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3 18 46 87 144 221 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 176 115 66 30 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 176 137 101 67 46 28 13 4 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 32 72 128 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 144 87 44 16 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 248 199 152 115 86 59 35 18 8 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 5 24 59 108 173 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 252 173 108 59 24 5 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 176 137 101 67 46 28 13 4 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 16 44 87 144 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 128 72 32 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 115 86 59 35 18 8 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 30 66 115 176 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 221 144 87 46 18 3 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 248 199 152 108 71 46 28 13 4 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3 18 46 87 144 221 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 176 115 66 30 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 176 137 101 67 40 19 8 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 32 72 128 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 144 87 44 16 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 248 199 152 115 86 59 35 17 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 5 24 59 108 173 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 173 108 59 24 5 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 176 137 101 67 46 28 13 4 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 16 44 87 144 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 128 72 32 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 248 199 152 115 86 59 35 18 8 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 30 66 115 176 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 221 144 87 46 18 3 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 176 137 101 67 46 28 13 4 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3 18 46 87 144 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 176 115 66 30 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 248 199 152 115 86 59 35 18 8 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 30 66 115 176 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 144 87 44 16 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 176 137 101 67 46 28 13 4 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3 18 46 87 144 221 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 173 108 59 24 5 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 248 199 152 115 86 59 35 18 8 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 32 72 128 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 128 72 32 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 176 137 101 67 46 28 13 4 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 5 24 59 108 173 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 221 144 87 46 18 3 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 40 71 108 173 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 176 115 66 35 18 8 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 16 44 87 144 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 176 115 66 30 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 19 44 87 144 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 144 87 44 16 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 30 66 115 176 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 144 87 46 18 3 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 30 66 115 176 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 252 173 108 59 24 5 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3 18 46 87 144 221 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 176 115 66 30 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3 18 46 87 144 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 128 72 32 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 32 72 128 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 144 87 44 16 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 30 66 115 176 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 221 144 87 46 18 3 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 5 24 59 108 173 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 252 173 108 59 24 5 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3 18 46 87 144 221 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 176 115 66 30 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 16 44 87 144 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 128 72 32 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 32 72 128 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 144 87 46 18 3 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 30 66 115 176 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 221 144 87 46 18 3 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 5 24 59 108 173 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 176 115 66 30 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3 18 46 87 144 221 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 176 115 66 30 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 16 44 87 144 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 144 87 44 16 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 32 72 128 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 144 87 44 16 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 30 66 115 176 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 252 173 108 59 24 5 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 5 24 59 108 173 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 173 108 59 24 5 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3 18 46 87 144 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 128 72 32 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 16 44 87 144 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 128 72 32 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 30 66 115 176 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 221 144 87 46 18 3 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 30 66 115 176 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 221 144 87 46 18 3 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3 18 46 87 144 221 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 176 115 66 30 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3 18 46 87 144 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 176 115 66 30 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 32 72 128 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 144 87 46 18 3 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 30 66 115 176 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 144 87 44 16 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 5 24 59 108 173 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 176 115 66 30 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3 18 46 87 144 221 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 173 108 59 24 5 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 16 44 87 144 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 144 87 44 16 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 32 72 128 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 128 72 32 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 30 66 115 176 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 252 173 108 59 24 5 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 5 24 59 108 173 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 221 144 87 46 18 3 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3 18 46 87 144 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 128 72 32 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 16 44 87 144 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 176 115 66 30 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 30 66 115 176 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 221 144 87 46 18 3 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 30 66 115 176 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 144 87 46 18 3 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3 18 46 87 144 221 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 176 115 66 30 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3 18 46 87 144 221 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 176 115 66 30 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 32 72 128 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 144 87 46 18 3 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 32 72 128 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 144 87 44 16 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 5 24 59 108 173 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 176 115 66 30 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 5 24 59 108 173 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 252 173 108 59 24 5 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 16 44 87 144 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 144 87 44 16 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 16 44 87 144 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 128 72 32 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 30 66 115 176 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 252 173 108 59 24 5 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 30 66 115 176 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 221 144 87 46 18 3 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3 18 46 87 144 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 128 72 32 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3 18 46 87 144 221 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 176 115 66 30 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 30 66 115 176 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 221 144 87 46 18 3 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 32 72 128 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 144 87 44 16 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3 18 46 87 144 221 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 176 115 66 30 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 5 24 59 108 173 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 173 108 59 24 5 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 32 72 128 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 144 87 46 18 3 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 16 44 87 144 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 128 72 32 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 5 24 59 108 173 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 176 115 66 30 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 30 66 115 176 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 221 144 87 46 18 3 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 16 44 87 144 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 144 87 44 16 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3 18 46 87 144 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 176 115 66 30 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 30 66 115 176 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 252 173 108 59 24 5 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 30 66 115 176 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 144 87 44 16 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3 18 46 87 144 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 128 72 32 9 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3 18 46 87 144 221 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 173 108 59 24 5 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 30 66 115 176 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 221 144 84 40 12 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 32 72 128 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 128 72 32 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3 18 46 87 144 221 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 238 157 93 46 15 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 5 24 59 108 173 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 221 144 87 46 18 3 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 32 72 128 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 248 165 99 49 17 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 16 44 87 144 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 176 115 66 30 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 5 24 59 108 173 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 30 66 115 176 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 144 87 46 18 3 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 16 44 87 144 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3 18 46 87 144 221 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 176 115 66 30 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 30 66 115 176 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 248 165 99 49 17 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 32 72 128 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 144 87 44 16 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3 18 46 87 144 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 238 157 93 46 15 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 5 24 59 108 173 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 252 173 108 59 24 5 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 30 66 115 176 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 221 144 84 40 12 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 16 44 87 144 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 128 72 32 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3 18 46 87 144 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 128 72 32 9 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 30 66 115 176 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 221 144 87 46 18 3 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 30 66 115 176 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 252 173 108 59 24 5 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3 18 46 87 144 221 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 176 115 66 30 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3 18 46 87 144 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 144 87 44 16 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 32 72 128 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 144 87 44 16 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 30 66 115 176 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 248 176 115 66 30 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 5 24 59 108 173 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 173 108 59 24 5 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3 18 46 86 137 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 137 86 46 18 3 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 16 44 87 144 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 128 72 32 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 8 28 59 101 152 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 152 101 59 28 8 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 30 66 115 176 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 221 144 87 46 18 3 0 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 13 35 67 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 67 35 13 9 5 2 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3 18 46 87 144 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 176 115 66 30 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 4 17 40 71 108 152 199 248 253 253 253 253 253 253 253 253 253 253 253 253 253 248 199 152 108 71 49 46 40 32 24 16 9 3 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 30 66 115 176 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 144 87 44 16 2 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 5 19 40 67 101 137 176 215 252 253 253 253 253 253 253 253 253 253 252 215 176 137 101 99 101 99 93 84 72 59 44 30 18 8 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3 18 46 87 144 221 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 173 108 59 24 5 0 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 17 35 59 86 115 144 173 199 221 238 248 252 248 238 221 199 173 144 128 144 157 165 168 165 157 144 128 108 87 66 46 28 13 4 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 32 72 128 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 128 72 32 9 1 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 4 13 28 46 66 87 108 128 144 157 165 168 165 157 144 128 144 173 199 221 238 248 252 248 238 221 199 173 144 115 86 59 35 17 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 5 24 59 108 173 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 221 144 87 46 18 3 0 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 8 18 30 44 59 72 84 93 99 101 99 101 137 176 215 252 253 253 253 253 253 253 253 253 253 252 215 176 137 101 67 40 19 5 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 16 44 87 144 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 176 115 66 30 9 1 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 3 9 16 24 32 40 46 49 71 108 152 199 248 253 253 253 253 253 253 253 253 253 253 253 253 253 248 199 152 108 71 40 17 4 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 30 66 115 176 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 144 87 46 18 3 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 2 5 9 13 35 67 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 67 35 13 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3 18 46 87 144 221 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 176 115 66 30 9 1 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 8 28 59 101 152 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 152 101 59 28 8 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 32 72 128 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 144 87 44 16 2 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3 18 46 86 137 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 137 86 46 18 3 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 5 24 59 108 173 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 252 173 108 59 24 5 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 30 66 115 176 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 248 176 115 66 30 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 16 44 87 144 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 128 72 32 9 1 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 16 44 87 144 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 144 87 46 18 3 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 30 66 115 176 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 221 144 87 46 18 3 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 5 24 59 108 173 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 252 176 115 66 30 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3 18 46 87 144 221 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 176 115 66 30 9 1 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 9 32 72 128 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 144 87 46 18 3 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 32 72 128 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 144 87 44 16 2 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 12 40 84 144 221 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 252 176 115 66 30 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 5 24 59 108 173 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 173 108 59 24 5 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 15 46 93 157 238 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 144 87 44 16 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 16 44 87 144 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 128 72 32 9 1 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 17 49 99 165 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 252 173 108 59 24 5 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 30 66 115 176 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 221 144 87 46 18 3 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 128 72 32 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3 18 46 87 144 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 176 115 66 30 9 1 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 221 144 87 46 18 3 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 30 66 115 176 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 144 87 44 16 2 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 17 49 99 165 248 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 176 115 66 30 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3 18 46 87 144 221 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 173 108 59 24 5 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 15 46 93 157 238 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 144 87 44 16 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 32 72 128 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 128 72 32 9 1 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 12 40 84 144 221 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 173 108 59 24 5 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 5 24 59 108 173 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 221 144 87 46 18 3 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 9 32 72 128 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 128 72 32 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 16 44 87 144 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 176 115 66 30 9 1 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 5 24 59 108 173 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 221 144 87 46 18 3 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 30 66 115 176 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 144 87 46 18 3 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 16 44 87 144 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 176 115 66 30 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 2 2 5 9 18 46 87 144 221 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 176 115 66 30 9 1 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 30 66 115 176 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 144 87 44 16 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 2 2 5 9 12 15 17 24 32 40 46 72 128 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 144 87 44 16 2 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3 18 46 87 144 221 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 173 108 59 24 5 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 2 2 5 9 12 15 17 24 32 40 46 49 59 72 84 93 99 108 173 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 252 173 108 59 24 5 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 32 72 128 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 128 72 32 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 2 2 5 9 12 15 17 24 32 40 46 49 59 72 84 93 99 108 128 144 157 165 173 199 221 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 128 72 32 9 1 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 5 24 59 108 173 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 221 144 87 46 18 3 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 2 5 9 12 15 17 24 32 40 46 49 59 72 84 93 99 108 128 144 157 165 173 199 221 238 248 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 221 144 87 46 18 3 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 16 44 87 144 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 176 115 66 30 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 2 2 5 9 12 16 24 32 40 46 49 59 72 84 93 99 108 128 144 157 165 173 199 221 238 248 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 176 115 66 30 9 1 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 30 66 115 176 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 144 87 44 16 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 2 2 5 9 12 15 17 24 32 40 46 59 72 84 93 99 108 128 144 157 165 173 199 221 238 248 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 144 87 44 16 2 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3 18 46 87 144 221 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 173 108 59 24 5 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 2 2 5 9 12 15 17 24 32 40 46 49 59 72 84 93 108 128 144 157 165 173 199 221 238 248 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 173 108 59 24 5 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 32 72 128 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 128 72 32 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 2 2 5 9 12 15 17 24 32 40 46 49 59 72 84 93 99 108 128 144 157 173 199 221 238 248 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 128 72 32 9 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 5 24 59 108 173 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 221 144 87 46 18 3 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 2 5 9 12 15 17 24 32 40 46 49 59 72 84 93 99 108 128 144 157 165 173 199 221 238 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 221 144 84 40 12 1 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 16 44 87 144 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 176 115 66 30 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 2 2 5 9 12 16 24 32 40 46 49 59 72 84 93 99 108 128 144 157 165 173 199 221 238 248 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 238 157 93 46 15 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 30 66 115 176 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 144 87 46 18 3 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 2 2 5 9 12 15 17 24 32 40 46 59 72 84 93 99 108 128 144 157 165 173 199 221 238 248 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 248 165 99 49 17 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3 18 46 87 144 221 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 176 115 66 30 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 2 2 5 9 12 15 17 24 32 40 46 49 59 72 84 93 108 128 144 157 165 173 199 221 238 248 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 32 72 128 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 144 87 44 16 2 0 0 0 0 0 0 0 0 1 2 2 5 9 12 15 17 24 32 40 46 49 59 72 84 93 99 108 128 144 157 173 199 221 238 248 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 5 24 59 108 173 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 252 173 108 59 24 5 0 0 0 1 2 2 5 9 12 15 17 24 32 40 46 49 59 72 84 93 99 108 128 144 157 165 173 199 221 238 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 254 254 254 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 16 44 87 144 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 128 72 32 9 2 5 9 12 15 17 24 32 40 46 49 59 72 84 93 99 108 128 144 157 165 173 199 221 238 248 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 254 254 254 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 30 66 115 176 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 221 144 87 46 18 16 24 32 40 46 49 59 72 84 93 99 108 128 144 157 165 173 199 221 238 248 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 254 254 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3 18 46 87 144 221 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 176 115 66 40 46 59 72 84 93 99 108 128 144 157 165 173 199 221 238 248 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 254 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 32 72 128 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 144 87 84 93 108 128 144 157 165 173 199 221 238 248 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 254 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 5 24 59 108 173 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 252 173 128 144 157 173 199 221 238 248 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 254 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 16 44 87 144 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 199 221 238 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 254 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 30 66 115 176 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 254 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3 18 46 87 144 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 30 66 115 176 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 254 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3 18 46 87 144 221 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 254 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 32 72 128 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 254 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 5 24 59 108 173 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 254 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 16 44 87 144 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 30 66 115 176 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 254 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3 18 46 87 144 221 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 254 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 32 72 128 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 254 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 252 248 238 221 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 5 24 59 108 173 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 254 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 252 248 238 221 199 173 165 157 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 16 44 87 144 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 254 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 252 248 238 221 199 173 165 157 144 128 108 99 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 30 66 115 176 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 252 248 238 221 199 173 165 157 144 128 108 99 93 84 72 59 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3 18 46 87 144 221 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 254 254 254 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 252 248 238 221 199 173 165 157 144 128 108 99 93 84 72 59 49 46 40 32 24 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 32 72 128 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 254 254 254 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 252 238 221 199 173 165 157 144 128 108 99 93 84 72 59 49 46 40 32 24 17 15 12 9 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 5 24 59 108 173 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 252 248 238 221 199 173 157 144 128 108 99 93 84 72 59 49 46 40 32 24 17 15 12 9 5 2 2 1 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 16 44 87 144 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 252 248 238 221 199 173 165 157 144 128 108 93 84 72 59 49 46 40 32 24 17 15 12 9 5 2 2 1 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 30 66 115 176 252 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 252 248 238 221 199 173 165 157 144 128 108 99 93 84 72 59 46 40 32 24 17 15 12 9 5 2 2 1 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3 18 46 87 144 215 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 252 248 238 221 199 173 165 157 144 128 108 99 93 84 72 59 49 46 40 32 24 16 12 9 5 2 2 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 30 66 115 176 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 252 238 221 199 173 165 157 144 128 108 99 93 84 72 59 49 46 40 32 24 17 15 12 9 5 2 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 252 248 238 221 199 173 157 144 128 108 99 93 84 72 59 49 46 40 32 24 17 15 12 9 5 2 2 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 252 248 238 221 199 173 165 157 144 128 108 93 84 72 59 49 46 40 32 24 17 15 12 9 5 2 2 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 252 248 238 221 199 173 165 157 144 128 108 99 93 84 72 59 46 40 32 24 17 15 12 9 5 2 2 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 252 248 238 221 199 173 165 157 144 128 108 99 93 84 72 59 49 46 40 32 24 16 12 9 5 2 2 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 252 248 238 221 199 173 165 157 144 128 108 99 93 84 72 59 49 46 40 32 24 17 15 12 9 5 2 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 252 238 221 199 173 165 157 144 128 108 99 93 84 72 59 49 46 40 32 24 17 15 12 9 5 2 2 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 238 221 199 173 157 144 128 108 99 93 84 72 59 49 46 40 32 24 17 15 12 9 5 2 2 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 144 128 108 93 84 72 59 49 46 40 32 24 17 15 12 9 5 2 2 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 72 59 46 40 32 24 17 15 12 9 5 2 2 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 24 16 12 9 5 2 2 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 17 49 99 165 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 248 165 99 49 17 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 15 46 93 157 238 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 238 157 93 46 15 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 12 40 84 144 221 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 221 144 84 40 12 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 9 32 72 128 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 128 72 32 9 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 5 24 59 108 173 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 252 173 108 59 24 5 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 16 44 87 144 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 144 87 44 16 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 30 66 115 176 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 248 176 115 66 30 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3 18 46 86 137 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 137 86 46 18 3 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 8 28 59 101 152 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 152 101 59 28 8 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 13 35 67 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 67 35 13 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 4 17 40 71 108 152 199 248 253 253 253 253 253 253 253 253 253 253 253 253 253 248 199 152 108 71 40 17 4 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 5 19 40 67 101 137 176 215 252 253 253 253 253 253 253 253 253 253 252 215 176 137 101 67 40 19 5 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 17 35 59 86 115 144 173 199 221 238 248 252 248 238 221 199 173 144 115 86 59 35 17 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 4 13 28 46 66 87 108 128 144 157 165 168 165 157 144 128 108 87 66 46 28 13 4 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 8 18 30 44 59 72 84 93 99 101 99 93 84 72 59 44 30 18 8 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 4 13 28 46 66 87 108 128 144 157 165 168 165 157 144 128 108 87 66 46 28 13 4 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 17 35 59 86 115 144 173 199 221 238 248 252 248 238 221 199 173 144 115 86 59 35 17 5 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 5 19 40 67 101 137 176 215 252 253 253 253 253 253 253 253 253 253 252 215 176 137 101 67 40 19 5 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 4 17 40 71 108 152 199 248 253 253 253 253 253 253 253 253 253 253 253 253 253 248 199 152 108 71 40 17 4 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 13 35 67 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 67 35 13 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 8 28 59 101 152 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 152 101 59 28 8 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3 18 46 86 137 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 137 86 46 18 3 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 30 66 115 176 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 248 176 115 66 30 9 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 16 44 87 144 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 144 87 44 16 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 5 24 59 108 173 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 252 173 108 59 24 5 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 9 32 72 128 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 128 72 32 9 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 12 40 84 144 221 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 221 144 84 40 12 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 15 46 93 157 238 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 238 157 93 46 15 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 17 49 99 165 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 248 165 99 49 17 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 24 16 12 9 5 2 2 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 72 59 46 40 32 24 17 15 12 9 5 2 2 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 144 128 108 93 84 72 59 49 46 40 32 24 17 15 12 9 5 2 2 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 238 221 199 173 157 144 128 108 99 93 84 72 59 49 46 40 32 24 17 15 12 9 5 2 2 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 252 238 221 199 173 165 157 144 128 108 99 93 84 72 59 49 46 40 32 24 17 15 12 9 5 2 2 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 252 248 238 221 199 173 165 157 144 128 108 99 93 84 72 59 49 46 40 32 24 17 15 12 9 5 2 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 252 248 238 221 199 173 165 157 144 128 108 99 93 84 72 59 49 46 40 32 24 16 12 9 5 2 2 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 252 248 238 221 199 173 165 157 144 128 108 99 93 84 72 59 46 40 32 24 17 15 12 9 5 2 2 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 252 248 238 221 199 173 165 157 144 128 108 93 84 72 59 49 46 40 32 24 17 15 12 9 5 2 2 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 252 248 238 221 199 173 157 144 128 108 99 93 84 72 59 49 46 40 32 24 17 15 12 9 5 2 2 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 252 238 221 199 173 165 157 144 128 108 99 93 84 72 59 49 46 40 32 24 17 15 12 9 5 2 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 252 248 238 221 199 173 165 157 144 128 108 99 93 84 72 59 49 46 40 32 24 16 12 9 5 2 2 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 252 248 238 221 199 173 165 157 144 128 108 99 93 84 72 59 46 40 32 24 17 15 12 9 5 2 2 1 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 252 248 238 221 199 173 165 157 144 128 108 93 84 72 59 49 46 40 32 24 17 15 12 9 5 2 2 1 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 252 248 238 221 199 173 157 144 128 108 99 93 84 72 59 49 46 40 32 24 17 15 12 9 5 2 2 1 2 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 17 49 99 165 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 254 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 252 238 221 199 173 165 157 144 128 108 99 93 84 72 59 49 46 40 32 24 17 15 12 9 18 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 15 46 93 157 238 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 254 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 252 248 238 221 199 173 165 157 144 128 108 99 93 84 72 59 49 46 40 32 24 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 12 40 84 144 221 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 252 248 238 221 199 173 165 157 144 128 108 99 93 84 72 59 51 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 9 32 72 128 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 254 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 252 248 238 221 199 173 165 157 144 128 108 99 101 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 5 24 59 108 173 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 254 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 252 248 238 221 199 173 165 157 168 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 16 44 87 144 215 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 254 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 252 248 238 221 252 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 9 30 66 115 176 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 254 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 3 18 46 86 137 199 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 254 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 8 28 59 101 152 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 13 35 67 108 157 212 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 254 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 4 17 40 71 108 152 199 248 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 254 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 5 19 40 67 101 137 176 215 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 254 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 5 17 35 59 86 115 144 173 199 221 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 254 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 4 13 28 46 66 87 108 128 144 173 199 221 238 248 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 2 8 18 30 44 59 72 87 108 128 144 157 165 173 199 221 238 248 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 254 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 3 9 16 24 32 44 59 72 84 93 99 108 128 144 157 165 173 199 221 238 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 254 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 2 5 9 16 24 32 40 46 49 59 72 84 93 99 108 128 144 157 173 199 221 238 248 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 254 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 2 5 9 12 15 17 24 32 40 46 49 59 72 84 93 108 128 144 157 165 173 199 221 238 248 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 254 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 2 2 5 9 12 15 17 24 32 40 46 59 72 84 93 99 108 128 144 157 165 173 199 221 238 248 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 254 254 254 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 2 2 5 9 12 16 24 32 40 46 49 59 72 84 93 99 108 128 144 157 165 173 199 221 238 248 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 254 254 253 253 253 253 253 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 2 5 9 12 15 17 24 32 40 46 49 59 72 84 93 99 108 128 144 157 165 173 199 221 238 248 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 254 254 254 253 253 253 253 253 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 2 2 5 9 12 15 17 24 32 40 46 49 59 72 84 93 99 108 128 144 157 165 173 199 221 238 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 254 254 254 253 253 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 2 2 5 9 12 15 17 24 32 40 46 49 59 72 84 93 99 108 128 144 157 173 199 221 238 248 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 254 254 254 253 253 253 253 253 253 253 253 253 253 253 253 252 168 101 51 18 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 2 2 5 9 12 15 17 24 32 40 46 49 59 72 84 93 108 128 144 157 165 173 199 221 238 248 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 248 165 99 49 17 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 2 2 5 9 12 15 17 24 32 40 46 59 72 84 93 99 108 128 144 157 165 173 199 221 238 248 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 238 157 93 46 15 2 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 2 2 5 9 12 16 24 32 40 46 49 59 72 84 93 99 108 128 144 157 165 173 199 221 238 248 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 221 144 84 40 12 1 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 2 5 9 12 15 17 24 32 40 46 49 59 72 84 93 99 108 128 144 157 165 173 199 221 238 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 128 72 32 9 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 2 2 5 9 12 15 17 24 32 40 46 49 59 72 84 93 99 108 128 144 157 173 199 221 238 248 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 252 173 108 59 24 5 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 2 2 5 9 12 15 17 24 32 40 46 49 59 72 84 93 108 128 144 157 165 173 199 221 238 248 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 215 144 87 44 16 2 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 2 2 5 9 12 15 17 24 32 40 46 59 72 84 93 99 108 128 144 157 165 173 199 221 238 248 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 248 176 115 66 30 9 1 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 2 2 5 9 12 16 24 32 40 46 49 59 72 84 93 99 108 128 144 157 165 173 199 221 238 248 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 199 137 86 46 18 3 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 2 5 9 12 15 17 24 32 40 46 49 59 72 84 93 99 108 128 144 157 165 173 199 221 238 248 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 152 101 59 28 8 1 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 2 2 5 9 12 15 17 24 32 40 46 49 59 72 84 93 99 108 128 144 157 165 173 199 221 238 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 212 157 108 67 35 13 2 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 2 2 5 9 12 15 17 24 32 40 46 49 59 72 84 93 99 108 128 144 157 173 199 221 238 248 252 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 253 248 199 152 108 71 40 17 4 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 2 2 5 9 12 15 17 24 32 40 46 49 59 72 84 93 108 128 144 157 165 173 199 221 238 248 252 253 253 253 253 253 253 253 253 253 253 253 252 215 176 137 101 67 40 19 5 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 2 2 5 9 12 15 17 24 32 40 46 59 72 84 93 99 108 128 144 157 165 173 199 221 238 248 252 252 252 248 238 221 199 173 144 115 86 59 35 17 5 1 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 2 2 5 9 12 16 24 32 40 46 49 59 72 84 93 99 108 128 144 157 165 168 168 168 165 157 144 128 108 87 66 46 28 13 4 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 2 5 9 12 15 17 24 32 40 46 49 59 72 84 93 99 101 101 101 99 93 84 72 59 44 30 18 8 2 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 2 2 5 9 12 15 17 24 32 40 46 49 51 51 51 49 46 40 32 24 16 9 3 1 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 2 2 5 9 12 15 17 18 18 18 17 15 12 9 5 2 1 0 0 0 0 0 0 0 0 0 0 0 + 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 2 2 2 2 2 2 2 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 diff --git a/navigations/sbpl/env_examples/nav3d/env1.cfg b/navigations/sbpl/env_examples/nav3d/env1.cfg new file mode 100755 index 0000000..6b5466e --- /dev/null +++ b/navigations/sbpl/env_examples/nav3d/env1.cfg @@ -0,0 +1,25 @@ +discretization(cells): 15 15 +obsthresh: 1 +cost_inscribed_thresh: 1 +cost_possibly_circumscribed_thresh: 0 +cellsize(meters): 0.025 +nominalvel(mpersecs): 1.0 +timetoturn45degsinplace(secs): 2.0 +start(meters,rads): 0.11 0.11 0 +end(meters,rads): 0.35 0.3 0 +environment: +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 1 1 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 +1 1 1 1 0 0 0 0 0 0 0 1 0 0 0 +1 1 1 1 0 0 0 0 0 0 0 1 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 diff --git a/navigations/sbpl/env_examples/nav3d/env2.cfg b/navigations/sbpl/env_examples/nav3d/env2.cfg new file mode 100755 index 0000000..e91813d --- /dev/null +++ b/navigations/sbpl/env_examples/nav3d/env2.cfg @@ -0,0 +1,1210 @@ +discretization(cells): 100 1200 +obsthresh: 1 +cost_inscribed_thresh: 1 +cost_possibly_circumscribed_thresh: 0 +cellsize(meters): 0.1 +nominalvel(mpersecs): 1.0 +timetoturn45degsinplace(secs): 2.0 +start(meters,rads): 0.1 0.2 0 +end(meters,rads): 9.8 99.8 0 +environment: +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 +1 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 diff --git a/navigations/sbpl/env_examples/nav3d/willow-25mm-inflated-env.zip b/navigations/sbpl/env_examples/nav3d/willow-25mm-inflated-env.zip new file mode 100755 index 0000000..a8da44d Binary files /dev/null and b/navigations/sbpl/env_examples/nav3d/willow-25mm-inflated-env.zip differ diff --git a/navigations/sbpl/env_examples/robarm/env1_20d.cfg b/navigations/sbpl/env_examples/robarm/env1_20d.cfg new file mode 100755 index 0000000..d658c5f --- /dev/null +++ b/navigations/sbpl/env_examples/robarm/env1_20d.cfg @@ -0,0 +1,57 @@ +environmentsize(meters): 50.0 50.0 +discretization(cells): 50 50 +basex(cells): 25 +linklengths(meters): 5.0 5.0 5.0 5.0 5.0 5.0 5.0 5.0 5.0 5.0 2.0 2.0 2.0 2.0 2.0 2.0 2.0 2.0 2.0 2.0 +linkstartangles(degrees): 90.0 90.0 90.0 90.0 0.0 0.0 270.0 270.0 0.0 0.0 90.0 90.0 90.0 90.0 90.0 90.0 90.0 90.0 90.0 90.0 +endeffectorgoal(cells): 10 10 +environment: +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +1 1 1 1 1 1 1 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +1 1 1 1 1 1 1 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +1 1 1 1 1 1 1 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +1 1 1 1 1 1 1 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 diff --git a/navigations/sbpl/env_examples/robarm/env1_6d.cfg b/navigations/sbpl/env_examples/robarm/env1_6d.cfg new file mode 100755 index 0000000..298447d --- /dev/null +++ b/navigations/sbpl/env_examples/robarm/env1_6d.cfg @@ -0,0 +1,57 @@ +environmentsize(meters): 50.0 50.0 +discretization(cells): 50 50 +basex(cells): 25 +linklengths(meters): 20.0 10.0 10.0 5.0 10.0 5.0 +linkstartangles(degrees): 90.0 0.0 90.0 90.0 0.0 90.0 +endeffectorgoal(cells): 10 10 +environment: +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +1 1 1 1 1 1 1 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +1 1 1 1 1 1 1 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +1 1 1 1 1 1 1 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +1 1 1 1 1 1 1 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 diff --git a/navigations/sbpl/env_examples/robarm/env2_6d.cfg b/navigations/sbpl/env_examples/robarm/env2_6d.cfg new file mode 100755 index 0000000..ec918e8 --- /dev/null +++ b/navigations/sbpl/env_examples/robarm/env2_6d.cfg @@ -0,0 +1,57 @@ +environmentsize(meters): 50.0 50.0 +discretization(cells): 50 50 +basex(cells): 25 +linklengths(meters): 20.0 10.0 10.0 5.0 10.0 10.0 +linkstartangles(degrees): 90.0 0.0 90.0 90.0 0.0 90.0 +endeffectorgoal(cells): 10 3 +environment: +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +1 1 1 1 1 1 1 1 1 0 0 0 0 0 0 1 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +1 1 1 1 1 1 1 1 1 0 0 0 0 0 0 1 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +1 1 1 1 1 1 1 1 1 0 0 0 0 0 0 1 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +1 1 1 1 1 1 1 1 1 0 0 0 0 0 0 1 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 diff --git a/navigations/sbpl/env_examples/robarm/env3_6d.cfg b/navigations/sbpl/env_examples/robarm/env3_6d.cfg new file mode 100755 index 0000000..b97f977 --- /dev/null +++ b/navigations/sbpl/env_examples/robarm/env3_6d.cfg @@ -0,0 +1,57 @@ +environmentsize(meters): 50.0 50.0 +discretization(cells): 50 50 +basex(cells): 25 +linklengths(meters): 20.0 10.0 10.0 5.0 10.0 10.0 +linkstartangles(degrees): 90.0 0.0 90.0 90.0 0.0 90.0 +endeffectorgoal(cells): 10 3 +environment: +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +1 1 1 1 1 1 1 1 1 0 0 0 0 0 0 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +1 1 1 1 1 1 1 1 1 0 0 0 0 0 0 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +1 1 1 1 1 1 1 1 1 0 0 0 0 0 0 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +1 1 1 1 1 1 1 1 1 0 0 0 0 0 0 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 1 1 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 1 1 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 diff --git a/navigations/sbpl/env_examples/robarm/env4_20d.cfg b/navigations/sbpl/env_examples/robarm/env4_20d.cfg new file mode 100755 index 0000000..c09ff7b --- /dev/null +++ b/navigations/sbpl/env_examples/robarm/env4_20d.cfg @@ -0,0 +1,57 @@ +environmentsize(meters): 50.0 50.0 +discretization(cells): 50 50 +basex(cells): 25 +linklengths(meters): 5.0 5.0 5.0 5.0 5.0 5.0 5.0 5.0 5.0 5.0 2.0 2.0 2.0 2.0 2.0 2.0 2.0 2.0 2.0 2.0 +linkstartangles(degrees): 90.0 90.0 90.0 90.0 0.0 0.0 270.0 270.0 0.0 0.0 90.0 90.0 90.0 90.0 90.0 90.0 90.0 90.0 90.0 90.0 +endeffectorgoal(cells): 10 10 +environment: +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +1 1 1 1 1 1 1 1 1 0 0 0 0 0 0 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +1 1 1 1 1 1 1 1 1 0 0 0 0 0 0 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +1 1 1 1 1 1 1 1 1 0 0 0 0 0 0 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +1 1 1 1 1 1 1 1 1 0 0 0 0 0 0 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 diff --git a/navigations/sbpl/matlab/mprim/all_file.mprim b/navigations/sbpl/matlab/mprim/all_file.mprim new file mode 100755 index 0000000..905f1bb --- /dev/null +++ b/navigations/sbpl/matlab/mprim/all_file.mprim @@ -0,0 +1,3123 @@ +resolution_m: 0.025000 +numberofangles: 16 +totalnumberofprimitives: 208 +primID: 0 +startangle_c: 0 +endpose_c: 1 0 0 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0028 0.0000 0.0000 +0.0056 0.0000 0.0000 +0.0083 0.0000 0.0000 +0.0111 0.0000 0.0000 +0.0139 0.0000 0.0000 +0.0167 0.0000 0.0000 +0.0194 0.0000 0.0000 +0.0222 0.0000 0.0000 +0.0250 0.0000 0.0000 +primID: 1 +startangle_c: 0 +endpose_c: 8 0 0 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0222 0.0000 0.0000 +0.0444 0.0000 0.0000 +0.0667 0.0000 0.0000 +0.0889 0.0000 0.0000 +0.1111 0.0000 0.0000 +0.1333 0.0000 0.0000 +0.1556 0.0000 0.0000 +0.1778 0.0000 0.0000 +0.2000 0.0000 0.0000 +primID: 2 +startangle_c: 0 +endpose_c: -1 0 0 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.0000 +-0.0028 0.0000 0.0000 +-0.0056 0.0000 0.0000 +-0.0083 0.0000 0.0000 +-0.0111 0.0000 0.0000 +-0.0139 0.0000 0.0000 +-0.0167 0.0000 0.0000 +-0.0194 0.0000 0.0000 +-0.0222 0.0000 0.0000 +-0.0250 0.0000 0.0000 +primID: 3 +startangle_c: 0 +endpose_c: 8 1 1 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0226 -0.0000 0.0000 +0.0452 -0.0000 0.0000 +0.0678 -0.0000 0.0000 +0.0903 0.0004 0.0488 +0.1128 0.0023 0.1176 +0.1352 0.0057 0.1864 +0.1572 0.0106 0.2551 +0.1789 0.0171 0.3239 +0.2000 0.0250 0.3927 +primID: 4 +startangle_c: 0 +endpose_c: 8 -1 -1 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0226 0.0000 0.0000 +0.0452 0.0000 0.0000 +0.0678 0.0000 0.0000 +0.0903 -0.0004 -0.0488 +0.1128 -0.0023 -0.1176 +0.1352 -0.0057 -0.1864 +0.1572 -0.0106 -0.2551 +0.1789 -0.0171 -0.3239 +0.2000 -0.0250 -0.3927 +primID: 5 +startangle_c: 0 +endpose_c: 0 0 1 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0000 0.0000 0.0436 +0.0000 0.0000 0.0873 +0.0000 0.0000 0.1309 +0.0000 0.0000 0.1745 +0.0000 0.0000 0.2182 +0.0000 0.0000 0.2618 +0.0000 0.0000 0.3054 +0.0000 0.0000 0.3491 +0.0000 0.0000 0.3927 +primID: 6 +startangle_c: 0 +endpose_c: 0 0 -1 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0000 0.0000 -0.0436 +0.0000 0.0000 -0.0873 +0.0000 0.0000 -0.1309 +0.0000 0.0000 -0.1745 +0.0000 0.0000 -0.2182 +0.0000 0.0000 -0.2618 +0.0000 0.0000 -0.3054 +0.0000 0.0000 -0.3491 +0.0000 0.0000 -0.3927 +primID: 7 +startangle_c: 0 +endpose_c: 0 1 0 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0000 0.0028 0.0000 +0.0000 0.0056 0.0000 +0.0000 0.0083 0.0000 +0.0000 0.0111 0.0000 +0.0000 0.0139 0.0000 +0.0000 0.0167 0.0000 +0.0000 0.0194 0.0000 +0.0000 0.0222 0.0000 +0.0000 0.0250 0.0000 +primID: 8 +startangle_c: 0 +endpose_c: 0 -1 0 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0000 -0.0028 0.0000 +0.0000 -0.0056 0.0000 +0.0000 -0.0083 0.0000 +0.0000 -0.0111 0.0000 +0.0000 -0.0139 0.0000 +0.0000 -0.0167 0.0000 +0.0000 -0.0194 0.0000 +0.0000 -0.0222 0.0000 +0.0000 -0.0250 0.0000 +primID: 9 +startangle_c: 0 +endpose_c: -8 -1 1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.0000 +-0.0226 0.0000 0.0000 +-0.0452 0.0000 0.0000 +-0.0678 0.0000 0.0000 +-0.0903 -0.0004 0.0488 +-0.1128 -0.0023 0.1176 +-0.1352 -0.0057 0.1864 +-0.1572 -0.0106 0.2551 +-0.1789 -0.0171 0.3239 +-0.2000 -0.0250 0.3927 +primID: 10 +startangle_c: 0 +endpose_c: -8 1 -1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.0000 +-0.0226 -0.0000 0.0000 +-0.0452 -0.0000 0.0000 +-0.0678 -0.0000 0.0000 +-0.0903 0.0004 -0.0488 +-0.1128 0.0023 -0.1176 +-0.1352 0.0057 -0.1864 +-0.1572 0.0106 -0.2551 +-0.1789 0.0171 -0.3239 +-0.2000 0.0250 -0.3927 +primID: 11 +startangle_c: 0 +endpose_c: 8 1 0 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0222 0.0028 0.0000 +0.0444 0.0056 0.0000 +0.0667 0.0083 0.0000 +0.0889 0.0111 0.0000 +0.1111 0.0139 0.0000 +0.1333 0.0167 0.0000 +0.1556 0.0194 0.0000 +0.1778 0.0222 0.0000 +0.2000 0.0250 0.0000 +primID: 12 +startangle_c: 0 +endpose_c: 8 -1 0 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0222 -0.0028 0.0000 +0.0444 -0.0056 0.0000 +0.0667 -0.0083 0.0000 +0.0889 -0.0111 0.0000 +0.1111 -0.0139 0.0000 +0.1333 -0.0167 0.0000 +0.1556 -0.0194 0.0000 +0.1778 -0.0222 0.0000 +0.2000 -0.0250 0.0000 +primID: 0 +startangle_c: 1 +endpose_c: 2 1 1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0056 0.0028 0.3927 +0.0111 0.0056 0.3927 +0.0167 0.0083 0.3927 +0.0222 0.0111 0.3927 +0.0278 0.0139 0.3927 +0.0333 0.0167 0.3927 +0.0389 0.0194 0.3927 +0.0444 0.0222 0.3927 +0.0500 0.0250 0.3927 +primID: 1 +startangle_c: 1 +endpose_c: 6 3 1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0167 0.0083 0.3927 +0.0333 0.0167 0.3927 +0.0500 0.0250 0.3927 +0.0667 0.0333 0.3927 +0.0833 0.0417 0.3927 +0.1000 0.0500 0.3927 +0.1167 0.0583 0.3927 +0.1333 0.0667 0.3927 +0.1500 0.0750 0.3927 +primID: 2 +startangle_c: 1 +endpose_c: -2 -1 1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.3927 +-0.0056 -0.0028 0.3927 +-0.0111 -0.0056 0.3927 +-0.0167 -0.0083 0.3927 +-0.0222 -0.0111 0.3927 +-0.0278 -0.0139 0.3927 +-0.0333 -0.0167 0.3927 +-0.0389 -0.0194 0.3927 +-0.0444 -0.0222 0.3927 +-0.0500 -0.0250 0.3927 +primID: 3 +startangle_c: 1 +endpose_c: 5 4 2 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0149 0.0092 0.4230 +0.0296 0.0189 0.4533 +0.0440 0.0291 0.4836 +0.0582 0.0398 0.5139 +0.0722 0.0509 0.5442 +0.0858 0.0625 0.5745 +0.0992 0.0746 0.6048 +0.1123 0.0871 0.6351 +0.1250 0.1000 0.6654 +primID: 4 +startangle_c: 1 +endpose_c: 7 2 0 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0188 0.0078 0.3927 +0.0377 0.0156 0.3927 +0.0565 0.0234 0.3927 +0.0754 0.0312 0.3736 +0.0946 0.0379 0.2989 +0.1143 0.0432 0.2242 +0.1344 0.0470 0.1494 +0.1546 0.0492 0.0747 +0.1750 0.0500 0.0000 +primID: 5 +startangle_c: 1 +endpose_c: 0 0 2 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0000 0.0000 0.4363 +0.0000 0.0000 0.4800 +0.0000 0.0000 0.5236 +0.0000 0.0000 0.5672 +0.0000 0.0000 0.6109 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.6981 +0.0000 0.0000 0.7418 +0.0000 0.0000 0.7854 +primID: 6 +startangle_c: 1 +endpose_c: 0 0 0 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0000 0.0000 0.3491 +0.0000 0.0000 0.3054 +0.0000 0.0000 0.2618 +0.0000 0.0000 0.2182 +0.0000 0.0000 0.1745 +0.0000 0.0000 0.1309 +0.0000 0.0000 0.0873 +0.0000 0.0000 0.0436 +0.0000 0.0000 0.0000 +primID: 7 +startangle_c: 1 +endpose_c: -1 2 1 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.3927 +-0.0028 0.0056 0.3927 +-0.0056 0.0111 0.3927 +-0.0083 0.0167 0.3927 +-0.0111 0.0222 0.3927 +-0.0139 0.0278 0.3927 +-0.0167 0.0333 0.3927 +-0.0194 0.0389 0.3927 +-0.0222 0.0444 0.3927 +-0.0250 0.0500 0.3927 +primID: 8 +startangle_c: 1 +endpose_c: 1 -2 1 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0028 -0.0056 0.3927 +0.0056 -0.0111 0.3927 +0.0083 -0.0167 0.3927 +0.0111 -0.0222 0.3927 +0.0139 -0.0278 0.3927 +0.0167 -0.0333 0.3927 +0.0194 -0.0389 0.3927 +0.0222 -0.0444 0.3927 +0.0250 -0.0500 0.3927 +primID: 9 +startangle_c: 1 +endpose_c: -5 -4 2 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.3927 +-0.0149 -0.0092 0.4230 +-0.0296 -0.0189 0.4533 +-0.0440 -0.0291 0.4836 +-0.0582 -0.0398 0.5139 +-0.0722 -0.0509 0.5442 +-0.0858 -0.0625 0.5745 +-0.0992 -0.0746 0.6048 +-0.1123 -0.0871 0.6351 +-0.1250 -0.1000 0.6654 +primID: 10 +startangle_c: 1 +endpose_c: -7 -2 0 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.3927 +-0.0188 -0.0078 0.3927 +-0.0377 -0.0156 0.3927 +-0.0565 -0.0234 0.3927 +-0.0754 -0.0312 0.3736 +-0.0946 -0.0379 0.2989 +-0.1143 -0.0432 0.2242 +-0.1344 -0.0470 0.1494 +-0.1546 -0.0492 0.0747 +-0.1750 -0.0500 0.0000 +primID: 11 +startangle_c: 1 +endpose_c: 5 4 1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0139 0.0111 0.3927 +0.0278 0.0222 0.3927 +0.0417 0.0333 0.3927 +0.0556 0.0444 0.3927 +0.0694 0.0556 0.3927 +0.0833 0.0667 0.3927 +0.0972 0.0778 0.3927 +0.1111 0.0889 0.3927 +0.1250 0.1000 0.3927 +primID: 12 +startangle_c: 1 +endpose_c: 7 2 1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0194 0.0056 0.3927 +0.0389 0.0111 0.3927 +0.0583 0.0167 0.3927 +0.0778 0.0222 0.3927 +0.0972 0.0278 0.3927 +0.1167 0.0333 0.3927 +0.1361 0.0389 0.3927 +0.1556 0.0444 0.3927 +0.1750 0.0500 0.3927 +primID: 0 +startangle_c: 2 +endpose_c: 1 1 2 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0028 0.0028 0.7854 +0.0056 0.0056 0.7854 +0.0083 0.0083 0.7854 +0.0111 0.0111 0.7854 +0.0139 0.0139 0.7854 +0.0167 0.0167 0.7854 +0.0194 0.0194 0.7854 +0.0222 0.0222 0.7854 +0.0250 0.0250 0.7854 +primID: 1 +startangle_c: 2 +endpose_c: 6 6 2 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0167 0.0167 0.7854 +0.0333 0.0333 0.7854 +0.0500 0.0500 0.7854 +0.0667 0.0667 0.7854 +0.0833 0.0833 0.7854 +0.1000 0.1000 0.7854 +0.1167 0.1167 0.7854 +0.1333 0.1333 0.7854 +0.1500 0.1500 0.7854 +primID: 2 +startangle_c: 2 +endpose_c: -1 -1 2 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.7854 +-0.0028 -0.0028 0.7854 +-0.0056 -0.0056 0.7854 +-0.0083 -0.0083 0.7854 +-0.0111 -0.0111 0.7854 +-0.0139 -0.0139 0.7854 +-0.0167 -0.0167 0.7854 +-0.0194 -0.0194 0.7854 +-0.0222 -0.0222 0.7854 +-0.0250 -0.0250 0.7854 +primID: 3 +startangle_c: 2 +endpose_c: 5 7 3 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0170 0.0170 0.7854 +0.0339 0.0342 0.8151 +0.0500 0.0522 0.8669 +0.0651 0.0709 0.9188 +0.0792 0.0904 0.9707 +0.0923 0.1107 1.0225 +0.1043 0.1315 1.0744 +0.1152 0.1530 1.1262 +0.1250 0.1750 1.1781 +primID: 4 +startangle_c: 2 +endpose_c: 7 5 1 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0170 0.0170 0.7854 +0.0342 0.0339 0.7557 +0.0522 0.0500 0.7039 +0.0709 0.0651 0.6520 +0.0904 0.0792 0.6001 +0.1107 0.0923 0.5483 +0.1315 0.1043 0.4964 +0.1530 0.1152 0.4446 +0.1750 0.1250 0.3927 +primID: 5 +startangle_c: 2 +endpose_c: 0 0 3 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0000 0.0000 0.8290 +0.0000 0.0000 0.8727 +0.0000 0.0000 0.9163 +0.0000 0.0000 0.9599 +0.0000 0.0000 1.0036 +0.0000 0.0000 1.0472 +0.0000 0.0000 1.0908 +0.0000 0.0000 1.1345 +0.0000 0.0000 1.1781 +primID: 6 +startangle_c: 2 +endpose_c: 0 0 1 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0000 0.0000 0.7418 +0.0000 0.0000 0.6981 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.6109 +0.0000 0.0000 0.5672 +0.0000 0.0000 0.5236 +0.0000 0.0000 0.4800 +0.0000 0.0000 0.4363 +0.0000 0.0000 0.3927 +primID: 7 +startangle_c: 2 +endpose_c: -1 1 2 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.7854 +-0.0028 0.0028 0.7854 +-0.0056 0.0056 0.7854 +-0.0083 0.0083 0.7854 +-0.0111 0.0111 0.7854 +-0.0139 0.0139 0.7854 +-0.0167 0.0167 0.7854 +-0.0194 0.0194 0.7854 +-0.0222 0.0222 0.7854 +-0.0250 0.0250 0.7854 +primID: 8 +startangle_c: 2 +endpose_c: 1 -1 2 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0028 -0.0028 0.7854 +0.0056 -0.0056 0.7854 +0.0083 -0.0083 0.7854 +0.0111 -0.0111 0.7854 +0.0139 -0.0139 0.7854 +0.0167 -0.0167 0.7854 +0.0194 -0.0194 0.7854 +0.0222 -0.0222 0.7854 +0.0250 -0.0250 0.7854 +primID: 9 +startangle_c: 2 +endpose_c: -5 -7 3 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.7854 +-0.0170 -0.0170 0.7854 +-0.0339 -0.0342 0.8151 +-0.0500 -0.0522 0.8669 +-0.0651 -0.0709 0.9188 +-0.0792 -0.0904 0.9707 +-0.0923 -0.1107 1.0225 +-0.1043 -0.1315 1.0744 +-0.1152 -0.1530 1.1262 +-0.1250 -0.1750 1.1781 +primID: 10 +startangle_c: 2 +endpose_c: -7 -5 1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.7854 +-0.0170 -0.0170 0.7854 +-0.0342 -0.0339 0.7557 +-0.0522 -0.0500 0.7039 +-0.0709 -0.0651 0.6520 +-0.0904 -0.0792 0.6001 +-0.1107 -0.0923 0.5483 +-0.1315 -0.1043 0.4964 +-0.1530 -0.1152 0.4446 +-0.1750 -0.1250 0.3927 +primID: 11 +startangle_c: 2 +endpose_c: 5 7 2 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0139 0.0194 0.7854 +0.0278 0.0389 0.7854 +0.0417 0.0583 0.7854 +0.0556 0.0778 0.7854 +0.0694 0.0972 0.7854 +0.0833 0.1167 0.7854 +0.0972 0.1361 0.7854 +0.1111 0.1556 0.7854 +0.1250 0.1750 0.7854 +primID: 12 +startangle_c: 2 +endpose_c: 7 5 2 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0194 0.0139 0.7854 +0.0389 0.0278 0.7854 +0.0583 0.0417 0.7854 +0.0778 0.0556 0.7854 +0.0972 0.0694 0.7854 +0.1167 0.0833 0.7854 +0.1361 0.0972 0.7854 +0.1556 0.1111 0.7854 +0.1750 0.1250 0.7854 +primID: 0 +startangle_c: 3 +endpose_c: 1 2 3 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0028 0.0056 1.1781 +0.0056 0.0111 1.1781 +0.0083 0.0167 1.1781 +0.0111 0.0222 1.1781 +0.0139 0.0278 1.1781 +0.0167 0.0333 1.1781 +0.0194 0.0389 1.1781 +0.0222 0.0444 1.1781 +0.0250 0.0500 1.1781 +primID: 1 +startangle_c: 3 +endpose_c: 3 6 3 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0083 0.0167 1.1781 +0.0167 0.0333 1.1781 +0.0250 0.0500 1.1781 +0.0333 0.0667 1.1781 +0.0417 0.0833 1.1781 +0.0500 0.1000 1.1781 +0.0583 0.1167 1.1781 +0.0667 0.1333 1.1781 +0.0750 0.1500 1.1781 +primID: 2 +startangle_c: 3 +endpose_c: -1 -2 3 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.1781 +-0.0028 -0.0056 1.1781 +-0.0056 -0.0111 1.1781 +-0.0083 -0.0167 1.1781 +-0.0111 -0.0222 1.1781 +-0.0139 -0.0278 1.1781 +-0.0167 -0.0333 1.1781 +-0.0194 -0.0389 1.1781 +-0.0222 -0.0444 1.1781 +-0.0250 -0.0500 1.1781 +primID: 3 +startangle_c: 3 +endpose_c: 4 5 2 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0092 0.0149 1.1478 +0.0189 0.0296 1.1175 +0.0291 0.0440 1.0872 +0.0398 0.0582 1.0569 +0.0509 0.0722 1.0266 +0.0625 0.0858 0.9963 +0.0746 0.0992 0.9660 +0.0871 0.1123 0.9357 +0.1000 0.1250 0.9054 +primID: 4 +startangle_c: 3 +endpose_c: 2 7 4 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0078 0.0188 1.1781 +0.0156 0.0377 1.1781 +0.0234 0.0565 1.1781 +0.0312 0.0754 1.1972 +0.0379 0.0946 1.2719 +0.0432 0.1143 1.3466 +0.0470 0.1344 1.4214 +0.0492 0.1546 1.4961 +0.0500 0.1750 1.5708 +primID: 5 +startangle_c: 3 +endpose_c: 0 0 2 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0000 0.0000 1.1345 +0.0000 0.0000 1.0908 +0.0000 0.0000 1.0472 +0.0000 0.0000 1.0036 +0.0000 0.0000 0.9599 +0.0000 0.0000 0.9163 +0.0000 0.0000 0.8727 +0.0000 0.0000 0.8290 +0.0000 0.0000 0.7854 +primID: 6 +startangle_c: 3 +endpose_c: 0 0 4 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0000 0.0000 1.2217 +0.0000 0.0000 1.2654 +0.0000 0.0000 1.3090 +0.0000 0.0000 1.3526 +0.0000 0.0000 1.3963 +0.0000 0.0000 1.4399 +0.0000 0.0000 1.4835 +0.0000 0.0000 1.5272 +0.0000 0.0000 1.5708 +primID: 7 +startangle_c: 3 +endpose_c: 2 -1 3 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0056 -0.0028 1.1781 +0.0111 -0.0056 1.1781 +0.0167 -0.0083 1.1781 +0.0222 -0.0111 1.1781 +0.0278 -0.0139 1.1781 +0.0333 -0.0167 1.1781 +0.0389 -0.0194 1.1781 +0.0444 -0.0222 1.1781 +0.0500 -0.0250 1.1781 +primID: 8 +startangle_c: 3 +endpose_c: -2 1 3 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.1781 +-0.0056 0.0028 1.1781 +-0.0111 0.0056 1.1781 +-0.0167 0.0083 1.1781 +-0.0222 0.0111 1.1781 +-0.0278 0.0139 1.1781 +-0.0333 0.0167 1.1781 +-0.0389 0.0194 1.1781 +-0.0444 0.0222 1.1781 +-0.0500 0.0250 1.1781 +primID: 9 +startangle_c: 3 +endpose_c: -4 -5 2 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.1781 +-0.0092 -0.0149 1.1478 +-0.0189 -0.0296 1.1175 +-0.0291 -0.0440 1.0872 +-0.0398 -0.0582 1.0569 +-0.0509 -0.0722 1.0266 +-0.0625 -0.0858 0.9963 +-0.0746 -0.0992 0.9660 +-0.0871 -0.1123 0.9357 +-0.1000 -0.1250 0.9054 +primID: 10 +startangle_c: 3 +endpose_c: -2 -7 4 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.1781 +-0.0078 -0.0188 1.1781 +-0.0156 -0.0377 1.1781 +-0.0234 -0.0565 1.1781 +-0.0312 -0.0754 1.1972 +-0.0379 -0.0946 1.2719 +-0.0432 -0.1143 1.3466 +-0.0470 -0.1344 1.4214 +-0.0492 -0.1546 1.4961 +-0.0500 -0.1750 1.5708 +primID: 11 +startangle_c: 3 +endpose_c: 4 5 3 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0111 0.0139 1.1781 +0.0222 0.0278 1.1781 +0.0333 0.0417 1.1781 +0.0444 0.0556 1.1781 +0.0556 0.0694 1.1781 +0.0667 0.0833 1.1781 +0.0778 0.0972 1.1781 +0.0889 0.1111 1.1781 +0.1000 0.1250 1.1781 +primID: 12 +startangle_c: 3 +endpose_c: 2 7 3 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0056 0.0194 1.1781 +0.0111 0.0389 1.1781 +0.0167 0.0583 1.1781 +0.0222 0.0778 1.1781 +0.0278 0.0972 1.1781 +0.0333 0.1167 1.1781 +0.0389 0.1361 1.1781 +0.0444 0.1556 1.1781 +0.0500 0.1750 1.1781 +primID: 0 +startangle_c: 4 +endpose_c: 0 1 4 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0028 1.5708 +0.0000 0.0056 1.5708 +0.0000 0.0083 1.5708 +0.0000 0.0111 1.5708 +0.0000 0.0139 1.5708 +0.0000 0.0167 1.5708 +0.0000 0.0194 1.5708 +0.0000 0.0222 1.5708 +0.0000 0.0250 1.5708 +primID: 1 +startangle_c: 4 +endpose_c: 0 8 4 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0222 1.5708 +0.0000 0.0444 1.5708 +0.0000 0.0667 1.5708 +0.0000 0.0889 1.5708 +0.0000 0.1111 1.5708 +0.0000 0.1333 1.5708 +0.0000 0.1556 1.5708 +0.0000 0.1778 1.5708 +0.0000 0.2000 1.5708 +primID: 2 +startangle_c: 4 +endpose_c: 0 -1 4 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 -0.0028 1.5708 +0.0000 -0.0056 1.5708 +0.0000 -0.0083 1.5708 +0.0000 -0.0111 1.5708 +0.0000 -0.0139 1.5708 +0.0000 -0.0167 1.5708 +0.0000 -0.0194 1.5708 +0.0000 -0.0222 1.5708 +0.0000 -0.0250 1.5708 +primID: 3 +startangle_c: 4 +endpose_c: -1 8 5 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0226 1.5708 +0.0000 0.0452 1.5708 +0.0000 0.0678 1.5708 +-0.0004 0.0903 1.6196 +-0.0023 0.1128 1.6884 +-0.0057 0.1352 1.7572 +-0.0106 0.1572 1.8259 +-0.0171 0.1789 1.8947 +-0.0250 0.2000 1.9635 +primID: 4 +startangle_c: 4 +endpose_c: 1 8 3 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.5708 +-0.0000 0.0226 1.5708 +-0.0000 0.0452 1.5708 +-0.0000 0.0678 1.5708 +0.0004 0.0903 1.5220 +0.0023 0.1128 1.4532 +0.0057 0.1352 1.3844 +0.0106 0.1572 1.3156 +0.0171 0.1789 1.2469 +0.0250 0.2000 1.1781 +primID: 5 +startangle_c: 4 +endpose_c: 0 0 5 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0000 1.6144 +0.0000 0.0000 1.6581 +0.0000 0.0000 1.7017 +0.0000 0.0000 1.7453 +0.0000 0.0000 1.7890 +0.0000 0.0000 1.8326 +0.0000 0.0000 1.8762 +0.0000 0.0000 1.9199 +0.0000 0.0000 1.9635 +primID: 6 +startangle_c: 4 +endpose_c: 0 0 3 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0000 1.5272 +0.0000 0.0000 1.4835 +0.0000 0.0000 1.4399 +0.0000 0.0000 1.3963 +0.0000 0.0000 1.3526 +0.0000 0.0000 1.3090 +0.0000 0.0000 1.2654 +0.0000 0.0000 1.2217 +0.0000 0.0000 1.1781 +primID: 7 +startangle_c: 4 +endpose_c: -1 0 4 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.5708 +-0.0028 0.0000 1.5708 +-0.0056 0.0000 1.5708 +-0.0083 0.0000 1.5708 +-0.0111 0.0000 1.5708 +-0.0139 0.0000 1.5708 +-0.0167 0.0000 1.5708 +-0.0194 0.0000 1.5708 +-0.0222 0.0000 1.5708 +-0.0250 0.0000 1.5708 +primID: 8 +startangle_c: 4 +endpose_c: 1 0 4 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0028 0.0000 1.5708 +0.0056 0.0000 1.5708 +0.0083 0.0000 1.5708 +0.0111 0.0000 1.5708 +0.0139 0.0000 1.5708 +0.0167 0.0000 1.5708 +0.0194 0.0000 1.5708 +0.0222 0.0000 1.5708 +0.0250 0.0000 1.5708 +primID: 9 +startangle_c: 4 +endpose_c: 1 -8 5 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.5708 +-0.0000 -0.0226 1.5708 +-0.0000 -0.0452 1.5708 +-0.0000 -0.0678 1.5708 +0.0004 -0.0903 1.6196 +0.0023 -0.1128 1.6884 +0.0057 -0.1352 1.7572 +0.0106 -0.1572 1.8259 +0.0171 -0.1789 1.8947 +0.0250 -0.2000 1.9635 +primID: 10 +startangle_c: 4 +endpose_c: -1 -8 3 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 -0.0226 1.5708 +0.0000 -0.0452 1.5708 +0.0000 -0.0678 1.5708 +-0.0004 -0.0903 1.5220 +-0.0023 -0.1128 1.4532 +-0.0057 -0.1352 1.3844 +-0.0106 -0.1572 1.3156 +-0.0171 -0.1789 1.2469 +-0.0250 -0.2000 1.1781 +primID: 11 +startangle_c: 4 +endpose_c: -1 8 4 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.5708 +-0.0028 0.0222 1.5708 +-0.0056 0.0444 1.5708 +-0.0083 0.0667 1.5708 +-0.0111 0.0889 1.5708 +-0.0139 0.1111 1.5708 +-0.0167 0.1333 1.5708 +-0.0194 0.1556 1.5708 +-0.0222 0.1778 1.5708 +-0.0250 0.2000 1.5708 +primID: 12 +startangle_c: 4 +endpose_c: 1 8 4 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0028 0.0222 1.5708 +0.0056 0.0444 1.5708 +0.0083 0.0667 1.5708 +0.0111 0.0889 1.5708 +0.0139 0.1111 1.5708 +0.0167 0.1333 1.5708 +0.0194 0.1556 1.5708 +0.0222 0.1778 1.5708 +0.0250 0.2000 1.5708 +primID: 0 +startangle_c: 5 +endpose_c: -1 2 5 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0028 0.0056 1.9635 +-0.0056 0.0111 1.9635 +-0.0083 0.0167 1.9635 +-0.0111 0.0222 1.9635 +-0.0139 0.0278 1.9635 +-0.0167 0.0333 1.9635 +-0.0194 0.0389 1.9635 +-0.0222 0.0444 1.9635 +-0.0250 0.0500 1.9635 +primID: 1 +startangle_c: 5 +endpose_c: -3 6 5 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0083 0.0167 1.9635 +-0.0167 0.0333 1.9635 +-0.0250 0.0500 1.9635 +-0.0333 0.0667 1.9635 +-0.0417 0.0833 1.9635 +-0.0500 0.1000 1.9635 +-0.0583 0.1167 1.9635 +-0.0667 0.1333 1.9635 +-0.0750 0.1500 1.9635 +primID: 2 +startangle_c: 5 +endpose_c: 1 -2 5 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0028 -0.0056 1.9635 +0.0056 -0.0111 1.9635 +0.0083 -0.0167 1.9635 +0.0111 -0.0222 1.9635 +0.0139 -0.0278 1.9635 +0.0167 -0.0333 1.9635 +0.0194 -0.0389 1.9635 +0.0222 -0.0444 1.9635 +0.0250 -0.0500 1.9635 +primID: 3 +startangle_c: 5 +endpose_c: -4 5 6 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0092 0.0149 1.9938 +-0.0189 0.0296 2.0241 +-0.0291 0.0440 2.0544 +-0.0398 0.0582 2.0847 +-0.0509 0.0722 2.1150 +-0.0625 0.0858 2.1453 +-0.0746 0.0992 2.1756 +-0.0871 0.1123 2.2059 +-0.1000 0.1250 2.2362 +primID: 4 +startangle_c: 5 +endpose_c: -2 7 4 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0078 0.0188 1.9635 +-0.0156 0.0377 1.9635 +-0.0234 0.0565 1.9635 +-0.0312 0.0754 1.9444 +-0.0379 0.0946 1.8697 +-0.0432 0.1143 1.7950 +-0.0470 0.1344 1.7202 +-0.0492 0.1546 1.6455 +-0.0500 0.1750 1.5708 +primID: 5 +startangle_c: 5 +endpose_c: 0 0 6 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0000 0.0000 2.0071 +0.0000 0.0000 2.0508 +0.0000 0.0000 2.0944 +0.0000 0.0000 2.1380 +0.0000 0.0000 2.1817 +0.0000 0.0000 2.2253 +0.0000 0.0000 2.2689 +0.0000 0.0000 2.3126 +0.0000 0.0000 2.3562 +primID: 6 +startangle_c: 5 +endpose_c: 0 0 4 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0000 0.0000 1.9199 +0.0000 0.0000 1.8762 +0.0000 0.0000 1.8326 +0.0000 0.0000 1.7890 +0.0000 0.0000 1.7453 +0.0000 0.0000 1.7017 +0.0000 0.0000 1.6581 +0.0000 0.0000 1.6144 +0.0000 0.0000 1.5708 +primID: 7 +startangle_c: 5 +endpose_c: -2 -1 5 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0056 -0.0028 1.9635 +-0.0111 -0.0056 1.9635 +-0.0167 -0.0083 1.9635 +-0.0222 -0.0111 1.9635 +-0.0278 -0.0139 1.9635 +-0.0333 -0.0167 1.9635 +-0.0389 -0.0194 1.9635 +-0.0444 -0.0222 1.9635 +-0.0500 -0.0250 1.9635 +primID: 8 +startangle_c: 5 +endpose_c: 2 1 5 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0056 0.0028 1.9635 +0.0111 0.0056 1.9635 +0.0167 0.0083 1.9635 +0.0222 0.0111 1.9635 +0.0278 0.0139 1.9635 +0.0333 0.0167 1.9635 +0.0389 0.0194 1.9635 +0.0444 0.0222 1.9635 +0.0500 0.0250 1.9635 +primID: 9 +startangle_c: 5 +endpose_c: 4 -5 6 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0092 -0.0149 1.9938 +0.0189 -0.0296 2.0241 +0.0291 -0.0440 2.0544 +0.0398 -0.0582 2.0847 +0.0509 -0.0722 2.1150 +0.0625 -0.0858 2.1453 +0.0746 -0.0992 2.1756 +0.0871 -0.1123 2.2059 +0.1000 -0.1250 2.2362 +primID: 10 +startangle_c: 5 +endpose_c: 2 -7 4 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0078 -0.0188 1.9635 +0.0156 -0.0377 1.9635 +0.0234 -0.0565 1.9635 +0.0312 -0.0754 1.9444 +0.0379 -0.0946 1.8697 +0.0432 -0.1143 1.7950 +0.0470 -0.1344 1.7202 +0.0492 -0.1546 1.6455 +0.0500 -0.1750 1.5708 +primID: 11 +startangle_c: 5 +endpose_c: -4 5 5 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0111 0.0139 1.9635 +-0.0222 0.0278 1.9635 +-0.0333 0.0417 1.9635 +-0.0444 0.0556 1.9635 +-0.0556 0.0694 1.9635 +-0.0667 0.0833 1.9635 +-0.0778 0.0972 1.9635 +-0.0889 0.1111 1.9635 +-0.1000 0.1250 1.9635 +primID: 12 +startangle_c: 5 +endpose_c: -2 7 5 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0056 0.0194 1.9635 +-0.0111 0.0389 1.9635 +-0.0167 0.0583 1.9635 +-0.0222 0.0778 1.9635 +-0.0278 0.0972 1.9635 +-0.0333 0.1167 1.9635 +-0.0389 0.1361 1.9635 +-0.0444 0.1556 1.9635 +-0.0500 0.1750 1.9635 +primID: 0 +startangle_c: 6 +endpose_c: -1 1 6 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0028 0.0028 2.3562 +-0.0056 0.0056 2.3562 +-0.0083 0.0083 2.3562 +-0.0111 0.0111 2.3562 +-0.0139 0.0139 2.3562 +-0.0167 0.0167 2.3562 +-0.0194 0.0194 2.3562 +-0.0222 0.0222 2.3562 +-0.0250 0.0250 2.3562 +primID: 1 +startangle_c: 6 +endpose_c: -6 6 6 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0167 0.0167 2.3562 +-0.0333 0.0333 2.3562 +-0.0500 0.0500 2.3562 +-0.0667 0.0667 2.3562 +-0.0833 0.0833 2.3562 +-0.1000 0.1000 2.3562 +-0.1167 0.1167 2.3562 +-0.1333 0.1333 2.3562 +-0.1500 0.1500 2.3562 +primID: 2 +startangle_c: 6 +endpose_c: 1 -1 6 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0028 -0.0028 2.3562 +0.0056 -0.0056 2.3562 +0.0083 -0.0083 2.3562 +0.0111 -0.0111 2.3562 +0.0139 -0.0139 2.3562 +0.0167 -0.0167 2.3562 +0.0194 -0.0194 2.3562 +0.0222 -0.0222 2.3562 +0.0250 -0.0250 2.3562 +primID: 3 +startangle_c: 6 +endpose_c: -7 5 7 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0170 0.0170 2.3562 +-0.0342 0.0339 2.3859 +-0.0522 0.0500 2.4377 +-0.0709 0.0651 2.4896 +-0.0904 0.0792 2.5415 +-0.1107 0.0923 2.5933 +-0.1315 0.1043 2.6452 +-0.1530 0.1152 2.6970 +-0.1750 0.1250 2.7489 +primID: 4 +startangle_c: 6 +endpose_c: -5 7 5 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0170 0.0170 2.3562 +-0.0339 0.0342 2.3265 +-0.0500 0.0522 2.2747 +-0.0651 0.0709 2.2228 +-0.0792 0.0904 2.1709 +-0.0923 0.1107 2.1191 +-0.1043 0.1315 2.0672 +-0.1152 0.1530 2.0154 +-0.1250 0.1750 1.9635 +primID: 5 +startangle_c: 6 +endpose_c: 0 0 7 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0000 0.0000 2.3998 +0.0000 0.0000 2.4435 +0.0000 0.0000 2.4871 +0.0000 0.0000 2.5307 +0.0000 0.0000 2.5744 +0.0000 0.0000 2.6180 +0.0000 0.0000 2.6616 +0.0000 0.0000 2.7053 +0.0000 0.0000 2.7489 +primID: 6 +startangle_c: 6 +endpose_c: 0 0 5 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0000 0.0000 2.3126 +0.0000 0.0000 2.2689 +0.0000 0.0000 2.2253 +0.0000 0.0000 2.1817 +0.0000 0.0000 2.1380 +0.0000 0.0000 2.0944 +0.0000 0.0000 2.0508 +0.0000 0.0000 2.0071 +0.0000 0.0000 1.9635 +primID: 7 +startangle_c: 6 +endpose_c: -1 -1 6 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0028 -0.0028 2.3562 +-0.0056 -0.0056 2.3562 +-0.0083 -0.0083 2.3562 +-0.0111 -0.0111 2.3562 +-0.0139 -0.0139 2.3562 +-0.0167 -0.0167 2.3562 +-0.0194 -0.0194 2.3562 +-0.0222 -0.0222 2.3562 +-0.0250 -0.0250 2.3562 +primID: 8 +startangle_c: 6 +endpose_c: 1 1 6 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0028 0.0028 2.3562 +0.0056 0.0056 2.3562 +0.0083 0.0083 2.3562 +0.0111 0.0111 2.3562 +0.0139 0.0139 2.3562 +0.0167 0.0167 2.3562 +0.0194 0.0194 2.3562 +0.0222 0.0222 2.3562 +0.0250 0.0250 2.3562 +primID: 9 +startangle_c: 6 +endpose_c: 7 -5 7 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0170 -0.0170 2.3562 +0.0342 -0.0339 2.3859 +0.0522 -0.0500 2.4377 +0.0709 -0.0651 2.4896 +0.0904 -0.0792 2.5415 +0.1107 -0.0923 2.5933 +0.1315 -0.1043 2.6452 +0.1530 -0.1152 2.6970 +0.1750 -0.1250 2.7489 +primID: 10 +startangle_c: 6 +endpose_c: 5 -7 5 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0170 -0.0170 2.3562 +0.0339 -0.0342 2.3265 +0.0500 -0.0522 2.2747 +0.0651 -0.0709 2.2228 +0.0792 -0.0904 2.1709 +0.0923 -0.1107 2.1191 +0.1043 -0.1315 2.0672 +0.1152 -0.1530 2.0154 +0.1250 -0.1750 1.9635 +primID: 11 +startangle_c: 6 +endpose_c: -7 5 6 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0194 0.0139 2.3562 +-0.0389 0.0278 2.3562 +-0.0583 0.0417 2.3562 +-0.0778 0.0556 2.3562 +-0.0972 0.0694 2.3562 +-0.1167 0.0833 2.3562 +-0.1361 0.0972 2.3562 +-0.1556 0.1111 2.3562 +-0.1750 0.1250 2.3562 +primID: 12 +startangle_c: 6 +endpose_c: -5 7 6 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0139 0.0194 2.3562 +-0.0278 0.0389 2.3562 +-0.0417 0.0583 2.3562 +-0.0556 0.0778 2.3562 +-0.0694 0.0972 2.3562 +-0.0833 0.1167 2.3562 +-0.0972 0.1361 2.3562 +-0.1111 0.1556 2.3562 +-0.1250 0.1750 2.3562 +primID: 0 +startangle_c: 7 +endpose_c: -2 1 7 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0056 0.0028 2.7489 +-0.0111 0.0056 2.7489 +-0.0167 0.0083 2.7489 +-0.0222 0.0111 2.7489 +-0.0278 0.0139 2.7489 +-0.0333 0.0167 2.7489 +-0.0389 0.0194 2.7489 +-0.0444 0.0222 2.7489 +-0.0500 0.0250 2.7489 +primID: 1 +startangle_c: 7 +endpose_c: -6 3 7 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0167 0.0083 2.7489 +-0.0333 0.0167 2.7489 +-0.0500 0.0250 2.7489 +-0.0667 0.0333 2.7489 +-0.0833 0.0417 2.7489 +-0.1000 0.0500 2.7489 +-0.1167 0.0583 2.7489 +-0.1333 0.0667 2.7489 +-0.1500 0.0750 2.7489 +primID: 2 +startangle_c: 7 +endpose_c: 2 -1 7 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0056 -0.0028 2.7489 +0.0111 -0.0056 2.7489 +0.0167 -0.0083 2.7489 +0.0222 -0.0111 2.7489 +0.0278 -0.0139 2.7489 +0.0333 -0.0167 2.7489 +0.0389 -0.0194 2.7489 +0.0444 -0.0222 2.7489 +0.0500 -0.0250 2.7489 +primID: 3 +startangle_c: 7 +endpose_c: -5 4 6 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0149 0.0092 2.7186 +-0.0296 0.0189 2.6883 +-0.0440 0.0291 2.6580 +-0.0582 0.0398 2.6277 +-0.0722 0.0509 2.5974 +-0.0858 0.0625 2.5671 +-0.0992 0.0746 2.5368 +-0.1123 0.0871 2.5065 +-0.1250 0.1000 2.4762 +primID: 4 +startangle_c: 7 +endpose_c: -7 2 8 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0188 0.0078 2.7489 +-0.0377 0.0156 2.7489 +-0.0565 0.0234 2.7489 +-0.0754 0.0312 2.7680 +-0.0946 0.0379 2.8427 +-0.1143 0.0432 2.9174 +-0.1344 0.0470 2.9921 +-0.1546 0.0492 3.0669 +-0.1750 0.0500 3.1416 +primID: 5 +startangle_c: 7 +endpose_c: 0 0 6 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0000 0.0000 2.7053 +0.0000 0.0000 2.6616 +0.0000 0.0000 2.6180 +0.0000 0.0000 2.5744 +0.0000 0.0000 2.5307 +0.0000 0.0000 2.4871 +0.0000 0.0000 2.4435 +0.0000 0.0000 2.3998 +0.0000 0.0000 2.3562 +primID: 6 +startangle_c: 7 +endpose_c: 0 0 8 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0000 0.0000 2.7925 +0.0000 0.0000 2.8362 +0.0000 0.0000 2.8798 +0.0000 0.0000 2.9234 +0.0000 0.0000 2.9671 +0.0000 0.0000 3.0107 +0.0000 0.0000 3.0543 +0.0000 0.0000 3.0980 +0.0000 0.0000 3.1416 +primID: 7 +startangle_c: 7 +endpose_c: 1 2 7 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0028 0.0056 2.7489 +0.0056 0.0111 2.7489 +0.0083 0.0167 2.7489 +0.0111 0.0222 2.7489 +0.0139 0.0278 2.7489 +0.0167 0.0333 2.7489 +0.0194 0.0389 2.7489 +0.0222 0.0444 2.7489 +0.0250 0.0500 2.7489 +primID: 8 +startangle_c: 7 +endpose_c: -1 -2 7 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0028 -0.0056 2.7489 +-0.0056 -0.0111 2.7489 +-0.0083 -0.0167 2.7489 +-0.0111 -0.0222 2.7489 +-0.0139 -0.0278 2.7489 +-0.0167 -0.0333 2.7489 +-0.0194 -0.0389 2.7489 +-0.0222 -0.0444 2.7489 +-0.0250 -0.0500 2.7489 +primID: 9 +startangle_c: 7 +endpose_c: 5 -4 6 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0149 -0.0092 2.7186 +0.0296 -0.0189 2.6883 +0.0440 -0.0291 2.6580 +0.0582 -0.0398 2.6277 +0.0722 -0.0509 2.5974 +0.0858 -0.0625 2.5671 +0.0992 -0.0746 2.5368 +0.1123 -0.0871 2.5065 +0.1250 -0.1000 2.4762 +primID: 10 +startangle_c: 7 +endpose_c: 7 -2 8 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0188 -0.0078 2.7489 +0.0377 -0.0156 2.7489 +0.0565 -0.0234 2.7489 +0.0754 -0.0312 2.7680 +0.0946 -0.0379 2.8427 +0.1143 -0.0432 2.9174 +0.1344 -0.0470 2.9921 +0.1546 -0.0492 3.0669 +0.1750 -0.0500 3.1416 +primID: 11 +startangle_c: 7 +endpose_c: -5 4 7 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0139 0.0111 2.7489 +-0.0278 0.0222 2.7489 +-0.0417 0.0333 2.7489 +-0.0556 0.0444 2.7489 +-0.0694 0.0556 2.7489 +-0.0833 0.0667 2.7489 +-0.0972 0.0778 2.7489 +-0.1111 0.0889 2.7489 +-0.1250 0.1000 2.7489 +primID: 12 +startangle_c: 7 +endpose_c: -7 2 7 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0194 0.0056 2.7489 +-0.0389 0.0111 2.7489 +-0.0583 0.0167 2.7489 +-0.0778 0.0222 2.7489 +-0.0972 0.0278 2.7489 +-0.1167 0.0333 2.7489 +-0.1361 0.0389 2.7489 +-0.1556 0.0444 2.7489 +-0.1750 0.0500 2.7489 +primID: 0 +startangle_c: 8 +endpose_c: -1 0 8 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0028 0.0000 3.1416 +-0.0056 0.0000 3.1416 +-0.0083 0.0000 3.1416 +-0.0111 0.0000 3.1416 +-0.0139 0.0000 3.1416 +-0.0167 0.0000 3.1416 +-0.0194 0.0000 3.1416 +-0.0222 0.0000 3.1416 +-0.0250 0.0000 3.1416 +primID: 1 +startangle_c: 8 +endpose_c: -8 0 8 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0222 0.0000 3.1416 +-0.0444 0.0000 3.1416 +-0.0667 0.0000 3.1416 +-0.0889 0.0000 3.1416 +-0.1111 0.0000 3.1416 +-0.1333 0.0000 3.1416 +-0.1556 0.0000 3.1416 +-0.1778 0.0000 3.1416 +-0.2000 0.0000 3.1416 +primID: 2 +startangle_c: 8 +endpose_c: 1 0 8 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0028 0.0000 3.1416 +0.0056 0.0000 3.1416 +0.0083 0.0000 3.1416 +0.0111 0.0000 3.1416 +0.0139 0.0000 3.1416 +0.0167 0.0000 3.1416 +0.0194 0.0000 3.1416 +0.0222 0.0000 3.1416 +0.0250 0.0000 3.1416 +primID: 3 +startangle_c: 8 +endpose_c: -8 -1 9 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0226 0.0000 3.1416 +-0.0452 0.0000 3.1416 +-0.0678 0.0000 3.1416 +-0.0903 -0.0004 3.1904 +-0.1128 -0.0023 3.2592 +-0.1352 -0.0057 3.3280 +-0.1572 -0.0106 3.3967 +-0.1789 -0.0171 3.4655 +-0.2000 -0.0250 3.5343 +primID: 4 +startangle_c: 8 +endpose_c: -8 1 7 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0226 0.0000 3.1416 +-0.0452 0.0000 3.1416 +-0.0678 0.0000 3.1416 +-0.0903 0.0004 3.0928 +-0.1128 0.0023 3.0240 +-0.1352 0.0057 2.9552 +-0.1572 0.0106 2.8864 +-0.1789 0.0171 2.8177 +-0.2000 0.0250 2.7489 +primID: 5 +startangle_c: 8 +endpose_c: 0 0 9 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0000 0.0000 3.1852 +0.0000 0.0000 3.2289 +0.0000 0.0000 3.2725 +0.0000 0.0000 3.3161 +0.0000 0.0000 3.3598 +0.0000 0.0000 3.4034 +0.0000 0.0000 3.4470 +0.0000 0.0000 3.4907 +0.0000 0.0000 3.5343 +primID: 6 +startangle_c: 8 +endpose_c: 0 0 7 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0000 0.0000 3.0980 +0.0000 0.0000 3.0543 +0.0000 0.0000 3.0107 +0.0000 0.0000 2.9671 +0.0000 0.0000 2.9234 +0.0000 0.0000 2.8798 +0.0000 0.0000 2.8362 +0.0000 0.0000 2.7925 +0.0000 0.0000 2.7489 +primID: 7 +startangle_c: 8 +endpose_c: 0 -1 8 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0000 -0.0028 3.1416 +0.0000 -0.0056 3.1416 +0.0000 -0.0083 3.1416 +0.0000 -0.0111 3.1416 +0.0000 -0.0139 3.1416 +0.0000 -0.0167 3.1416 +0.0000 -0.0194 3.1416 +0.0000 -0.0222 3.1416 +0.0000 -0.0250 3.1416 +primID: 8 +startangle_c: 8 +endpose_c: 0 1 8 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0000 0.0028 3.1416 +0.0000 0.0056 3.1416 +0.0000 0.0083 3.1416 +0.0000 0.0111 3.1416 +0.0000 0.0139 3.1416 +0.0000 0.0167 3.1416 +0.0000 0.0194 3.1416 +0.0000 0.0222 3.1416 +0.0000 0.0250 3.1416 +primID: 9 +startangle_c: 8 +endpose_c: 8 1 9 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0226 -0.0000 3.1416 +0.0452 -0.0000 3.1416 +0.0678 -0.0000 3.1416 +0.0903 0.0004 3.1904 +0.1128 0.0023 3.2592 +0.1352 0.0057 3.3280 +0.1572 0.0106 3.3967 +0.1789 0.0171 3.4655 +0.2000 0.0250 3.5343 +primID: 10 +startangle_c: 8 +endpose_c: 8 -1 7 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0226 -0.0000 3.1416 +0.0452 -0.0000 3.1416 +0.0678 -0.0000 3.1416 +0.0903 -0.0004 3.0928 +0.1128 -0.0023 3.0240 +0.1352 -0.0057 2.9552 +0.1572 -0.0106 2.8864 +0.1789 -0.0171 2.8177 +0.2000 -0.0250 2.7489 +primID: 11 +startangle_c: 8 +endpose_c: -8 -1 8 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0222 -0.0028 3.1416 +-0.0444 -0.0056 3.1416 +-0.0667 -0.0083 3.1416 +-0.0889 -0.0111 3.1416 +-0.1111 -0.0139 3.1416 +-0.1333 -0.0167 3.1416 +-0.1556 -0.0194 3.1416 +-0.1778 -0.0222 3.1416 +-0.2000 -0.0250 3.1416 +primID: 12 +startangle_c: 8 +endpose_c: -8 1 8 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0222 0.0028 3.1416 +-0.0444 0.0056 3.1416 +-0.0667 0.0083 3.1416 +-0.0889 0.0111 3.1416 +-0.1111 0.0139 3.1416 +-0.1333 0.0167 3.1416 +-0.1556 0.0194 3.1416 +-0.1778 0.0222 3.1416 +-0.2000 0.0250 3.1416 +primID: 0 +startangle_c: 9 +endpose_c: -2 -1 9 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0056 -0.0028 3.5343 +-0.0111 -0.0056 3.5343 +-0.0167 -0.0083 3.5343 +-0.0222 -0.0111 3.5343 +-0.0278 -0.0139 3.5343 +-0.0333 -0.0167 3.5343 +-0.0389 -0.0194 3.5343 +-0.0444 -0.0222 3.5343 +-0.0500 -0.0250 3.5343 +primID: 1 +startangle_c: 9 +endpose_c: -6 -3 9 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0167 -0.0083 3.5343 +-0.0333 -0.0167 3.5343 +-0.0500 -0.0250 3.5343 +-0.0667 -0.0333 3.5343 +-0.0833 -0.0417 3.5343 +-0.1000 -0.0500 3.5343 +-0.1167 -0.0583 3.5343 +-0.1333 -0.0667 3.5343 +-0.1500 -0.0750 3.5343 +primID: 2 +startangle_c: 9 +endpose_c: 2 1 9 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0056 0.0028 3.5343 +0.0111 0.0056 3.5343 +0.0167 0.0083 3.5343 +0.0222 0.0111 3.5343 +0.0278 0.0139 3.5343 +0.0333 0.0167 3.5343 +0.0389 0.0194 3.5343 +0.0444 0.0222 3.5343 +0.0500 0.0250 3.5343 +primID: 3 +startangle_c: 9 +endpose_c: -5 -4 10 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0149 -0.0092 3.5646 +-0.0296 -0.0189 3.5949 +-0.0440 -0.0291 3.6252 +-0.0582 -0.0398 3.6555 +-0.0722 -0.0509 3.6858 +-0.0858 -0.0625 3.7161 +-0.0992 -0.0746 3.7464 +-0.1123 -0.0871 3.7767 +-0.1250 -0.1000 3.8070 +primID: 4 +startangle_c: 9 +endpose_c: -7 -2 8 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0188 -0.0078 3.5343 +-0.0377 -0.0156 3.5343 +-0.0565 -0.0234 3.5343 +-0.0754 -0.0312 3.5152 +-0.0946 -0.0379 3.4405 +-0.1143 -0.0432 3.3658 +-0.1344 -0.0470 3.2910 +-0.1546 -0.0492 3.2163 +-0.1750 -0.0500 3.1416 +primID: 5 +startangle_c: 9 +endpose_c: 0 0 10 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0000 0.0000 3.5779 +0.0000 0.0000 3.6216 +0.0000 0.0000 3.6652 +0.0000 0.0000 3.7088 +0.0000 0.0000 3.7525 +0.0000 0.0000 3.7961 +0.0000 0.0000 3.8397 +0.0000 0.0000 3.8834 +0.0000 0.0000 3.9270 +primID: 6 +startangle_c: 9 +endpose_c: 0 0 8 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0000 0.0000 3.4907 +0.0000 0.0000 3.4470 +0.0000 0.0000 3.4034 +0.0000 0.0000 3.3598 +0.0000 0.0000 3.3161 +0.0000 0.0000 3.2725 +0.0000 0.0000 3.2289 +0.0000 0.0000 3.1852 +0.0000 0.0000 3.1416 +primID: 7 +startangle_c: 9 +endpose_c: 1 -2 9 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0028 -0.0056 3.5343 +0.0056 -0.0111 3.5343 +0.0083 -0.0167 3.5343 +0.0111 -0.0222 3.5343 +0.0139 -0.0278 3.5343 +0.0167 -0.0333 3.5343 +0.0194 -0.0389 3.5343 +0.0222 -0.0444 3.5343 +0.0250 -0.0500 3.5343 +primID: 8 +startangle_c: 9 +endpose_c: -1 2 9 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0028 0.0056 3.5343 +-0.0056 0.0111 3.5343 +-0.0083 0.0167 3.5343 +-0.0111 0.0222 3.5343 +-0.0139 0.0278 3.5343 +-0.0167 0.0333 3.5343 +-0.0194 0.0389 3.5343 +-0.0222 0.0444 3.5343 +-0.0250 0.0500 3.5343 +primID: 9 +startangle_c: 9 +endpose_c: 5 4 10 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0149 0.0092 3.5646 +0.0296 0.0189 3.5949 +0.0440 0.0291 3.6252 +0.0582 0.0398 3.6555 +0.0722 0.0509 3.6858 +0.0858 0.0625 3.7161 +0.0992 0.0746 3.7464 +0.1123 0.0871 3.7767 +0.1250 0.1000 3.8070 +primID: 10 +startangle_c: 9 +endpose_c: 7 2 8 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0188 0.0078 3.5343 +0.0377 0.0156 3.5343 +0.0565 0.0234 3.5343 +0.0754 0.0312 3.5152 +0.0946 0.0379 3.4405 +0.1143 0.0432 3.3658 +0.1344 0.0470 3.2910 +0.1546 0.0492 3.2163 +0.1750 0.0500 3.1416 +primID: 11 +startangle_c: 9 +endpose_c: -5 -4 9 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0139 -0.0111 3.5343 +-0.0278 -0.0222 3.5343 +-0.0417 -0.0333 3.5343 +-0.0556 -0.0444 3.5343 +-0.0694 -0.0556 3.5343 +-0.0833 -0.0667 3.5343 +-0.0972 -0.0778 3.5343 +-0.1111 -0.0889 3.5343 +-0.1250 -0.1000 3.5343 +primID: 12 +startangle_c: 9 +endpose_c: -7 -2 9 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0194 -0.0056 3.5343 +-0.0389 -0.0111 3.5343 +-0.0583 -0.0167 3.5343 +-0.0778 -0.0222 3.5343 +-0.0972 -0.0278 3.5343 +-0.1167 -0.0333 3.5343 +-0.1361 -0.0389 3.5343 +-0.1556 -0.0444 3.5343 +-0.1750 -0.0500 3.5343 +primID: 0 +startangle_c: 10 +endpose_c: -1 -1 10 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0028 -0.0028 3.9270 +-0.0056 -0.0056 3.9270 +-0.0083 -0.0083 3.9270 +-0.0111 -0.0111 3.9270 +-0.0139 -0.0139 3.9270 +-0.0167 -0.0167 3.9270 +-0.0194 -0.0194 3.9270 +-0.0222 -0.0222 3.9270 +-0.0250 -0.0250 3.9270 +primID: 1 +startangle_c: 10 +endpose_c: -6 -6 10 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0167 -0.0167 3.9270 +-0.0333 -0.0333 3.9270 +-0.0500 -0.0500 3.9270 +-0.0667 -0.0667 3.9270 +-0.0833 -0.0833 3.9270 +-0.1000 -0.1000 3.9270 +-0.1167 -0.1167 3.9270 +-0.1333 -0.1333 3.9270 +-0.1500 -0.1500 3.9270 +primID: 2 +startangle_c: 10 +endpose_c: 1 1 10 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0028 0.0028 3.9270 +0.0056 0.0056 3.9270 +0.0083 0.0083 3.9270 +0.0111 0.0111 3.9270 +0.0139 0.0139 3.9270 +0.0167 0.0167 3.9270 +0.0194 0.0194 3.9270 +0.0222 0.0222 3.9270 +0.0250 0.0250 3.9270 +primID: 3 +startangle_c: 10 +endpose_c: -5 -7 11 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0170 -0.0170 3.9270 +-0.0339 -0.0342 3.9567 +-0.0500 -0.0522 4.0085 +-0.0651 -0.0709 4.0604 +-0.0792 -0.0904 4.1123 +-0.0923 -0.1107 4.1641 +-0.1043 -0.1315 4.2160 +-0.1152 -0.1530 4.2678 +-0.1250 -0.1750 4.3197 +primID: 4 +startangle_c: 10 +endpose_c: -7 -5 9 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0170 -0.0170 3.9270 +-0.0342 -0.0339 3.8973 +-0.0522 -0.0500 3.8455 +-0.0709 -0.0651 3.7936 +-0.0904 -0.0792 3.7417 +-0.1107 -0.0923 3.6899 +-0.1315 -0.1043 3.6380 +-0.1530 -0.1152 3.5862 +-0.1750 -0.1250 3.5343 +primID: 5 +startangle_c: 10 +endpose_c: 0 0 11 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.9706 +0.0000 0.0000 4.0143 +0.0000 0.0000 4.0579 +0.0000 0.0000 4.1015 +0.0000 0.0000 4.1452 +0.0000 0.0000 4.1888 +0.0000 0.0000 4.2324 +0.0000 0.0000 4.2761 +0.0000 0.0000 4.3197 +primID: 6 +startangle_c: 10 +endpose_c: 0 0 9 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.8834 +0.0000 0.0000 3.8397 +0.0000 0.0000 3.7961 +0.0000 0.0000 3.7525 +0.0000 0.0000 3.7088 +0.0000 0.0000 3.6652 +0.0000 0.0000 3.6216 +0.0000 0.0000 3.5779 +0.0000 0.0000 3.5343 +primID: 7 +startangle_c: 10 +endpose_c: 1 -1 10 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0028 -0.0028 3.9270 +0.0056 -0.0056 3.9270 +0.0083 -0.0083 3.9270 +0.0111 -0.0111 3.9270 +0.0139 -0.0139 3.9270 +0.0167 -0.0167 3.9270 +0.0194 -0.0194 3.9270 +0.0222 -0.0222 3.9270 +0.0250 -0.0250 3.9270 +primID: 8 +startangle_c: 10 +endpose_c: -1 1 10 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0028 0.0028 3.9270 +-0.0056 0.0056 3.9270 +-0.0083 0.0083 3.9270 +-0.0111 0.0111 3.9270 +-0.0139 0.0139 3.9270 +-0.0167 0.0167 3.9270 +-0.0194 0.0194 3.9270 +-0.0222 0.0222 3.9270 +-0.0250 0.0250 3.9270 +primID: 9 +startangle_c: 10 +endpose_c: 5 7 11 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0170 0.0170 3.9270 +0.0339 0.0342 3.9567 +0.0500 0.0522 4.0085 +0.0651 0.0709 4.0604 +0.0792 0.0904 4.1123 +0.0923 0.1107 4.1641 +0.1043 0.1315 4.2160 +0.1152 0.1530 4.2678 +0.1250 0.1750 4.3197 +primID: 10 +startangle_c: 10 +endpose_c: 7 5 9 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0170 0.0170 3.9270 +0.0342 0.0339 3.8973 +0.0522 0.0500 3.8455 +0.0709 0.0651 3.7936 +0.0904 0.0792 3.7417 +0.1107 0.0923 3.6899 +0.1315 0.1043 3.6380 +0.1530 0.1152 3.5862 +0.1750 0.1250 3.5343 +primID: 11 +startangle_c: 10 +endpose_c: -5 -7 10 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0139 -0.0194 3.9270 +-0.0278 -0.0389 3.9270 +-0.0417 -0.0583 3.9270 +-0.0556 -0.0778 3.9270 +-0.0694 -0.0972 3.9270 +-0.0833 -0.1167 3.9270 +-0.0972 -0.1361 3.9270 +-0.1111 -0.1556 3.9270 +-0.1250 -0.1750 3.9270 +primID: 12 +startangle_c: 10 +endpose_c: -7 -5 10 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0194 -0.0139 3.9270 +-0.0389 -0.0278 3.9270 +-0.0583 -0.0417 3.9270 +-0.0778 -0.0556 3.9270 +-0.0972 -0.0694 3.9270 +-0.1167 -0.0833 3.9270 +-0.1361 -0.0972 3.9270 +-0.1556 -0.1111 3.9270 +-0.1750 -0.1250 3.9270 +primID: 0 +startangle_c: 11 +endpose_c: -1 -2 11 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0028 -0.0056 4.3197 +-0.0056 -0.0111 4.3197 +-0.0083 -0.0167 4.3197 +-0.0111 -0.0222 4.3197 +-0.0139 -0.0278 4.3197 +-0.0167 -0.0333 4.3197 +-0.0194 -0.0389 4.3197 +-0.0222 -0.0444 4.3197 +-0.0250 -0.0500 4.3197 +primID: 1 +startangle_c: 11 +endpose_c: -3 -6 11 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0083 -0.0167 4.3197 +-0.0167 -0.0333 4.3197 +-0.0250 -0.0500 4.3197 +-0.0333 -0.0667 4.3197 +-0.0417 -0.0833 4.3197 +-0.0500 -0.1000 4.3197 +-0.0583 -0.1167 4.3197 +-0.0667 -0.1333 4.3197 +-0.0750 -0.1500 4.3197 +primID: 2 +startangle_c: 11 +endpose_c: 1 2 11 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0028 0.0056 4.3197 +0.0056 0.0111 4.3197 +0.0083 0.0167 4.3197 +0.0111 0.0222 4.3197 +0.0139 0.0278 4.3197 +0.0167 0.0333 4.3197 +0.0194 0.0389 4.3197 +0.0222 0.0444 4.3197 +0.0250 0.0500 4.3197 +primID: 3 +startangle_c: 11 +endpose_c: -4 -5 10 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0092 -0.0149 4.2894 +-0.0189 -0.0296 4.2591 +-0.0291 -0.0440 4.2288 +-0.0398 -0.0582 4.1985 +-0.0509 -0.0722 4.1682 +-0.0625 -0.0858 4.1379 +-0.0746 -0.0992 4.1076 +-0.0871 -0.1123 4.0773 +-0.1000 -0.1250 4.0470 +primID: 4 +startangle_c: 11 +endpose_c: -2 -7 12 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0078 -0.0188 4.3197 +-0.0156 -0.0377 4.3197 +-0.0234 -0.0565 4.3197 +-0.0312 -0.0754 4.3388 +-0.0379 -0.0946 4.4135 +-0.0432 -0.1143 4.4882 +-0.0470 -0.1344 4.5629 +-0.0492 -0.1546 4.6377 +-0.0500 -0.1750 4.7124 +primID: 5 +startangle_c: 11 +endpose_c: 0 0 10 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0000 0.0000 4.2761 +0.0000 0.0000 4.2324 +0.0000 0.0000 4.1888 +0.0000 0.0000 4.1452 +0.0000 0.0000 4.1015 +0.0000 0.0000 4.0579 +0.0000 0.0000 4.0143 +0.0000 0.0000 3.9706 +0.0000 0.0000 3.9270 +primID: 6 +startangle_c: 11 +endpose_c: 0 0 12 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0000 0.0000 4.3633 +0.0000 0.0000 4.4070 +0.0000 0.0000 4.4506 +0.0000 0.0000 4.4942 +0.0000 0.0000 4.5379 +0.0000 0.0000 4.5815 +0.0000 0.0000 4.6251 +0.0000 0.0000 4.6688 +0.0000 0.0000 4.7124 +primID: 7 +startangle_c: 11 +endpose_c: -2 1 11 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0056 0.0028 4.3197 +-0.0111 0.0056 4.3197 +-0.0167 0.0083 4.3197 +-0.0222 0.0111 4.3197 +-0.0278 0.0139 4.3197 +-0.0333 0.0167 4.3197 +-0.0389 0.0194 4.3197 +-0.0444 0.0222 4.3197 +-0.0500 0.0250 4.3197 +primID: 8 +startangle_c: 11 +endpose_c: 2 -1 11 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0056 -0.0028 4.3197 +0.0111 -0.0056 4.3197 +0.0167 -0.0083 4.3197 +0.0222 -0.0111 4.3197 +0.0278 -0.0139 4.3197 +0.0333 -0.0167 4.3197 +0.0389 -0.0194 4.3197 +0.0444 -0.0222 4.3197 +0.0500 -0.0250 4.3197 +primID: 9 +startangle_c: 11 +endpose_c: 4 5 10 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0092 0.0149 4.2894 +0.0189 0.0296 4.2591 +0.0291 0.0440 4.2288 +0.0398 0.0582 4.1985 +0.0509 0.0722 4.1682 +0.0625 0.0858 4.1379 +0.0746 0.0992 4.1076 +0.0871 0.1123 4.0773 +0.1000 0.1250 4.0470 +primID: 10 +startangle_c: 11 +endpose_c: 2 7 12 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0078 0.0188 4.3197 +0.0156 0.0377 4.3197 +0.0234 0.0565 4.3197 +0.0312 0.0754 4.3388 +0.0379 0.0946 4.4135 +0.0432 0.1143 4.4882 +0.0470 0.1344 4.5629 +0.0492 0.1546 4.6377 +0.0500 0.1750 4.7124 +primID: 11 +startangle_c: 11 +endpose_c: -4 -5 11 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0111 -0.0139 4.3197 +-0.0222 -0.0278 4.3197 +-0.0333 -0.0417 4.3197 +-0.0444 -0.0556 4.3197 +-0.0556 -0.0694 4.3197 +-0.0667 -0.0833 4.3197 +-0.0778 -0.0972 4.3197 +-0.0889 -0.1111 4.3197 +-0.1000 -0.1250 4.3197 +primID: 12 +startangle_c: 11 +endpose_c: -2 -7 11 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0056 -0.0194 4.3197 +-0.0111 -0.0389 4.3197 +-0.0167 -0.0583 4.3197 +-0.0222 -0.0778 4.3197 +-0.0278 -0.0972 4.3197 +-0.0333 -0.1167 4.3197 +-0.0389 -0.1361 4.3197 +-0.0444 -0.1556 4.3197 +-0.0500 -0.1750 4.3197 +primID: 0 +startangle_c: 12 +endpose_c: 0 -1 12 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0028 4.7124 +0.0000 -0.0056 4.7124 +0.0000 -0.0083 4.7124 +0.0000 -0.0111 4.7124 +0.0000 -0.0139 4.7124 +0.0000 -0.0167 4.7124 +0.0000 -0.0194 4.7124 +0.0000 -0.0222 4.7124 +0.0000 -0.0250 4.7124 +primID: 1 +startangle_c: 12 +endpose_c: 0 -8 12 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0222 4.7124 +0.0000 -0.0444 4.7124 +0.0000 -0.0667 4.7124 +0.0000 -0.0889 4.7124 +0.0000 -0.1111 4.7124 +0.0000 -0.1333 4.7124 +0.0000 -0.1556 4.7124 +0.0000 -0.1778 4.7124 +0.0000 -0.2000 4.7124 +primID: 2 +startangle_c: 12 +endpose_c: 0 1 12 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0028 4.7124 +0.0000 0.0056 4.7124 +0.0000 0.0083 4.7124 +0.0000 0.0111 4.7124 +0.0000 0.0139 4.7124 +0.0000 0.0167 4.7124 +0.0000 0.0194 4.7124 +0.0000 0.0222 4.7124 +0.0000 0.0250 4.7124 +primID: 3 +startangle_c: 12 +endpose_c: 1 -8 13 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.7124 +-0.0000 -0.0226 4.7124 +-0.0000 -0.0452 4.7124 +-0.0000 -0.0678 4.7124 +0.0004 -0.0903 4.7612 +0.0023 -0.1128 4.8300 +0.0057 -0.1352 4.8988 +0.0106 -0.1572 4.9675 +0.0171 -0.1789 5.0363 +0.0250 -0.2000 5.1051 +primID: 4 +startangle_c: 12 +endpose_c: -1 -8 11 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.7124 +-0.0000 -0.0226 4.7124 +-0.0000 -0.0452 4.7124 +-0.0000 -0.0678 4.7124 +-0.0004 -0.0903 4.6636 +-0.0023 -0.1128 4.5948 +-0.0057 -0.1352 4.5260 +-0.0106 -0.1572 4.4572 +-0.0171 -0.1789 4.3885 +-0.0250 -0.2000 4.3197 +primID: 5 +startangle_c: 12 +endpose_c: 0 0 13 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0000 4.7560 +0.0000 0.0000 4.7997 +0.0000 0.0000 4.8433 +0.0000 0.0000 4.8869 +0.0000 0.0000 4.9306 +0.0000 0.0000 4.9742 +0.0000 0.0000 5.0178 +0.0000 0.0000 5.0615 +0.0000 0.0000 5.1051 +primID: 6 +startangle_c: 12 +endpose_c: 0 0 11 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0000 4.6688 +0.0000 0.0000 4.6251 +0.0000 0.0000 4.5815 +0.0000 0.0000 4.5379 +0.0000 0.0000 4.4942 +0.0000 0.0000 4.4506 +0.0000 0.0000 4.4070 +0.0000 0.0000 4.3633 +0.0000 0.0000 4.3197 +primID: 7 +startangle_c: 12 +endpose_c: 1 0 12 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0028 0.0000 4.7124 +0.0056 0.0000 4.7124 +0.0083 0.0000 4.7124 +0.0111 0.0000 4.7124 +0.0139 0.0000 4.7124 +0.0167 0.0000 4.7124 +0.0194 0.0000 4.7124 +0.0222 0.0000 4.7124 +0.0250 0.0000 4.7124 +primID: 8 +startangle_c: 12 +endpose_c: -1 0 12 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 4.7124 +-0.0028 0.0000 4.7124 +-0.0056 0.0000 4.7124 +-0.0083 0.0000 4.7124 +-0.0111 0.0000 4.7124 +-0.0139 0.0000 4.7124 +-0.0167 0.0000 4.7124 +-0.0194 0.0000 4.7124 +-0.0222 0.0000 4.7124 +-0.0250 0.0000 4.7124 +primID: 9 +startangle_c: 12 +endpose_c: -1 8 13 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0226 4.7124 +0.0000 0.0452 4.7124 +0.0000 0.0678 4.7124 +-0.0004 0.0903 4.7612 +-0.0023 0.1128 4.8300 +-0.0057 0.1352 4.8988 +-0.0106 0.1572 4.9675 +-0.0171 0.1789 5.0363 +-0.0250 0.2000 5.1051 +primID: 10 +startangle_c: 12 +endpose_c: 1 8 11 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0226 4.7124 +0.0000 0.0452 4.7124 +0.0000 0.0678 4.7124 +0.0004 0.0903 4.6636 +0.0023 0.1128 4.5948 +0.0057 0.1352 4.5260 +0.0106 0.1572 4.4572 +0.0171 0.1789 4.3885 +0.0250 0.2000 4.3197 +primID: 11 +startangle_c: 12 +endpose_c: 1 -8 12 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0028 -0.0222 4.7124 +0.0056 -0.0444 4.7124 +0.0083 -0.0667 4.7124 +0.0111 -0.0889 4.7124 +0.0139 -0.1111 4.7124 +0.0167 -0.1333 4.7124 +0.0194 -0.1556 4.7124 +0.0222 -0.1778 4.7124 +0.0250 -0.2000 4.7124 +primID: 12 +startangle_c: 12 +endpose_c: -1 -8 12 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.7124 +-0.0028 -0.0222 4.7124 +-0.0056 -0.0444 4.7124 +-0.0083 -0.0667 4.7124 +-0.0111 -0.0889 4.7124 +-0.0139 -0.1111 4.7124 +-0.0167 -0.1333 4.7124 +-0.0194 -0.1556 4.7124 +-0.0222 -0.1778 4.7124 +-0.0250 -0.2000 4.7124 +primID: 0 +startangle_c: 13 +endpose_c: 1 -2 13 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0028 -0.0056 5.1051 +0.0056 -0.0111 5.1051 +0.0083 -0.0167 5.1051 +0.0111 -0.0222 5.1051 +0.0139 -0.0278 5.1051 +0.0167 -0.0333 5.1051 +0.0194 -0.0389 5.1051 +0.0222 -0.0444 5.1051 +0.0250 -0.0500 5.1051 +primID: 1 +startangle_c: 13 +endpose_c: 3 -6 13 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0083 -0.0167 5.1051 +0.0167 -0.0333 5.1051 +0.0250 -0.0500 5.1051 +0.0333 -0.0667 5.1051 +0.0417 -0.0833 5.1051 +0.0500 -0.1000 5.1051 +0.0583 -0.1167 5.1051 +0.0667 -0.1333 5.1051 +0.0750 -0.1500 5.1051 +primID: 2 +startangle_c: 13 +endpose_c: -1 2 13 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.1051 +-0.0028 0.0056 5.1051 +-0.0056 0.0111 5.1051 +-0.0083 0.0167 5.1051 +-0.0111 0.0222 5.1051 +-0.0139 0.0278 5.1051 +-0.0167 0.0333 5.1051 +-0.0194 0.0389 5.1051 +-0.0222 0.0444 5.1051 +-0.0250 0.0500 5.1051 +primID: 3 +startangle_c: 13 +endpose_c: 4 -5 14 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0092 -0.0149 5.1354 +0.0189 -0.0296 5.1657 +0.0291 -0.0440 5.1960 +0.0398 -0.0582 5.2263 +0.0509 -0.0722 5.2566 +0.0625 -0.0858 5.2869 +0.0746 -0.0992 5.3172 +0.0871 -0.1123 5.3475 +0.1000 -0.1250 5.3778 +primID: 4 +startangle_c: 13 +endpose_c: 2 -7 12 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0078 -0.0188 5.1051 +0.0156 -0.0377 5.1051 +0.0234 -0.0565 5.1051 +0.0312 -0.0754 5.0860 +0.0379 -0.0946 5.0113 +0.0432 -0.1143 4.9366 +0.0470 -0.1344 4.8618 +0.0492 -0.1546 4.7871 +0.0500 -0.1750 4.7124 +primID: 5 +startangle_c: 13 +endpose_c: 0 0 14 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0000 0.0000 5.1487 +0.0000 0.0000 5.1924 +0.0000 0.0000 5.2360 +0.0000 0.0000 5.2796 +0.0000 0.0000 5.3233 +0.0000 0.0000 5.3669 +0.0000 0.0000 5.4105 +0.0000 0.0000 5.4542 +0.0000 0.0000 5.4978 +primID: 6 +startangle_c: 13 +endpose_c: 0 0 12 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0000 0.0000 5.0615 +0.0000 0.0000 5.0178 +0.0000 0.0000 4.9742 +0.0000 0.0000 4.9306 +0.0000 0.0000 4.8869 +0.0000 0.0000 4.8433 +0.0000 0.0000 4.7997 +0.0000 0.0000 4.7560 +0.0000 0.0000 4.7124 +primID: 7 +startangle_c: 13 +endpose_c: 2 1 13 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0056 0.0028 5.1051 +0.0111 0.0056 5.1051 +0.0167 0.0083 5.1051 +0.0222 0.0111 5.1051 +0.0278 0.0139 5.1051 +0.0333 0.0167 5.1051 +0.0389 0.0194 5.1051 +0.0444 0.0222 5.1051 +0.0500 0.0250 5.1051 +primID: 8 +startangle_c: 13 +endpose_c: -2 -1 13 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.1051 +-0.0056 -0.0028 5.1051 +-0.0111 -0.0056 5.1051 +-0.0167 -0.0083 5.1051 +-0.0222 -0.0111 5.1051 +-0.0278 -0.0139 5.1051 +-0.0333 -0.0167 5.1051 +-0.0389 -0.0194 5.1051 +-0.0444 -0.0222 5.1051 +-0.0500 -0.0250 5.1051 +primID: 9 +startangle_c: 13 +endpose_c: -4 5 14 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.1051 +-0.0092 0.0149 5.1354 +-0.0189 0.0296 5.1657 +-0.0291 0.0440 5.1960 +-0.0398 0.0582 5.2263 +-0.0509 0.0722 5.2566 +-0.0625 0.0858 5.2869 +-0.0746 0.0992 5.3172 +-0.0871 0.1123 5.3475 +-0.1000 0.1250 5.3778 +primID: 10 +startangle_c: 13 +endpose_c: -2 7 12 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.1051 +-0.0078 0.0188 5.1051 +-0.0156 0.0377 5.1051 +-0.0234 0.0565 5.1051 +-0.0312 0.0754 5.0860 +-0.0379 0.0946 5.0113 +-0.0432 0.1143 4.9366 +-0.0470 0.1344 4.8618 +-0.0492 0.1546 4.7871 +-0.0500 0.1750 4.7124 +primID: 11 +startangle_c: 13 +endpose_c: 4 -5 13 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0111 -0.0139 5.1051 +0.0222 -0.0278 5.1051 +0.0333 -0.0417 5.1051 +0.0444 -0.0556 5.1051 +0.0556 -0.0694 5.1051 +0.0667 -0.0833 5.1051 +0.0778 -0.0972 5.1051 +0.0889 -0.1111 5.1051 +0.1000 -0.1250 5.1051 +primID: 12 +startangle_c: 13 +endpose_c: 2 -7 13 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0056 -0.0194 5.1051 +0.0111 -0.0389 5.1051 +0.0167 -0.0583 5.1051 +0.0222 -0.0778 5.1051 +0.0278 -0.0972 5.1051 +0.0333 -0.1167 5.1051 +0.0389 -0.1361 5.1051 +0.0444 -0.1556 5.1051 +0.0500 -0.1750 5.1051 +primID: 0 +startangle_c: 14 +endpose_c: 1 -1 14 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0028 -0.0028 5.4978 +0.0056 -0.0056 5.4978 +0.0083 -0.0083 5.4978 +0.0111 -0.0111 5.4978 +0.0139 -0.0139 5.4978 +0.0167 -0.0167 5.4978 +0.0194 -0.0194 5.4978 +0.0222 -0.0222 5.4978 +0.0250 -0.0250 5.4978 +primID: 1 +startangle_c: 14 +endpose_c: 6 -6 14 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0167 -0.0167 5.4978 +0.0333 -0.0333 5.4978 +0.0500 -0.0500 5.4978 +0.0667 -0.0667 5.4978 +0.0833 -0.0833 5.4978 +0.1000 -0.1000 5.4978 +0.1167 -0.1167 5.4978 +0.1333 -0.1333 5.4978 +0.1500 -0.1500 5.4978 +primID: 2 +startangle_c: 14 +endpose_c: -1 1 14 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.4978 +-0.0028 0.0028 5.4978 +-0.0056 0.0056 5.4978 +-0.0083 0.0083 5.4978 +-0.0111 0.0111 5.4978 +-0.0139 0.0139 5.4978 +-0.0167 0.0167 5.4978 +-0.0194 0.0194 5.4978 +-0.0222 0.0222 5.4978 +-0.0250 0.0250 5.4978 +primID: 3 +startangle_c: 14 +endpose_c: 7 -5 15 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0170 -0.0170 5.4978 +0.0342 -0.0339 5.5275 +0.0522 -0.0500 5.5793 +0.0709 -0.0651 5.6312 +0.0904 -0.0792 5.6830 +0.1107 -0.0923 5.7349 +0.1315 -0.1043 5.7868 +0.1530 -0.1152 5.8386 +0.1750 -0.1250 5.8905 +primID: 4 +startangle_c: 14 +endpose_c: 5 -7 13 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0170 -0.0170 5.4978 +0.0339 -0.0342 5.4681 +0.0500 -0.0522 5.4162 +0.0651 -0.0709 5.3644 +0.0792 -0.0904 5.3125 +0.0923 -0.1107 5.2607 +0.1043 -0.1315 5.2088 +0.1152 -0.1530 5.1569 +0.1250 -0.1750 5.1051 +primID: 5 +startangle_c: 14 +endpose_c: 0 0 15 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0000 0.0000 5.5414 +0.0000 0.0000 5.5851 +0.0000 0.0000 5.6287 +0.0000 0.0000 5.6723 +0.0000 0.0000 5.7160 +0.0000 0.0000 5.7596 +0.0000 0.0000 5.8032 +0.0000 0.0000 5.8469 +0.0000 0.0000 5.8905 +primID: 6 +startangle_c: 14 +endpose_c: 0 0 13 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0000 0.0000 5.4542 +0.0000 0.0000 5.4105 +0.0000 0.0000 5.3669 +0.0000 0.0000 5.3233 +0.0000 0.0000 5.2796 +0.0000 0.0000 5.2360 +0.0000 0.0000 5.1924 +0.0000 0.0000 5.1487 +0.0000 0.0000 5.1051 +primID: 7 +startangle_c: 14 +endpose_c: 1 1 14 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0028 0.0028 5.4978 +0.0056 0.0056 5.4978 +0.0083 0.0083 5.4978 +0.0111 0.0111 5.4978 +0.0139 0.0139 5.4978 +0.0167 0.0167 5.4978 +0.0194 0.0194 5.4978 +0.0222 0.0222 5.4978 +0.0250 0.0250 5.4978 +primID: 8 +startangle_c: 14 +endpose_c: -1 -1 14 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.4978 +-0.0028 -0.0028 5.4978 +-0.0056 -0.0056 5.4978 +-0.0083 -0.0083 5.4978 +-0.0111 -0.0111 5.4978 +-0.0139 -0.0139 5.4978 +-0.0167 -0.0167 5.4978 +-0.0194 -0.0194 5.4978 +-0.0222 -0.0222 5.4978 +-0.0250 -0.0250 5.4978 +primID: 9 +startangle_c: 14 +endpose_c: -7 5 15 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.4978 +-0.0170 0.0170 5.4978 +-0.0342 0.0339 5.5275 +-0.0522 0.0500 5.5793 +-0.0709 0.0651 5.6312 +-0.0904 0.0792 5.6830 +-0.1107 0.0923 5.7349 +-0.1315 0.1043 5.7868 +-0.1530 0.1152 5.8386 +-0.1750 0.1250 5.8905 +primID: 10 +startangle_c: 14 +endpose_c: -5 7 13 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.4978 +-0.0170 0.0170 5.4978 +-0.0339 0.0342 5.4681 +-0.0500 0.0522 5.4162 +-0.0651 0.0709 5.3644 +-0.0792 0.0904 5.3125 +-0.0923 0.1107 5.2607 +-0.1043 0.1315 5.2088 +-0.1152 0.1530 5.1569 +-0.1250 0.1750 5.1051 +primID: 11 +startangle_c: 14 +endpose_c: 7 -5 14 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0194 -0.0139 5.4978 +0.0389 -0.0278 5.4978 +0.0583 -0.0417 5.4978 +0.0778 -0.0556 5.4978 +0.0972 -0.0694 5.4978 +0.1167 -0.0833 5.4978 +0.1361 -0.0972 5.4978 +0.1556 -0.1111 5.4978 +0.1750 -0.1250 5.4978 +primID: 12 +startangle_c: 14 +endpose_c: 5 -7 14 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0139 -0.0194 5.4978 +0.0278 -0.0389 5.4978 +0.0417 -0.0583 5.4978 +0.0556 -0.0778 5.4978 +0.0694 -0.0972 5.4978 +0.0833 -0.1167 5.4978 +0.0972 -0.1361 5.4978 +0.1111 -0.1556 5.4978 +0.1250 -0.1750 5.4978 +primID: 0 +startangle_c: 15 +endpose_c: 2 -1 15 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0056 -0.0028 5.8905 +0.0111 -0.0056 5.8905 +0.0167 -0.0083 5.8905 +0.0222 -0.0111 5.8905 +0.0278 -0.0139 5.8905 +0.0333 -0.0167 5.8905 +0.0389 -0.0194 5.8905 +0.0444 -0.0222 5.8905 +0.0500 -0.0250 5.8905 +primID: 1 +startangle_c: 15 +endpose_c: 6 -3 15 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0167 -0.0083 5.8905 +0.0333 -0.0167 5.8905 +0.0500 -0.0250 5.8905 +0.0667 -0.0333 5.8905 +0.0833 -0.0417 5.8905 +0.1000 -0.0500 5.8905 +0.1167 -0.0583 5.8905 +0.1333 -0.0667 5.8905 +0.1500 -0.0750 5.8905 +primID: 2 +startangle_c: 15 +endpose_c: -2 1 15 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.8905 +-0.0056 0.0028 5.8905 +-0.0111 0.0056 5.8905 +-0.0167 0.0083 5.8905 +-0.0222 0.0111 5.8905 +-0.0278 0.0139 5.8905 +-0.0333 0.0167 5.8905 +-0.0389 0.0194 5.8905 +-0.0444 0.0222 5.8905 +-0.0500 0.0250 5.8905 +primID: 3 +startangle_c: 15 +endpose_c: 5 -4 14 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0149 -0.0092 5.8602 +0.0296 -0.0189 5.8299 +0.0440 -0.0291 5.7996 +0.0582 -0.0398 5.7693 +0.0722 -0.0509 5.7390 +0.0858 -0.0625 5.7087 +0.0992 -0.0746 5.6784 +0.1123 -0.0871 5.6481 +0.1250 -0.1000 5.6178 +primID: 4 +startangle_c: 15 +endpose_c: 7 -2 0 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0188 -0.0078 5.8905 +0.0377 -0.0156 5.8905 +0.0565 -0.0234 5.8905 +0.0754 -0.0312 5.9096 +0.0946 -0.0379 5.9843 +0.1143 -0.0432 6.0590 +0.1344 -0.0470 6.1337 +0.1546 -0.0492 6.2085 +0.1750 -0.0500 6.2832 +primID: 5 +startangle_c: 15 +endpose_c: 0 0 14 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0000 0.0000 5.8469 +0.0000 0.0000 5.8032 +0.0000 0.0000 5.7596 +0.0000 0.0000 5.7160 +0.0000 0.0000 5.6723 +0.0000 0.0000 5.6287 +0.0000 0.0000 5.5851 +0.0000 0.0000 5.5414 +0.0000 0.0000 5.4978 +primID: 6 +startangle_c: 15 +endpose_c: 0 0 0 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0000 0.0000 5.9341 +0.0000 0.0000 5.9778 +0.0000 0.0000 6.0214 +0.0000 0.0000 6.0650 +0.0000 0.0000 6.1087 +0.0000 0.0000 6.1523 +0.0000 0.0000 6.1959 +0.0000 0.0000 6.2396 +0.0000 0.0000 0.0000 +primID: 7 +startangle_c: 15 +endpose_c: -1 -2 15 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.8905 +-0.0028 -0.0056 5.8905 +-0.0056 -0.0111 5.8905 +-0.0083 -0.0167 5.8905 +-0.0111 -0.0222 5.8905 +-0.0139 -0.0278 5.8905 +-0.0167 -0.0333 5.8905 +-0.0194 -0.0389 5.8905 +-0.0222 -0.0444 5.8905 +-0.0250 -0.0500 5.8905 +primID: 8 +startangle_c: 15 +endpose_c: 1 2 15 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0028 0.0056 5.8905 +0.0056 0.0111 5.8905 +0.0083 0.0167 5.8905 +0.0111 0.0222 5.8905 +0.0139 0.0278 5.8905 +0.0167 0.0333 5.8905 +0.0194 0.0389 5.8905 +0.0222 0.0444 5.8905 +0.0250 0.0500 5.8905 +primID: 9 +startangle_c: 15 +endpose_c: -5 4 14 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.8905 +-0.0149 0.0092 5.8602 +-0.0296 0.0189 5.8299 +-0.0440 0.0291 5.7996 +-0.0582 0.0398 5.7693 +-0.0722 0.0509 5.7390 +-0.0858 0.0625 5.7087 +-0.0992 0.0746 5.6784 +-0.1123 0.0871 5.6481 +-0.1250 0.1000 5.6178 +primID: 10 +startangle_c: 15 +endpose_c: -7 2 0 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.8905 +-0.0188 0.0078 5.8905 +-0.0377 0.0156 5.8905 +-0.0565 0.0234 5.8905 +-0.0754 0.0312 5.9096 +-0.0946 0.0379 5.9843 +-0.1143 0.0432 6.0590 +-0.1344 0.0470 6.1337 +-0.1546 0.0492 6.2085 +-0.1750 0.0500 6.2832 +primID: 11 +startangle_c: 15 +endpose_c: 5 -4 15 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0139 -0.0111 5.8905 +0.0278 -0.0222 5.8905 +0.0417 -0.0333 5.8905 +0.0556 -0.0444 5.8905 +0.0694 -0.0556 5.8905 +0.0833 -0.0667 5.8905 +0.0972 -0.0778 5.8905 +0.1111 -0.0889 5.8905 +0.1250 -0.1000 5.8905 +primID: 12 +startangle_c: 15 +endpose_c: 7 -2 15 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0194 -0.0056 5.8905 +0.0389 -0.0111 5.8905 +0.0583 -0.0167 5.8905 +0.0778 -0.0222 5.8905 +0.0972 -0.0278 5.8905 +0.1167 -0.0333 5.8905 +0.1361 -0.0389 5.8905 +0.1556 -0.0444 5.8905 +0.1750 -0.0500 5.8905 diff --git a/navigations/sbpl/matlab/mprim/genmprim.m b/navigations/sbpl/matlab/mprim/genmprim.m new file mode 100755 index 0000000..f959c35 --- /dev/null +++ b/navigations/sbpl/matlab/mprim/genmprim.m @@ -0,0 +1,316 @@ +% /* +% * Copyright (c) 2008, Maxim Likhachev +% * All rights reserved. +% * +% * Redistribution and use in source and binary forms, with or without +% * modification, are permitted provided that the following conditions are met: +% * +% * * Redistributions of source code must retain the above copyright +% * notice, this list of conditions and the following disclaimer. +% * * Redistributions in binary form must reproduce the above copyright +% * notice, this list of conditions and the following disclaimer in the +% * documentation and/or other materials provided with the distribution. +% * * Neither the name of the Carnegie Mellon University nor the names of its +% * contributors may be used to endorse or promote products derived from +% * this software without specific prior written permission. +% * +% * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +% * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +% * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +% * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +% * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +% * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +% * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +% * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +% * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +% * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +% * POSSIBILITY OF SUCH DAMAGE. +% */ + +function[] = genmprim(outfilename) + +% +%generates motion primitives and saves them into file +% +%written by Maxim Likhachev +%--------------------------------------------------- +% + +%defines + +LINESEGMENT_MPRIMS = 1; %set the desired type of motion primitives +UNICYCLE_MPRIMS = 0; + + + +if LINESEGMENT_MPRIMS == 1 + resolution = 0.01; + numberofangles = 32; %preferably a power of 2, definitely multiple of 8 + numberofprimsperangle = 16; + + %multipliers (multiplier is used as costmult*cost) + forwardcostmult = 1; + backwardcostmult = 5; + forwardandturncostmult = 1; + sidestepcostmult = 50; + turninplacecostmult = 50; + + %note, what is shown x,y,theta changes (not absolute numbers) + + %0 degreees + basemprimendpts0_c = zeros(numberofprimsperangle, 4); %x,y,theta,costmult + %x aligned with the heading of the robot, angles are positive + %counterclockwise + %0 theta change + basemprimendpts0_c(1,:) = [1 0 0 forwardcostmult]; + basemprimendpts0_c(2,:) = [4 0 0 forwardcostmult]; + basemprimendpts0_c(3,:) = [8 0 0 forwardcostmult]; + basemprimendpts0_c(4,:) = [6 2 0 sidestepcostmult]; + basemprimendpts0_c(5,:) = [6 -2 0 sidestepcostmult]; + basemprimendpts0_c(6,:) = [2 3 0 sidestepcostmult]; + basemprimendpts0_c(7,:) = [2 -3 0 sidestepcostmult]; + basemprimendpts0_c(8,:) = [-5 0 0 backwardcostmult]; + %1/32 theta change + basemprimendpts0_c(9,:) = [6 2 1 forwardandturncostmult]; + basemprimendpts0_c(10,:) = [6 -2 -1 forwardandturncostmult]; + %2/32 theta change + basemprimendpts0_c(11,:) = [4 3 2 forwardandturncostmult]; + basemprimendpts0_c(12,:) = [4 -3 -2 forwardandturncostmult]; + %turn in place + basemprimendpts0_c(13,:) = [0 0 1 turninplacecostmult]; + basemprimendpts0_c(14,:) = [0 0 -1 turninplacecostmult]; + basemprimendpts0_c(15,:) = [0 0 3 turninplacecostmult]; + basemprimendpts0_c(16,:) = [0 0 -3 turninplacecostmult]; + + %45 degrees + basemprimendpts45_c = zeros(numberofprimsperangle, 4); %x,y,theta,costmult (multiplier is used as costmult*cost) + %x aligned with the heading of the robot, angles are positive + %counterclockwise + %0 theta change + basemprimendpts45_c(1,:) = [1 1 0 forwardcostmult]; + basemprimendpts45_c(2,:) = [3 3 0 forwardcostmult]; + basemprimendpts45_c(3,:) = [6 6 0 forwardcostmult]; + basemprimendpts45_c(4,:) = [2 6 0 sidestepcostmult]; + basemprimendpts45_c(5,:) = [6 2 0 sidestepcostmult]; + basemprimendpts45_c(6,:) = [0 4 0 sidestepcostmult]; + basemprimendpts45_c(7,:) = [4 0 0 sidestepcostmult]; + basemprimendpts45_c(8,:) = [-4 -4 0 backwardcostmult]; + %1/32 theta change + basemprimendpts45_c(9,:) = [2 6 1 forwardandturncostmult]; + basemprimendpts45_c(10,:) = [6 2 -1 forwardandturncostmult]; + %2/32 theta change + basemprimendpts45_c(11,:) = [1 5 2 forwardandturncostmult]; + basemprimendpts45_c(12,:) = [5 1 -2 forwardandturncostmult]; + %turn in place + basemprimendpts45_c(13,:) = [0 0 1 turninplacecostmult]; + basemprimendpts45_c(14,:) = [0 0 -1 turninplacecostmult]; + basemprimendpts45_c(15,:) = [0 0 3 turninplacecostmult]; + basemprimendpts45_c(16,:) = [0 0 -3 turninplacecostmult]; + + %22.5 degrees + basemprimendpts22p5_c = zeros(numberofprimsperangle, 4); %x,y,theta,costmult (multiplier is used as costmult*cost) + %x aligned with the heading of the robot, angles are positive + %counterclockwise + %0 theta change + basemprimendpts22p5_c(1,:) = [2 1 0 forwardcostmult]; + basemprimendpts22p5_c(2,:) = [4 2 0 forwardcostmult]; + basemprimendpts22p5_c(3,:) = [6 3 0 forwardcostmult]; + basemprimendpts22p5_c(4,:) = [4 4 0 sidestepcostmult]; + basemprimendpts22p5_c(5,:) = [6 2 0 sidestepcostmult]; + basemprimendpts22p5_c(6,:) = [0 3 0 sidestepcostmult]; + basemprimendpts22p5_c(7,:) = [4 -1 0 sidestepcostmult]; + basemprimendpts22p5_c(8,:) = [-4 -2 0 backwardcostmult]; + %1/32 theta change + basemprimendpts22p5_c(9,:) = [4 4 1 forwardandturncostmult]; + basemprimendpts22p5_c(10,:) = [6 2 -1 forwardandturncostmult]; + %2/32 theta change + basemprimendpts22p5_c(11,:) = [2 4 2 forwardandturncostmult]; + basemprimendpts22p5_c(12,:) = [6 0 -2 forwardandturncostmult]; + %turn in place + basemprimendpts22p5_c(13,:) = [0 0 1 turninplacecostmult]; + basemprimendpts22p5_c(14,:) = [0 0 -1 turninplacecostmult]; + basemprimendpts22p5_c(15,:) = [0 0 3 turninplacecostmult]; + basemprimendpts22p5_c(16,:) = [0 0 -3 turninplacecostmult]; + + %11.25 degrees + basemprimendpts11p25_c = zeros(numberofprimsperangle, 4); %x,y,theta,costmult (multiplier is used as costmult*cost) + %x aligned with the heading of the robot, angles are positive + %counterclockwise + %0 theta change + basemprimendpts11p25_c(1,:) = [3 1 0 forwardcostmult]; + basemprimendpts11p25_c(2,:) = [6 2 0 forwardcostmult]; + basemprimendpts11p25_c(3,:) = [9 3 0 forwardcostmult]; + basemprimendpts11p25_c(4,:) = [4 3 0 sidestepcostmult]; + basemprimendpts11p25_c(5,:) = [6 0 0 sidestepcostmult]; + basemprimendpts11p25_c(6,:) = [1 3 0 sidestepcostmult]; + basemprimendpts11p25_c(7,:) = [3 -2 0 sidestepcostmult]; + basemprimendpts11p25_c(8,:) = [-6 -2 0 backwardcostmult]; + %1/32 theta change + basemprimendpts11p25_c(9,:) = [4 3 1 forwardandturncostmult]; + basemprimendpts11p25_c(10,:) = [6 0 -1 forwardandturncostmult]; + %2/32 theta change + basemprimendpts11p25_c(11,:) = [2 4 2 forwardandturncostmult]; + basemprimendpts11p25_c(12,:) = [5 -1 -2 forwardandturncostmult]; + %turn in place + basemprimendpts11p25_c(13,:) = [0 0 1 turninplacecostmult]; + basemprimendpts11p25_c(14,:) = [0 0 -1 turninplacecostmult]; + basemprimendpts11p25_c(15,:) = [0 0 3 turninplacecostmult]; + basemprimendpts11p25_c(16,:) = [0 0 -3 turninplacecostmult]; + + %33.75 degrees + basemprimendpts33p75_c = zeros(numberofprimsperangle, 4); %x,y,theta,costmult + %x aligned with the heading of the robot, angles are positive + %counterclockwise + %0 theta change + basemprimendpts33p75_c(1,:) = [3 2 0 forwardcostmult]; + basemprimendpts33p75_c(2,:) = [6 4 0 forwardcostmult]; + basemprimendpts33p75_c(3,:) = [9 6 0 forwardcostmult]; + basemprimendpts33p75_c(4,:) = [4 5 0 sidestepcostmult]; + basemprimendpts33p75_c(5,:) = [6 2 0 sidestepcostmult]; + basemprimendpts33p75_c(6,:) = [0 4 0 sidestepcostmult]; + basemprimendpts33p75_c(7,:) = [3 -2 0 sidestepcostmult]; + basemprimendpts33p75_c(8,:) = [-6 -4 0 backwardcostmult]; + %1/32 theta change + basemprimendpts33p75_c(9,:) = [4 5 1 forwardandturncostmult]; + basemprimendpts33p75_c(10,:) = [6 2 -1 forwardandturncostmult]; + %2/32 theta change + basemprimendpts33p75_c(11,:) = [1 5 2 forwardandturncostmult]; + basemprimendpts33p75_c(12,:) = [3 -2 -2 forwardandturncostmult]; + %turn in place + basemprimendpts33p75_c(13,:) = [0 0 1 turninplacecostmult]; + basemprimendpts33p75_c(14,:) = [0 0 -1 turninplacecostmult]; + basemprimendpts33p75_c(15,:) = [0 0 3 turninplacecostmult]; + basemprimendpts33p75_c(16,:) = [0 0 -3 turninplacecostmult]; + + +elseif UNICYCLE_MPRIMS == 1 + fprintf(1, 'ERROR: unsupported mprims type\n'); + return; +else + fprintf(1, 'ERROR: undefined mprims type\n'); + return; +end; + + +fout = fopen(outfilename, 'w'); + + +%write the header +fprintf(fout, 'resolution_m: %f\n', resolution); +fprintf(fout, 'numberofangles: %d\n', numberofangles); +fprintf(fout, 'totalnumberofprimitives: %d\n', numberofprimsperangle*numberofangles); + +%iterate over angles +for angleind = 1:numberofangles + + figure(1); + hold off; + + text(0, 0, int2str(angleind)); + + %iterate over primitives + for primind = 1:numberofprimsperangle + fprintf(fout, 'primID: %d\n', primind-1); + fprintf(fout, 'startangle_c: %d\n', angleind-1); + + %current angle + currentangle = (angleind-1)*2*pi/numberofangles; + currentangle_36000int = round((angleind-1)*36000/numberofangles); + + %compute which template to use + if (rem(currentangle_36000int, 9000) == 0) + basemprimendpts_c = basemprimendpts0_c(primind,:); + angle = currentangle; + elseif (rem(currentangle_36000int, 4500) == 0) + basemprimendpts_c = basemprimendpts45_c(primind,:); + angle = currentangle - 45*pi/180; + elseif (rem(currentangle_36000int-7875, 9000) == 0) + basemprimendpts_c = basemprimendpts33p75_c(primind,:); + basemprimendpts_c(1) = basemprimendpts33p75_c(primind, 2); %reverse x and y + basemprimendpts_c(2) = basemprimendpts33p75_c(primind, 1); + basemprimendpts_c(3) = -basemprimendpts33p75_c(primind, 3); %reverse the angle as well + angle = currentangle - 78.75*pi/180; + fprintf(1, '78p75\n'); + elseif (rem(currentangle_36000int-6750, 9000) == 0) + basemprimendpts_c = basemprimendpts22p5_c(primind,:); + basemprimendpts_c(1) = basemprimendpts22p5_c(primind, 2); %reverse x and y + basemprimendpts_c(2) = basemprimendpts22p5_c(primind, 1); + basemprimendpts_c(3) = -basemprimendpts22p5_c(primind, 3); %reverse the angle as well + %fprintf(1, '%d %d %d onto %d %d %d\n', basemprimendpts22p5_c(1), basemprimendpts22p5_c(2), basemprimendpts22p5_c(3), ... + % basemprimendpts_c(1), basemprimendpts_c(2), basemprimendpts_c(3)); + angle = currentangle - 67.5*pi/180; + fprintf(1, '67p5\n'); + elseif (rem(currentangle_36000int-5625, 9000) == 0) + basemprimendpts_c = basemprimendpts11p25_c(primind,:); + basemprimendpts_c(1) = basemprimendpts11p25_c(primind, 2); %reverse x and y + basemprimendpts_c(2) = basemprimendpts11p25_c(primind, 1); + basemprimendpts_c(3) = -basemprimendpts11p25_c(primind, 3); %reverse the angle as well + angle = currentangle - 56.25*pi/180; + fprintf(1, '56p25\n'); + elseif (rem(currentangle_36000int-3375, 9000) == 0) + basemprimendpts_c = basemprimendpts33p75_c(primind,:); + angle = currentangle - 33.75*pi/180; + fprintf(1, '33p75\n'); + elseif (rem(currentangle_36000int-2250, 9000) == 0) + basemprimendpts_c = basemprimendpts22p5_c(primind,:); + angle = currentangle - 22.5*pi/180; + fprintf(1, '22p5\n'); + elseif (rem(currentangle_36000int-1125, 9000) == 0) + basemprimendpts_c = basemprimendpts11p25_c(primind,:); + angle = currentangle - 11.25*pi/180; + fprintf(1, '11p25\n'); + else + fprintf(1, 'ERROR: invalid angular resolution. angle = %d\n', currentangle_36000int); + return; + end; + + %now figure out what action will be + baseendpose_c = basemprimendpts_c(1:3); + additionalactioncostmult = basemprimendpts_c(4); + endx_c = round(baseendpose_c(1)*cos(angle) - baseendpose_c(2)*sin(angle)); + endy_c = round(baseendpose_c(1)*sin(angle) + baseendpose_c(2)*cos(angle)); + endtheta_c = rem(angleind - 1 + baseendpose_c(3), numberofangles); + endpose_c = [endx_c endy_c endtheta_c]; + + fprintf(1, 'rotation angle=%f\n', angle*180/pi); + + if baseendpose_c(2) == 0 & baseendpose_c(3) == 0 + %fprintf(1, 'endpose=%d %d %d\n', endpose_c(1), endpose_c(2), endpose_c(3)); + end; + + %generate intermediate poses (remember they are w.r.t 0,0 (and not + %centers of the cells) + numofsamples = 10; + intermcells_m = zeros(numofsamples,3); + if LINESEGMENT_MPRIMS == 1 + startpt = [0 0 currentangle]; + endpt = [endpose_c(1)*resolution endpose_c(2)*resolution ... + rem(angleind - 1 + baseendpose_c(3), numberofangles)*2*pi/numberofangles]; + intermcells_m = zeros(numofsamples,3); + for iind = 1:numofsamples + intermcells_m(iind,:) = [startpt(1) + (endpt(1) - startpt(1))*(iind-1)/(numofsamples-1) ... + startpt(2) + (endpt(2) - startpt(2))*(iind-1)/(numofsamples-1) ... + 0]; + rotation_angle = (baseendpose_c(3) ) * (2*pi/numberofangles); + intermcells_m(iind,3) = rem(startpt(3) + (rotation_angle)*(iind-1)/(numofsamples-1), 2*pi); + end; + end; + + %write out + fprintf(fout, 'endpose_c: %d %d %d\n', endpose_c(1), endpose_c(2), endpose_c(3)); + fprintf(fout, 'additionalactioncostmult: %d\n', additionalactioncostmult); + fprintf(fout, 'intermediateposes: %d\n', size(intermcells_m,1)); + for interind = 1:size(intermcells_m, 1) + fprintf(fout, '%.4f %.4f %.4f\n', intermcells_m(interind,1), intermcells_m(interind,2), intermcells_m(interind,3)); + end; + + plot(intermcells_m(:,1), intermcells_m(:,2)); + text(intermcells_m(numofsamples,1), intermcells_m(numofsamples,2), int2str(endpose_c(3))); + hold on; + + end; + grid; + pause; +end; + +fclose('all'); diff --git a/navigations/sbpl/matlab/mprim/genmprim_unicycle.m b/navigations/sbpl/matlab/mprim/genmprim_unicycle.m new file mode 100755 index 0000000..c0722bb --- /dev/null +++ b/navigations/sbpl/matlab/mprim/genmprim_unicycle.m @@ -0,0 +1,279 @@ +% /* +% * Copyright (c) 2008, Maxim Likhachev +% * All rights reserved. +% * +% * Redistribution and use in source and binary forms, with or without +% * modification, are permitted provided that the following conditions are met: +% * +% * * Redistributions of source code must retain the above copyright +% * notice, this list of conditions and the following disclaimer. +% * * Redistributions in binary form must reproduce the above copyright +% * notice, this list of conditions and the following disclaimer in the +% * documentation and/or other materials provided with the distribution. +% * * Neither the name of the Carnegie Mellon University nor the names of its +% * contributors may be used to endorse or promote products derived from +% * this software without specific prior written permission. +% * +% * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +% * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +% * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +% * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +% * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +% * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +% * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +% * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +% * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +% * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +% * POSSIBILITY OF SUCH DAMAGE. +% */ +function[] = genmprim_unicycle(outfilename) + +% +%generates motion primitives and saves them into file +% +%written by Maxim Likhachev +%--------------------------------------------------- +% + +%defines + +UNICYCLE_MPRIM_16DEGS = 1; + + +if UNICYCLE_MPRIM_16DEGS == 1 + resolution = 0.025; + numberofangles = 16; %preferably a power of 2, definitely multiple of 8 + numberofprimsperangle = 5; + + %multipliers (multiplier is used as costmult*cost) + forwardcostmult = 1; + backwardcostmult = 5; + forwardandturncostmult = 2; + sidestepcostmult = 10; + turninplacecostmult = 5; + + %note, what is shown x,y,theta changes (not absolute numbers) + + %0 degreees + basemprimendpts0_c = zeros(numberofprimsperangle, 4); %x,y,theta,costmult + %x aligned with the heading of the robot, angles are positive + %counterclockwise + %0 theta change + basemprimendpts0_c(1,:) = [1 0 0 forwardcostmult]; + basemprimendpts0_c(2,:) = [8 0 0 forwardcostmult]; + basemprimendpts0_c(3,:) = [-1 0 0 backwardcostmult]; + %1/16 theta change + basemprimendpts0_c(4,:) = [8 1 1 forwardandturncostmult]; + basemprimendpts0_c(5,:) = [8 -1 -1 forwardandturncostmult]; + %turn in place + %basemprimendpts0_c(6,:) = [0 0 1 turninplacecostmult]; + %basemprimendpts0_c(7,:) = [0 0 -1 turninplacecostmult]; + + %45 degrees + basemprimendpts45_c = zeros(numberofprimsperangle, 4); %x,y,theta,costmult (multiplier is used as costmult*cost) + %x aligned with the heading of the robot, angles are positive + %counterclockwise + %0 theta change + basemprimendpts45_c(1,:) = [1 1 0 forwardcostmult]; + basemprimendpts45_c(2,:) = [6 6 0 forwardcostmult]; + basemprimendpts45_c(3,:) = [-1 -1 0 backwardcostmult]; + %1/16 theta change + basemprimendpts45_c(4,:) = [5 7 1 forwardandturncostmult]; + basemprimendpts45_c(5,:) = [7 5 -1 forwardandturncostmult]; + %turn in place + %basemprimendpts45_c(6,:) = [0 0 1 turninplacecostmult]; + %basemprimendpts45_c(7,:) = [0 0 -1 turninplacecostmult]; + + %22.5 degrees + basemprimendpts22p5_c = zeros(numberofprimsperangle, 4); %x,y,theta,costmult (multiplier is used as costmult*cost) + %x aligned with the heading of the robot, angles are positive + %counterclockwise + %0 theta change + basemprimendpts22p5_c(1,:) = [2 1 0 forwardcostmult]; + basemprimendpts22p5_c(2,:) = [6 3 0 forwardcostmult]; + basemprimendpts22p5_c(3,:) = [-2 -1 0 backwardcostmult]; + %1/16 theta change + basemprimendpts22p5_c(4,:) = [5 4 1 forwardandturncostmult]; + basemprimendpts22p5_c(5,:) = [7 2 -1 forwardandturncostmult]; + %turn in place + %basemprimendpts22p5_c(6,:) = [0 0 1 turninplacecostmult]; + %basemprimendpts22p5_c(7,:) = [0 0 -1 turninplacecostmult]; + +else + fprintf(1, 'ERROR: undefined mprims type\n'); + return; +end; + + +fout = fopen(outfilename, 'w'); + + +%write the header +fprintf(fout, 'resolution_m: %f\n', resolution); +fprintf(fout, 'numberofangles: %d\n', numberofangles); +fprintf(fout, 'totalnumberofprimitives: %d\n', numberofprimsperangle*numberofangles); + +%iterate over angles +for angleind = 1:numberofangles + + figure(1); + hold off; + + text(0, 0, int2str(angleind)); + + %iterate over primitives + for primind = 1:numberofprimsperangle + fprintf(fout, 'primID: %d\n', primind-1); + fprintf(fout, 'startangle_c: %d\n', angleind-1); + + %current angle + currentangle = (angleind-1)*2*pi/numberofangles; + currentangle_36000int = round((angleind-1)*36000/numberofangles); + + %compute which template to use + if (rem(currentangle_36000int, 9000) == 0) + basemprimendpts_c = basemprimendpts0_c(primind,:); + angle = currentangle; + elseif (rem(currentangle_36000int, 4500) == 0) + basemprimendpts_c = basemprimendpts45_c(primind,:); + angle = currentangle - 45*pi/180; + elseif (rem(currentangle_36000int-7875, 9000) == 0) + basemprimendpts_c = basemprimendpts33p75_c(primind,:); + basemprimendpts_c(1) = basemprimendpts33p75_c(primind, 2); %reverse x and y + basemprimendpts_c(2) = basemprimendpts33p75_c(primind, 1); + basemprimendpts_c(3) = -basemprimendpts33p75_c(primind, 3); %reverse the angle as well + angle = currentangle - 78.75*pi/180; + fprintf(1, '78p75\n'); + elseif (rem(currentangle_36000int-6750, 9000) == 0) + basemprimendpts_c = basemprimendpts22p5_c(primind,:); + basemprimendpts_c(1) = basemprimendpts22p5_c(primind, 2); %reverse x and y + basemprimendpts_c(2) = basemprimendpts22p5_c(primind, 1); + basemprimendpts_c(3) = -basemprimendpts22p5_c(primind, 3); %reverse the angle as well + %fprintf(1, '%d %d %d onto %d %d %d\n', basemprimendpts22p5_c(1), basemprimendpts22p5_c(2), basemprimendpts22p5_c(3), ... + % basemprimendpts_c(1), basemprimendpts_c(2), basemprimendpts_c(3)); + angle = currentangle - 67.5*pi/180; + fprintf(1, '67p5\n'); + elseif (rem(currentangle_36000int-5625, 9000) == 0) + basemprimendpts_c = basemprimendpts11p25_c(primind,:); + basemprimendpts_c(1) = basemprimendpts11p25_c(primind, 2); %reverse x and y + basemprimendpts_c(2) = basemprimendpts11p25_c(primind, 1); + basemprimendpts_c(3) = -basemprimendpts11p25_c(primind, 3); %reverse the angle as well + angle = currentangle - 56.25*pi/180; + fprintf(1, '56p25\n'); + elseif (rem(currentangle_36000int-3375, 9000) == 0) + basemprimendpts_c = basemprimendpts33p75_c(primind,:); + angle = currentangle - 33.75*pi/180; + fprintf(1, '33p75\n'); + elseif (rem(currentangle_36000int-2250, 9000) == 0) + basemprimendpts_c = basemprimendpts22p5_c(primind,:); + angle = currentangle - 22.5*pi/180; + fprintf(1, '22p5\n'); + elseif (rem(currentangle_36000int-1125, 9000) == 0) + basemprimendpts_c = basemprimendpts11p25_c(primind,:); + angle = currentangle - 11.25*pi/180; + fprintf(1, '11p25\n'); + else + fprintf(1, 'ERROR: invalid angular resolution. angle = %d\n', currentangle_36000int); + return; + end; + + %now figure out what action will be + baseendpose_c = basemprimendpts_c(1:3); + additionalactioncostmult = basemprimendpts_c(4); + endx_c = round(baseendpose_c(1)*cos(angle) - baseendpose_c(2)*sin(angle)); + endy_c = round(baseendpose_c(1)*sin(angle) + baseendpose_c(2)*cos(angle)); + endtheta_c = rem(angleind - 1 + baseendpose_c(3), numberofangles); + endpose_c = [endx_c endy_c endtheta_c]; + + fprintf(1, 'rotation angle=%f\n', angle*180/pi); + + if baseendpose_c(2) == 0 & baseendpose_c(3) == 0 + %fprintf(1, 'endpose=%d %d %d\n', endpose_c(1), endpose_c(2), endpose_c(3)); + end; + + %generate intermediate poses (remember they are w.r.t 0,0 (and not + %centers of the cells) + numofsamples = 10; + intermcells_m = zeros(numofsamples,3); + if UNICYCLE_MPRIM_16DEGS == 1 + startpt = [0 0 currentangle]; + endpt = [endpose_c(1)*resolution endpose_c(2)*resolution ... + rem(angleind - 1 + baseendpose_c(3), numberofangles)*2*pi/numberofangles]; + intermcells_m = zeros(numofsamples,3); + if ((endx_c == 0 & endy_c == 0) | baseendpose_c(3) == 0) %turn in place or move forward + for iind = 1:numofsamples + intermcells_m(iind,:) = [startpt(1) + (endpt(1) - startpt(1))*(iind-1)/(numofsamples-1) ... + startpt(2) + (endpt(2) - startpt(2))*(iind-1)/(numofsamples-1) ... + 0]; + rotation_angle = (baseendpose_c(3) ) * (2*pi/numberofangles); + intermcells_m(iind,3) = rem(startpt(3) + (rotation_angle)*(iind-1)/(numofsamples-1), 2*pi); + + end; + else %unicycle-based move forward or backward + R = [cos(startpt(3)) sin(endpt(3)) - sin(startpt(3)); + sin(startpt(3)) -(cos(endpt(3)) - cos(startpt(3)))]; + S = pinv(R)*[endpt(1) - startpt(1); endpt(2) - startpt(2)]; + l = S(1); + tvoverrv = S(2); + rv = (baseendpose_c(3)*2*pi/numberofangles + l/tvoverrv); + tv = tvoverrv*rv; + + if l < 0 + fprintf(1, 'WARNING: l = %d < 0 -> bad action start/end points\n', l); + l = 0; + end; + %compute rv + %rv = baseendpose_c(3)*2*pi/numberofangles; + %compute tv + %tvx = (endpt(1) - startpt(1))*rv/(sin(endpt(3)) - sin(startpt(3))) + %tvy = -(endpt(2) - startpt(2))*rv/(cos(endpt(3)) - cos(startpt(3))) + %tv = (tvx + tvy)/2.0; + %generate samples + for iind = 1:numofsamples + dt = (iind-1)/(numofsamples-1); + + %dtheta = rv*dt + startpt(3); + %intermcells_m(iind,:) = [startpt(1) + tv/rv*(sin(dtheta) - sin(startpt(3))) ... + % startpt(2) - tv/rv*(cos(dtheta) - cos(startpt(3))) ... + % dtheta]; + + if(dt*tv < l) + intermcells_m(iind,:) = [startpt(1) + dt*tv*cos(startpt(3)) ... + startpt(2) + dt*tv*sin(startpt(3)) ... + startpt(3)]; + else + dtheta = rv*(dt - l/tv) + startpt(3); + intermcells_m(iind,:) = [startpt(1) + l*cos(startpt(3)) + tvoverrv*(sin(dtheta) - sin(startpt(3))) ... + startpt(2) + l*sin(startpt(3)) - tvoverrv*(cos(dtheta) - cos(startpt(3))) ... + dtheta]; + end; + end; + %correct + errorxy = [endpt(1) - intermcells_m(numofsamples,1) ... + endpt(2) - intermcells_m(numofsamples,2)]; + fprintf(1, 'l=%f errx=%f erry=%f\n', l, errorxy(1), errorxy(2)); + interpfactor = [0:1/(numofsamples-1):1]; + intermcells_m(:,1) = intermcells_m(:,1) + errorxy(1)*interpfactor'; + intermcells_m(:,2) = intermcells_m(:,2) + errorxy(2)*interpfactor'; + end; + end; + + %write out + fprintf(fout, 'endpose_c: %d %d %d\n', endpose_c(1), endpose_c(2), endpose_c(3)); + fprintf(fout, 'additionalactioncostmult: %d\n', additionalactioncostmult); + fprintf(fout, 'intermediateposes: %d\n', size(intermcells_m,1)); + for interind = 1:size(intermcells_m, 1) + fprintf(fout, '%.4f %.4f %.4f\n', intermcells_m(interind,1), intermcells_m(interind,2), intermcells_m(interind,3)); + end; + + plot(intermcells_m(:,1), intermcells_m(:,2)); + axis([-0.3 0.3 -0.3 0.3]); + text(intermcells_m(numofsamples,1), intermcells_m(numofsamples,2), int2str(endpose_c(3))); + hold on; + + end; + grid; + pause; +end; + +fclose('all'); diff --git a/navigations/sbpl/matlab/mprim/genmprim_unicycle_circular_non_uniform.m b/navigations/sbpl/matlab/mprim/genmprim_unicycle_circular_non_uniform.m new file mode 100755 index 0000000..a693491 --- /dev/null +++ b/navigations/sbpl/matlab/mprim/genmprim_unicycle_circular_non_uniform.m @@ -0,0 +1,741 @@ +function[] = genmprim_unicycle_circular_non_uniform (outfilename) +% Generates circular motion primitives with min turning radius and saves them into a file. +% For each angle from the list_of_angles array generates a set of 4 forward moving motion primitives +% and 4 symmetric backward moving motion primitives. +% +% This function takes one optional argument - 'outfilename', which specifies +% the location of the output file where motion primitives data is saved. +% If this argiment is omitted, the file name is hardcoded. +% +% The script builds the following types of motion primitives with unique ids for each +% angle from the list_of_angles array: +% +% if has_turn_in_place_prims == 0 +% +% 1 - short forward +% 2 - long forward +% 3 - forward and turn left +% 4 - forward and turn right +% 5 - short backward +% 6 - long backward +% 7 - backward and turn left +% 8 - backward and turn right +% +% if has_turn_in_place_prims == 1 +% +% 1 - short forward +% 2 - long forward +% 3 - forward and turn left +% 4 - forward and turn right +% 5 - turn in place forward +% 6 - short backward +% 7 - long backward +% 8 - backward and turn left +% 9 - backward and turn right +% 10 - turn in place backward +% +% +% Configurarion parameters: +% resolution grid resolution +% errmin max acceptable error for the distance between the endpoint of the motion primitive and the grid node. +% rmin_m min acceptable turning radius im meters +% xmin min x coordinate for the endpoint of the circular motion primitive +% ymin min y coordinate for the endpoint of the circular motion primitive +% xmax max x coordinate for the endpoint of the circular motion primitive +% ymax max y coordinate for the endpoint of the circular motion primitive +% countmax max number of different acceptable (by errmin and rmax) primitives of different lengths to calculate before choosing the best among them. +% +% alfa the angle satisfying the condition: alfa = atan(0.5)= 26.56505118 degrees, 0.46364761 radians +% numberofangles number of angles for which motion primitives are generated +% number_of_base_prims_per_angle number of base (forward moving) primitives per angle +% numberofbaseangles number of base angles: 0, alfa and 45 +% degrees. All other angles are rotations or reflections of these base angles. +% has_backward_prims can be 1 or 0, if 0, backward moving primitives are not generated. +% list_if_angles list of angles for which sets of motion primitives are built +% degrees: 0 26.5651 45.00 63.4349 90.00 116.5651 135.00 153.4349 180.00 206.5651 225.00 243.4349 270.00 296.5651 315.00 333.4349 360.00 +% radians: 0 0.4538 0.7854 1.1170 1.5708 2.0246 2.3562 2.6878 3.1416 3.5954 3.9270 4.2586 4.7124 5.1662 5.4978 5.8294 6.2832 +% +% Cost multipliers (multiplier is used as costmult*cost) +% forwardcostmult cost multiplier for the forward motion +% backwardcostmult cost multiplier for the backward motion +% forwardandturncostmult cost multiplier for the forward-and-turn motion +% backwardandturncostmult cost multiplier for the backward-and-turn motion +% +% This script prints 3 coordinates for each motion primitive: x, y, theta +%%%%% + +fprintf(1, 'genmprim_unicycle_circular_non_uniform\n'); + +% configuration parameters +resolution = 0.1; %0.025; %0.1; +errmin = 0.05; %0.05; +rmin_m = 3.0; %1.0; +rmin_c = rmin_m/resolution; +fprintf(1, 'resolution=%f rmin_m=%f meters rmin_c=%f cells errmin=%f\n', resolution, rmin_m, rmin_c, errmin); + +if nargin < 1 + %outputFile = 0; + basefilename = 'non_uniform_'; + outfilename = generate_file_name(basefilename, resolution, rmin_m, errmin); + fprintf(1, 'outfilename = %s\n', outfilename); +end + +xmin = 0; +ymin = 0; +xmax = 40; +ymax = 40; +countmax = 40; +interm_spacing_m = resolution/2; % Approximate spacing of intermediate poses in meters +interm_spacing_c = interm_spacing_m/resolution; +interm_spacing_rad = 0.05; % Approximate spacing of intermediate poses in radians +fprintf(1, 'xmin=%f xmax=%f ymin=%f ymax=%f\n', xmin, xmax, ymin, ymax); +fprintf(1, 'countmax=%d interm_spacing_m=%f meters interm_spacing_rad=%f radians\n', countmax, interm_spacing_m, interm_spacing_rad); + +numberofangles = 16; +%number_of_base_prims_per_angle = 4; +%max_number_of_prims_per_angle = 8; +numberofbaseangles = 3; % 0, alfa and 45 degrees +has_backward_prims = 1; +has_turn_in_place_prims = 1; +number_of_base_prims_per_angle = 4 + has_turn_in_place_prims; +max_number_of_prims_per_angle = 2 * number_of_base_prims_per_angle; %this is only needed for arrays memory allocations +numberofprimsperangle = (1 + has_backward_prims) * number_of_base_prims_per_angle; % This is the total number of primitives per angle + +totalnumberofprimitives = numberofprimsperangle*numberofangles; +fprintf(1, 'numberofangles=%d number_of_base_prims_per_angle=%d\n', numberofangles, number_of_base_prims_per_angle); +fprintf(1, 'has_backward_prims=%d\n', has_backward_prims); +fprintf(1, 'has_turn_in_place_prims=%d\n', has_turn_in_place_prims); +fprintf(1, 'numberofprimsperangle=%d totalnumberofprimitives=%d\n', numberofprimsperangle, totalnumberofprimitives); + +start_x = 0.0; +start_y = 0.0; + +%multipliers (multiplier is used as costmult*cost) +forwardcostmult = 1; +backwardcostmult = 5; +forwardandturncostmult = 2; +backwardandturncostmult = 3; +turninplacecostmult = 5; + +costmult = [] +if (has_turn_in_place_prims) + costmult = [forwardcostmult, forwardcostmult, forwardandturncostmult, forwardandturncostmult, turninplacecostmult, backwardcostmult, backwardcostmult, backwardandturncostmult, backwardandturncostmult, turninplacecostmult]; +else + costmult = [forwardcostmult, forwardcostmult, forwardandturncostmult, forwardandturncostmult, tbackwardcostmult, backwardcostmult, backwardandturncostmult, backwardandturncostmult]; +end; + +% list of angles increments in discrete units for the end pose of the primitive relative to the start pose +prim_angle_increments = [0, 0, 1, -1]; + +alfa = 26.56505118; +alfa1 = alfa*100000000; +beta = 90 - alfa; +beta1 = beta*100000000; +imax = has_backward_prims + 1; +fprintf(1, 'alfa1=%f beta=%f beta1=%f imax=%d\n', alfa1, beta, beta1, imax); + +%list_of_angles (degrees): 0 26.5651 45.00 63.4349 90.00 116.5651 135.00 153.4349 180.00 206.5651 225.00 243.4349 270.00 296.5651 315.00 333.4349 360.00 +%list_of_angles (radians): 0 0.4538 0.7854 1.1170 1.5708 2.0246 2.3562 2.6878 3.1416 3.5954 3.9270 4.2586 4.7124 5.1662 5.4978 5.8294 6.2832 +fprintf(1, '*******************************\n'); +list_of_angles = zeros(1, numberofangles+1); +list_of_angles(1:2:17) = (0:45:360); +list_of_angles([2 6 10 14]) = list_of_angles([1 5 9 13]) + alfa; +list_of_angles([4 8 12 16]) = list_of_angles([5 9 13 17]) - alfa; +list_of_angles +list_of_angles = list_of_angles .* pi/180; +list_of_angles +fprintf(1, '*******************************\n'); + +fout = fopen(outfilename, 'w'); +%write the header +fprintf(fout, 'resolution_m: %f\n', resolution); +fprintf(fout, 'min_turning_radius_m: %f\n', rmin_m); +fprintf(fout, 'numberofangles: %d\n', numberofangles); +for angleind = 1:numberofangles + fprintf(fout, 'angle:%d %.8f\n', angleind-1, list_of_angles(angleind)); +end; +fprintf(fout, 'totalnumberofprimitives: %d\n', totalnumberofprimitives); + +% Note, what is shown x,y,theta changes (not absolute numbers) x aligned +% with the heading of the robot, angles are positive and counterclockwise + +% Initialize arrays to store acceptable circular primitives before choosing the best among them. +% We only need 3 base sets of primitives for angles 0, alfa and 45 degrees. +primdata = zeros(numberofbaseangles, max_number_of_prims_per_angle, countmax, 8); % startx, starty, starttheta, endx, endy, endtheta, tvoverrv, rv +primcount = zeros(numberofbaseangles, max_number_of_prims_per_angle); +basemprimendpts_c = zeros(numberofbaseangles, numberofprimsperangle, 6); % x_c, y_c, theta_c, costmult, tvoverrv, rv + +% Calculate sets of valid primitives with ids 2,3,4 for base angles 0, alfa and 45 degrees. +% Primitives with id=1 (short forward) will be calculated by re-scaling primitives with id=2 (long forward). +for angleind=1:3 + for primind=2:4 + if (angleind == 1 && primind == 4) + gen_base_prims(angleind, primind, xmin, xmax, -ymax, -ymin); + else + gen_base_prims(angleind, primind, xmin, xmax, ymin, ymax); + end; + end; +end; + +fprintf(1, '\n'); +fprintf(1, 'find best primitives start:\n'); +find_best_prims(); + +fprintf(1, '\n++++++++++++++++++\n'); +fprintf(1, 'start writing primitives to file:\n'); +fprintf(1, '\n'); + +h1f = figure(1); +h1a = axes('parent',h1f); +hold on; + +s = 2.0; %0.6; +xxmin = -s; +xxmax = s; +yymin = -s; +yymax = s; +xt = 5*resolution; +yt = 5*resolution; + +axis equal; +axis([xxmin xxmax yymin yymax]); +%axis([-0.5 0.5 -0.5 0.5]); +set(gca,'XTick', xxmin:xt:xxmax); +set(gca,'YTick',yymin:yt:yymax); +grid on; + +primposes = []; +primsamples = []; +primendangle = []; + +% Iterate over angles +for angleind = 1:numberofangles + fprintf(1, '***************\n'); + fprintf(1, 'angleind=%d\n', angleind-1); + + currentangle = list_of_angles(angleind); + currentangle_36000int = round(currentangle*18000000000/pi); + + fprintf(1, '--------------------\n'); + fprintf(1, 'currentangle=%f currentangle_36000int=%d\n', currentangle, currentangle_36000int); + + numofsamples0 = zeros(numberofprimsperangle); + endPoses_c = zeros(numberofprimsperangle, 3); % x_c, y_c, theta_c + turningradiuses = zeros(numberofprimsperangle); + intermposes_m = []; + intermcells_m_orig = []; %zeros(numofsamples, 3); %x,y,theta + + for primind = 1:numberofprimsperangle %number_of_base_prims_per_angle %[1,3,4] + + fprintf(1, '+++++++++++++++++++++++++++\n'); + fprintf(1, 'primind=%d\n', primind-1); + + %compute which template to use + if (rem(currentangle_36000int, 9000000000) == 0) + mprimendpts_c = basemprimendpts_c(1, primind,:); + angle = currentangle; + turning_radius = mprimendpts_c(5); + rvel = mprimendpts_c(6); + fprintf(1, '0000 angle=%f\n', angle); + elseif (rem(currentangle_36000int, 4500000000) == 0) + mprimendpts_c = basemprimendpts_c(3, primind,:); + angle = currentangle - 45*pi/180; + turning_radius = mprimendpts_c(5); + rvel = mprimendpts_c(6); + fprintf(1, '4500 angle=%f\n', angle); + elseif (rem(currentangle_36000int-beta1, 9000000000) == 0) %6400 + mprimendpts_c = basemprimendpts_c(2, primind,:); + mprimendpts_c(1) = basemprimendpts_c(2, primind,2); %reeverse x and y + mprimendpts_c(2) = basemprimendpts_c(2, primind,1); + mprimendpts_c(3) = -basemprimendpts_c(2, primind,3); %reverse the angle as well + angle = currentangle - beta*pi/180; + turning_radius = -mprimendpts_c(5); + rvel = -mprimendpts_c(6); + fprintf(1, '90-alfa angle=%f\n', angle); + elseif (rem(currentangle_36000int-alfa1, 9000000000) == 0) + mprimendpts_c = basemprimendpts_c(2, primind,:); + angle = currentangle - alfa*pi/180; + turning_radius = mprimendpts_c(5); + rvel = mprimendpts_c(6); + fprintf(1, 'alfa angle=%f\n', angle); + else + fprintf(1, 'ERROR: invalid angular resolution. angle = %d\n', currentangle_36000int); + return; + end; + + [res, turning_radius_center] = generate_intermediate_poses(angleind, primind, currentangle, angle, rvel, turning_radius, mprimendpts_c); + + for ii = 1:numofsamples + intermposes_m(primind, ii, :) = [intermcells_m(primind,ii,1)*resolution intermcells_m(primind,ii,2)*resolution intermcells_m(primind,ii,3)]; % x, y, theta + %intermposes_m_orig(primind, iind, :) = [sgn*intermcells_m_orig(iind,1) sgn*intermcells_m_orig(iind,2) intermcells_m(iind,3)]; % x, y, theta + primposes(angleind, primind, ii, :) = intermposes_m(primind, ii, :); + end; + %pause; + + end; %for primind = 1:numberofprimsperangle + + %output to the mprim file and plot + for primind = 1:numberofprimsperangle + fprintf(fout, 'primID: %d\n', primind-1); + fprintf(fout, 'startangle_c: %d\n', angleind-1); + fprintf(fout, 'endpose_c: %d %d %d\n', endPoses_c(primind,1), endPoses_c(primind,2), endPoses_c(primind,3)); + + additionalcostmult = costmult(primind); + + fprintf(fout, 'additionalactioncostmult: %d\n', additionalcostmult); + fprintf(fout, 'turning_radius: %.4f\n', turningradiuses(primind)); + + numofsamples = numofsamples0(primind); + + fprintf(fout, 'intermediateposes: %d\n', numofsamples); + for interind = 1:numofsamples + fprintf(fout, '%.4f %.4f %.4f\n', intermposes_m(primind,interind,1), intermposes_m(primind,interind,2), intermposes_m(primind,interind,3)); + end; + plot(squeeze(intermposes_m(primind, 1:numofsamples, 1)), squeeze(intermposes_m(primind, 1:numofsamples, 2)), 'r'); + + dl = 0.0; + if (primind == 3) + dl = 0.05; + elseif (primind == 4) + dl = -0.05; + end; + slabel = [int2str(angleind), '-', int2str(primind)]; + %text(intermposes_m(primind,numofsamples,1)+dl, intermposes_m(primind,numofsamples,2)+dl, slabel); + + end; %primid + %pause; +end; %angleid + +%%%%%%%%%%%%%%%%%%%%%%%****************************** + +fprintf(1, '!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!\n'); +fclose('all'); + +function[] = gen_base_prims(angle_ind, prim_ind, xmin0, xmax0, ymin0, ymax0) + + fprintf(1, '\ngen_base_prims: angle_ind=%d prim_ind=%d\n', angle_ind, prim_ind); + angle_incr = prim_angle_increments(prim_ind); + start_theta = list_of_angles(angle_ind); + if (angle_ind == 1 && angle_incr == -1) + end_theta = -list_of_angles(2); + else + end_theta = list_of_angles(angle_ind + angle_incr); + end; + + for i=1:imax + count = 0; + if (i == 1) + xmn0 = xmin0; + xmx0 = xmax0; + ymn0 = ymin0; + ymx0 = ymax0; + prm_ind = prim_ind; + else + xmn0 = -xmax0; + xmx0 = -xmin0; + ymn0 = -ymax0; + ymx0 = -ymin0; + prm_ind = prim_ind + number_of_base_prims_per_angle; %4; + end; + basemprimendpts_c(angle_ind, prm_ind, 3) = angle_incr; + + fprintf(1, '\nangle_ind=%d prm_ind=%d\n', angle_ind, prm_ind); + fprintf(1, 'start_theta=%f end_theta=%f basemprimendpts_c(3)=%f angle_incr=%d\n', start_theta, end_theta, basemprimendpts_c(angle_ind,prim_ind,3), angle_incr); + + %fprintf(1,'xmn0=%f xmx0=%f\n', xmn0,xmx0); + %fprintf(1,'ymn0=%f ymx0=%f\n', ymn0,ymx0); + + for endx_c = xmn0:xmx0 + for endy_c = ymn0:ymx0 + prim_endx_c = endx_c; + prim_endy_c = endy_c; + + if (prim_ind == 3 || prim_ind == 4) + R = [sin(end_theta) - sin(start_theta); cos(start_theta) - cos(end_theta)]; + RT = R'; + B = [prim_endx_c - start_x; prim_endy_c - start_y]; + tvoverrv = pinv(RT*R)*RT*B; + if (abs(tvoverrv) < rmin_c) + continue; + end; + + rv = end_theta - start_theta; + tv = rv*tvoverrv; + err = abs(R*tvoverrv - B); + errxy = norm(err); + + if (errxy < errmin) + fprintf(1, 'count=%d endx_c=%d endy_c=%d errxy=%f tvoverrv=%f rv=%f tv=%f prim_endx_c=%f prim_endy_c=%f\n', count, endx_c, endy_c, errxy, tvoverrv, rv, tv, prim_endx_c, prim_endy_c); + end + else + yy = prim_endx_c*tan(end_theta); + errxy = abs(prim_endy_c - yy); + tvoverrv = sqrt(prim_endx_c*prim_endx_c + yy*yy); + rv = 0.0; + tv = tvoverrv; + % if (errxy < 2*errmin) + % fprintf(1, 'count=%d endx_c=%d endy_c=%d errxy=%f tvoverrv=%f rv=%f tv=%f prim_endx_c=%f prim_endy_c=%f\n', count, endx_c, endy_c, errxy, tvoverrv, rv, tv, prim_endx_c, prim_endy_c); + % end + end; + + if (errxy > errmin) + continue; + end; + + if (count+1 > countmax) + fprintf(1, 'endy: count = %d, countmax = %d\n', count, countmax); + break; + end; + count = count + 1; + + primdata(angle_ind, prm_ind, count, 1) = start_x; + primdata(angle_ind, prm_ind, count, 2) = start_y; + primdata(angle_ind, prm_ind, count, 3) = start_theta; + primdata(angle_ind, prm_ind, count, 4) = prim_endx_c; + primdata(angle_ind, prm_ind, count, 5) = prim_endy_c; + primdata(angle_ind, prm_ind, count, 6) = end_theta; + primdata(angle_ind, prm_ind, count, 7) = tvoverrv; + primdata(angle_ind, prm_ind, count, 8) = rv; + %pause; + end; %for end_y + + if (count+1 > countmax) + fprintf(1, 'endx: count = %d, countmax = %d\n', count, countmax); + break; + end; + + end; %for end_x + primcount(angle_ind, prm_ind) = count; + fprintf(1, 'count=%f\n', primcount(angle_ind, prm_ind)); + + end %for i=1:imax +end + +function[] = find_best_prims() + % First find the motion primitive for angle_ind = 1 and prim_ind = 4 + % with minimal turning radius among selected set of primitives that + % satisfy the given min turning radius and epsilon conditions. + + [rmin0, countmin] = min(abs(primdata(1, 4, 1:primcount(1, 4), 7))); + fprintf(1, 'countmin=%f rmin0=%f\n', countmin, rmin0); + + %Iterate over all saved motion primitives for all angles and for each + %angle find a set of primitives with turning radius closest to the min radius found above. + + rrm = rmin0; + %rrm = 30.0; + %rad = []; + + for angle_id=1:numberofbaseangles + + fprintf(1, '************* angle_id=%f *********\n', angle_id); + + i1 = number_of_base_prims_per_angle + 3; %7; + i2 = number_of_base_prims_per_angle + 4; %8; + + for prim_ind = [3,4,i1,i2] %4:-1:3 + if (has_backward_prims == 0 && prim_ind > number_of_base_prims_per_angle) %>4 + continue; + end + + fprintf(1, '------------- prim_ind=%f -----------\n', prim_ind); + +% [dmin, countmin] = min(abs(abs(primdata(angle_id, prim_ind, 1:primcount(angle_id, prim_ind), 7)) - rmin0)); +% if (angle_id == 1) +% rrm = rmin0; +% elseif (prim_ind == 3) +% rrm = rad(angle_id, 4); +% else +% rrm = rad(angle_id-1, 3); +% end; + fprintf(1, 'rrm=%f\n', rrm); + + fprintf(1, 'primcount(angle_id, prim_ind)=%d\n', primcount(angle_id, prim_ind)); + + [dmin, countmin] = min(abs(abs(primdata(angle_id, prim_ind, 1:primcount(angle_id, prim_ind), 7)) - rrm)); + fprintf(1, 'countmin=%f dmin=%f\n', countmin, dmin); + + tvoverrv = primdata(angle_id, prim_ind, countmin, 7); + %rad(angle_id, prim_ind) = abs(tvoverrv); + + rv = primdata(angle_id, prim_ind, countmin, 6) - primdata(angle_id, prim_ind, countmin, 3); + tv = rv*tvoverrv; + fprintf(1, 'tvoverrv=%f rv=%f tv=%f\n', tvoverrv, rv, tv); + + basemprimendpts_c(angle_id, prim_ind, 1) = primdata(angle_id, prim_ind, countmin, 4); + basemprimendpts_c(angle_id, prim_ind, 2) = primdata(angle_id, prim_ind, countmin, 5); + basemprimendpts_c(angle_id, prim_ind, 5) = primdata(angle_id, prim_ind, countmin, 7); + basemprimendpts_c(angle_id, prim_ind, 6) = primdata(angle_id, prim_ind, countmin, 8); + + fprintf(1, 'basemprimendpts_c=%f %f %f %f %f %f\n', basemprimendpts_c(angle_id, prim_ind, :)); %x, y, angle_incr, costmult,tvoverrv, rv + end; + + for i = 1:imax + %prim_ind = 2; %long forward + prim_ind = 2 + (i-1)*number_of_base_prims_per_angle; %4; + fprintf(1, '------------- prim_ind=%f -----------\n', prim_ind); + i1 = prim_ind+1; + i2 = prim_ind+2; + + x = (basemprimendpts_c(angle_id, i1, 1) + basemprimendpts_c(angle_id, i2, 1))/2; + y = (basemprimendpts_c(angle_id, i1, 2) + basemprimendpts_c(angle_id, i2, 2))/2; + fprintf(1, 'x=%f y=%f primcount=%d\n', x, y, primcount(angle_id, prim_ind)); + + [dmin, countmin] = min(sqrt((primdata(angle_id, prim_ind, 1:primcount(angle_id, prim_ind), 4)-x).^2 + (primdata(angle_id, prim_ind, 1:primcount(angle_id, prim_ind), 5)-y).^2)); + + fprintf(1, 'angle_id=%d prim_ind=%d countmin=%d dmin=%f\n', angle_id, prim_ind, countmin, dmin); + basemprimendpts_c(angle_id, prim_ind, 1) = primdata(angle_id, prim_ind, countmin, 4); + basemprimendpts_c(angle_id, prim_ind, 2) = primdata(angle_id, prim_ind, countmin, 5); + fprintf(1, 'basemprimendpts_c=%f %f %f %f %f %f\n', basemprimendpts_c(angle_id, prim_ind, :)); + + %prim_ind = 1; %short forward + i1 = prim_ind; + prim_ind = prim_ind - 1; + fprintf(1, '------------- prim_ind=%f -----------\n', prim_ind); + x = basemprimendpts_c(angle_id, i1, 1); + y = basemprimendpts_c(angle_id, i1, 2); + d = nonzero_min(abs(x), abs(y)); + basemprimendpts_c(angle_id, prim_ind, 1) = x/d; + basemprimendpts_c(angle_id, prim_ind, 2) = y/d; + fprintf(1, 'basemprimendpts_c=%f %f %f %f %f %f\n', basemprimendpts_c(angle_id, prim_ind, :)); + + %prim_ind = 5; %short forward + if (has_turn_in_place_prims == 1) + prim_ind = 5 + (i-1)*number_of_base_prims_per_angle; + fprintf(1, '------------- prim_ind=%f -----------\n', prim_ind); + basemprimendpts_c(angle_id, prim_ind, 1) = 0.0; + basemprimendpts_c(angle_id, prim_ind, 2) = 0.0; + if (prim_ind == 5) + i1 = prim_ind-2; + else + i1 = prim_ind-1; + end; + basemprimendpts_c(angle_id, prim_ind, 3) = basemprimendpts_c(angle_id, i1, 3); + basemprimendpts_c(angle_id, prim_ind, 5) = 0.0; + basemprimendpts_c(angle_id, prim_ind, 6) = basemprimendpts_c(angle_id, i1, 6); + fprintf(1, 'basemprimendpts_c=%f %f %f %f %f %f\n', basemprimendpts_c(angle_id, prim_ind, :)); + end + end; + end; +end + +%generate intermediate poses (remember they are w.r.t 0,0 (and not centers of the cells) +function[res, turning_radius_center] = generate_intermediate_poses(angleind, primind, currentangle, angle, rvel, turning_radius, mprimendpts_c) + + baseendpose_c = mprimendpts_c(1:3); + endtheta_c = rem(angleind - 1 + baseendpose_c(3), numberofangles); + + fprintf(1,'\n'); + fprintf(1, 'generate_intermediate_poses start\n'); + fprintf(1, 'baseendpose_c: %f %f %f endtheta_c=%d\n', baseendpose_c, endtheta_c); + startpt = [0 0 currentangle]; + + endx_c = round(baseendpose_c(1)*cos(angle) - baseendpose_c(2)*sin(angle)); + endy_c = round(baseendpose_c(1)*sin(angle) + baseendpose_c(2)*cos(angle)); + if (angleind == 1 && endtheta_c == -1) + end_angle = -list_of_angles(2); + else + end_angle = list_of_angles(endtheta_c + 1); + end; + endpt = [endx_c endy_c end_angle]; + + dist_m = sqrt(sum((endpt(1:2) - startpt(1:2)).^2)); + dist_rad = abs(currentangle - end_angle); + fprintf(1, 'currentangle=%f end_angle=%f\n', currentangle, end_angle); + + if (endx_c == 0 && endy_c == 0) + numofsamples = abs(round(dist_rad/interm_spacing_rad)); + else + numofsamples = floor(dist_m/interm_spacing_c) + 1; + end; + %numofsamples = 1 + max(round(dist_m/interm_spacing_m), abs(round(dist_rad/interm_spacing_rad))); + fprintf(1, 'endx_c=%f endy_c=%f endtheta_c=%d turning_radius=%f rvel=%f transformation angle=%f end_angle=%f numofsamples=%d dist_m=%f dist_rad=%f\n', endx_c, endy_c, endtheta_c, turning_radius, rvel, angle*180/pi, end_angle, numofsamples, dist_m, dist_rad); + numofsamples0(primind) = numofsamples; + + if (baseendpose_c(3) == 0) %move forward/backward + for iind = 1:numofsamples + dt = (iind-1)/(numofsamples-1); + intermcells_m(primind, iind,:) = [startpt(1) + (endpt(1) - startpt(1))*dt ... + startpt(2) + (endpt(2) - startpt(2))*dt ... + rem(startpt(3) + (endpt(3) - startpt(3))*dt, 2*pi)]; + end; + res = correct_poses(); + turning_radius_center = 0.0; + elseif (endx_c == 0 && endy_c == 0) %turn in place + for iind = 1:numofsamples + dt = (iind-1)/(numofsamples-1); + dtheta = rvel*dt + startpt(3); + intermcells_m(primind, iind,:) = [0.0 0.0 dtheta]; + end; + res = correct_poses(); + turning_radius_center = 0.0; + else + for iind = 1:numofsamples + dt = (iind-1)/(numofsamples-1); + + dtheta = rvel*dt + startpt(3); + x = startpt(1) + turning_radius*(sin(dtheta) - sin(startpt(3))); + y = startpt(2) + turning_radius*(cos(startpt(3)) - cos(dtheta)); + intermcells_m(primind, iind,:) = [x y dtheta]; +% fprintf(1, 'iind=%d dt=%f x=%f y=%f dtheta=%f %f %f\n', iind, dt, intermcells_m(iind,1), intermcells_m(iind,2), dtheta, x, y); + end; + res = correct_poses(); + [turning_radius_center, arc_len_m, turn_angle] = average_turning_radius(); + end; + %pause; + + k = primind; + endPoses_c(k, :) = [round(endx_c) round(endy_c) round(endtheta_c)]; + turningradiuses(k) = turning_radius*resolution; + turningradiuses_center(k) = turning_radius_center; + + primsamples(angleind, k) = numofsamples; + primendangle(angleind, k) = endtheta_c; + %pause; + + function[turn_rad_aver, arc_len_m, turn_angle] = average_turning_radius() + + turn_angle = 0.0; + turn_rad_aver = 0.0; + arc_len_m = 0.0; + for ind = 1:numofsamples + if (ind > 1) + dx = intermcells_m(primind, ind,1) - intermcells_m(primind, ind-1,1); + dy = intermcells_m(primind, ind,2) - intermcells_m(primind, ind-1,2); + ds = sqrt(dx*dx + dy*dy); + dth = (intermcells_m(primind, ind,3) - intermcells_m(primind, ind-1,3)); + arc_len_m = arc_len_m + ds; + turn_angle = turn_angle + dth; + turn_rad = ds/dth; + turn_rad_aver = turn_rad_aver + abs(turn_rad); + %fprintf(1, 'ind=%d ds=%f dth=%f turn_rad=%f\n', ind, ds, dth, turn_rad); + end; + end + turn_rad_aver = turn_rad_aver/(numofsamples - 1); + turn_angle = abs(turn_angle); + fprintf('arc_len_m = %f turn_angle = %f turn_rad_aver = %f\n', arc_len_m, turn_angle, turn_rad_aver); + end + + %correct intermediate poses using interpolation to place the end point of the motion primitive exactly to the grid node. + function[status] = correct_poses() + + status = true; + %error = [endpt(1) - intermcells_m(primind, numofsamples,1) endpt(2) - intermcells_m(primind, numofsamples,2) endpt(3) - intermcells_m(primind, numofsamples,3)]; + errx = endpt(1) - intermcells_m(primind, numofsamples,1); + erry = endpt(2) - intermcells_m(primind, numofsamples,2); + errth = endpt(3) - intermcells_m(primind, numofsamples,3); + + fprintf(1, '********************\n'); + fprintf(1, 'correction:\n'); + fprintf(1,'numofsamples = %d\n', numofsamples); + fprintf(1, 'startpt(1)=%f startpt(2)=%f startpt(3)=%f\n', startpt(1), startpt(2), startpt(3)); + fprintf(1, 'endpt(1)=%f endpt(2)=%f endpt(3)=%f\n', endpt(1), endpt(2), endpt(3)); + fprintf(1, 'mprimendpts_c(1)=%f mprimendpts_c(2)=%f mprimendpts_c(3)=%f\n', mprimendpts_c(1), mprimendpts_c(2), mprimendpts_c(3)); + + fprintf(1, 'error: dx %f dy %f dtheta %f\n', errx, erry, errth); + + R0 = [sin(end_angle) - sin(startpt(3)); cos(startpt(3)) - cos(end_angle)]; + RT0 = R0'; + B0 = [endpt(1) - start_x; endpt(2) - start_y]; + tr = abs(pinv(RT0*R0)*RT0*B0); + fprintf(1, 'tr = %f\n', tr); + + if (tr > 0 && tr < rmin_m) + fprintf(1, 'WARNING: After interpolation turning radius is less than the specified min!\n'); + status = false; + end; + + interpfactor = 0:1/(numofsamples-1):1; + + %save original motion for display purposes only + for i=1:numofsamples + intermcells_m_orig(primind, i,1) = intermcells_m(primind, i,1); + intermcells_m_orig(primind, i,2) = intermcells_m(primind, i,2); + intermcells_m_orig(primind, i,3) = intermcells_m(primind, i,3); + end; + + %correct intermideate poses using interpolation + for i=1:numofsamples + intermcells_m(primind, i,1) = intermcells_m(primind, i,1) + errx*interpfactor(i); + intermcells_m(primind, i,2) = intermcells_m(primind, i,2) + erry*interpfactor(i); + end; + end +end + +function d = nonzero_min(x,y) + if (x == 0) + d = y; + elseif (y == 0) + d = x; + else + d = min(x, y); + end; +end + +function[x1,y1,theta1] = rotate(x,y,theta,theta0) + x1 = x * cos(theta0) - y * sin(theta0); + y1 = x * sin(theta0) + y * cos(theta0); + + r = [cos(theta/2), 0.0, 0.0, sin(theta/2)]; + q = [cos(theta0/2), 0.0, 0.0, sin(theta0/2)]; + + f(1) = (r(1) * q(1)) - (r(2) * q(2)) - (r(3) * q(3)) - (r(4) * q(4)); + f(2) = (r(1) * q(2)) + (r(2) * q(1)) - (r(3) * q(4)) + (r(4) * q(3)); + f(3) = (r(1) * q(3)) + (r(2) * q(4)) + (r(3) * q(1)) - (r(4) * q(2)); + f(4) = (r(1) * q(4)) - (r(2) * q(3)) + (r(3) * q(2)) + (r(4) * q(1)); + theta1 = 2*atan2(f(4), f(1)); +end + +function[x1,y1,theta1] = rotate_clockwise(x,y,theta,theta0) + + r = [cos(theta/2), 0.0, 0.0, sin(theta/2)]; + q = [cos(theta0/2), 0.0, 0.0, sin(theta0/2)]; + q(4) = -q(4); + theta00 = 2*atan2(q(4), q(1)); + + x1 = x * cos(theta00) - y * sin(theta00); + y1 = x * sin(theta00) + y * cos(theta00); + + f(1) = (r(1) * q(1)) - (r(2) * q(2)) - (r(3) * q(3)) - (r(4) * q(4)); + f(2) = (r(1) * q(2)) + (r(2) * q(1)) - (r(3) * q(4)) + (r(4) * q(3)); + f(3) = (r(1) * q(3)) + (r(2) * q(4)) + (r(3) * q(1)) - (r(4) * q(2)); + f(4) = (r(1) * q(4)) - (r(2) * q(3)) + (r(3) * q(2)) + (r(4) * q(1)); + theta1 = 2*atan2(f(4), f(1)); +end + +function[x1,y1,theta1] = add_origin_and_turn(x,y,theta, x0,y0,theta0) + [x1,y1,theta1] = rotate(x,y,theta,theta0); + x1 = x1 + x0; + y1 = y1 + y0; +end + +function[x1,y1,theta1] = remove_origin_and_turn(x,y,theta, x0,y0,theta0) + x2 = x - x0; + y2 = y - y0; + [x1,y1,theta1] = rotate_clockwise(x2,y2,theta,theta0); +end + +function[x2,y2,theta2] = transform(x0, y0, theta0, start_theta) + [x1,y1,theta1] = add_origin_and_turn(1.0,0.0,0.0, x0,y0,theta0); + x2 = x1 - cos(start_theta); + y2 = y1 - sin(start_theta); + theta2 = theta1; +end + +function[outfilename] = generate_file_name(base_name, res, rmin_m, errmin) + res_s = num2str(res, 2); + res_s = strrep(res_s, '.', ''); + rmin_s = num2str(rmin_m, 2); + rmin_s = strrep(rmin_s, '.', ''); + err_s = num2str(errmin, 2); + err_s = strrep(err_s, '.', ''); + outfilename1 = strcat(base_name, 'res'); + outfilename2 = strcat(outfilename1, res_s); + outfilename1 = strcat(outfilename2, '_rad'); + outfilename2 = strcat(outfilename1, rmin_s); + outfilename1 = strcat(outfilename2, '_err'); + outfilename2 = strcat(outfilename1, err_s); + outfilename = strcat(outfilename2, '.mprim'); +end + +end \ No newline at end of file diff --git a/navigations/sbpl/matlab/mprim/genmprim_unicycleplussideways.m b/navigations/sbpl/matlab/mprim/genmprim_unicycleplussideways.m new file mode 100755 index 0000000..b4f0903 --- /dev/null +++ b/navigations/sbpl/matlab/mprim/genmprim_unicycleplussideways.m @@ -0,0 +1,286 @@ +% /* +% * Copyright (c) 2008, Maxim Likhachev +% * All rights reserved. +% * +% * Redistribution and use in source and binary forms, with or without +% * modification, are permitted provided that the following conditions are met: +% * +% * * Redistributions of source code must retain the above copyright +% * notice, this list of conditions and the following disclaimer. +% * * Redistributions in binary form must reproduce the above copyright +% * notice, this list of conditions and the following disclaimer in the +% * documentation and/or other materials provided with the distribution. +% * * Neither the name of the Carnegie Mellon University nor the names of its +% * contributors may be used to endorse or promote products derived from +% * this software without specific prior written permission. +% * +% * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +% * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +% * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +% * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +% * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +% * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +% * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +% * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +% * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +% * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +% * POSSIBILITY OF SUCH DAMAGE. +% */ +function[] = genmprim_unicycleplussideways(outfilename) + +% +%generates motion primitives and saves them into file +% +%written by Maxim Likhachev +%--------------------------------------------------- +% + +%defines + +UNICYCLE_MPRIM_16DEGS = 1; + + +if UNICYCLE_MPRIM_16DEGS == 1 + resolution = 0.025; + numberofangles = 16; %preferably a power of 2, definitely multiple of 8 + numberofprimsperangle = 9; + + %multipliers (multiplier is used as costmult*cost) + forwardcostmult = 1; + backwardcostmult = 5; + forwardandturncostmult = 3; + sidestepcostmult = 2; + turninplacecostmult = 1; + + %note, what is shown x,y,theta *changes* (that is, dx,dy,dtheta and not absolute numbers) + + %0 degreees + basemprimendpts0_c = zeros(numberofprimsperangle, 4); %x,y,theta,costmult + %angles are positive counterclockwise + %0 theta change + basemprimendpts0_c(1,:) = [1 0 0 forwardcostmult]; + basemprimendpts0_c(2,:) = [8 0 0 forwardcostmult]; + basemprimendpts0_c(3,:) = [-1 0 0 backwardcostmult]; + %1/16 theta change + basemprimendpts0_c(4,:) = [8 1 1 forwardandturncostmult]; + basemprimendpts0_c(5,:) = [8 -1 -1 forwardandturncostmult]; + %turn in place + basemprimendpts0_c(6,:) = [0 0 1 turninplacecostmult]; + basemprimendpts0_c(7,:) = [0 0 -1 turninplacecostmult]; + %sideways maintaining the same heading + basemprimendpts0_c(8,:) = [0 1 0 sidestepcostmult]; + basemprimendpts0_c(9,:) = [0 -1 0 sidestepcostmult]; + + %45 degrees + basemprimendpts45_c = zeros(numberofprimsperangle, 4); %x,y,theta,costmult (multiplier is used as costmult*cost) + %angles are positive counterclockwise + %0 theta change + basemprimendpts45_c(1,:) = [1 1 0 forwardcostmult]; + basemprimendpts45_c(2,:) = [6 6 0 forwardcostmult]; + basemprimendpts45_c(3,:) = [-1 -1 0 backwardcostmult]; + %1/16 theta change + basemprimendpts45_c(4,:) = [5 7 1 forwardandturncostmult]; + basemprimendpts45_c(5,:) = [7 5 -1 forwardandturncostmult]; + %turn in place + basemprimendpts45_c(6,:) = [0 0 1 turninplacecostmult]; + basemprimendpts45_c(7,:) = [0 0 -1 turninplacecostmult]; + %sideways maintaining the same heading + basemprimendpts45_c(8,:) = [-1 1 0 sidestepcostmult]; + basemprimendpts45_c(9,:) = [1 -1 0 sidestepcostmult]; + + %22.5 degrees + basemprimendpts22p5_c = zeros(numberofprimsperangle, 4); %x,y,theta,costmult (multiplier is used as costmult*cost) + %angles are positive counterclockwise + %0 theta change + basemprimendpts22p5_c(1,:) = [2 1 0 forwardcostmult]; + basemprimendpts22p5_c(2,:) = [6 3 0 forwardcostmult]; + basemprimendpts22p5_c(3,:) = [-2 -1 0 backwardcostmult]; + %1/16 theta change + basemprimendpts22p5_c(4,:) = [5 4 1 forwardandturncostmult]; + basemprimendpts22p5_c(5,:) = [7 2 -1 forwardandturncostmult]; + %turn in place + basemprimendpts22p5_c(6,:) = [0 0 1 turninplacecostmult]; + basemprimendpts22p5_c(7,:) = [0 0 -1 turninplacecostmult]; + %sideways maintaining the same heading + basemprimendpts22p5_c(8,:) = [-1 2 0 sidestepcostmult]; + basemprimendpts22p5_c(9,:) = [1 -2 0 sidestepcostmult]; + +else + fprintf(1, 'ERROR: undefined mprims type\n'); + return; +end; + + +fout = fopen(outfilename, 'w'); + + +%write the header +fprintf(fout, 'resolution_m: %f\n', resolution); +fprintf(fout, 'numberofangles: %d\n', numberofangles); +fprintf(fout, 'totalnumberofprimitives: %d\n', numberofprimsperangle*numberofangles); + +%iterate over angles +for angleind = 1:numberofangles + + figure(1); + hold off; + + text(0, 0, int2str(angleind)); + + %iterate over primitives + for primind = 1:numberofprimsperangle + fprintf(fout, 'primID: %d\n', primind-1); + fprintf(fout, 'startangle_c: %d\n', angleind-1); + + %current angle + currentangle = (angleind-1)*2*pi/numberofangles; + currentangle_36000int = round((angleind-1)*36000/numberofangles); + + %compute which template to use + if (rem(currentangle_36000int, 9000) == 0) + basemprimendpts_c = basemprimendpts0_c(primind,:); + angle = currentangle; + fprintf(1, '90\n'); + elseif (rem(currentangle_36000int, 4500) == 0) + basemprimendpts_c = basemprimendpts45_c(primind,:); + angle = currentangle - 45*pi/180; + fprintf(1, '45\n'); + elseif (rem(currentangle_36000int-7875, 9000) == 0) + basemprimendpts_c = basemprimendpts33p75_c(primind,:); + basemprimendpts_c(1) = basemprimendpts33p75_c(primind, 2); %reverse x and y + basemprimendpts_c(2) = basemprimendpts33p75_c(primind, 1); + basemprimendpts_c(3) = -basemprimendpts33p75_c(primind, 3); %reverse the angle as well + angle = currentangle - 78.75*pi/180; + fprintf(1, '78p75\n'); + elseif (rem(currentangle_36000int-6750, 9000) == 0) + basemprimendpts_c = basemprimendpts22p5_c(primind,:); + basemprimendpts_c(1) = basemprimendpts22p5_c(primind, 2); %reverse x and y + basemprimendpts_c(2) = basemprimendpts22p5_c(primind, 1); + basemprimendpts_c(3) = -basemprimendpts22p5_c(primind, 3); %reverse the angle as well + %fprintf(1, '%d %d %d onto %d %d %d\n', basemprimendpts22p5_c(1), basemprimendpts22p5_c(2), basemprimendpts22p5_c(3), ... + % basemprimendpts_c(1), basemprimendpts_c(2), basemprimendpts_c(3)); + angle = currentangle - 67.5*pi/180; + fprintf(1, '67p5\n'); + elseif (rem(currentangle_36000int-5625, 9000) == 0) + basemprimendpts_c = basemprimendpts11p25_c(primind,:); + basemprimendpts_c(1) = basemprimendpts11p25_c(primind, 2); %reverse x and y + basemprimendpts_c(2) = basemprimendpts11p25_c(primind, 1); + basemprimendpts_c(3) = -basemprimendpts11p25_c(primind, 3); %reverse the angle as well + angle = currentangle - 56.25*pi/180; + fprintf(1, '56p25\n'); + elseif (rem(currentangle_36000int-3375, 9000) == 0) + basemprimendpts_c = basemprimendpts33p75_c(primind,:); + angle = currentangle - 33.75*pi/180; + fprintf(1, '33p75\n'); + elseif (rem(currentangle_36000int-2250, 9000) == 0) + basemprimendpts_c = basemprimendpts22p5_c(primind,:); + angle = currentangle - 22.5*pi/180; + fprintf(1, '22p5\n'); + elseif (rem(currentangle_36000int-1125, 9000) == 0) + basemprimendpts_c = basemprimendpts11p25_c(primind,:); + angle = currentangle - 11.25*pi/180; + fprintf(1, '11p25\n'); + else + fprintf(1, 'ERROR: invalid angular resolution. angle = %d\n', currentangle_36000int); + return; + end; + + %now figure out what action will be + baseendpose_c = basemprimendpts_c(1:3); + additionalactioncostmult = basemprimendpts_c(4); + endx_c = round(baseendpose_c(1)*cos(angle) - baseendpose_c(2)*sin(angle)); + endy_c = round(baseendpose_c(1)*sin(angle) + baseendpose_c(2)*cos(angle)); + endtheta_c = rem(angleind - 1 + baseendpose_c(3), numberofangles); + endpose_c = [endx_c endy_c endtheta_c]; + + fprintf(1, 'rotation angle=%f\n', angle*180/pi); + + if baseendpose_c(2) == 0 & baseendpose_c(3) == 0 + %fprintf(1, 'endpose=%d %d %d\n', endpose_c(1), endpose_c(2), endpose_c(3)); + end; + + %generate intermediate poses (remember they are w.r.t 0,0 (and not + %centers of the cells) + numofsamples = 10; + intermcells_m = zeros(numofsamples,3); + if UNICYCLE_MPRIM_16DEGS == 1 + startpt = [0 0 currentangle]; + endpt = [endpose_c(1)*resolution endpose_c(2)*resolution ... + rem(angleind - 1 + baseendpose_c(3), numberofangles)*2*pi/numberofangles]; + intermcells_m = zeros(numofsamples,3); + if ((endx_c == 0 & endy_c == 0) | baseendpose_c(3) == 0) %turn in place or move forward + for iind = 1:numofsamples + intermcells_m(iind,:) = [startpt(1) + (endpt(1) - startpt(1))*(iind-1)/(numofsamples-1) ... + startpt(2) + (endpt(2) - startpt(2))*(iind-1)/(numofsamples-1) ... + 0]; + rotation_angle = (baseendpose_c(3) ) * (2*pi/numberofangles); + intermcells_m(iind,3) = rem(startpt(3) + (rotation_angle)*(iind-1)/(numofsamples-1), 2*pi); + end; + else %unicycle-based move forward or backward + R = [cos(startpt(3)) sin(endpt(3)) - sin(startpt(3)); + sin(startpt(3)) -(cos(endpt(3)) - cos(startpt(3)))]; + S = pinv(R)*[endpt(1) - startpt(1); endpt(2) - startpt(2)]; + l = S(1); + tvoverrv = S(2); + rv = (baseendpose_c(3)*2*pi/numberofangles + l/tvoverrv); + tv = tvoverrv*rv; + + if l < 0 + fprintf(1, 'WARNING: l = %d < 0 -> bad action start/end points\n', l); + l = 0; + end; + %compute rv + %rv = baseendpose_c(3)*2*pi/numberofangles; + %compute tv + %tvx = (endpt(1) - startpt(1))*rv/(sin(endpt(3)) - sin(startpt(3))) + %tvy = -(endpt(2) - startpt(2))*rv/(cos(endpt(3)) - cos(startpt(3))) + %tv = (tvx + tvy)/2.0; + %generate samples + for iind = 1:numofsamples + dt = (iind-1)/(numofsamples-1); + + %dtheta = rv*dt + startpt(3); + %intermcells_m(iind,:) = [startpt(1) + tv/rv*(sin(dtheta) - sin(startpt(3))) ... + % startpt(2) - tv/rv*(cos(dtheta) - cos(startpt(3))) ... + % dtheta]; + + if(dt*tv < l) + intermcells_m(iind,:) = [startpt(1) + dt*tv*cos(startpt(3)) ... + startpt(2) + dt*tv*sin(startpt(3)) ... + startpt(3)]; + else + dtheta = rv*(dt - l/tv) + startpt(3); + intermcells_m(iind,:) = [startpt(1) + l*cos(startpt(3)) + tvoverrv*(sin(dtheta) - sin(startpt(3))) ... + startpt(2) + l*sin(startpt(3)) - tvoverrv*(cos(dtheta) - cos(startpt(3))) ... + dtheta]; + end; + end; + %correct + errorxy = [endpt(1) - intermcells_m(numofsamples,1) ... + endpt(2) - intermcells_m(numofsamples,2)]; + fprintf(1, 'l=%f errx=%f erry=%f\n', l, errorxy(1), errorxy(2)); + interpfactor = [0:1/(numofsamples-1):1]; + intermcells_m(:,1) = intermcells_m(:,1) + errorxy(1)*interpfactor'; + intermcells_m(:,2) = intermcells_m(:,2) + errorxy(2)*interpfactor'; + end; + end; + + %write out + fprintf(fout, 'endpose_c: %d %d %d\n', endpose_c(1), endpose_c(2), endpose_c(3)); + fprintf(fout, 'additionalactioncostmult: %d\n', additionalactioncostmult); + fprintf(fout, 'intermediateposes: %d\n', size(intermcells_m,1)); + for interind = 1:size(intermcells_m, 1) + fprintf(fout, '%.4f %.4f %.4f\n', intermcells_m(interind,1), intermcells_m(interind,2), intermcells_m(interind,3)); + end; + + plot(intermcells_m(:,1), intermcells_m(:,2)); + axis([-0.3 0.3 -0.3 0.3]); + text(intermcells_m(numofsamples,1), intermcells_m(numofsamples,2), int2str(endpose_c(3))); + hold on; + + end; + grid; + pause; +end; + +fclose('all'); diff --git a/navigations/sbpl/matlab/mprim/genmprim_unicycleplussidewaysplusbackturn.m b/navigations/sbpl/matlab/mprim/genmprim_unicycleplussidewaysplusbackturn.m new file mode 100755 index 0000000..320dea2 --- /dev/null +++ b/navigations/sbpl/matlab/mprim/genmprim_unicycleplussidewaysplusbackturn.m @@ -0,0 +1,296 @@ +% /* +% * Copyright (c) 2008, Maxim Likhachev +% * All rights reserved. +% * +% * Redistribution and use in source and binary forms, with or without +% * modification, are permitted provided that the following conditions are met: +% * +% * * Redistributions of source code must retain the above copyright +% * notice, this list of conditions and the following disclaimer. +% * * Redistributions in binary form must reproduce the above copyright +% * notice, this list of conditions and the following disclaimer in the +% * documentation and/or other materials provided with the distribution. +% * * Neither the name of the Carnegie Mellon University nor the names of its +% * contributors may be used to endorse or promote products derived from +% * this software without specific prior written permission. +% * +% * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +% * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +% * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +% * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +% * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +% * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +% * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +% * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +% * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +% * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +% * POSSIBILITY OF SUCH DAMAGE. +% */ +function[] = genmprim_unicycleplussidewaysplusbackturn(outfilename) + +% +%generates motion primitives and saves them into file +% +%written by Maxim Likhachev +%--------------------------------------------------- +% + +%defines + +UNICYCLE_MPRIM_16DEGS = 1; + + +if UNICYCLE_MPRIM_16DEGS == 1 + resolution = 0.025; + numberofangles = 16; %preferably a power of 2, definitely multiple of 8 + numberofprimsperangle = 11; + + %multipliers (multiplier is used as costmult*cost) + forwardcostmult = 1; + backwardcostmult = 5; + forwardandturncostmult = 3; + sidestepcostmult = 2; + turninplacecostmult = 1; + + %note, what is shown x,y,theta *changes* (that is, dx,dy,dtheta and not absolute numbers) + + %0 degreees + basemprimendpts0_c = zeros(numberofprimsperangle, 4); %x,y,theta,costmult + %angles are positive counterclockwise + %0 theta change + basemprimendpts0_c(1,:) = [1 0 0 forwardcostmult]; + basemprimendpts0_c(2,:) = [8 0 0 forwardcostmult]; + basemprimendpts0_c(3,:) = [-1 0 0 backwardcostmult]; + %1/16 theta change + basemprimendpts0_c(4,:) = [8 1 1 forwardandturncostmult]; + basemprimendpts0_c(5,:) = [8 -1 -1 forwardandturncostmult]; + %turn in place + basemprimendpts0_c(6,:) = [0 0 1 turninplacecostmult]; + basemprimendpts0_c(7,:) = [0 0 -1 turninplacecostmult]; + %sideways maintaining the same heading + basemprimendpts0_c(8,:) = [0 1 0 sidestepcostmult]; + basemprimendpts0_c(9,:) = [0 -1 0 sidestepcostmult]; + %1/16 theta change going backward + basemprimendpts0_c(10,:) = [-8 -1 1 backwardcostmult]; + basemprimendpts0_c(11,:) = [-8 1 -1 backwardcostmult]; + + %45 degrees + basemprimendpts45_c = zeros(numberofprimsperangle, 4); %x,y,theta,costmult (multiplier is used as costmult*cost) + %angles are positive counterclockwise + %0 theta change + basemprimendpts45_c(1,:) = [1 1 0 forwardcostmult]; + basemprimendpts45_c(2,:) = [6 6 0 forwardcostmult]; + basemprimendpts45_c(3,:) = [-1 -1 0 backwardcostmult]; + %1/16 theta change + basemprimendpts45_c(4,:) = [5 7 1 forwardandturncostmult]; + basemprimendpts45_c(5,:) = [7 5 -1 forwardandturncostmult]; + %turn in place + basemprimendpts45_c(6,:) = [0 0 1 turninplacecostmult]; + basemprimendpts45_c(7,:) = [0 0 -1 turninplacecostmult]; + %sideways maintaining the same heading + basemprimendpts45_c(8,:) = [-1 1 0 sidestepcostmult]; + basemprimendpts45_c(9,:) = [1 -1 0 sidestepcostmult]; + %1/16 theta change going back + basemprimendpts45_c(10,:) = [-5 -7 1 backwardcostmult]; + basemprimendpts45_c(11,:) = [-7 -5 -1 backwardcostmult]; + + %22.5 degrees + basemprimendpts22p5_c = zeros(numberofprimsperangle, 4); %x,y,theta,costmult (multiplier is used as costmult*cost) + %angles are positive counterclockwise + %0 theta change + basemprimendpts22p5_c(1,:) = [2 1 0 forwardcostmult]; + basemprimendpts22p5_c(2,:) = [6 3 0 forwardcostmult]; + basemprimendpts22p5_c(3,:) = [-2 -1 0 backwardcostmult]; + %1/16 theta change + basemprimendpts22p5_c(4,:) = [5 4 1 forwardandturncostmult]; + basemprimendpts22p5_c(5,:) = [7 2 -1 forwardandturncostmult]; + %turn in place + basemprimendpts22p5_c(6,:) = [0 0 1 turninplacecostmult]; + basemprimendpts22p5_c(7,:) = [0 0 -1 turninplacecostmult]; + %sideways maintaining the same heading + basemprimendpts22p5_c(8,:) = [-1 2 0 sidestepcostmult]; + basemprimendpts22p5_c(9,:) = [1 -2 0 sidestepcostmult]; + %1/16 theta change going back + basemprimendpts22p5_c(10,:) = [-5 -4 1 backwardcostmult]; + basemprimendpts22p5_c(11,:) = [-7 -2 -1 backwardcostmult]; + + +else + fprintf(1, 'ERROR: undefined mprims type\n'); + return; +end; + + +fout = fopen(outfilename, 'w'); + + +%write the header +fprintf(fout, 'resolution_m: %f\n', resolution); +fprintf(fout, 'numberofangles: %d\n', numberofangles); +fprintf(fout, 'totalnumberofprimitives: %d\n', numberofprimsperangle*numberofangles); + +%iterate over angles +for angleind = 1:numberofangles + + figure(1); + hold off; + + text(0, 0, int2str(angleind)); + + %iterate over primitives + for primind = 1:numberofprimsperangle + fprintf(fout, 'primID: %d\n', primind-1); + fprintf(fout, 'startangle_c: %d\n', angleind-1); + + %current angle + currentangle = (angleind-1)*2*pi/numberofangles; + currentangle_36000int = round((angleind-1)*36000/numberofangles); + + %compute which template to use + if (rem(currentangle_36000int, 9000) == 0) + basemprimendpts_c = basemprimendpts0_c(primind,:); + angle = currentangle; + fprintf(1, '90\n'); + elseif (rem(currentangle_36000int, 4500) == 0) + basemprimendpts_c = basemprimendpts45_c(primind,:); + angle = currentangle - 45*pi/180; + fprintf(1, '45\n'); + elseif (rem(currentangle_36000int-7875, 9000) == 0) + basemprimendpts_c = basemprimendpts33p75_c(primind,:); + basemprimendpts_c(1) = basemprimendpts33p75_c(primind, 2); %reverse x and y + basemprimendpts_c(2) = basemprimendpts33p75_c(primind, 1); + basemprimendpts_c(3) = -basemprimendpts33p75_c(primind, 3); %reverse the angle as well + angle = currentangle - 78.75*pi/180; + fprintf(1, '78p75\n'); + elseif (rem(currentangle_36000int-6750, 9000) == 0) + basemprimendpts_c = basemprimendpts22p5_c(primind,:); + basemprimendpts_c(1) = basemprimendpts22p5_c(primind, 2); %reverse x and y + basemprimendpts_c(2) = basemprimendpts22p5_c(primind, 1); + basemprimendpts_c(3) = -basemprimendpts22p5_c(primind, 3); %reverse the angle as well + %fprintf(1, '%d %d %d onto %d %d %d\n', basemprimendpts22p5_c(1), basemprimendpts22p5_c(2), basemprimendpts22p5_c(3), ... + % basemprimendpts_c(1), basemprimendpts_c(2), basemprimendpts_c(3)); + angle = currentangle - 67.5*pi/180; + fprintf(1, '67p5\n'); + elseif (rem(currentangle_36000int-5625, 9000) == 0) + basemprimendpts_c = basemprimendpts11p25_c(primind,:); + basemprimendpts_c(1) = basemprimendpts11p25_c(primind, 2); %reverse x and y + basemprimendpts_c(2) = basemprimendpts11p25_c(primind, 1); + basemprimendpts_c(3) = -basemprimendpts11p25_c(primind, 3); %reverse the angle as well + angle = currentangle - 56.25*pi/180; + fprintf(1, '56p25\n'); + elseif (rem(currentangle_36000int-3375, 9000) == 0) + basemprimendpts_c = basemprimendpts33p75_c(primind,:); + angle = currentangle - 33.75*pi/180; + fprintf(1, '33p75\n'); + elseif (rem(currentangle_36000int-2250, 9000) == 0) + basemprimendpts_c = basemprimendpts22p5_c(primind,:); + angle = currentangle - 22.5*pi/180; + fprintf(1, '22p5\n'); + elseif (rem(currentangle_36000int-1125, 9000) == 0) + basemprimendpts_c = basemprimendpts11p25_c(primind,:); + angle = currentangle - 11.25*pi/180; + fprintf(1, '11p25\n'); + else + fprintf(1, 'ERROR: invalid angular resolution. angle = %d\n', currentangle_36000int); + return; + end; + + %now figure out what action will be + baseendpose_c = basemprimendpts_c(1:3); + additionalactioncostmult = basemprimendpts_c(4); + endx_c = round(baseendpose_c(1)*cos(angle) - baseendpose_c(2)*sin(angle)); + endy_c = round(baseendpose_c(1)*sin(angle) + baseendpose_c(2)*cos(angle)); + endtheta_c = rem(angleind - 1 + baseendpose_c(3), numberofangles); + endpose_c = [endx_c endy_c endtheta_c]; + + fprintf(1, 'rotation angle=%f\n', angle*180/pi); + + if baseendpose_c(2) == 0 & baseendpose_c(3) == 0 + %fprintf(1, 'endpose=%d %d %d\n', endpose_c(1), endpose_c(2), endpose_c(3)); + end; + + %generate intermediate poses (remember they are w.r.t 0,0 (and not + %centers of the cells) + numofsamples = 10; + intermcells_m = zeros(numofsamples,3); + if UNICYCLE_MPRIM_16DEGS == 1 + startpt = [0 0 currentangle]; + endpt = [endpose_c(1)*resolution endpose_c(2)*resolution ... + rem(angleind - 1 + baseendpose_c(3), numberofangles)*2*pi/numberofangles]; + intermcells_m = zeros(numofsamples,3); + if ((endx_c == 0 & endy_c == 0) | baseendpose_c(3) == 0) %turn in place or move forward + for iind = 1:numofsamples + intermcells_m(iind,:) = [startpt(1) + (endpt(1) - startpt(1))*(iind-1)/(numofsamples-1) ... + startpt(2) + (endpt(2) - startpt(2))*(iind-1)/(numofsamples-1) ... + 0]; + rotation_angle = (baseendpose_c(3) ) * (2*pi/numberofangles); + intermcells_m(iind,3) = rem(startpt(3) + (rotation_angle)*(iind-1)/(numofsamples-1), 2*pi); + end; + else %unicycle-based move forward or backward + R = [cos(startpt(3)) sin(endpt(3)) - sin(startpt(3)); + sin(startpt(3)) -(cos(endpt(3)) - cos(startpt(3)))]; + S = pinv(R)*[endpt(1) - startpt(1); endpt(2) - startpt(2)]; + l = S(1); + tvoverrv = S(2); + rv = (baseendpose_c(3)*2*pi/numberofangles + l/tvoverrv); + tv = tvoverrv*rv; + + if ((l < 0 & tv > 0) | (l > 0 & tv < 0)) + fprintf(1, 'WARNING: l = %d < 0 -> bad action start/end points\n', l); + l = 0; + end; + %compute rv + %rv = baseendpose_c(3)*2*pi/numberofangles; + %compute tv + %tvx = (endpt(1) - startpt(1))*rv/(sin(endpt(3)) - sin(startpt(3))) + %tvy = -(endpt(2) - startpt(2))*rv/(cos(endpt(3)) - cos(startpt(3))) + %tv = (tvx + tvy)/2.0; + %generate samples + for iind = 1:numofsamples + dt = (iind-1)/(numofsamples-1); + + %dtheta = rv*dt + startpt(3); + %intermcells_m(iind,:) = [startpt(1) + tv/rv*(sin(dtheta) - sin(startpt(3))) ... + % startpt(2) - tv/rv*(cos(dtheta) - cos(startpt(3))) ... + % dtheta]; + + if(abs(dt*tv) < abs(l)) + intermcells_m(iind,:) = [startpt(1) + dt*tv*cos(startpt(3)) ... + startpt(2) + dt*tv*sin(startpt(3)) ... + startpt(3)]; + else + dtheta = rv*(dt - l/tv) + startpt(3); + intermcells_m(iind,:) = [startpt(1) + l*cos(startpt(3)) + tvoverrv*(sin(dtheta) - sin(startpt(3))) ... + startpt(2) + l*sin(startpt(3)) - tvoverrv*(cos(dtheta) - cos(startpt(3))) ... + dtheta]; + end; + end; + %correct + errorxy = [endpt(1) - intermcells_m(numofsamples,1) ... + endpt(2) - intermcells_m(numofsamples,2)]; + fprintf(1, 'l=%f errx=%f erry=%f\n', l, errorxy(1), errorxy(2)); + interpfactor = [0:1/(numofsamples-1):1]; + intermcells_m(:,1) = intermcells_m(:,1) + errorxy(1)*interpfactor'; + intermcells_m(:,2) = intermcells_m(:,2) + errorxy(2)*interpfactor'; + end; + end; + + %write out + fprintf(fout, 'endpose_c: %d %d %d\n', endpose_c(1), endpose_c(2), endpose_c(3)); + fprintf(fout, 'additionalactioncostmult: %d\n', additionalactioncostmult); + fprintf(fout, 'intermediateposes: %d\n', size(intermcells_m,1)); + for interind = 1:size(intermcells_m, 1) + fprintf(fout, '%.4f %.4f %.4f\n', intermcells_m(interind,1), intermcells_m(interind,2), intermcells_m(interind,3)); + end; + + plot(intermcells_m(:,1), intermcells_m(:,2)); + axis([-0.3 0.3 -0.3 0.3]); + text(intermcells_m(numofsamples,1), intermcells_m(numofsamples,2), int2str(endpose_c(3))); + hold on; + + end; + grid; + pause; +end; + +fclose('all'); diff --git a/navigations/sbpl/matlab/mprim/genmprim_unicycleplussidewaysplusbackturnplusdiag.m b/navigations/sbpl/matlab/mprim/genmprim_unicycleplussidewaysplusbackturnplusdiag.m new file mode 100755 index 0000000..157fe52 --- /dev/null +++ b/navigations/sbpl/matlab/mprim/genmprim_unicycleplussidewaysplusbackturnplusdiag.m @@ -0,0 +1,306 @@ +% /* +% * Copyright (c) 2008, Maxim Likhachev +% * All rights reserved. +% * +% * Redistribution and use in source and binary forms, with or without +% * modification, are permitted provided that the following conditions are met: +% * +% * * Redistributions of source code must retain the above copyright +% * notice, this list of conditions and the following disclaimer. +% * * Redistributions in binary form must reproduce the above copyright +% * notice, this list of conditions and the following disclaimer in the +% * documentation and/or other materials provided with the distribution. +% * * Neither the name of the Carnegie Mellon University nor the names of its +% * contributors may be used to endorse or promote products derived from +% * this software without specific prior written permission. +% * +% * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +% * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +% * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +% * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +% * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +% * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +% * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +% * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +% * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +% * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +% * POSSIBILITY OF SUCH DAMAGE. +% */ +function[] = genmprim_unicycleplussidewaysplusbackturnplusdiag(outfilename) + +% +%generates motion primitives and saves them into file +% +%written by Maxim Likhachev +%--------------------------------------------------- +% + +%defines + +UNICYCLE_MPRIM_16DEGS = 1; + + +if UNICYCLE_MPRIM_16DEGS == 1 + resolution = 0.025; + numberofangles = 16; %preferably a power of 2, definitely multiple of 8 + numberofprimsperangle = 13; + + %multipliers (multiplier is used as costmult*cost) + forwardcostmult = 1; + backwardcostmult = 1; + forwardandturncostmult = 20; % 3; + sidestepcostmult = 2; + turninplacecostmult = 20; + forwarddiagcostmult = 1; %move forward slightly to the left/right without changing heading + + %note, what is shown x,y,theta *changes* (that is, dx,dy,dtheta and not absolute numbers) + + %0 degreees + basemprimendpts0_c = zeros(numberofprimsperangle, 4); %x,y,theta,costmult + %angles are positive counterclockwise + %0 theta change + basemprimendpts0_c(1,:) = [1 0 0 forwardcostmult]; + basemprimendpts0_c(2,:) = [8 0 0 forwardcostmult]; + basemprimendpts0_c(3,:) = [-1 0 0 backwardcostmult]; + %1/16 theta change + basemprimendpts0_c(4,:) = [8 1 1 forwardandturncostmult]; + basemprimendpts0_c(5,:) = [8 -1 -1 forwardandturncostmult]; + %turn in place + basemprimendpts0_c(6,:) = [0 0 1 turninplacecostmult]; + basemprimendpts0_c(7,:) = [0 0 -1 turninplacecostmult]; + %sideways maintaining the same heading + basemprimendpts0_c(8,:) = [0 1 0 sidestepcostmult]; + basemprimendpts0_c(9,:) = [0 -1 0 sidestepcostmult]; + %1/16 theta change going backward + basemprimendpts0_c(10,:) = [-8 -1 1 backwardcostmult]; + basemprimendpts0_c(11,:) = [-8 1 -1 backwardcostmult]; + %forward diagonal + basemprimendpts0_c(12,:) = [8 1 0 forwarddiagcostmult]; + basemprimendpts0_c(13,:) = [8 -1 0 forwarddiagcostmult]; + + %45 degrees + basemprimendpts45_c = zeros(numberofprimsperangle, 4); %x,y,theta,costmult (multiplier is used as costmult*cost) + %angles are positive counterclockwise + %0 theta change + basemprimendpts45_c(1,:) = [1 1 0 forwardcostmult]; + basemprimendpts45_c(2,:) = [6 6 0 forwardcostmult]; + basemprimendpts45_c(3,:) = [-1 -1 0 backwardcostmult]; + %1/16 theta change + basemprimendpts45_c(4,:) = [5 7 1 forwardandturncostmult]; + basemprimendpts45_c(5,:) = [7 5 -1 forwardandturncostmult]; + %turn in place + basemprimendpts45_c(6,:) = [0 0 1 turninplacecostmult]; + basemprimendpts45_c(7,:) = [0 0 -1 turninplacecostmult]; + %sideways maintaining the same heading + basemprimendpts45_c(8,:) = [-1 1 0 sidestepcostmult]; + basemprimendpts45_c(9,:) = [1 -1 0 sidestepcostmult]; + %1/16 theta change going back + basemprimendpts45_c(10,:) = [-5 -7 1 backwardcostmult]; + basemprimendpts45_c(11,:) = [-7 -5 -1 backwardcostmult]; + %forward diagonal + basemprimendpts45_c(12,:) = [5 7 0 forwarddiagcostmult]; + basemprimendpts45_c(13,:) = [7 5 0 forwarddiagcostmult]; + + %22.5 degrees + basemprimendpts22p5_c = zeros(numberofprimsperangle, 4); %x,y,theta,costmult (multiplier is used as costmult*cost) + %angles are positive counterclockwise + %0 theta change + basemprimendpts22p5_c(1,:) = [2 1 0 forwardcostmult]; + basemprimendpts22p5_c(2,:) = [6 3 0 forwardcostmult]; + basemprimendpts22p5_c(3,:) = [-2 -1 0 backwardcostmult]; + %1/16 theta change + basemprimendpts22p5_c(4,:) = [5 4 1 forwardandturncostmult]; + basemprimendpts22p5_c(5,:) = [7 2 -1 forwardandturncostmult]; + %turn in place + basemprimendpts22p5_c(6,:) = [0 0 1 turninplacecostmult]; + basemprimendpts22p5_c(7,:) = [0 0 -1 turninplacecostmult]; + %sideways maintaining the same heading + basemprimendpts22p5_c(8,:) = [-1 2 0 sidestepcostmult]; + basemprimendpts22p5_c(9,:) = [1 -2 0 sidestepcostmult]; + %1/16 theta change going back + basemprimendpts22p5_c(10,:) = [-5 -4 1 backwardcostmult]; + basemprimendpts22p5_c(11,:) = [-7 -2 -1 backwardcostmult]; + %forward diagonal + basemprimendpts22p5_c(12,:) = [5 4 0 forwarddiagcostmult]; + basemprimendpts22p5_c(13,:) = [7 2 0 forwarddiagcostmult]; + + +else + fprintf(1, 'ERROR: undefined mprims type\n'); + return; +end; + + +fout = fopen(outfilename, 'w'); + + +%write the header +fprintf(fout, 'resolution_m: %f\n', resolution); +fprintf(fout, 'numberofangles: %d\n', numberofangles); +fprintf(fout, 'totalnumberofprimitives: %d\n', numberofprimsperangle*numberofangles); + +%iterate over angles +for angleind = 1:numberofangles + + figure(1); + hold off; + + text(0, 0, int2str(angleind)); + + %iterate over primitives + for primind = 1:numberofprimsperangle + fprintf(fout, 'primID: %d\n', primind-1); + fprintf(fout, 'startangle_c: %d\n', angleind-1); + + %current angle + currentangle = (angleind-1)*2*pi/numberofangles; + currentangle_36000int = round((angleind-1)*36000/numberofangles); + + %compute which template to use + if (rem(currentangle_36000int, 9000) == 0) + basemprimendpts_c = basemprimendpts0_c(primind,:); + angle = currentangle; + fprintf(1, '90\n'); + elseif (rem(currentangle_36000int, 4500) == 0) + basemprimendpts_c = basemprimendpts45_c(primind,:); + angle = currentangle - 45*pi/180; + fprintf(1, '45\n'); + elseif (rem(currentangle_36000int-7875, 9000) == 0) + basemprimendpts_c = basemprimendpts33p75_c(primind,:); + basemprimendpts_c(1) = basemprimendpts33p75_c(primind, 2); %reverse x and y + basemprimendpts_c(2) = basemprimendpts33p75_c(primind, 1); + basemprimendpts_c(3) = -basemprimendpts33p75_c(primind, 3); %reverse the angle as well + angle = currentangle - 78.75*pi/180; + fprintf(1, '78p75\n'); + elseif (rem(currentangle_36000int-6750, 9000) == 0) + basemprimendpts_c = basemprimendpts22p5_c(primind,:); + basemprimendpts_c(1) = basemprimendpts22p5_c(primind, 2); %reverse x and y + basemprimendpts_c(2) = basemprimendpts22p5_c(primind, 1); + basemprimendpts_c(3) = -basemprimendpts22p5_c(primind, 3); %reverse the angle as well + %fprintf(1, '%d %d %d onto %d %d %d\n', basemprimendpts22p5_c(1), basemprimendpts22p5_c(2), basemprimendpts22p5_c(3), ... + % basemprimendpts_c(1), basemprimendpts_c(2), basemprimendpts_c(3)); + angle = currentangle - 67.5*pi/180; + fprintf(1, '67p5\n'); + elseif (rem(currentangle_36000int-5625, 9000) == 0) + basemprimendpts_c = basemprimendpts11p25_c(primind,:); + basemprimendpts_c(1) = basemprimendpts11p25_c(primind, 2); %reverse x and y + basemprimendpts_c(2) = basemprimendpts11p25_c(primind, 1); + basemprimendpts_c(3) = -basemprimendpts11p25_c(primind, 3); %reverse the angle as well + angle = currentangle - 56.25*pi/180; + fprintf(1, '56p25\n'); + elseif (rem(currentangle_36000int-3375, 9000) == 0) + basemprimendpts_c = basemprimendpts33p75_c(primind,:); + angle = currentangle - 33.75*pi/180; + fprintf(1, '33p75\n'); + elseif (rem(currentangle_36000int-2250, 9000) == 0) + basemprimendpts_c = basemprimendpts22p5_c(primind,:); + angle = currentangle - 22.5*pi/180; + fprintf(1, '22p5\n'); + elseif (rem(currentangle_36000int-1125, 9000) == 0) + basemprimendpts_c = basemprimendpts11p25_c(primind,:); + angle = currentangle - 11.25*pi/180; + fprintf(1, '11p25\n'); + else + fprintf(1, 'ERROR: invalid angular resolution. angle = %d\n', currentangle_36000int); + return; + end; + + %now figure out what action will be + baseendpose_c = basemprimendpts_c(1:3); + additionalactioncostmult = basemprimendpts_c(4); + endx_c = round(baseendpose_c(1)*cos(angle) - baseendpose_c(2)*sin(angle)); + endy_c = round(baseendpose_c(1)*sin(angle) + baseendpose_c(2)*cos(angle)); + endtheta_c = rem(angleind - 1 + baseendpose_c(3), numberofangles); + endpose_c = [endx_c endy_c endtheta_c]; + + fprintf(1, 'rotation angle=%f\n', angle*180/pi); + + if baseendpose_c(2) == 0 & baseendpose_c(3) == 0 + %fprintf(1, 'endpose=%d %d %d\n', endpose_c(1), endpose_c(2), endpose_c(3)); + end; + + %generate intermediate poses (remember they are w.r.t 0,0 (and not + %centers of the cells) + numofsamples = 10; + intermcells_m = zeros(numofsamples,3); + if UNICYCLE_MPRIM_16DEGS == 1 + startpt = [0 0 currentangle]; + endpt = [endpose_c(1)*resolution endpose_c(2)*resolution ... + rem(angleind - 1 + baseendpose_c(3), numberofangles)*2*pi/numberofangles]; + intermcells_m = zeros(numofsamples,3); + if ((endx_c == 0 & endy_c == 0) | baseendpose_c(3) == 0) %turn in place or move forward + for iind = 1:numofsamples + intermcells_m(iind,:) = [startpt(1) + (endpt(1) - startpt(1))*(iind-1)/(numofsamples-1) ... + startpt(2) + (endpt(2) - startpt(2))*(iind-1)/(numofsamples-1) ... + 0]; + rotation_angle = (baseendpose_c(3) ) * (2*pi/numberofangles); + intermcells_m(iind,3) = rem(startpt(3) + (rotation_angle)*(iind-1)/(numofsamples-1), 2*pi); + end; + else %unicycle-based move forward or backward + R = [cos(startpt(3)) sin(endpt(3)) - sin(startpt(3)); + sin(startpt(3)) -(cos(endpt(3)) - cos(startpt(3)))]; + S = pinv(R)*[endpt(1) - startpt(1); endpt(2) - startpt(2)]; + l = S(1); + tvoverrv = S(2); + rv = (baseendpose_c(3)*2*pi/numberofangles + l/tvoverrv); + tv = tvoverrv*rv; + + if ((l < 0 & tv > 0) | (l > 0 & tv < 0)) + fprintf(1, 'WARNING: l = %d < 0 -> bad action start/end points\n', l); + l = 0; + end; + %compute rv + %rv = baseendpose_c(3)*2*pi/numberofangles; + %compute tv + %tvx = (endpt(1) - startpt(1))*rv/(sin(endpt(3)) - sin(startpt(3))) + %tvy = -(endpt(2) - startpt(2))*rv/(cos(endpt(3)) - cos(startpt(3))) + %tv = (tvx + tvy)/2.0; + %generate samples + for iind = 1:numofsamples + dt = (iind-1)/(numofsamples-1); + + %dtheta = rv*dt + startpt(3); + %intermcells_m(iind,:) = [startpt(1) + tv/rv*(sin(dtheta) - sin(startpt(3))) ... + % startpt(2) - tv/rv*(cos(dtheta) - cos(startpt(3))) ... + % dtheta]; + + if(abs(dt*tv) < abs(l)) + intermcells_m(iind,:) = [startpt(1) + dt*tv*cos(startpt(3)) ... + startpt(2) + dt*tv*sin(startpt(3)) ... + startpt(3)]; + else + dtheta = rv*(dt - l/tv) + startpt(3); + intermcells_m(iind,:) = [startpt(1) + l*cos(startpt(3)) + tvoverrv*(sin(dtheta) - sin(startpt(3))) ... + startpt(2) + l*sin(startpt(3)) - tvoverrv*(cos(dtheta) - cos(startpt(3))) ... + dtheta]; + end; + end; + %correct + errorxy = [endpt(1) - intermcells_m(numofsamples,1) ... + endpt(2) - intermcells_m(numofsamples,2)]; + fprintf(1, 'l=%f errx=%f erry=%f\n', l, errorxy(1), errorxy(2)); + interpfactor = [0:1/(numofsamples-1):1]; + intermcells_m(:,1) = intermcells_m(:,1) + errorxy(1)*interpfactor'; + intermcells_m(:,2) = intermcells_m(:,2) + errorxy(2)*interpfactor'; + end; + end; + + %write out + fprintf(fout, 'endpose_c: %d %d %d\n', endpose_c(1), endpose_c(2), endpose_c(3)); + fprintf(fout, 'additionalactioncostmult: %d\n', additionalactioncostmult); + fprintf(fout, 'intermediateposes: %d\n', size(intermcells_m,1)); + for interind = 1:size(intermcells_m, 1) + fprintf(fout, '%.4f %.4f %.4f\n', intermcells_m(interind,1), intermcells_m(interind,2), intermcells_m(interind,3)); + end; + + plot(intermcells_m(:,1), intermcells_m(:,2)); + axis([-0.3 0.3 -0.3 0.3]); + text(intermcells_m(numofsamples,1), intermcells_m(numofsamples,2), int2str(endpose_c(3))); + hold on; + + end; + grid; + pause; +end; + +fclose('all'); diff --git a/navigations/sbpl/matlab/mprim/mprim_unic_sideback.mprim b/navigations/sbpl/matlab/mprim/mprim_unic_sideback.mprim new file mode 100755 index 0000000..e74eee1 --- /dev/null +++ b/navigations/sbpl/matlab/mprim/mprim_unic_sideback.mprim @@ -0,0 +1,2643 @@ +resolution_m: 0.025000 +numberofangles: 16 +totalnumberofprimitives: 176 +primID: 0 +startangle_c: 0 +endpose_c: 1 0 0 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0028 0.0000 0.0000 +0.0056 0.0000 0.0000 +0.0083 0.0000 0.0000 +0.0111 0.0000 0.0000 +0.0139 0.0000 0.0000 +0.0167 0.0000 0.0000 +0.0194 0.0000 0.0000 +0.0222 0.0000 0.0000 +0.0250 0.0000 0.0000 +primID: 1 +startangle_c: 0 +endpose_c: 8 0 0 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0222 0.0000 0.0000 +0.0444 0.0000 0.0000 +0.0667 0.0000 0.0000 +0.0889 0.0000 0.0000 +0.1111 0.0000 0.0000 +0.1333 0.0000 0.0000 +0.1556 0.0000 0.0000 +0.1778 0.0000 0.0000 +0.2000 0.0000 0.0000 +primID: 2 +startangle_c: 0 +endpose_c: -1 0 0 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 0.0000 +-0.0028 0.0000 0.0000 +-0.0056 0.0000 0.0000 +-0.0083 0.0000 0.0000 +-0.0111 0.0000 0.0000 +-0.0139 0.0000 0.0000 +-0.0167 0.0000 0.0000 +-0.0194 0.0000 0.0000 +-0.0222 0.0000 0.0000 +-0.0250 0.0000 0.0000 +primID: 3 +startangle_c: 0 +endpose_c: 8 1 1 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0226 -0.0000 0.0000 +0.0452 -0.0000 0.0000 +0.0678 -0.0000 0.0000 +0.0903 0.0004 0.0488 +0.1128 0.0023 0.1176 +0.1352 0.0057 0.1864 +0.1572 0.0106 0.2551 +0.1789 0.0171 0.3239 +0.2000 0.0250 0.3927 +primID: 4 +startangle_c: 0 +endpose_c: 8 -1 -1 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0226 0.0000 0.0000 +0.0452 0.0000 0.0000 +0.0678 0.0000 0.0000 +0.0903 -0.0004 -0.0488 +0.1128 -0.0023 -0.1176 +0.1352 -0.0057 -0.1864 +0.1572 -0.0106 -0.2551 +0.1789 -0.0171 -0.3239 +0.2000 -0.0250 -0.3927 +primID: 5 +startangle_c: 0 +endpose_c: 0 0 1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0000 0.0000 0.0436 +0.0000 0.0000 0.0873 +0.0000 0.0000 0.1309 +0.0000 0.0000 0.1745 +0.0000 0.0000 0.2182 +0.0000 0.0000 0.2618 +0.0000 0.0000 0.3054 +0.0000 0.0000 0.3491 +0.0000 0.0000 0.3927 +primID: 6 +startangle_c: 0 +endpose_c: 0 0 -1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0000 0.0000 -0.0436 +0.0000 0.0000 -0.0873 +0.0000 0.0000 -0.1309 +0.0000 0.0000 -0.1745 +0.0000 0.0000 -0.2182 +0.0000 0.0000 -0.2618 +0.0000 0.0000 -0.3054 +0.0000 0.0000 -0.3491 +0.0000 0.0000 -0.3927 +primID: 7 +startangle_c: 0 +endpose_c: 0 1 0 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0000 0.0028 0.0000 +0.0000 0.0056 0.0000 +0.0000 0.0083 0.0000 +0.0000 0.0111 0.0000 +0.0000 0.0139 0.0000 +0.0000 0.0167 0.0000 +0.0000 0.0194 0.0000 +0.0000 0.0222 0.0000 +0.0000 0.0250 0.0000 +primID: 8 +startangle_c: 0 +endpose_c: 0 -1 0 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0000 -0.0028 0.0000 +0.0000 -0.0056 0.0000 +0.0000 -0.0083 0.0000 +0.0000 -0.0111 0.0000 +0.0000 -0.0139 0.0000 +0.0000 -0.0167 0.0000 +0.0000 -0.0194 0.0000 +0.0000 -0.0222 0.0000 +0.0000 -0.0250 0.0000 +primID: 9 +startangle_c: 0 +endpose_c: -8 -1 1 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 0.0000 +-0.0226 0.0000 0.0000 +-0.0452 0.0000 0.0000 +-0.0678 0.0000 0.0000 +-0.0903 -0.0004 0.0488 +-0.1128 -0.0023 0.1176 +-0.1352 -0.0057 0.1864 +-0.1572 -0.0106 0.2551 +-0.1789 -0.0171 0.3239 +-0.2000 -0.0250 0.3927 +primID: 10 +startangle_c: 0 +endpose_c: -8 1 -1 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 0.0000 +-0.0226 -0.0000 0.0000 +-0.0452 -0.0000 0.0000 +-0.0678 -0.0000 0.0000 +-0.0903 0.0004 -0.0488 +-0.1128 0.0023 -0.1176 +-0.1352 0.0057 -0.1864 +-0.1572 0.0106 -0.2551 +-0.1789 0.0171 -0.3239 +-0.2000 0.0250 -0.3927 +primID: 0 +startangle_c: 1 +endpose_c: 2 1 1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0056 0.0028 0.3927 +0.0111 0.0056 0.3927 +0.0167 0.0083 0.3927 +0.0222 0.0111 0.3927 +0.0278 0.0139 0.3927 +0.0333 0.0167 0.3927 +0.0389 0.0194 0.3927 +0.0444 0.0222 0.3927 +0.0500 0.0250 0.3927 +primID: 1 +startangle_c: 1 +endpose_c: 6 3 1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0167 0.0083 0.3927 +0.0333 0.0167 0.3927 +0.0500 0.0250 0.3927 +0.0667 0.0333 0.3927 +0.0833 0.0417 0.3927 +0.1000 0.0500 0.3927 +0.1167 0.0583 0.3927 +0.1333 0.0667 0.3927 +0.1500 0.0750 0.3927 +primID: 2 +startangle_c: 1 +endpose_c: -2 -1 1 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 0.3927 +-0.0056 -0.0028 0.3927 +-0.0111 -0.0056 0.3927 +-0.0167 -0.0083 0.3927 +-0.0222 -0.0111 0.3927 +-0.0278 -0.0139 0.3927 +-0.0333 -0.0167 0.3927 +-0.0389 -0.0194 0.3927 +-0.0444 -0.0222 0.3927 +-0.0500 -0.0250 0.3927 +primID: 3 +startangle_c: 1 +endpose_c: 5 4 2 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0149 0.0092 0.4230 +0.0296 0.0189 0.4533 +0.0440 0.0291 0.4836 +0.0582 0.0398 0.5139 +0.0722 0.0509 0.5442 +0.0858 0.0625 0.5745 +0.0992 0.0746 0.6048 +0.1123 0.0871 0.6351 +0.1250 0.1000 0.6654 +primID: 4 +startangle_c: 1 +endpose_c: 7 2 0 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0188 0.0078 0.3927 +0.0377 0.0156 0.3927 +0.0565 0.0234 0.3927 +0.0754 0.0312 0.3736 +0.0946 0.0379 0.2989 +0.1143 0.0432 0.2242 +0.1344 0.0470 0.1494 +0.1546 0.0492 0.0747 +0.1750 0.0500 0.0000 +primID: 5 +startangle_c: 1 +endpose_c: 0 0 2 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0000 0.0000 0.4363 +0.0000 0.0000 0.4800 +0.0000 0.0000 0.5236 +0.0000 0.0000 0.5672 +0.0000 0.0000 0.6109 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.6981 +0.0000 0.0000 0.7418 +0.0000 0.0000 0.7854 +primID: 6 +startangle_c: 1 +endpose_c: 0 0 0 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0000 0.0000 0.3491 +0.0000 0.0000 0.3054 +0.0000 0.0000 0.2618 +0.0000 0.0000 0.2182 +0.0000 0.0000 0.1745 +0.0000 0.0000 0.1309 +0.0000 0.0000 0.0873 +0.0000 0.0000 0.0436 +0.0000 0.0000 0.0000 +primID: 7 +startangle_c: 1 +endpose_c: -1 2 1 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.3927 +-0.0028 0.0056 0.3927 +-0.0056 0.0111 0.3927 +-0.0083 0.0167 0.3927 +-0.0111 0.0222 0.3927 +-0.0139 0.0278 0.3927 +-0.0167 0.0333 0.3927 +-0.0194 0.0389 0.3927 +-0.0222 0.0444 0.3927 +-0.0250 0.0500 0.3927 +primID: 8 +startangle_c: 1 +endpose_c: 1 -2 1 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0028 -0.0056 0.3927 +0.0056 -0.0111 0.3927 +0.0083 -0.0167 0.3927 +0.0111 -0.0222 0.3927 +0.0139 -0.0278 0.3927 +0.0167 -0.0333 0.3927 +0.0194 -0.0389 0.3927 +0.0222 -0.0444 0.3927 +0.0250 -0.0500 0.3927 +primID: 9 +startangle_c: 1 +endpose_c: -5 -4 2 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 0.3927 +-0.0149 -0.0092 0.4230 +-0.0296 -0.0189 0.4533 +-0.0440 -0.0291 0.4836 +-0.0582 -0.0398 0.5139 +-0.0722 -0.0509 0.5442 +-0.0858 -0.0625 0.5745 +-0.0992 -0.0746 0.6048 +-0.1123 -0.0871 0.6351 +-0.1250 -0.1000 0.6654 +primID: 10 +startangle_c: 1 +endpose_c: -7 -2 0 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 0.3927 +-0.0188 -0.0078 0.3927 +-0.0377 -0.0156 0.3927 +-0.0565 -0.0234 0.3927 +-0.0754 -0.0312 0.3736 +-0.0946 -0.0379 0.2989 +-0.1143 -0.0432 0.2242 +-0.1344 -0.0470 0.1494 +-0.1546 -0.0492 0.0747 +-0.1750 -0.0500 0.0000 +primID: 0 +startangle_c: 2 +endpose_c: 1 1 2 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0028 0.0028 0.7854 +0.0056 0.0056 0.7854 +0.0083 0.0083 0.7854 +0.0111 0.0111 0.7854 +0.0139 0.0139 0.7854 +0.0167 0.0167 0.7854 +0.0194 0.0194 0.7854 +0.0222 0.0222 0.7854 +0.0250 0.0250 0.7854 +primID: 1 +startangle_c: 2 +endpose_c: 6 6 2 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0167 0.0167 0.7854 +0.0333 0.0333 0.7854 +0.0500 0.0500 0.7854 +0.0667 0.0667 0.7854 +0.0833 0.0833 0.7854 +0.1000 0.1000 0.7854 +0.1167 0.1167 0.7854 +0.1333 0.1333 0.7854 +0.1500 0.1500 0.7854 +primID: 2 +startangle_c: 2 +endpose_c: -1 -1 2 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 0.7854 +-0.0028 -0.0028 0.7854 +-0.0056 -0.0056 0.7854 +-0.0083 -0.0083 0.7854 +-0.0111 -0.0111 0.7854 +-0.0139 -0.0139 0.7854 +-0.0167 -0.0167 0.7854 +-0.0194 -0.0194 0.7854 +-0.0222 -0.0222 0.7854 +-0.0250 -0.0250 0.7854 +primID: 3 +startangle_c: 2 +endpose_c: 5 7 3 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0170 0.0170 0.7854 +0.0339 0.0342 0.8151 +0.0500 0.0522 0.8669 +0.0651 0.0709 0.9188 +0.0792 0.0904 0.9707 +0.0923 0.1107 1.0225 +0.1043 0.1315 1.0744 +0.1152 0.1530 1.1262 +0.1250 0.1750 1.1781 +primID: 4 +startangle_c: 2 +endpose_c: 7 5 1 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0170 0.0170 0.7854 +0.0342 0.0339 0.7557 +0.0522 0.0500 0.7039 +0.0709 0.0651 0.6520 +0.0904 0.0792 0.6001 +0.1107 0.0923 0.5483 +0.1315 0.1043 0.4964 +0.1530 0.1152 0.4446 +0.1750 0.1250 0.3927 +primID: 5 +startangle_c: 2 +endpose_c: 0 0 3 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0000 0.0000 0.8290 +0.0000 0.0000 0.8727 +0.0000 0.0000 0.9163 +0.0000 0.0000 0.9599 +0.0000 0.0000 1.0036 +0.0000 0.0000 1.0472 +0.0000 0.0000 1.0908 +0.0000 0.0000 1.1345 +0.0000 0.0000 1.1781 +primID: 6 +startangle_c: 2 +endpose_c: 0 0 1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0000 0.0000 0.7418 +0.0000 0.0000 0.6981 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.6109 +0.0000 0.0000 0.5672 +0.0000 0.0000 0.5236 +0.0000 0.0000 0.4800 +0.0000 0.0000 0.4363 +0.0000 0.0000 0.3927 +primID: 7 +startangle_c: 2 +endpose_c: -1 1 2 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.7854 +-0.0028 0.0028 0.7854 +-0.0056 0.0056 0.7854 +-0.0083 0.0083 0.7854 +-0.0111 0.0111 0.7854 +-0.0139 0.0139 0.7854 +-0.0167 0.0167 0.7854 +-0.0194 0.0194 0.7854 +-0.0222 0.0222 0.7854 +-0.0250 0.0250 0.7854 +primID: 8 +startangle_c: 2 +endpose_c: 1 -1 2 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0028 -0.0028 0.7854 +0.0056 -0.0056 0.7854 +0.0083 -0.0083 0.7854 +0.0111 -0.0111 0.7854 +0.0139 -0.0139 0.7854 +0.0167 -0.0167 0.7854 +0.0194 -0.0194 0.7854 +0.0222 -0.0222 0.7854 +0.0250 -0.0250 0.7854 +primID: 9 +startangle_c: 2 +endpose_c: -5 -7 3 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 0.7854 +-0.0170 -0.0170 0.7854 +-0.0339 -0.0342 0.8151 +-0.0500 -0.0522 0.8669 +-0.0651 -0.0709 0.9188 +-0.0792 -0.0904 0.9707 +-0.0923 -0.1107 1.0225 +-0.1043 -0.1315 1.0744 +-0.1152 -0.1530 1.1262 +-0.1250 -0.1750 1.1781 +primID: 10 +startangle_c: 2 +endpose_c: -7 -5 1 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 0.7854 +-0.0170 -0.0170 0.7854 +-0.0342 -0.0339 0.7557 +-0.0522 -0.0500 0.7039 +-0.0709 -0.0651 0.6520 +-0.0904 -0.0792 0.6001 +-0.1107 -0.0923 0.5483 +-0.1315 -0.1043 0.4964 +-0.1530 -0.1152 0.4446 +-0.1750 -0.1250 0.3927 +primID: 0 +startangle_c: 3 +endpose_c: 1 2 3 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0028 0.0056 1.1781 +0.0056 0.0111 1.1781 +0.0083 0.0167 1.1781 +0.0111 0.0222 1.1781 +0.0139 0.0278 1.1781 +0.0167 0.0333 1.1781 +0.0194 0.0389 1.1781 +0.0222 0.0444 1.1781 +0.0250 0.0500 1.1781 +primID: 1 +startangle_c: 3 +endpose_c: 3 6 3 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0083 0.0167 1.1781 +0.0167 0.0333 1.1781 +0.0250 0.0500 1.1781 +0.0333 0.0667 1.1781 +0.0417 0.0833 1.1781 +0.0500 0.1000 1.1781 +0.0583 0.1167 1.1781 +0.0667 0.1333 1.1781 +0.0750 0.1500 1.1781 +primID: 2 +startangle_c: 3 +endpose_c: -1 -2 3 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 1.1781 +-0.0028 -0.0056 1.1781 +-0.0056 -0.0111 1.1781 +-0.0083 -0.0167 1.1781 +-0.0111 -0.0222 1.1781 +-0.0139 -0.0278 1.1781 +-0.0167 -0.0333 1.1781 +-0.0194 -0.0389 1.1781 +-0.0222 -0.0444 1.1781 +-0.0250 -0.0500 1.1781 +primID: 3 +startangle_c: 3 +endpose_c: 4 5 2 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0092 0.0149 1.1478 +0.0189 0.0296 1.1175 +0.0291 0.0440 1.0872 +0.0398 0.0582 1.0569 +0.0509 0.0722 1.0266 +0.0625 0.0858 0.9963 +0.0746 0.0992 0.9660 +0.0871 0.1123 0.9357 +0.1000 0.1250 0.9054 +primID: 4 +startangle_c: 3 +endpose_c: 2 7 4 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0078 0.0188 1.1781 +0.0156 0.0377 1.1781 +0.0234 0.0565 1.1781 +0.0312 0.0754 1.1972 +0.0379 0.0946 1.2719 +0.0432 0.1143 1.3466 +0.0470 0.1344 1.4214 +0.0492 0.1546 1.4961 +0.0500 0.1750 1.5708 +primID: 5 +startangle_c: 3 +endpose_c: 0 0 2 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0000 0.0000 1.1345 +0.0000 0.0000 1.0908 +0.0000 0.0000 1.0472 +0.0000 0.0000 1.0036 +0.0000 0.0000 0.9599 +0.0000 0.0000 0.9163 +0.0000 0.0000 0.8727 +0.0000 0.0000 0.8290 +0.0000 0.0000 0.7854 +primID: 6 +startangle_c: 3 +endpose_c: 0 0 4 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0000 0.0000 1.2217 +0.0000 0.0000 1.2654 +0.0000 0.0000 1.3090 +0.0000 0.0000 1.3526 +0.0000 0.0000 1.3963 +0.0000 0.0000 1.4399 +0.0000 0.0000 1.4835 +0.0000 0.0000 1.5272 +0.0000 0.0000 1.5708 +primID: 7 +startangle_c: 3 +endpose_c: 2 -1 3 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0056 -0.0028 1.1781 +0.0111 -0.0056 1.1781 +0.0167 -0.0083 1.1781 +0.0222 -0.0111 1.1781 +0.0278 -0.0139 1.1781 +0.0333 -0.0167 1.1781 +0.0389 -0.0194 1.1781 +0.0444 -0.0222 1.1781 +0.0500 -0.0250 1.1781 +primID: 8 +startangle_c: 3 +endpose_c: -2 1 3 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.1781 +-0.0056 0.0028 1.1781 +-0.0111 0.0056 1.1781 +-0.0167 0.0083 1.1781 +-0.0222 0.0111 1.1781 +-0.0278 0.0139 1.1781 +-0.0333 0.0167 1.1781 +-0.0389 0.0194 1.1781 +-0.0444 0.0222 1.1781 +-0.0500 0.0250 1.1781 +primID: 9 +startangle_c: 3 +endpose_c: -4 -5 2 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 1.1781 +-0.0092 -0.0149 1.1478 +-0.0189 -0.0296 1.1175 +-0.0291 -0.0440 1.0872 +-0.0398 -0.0582 1.0569 +-0.0509 -0.0722 1.0266 +-0.0625 -0.0858 0.9963 +-0.0746 -0.0992 0.9660 +-0.0871 -0.1123 0.9357 +-0.1000 -0.1250 0.9054 +primID: 10 +startangle_c: 3 +endpose_c: -2 -7 4 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 1.1781 +-0.0078 -0.0188 1.1781 +-0.0156 -0.0377 1.1781 +-0.0234 -0.0565 1.1781 +-0.0312 -0.0754 1.1972 +-0.0379 -0.0946 1.2719 +-0.0432 -0.1143 1.3466 +-0.0470 -0.1344 1.4214 +-0.0492 -0.1546 1.4961 +-0.0500 -0.1750 1.5708 +primID: 0 +startangle_c: 4 +endpose_c: 0 1 4 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0028 1.5708 +0.0000 0.0056 1.5708 +0.0000 0.0083 1.5708 +0.0000 0.0111 1.5708 +0.0000 0.0139 1.5708 +0.0000 0.0167 1.5708 +0.0000 0.0194 1.5708 +0.0000 0.0222 1.5708 +0.0000 0.0250 1.5708 +primID: 1 +startangle_c: 4 +endpose_c: 0 8 4 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0222 1.5708 +0.0000 0.0444 1.5708 +0.0000 0.0667 1.5708 +0.0000 0.0889 1.5708 +0.0000 0.1111 1.5708 +0.0000 0.1333 1.5708 +0.0000 0.1556 1.5708 +0.0000 0.1778 1.5708 +0.0000 0.2000 1.5708 +primID: 2 +startangle_c: 4 +endpose_c: 0 -1 4 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 -0.0028 1.5708 +0.0000 -0.0056 1.5708 +0.0000 -0.0083 1.5708 +0.0000 -0.0111 1.5708 +0.0000 -0.0139 1.5708 +0.0000 -0.0167 1.5708 +0.0000 -0.0194 1.5708 +0.0000 -0.0222 1.5708 +0.0000 -0.0250 1.5708 +primID: 3 +startangle_c: 4 +endpose_c: -1 8 5 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0226 1.5708 +0.0000 0.0452 1.5708 +0.0000 0.0678 1.5708 +-0.0004 0.0903 1.6196 +-0.0023 0.1128 1.6884 +-0.0057 0.1352 1.7572 +-0.0106 0.1572 1.8259 +-0.0171 0.1789 1.8947 +-0.0250 0.2000 1.9635 +primID: 4 +startangle_c: 4 +endpose_c: 1 8 3 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 1.5708 +-0.0000 0.0226 1.5708 +-0.0000 0.0452 1.5708 +-0.0000 0.0678 1.5708 +0.0004 0.0903 1.5220 +0.0023 0.1128 1.4532 +0.0057 0.1352 1.3844 +0.0106 0.1572 1.3156 +0.0171 0.1789 1.2469 +0.0250 0.2000 1.1781 +primID: 5 +startangle_c: 4 +endpose_c: 0 0 5 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0000 1.6144 +0.0000 0.0000 1.6581 +0.0000 0.0000 1.7017 +0.0000 0.0000 1.7453 +0.0000 0.0000 1.7890 +0.0000 0.0000 1.8326 +0.0000 0.0000 1.8762 +0.0000 0.0000 1.9199 +0.0000 0.0000 1.9635 +primID: 6 +startangle_c: 4 +endpose_c: 0 0 3 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0000 1.5272 +0.0000 0.0000 1.4835 +0.0000 0.0000 1.4399 +0.0000 0.0000 1.3963 +0.0000 0.0000 1.3526 +0.0000 0.0000 1.3090 +0.0000 0.0000 1.2654 +0.0000 0.0000 1.2217 +0.0000 0.0000 1.1781 +primID: 7 +startangle_c: 4 +endpose_c: -1 0 4 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.5708 +-0.0028 0.0000 1.5708 +-0.0056 0.0000 1.5708 +-0.0083 0.0000 1.5708 +-0.0111 0.0000 1.5708 +-0.0139 0.0000 1.5708 +-0.0167 0.0000 1.5708 +-0.0194 0.0000 1.5708 +-0.0222 0.0000 1.5708 +-0.0250 0.0000 1.5708 +primID: 8 +startangle_c: 4 +endpose_c: 1 0 4 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0028 0.0000 1.5708 +0.0056 0.0000 1.5708 +0.0083 0.0000 1.5708 +0.0111 0.0000 1.5708 +0.0139 0.0000 1.5708 +0.0167 0.0000 1.5708 +0.0194 0.0000 1.5708 +0.0222 0.0000 1.5708 +0.0250 0.0000 1.5708 +primID: 9 +startangle_c: 4 +endpose_c: 1 -8 5 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 1.5708 +-0.0000 -0.0226 1.5708 +-0.0000 -0.0452 1.5708 +-0.0000 -0.0678 1.5708 +0.0004 -0.0903 1.6196 +0.0023 -0.1128 1.6884 +0.0057 -0.1352 1.7572 +0.0106 -0.1572 1.8259 +0.0171 -0.1789 1.8947 +0.0250 -0.2000 1.9635 +primID: 10 +startangle_c: 4 +endpose_c: -1 -8 3 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 -0.0226 1.5708 +0.0000 -0.0452 1.5708 +0.0000 -0.0678 1.5708 +-0.0004 -0.0903 1.5220 +-0.0023 -0.1128 1.4532 +-0.0057 -0.1352 1.3844 +-0.0106 -0.1572 1.3156 +-0.0171 -0.1789 1.2469 +-0.0250 -0.2000 1.1781 +primID: 0 +startangle_c: 5 +endpose_c: -1 2 5 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0028 0.0056 1.9635 +-0.0056 0.0111 1.9635 +-0.0083 0.0167 1.9635 +-0.0111 0.0222 1.9635 +-0.0139 0.0278 1.9635 +-0.0167 0.0333 1.9635 +-0.0194 0.0389 1.9635 +-0.0222 0.0444 1.9635 +-0.0250 0.0500 1.9635 +primID: 1 +startangle_c: 5 +endpose_c: -3 6 5 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0083 0.0167 1.9635 +-0.0167 0.0333 1.9635 +-0.0250 0.0500 1.9635 +-0.0333 0.0667 1.9635 +-0.0417 0.0833 1.9635 +-0.0500 0.1000 1.9635 +-0.0583 0.1167 1.9635 +-0.0667 0.1333 1.9635 +-0.0750 0.1500 1.9635 +primID: 2 +startangle_c: 5 +endpose_c: 1 -2 5 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0028 -0.0056 1.9635 +0.0056 -0.0111 1.9635 +0.0083 -0.0167 1.9635 +0.0111 -0.0222 1.9635 +0.0139 -0.0278 1.9635 +0.0167 -0.0333 1.9635 +0.0194 -0.0389 1.9635 +0.0222 -0.0444 1.9635 +0.0250 -0.0500 1.9635 +primID: 3 +startangle_c: 5 +endpose_c: -4 5 6 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0092 0.0149 1.9938 +-0.0189 0.0296 2.0241 +-0.0291 0.0440 2.0544 +-0.0398 0.0582 2.0847 +-0.0509 0.0722 2.1150 +-0.0625 0.0858 2.1453 +-0.0746 0.0992 2.1756 +-0.0871 0.1123 2.2059 +-0.1000 0.1250 2.2362 +primID: 4 +startangle_c: 5 +endpose_c: -2 7 4 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0078 0.0188 1.9635 +-0.0156 0.0377 1.9635 +-0.0234 0.0565 1.9635 +-0.0312 0.0754 1.9444 +-0.0379 0.0946 1.8697 +-0.0432 0.1143 1.7950 +-0.0470 0.1344 1.7202 +-0.0492 0.1546 1.6455 +-0.0500 0.1750 1.5708 +primID: 5 +startangle_c: 5 +endpose_c: 0 0 6 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0000 0.0000 2.0071 +0.0000 0.0000 2.0508 +0.0000 0.0000 2.0944 +0.0000 0.0000 2.1380 +0.0000 0.0000 2.1817 +0.0000 0.0000 2.2253 +0.0000 0.0000 2.2689 +0.0000 0.0000 2.3126 +0.0000 0.0000 2.3562 +primID: 6 +startangle_c: 5 +endpose_c: 0 0 4 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0000 0.0000 1.9199 +0.0000 0.0000 1.8762 +0.0000 0.0000 1.8326 +0.0000 0.0000 1.7890 +0.0000 0.0000 1.7453 +0.0000 0.0000 1.7017 +0.0000 0.0000 1.6581 +0.0000 0.0000 1.6144 +0.0000 0.0000 1.5708 +primID: 7 +startangle_c: 5 +endpose_c: -2 -1 5 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0056 -0.0028 1.9635 +-0.0111 -0.0056 1.9635 +-0.0167 -0.0083 1.9635 +-0.0222 -0.0111 1.9635 +-0.0278 -0.0139 1.9635 +-0.0333 -0.0167 1.9635 +-0.0389 -0.0194 1.9635 +-0.0444 -0.0222 1.9635 +-0.0500 -0.0250 1.9635 +primID: 8 +startangle_c: 5 +endpose_c: 2 1 5 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0056 0.0028 1.9635 +0.0111 0.0056 1.9635 +0.0167 0.0083 1.9635 +0.0222 0.0111 1.9635 +0.0278 0.0139 1.9635 +0.0333 0.0167 1.9635 +0.0389 0.0194 1.9635 +0.0444 0.0222 1.9635 +0.0500 0.0250 1.9635 +primID: 9 +startangle_c: 5 +endpose_c: 4 -5 6 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0092 -0.0149 1.9938 +0.0189 -0.0296 2.0241 +0.0291 -0.0440 2.0544 +0.0398 -0.0582 2.0847 +0.0509 -0.0722 2.1150 +0.0625 -0.0858 2.1453 +0.0746 -0.0992 2.1756 +0.0871 -0.1123 2.2059 +0.1000 -0.1250 2.2362 +primID: 10 +startangle_c: 5 +endpose_c: 2 -7 4 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0078 -0.0188 1.9635 +0.0156 -0.0377 1.9635 +0.0234 -0.0565 1.9635 +0.0312 -0.0754 1.9444 +0.0379 -0.0946 1.8697 +0.0432 -0.1143 1.7950 +0.0470 -0.1344 1.7202 +0.0492 -0.1546 1.6455 +0.0500 -0.1750 1.5708 +primID: 0 +startangle_c: 6 +endpose_c: -1 1 6 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0028 0.0028 2.3562 +-0.0056 0.0056 2.3562 +-0.0083 0.0083 2.3562 +-0.0111 0.0111 2.3562 +-0.0139 0.0139 2.3562 +-0.0167 0.0167 2.3562 +-0.0194 0.0194 2.3562 +-0.0222 0.0222 2.3562 +-0.0250 0.0250 2.3562 +primID: 1 +startangle_c: 6 +endpose_c: -6 6 6 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0167 0.0167 2.3562 +-0.0333 0.0333 2.3562 +-0.0500 0.0500 2.3562 +-0.0667 0.0667 2.3562 +-0.0833 0.0833 2.3562 +-0.1000 0.1000 2.3562 +-0.1167 0.1167 2.3562 +-0.1333 0.1333 2.3562 +-0.1500 0.1500 2.3562 +primID: 2 +startangle_c: 6 +endpose_c: 1 -1 6 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0028 -0.0028 2.3562 +0.0056 -0.0056 2.3562 +0.0083 -0.0083 2.3562 +0.0111 -0.0111 2.3562 +0.0139 -0.0139 2.3562 +0.0167 -0.0167 2.3562 +0.0194 -0.0194 2.3562 +0.0222 -0.0222 2.3562 +0.0250 -0.0250 2.3562 +primID: 3 +startangle_c: 6 +endpose_c: -7 5 7 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0170 0.0170 2.3562 +-0.0342 0.0339 2.3859 +-0.0522 0.0500 2.4377 +-0.0709 0.0651 2.4896 +-0.0904 0.0792 2.5415 +-0.1107 0.0923 2.5933 +-0.1315 0.1043 2.6452 +-0.1530 0.1152 2.6970 +-0.1750 0.1250 2.7489 +primID: 4 +startangle_c: 6 +endpose_c: -5 7 5 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0170 0.0170 2.3562 +-0.0339 0.0342 2.3265 +-0.0500 0.0522 2.2747 +-0.0651 0.0709 2.2228 +-0.0792 0.0904 2.1709 +-0.0923 0.1107 2.1191 +-0.1043 0.1315 2.0672 +-0.1152 0.1530 2.0154 +-0.1250 0.1750 1.9635 +primID: 5 +startangle_c: 6 +endpose_c: 0 0 7 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0000 0.0000 2.3998 +0.0000 0.0000 2.4435 +0.0000 0.0000 2.4871 +0.0000 0.0000 2.5307 +0.0000 0.0000 2.5744 +0.0000 0.0000 2.6180 +0.0000 0.0000 2.6616 +0.0000 0.0000 2.7053 +0.0000 0.0000 2.7489 +primID: 6 +startangle_c: 6 +endpose_c: 0 0 5 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0000 0.0000 2.3126 +0.0000 0.0000 2.2689 +0.0000 0.0000 2.2253 +0.0000 0.0000 2.1817 +0.0000 0.0000 2.1380 +0.0000 0.0000 2.0944 +0.0000 0.0000 2.0508 +0.0000 0.0000 2.0071 +0.0000 0.0000 1.9635 +primID: 7 +startangle_c: 6 +endpose_c: -1 -1 6 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0028 -0.0028 2.3562 +-0.0056 -0.0056 2.3562 +-0.0083 -0.0083 2.3562 +-0.0111 -0.0111 2.3562 +-0.0139 -0.0139 2.3562 +-0.0167 -0.0167 2.3562 +-0.0194 -0.0194 2.3562 +-0.0222 -0.0222 2.3562 +-0.0250 -0.0250 2.3562 +primID: 8 +startangle_c: 6 +endpose_c: 1 1 6 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0028 0.0028 2.3562 +0.0056 0.0056 2.3562 +0.0083 0.0083 2.3562 +0.0111 0.0111 2.3562 +0.0139 0.0139 2.3562 +0.0167 0.0167 2.3562 +0.0194 0.0194 2.3562 +0.0222 0.0222 2.3562 +0.0250 0.0250 2.3562 +primID: 9 +startangle_c: 6 +endpose_c: 7 -5 7 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0170 -0.0170 2.3562 +0.0342 -0.0339 2.3859 +0.0522 -0.0500 2.4377 +0.0709 -0.0651 2.4896 +0.0904 -0.0792 2.5415 +0.1107 -0.0923 2.5933 +0.1315 -0.1043 2.6452 +0.1530 -0.1152 2.6970 +0.1750 -0.1250 2.7489 +primID: 10 +startangle_c: 6 +endpose_c: 5 -7 5 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0170 -0.0170 2.3562 +0.0339 -0.0342 2.3265 +0.0500 -0.0522 2.2747 +0.0651 -0.0709 2.2228 +0.0792 -0.0904 2.1709 +0.0923 -0.1107 2.1191 +0.1043 -0.1315 2.0672 +0.1152 -0.1530 2.0154 +0.1250 -0.1750 1.9635 +primID: 0 +startangle_c: 7 +endpose_c: -2 1 7 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0056 0.0028 2.7489 +-0.0111 0.0056 2.7489 +-0.0167 0.0083 2.7489 +-0.0222 0.0111 2.7489 +-0.0278 0.0139 2.7489 +-0.0333 0.0167 2.7489 +-0.0389 0.0194 2.7489 +-0.0444 0.0222 2.7489 +-0.0500 0.0250 2.7489 +primID: 1 +startangle_c: 7 +endpose_c: -6 3 7 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0167 0.0083 2.7489 +-0.0333 0.0167 2.7489 +-0.0500 0.0250 2.7489 +-0.0667 0.0333 2.7489 +-0.0833 0.0417 2.7489 +-0.1000 0.0500 2.7489 +-0.1167 0.0583 2.7489 +-0.1333 0.0667 2.7489 +-0.1500 0.0750 2.7489 +primID: 2 +startangle_c: 7 +endpose_c: 2 -1 7 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0056 -0.0028 2.7489 +0.0111 -0.0056 2.7489 +0.0167 -0.0083 2.7489 +0.0222 -0.0111 2.7489 +0.0278 -0.0139 2.7489 +0.0333 -0.0167 2.7489 +0.0389 -0.0194 2.7489 +0.0444 -0.0222 2.7489 +0.0500 -0.0250 2.7489 +primID: 3 +startangle_c: 7 +endpose_c: -5 4 6 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0149 0.0092 2.7186 +-0.0296 0.0189 2.6883 +-0.0440 0.0291 2.6580 +-0.0582 0.0398 2.6277 +-0.0722 0.0509 2.5974 +-0.0858 0.0625 2.5671 +-0.0992 0.0746 2.5368 +-0.1123 0.0871 2.5065 +-0.1250 0.1000 2.4762 +primID: 4 +startangle_c: 7 +endpose_c: -7 2 8 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0188 0.0078 2.7489 +-0.0377 0.0156 2.7489 +-0.0565 0.0234 2.7489 +-0.0754 0.0312 2.7680 +-0.0946 0.0379 2.8427 +-0.1143 0.0432 2.9174 +-0.1344 0.0470 2.9921 +-0.1546 0.0492 3.0669 +-0.1750 0.0500 3.1416 +primID: 5 +startangle_c: 7 +endpose_c: 0 0 6 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0000 0.0000 2.7053 +0.0000 0.0000 2.6616 +0.0000 0.0000 2.6180 +0.0000 0.0000 2.5744 +0.0000 0.0000 2.5307 +0.0000 0.0000 2.4871 +0.0000 0.0000 2.4435 +0.0000 0.0000 2.3998 +0.0000 0.0000 2.3562 +primID: 6 +startangle_c: 7 +endpose_c: 0 0 8 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0000 0.0000 2.7925 +0.0000 0.0000 2.8362 +0.0000 0.0000 2.8798 +0.0000 0.0000 2.9234 +0.0000 0.0000 2.9671 +0.0000 0.0000 3.0107 +0.0000 0.0000 3.0543 +0.0000 0.0000 3.0980 +0.0000 0.0000 3.1416 +primID: 7 +startangle_c: 7 +endpose_c: 1 2 7 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0028 0.0056 2.7489 +0.0056 0.0111 2.7489 +0.0083 0.0167 2.7489 +0.0111 0.0222 2.7489 +0.0139 0.0278 2.7489 +0.0167 0.0333 2.7489 +0.0194 0.0389 2.7489 +0.0222 0.0444 2.7489 +0.0250 0.0500 2.7489 +primID: 8 +startangle_c: 7 +endpose_c: -1 -2 7 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0028 -0.0056 2.7489 +-0.0056 -0.0111 2.7489 +-0.0083 -0.0167 2.7489 +-0.0111 -0.0222 2.7489 +-0.0139 -0.0278 2.7489 +-0.0167 -0.0333 2.7489 +-0.0194 -0.0389 2.7489 +-0.0222 -0.0444 2.7489 +-0.0250 -0.0500 2.7489 +primID: 9 +startangle_c: 7 +endpose_c: 5 -4 6 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0149 -0.0092 2.7186 +0.0296 -0.0189 2.6883 +0.0440 -0.0291 2.6580 +0.0582 -0.0398 2.6277 +0.0722 -0.0509 2.5974 +0.0858 -0.0625 2.5671 +0.0992 -0.0746 2.5368 +0.1123 -0.0871 2.5065 +0.1250 -0.1000 2.4762 +primID: 10 +startangle_c: 7 +endpose_c: 7 -2 8 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0188 -0.0078 2.7489 +0.0377 -0.0156 2.7489 +0.0565 -0.0234 2.7489 +0.0754 -0.0312 2.7680 +0.0946 -0.0379 2.8427 +0.1143 -0.0432 2.9174 +0.1344 -0.0470 2.9921 +0.1546 -0.0492 3.0669 +0.1750 -0.0500 3.1416 +primID: 0 +startangle_c: 8 +endpose_c: -1 0 8 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0028 0.0000 3.1416 +-0.0056 0.0000 3.1416 +-0.0083 0.0000 3.1416 +-0.0111 0.0000 3.1416 +-0.0139 0.0000 3.1416 +-0.0167 0.0000 3.1416 +-0.0194 0.0000 3.1416 +-0.0222 0.0000 3.1416 +-0.0250 0.0000 3.1416 +primID: 1 +startangle_c: 8 +endpose_c: -8 0 8 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0222 0.0000 3.1416 +-0.0444 0.0000 3.1416 +-0.0667 0.0000 3.1416 +-0.0889 0.0000 3.1416 +-0.1111 0.0000 3.1416 +-0.1333 0.0000 3.1416 +-0.1556 0.0000 3.1416 +-0.1778 0.0000 3.1416 +-0.2000 0.0000 3.1416 +primID: 2 +startangle_c: 8 +endpose_c: 1 0 8 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0028 0.0000 3.1416 +0.0056 0.0000 3.1416 +0.0083 0.0000 3.1416 +0.0111 0.0000 3.1416 +0.0139 0.0000 3.1416 +0.0167 0.0000 3.1416 +0.0194 0.0000 3.1416 +0.0222 0.0000 3.1416 +0.0250 0.0000 3.1416 +primID: 3 +startangle_c: 8 +endpose_c: -8 -1 9 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0226 0.0000 3.1416 +-0.0452 0.0000 3.1416 +-0.0678 0.0000 3.1416 +-0.0903 -0.0004 3.1904 +-0.1128 -0.0023 3.2592 +-0.1352 -0.0057 3.3280 +-0.1572 -0.0106 3.3967 +-0.1789 -0.0171 3.4655 +-0.2000 -0.0250 3.5343 +primID: 4 +startangle_c: 8 +endpose_c: -8 1 7 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0226 0.0000 3.1416 +-0.0452 0.0000 3.1416 +-0.0678 0.0000 3.1416 +-0.0903 0.0004 3.0928 +-0.1128 0.0023 3.0240 +-0.1352 0.0057 2.9552 +-0.1572 0.0106 2.8864 +-0.1789 0.0171 2.8177 +-0.2000 0.0250 2.7489 +primID: 5 +startangle_c: 8 +endpose_c: 0 0 9 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0000 0.0000 3.1852 +0.0000 0.0000 3.2289 +0.0000 0.0000 3.2725 +0.0000 0.0000 3.3161 +0.0000 0.0000 3.3598 +0.0000 0.0000 3.4034 +0.0000 0.0000 3.4470 +0.0000 0.0000 3.4907 +0.0000 0.0000 3.5343 +primID: 6 +startangle_c: 8 +endpose_c: 0 0 7 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0000 0.0000 3.0980 +0.0000 0.0000 3.0543 +0.0000 0.0000 3.0107 +0.0000 0.0000 2.9671 +0.0000 0.0000 2.9234 +0.0000 0.0000 2.8798 +0.0000 0.0000 2.8362 +0.0000 0.0000 2.7925 +0.0000 0.0000 2.7489 +primID: 7 +startangle_c: 8 +endpose_c: 0 -1 8 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0000 -0.0028 3.1416 +0.0000 -0.0056 3.1416 +0.0000 -0.0083 3.1416 +0.0000 -0.0111 3.1416 +0.0000 -0.0139 3.1416 +0.0000 -0.0167 3.1416 +0.0000 -0.0194 3.1416 +0.0000 -0.0222 3.1416 +0.0000 -0.0250 3.1416 +primID: 8 +startangle_c: 8 +endpose_c: 0 1 8 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0000 0.0028 3.1416 +0.0000 0.0056 3.1416 +0.0000 0.0083 3.1416 +0.0000 0.0111 3.1416 +0.0000 0.0139 3.1416 +0.0000 0.0167 3.1416 +0.0000 0.0194 3.1416 +0.0000 0.0222 3.1416 +0.0000 0.0250 3.1416 +primID: 9 +startangle_c: 8 +endpose_c: 8 1 9 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0226 -0.0000 3.1416 +0.0452 -0.0000 3.1416 +0.0678 -0.0000 3.1416 +0.0903 0.0004 3.1904 +0.1128 0.0023 3.2592 +0.1352 0.0057 3.3280 +0.1572 0.0106 3.3967 +0.1789 0.0171 3.4655 +0.2000 0.0250 3.5343 +primID: 10 +startangle_c: 8 +endpose_c: 8 -1 7 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0226 -0.0000 3.1416 +0.0452 -0.0000 3.1416 +0.0678 -0.0000 3.1416 +0.0903 -0.0004 3.0928 +0.1128 -0.0023 3.0240 +0.1352 -0.0057 2.9552 +0.1572 -0.0106 2.8864 +0.1789 -0.0171 2.8177 +0.2000 -0.0250 2.7489 +primID: 0 +startangle_c: 9 +endpose_c: -2 -1 9 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0056 -0.0028 3.5343 +-0.0111 -0.0056 3.5343 +-0.0167 -0.0083 3.5343 +-0.0222 -0.0111 3.5343 +-0.0278 -0.0139 3.5343 +-0.0333 -0.0167 3.5343 +-0.0389 -0.0194 3.5343 +-0.0444 -0.0222 3.5343 +-0.0500 -0.0250 3.5343 +primID: 1 +startangle_c: 9 +endpose_c: -6 -3 9 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0167 -0.0083 3.5343 +-0.0333 -0.0167 3.5343 +-0.0500 -0.0250 3.5343 +-0.0667 -0.0333 3.5343 +-0.0833 -0.0417 3.5343 +-0.1000 -0.0500 3.5343 +-0.1167 -0.0583 3.5343 +-0.1333 -0.0667 3.5343 +-0.1500 -0.0750 3.5343 +primID: 2 +startangle_c: 9 +endpose_c: 2 1 9 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0056 0.0028 3.5343 +0.0111 0.0056 3.5343 +0.0167 0.0083 3.5343 +0.0222 0.0111 3.5343 +0.0278 0.0139 3.5343 +0.0333 0.0167 3.5343 +0.0389 0.0194 3.5343 +0.0444 0.0222 3.5343 +0.0500 0.0250 3.5343 +primID: 3 +startangle_c: 9 +endpose_c: -5 -4 10 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0149 -0.0092 3.5646 +-0.0296 -0.0189 3.5949 +-0.0440 -0.0291 3.6252 +-0.0582 -0.0398 3.6555 +-0.0722 -0.0509 3.6858 +-0.0858 -0.0625 3.7161 +-0.0992 -0.0746 3.7464 +-0.1123 -0.0871 3.7767 +-0.1250 -0.1000 3.8070 +primID: 4 +startangle_c: 9 +endpose_c: -7 -2 8 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0188 -0.0078 3.5343 +-0.0377 -0.0156 3.5343 +-0.0565 -0.0234 3.5343 +-0.0754 -0.0312 3.5152 +-0.0946 -0.0379 3.4405 +-0.1143 -0.0432 3.3658 +-0.1344 -0.0470 3.2910 +-0.1546 -0.0492 3.2163 +-0.1750 -0.0500 3.1416 +primID: 5 +startangle_c: 9 +endpose_c: 0 0 10 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0000 0.0000 3.5779 +0.0000 0.0000 3.6216 +0.0000 0.0000 3.6652 +0.0000 0.0000 3.7088 +0.0000 0.0000 3.7525 +0.0000 0.0000 3.7961 +0.0000 0.0000 3.8397 +0.0000 0.0000 3.8834 +0.0000 0.0000 3.9270 +primID: 6 +startangle_c: 9 +endpose_c: 0 0 8 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0000 0.0000 3.4907 +0.0000 0.0000 3.4470 +0.0000 0.0000 3.4034 +0.0000 0.0000 3.3598 +0.0000 0.0000 3.3161 +0.0000 0.0000 3.2725 +0.0000 0.0000 3.2289 +0.0000 0.0000 3.1852 +0.0000 0.0000 3.1416 +primID: 7 +startangle_c: 9 +endpose_c: 1 -2 9 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0028 -0.0056 3.5343 +0.0056 -0.0111 3.5343 +0.0083 -0.0167 3.5343 +0.0111 -0.0222 3.5343 +0.0139 -0.0278 3.5343 +0.0167 -0.0333 3.5343 +0.0194 -0.0389 3.5343 +0.0222 -0.0444 3.5343 +0.0250 -0.0500 3.5343 +primID: 8 +startangle_c: 9 +endpose_c: -1 2 9 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0028 0.0056 3.5343 +-0.0056 0.0111 3.5343 +-0.0083 0.0167 3.5343 +-0.0111 0.0222 3.5343 +-0.0139 0.0278 3.5343 +-0.0167 0.0333 3.5343 +-0.0194 0.0389 3.5343 +-0.0222 0.0444 3.5343 +-0.0250 0.0500 3.5343 +primID: 9 +startangle_c: 9 +endpose_c: 5 4 10 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0149 0.0092 3.5646 +0.0296 0.0189 3.5949 +0.0440 0.0291 3.6252 +0.0582 0.0398 3.6555 +0.0722 0.0509 3.6858 +0.0858 0.0625 3.7161 +0.0992 0.0746 3.7464 +0.1123 0.0871 3.7767 +0.1250 0.1000 3.8070 +primID: 10 +startangle_c: 9 +endpose_c: 7 2 8 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0188 0.0078 3.5343 +0.0377 0.0156 3.5343 +0.0565 0.0234 3.5343 +0.0754 0.0312 3.5152 +0.0946 0.0379 3.4405 +0.1143 0.0432 3.3658 +0.1344 0.0470 3.2910 +0.1546 0.0492 3.2163 +0.1750 0.0500 3.1416 +primID: 0 +startangle_c: 10 +endpose_c: -1 -1 10 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0028 -0.0028 3.9270 +-0.0056 -0.0056 3.9270 +-0.0083 -0.0083 3.9270 +-0.0111 -0.0111 3.9270 +-0.0139 -0.0139 3.9270 +-0.0167 -0.0167 3.9270 +-0.0194 -0.0194 3.9270 +-0.0222 -0.0222 3.9270 +-0.0250 -0.0250 3.9270 +primID: 1 +startangle_c: 10 +endpose_c: -6 -6 10 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0167 -0.0167 3.9270 +-0.0333 -0.0333 3.9270 +-0.0500 -0.0500 3.9270 +-0.0667 -0.0667 3.9270 +-0.0833 -0.0833 3.9270 +-0.1000 -0.1000 3.9270 +-0.1167 -0.1167 3.9270 +-0.1333 -0.1333 3.9270 +-0.1500 -0.1500 3.9270 +primID: 2 +startangle_c: 10 +endpose_c: 1 1 10 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0028 0.0028 3.9270 +0.0056 0.0056 3.9270 +0.0083 0.0083 3.9270 +0.0111 0.0111 3.9270 +0.0139 0.0139 3.9270 +0.0167 0.0167 3.9270 +0.0194 0.0194 3.9270 +0.0222 0.0222 3.9270 +0.0250 0.0250 3.9270 +primID: 3 +startangle_c: 10 +endpose_c: -5 -7 11 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0170 -0.0170 3.9270 +-0.0339 -0.0342 3.9567 +-0.0500 -0.0522 4.0085 +-0.0651 -0.0709 4.0604 +-0.0792 -0.0904 4.1123 +-0.0923 -0.1107 4.1641 +-0.1043 -0.1315 4.2160 +-0.1152 -0.1530 4.2678 +-0.1250 -0.1750 4.3197 +primID: 4 +startangle_c: 10 +endpose_c: -7 -5 9 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0170 -0.0170 3.9270 +-0.0342 -0.0339 3.8973 +-0.0522 -0.0500 3.8455 +-0.0709 -0.0651 3.7936 +-0.0904 -0.0792 3.7417 +-0.1107 -0.0923 3.6899 +-0.1315 -0.1043 3.6380 +-0.1530 -0.1152 3.5862 +-0.1750 -0.1250 3.5343 +primID: 5 +startangle_c: 10 +endpose_c: 0 0 11 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.9706 +0.0000 0.0000 4.0143 +0.0000 0.0000 4.0579 +0.0000 0.0000 4.1015 +0.0000 0.0000 4.1452 +0.0000 0.0000 4.1888 +0.0000 0.0000 4.2324 +0.0000 0.0000 4.2761 +0.0000 0.0000 4.3197 +primID: 6 +startangle_c: 10 +endpose_c: 0 0 9 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.8834 +0.0000 0.0000 3.8397 +0.0000 0.0000 3.7961 +0.0000 0.0000 3.7525 +0.0000 0.0000 3.7088 +0.0000 0.0000 3.6652 +0.0000 0.0000 3.6216 +0.0000 0.0000 3.5779 +0.0000 0.0000 3.5343 +primID: 7 +startangle_c: 10 +endpose_c: 1 -1 10 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0028 -0.0028 3.9270 +0.0056 -0.0056 3.9270 +0.0083 -0.0083 3.9270 +0.0111 -0.0111 3.9270 +0.0139 -0.0139 3.9270 +0.0167 -0.0167 3.9270 +0.0194 -0.0194 3.9270 +0.0222 -0.0222 3.9270 +0.0250 -0.0250 3.9270 +primID: 8 +startangle_c: 10 +endpose_c: -1 1 10 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0028 0.0028 3.9270 +-0.0056 0.0056 3.9270 +-0.0083 0.0083 3.9270 +-0.0111 0.0111 3.9270 +-0.0139 0.0139 3.9270 +-0.0167 0.0167 3.9270 +-0.0194 0.0194 3.9270 +-0.0222 0.0222 3.9270 +-0.0250 0.0250 3.9270 +primID: 9 +startangle_c: 10 +endpose_c: 5 7 11 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0170 0.0170 3.9270 +0.0339 0.0342 3.9567 +0.0500 0.0522 4.0085 +0.0651 0.0709 4.0604 +0.0792 0.0904 4.1123 +0.0923 0.1107 4.1641 +0.1043 0.1315 4.2160 +0.1152 0.1530 4.2678 +0.1250 0.1750 4.3197 +primID: 10 +startangle_c: 10 +endpose_c: 7 5 9 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0170 0.0170 3.9270 +0.0342 0.0339 3.8973 +0.0522 0.0500 3.8455 +0.0709 0.0651 3.7936 +0.0904 0.0792 3.7417 +0.1107 0.0923 3.6899 +0.1315 0.1043 3.6380 +0.1530 0.1152 3.5862 +0.1750 0.1250 3.5343 +primID: 0 +startangle_c: 11 +endpose_c: -1 -2 11 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0028 -0.0056 4.3197 +-0.0056 -0.0111 4.3197 +-0.0083 -0.0167 4.3197 +-0.0111 -0.0222 4.3197 +-0.0139 -0.0278 4.3197 +-0.0167 -0.0333 4.3197 +-0.0194 -0.0389 4.3197 +-0.0222 -0.0444 4.3197 +-0.0250 -0.0500 4.3197 +primID: 1 +startangle_c: 11 +endpose_c: -3 -6 11 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0083 -0.0167 4.3197 +-0.0167 -0.0333 4.3197 +-0.0250 -0.0500 4.3197 +-0.0333 -0.0667 4.3197 +-0.0417 -0.0833 4.3197 +-0.0500 -0.1000 4.3197 +-0.0583 -0.1167 4.3197 +-0.0667 -0.1333 4.3197 +-0.0750 -0.1500 4.3197 +primID: 2 +startangle_c: 11 +endpose_c: 1 2 11 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0028 0.0056 4.3197 +0.0056 0.0111 4.3197 +0.0083 0.0167 4.3197 +0.0111 0.0222 4.3197 +0.0139 0.0278 4.3197 +0.0167 0.0333 4.3197 +0.0194 0.0389 4.3197 +0.0222 0.0444 4.3197 +0.0250 0.0500 4.3197 +primID: 3 +startangle_c: 11 +endpose_c: -4 -5 10 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0092 -0.0149 4.2894 +-0.0189 -0.0296 4.2591 +-0.0291 -0.0440 4.2288 +-0.0398 -0.0582 4.1985 +-0.0509 -0.0722 4.1682 +-0.0625 -0.0858 4.1379 +-0.0746 -0.0992 4.1076 +-0.0871 -0.1123 4.0773 +-0.1000 -0.1250 4.0470 +primID: 4 +startangle_c: 11 +endpose_c: -2 -7 12 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0078 -0.0188 4.3197 +-0.0156 -0.0377 4.3197 +-0.0234 -0.0565 4.3197 +-0.0312 -0.0754 4.3388 +-0.0379 -0.0946 4.4135 +-0.0432 -0.1143 4.4882 +-0.0470 -0.1344 4.5629 +-0.0492 -0.1546 4.6377 +-0.0500 -0.1750 4.7124 +primID: 5 +startangle_c: 11 +endpose_c: 0 0 10 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0000 0.0000 4.2761 +0.0000 0.0000 4.2324 +0.0000 0.0000 4.1888 +0.0000 0.0000 4.1452 +0.0000 0.0000 4.1015 +0.0000 0.0000 4.0579 +0.0000 0.0000 4.0143 +0.0000 0.0000 3.9706 +0.0000 0.0000 3.9270 +primID: 6 +startangle_c: 11 +endpose_c: 0 0 12 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0000 0.0000 4.3633 +0.0000 0.0000 4.4070 +0.0000 0.0000 4.4506 +0.0000 0.0000 4.4942 +0.0000 0.0000 4.5379 +0.0000 0.0000 4.5815 +0.0000 0.0000 4.6251 +0.0000 0.0000 4.6688 +0.0000 0.0000 4.7124 +primID: 7 +startangle_c: 11 +endpose_c: -2 1 11 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0056 0.0028 4.3197 +-0.0111 0.0056 4.3197 +-0.0167 0.0083 4.3197 +-0.0222 0.0111 4.3197 +-0.0278 0.0139 4.3197 +-0.0333 0.0167 4.3197 +-0.0389 0.0194 4.3197 +-0.0444 0.0222 4.3197 +-0.0500 0.0250 4.3197 +primID: 8 +startangle_c: 11 +endpose_c: 2 -1 11 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0056 -0.0028 4.3197 +0.0111 -0.0056 4.3197 +0.0167 -0.0083 4.3197 +0.0222 -0.0111 4.3197 +0.0278 -0.0139 4.3197 +0.0333 -0.0167 4.3197 +0.0389 -0.0194 4.3197 +0.0444 -0.0222 4.3197 +0.0500 -0.0250 4.3197 +primID: 9 +startangle_c: 11 +endpose_c: 4 5 10 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0092 0.0149 4.2894 +0.0189 0.0296 4.2591 +0.0291 0.0440 4.2288 +0.0398 0.0582 4.1985 +0.0509 0.0722 4.1682 +0.0625 0.0858 4.1379 +0.0746 0.0992 4.1076 +0.0871 0.1123 4.0773 +0.1000 0.1250 4.0470 +primID: 10 +startangle_c: 11 +endpose_c: 2 7 12 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0078 0.0188 4.3197 +0.0156 0.0377 4.3197 +0.0234 0.0565 4.3197 +0.0312 0.0754 4.3388 +0.0379 0.0946 4.4135 +0.0432 0.1143 4.4882 +0.0470 0.1344 4.5629 +0.0492 0.1546 4.6377 +0.0500 0.1750 4.7124 +primID: 0 +startangle_c: 12 +endpose_c: 0 -1 12 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0028 4.7124 +0.0000 -0.0056 4.7124 +0.0000 -0.0083 4.7124 +0.0000 -0.0111 4.7124 +0.0000 -0.0139 4.7124 +0.0000 -0.0167 4.7124 +0.0000 -0.0194 4.7124 +0.0000 -0.0222 4.7124 +0.0000 -0.0250 4.7124 +primID: 1 +startangle_c: 12 +endpose_c: 0 -8 12 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0222 4.7124 +0.0000 -0.0444 4.7124 +0.0000 -0.0667 4.7124 +0.0000 -0.0889 4.7124 +0.0000 -0.1111 4.7124 +0.0000 -0.1333 4.7124 +0.0000 -0.1556 4.7124 +0.0000 -0.1778 4.7124 +0.0000 -0.2000 4.7124 +primID: 2 +startangle_c: 12 +endpose_c: 0 1 12 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0028 4.7124 +0.0000 0.0056 4.7124 +0.0000 0.0083 4.7124 +0.0000 0.0111 4.7124 +0.0000 0.0139 4.7124 +0.0000 0.0167 4.7124 +0.0000 0.0194 4.7124 +0.0000 0.0222 4.7124 +0.0000 0.0250 4.7124 +primID: 3 +startangle_c: 12 +endpose_c: 1 -8 13 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 4.7124 +-0.0000 -0.0226 4.7124 +-0.0000 -0.0452 4.7124 +-0.0000 -0.0678 4.7124 +0.0004 -0.0903 4.7612 +0.0023 -0.1128 4.8300 +0.0057 -0.1352 4.8988 +0.0106 -0.1572 4.9675 +0.0171 -0.1789 5.0363 +0.0250 -0.2000 5.1051 +primID: 4 +startangle_c: 12 +endpose_c: -1 -8 11 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 4.7124 +-0.0000 -0.0226 4.7124 +-0.0000 -0.0452 4.7124 +-0.0000 -0.0678 4.7124 +-0.0004 -0.0903 4.6636 +-0.0023 -0.1128 4.5948 +-0.0057 -0.1352 4.5260 +-0.0106 -0.1572 4.4572 +-0.0171 -0.1789 4.3885 +-0.0250 -0.2000 4.3197 +primID: 5 +startangle_c: 12 +endpose_c: 0 0 13 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0000 4.7560 +0.0000 0.0000 4.7997 +0.0000 0.0000 4.8433 +0.0000 0.0000 4.8869 +0.0000 0.0000 4.9306 +0.0000 0.0000 4.9742 +0.0000 0.0000 5.0178 +0.0000 0.0000 5.0615 +0.0000 0.0000 5.1051 +primID: 6 +startangle_c: 12 +endpose_c: 0 0 11 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0000 4.6688 +0.0000 0.0000 4.6251 +0.0000 0.0000 4.5815 +0.0000 0.0000 4.5379 +0.0000 0.0000 4.4942 +0.0000 0.0000 4.4506 +0.0000 0.0000 4.4070 +0.0000 0.0000 4.3633 +0.0000 0.0000 4.3197 +primID: 7 +startangle_c: 12 +endpose_c: 1 0 12 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0028 0.0000 4.7124 +0.0056 0.0000 4.7124 +0.0083 0.0000 4.7124 +0.0111 0.0000 4.7124 +0.0139 0.0000 4.7124 +0.0167 0.0000 4.7124 +0.0194 0.0000 4.7124 +0.0222 0.0000 4.7124 +0.0250 0.0000 4.7124 +primID: 8 +startangle_c: 12 +endpose_c: -1 0 12 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 4.7124 +-0.0028 0.0000 4.7124 +-0.0056 0.0000 4.7124 +-0.0083 0.0000 4.7124 +-0.0111 0.0000 4.7124 +-0.0139 0.0000 4.7124 +-0.0167 0.0000 4.7124 +-0.0194 0.0000 4.7124 +-0.0222 0.0000 4.7124 +-0.0250 0.0000 4.7124 +primID: 9 +startangle_c: 12 +endpose_c: -1 8 13 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0226 4.7124 +0.0000 0.0452 4.7124 +0.0000 0.0678 4.7124 +-0.0004 0.0903 4.7612 +-0.0023 0.1128 4.8300 +-0.0057 0.1352 4.8988 +-0.0106 0.1572 4.9675 +-0.0171 0.1789 5.0363 +-0.0250 0.2000 5.1051 +primID: 10 +startangle_c: 12 +endpose_c: 1 8 11 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0226 4.7124 +0.0000 0.0452 4.7124 +0.0000 0.0678 4.7124 +0.0004 0.0903 4.6636 +0.0023 0.1128 4.5948 +0.0057 0.1352 4.5260 +0.0106 0.1572 4.4572 +0.0171 0.1789 4.3885 +0.0250 0.2000 4.3197 +primID: 0 +startangle_c: 13 +endpose_c: 1 -2 13 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0028 -0.0056 5.1051 +0.0056 -0.0111 5.1051 +0.0083 -0.0167 5.1051 +0.0111 -0.0222 5.1051 +0.0139 -0.0278 5.1051 +0.0167 -0.0333 5.1051 +0.0194 -0.0389 5.1051 +0.0222 -0.0444 5.1051 +0.0250 -0.0500 5.1051 +primID: 1 +startangle_c: 13 +endpose_c: 3 -6 13 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0083 -0.0167 5.1051 +0.0167 -0.0333 5.1051 +0.0250 -0.0500 5.1051 +0.0333 -0.0667 5.1051 +0.0417 -0.0833 5.1051 +0.0500 -0.1000 5.1051 +0.0583 -0.1167 5.1051 +0.0667 -0.1333 5.1051 +0.0750 -0.1500 5.1051 +primID: 2 +startangle_c: 13 +endpose_c: -1 2 13 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 5.1051 +-0.0028 0.0056 5.1051 +-0.0056 0.0111 5.1051 +-0.0083 0.0167 5.1051 +-0.0111 0.0222 5.1051 +-0.0139 0.0278 5.1051 +-0.0167 0.0333 5.1051 +-0.0194 0.0389 5.1051 +-0.0222 0.0444 5.1051 +-0.0250 0.0500 5.1051 +primID: 3 +startangle_c: 13 +endpose_c: 4 -5 14 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0092 -0.0149 5.1354 +0.0189 -0.0296 5.1657 +0.0291 -0.0440 5.1960 +0.0398 -0.0582 5.2263 +0.0509 -0.0722 5.2566 +0.0625 -0.0858 5.2869 +0.0746 -0.0992 5.3172 +0.0871 -0.1123 5.3475 +0.1000 -0.1250 5.3778 +primID: 4 +startangle_c: 13 +endpose_c: 2 -7 12 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0078 -0.0188 5.1051 +0.0156 -0.0377 5.1051 +0.0234 -0.0565 5.1051 +0.0312 -0.0754 5.0860 +0.0379 -0.0946 5.0113 +0.0432 -0.1143 4.9366 +0.0470 -0.1344 4.8618 +0.0492 -0.1546 4.7871 +0.0500 -0.1750 4.7124 +primID: 5 +startangle_c: 13 +endpose_c: 0 0 14 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0000 0.0000 5.1487 +0.0000 0.0000 5.1924 +0.0000 0.0000 5.2360 +0.0000 0.0000 5.2796 +0.0000 0.0000 5.3233 +0.0000 0.0000 5.3669 +0.0000 0.0000 5.4105 +0.0000 0.0000 5.4542 +0.0000 0.0000 5.4978 +primID: 6 +startangle_c: 13 +endpose_c: 0 0 12 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0000 0.0000 5.0615 +0.0000 0.0000 5.0178 +0.0000 0.0000 4.9742 +0.0000 0.0000 4.9306 +0.0000 0.0000 4.8869 +0.0000 0.0000 4.8433 +0.0000 0.0000 4.7997 +0.0000 0.0000 4.7560 +0.0000 0.0000 4.7124 +primID: 7 +startangle_c: 13 +endpose_c: 2 1 13 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0056 0.0028 5.1051 +0.0111 0.0056 5.1051 +0.0167 0.0083 5.1051 +0.0222 0.0111 5.1051 +0.0278 0.0139 5.1051 +0.0333 0.0167 5.1051 +0.0389 0.0194 5.1051 +0.0444 0.0222 5.1051 +0.0500 0.0250 5.1051 +primID: 8 +startangle_c: 13 +endpose_c: -2 -1 13 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.1051 +-0.0056 -0.0028 5.1051 +-0.0111 -0.0056 5.1051 +-0.0167 -0.0083 5.1051 +-0.0222 -0.0111 5.1051 +-0.0278 -0.0139 5.1051 +-0.0333 -0.0167 5.1051 +-0.0389 -0.0194 5.1051 +-0.0444 -0.0222 5.1051 +-0.0500 -0.0250 5.1051 +primID: 9 +startangle_c: 13 +endpose_c: -4 5 14 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 5.1051 +-0.0092 0.0149 5.1354 +-0.0189 0.0296 5.1657 +-0.0291 0.0440 5.1960 +-0.0398 0.0582 5.2263 +-0.0509 0.0722 5.2566 +-0.0625 0.0858 5.2869 +-0.0746 0.0992 5.3172 +-0.0871 0.1123 5.3475 +-0.1000 0.1250 5.3778 +primID: 10 +startangle_c: 13 +endpose_c: -2 7 12 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 5.1051 +-0.0078 0.0188 5.1051 +-0.0156 0.0377 5.1051 +-0.0234 0.0565 5.1051 +-0.0312 0.0754 5.0860 +-0.0379 0.0946 5.0113 +-0.0432 0.1143 4.9366 +-0.0470 0.1344 4.8618 +-0.0492 0.1546 4.7871 +-0.0500 0.1750 4.7124 +primID: 0 +startangle_c: 14 +endpose_c: 1 -1 14 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0028 -0.0028 5.4978 +0.0056 -0.0056 5.4978 +0.0083 -0.0083 5.4978 +0.0111 -0.0111 5.4978 +0.0139 -0.0139 5.4978 +0.0167 -0.0167 5.4978 +0.0194 -0.0194 5.4978 +0.0222 -0.0222 5.4978 +0.0250 -0.0250 5.4978 +primID: 1 +startangle_c: 14 +endpose_c: 6 -6 14 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0167 -0.0167 5.4978 +0.0333 -0.0333 5.4978 +0.0500 -0.0500 5.4978 +0.0667 -0.0667 5.4978 +0.0833 -0.0833 5.4978 +0.1000 -0.1000 5.4978 +0.1167 -0.1167 5.4978 +0.1333 -0.1333 5.4978 +0.1500 -0.1500 5.4978 +primID: 2 +startangle_c: 14 +endpose_c: -1 1 14 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 5.4978 +-0.0028 0.0028 5.4978 +-0.0056 0.0056 5.4978 +-0.0083 0.0083 5.4978 +-0.0111 0.0111 5.4978 +-0.0139 0.0139 5.4978 +-0.0167 0.0167 5.4978 +-0.0194 0.0194 5.4978 +-0.0222 0.0222 5.4978 +-0.0250 0.0250 5.4978 +primID: 3 +startangle_c: 14 +endpose_c: 7 -5 15 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0170 -0.0170 5.4978 +0.0342 -0.0339 5.5275 +0.0522 -0.0500 5.5793 +0.0709 -0.0651 5.6312 +0.0904 -0.0792 5.6830 +0.1107 -0.0923 5.7349 +0.1315 -0.1043 5.7868 +0.1530 -0.1152 5.8386 +0.1750 -0.1250 5.8905 +primID: 4 +startangle_c: 14 +endpose_c: 5 -7 13 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0170 -0.0170 5.4978 +0.0339 -0.0342 5.4681 +0.0500 -0.0522 5.4162 +0.0651 -0.0709 5.3644 +0.0792 -0.0904 5.3125 +0.0923 -0.1107 5.2607 +0.1043 -0.1315 5.2088 +0.1152 -0.1530 5.1569 +0.1250 -0.1750 5.1051 +primID: 5 +startangle_c: 14 +endpose_c: 0 0 15 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0000 0.0000 5.5414 +0.0000 0.0000 5.5851 +0.0000 0.0000 5.6287 +0.0000 0.0000 5.6723 +0.0000 0.0000 5.7160 +0.0000 0.0000 5.7596 +0.0000 0.0000 5.8032 +0.0000 0.0000 5.8469 +0.0000 0.0000 5.8905 +primID: 6 +startangle_c: 14 +endpose_c: 0 0 13 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0000 0.0000 5.4542 +0.0000 0.0000 5.4105 +0.0000 0.0000 5.3669 +0.0000 0.0000 5.3233 +0.0000 0.0000 5.2796 +0.0000 0.0000 5.2360 +0.0000 0.0000 5.1924 +0.0000 0.0000 5.1487 +0.0000 0.0000 5.1051 +primID: 7 +startangle_c: 14 +endpose_c: 1 1 14 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0028 0.0028 5.4978 +0.0056 0.0056 5.4978 +0.0083 0.0083 5.4978 +0.0111 0.0111 5.4978 +0.0139 0.0139 5.4978 +0.0167 0.0167 5.4978 +0.0194 0.0194 5.4978 +0.0222 0.0222 5.4978 +0.0250 0.0250 5.4978 +primID: 8 +startangle_c: 14 +endpose_c: -1 -1 14 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.4978 +-0.0028 -0.0028 5.4978 +-0.0056 -0.0056 5.4978 +-0.0083 -0.0083 5.4978 +-0.0111 -0.0111 5.4978 +-0.0139 -0.0139 5.4978 +-0.0167 -0.0167 5.4978 +-0.0194 -0.0194 5.4978 +-0.0222 -0.0222 5.4978 +-0.0250 -0.0250 5.4978 +primID: 9 +startangle_c: 14 +endpose_c: -7 5 15 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 5.4978 +-0.0170 0.0170 5.4978 +-0.0342 0.0339 5.5275 +-0.0522 0.0500 5.5793 +-0.0709 0.0651 5.6312 +-0.0904 0.0792 5.6830 +-0.1107 0.0923 5.7349 +-0.1315 0.1043 5.7868 +-0.1530 0.1152 5.8386 +-0.1750 0.1250 5.8905 +primID: 10 +startangle_c: 14 +endpose_c: -5 7 13 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 5.4978 +-0.0170 0.0170 5.4978 +-0.0339 0.0342 5.4681 +-0.0500 0.0522 5.4162 +-0.0651 0.0709 5.3644 +-0.0792 0.0904 5.3125 +-0.0923 0.1107 5.2607 +-0.1043 0.1315 5.2088 +-0.1152 0.1530 5.1569 +-0.1250 0.1750 5.1051 +primID: 0 +startangle_c: 15 +endpose_c: 2 -1 15 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0056 -0.0028 5.8905 +0.0111 -0.0056 5.8905 +0.0167 -0.0083 5.8905 +0.0222 -0.0111 5.8905 +0.0278 -0.0139 5.8905 +0.0333 -0.0167 5.8905 +0.0389 -0.0194 5.8905 +0.0444 -0.0222 5.8905 +0.0500 -0.0250 5.8905 +primID: 1 +startangle_c: 15 +endpose_c: 6 -3 15 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0167 -0.0083 5.8905 +0.0333 -0.0167 5.8905 +0.0500 -0.0250 5.8905 +0.0667 -0.0333 5.8905 +0.0833 -0.0417 5.8905 +0.1000 -0.0500 5.8905 +0.1167 -0.0583 5.8905 +0.1333 -0.0667 5.8905 +0.1500 -0.0750 5.8905 +primID: 2 +startangle_c: 15 +endpose_c: -2 1 15 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 5.8905 +-0.0056 0.0028 5.8905 +-0.0111 0.0056 5.8905 +-0.0167 0.0083 5.8905 +-0.0222 0.0111 5.8905 +-0.0278 0.0139 5.8905 +-0.0333 0.0167 5.8905 +-0.0389 0.0194 5.8905 +-0.0444 0.0222 5.8905 +-0.0500 0.0250 5.8905 +primID: 3 +startangle_c: 15 +endpose_c: 5 -4 14 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0149 -0.0092 5.8602 +0.0296 -0.0189 5.8299 +0.0440 -0.0291 5.7996 +0.0582 -0.0398 5.7693 +0.0722 -0.0509 5.7390 +0.0858 -0.0625 5.7087 +0.0992 -0.0746 5.6784 +0.1123 -0.0871 5.6481 +0.1250 -0.1000 5.6178 +primID: 4 +startangle_c: 15 +endpose_c: 7 -2 0 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0188 -0.0078 5.8905 +0.0377 -0.0156 5.8905 +0.0565 -0.0234 5.8905 +0.0754 -0.0312 5.9096 +0.0946 -0.0379 5.9843 +0.1143 -0.0432 6.0590 +0.1344 -0.0470 6.1337 +0.1546 -0.0492 6.2085 +0.1750 -0.0500 6.2832 +primID: 5 +startangle_c: 15 +endpose_c: 0 0 14 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0000 0.0000 5.8469 +0.0000 0.0000 5.8032 +0.0000 0.0000 5.7596 +0.0000 0.0000 5.7160 +0.0000 0.0000 5.6723 +0.0000 0.0000 5.6287 +0.0000 0.0000 5.5851 +0.0000 0.0000 5.5414 +0.0000 0.0000 5.4978 +primID: 6 +startangle_c: 15 +endpose_c: 0 0 0 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0000 0.0000 5.9341 +0.0000 0.0000 5.9778 +0.0000 0.0000 6.0214 +0.0000 0.0000 6.0650 +0.0000 0.0000 6.1087 +0.0000 0.0000 6.1523 +0.0000 0.0000 6.1959 +0.0000 0.0000 6.2396 +0.0000 0.0000 0.0000 +primID: 7 +startangle_c: 15 +endpose_c: -1 -2 15 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.8905 +-0.0028 -0.0056 5.8905 +-0.0056 -0.0111 5.8905 +-0.0083 -0.0167 5.8905 +-0.0111 -0.0222 5.8905 +-0.0139 -0.0278 5.8905 +-0.0167 -0.0333 5.8905 +-0.0194 -0.0389 5.8905 +-0.0222 -0.0444 5.8905 +-0.0250 -0.0500 5.8905 +primID: 8 +startangle_c: 15 +endpose_c: 1 2 15 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0028 0.0056 5.8905 +0.0056 0.0111 5.8905 +0.0083 0.0167 5.8905 +0.0111 0.0222 5.8905 +0.0139 0.0278 5.8905 +0.0167 0.0333 5.8905 +0.0194 0.0389 5.8905 +0.0222 0.0444 5.8905 +0.0250 0.0500 5.8905 +primID: 9 +startangle_c: 15 +endpose_c: -5 4 14 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 5.8905 +-0.0149 0.0092 5.8602 +-0.0296 0.0189 5.8299 +-0.0440 0.0291 5.7996 +-0.0582 0.0398 5.7693 +-0.0722 0.0509 5.7390 +-0.0858 0.0625 5.7087 +-0.0992 0.0746 5.6784 +-0.1123 0.0871 5.6481 +-0.1250 0.1000 5.6178 +primID: 10 +startangle_c: 15 +endpose_c: -7 2 0 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 5.8905 +-0.0188 0.0078 5.8905 +-0.0377 0.0156 5.8905 +-0.0565 0.0234 5.8905 +-0.0754 0.0312 5.9096 +-0.0946 0.0379 5.9843 +-0.1143 0.0432 6.0590 +-0.1344 0.0470 6.1337 +-0.1546 0.0492 6.2085 +-0.1750 0.0500 6.2832 diff --git a/navigations/sbpl/matlab/mprim/mprim_unic_sidebackdiag.mprim b/navigations/sbpl/matlab/mprim/mprim_unic_sidebackdiag.mprim new file mode 100755 index 0000000..d51d5d4 --- /dev/null +++ b/navigations/sbpl/matlab/mprim/mprim_unic_sidebackdiag.mprim @@ -0,0 +1,3123 @@ +resolution_m: 0.025000 +numberofangles: 16 +totalnumberofprimitives: 208 +primID: 0 +startangle_c: 0 +endpose_c: 1 0 0 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0028 0.0000 0.0000 +0.0056 0.0000 0.0000 +0.0083 0.0000 0.0000 +0.0111 0.0000 0.0000 +0.0139 0.0000 0.0000 +0.0167 0.0000 0.0000 +0.0194 0.0000 0.0000 +0.0222 0.0000 0.0000 +0.0250 0.0000 0.0000 +primID: 1 +startangle_c: 0 +endpose_c: 8 0 0 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0222 0.0000 0.0000 +0.0444 0.0000 0.0000 +0.0667 0.0000 0.0000 +0.0889 0.0000 0.0000 +0.1111 0.0000 0.0000 +0.1333 0.0000 0.0000 +0.1556 0.0000 0.0000 +0.1778 0.0000 0.0000 +0.2000 0.0000 0.0000 +primID: 2 +startangle_c: 0 +endpose_c: -1 0 0 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 0.0000 +-0.0028 0.0000 0.0000 +-0.0056 0.0000 0.0000 +-0.0083 0.0000 0.0000 +-0.0111 0.0000 0.0000 +-0.0139 0.0000 0.0000 +-0.0167 0.0000 0.0000 +-0.0194 0.0000 0.0000 +-0.0222 0.0000 0.0000 +-0.0250 0.0000 0.0000 +primID: 3 +startangle_c: 0 +endpose_c: 8 1 1 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0226 -0.0000 0.0000 +0.0452 -0.0000 0.0000 +0.0678 -0.0000 0.0000 +0.0903 0.0004 0.0488 +0.1128 0.0023 0.1176 +0.1352 0.0057 0.1864 +0.1572 0.0106 0.2551 +0.1789 0.0171 0.3239 +0.2000 0.0250 0.3927 +primID: 4 +startangle_c: 0 +endpose_c: 8 -1 -1 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0226 0.0000 0.0000 +0.0452 0.0000 0.0000 +0.0678 0.0000 0.0000 +0.0903 -0.0004 -0.0488 +0.1128 -0.0023 -0.1176 +0.1352 -0.0057 -0.1864 +0.1572 -0.0106 -0.2551 +0.1789 -0.0171 -0.3239 +0.2000 -0.0250 -0.3927 +primID: 5 +startangle_c: 0 +endpose_c: 0 0 1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0000 0.0000 0.0436 +0.0000 0.0000 0.0873 +0.0000 0.0000 0.1309 +0.0000 0.0000 0.1745 +0.0000 0.0000 0.2182 +0.0000 0.0000 0.2618 +0.0000 0.0000 0.3054 +0.0000 0.0000 0.3491 +0.0000 0.0000 0.3927 +primID: 6 +startangle_c: 0 +endpose_c: 0 0 -1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0000 0.0000 -0.0436 +0.0000 0.0000 -0.0873 +0.0000 0.0000 -0.1309 +0.0000 0.0000 -0.1745 +0.0000 0.0000 -0.2182 +0.0000 0.0000 -0.2618 +0.0000 0.0000 -0.3054 +0.0000 0.0000 -0.3491 +0.0000 0.0000 -0.3927 +primID: 7 +startangle_c: 0 +endpose_c: 0 1 0 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0000 0.0028 0.0000 +0.0000 0.0056 0.0000 +0.0000 0.0083 0.0000 +0.0000 0.0111 0.0000 +0.0000 0.0139 0.0000 +0.0000 0.0167 0.0000 +0.0000 0.0194 0.0000 +0.0000 0.0222 0.0000 +0.0000 0.0250 0.0000 +primID: 8 +startangle_c: 0 +endpose_c: 0 -1 0 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0000 -0.0028 0.0000 +0.0000 -0.0056 0.0000 +0.0000 -0.0083 0.0000 +0.0000 -0.0111 0.0000 +0.0000 -0.0139 0.0000 +0.0000 -0.0167 0.0000 +0.0000 -0.0194 0.0000 +0.0000 -0.0222 0.0000 +0.0000 -0.0250 0.0000 +primID: 9 +startangle_c: 0 +endpose_c: -8 -1 1 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 0.0000 +-0.0226 0.0000 0.0000 +-0.0452 0.0000 0.0000 +-0.0678 0.0000 0.0000 +-0.0903 -0.0004 0.0488 +-0.1128 -0.0023 0.1176 +-0.1352 -0.0057 0.1864 +-0.1572 -0.0106 0.2551 +-0.1789 -0.0171 0.3239 +-0.2000 -0.0250 0.3927 +primID: 10 +startangle_c: 0 +endpose_c: -8 1 -1 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 0.0000 +-0.0226 -0.0000 0.0000 +-0.0452 -0.0000 0.0000 +-0.0678 -0.0000 0.0000 +-0.0903 0.0004 -0.0488 +-0.1128 0.0023 -0.1176 +-0.1352 0.0057 -0.1864 +-0.1572 0.0106 -0.2551 +-0.1789 0.0171 -0.3239 +-0.2000 0.0250 -0.3927 +primID: 11 +startangle_c: 0 +endpose_c: 8 1 0 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0222 0.0028 0.0000 +0.0444 0.0056 0.0000 +0.0667 0.0083 0.0000 +0.0889 0.0111 0.0000 +0.1111 0.0139 0.0000 +0.1333 0.0167 0.0000 +0.1556 0.0194 0.0000 +0.1778 0.0222 0.0000 +0.2000 0.0250 0.0000 +primID: 12 +startangle_c: 0 +endpose_c: 8 -1 0 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0222 -0.0028 0.0000 +0.0444 -0.0056 0.0000 +0.0667 -0.0083 0.0000 +0.0889 -0.0111 0.0000 +0.1111 -0.0139 0.0000 +0.1333 -0.0167 0.0000 +0.1556 -0.0194 0.0000 +0.1778 -0.0222 0.0000 +0.2000 -0.0250 0.0000 +primID: 0 +startangle_c: 1 +endpose_c: 2 1 1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0056 0.0028 0.3927 +0.0111 0.0056 0.3927 +0.0167 0.0083 0.3927 +0.0222 0.0111 0.3927 +0.0278 0.0139 0.3927 +0.0333 0.0167 0.3927 +0.0389 0.0194 0.3927 +0.0444 0.0222 0.3927 +0.0500 0.0250 0.3927 +primID: 1 +startangle_c: 1 +endpose_c: 6 3 1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0167 0.0083 0.3927 +0.0333 0.0167 0.3927 +0.0500 0.0250 0.3927 +0.0667 0.0333 0.3927 +0.0833 0.0417 0.3927 +0.1000 0.0500 0.3927 +0.1167 0.0583 0.3927 +0.1333 0.0667 0.3927 +0.1500 0.0750 0.3927 +primID: 2 +startangle_c: 1 +endpose_c: -2 -1 1 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 0.3927 +-0.0056 -0.0028 0.3927 +-0.0111 -0.0056 0.3927 +-0.0167 -0.0083 0.3927 +-0.0222 -0.0111 0.3927 +-0.0278 -0.0139 0.3927 +-0.0333 -0.0167 0.3927 +-0.0389 -0.0194 0.3927 +-0.0444 -0.0222 0.3927 +-0.0500 -0.0250 0.3927 +primID: 3 +startangle_c: 1 +endpose_c: 5 4 2 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0149 0.0092 0.4230 +0.0296 0.0189 0.4533 +0.0440 0.0291 0.4836 +0.0582 0.0398 0.5139 +0.0722 0.0509 0.5442 +0.0858 0.0625 0.5745 +0.0992 0.0746 0.6048 +0.1123 0.0871 0.6351 +0.1250 0.1000 0.6654 +primID: 4 +startangle_c: 1 +endpose_c: 7 2 0 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0188 0.0078 0.3927 +0.0377 0.0156 0.3927 +0.0565 0.0234 0.3927 +0.0754 0.0312 0.3736 +0.0946 0.0379 0.2989 +0.1143 0.0432 0.2242 +0.1344 0.0470 0.1494 +0.1546 0.0492 0.0747 +0.1750 0.0500 0.0000 +primID: 5 +startangle_c: 1 +endpose_c: 0 0 2 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0000 0.0000 0.4363 +0.0000 0.0000 0.4800 +0.0000 0.0000 0.5236 +0.0000 0.0000 0.5672 +0.0000 0.0000 0.6109 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.6981 +0.0000 0.0000 0.7418 +0.0000 0.0000 0.7854 +primID: 6 +startangle_c: 1 +endpose_c: 0 0 0 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0000 0.0000 0.3491 +0.0000 0.0000 0.3054 +0.0000 0.0000 0.2618 +0.0000 0.0000 0.2182 +0.0000 0.0000 0.1745 +0.0000 0.0000 0.1309 +0.0000 0.0000 0.0873 +0.0000 0.0000 0.0436 +0.0000 0.0000 0.0000 +primID: 7 +startangle_c: 1 +endpose_c: -1 2 1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.3927 +-0.0028 0.0056 0.3927 +-0.0056 0.0111 0.3927 +-0.0083 0.0167 0.3927 +-0.0111 0.0222 0.3927 +-0.0139 0.0278 0.3927 +-0.0167 0.0333 0.3927 +-0.0194 0.0389 0.3927 +-0.0222 0.0444 0.3927 +-0.0250 0.0500 0.3927 +primID: 8 +startangle_c: 1 +endpose_c: 1 -2 1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0028 -0.0056 0.3927 +0.0056 -0.0111 0.3927 +0.0083 -0.0167 0.3927 +0.0111 -0.0222 0.3927 +0.0139 -0.0278 0.3927 +0.0167 -0.0333 0.3927 +0.0194 -0.0389 0.3927 +0.0222 -0.0444 0.3927 +0.0250 -0.0500 0.3927 +primID: 9 +startangle_c: 1 +endpose_c: -5 -4 2 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 0.3927 +-0.0149 -0.0092 0.4230 +-0.0296 -0.0189 0.4533 +-0.0440 -0.0291 0.4836 +-0.0582 -0.0398 0.5139 +-0.0722 -0.0509 0.5442 +-0.0858 -0.0625 0.5745 +-0.0992 -0.0746 0.6048 +-0.1123 -0.0871 0.6351 +-0.1250 -0.1000 0.6654 +primID: 10 +startangle_c: 1 +endpose_c: -7 -2 0 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 0.3927 +-0.0188 -0.0078 0.3927 +-0.0377 -0.0156 0.3927 +-0.0565 -0.0234 0.3927 +-0.0754 -0.0312 0.3736 +-0.0946 -0.0379 0.2989 +-0.1143 -0.0432 0.2242 +-0.1344 -0.0470 0.1494 +-0.1546 -0.0492 0.0747 +-0.1750 -0.0500 0.0000 +primID: 11 +startangle_c: 1 +endpose_c: 5 4 1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0139 0.0111 0.3927 +0.0278 0.0222 0.3927 +0.0417 0.0333 0.3927 +0.0556 0.0444 0.3927 +0.0694 0.0556 0.3927 +0.0833 0.0667 0.3927 +0.0972 0.0778 0.3927 +0.1111 0.0889 0.3927 +0.1250 0.1000 0.3927 +primID: 12 +startangle_c: 1 +endpose_c: 7 2 1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0194 0.0056 0.3927 +0.0389 0.0111 0.3927 +0.0583 0.0167 0.3927 +0.0778 0.0222 0.3927 +0.0972 0.0278 0.3927 +0.1167 0.0333 0.3927 +0.1361 0.0389 0.3927 +0.1556 0.0444 0.3927 +0.1750 0.0500 0.3927 +primID: 0 +startangle_c: 2 +endpose_c: 1 1 2 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0028 0.0028 0.7854 +0.0056 0.0056 0.7854 +0.0083 0.0083 0.7854 +0.0111 0.0111 0.7854 +0.0139 0.0139 0.7854 +0.0167 0.0167 0.7854 +0.0194 0.0194 0.7854 +0.0222 0.0222 0.7854 +0.0250 0.0250 0.7854 +primID: 1 +startangle_c: 2 +endpose_c: 6 6 2 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0167 0.0167 0.7854 +0.0333 0.0333 0.7854 +0.0500 0.0500 0.7854 +0.0667 0.0667 0.7854 +0.0833 0.0833 0.7854 +0.1000 0.1000 0.7854 +0.1167 0.1167 0.7854 +0.1333 0.1333 0.7854 +0.1500 0.1500 0.7854 +primID: 2 +startangle_c: 2 +endpose_c: -1 -1 2 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 0.7854 +-0.0028 -0.0028 0.7854 +-0.0056 -0.0056 0.7854 +-0.0083 -0.0083 0.7854 +-0.0111 -0.0111 0.7854 +-0.0139 -0.0139 0.7854 +-0.0167 -0.0167 0.7854 +-0.0194 -0.0194 0.7854 +-0.0222 -0.0222 0.7854 +-0.0250 -0.0250 0.7854 +primID: 3 +startangle_c: 2 +endpose_c: 5 7 3 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0170 0.0170 0.7854 +0.0339 0.0342 0.8151 +0.0500 0.0522 0.8669 +0.0651 0.0709 0.9188 +0.0792 0.0904 0.9707 +0.0923 0.1107 1.0225 +0.1043 0.1315 1.0744 +0.1152 0.1530 1.1262 +0.1250 0.1750 1.1781 +primID: 4 +startangle_c: 2 +endpose_c: 7 5 1 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0170 0.0170 0.7854 +0.0342 0.0339 0.7557 +0.0522 0.0500 0.7039 +0.0709 0.0651 0.6520 +0.0904 0.0792 0.6001 +0.1107 0.0923 0.5483 +0.1315 0.1043 0.4964 +0.1530 0.1152 0.4446 +0.1750 0.1250 0.3927 +primID: 5 +startangle_c: 2 +endpose_c: 0 0 3 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0000 0.0000 0.8290 +0.0000 0.0000 0.8727 +0.0000 0.0000 0.9163 +0.0000 0.0000 0.9599 +0.0000 0.0000 1.0036 +0.0000 0.0000 1.0472 +0.0000 0.0000 1.0908 +0.0000 0.0000 1.1345 +0.0000 0.0000 1.1781 +primID: 6 +startangle_c: 2 +endpose_c: 0 0 1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0000 0.0000 0.7418 +0.0000 0.0000 0.6981 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.6109 +0.0000 0.0000 0.5672 +0.0000 0.0000 0.5236 +0.0000 0.0000 0.4800 +0.0000 0.0000 0.4363 +0.0000 0.0000 0.3927 +primID: 7 +startangle_c: 2 +endpose_c: -1 1 2 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.7854 +-0.0028 0.0028 0.7854 +-0.0056 0.0056 0.7854 +-0.0083 0.0083 0.7854 +-0.0111 0.0111 0.7854 +-0.0139 0.0139 0.7854 +-0.0167 0.0167 0.7854 +-0.0194 0.0194 0.7854 +-0.0222 0.0222 0.7854 +-0.0250 0.0250 0.7854 +primID: 8 +startangle_c: 2 +endpose_c: 1 -1 2 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0028 -0.0028 0.7854 +0.0056 -0.0056 0.7854 +0.0083 -0.0083 0.7854 +0.0111 -0.0111 0.7854 +0.0139 -0.0139 0.7854 +0.0167 -0.0167 0.7854 +0.0194 -0.0194 0.7854 +0.0222 -0.0222 0.7854 +0.0250 -0.0250 0.7854 +primID: 9 +startangle_c: 2 +endpose_c: -5 -7 3 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 0.7854 +-0.0170 -0.0170 0.7854 +-0.0339 -0.0342 0.8151 +-0.0500 -0.0522 0.8669 +-0.0651 -0.0709 0.9188 +-0.0792 -0.0904 0.9707 +-0.0923 -0.1107 1.0225 +-0.1043 -0.1315 1.0744 +-0.1152 -0.1530 1.1262 +-0.1250 -0.1750 1.1781 +primID: 10 +startangle_c: 2 +endpose_c: -7 -5 1 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 0.7854 +-0.0170 -0.0170 0.7854 +-0.0342 -0.0339 0.7557 +-0.0522 -0.0500 0.7039 +-0.0709 -0.0651 0.6520 +-0.0904 -0.0792 0.6001 +-0.1107 -0.0923 0.5483 +-0.1315 -0.1043 0.4964 +-0.1530 -0.1152 0.4446 +-0.1750 -0.1250 0.3927 +primID: 11 +startangle_c: 2 +endpose_c: 5 7 2 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0139 0.0194 0.7854 +0.0278 0.0389 0.7854 +0.0417 0.0583 0.7854 +0.0556 0.0778 0.7854 +0.0694 0.0972 0.7854 +0.0833 0.1167 0.7854 +0.0972 0.1361 0.7854 +0.1111 0.1556 0.7854 +0.1250 0.1750 0.7854 +primID: 12 +startangle_c: 2 +endpose_c: 7 5 2 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0194 0.0139 0.7854 +0.0389 0.0278 0.7854 +0.0583 0.0417 0.7854 +0.0778 0.0556 0.7854 +0.0972 0.0694 0.7854 +0.1167 0.0833 0.7854 +0.1361 0.0972 0.7854 +0.1556 0.1111 0.7854 +0.1750 0.1250 0.7854 +primID: 0 +startangle_c: 3 +endpose_c: 1 2 3 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0028 0.0056 1.1781 +0.0056 0.0111 1.1781 +0.0083 0.0167 1.1781 +0.0111 0.0222 1.1781 +0.0139 0.0278 1.1781 +0.0167 0.0333 1.1781 +0.0194 0.0389 1.1781 +0.0222 0.0444 1.1781 +0.0250 0.0500 1.1781 +primID: 1 +startangle_c: 3 +endpose_c: 3 6 3 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0083 0.0167 1.1781 +0.0167 0.0333 1.1781 +0.0250 0.0500 1.1781 +0.0333 0.0667 1.1781 +0.0417 0.0833 1.1781 +0.0500 0.1000 1.1781 +0.0583 0.1167 1.1781 +0.0667 0.1333 1.1781 +0.0750 0.1500 1.1781 +primID: 2 +startangle_c: 3 +endpose_c: -1 -2 3 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 1.1781 +-0.0028 -0.0056 1.1781 +-0.0056 -0.0111 1.1781 +-0.0083 -0.0167 1.1781 +-0.0111 -0.0222 1.1781 +-0.0139 -0.0278 1.1781 +-0.0167 -0.0333 1.1781 +-0.0194 -0.0389 1.1781 +-0.0222 -0.0444 1.1781 +-0.0250 -0.0500 1.1781 +primID: 3 +startangle_c: 3 +endpose_c: 4 5 2 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0092 0.0149 1.1478 +0.0189 0.0296 1.1175 +0.0291 0.0440 1.0872 +0.0398 0.0582 1.0569 +0.0509 0.0722 1.0266 +0.0625 0.0858 0.9963 +0.0746 0.0992 0.9660 +0.0871 0.1123 0.9357 +0.1000 0.1250 0.9054 +primID: 4 +startangle_c: 3 +endpose_c: 2 7 4 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0078 0.0188 1.1781 +0.0156 0.0377 1.1781 +0.0234 0.0565 1.1781 +0.0312 0.0754 1.1972 +0.0379 0.0946 1.2719 +0.0432 0.1143 1.3466 +0.0470 0.1344 1.4214 +0.0492 0.1546 1.4961 +0.0500 0.1750 1.5708 +primID: 5 +startangle_c: 3 +endpose_c: 0 0 2 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0000 0.0000 1.1345 +0.0000 0.0000 1.0908 +0.0000 0.0000 1.0472 +0.0000 0.0000 1.0036 +0.0000 0.0000 0.9599 +0.0000 0.0000 0.9163 +0.0000 0.0000 0.8727 +0.0000 0.0000 0.8290 +0.0000 0.0000 0.7854 +primID: 6 +startangle_c: 3 +endpose_c: 0 0 4 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0000 0.0000 1.2217 +0.0000 0.0000 1.2654 +0.0000 0.0000 1.3090 +0.0000 0.0000 1.3526 +0.0000 0.0000 1.3963 +0.0000 0.0000 1.4399 +0.0000 0.0000 1.4835 +0.0000 0.0000 1.5272 +0.0000 0.0000 1.5708 +primID: 7 +startangle_c: 3 +endpose_c: 2 -1 3 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0056 -0.0028 1.1781 +0.0111 -0.0056 1.1781 +0.0167 -0.0083 1.1781 +0.0222 -0.0111 1.1781 +0.0278 -0.0139 1.1781 +0.0333 -0.0167 1.1781 +0.0389 -0.0194 1.1781 +0.0444 -0.0222 1.1781 +0.0500 -0.0250 1.1781 +primID: 8 +startangle_c: 3 +endpose_c: -2 1 3 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.1781 +-0.0056 0.0028 1.1781 +-0.0111 0.0056 1.1781 +-0.0167 0.0083 1.1781 +-0.0222 0.0111 1.1781 +-0.0278 0.0139 1.1781 +-0.0333 0.0167 1.1781 +-0.0389 0.0194 1.1781 +-0.0444 0.0222 1.1781 +-0.0500 0.0250 1.1781 +primID: 9 +startangle_c: 3 +endpose_c: -4 -5 2 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 1.1781 +-0.0092 -0.0149 1.1478 +-0.0189 -0.0296 1.1175 +-0.0291 -0.0440 1.0872 +-0.0398 -0.0582 1.0569 +-0.0509 -0.0722 1.0266 +-0.0625 -0.0858 0.9963 +-0.0746 -0.0992 0.9660 +-0.0871 -0.1123 0.9357 +-0.1000 -0.1250 0.9054 +primID: 10 +startangle_c: 3 +endpose_c: -2 -7 4 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 1.1781 +-0.0078 -0.0188 1.1781 +-0.0156 -0.0377 1.1781 +-0.0234 -0.0565 1.1781 +-0.0312 -0.0754 1.1972 +-0.0379 -0.0946 1.2719 +-0.0432 -0.1143 1.3466 +-0.0470 -0.1344 1.4214 +-0.0492 -0.1546 1.4961 +-0.0500 -0.1750 1.5708 +primID: 11 +startangle_c: 3 +endpose_c: 4 5 3 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0111 0.0139 1.1781 +0.0222 0.0278 1.1781 +0.0333 0.0417 1.1781 +0.0444 0.0556 1.1781 +0.0556 0.0694 1.1781 +0.0667 0.0833 1.1781 +0.0778 0.0972 1.1781 +0.0889 0.1111 1.1781 +0.1000 0.1250 1.1781 +primID: 12 +startangle_c: 3 +endpose_c: 2 7 3 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0056 0.0194 1.1781 +0.0111 0.0389 1.1781 +0.0167 0.0583 1.1781 +0.0222 0.0778 1.1781 +0.0278 0.0972 1.1781 +0.0333 0.1167 1.1781 +0.0389 0.1361 1.1781 +0.0444 0.1556 1.1781 +0.0500 0.1750 1.1781 +primID: 0 +startangle_c: 4 +endpose_c: 0 1 4 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0028 1.5708 +0.0000 0.0056 1.5708 +0.0000 0.0083 1.5708 +0.0000 0.0111 1.5708 +0.0000 0.0139 1.5708 +0.0000 0.0167 1.5708 +0.0000 0.0194 1.5708 +0.0000 0.0222 1.5708 +0.0000 0.0250 1.5708 +primID: 1 +startangle_c: 4 +endpose_c: 0 8 4 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0222 1.5708 +0.0000 0.0444 1.5708 +0.0000 0.0667 1.5708 +0.0000 0.0889 1.5708 +0.0000 0.1111 1.5708 +0.0000 0.1333 1.5708 +0.0000 0.1556 1.5708 +0.0000 0.1778 1.5708 +0.0000 0.2000 1.5708 +primID: 2 +startangle_c: 4 +endpose_c: 0 -1 4 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 -0.0028 1.5708 +0.0000 -0.0056 1.5708 +0.0000 -0.0083 1.5708 +0.0000 -0.0111 1.5708 +0.0000 -0.0139 1.5708 +0.0000 -0.0167 1.5708 +0.0000 -0.0194 1.5708 +0.0000 -0.0222 1.5708 +0.0000 -0.0250 1.5708 +primID: 3 +startangle_c: 4 +endpose_c: -1 8 5 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0226 1.5708 +0.0000 0.0452 1.5708 +0.0000 0.0678 1.5708 +-0.0004 0.0903 1.6196 +-0.0023 0.1128 1.6884 +-0.0057 0.1352 1.7572 +-0.0106 0.1572 1.8259 +-0.0171 0.1789 1.8947 +-0.0250 0.2000 1.9635 +primID: 4 +startangle_c: 4 +endpose_c: 1 8 3 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.5708 +-0.0000 0.0226 1.5708 +-0.0000 0.0452 1.5708 +-0.0000 0.0678 1.5708 +0.0004 0.0903 1.5220 +0.0023 0.1128 1.4532 +0.0057 0.1352 1.3844 +0.0106 0.1572 1.3156 +0.0171 0.1789 1.2469 +0.0250 0.2000 1.1781 +primID: 5 +startangle_c: 4 +endpose_c: 0 0 5 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0000 1.6144 +0.0000 0.0000 1.6581 +0.0000 0.0000 1.7017 +0.0000 0.0000 1.7453 +0.0000 0.0000 1.7890 +0.0000 0.0000 1.8326 +0.0000 0.0000 1.8762 +0.0000 0.0000 1.9199 +0.0000 0.0000 1.9635 +primID: 6 +startangle_c: 4 +endpose_c: 0 0 3 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0000 1.5272 +0.0000 0.0000 1.4835 +0.0000 0.0000 1.4399 +0.0000 0.0000 1.3963 +0.0000 0.0000 1.3526 +0.0000 0.0000 1.3090 +0.0000 0.0000 1.2654 +0.0000 0.0000 1.2217 +0.0000 0.0000 1.1781 +primID: 7 +startangle_c: 4 +endpose_c: -1 0 4 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.5708 +-0.0028 0.0000 1.5708 +-0.0056 0.0000 1.5708 +-0.0083 0.0000 1.5708 +-0.0111 0.0000 1.5708 +-0.0139 0.0000 1.5708 +-0.0167 0.0000 1.5708 +-0.0194 0.0000 1.5708 +-0.0222 0.0000 1.5708 +-0.0250 0.0000 1.5708 +primID: 8 +startangle_c: 4 +endpose_c: 1 0 4 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0028 0.0000 1.5708 +0.0056 0.0000 1.5708 +0.0083 0.0000 1.5708 +0.0111 0.0000 1.5708 +0.0139 0.0000 1.5708 +0.0167 0.0000 1.5708 +0.0194 0.0000 1.5708 +0.0222 0.0000 1.5708 +0.0250 0.0000 1.5708 +primID: 9 +startangle_c: 4 +endpose_c: 1 -8 5 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 1.5708 +-0.0000 -0.0226 1.5708 +-0.0000 -0.0452 1.5708 +-0.0000 -0.0678 1.5708 +0.0004 -0.0903 1.6196 +0.0023 -0.1128 1.6884 +0.0057 -0.1352 1.7572 +0.0106 -0.1572 1.8259 +0.0171 -0.1789 1.8947 +0.0250 -0.2000 1.9635 +primID: 10 +startangle_c: 4 +endpose_c: -1 -8 3 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 -0.0226 1.5708 +0.0000 -0.0452 1.5708 +0.0000 -0.0678 1.5708 +-0.0004 -0.0903 1.5220 +-0.0023 -0.1128 1.4532 +-0.0057 -0.1352 1.3844 +-0.0106 -0.1572 1.3156 +-0.0171 -0.1789 1.2469 +-0.0250 -0.2000 1.1781 +primID: 11 +startangle_c: 4 +endpose_c: -1 8 4 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.5708 +-0.0028 0.0222 1.5708 +-0.0056 0.0444 1.5708 +-0.0083 0.0667 1.5708 +-0.0111 0.0889 1.5708 +-0.0139 0.1111 1.5708 +-0.0167 0.1333 1.5708 +-0.0194 0.1556 1.5708 +-0.0222 0.1778 1.5708 +-0.0250 0.2000 1.5708 +primID: 12 +startangle_c: 4 +endpose_c: 1 8 4 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0028 0.0222 1.5708 +0.0056 0.0444 1.5708 +0.0083 0.0667 1.5708 +0.0111 0.0889 1.5708 +0.0139 0.1111 1.5708 +0.0167 0.1333 1.5708 +0.0194 0.1556 1.5708 +0.0222 0.1778 1.5708 +0.0250 0.2000 1.5708 +primID: 0 +startangle_c: 5 +endpose_c: -1 2 5 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0028 0.0056 1.9635 +-0.0056 0.0111 1.9635 +-0.0083 0.0167 1.9635 +-0.0111 0.0222 1.9635 +-0.0139 0.0278 1.9635 +-0.0167 0.0333 1.9635 +-0.0194 0.0389 1.9635 +-0.0222 0.0444 1.9635 +-0.0250 0.0500 1.9635 +primID: 1 +startangle_c: 5 +endpose_c: -3 6 5 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0083 0.0167 1.9635 +-0.0167 0.0333 1.9635 +-0.0250 0.0500 1.9635 +-0.0333 0.0667 1.9635 +-0.0417 0.0833 1.9635 +-0.0500 0.1000 1.9635 +-0.0583 0.1167 1.9635 +-0.0667 0.1333 1.9635 +-0.0750 0.1500 1.9635 +primID: 2 +startangle_c: 5 +endpose_c: 1 -2 5 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0028 -0.0056 1.9635 +0.0056 -0.0111 1.9635 +0.0083 -0.0167 1.9635 +0.0111 -0.0222 1.9635 +0.0139 -0.0278 1.9635 +0.0167 -0.0333 1.9635 +0.0194 -0.0389 1.9635 +0.0222 -0.0444 1.9635 +0.0250 -0.0500 1.9635 +primID: 3 +startangle_c: 5 +endpose_c: -4 5 6 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0092 0.0149 1.9938 +-0.0189 0.0296 2.0241 +-0.0291 0.0440 2.0544 +-0.0398 0.0582 2.0847 +-0.0509 0.0722 2.1150 +-0.0625 0.0858 2.1453 +-0.0746 0.0992 2.1756 +-0.0871 0.1123 2.2059 +-0.1000 0.1250 2.2362 +primID: 4 +startangle_c: 5 +endpose_c: -2 7 4 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0078 0.0188 1.9635 +-0.0156 0.0377 1.9635 +-0.0234 0.0565 1.9635 +-0.0312 0.0754 1.9444 +-0.0379 0.0946 1.8697 +-0.0432 0.1143 1.7950 +-0.0470 0.1344 1.7202 +-0.0492 0.1546 1.6455 +-0.0500 0.1750 1.5708 +primID: 5 +startangle_c: 5 +endpose_c: 0 0 6 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0000 0.0000 2.0071 +0.0000 0.0000 2.0508 +0.0000 0.0000 2.0944 +0.0000 0.0000 2.1380 +0.0000 0.0000 2.1817 +0.0000 0.0000 2.2253 +0.0000 0.0000 2.2689 +0.0000 0.0000 2.3126 +0.0000 0.0000 2.3562 +primID: 6 +startangle_c: 5 +endpose_c: 0 0 4 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0000 0.0000 1.9199 +0.0000 0.0000 1.8762 +0.0000 0.0000 1.8326 +0.0000 0.0000 1.7890 +0.0000 0.0000 1.7453 +0.0000 0.0000 1.7017 +0.0000 0.0000 1.6581 +0.0000 0.0000 1.6144 +0.0000 0.0000 1.5708 +primID: 7 +startangle_c: 5 +endpose_c: -2 -1 5 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0056 -0.0028 1.9635 +-0.0111 -0.0056 1.9635 +-0.0167 -0.0083 1.9635 +-0.0222 -0.0111 1.9635 +-0.0278 -0.0139 1.9635 +-0.0333 -0.0167 1.9635 +-0.0389 -0.0194 1.9635 +-0.0444 -0.0222 1.9635 +-0.0500 -0.0250 1.9635 +primID: 8 +startangle_c: 5 +endpose_c: 2 1 5 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0056 0.0028 1.9635 +0.0111 0.0056 1.9635 +0.0167 0.0083 1.9635 +0.0222 0.0111 1.9635 +0.0278 0.0139 1.9635 +0.0333 0.0167 1.9635 +0.0389 0.0194 1.9635 +0.0444 0.0222 1.9635 +0.0500 0.0250 1.9635 +primID: 9 +startangle_c: 5 +endpose_c: 4 -5 6 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0092 -0.0149 1.9938 +0.0189 -0.0296 2.0241 +0.0291 -0.0440 2.0544 +0.0398 -0.0582 2.0847 +0.0509 -0.0722 2.1150 +0.0625 -0.0858 2.1453 +0.0746 -0.0992 2.1756 +0.0871 -0.1123 2.2059 +0.1000 -0.1250 2.2362 +primID: 10 +startangle_c: 5 +endpose_c: 2 -7 4 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0078 -0.0188 1.9635 +0.0156 -0.0377 1.9635 +0.0234 -0.0565 1.9635 +0.0312 -0.0754 1.9444 +0.0379 -0.0946 1.8697 +0.0432 -0.1143 1.7950 +0.0470 -0.1344 1.7202 +0.0492 -0.1546 1.6455 +0.0500 -0.1750 1.5708 +primID: 11 +startangle_c: 5 +endpose_c: -4 5 5 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0111 0.0139 1.9635 +-0.0222 0.0278 1.9635 +-0.0333 0.0417 1.9635 +-0.0444 0.0556 1.9635 +-0.0556 0.0694 1.9635 +-0.0667 0.0833 1.9635 +-0.0778 0.0972 1.9635 +-0.0889 0.1111 1.9635 +-0.1000 0.1250 1.9635 +primID: 12 +startangle_c: 5 +endpose_c: -2 7 5 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0056 0.0194 1.9635 +-0.0111 0.0389 1.9635 +-0.0167 0.0583 1.9635 +-0.0222 0.0778 1.9635 +-0.0278 0.0972 1.9635 +-0.0333 0.1167 1.9635 +-0.0389 0.1361 1.9635 +-0.0444 0.1556 1.9635 +-0.0500 0.1750 1.9635 +primID: 0 +startangle_c: 6 +endpose_c: -1 1 6 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0028 0.0028 2.3562 +-0.0056 0.0056 2.3562 +-0.0083 0.0083 2.3562 +-0.0111 0.0111 2.3562 +-0.0139 0.0139 2.3562 +-0.0167 0.0167 2.3562 +-0.0194 0.0194 2.3562 +-0.0222 0.0222 2.3562 +-0.0250 0.0250 2.3562 +primID: 1 +startangle_c: 6 +endpose_c: -6 6 6 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0167 0.0167 2.3562 +-0.0333 0.0333 2.3562 +-0.0500 0.0500 2.3562 +-0.0667 0.0667 2.3562 +-0.0833 0.0833 2.3562 +-0.1000 0.1000 2.3562 +-0.1167 0.1167 2.3562 +-0.1333 0.1333 2.3562 +-0.1500 0.1500 2.3562 +primID: 2 +startangle_c: 6 +endpose_c: 1 -1 6 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0028 -0.0028 2.3562 +0.0056 -0.0056 2.3562 +0.0083 -0.0083 2.3562 +0.0111 -0.0111 2.3562 +0.0139 -0.0139 2.3562 +0.0167 -0.0167 2.3562 +0.0194 -0.0194 2.3562 +0.0222 -0.0222 2.3562 +0.0250 -0.0250 2.3562 +primID: 3 +startangle_c: 6 +endpose_c: -7 5 7 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0170 0.0170 2.3562 +-0.0342 0.0339 2.3859 +-0.0522 0.0500 2.4377 +-0.0709 0.0651 2.4896 +-0.0904 0.0792 2.5415 +-0.1107 0.0923 2.5933 +-0.1315 0.1043 2.6452 +-0.1530 0.1152 2.6970 +-0.1750 0.1250 2.7489 +primID: 4 +startangle_c: 6 +endpose_c: -5 7 5 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0170 0.0170 2.3562 +-0.0339 0.0342 2.3265 +-0.0500 0.0522 2.2747 +-0.0651 0.0709 2.2228 +-0.0792 0.0904 2.1709 +-0.0923 0.1107 2.1191 +-0.1043 0.1315 2.0672 +-0.1152 0.1530 2.0154 +-0.1250 0.1750 1.9635 +primID: 5 +startangle_c: 6 +endpose_c: 0 0 7 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0000 0.0000 2.3998 +0.0000 0.0000 2.4435 +0.0000 0.0000 2.4871 +0.0000 0.0000 2.5307 +0.0000 0.0000 2.5744 +0.0000 0.0000 2.6180 +0.0000 0.0000 2.6616 +0.0000 0.0000 2.7053 +0.0000 0.0000 2.7489 +primID: 6 +startangle_c: 6 +endpose_c: 0 0 5 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0000 0.0000 2.3126 +0.0000 0.0000 2.2689 +0.0000 0.0000 2.2253 +0.0000 0.0000 2.1817 +0.0000 0.0000 2.1380 +0.0000 0.0000 2.0944 +0.0000 0.0000 2.0508 +0.0000 0.0000 2.0071 +0.0000 0.0000 1.9635 +primID: 7 +startangle_c: 6 +endpose_c: -1 -1 6 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0028 -0.0028 2.3562 +-0.0056 -0.0056 2.3562 +-0.0083 -0.0083 2.3562 +-0.0111 -0.0111 2.3562 +-0.0139 -0.0139 2.3562 +-0.0167 -0.0167 2.3562 +-0.0194 -0.0194 2.3562 +-0.0222 -0.0222 2.3562 +-0.0250 -0.0250 2.3562 +primID: 8 +startangle_c: 6 +endpose_c: 1 1 6 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0028 0.0028 2.3562 +0.0056 0.0056 2.3562 +0.0083 0.0083 2.3562 +0.0111 0.0111 2.3562 +0.0139 0.0139 2.3562 +0.0167 0.0167 2.3562 +0.0194 0.0194 2.3562 +0.0222 0.0222 2.3562 +0.0250 0.0250 2.3562 +primID: 9 +startangle_c: 6 +endpose_c: 7 -5 7 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0170 -0.0170 2.3562 +0.0342 -0.0339 2.3859 +0.0522 -0.0500 2.4377 +0.0709 -0.0651 2.4896 +0.0904 -0.0792 2.5415 +0.1107 -0.0923 2.5933 +0.1315 -0.1043 2.6452 +0.1530 -0.1152 2.6970 +0.1750 -0.1250 2.7489 +primID: 10 +startangle_c: 6 +endpose_c: 5 -7 5 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0170 -0.0170 2.3562 +0.0339 -0.0342 2.3265 +0.0500 -0.0522 2.2747 +0.0651 -0.0709 2.2228 +0.0792 -0.0904 2.1709 +0.0923 -0.1107 2.1191 +0.1043 -0.1315 2.0672 +0.1152 -0.1530 2.0154 +0.1250 -0.1750 1.9635 +primID: 11 +startangle_c: 6 +endpose_c: -7 5 6 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0194 0.0139 2.3562 +-0.0389 0.0278 2.3562 +-0.0583 0.0417 2.3562 +-0.0778 0.0556 2.3562 +-0.0972 0.0694 2.3562 +-0.1167 0.0833 2.3562 +-0.1361 0.0972 2.3562 +-0.1556 0.1111 2.3562 +-0.1750 0.1250 2.3562 +primID: 12 +startangle_c: 6 +endpose_c: -5 7 6 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0139 0.0194 2.3562 +-0.0278 0.0389 2.3562 +-0.0417 0.0583 2.3562 +-0.0556 0.0778 2.3562 +-0.0694 0.0972 2.3562 +-0.0833 0.1167 2.3562 +-0.0972 0.1361 2.3562 +-0.1111 0.1556 2.3562 +-0.1250 0.1750 2.3562 +primID: 0 +startangle_c: 7 +endpose_c: -2 1 7 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0056 0.0028 2.7489 +-0.0111 0.0056 2.7489 +-0.0167 0.0083 2.7489 +-0.0222 0.0111 2.7489 +-0.0278 0.0139 2.7489 +-0.0333 0.0167 2.7489 +-0.0389 0.0194 2.7489 +-0.0444 0.0222 2.7489 +-0.0500 0.0250 2.7489 +primID: 1 +startangle_c: 7 +endpose_c: -6 3 7 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0167 0.0083 2.7489 +-0.0333 0.0167 2.7489 +-0.0500 0.0250 2.7489 +-0.0667 0.0333 2.7489 +-0.0833 0.0417 2.7489 +-0.1000 0.0500 2.7489 +-0.1167 0.0583 2.7489 +-0.1333 0.0667 2.7489 +-0.1500 0.0750 2.7489 +primID: 2 +startangle_c: 7 +endpose_c: 2 -1 7 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0056 -0.0028 2.7489 +0.0111 -0.0056 2.7489 +0.0167 -0.0083 2.7489 +0.0222 -0.0111 2.7489 +0.0278 -0.0139 2.7489 +0.0333 -0.0167 2.7489 +0.0389 -0.0194 2.7489 +0.0444 -0.0222 2.7489 +0.0500 -0.0250 2.7489 +primID: 3 +startangle_c: 7 +endpose_c: -5 4 6 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0149 0.0092 2.7186 +-0.0296 0.0189 2.6883 +-0.0440 0.0291 2.6580 +-0.0582 0.0398 2.6277 +-0.0722 0.0509 2.5974 +-0.0858 0.0625 2.5671 +-0.0992 0.0746 2.5368 +-0.1123 0.0871 2.5065 +-0.1250 0.1000 2.4762 +primID: 4 +startangle_c: 7 +endpose_c: -7 2 8 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0188 0.0078 2.7489 +-0.0377 0.0156 2.7489 +-0.0565 0.0234 2.7489 +-0.0754 0.0312 2.7680 +-0.0946 0.0379 2.8427 +-0.1143 0.0432 2.9174 +-0.1344 0.0470 2.9921 +-0.1546 0.0492 3.0669 +-0.1750 0.0500 3.1416 +primID: 5 +startangle_c: 7 +endpose_c: 0 0 6 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0000 0.0000 2.7053 +0.0000 0.0000 2.6616 +0.0000 0.0000 2.6180 +0.0000 0.0000 2.5744 +0.0000 0.0000 2.5307 +0.0000 0.0000 2.4871 +0.0000 0.0000 2.4435 +0.0000 0.0000 2.3998 +0.0000 0.0000 2.3562 +primID: 6 +startangle_c: 7 +endpose_c: 0 0 8 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0000 0.0000 2.7925 +0.0000 0.0000 2.8362 +0.0000 0.0000 2.8798 +0.0000 0.0000 2.9234 +0.0000 0.0000 2.9671 +0.0000 0.0000 3.0107 +0.0000 0.0000 3.0543 +0.0000 0.0000 3.0980 +0.0000 0.0000 3.1416 +primID: 7 +startangle_c: 7 +endpose_c: 1 2 7 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0028 0.0056 2.7489 +0.0056 0.0111 2.7489 +0.0083 0.0167 2.7489 +0.0111 0.0222 2.7489 +0.0139 0.0278 2.7489 +0.0167 0.0333 2.7489 +0.0194 0.0389 2.7489 +0.0222 0.0444 2.7489 +0.0250 0.0500 2.7489 +primID: 8 +startangle_c: 7 +endpose_c: -1 -2 7 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0028 -0.0056 2.7489 +-0.0056 -0.0111 2.7489 +-0.0083 -0.0167 2.7489 +-0.0111 -0.0222 2.7489 +-0.0139 -0.0278 2.7489 +-0.0167 -0.0333 2.7489 +-0.0194 -0.0389 2.7489 +-0.0222 -0.0444 2.7489 +-0.0250 -0.0500 2.7489 +primID: 9 +startangle_c: 7 +endpose_c: 5 -4 6 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0149 -0.0092 2.7186 +0.0296 -0.0189 2.6883 +0.0440 -0.0291 2.6580 +0.0582 -0.0398 2.6277 +0.0722 -0.0509 2.5974 +0.0858 -0.0625 2.5671 +0.0992 -0.0746 2.5368 +0.1123 -0.0871 2.5065 +0.1250 -0.1000 2.4762 +primID: 10 +startangle_c: 7 +endpose_c: 7 -2 8 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0188 -0.0078 2.7489 +0.0377 -0.0156 2.7489 +0.0565 -0.0234 2.7489 +0.0754 -0.0312 2.7680 +0.0946 -0.0379 2.8427 +0.1143 -0.0432 2.9174 +0.1344 -0.0470 2.9921 +0.1546 -0.0492 3.0669 +0.1750 -0.0500 3.1416 +primID: 11 +startangle_c: 7 +endpose_c: -5 4 7 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0139 0.0111 2.7489 +-0.0278 0.0222 2.7489 +-0.0417 0.0333 2.7489 +-0.0556 0.0444 2.7489 +-0.0694 0.0556 2.7489 +-0.0833 0.0667 2.7489 +-0.0972 0.0778 2.7489 +-0.1111 0.0889 2.7489 +-0.1250 0.1000 2.7489 +primID: 12 +startangle_c: 7 +endpose_c: -7 2 7 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0194 0.0056 2.7489 +-0.0389 0.0111 2.7489 +-0.0583 0.0167 2.7489 +-0.0778 0.0222 2.7489 +-0.0972 0.0278 2.7489 +-0.1167 0.0333 2.7489 +-0.1361 0.0389 2.7489 +-0.1556 0.0444 2.7489 +-0.1750 0.0500 2.7489 +primID: 0 +startangle_c: 8 +endpose_c: -1 0 8 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0028 0.0000 3.1416 +-0.0056 0.0000 3.1416 +-0.0083 0.0000 3.1416 +-0.0111 0.0000 3.1416 +-0.0139 0.0000 3.1416 +-0.0167 0.0000 3.1416 +-0.0194 0.0000 3.1416 +-0.0222 0.0000 3.1416 +-0.0250 0.0000 3.1416 +primID: 1 +startangle_c: 8 +endpose_c: -8 0 8 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0222 0.0000 3.1416 +-0.0444 0.0000 3.1416 +-0.0667 0.0000 3.1416 +-0.0889 0.0000 3.1416 +-0.1111 0.0000 3.1416 +-0.1333 0.0000 3.1416 +-0.1556 0.0000 3.1416 +-0.1778 0.0000 3.1416 +-0.2000 0.0000 3.1416 +primID: 2 +startangle_c: 8 +endpose_c: 1 0 8 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0028 0.0000 3.1416 +0.0056 0.0000 3.1416 +0.0083 0.0000 3.1416 +0.0111 0.0000 3.1416 +0.0139 0.0000 3.1416 +0.0167 0.0000 3.1416 +0.0194 0.0000 3.1416 +0.0222 0.0000 3.1416 +0.0250 0.0000 3.1416 +primID: 3 +startangle_c: 8 +endpose_c: -8 -1 9 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0226 0.0000 3.1416 +-0.0452 0.0000 3.1416 +-0.0678 0.0000 3.1416 +-0.0903 -0.0004 3.1904 +-0.1128 -0.0023 3.2592 +-0.1352 -0.0057 3.3280 +-0.1572 -0.0106 3.3967 +-0.1789 -0.0171 3.4655 +-0.2000 -0.0250 3.5343 +primID: 4 +startangle_c: 8 +endpose_c: -8 1 7 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0226 0.0000 3.1416 +-0.0452 0.0000 3.1416 +-0.0678 0.0000 3.1416 +-0.0903 0.0004 3.0928 +-0.1128 0.0023 3.0240 +-0.1352 0.0057 2.9552 +-0.1572 0.0106 2.8864 +-0.1789 0.0171 2.8177 +-0.2000 0.0250 2.7489 +primID: 5 +startangle_c: 8 +endpose_c: 0 0 9 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0000 0.0000 3.1852 +0.0000 0.0000 3.2289 +0.0000 0.0000 3.2725 +0.0000 0.0000 3.3161 +0.0000 0.0000 3.3598 +0.0000 0.0000 3.4034 +0.0000 0.0000 3.4470 +0.0000 0.0000 3.4907 +0.0000 0.0000 3.5343 +primID: 6 +startangle_c: 8 +endpose_c: 0 0 7 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0000 0.0000 3.0980 +0.0000 0.0000 3.0543 +0.0000 0.0000 3.0107 +0.0000 0.0000 2.9671 +0.0000 0.0000 2.9234 +0.0000 0.0000 2.8798 +0.0000 0.0000 2.8362 +0.0000 0.0000 2.7925 +0.0000 0.0000 2.7489 +primID: 7 +startangle_c: 8 +endpose_c: 0 -1 8 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0000 -0.0028 3.1416 +0.0000 -0.0056 3.1416 +0.0000 -0.0083 3.1416 +0.0000 -0.0111 3.1416 +0.0000 -0.0139 3.1416 +0.0000 -0.0167 3.1416 +0.0000 -0.0194 3.1416 +0.0000 -0.0222 3.1416 +0.0000 -0.0250 3.1416 +primID: 8 +startangle_c: 8 +endpose_c: 0 1 8 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0000 0.0028 3.1416 +0.0000 0.0056 3.1416 +0.0000 0.0083 3.1416 +0.0000 0.0111 3.1416 +0.0000 0.0139 3.1416 +0.0000 0.0167 3.1416 +0.0000 0.0194 3.1416 +0.0000 0.0222 3.1416 +0.0000 0.0250 3.1416 +primID: 9 +startangle_c: 8 +endpose_c: 8 1 9 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0226 -0.0000 3.1416 +0.0452 -0.0000 3.1416 +0.0678 -0.0000 3.1416 +0.0903 0.0004 3.1904 +0.1128 0.0023 3.2592 +0.1352 0.0057 3.3280 +0.1572 0.0106 3.3967 +0.1789 0.0171 3.4655 +0.2000 0.0250 3.5343 +primID: 10 +startangle_c: 8 +endpose_c: 8 -1 7 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0226 -0.0000 3.1416 +0.0452 -0.0000 3.1416 +0.0678 -0.0000 3.1416 +0.0903 -0.0004 3.0928 +0.1128 -0.0023 3.0240 +0.1352 -0.0057 2.9552 +0.1572 -0.0106 2.8864 +0.1789 -0.0171 2.8177 +0.2000 -0.0250 2.7489 +primID: 11 +startangle_c: 8 +endpose_c: -8 -1 8 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0222 -0.0028 3.1416 +-0.0444 -0.0056 3.1416 +-0.0667 -0.0083 3.1416 +-0.0889 -0.0111 3.1416 +-0.1111 -0.0139 3.1416 +-0.1333 -0.0167 3.1416 +-0.1556 -0.0194 3.1416 +-0.1778 -0.0222 3.1416 +-0.2000 -0.0250 3.1416 +primID: 12 +startangle_c: 8 +endpose_c: -8 1 8 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0222 0.0028 3.1416 +-0.0444 0.0056 3.1416 +-0.0667 0.0083 3.1416 +-0.0889 0.0111 3.1416 +-0.1111 0.0139 3.1416 +-0.1333 0.0167 3.1416 +-0.1556 0.0194 3.1416 +-0.1778 0.0222 3.1416 +-0.2000 0.0250 3.1416 +primID: 0 +startangle_c: 9 +endpose_c: -2 -1 9 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0056 -0.0028 3.5343 +-0.0111 -0.0056 3.5343 +-0.0167 -0.0083 3.5343 +-0.0222 -0.0111 3.5343 +-0.0278 -0.0139 3.5343 +-0.0333 -0.0167 3.5343 +-0.0389 -0.0194 3.5343 +-0.0444 -0.0222 3.5343 +-0.0500 -0.0250 3.5343 +primID: 1 +startangle_c: 9 +endpose_c: -6 -3 9 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0167 -0.0083 3.5343 +-0.0333 -0.0167 3.5343 +-0.0500 -0.0250 3.5343 +-0.0667 -0.0333 3.5343 +-0.0833 -0.0417 3.5343 +-0.1000 -0.0500 3.5343 +-0.1167 -0.0583 3.5343 +-0.1333 -0.0667 3.5343 +-0.1500 -0.0750 3.5343 +primID: 2 +startangle_c: 9 +endpose_c: 2 1 9 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0056 0.0028 3.5343 +0.0111 0.0056 3.5343 +0.0167 0.0083 3.5343 +0.0222 0.0111 3.5343 +0.0278 0.0139 3.5343 +0.0333 0.0167 3.5343 +0.0389 0.0194 3.5343 +0.0444 0.0222 3.5343 +0.0500 0.0250 3.5343 +primID: 3 +startangle_c: 9 +endpose_c: -5 -4 10 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0149 -0.0092 3.5646 +-0.0296 -0.0189 3.5949 +-0.0440 -0.0291 3.6252 +-0.0582 -0.0398 3.6555 +-0.0722 -0.0509 3.6858 +-0.0858 -0.0625 3.7161 +-0.0992 -0.0746 3.7464 +-0.1123 -0.0871 3.7767 +-0.1250 -0.1000 3.8070 +primID: 4 +startangle_c: 9 +endpose_c: -7 -2 8 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0188 -0.0078 3.5343 +-0.0377 -0.0156 3.5343 +-0.0565 -0.0234 3.5343 +-0.0754 -0.0312 3.5152 +-0.0946 -0.0379 3.4405 +-0.1143 -0.0432 3.3658 +-0.1344 -0.0470 3.2910 +-0.1546 -0.0492 3.2163 +-0.1750 -0.0500 3.1416 +primID: 5 +startangle_c: 9 +endpose_c: 0 0 10 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0000 0.0000 3.5779 +0.0000 0.0000 3.6216 +0.0000 0.0000 3.6652 +0.0000 0.0000 3.7088 +0.0000 0.0000 3.7525 +0.0000 0.0000 3.7961 +0.0000 0.0000 3.8397 +0.0000 0.0000 3.8834 +0.0000 0.0000 3.9270 +primID: 6 +startangle_c: 9 +endpose_c: 0 0 8 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0000 0.0000 3.4907 +0.0000 0.0000 3.4470 +0.0000 0.0000 3.4034 +0.0000 0.0000 3.3598 +0.0000 0.0000 3.3161 +0.0000 0.0000 3.2725 +0.0000 0.0000 3.2289 +0.0000 0.0000 3.1852 +0.0000 0.0000 3.1416 +primID: 7 +startangle_c: 9 +endpose_c: 1 -2 9 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0028 -0.0056 3.5343 +0.0056 -0.0111 3.5343 +0.0083 -0.0167 3.5343 +0.0111 -0.0222 3.5343 +0.0139 -0.0278 3.5343 +0.0167 -0.0333 3.5343 +0.0194 -0.0389 3.5343 +0.0222 -0.0444 3.5343 +0.0250 -0.0500 3.5343 +primID: 8 +startangle_c: 9 +endpose_c: -1 2 9 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0028 0.0056 3.5343 +-0.0056 0.0111 3.5343 +-0.0083 0.0167 3.5343 +-0.0111 0.0222 3.5343 +-0.0139 0.0278 3.5343 +-0.0167 0.0333 3.5343 +-0.0194 0.0389 3.5343 +-0.0222 0.0444 3.5343 +-0.0250 0.0500 3.5343 +primID: 9 +startangle_c: 9 +endpose_c: 5 4 10 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0149 0.0092 3.5646 +0.0296 0.0189 3.5949 +0.0440 0.0291 3.6252 +0.0582 0.0398 3.6555 +0.0722 0.0509 3.6858 +0.0858 0.0625 3.7161 +0.0992 0.0746 3.7464 +0.1123 0.0871 3.7767 +0.1250 0.1000 3.8070 +primID: 10 +startangle_c: 9 +endpose_c: 7 2 8 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0188 0.0078 3.5343 +0.0377 0.0156 3.5343 +0.0565 0.0234 3.5343 +0.0754 0.0312 3.5152 +0.0946 0.0379 3.4405 +0.1143 0.0432 3.3658 +0.1344 0.0470 3.2910 +0.1546 0.0492 3.2163 +0.1750 0.0500 3.1416 +primID: 11 +startangle_c: 9 +endpose_c: -5 -4 9 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0139 -0.0111 3.5343 +-0.0278 -0.0222 3.5343 +-0.0417 -0.0333 3.5343 +-0.0556 -0.0444 3.5343 +-0.0694 -0.0556 3.5343 +-0.0833 -0.0667 3.5343 +-0.0972 -0.0778 3.5343 +-0.1111 -0.0889 3.5343 +-0.1250 -0.1000 3.5343 +primID: 12 +startangle_c: 9 +endpose_c: -7 -2 9 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0194 -0.0056 3.5343 +-0.0389 -0.0111 3.5343 +-0.0583 -0.0167 3.5343 +-0.0778 -0.0222 3.5343 +-0.0972 -0.0278 3.5343 +-0.1167 -0.0333 3.5343 +-0.1361 -0.0389 3.5343 +-0.1556 -0.0444 3.5343 +-0.1750 -0.0500 3.5343 +primID: 0 +startangle_c: 10 +endpose_c: -1 -1 10 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0028 -0.0028 3.9270 +-0.0056 -0.0056 3.9270 +-0.0083 -0.0083 3.9270 +-0.0111 -0.0111 3.9270 +-0.0139 -0.0139 3.9270 +-0.0167 -0.0167 3.9270 +-0.0194 -0.0194 3.9270 +-0.0222 -0.0222 3.9270 +-0.0250 -0.0250 3.9270 +primID: 1 +startangle_c: 10 +endpose_c: -6 -6 10 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0167 -0.0167 3.9270 +-0.0333 -0.0333 3.9270 +-0.0500 -0.0500 3.9270 +-0.0667 -0.0667 3.9270 +-0.0833 -0.0833 3.9270 +-0.1000 -0.1000 3.9270 +-0.1167 -0.1167 3.9270 +-0.1333 -0.1333 3.9270 +-0.1500 -0.1500 3.9270 +primID: 2 +startangle_c: 10 +endpose_c: 1 1 10 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0028 0.0028 3.9270 +0.0056 0.0056 3.9270 +0.0083 0.0083 3.9270 +0.0111 0.0111 3.9270 +0.0139 0.0139 3.9270 +0.0167 0.0167 3.9270 +0.0194 0.0194 3.9270 +0.0222 0.0222 3.9270 +0.0250 0.0250 3.9270 +primID: 3 +startangle_c: 10 +endpose_c: -5 -7 11 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0170 -0.0170 3.9270 +-0.0339 -0.0342 3.9567 +-0.0500 -0.0522 4.0085 +-0.0651 -0.0709 4.0604 +-0.0792 -0.0904 4.1123 +-0.0923 -0.1107 4.1641 +-0.1043 -0.1315 4.2160 +-0.1152 -0.1530 4.2678 +-0.1250 -0.1750 4.3197 +primID: 4 +startangle_c: 10 +endpose_c: -7 -5 9 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0170 -0.0170 3.9270 +-0.0342 -0.0339 3.8973 +-0.0522 -0.0500 3.8455 +-0.0709 -0.0651 3.7936 +-0.0904 -0.0792 3.7417 +-0.1107 -0.0923 3.6899 +-0.1315 -0.1043 3.6380 +-0.1530 -0.1152 3.5862 +-0.1750 -0.1250 3.5343 +primID: 5 +startangle_c: 10 +endpose_c: 0 0 11 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.9706 +0.0000 0.0000 4.0143 +0.0000 0.0000 4.0579 +0.0000 0.0000 4.1015 +0.0000 0.0000 4.1452 +0.0000 0.0000 4.1888 +0.0000 0.0000 4.2324 +0.0000 0.0000 4.2761 +0.0000 0.0000 4.3197 +primID: 6 +startangle_c: 10 +endpose_c: 0 0 9 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.8834 +0.0000 0.0000 3.8397 +0.0000 0.0000 3.7961 +0.0000 0.0000 3.7525 +0.0000 0.0000 3.7088 +0.0000 0.0000 3.6652 +0.0000 0.0000 3.6216 +0.0000 0.0000 3.5779 +0.0000 0.0000 3.5343 +primID: 7 +startangle_c: 10 +endpose_c: 1 -1 10 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0028 -0.0028 3.9270 +0.0056 -0.0056 3.9270 +0.0083 -0.0083 3.9270 +0.0111 -0.0111 3.9270 +0.0139 -0.0139 3.9270 +0.0167 -0.0167 3.9270 +0.0194 -0.0194 3.9270 +0.0222 -0.0222 3.9270 +0.0250 -0.0250 3.9270 +primID: 8 +startangle_c: 10 +endpose_c: -1 1 10 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0028 0.0028 3.9270 +-0.0056 0.0056 3.9270 +-0.0083 0.0083 3.9270 +-0.0111 0.0111 3.9270 +-0.0139 0.0139 3.9270 +-0.0167 0.0167 3.9270 +-0.0194 0.0194 3.9270 +-0.0222 0.0222 3.9270 +-0.0250 0.0250 3.9270 +primID: 9 +startangle_c: 10 +endpose_c: 5 7 11 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0170 0.0170 3.9270 +0.0339 0.0342 3.9567 +0.0500 0.0522 4.0085 +0.0651 0.0709 4.0604 +0.0792 0.0904 4.1123 +0.0923 0.1107 4.1641 +0.1043 0.1315 4.2160 +0.1152 0.1530 4.2678 +0.1250 0.1750 4.3197 +primID: 10 +startangle_c: 10 +endpose_c: 7 5 9 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0170 0.0170 3.9270 +0.0342 0.0339 3.8973 +0.0522 0.0500 3.8455 +0.0709 0.0651 3.7936 +0.0904 0.0792 3.7417 +0.1107 0.0923 3.6899 +0.1315 0.1043 3.6380 +0.1530 0.1152 3.5862 +0.1750 0.1250 3.5343 +primID: 11 +startangle_c: 10 +endpose_c: -5 -7 10 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0139 -0.0194 3.9270 +-0.0278 -0.0389 3.9270 +-0.0417 -0.0583 3.9270 +-0.0556 -0.0778 3.9270 +-0.0694 -0.0972 3.9270 +-0.0833 -0.1167 3.9270 +-0.0972 -0.1361 3.9270 +-0.1111 -0.1556 3.9270 +-0.1250 -0.1750 3.9270 +primID: 12 +startangle_c: 10 +endpose_c: -7 -5 10 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0194 -0.0139 3.9270 +-0.0389 -0.0278 3.9270 +-0.0583 -0.0417 3.9270 +-0.0778 -0.0556 3.9270 +-0.0972 -0.0694 3.9270 +-0.1167 -0.0833 3.9270 +-0.1361 -0.0972 3.9270 +-0.1556 -0.1111 3.9270 +-0.1750 -0.1250 3.9270 +primID: 0 +startangle_c: 11 +endpose_c: -1 -2 11 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0028 -0.0056 4.3197 +-0.0056 -0.0111 4.3197 +-0.0083 -0.0167 4.3197 +-0.0111 -0.0222 4.3197 +-0.0139 -0.0278 4.3197 +-0.0167 -0.0333 4.3197 +-0.0194 -0.0389 4.3197 +-0.0222 -0.0444 4.3197 +-0.0250 -0.0500 4.3197 +primID: 1 +startangle_c: 11 +endpose_c: -3 -6 11 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0083 -0.0167 4.3197 +-0.0167 -0.0333 4.3197 +-0.0250 -0.0500 4.3197 +-0.0333 -0.0667 4.3197 +-0.0417 -0.0833 4.3197 +-0.0500 -0.1000 4.3197 +-0.0583 -0.1167 4.3197 +-0.0667 -0.1333 4.3197 +-0.0750 -0.1500 4.3197 +primID: 2 +startangle_c: 11 +endpose_c: 1 2 11 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0028 0.0056 4.3197 +0.0056 0.0111 4.3197 +0.0083 0.0167 4.3197 +0.0111 0.0222 4.3197 +0.0139 0.0278 4.3197 +0.0167 0.0333 4.3197 +0.0194 0.0389 4.3197 +0.0222 0.0444 4.3197 +0.0250 0.0500 4.3197 +primID: 3 +startangle_c: 11 +endpose_c: -4 -5 10 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0092 -0.0149 4.2894 +-0.0189 -0.0296 4.2591 +-0.0291 -0.0440 4.2288 +-0.0398 -0.0582 4.1985 +-0.0509 -0.0722 4.1682 +-0.0625 -0.0858 4.1379 +-0.0746 -0.0992 4.1076 +-0.0871 -0.1123 4.0773 +-0.1000 -0.1250 4.0470 +primID: 4 +startangle_c: 11 +endpose_c: -2 -7 12 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0078 -0.0188 4.3197 +-0.0156 -0.0377 4.3197 +-0.0234 -0.0565 4.3197 +-0.0312 -0.0754 4.3388 +-0.0379 -0.0946 4.4135 +-0.0432 -0.1143 4.4882 +-0.0470 -0.1344 4.5629 +-0.0492 -0.1546 4.6377 +-0.0500 -0.1750 4.7124 +primID: 5 +startangle_c: 11 +endpose_c: 0 0 10 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0000 0.0000 4.2761 +0.0000 0.0000 4.2324 +0.0000 0.0000 4.1888 +0.0000 0.0000 4.1452 +0.0000 0.0000 4.1015 +0.0000 0.0000 4.0579 +0.0000 0.0000 4.0143 +0.0000 0.0000 3.9706 +0.0000 0.0000 3.9270 +primID: 6 +startangle_c: 11 +endpose_c: 0 0 12 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0000 0.0000 4.3633 +0.0000 0.0000 4.4070 +0.0000 0.0000 4.4506 +0.0000 0.0000 4.4942 +0.0000 0.0000 4.5379 +0.0000 0.0000 4.5815 +0.0000 0.0000 4.6251 +0.0000 0.0000 4.6688 +0.0000 0.0000 4.7124 +primID: 7 +startangle_c: 11 +endpose_c: -2 1 11 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0056 0.0028 4.3197 +-0.0111 0.0056 4.3197 +-0.0167 0.0083 4.3197 +-0.0222 0.0111 4.3197 +-0.0278 0.0139 4.3197 +-0.0333 0.0167 4.3197 +-0.0389 0.0194 4.3197 +-0.0444 0.0222 4.3197 +-0.0500 0.0250 4.3197 +primID: 8 +startangle_c: 11 +endpose_c: 2 -1 11 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0056 -0.0028 4.3197 +0.0111 -0.0056 4.3197 +0.0167 -0.0083 4.3197 +0.0222 -0.0111 4.3197 +0.0278 -0.0139 4.3197 +0.0333 -0.0167 4.3197 +0.0389 -0.0194 4.3197 +0.0444 -0.0222 4.3197 +0.0500 -0.0250 4.3197 +primID: 9 +startangle_c: 11 +endpose_c: 4 5 10 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0092 0.0149 4.2894 +0.0189 0.0296 4.2591 +0.0291 0.0440 4.2288 +0.0398 0.0582 4.1985 +0.0509 0.0722 4.1682 +0.0625 0.0858 4.1379 +0.0746 0.0992 4.1076 +0.0871 0.1123 4.0773 +0.1000 0.1250 4.0470 +primID: 10 +startangle_c: 11 +endpose_c: 2 7 12 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0078 0.0188 4.3197 +0.0156 0.0377 4.3197 +0.0234 0.0565 4.3197 +0.0312 0.0754 4.3388 +0.0379 0.0946 4.4135 +0.0432 0.1143 4.4882 +0.0470 0.1344 4.5629 +0.0492 0.1546 4.6377 +0.0500 0.1750 4.7124 +primID: 11 +startangle_c: 11 +endpose_c: -4 -5 11 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0111 -0.0139 4.3197 +-0.0222 -0.0278 4.3197 +-0.0333 -0.0417 4.3197 +-0.0444 -0.0556 4.3197 +-0.0556 -0.0694 4.3197 +-0.0667 -0.0833 4.3197 +-0.0778 -0.0972 4.3197 +-0.0889 -0.1111 4.3197 +-0.1000 -0.1250 4.3197 +primID: 12 +startangle_c: 11 +endpose_c: -2 -7 11 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0056 -0.0194 4.3197 +-0.0111 -0.0389 4.3197 +-0.0167 -0.0583 4.3197 +-0.0222 -0.0778 4.3197 +-0.0278 -0.0972 4.3197 +-0.0333 -0.1167 4.3197 +-0.0389 -0.1361 4.3197 +-0.0444 -0.1556 4.3197 +-0.0500 -0.1750 4.3197 +primID: 0 +startangle_c: 12 +endpose_c: 0 -1 12 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0028 4.7124 +0.0000 -0.0056 4.7124 +0.0000 -0.0083 4.7124 +0.0000 -0.0111 4.7124 +0.0000 -0.0139 4.7124 +0.0000 -0.0167 4.7124 +0.0000 -0.0194 4.7124 +0.0000 -0.0222 4.7124 +0.0000 -0.0250 4.7124 +primID: 1 +startangle_c: 12 +endpose_c: 0 -8 12 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0222 4.7124 +0.0000 -0.0444 4.7124 +0.0000 -0.0667 4.7124 +0.0000 -0.0889 4.7124 +0.0000 -0.1111 4.7124 +0.0000 -0.1333 4.7124 +0.0000 -0.1556 4.7124 +0.0000 -0.1778 4.7124 +0.0000 -0.2000 4.7124 +primID: 2 +startangle_c: 12 +endpose_c: 0 1 12 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0028 4.7124 +0.0000 0.0056 4.7124 +0.0000 0.0083 4.7124 +0.0000 0.0111 4.7124 +0.0000 0.0139 4.7124 +0.0000 0.0167 4.7124 +0.0000 0.0194 4.7124 +0.0000 0.0222 4.7124 +0.0000 0.0250 4.7124 +primID: 3 +startangle_c: 12 +endpose_c: 1 -8 13 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.7124 +-0.0000 -0.0226 4.7124 +-0.0000 -0.0452 4.7124 +-0.0000 -0.0678 4.7124 +0.0004 -0.0903 4.7612 +0.0023 -0.1128 4.8300 +0.0057 -0.1352 4.8988 +0.0106 -0.1572 4.9675 +0.0171 -0.1789 5.0363 +0.0250 -0.2000 5.1051 +primID: 4 +startangle_c: 12 +endpose_c: -1 -8 11 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.7124 +-0.0000 -0.0226 4.7124 +-0.0000 -0.0452 4.7124 +-0.0000 -0.0678 4.7124 +-0.0004 -0.0903 4.6636 +-0.0023 -0.1128 4.5948 +-0.0057 -0.1352 4.5260 +-0.0106 -0.1572 4.4572 +-0.0171 -0.1789 4.3885 +-0.0250 -0.2000 4.3197 +primID: 5 +startangle_c: 12 +endpose_c: 0 0 13 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0000 4.7560 +0.0000 0.0000 4.7997 +0.0000 0.0000 4.8433 +0.0000 0.0000 4.8869 +0.0000 0.0000 4.9306 +0.0000 0.0000 4.9742 +0.0000 0.0000 5.0178 +0.0000 0.0000 5.0615 +0.0000 0.0000 5.1051 +primID: 6 +startangle_c: 12 +endpose_c: 0 0 11 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0000 4.6688 +0.0000 0.0000 4.6251 +0.0000 0.0000 4.5815 +0.0000 0.0000 4.5379 +0.0000 0.0000 4.4942 +0.0000 0.0000 4.4506 +0.0000 0.0000 4.4070 +0.0000 0.0000 4.3633 +0.0000 0.0000 4.3197 +primID: 7 +startangle_c: 12 +endpose_c: 1 0 12 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0028 0.0000 4.7124 +0.0056 0.0000 4.7124 +0.0083 0.0000 4.7124 +0.0111 0.0000 4.7124 +0.0139 0.0000 4.7124 +0.0167 0.0000 4.7124 +0.0194 0.0000 4.7124 +0.0222 0.0000 4.7124 +0.0250 0.0000 4.7124 +primID: 8 +startangle_c: 12 +endpose_c: -1 0 12 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.7124 +-0.0028 0.0000 4.7124 +-0.0056 0.0000 4.7124 +-0.0083 0.0000 4.7124 +-0.0111 0.0000 4.7124 +-0.0139 0.0000 4.7124 +-0.0167 0.0000 4.7124 +-0.0194 0.0000 4.7124 +-0.0222 0.0000 4.7124 +-0.0250 0.0000 4.7124 +primID: 9 +startangle_c: 12 +endpose_c: -1 8 13 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0226 4.7124 +0.0000 0.0452 4.7124 +0.0000 0.0678 4.7124 +-0.0004 0.0903 4.7612 +-0.0023 0.1128 4.8300 +-0.0057 0.1352 4.8988 +-0.0106 0.1572 4.9675 +-0.0171 0.1789 5.0363 +-0.0250 0.2000 5.1051 +primID: 10 +startangle_c: 12 +endpose_c: 1 8 11 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0226 4.7124 +0.0000 0.0452 4.7124 +0.0000 0.0678 4.7124 +0.0004 0.0903 4.6636 +0.0023 0.1128 4.5948 +0.0057 0.1352 4.5260 +0.0106 0.1572 4.4572 +0.0171 0.1789 4.3885 +0.0250 0.2000 4.3197 +primID: 11 +startangle_c: 12 +endpose_c: 1 -8 12 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0028 -0.0222 4.7124 +0.0056 -0.0444 4.7124 +0.0083 -0.0667 4.7124 +0.0111 -0.0889 4.7124 +0.0139 -0.1111 4.7124 +0.0167 -0.1333 4.7124 +0.0194 -0.1556 4.7124 +0.0222 -0.1778 4.7124 +0.0250 -0.2000 4.7124 +primID: 12 +startangle_c: 12 +endpose_c: -1 -8 12 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.7124 +-0.0028 -0.0222 4.7124 +-0.0056 -0.0444 4.7124 +-0.0083 -0.0667 4.7124 +-0.0111 -0.0889 4.7124 +-0.0139 -0.1111 4.7124 +-0.0167 -0.1333 4.7124 +-0.0194 -0.1556 4.7124 +-0.0222 -0.1778 4.7124 +-0.0250 -0.2000 4.7124 +primID: 0 +startangle_c: 13 +endpose_c: 1 -2 13 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0028 -0.0056 5.1051 +0.0056 -0.0111 5.1051 +0.0083 -0.0167 5.1051 +0.0111 -0.0222 5.1051 +0.0139 -0.0278 5.1051 +0.0167 -0.0333 5.1051 +0.0194 -0.0389 5.1051 +0.0222 -0.0444 5.1051 +0.0250 -0.0500 5.1051 +primID: 1 +startangle_c: 13 +endpose_c: 3 -6 13 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0083 -0.0167 5.1051 +0.0167 -0.0333 5.1051 +0.0250 -0.0500 5.1051 +0.0333 -0.0667 5.1051 +0.0417 -0.0833 5.1051 +0.0500 -0.1000 5.1051 +0.0583 -0.1167 5.1051 +0.0667 -0.1333 5.1051 +0.0750 -0.1500 5.1051 +primID: 2 +startangle_c: 13 +endpose_c: -1 2 13 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 5.1051 +-0.0028 0.0056 5.1051 +-0.0056 0.0111 5.1051 +-0.0083 0.0167 5.1051 +-0.0111 0.0222 5.1051 +-0.0139 0.0278 5.1051 +-0.0167 0.0333 5.1051 +-0.0194 0.0389 5.1051 +-0.0222 0.0444 5.1051 +-0.0250 0.0500 5.1051 +primID: 3 +startangle_c: 13 +endpose_c: 4 -5 14 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0092 -0.0149 5.1354 +0.0189 -0.0296 5.1657 +0.0291 -0.0440 5.1960 +0.0398 -0.0582 5.2263 +0.0509 -0.0722 5.2566 +0.0625 -0.0858 5.2869 +0.0746 -0.0992 5.3172 +0.0871 -0.1123 5.3475 +0.1000 -0.1250 5.3778 +primID: 4 +startangle_c: 13 +endpose_c: 2 -7 12 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0078 -0.0188 5.1051 +0.0156 -0.0377 5.1051 +0.0234 -0.0565 5.1051 +0.0312 -0.0754 5.0860 +0.0379 -0.0946 5.0113 +0.0432 -0.1143 4.9366 +0.0470 -0.1344 4.8618 +0.0492 -0.1546 4.7871 +0.0500 -0.1750 4.7124 +primID: 5 +startangle_c: 13 +endpose_c: 0 0 14 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0000 0.0000 5.1487 +0.0000 0.0000 5.1924 +0.0000 0.0000 5.2360 +0.0000 0.0000 5.2796 +0.0000 0.0000 5.3233 +0.0000 0.0000 5.3669 +0.0000 0.0000 5.4105 +0.0000 0.0000 5.4542 +0.0000 0.0000 5.4978 +primID: 6 +startangle_c: 13 +endpose_c: 0 0 12 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0000 0.0000 5.0615 +0.0000 0.0000 5.0178 +0.0000 0.0000 4.9742 +0.0000 0.0000 4.9306 +0.0000 0.0000 4.8869 +0.0000 0.0000 4.8433 +0.0000 0.0000 4.7997 +0.0000 0.0000 4.7560 +0.0000 0.0000 4.7124 +primID: 7 +startangle_c: 13 +endpose_c: 2 1 13 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0056 0.0028 5.1051 +0.0111 0.0056 5.1051 +0.0167 0.0083 5.1051 +0.0222 0.0111 5.1051 +0.0278 0.0139 5.1051 +0.0333 0.0167 5.1051 +0.0389 0.0194 5.1051 +0.0444 0.0222 5.1051 +0.0500 0.0250 5.1051 +primID: 8 +startangle_c: 13 +endpose_c: -2 -1 13 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.1051 +-0.0056 -0.0028 5.1051 +-0.0111 -0.0056 5.1051 +-0.0167 -0.0083 5.1051 +-0.0222 -0.0111 5.1051 +-0.0278 -0.0139 5.1051 +-0.0333 -0.0167 5.1051 +-0.0389 -0.0194 5.1051 +-0.0444 -0.0222 5.1051 +-0.0500 -0.0250 5.1051 +primID: 9 +startangle_c: 13 +endpose_c: -4 5 14 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 5.1051 +-0.0092 0.0149 5.1354 +-0.0189 0.0296 5.1657 +-0.0291 0.0440 5.1960 +-0.0398 0.0582 5.2263 +-0.0509 0.0722 5.2566 +-0.0625 0.0858 5.2869 +-0.0746 0.0992 5.3172 +-0.0871 0.1123 5.3475 +-0.1000 0.1250 5.3778 +primID: 10 +startangle_c: 13 +endpose_c: -2 7 12 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 5.1051 +-0.0078 0.0188 5.1051 +-0.0156 0.0377 5.1051 +-0.0234 0.0565 5.1051 +-0.0312 0.0754 5.0860 +-0.0379 0.0946 5.0113 +-0.0432 0.1143 4.9366 +-0.0470 0.1344 4.8618 +-0.0492 0.1546 4.7871 +-0.0500 0.1750 4.7124 +primID: 11 +startangle_c: 13 +endpose_c: 4 -5 13 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0111 -0.0139 5.1051 +0.0222 -0.0278 5.1051 +0.0333 -0.0417 5.1051 +0.0444 -0.0556 5.1051 +0.0556 -0.0694 5.1051 +0.0667 -0.0833 5.1051 +0.0778 -0.0972 5.1051 +0.0889 -0.1111 5.1051 +0.1000 -0.1250 5.1051 +primID: 12 +startangle_c: 13 +endpose_c: 2 -7 13 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0056 -0.0194 5.1051 +0.0111 -0.0389 5.1051 +0.0167 -0.0583 5.1051 +0.0222 -0.0778 5.1051 +0.0278 -0.0972 5.1051 +0.0333 -0.1167 5.1051 +0.0389 -0.1361 5.1051 +0.0444 -0.1556 5.1051 +0.0500 -0.1750 5.1051 +primID: 0 +startangle_c: 14 +endpose_c: 1 -1 14 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0028 -0.0028 5.4978 +0.0056 -0.0056 5.4978 +0.0083 -0.0083 5.4978 +0.0111 -0.0111 5.4978 +0.0139 -0.0139 5.4978 +0.0167 -0.0167 5.4978 +0.0194 -0.0194 5.4978 +0.0222 -0.0222 5.4978 +0.0250 -0.0250 5.4978 +primID: 1 +startangle_c: 14 +endpose_c: 6 -6 14 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0167 -0.0167 5.4978 +0.0333 -0.0333 5.4978 +0.0500 -0.0500 5.4978 +0.0667 -0.0667 5.4978 +0.0833 -0.0833 5.4978 +0.1000 -0.1000 5.4978 +0.1167 -0.1167 5.4978 +0.1333 -0.1333 5.4978 +0.1500 -0.1500 5.4978 +primID: 2 +startangle_c: 14 +endpose_c: -1 1 14 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 5.4978 +-0.0028 0.0028 5.4978 +-0.0056 0.0056 5.4978 +-0.0083 0.0083 5.4978 +-0.0111 0.0111 5.4978 +-0.0139 0.0139 5.4978 +-0.0167 0.0167 5.4978 +-0.0194 0.0194 5.4978 +-0.0222 0.0222 5.4978 +-0.0250 0.0250 5.4978 +primID: 3 +startangle_c: 14 +endpose_c: 7 -5 15 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0170 -0.0170 5.4978 +0.0342 -0.0339 5.5275 +0.0522 -0.0500 5.5793 +0.0709 -0.0651 5.6312 +0.0904 -0.0792 5.6830 +0.1107 -0.0923 5.7349 +0.1315 -0.1043 5.7868 +0.1530 -0.1152 5.8386 +0.1750 -0.1250 5.8905 +primID: 4 +startangle_c: 14 +endpose_c: 5 -7 13 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0170 -0.0170 5.4978 +0.0339 -0.0342 5.4681 +0.0500 -0.0522 5.4162 +0.0651 -0.0709 5.3644 +0.0792 -0.0904 5.3125 +0.0923 -0.1107 5.2607 +0.1043 -0.1315 5.2088 +0.1152 -0.1530 5.1569 +0.1250 -0.1750 5.1051 +primID: 5 +startangle_c: 14 +endpose_c: 0 0 15 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0000 0.0000 5.5414 +0.0000 0.0000 5.5851 +0.0000 0.0000 5.6287 +0.0000 0.0000 5.6723 +0.0000 0.0000 5.7160 +0.0000 0.0000 5.7596 +0.0000 0.0000 5.8032 +0.0000 0.0000 5.8469 +0.0000 0.0000 5.8905 +primID: 6 +startangle_c: 14 +endpose_c: 0 0 13 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0000 0.0000 5.4542 +0.0000 0.0000 5.4105 +0.0000 0.0000 5.3669 +0.0000 0.0000 5.3233 +0.0000 0.0000 5.2796 +0.0000 0.0000 5.2360 +0.0000 0.0000 5.1924 +0.0000 0.0000 5.1487 +0.0000 0.0000 5.1051 +primID: 7 +startangle_c: 14 +endpose_c: 1 1 14 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0028 0.0028 5.4978 +0.0056 0.0056 5.4978 +0.0083 0.0083 5.4978 +0.0111 0.0111 5.4978 +0.0139 0.0139 5.4978 +0.0167 0.0167 5.4978 +0.0194 0.0194 5.4978 +0.0222 0.0222 5.4978 +0.0250 0.0250 5.4978 +primID: 8 +startangle_c: 14 +endpose_c: -1 -1 14 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.4978 +-0.0028 -0.0028 5.4978 +-0.0056 -0.0056 5.4978 +-0.0083 -0.0083 5.4978 +-0.0111 -0.0111 5.4978 +-0.0139 -0.0139 5.4978 +-0.0167 -0.0167 5.4978 +-0.0194 -0.0194 5.4978 +-0.0222 -0.0222 5.4978 +-0.0250 -0.0250 5.4978 +primID: 9 +startangle_c: 14 +endpose_c: -7 5 15 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 5.4978 +-0.0170 0.0170 5.4978 +-0.0342 0.0339 5.5275 +-0.0522 0.0500 5.5793 +-0.0709 0.0651 5.6312 +-0.0904 0.0792 5.6830 +-0.1107 0.0923 5.7349 +-0.1315 0.1043 5.7868 +-0.1530 0.1152 5.8386 +-0.1750 0.1250 5.8905 +primID: 10 +startangle_c: 14 +endpose_c: -5 7 13 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 5.4978 +-0.0170 0.0170 5.4978 +-0.0339 0.0342 5.4681 +-0.0500 0.0522 5.4162 +-0.0651 0.0709 5.3644 +-0.0792 0.0904 5.3125 +-0.0923 0.1107 5.2607 +-0.1043 0.1315 5.2088 +-0.1152 0.1530 5.1569 +-0.1250 0.1750 5.1051 +primID: 11 +startangle_c: 14 +endpose_c: 7 -5 14 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0194 -0.0139 5.4978 +0.0389 -0.0278 5.4978 +0.0583 -0.0417 5.4978 +0.0778 -0.0556 5.4978 +0.0972 -0.0694 5.4978 +0.1167 -0.0833 5.4978 +0.1361 -0.0972 5.4978 +0.1556 -0.1111 5.4978 +0.1750 -0.1250 5.4978 +primID: 12 +startangle_c: 14 +endpose_c: 5 -7 14 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0139 -0.0194 5.4978 +0.0278 -0.0389 5.4978 +0.0417 -0.0583 5.4978 +0.0556 -0.0778 5.4978 +0.0694 -0.0972 5.4978 +0.0833 -0.1167 5.4978 +0.0972 -0.1361 5.4978 +0.1111 -0.1556 5.4978 +0.1250 -0.1750 5.4978 +primID: 0 +startangle_c: 15 +endpose_c: 2 -1 15 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0056 -0.0028 5.8905 +0.0111 -0.0056 5.8905 +0.0167 -0.0083 5.8905 +0.0222 -0.0111 5.8905 +0.0278 -0.0139 5.8905 +0.0333 -0.0167 5.8905 +0.0389 -0.0194 5.8905 +0.0444 -0.0222 5.8905 +0.0500 -0.0250 5.8905 +primID: 1 +startangle_c: 15 +endpose_c: 6 -3 15 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0167 -0.0083 5.8905 +0.0333 -0.0167 5.8905 +0.0500 -0.0250 5.8905 +0.0667 -0.0333 5.8905 +0.0833 -0.0417 5.8905 +0.1000 -0.0500 5.8905 +0.1167 -0.0583 5.8905 +0.1333 -0.0667 5.8905 +0.1500 -0.0750 5.8905 +primID: 2 +startangle_c: 15 +endpose_c: -2 1 15 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 5.8905 +-0.0056 0.0028 5.8905 +-0.0111 0.0056 5.8905 +-0.0167 0.0083 5.8905 +-0.0222 0.0111 5.8905 +-0.0278 0.0139 5.8905 +-0.0333 0.0167 5.8905 +-0.0389 0.0194 5.8905 +-0.0444 0.0222 5.8905 +-0.0500 0.0250 5.8905 +primID: 3 +startangle_c: 15 +endpose_c: 5 -4 14 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0149 -0.0092 5.8602 +0.0296 -0.0189 5.8299 +0.0440 -0.0291 5.7996 +0.0582 -0.0398 5.7693 +0.0722 -0.0509 5.7390 +0.0858 -0.0625 5.7087 +0.0992 -0.0746 5.6784 +0.1123 -0.0871 5.6481 +0.1250 -0.1000 5.6178 +primID: 4 +startangle_c: 15 +endpose_c: 7 -2 0 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0188 -0.0078 5.8905 +0.0377 -0.0156 5.8905 +0.0565 -0.0234 5.8905 +0.0754 -0.0312 5.9096 +0.0946 -0.0379 5.9843 +0.1143 -0.0432 6.0590 +0.1344 -0.0470 6.1337 +0.1546 -0.0492 6.2085 +0.1750 -0.0500 6.2832 +primID: 5 +startangle_c: 15 +endpose_c: 0 0 14 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0000 0.0000 5.8469 +0.0000 0.0000 5.8032 +0.0000 0.0000 5.7596 +0.0000 0.0000 5.7160 +0.0000 0.0000 5.6723 +0.0000 0.0000 5.6287 +0.0000 0.0000 5.5851 +0.0000 0.0000 5.5414 +0.0000 0.0000 5.4978 +primID: 6 +startangle_c: 15 +endpose_c: 0 0 0 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0000 0.0000 5.9341 +0.0000 0.0000 5.9778 +0.0000 0.0000 6.0214 +0.0000 0.0000 6.0650 +0.0000 0.0000 6.1087 +0.0000 0.0000 6.1523 +0.0000 0.0000 6.1959 +0.0000 0.0000 6.2396 +0.0000 0.0000 0.0000 +primID: 7 +startangle_c: 15 +endpose_c: -1 -2 15 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.8905 +-0.0028 -0.0056 5.8905 +-0.0056 -0.0111 5.8905 +-0.0083 -0.0167 5.8905 +-0.0111 -0.0222 5.8905 +-0.0139 -0.0278 5.8905 +-0.0167 -0.0333 5.8905 +-0.0194 -0.0389 5.8905 +-0.0222 -0.0444 5.8905 +-0.0250 -0.0500 5.8905 +primID: 8 +startangle_c: 15 +endpose_c: 1 2 15 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0028 0.0056 5.8905 +0.0056 0.0111 5.8905 +0.0083 0.0167 5.8905 +0.0111 0.0222 5.8905 +0.0139 0.0278 5.8905 +0.0167 0.0333 5.8905 +0.0194 0.0389 5.8905 +0.0222 0.0444 5.8905 +0.0250 0.0500 5.8905 +primID: 9 +startangle_c: 15 +endpose_c: -5 4 14 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 5.8905 +-0.0149 0.0092 5.8602 +-0.0296 0.0189 5.8299 +-0.0440 0.0291 5.7996 +-0.0582 0.0398 5.7693 +-0.0722 0.0509 5.7390 +-0.0858 0.0625 5.7087 +-0.0992 0.0746 5.6784 +-0.1123 0.0871 5.6481 +-0.1250 0.1000 5.6178 +primID: 10 +startangle_c: 15 +endpose_c: -7 2 0 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 5.8905 +-0.0188 0.0078 5.8905 +-0.0377 0.0156 5.8905 +-0.0565 0.0234 5.8905 +-0.0754 0.0312 5.9096 +-0.0946 0.0379 5.9843 +-0.1143 0.0432 6.0590 +-0.1344 0.0470 6.1337 +-0.1546 0.0492 6.2085 +-0.1750 0.0500 6.2832 +primID: 11 +startangle_c: 15 +endpose_c: 5 -4 15 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0139 -0.0111 5.8905 +0.0278 -0.0222 5.8905 +0.0417 -0.0333 5.8905 +0.0556 -0.0444 5.8905 +0.0694 -0.0556 5.8905 +0.0833 -0.0667 5.8905 +0.0972 -0.0778 5.8905 +0.1111 -0.0889 5.8905 +0.1250 -0.1000 5.8905 +primID: 12 +startangle_c: 15 +endpose_c: 7 -2 15 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0194 -0.0056 5.8905 +0.0389 -0.0111 5.8905 +0.0583 -0.0167 5.8905 +0.0778 -0.0222 5.8905 +0.0972 -0.0278 5.8905 +0.1167 -0.0333 5.8905 +0.1361 -0.0389 5.8905 +0.1556 -0.0444 5.8905 +0.1750 -0.0500 5.8905 diff --git a/navigations/sbpl/matlab/mprim/non_uniform_res0025_rad1_err005.mprim b/navigations/sbpl/matlab/mprim/non_uniform_res0025_rad1_err005.mprim new file mode 100755 index 0000000..e5e8d6a --- /dev/null +++ b/navigations/sbpl/matlab/mprim/non_uniform_res0025_rad1_err005.mprim @@ -0,0 +1,5723 @@ +resolution_m: 0.025000 +min_turning_radius_m: 1.000000 +numberofangles: 16 +angle:0 0.00000000 +angle:1 0.46364761 +angle:2 0.78539816 +angle:3 1.10714872 +angle:4 1.57079633 +angle:5 2.03444394 +angle:6 2.35619449 +angle:7 2.67794504 +angle:8 3.14159265 +angle:9 3.60524026 +angle:10 3.92699082 +angle:11 4.24874137 +angle:12 4.71238898 +angle:13 5.17603659 +angle:14 5.49778714 +angle:15 5.81953770 +totalnumberofprimitives: 160 +primID: 0 +startangle_c: 0 +endpose_c: 1 0 0 +additionalactioncostmult: 1 +turning_radius: 0.0000 +intermediateposes: 3 +0.0000 0.0000 0.0000 +0.0125 0.0000 0.0000 +0.0250 0.0000 0.0000 +primID: 1 +startangle_c: 0 +endpose_c: 21 0 0 +additionalactioncostmult: 1 +turning_radius: 0.0000 +intermediateposes: 43 +0.0000 0.0000 0.0000 +0.0125 0.0000 0.0000 +0.0250 0.0000 0.0000 +0.0375 0.0000 0.0000 +0.0500 0.0000 0.0000 +0.0625 0.0000 0.0000 +0.0750 0.0000 0.0000 +0.0875 0.0000 0.0000 +0.1000 0.0000 0.0000 +0.1125 0.0000 0.0000 +0.1250 0.0000 0.0000 +0.1375 0.0000 0.0000 +0.1500 0.0000 0.0000 +0.1625 0.0000 0.0000 +0.1750 0.0000 0.0000 +0.1875 0.0000 0.0000 +0.2000 0.0000 0.0000 +0.2125 0.0000 0.0000 +0.2250 0.0000 0.0000 +0.2375 0.0000 0.0000 +0.2500 0.0000 0.0000 +0.2625 0.0000 0.0000 +0.2750 0.0000 0.0000 +0.2875 0.0000 0.0000 +0.3000 0.0000 0.0000 +0.3125 0.0000 0.0000 +0.3250 0.0000 0.0000 +0.3375 0.0000 0.0000 +0.3500 0.0000 0.0000 +0.3625 0.0000 0.0000 +0.3750 0.0000 0.0000 +0.3875 0.0000 0.0000 +0.4000 0.0000 0.0000 +0.4125 0.0000 0.0000 +0.4250 0.0000 0.0000 +0.4375 0.0000 0.0000 +0.4500 0.0000 0.0000 +0.4625 0.0000 0.0000 +0.4750 0.0000 0.0000 +0.4875 0.0000 0.0000 +0.5000 0.0000 0.0000 +0.5125 0.0000 0.0000 +0.5250 0.0000 0.0000 +primID: 2 +startangle_c: 0 +endpose_c: 21 5 1 +additionalactioncostmult: 2 +turning_radius: 1.1745 +intermediateposes: 44 +0.0000 0.0000 0.0000 +0.0127 0.0001 0.0108 +0.0253 0.0003 0.0216 +0.0380 0.0007 0.0323 +0.0506 0.0012 0.0431 +0.0633 0.0018 0.0539 +0.0759 0.0026 0.0647 +0.0885 0.0035 0.0755 +0.1011 0.0046 0.0863 +0.1137 0.0057 0.0970 +0.1263 0.0071 0.1078 +0.1389 0.0085 0.1186 +0.1515 0.0101 0.1294 +0.1640 0.0118 0.1402 +0.1765 0.0137 0.1510 +0.1890 0.0157 0.1617 +0.2015 0.0178 0.1725 +0.2140 0.0201 0.1833 +0.2264 0.0225 0.1941 +0.2388 0.0250 0.2049 +0.2512 0.0277 0.2157 +0.2636 0.0305 0.2264 +0.2759 0.0334 0.2372 +0.2882 0.0365 0.2480 +0.3004 0.0397 0.2588 +0.3126 0.0430 0.2696 +0.3248 0.0465 0.2803 +0.3370 0.0501 0.2911 +0.3491 0.0538 0.3019 +0.3611 0.0576 0.3127 +0.3732 0.0616 0.3235 +0.3851 0.0657 0.3343 +0.3971 0.0700 0.3450 +0.4090 0.0743 0.3558 +0.4208 0.0788 0.3666 +0.4326 0.0835 0.3774 +0.4443 0.0882 0.3882 +0.4560 0.0931 0.3990 +0.4677 0.0981 0.4097 +0.4792 0.1032 0.4205 +0.4908 0.1085 0.4313 +0.5022 0.1139 0.4421 +0.5136 0.1194 0.4529 +0.5250 0.1250 0.4636 +primID: 3 +startangle_c: 0 +endpose_c: 21 -5 -1 +additionalactioncostmult: 2 +turning_radius: -1.1745 +intermediateposes: 44 +0.0000 0.0000 0.0000 +0.0127 -0.0001 -0.0108 +0.0253 -0.0003 -0.0216 +0.0380 -0.0007 -0.0323 +0.0506 -0.0012 -0.0431 +0.0633 -0.0018 -0.0539 +0.0759 -0.0026 -0.0647 +0.0885 -0.0035 -0.0755 +0.1011 -0.0046 -0.0863 +0.1137 -0.0057 -0.0970 +0.1263 -0.0071 -0.1078 +0.1389 -0.0085 -0.1186 +0.1515 -0.0101 -0.1294 +0.1640 -0.0118 -0.1402 +0.1765 -0.0137 -0.1510 +0.1890 -0.0157 -0.1617 +0.2015 -0.0178 -0.1725 +0.2140 -0.0201 -0.1833 +0.2264 -0.0225 -0.1941 +0.2388 -0.0250 -0.2049 +0.2512 -0.0277 -0.2157 +0.2636 -0.0305 -0.2264 +0.2759 -0.0334 -0.2372 +0.2882 -0.0365 -0.2480 +0.3004 -0.0397 -0.2588 +0.3126 -0.0430 -0.2696 +0.3248 -0.0465 -0.2803 +0.3370 -0.0501 -0.2911 +0.3491 -0.0538 -0.3019 +0.3611 -0.0576 -0.3127 +0.3732 -0.0616 -0.3235 +0.3851 -0.0657 -0.3343 +0.3971 -0.0700 -0.3450 +0.4090 -0.0743 -0.3558 +0.4208 -0.0788 -0.3666 +0.4326 -0.0835 -0.3774 +0.4443 -0.0882 -0.3882 +0.4560 -0.0931 -0.3990 +0.4677 -0.0981 -0.4097 +0.4792 -0.1032 -0.4205 +0.4908 -0.1085 -0.4313 +0.5022 -0.1139 -0.4421 +0.5136 -0.1194 -0.4529 +0.5250 -0.1250 -0.4636 +primID: 4 +startangle_c: 0 +endpose_c: 0 0 1 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 9 +0.0000 0.0000 0.0000 +0.0000 0.0000 0.0580 +0.0000 0.0000 0.1159 +0.0000 0.0000 0.1739 +0.0000 0.0000 0.2318 +0.0000 0.0000 0.2898 +0.0000 0.0000 0.3477 +0.0000 0.0000 0.4057 +0.0000 0.0000 0.4636 +primID: 5 +startangle_c: 0 +endpose_c: -1 0 0 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 3 +0.0000 0.0000 0.0000 +-0.0125 0.0000 0.0000 +-0.0250 0.0000 0.0000 +primID: 6 +startangle_c: 0 +endpose_c: -21 0 0 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 43 +0.0000 0.0000 0.0000 +-0.0125 0.0000 0.0000 +-0.0250 0.0000 0.0000 +-0.0375 0.0000 0.0000 +-0.0500 0.0000 0.0000 +-0.0625 0.0000 0.0000 +-0.0750 0.0000 0.0000 +-0.0875 0.0000 0.0000 +-0.1000 0.0000 0.0000 +-0.1125 0.0000 0.0000 +-0.1250 0.0000 0.0000 +-0.1375 0.0000 0.0000 +-0.1500 0.0000 0.0000 +-0.1625 0.0000 0.0000 +-0.1750 0.0000 0.0000 +-0.1875 0.0000 0.0000 +-0.2000 0.0000 0.0000 +-0.2125 0.0000 0.0000 +-0.2250 0.0000 0.0000 +-0.2375 0.0000 0.0000 +-0.2500 0.0000 0.0000 +-0.2625 0.0000 0.0000 +-0.2750 0.0000 0.0000 +-0.2875 0.0000 0.0000 +-0.3000 0.0000 0.0000 +-0.3125 0.0000 0.0000 +-0.3250 0.0000 0.0000 +-0.3375 0.0000 0.0000 +-0.3500 0.0000 0.0000 +-0.3625 0.0000 0.0000 +-0.3750 0.0000 0.0000 +-0.3875 0.0000 0.0000 +-0.4000 0.0000 0.0000 +-0.4125 0.0000 0.0000 +-0.4250 0.0000 0.0000 +-0.4375 0.0000 0.0000 +-0.4500 0.0000 0.0000 +-0.4625 0.0000 0.0000 +-0.4750 0.0000 0.0000 +-0.4875 0.0000 0.0000 +-0.5000 0.0000 0.0000 +-0.5125 0.0000 0.0000 +-0.5250 0.0000 0.0000 +primID: 7 +startangle_c: 0 +endpose_c: -21 -5 1 +additionalactioncostmult: 3 +turning_radius: -1.1745 +intermediateposes: 44 +0.0000 0.0000 0.0000 +-0.0127 -0.0001 0.0108 +-0.0253 -0.0003 0.0216 +-0.0380 -0.0007 0.0323 +-0.0506 -0.0012 0.0431 +-0.0633 -0.0018 0.0539 +-0.0759 -0.0026 0.0647 +-0.0885 -0.0035 0.0755 +-0.1011 -0.0046 0.0863 +-0.1137 -0.0057 0.0970 +-0.1263 -0.0071 0.1078 +-0.1389 -0.0085 0.1186 +-0.1515 -0.0101 0.1294 +-0.1640 -0.0118 0.1402 +-0.1765 -0.0137 0.1510 +-0.1890 -0.0157 0.1617 +-0.2015 -0.0178 0.1725 +-0.2140 -0.0201 0.1833 +-0.2264 -0.0225 0.1941 +-0.2388 -0.0250 0.2049 +-0.2512 -0.0277 0.2157 +-0.2636 -0.0305 0.2264 +-0.2759 -0.0334 0.2372 +-0.2882 -0.0365 0.2480 +-0.3004 -0.0397 0.2588 +-0.3126 -0.0430 0.2696 +-0.3248 -0.0465 0.2803 +-0.3370 -0.0501 0.2911 +-0.3491 -0.0538 0.3019 +-0.3611 -0.0576 0.3127 +-0.3732 -0.0616 0.3235 +-0.3851 -0.0657 0.3343 +-0.3971 -0.0700 0.3450 +-0.4090 -0.0743 0.3558 +-0.4208 -0.0788 0.3666 +-0.4326 -0.0835 0.3774 +-0.4443 -0.0882 0.3882 +-0.4560 -0.0931 0.3990 +-0.4677 -0.0981 0.4097 +-0.4792 -0.1032 0.4205 +-0.4908 -0.1085 0.4313 +-0.5022 -0.1139 0.4421 +-0.5136 -0.1194 0.4529 +-0.5250 -0.1250 0.4636 +primID: 8 +startangle_c: 0 +endpose_c: -21 5 -1 +additionalactioncostmult: 3 +turning_radius: 1.1745 +intermediateposes: 44 +0.0000 0.0000 0.0000 +-0.0127 0.0001 -0.0108 +-0.0253 0.0003 -0.0216 +-0.0380 0.0007 -0.0323 +-0.0506 0.0012 -0.0431 +-0.0633 0.0018 -0.0539 +-0.0759 0.0026 -0.0647 +-0.0885 0.0035 -0.0755 +-0.1011 0.0046 -0.0863 +-0.1137 0.0057 -0.0970 +-0.1263 0.0071 -0.1078 +-0.1389 0.0085 -0.1186 +-0.1515 0.0101 -0.1294 +-0.1640 0.0118 -0.1402 +-0.1765 0.0137 -0.1510 +-0.1890 0.0157 -0.1617 +-0.2015 0.0178 -0.1725 +-0.2140 0.0201 -0.1833 +-0.2264 0.0225 -0.1941 +-0.2388 0.0250 -0.2049 +-0.2512 0.0277 -0.2157 +-0.2636 0.0305 -0.2264 +-0.2759 0.0334 -0.2372 +-0.2882 0.0365 -0.2480 +-0.3004 0.0397 -0.2588 +-0.3126 0.0430 -0.2696 +-0.3248 0.0465 -0.2803 +-0.3370 0.0501 -0.2911 +-0.3491 0.0538 -0.3019 +-0.3611 0.0576 -0.3127 +-0.3732 0.0616 -0.3235 +-0.3851 0.0657 -0.3343 +-0.3971 0.0700 -0.3450 +-0.4090 0.0743 -0.3558 +-0.4208 0.0788 -0.3666 +-0.4326 0.0835 -0.3774 +-0.4443 0.0882 -0.3882 +-0.4560 0.0931 -0.3990 +-0.4677 0.0981 -0.4097 +-0.4792 0.1032 -0.4205 +-0.4908 0.1085 -0.4313 +-0.5022 0.1139 -0.4421 +-0.5136 0.1194 -0.4529 +-0.5250 0.1250 -0.4636 +primID: 9 +startangle_c: 0 +endpose_c: 0 0 -1 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 9 +0.0000 0.0000 0.0000 +0.0000 0.0000 -0.0580 +0.0000 0.0000 -0.1159 +0.0000 0.0000 -0.1739 +0.0000 0.0000 -0.2318 +0.0000 0.0000 -0.2898 +0.0000 0.0000 -0.3477 +0.0000 0.0000 -0.4057 +0.0000 0.0000 -0.4636 +primID: 0 +startangle_c: 1 +endpose_c: 2 1 1 +additionalactioncostmult: 1 +turning_radius: 0.0000 +intermediateposes: 5 +0.0000 0.0000 0.4636 +0.0125 0.0063 0.4636 +0.0250 0.0125 0.4636 +0.0375 0.0188 0.4636 +0.0500 0.0250 0.4636 +primID: 1 +startangle_c: 1 +endpose_c: 20 10 1 +additionalactioncostmult: 1 +turning_radius: 0.0000 +intermediateposes: 45 +0.0000 0.0000 0.4636 +0.0114 0.0057 0.4636 +0.0227 0.0114 0.4636 +0.0341 0.0170 0.4636 +0.0455 0.0227 0.4636 +0.0568 0.0284 0.4636 +0.0682 0.0341 0.4636 +0.0795 0.0398 0.4636 +0.0909 0.0455 0.4636 +0.1023 0.0511 0.4636 +0.1136 0.0568 0.4636 +0.1250 0.0625 0.4636 +0.1364 0.0682 0.4636 +0.1477 0.0739 0.4636 +0.1591 0.0795 0.4636 +0.1705 0.0852 0.4636 +0.1818 0.0909 0.4636 +0.1932 0.0966 0.4636 +0.2045 0.1023 0.4636 +0.2159 0.1080 0.4636 +0.2273 0.1136 0.4636 +0.2386 0.1193 0.4636 +0.2500 0.1250 0.4636 +0.2614 0.1307 0.4636 +0.2727 0.1364 0.4636 +0.2841 0.1420 0.4636 +0.2955 0.1477 0.4636 +0.3068 0.1534 0.4636 +0.3182 0.1591 0.4636 +0.3295 0.1648 0.4636 +0.3409 0.1705 0.4636 +0.3523 0.1761 0.4636 +0.3636 0.1818 0.4636 +0.3750 0.1875 0.4636 +0.3864 0.1932 0.4636 +0.3977 0.1989 0.4636 +0.4091 0.2045 0.4636 +0.4205 0.2102 0.4636 +0.4318 0.2159 0.4636 +0.4432 0.2216 0.4636 +0.4545 0.2273 0.4636 +0.4659 0.2330 0.4636 +0.4773 0.2386 0.4636 +0.4886 0.2443 0.4636 +0.5000 0.2500 0.4636 +primID: 2 +startangle_c: 1 +endpose_c: 18 13 2 +additionalactioncostmult: 2 +turning_radius: 1.7327 +intermediateposes: 45 +0.0000 0.0000 0.4636 +0.0113 0.0057 0.4710 +0.0226 0.0115 0.4783 +0.0338 0.0174 0.4856 +0.0450 0.0234 0.4929 +0.0561 0.0294 0.5002 +0.0672 0.0355 0.5075 +0.0782 0.0417 0.5148 +0.0892 0.0480 0.5221 +0.1002 0.0544 0.5295 +0.1111 0.0609 0.5368 +0.1219 0.0674 0.5441 +0.1328 0.0740 0.5514 +0.1435 0.0807 0.5587 +0.1542 0.0874 0.5660 +0.1649 0.0943 0.5733 +0.1755 0.1012 0.5806 +0.1861 0.1082 0.5880 +0.1966 0.1153 0.5953 +0.2070 0.1224 0.6026 +0.2174 0.1297 0.6099 +0.2278 0.1370 0.6172 +0.2381 0.1443 0.6245 +0.2483 0.1518 0.6318 +0.2585 0.1593 0.6391 +0.2687 0.1669 0.6465 +0.2787 0.1746 0.6538 +0.2888 0.1824 0.6611 +0.2987 0.1902 0.6684 +0.3086 0.1981 0.6757 +0.3185 0.2061 0.6830 +0.3283 0.2141 0.6903 +0.3380 0.2222 0.6976 +0.3477 0.2304 0.7050 +0.3573 0.2387 0.7123 +0.3668 0.2470 0.7196 +0.3763 0.2554 0.7269 +0.3858 0.2638 0.7342 +0.3951 0.2724 0.7415 +0.4044 0.2810 0.7488 +0.4137 0.2897 0.7561 +0.4229 0.2984 0.7635 +0.4320 0.3072 0.7708 +0.4410 0.3161 0.7781 +0.4500 0.3250 0.7854 +primID: 3 +startangle_c: 1 +endpose_c: 21 5 0 +additionalactioncostmult: 2 +turning_radius: -1.1745 +intermediateposes: 44 +0.0000 0.0000 0.4636 +0.0114 0.0056 0.4529 +0.0228 0.0111 0.4421 +0.0342 0.0165 0.4313 +0.0458 0.0218 0.4205 +0.0573 0.0269 0.4097 +0.0690 0.0319 0.3990 +0.0807 0.0368 0.3882 +0.0924 0.0415 0.3774 +0.1042 0.0462 0.3666 +0.1160 0.0507 0.3558 +0.1279 0.0550 0.3450 +0.1399 0.0593 0.3343 +0.1518 0.0634 0.3235 +0.1639 0.0674 0.3127 +0.1759 0.0712 0.3019 +0.1880 0.0749 0.2911 +0.2002 0.0785 0.2803 +0.2124 0.0820 0.2696 +0.2246 0.0853 0.2588 +0.2368 0.0885 0.2480 +0.2491 0.0916 0.2372 +0.2614 0.0945 0.2264 +0.2738 0.0973 0.2157 +0.2862 0.1000 0.2049 +0.2986 0.1025 0.1941 +0.3110 0.1049 0.1833 +0.3235 0.1072 0.1725 +0.3360 0.1093 0.1617 +0.3485 0.1113 0.1510 +0.3610 0.1132 0.1402 +0.3735 0.1149 0.1294 +0.3861 0.1165 0.1186 +0.3987 0.1179 0.1078 +0.4113 0.1193 0.0970 +0.4239 0.1204 0.0863 +0.4365 0.1215 0.0755 +0.4491 0.1224 0.0647 +0.4617 0.1232 0.0539 +0.4744 0.1238 0.0431 +0.4870 0.1243 0.0323 +0.4997 0.1247 0.0216 +0.5123 0.1249 0.0108 +0.5250 0.1250 0.0000 +primID: 4 +startangle_c: 1 +endpose_c: 0 0 2 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 6 +0.0000 0.0000 0.4636 +0.0000 0.0000 0.5280 +0.0000 0.0000 0.5923 +0.0000 0.0000 0.6567 +0.0000 0.0000 0.7210 +0.0000 0.0000 0.7854 +primID: 5 +startangle_c: 1 +endpose_c: -2 -1 1 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 5 +0.0000 0.0000 0.4636 +-0.0125 -0.0063 0.4636 +-0.0250 -0.0125 0.4636 +-0.0375 -0.0188 0.4636 +-0.0500 -0.0250 0.4636 +primID: 6 +startangle_c: 1 +endpose_c: -20 -10 1 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 45 +0.0000 0.0000 0.4636 +-0.0114 -0.0057 0.4636 +-0.0227 -0.0114 0.4636 +-0.0341 -0.0170 0.4636 +-0.0455 -0.0227 0.4636 +-0.0568 -0.0284 0.4636 +-0.0682 -0.0341 0.4636 +-0.0795 -0.0398 0.4636 +-0.0909 -0.0455 0.4636 +-0.1023 -0.0511 0.4636 +-0.1136 -0.0568 0.4636 +-0.1250 -0.0625 0.4636 +-0.1364 -0.0682 0.4636 +-0.1477 -0.0739 0.4636 +-0.1591 -0.0795 0.4636 +-0.1705 -0.0852 0.4636 +-0.1818 -0.0909 0.4636 +-0.1932 -0.0966 0.4636 +-0.2045 -0.1023 0.4636 +-0.2159 -0.1080 0.4636 +-0.2273 -0.1136 0.4636 +-0.2386 -0.1193 0.4636 +-0.2500 -0.1250 0.4636 +-0.2614 -0.1307 0.4636 +-0.2727 -0.1364 0.4636 +-0.2841 -0.1420 0.4636 +-0.2955 -0.1477 0.4636 +-0.3068 -0.1534 0.4636 +-0.3182 -0.1591 0.4636 +-0.3295 -0.1648 0.4636 +-0.3409 -0.1705 0.4636 +-0.3523 -0.1761 0.4636 +-0.3636 -0.1818 0.4636 +-0.3750 -0.1875 0.4636 +-0.3864 -0.1932 0.4636 +-0.3977 -0.1989 0.4636 +-0.4091 -0.2045 0.4636 +-0.4205 -0.2102 0.4636 +-0.4318 -0.2159 0.4636 +-0.4432 -0.2216 0.4636 +-0.4545 -0.2273 0.4636 +-0.4659 -0.2330 0.4636 +-0.4773 -0.2386 0.4636 +-0.4886 -0.2443 0.4636 +-0.5000 -0.2500 0.4636 +primID: 7 +startangle_c: 1 +endpose_c: -18 -13 2 +additionalactioncostmult: 3 +turning_radius: -1.7327 +intermediateposes: 45 +0.0000 0.0000 0.4636 +-0.0113 -0.0057 0.4710 +-0.0226 -0.0115 0.4783 +-0.0338 -0.0174 0.4856 +-0.0450 -0.0234 0.4929 +-0.0561 -0.0294 0.5002 +-0.0672 -0.0355 0.5075 +-0.0782 -0.0417 0.5148 +-0.0892 -0.0480 0.5221 +-0.1002 -0.0544 0.5295 +-0.1111 -0.0609 0.5368 +-0.1219 -0.0674 0.5441 +-0.1328 -0.0740 0.5514 +-0.1435 -0.0807 0.5587 +-0.1542 -0.0874 0.5660 +-0.1649 -0.0943 0.5733 +-0.1755 -0.1012 0.5806 +-0.1861 -0.1082 0.5880 +-0.1966 -0.1153 0.5953 +-0.2070 -0.1224 0.6026 +-0.2174 -0.1297 0.6099 +-0.2278 -0.1370 0.6172 +-0.2381 -0.1443 0.6245 +-0.2483 -0.1518 0.6318 +-0.2585 -0.1593 0.6391 +-0.2687 -0.1669 0.6465 +-0.2787 -0.1746 0.6538 +-0.2888 -0.1824 0.6611 +-0.2987 -0.1902 0.6684 +-0.3086 -0.1981 0.6757 +-0.3185 -0.2061 0.6830 +-0.3283 -0.2141 0.6903 +-0.3380 -0.2222 0.6976 +-0.3477 -0.2304 0.7050 +-0.3573 -0.2387 0.7123 +-0.3668 -0.2470 0.7196 +-0.3763 -0.2554 0.7269 +-0.3858 -0.2638 0.7342 +-0.3951 -0.2724 0.7415 +-0.4044 -0.2810 0.7488 +-0.4137 -0.2897 0.7561 +-0.4229 -0.2984 0.7635 +-0.4320 -0.3072 0.7708 +-0.4410 -0.3161 0.7781 +-0.4500 -0.3250 0.7854 +primID: 8 +startangle_c: 1 +endpose_c: -21 -5 0 +additionalactioncostmult: 3 +turning_radius: 1.1745 +intermediateposes: 44 +0.0000 0.0000 0.4636 +-0.0114 -0.0056 0.4529 +-0.0228 -0.0111 0.4421 +-0.0342 -0.0165 0.4313 +-0.0458 -0.0218 0.4205 +-0.0573 -0.0269 0.4097 +-0.0690 -0.0319 0.3990 +-0.0807 -0.0368 0.3882 +-0.0924 -0.0415 0.3774 +-0.1042 -0.0462 0.3666 +-0.1160 -0.0507 0.3558 +-0.1279 -0.0550 0.3450 +-0.1399 -0.0593 0.3343 +-0.1518 -0.0634 0.3235 +-0.1639 -0.0674 0.3127 +-0.1759 -0.0712 0.3019 +-0.1880 -0.0749 0.2911 +-0.2002 -0.0785 0.2803 +-0.2124 -0.0820 0.2696 +-0.2246 -0.0853 0.2588 +-0.2368 -0.0885 0.2480 +-0.2491 -0.0916 0.2372 +-0.2614 -0.0945 0.2264 +-0.2738 -0.0973 0.2157 +-0.2862 -0.1000 0.2049 +-0.2986 -0.1025 0.1941 +-0.3110 -0.1049 0.1833 +-0.3235 -0.1072 0.1725 +-0.3360 -0.1093 0.1617 +-0.3485 -0.1113 0.1510 +-0.3610 -0.1132 0.1402 +-0.3735 -0.1149 0.1294 +-0.3861 -0.1165 0.1186 +-0.3987 -0.1179 0.1078 +-0.4113 -0.1193 0.0970 +-0.4239 -0.1204 0.0863 +-0.4365 -0.1215 0.0755 +-0.4491 -0.1224 0.0647 +-0.4617 -0.1232 0.0539 +-0.4744 -0.1238 0.0431 +-0.4870 -0.1243 0.0323 +-0.4997 -0.1247 0.0216 +-0.5123 -0.1249 0.0108 +-0.5250 -0.1250 0.0000 +primID: 9 +startangle_c: 1 +endpose_c: 0 0 0 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 9 +0.0000 0.0000 0.4636 +0.0000 0.0000 0.4057 +0.0000 0.0000 0.3477 +0.0000 0.0000 0.2898 +0.0000 0.0000 0.2318 +0.0000 0.0000 0.1739 +0.0000 0.0000 0.1159 +0.0000 0.0000 0.0580 +0.0000 0.0000 0.0000 +primID: 0 +startangle_c: 2 +endpose_c: 1 1 2 +additionalactioncostmult: 1 +turning_radius: 0.0000 +intermediateposes: 3 +0.0000 0.0000 0.7854 +0.0125 0.0125 0.7854 +0.0250 0.0250 0.7854 +primID: 1 +startangle_c: 2 +endpose_c: 15 15 2 +additionalactioncostmult: 1 +turning_radius: 0.0000 +intermediateposes: 43 +0.0000 0.0000 0.7854 +0.0089 0.0089 0.7854 +0.0179 0.0179 0.7854 +0.0268 0.0268 0.7854 +0.0357 0.0357 0.7854 +0.0446 0.0446 0.7854 +0.0536 0.0536 0.7854 +0.0625 0.0625 0.7854 +0.0714 0.0714 0.7854 +0.0804 0.0804 0.7854 +0.0893 0.0893 0.7854 +0.0982 0.0982 0.7854 +0.1071 0.1071 0.7854 +0.1161 0.1161 0.7854 +0.1250 0.1250 0.7854 +0.1339 0.1339 0.7854 +0.1429 0.1429 0.7854 +0.1518 0.1518 0.7854 +0.1607 0.1607 0.7854 +0.1696 0.1696 0.7854 +0.1786 0.1786 0.7854 +0.1875 0.1875 0.7854 +0.1964 0.1964 0.7854 +0.2054 0.2054 0.7854 +0.2143 0.2143 0.7854 +0.2232 0.2232 0.7854 +0.2321 0.2321 0.7854 +0.2411 0.2411 0.7854 +0.2500 0.2500 0.7854 +0.2589 0.2589 0.7854 +0.2679 0.2679 0.7854 +0.2768 0.2768 0.7854 +0.2857 0.2857 0.7854 +0.2946 0.2946 0.7854 +0.3036 0.3036 0.7854 +0.3125 0.3125 0.7854 +0.3214 0.3214 0.7854 +0.3304 0.3304 0.7854 +0.3393 0.3393 0.7854 +0.3482 0.3482 0.7854 +0.3571 0.3571 0.7854 +0.3661 0.3661 0.7854 +0.3750 0.3750 0.7854 +primID: 2 +startangle_c: 2 +endpose_c: 13 18 3 +additionalactioncostmult: 2 +turning_radius: 1.7327 +intermediateposes: 45 +0.0000 0.0000 0.7854 +0.0089 0.0090 0.7927 +0.0178 0.0180 0.8000 +0.0266 0.0271 0.8073 +0.0353 0.0363 0.8146 +0.0440 0.0456 0.8220 +0.0526 0.0549 0.8293 +0.0612 0.0642 0.8366 +0.0696 0.0737 0.8439 +0.0780 0.0832 0.8512 +0.0863 0.0927 0.8585 +0.0946 0.1023 0.8658 +0.1028 0.1120 0.8731 +0.1109 0.1217 0.8805 +0.1189 0.1315 0.8878 +0.1269 0.1414 0.8951 +0.1348 0.1513 0.9024 +0.1426 0.1612 0.9097 +0.1504 0.1713 0.9170 +0.1581 0.1813 0.9243 +0.1657 0.1915 0.9316 +0.1732 0.2017 0.9390 +0.1807 0.2119 0.9463 +0.1880 0.2222 0.9536 +0.1953 0.2326 0.9609 +0.2026 0.2430 0.9682 +0.2097 0.2534 0.9755 +0.2168 0.2639 0.9828 +0.2238 0.2745 0.9901 +0.2307 0.2851 0.9975 +0.2376 0.2958 1.0048 +0.2443 0.3065 1.0121 +0.2510 0.3172 1.0194 +0.2576 0.3281 1.0267 +0.2641 0.3389 1.0340 +0.2706 0.3498 1.0413 +0.2770 0.3608 1.0486 +0.2833 0.3718 1.0560 +0.2895 0.3828 1.0633 +0.2956 0.3939 1.0706 +0.3016 0.4050 1.0779 +0.3076 0.4162 1.0852 +0.3135 0.4274 1.0925 +0.3193 0.4387 1.0998 +0.3250 0.4500 1.1071 +primID: 3 +startangle_c: 2 +endpose_c: 18 13 1 +additionalactioncostmult: 2 +turning_radius: -1.7327 +intermediateposes: 45 +0.0000 0.0000 0.7854 +0.0090 0.0089 0.7781 +0.0180 0.0178 0.7708 +0.0271 0.0266 0.7635 +0.0363 0.0353 0.7561 +0.0456 0.0440 0.7488 +0.0549 0.0526 0.7415 +0.0642 0.0612 0.7342 +0.0737 0.0696 0.7269 +0.0832 0.0780 0.7196 +0.0927 0.0863 0.7123 +0.1023 0.0946 0.7050 +0.1120 0.1028 0.6976 +0.1217 0.1109 0.6903 +0.1315 0.1189 0.6830 +0.1414 0.1269 0.6757 +0.1513 0.1348 0.6684 +0.1612 0.1426 0.6611 +0.1713 0.1504 0.6538 +0.1813 0.1581 0.6465 +0.1915 0.1657 0.6391 +0.2017 0.1732 0.6318 +0.2119 0.1807 0.6245 +0.2222 0.1880 0.6172 +0.2326 0.1953 0.6099 +0.2430 0.2026 0.6026 +0.2534 0.2097 0.5953 +0.2639 0.2168 0.5880 +0.2745 0.2238 0.5806 +0.2851 0.2307 0.5733 +0.2958 0.2376 0.5660 +0.3065 0.2443 0.5587 +0.3172 0.2510 0.5514 +0.3281 0.2576 0.5441 +0.3389 0.2641 0.5368 +0.3498 0.2706 0.5295 +0.3608 0.2770 0.5221 +0.3718 0.2833 0.5148 +0.3828 0.2895 0.5075 +0.3939 0.2956 0.5002 +0.4050 0.3016 0.4929 +0.4162 0.3076 0.4856 +0.4274 0.3135 0.4783 +0.4387 0.3193 0.4710 +0.4500 0.3250 0.4636 +primID: 4 +startangle_c: 2 +endpose_c: 0 0 3 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 6 +0.0000 0.0000 0.7854 +0.0000 0.0000 0.8497 +0.0000 0.0000 0.9141 +0.0000 0.0000 0.9784 +0.0000 0.0000 1.0428 +0.0000 0.0000 1.1071 +primID: 5 +startangle_c: 2 +endpose_c: -1 -1 2 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 3 +0.0000 0.0000 0.7854 +-0.0125 -0.0125 0.7854 +-0.0250 -0.0250 0.7854 +primID: 6 +startangle_c: 2 +endpose_c: -16 -16 2 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 46 +0.0000 0.0000 0.7854 +-0.0089 -0.0089 0.7854 +-0.0178 -0.0178 0.7854 +-0.0267 -0.0267 0.7854 +-0.0356 -0.0356 0.7854 +-0.0444 -0.0444 0.7854 +-0.0533 -0.0533 0.7854 +-0.0622 -0.0622 0.7854 +-0.0711 -0.0711 0.7854 +-0.0800 -0.0800 0.7854 +-0.0889 -0.0889 0.7854 +-0.0978 -0.0978 0.7854 +-0.1067 -0.1067 0.7854 +-0.1156 -0.1156 0.7854 +-0.1244 -0.1244 0.7854 +-0.1333 -0.1333 0.7854 +-0.1422 -0.1422 0.7854 +-0.1511 -0.1511 0.7854 +-0.1600 -0.1600 0.7854 +-0.1689 -0.1689 0.7854 +-0.1778 -0.1778 0.7854 +-0.1867 -0.1867 0.7854 +-0.1956 -0.1956 0.7854 +-0.2044 -0.2044 0.7854 +-0.2133 -0.2133 0.7854 +-0.2222 -0.2222 0.7854 +-0.2311 -0.2311 0.7854 +-0.2400 -0.2400 0.7854 +-0.2489 -0.2489 0.7854 +-0.2578 -0.2578 0.7854 +-0.2667 -0.2667 0.7854 +-0.2756 -0.2756 0.7854 +-0.2844 -0.2844 0.7854 +-0.2933 -0.2933 0.7854 +-0.3022 -0.3022 0.7854 +-0.3111 -0.3111 0.7854 +-0.3200 -0.3200 0.7854 +-0.3289 -0.3289 0.7854 +-0.3378 -0.3378 0.7854 +-0.3467 -0.3467 0.7854 +-0.3556 -0.3556 0.7854 +-0.3644 -0.3644 0.7854 +-0.3733 -0.3733 0.7854 +-0.3822 -0.3822 0.7854 +-0.3911 -0.3911 0.7854 +-0.4000 -0.4000 0.7854 +primID: 7 +startangle_c: 2 +endpose_c: -13 -18 3 +additionalactioncostmult: 3 +turning_radius: -1.7327 +intermediateposes: 45 +0.0000 0.0000 0.7854 +-0.0089 -0.0090 0.7927 +-0.0178 -0.0180 0.8000 +-0.0266 -0.0271 0.8073 +-0.0353 -0.0363 0.8146 +-0.0440 -0.0456 0.8220 +-0.0526 -0.0549 0.8293 +-0.0612 -0.0642 0.8366 +-0.0696 -0.0737 0.8439 +-0.0780 -0.0832 0.8512 +-0.0863 -0.0927 0.8585 +-0.0946 -0.1023 0.8658 +-0.1028 -0.1120 0.8731 +-0.1109 -0.1217 0.8805 +-0.1189 -0.1315 0.8878 +-0.1269 -0.1414 0.8951 +-0.1348 -0.1513 0.9024 +-0.1426 -0.1612 0.9097 +-0.1504 -0.1713 0.9170 +-0.1581 -0.1813 0.9243 +-0.1657 -0.1915 0.9316 +-0.1732 -0.2017 0.9390 +-0.1807 -0.2119 0.9463 +-0.1880 -0.2222 0.9536 +-0.1953 -0.2326 0.9609 +-0.2026 -0.2430 0.9682 +-0.2097 -0.2534 0.9755 +-0.2168 -0.2639 0.9828 +-0.2238 -0.2745 0.9901 +-0.2307 -0.2851 0.9975 +-0.2376 -0.2958 1.0048 +-0.2443 -0.3065 1.0121 +-0.2510 -0.3172 1.0194 +-0.2576 -0.3281 1.0267 +-0.2641 -0.3389 1.0340 +-0.2706 -0.3498 1.0413 +-0.2770 -0.3608 1.0486 +-0.2833 -0.3718 1.0560 +-0.2895 -0.3828 1.0633 +-0.2956 -0.3939 1.0706 +-0.3016 -0.4050 1.0779 +-0.3076 -0.4162 1.0852 +-0.3135 -0.4274 1.0925 +-0.3193 -0.4387 1.0998 +-0.3250 -0.4500 1.1071 +primID: 8 +startangle_c: 2 +endpose_c: -18 -13 1 +additionalactioncostmult: 3 +turning_radius: 1.7327 +intermediateposes: 45 +0.0000 0.0000 0.7854 +-0.0090 -0.0089 0.7781 +-0.0180 -0.0178 0.7708 +-0.0271 -0.0266 0.7635 +-0.0363 -0.0353 0.7561 +-0.0456 -0.0440 0.7488 +-0.0549 -0.0526 0.7415 +-0.0642 -0.0612 0.7342 +-0.0737 -0.0696 0.7269 +-0.0832 -0.0780 0.7196 +-0.0927 -0.0863 0.7123 +-0.1023 -0.0946 0.7050 +-0.1120 -0.1028 0.6976 +-0.1217 -0.1109 0.6903 +-0.1315 -0.1189 0.6830 +-0.1414 -0.1269 0.6757 +-0.1513 -0.1348 0.6684 +-0.1612 -0.1426 0.6611 +-0.1713 -0.1504 0.6538 +-0.1813 -0.1581 0.6465 +-0.1915 -0.1657 0.6391 +-0.2017 -0.1732 0.6318 +-0.2119 -0.1807 0.6245 +-0.2222 -0.1880 0.6172 +-0.2326 -0.1953 0.6099 +-0.2430 -0.2026 0.6026 +-0.2534 -0.2097 0.5953 +-0.2639 -0.2168 0.5880 +-0.2745 -0.2238 0.5806 +-0.2851 -0.2307 0.5733 +-0.2958 -0.2376 0.5660 +-0.3065 -0.2443 0.5587 +-0.3172 -0.2510 0.5514 +-0.3281 -0.2576 0.5441 +-0.3389 -0.2641 0.5368 +-0.3498 -0.2706 0.5295 +-0.3608 -0.2770 0.5221 +-0.3718 -0.2833 0.5148 +-0.3828 -0.2895 0.5075 +-0.3939 -0.2956 0.5002 +-0.4050 -0.3016 0.4929 +-0.4162 -0.3076 0.4856 +-0.4274 -0.3135 0.4783 +-0.4387 -0.3193 0.4710 +-0.4500 -0.3250 0.4636 +primID: 9 +startangle_c: 2 +endpose_c: 0 0 1 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 6 +0.0000 0.0000 0.7854 +0.0000 0.0000 0.7210 +0.0000 0.0000 0.6567 +0.0000 0.0000 0.5923 +0.0000 0.0000 0.5280 +0.0000 0.0000 0.4636 +primID: 0 +startangle_c: 3 +endpose_c: 1 2 3 +additionalactioncostmult: 1 +turning_radius: -0.0000 +intermediateposes: 5 +0.0000 0.0000 1.1071 +0.0063 0.0125 1.1071 +0.0125 0.0250 1.1071 +0.0188 0.0375 1.1071 +0.0250 0.0500 1.1071 +primID: 1 +startangle_c: 3 +endpose_c: 10 20 3 +additionalactioncostmult: 1 +turning_radius: -0.0000 +intermediateposes: 45 +0.0000 0.0000 1.1071 +0.0057 0.0114 1.1071 +0.0114 0.0227 1.1071 +0.0170 0.0341 1.1071 +0.0227 0.0455 1.1071 +0.0284 0.0568 1.1071 +0.0341 0.0682 1.1071 +0.0398 0.0795 1.1071 +0.0455 0.0909 1.1071 +0.0511 0.1023 1.1071 +0.0568 0.1136 1.1071 +0.0625 0.1250 1.1071 +0.0682 0.1364 1.1071 +0.0739 0.1477 1.1071 +0.0795 0.1591 1.1071 +0.0852 0.1705 1.1071 +0.0909 0.1818 1.1071 +0.0966 0.1932 1.1071 +0.1023 0.2045 1.1071 +0.1080 0.2159 1.1071 +0.1136 0.2273 1.1071 +0.1193 0.2386 1.1071 +0.1250 0.2500 1.1071 +0.1307 0.2614 1.1071 +0.1364 0.2727 1.1071 +0.1420 0.2841 1.1071 +0.1477 0.2955 1.1071 +0.1534 0.3068 1.1071 +0.1591 0.3182 1.1071 +0.1648 0.3295 1.1071 +0.1705 0.3409 1.1071 +0.1761 0.3523 1.1071 +0.1818 0.3636 1.1071 +0.1875 0.3750 1.1071 +0.1932 0.3864 1.1071 +0.1989 0.3977 1.1071 +0.2045 0.4091 1.1071 +0.2102 0.4205 1.1071 +0.2159 0.4318 1.1071 +0.2216 0.4432 1.1071 +0.2273 0.4545 1.1071 +0.2330 0.4659 1.1071 +0.2386 0.4773 1.1071 +0.2443 0.4886 1.1071 +0.2500 0.5000 1.1071 +primID: 2 +startangle_c: 3 +endpose_c: 13 18 2 +additionalactioncostmult: 2 +turning_radius: -1.7327 +intermediateposes: 45 +0.0000 0.0000 1.1071 +0.0057 0.0113 1.0998 +0.0115 0.0226 1.0925 +0.0174 0.0338 1.0852 +0.0234 0.0450 1.0779 +0.0294 0.0561 1.0706 +0.0355 0.0672 1.0633 +0.0417 0.0782 1.0560 +0.0480 0.0892 1.0486 +0.0544 0.1002 1.0413 +0.0609 0.1111 1.0340 +0.0674 0.1219 1.0267 +0.0740 0.1328 1.0194 +0.0807 0.1435 1.0121 +0.0874 0.1542 1.0048 +0.0943 0.1649 0.9975 +0.1012 0.1755 0.9901 +0.1082 0.1861 0.9828 +0.1153 0.1966 0.9755 +0.1224 0.2070 0.9682 +0.1297 0.2174 0.9609 +0.1370 0.2278 0.9536 +0.1443 0.2381 0.9463 +0.1518 0.2483 0.9390 +0.1593 0.2585 0.9316 +0.1669 0.2687 0.9243 +0.1746 0.2787 0.9170 +0.1824 0.2888 0.9097 +0.1902 0.2987 0.9024 +0.1981 0.3086 0.8951 +0.2061 0.3185 0.8878 +0.2141 0.3283 0.8805 +0.2222 0.3380 0.8731 +0.2304 0.3477 0.8658 +0.2387 0.3573 0.8585 +0.2470 0.3668 0.8512 +0.2554 0.3763 0.8439 +0.2638 0.3858 0.8366 +0.2724 0.3951 0.8293 +0.2810 0.4044 0.8220 +0.2897 0.4137 0.8146 +0.2984 0.4229 0.8073 +0.3072 0.4320 0.8000 +0.3161 0.4410 0.7927 +0.3250 0.4500 0.7854 +primID: 3 +startangle_c: 3 +endpose_c: 5 21 4 +additionalactioncostmult: 2 +turning_radius: 1.1745 +intermediateposes: 44 +0.0000 0.0000 1.1071 +0.0056 0.0114 1.1179 +0.0111 0.0228 1.1287 +0.0165 0.0342 1.1395 +0.0218 0.0458 1.1503 +0.0269 0.0573 1.1611 +0.0319 0.0690 1.1718 +0.0368 0.0807 1.1826 +0.0415 0.0924 1.1934 +0.0462 0.1042 1.2042 +0.0507 0.1160 1.2150 +0.0550 0.1279 1.2258 +0.0593 0.1399 1.2365 +0.0634 0.1518 1.2473 +0.0674 0.1639 1.2581 +0.0712 0.1759 1.2689 +0.0749 0.1880 1.2797 +0.0785 0.2002 1.2905 +0.0820 0.2124 1.3012 +0.0853 0.2246 1.3120 +0.0885 0.2368 1.3228 +0.0916 0.2491 1.3336 +0.0945 0.2614 1.3444 +0.0973 0.2738 1.3551 +0.1000 0.2862 1.3659 +0.1025 0.2986 1.3767 +0.1049 0.3110 1.3875 +0.1072 0.3235 1.3983 +0.1093 0.3360 1.4091 +0.1113 0.3485 1.4198 +0.1132 0.3610 1.4306 +0.1149 0.3735 1.4414 +0.1165 0.3861 1.4522 +0.1179 0.3987 1.4630 +0.1193 0.4113 1.4738 +0.1204 0.4239 1.4845 +0.1215 0.4365 1.4953 +0.1224 0.4491 1.5061 +0.1232 0.4617 1.5169 +0.1238 0.4744 1.5277 +0.1243 0.4870 1.5384 +0.1247 0.4997 1.5492 +0.1249 0.5123 1.5600 +0.1250 0.5250 1.5708 +primID: 4 +startangle_c: 3 +endpose_c: 0 0 2 +additionalactioncostmult: 5 +turning_radius: -0.0000 +intermediateposes: 6 +0.0000 0.0000 1.1071 +0.0000 0.0000 1.0428 +0.0000 0.0000 0.9784 +0.0000 0.0000 0.9141 +0.0000 0.0000 0.8497 +0.0000 0.0000 0.7854 +primID: 5 +startangle_c: 3 +endpose_c: -1 -2 3 +additionalactioncostmult: 5 +turning_radius: -0.0000 +intermediateposes: 5 +0.0000 0.0000 1.1071 +-0.0063 -0.0125 1.1071 +-0.0125 -0.0250 1.1071 +-0.0188 -0.0375 1.1071 +-0.0250 -0.0500 1.1071 +primID: 6 +startangle_c: 3 +endpose_c: -10 -20 3 +additionalactioncostmult: 5 +turning_radius: -0.0000 +intermediateposes: 45 +0.0000 0.0000 1.1071 +-0.0057 -0.0114 1.1071 +-0.0114 -0.0227 1.1071 +-0.0170 -0.0341 1.1071 +-0.0227 -0.0455 1.1071 +-0.0284 -0.0568 1.1071 +-0.0341 -0.0682 1.1071 +-0.0398 -0.0795 1.1071 +-0.0455 -0.0909 1.1071 +-0.0511 -0.1023 1.1071 +-0.0568 -0.1136 1.1071 +-0.0625 -0.1250 1.1071 +-0.0682 -0.1364 1.1071 +-0.0739 -0.1477 1.1071 +-0.0795 -0.1591 1.1071 +-0.0852 -0.1705 1.1071 +-0.0909 -0.1818 1.1071 +-0.0966 -0.1932 1.1071 +-0.1023 -0.2045 1.1071 +-0.1080 -0.2159 1.1071 +-0.1136 -0.2273 1.1071 +-0.1193 -0.2386 1.1071 +-0.1250 -0.2500 1.1071 +-0.1307 -0.2614 1.1071 +-0.1364 -0.2727 1.1071 +-0.1420 -0.2841 1.1071 +-0.1477 -0.2955 1.1071 +-0.1534 -0.3068 1.1071 +-0.1591 -0.3182 1.1071 +-0.1648 -0.3295 1.1071 +-0.1705 -0.3409 1.1071 +-0.1761 -0.3523 1.1071 +-0.1818 -0.3636 1.1071 +-0.1875 -0.3750 1.1071 +-0.1932 -0.3864 1.1071 +-0.1989 -0.3977 1.1071 +-0.2045 -0.4091 1.1071 +-0.2102 -0.4205 1.1071 +-0.2159 -0.4318 1.1071 +-0.2216 -0.4432 1.1071 +-0.2273 -0.4545 1.1071 +-0.2330 -0.4659 1.1071 +-0.2386 -0.4773 1.1071 +-0.2443 -0.4886 1.1071 +-0.2500 -0.5000 1.1071 +primID: 7 +startangle_c: 3 +endpose_c: -13 -18 2 +additionalactioncostmult: 3 +turning_radius: 1.7327 +intermediateposes: 45 +0.0000 0.0000 1.1071 +-0.0057 -0.0113 1.0998 +-0.0115 -0.0226 1.0925 +-0.0174 -0.0338 1.0852 +-0.0234 -0.0450 1.0779 +-0.0294 -0.0561 1.0706 +-0.0355 -0.0672 1.0633 +-0.0417 -0.0782 1.0560 +-0.0480 -0.0892 1.0486 +-0.0544 -0.1002 1.0413 +-0.0609 -0.1111 1.0340 +-0.0674 -0.1219 1.0267 +-0.0740 -0.1328 1.0194 +-0.0807 -0.1435 1.0121 +-0.0874 -0.1542 1.0048 +-0.0943 -0.1649 0.9975 +-0.1012 -0.1755 0.9901 +-0.1082 -0.1861 0.9828 +-0.1153 -0.1966 0.9755 +-0.1224 -0.2070 0.9682 +-0.1297 -0.2174 0.9609 +-0.1370 -0.2278 0.9536 +-0.1443 -0.2381 0.9463 +-0.1518 -0.2483 0.9390 +-0.1593 -0.2585 0.9316 +-0.1669 -0.2687 0.9243 +-0.1746 -0.2787 0.9170 +-0.1824 -0.2888 0.9097 +-0.1902 -0.2987 0.9024 +-0.1981 -0.3086 0.8951 +-0.2061 -0.3185 0.8878 +-0.2141 -0.3283 0.8805 +-0.2222 -0.3380 0.8731 +-0.2304 -0.3477 0.8658 +-0.2387 -0.3573 0.8585 +-0.2470 -0.3668 0.8512 +-0.2554 -0.3763 0.8439 +-0.2638 -0.3858 0.8366 +-0.2724 -0.3951 0.8293 +-0.2810 -0.4044 0.8220 +-0.2897 -0.4137 0.8146 +-0.2984 -0.4229 0.8073 +-0.3072 -0.4320 0.8000 +-0.3161 -0.4410 0.7927 +-0.3250 -0.4500 0.7854 +primID: 8 +startangle_c: 3 +endpose_c: -5 -21 4 +additionalactioncostmult: 3 +turning_radius: -1.1745 +intermediateposes: 44 +0.0000 0.0000 1.1071 +-0.0056 -0.0114 1.1179 +-0.0111 -0.0228 1.1287 +-0.0165 -0.0342 1.1395 +-0.0218 -0.0458 1.1503 +-0.0269 -0.0573 1.1611 +-0.0319 -0.0690 1.1718 +-0.0368 -0.0807 1.1826 +-0.0415 -0.0924 1.1934 +-0.0462 -0.1042 1.2042 +-0.0507 -0.1160 1.2150 +-0.0550 -0.1279 1.2258 +-0.0593 -0.1399 1.2365 +-0.0634 -0.1518 1.2473 +-0.0674 -0.1639 1.2581 +-0.0712 -0.1759 1.2689 +-0.0749 -0.1880 1.2797 +-0.0785 -0.2002 1.2905 +-0.0820 -0.2124 1.3012 +-0.0853 -0.2246 1.3120 +-0.0885 -0.2368 1.3228 +-0.0916 -0.2491 1.3336 +-0.0945 -0.2614 1.3444 +-0.0973 -0.2738 1.3551 +-0.1000 -0.2862 1.3659 +-0.1025 -0.2986 1.3767 +-0.1049 -0.3110 1.3875 +-0.1072 -0.3235 1.3983 +-0.1093 -0.3360 1.4091 +-0.1113 -0.3485 1.4198 +-0.1132 -0.3610 1.4306 +-0.1149 -0.3735 1.4414 +-0.1165 -0.3861 1.4522 +-0.1179 -0.3987 1.4630 +-0.1193 -0.4113 1.4738 +-0.1204 -0.4239 1.4845 +-0.1215 -0.4365 1.4953 +-0.1224 -0.4491 1.5061 +-0.1232 -0.4617 1.5169 +-0.1238 -0.4744 1.5277 +-0.1243 -0.4870 1.5384 +-0.1247 -0.4997 1.5492 +-0.1249 -0.5123 1.5600 +-0.1250 -0.5250 1.5708 +primID: 9 +startangle_c: 3 +endpose_c: 0 0 4 +additionalactioncostmult: 5 +turning_radius: -0.0000 +intermediateposes: 9 +0.0000 0.0000 1.1071 +0.0000 0.0000 1.1651 +0.0000 0.0000 1.2231 +0.0000 0.0000 1.2810 +0.0000 0.0000 1.3390 +0.0000 0.0000 1.3969 +0.0000 0.0000 1.4549 +0.0000 0.0000 1.5128 +0.0000 0.0000 1.5708 +primID: 0 +startangle_c: 4 +endpose_c: 0 1 4 +additionalactioncostmult: 1 +turning_radius: 0.0000 +intermediateposes: 3 +0.0000 0.0000 1.5708 +0.0000 0.0125 1.5708 +0.0000 0.0250 1.5708 +primID: 1 +startangle_c: 4 +endpose_c: 0 21 4 +additionalactioncostmult: 1 +turning_radius: 0.0000 +intermediateposes: 43 +0.0000 0.0000 1.5708 +0.0000 0.0125 1.5708 +0.0000 0.0250 1.5708 +0.0000 0.0375 1.5708 +0.0000 0.0500 1.5708 +0.0000 0.0625 1.5708 +0.0000 0.0750 1.5708 +0.0000 0.0875 1.5708 +0.0000 0.1000 1.5708 +0.0000 0.1125 1.5708 +0.0000 0.1250 1.5708 +0.0000 0.1375 1.5708 +0.0000 0.1500 1.5708 +0.0000 0.1625 1.5708 +0.0000 0.1750 1.5708 +0.0000 0.1875 1.5708 +0.0000 0.2000 1.5708 +0.0000 0.2125 1.5708 +0.0000 0.2250 1.5708 +0.0000 0.2375 1.5708 +0.0000 0.2500 1.5708 +0.0000 0.2625 1.5708 +0.0000 0.2750 1.5708 +0.0000 0.2875 1.5708 +0.0000 0.3000 1.5708 +0.0000 0.3125 1.5708 +0.0000 0.3250 1.5708 +0.0000 0.3375 1.5708 +0.0000 0.3500 1.5708 +0.0000 0.3625 1.5708 +0.0000 0.3750 1.5708 +0.0000 0.3875 1.5708 +0.0000 0.4000 1.5708 +0.0000 0.4125 1.5708 +0.0000 0.4250 1.5708 +0.0000 0.4375 1.5708 +0.0000 0.4500 1.5708 +0.0000 0.4625 1.5708 +0.0000 0.4750 1.5708 +0.0000 0.4875 1.5708 +0.0000 0.5000 1.5708 +0.0000 0.5125 1.5708 +0.0000 0.5250 1.5708 +primID: 2 +startangle_c: 4 +endpose_c: -5 21 5 +additionalactioncostmult: 2 +turning_radius: 1.1745 +intermediateposes: 44 +0.0000 0.0000 1.5708 +-0.0001 0.0127 1.5816 +-0.0003 0.0253 1.5924 +-0.0007 0.0380 1.6031 +-0.0012 0.0506 1.6139 +-0.0018 0.0633 1.6247 +-0.0026 0.0759 1.6355 +-0.0035 0.0885 1.6463 +-0.0046 0.1011 1.6571 +-0.0057 0.1137 1.6678 +-0.0071 0.1263 1.6786 +-0.0085 0.1389 1.6894 +-0.0101 0.1515 1.7002 +-0.0118 0.1640 1.7110 +-0.0137 0.1765 1.7218 +-0.0157 0.1890 1.7325 +-0.0178 0.2015 1.7433 +-0.0201 0.2140 1.7541 +-0.0225 0.2264 1.7649 +-0.0250 0.2388 1.7757 +-0.0277 0.2512 1.7864 +-0.0305 0.2636 1.7972 +-0.0334 0.2759 1.8080 +-0.0365 0.2882 1.8188 +-0.0397 0.3004 1.8296 +-0.0430 0.3126 1.8404 +-0.0465 0.3248 1.8511 +-0.0501 0.3370 1.8619 +-0.0538 0.3491 1.8727 +-0.0576 0.3611 1.8835 +-0.0616 0.3732 1.8943 +-0.0657 0.3851 1.9051 +-0.0700 0.3971 1.9158 +-0.0743 0.4090 1.9266 +-0.0788 0.4208 1.9374 +-0.0835 0.4326 1.9482 +-0.0882 0.4443 1.9590 +-0.0931 0.4560 1.9697 +-0.0981 0.4677 1.9805 +-0.1032 0.4792 1.9913 +-0.1085 0.4908 2.0021 +-0.1139 0.5022 2.0129 +-0.1194 0.5136 2.0237 +-0.1250 0.5250 2.0344 +primID: 3 +startangle_c: 4 +endpose_c: 5 21 3 +additionalactioncostmult: 2 +turning_radius: -1.1745 +intermediateposes: 44 +0.0000 0.0000 1.5708 +0.0001 0.0127 1.5600 +0.0003 0.0253 1.5492 +0.0007 0.0380 1.5384 +0.0012 0.0506 1.5277 +0.0018 0.0633 1.5169 +0.0026 0.0759 1.5061 +0.0035 0.0885 1.4953 +0.0046 0.1011 1.4845 +0.0057 0.1137 1.4738 +0.0071 0.1263 1.4630 +0.0085 0.1389 1.4522 +0.0101 0.1515 1.4414 +0.0118 0.1640 1.4306 +0.0137 0.1765 1.4198 +0.0157 0.1890 1.4091 +0.0178 0.2015 1.3983 +0.0201 0.2140 1.3875 +0.0225 0.2264 1.3767 +0.0250 0.2388 1.3659 +0.0277 0.2512 1.3551 +0.0305 0.2636 1.3444 +0.0334 0.2759 1.3336 +0.0365 0.2882 1.3228 +0.0397 0.3004 1.3120 +0.0430 0.3126 1.3012 +0.0465 0.3248 1.2905 +0.0501 0.3370 1.2797 +0.0538 0.3491 1.2689 +0.0576 0.3611 1.2581 +0.0616 0.3732 1.2473 +0.0657 0.3851 1.2365 +0.0700 0.3971 1.2258 +0.0743 0.4090 1.2150 +0.0788 0.4208 1.2042 +0.0835 0.4326 1.1934 +0.0882 0.4443 1.1826 +0.0931 0.4560 1.1718 +0.0981 0.4677 1.1611 +0.1032 0.4792 1.1503 +0.1085 0.4908 1.1395 +0.1139 0.5022 1.1287 +0.1194 0.5136 1.1179 +0.1250 0.5250 1.1071 +primID: 4 +startangle_c: 4 +endpose_c: 0 0 5 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 9 +0.0000 0.0000 1.5708 +0.0000 0.0000 1.6288 +0.0000 0.0000 1.6867 +0.0000 0.0000 1.7447 +0.0000 0.0000 1.8026 +0.0000 0.0000 1.8606 +0.0000 0.0000 1.9185 +0.0000 0.0000 1.9765 +0.0000 0.0000 2.0344 +primID: 5 +startangle_c: 4 +endpose_c: 0 -1 4 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 3 +0.0000 0.0000 1.5708 +0.0000 -0.0125 1.5708 +0.0000 -0.0250 1.5708 +primID: 6 +startangle_c: 4 +endpose_c: 0 -21 4 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 43 +0.0000 0.0000 1.5708 +0.0000 -0.0125 1.5708 +0.0000 -0.0250 1.5708 +0.0000 -0.0375 1.5708 +0.0000 -0.0500 1.5708 +0.0000 -0.0625 1.5708 +0.0000 -0.0750 1.5708 +0.0000 -0.0875 1.5708 +0.0000 -0.1000 1.5708 +0.0000 -0.1125 1.5708 +0.0000 -0.1250 1.5708 +0.0000 -0.1375 1.5708 +0.0000 -0.1500 1.5708 +0.0000 -0.1625 1.5708 +0.0000 -0.1750 1.5708 +0.0000 -0.1875 1.5708 +0.0000 -0.2000 1.5708 +0.0000 -0.2125 1.5708 +0.0000 -0.2250 1.5708 +0.0000 -0.2375 1.5708 +0.0000 -0.2500 1.5708 +0.0000 -0.2625 1.5708 +0.0000 -0.2750 1.5708 +0.0000 -0.2875 1.5708 +0.0000 -0.3000 1.5708 +0.0000 -0.3125 1.5708 +0.0000 -0.3250 1.5708 +0.0000 -0.3375 1.5708 +0.0000 -0.3500 1.5708 +0.0000 -0.3625 1.5708 +0.0000 -0.3750 1.5708 +0.0000 -0.3875 1.5708 +0.0000 -0.4000 1.5708 +0.0000 -0.4125 1.5708 +0.0000 -0.4250 1.5708 +0.0000 -0.4375 1.5708 +0.0000 -0.4500 1.5708 +0.0000 -0.4625 1.5708 +0.0000 -0.4750 1.5708 +0.0000 -0.4875 1.5708 +0.0000 -0.5000 1.5708 +0.0000 -0.5125 1.5708 +0.0000 -0.5250 1.5708 +primID: 7 +startangle_c: 4 +endpose_c: 5 -21 5 +additionalactioncostmult: 3 +turning_radius: -1.1745 +intermediateposes: 44 +0.0000 0.0000 1.5708 +0.0001 -0.0127 1.5816 +0.0003 -0.0253 1.5924 +0.0007 -0.0380 1.6031 +0.0012 -0.0506 1.6139 +0.0018 -0.0633 1.6247 +0.0026 -0.0759 1.6355 +0.0035 -0.0885 1.6463 +0.0046 -0.1011 1.6571 +0.0057 -0.1137 1.6678 +0.0071 -0.1263 1.6786 +0.0085 -0.1389 1.6894 +0.0101 -0.1515 1.7002 +0.0118 -0.1640 1.7110 +0.0137 -0.1765 1.7218 +0.0157 -0.1890 1.7325 +0.0178 -0.2015 1.7433 +0.0201 -0.2140 1.7541 +0.0225 -0.2264 1.7649 +0.0250 -0.2388 1.7757 +0.0277 -0.2512 1.7864 +0.0305 -0.2636 1.7972 +0.0334 -0.2759 1.8080 +0.0365 -0.2882 1.8188 +0.0397 -0.3004 1.8296 +0.0430 -0.3126 1.8404 +0.0465 -0.3248 1.8511 +0.0501 -0.3370 1.8619 +0.0538 -0.3491 1.8727 +0.0576 -0.3611 1.8835 +0.0616 -0.3732 1.8943 +0.0657 -0.3851 1.9051 +0.0700 -0.3971 1.9158 +0.0743 -0.4090 1.9266 +0.0788 -0.4208 1.9374 +0.0835 -0.4326 1.9482 +0.0882 -0.4443 1.9590 +0.0931 -0.4560 1.9697 +0.0981 -0.4677 1.9805 +0.1032 -0.4792 1.9913 +0.1085 -0.4908 2.0021 +0.1139 -0.5022 2.0129 +0.1194 -0.5136 2.0237 +0.1250 -0.5250 2.0344 +primID: 8 +startangle_c: 4 +endpose_c: -5 -21 3 +additionalactioncostmult: 3 +turning_radius: 1.1745 +intermediateposes: 44 +0.0000 0.0000 1.5708 +-0.0001 -0.0127 1.5600 +-0.0003 -0.0253 1.5492 +-0.0007 -0.0380 1.5384 +-0.0012 -0.0506 1.5277 +-0.0018 -0.0633 1.5169 +-0.0026 -0.0759 1.5061 +-0.0035 -0.0885 1.4953 +-0.0046 -0.1011 1.4845 +-0.0057 -0.1137 1.4738 +-0.0071 -0.1263 1.4630 +-0.0085 -0.1389 1.4522 +-0.0101 -0.1515 1.4414 +-0.0118 -0.1640 1.4306 +-0.0137 -0.1765 1.4198 +-0.0157 -0.1890 1.4091 +-0.0178 -0.2015 1.3983 +-0.0201 -0.2140 1.3875 +-0.0225 -0.2264 1.3767 +-0.0250 -0.2388 1.3659 +-0.0277 -0.2512 1.3551 +-0.0305 -0.2636 1.3444 +-0.0334 -0.2759 1.3336 +-0.0365 -0.2882 1.3228 +-0.0397 -0.3004 1.3120 +-0.0430 -0.3126 1.3012 +-0.0465 -0.3248 1.2905 +-0.0501 -0.3370 1.2797 +-0.0538 -0.3491 1.2689 +-0.0576 -0.3611 1.2581 +-0.0616 -0.3732 1.2473 +-0.0657 -0.3851 1.2365 +-0.0700 -0.3971 1.2258 +-0.0743 -0.4090 1.2150 +-0.0788 -0.4208 1.2042 +-0.0835 -0.4326 1.1934 +-0.0882 -0.4443 1.1826 +-0.0931 -0.4560 1.1718 +-0.0981 -0.4677 1.1611 +-0.1032 -0.4792 1.1503 +-0.1085 -0.4908 1.1395 +-0.1139 -0.5022 1.1287 +-0.1194 -0.5136 1.1179 +-0.1250 -0.5250 1.1071 +primID: 9 +startangle_c: 4 +endpose_c: 0 0 3 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 9 +0.0000 0.0000 1.5708 +0.0000 0.0000 1.5128 +0.0000 0.0000 1.4549 +0.0000 0.0000 1.3969 +0.0000 0.0000 1.3390 +0.0000 0.0000 1.2810 +0.0000 0.0000 1.2231 +0.0000 0.0000 1.1651 +0.0000 0.0000 1.1071 +primID: 0 +startangle_c: 5 +endpose_c: -1 2 5 +additionalactioncostmult: 1 +turning_radius: 0.0000 +intermediateposes: 5 +0.0000 0.0000 2.0344 +-0.0063 0.0125 2.0344 +-0.0125 0.0250 2.0344 +-0.0188 0.0375 2.0344 +-0.0250 0.0500 2.0344 +primID: 1 +startangle_c: 5 +endpose_c: -10 20 5 +additionalactioncostmult: 1 +turning_radius: 0.0000 +intermediateposes: 45 +0.0000 0.0000 2.0344 +-0.0057 0.0114 2.0344 +-0.0114 0.0227 2.0344 +-0.0170 0.0341 2.0344 +-0.0227 0.0455 2.0344 +-0.0284 0.0568 2.0344 +-0.0341 0.0682 2.0344 +-0.0398 0.0795 2.0344 +-0.0455 0.0909 2.0344 +-0.0511 0.1023 2.0344 +-0.0568 0.1136 2.0344 +-0.0625 0.1250 2.0344 +-0.0682 0.1364 2.0344 +-0.0739 0.1477 2.0344 +-0.0795 0.1591 2.0344 +-0.0852 0.1705 2.0344 +-0.0909 0.1818 2.0344 +-0.0966 0.1932 2.0344 +-0.1023 0.2045 2.0344 +-0.1080 0.2159 2.0344 +-0.1136 0.2273 2.0344 +-0.1193 0.2386 2.0344 +-0.1250 0.2500 2.0344 +-0.1307 0.2614 2.0344 +-0.1364 0.2727 2.0344 +-0.1420 0.2841 2.0344 +-0.1477 0.2955 2.0344 +-0.1534 0.3068 2.0344 +-0.1591 0.3182 2.0344 +-0.1648 0.3295 2.0344 +-0.1705 0.3409 2.0344 +-0.1761 0.3523 2.0344 +-0.1818 0.3636 2.0344 +-0.1875 0.3750 2.0344 +-0.1932 0.3864 2.0344 +-0.1989 0.3977 2.0344 +-0.2045 0.4091 2.0344 +-0.2102 0.4205 2.0344 +-0.2159 0.4318 2.0344 +-0.2216 0.4432 2.0344 +-0.2273 0.4545 2.0344 +-0.2330 0.4659 2.0344 +-0.2386 0.4773 2.0344 +-0.2443 0.4886 2.0344 +-0.2500 0.5000 2.0344 +primID: 2 +startangle_c: 5 +endpose_c: -13 18 6 +additionalactioncostmult: 2 +turning_radius: 1.7327 +intermediateposes: 45 +0.0000 0.0000 2.0344 +-0.0057 0.0113 2.0418 +-0.0115 0.0226 2.0491 +-0.0174 0.0338 2.0564 +-0.0234 0.0450 2.0637 +-0.0294 0.0561 2.0710 +-0.0355 0.0672 2.0783 +-0.0417 0.0782 2.0856 +-0.0480 0.0892 2.0929 +-0.0544 0.1002 2.1003 +-0.0609 0.1111 2.1076 +-0.0674 0.1219 2.1149 +-0.0740 0.1328 2.1222 +-0.0807 0.1435 2.1295 +-0.0874 0.1542 2.1368 +-0.0943 0.1649 2.1441 +-0.1012 0.1755 2.1514 +-0.1082 0.1861 2.1588 +-0.1153 0.1966 2.1661 +-0.1224 0.2070 2.1734 +-0.1297 0.2174 2.1807 +-0.1370 0.2278 2.1880 +-0.1443 0.2381 2.1953 +-0.1518 0.2483 2.2026 +-0.1593 0.2585 2.2099 +-0.1669 0.2687 2.2173 +-0.1746 0.2787 2.2246 +-0.1824 0.2888 2.2319 +-0.1902 0.2987 2.2392 +-0.1981 0.3086 2.2465 +-0.2061 0.3185 2.2538 +-0.2141 0.3283 2.2611 +-0.2222 0.3380 2.2684 +-0.2304 0.3477 2.2758 +-0.2387 0.3573 2.2831 +-0.2470 0.3668 2.2904 +-0.2554 0.3763 2.2977 +-0.2638 0.3858 2.3050 +-0.2724 0.3951 2.3123 +-0.2810 0.4044 2.3196 +-0.2897 0.4137 2.3269 +-0.2984 0.4229 2.3343 +-0.3072 0.4320 2.3416 +-0.3161 0.4410 2.3489 +-0.3250 0.4500 2.3562 +primID: 3 +startangle_c: 5 +endpose_c: -5 21 4 +additionalactioncostmult: 2 +turning_radius: -1.1745 +intermediateposes: 44 +0.0000 0.0000 2.0344 +-0.0056 0.0114 2.0237 +-0.0111 0.0228 2.0129 +-0.0165 0.0342 2.0021 +-0.0218 0.0458 1.9913 +-0.0269 0.0573 1.9805 +-0.0319 0.0690 1.9697 +-0.0368 0.0807 1.9590 +-0.0415 0.0924 1.9482 +-0.0462 0.1042 1.9374 +-0.0507 0.1160 1.9266 +-0.0550 0.1279 1.9158 +-0.0593 0.1399 1.9051 +-0.0634 0.1518 1.8943 +-0.0674 0.1639 1.8835 +-0.0712 0.1759 1.8727 +-0.0749 0.1880 1.8619 +-0.0785 0.2002 1.8511 +-0.0820 0.2124 1.8404 +-0.0853 0.2246 1.8296 +-0.0885 0.2368 1.8188 +-0.0916 0.2491 1.8080 +-0.0945 0.2614 1.7972 +-0.0973 0.2738 1.7864 +-0.1000 0.2862 1.7757 +-0.1025 0.2986 1.7649 +-0.1049 0.3110 1.7541 +-0.1072 0.3235 1.7433 +-0.1093 0.3360 1.7325 +-0.1113 0.3485 1.7218 +-0.1132 0.3610 1.7110 +-0.1149 0.3735 1.7002 +-0.1165 0.3861 1.6894 +-0.1179 0.3987 1.6786 +-0.1193 0.4113 1.6678 +-0.1204 0.4239 1.6571 +-0.1215 0.4365 1.6463 +-0.1224 0.4491 1.6355 +-0.1232 0.4617 1.6247 +-0.1238 0.4744 1.6139 +-0.1243 0.4870 1.6031 +-0.1247 0.4997 1.5924 +-0.1249 0.5123 1.5816 +-0.1250 0.5250 1.5708 +primID: 4 +startangle_c: 5 +endpose_c: 0 0 6 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 6 +0.0000 0.0000 2.0344 +0.0000 0.0000 2.0988 +0.0000 0.0000 2.1631 +0.0000 0.0000 2.2275 +0.0000 0.0000 2.2918 +0.0000 0.0000 2.3562 +primID: 5 +startangle_c: 5 +endpose_c: 1 -2 5 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 5 +0.0000 0.0000 2.0344 +0.0063 -0.0125 2.0344 +0.0125 -0.0250 2.0344 +0.0188 -0.0375 2.0344 +0.0250 -0.0500 2.0344 +primID: 6 +startangle_c: 5 +endpose_c: 10 -20 5 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 45 +0.0000 0.0000 2.0344 +0.0057 -0.0114 2.0344 +0.0114 -0.0227 2.0344 +0.0170 -0.0341 2.0344 +0.0227 -0.0455 2.0344 +0.0284 -0.0568 2.0344 +0.0341 -0.0682 2.0344 +0.0398 -0.0795 2.0344 +0.0455 -0.0909 2.0344 +0.0511 -0.1023 2.0344 +0.0568 -0.1136 2.0344 +0.0625 -0.1250 2.0344 +0.0682 -0.1364 2.0344 +0.0739 -0.1477 2.0344 +0.0795 -0.1591 2.0344 +0.0852 -0.1705 2.0344 +0.0909 -0.1818 2.0344 +0.0966 -0.1932 2.0344 +0.1023 -0.2045 2.0344 +0.1080 -0.2159 2.0344 +0.1136 -0.2273 2.0344 +0.1193 -0.2386 2.0344 +0.1250 -0.2500 2.0344 +0.1307 -0.2614 2.0344 +0.1364 -0.2727 2.0344 +0.1420 -0.2841 2.0344 +0.1477 -0.2955 2.0344 +0.1534 -0.3068 2.0344 +0.1591 -0.3182 2.0344 +0.1648 -0.3295 2.0344 +0.1705 -0.3409 2.0344 +0.1761 -0.3523 2.0344 +0.1818 -0.3636 2.0344 +0.1875 -0.3750 2.0344 +0.1932 -0.3864 2.0344 +0.1989 -0.3977 2.0344 +0.2045 -0.4091 2.0344 +0.2102 -0.4205 2.0344 +0.2159 -0.4318 2.0344 +0.2216 -0.4432 2.0344 +0.2273 -0.4545 2.0344 +0.2330 -0.4659 2.0344 +0.2386 -0.4773 2.0344 +0.2443 -0.4886 2.0344 +0.2500 -0.5000 2.0344 +primID: 7 +startangle_c: 5 +endpose_c: 13 -18 6 +additionalactioncostmult: 3 +turning_radius: -1.7327 +intermediateposes: 45 +0.0000 0.0000 2.0344 +0.0057 -0.0113 2.0418 +0.0115 -0.0226 2.0491 +0.0174 -0.0338 2.0564 +0.0234 -0.0450 2.0637 +0.0294 -0.0561 2.0710 +0.0355 -0.0672 2.0783 +0.0417 -0.0782 2.0856 +0.0480 -0.0892 2.0929 +0.0544 -0.1002 2.1003 +0.0609 -0.1111 2.1076 +0.0674 -0.1219 2.1149 +0.0740 -0.1328 2.1222 +0.0807 -0.1435 2.1295 +0.0874 -0.1542 2.1368 +0.0943 -0.1649 2.1441 +0.1012 -0.1755 2.1514 +0.1082 -0.1861 2.1588 +0.1153 -0.1966 2.1661 +0.1224 -0.2070 2.1734 +0.1297 -0.2174 2.1807 +0.1370 -0.2278 2.1880 +0.1443 -0.2381 2.1953 +0.1518 -0.2483 2.2026 +0.1593 -0.2585 2.2099 +0.1669 -0.2687 2.2173 +0.1746 -0.2787 2.2246 +0.1824 -0.2888 2.2319 +0.1902 -0.2987 2.2392 +0.1981 -0.3086 2.2465 +0.2061 -0.3185 2.2538 +0.2141 -0.3283 2.2611 +0.2222 -0.3380 2.2684 +0.2304 -0.3477 2.2758 +0.2387 -0.3573 2.2831 +0.2470 -0.3668 2.2904 +0.2554 -0.3763 2.2977 +0.2638 -0.3858 2.3050 +0.2724 -0.3951 2.3123 +0.2810 -0.4044 2.3196 +0.2897 -0.4137 2.3269 +0.2984 -0.4229 2.3343 +0.3072 -0.4320 2.3416 +0.3161 -0.4410 2.3489 +0.3250 -0.4500 2.3562 +primID: 8 +startangle_c: 5 +endpose_c: 5 -21 4 +additionalactioncostmult: 3 +turning_radius: 1.1745 +intermediateposes: 44 +0.0000 0.0000 2.0344 +0.0056 -0.0114 2.0237 +0.0111 -0.0228 2.0129 +0.0165 -0.0342 2.0021 +0.0218 -0.0458 1.9913 +0.0269 -0.0573 1.9805 +0.0319 -0.0690 1.9697 +0.0368 -0.0807 1.9590 +0.0415 -0.0924 1.9482 +0.0462 -0.1042 1.9374 +0.0507 -0.1160 1.9266 +0.0550 -0.1279 1.9158 +0.0593 -0.1399 1.9051 +0.0634 -0.1518 1.8943 +0.0674 -0.1639 1.8835 +0.0712 -0.1759 1.8727 +0.0749 -0.1880 1.8619 +0.0785 -0.2002 1.8511 +0.0820 -0.2124 1.8404 +0.0853 -0.2246 1.8296 +0.0885 -0.2368 1.8188 +0.0916 -0.2491 1.8080 +0.0945 -0.2614 1.7972 +0.0973 -0.2738 1.7864 +0.1000 -0.2862 1.7757 +0.1025 -0.2986 1.7649 +0.1049 -0.3110 1.7541 +0.1072 -0.3235 1.7433 +0.1093 -0.3360 1.7325 +0.1113 -0.3485 1.7218 +0.1132 -0.3610 1.7110 +0.1149 -0.3735 1.7002 +0.1165 -0.3861 1.6894 +0.1179 -0.3987 1.6786 +0.1193 -0.4113 1.6678 +0.1204 -0.4239 1.6571 +0.1215 -0.4365 1.6463 +0.1224 -0.4491 1.6355 +0.1232 -0.4617 1.6247 +0.1238 -0.4744 1.6139 +0.1243 -0.4870 1.6031 +0.1247 -0.4997 1.5924 +0.1249 -0.5123 1.5816 +0.1250 -0.5250 1.5708 +primID: 9 +startangle_c: 5 +endpose_c: 0 0 4 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 9 +0.0000 0.0000 2.0344 +0.0000 0.0000 1.9765 +0.0000 0.0000 1.9185 +0.0000 0.0000 1.8606 +0.0000 0.0000 1.8026 +0.0000 0.0000 1.7447 +0.0000 0.0000 1.6867 +0.0000 0.0000 1.6288 +0.0000 0.0000 1.5708 +primID: 0 +startangle_c: 6 +endpose_c: -1 1 6 +additionalactioncostmult: 1 +turning_radius: 0.0000 +intermediateposes: 3 +0.0000 0.0000 2.3562 +-0.0125 0.0125 2.3562 +-0.0250 0.0250 2.3562 +primID: 1 +startangle_c: 6 +endpose_c: -15 15 6 +additionalactioncostmult: 1 +turning_radius: 0.0000 +intermediateposes: 43 +0.0000 0.0000 2.3562 +-0.0089 0.0089 2.3562 +-0.0179 0.0179 2.3562 +-0.0268 0.0268 2.3562 +-0.0357 0.0357 2.3562 +-0.0446 0.0446 2.3562 +-0.0536 0.0536 2.3562 +-0.0625 0.0625 2.3562 +-0.0714 0.0714 2.3562 +-0.0804 0.0804 2.3562 +-0.0893 0.0893 2.3562 +-0.0982 0.0982 2.3562 +-0.1071 0.1071 2.3562 +-0.1161 0.1161 2.3562 +-0.1250 0.1250 2.3562 +-0.1339 0.1339 2.3562 +-0.1429 0.1429 2.3562 +-0.1518 0.1518 2.3562 +-0.1607 0.1607 2.3562 +-0.1696 0.1696 2.3562 +-0.1786 0.1786 2.3562 +-0.1875 0.1875 2.3562 +-0.1964 0.1964 2.3562 +-0.2054 0.2054 2.3562 +-0.2143 0.2143 2.3562 +-0.2232 0.2232 2.3562 +-0.2321 0.2321 2.3562 +-0.2411 0.2411 2.3562 +-0.2500 0.2500 2.3562 +-0.2589 0.2589 2.3562 +-0.2679 0.2679 2.3562 +-0.2768 0.2768 2.3562 +-0.2857 0.2857 2.3562 +-0.2946 0.2946 2.3562 +-0.3036 0.3036 2.3562 +-0.3125 0.3125 2.3562 +-0.3214 0.3214 2.3562 +-0.3304 0.3304 2.3562 +-0.3393 0.3393 2.3562 +-0.3482 0.3482 2.3562 +-0.3571 0.3571 2.3562 +-0.3661 0.3661 2.3562 +-0.3750 0.3750 2.3562 +primID: 2 +startangle_c: 6 +endpose_c: -18 13 7 +additionalactioncostmult: 2 +turning_radius: 1.7327 +intermediateposes: 45 +0.0000 0.0000 2.3562 +-0.0090 0.0089 2.3635 +-0.0180 0.0178 2.3708 +-0.0271 0.0266 2.3781 +-0.0363 0.0353 2.3854 +-0.0456 0.0440 2.3928 +-0.0549 0.0526 2.4001 +-0.0642 0.0612 2.4074 +-0.0737 0.0696 2.4147 +-0.0832 0.0780 2.4220 +-0.0927 0.0863 2.4293 +-0.1023 0.0946 2.4366 +-0.1120 0.1028 2.4439 +-0.1217 0.1109 2.4513 +-0.1315 0.1189 2.4586 +-0.1414 0.1269 2.4659 +-0.1513 0.1348 2.4732 +-0.1612 0.1426 2.4805 +-0.1713 0.1504 2.4878 +-0.1813 0.1581 2.4951 +-0.1915 0.1657 2.5024 +-0.2017 0.1732 2.5098 +-0.2119 0.1807 2.5171 +-0.2222 0.1880 2.5244 +-0.2326 0.1953 2.5317 +-0.2430 0.2026 2.5390 +-0.2534 0.2097 2.5463 +-0.2639 0.2168 2.5536 +-0.2745 0.2238 2.5609 +-0.2851 0.2307 2.5683 +-0.2958 0.2376 2.5756 +-0.3065 0.2443 2.5829 +-0.3172 0.2510 2.5902 +-0.3281 0.2576 2.5975 +-0.3389 0.2641 2.6048 +-0.3498 0.2706 2.6121 +-0.3608 0.2770 2.6194 +-0.3718 0.2833 2.6268 +-0.3828 0.2895 2.6341 +-0.3939 0.2956 2.6414 +-0.4050 0.3016 2.6487 +-0.4162 0.3076 2.6560 +-0.4274 0.3135 2.6633 +-0.4387 0.3193 2.6706 +-0.4500 0.3250 2.6779 +primID: 3 +startangle_c: 6 +endpose_c: -13 18 5 +additionalactioncostmult: 2 +turning_radius: -1.7327 +intermediateposes: 45 +0.0000 0.0000 2.3562 +-0.0089 0.0090 2.3489 +-0.0178 0.0180 2.3416 +-0.0266 0.0271 2.3343 +-0.0353 0.0363 2.3269 +-0.0440 0.0456 2.3196 +-0.0526 0.0549 2.3123 +-0.0612 0.0642 2.3050 +-0.0696 0.0737 2.2977 +-0.0780 0.0832 2.2904 +-0.0863 0.0927 2.2831 +-0.0946 0.1023 2.2758 +-0.1028 0.1120 2.2684 +-0.1109 0.1217 2.2611 +-0.1189 0.1315 2.2538 +-0.1269 0.1414 2.2465 +-0.1348 0.1513 2.2392 +-0.1426 0.1612 2.2319 +-0.1504 0.1713 2.2246 +-0.1581 0.1813 2.2173 +-0.1657 0.1915 2.2099 +-0.1732 0.2017 2.2026 +-0.1807 0.2119 2.1953 +-0.1880 0.2222 2.1880 +-0.1953 0.2326 2.1807 +-0.2026 0.2430 2.1734 +-0.2097 0.2534 2.1661 +-0.2168 0.2639 2.1588 +-0.2238 0.2745 2.1514 +-0.2307 0.2851 2.1441 +-0.2376 0.2958 2.1368 +-0.2443 0.3065 2.1295 +-0.2510 0.3172 2.1222 +-0.2576 0.3281 2.1149 +-0.2641 0.3389 2.1076 +-0.2706 0.3498 2.1003 +-0.2770 0.3608 2.0929 +-0.2833 0.3718 2.0856 +-0.2895 0.3828 2.0783 +-0.2956 0.3939 2.0710 +-0.3016 0.4050 2.0637 +-0.3076 0.4162 2.0564 +-0.3135 0.4274 2.0491 +-0.3193 0.4387 2.0418 +-0.3250 0.4500 2.0344 +primID: 4 +startangle_c: 6 +endpose_c: 0 0 7 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 6 +0.0000 0.0000 2.3562 +0.0000 0.0000 2.4205 +0.0000 0.0000 2.4849 +0.0000 0.0000 2.5492 +0.0000 0.0000 2.6136 +0.0000 0.0000 2.6779 +primID: 5 +startangle_c: 6 +endpose_c: 1 -1 6 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 3 +0.0000 0.0000 2.3562 +0.0125 -0.0125 2.3562 +0.0250 -0.0250 2.3562 +primID: 6 +startangle_c: 6 +endpose_c: 16 -16 6 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 46 +0.0000 0.0000 2.3562 +0.0089 -0.0089 2.3562 +0.0178 -0.0178 2.3562 +0.0267 -0.0267 2.3562 +0.0356 -0.0356 2.3562 +0.0444 -0.0444 2.3562 +0.0533 -0.0533 2.3562 +0.0622 -0.0622 2.3562 +0.0711 -0.0711 2.3562 +0.0800 -0.0800 2.3562 +0.0889 -0.0889 2.3562 +0.0978 -0.0978 2.3562 +0.1067 -0.1067 2.3562 +0.1156 -0.1156 2.3562 +0.1244 -0.1244 2.3562 +0.1333 -0.1333 2.3562 +0.1422 -0.1422 2.3562 +0.1511 -0.1511 2.3562 +0.1600 -0.1600 2.3562 +0.1689 -0.1689 2.3562 +0.1778 -0.1778 2.3562 +0.1867 -0.1867 2.3562 +0.1956 -0.1956 2.3562 +0.2044 -0.2044 2.3562 +0.2133 -0.2133 2.3562 +0.2222 -0.2222 2.3562 +0.2311 -0.2311 2.3562 +0.2400 -0.2400 2.3562 +0.2489 -0.2489 2.3562 +0.2578 -0.2578 2.3562 +0.2667 -0.2667 2.3562 +0.2756 -0.2756 2.3562 +0.2844 -0.2844 2.3562 +0.2933 -0.2933 2.3562 +0.3022 -0.3022 2.3562 +0.3111 -0.3111 2.3562 +0.3200 -0.3200 2.3562 +0.3289 -0.3289 2.3562 +0.3378 -0.3378 2.3562 +0.3467 -0.3467 2.3562 +0.3556 -0.3556 2.3562 +0.3644 -0.3644 2.3562 +0.3733 -0.3733 2.3562 +0.3822 -0.3822 2.3562 +0.3911 -0.3911 2.3562 +0.4000 -0.4000 2.3562 +primID: 7 +startangle_c: 6 +endpose_c: 18 -13 7 +additionalactioncostmult: 3 +turning_radius: -1.7327 +intermediateposes: 45 +0.0000 0.0000 2.3562 +0.0090 -0.0089 2.3635 +0.0180 -0.0178 2.3708 +0.0271 -0.0266 2.3781 +0.0363 -0.0353 2.3854 +0.0456 -0.0440 2.3928 +0.0549 -0.0526 2.4001 +0.0642 -0.0612 2.4074 +0.0737 -0.0696 2.4147 +0.0832 -0.0780 2.4220 +0.0927 -0.0863 2.4293 +0.1023 -0.0946 2.4366 +0.1120 -0.1028 2.4439 +0.1217 -0.1109 2.4513 +0.1315 -0.1189 2.4586 +0.1414 -0.1269 2.4659 +0.1513 -0.1348 2.4732 +0.1612 -0.1426 2.4805 +0.1713 -0.1504 2.4878 +0.1813 -0.1581 2.4951 +0.1915 -0.1657 2.5024 +0.2017 -0.1732 2.5098 +0.2119 -0.1807 2.5171 +0.2222 -0.1880 2.5244 +0.2326 -0.1953 2.5317 +0.2430 -0.2026 2.5390 +0.2534 -0.2097 2.5463 +0.2639 -0.2168 2.5536 +0.2745 -0.2238 2.5609 +0.2851 -0.2307 2.5683 +0.2958 -0.2376 2.5756 +0.3065 -0.2443 2.5829 +0.3172 -0.2510 2.5902 +0.3281 -0.2576 2.5975 +0.3389 -0.2641 2.6048 +0.3498 -0.2706 2.6121 +0.3608 -0.2770 2.6194 +0.3718 -0.2833 2.6268 +0.3828 -0.2895 2.6341 +0.3939 -0.2956 2.6414 +0.4050 -0.3016 2.6487 +0.4162 -0.3076 2.6560 +0.4274 -0.3135 2.6633 +0.4387 -0.3193 2.6706 +0.4500 -0.3250 2.6779 +primID: 8 +startangle_c: 6 +endpose_c: 13 -18 5 +additionalactioncostmult: 3 +turning_radius: 1.7327 +intermediateposes: 45 +0.0000 0.0000 2.3562 +0.0089 -0.0090 2.3489 +0.0178 -0.0180 2.3416 +0.0266 -0.0271 2.3343 +0.0353 -0.0363 2.3269 +0.0440 -0.0456 2.3196 +0.0526 -0.0549 2.3123 +0.0612 -0.0642 2.3050 +0.0696 -0.0737 2.2977 +0.0780 -0.0832 2.2904 +0.0863 -0.0927 2.2831 +0.0946 -0.1023 2.2758 +0.1028 -0.1120 2.2684 +0.1109 -0.1217 2.2611 +0.1189 -0.1315 2.2538 +0.1269 -0.1414 2.2465 +0.1348 -0.1513 2.2392 +0.1426 -0.1612 2.2319 +0.1504 -0.1713 2.2246 +0.1581 -0.1813 2.2173 +0.1657 -0.1915 2.2099 +0.1732 -0.2017 2.2026 +0.1807 -0.2119 2.1953 +0.1880 -0.2222 2.1880 +0.1953 -0.2326 2.1807 +0.2026 -0.2430 2.1734 +0.2097 -0.2534 2.1661 +0.2168 -0.2639 2.1588 +0.2238 -0.2745 2.1514 +0.2307 -0.2851 2.1441 +0.2376 -0.2958 2.1368 +0.2443 -0.3065 2.1295 +0.2510 -0.3172 2.1222 +0.2576 -0.3281 2.1149 +0.2641 -0.3389 2.1076 +0.2706 -0.3498 2.1003 +0.2770 -0.3608 2.0929 +0.2833 -0.3718 2.0856 +0.2895 -0.3828 2.0783 +0.2956 -0.3939 2.0710 +0.3016 -0.4050 2.0637 +0.3076 -0.4162 2.0564 +0.3135 -0.4274 2.0491 +0.3193 -0.4387 2.0418 +0.3250 -0.4500 2.0344 +primID: 9 +startangle_c: 6 +endpose_c: 0 0 5 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 6 +0.0000 0.0000 2.3562 +0.0000 0.0000 2.2918 +0.0000 0.0000 2.2275 +0.0000 0.0000 2.1631 +0.0000 0.0000 2.0988 +0.0000 0.0000 2.0344 +primID: 0 +startangle_c: 7 +endpose_c: -2 1 7 +additionalactioncostmult: 1 +turning_radius: -0.0000 +intermediateposes: 5 +0.0000 0.0000 2.6779 +-0.0125 0.0063 2.6779 +-0.0250 0.0125 2.6779 +-0.0375 0.0188 2.6779 +-0.0500 0.0250 2.6779 +primID: 1 +startangle_c: 7 +endpose_c: -20 10 7 +additionalactioncostmult: 1 +turning_radius: -0.0000 +intermediateposes: 45 +0.0000 0.0000 2.6779 +-0.0114 0.0057 2.6779 +-0.0227 0.0114 2.6779 +-0.0341 0.0170 2.6779 +-0.0455 0.0227 2.6779 +-0.0568 0.0284 2.6779 +-0.0682 0.0341 2.6779 +-0.0795 0.0398 2.6779 +-0.0909 0.0455 2.6779 +-0.1023 0.0511 2.6779 +-0.1136 0.0568 2.6779 +-0.1250 0.0625 2.6779 +-0.1364 0.0682 2.6779 +-0.1477 0.0739 2.6779 +-0.1591 0.0795 2.6779 +-0.1705 0.0852 2.6779 +-0.1818 0.0909 2.6779 +-0.1932 0.0966 2.6779 +-0.2045 0.1023 2.6779 +-0.2159 0.1080 2.6779 +-0.2273 0.1136 2.6779 +-0.2386 0.1193 2.6779 +-0.2500 0.1250 2.6779 +-0.2614 0.1307 2.6779 +-0.2727 0.1364 2.6779 +-0.2841 0.1420 2.6779 +-0.2955 0.1477 2.6779 +-0.3068 0.1534 2.6779 +-0.3182 0.1591 2.6779 +-0.3295 0.1648 2.6779 +-0.3409 0.1705 2.6779 +-0.3523 0.1761 2.6779 +-0.3636 0.1818 2.6779 +-0.3750 0.1875 2.6779 +-0.3864 0.1932 2.6779 +-0.3977 0.1989 2.6779 +-0.4091 0.2045 2.6779 +-0.4205 0.2102 2.6779 +-0.4318 0.2159 2.6779 +-0.4432 0.2216 2.6779 +-0.4545 0.2273 2.6779 +-0.4659 0.2330 2.6779 +-0.4773 0.2386 2.6779 +-0.4886 0.2443 2.6779 +-0.5000 0.2500 2.6779 +primID: 2 +startangle_c: 7 +endpose_c: -18 13 6 +additionalactioncostmult: 2 +turning_radius: -1.7327 +intermediateposes: 45 +0.0000 0.0000 2.6779 +-0.0113 0.0057 2.6706 +-0.0226 0.0115 2.6633 +-0.0338 0.0174 2.6560 +-0.0450 0.0234 2.6487 +-0.0561 0.0294 2.6414 +-0.0672 0.0355 2.6341 +-0.0782 0.0417 2.6268 +-0.0892 0.0480 2.6194 +-0.1002 0.0544 2.6121 +-0.1111 0.0609 2.6048 +-0.1219 0.0674 2.5975 +-0.1328 0.0740 2.5902 +-0.1435 0.0807 2.5829 +-0.1542 0.0874 2.5756 +-0.1649 0.0943 2.5683 +-0.1755 0.1012 2.5609 +-0.1861 0.1082 2.5536 +-0.1966 0.1153 2.5463 +-0.2070 0.1224 2.5390 +-0.2174 0.1297 2.5317 +-0.2278 0.1370 2.5244 +-0.2381 0.1443 2.5171 +-0.2483 0.1518 2.5098 +-0.2585 0.1593 2.5024 +-0.2687 0.1669 2.4951 +-0.2787 0.1746 2.4878 +-0.2888 0.1824 2.4805 +-0.2987 0.1902 2.4732 +-0.3086 0.1981 2.4659 +-0.3185 0.2061 2.4586 +-0.3283 0.2141 2.4513 +-0.3380 0.2222 2.4439 +-0.3477 0.2304 2.4366 +-0.3573 0.2387 2.4293 +-0.3668 0.2470 2.4220 +-0.3763 0.2554 2.4147 +-0.3858 0.2638 2.4074 +-0.3951 0.2724 2.4001 +-0.4044 0.2810 2.3928 +-0.4137 0.2897 2.3854 +-0.4229 0.2984 2.3781 +-0.4320 0.3072 2.3708 +-0.4410 0.3161 2.3635 +-0.4500 0.3250 2.3562 +primID: 3 +startangle_c: 7 +endpose_c: -21 5 8 +additionalactioncostmult: 2 +turning_radius: 1.1745 +intermediateposes: 44 +0.0000 0.0000 2.6779 +-0.0114 0.0056 2.6887 +-0.0228 0.0111 2.6995 +-0.0342 0.0165 2.7103 +-0.0458 0.0218 2.7211 +-0.0573 0.0269 2.7319 +-0.0690 0.0319 2.7426 +-0.0807 0.0368 2.7534 +-0.0924 0.0415 2.7642 +-0.1042 0.0462 2.7750 +-0.1160 0.0507 2.7858 +-0.1279 0.0550 2.7966 +-0.1399 0.0593 2.8073 +-0.1518 0.0634 2.8181 +-0.1639 0.0674 2.8289 +-0.1759 0.0712 2.8397 +-0.1880 0.0749 2.8505 +-0.2002 0.0785 2.8612 +-0.2124 0.0820 2.8720 +-0.2246 0.0853 2.8828 +-0.2368 0.0885 2.8936 +-0.2491 0.0916 2.9044 +-0.2614 0.0945 2.9152 +-0.2738 0.0973 2.9259 +-0.2862 0.1000 2.9367 +-0.2986 0.1025 2.9475 +-0.3110 0.1049 2.9583 +-0.3235 0.1072 2.9691 +-0.3360 0.1093 2.9799 +-0.3485 0.1113 2.9906 +-0.3610 0.1132 3.0014 +-0.3735 0.1149 3.0122 +-0.3861 0.1165 3.0230 +-0.3987 0.1179 3.0338 +-0.4113 0.1193 3.0446 +-0.4239 0.1204 3.0553 +-0.4365 0.1215 3.0661 +-0.4491 0.1224 3.0769 +-0.4617 0.1232 3.0877 +-0.4744 0.1238 3.0985 +-0.4870 0.1243 3.1092 +-0.4997 0.1247 3.1200 +-0.5123 0.1249 3.1308 +-0.5250 0.1250 3.1416 +primID: 4 +startangle_c: 7 +endpose_c: 0 0 6 +additionalactioncostmult: 5 +turning_radius: -0.0000 +intermediateposes: 6 +0.0000 0.0000 2.6779 +0.0000 0.0000 2.6136 +0.0000 0.0000 2.5492 +0.0000 0.0000 2.4849 +0.0000 0.0000 2.4205 +0.0000 0.0000 2.3562 +primID: 5 +startangle_c: 7 +endpose_c: 2 -1 7 +additionalactioncostmult: 5 +turning_radius: -0.0000 +intermediateposes: 5 +0.0000 0.0000 2.6779 +0.0125 -0.0063 2.6779 +0.0250 -0.0125 2.6779 +0.0375 -0.0188 2.6779 +0.0500 -0.0250 2.6779 +primID: 6 +startangle_c: 7 +endpose_c: 20 -10 7 +additionalactioncostmult: 5 +turning_radius: -0.0000 +intermediateposes: 45 +0.0000 0.0000 2.6779 +0.0114 -0.0057 2.6779 +0.0227 -0.0114 2.6779 +0.0341 -0.0170 2.6779 +0.0455 -0.0227 2.6779 +0.0568 -0.0284 2.6779 +0.0682 -0.0341 2.6779 +0.0795 -0.0398 2.6779 +0.0909 -0.0455 2.6779 +0.1023 -0.0511 2.6779 +0.1136 -0.0568 2.6779 +0.1250 -0.0625 2.6779 +0.1364 -0.0682 2.6779 +0.1477 -0.0739 2.6779 +0.1591 -0.0795 2.6779 +0.1705 -0.0852 2.6779 +0.1818 -0.0909 2.6779 +0.1932 -0.0966 2.6779 +0.2045 -0.1023 2.6779 +0.2159 -0.1080 2.6779 +0.2273 -0.1136 2.6779 +0.2386 -0.1193 2.6779 +0.2500 -0.1250 2.6779 +0.2614 -0.1307 2.6779 +0.2727 -0.1364 2.6779 +0.2841 -0.1420 2.6779 +0.2955 -0.1477 2.6779 +0.3068 -0.1534 2.6779 +0.3182 -0.1591 2.6779 +0.3295 -0.1648 2.6779 +0.3409 -0.1705 2.6779 +0.3523 -0.1761 2.6779 +0.3636 -0.1818 2.6779 +0.3750 -0.1875 2.6779 +0.3864 -0.1932 2.6779 +0.3977 -0.1989 2.6779 +0.4091 -0.2045 2.6779 +0.4205 -0.2102 2.6779 +0.4318 -0.2159 2.6779 +0.4432 -0.2216 2.6779 +0.4545 -0.2273 2.6779 +0.4659 -0.2330 2.6779 +0.4773 -0.2386 2.6779 +0.4886 -0.2443 2.6779 +0.5000 -0.2500 2.6779 +primID: 7 +startangle_c: 7 +endpose_c: 18 -13 6 +additionalactioncostmult: 3 +turning_radius: 1.7327 +intermediateposes: 45 +0.0000 0.0000 2.6779 +0.0113 -0.0057 2.6706 +0.0226 -0.0115 2.6633 +0.0338 -0.0174 2.6560 +0.0450 -0.0234 2.6487 +0.0561 -0.0294 2.6414 +0.0672 -0.0355 2.6341 +0.0782 -0.0417 2.6268 +0.0892 -0.0480 2.6194 +0.1002 -0.0544 2.6121 +0.1111 -0.0609 2.6048 +0.1219 -0.0674 2.5975 +0.1328 -0.0740 2.5902 +0.1435 -0.0807 2.5829 +0.1542 -0.0874 2.5756 +0.1649 -0.0943 2.5683 +0.1755 -0.1012 2.5609 +0.1861 -0.1082 2.5536 +0.1966 -0.1153 2.5463 +0.2070 -0.1224 2.5390 +0.2174 -0.1297 2.5317 +0.2278 -0.1370 2.5244 +0.2381 -0.1443 2.5171 +0.2483 -0.1518 2.5098 +0.2585 -0.1593 2.5024 +0.2687 -0.1669 2.4951 +0.2787 -0.1746 2.4878 +0.2888 -0.1824 2.4805 +0.2987 -0.1902 2.4732 +0.3086 -0.1981 2.4659 +0.3185 -0.2061 2.4586 +0.3283 -0.2141 2.4513 +0.3380 -0.2222 2.4439 +0.3477 -0.2304 2.4366 +0.3573 -0.2387 2.4293 +0.3668 -0.2470 2.4220 +0.3763 -0.2554 2.4147 +0.3858 -0.2638 2.4074 +0.3951 -0.2724 2.4001 +0.4044 -0.2810 2.3928 +0.4137 -0.2897 2.3854 +0.4229 -0.2984 2.3781 +0.4320 -0.3072 2.3708 +0.4410 -0.3161 2.3635 +0.4500 -0.3250 2.3562 +primID: 8 +startangle_c: 7 +endpose_c: 21 -5 8 +additionalactioncostmult: 3 +turning_radius: -1.1745 +intermediateposes: 44 +0.0000 0.0000 2.6779 +0.0114 -0.0056 2.6887 +0.0228 -0.0111 2.6995 +0.0342 -0.0165 2.7103 +0.0458 -0.0218 2.7211 +0.0573 -0.0269 2.7319 +0.0690 -0.0319 2.7426 +0.0807 -0.0368 2.7534 +0.0924 -0.0415 2.7642 +0.1042 -0.0462 2.7750 +0.1160 -0.0507 2.7858 +0.1279 -0.0550 2.7966 +0.1399 -0.0593 2.8073 +0.1518 -0.0634 2.8181 +0.1639 -0.0674 2.8289 +0.1759 -0.0712 2.8397 +0.1880 -0.0749 2.8505 +0.2002 -0.0785 2.8612 +0.2124 -0.0820 2.8720 +0.2246 -0.0853 2.8828 +0.2368 -0.0885 2.8936 +0.2491 -0.0916 2.9044 +0.2614 -0.0945 2.9152 +0.2738 -0.0973 2.9259 +0.2862 -0.1000 2.9367 +0.2986 -0.1025 2.9475 +0.3110 -0.1049 2.9583 +0.3235 -0.1072 2.9691 +0.3360 -0.1093 2.9799 +0.3485 -0.1113 2.9906 +0.3610 -0.1132 3.0014 +0.3735 -0.1149 3.0122 +0.3861 -0.1165 3.0230 +0.3987 -0.1179 3.0338 +0.4113 -0.1193 3.0446 +0.4239 -0.1204 3.0553 +0.4365 -0.1215 3.0661 +0.4491 -0.1224 3.0769 +0.4617 -0.1232 3.0877 +0.4744 -0.1238 3.0985 +0.4870 -0.1243 3.1092 +0.4997 -0.1247 3.1200 +0.5123 -0.1249 3.1308 +0.5250 -0.1250 3.1416 +primID: 9 +startangle_c: 7 +endpose_c: 0 0 8 +additionalactioncostmult: 5 +turning_radius: -0.0000 +intermediateposes: 9 +0.0000 0.0000 2.6779 +0.0000 0.0000 2.7359 +0.0000 0.0000 2.7939 +0.0000 0.0000 2.8518 +0.0000 0.0000 2.9098 +0.0000 0.0000 2.9677 +0.0000 0.0000 3.0257 +0.0000 0.0000 3.0836 +0.0000 0.0000 3.1416 +primID: 0 +startangle_c: 8 +endpose_c: -1 0 8 +additionalactioncostmult: 1 +turning_radius: 0.0000 +intermediateposes: 3 +0.0000 0.0000 3.1416 +-0.0125 0.0000 3.1416 +-0.0250 0.0000 3.1416 +primID: 1 +startangle_c: 8 +endpose_c: -21 0 8 +additionalactioncostmult: 1 +turning_radius: 0.0000 +intermediateposes: 43 +0.0000 0.0000 3.1416 +-0.0125 0.0000 3.1416 +-0.0250 0.0000 3.1416 +-0.0375 0.0000 3.1416 +-0.0500 0.0000 3.1416 +-0.0625 0.0000 3.1416 +-0.0750 0.0000 3.1416 +-0.0875 0.0000 3.1416 +-0.1000 0.0000 3.1416 +-0.1125 0.0000 3.1416 +-0.1250 0.0000 3.1416 +-0.1375 0.0000 3.1416 +-0.1500 0.0000 3.1416 +-0.1625 0.0000 3.1416 +-0.1750 0.0000 3.1416 +-0.1875 0.0000 3.1416 +-0.2000 0.0000 3.1416 +-0.2125 0.0000 3.1416 +-0.2250 0.0000 3.1416 +-0.2375 0.0000 3.1416 +-0.2500 0.0000 3.1416 +-0.2625 0.0000 3.1416 +-0.2750 0.0000 3.1416 +-0.2875 0.0000 3.1416 +-0.3000 0.0000 3.1416 +-0.3125 0.0000 3.1416 +-0.3250 0.0000 3.1416 +-0.3375 0.0000 3.1416 +-0.3500 0.0000 3.1416 +-0.3625 0.0000 3.1416 +-0.3750 0.0000 3.1416 +-0.3875 0.0000 3.1416 +-0.4000 0.0000 3.1416 +-0.4125 0.0000 3.1416 +-0.4250 0.0000 3.1416 +-0.4375 0.0000 3.1416 +-0.4500 0.0000 3.1416 +-0.4625 0.0000 3.1416 +-0.4750 0.0000 3.1416 +-0.4875 0.0000 3.1416 +-0.5000 0.0000 3.1416 +-0.5125 0.0000 3.1416 +-0.5250 0.0000 3.1416 +primID: 2 +startangle_c: 8 +endpose_c: -21 -5 9 +additionalactioncostmult: 2 +turning_radius: 1.1745 +intermediateposes: 44 +0.0000 0.0000 3.1416 +-0.0127 -0.0001 3.1524 +-0.0253 -0.0003 3.1632 +-0.0380 -0.0007 3.1739 +-0.0506 -0.0012 3.1847 +-0.0633 -0.0018 3.1955 +-0.0759 -0.0026 3.2063 +-0.0885 -0.0035 3.2171 +-0.1011 -0.0046 3.2279 +-0.1137 -0.0057 3.2386 +-0.1263 -0.0071 3.2494 +-0.1389 -0.0085 3.2602 +-0.1515 -0.0101 3.2710 +-0.1640 -0.0118 3.2818 +-0.1765 -0.0137 3.2925 +-0.1890 -0.0157 3.3033 +-0.2015 -0.0178 3.3141 +-0.2140 -0.0201 3.3249 +-0.2264 -0.0225 3.3357 +-0.2388 -0.0250 3.3465 +-0.2512 -0.0277 3.3572 +-0.2636 -0.0305 3.3680 +-0.2759 -0.0334 3.3788 +-0.2882 -0.0365 3.3896 +-0.3004 -0.0397 3.4004 +-0.3126 -0.0430 3.4112 +-0.3248 -0.0465 3.4219 +-0.3370 -0.0501 3.4327 +-0.3491 -0.0538 3.4435 +-0.3611 -0.0576 3.4543 +-0.3732 -0.0616 3.4651 +-0.3851 -0.0657 3.4759 +-0.3971 -0.0700 3.4866 +-0.4090 -0.0743 3.4974 +-0.4208 -0.0788 3.5082 +-0.4326 -0.0835 3.5190 +-0.4443 -0.0882 3.5298 +-0.4560 -0.0931 3.5405 +-0.4677 -0.0981 3.5513 +-0.4792 -0.1032 3.5621 +-0.4908 -0.1085 3.5729 +-0.5022 -0.1139 3.5837 +-0.5136 -0.1194 3.5945 +-0.5250 -0.1250 3.6052 +primID: 3 +startangle_c: 8 +endpose_c: -21 5 7 +additionalactioncostmult: 2 +turning_radius: -1.1745 +intermediateposes: 44 +0.0000 0.0000 3.1416 +-0.0127 0.0001 3.1308 +-0.0253 0.0003 3.1200 +-0.0380 0.0007 3.1092 +-0.0506 0.0012 3.0985 +-0.0633 0.0018 3.0877 +-0.0759 0.0026 3.0769 +-0.0885 0.0035 3.0661 +-0.1011 0.0046 3.0553 +-0.1137 0.0057 3.0446 +-0.1263 0.0071 3.0338 +-0.1389 0.0085 3.0230 +-0.1515 0.0101 3.0122 +-0.1640 0.0118 3.0014 +-0.1765 0.0137 2.9906 +-0.1890 0.0157 2.9799 +-0.2015 0.0178 2.9691 +-0.2140 0.0201 2.9583 +-0.2264 0.0225 2.9475 +-0.2388 0.0250 2.9367 +-0.2512 0.0277 2.9259 +-0.2636 0.0305 2.9152 +-0.2759 0.0334 2.9044 +-0.2882 0.0365 2.8936 +-0.3004 0.0397 2.8828 +-0.3126 0.0430 2.8720 +-0.3248 0.0465 2.8612 +-0.3370 0.0501 2.8505 +-0.3491 0.0538 2.8397 +-0.3611 0.0576 2.8289 +-0.3732 0.0616 2.8181 +-0.3851 0.0657 2.8073 +-0.3971 0.0700 2.7966 +-0.4090 0.0743 2.7858 +-0.4208 0.0788 2.7750 +-0.4326 0.0835 2.7642 +-0.4443 0.0882 2.7534 +-0.4560 0.0931 2.7426 +-0.4677 0.0981 2.7319 +-0.4792 0.1032 2.7211 +-0.4908 0.1085 2.7103 +-0.5022 0.1139 2.6995 +-0.5136 0.1194 2.6887 +-0.5250 0.1250 2.6779 +primID: 4 +startangle_c: 8 +endpose_c: 0 0 9 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 9 +0.0000 0.0000 3.1416 +0.0000 0.0000 3.1995 +0.0000 0.0000 3.2575 +0.0000 0.0000 3.3155 +0.0000 0.0000 3.3734 +0.0000 0.0000 3.4314 +0.0000 0.0000 3.4893 +0.0000 0.0000 3.5473 +0.0000 0.0000 3.6052 +primID: 5 +startangle_c: 8 +endpose_c: 1 0 8 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 3 +0.0000 0.0000 3.1416 +0.0125 0.0000 3.1416 +0.0250 0.0000 3.1416 +primID: 6 +startangle_c: 8 +endpose_c: 21 0 8 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 43 +0.0000 0.0000 3.1416 +0.0125 0.0000 3.1416 +0.0250 0.0000 3.1416 +0.0375 0.0000 3.1416 +0.0500 0.0000 3.1416 +0.0625 0.0000 3.1416 +0.0750 0.0000 3.1416 +0.0875 0.0000 3.1416 +0.1000 0.0000 3.1416 +0.1125 0.0000 3.1416 +0.1250 0.0000 3.1416 +0.1375 0.0000 3.1416 +0.1500 0.0000 3.1416 +0.1625 0.0000 3.1416 +0.1750 0.0000 3.1416 +0.1875 0.0000 3.1416 +0.2000 0.0000 3.1416 +0.2125 0.0000 3.1416 +0.2250 0.0000 3.1416 +0.2375 0.0000 3.1416 +0.2500 0.0000 3.1416 +0.2625 0.0000 3.1416 +0.2750 0.0000 3.1416 +0.2875 0.0000 3.1416 +0.3000 0.0000 3.1416 +0.3125 0.0000 3.1416 +0.3250 0.0000 3.1416 +0.3375 0.0000 3.1416 +0.3500 0.0000 3.1416 +0.3625 0.0000 3.1416 +0.3750 0.0000 3.1416 +0.3875 0.0000 3.1416 +0.4000 0.0000 3.1416 +0.4125 0.0000 3.1416 +0.4250 0.0000 3.1416 +0.4375 0.0000 3.1416 +0.4500 0.0000 3.1416 +0.4625 0.0000 3.1416 +0.4750 0.0000 3.1416 +0.4875 0.0000 3.1416 +0.5000 0.0000 3.1416 +0.5125 0.0000 3.1416 +0.5250 0.0000 3.1416 +primID: 7 +startangle_c: 8 +endpose_c: 21 5 9 +additionalactioncostmult: 3 +turning_radius: -1.1745 +intermediateposes: 44 +0.0000 0.0000 3.1416 +0.0127 0.0001 3.1524 +0.0253 0.0003 3.1632 +0.0380 0.0007 3.1739 +0.0506 0.0012 3.1847 +0.0633 0.0018 3.1955 +0.0759 0.0026 3.2063 +0.0885 0.0035 3.2171 +0.1011 0.0046 3.2279 +0.1137 0.0057 3.2386 +0.1263 0.0071 3.2494 +0.1389 0.0085 3.2602 +0.1515 0.0101 3.2710 +0.1640 0.0118 3.2818 +0.1765 0.0137 3.2925 +0.1890 0.0157 3.3033 +0.2015 0.0178 3.3141 +0.2140 0.0201 3.3249 +0.2264 0.0225 3.3357 +0.2388 0.0250 3.3465 +0.2512 0.0277 3.3572 +0.2636 0.0305 3.3680 +0.2759 0.0334 3.3788 +0.2882 0.0365 3.3896 +0.3004 0.0397 3.4004 +0.3126 0.0430 3.4112 +0.3248 0.0465 3.4219 +0.3370 0.0501 3.4327 +0.3491 0.0538 3.4435 +0.3611 0.0576 3.4543 +0.3732 0.0616 3.4651 +0.3851 0.0657 3.4759 +0.3971 0.0700 3.4866 +0.4090 0.0743 3.4974 +0.4208 0.0788 3.5082 +0.4326 0.0835 3.5190 +0.4443 0.0882 3.5298 +0.4560 0.0931 3.5405 +0.4677 0.0981 3.5513 +0.4792 0.1032 3.5621 +0.4908 0.1085 3.5729 +0.5022 0.1139 3.5837 +0.5136 0.1194 3.5945 +0.5250 0.1250 3.6052 +primID: 8 +startangle_c: 8 +endpose_c: 21 -5 7 +additionalactioncostmult: 3 +turning_radius: 1.1745 +intermediateposes: 44 +0.0000 0.0000 3.1416 +0.0127 -0.0001 3.1308 +0.0253 -0.0003 3.1200 +0.0380 -0.0007 3.1092 +0.0506 -0.0012 3.0985 +0.0633 -0.0018 3.0877 +0.0759 -0.0026 3.0769 +0.0885 -0.0035 3.0661 +0.1011 -0.0046 3.0553 +0.1137 -0.0057 3.0446 +0.1263 -0.0071 3.0338 +0.1389 -0.0085 3.0230 +0.1515 -0.0101 3.0122 +0.1640 -0.0118 3.0014 +0.1765 -0.0137 2.9906 +0.1890 -0.0157 2.9799 +0.2015 -0.0178 2.9691 +0.2140 -0.0201 2.9583 +0.2264 -0.0225 2.9475 +0.2388 -0.0250 2.9367 +0.2512 -0.0277 2.9259 +0.2636 -0.0305 2.9152 +0.2759 -0.0334 2.9044 +0.2882 -0.0365 2.8936 +0.3004 -0.0397 2.8828 +0.3126 -0.0430 2.8720 +0.3248 -0.0465 2.8612 +0.3370 -0.0501 2.8505 +0.3491 -0.0538 2.8397 +0.3611 -0.0576 2.8289 +0.3732 -0.0616 2.8181 +0.3851 -0.0657 2.8073 +0.3971 -0.0700 2.7966 +0.4090 -0.0743 2.7858 +0.4208 -0.0788 2.7750 +0.4326 -0.0835 2.7642 +0.4443 -0.0882 2.7534 +0.4560 -0.0931 2.7426 +0.4677 -0.0981 2.7319 +0.4792 -0.1032 2.7211 +0.4908 -0.1085 2.7103 +0.5022 -0.1139 2.6995 +0.5136 -0.1194 2.6887 +0.5250 -0.1250 2.6779 +primID: 9 +startangle_c: 8 +endpose_c: 0 0 7 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 9 +0.0000 0.0000 3.1416 +0.0000 0.0000 3.0836 +0.0000 0.0000 3.0257 +0.0000 0.0000 2.9677 +0.0000 0.0000 2.9098 +0.0000 0.0000 2.8518 +0.0000 0.0000 2.7939 +0.0000 0.0000 2.7359 +0.0000 0.0000 2.6779 +primID: 0 +startangle_c: 9 +endpose_c: -2 -1 9 +additionalactioncostmult: 1 +turning_radius: 0.0000 +intermediateposes: 5 +0.0000 0.0000 3.6052 +-0.0125 -0.0063 3.6052 +-0.0250 -0.0125 3.6052 +-0.0375 -0.0188 3.6052 +-0.0500 -0.0250 3.6052 +primID: 1 +startangle_c: 9 +endpose_c: -20 -10 9 +additionalactioncostmult: 1 +turning_radius: 0.0000 +intermediateposes: 45 +0.0000 0.0000 3.6052 +-0.0114 -0.0057 3.6052 +-0.0227 -0.0114 3.6052 +-0.0341 -0.0170 3.6052 +-0.0455 -0.0227 3.6052 +-0.0568 -0.0284 3.6052 +-0.0682 -0.0341 3.6052 +-0.0795 -0.0398 3.6052 +-0.0909 -0.0455 3.6052 +-0.1023 -0.0511 3.6052 +-0.1136 -0.0568 3.6052 +-0.1250 -0.0625 3.6052 +-0.1364 -0.0682 3.6052 +-0.1477 -0.0739 3.6052 +-0.1591 -0.0795 3.6052 +-0.1705 -0.0852 3.6052 +-0.1818 -0.0909 3.6052 +-0.1932 -0.0966 3.6052 +-0.2045 -0.1023 3.6052 +-0.2159 -0.1080 3.6052 +-0.2273 -0.1136 3.6052 +-0.2386 -0.1193 3.6052 +-0.2500 -0.1250 3.6052 +-0.2614 -0.1307 3.6052 +-0.2727 -0.1364 3.6052 +-0.2841 -0.1420 3.6052 +-0.2955 -0.1477 3.6052 +-0.3068 -0.1534 3.6052 +-0.3182 -0.1591 3.6052 +-0.3295 -0.1648 3.6052 +-0.3409 -0.1705 3.6052 +-0.3523 -0.1761 3.6052 +-0.3636 -0.1818 3.6052 +-0.3750 -0.1875 3.6052 +-0.3864 -0.1932 3.6052 +-0.3977 -0.1989 3.6052 +-0.4091 -0.2045 3.6052 +-0.4205 -0.2102 3.6052 +-0.4318 -0.2159 3.6052 +-0.4432 -0.2216 3.6052 +-0.4545 -0.2273 3.6052 +-0.4659 -0.2330 3.6052 +-0.4773 -0.2386 3.6052 +-0.4886 -0.2443 3.6052 +-0.5000 -0.2500 3.6052 +primID: 2 +startangle_c: 9 +endpose_c: -18 -13 10 +additionalactioncostmult: 2 +turning_radius: 1.7327 +intermediateposes: 45 +0.0000 0.0000 3.6052 +-0.0113 -0.0057 3.6126 +-0.0226 -0.0115 3.6199 +-0.0338 -0.0174 3.6272 +-0.0450 -0.0234 3.6345 +-0.0561 -0.0294 3.6418 +-0.0672 -0.0355 3.6491 +-0.0782 -0.0417 3.6564 +-0.0892 -0.0480 3.6637 +-0.1002 -0.0544 3.6711 +-0.1111 -0.0609 3.6784 +-0.1219 -0.0674 3.6857 +-0.1328 -0.0740 3.6930 +-0.1435 -0.0807 3.7003 +-0.1542 -0.0874 3.7076 +-0.1649 -0.0943 3.7149 +-0.1755 -0.1012 3.7222 +-0.1861 -0.1082 3.7296 +-0.1966 -0.1153 3.7369 +-0.2070 -0.1224 3.7442 +-0.2174 -0.1297 3.7515 +-0.2278 -0.1370 3.7588 +-0.2381 -0.1443 3.7661 +-0.2483 -0.1518 3.7734 +-0.2585 -0.1593 3.7807 +-0.2687 -0.1669 3.7881 +-0.2787 -0.1746 3.7954 +-0.2888 -0.1824 3.8027 +-0.2987 -0.1902 3.8100 +-0.3086 -0.1981 3.8173 +-0.3185 -0.2061 3.8246 +-0.3283 -0.2141 3.8319 +-0.3380 -0.2222 3.8392 +-0.3477 -0.2304 3.8466 +-0.3573 -0.2387 3.8539 +-0.3668 -0.2470 3.8612 +-0.3763 -0.2554 3.8685 +-0.3858 -0.2638 3.8758 +-0.3951 -0.2724 3.8831 +-0.4044 -0.2810 3.8904 +-0.4137 -0.2897 3.8977 +-0.4229 -0.2984 3.9051 +-0.4320 -0.3072 3.9124 +-0.4410 -0.3161 3.9197 +-0.4500 -0.3250 3.9270 +primID: 3 +startangle_c: 9 +endpose_c: -21 -5 8 +additionalactioncostmult: 2 +turning_radius: -1.1745 +intermediateposes: 44 +0.0000 0.0000 3.6052 +-0.0114 -0.0056 3.5945 +-0.0228 -0.0111 3.5837 +-0.0342 -0.0165 3.5729 +-0.0458 -0.0218 3.5621 +-0.0573 -0.0269 3.5513 +-0.0690 -0.0319 3.5405 +-0.0807 -0.0368 3.5298 +-0.0924 -0.0415 3.5190 +-0.1042 -0.0462 3.5082 +-0.1160 -0.0507 3.4974 +-0.1279 -0.0550 3.4866 +-0.1399 -0.0593 3.4759 +-0.1518 -0.0634 3.4651 +-0.1639 -0.0674 3.4543 +-0.1759 -0.0712 3.4435 +-0.1880 -0.0749 3.4327 +-0.2002 -0.0785 3.4219 +-0.2124 -0.0820 3.4112 +-0.2246 -0.0853 3.4004 +-0.2368 -0.0885 3.3896 +-0.2491 -0.0916 3.3788 +-0.2614 -0.0945 3.3680 +-0.2738 -0.0973 3.3572 +-0.2862 -0.1000 3.3465 +-0.2986 -0.1025 3.3357 +-0.3110 -0.1049 3.3249 +-0.3235 -0.1072 3.3141 +-0.3360 -0.1093 3.3033 +-0.3485 -0.1113 3.2925 +-0.3610 -0.1132 3.2818 +-0.3735 -0.1149 3.2710 +-0.3861 -0.1165 3.2602 +-0.3987 -0.1179 3.2494 +-0.4113 -0.1193 3.2386 +-0.4239 -0.1204 3.2279 +-0.4365 -0.1215 3.2171 +-0.4491 -0.1224 3.2063 +-0.4617 -0.1232 3.1955 +-0.4744 -0.1238 3.1847 +-0.4870 -0.1243 3.1739 +-0.4997 -0.1247 3.1632 +-0.5123 -0.1249 3.1524 +-0.5250 -0.1250 3.1416 +primID: 4 +startangle_c: 9 +endpose_c: 0 0 10 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 6 +0.0000 0.0000 3.6052 +0.0000 0.0000 3.6696 +0.0000 0.0000 3.7339 +0.0000 0.0000 3.7983 +0.0000 0.0000 3.8626 +0.0000 0.0000 3.9270 +primID: 5 +startangle_c: 9 +endpose_c: 2 1 9 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 5 +0.0000 0.0000 3.6052 +0.0125 0.0063 3.6052 +0.0250 0.0125 3.6052 +0.0375 0.0188 3.6052 +0.0500 0.0250 3.6052 +primID: 6 +startangle_c: 9 +endpose_c: 20 10 9 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 45 +0.0000 0.0000 3.6052 +0.0114 0.0057 3.6052 +0.0227 0.0114 3.6052 +0.0341 0.0170 3.6052 +0.0455 0.0227 3.6052 +0.0568 0.0284 3.6052 +0.0682 0.0341 3.6052 +0.0795 0.0398 3.6052 +0.0909 0.0455 3.6052 +0.1023 0.0511 3.6052 +0.1136 0.0568 3.6052 +0.1250 0.0625 3.6052 +0.1364 0.0682 3.6052 +0.1477 0.0739 3.6052 +0.1591 0.0795 3.6052 +0.1705 0.0852 3.6052 +0.1818 0.0909 3.6052 +0.1932 0.0966 3.6052 +0.2045 0.1023 3.6052 +0.2159 0.1080 3.6052 +0.2273 0.1136 3.6052 +0.2386 0.1193 3.6052 +0.2500 0.1250 3.6052 +0.2614 0.1307 3.6052 +0.2727 0.1364 3.6052 +0.2841 0.1420 3.6052 +0.2955 0.1477 3.6052 +0.3068 0.1534 3.6052 +0.3182 0.1591 3.6052 +0.3295 0.1648 3.6052 +0.3409 0.1705 3.6052 +0.3523 0.1761 3.6052 +0.3636 0.1818 3.6052 +0.3750 0.1875 3.6052 +0.3864 0.1932 3.6052 +0.3977 0.1989 3.6052 +0.4091 0.2045 3.6052 +0.4205 0.2102 3.6052 +0.4318 0.2159 3.6052 +0.4432 0.2216 3.6052 +0.4545 0.2273 3.6052 +0.4659 0.2330 3.6052 +0.4773 0.2386 3.6052 +0.4886 0.2443 3.6052 +0.5000 0.2500 3.6052 +primID: 7 +startangle_c: 9 +endpose_c: 18 13 10 +additionalactioncostmult: 3 +turning_radius: -1.7327 +intermediateposes: 45 +0.0000 0.0000 3.6052 +0.0113 0.0057 3.6126 +0.0226 0.0115 3.6199 +0.0338 0.0174 3.6272 +0.0450 0.0234 3.6345 +0.0561 0.0294 3.6418 +0.0672 0.0355 3.6491 +0.0782 0.0417 3.6564 +0.0892 0.0480 3.6637 +0.1002 0.0544 3.6711 +0.1111 0.0609 3.6784 +0.1219 0.0674 3.6857 +0.1328 0.0740 3.6930 +0.1435 0.0807 3.7003 +0.1542 0.0874 3.7076 +0.1649 0.0943 3.7149 +0.1755 0.1012 3.7222 +0.1861 0.1082 3.7296 +0.1966 0.1153 3.7369 +0.2070 0.1224 3.7442 +0.2174 0.1297 3.7515 +0.2278 0.1370 3.7588 +0.2381 0.1443 3.7661 +0.2483 0.1518 3.7734 +0.2585 0.1593 3.7807 +0.2687 0.1669 3.7881 +0.2787 0.1746 3.7954 +0.2888 0.1824 3.8027 +0.2987 0.1902 3.8100 +0.3086 0.1981 3.8173 +0.3185 0.2061 3.8246 +0.3283 0.2141 3.8319 +0.3380 0.2222 3.8392 +0.3477 0.2304 3.8466 +0.3573 0.2387 3.8539 +0.3668 0.2470 3.8612 +0.3763 0.2554 3.8685 +0.3858 0.2638 3.8758 +0.3951 0.2724 3.8831 +0.4044 0.2810 3.8904 +0.4137 0.2897 3.8977 +0.4229 0.2984 3.9051 +0.4320 0.3072 3.9124 +0.4410 0.3161 3.9197 +0.4500 0.3250 3.9270 +primID: 8 +startangle_c: 9 +endpose_c: 21 5 8 +additionalactioncostmult: 3 +turning_radius: 1.1745 +intermediateposes: 44 +0.0000 0.0000 3.6052 +0.0114 0.0056 3.5945 +0.0228 0.0111 3.5837 +0.0342 0.0165 3.5729 +0.0458 0.0218 3.5621 +0.0573 0.0269 3.5513 +0.0690 0.0319 3.5405 +0.0807 0.0368 3.5298 +0.0924 0.0415 3.5190 +0.1042 0.0462 3.5082 +0.1160 0.0507 3.4974 +0.1279 0.0550 3.4866 +0.1399 0.0593 3.4759 +0.1518 0.0634 3.4651 +0.1639 0.0674 3.4543 +0.1759 0.0712 3.4435 +0.1880 0.0749 3.4327 +0.2002 0.0785 3.4219 +0.2124 0.0820 3.4112 +0.2246 0.0853 3.4004 +0.2368 0.0885 3.3896 +0.2491 0.0916 3.3788 +0.2614 0.0945 3.3680 +0.2738 0.0973 3.3572 +0.2862 0.1000 3.3465 +0.2986 0.1025 3.3357 +0.3110 0.1049 3.3249 +0.3235 0.1072 3.3141 +0.3360 0.1093 3.3033 +0.3485 0.1113 3.2925 +0.3610 0.1132 3.2818 +0.3735 0.1149 3.2710 +0.3861 0.1165 3.2602 +0.3987 0.1179 3.2494 +0.4113 0.1193 3.2386 +0.4239 0.1204 3.2279 +0.4365 0.1215 3.2171 +0.4491 0.1224 3.2063 +0.4617 0.1232 3.1955 +0.4744 0.1238 3.1847 +0.4870 0.1243 3.1739 +0.4997 0.1247 3.1632 +0.5123 0.1249 3.1524 +0.5250 0.1250 3.1416 +primID: 9 +startangle_c: 9 +endpose_c: 0 0 8 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 9 +0.0000 0.0000 3.6052 +0.0000 0.0000 3.5473 +0.0000 0.0000 3.4893 +0.0000 0.0000 3.4314 +0.0000 0.0000 3.3734 +0.0000 0.0000 3.3155 +0.0000 0.0000 3.2575 +0.0000 0.0000 3.1995 +0.0000 0.0000 3.1416 +primID: 0 +startangle_c: 10 +endpose_c: -1 -1 10 +additionalactioncostmult: 1 +turning_radius: 0.0000 +intermediateposes: 3 +0.0000 0.0000 3.9270 +-0.0125 -0.0125 3.9270 +-0.0250 -0.0250 3.9270 +primID: 1 +startangle_c: 10 +endpose_c: -15 -15 10 +additionalactioncostmult: 1 +turning_radius: 0.0000 +intermediateposes: 43 +0.0000 0.0000 3.9270 +-0.0089 -0.0089 3.9270 +-0.0179 -0.0179 3.9270 +-0.0268 -0.0268 3.9270 +-0.0357 -0.0357 3.9270 +-0.0446 -0.0446 3.9270 +-0.0536 -0.0536 3.9270 +-0.0625 -0.0625 3.9270 +-0.0714 -0.0714 3.9270 +-0.0804 -0.0804 3.9270 +-0.0893 -0.0893 3.9270 +-0.0982 -0.0982 3.9270 +-0.1071 -0.1071 3.9270 +-0.1161 -0.1161 3.9270 +-0.1250 -0.1250 3.9270 +-0.1339 -0.1339 3.9270 +-0.1429 -0.1429 3.9270 +-0.1518 -0.1518 3.9270 +-0.1607 -0.1607 3.9270 +-0.1696 -0.1696 3.9270 +-0.1786 -0.1786 3.9270 +-0.1875 -0.1875 3.9270 +-0.1964 -0.1964 3.9270 +-0.2054 -0.2054 3.9270 +-0.2143 -0.2143 3.9270 +-0.2232 -0.2232 3.9270 +-0.2321 -0.2321 3.9270 +-0.2411 -0.2411 3.9270 +-0.2500 -0.2500 3.9270 +-0.2589 -0.2589 3.9270 +-0.2679 -0.2679 3.9270 +-0.2768 -0.2768 3.9270 +-0.2857 -0.2857 3.9270 +-0.2946 -0.2946 3.9270 +-0.3036 -0.3036 3.9270 +-0.3125 -0.3125 3.9270 +-0.3214 -0.3214 3.9270 +-0.3304 -0.3304 3.9270 +-0.3393 -0.3393 3.9270 +-0.3482 -0.3482 3.9270 +-0.3571 -0.3571 3.9270 +-0.3661 -0.3661 3.9270 +-0.3750 -0.3750 3.9270 +primID: 2 +startangle_c: 10 +endpose_c: -13 -18 11 +additionalactioncostmult: 2 +turning_radius: 1.7327 +intermediateposes: 45 +0.0000 0.0000 3.9270 +-0.0089 -0.0090 3.9343 +-0.0178 -0.0180 3.9416 +-0.0266 -0.0271 3.9489 +-0.0353 -0.0363 3.9562 +-0.0440 -0.0456 3.9636 +-0.0526 -0.0549 3.9709 +-0.0612 -0.0642 3.9782 +-0.0696 -0.0737 3.9855 +-0.0780 -0.0832 3.9928 +-0.0863 -0.0927 4.0001 +-0.0946 -0.1023 4.0074 +-0.1028 -0.1120 4.0147 +-0.1109 -0.1217 4.0221 +-0.1189 -0.1315 4.0294 +-0.1269 -0.1414 4.0367 +-0.1348 -0.1513 4.0440 +-0.1426 -0.1612 4.0513 +-0.1504 -0.1713 4.0586 +-0.1581 -0.1813 4.0659 +-0.1657 -0.1915 4.0732 +-0.1732 -0.2017 4.0806 +-0.1807 -0.2119 4.0879 +-0.1880 -0.2222 4.0952 +-0.1953 -0.2326 4.1025 +-0.2026 -0.2430 4.1098 +-0.2097 -0.2534 4.1171 +-0.2168 -0.2639 4.1244 +-0.2238 -0.2745 4.1317 +-0.2307 -0.2851 4.1391 +-0.2376 -0.2958 4.1464 +-0.2443 -0.3065 4.1537 +-0.2510 -0.3172 4.1610 +-0.2576 -0.3281 4.1683 +-0.2641 -0.3389 4.1756 +-0.2706 -0.3498 4.1829 +-0.2770 -0.3608 4.1902 +-0.2833 -0.3718 4.1976 +-0.2895 -0.3828 4.2049 +-0.2956 -0.3939 4.2122 +-0.3016 -0.4050 4.2195 +-0.3076 -0.4162 4.2268 +-0.3135 -0.4274 4.2341 +-0.3193 -0.4387 4.2414 +-0.3250 -0.4500 4.2487 +primID: 3 +startangle_c: 10 +endpose_c: -18 -13 9 +additionalactioncostmult: 2 +turning_radius: -1.7327 +intermediateposes: 45 +0.0000 0.0000 3.9270 +-0.0090 -0.0089 3.9197 +-0.0180 -0.0178 3.9124 +-0.0271 -0.0266 3.9051 +-0.0363 -0.0353 3.8977 +-0.0456 -0.0440 3.8904 +-0.0549 -0.0526 3.8831 +-0.0642 -0.0612 3.8758 +-0.0737 -0.0696 3.8685 +-0.0832 -0.0780 3.8612 +-0.0927 -0.0863 3.8539 +-0.1023 -0.0946 3.8466 +-0.1120 -0.1028 3.8392 +-0.1217 -0.1109 3.8319 +-0.1315 -0.1189 3.8246 +-0.1414 -0.1269 3.8173 +-0.1513 -0.1348 3.8100 +-0.1612 -0.1426 3.8027 +-0.1713 -0.1504 3.7954 +-0.1813 -0.1581 3.7881 +-0.1915 -0.1657 3.7807 +-0.2017 -0.1732 3.7734 +-0.2119 -0.1807 3.7661 +-0.2222 -0.1880 3.7588 +-0.2326 -0.1953 3.7515 +-0.2430 -0.2026 3.7442 +-0.2534 -0.2097 3.7369 +-0.2639 -0.2168 3.7296 +-0.2745 -0.2238 3.7222 +-0.2851 -0.2307 3.7149 +-0.2958 -0.2376 3.7076 +-0.3065 -0.2443 3.7003 +-0.3172 -0.2510 3.6930 +-0.3281 -0.2576 3.6857 +-0.3389 -0.2641 3.6784 +-0.3498 -0.2706 3.6711 +-0.3608 -0.2770 3.6637 +-0.3718 -0.2833 3.6564 +-0.3828 -0.2895 3.6491 +-0.3939 -0.2956 3.6418 +-0.4050 -0.3016 3.6345 +-0.4162 -0.3076 3.6272 +-0.4274 -0.3135 3.6199 +-0.4387 -0.3193 3.6126 +-0.4500 -0.3250 3.6052 +primID: 4 +startangle_c: 10 +endpose_c: 0 0 11 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 6 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.9913 +0.0000 0.0000 4.0557 +0.0000 0.0000 4.1200 +0.0000 0.0000 4.1844 +0.0000 0.0000 4.2487 +primID: 5 +startangle_c: 10 +endpose_c: 1 1 10 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 3 +0.0000 0.0000 3.9270 +0.0125 0.0125 3.9270 +0.0250 0.0250 3.9270 +primID: 6 +startangle_c: 10 +endpose_c: 16 16 10 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 46 +0.0000 0.0000 3.9270 +0.0089 0.0089 3.9270 +0.0178 0.0178 3.9270 +0.0267 0.0267 3.9270 +0.0356 0.0356 3.9270 +0.0444 0.0444 3.9270 +0.0533 0.0533 3.9270 +0.0622 0.0622 3.9270 +0.0711 0.0711 3.9270 +0.0800 0.0800 3.9270 +0.0889 0.0889 3.9270 +0.0978 0.0978 3.9270 +0.1067 0.1067 3.9270 +0.1156 0.1156 3.9270 +0.1244 0.1244 3.9270 +0.1333 0.1333 3.9270 +0.1422 0.1422 3.9270 +0.1511 0.1511 3.9270 +0.1600 0.1600 3.9270 +0.1689 0.1689 3.9270 +0.1778 0.1778 3.9270 +0.1867 0.1867 3.9270 +0.1956 0.1956 3.9270 +0.2044 0.2044 3.9270 +0.2133 0.2133 3.9270 +0.2222 0.2222 3.9270 +0.2311 0.2311 3.9270 +0.2400 0.2400 3.9270 +0.2489 0.2489 3.9270 +0.2578 0.2578 3.9270 +0.2667 0.2667 3.9270 +0.2756 0.2756 3.9270 +0.2844 0.2844 3.9270 +0.2933 0.2933 3.9270 +0.3022 0.3022 3.9270 +0.3111 0.3111 3.9270 +0.3200 0.3200 3.9270 +0.3289 0.3289 3.9270 +0.3378 0.3378 3.9270 +0.3467 0.3467 3.9270 +0.3556 0.3556 3.9270 +0.3644 0.3644 3.9270 +0.3733 0.3733 3.9270 +0.3822 0.3822 3.9270 +0.3911 0.3911 3.9270 +0.4000 0.4000 3.9270 +primID: 7 +startangle_c: 10 +endpose_c: 13 18 11 +additionalactioncostmult: 3 +turning_radius: -1.7327 +intermediateposes: 45 +0.0000 0.0000 3.9270 +0.0089 0.0090 3.9343 +0.0178 0.0180 3.9416 +0.0266 0.0271 3.9489 +0.0353 0.0363 3.9562 +0.0440 0.0456 3.9636 +0.0526 0.0549 3.9709 +0.0612 0.0642 3.9782 +0.0696 0.0737 3.9855 +0.0780 0.0832 3.9928 +0.0863 0.0927 4.0001 +0.0946 0.1023 4.0074 +0.1028 0.1120 4.0147 +0.1109 0.1217 4.0221 +0.1189 0.1315 4.0294 +0.1269 0.1414 4.0367 +0.1348 0.1513 4.0440 +0.1426 0.1612 4.0513 +0.1504 0.1713 4.0586 +0.1581 0.1813 4.0659 +0.1657 0.1915 4.0732 +0.1732 0.2017 4.0806 +0.1807 0.2119 4.0879 +0.1880 0.2222 4.0952 +0.1953 0.2326 4.1025 +0.2026 0.2430 4.1098 +0.2097 0.2534 4.1171 +0.2168 0.2639 4.1244 +0.2238 0.2745 4.1317 +0.2307 0.2851 4.1391 +0.2376 0.2958 4.1464 +0.2443 0.3065 4.1537 +0.2510 0.3172 4.1610 +0.2576 0.3281 4.1683 +0.2641 0.3389 4.1756 +0.2706 0.3498 4.1829 +0.2770 0.3608 4.1902 +0.2833 0.3718 4.1976 +0.2895 0.3828 4.2049 +0.2956 0.3939 4.2122 +0.3016 0.4050 4.2195 +0.3076 0.4162 4.2268 +0.3135 0.4274 4.2341 +0.3193 0.4387 4.2414 +0.3250 0.4500 4.2487 +primID: 8 +startangle_c: 10 +endpose_c: 18 13 9 +additionalactioncostmult: 3 +turning_radius: 1.7327 +intermediateposes: 45 +0.0000 0.0000 3.9270 +0.0090 0.0089 3.9197 +0.0180 0.0178 3.9124 +0.0271 0.0266 3.9051 +0.0363 0.0353 3.8977 +0.0456 0.0440 3.8904 +0.0549 0.0526 3.8831 +0.0642 0.0612 3.8758 +0.0737 0.0696 3.8685 +0.0832 0.0780 3.8612 +0.0927 0.0863 3.8539 +0.1023 0.0946 3.8466 +0.1120 0.1028 3.8392 +0.1217 0.1109 3.8319 +0.1315 0.1189 3.8246 +0.1414 0.1269 3.8173 +0.1513 0.1348 3.8100 +0.1612 0.1426 3.8027 +0.1713 0.1504 3.7954 +0.1813 0.1581 3.7881 +0.1915 0.1657 3.7807 +0.2017 0.1732 3.7734 +0.2119 0.1807 3.7661 +0.2222 0.1880 3.7588 +0.2326 0.1953 3.7515 +0.2430 0.2026 3.7442 +0.2534 0.2097 3.7369 +0.2639 0.2168 3.7296 +0.2745 0.2238 3.7222 +0.2851 0.2307 3.7149 +0.2958 0.2376 3.7076 +0.3065 0.2443 3.7003 +0.3172 0.2510 3.6930 +0.3281 0.2576 3.6857 +0.3389 0.2641 3.6784 +0.3498 0.2706 3.6711 +0.3608 0.2770 3.6637 +0.3718 0.2833 3.6564 +0.3828 0.2895 3.6491 +0.3939 0.2956 3.6418 +0.4050 0.3016 3.6345 +0.4162 0.3076 3.6272 +0.4274 0.3135 3.6199 +0.4387 0.3193 3.6126 +0.4500 0.3250 3.6052 +primID: 9 +startangle_c: 10 +endpose_c: 0 0 9 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 6 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.8626 +0.0000 0.0000 3.7983 +0.0000 0.0000 3.7339 +0.0000 0.0000 3.6696 +0.0000 0.0000 3.6052 +primID: 0 +startangle_c: 11 +endpose_c: -1 -2 11 +additionalactioncostmult: 1 +turning_radius: -0.0000 +intermediateposes: 5 +0.0000 0.0000 4.2487 +-0.0063 -0.0125 4.2487 +-0.0125 -0.0250 4.2487 +-0.0188 -0.0375 4.2487 +-0.0250 -0.0500 4.2487 +primID: 1 +startangle_c: 11 +endpose_c: -10 -20 11 +additionalactioncostmult: 1 +turning_radius: -0.0000 +intermediateposes: 45 +0.0000 0.0000 4.2487 +-0.0057 -0.0114 4.2487 +-0.0114 -0.0227 4.2487 +-0.0170 -0.0341 4.2487 +-0.0227 -0.0455 4.2487 +-0.0284 -0.0568 4.2487 +-0.0341 -0.0682 4.2487 +-0.0398 -0.0795 4.2487 +-0.0455 -0.0909 4.2487 +-0.0511 -0.1023 4.2487 +-0.0568 -0.1136 4.2487 +-0.0625 -0.1250 4.2487 +-0.0682 -0.1364 4.2487 +-0.0739 -0.1477 4.2487 +-0.0795 -0.1591 4.2487 +-0.0852 -0.1705 4.2487 +-0.0909 -0.1818 4.2487 +-0.0966 -0.1932 4.2487 +-0.1023 -0.2045 4.2487 +-0.1080 -0.2159 4.2487 +-0.1136 -0.2273 4.2487 +-0.1193 -0.2386 4.2487 +-0.1250 -0.2500 4.2487 +-0.1307 -0.2614 4.2487 +-0.1364 -0.2727 4.2487 +-0.1420 -0.2841 4.2487 +-0.1477 -0.2955 4.2487 +-0.1534 -0.3068 4.2487 +-0.1591 -0.3182 4.2487 +-0.1648 -0.3295 4.2487 +-0.1705 -0.3409 4.2487 +-0.1761 -0.3523 4.2487 +-0.1818 -0.3636 4.2487 +-0.1875 -0.3750 4.2487 +-0.1932 -0.3864 4.2487 +-0.1989 -0.3977 4.2487 +-0.2045 -0.4091 4.2487 +-0.2102 -0.4205 4.2487 +-0.2159 -0.4318 4.2487 +-0.2216 -0.4432 4.2487 +-0.2273 -0.4545 4.2487 +-0.2330 -0.4659 4.2487 +-0.2386 -0.4773 4.2487 +-0.2443 -0.4886 4.2487 +-0.2500 -0.5000 4.2487 +primID: 2 +startangle_c: 11 +endpose_c: -13 -18 10 +additionalactioncostmult: 2 +turning_radius: -1.7327 +intermediateposes: 45 +0.0000 0.0000 4.2487 +-0.0057 -0.0113 4.2414 +-0.0115 -0.0226 4.2341 +-0.0174 -0.0338 4.2268 +-0.0234 -0.0450 4.2195 +-0.0294 -0.0561 4.2122 +-0.0355 -0.0672 4.2049 +-0.0417 -0.0782 4.1976 +-0.0480 -0.0892 4.1902 +-0.0544 -0.1002 4.1829 +-0.0609 -0.1111 4.1756 +-0.0674 -0.1219 4.1683 +-0.0740 -0.1328 4.1610 +-0.0807 -0.1435 4.1537 +-0.0874 -0.1542 4.1464 +-0.0943 -0.1649 4.1391 +-0.1012 -0.1755 4.1317 +-0.1082 -0.1861 4.1244 +-0.1153 -0.1966 4.1171 +-0.1224 -0.2070 4.1098 +-0.1297 -0.2174 4.1025 +-0.1370 -0.2278 4.0952 +-0.1443 -0.2381 4.0879 +-0.1518 -0.2483 4.0806 +-0.1593 -0.2585 4.0732 +-0.1669 -0.2687 4.0659 +-0.1746 -0.2787 4.0586 +-0.1824 -0.2888 4.0513 +-0.1902 -0.2987 4.0440 +-0.1981 -0.3086 4.0367 +-0.2061 -0.3185 4.0294 +-0.2141 -0.3283 4.0221 +-0.2222 -0.3380 4.0147 +-0.2304 -0.3477 4.0074 +-0.2387 -0.3573 4.0001 +-0.2470 -0.3668 3.9928 +-0.2554 -0.3763 3.9855 +-0.2638 -0.3858 3.9782 +-0.2724 -0.3951 3.9709 +-0.2810 -0.4044 3.9636 +-0.2897 -0.4137 3.9562 +-0.2984 -0.4229 3.9489 +-0.3072 -0.4320 3.9416 +-0.3161 -0.4410 3.9343 +-0.3250 -0.4500 3.9270 +primID: 3 +startangle_c: 11 +endpose_c: -5 -21 12 +additionalactioncostmult: 2 +turning_radius: 1.1745 +intermediateposes: 44 +0.0000 0.0000 4.2487 +-0.0056 -0.0114 4.2595 +-0.0111 -0.0228 4.2703 +-0.0165 -0.0342 4.2811 +-0.0218 -0.0458 4.2919 +-0.0269 -0.0573 4.3027 +-0.0319 -0.0690 4.3134 +-0.0368 -0.0807 4.3242 +-0.0415 -0.0924 4.3350 +-0.0462 -0.1042 4.3458 +-0.0507 -0.1160 4.3566 +-0.0550 -0.1279 4.3673 +-0.0593 -0.1399 4.3781 +-0.0634 -0.1518 4.3889 +-0.0674 -0.1639 4.3997 +-0.0712 -0.1759 4.4105 +-0.0749 -0.1880 4.4213 +-0.0785 -0.2002 4.4320 +-0.0820 -0.2124 4.4428 +-0.0853 -0.2246 4.4536 +-0.0885 -0.2368 4.4644 +-0.0916 -0.2491 4.4752 +-0.0945 -0.2614 4.4860 +-0.0973 -0.2738 4.4967 +-0.1000 -0.2862 4.5075 +-0.1025 -0.2986 4.5183 +-0.1049 -0.3110 4.5291 +-0.1072 -0.3235 4.5399 +-0.1093 -0.3360 4.5507 +-0.1113 -0.3485 4.5614 +-0.1132 -0.3610 4.5722 +-0.1149 -0.3735 4.5830 +-0.1165 -0.3861 4.5938 +-0.1179 -0.3987 4.6046 +-0.1193 -0.4113 4.6153 +-0.1204 -0.4239 4.6261 +-0.1215 -0.4365 4.6369 +-0.1224 -0.4491 4.6477 +-0.1232 -0.4617 4.6585 +-0.1238 -0.4744 4.6693 +-0.1243 -0.4870 4.6800 +-0.1247 -0.4997 4.6908 +-0.1249 -0.5123 4.7016 +-0.1250 -0.5250 4.7124 +primID: 4 +startangle_c: 11 +endpose_c: 0 0 10 +additionalactioncostmult: 5 +turning_radius: -0.0000 +intermediateposes: 6 +0.0000 0.0000 4.2487 +0.0000 0.0000 4.1844 +0.0000 0.0000 4.1200 +0.0000 0.0000 4.0557 +0.0000 0.0000 3.9913 +0.0000 0.0000 3.9270 +primID: 5 +startangle_c: 11 +endpose_c: 1 2 11 +additionalactioncostmult: 5 +turning_radius: -0.0000 +intermediateposes: 5 +0.0000 0.0000 4.2487 +0.0063 0.0125 4.2487 +0.0125 0.0250 4.2487 +0.0188 0.0375 4.2487 +0.0250 0.0500 4.2487 +primID: 6 +startangle_c: 11 +endpose_c: 10 20 11 +additionalactioncostmult: 5 +turning_radius: -0.0000 +intermediateposes: 45 +0.0000 0.0000 4.2487 +0.0057 0.0114 4.2487 +0.0114 0.0227 4.2487 +0.0170 0.0341 4.2487 +0.0227 0.0455 4.2487 +0.0284 0.0568 4.2487 +0.0341 0.0682 4.2487 +0.0398 0.0795 4.2487 +0.0455 0.0909 4.2487 +0.0511 0.1023 4.2487 +0.0568 0.1136 4.2487 +0.0625 0.1250 4.2487 +0.0682 0.1364 4.2487 +0.0739 0.1477 4.2487 +0.0795 0.1591 4.2487 +0.0852 0.1705 4.2487 +0.0909 0.1818 4.2487 +0.0966 0.1932 4.2487 +0.1023 0.2045 4.2487 +0.1080 0.2159 4.2487 +0.1136 0.2273 4.2487 +0.1193 0.2386 4.2487 +0.1250 0.2500 4.2487 +0.1307 0.2614 4.2487 +0.1364 0.2727 4.2487 +0.1420 0.2841 4.2487 +0.1477 0.2955 4.2487 +0.1534 0.3068 4.2487 +0.1591 0.3182 4.2487 +0.1648 0.3295 4.2487 +0.1705 0.3409 4.2487 +0.1761 0.3523 4.2487 +0.1818 0.3636 4.2487 +0.1875 0.3750 4.2487 +0.1932 0.3864 4.2487 +0.1989 0.3977 4.2487 +0.2045 0.4091 4.2487 +0.2102 0.4205 4.2487 +0.2159 0.4318 4.2487 +0.2216 0.4432 4.2487 +0.2273 0.4545 4.2487 +0.2330 0.4659 4.2487 +0.2386 0.4773 4.2487 +0.2443 0.4886 4.2487 +0.2500 0.5000 4.2487 +primID: 7 +startangle_c: 11 +endpose_c: 13 18 10 +additionalactioncostmult: 3 +turning_radius: 1.7327 +intermediateposes: 45 +0.0000 0.0000 4.2487 +0.0057 0.0113 4.2414 +0.0115 0.0226 4.2341 +0.0174 0.0338 4.2268 +0.0234 0.0450 4.2195 +0.0294 0.0561 4.2122 +0.0355 0.0672 4.2049 +0.0417 0.0782 4.1976 +0.0480 0.0892 4.1902 +0.0544 0.1002 4.1829 +0.0609 0.1111 4.1756 +0.0674 0.1219 4.1683 +0.0740 0.1328 4.1610 +0.0807 0.1435 4.1537 +0.0874 0.1542 4.1464 +0.0943 0.1649 4.1391 +0.1012 0.1755 4.1317 +0.1082 0.1861 4.1244 +0.1153 0.1966 4.1171 +0.1224 0.2070 4.1098 +0.1297 0.2174 4.1025 +0.1370 0.2278 4.0952 +0.1443 0.2381 4.0879 +0.1518 0.2483 4.0806 +0.1593 0.2585 4.0732 +0.1669 0.2687 4.0659 +0.1746 0.2787 4.0586 +0.1824 0.2888 4.0513 +0.1902 0.2987 4.0440 +0.1981 0.3086 4.0367 +0.2061 0.3185 4.0294 +0.2141 0.3283 4.0221 +0.2222 0.3380 4.0147 +0.2304 0.3477 4.0074 +0.2387 0.3573 4.0001 +0.2470 0.3668 3.9928 +0.2554 0.3763 3.9855 +0.2638 0.3858 3.9782 +0.2724 0.3951 3.9709 +0.2810 0.4044 3.9636 +0.2897 0.4137 3.9562 +0.2984 0.4229 3.9489 +0.3072 0.4320 3.9416 +0.3161 0.4410 3.9343 +0.3250 0.4500 3.9270 +primID: 8 +startangle_c: 11 +endpose_c: 5 21 12 +additionalactioncostmult: 3 +turning_radius: -1.1745 +intermediateposes: 44 +0.0000 0.0000 4.2487 +0.0056 0.0114 4.2595 +0.0111 0.0228 4.2703 +0.0165 0.0342 4.2811 +0.0218 0.0458 4.2919 +0.0269 0.0573 4.3027 +0.0319 0.0690 4.3134 +0.0368 0.0807 4.3242 +0.0415 0.0924 4.3350 +0.0462 0.1042 4.3458 +0.0507 0.1160 4.3566 +0.0550 0.1279 4.3673 +0.0593 0.1399 4.3781 +0.0634 0.1518 4.3889 +0.0674 0.1639 4.3997 +0.0712 0.1759 4.4105 +0.0749 0.1880 4.4213 +0.0785 0.2002 4.4320 +0.0820 0.2124 4.4428 +0.0853 0.2246 4.4536 +0.0885 0.2368 4.4644 +0.0916 0.2491 4.4752 +0.0945 0.2614 4.4860 +0.0973 0.2738 4.4967 +0.1000 0.2862 4.5075 +0.1025 0.2986 4.5183 +0.1049 0.3110 4.5291 +0.1072 0.3235 4.5399 +0.1093 0.3360 4.5507 +0.1113 0.3485 4.5614 +0.1132 0.3610 4.5722 +0.1149 0.3735 4.5830 +0.1165 0.3861 4.5938 +0.1179 0.3987 4.6046 +0.1193 0.4113 4.6153 +0.1204 0.4239 4.6261 +0.1215 0.4365 4.6369 +0.1224 0.4491 4.6477 +0.1232 0.4617 4.6585 +0.1238 0.4744 4.6693 +0.1243 0.4870 4.6800 +0.1247 0.4997 4.6908 +0.1249 0.5123 4.7016 +0.1250 0.5250 4.7124 +primID: 9 +startangle_c: 11 +endpose_c: 0 0 12 +additionalactioncostmult: 5 +turning_radius: -0.0000 +intermediateposes: 9 +0.0000 0.0000 4.2487 +0.0000 0.0000 4.3067 +0.0000 0.0000 4.3647 +0.0000 0.0000 4.4226 +0.0000 0.0000 4.4806 +0.0000 0.0000 4.5385 +0.0000 0.0000 4.5965 +0.0000 0.0000 4.6544 +0.0000 0.0000 4.7124 +primID: 0 +startangle_c: 12 +endpose_c: 0 -1 12 +additionalactioncostmult: 1 +turning_radius: 0.0000 +intermediateposes: 3 +0.0000 0.0000 4.7124 +0.0000 -0.0125 4.7124 +0.0000 -0.0250 4.7124 +primID: 1 +startangle_c: 12 +endpose_c: 0 -21 12 +additionalactioncostmult: 1 +turning_radius: 0.0000 +intermediateposes: 43 +0.0000 0.0000 4.7124 +0.0000 -0.0125 4.7124 +0.0000 -0.0250 4.7124 +0.0000 -0.0375 4.7124 +0.0000 -0.0500 4.7124 +0.0000 -0.0625 4.7124 +0.0000 -0.0750 4.7124 +0.0000 -0.0875 4.7124 +0.0000 -0.1000 4.7124 +0.0000 -0.1125 4.7124 +0.0000 -0.1250 4.7124 +0.0000 -0.1375 4.7124 +0.0000 -0.1500 4.7124 +0.0000 -0.1625 4.7124 +0.0000 -0.1750 4.7124 +0.0000 -0.1875 4.7124 +0.0000 -0.2000 4.7124 +0.0000 -0.2125 4.7124 +0.0000 -0.2250 4.7124 +0.0000 -0.2375 4.7124 +0.0000 -0.2500 4.7124 +0.0000 -0.2625 4.7124 +0.0000 -0.2750 4.7124 +0.0000 -0.2875 4.7124 +0.0000 -0.3000 4.7124 +0.0000 -0.3125 4.7124 +0.0000 -0.3250 4.7124 +0.0000 -0.3375 4.7124 +0.0000 -0.3500 4.7124 +0.0000 -0.3625 4.7124 +0.0000 -0.3750 4.7124 +0.0000 -0.3875 4.7124 +0.0000 -0.4000 4.7124 +0.0000 -0.4125 4.7124 +0.0000 -0.4250 4.7124 +0.0000 -0.4375 4.7124 +0.0000 -0.4500 4.7124 +0.0000 -0.4625 4.7124 +0.0000 -0.4750 4.7124 +0.0000 -0.4875 4.7124 +0.0000 -0.5000 4.7124 +0.0000 -0.5125 4.7124 +0.0000 -0.5250 4.7124 +primID: 2 +startangle_c: 12 +endpose_c: 5 -21 13 +additionalactioncostmult: 2 +turning_radius: 1.1745 +intermediateposes: 44 +0.0000 0.0000 4.7124 +0.0001 -0.0127 4.7232 +0.0003 -0.0253 4.7340 +0.0007 -0.0380 4.7447 +0.0012 -0.0506 4.7555 +0.0018 -0.0633 4.7663 +0.0026 -0.0759 4.7771 +0.0035 -0.0885 4.7879 +0.0046 -0.1011 4.7986 +0.0057 -0.1137 4.8094 +0.0071 -0.1263 4.8202 +0.0085 -0.1389 4.8310 +0.0101 -0.1515 4.8418 +0.0118 -0.1640 4.8526 +0.0137 -0.1765 4.8633 +0.0157 -0.1890 4.8741 +0.0178 -0.2015 4.8849 +0.0201 -0.2140 4.8957 +0.0225 -0.2264 4.9065 +0.0250 -0.2388 4.9173 +0.0277 -0.2512 4.9280 +0.0305 -0.2636 4.9388 +0.0334 -0.2759 4.9496 +0.0365 -0.2882 4.9604 +0.0397 -0.3004 4.9712 +0.0430 -0.3126 4.9820 +0.0465 -0.3248 4.9927 +0.0501 -0.3370 5.0035 +0.0538 -0.3491 5.0143 +0.0576 -0.3611 5.0251 +0.0616 -0.3732 5.0359 +0.0657 -0.3851 5.0466 +0.0700 -0.3971 5.0574 +0.0743 -0.4090 5.0682 +0.0788 -0.4208 5.0790 +0.0835 -0.4326 5.0898 +0.0882 -0.4443 5.1006 +0.0931 -0.4560 5.1113 +0.0981 -0.4677 5.1221 +0.1032 -0.4792 5.1329 +0.1085 -0.4908 5.1437 +0.1139 -0.5022 5.1545 +0.1194 -0.5136 5.1653 +0.1250 -0.5250 5.1760 +primID: 3 +startangle_c: 12 +endpose_c: -5 -21 11 +additionalactioncostmult: 2 +turning_radius: -1.1745 +intermediateposes: 44 +0.0000 0.0000 4.7124 +-0.0001 -0.0127 4.7016 +-0.0003 -0.0253 4.6908 +-0.0007 -0.0380 4.6800 +-0.0012 -0.0506 4.6693 +-0.0018 -0.0633 4.6585 +-0.0026 -0.0759 4.6477 +-0.0035 -0.0885 4.6369 +-0.0046 -0.1011 4.6261 +-0.0057 -0.1137 4.6153 +-0.0071 -0.1263 4.6046 +-0.0085 -0.1389 4.5938 +-0.0101 -0.1515 4.5830 +-0.0118 -0.1640 4.5722 +-0.0137 -0.1765 4.5614 +-0.0157 -0.1890 4.5507 +-0.0178 -0.2015 4.5399 +-0.0201 -0.2140 4.5291 +-0.0225 -0.2264 4.5183 +-0.0250 -0.2388 4.5075 +-0.0277 -0.2512 4.4967 +-0.0305 -0.2636 4.4860 +-0.0334 -0.2759 4.4752 +-0.0365 -0.2882 4.4644 +-0.0397 -0.3004 4.4536 +-0.0430 -0.3126 4.4428 +-0.0465 -0.3248 4.4320 +-0.0501 -0.3370 4.4213 +-0.0538 -0.3491 4.4105 +-0.0576 -0.3611 4.3997 +-0.0616 -0.3732 4.3889 +-0.0657 -0.3851 4.3781 +-0.0700 -0.3971 4.3673 +-0.0743 -0.4090 4.3566 +-0.0788 -0.4208 4.3458 +-0.0835 -0.4326 4.3350 +-0.0882 -0.4443 4.3242 +-0.0931 -0.4560 4.3134 +-0.0981 -0.4677 4.3027 +-0.1032 -0.4792 4.2919 +-0.1085 -0.4908 4.2811 +-0.1139 -0.5022 4.2703 +-0.1194 -0.5136 4.2595 +-0.1250 -0.5250 4.2487 +primID: 4 +startangle_c: 12 +endpose_c: 0 0 13 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 9 +0.0000 0.0000 4.7124 +0.0000 0.0000 4.7703 +0.0000 0.0000 4.8283 +0.0000 0.0000 4.8863 +0.0000 0.0000 4.9442 +0.0000 0.0000 5.0022 +0.0000 0.0000 5.0601 +0.0000 0.0000 5.1181 +0.0000 0.0000 5.1760 +primID: 5 +startangle_c: 12 +endpose_c: 0 1 12 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 3 +0.0000 0.0000 4.7124 +0.0000 0.0125 4.7124 +0.0000 0.0250 4.7124 +primID: 6 +startangle_c: 12 +endpose_c: 0 21 12 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 43 +0.0000 0.0000 4.7124 +0.0000 0.0125 4.7124 +0.0000 0.0250 4.7124 +0.0000 0.0375 4.7124 +0.0000 0.0500 4.7124 +0.0000 0.0625 4.7124 +0.0000 0.0750 4.7124 +0.0000 0.0875 4.7124 +0.0000 0.1000 4.7124 +0.0000 0.1125 4.7124 +0.0000 0.1250 4.7124 +0.0000 0.1375 4.7124 +0.0000 0.1500 4.7124 +0.0000 0.1625 4.7124 +0.0000 0.1750 4.7124 +0.0000 0.1875 4.7124 +0.0000 0.2000 4.7124 +0.0000 0.2125 4.7124 +0.0000 0.2250 4.7124 +0.0000 0.2375 4.7124 +0.0000 0.2500 4.7124 +0.0000 0.2625 4.7124 +0.0000 0.2750 4.7124 +0.0000 0.2875 4.7124 +0.0000 0.3000 4.7124 +0.0000 0.3125 4.7124 +0.0000 0.3250 4.7124 +0.0000 0.3375 4.7124 +0.0000 0.3500 4.7124 +0.0000 0.3625 4.7124 +0.0000 0.3750 4.7124 +0.0000 0.3875 4.7124 +0.0000 0.4000 4.7124 +0.0000 0.4125 4.7124 +0.0000 0.4250 4.7124 +0.0000 0.4375 4.7124 +0.0000 0.4500 4.7124 +0.0000 0.4625 4.7124 +0.0000 0.4750 4.7124 +0.0000 0.4875 4.7124 +0.0000 0.5000 4.7124 +0.0000 0.5125 4.7124 +0.0000 0.5250 4.7124 +primID: 7 +startangle_c: 12 +endpose_c: -5 21 13 +additionalactioncostmult: 3 +turning_radius: -1.1745 +intermediateposes: 44 +0.0000 0.0000 4.7124 +-0.0001 0.0127 4.7232 +-0.0003 0.0253 4.7340 +-0.0007 0.0380 4.7447 +-0.0012 0.0506 4.7555 +-0.0018 0.0633 4.7663 +-0.0026 0.0759 4.7771 +-0.0035 0.0885 4.7879 +-0.0046 0.1011 4.7986 +-0.0057 0.1137 4.8094 +-0.0071 0.1263 4.8202 +-0.0085 0.1389 4.8310 +-0.0101 0.1515 4.8418 +-0.0118 0.1640 4.8526 +-0.0137 0.1765 4.8633 +-0.0157 0.1890 4.8741 +-0.0178 0.2015 4.8849 +-0.0201 0.2140 4.8957 +-0.0225 0.2264 4.9065 +-0.0250 0.2388 4.9173 +-0.0277 0.2512 4.9280 +-0.0305 0.2636 4.9388 +-0.0334 0.2759 4.9496 +-0.0365 0.2882 4.9604 +-0.0397 0.3004 4.9712 +-0.0430 0.3126 4.9820 +-0.0465 0.3248 4.9927 +-0.0501 0.3370 5.0035 +-0.0538 0.3491 5.0143 +-0.0576 0.3611 5.0251 +-0.0616 0.3732 5.0359 +-0.0657 0.3851 5.0466 +-0.0700 0.3971 5.0574 +-0.0743 0.4090 5.0682 +-0.0788 0.4208 5.0790 +-0.0835 0.4326 5.0898 +-0.0882 0.4443 5.1006 +-0.0931 0.4560 5.1113 +-0.0981 0.4677 5.1221 +-0.1032 0.4792 5.1329 +-0.1085 0.4908 5.1437 +-0.1139 0.5022 5.1545 +-0.1194 0.5136 5.1653 +-0.1250 0.5250 5.1760 +primID: 8 +startangle_c: 12 +endpose_c: 5 21 11 +additionalactioncostmult: 3 +turning_radius: 1.1745 +intermediateposes: 44 +0.0000 0.0000 4.7124 +0.0001 0.0127 4.7016 +0.0003 0.0253 4.6908 +0.0007 0.0380 4.6800 +0.0012 0.0506 4.6693 +0.0018 0.0633 4.6585 +0.0026 0.0759 4.6477 +0.0035 0.0885 4.6369 +0.0046 0.1011 4.6261 +0.0057 0.1137 4.6153 +0.0071 0.1263 4.6046 +0.0085 0.1389 4.5938 +0.0101 0.1515 4.5830 +0.0118 0.1640 4.5722 +0.0137 0.1765 4.5614 +0.0157 0.1890 4.5507 +0.0178 0.2015 4.5399 +0.0201 0.2140 4.5291 +0.0225 0.2264 4.5183 +0.0250 0.2388 4.5075 +0.0277 0.2512 4.4967 +0.0305 0.2636 4.4860 +0.0334 0.2759 4.4752 +0.0365 0.2882 4.4644 +0.0397 0.3004 4.4536 +0.0430 0.3126 4.4428 +0.0465 0.3248 4.4320 +0.0501 0.3370 4.4213 +0.0538 0.3491 4.4105 +0.0576 0.3611 4.3997 +0.0616 0.3732 4.3889 +0.0657 0.3851 4.3781 +0.0700 0.3971 4.3673 +0.0743 0.4090 4.3566 +0.0788 0.4208 4.3458 +0.0835 0.4326 4.3350 +0.0882 0.4443 4.3242 +0.0931 0.4560 4.3134 +0.0981 0.4677 4.3027 +0.1032 0.4792 4.2919 +0.1085 0.4908 4.2811 +0.1139 0.5022 4.2703 +0.1194 0.5136 4.2595 +0.1250 0.5250 4.2487 +primID: 9 +startangle_c: 12 +endpose_c: 0 0 11 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 9 +0.0000 0.0000 4.7124 +0.0000 0.0000 4.6544 +0.0000 0.0000 4.5965 +0.0000 0.0000 4.5385 +0.0000 0.0000 4.4806 +0.0000 0.0000 4.4226 +0.0000 0.0000 4.3647 +0.0000 0.0000 4.3067 +0.0000 0.0000 4.2487 +primID: 0 +startangle_c: 13 +endpose_c: 1 -2 13 +additionalactioncostmult: 1 +turning_radius: 0.0000 +intermediateposes: 5 +0.0000 0.0000 5.1760 +0.0063 -0.0125 5.1760 +0.0125 -0.0250 5.1760 +0.0188 -0.0375 5.1760 +0.0250 -0.0500 5.1760 +primID: 1 +startangle_c: 13 +endpose_c: 10 -20 13 +additionalactioncostmult: 1 +turning_radius: 0.0000 +intermediateposes: 45 +0.0000 0.0000 5.1760 +0.0057 -0.0114 5.1760 +0.0114 -0.0227 5.1760 +0.0170 -0.0341 5.1760 +0.0227 -0.0455 5.1760 +0.0284 -0.0568 5.1760 +0.0341 -0.0682 5.1760 +0.0398 -0.0795 5.1760 +0.0455 -0.0909 5.1760 +0.0511 -0.1023 5.1760 +0.0568 -0.1136 5.1760 +0.0625 -0.1250 5.1760 +0.0682 -0.1364 5.1760 +0.0739 -0.1477 5.1760 +0.0795 -0.1591 5.1760 +0.0852 -0.1705 5.1760 +0.0909 -0.1818 5.1760 +0.0966 -0.1932 5.1760 +0.1023 -0.2045 5.1760 +0.1080 -0.2159 5.1760 +0.1136 -0.2273 5.1760 +0.1193 -0.2386 5.1760 +0.1250 -0.2500 5.1760 +0.1307 -0.2614 5.1760 +0.1364 -0.2727 5.1760 +0.1420 -0.2841 5.1760 +0.1477 -0.2955 5.1760 +0.1534 -0.3068 5.1760 +0.1591 -0.3182 5.1760 +0.1648 -0.3295 5.1760 +0.1705 -0.3409 5.1760 +0.1761 -0.3523 5.1760 +0.1818 -0.3636 5.1760 +0.1875 -0.3750 5.1760 +0.1932 -0.3864 5.1760 +0.1989 -0.3977 5.1760 +0.2045 -0.4091 5.1760 +0.2102 -0.4205 5.1760 +0.2159 -0.4318 5.1760 +0.2216 -0.4432 5.1760 +0.2273 -0.4545 5.1760 +0.2330 -0.4659 5.1760 +0.2386 -0.4773 5.1760 +0.2443 -0.4886 5.1760 +0.2500 -0.5000 5.1760 +primID: 2 +startangle_c: 13 +endpose_c: 13 -18 14 +additionalactioncostmult: 2 +turning_radius: 1.7327 +intermediateposes: 45 +0.0000 0.0000 5.1760 +0.0057 -0.0113 5.1833 +0.0115 -0.0226 5.1907 +0.0174 -0.0338 5.1980 +0.0234 -0.0450 5.2053 +0.0294 -0.0561 5.2126 +0.0355 -0.0672 5.2199 +0.0417 -0.0782 5.2272 +0.0480 -0.0892 5.2345 +0.0544 -0.1002 5.2418 +0.0609 -0.1111 5.2492 +0.0674 -0.1219 5.2565 +0.0740 -0.1328 5.2638 +0.0807 -0.1435 5.2711 +0.0874 -0.1542 5.2784 +0.0943 -0.1649 5.2857 +0.1012 -0.1755 5.2930 +0.1082 -0.1861 5.3003 +0.1153 -0.1966 5.3077 +0.1224 -0.2070 5.3150 +0.1297 -0.2174 5.3223 +0.1370 -0.2278 5.3296 +0.1443 -0.2381 5.3369 +0.1518 -0.2483 5.3442 +0.1593 -0.2585 5.3515 +0.1669 -0.2687 5.3588 +0.1746 -0.2787 5.3662 +0.1824 -0.2888 5.3735 +0.1902 -0.2987 5.3808 +0.1981 -0.3086 5.3881 +0.2061 -0.3185 5.3954 +0.2141 -0.3283 5.4027 +0.2222 -0.3380 5.4100 +0.2304 -0.3477 5.4173 +0.2387 -0.3573 5.4247 +0.2470 -0.3668 5.4320 +0.2554 -0.3763 5.4393 +0.2638 -0.3858 5.4466 +0.2724 -0.3951 5.4539 +0.2810 -0.4044 5.4612 +0.2897 -0.4137 5.4685 +0.2984 -0.4229 5.4758 +0.3072 -0.4320 5.4832 +0.3161 -0.4410 5.4905 +0.3250 -0.4500 5.4978 +primID: 3 +startangle_c: 13 +endpose_c: 5 -21 12 +additionalactioncostmult: 2 +turning_radius: -1.1745 +intermediateposes: 44 +0.0000 0.0000 5.1760 +0.0056 -0.0114 5.1653 +0.0111 -0.0228 5.1545 +0.0165 -0.0342 5.1437 +0.0218 -0.0458 5.1329 +0.0269 -0.0573 5.1221 +0.0319 -0.0690 5.1113 +0.0368 -0.0807 5.1006 +0.0415 -0.0924 5.0898 +0.0462 -0.1042 5.0790 +0.0507 -0.1160 5.0682 +0.0550 -0.1279 5.0574 +0.0593 -0.1399 5.0466 +0.0634 -0.1518 5.0359 +0.0674 -0.1639 5.0251 +0.0712 -0.1759 5.0143 +0.0749 -0.1880 5.0035 +0.0785 -0.2002 4.9927 +0.0820 -0.2124 4.9820 +0.0853 -0.2246 4.9712 +0.0885 -0.2368 4.9604 +0.0916 -0.2491 4.9496 +0.0945 -0.2614 4.9388 +0.0973 -0.2738 4.9280 +0.1000 -0.2862 4.9173 +0.1025 -0.2986 4.9065 +0.1049 -0.3110 4.8957 +0.1072 -0.3235 4.8849 +0.1093 -0.3360 4.8741 +0.1113 -0.3485 4.8633 +0.1132 -0.3610 4.8526 +0.1149 -0.3735 4.8418 +0.1165 -0.3861 4.8310 +0.1179 -0.3987 4.8202 +0.1193 -0.4113 4.8094 +0.1204 -0.4239 4.7986 +0.1215 -0.4365 4.7879 +0.1224 -0.4491 4.7771 +0.1232 -0.4617 4.7663 +0.1238 -0.4744 4.7555 +0.1243 -0.4870 4.7447 +0.1247 -0.4997 4.7340 +0.1249 -0.5123 4.7232 +0.1250 -0.5250 4.7124 +primID: 4 +startangle_c: 13 +endpose_c: 0 0 14 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 6 +0.0000 0.0000 5.1760 +0.0000 0.0000 5.2404 +0.0000 0.0000 5.3047 +0.0000 0.0000 5.3691 +0.0000 0.0000 5.4334 +0.0000 0.0000 5.4978 +primID: 5 +startangle_c: 13 +endpose_c: -1 2 13 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 5 +0.0000 0.0000 5.1760 +-0.0063 0.0125 5.1760 +-0.0125 0.0250 5.1760 +-0.0188 0.0375 5.1760 +-0.0250 0.0500 5.1760 +primID: 6 +startangle_c: 13 +endpose_c: -10 20 13 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 45 +0.0000 0.0000 5.1760 +-0.0057 0.0114 5.1760 +-0.0114 0.0227 5.1760 +-0.0170 0.0341 5.1760 +-0.0227 0.0455 5.1760 +-0.0284 0.0568 5.1760 +-0.0341 0.0682 5.1760 +-0.0398 0.0795 5.1760 +-0.0455 0.0909 5.1760 +-0.0511 0.1023 5.1760 +-0.0568 0.1136 5.1760 +-0.0625 0.1250 5.1760 +-0.0682 0.1364 5.1760 +-0.0739 0.1477 5.1760 +-0.0795 0.1591 5.1760 +-0.0852 0.1705 5.1760 +-0.0909 0.1818 5.1760 +-0.0966 0.1932 5.1760 +-0.1023 0.2045 5.1760 +-0.1080 0.2159 5.1760 +-0.1136 0.2273 5.1760 +-0.1193 0.2386 5.1760 +-0.1250 0.2500 5.1760 +-0.1307 0.2614 5.1760 +-0.1364 0.2727 5.1760 +-0.1420 0.2841 5.1760 +-0.1477 0.2955 5.1760 +-0.1534 0.3068 5.1760 +-0.1591 0.3182 5.1760 +-0.1648 0.3295 5.1760 +-0.1705 0.3409 5.1760 +-0.1761 0.3523 5.1760 +-0.1818 0.3636 5.1760 +-0.1875 0.3750 5.1760 +-0.1932 0.3864 5.1760 +-0.1989 0.3977 5.1760 +-0.2045 0.4091 5.1760 +-0.2102 0.4205 5.1760 +-0.2159 0.4318 5.1760 +-0.2216 0.4432 5.1760 +-0.2273 0.4545 5.1760 +-0.2330 0.4659 5.1760 +-0.2386 0.4773 5.1760 +-0.2443 0.4886 5.1760 +-0.2500 0.5000 5.1760 +primID: 7 +startangle_c: 13 +endpose_c: -13 18 14 +additionalactioncostmult: 3 +turning_radius: -1.7327 +intermediateposes: 45 +0.0000 0.0000 5.1760 +-0.0057 0.0113 5.1833 +-0.0115 0.0226 5.1907 +-0.0174 0.0338 5.1980 +-0.0234 0.0450 5.2053 +-0.0294 0.0561 5.2126 +-0.0355 0.0672 5.2199 +-0.0417 0.0782 5.2272 +-0.0480 0.0892 5.2345 +-0.0544 0.1002 5.2418 +-0.0609 0.1111 5.2492 +-0.0674 0.1219 5.2565 +-0.0740 0.1328 5.2638 +-0.0807 0.1435 5.2711 +-0.0874 0.1542 5.2784 +-0.0943 0.1649 5.2857 +-0.1012 0.1755 5.2930 +-0.1082 0.1861 5.3003 +-0.1153 0.1966 5.3077 +-0.1224 0.2070 5.3150 +-0.1297 0.2174 5.3223 +-0.1370 0.2278 5.3296 +-0.1443 0.2381 5.3369 +-0.1518 0.2483 5.3442 +-0.1593 0.2585 5.3515 +-0.1669 0.2687 5.3588 +-0.1746 0.2787 5.3662 +-0.1824 0.2888 5.3735 +-0.1902 0.2987 5.3808 +-0.1981 0.3086 5.3881 +-0.2061 0.3185 5.3954 +-0.2141 0.3283 5.4027 +-0.2222 0.3380 5.4100 +-0.2304 0.3477 5.4173 +-0.2387 0.3573 5.4247 +-0.2470 0.3668 5.4320 +-0.2554 0.3763 5.4393 +-0.2638 0.3858 5.4466 +-0.2724 0.3951 5.4539 +-0.2810 0.4044 5.4612 +-0.2897 0.4137 5.4685 +-0.2984 0.4229 5.4758 +-0.3072 0.4320 5.4832 +-0.3161 0.4410 5.4905 +-0.3250 0.4500 5.4978 +primID: 8 +startangle_c: 13 +endpose_c: -5 21 12 +additionalactioncostmult: 3 +turning_radius: 1.1745 +intermediateposes: 44 +0.0000 0.0000 5.1760 +-0.0056 0.0114 5.1653 +-0.0111 0.0228 5.1545 +-0.0165 0.0342 5.1437 +-0.0218 0.0458 5.1329 +-0.0269 0.0573 5.1221 +-0.0319 0.0690 5.1113 +-0.0368 0.0807 5.1006 +-0.0415 0.0924 5.0898 +-0.0462 0.1042 5.0790 +-0.0507 0.1160 5.0682 +-0.0550 0.1279 5.0574 +-0.0593 0.1399 5.0466 +-0.0634 0.1518 5.0359 +-0.0674 0.1639 5.0251 +-0.0712 0.1759 5.0143 +-0.0749 0.1880 5.0035 +-0.0785 0.2002 4.9927 +-0.0820 0.2124 4.9820 +-0.0853 0.2246 4.9712 +-0.0885 0.2368 4.9604 +-0.0916 0.2491 4.9496 +-0.0945 0.2614 4.9388 +-0.0973 0.2738 4.9280 +-0.1000 0.2862 4.9173 +-0.1025 0.2986 4.9065 +-0.1049 0.3110 4.8957 +-0.1072 0.3235 4.8849 +-0.1093 0.3360 4.8741 +-0.1113 0.3485 4.8633 +-0.1132 0.3610 4.8526 +-0.1149 0.3735 4.8418 +-0.1165 0.3861 4.8310 +-0.1179 0.3987 4.8202 +-0.1193 0.4113 4.8094 +-0.1204 0.4239 4.7986 +-0.1215 0.4365 4.7879 +-0.1224 0.4491 4.7771 +-0.1232 0.4617 4.7663 +-0.1238 0.4744 4.7555 +-0.1243 0.4870 4.7447 +-0.1247 0.4997 4.7340 +-0.1249 0.5123 4.7232 +-0.1250 0.5250 4.7124 +primID: 9 +startangle_c: 13 +endpose_c: 0 0 12 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 9 +0.0000 0.0000 5.1760 +0.0000 0.0000 5.1181 +0.0000 0.0000 5.0601 +0.0000 0.0000 5.0022 +0.0000 0.0000 4.9442 +0.0000 0.0000 4.8863 +0.0000 0.0000 4.8283 +0.0000 0.0000 4.7703 +0.0000 0.0000 4.7124 +primID: 0 +startangle_c: 14 +endpose_c: 1 -1 14 +additionalactioncostmult: 1 +turning_radius: 0.0000 +intermediateposes: 3 +0.0000 0.0000 5.4978 +0.0125 -0.0125 5.4978 +0.0250 -0.0250 5.4978 +primID: 1 +startangle_c: 14 +endpose_c: 15 -15 14 +additionalactioncostmult: 1 +turning_radius: 0.0000 +intermediateposes: 43 +0.0000 0.0000 5.4978 +0.0089 -0.0089 5.4978 +0.0179 -0.0179 5.4978 +0.0268 -0.0268 5.4978 +0.0357 -0.0357 5.4978 +0.0446 -0.0446 5.4978 +0.0536 -0.0536 5.4978 +0.0625 -0.0625 5.4978 +0.0714 -0.0714 5.4978 +0.0804 -0.0804 5.4978 +0.0893 -0.0893 5.4978 +0.0982 -0.0982 5.4978 +0.1071 -0.1071 5.4978 +0.1161 -0.1161 5.4978 +0.1250 -0.1250 5.4978 +0.1339 -0.1339 5.4978 +0.1429 -0.1429 5.4978 +0.1518 -0.1518 5.4978 +0.1607 -0.1607 5.4978 +0.1696 -0.1696 5.4978 +0.1786 -0.1786 5.4978 +0.1875 -0.1875 5.4978 +0.1964 -0.1964 5.4978 +0.2054 -0.2054 5.4978 +0.2143 -0.2143 5.4978 +0.2232 -0.2232 5.4978 +0.2321 -0.2321 5.4978 +0.2411 -0.2411 5.4978 +0.2500 -0.2500 5.4978 +0.2589 -0.2589 5.4978 +0.2679 -0.2679 5.4978 +0.2768 -0.2768 5.4978 +0.2857 -0.2857 5.4978 +0.2946 -0.2946 5.4978 +0.3036 -0.3036 5.4978 +0.3125 -0.3125 5.4978 +0.3214 -0.3214 5.4978 +0.3304 -0.3304 5.4978 +0.3393 -0.3393 5.4978 +0.3482 -0.3482 5.4978 +0.3571 -0.3571 5.4978 +0.3661 -0.3661 5.4978 +0.3750 -0.3750 5.4978 +primID: 2 +startangle_c: 14 +endpose_c: 18 -13 15 +additionalactioncostmult: 2 +turning_radius: 1.7327 +intermediateposes: 45 +0.0000 0.0000 5.4978 +0.0090 -0.0089 5.5051 +0.0180 -0.0178 5.5124 +0.0271 -0.0266 5.5197 +0.0363 -0.0353 5.5270 +0.0456 -0.0440 5.5343 +0.0549 -0.0526 5.5417 +0.0642 -0.0612 5.5490 +0.0737 -0.0696 5.5563 +0.0832 -0.0780 5.5636 +0.0927 -0.0863 5.5709 +0.1023 -0.0946 5.5782 +0.1120 -0.1028 5.5855 +0.1217 -0.1109 5.5928 +0.1315 -0.1189 5.6002 +0.1414 -0.1269 5.6075 +0.1513 -0.1348 5.6148 +0.1612 -0.1426 5.6221 +0.1713 -0.1504 5.6294 +0.1813 -0.1581 5.6367 +0.1915 -0.1657 5.6440 +0.2017 -0.1732 5.6513 +0.2119 -0.1807 5.6587 +0.2222 -0.1880 5.6660 +0.2326 -0.1953 5.6733 +0.2430 -0.2026 5.6806 +0.2534 -0.2097 5.6879 +0.2639 -0.2168 5.6952 +0.2745 -0.2238 5.7025 +0.2851 -0.2307 5.7099 +0.2958 -0.2376 5.7172 +0.3065 -0.2443 5.7245 +0.3172 -0.2510 5.7318 +0.3281 -0.2576 5.7391 +0.3389 -0.2641 5.7464 +0.3498 -0.2706 5.7537 +0.3608 -0.2770 5.7610 +0.3718 -0.2833 5.7684 +0.3828 -0.2895 5.7757 +0.3939 -0.2956 5.7830 +0.4050 -0.3016 5.7903 +0.4162 -0.3076 5.7976 +0.4274 -0.3135 5.8049 +0.4387 -0.3193 5.8122 +0.4500 -0.3250 5.8195 +primID: 3 +startangle_c: 14 +endpose_c: 13 -18 13 +additionalactioncostmult: 2 +turning_radius: -1.7327 +intermediateposes: 45 +0.0000 0.0000 5.4978 +0.0089 -0.0090 5.4905 +0.0178 -0.0180 5.4832 +0.0266 -0.0271 5.4758 +0.0353 -0.0363 5.4685 +0.0440 -0.0456 5.4612 +0.0526 -0.0549 5.4539 +0.0612 -0.0642 5.4466 +0.0696 -0.0737 5.4393 +0.0780 -0.0832 5.4320 +0.0863 -0.0927 5.4247 +0.0946 -0.1023 5.4173 +0.1028 -0.1120 5.4100 +0.1109 -0.1217 5.4027 +0.1189 -0.1315 5.3954 +0.1269 -0.1414 5.3881 +0.1348 -0.1513 5.3808 +0.1426 -0.1612 5.3735 +0.1504 -0.1713 5.3662 +0.1581 -0.1813 5.3588 +0.1657 -0.1915 5.3515 +0.1732 -0.2017 5.3442 +0.1807 -0.2119 5.3369 +0.1880 -0.2222 5.3296 +0.1953 -0.2326 5.3223 +0.2026 -0.2430 5.3150 +0.2097 -0.2534 5.3077 +0.2168 -0.2639 5.3003 +0.2238 -0.2745 5.2930 +0.2307 -0.2851 5.2857 +0.2376 -0.2958 5.2784 +0.2443 -0.3065 5.2711 +0.2510 -0.3172 5.2638 +0.2576 -0.3281 5.2565 +0.2641 -0.3389 5.2492 +0.2706 -0.3498 5.2418 +0.2770 -0.3608 5.2345 +0.2833 -0.3718 5.2272 +0.2895 -0.3828 5.2199 +0.2956 -0.3939 5.2126 +0.3016 -0.4050 5.2053 +0.3076 -0.4162 5.1980 +0.3135 -0.4274 5.1907 +0.3193 -0.4387 5.1833 +0.3250 -0.4500 5.1760 +primID: 4 +startangle_c: 14 +endpose_c: 0 0 15 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 6 +0.0000 0.0000 5.4978 +0.0000 0.0000 5.5621 +0.0000 0.0000 5.6265 +0.0000 0.0000 5.6908 +0.0000 0.0000 5.7552 +0.0000 0.0000 5.8195 +primID: 5 +startangle_c: 14 +endpose_c: -1 1 14 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 3 +0.0000 0.0000 5.4978 +-0.0125 0.0125 5.4978 +-0.0250 0.0250 5.4978 +primID: 6 +startangle_c: 14 +endpose_c: -16 16 14 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 46 +0.0000 0.0000 5.4978 +-0.0089 0.0089 5.4978 +-0.0178 0.0178 5.4978 +-0.0267 0.0267 5.4978 +-0.0356 0.0356 5.4978 +-0.0444 0.0444 5.4978 +-0.0533 0.0533 5.4978 +-0.0622 0.0622 5.4978 +-0.0711 0.0711 5.4978 +-0.0800 0.0800 5.4978 +-0.0889 0.0889 5.4978 +-0.0978 0.0978 5.4978 +-0.1067 0.1067 5.4978 +-0.1156 0.1156 5.4978 +-0.1244 0.1244 5.4978 +-0.1333 0.1333 5.4978 +-0.1422 0.1422 5.4978 +-0.1511 0.1511 5.4978 +-0.1600 0.1600 5.4978 +-0.1689 0.1689 5.4978 +-0.1778 0.1778 5.4978 +-0.1867 0.1867 5.4978 +-0.1956 0.1956 5.4978 +-0.2044 0.2044 5.4978 +-0.2133 0.2133 5.4978 +-0.2222 0.2222 5.4978 +-0.2311 0.2311 5.4978 +-0.2400 0.2400 5.4978 +-0.2489 0.2489 5.4978 +-0.2578 0.2578 5.4978 +-0.2667 0.2667 5.4978 +-0.2756 0.2756 5.4978 +-0.2844 0.2844 5.4978 +-0.2933 0.2933 5.4978 +-0.3022 0.3022 5.4978 +-0.3111 0.3111 5.4978 +-0.3200 0.3200 5.4978 +-0.3289 0.3289 5.4978 +-0.3378 0.3378 5.4978 +-0.3467 0.3467 5.4978 +-0.3556 0.3556 5.4978 +-0.3644 0.3644 5.4978 +-0.3733 0.3733 5.4978 +-0.3822 0.3822 5.4978 +-0.3911 0.3911 5.4978 +-0.4000 0.4000 5.4978 +primID: 7 +startangle_c: 14 +endpose_c: -18 13 15 +additionalactioncostmult: 3 +turning_radius: -1.7327 +intermediateposes: 45 +0.0000 0.0000 5.4978 +-0.0090 0.0089 5.5051 +-0.0180 0.0178 5.5124 +-0.0271 0.0266 5.5197 +-0.0363 0.0353 5.5270 +-0.0456 0.0440 5.5343 +-0.0549 0.0526 5.5417 +-0.0642 0.0612 5.5490 +-0.0737 0.0696 5.5563 +-0.0832 0.0780 5.5636 +-0.0927 0.0863 5.5709 +-0.1023 0.0946 5.5782 +-0.1120 0.1028 5.5855 +-0.1217 0.1109 5.5928 +-0.1315 0.1189 5.6002 +-0.1414 0.1269 5.6075 +-0.1513 0.1348 5.6148 +-0.1612 0.1426 5.6221 +-0.1713 0.1504 5.6294 +-0.1813 0.1581 5.6367 +-0.1915 0.1657 5.6440 +-0.2017 0.1732 5.6513 +-0.2119 0.1807 5.6587 +-0.2222 0.1880 5.6660 +-0.2326 0.1953 5.6733 +-0.2430 0.2026 5.6806 +-0.2534 0.2097 5.6879 +-0.2639 0.2168 5.6952 +-0.2745 0.2238 5.7025 +-0.2851 0.2307 5.7099 +-0.2958 0.2376 5.7172 +-0.3065 0.2443 5.7245 +-0.3172 0.2510 5.7318 +-0.3281 0.2576 5.7391 +-0.3389 0.2641 5.7464 +-0.3498 0.2706 5.7537 +-0.3608 0.2770 5.7610 +-0.3718 0.2833 5.7684 +-0.3828 0.2895 5.7757 +-0.3939 0.2956 5.7830 +-0.4050 0.3016 5.7903 +-0.4162 0.3076 5.7976 +-0.4274 0.3135 5.8049 +-0.4387 0.3193 5.8122 +-0.4500 0.3250 5.8195 +primID: 8 +startangle_c: 14 +endpose_c: -13 18 13 +additionalactioncostmult: 3 +turning_radius: 1.7327 +intermediateposes: 45 +0.0000 0.0000 5.4978 +-0.0089 0.0090 5.4905 +-0.0178 0.0180 5.4832 +-0.0266 0.0271 5.4758 +-0.0353 0.0363 5.4685 +-0.0440 0.0456 5.4612 +-0.0526 0.0549 5.4539 +-0.0612 0.0642 5.4466 +-0.0696 0.0737 5.4393 +-0.0780 0.0832 5.4320 +-0.0863 0.0927 5.4247 +-0.0946 0.1023 5.4173 +-0.1028 0.1120 5.4100 +-0.1109 0.1217 5.4027 +-0.1189 0.1315 5.3954 +-0.1269 0.1414 5.3881 +-0.1348 0.1513 5.3808 +-0.1426 0.1612 5.3735 +-0.1504 0.1713 5.3662 +-0.1581 0.1813 5.3588 +-0.1657 0.1915 5.3515 +-0.1732 0.2017 5.3442 +-0.1807 0.2119 5.3369 +-0.1880 0.2222 5.3296 +-0.1953 0.2326 5.3223 +-0.2026 0.2430 5.3150 +-0.2097 0.2534 5.3077 +-0.2168 0.2639 5.3003 +-0.2238 0.2745 5.2930 +-0.2307 0.2851 5.2857 +-0.2376 0.2958 5.2784 +-0.2443 0.3065 5.2711 +-0.2510 0.3172 5.2638 +-0.2576 0.3281 5.2565 +-0.2641 0.3389 5.2492 +-0.2706 0.3498 5.2418 +-0.2770 0.3608 5.2345 +-0.2833 0.3718 5.2272 +-0.2895 0.3828 5.2199 +-0.2956 0.3939 5.2126 +-0.3016 0.4050 5.2053 +-0.3076 0.4162 5.1980 +-0.3135 0.4274 5.1907 +-0.3193 0.4387 5.1833 +-0.3250 0.4500 5.1760 +primID: 9 +startangle_c: 14 +endpose_c: 0 0 13 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 6 +0.0000 0.0000 5.4978 +0.0000 0.0000 5.4334 +0.0000 0.0000 5.3691 +0.0000 0.0000 5.3047 +0.0000 0.0000 5.2404 +0.0000 0.0000 5.1760 +primID: 0 +startangle_c: 15 +endpose_c: 2 -1 15 +additionalactioncostmult: 1 +turning_radius: -0.0000 +intermediateposes: 5 +0.0000 0.0000 5.8195 +0.0125 -0.0063 5.8195 +0.0250 -0.0125 5.8195 +0.0375 -0.0188 5.8195 +0.0500 -0.0250 5.8195 +primID: 1 +startangle_c: 15 +endpose_c: 20 -10 15 +additionalactioncostmult: 1 +turning_radius: -0.0000 +intermediateposes: 45 +0.0000 0.0000 5.8195 +0.0114 -0.0057 5.8195 +0.0227 -0.0114 5.8195 +0.0341 -0.0170 5.8195 +0.0455 -0.0227 5.8195 +0.0568 -0.0284 5.8195 +0.0682 -0.0341 5.8195 +0.0795 -0.0398 5.8195 +0.0909 -0.0455 5.8195 +0.1023 -0.0511 5.8195 +0.1136 -0.0568 5.8195 +0.1250 -0.0625 5.8195 +0.1364 -0.0682 5.8195 +0.1477 -0.0739 5.8195 +0.1591 -0.0795 5.8195 +0.1705 -0.0852 5.8195 +0.1818 -0.0909 5.8195 +0.1932 -0.0966 5.8195 +0.2045 -0.1023 5.8195 +0.2159 -0.1080 5.8195 +0.2273 -0.1136 5.8195 +0.2386 -0.1193 5.8195 +0.2500 -0.1250 5.8195 +0.2614 -0.1307 5.8195 +0.2727 -0.1364 5.8195 +0.2841 -0.1420 5.8195 +0.2955 -0.1477 5.8195 +0.3068 -0.1534 5.8195 +0.3182 -0.1591 5.8195 +0.3295 -0.1648 5.8195 +0.3409 -0.1705 5.8195 +0.3523 -0.1761 5.8195 +0.3636 -0.1818 5.8195 +0.3750 -0.1875 5.8195 +0.3864 -0.1932 5.8195 +0.3977 -0.1989 5.8195 +0.4091 -0.2045 5.8195 +0.4205 -0.2102 5.8195 +0.4318 -0.2159 5.8195 +0.4432 -0.2216 5.8195 +0.4545 -0.2273 5.8195 +0.4659 -0.2330 5.8195 +0.4773 -0.2386 5.8195 +0.4886 -0.2443 5.8195 +0.5000 -0.2500 5.8195 +primID: 2 +startangle_c: 15 +endpose_c: 18 -13 14 +additionalactioncostmult: 2 +turning_radius: -1.7327 +intermediateposes: 45 +0.0000 0.0000 5.8195 +0.0113 -0.0057 5.8122 +0.0226 -0.0115 5.8049 +0.0338 -0.0174 5.7976 +0.0450 -0.0234 5.7903 +0.0561 -0.0294 5.7830 +0.0672 -0.0355 5.7757 +0.0782 -0.0417 5.7684 +0.0892 -0.0480 5.7610 +0.1002 -0.0544 5.7537 +0.1111 -0.0609 5.7464 +0.1219 -0.0674 5.7391 +0.1328 -0.0740 5.7318 +0.1435 -0.0807 5.7245 +0.1542 -0.0874 5.7172 +0.1649 -0.0943 5.7099 +0.1755 -0.1012 5.7025 +0.1861 -0.1082 5.6952 +0.1966 -0.1153 5.6879 +0.2070 -0.1224 5.6806 +0.2174 -0.1297 5.6733 +0.2278 -0.1370 5.6660 +0.2381 -0.1443 5.6587 +0.2483 -0.1518 5.6513 +0.2585 -0.1593 5.6440 +0.2687 -0.1669 5.6367 +0.2787 -0.1746 5.6294 +0.2888 -0.1824 5.6221 +0.2987 -0.1902 5.6148 +0.3086 -0.1981 5.6075 +0.3185 -0.2061 5.6002 +0.3283 -0.2141 5.5928 +0.3380 -0.2222 5.5855 +0.3477 -0.2304 5.5782 +0.3573 -0.2387 5.5709 +0.3668 -0.2470 5.5636 +0.3763 -0.2554 5.5563 +0.3858 -0.2638 5.5490 +0.3951 -0.2724 5.5417 +0.4044 -0.2810 5.5343 +0.4137 -0.2897 5.5270 +0.4229 -0.2984 5.5197 +0.4320 -0.3072 5.5124 +0.4410 -0.3161 5.5051 +0.4500 -0.3250 5.4978 +primID: 3 +startangle_c: 15 +endpose_c: 21 -5 0 +additionalactioncostmult: 2 +turning_radius: 1.1745 +intermediateposes: 44 +0.0000 0.0000 5.8195 +0.0114 -0.0056 5.8303 +0.0228 -0.0111 5.8411 +0.0342 -0.0165 5.8519 +0.0458 -0.0218 5.8627 +0.0573 -0.0269 5.8735 +0.0690 -0.0319 5.8842 +0.0807 -0.0368 5.8950 +0.0924 -0.0415 5.9058 +0.1042 -0.0462 5.9166 +0.1160 -0.0507 5.9274 +0.1279 -0.0550 5.9381 +0.1399 -0.0593 5.9489 +0.1518 -0.0634 5.9597 +0.1639 -0.0674 5.9705 +0.1759 -0.0712 5.9813 +0.1880 -0.0749 5.9921 +0.2002 -0.0785 6.0028 +0.2124 -0.0820 6.0136 +0.2246 -0.0853 6.0244 +0.2368 -0.0885 6.0352 +0.2491 -0.0916 6.0460 +0.2614 -0.0945 6.0568 +0.2738 -0.0973 6.0675 +0.2862 -0.1000 6.0783 +0.2986 -0.1025 6.0891 +0.3110 -0.1049 6.0999 +0.3235 -0.1072 6.1107 +0.3360 -0.1093 6.1214 +0.3485 -0.1113 6.1322 +0.3610 -0.1132 6.1430 +0.3735 -0.1149 6.1538 +0.3861 -0.1165 6.1646 +0.3987 -0.1179 6.1754 +0.4113 -0.1193 6.1861 +0.4239 -0.1204 6.1969 +0.4365 -0.1215 6.2077 +0.4491 -0.1224 6.2185 +0.4617 -0.1232 6.2293 +0.4744 -0.1238 6.2401 +0.4870 -0.1243 6.2508 +0.4997 -0.1247 6.2616 +0.5123 -0.1249 6.2724 +0.5250 -0.1250 6.2832 +primID: 4 +startangle_c: 15 +endpose_c: 0 0 14 +additionalactioncostmult: 5 +turning_radius: -0.0000 +intermediateposes: 6 +0.0000 0.0000 5.8195 +0.0000 0.0000 5.7552 +0.0000 0.0000 5.6908 +0.0000 0.0000 5.6265 +0.0000 0.0000 5.5621 +0.0000 0.0000 5.4978 +primID: 5 +startangle_c: 15 +endpose_c: -2 1 15 +additionalactioncostmult: 5 +turning_radius: -0.0000 +intermediateposes: 5 +0.0000 0.0000 5.8195 +-0.0125 0.0063 5.8195 +-0.0250 0.0125 5.8195 +-0.0375 0.0188 5.8195 +-0.0500 0.0250 5.8195 +primID: 6 +startangle_c: 15 +endpose_c: -20 10 15 +additionalactioncostmult: 5 +turning_radius: -0.0000 +intermediateposes: 45 +0.0000 0.0000 5.8195 +-0.0114 0.0057 5.8195 +-0.0227 0.0114 5.8195 +-0.0341 0.0170 5.8195 +-0.0455 0.0227 5.8195 +-0.0568 0.0284 5.8195 +-0.0682 0.0341 5.8195 +-0.0795 0.0398 5.8195 +-0.0909 0.0455 5.8195 +-0.1023 0.0511 5.8195 +-0.1136 0.0568 5.8195 +-0.1250 0.0625 5.8195 +-0.1364 0.0682 5.8195 +-0.1477 0.0739 5.8195 +-0.1591 0.0795 5.8195 +-0.1705 0.0852 5.8195 +-0.1818 0.0909 5.8195 +-0.1932 0.0966 5.8195 +-0.2045 0.1023 5.8195 +-0.2159 0.1080 5.8195 +-0.2273 0.1136 5.8195 +-0.2386 0.1193 5.8195 +-0.2500 0.1250 5.8195 +-0.2614 0.1307 5.8195 +-0.2727 0.1364 5.8195 +-0.2841 0.1420 5.8195 +-0.2955 0.1477 5.8195 +-0.3068 0.1534 5.8195 +-0.3182 0.1591 5.8195 +-0.3295 0.1648 5.8195 +-0.3409 0.1705 5.8195 +-0.3523 0.1761 5.8195 +-0.3636 0.1818 5.8195 +-0.3750 0.1875 5.8195 +-0.3864 0.1932 5.8195 +-0.3977 0.1989 5.8195 +-0.4091 0.2045 5.8195 +-0.4205 0.2102 5.8195 +-0.4318 0.2159 5.8195 +-0.4432 0.2216 5.8195 +-0.4545 0.2273 5.8195 +-0.4659 0.2330 5.8195 +-0.4773 0.2386 5.8195 +-0.4886 0.2443 5.8195 +-0.5000 0.2500 5.8195 +primID: 7 +startangle_c: 15 +endpose_c: -18 13 14 +additionalactioncostmult: 3 +turning_radius: 1.7327 +intermediateposes: 45 +0.0000 0.0000 5.8195 +-0.0113 0.0057 5.8122 +-0.0226 0.0115 5.8049 +-0.0338 0.0174 5.7976 +-0.0450 0.0234 5.7903 +-0.0561 0.0294 5.7830 +-0.0672 0.0355 5.7757 +-0.0782 0.0417 5.7684 +-0.0892 0.0480 5.7610 +-0.1002 0.0544 5.7537 +-0.1111 0.0609 5.7464 +-0.1219 0.0674 5.7391 +-0.1328 0.0740 5.7318 +-0.1435 0.0807 5.7245 +-0.1542 0.0874 5.7172 +-0.1649 0.0943 5.7099 +-0.1755 0.1012 5.7025 +-0.1861 0.1082 5.6952 +-0.1966 0.1153 5.6879 +-0.2070 0.1224 5.6806 +-0.2174 0.1297 5.6733 +-0.2278 0.1370 5.6660 +-0.2381 0.1443 5.6587 +-0.2483 0.1518 5.6513 +-0.2585 0.1593 5.6440 +-0.2687 0.1669 5.6367 +-0.2787 0.1746 5.6294 +-0.2888 0.1824 5.6221 +-0.2987 0.1902 5.6148 +-0.3086 0.1981 5.6075 +-0.3185 0.2061 5.6002 +-0.3283 0.2141 5.5928 +-0.3380 0.2222 5.5855 +-0.3477 0.2304 5.5782 +-0.3573 0.2387 5.5709 +-0.3668 0.2470 5.5636 +-0.3763 0.2554 5.5563 +-0.3858 0.2638 5.5490 +-0.3951 0.2724 5.5417 +-0.4044 0.2810 5.5343 +-0.4137 0.2897 5.5270 +-0.4229 0.2984 5.5197 +-0.4320 0.3072 5.5124 +-0.4410 0.3161 5.5051 +-0.4500 0.3250 5.4978 +primID: 8 +startangle_c: 15 +endpose_c: -21 5 0 +additionalactioncostmult: 3 +turning_radius: -1.1745 +intermediateposes: 44 +0.0000 0.0000 5.8195 +-0.0114 0.0056 5.8303 +-0.0228 0.0111 5.8411 +-0.0342 0.0165 5.8519 +-0.0458 0.0218 5.8627 +-0.0573 0.0269 5.8735 +-0.0690 0.0319 5.8842 +-0.0807 0.0368 5.8950 +-0.0924 0.0415 5.9058 +-0.1042 0.0462 5.9166 +-0.1160 0.0507 5.9274 +-0.1279 0.0550 5.9381 +-0.1399 0.0593 5.9489 +-0.1518 0.0634 5.9597 +-0.1639 0.0674 5.9705 +-0.1759 0.0712 5.9813 +-0.1880 0.0749 5.9921 +-0.2002 0.0785 6.0028 +-0.2124 0.0820 6.0136 +-0.2246 0.0853 6.0244 +-0.2368 0.0885 6.0352 +-0.2491 0.0916 6.0460 +-0.2614 0.0945 6.0568 +-0.2738 0.0973 6.0675 +-0.2862 0.1000 6.0783 +-0.2986 0.1025 6.0891 +-0.3110 0.1049 6.0999 +-0.3235 0.1072 6.1107 +-0.3360 0.1093 6.1214 +-0.3485 0.1113 6.1322 +-0.3610 0.1132 6.1430 +-0.3735 0.1149 6.1538 +-0.3861 0.1165 6.1646 +-0.3987 0.1179 6.1754 +-0.4113 0.1193 6.1861 +-0.4239 0.1204 6.1969 +-0.4365 0.1215 6.2077 +-0.4491 0.1224 6.2185 +-0.4617 0.1232 6.2293 +-0.4744 0.1238 6.2401 +-0.4870 0.1243 6.2508 +-0.4997 0.1247 6.2616 +-0.5123 0.1249 6.2724 +-0.5250 0.1250 6.2832 +primID: 9 +startangle_c: 15 +endpose_c: 0 0 0 +additionalactioncostmult: 5 +turning_radius: -0.0000 +intermediateposes: 116 +0.0000 0.0000 5.8195 +0.0000 0.0000 5.8236 +0.0000 0.0000 5.8276 +0.0000 0.0000 5.8316 +0.0000 0.0000 5.8357 +0.0000 0.0000 5.8397 +0.0000 0.0000 5.8437 +0.0000 0.0000 5.8478 +0.0000 0.0000 5.8518 +0.0000 0.0000 5.8558 +0.0000 0.0000 5.8599 +0.0000 0.0000 5.8639 +0.0000 0.0000 5.8679 +0.0000 0.0000 5.8720 +0.0000 0.0000 5.8760 +0.0000 0.0000 5.8800 +0.0000 0.0000 5.8840 +0.0000 0.0000 5.8881 +0.0000 0.0000 5.8921 +0.0000 0.0000 5.8961 +0.0000 0.0000 5.9002 +0.0000 0.0000 5.9042 +0.0000 0.0000 5.9082 +0.0000 0.0000 5.9123 +0.0000 0.0000 5.9163 +0.0000 0.0000 5.9203 +0.0000 0.0000 5.9244 +0.0000 0.0000 5.9284 +0.0000 0.0000 5.9324 +0.0000 0.0000 5.9365 +0.0000 0.0000 5.9405 +0.0000 0.0000 5.9445 +0.0000 0.0000 5.9486 +0.0000 0.0000 5.9526 +0.0000 0.0000 5.9566 +0.0000 0.0000 5.9606 +0.0000 0.0000 5.9647 +0.0000 0.0000 5.9687 +0.0000 0.0000 5.9727 +0.0000 0.0000 5.9768 +0.0000 0.0000 5.9808 +0.0000 0.0000 5.9848 +0.0000 0.0000 5.9889 +0.0000 0.0000 5.9929 +0.0000 0.0000 5.9969 +0.0000 0.0000 6.0010 +0.0000 0.0000 6.0050 +0.0000 0.0000 6.0090 +0.0000 0.0000 6.0131 +0.0000 0.0000 6.0171 +0.0000 0.0000 6.0211 +0.0000 0.0000 6.0252 +0.0000 0.0000 6.0292 +0.0000 0.0000 6.0332 +0.0000 0.0000 6.0373 +0.0000 0.0000 6.0413 +0.0000 0.0000 6.0453 +0.0000 0.0000 6.0493 +0.0000 0.0000 6.0534 +0.0000 0.0000 6.0574 +0.0000 0.0000 6.0614 +0.0000 0.0000 6.0655 +0.0000 0.0000 6.0695 +0.0000 0.0000 6.0735 +0.0000 0.0000 6.0776 +0.0000 0.0000 6.0816 +0.0000 0.0000 6.0856 +0.0000 0.0000 6.0897 +0.0000 0.0000 6.0937 +0.0000 0.0000 6.0977 +0.0000 0.0000 6.1018 +0.0000 0.0000 6.1058 +0.0000 0.0000 6.1098 +0.0000 0.0000 6.1139 +0.0000 0.0000 6.1179 +0.0000 0.0000 6.1219 +0.0000 0.0000 6.1259 +0.0000 0.0000 6.1300 +0.0000 0.0000 6.1340 +0.0000 0.0000 6.1380 +0.0000 0.0000 6.1421 +0.0000 0.0000 6.1461 +0.0000 0.0000 6.1501 +0.0000 0.0000 6.1542 +0.0000 0.0000 6.1582 +0.0000 0.0000 6.1622 +0.0000 0.0000 6.1663 +0.0000 0.0000 6.1703 +0.0000 0.0000 6.1743 +0.0000 0.0000 6.1784 +0.0000 0.0000 6.1824 +0.0000 0.0000 6.1864 +0.0000 0.0000 6.1905 +0.0000 0.0000 6.1945 +0.0000 0.0000 6.1985 +0.0000 0.0000 6.2026 +0.0000 0.0000 6.2066 +0.0000 0.0000 6.2106 +0.0000 0.0000 6.2146 +0.0000 0.0000 6.2187 +0.0000 0.0000 6.2227 +0.0000 0.0000 6.2267 +0.0000 0.0000 6.2308 +0.0000 0.0000 6.2348 +0.0000 0.0000 6.2388 +0.0000 0.0000 6.2429 +0.0000 0.0000 6.2469 +0.0000 0.0000 6.2509 +0.0000 0.0000 6.2550 +0.0000 0.0000 6.2590 +0.0000 0.0000 6.2630 +0.0000 0.0000 6.2671 +0.0000 0.0000 6.2711 +0.0000 0.0000 6.2751 +0.0000 0.0000 6.2792 +0.0000 0.0000 6.2832 diff --git a/navigations/sbpl/matlab/mprim/non_uniform_res01_rad3_err005.mprim b/navigations/sbpl/matlab/mprim/non_uniform_res01_rad3_err005.mprim new file mode 100755 index 0000000..943d45f --- /dev/null +++ b/navigations/sbpl/matlab/mprim/non_uniform_res01_rad3_err005.mprim @@ -0,0 +1,5307 @@ +resolution_m: 0.100000 +min_turning_radius_m: 3.000000 +numberofangles: 16 +angle:0 0.00000000 +angle:1 0.46364761 +angle:2 0.78539816 +angle:3 1.10714872 +angle:4 1.57079633 +angle:5 2.03444394 +angle:6 2.35619449 +angle:7 2.67794504 +angle:8 3.14159265 +angle:9 3.60524026 +angle:10 3.92699082 +angle:11 4.24874137 +angle:12 4.71238898 +angle:13 5.17603659 +angle:14 5.49778714 +angle:15 5.81953770 +totalnumberofprimitives: 160 +primID: 0 +startangle_c: 0 +endpose_c: 1 0 0 +additionalactioncostmult: 1 +turning_radius: 0.0000 +intermediateposes: 3 +0.0000 0.0000 0.0000 +0.0500 0.0000 0.0000 +0.1000 0.0000 0.0000 +primID: 1 +startangle_c: 0 +endpose_c: 17 0 0 +additionalactioncostmult: 1 +turning_radius: 0.0000 +intermediateposes: 35 +0.0000 0.0000 0.0000 +0.0500 0.0000 0.0000 +0.1000 0.0000 0.0000 +0.1500 0.0000 0.0000 +0.2000 0.0000 0.0000 +0.2500 0.0000 0.0000 +0.3000 0.0000 0.0000 +0.3500 0.0000 0.0000 +0.4000 0.0000 0.0000 +0.4500 0.0000 0.0000 +0.5000 0.0000 0.0000 +0.5500 0.0000 0.0000 +0.6000 0.0000 0.0000 +0.6500 0.0000 0.0000 +0.7000 0.0000 0.0000 +0.7500 0.0000 0.0000 +0.8000 0.0000 0.0000 +0.8500 0.0000 0.0000 +0.9000 0.0000 0.0000 +0.9500 0.0000 0.0000 +1.0000 0.0000 0.0000 +1.0500 0.0000 0.0000 +1.1000 0.0000 0.0000 +1.1500 0.0000 0.0000 +1.2000 0.0000 0.0000 +1.2500 0.0000 0.0000 +1.3000 0.0000 0.0000 +1.3500 0.0000 0.0000 +1.4000 0.0000 0.0000 +1.4500 0.0000 0.0000 +1.5000 0.0000 0.0000 +1.5500 0.0000 0.0000 +1.6000 0.0000 0.0000 +1.6500 0.0000 0.0000 +1.7000 0.0000 0.0000 +primID: 2 +startangle_c: 0 +endpose_c: 17 4 1 +additionalactioncostmult: 2 +turning_radius: 3.8007 +intermediateposes: 35 +0.0000 0.0000 0.0000 +0.0518 0.0003 0.0136 +0.1037 0.0013 0.0273 +0.1555 0.0031 0.0409 +0.2072 0.0055 0.0545 +0.2590 0.0086 0.0682 +0.3107 0.0125 0.0818 +0.3623 0.0170 0.0955 +0.4139 0.0223 0.1091 +0.4654 0.0283 0.1227 +0.5168 0.0349 0.1364 +0.5681 0.0423 0.1500 +0.6193 0.0503 0.1636 +0.6704 0.0591 0.1773 +0.7213 0.0685 0.1909 +0.7721 0.0787 0.2046 +0.8228 0.0895 0.2182 +0.8734 0.1010 0.2318 +0.9237 0.1133 0.2455 +0.9739 0.1262 0.2591 +1.0239 0.1397 0.2727 +1.0738 0.1540 0.2864 +1.1234 0.1690 0.3000 +1.1728 0.1846 0.3136 +1.2220 0.2009 0.3273 +1.2710 0.2178 0.3409 +1.3197 0.2354 0.3546 +1.3682 0.2537 0.3682 +1.4164 0.2727 0.3818 +1.4644 0.2923 0.3955 +1.5121 0.3125 0.4091 +1.5595 0.3334 0.4227 +1.6066 0.3550 0.4364 +1.6535 0.3772 0.4500 +1.7000 0.4000 0.4636 +primID: 3 +startangle_c: 0 +endpose_c: 17 -4 -1 +additionalactioncostmult: 2 +turning_radius: -3.8007 +intermediateposes: 35 +0.0000 0.0000 0.0000 +0.0518 -0.0003 -0.0136 +0.1037 -0.0013 -0.0273 +0.1555 -0.0031 -0.0409 +0.2072 -0.0055 -0.0545 +0.2590 -0.0086 -0.0682 +0.3107 -0.0125 -0.0818 +0.3623 -0.0170 -0.0955 +0.4139 -0.0223 -0.1091 +0.4654 -0.0283 -0.1227 +0.5168 -0.0349 -0.1364 +0.5681 -0.0423 -0.1500 +0.6193 -0.0503 -0.1636 +0.6704 -0.0591 -0.1773 +0.7213 -0.0685 -0.1909 +0.7721 -0.0787 -0.2046 +0.8228 -0.0895 -0.2182 +0.8734 -0.1010 -0.2318 +0.9237 -0.1133 -0.2455 +0.9739 -0.1262 -0.2591 +1.0239 -0.1397 -0.2727 +1.0738 -0.1540 -0.2864 +1.1234 -0.1690 -0.3000 +1.1728 -0.1846 -0.3136 +1.2220 -0.2009 -0.3273 +1.2710 -0.2178 -0.3409 +1.3197 -0.2354 -0.3546 +1.3682 -0.2537 -0.3682 +1.4164 -0.2727 -0.3818 +1.4644 -0.2923 -0.3955 +1.5121 -0.3125 -0.4091 +1.5595 -0.3334 -0.4227 +1.6066 -0.3550 -0.4364 +1.6535 -0.3772 -0.4500 +1.7000 -0.4000 -0.4636 +primID: 4 +startangle_c: 0 +endpose_c: 0 0 1 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 9 +0.0000 0.0000 0.0000 +0.0000 0.0000 0.0580 +0.0000 0.0000 0.1159 +0.0000 0.0000 0.1739 +0.0000 0.0000 0.2318 +0.0000 0.0000 0.2898 +0.0000 0.0000 0.3477 +0.0000 0.0000 0.4057 +0.0000 0.0000 0.4636 +primID: 5 +startangle_c: 0 +endpose_c: -1 0 0 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 3 +0.0000 0.0000 0.0000 +-0.0500 0.0000 0.0000 +-0.1000 0.0000 0.0000 +primID: 6 +startangle_c: 0 +endpose_c: -17 0 0 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 35 +0.0000 0.0000 0.0000 +-0.0500 0.0000 0.0000 +-0.1000 0.0000 0.0000 +-0.1500 0.0000 0.0000 +-0.2000 0.0000 0.0000 +-0.2500 0.0000 0.0000 +-0.3000 0.0000 0.0000 +-0.3500 0.0000 0.0000 +-0.4000 0.0000 0.0000 +-0.4500 0.0000 0.0000 +-0.5000 0.0000 0.0000 +-0.5500 0.0000 0.0000 +-0.6000 0.0000 0.0000 +-0.6500 0.0000 0.0000 +-0.7000 0.0000 0.0000 +-0.7500 0.0000 0.0000 +-0.8000 0.0000 0.0000 +-0.8500 0.0000 0.0000 +-0.9000 0.0000 0.0000 +-0.9500 0.0000 0.0000 +-1.0000 0.0000 0.0000 +-1.0500 0.0000 0.0000 +-1.1000 0.0000 0.0000 +-1.1500 0.0000 0.0000 +-1.2000 0.0000 0.0000 +-1.2500 0.0000 0.0000 +-1.3000 0.0000 0.0000 +-1.3500 0.0000 0.0000 +-1.4000 0.0000 0.0000 +-1.4500 0.0000 0.0000 +-1.5000 0.0000 0.0000 +-1.5500 0.0000 0.0000 +-1.6000 0.0000 0.0000 +-1.6500 0.0000 0.0000 +-1.7000 0.0000 0.0000 +primID: 7 +startangle_c: 0 +endpose_c: -17 -4 1 +additionalactioncostmult: 3 +turning_radius: -3.8007 +intermediateposes: 35 +0.0000 0.0000 0.0000 +-0.0518 -0.0003 0.0136 +-0.1037 -0.0013 0.0273 +-0.1555 -0.0031 0.0409 +-0.2072 -0.0055 0.0545 +-0.2590 -0.0086 0.0682 +-0.3107 -0.0125 0.0818 +-0.3623 -0.0170 0.0955 +-0.4139 -0.0223 0.1091 +-0.4654 -0.0283 0.1227 +-0.5168 -0.0349 0.1364 +-0.5681 -0.0423 0.1500 +-0.6193 -0.0503 0.1636 +-0.6704 -0.0591 0.1773 +-0.7213 -0.0685 0.1909 +-0.7721 -0.0787 0.2046 +-0.8228 -0.0895 0.2182 +-0.8734 -0.1010 0.2318 +-0.9237 -0.1133 0.2455 +-0.9739 -0.1262 0.2591 +-1.0239 -0.1397 0.2727 +-1.0738 -0.1540 0.2864 +-1.1234 -0.1690 0.3000 +-1.1728 -0.1846 0.3136 +-1.2220 -0.2009 0.3273 +-1.2710 -0.2178 0.3409 +-1.3197 -0.2354 0.3546 +-1.3682 -0.2537 0.3682 +-1.4164 -0.2727 0.3818 +-1.4644 -0.2923 0.3955 +-1.5121 -0.3125 0.4091 +-1.5595 -0.3334 0.4227 +-1.6066 -0.3550 0.4364 +-1.6535 -0.3772 0.4500 +-1.7000 -0.4000 0.4636 +primID: 8 +startangle_c: 0 +endpose_c: -17 4 -1 +additionalactioncostmult: 3 +turning_radius: 3.8007 +intermediateposes: 35 +0.0000 0.0000 0.0000 +-0.0518 0.0003 -0.0136 +-0.1037 0.0013 -0.0273 +-0.1555 0.0031 -0.0409 +-0.2072 0.0055 -0.0545 +-0.2590 0.0086 -0.0682 +-0.3107 0.0125 -0.0818 +-0.3623 0.0170 -0.0955 +-0.4139 0.0223 -0.1091 +-0.4654 0.0283 -0.1227 +-0.5168 0.0349 -0.1364 +-0.5681 0.0423 -0.1500 +-0.6193 0.0503 -0.1636 +-0.6704 0.0591 -0.1773 +-0.7213 0.0685 -0.1909 +-0.7721 0.0787 -0.2046 +-0.8228 0.0895 -0.2182 +-0.8734 0.1010 -0.2318 +-0.9237 0.1133 -0.2455 +-0.9739 0.1262 -0.2591 +-1.0239 0.1397 -0.2727 +-1.0738 0.1540 -0.2864 +-1.1234 0.1690 -0.3000 +-1.1728 0.1846 -0.3136 +-1.2220 0.2009 -0.3273 +-1.2710 0.2178 -0.3409 +-1.3197 0.2354 -0.3546 +-1.3682 0.2537 -0.3682 +-1.4164 0.2727 -0.3818 +-1.4644 0.2923 -0.3955 +-1.5121 0.3125 -0.4091 +-1.5595 0.3334 -0.4227 +-1.6066 0.3550 -0.4364 +-1.6535 0.3772 -0.4500 +-1.7000 0.4000 -0.4636 +primID: 9 +startangle_c: 0 +endpose_c: 0 0 -1 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 9 +0.0000 0.0000 0.0000 +0.0000 0.0000 -0.0580 +0.0000 0.0000 -0.1159 +0.0000 0.0000 -0.1739 +0.0000 0.0000 -0.2318 +0.0000 0.0000 -0.2898 +0.0000 0.0000 -0.3477 +0.0000 0.0000 -0.4057 +0.0000 0.0000 -0.4636 +primID: 0 +startangle_c: 1 +endpose_c: 2 1 1 +additionalactioncostmult: 1 +turning_radius: 0.0000 +intermediateposes: 5 +0.0000 0.0000 0.4636 +0.0500 0.0250 0.4636 +0.1000 0.0500 0.4636 +0.1500 0.0750 0.4636 +0.2000 0.1000 0.4636 +primID: 1 +startangle_c: 1 +endpose_c: 18 9 1 +additionalactioncostmult: 1 +turning_radius: 0.0000 +intermediateposes: 41 +0.0000 0.0000 0.4636 +0.0450 0.0225 0.4636 +0.0900 0.0450 0.4636 +0.1350 0.0675 0.4636 +0.1800 0.0900 0.4636 +0.2250 0.1125 0.4636 +0.2700 0.1350 0.4636 +0.3150 0.1575 0.4636 +0.3600 0.1800 0.4636 +0.4050 0.2025 0.4636 +0.4500 0.2250 0.4636 +0.4950 0.2475 0.4636 +0.5400 0.2700 0.4636 +0.5850 0.2925 0.4636 +0.6300 0.3150 0.4636 +0.6750 0.3375 0.4636 +0.7200 0.3600 0.4636 +0.7650 0.3825 0.4636 +0.8100 0.4050 0.4636 +0.8550 0.4275 0.4636 +0.9000 0.4500 0.4636 +0.9450 0.4725 0.4636 +0.9900 0.4950 0.4636 +1.0350 0.5175 0.4636 +1.0800 0.5400 0.4636 +1.1250 0.5625 0.4636 +1.1700 0.5850 0.4636 +1.2150 0.6075 0.4636 +1.2600 0.6300 0.4636 +1.3050 0.6525 0.4636 +1.3500 0.6750 0.4636 +1.3950 0.6975 0.4636 +1.4400 0.7200 0.4636 +1.4850 0.7425 0.4636 +1.5300 0.7650 0.4636 +1.5750 0.7875 0.4636 +1.6200 0.8100 0.4636 +1.6650 0.8325 0.4636 +1.7100 0.8550 0.4636 +1.7550 0.8775 0.4636 +1.8000 0.9000 0.4636 +primID: 2 +startangle_c: 1 +endpose_c: 18 13 2 +additionalactioncostmult: 2 +turning_radius: 6.9307 +intermediateposes: 45 +0.0000 0.0000 0.4636 +0.0452 0.0229 0.4710 +0.0903 0.0461 0.4783 +0.1351 0.0696 0.4856 +0.1799 0.0935 0.4929 +0.2244 0.1176 0.5002 +0.2687 0.1421 0.5075 +0.3129 0.1670 0.5148 +0.3569 0.1921 0.5221 +0.4007 0.2176 0.5295 +0.4443 0.2434 0.5368 +0.4878 0.2695 0.5441 +0.5310 0.2960 0.5514 +0.5740 0.3227 0.5587 +0.6169 0.3498 0.5660 +0.6595 0.3771 0.5733 +0.7020 0.4048 0.5806 +0.7442 0.4328 0.5880 +0.7863 0.4611 0.5953 +0.8281 0.4897 0.6026 +0.8697 0.5187 0.6099 +0.9111 0.5479 0.6172 +0.9523 0.5774 0.6245 +0.9933 0.6072 0.6318 +1.0341 0.6373 0.6391 +1.0746 0.6678 0.6465 +1.1149 0.6985 0.6538 +1.1550 0.7295 0.6611 +1.1949 0.7608 0.6684 +1.2345 0.7924 0.6757 +1.2739 0.8243 0.6830 +1.3131 0.8564 0.6903 +1.3520 0.8889 0.6976 +1.3907 0.9216 0.7050 +1.4291 0.9547 0.7123 +1.4673 0.9880 0.7196 +1.5053 1.0215 0.7269 +1.5430 1.0554 0.7342 +1.5805 1.0895 0.7415 +1.6177 1.1239 0.7488 +1.6547 1.1586 0.7561 +1.6914 1.1936 0.7635 +1.7279 1.2288 0.7708 +1.7641 1.2643 0.7781 +1.8000 1.3000 0.7854 +primID: 3 +startangle_c: 1 +endpose_c: 17 4 0 +additionalactioncostmult: 2 +turning_radius: -3.8007 +intermediateposes: 35 +0.0000 0.0000 0.4636 +0.0465 0.0228 0.4500 +0.0934 0.0450 0.4364 +0.1405 0.0666 0.4227 +0.1879 0.0875 0.4091 +0.2356 0.1077 0.3955 +0.2836 0.1273 0.3818 +0.3318 0.1463 0.3682 +0.3803 0.1646 0.3546 +0.4290 0.1822 0.3409 +0.4780 0.1991 0.3273 +0.5272 0.2154 0.3136 +0.5766 0.2310 0.3000 +0.6262 0.2460 0.2864 +0.6761 0.2603 0.2727 +0.7261 0.2738 0.2591 +0.7763 0.2867 0.2455 +0.8266 0.2990 0.2318 +0.8772 0.3105 0.2182 +0.9279 0.3213 0.2046 +0.9787 0.3315 0.1909 +1.0296 0.3409 0.1773 +1.0807 0.3497 0.1636 +1.1319 0.3577 0.1500 +1.1832 0.3651 0.1364 +1.2346 0.3717 0.1227 +1.2861 0.3777 0.1091 +1.3377 0.3830 0.0955 +1.3893 0.3875 0.0818 +1.4410 0.3914 0.0682 +1.4928 0.3945 0.0545 +1.5445 0.3969 0.0409 +1.5963 0.3987 0.0273 +1.6482 0.3997 0.0136 +1.7000 0.4000 0.0000 +primID: 4 +startangle_c: 1 +endpose_c: 0 0 2 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 6 +0.0000 0.0000 0.4636 +0.0000 0.0000 0.5280 +0.0000 0.0000 0.5923 +0.0000 0.0000 0.6567 +0.0000 0.0000 0.7210 +0.0000 0.0000 0.7854 +primID: 5 +startangle_c: 1 +endpose_c: -2 -1 1 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 5 +0.0000 0.0000 0.4636 +-0.0500 -0.0250 0.4636 +-0.1000 -0.0500 0.4636 +-0.1500 -0.0750 0.4636 +-0.2000 -0.1000 0.4636 +primID: 6 +startangle_c: 1 +endpose_c: -18 -9 1 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 41 +0.0000 0.0000 0.4636 +-0.0450 -0.0225 0.4636 +-0.0900 -0.0450 0.4636 +-0.1350 -0.0675 0.4636 +-0.1800 -0.0900 0.4636 +-0.2250 -0.1125 0.4636 +-0.2700 -0.1350 0.4636 +-0.3150 -0.1575 0.4636 +-0.3600 -0.1800 0.4636 +-0.4050 -0.2025 0.4636 +-0.4500 -0.2250 0.4636 +-0.4950 -0.2475 0.4636 +-0.5400 -0.2700 0.4636 +-0.5850 -0.2925 0.4636 +-0.6300 -0.3150 0.4636 +-0.6750 -0.3375 0.4636 +-0.7200 -0.3600 0.4636 +-0.7650 -0.3825 0.4636 +-0.8100 -0.4050 0.4636 +-0.8550 -0.4275 0.4636 +-0.9000 -0.4500 0.4636 +-0.9450 -0.4725 0.4636 +-0.9900 -0.4950 0.4636 +-1.0350 -0.5175 0.4636 +-1.0800 -0.5400 0.4636 +-1.1250 -0.5625 0.4636 +-1.1700 -0.5850 0.4636 +-1.2150 -0.6075 0.4636 +-1.2600 -0.6300 0.4636 +-1.3050 -0.6525 0.4636 +-1.3500 -0.6750 0.4636 +-1.3950 -0.6975 0.4636 +-1.4400 -0.7200 0.4636 +-1.4850 -0.7425 0.4636 +-1.5300 -0.7650 0.4636 +-1.5750 -0.7875 0.4636 +-1.6200 -0.8100 0.4636 +-1.6650 -0.8325 0.4636 +-1.7100 -0.8550 0.4636 +-1.7550 -0.8775 0.4636 +-1.8000 -0.9000 0.4636 +primID: 7 +startangle_c: 1 +endpose_c: -18 -13 2 +additionalactioncostmult: 3 +turning_radius: -6.9307 +intermediateposes: 45 +0.0000 0.0000 0.4636 +-0.0452 -0.0229 0.4710 +-0.0903 -0.0461 0.4783 +-0.1351 -0.0696 0.4856 +-0.1799 -0.0935 0.4929 +-0.2244 -0.1176 0.5002 +-0.2687 -0.1421 0.5075 +-0.3129 -0.1670 0.5148 +-0.3569 -0.1921 0.5221 +-0.4007 -0.2176 0.5295 +-0.4443 -0.2434 0.5368 +-0.4878 -0.2695 0.5441 +-0.5310 -0.2960 0.5514 +-0.5740 -0.3227 0.5587 +-0.6169 -0.3498 0.5660 +-0.6595 -0.3771 0.5733 +-0.7020 -0.4048 0.5806 +-0.7442 -0.4328 0.5880 +-0.7863 -0.4611 0.5953 +-0.8281 -0.4897 0.6026 +-0.8697 -0.5187 0.6099 +-0.9111 -0.5479 0.6172 +-0.9523 -0.5774 0.6245 +-0.9933 -0.6072 0.6318 +-1.0341 -0.6373 0.6391 +-1.0746 -0.6678 0.6465 +-1.1149 -0.6985 0.6538 +-1.1550 -0.7295 0.6611 +-1.1949 -0.7608 0.6684 +-1.2345 -0.7924 0.6757 +-1.2739 -0.8243 0.6830 +-1.3131 -0.8564 0.6903 +-1.3520 -0.8889 0.6976 +-1.3907 -0.9216 0.7050 +-1.4291 -0.9547 0.7123 +-1.4673 -0.9880 0.7196 +-1.5053 -1.0215 0.7269 +-1.5430 -1.0554 0.7342 +-1.5805 -1.0895 0.7415 +-1.6177 -1.1239 0.7488 +-1.6547 -1.1586 0.7561 +-1.6914 -1.1936 0.7635 +-1.7279 -1.2288 0.7708 +-1.7641 -1.2643 0.7781 +-1.8000 -1.3000 0.7854 +primID: 8 +startangle_c: 1 +endpose_c: -17 -4 0 +additionalactioncostmult: 3 +turning_radius: 3.8007 +intermediateposes: 35 +0.0000 0.0000 0.4636 +-0.0465 -0.0228 0.4500 +-0.0934 -0.0450 0.4364 +-0.1405 -0.0666 0.4227 +-0.1879 -0.0875 0.4091 +-0.2356 -0.1077 0.3955 +-0.2836 -0.1273 0.3818 +-0.3318 -0.1463 0.3682 +-0.3803 -0.1646 0.3546 +-0.4290 -0.1822 0.3409 +-0.4780 -0.1991 0.3273 +-0.5272 -0.2154 0.3136 +-0.5766 -0.2310 0.3000 +-0.6262 -0.2460 0.2864 +-0.6761 -0.2603 0.2727 +-0.7261 -0.2738 0.2591 +-0.7763 -0.2867 0.2455 +-0.8266 -0.2990 0.2318 +-0.8772 -0.3105 0.2182 +-0.9279 -0.3213 0.2046 +-0.9787 -0.3315 0.1909 +-1.0296 -0.3409 0.1773 +-1.0807 -0.3497 0.1636 +-1.1319 -0.3577 0.1500 +-1.1832 -0.3651 0.1364 +-1.2346 -0.3717 0.1227 +-1.2861 -0.3777 0.1091 +-1.3377 -0.3830 0.0955 +-1.3893 -0.3875 0.0818 +-1.4410 -0.3914 0.0682 +-1.4928 -0.3945 0.0545 +-1.5445 -0.3969 0.0409 +-1.5963 -0.3987 0.0273 +-1.6482 -0.3997 0.0136 +-1.7000 -0.4000 0.0000 +primID: 9 +startangle_c: 1 +endpose_c: 0 0 0 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 9 +0.0000 0.0000 0.4636 +0.0000 0.0000 0.4057 +0.0000 0.0000 0.3477 +0.0000 0.0000 0.2898 +0.0000 0.0000 0.2318 +0.0000 0.0000 0.1739 +0.0000 0.0000 0.1159 +0.0000 0.0000 0.0580 +0.0000 0.0000 0.0000 +primID: 0 +startangle_c: 2 +endpose_c: 1 1 2 +additionalactioncostmult: 1 +turning_radius: 0.0000 +intermediateposes: 3 +0.0000 0.0000 0.7854 +0.0500 0.0500 0.7854 +0.1000 0.1000 0.7854 +primID: 1 +startangle_c: 2 +endpose_c: 15 15 2 +additionalactioncostmult: 1 +turning_radius: 0.0000 +intermediateposes: 43 +0.0000 0.0000 0.7854 +0.0357 0.0357 0.7854 +0.0714 0.0714 0.7854 +0.1071 0.1071 0.7854 +0.1429 0.1429 0.7854 +0.1786 0.1786 0.7854 +0.2143 0.2143 0.7854 +0.2500 0.2500 0.7854 +0.2857 0.2857 0.7854 +0.3214 0.3214 0.7854 +0.3571 0.3571 0.7854 +0.3929 0.3929 0.7854 +0.4286 0.4286 0.7854 +0.4643 0.4643 0.7854 +0.5000 0.5000 0.7854 +0.5357 0.5357 0.7854 +0.5714 0.5714 0.7854 +0.6071 0.6071 0.7854 +0.6429 0.6429 0.7854 +0.6786 0.6786 0.7854 +0.7143 0.7143 0.7854 +0.7500 0.7500 0.7854 +0.7857 0.7857 0.7854 +0.8214 0.8214 0.7854 +0.8571 0.8571 0.7854 +0.8929 0.8929 0.7854 +0.9286 0.9286 0.7854 +0.9643 0.9643 0.7854 +1.0000 1.0000 0.7854 +1.0357 1.0357 0.7854 +1.0714 1.0714 0.7854 +1.1071 1.1071 0.7854 +1.1429 1.1429 0.7854 +1.1786 1.1786 0.7854 +1.2143 1.2143 0.7854 +1.2500 1.2500 0.7854 +1.2857 1.2857 0.7854 +1.3214 1.3214 0.7854 +1.3571 1.3571 0.7854 +1.3929 1.3929 0.7854 +1.4286 1.4286 0.7854 +1.4643 1.4643 0.7854 +1.5000 1.5000 0.7854 +primID: 2 +startangle_c: 2 +endpose_c: 13 18 3 +additionalactioncostmult: 2 +turning_radius: 6.9307 +intermediateposes: 45 +0.0000 0.0000 0.7854 +0.0357 0.0359 0.7927 +0.0712 0.0721 0.8000 +0.1064 0.1086 0.8073 +0.1414 0.1453 0.8146 +0.1761 0.1823 0.8220 +0.2105 0.2195 0.8293 +0.2446 0.2570 0.8366 +0.2785 0.2947 0.8439 +0.3120 0.3327 0.8512 +0.3453 0.3709 0.8585 +0.3784 0.4093 0.8658 +0.4111 0.4480 0.8731 +0.4436 0.4869 0.8805 +0.4757 0.5261 0.8878 +0.5076 0.5655 0.8951 +0.5392 0.6051 0.9024 +0.5705 0.6450 0.9097 +0.6015 0.6851 0.9170 +0.6322 0.7254 0.9243 +0.6627 0.7659 0.9316 +0.6928 0.8067 0.9390 +0.7226 0.8477 0.9463 +0.7521 0.8889 0.9536 +0.7813 0.9303 0.9609 +0.8103 0.9719 0.9682 +0.8389 1.0137 0.9755 +0.8672 1.0558 0.9828 +0.8952 1.0980 0.9901 +0.9229 1.1405 0.9975 +0.9502 1.1831 1.0048 +0.9773 1.2260 1.0121 +1.0040 1.2690 1.0194 +1.0305 1.3122 1.0267 +1.0566 1.3557 1.0340 +1.0824 1.3993 1.0413 +1.1079 1.4431 1.0486 +1.1330 1.4871 1.0560 +1.1579 1.5313 1.0633 +1.1824 1.5756 1.0706 +1.2065 1.6201 1.0779 +1.2304 1.6649 1.0852 +1.2539 1.7097 1.0925 +1.2771 1.7548 1.0998 +1.3000 1.8000 1.1071 +primID: 3 +startangle_c: 2 +endpose_c: 18 13 1 +additionalactioncostmult: 2 +turning_radius: -6.9307 +intermediateposes: 45 +0.0000 0.0000 0.7854 +0.0359 0.0357 0.7781 +0.0721 0.0712 0.7708 +0.1086 0.1064 0.7635 +0.1453 0.1414 0.7561 +0.1823 0.1761 0.7488 +0.2195 0.2105 0.7415 +0.2570 0.2446 0.7342 +0.2947 0.2785 0.7269 +0.3327 0.3120 0.7196 +0.3709 0.3453 0.7123 +0.4093 0.3784 0.7050 +0.4480 0.4111 0.6976 +0.4869 0.4436 0.6903 +0.5261 0.4757 0.6830 +0.5655 0.5076 0.6757 +0.6051 0.5392 0.6684 +0.6450 0.5705 0.6611 +0.6851 0.6015 0.6538 +0.7254 0.6322 0.6465 +0.7659 0.6627 0.6391 +0.8067 0.6928 0.6318 +0.8477 0.7226 0.6245 +0.8889 0.7521 0.6172 +0.9303 0.7813 0.6099 +0.9719 0.8103 0.6026 +1.0137 0.8389 0.5953 +1.0558 0.8672 0.5880 +1.0980 0.8952 0.5806 +1.1405 0.9229 0.5733 +1.1831 0.9502 0.5660 +1.2260 0.9773 0.5587 +1.2690 1.0040 0.5514 +1.3122 1.0305 0.5441 +1.3557 1.0566 0.5368 +1.3993 1.0824 0.5295 +1.4431 1.1079 0.5221 +1.4871 1.1330 0.5148 +1.5313 1.1579 0.5075 +1.5756 1.1824 0.5002 +1.6201 1.2065 0.4929 +1.6649 1.2304 0.4856 +1.7097 1.2539 0.4783 +1.7548 1.2771 0.4710 +1.8000 1.3000 0.4636 +primID: 4 +startangle_c: 2 +endpose_c: 0 0 3 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 6 +0.0000 0.0000 0.7854 +0.0000 0.0000 0.8497 +0.0000 0.0000 0.9141 +0.0000 0.0000 0.9784 +0.0000 0.0000 1.0428 +0.0000 0.0000 1.1071 +primID: 5 +startangle_c: 2 +endpose_c: -1 -1 2 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 3 +0.0000 0.0000 0.7854 +-0.0500 -0.0500 0.7854 +-0.1000 -0.1000 0.7854 +primID: 6 +startangle_c: 2 +endpose_c: -16 -16 2 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 46 +0.0000 0.0000 0.7854 +-0.0356 -0.0356 0.7854 +-0.0711 -0.0711 0.7854 +-0.1067 -0.1067 0.7854 +-0.1422 -0.1422 0.7854 +-0.1778 -0.1778 0.7854 +-0.2133 -0.2133 0.7854 +-0.2489 -0.2489 0.7854 +-0.2844 -0.2844 0.7854 +-0.3200 -0.3200 0.7854 +-0.3556 -0.3556 0.7854 +-0.3911 -0.3911 0.7854 +-0.4267 -0.4267 0.7854 +-0.4622 -0.4622 0.7854 +-0.4978 -0.4978 0.7854 +-0.5333 -0.5333 0.7854 +-0.5689 -0.5689 0.7854 +-0.6044 -0.6044 0.7854 +-0.6400 -0.6400 0.7854 +-0.6756 -0.6756 0.7854 +-0.7111 -0.7111 0.7854 +-0.7467 -0.7467 0.7854 +-0.7822 -0.7822 0.7854 +-0.8178 -0.8178 0.7854 +-0.8533 -0.8533 0.7854 +-0.8889 -0.8889 0.7854 +-0.9244 -0.9244 0.7854 +-0.9600 -0.9600 0.7854 +-0.9956 -0.9956 0.7854 +-1.0311 -1.0311 0.7854 +-1.0667 -1.0667 0.7854 +-1.1022 -1.1022 0.7854 +-1.1378 -1.1378 0.7854 +-1.1733 -1.1733 0.7854 +-1.2089 -1.2089 0.7854 +-1.2444 -1.2444 0.7854 +-1.2800 -1.2800 0.7854 +-1.3156 -1.3156 0.7854 +-1.3511 -1.3511 0.7854 +-1.3867 -1.3867 0.7854 +-1.4222 -1.4222 0.7854 +-1.4578 -1.4578 0.7854 +-1.4933 -1.4933 0.7854 +-1.5289 -1.5289 0.7854 +-1.5644 -1.5644 0.7854 +-1.6000 -1.6000 0.7854 +primID: 7 +startangle_c: 2 +endpose_c: -13 -18 3 +additionalactioncostmult: 3 +turning_radius: -6.9307 +intermediateposes: 45 +0.0000 0.0000 0.7854 +-0.0357 -0.0359 0.7927 +-0.0712 -0.0721 0.8000 +-0.1064 -0.1086 0.8073 +-0.1414 -0.1453 0.8146 +-0.1761 -0.1823 0.8220 +-0.2105 -0.2195 0.8293 +-0.2446 -0.2570 0.8366 +-0.2785 -0.2947 0.8439 +-0.3120 -0.3327 0.8512 +-0.3453 -0.3709 0.8585 +-0.3784 -0.4093 0.8658 +-0.4111 -0.4480 0.8731 +-0.4436 -0.4869 0.8805 +-0.4757 -0.5261 0.8878 +-0.5076 -0.5655 0.8951 +-0.5392 -0.6051 0.9024 +-0.5705 -0.6450 0.9097 +-0.6015 -0.6851 0.9170 +-0.6322 -0.7254 0.9243 +-0.6627 -0.7659 0.9316 +-0.6928 -0.8067 0.9390 +-0.7226 -0.8477 0.9463 +-0.7521 -0.8889 0.9536 +-0.7813 -0.9303 0.9609 +-0.8103 -0.9719 0.9682 +-0.8389 -1.0137 0.9755 +-0.8672 -1.0558 0.9828 +-0.8952 -1.0980 0.9901 +-0.9229 -1.1405 0.9975 +-0.9502 -1.1831 1.0048 +-0.9773 -1.2260 1.0121 +-1.0040 -1.2690 1.0194 +-1.0305 -1.3122 1.0267 +-1.0566 -1.3557 1.0340 +-1.0824 -1.3993 1.0413 +-1.1079 -1.4431 1.0486 +-1.1330 -1.4871 1.0560 +-1.1579 -1.5313 1.0633 +-1.1824 -1.5756 1.0706 +-1.2065 -1.6201 1.0779 +-1.2304 -1.6649 1.0852 +-1.2539 -1.7097 1.0925 +-1.2771 -1.7548 1.0998 +-1.3000 -1.8000 1.1071 +primID: 8 +startangle_c: 2 +endpose_c: -18 -13 1 +additionalactioncostmult: 3 +turning_radius: 6.9307 +intermediateposes: 45 +0.0000 0.0000 0.7854 +-0.0359 -0.0357 0.7781 +-0.0721 -0.0712 0.7708 +-0.1086 -0.1064 0.7635 +-0.1453 -0.1414 0.7561 +-0.1823 -0.1761 0.7488 +-0.2195 -0.2105 0.7415 +-0.2570 -0.2446 0.7342 +-0.2947 -0.2785 0.7269 +-0.3327 -0.3120 0.7196 +-0.3709 -0.3453 0.7123 +-0.4093 -0.3784 0.7050 +-0.4480 -0.4111 0.6976 +-0.4869 -0.4436 0.6903 +-0.5261 -0.4757 0.6830 +-0.5655 -0.5076 0.6757 +-0.6051 -0.5392 0.6684 +-0.6450 -0.5705 0.6611 +-0.6851 -0.6015 0.6538 +-0.7254 -0.6322 0.6465 +-0.7659 -0.6627 0.6391 +-0.8067 -0.6928 0.6318 +-0.8477 -0.7226 0.6245 +-0.8889 -0.7521 0.6172 +-0.9303 -0.7813 0.6099 +-0.9719 -0.8103 0.6026 +-1.0137 -0.8389 0.5953 +-1.0558 -0.8672 0.5880 +-1.0980 -0.8952 0.5806 +-1.1405 -0.9229 0.5733 +-1.1831 -0.9502 0.5660 +-1.2260 -0.9773 0.5587 +-1.2690 -1.0040 0.5514 +-1.3122 -1.0305 0.5441 +-1.3557 -1.0566 0.5368 +-1.3993 -1.0824 0.5295 +-1.4431 -1.1079 0.5221 +-1.4871 -1.1330 0.5148 +-1.5313 -1.1579 0.5075 +-1.5756 -1.1824 0.5002 +-1.6201 -1.2065 0.4929 +-1.6649 -1.2304 0.4856 +-1.7097 -1.2539 0.4783 +-1.7548 -1.2771 0.4710 +-1.8000 -1.3000 0.4636 +primID: 9 +startangle_c: 2 +endpose_c: 0 0 1 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 6 +0.0000 0.0000 0.7854 +0.0000 0.0000 0.7210 +0.0000 0.0000 0.6567 +0.0000 0.0000 0.5923 +0.0000 0.0000 0.5280 +0.0000 0.0000 0.4636 +primID: 0 +startangle_c: 3 +endpose_c: 1 2 3 +additionalactioncostmult: 1 +turning_radius: -0.0000 +intermediateposes: 5 +0.0000 0.0000 1.1071 +0.0250 0.0500 1.1071 +0.0500 0.1000 1.1071 +0.0750 0.1500 1.1071 +0.1000 0.2000 1.1071 +primID: 1 +startangle_c: 3 +endpose_c: 9 18 3 +additionalactioncostmult: 1 +turning_radius: -0.0000 +intermediateposes: 41 +0.0000 0.0000 1.1071 +0.0225 0.0450 1.1071 +0.0450 0.0900 1.1071 +0.0675 0.1350 1.1071 +0.0900 0.1800 1.1071 +0.1125 0.2250 1.1071 +0.1350 0.2700 1.1071 +0.1575 0.3150 1.1071 +0.1800 0.3600 1.1071 +0.2025 0.4050 1.1071 +0.2250 0.4500 1.1071 +0.2475 0.4950 1.1071 +0.2700 0.5400 1.1071 +0.2925 0.5850 1.1071 +0.3150 0.6300 1.1071 +0.3375 0.6750 1.1071 +0.3600 0.7200 1.1071 +0.3825 0.7650 1.1071 +0.4050 0.8100 1.1071 +0.4275 0.8550 1.1071 +0.4500 0.9000 1.1071 +0.4725 0.9450 1.1071 +0.4950 0.9900 1.1071 +0.5175 1.0350 1.1071 +0.5400 1.0800 1.1071 +0.5625 1.1250 1.1071 +0.5850 1.1700 1.1071 +0.6075 1.2150 1.1071 +0.6300 1.2600 1.1071 +0.6525 1.3050 1.1071 +0.6750 1.3500 1.1071 +0.6975 1.3950 1.1071 +0.7200 1.4400 1.1071 +0.7425 1.4850 1.1071 +0.7650 1.5300 1.1071 +0.7875 1.5750 1.1071 +0.8100 1.6200 1.1071 +0.8325 1.6650 1.1071 +0.8550 1.7100 1.1071 +0.8775 1.7550 1.1071 +0.9000 1.8000 1.1071 +primID: 2 +startangle_c: 3 +endpose_c: 13 18 2 +additionalactioncostmult: 2 +turning_radius: -6.9307 +intermediateposes: 45 +0.0000 0.0000 1.1071 +0.0229 0.0452 1.0998 +0.0461 0.0903 1.0925 +0.0696 0.1351 1.0852 +0.0935 0.1799 1.0779 +0.1176 0.2244 1.0706 +0.1421 0.2687 1.0633 +0.1670 0.3129 1.0560 +0.1921 0.3569 1.0486 +0.2176 0.4007 1.0413 +0.2434 0.4443 1.0340 +0.2695 0.4878 1.0267 +0.2960 0.5310 1.0194 +0.3227 0.5740 1.0121 +0.3498 0.6169 1.0048 +0.3771 0.6595 0.9975 +0.4048 0.7020 0.9901 +0.4328 0.7442 0.9828 +0.4611 0.7863 0.9755 +0.4897 0.8281 0.9682 +0.5187 0.8697 0.9609 +0.5479 0.9111 0.9536 +0.5774 0.9523 0.9463 +0.6072 0.9933 0.9390 +0.6373 1.0341 0.9316 +0.6678 1.0746 0.9243 +0.6985 1.1149 0.9170 +0.7295 1.1550 0.9097 +0.7608 1.1949 0.9024 +0.7924 1.2345 0.8951 +0.8243 1.2739 0.8878 +0.8564 1.3131 0.8805 +0.8889 1.3520 0.8731 +0.9216 1.3907 0.8658 +0.9547 1.4291 0.8585 +0.9880 1.4673 0.8512 +1.0215 1.5053 0.8439 +1.0554 1.5430 0.8366 +1.0895 1.5805 0.8293 +1.1239 1.6177 0.8220 +1.1586 1.6547 0.8146 +1.1936 1.6914 0.8073 +1.2288 1.7279 0.8000 +1.2643 1.7641 0.7927 +1.3000 1.8000 0.7854 +primID: 3 +startangle_c: 3 +endpose_c: 4 17 4 +additionalactioncostmult: 2 +turning_radius: 3.8007 +intermediateposes: 35 +0.0000 0.0000 1.1071 +0.0228 0.0465 1.1208 +0.0450 0.0934 1.1344 +0.0666 0.1405 1.1481 +0.0875 0.1879 1.1617 +0.1077 0.2356 1.1753 +0.1273 0.2836 1.1890 +0.1463 0.3318 1.2026 +0.1646 0.3803 1.2162 +0.1822 0.4290 1.2299 +0.1991 0.4780 1.2435 +0.2154 0.5272 1.2572 +0.2310 0.5766 1.2708 +0.2460 0.6262 1.2844 +0.2603 0.6761 1.2981 +0.2738 0.7261 1.3117 +0.2867 0.7763 1.3253 +0.2990 0.8266 1.3390 +0.3105 0.8772 1.3526 +0.3213 0.9279 1.3662 +0.3315 0.9787 1.3799 +0.3409 1.0296 1.3935 +0.3497 1.0807 1.4072 +0.3577 1.1319 1.4208 +0.3651 1.1832 1.4344 +0.3717 1.2346 1.4481 +0.3777 1.2861 1.4617 +0.3830 1.3377 1.4753 +0.3875 1.3893 1.4890 +0.3914 1.4410 1.5026 +0.3945 1.4928 1.5162 +0.3969 1.5445 1.5299 +0.3987 1.5963 1.5435 +0.3997 1.6482 1.5572 +0.4000 1.7000 1.5708 +primID: 4 +startangle_c: 3 +endpose_c: 0 0 2 +additionalactioncostmult: 5 +turning_radius: -0.0000 +intermediateposes: 6 +0.0000 0.0000 1.1071 +0.0000 0.0000 1.0428 +0.0000 0.0000 0.9784 +0.0000 0.0000 0.9141 +0.0000 0.0000 0.8497 +0.0000 0.0000 0.7854 +primID: 5 +startangle_c: 3 +endpose_c: -1 -2 3 +additionalactioncostmult: 5 +turning_radius: -0.0000 +intermediateposes: 5 +0.0000 0.0000 1.1071 +-0.0250 -0.0500 1.1071 +-0.0500 -0.1000 1.1071 +-0.0750 -0.1500 1.1071 +-0.1000 -0.2000 1.1071 +primID: 6 +startangle_c: 3 +endpose_c: -9 -18 3 +additionalactioncostmult: 5 +turning_radius: -0.0000 +intermediateposes: 41 +0.0000 0.0000 1.1071 +-0.0225 -0.0450 1.1071 +-0.0450 -0.0900 1.1071 +-0.0675 -0.1350 1.1071 +-0.0900 -0.1800 1.1071 +-0.1125 -0.2250 1.1071 +-0.1350 -0.2700 1.1071 +-0.1575 -0.3150 1.1071 +-0.1800 -0.3600 1.1071 +-0.2025 -0.4050 1.1071 +-0.2250 -0.4500 1.1071 +-0.2475 -0.4950 1.1071 +-0.2700 -0.5400 1.1071 +-0.2925 -0.5850 1.1071 +-0.3150 -0.6300 1.1071 +-0.3375 -0.6750 1.1071 +-0.3600 -0.7200 1.1071 +-0.3825 -0.7650 1.1071 +-0.4050 -0.8100 1.1071 +-0.4275 -0.8550 1.1071 +-0.4500 -0.9000 1.1071 +-0.4725 -0.9450 1.1071 +-0.4950 -0.9900 1.1071 +-0.5175 -1.0350 1.1071 +-0.5400 -1.0800 1.1071 +-0.5625 -1.1250 1.1071 +-0.5850 -1.1700 1.1071 +-0.6075 -1.2150 1.1071 +-0.6300 -1.2600 1.1071 +-0.6525 -1.3050 1.1071 +-0.6750 -1.3500 1.1071 +-0.6975 -1.3950 1.1071 +-0.7200 -1.4400 1.1071 +-0.7425 -1.4850 1.1071 +-0.7650 -1.5300 1.1071 +-0.7875 -1.5750 1.1071 +-0.8100 -1.6200 1.1071 +-0.8325 -1.6650 1.1071 +-0.8550 -1.7100 1.1071 +-0.8775 -1.7550 1.1071 +-0.9000 -1.8000 1.1071 +primID: 7 +startangle_c: 3 +endpose_c: -13 -18 2 +additionalactioncostmult: 3 +turning_radius: 6.9307 +intermediateposes: 45 +0.0000 0.0000 1.1071 +-0.0229 -0.0452 1.0998 +-0.0461 -0.0903 1.0925 +-0.0696 -0.1351 1.0852 +-0.0935 -0.1799 1.0779 +-0.1176 -0.2244 1.0706 +-0.1421 -0.2687 1.0633 +-0.1670 -0.3129 1.0560 +-0.1921 -0.3569 1.0486 +-0.2176 -0.4007 1.0413 +-0.2434 -0.4443 1.0340 +-0.2695 -0.4878 1.0267 +-0.2960 -0.5310 1.0194 +-0.3227 -0.5740 1.0121 +-0.3498 -0.6169 1.0048 +-0.3771 -0.6595 0.9975 +-0.4048 -0.7020 0.9901 +-0.4328 -0.7442 0.9828 +-0.4611 -0.7863 0.9755 +-0.4897 -0.8281 0.9682 +-0.5187 -0.8697 0.9609 +-0.5479 -0.9111 0.9536 +-0.5774 -0.9523 0.9463 +-0.6072 -0.9933 0.9390 +-0.6373 -1.0341 0.9316 +-0.6678 -1.0746 0.9243 +-0.6985 -1.1149 0.9170 +-0.7295 -1.1550 0.9097 +-0.7608 -1.1949 0.9024 +-0.7924 -1.2345 0.8951 +-0.8243 -1.2739 0.8878 +-0.8564 -1.3131 0.8805 +-0.8889 -1.3520 0.8731 +-0.9216 -1.3907 0.8658 +-0.9547 -1.4291 0.8585 +-0.9880 -1.4673 0.8512 +-1.0215 -1.5053 0.8439 +-1.0554 -1.5430 0.8366 +-1.0895 -1.5805 0.8293 +-1.1239 -1.6177 0.8220 +-1.1586 -1.6547 0.8146 +-1.1936 -1.6914 0.8073 +-1.2288 -1.7279 0.8000 +-1.2643 -1.7641 0.7927 +-1.3000 -1.8000 0.7854 +primID: 8 +startangle_c: 3 +endpose_c: -4 -17 4 +additionalactioncostmult: 3 +turning_radius: -3.8007 +intermediateposes: 35 +0.0000 0.0000 1.1071 +-0.0228 -0.0465 1.1208 +-0.0450 -0.0934 1.1344 +-0.0666 -0.1405 1.1481 +-0.0875 -0.1879 1.1617 +-0.1077 -0.2356 1.1753 +-0.1273 -0.2836 1.1890 +-0.1463 -0.3318 1.2026 +-0.1646 -0.3803 1.2162 +-0.1822 -0.4290 1.2299 +-0.1991 -0.4780 1.2435 +-0.2154 -0.5272 1.2572 +-0.2310 -0.5766 1.2708 +-0.2460 -0.6262 1.2844 +-0.2603 -0.6761 1.2981 +-0.2738 -0.7261 1.3117 +-0.2867 -0.7763 1.3253 +-0.2990 -0.8266 1.3390 +-0.3105 -0.8772 1.3526 +-0.3213 -0.9279 1.3662 +-0.3315 -0.9787 1.3799 +-0.3409 -1.0296 1.3935 +-0.3497 -1.0807 1.4072 +-0.3577 -1.1319 1.4208 +-0.3651 -1.1832 1.4344 +-0.3717 -1.2346 1.4481 +-0.3777 -1.2861 1.4617 +-0.3830 -1.3377 1.4753 +-0.3875 -1.3893 1.4890 +-0.3914 -1.4410 1.5026 +-0.3945 -1.4928 1.5162 +-0.3969 -1.5445 1.5299 +-0.3987 -1.5963 1.5435 +-0.3997 -1.6482 1.5572 +-0.4000 -1.7000 1.5708 +primID: 9 +startangle_c: 3 +endpose_c: 0 0 4 +additionalactioncostmult: 5 +turning_radius: -0.0000 +intermediateposes: 9 +0.0000 0.0000 1.1071 +0.0000 0.0000 1.1651 +0.0000 0.0000 1.2231 +0.0000 0.0000 1.2810 +0.0000 0.0000 1.3390 +0.0000 0.0000 1.3969 +0.0000 0.0000 1.4549 +0.0000 0.0000 1.5128 +0.0000 0.0000 1.5708 +primID: 0 +startangle_c: 4 +endpose_c: 0 1 4 +additionalactioncostmult: 1 +turning_radius: 0.0000 +intermediateposes: 3 +0.0000 0.0000 1.5708 +0.0000 0.0500 1.5708 +0.0000 0.1000 1.5708 +primID: 1 +startangle_c: 4 +endpose_c: 0 17 4 +additionalactioncostmult: 1 +turning_radius: 0.0000 +intermediateposes: 35 +0.0000 0.0000 1.5708 +0.0000 0.0500 1.5708 +0.0000 0.1000 1.5708 +0.0000 0.1500 1.5708 +0.0000 0.2000 1.5708 +0.0000 0.2500 1.5708 +0.0000 0.3000 1.5708 +0.0000 0.3500 1.5708 +0.0000 0.4000 1.5708 +0.0000 0.4500 1.5708 +0.0000 0.5000 1.5708 +0.0000 0.5500 1.5708 +0.0000 0.6000 1.5708 +0.0000 0.6500 1.5708 +0.0000 0.7000 1.5708 +0.0000 0.7500 1.5708 +0.0000 0.8000 1.5708 +0.0000 0.8500 1.5708 +0.0000 0.9000 1.5708 +0.0000 0.9500 1.5708 +0.0000 1.0000 1.5708 +0.0000 1.0500 1.5708 +0.0000 1.1000 1.5708 +0.0000 1.1500 1.5708 +0.0000 1.2000 1.5708 +0.0000 1.2500 1.5708 +0.0000 1.3000 1.5708 +0.0000 1.3500 1.5708 +0.0000 1.4000 1.5708 +0.0000 1.4500 1.5708 +0.0000 1.5000 1.5708 +0.0000 1.5500 1.5708 +0.0000 1.6000 1.5708 +0.0000 1.6500 1.5708 +0.0000 1.7000 1.5708 +primID: 2 +startangle_c: 4 +endpose_c: -4 17 5 +additionalactioncostmult: 2 +turning_radius: 3.8007 +intermediateposes: 35 +0.0000 0.0000 1.5708 +-0.0003 0.0518 1.5844 +-0.0013 0.1037 1.5981 +-0.0031 0.1555 1.6117 +-0.0055 0.2072 1.6253 +-0.0086 0.2590 1.6390 +-0.0125 0.3107 1.6526 +-0.0170 0.3623 1.6663 +-0.0223 0.4139 1.6799 +-0.0283 0.4654 1.6935 +-0.0349 0.5168 1.7072 +-0.0423 0.5681 1.7208 +-0.0503 0.6193 1.7344 +-0.0591 0.6704 1.7481 +-0.0685 0.7213 1.7617 +-0.0787 0.7721 1.7753 +-0.0895 0.8228 1.7890 +-0.1010 0.8734 1.8026 +-0.1133 0.9237 1.8163 +-0.1262 0.9739 1.8299 +-0.1397 1.0239 1.8435 +-0.1540 1.0738 1.8572 +-0.1690 1.1234 1.8708 +-0.1846 1.1728 1.8844 +-0.2009 1.2220 1.8981 +-0.2178 1.2710 1.9117 +-0.2354 1.3197 1.9254 +-0.2537 1.3682 1.9390 +-0.2727 1.4164 1.9526 +-0.2923 1.4644 1.9663 +-0.3125 1.5121 1.9799 +-0.3334 1.5595 1.9935 +-0.3550 1.6066 2.0072 +-0.3772 1.6535 2.0208 +-0.4000 1.7000 2.0344 +primID: 3 +startangle_c: 4 +endpose_c: 4 17 3 +additionalactioncostmult: 2 +turning_radius: -3.8007 +intermediateposes: 35 +0.0000 0.0000 1.5708 +0.0003 0.0518 1.5572 +0.0013 0.1037 1.5435 +0.0031 0.1555 1.5299 +0.0055 0.2072 1.5162 +0.0086 0.2590 1.5026 +0.0125 0.3107 1.4890 +0.0170 0.3623 1.4753 +0.0223 0.4139 1.4617 +0.0283 0.4654 1.4481 +0.0349 0.5168 1.4344 +0.0423 0.5681 1.4208 +0.0503 0.6193 1.4072 +0.0591 0.6704 1.3935 +0.0685 0.7213 1.3799 +0.0787 0.7721 1.3662 +0.0895 0.8228 1.3526 +0.1010 0.8734 1.3390 +0.1133 0.9237 1.3253 +0.1262 0.9739 1.3117 +0.1397 1.0239 1.2981 +0.1540 1.0738 1.2844 +0.1690 1.1234 1.2708 +0.1846 1.1728 1.2572 +0.2009 1.2220 1.2435 +0.2178 1.2710 1.2299 +0.2354 1.3197 1.2162 +0.2537 1.3682 1.2026 +0.2727 1.4164 1.1890 +0.2923 1.4644 1.1753 +0.3125 1.5121 1.1617 +0.3334 1.5595 1.1481 +0.3550 1.6066 1.1344 +0.3772 1.6535 1.1208 +0.4000 1.7000 1.1071 +primID: 4 +startangle_c: 4 +endpose_c: 0 0 5 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 9 +0.0000 0.0000 1.5708 +0.0000 0.0000 1.6288 +0.0000 0.0000 1.6867 +0.0000 0.0000 1.7447 +0.0000 0.0000 1.8026 +0.0000 0.0000 1.8606 +0.0000 0.0000 1.9185 +0.0000 0.0000 1.9765 +0.0000 0.0000 2.0344 +primID: 5 +startangle_c: 4 +endpose_c: 0 -1 4 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 3 +0.0000 0.0000 1.5708 +0.0000 -0.0500 1.5708 +0.0000 -0.1000 1.5708 +primID: 6 +startangle_c: 4 +endpose_c: 0 -17 4 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 35 +0.0000 0.0000 1.5708 +0.0000 -0.0500 1.5708 +0.0000 -0.1000 1.5708 +0.0000 -0.1500 1.5708 +0.0000 -0.2000 1.5708 +0.0000 -0.2500 1.5708 +0.0000 -0.3000 1.5708 +0.0000 -0.3500 1.5708 +0.0000 -0.4000 1.5708 +0.0000 -0.4500 1.5708 +0.0000 -0.5000 1.5708 +0.0000 -0.5500 1.5708 +0.0000 -0.6000 1.5708 +0.0000 -0.6500 1.5708 +0.0000 -0.7000 1.5708 +0.0000 -0.7500 1.5708 +0.0000 -0.8000 1.5708 +0.0000 -0.8500 1.5708 +0.0000 -0.9000 1.5708 +0.0000 -0.9500 1.5708 +0.0000 -1.0000 1.5708 +0.0000 -1.0500 1.5708 +0.0000 -1.1000 1.5708 +0.0000 -1.1500 1.5708 +0.0000 -1.2000 1.5708 +0.0000 -1.2500 1.5708 +0.0000 -1.3000 1.5708 +0.0000 -1.3500 1.5708 +0.0000 -1.4000 1.5708 +0.0000 -1.4500 1.5708 +0.0000 -1.5000 1.5708 +0.0000 -1.5500 1.5708 +0.0000 -1.6000 1.5708 +0.0000 -1.6500 1.5708 +0.0000 -1.7000 1.5708 +primID: 7 +startangle_c: 4 +endpose_c: 4 -17 5 +additionalactioncostmult: 3 +turning_radius: -3.8007 +intermediateposes: 35 +0.0000 0.0000 1.5708 +0.0003 -0.0518 1.5844 +0.0013 -0.1037 1.5981 +0.0031 -0.1555 1.6117 +0.0055 -0.2072 1.6253 +0.0086 -0.2590 1.6390 +0.0125 -0.3107 1.6526 +0.0170 -0.3623 1.6663 +0.0223 -0.4139 1.6799 +0.0283 -0.4654 1.6935 +0.0349 -0.5168 1.7072 +0.0423 -0.5681 1.7208 +0.0503 -0.6193 1.7344 +0.0591 -0.6704 1.7481 +0.0685 -0.7213 1.7617 +0.0787 -0.7721 1.7753 +0.0895 -0.8228 1.7890 +0.1010 -0.8734 1.8026 +0.1133 -0.9237 1.8163 +0.1262 -0.9739 1.8299 +0.1397 -1.0239 1.8435 +0.1540 -1.0738 1.8572 +0.1690 -1.1234 1.8708 +0.1846 -1.1728 1.8844 +0.2009 -1.2220 1.8981 +0.2178 -1.2710 1.9117 +0.2354 -1.3197 1.9254 +0.2537 -1.3682 1.9390 +0.2727 -1.4164 1.9526 +0.2923 -1.4644 1.9663 +0.3125 -1.5121 1.9799 +0.3334 -1.5595 1.9935 +0.3550 -1.6066 2.0072 +0.3772 -1.6535 2.0208 +0.4000 -1.7000 2.0344 +primID: 8 +startangle_c: 4 +endpose_c: -4 -17 3 +additionalactioncostmult: 3 +turning_radius: 3.8007 +intermediateposes: 35 +0.0000 0.0000 1.5708 +-0.0003 -0.0518 1.5572 +-0.0013 -0.1037 1.5435 +-0.0031 -0.1555 1.5299 +-0.0055 -0.2072 1.5162 +-0.0086 -0.2590 1.5026 +-0.0125 -0.3107 1.4890 +-0.0170 -0.3623 1.4753 +-0.0223 -0.4139 1.4617 +-0.0283 -0.4654 1.4481 +-0.0349 -0.5168 1.4344 +-0.0423 -0.5681 1.4208 +-0.0503 -0.6193 1.4072 +-0.0591 -0.6704 1.3935 +-0.0685 -0.7213 1.3799 +-0.0787 -0.7721 1.3662 +-0.0895 -0.8228 1.3526 +-0.1010 -0.8734 1.3390 +-0.1133 -0.9237 1.3253 +-0.1262 -0.9739 1.3117 +-0.1397 -1.0239 1.2981 +-0.1540 -1.0738 1.2844 +-0.1690 -1.1234 1.2708 +-0.1846 -1.1728 1.2572 +-0.2009 -1.2220 1.2435 +-0.2178 -1.2710 1.2299 +-0.2354 -1.3197 1.2162 +-0.2537 -1.3682 1.2026 +-0.2727 -1.4164 1.1890 +-0.2923 -1.4644 1.1753 +-0.3125 -1.5121 1.1617 +-0.3334 -1.5595 1.1481 +-0.3550 -1.6066 1.1344 +-0.3772 -1.6535 1.1208 +-0.4000 -1.7000 1.1071 +primID: 9 +startangle_c: 4 +endpose_c: 0 0 3 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 9 +0.0000 0.0000 1.5708 +0.0000 0.0000 1.5128 +0.0000 0.0000 1.4549 +0.0000 0.0000 1.3969 +0.0000 0.0000 1.3390 +0.0000 0.0000 1.2810 +0.0000 0.0000 1.2231 +0.0000 0.0000 1.1651 +0.0000 0.0000 1.1071 +primID: 0 +startangle_c: 5 +endpose_c: -1 2 5 +additionalactioncostmult: 1 +turning_radius: 0.0000 +intermediateposes: 5 +0.0000 0.0000 2.0344 +-0.0250 0.0500 2.0344 +-0.0500 0.1000 2.0344 +-0.0750 0.1500 2.0344 +-0.1000 0.2000 2.0344 +primID: 1 +startangle_c: 5 +endpose_c: -9 18 5 +additionalactioncostmult: 1 +turning_radius: 0.0000 +intermediateposes: 41 +0.0000 0.0000 2.0344 +-0.0225 0.0450 2.0344 +-0.0450 0.0900 2.0344 +-0.0675 0.1350 2.0344 +-0.0900 0.1800 2.0344 +-0.1125 0.2250 2.0344 +-0.1350 0.2700 2.0344 +-0.1575 0.3150 2.0344 +-0.1800 0.3600 2.0344 +-0.2025 0.4050 2.0344 +-0.2250 0.4500 2.0344 +-0.2475 0.4950 2.0344 +-0.2700 0.5400 2.0344 +-0.2925 0.5850 2.0344 +-0.3150 0.6300 2.0344 +-0.3375 0.6750 2.0344 +-0.3600 0.7200 2.0344 +-0.3825 0.7650 2.0344 +-0.4050 0.8100 2.0344 +-0.4275 0.8550 2.0344 +-0.4500 0.9000 2.0344 +-0.4725 0.9450 2.0344 +-0.4950 0.9900 2.0344 +-0.5175 1.0350 2.0344 +-0.5400 1.0800 2.0344 +-0.5625 1.1250 2.0344 +-0.5850 1.1700 2.0344 +-0.6075 1.2150 2.0344 +-0.6300 1.2600 2.0344 +-0.6525 1.3050 2.0344 +-0.6750 1.3500 2.0344 +-0.6975 1.3950 2.0344 +-0.7200 1.4400 2.0344 +-0.7425 1.4850 2.0344 +-0.7650 1.5300 2.0344 +-0.7875 1.5750 2.0344 +-0.8100 1.6200 2.0344 +-0.8325 1.6650 2.0344 +-0.8550 1.7100 2.0344 +-0.8775 1.7550 2.0344 +-0.9000 1.8000 2.0344 +primID: 2 +startangle_c: 5 +endpose_c: -13 18 6 +additionalactioncostmult: 2 +turning_radius: 6.9307 +intermediateposes: 45 +0.0000 0.0000 2.0344 +-0.0229 0.0452 2.0418 +-0.0461 0.0903 2.0491 +-0.0696 0.1351 2.0564 +-0.0935 0.1799 2.0637 +-0.1176 0.2244 2.0710 +-0.1421 0.2687 2.0783 +-0.1670 0.3129 2.0856 +-0.1921 0.3569 2.0929 +-0.2176 0.4007 2.1003 +-0.2434 0.4443 2.1076 +-0.2695 0.4878 2.1149 +-0.2960 0.5310 2.1222 +-0.3227 0.5740 2.1295 +-0.3498 0.6169 2.1368 +-0.3771 0.6595 2.1441 +-0.4048 0.7020 2.1514 +-0.4328 0.7442 2.1588 +-0.4611 0.7863 2.1661 +-0.4897 0.8281 2.1734 +-0.5187 0.8697 2.1807 +-0.5479 0.9111 2.1880 +-0.5774 0.9523 2.1953 +-0.6072 0.9933 2.2026 +-0.6373 1.0341 2.2099 +-0.6678 1.0746 2.2173 +-0.6985 1.1149 2.2246 +-0.7295 1.1550 2.2319 +-0.7608 1.1949 2.2392 +-0.7924 1.2345 2.2465 +-0.8243 1.2739 2.2538 +-0.8564 1.3131 2.2611 +-0.8889 1.3520 2.2684 +-0.9216 1.3907 2.2758 +-0.9547 1.4291 2.2831 +-0.9880 1.4673 2.2904 +-1.0215 1.5053 2.2977 +-1.0554 1.5430 2.3050 +-1.0895 1.5805 2.3123 +-1.1239 1.6177 2.3196 +-1.1586 1.6547 2.3269 +-1.1936 1.6914 2.3343 +-1.2288 1.7279 2.3416 +-1.2643 1.7641 2.3489 +-1.3000 1.8000 2.3562 +primID: 3 +startangle_c: 5 +endpose_c: -4 17 4 +additionalactioncostmult: 2 +turning_radius: -3.8007 +intermediateposes: 35 +0.0000 0.0000 2.0344 +-0.0228 0.0465 2.0208 +-0.0450 0.0934 2.0072 +-0.0666 0.1405 1.9935 +-0.0875 0.1879 1.9799 +-0.1077 0.2356 1.9663 +-0.1273 0.2836 1.9526 +-0.1463 0.3318 1.9390 +-0.1646 0.3803 1.9254 +-0.1822 0.4290 1.9117 +-0.1991 0.4780 1.8981 +-0.2154 0.5272 1.8844 +-0.2310 0.5766 1.8708 +-0.2460 0.6262 1.8572 +-0.2603 0.6761 1.8435 +-0.2738 0.7261 1.8299 +-0.2867 0.7763 1.8163 +-0.2990 0.8266 1.8026 +-0.3105 0.8772 1.7890 +-0.3213 0.9279 1.7753 +-0.3315 0.9787 1.7617 +-0.3409 1.0296 1.7481 +-0.3497 1.0807 1.7344 +-0.3577 1.1319 1.7208 +-0.3651 1.1832 1.7072 +-0.3717 1.2346 1.6935 +-0.3777 1.2861 1.6799 +-0.3830 1.3377 1.6663 +-0.3875 1.3893 1.6526 +-0.3914 1.4410 1.6390 +-0.3945 1.4928 1.6253 +-0.3969 1.5445 1.6117 +-0.3987 1.5963 1.5981 +-0.3997 1.6482 1.5844 +-0.4000 1.7000 1.5708 +primID: 4 +startangle_c: 5 +endpose_c: 0 0 6 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 6 +0.0000 0.0000 2.0344 +0.0000 0.0000 2.0988 +0.0000 0.0000 2.1631 +0.0000 0.0000 2.2275 +0.0000 0.0000 2.2918 +0.0000 0.0000 2.3562 +primID: 5 +startangle_c: 5 +endpose_c: 1 -2 5 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 5 +0.0000 0.0000 2.0344 +0.0250 -0.0500 2.0344 +0.0500 -0.1000 2.0344 +0.0750 -0.1500 2.0344 +0.1000 -0.2000 2.0344 +primID: 6 +startangle_c: 5 +endpose_c: 9 -18 5 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 41 +0.0000 0.0000 2.0344 +0.0225 -0.0450 2.0344 +0.0450 -0.0900 2.0344 +0.0675 -0.1350 2.0344 +0.0900 -0.1800 2.0344 +0.1125 -0.2250 2.0344 +0.1350 -0.2700 2.0344 +0.1575 -0.3150 2.0344 +0.1800 -0.3600 2.0344 +0.2025 -0.4050 2.0344 +0.2250 -0.4500 2.0344 +0.2475 -0.4950 2.0344 +0.2700 -0.5400 2.0344 +0.2925 -0.5850 2.0344 +0.3150 -0.6300 2.0344 +0.3375 -0.6750 2.0344 +0.3600 -0.7200 2.0344 +0.3825 -0.7650 2.0344 +0.4050 -0.8100 2.0344 +0.4275 -0.8550 2.0344 +0.4500 -0.9000 2.0344 +0.4725 -0.9450 2.0344 +0.4950 -0.9900 2.0344 +0.5175 -1.0350 2.0344 +0.5400 -1.0800 2.0344 +0.5625 -1.1250 2.0344 +0.5850 -1.1700 2.0344 +0.6075 -1.2150 2.0344 +0.6300 -1.2600 2.0344 +0.6525 -1.3050 2.0344 +0.6750 -1.3500 2.0344 +0.6975 -1.3950 2.0344 +0.7200 -1.4400 2.0344 +0.7425 -1.4850 2.0344 +0.7650 -1.5300 2.0344 +0.7875 -1.5750 2.0344 +0.8100 -1.6200 2.0344 +0.8325 -1.6650 2.0344 +0.8550 -1.7100 2.0344 +0.8775 -1.7550 2.0344 +0.9000 -1.8000 2.0344 +primID: 7 +startangle_c: 5 +endpose_c: 13 -18 6 +additionalactioncostmult: 3 +turning_radius: -6.9307 +intermediateposes: 45 +0.0000 0.0000 2.0344 +0.0229 -0.0452 2.0418 +0.0461 -0.0903 2.0491 +0.0696 -0.1351 2.0564 +0.0935 -0.1799 2.0637 +0.1176 -0.2244 2.0710 +0.1421 -0.2687 2.0783 +0.1670 -0.3129 2.0856 +0.1921 -0.3569 2.0929 +0.2176 -0.4007 2.1003 +0.2434 -0.4443 2.1076 +0.2695 -0.4878 2.1149 +0.2960 -0.5310 2.1222 +0.3227 -0.5740 2.1295 +0.3498 -0.6169 2.1368 +0.3771 -0.6595 2.1441 +0.4048 -0.7020 2.1514 +0.4328 -0.7442 2.1588 +0.4611 -0.7863 2.1661 +0.4897 -0.8281 2.1734 +0.5187 -0.8697 2.1807 +0.5479 -0.9111 2.1880 +0.5774 -0.9523 2.1953 +0.6072 -0.9933 2.2026 +0.6373 -1.0341 2.2099 +0.6678 -1.0746 2.2173 +0.6985 -1.1149 2.2246 +0.7295 -1.1550 2.2319 +0.7608 -1.1949 2.2392 +0.7924 -1.2345 2.2465 +0.8243 -1.2739 2.2538 +0.8564 -1.3131 2.2611 +0.8889 -1.3520 2.2684 +0.9216 -1.3907 2.2758 +0.9547 -1.4291 2.2831 +0.9880 -1.4673 2.2904 +1.0215 -1.5053 2.2977 +1.0554 -1.5430 2.3050 +1.0895 -1.5805 2.3123 +1.1239 -1.6177 2.3196 +1.1586 -1.6547 2.3269 +1.1936 -1.6914 2.3343 +1.2288 -1.7279 2.3416 +1.2643 -1.7641 2.3489 +1.3000 -1.8000 2.3562 +primID: 8 +startangle_c: 5 +endpose_c: 4 -17 4 +additionalactioncostmult: 3 +turning_radius: 3.8007 +intermediateposes: 35 +0.0000 0.0000 2.0344 +0.0228 -0.0465 2.0208 +0.0450 -0.0934 2.0072 +0.0666 -0.1405 1.9935 +0.0875 -0.1879 1.9799 +0.1077 -0.2356 1.9663 +0.1273 -0.2836 1.9526 +0.1463 -0.3318 1.9390 +0.1646 -0.3803 1.9254 +0.1822 -0.4290 1.9117 +0.1991 -0.4780 1.8981 +0.2154 -0.5272 1.8844 +0.2310 -0.5766 1.8708 +0.2460 -0.6262 1.8572 +0.2603 -0.6761 1.8435 +0.2738 -0.7261 1.8299 +0.2867 -0.7763 1.8163 +0.2990 -0.8266 1.8026 +0.3105 -0.8772 1.7890 +0.3213 -0.9279 1.7753 +0.3315 -0.9787 1.7617 +0.3409 -1.0296 1.7481 +0.3497 -1.0807 1.7344 +0.3577 -1.1319 1.7208 +0.3651 -1.1832 1.7072 +0.3717 -1.2346 1.6935 +0.3777 -1.2861 1.6799 +0.3830 -1.3377 1.6663 +0.3875 -1.3893 1.6526 +0.3914 -1.4410 1.6390 +0.3945 -1.4928 1.6253 +0.3969 -1.5445 1.6117 +0.3987 -1.5963 1.5981 +0.3997 -1.6482 1.5844 +0.4000 -1.7000 1.5708 +primID: 9 +startangle_c: 5 +endpose_c: 0 0 4 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 9 +0.0000 0.0000 2.0344 +0.0000 0.0000 1.9765 +0.0000 0.0000 1.9185 +0.0000 0.0000 1.8606 +0.0000 0.0000 1.8026 +0.0000 0.0000 1.7447 +0.0000 0.0000 1.6867 +0.0000 0.0000 1.6288 +0.0000 0.0000 1.5708 +primID: 0 +startangle_c: 6 +endpose_c: -1 1 6 +additionalactioncostmult: 1 +turning_radius: 0.0000 +intermediateposes: 3 +0.0000 0.0000 2.3562 +-0.0500 0.0500 2.3562 +-0.1000 0.1000 2.3562 +primID: 1 +startangle_c: 6 +endpose_c: -15 15 6 +additionalactioncostmult: 1 +turning_radius: 0.0000 +intermediateposes: 43 +0.0000 0.0000 2.3562 +-0.0357 0.0357 2.3562 +-0.0714 0.0714 2.3562 +-0.1071 0.1071 2.3562 +-0.1429 0.1429 2.3562 +-0.1786 0.1786 2.3562 +-0.2143 0.2143 2.3562 +-0.2500 0.2500 2.3562 +-0.2857 0.2857 2.3562 +-0.3214 0.3214 2.3562 +-0.3571 0.3571 2.3562 +-0.3929 0.3929 2.3562 +-0.4286 0.4286 2.3562 +-0.4643 0.4643 2.3562 +-0.5000 0.5000 2.3562 +-0.5357 0.5357 2.3562 +-0.5714 0.5714 2.3562 +-0.6071 0.6071 2.3562 +-0.6429 0.6429 2.3562 +-0.6786 0.6786 2.3562 +-0.7143 0.7143 2.3562 +-0.7500 0.7500 2.3562 +-0.7857 0.7857 2.3562 +-0.8214 0.8214 2.3562 +-0.8571 0.8571 2.3562 +-0.8929 0.8929 2.3562 +-0.9286 0.9286 2.3562 +-0.9643 0.9643 2.3562 +-1.0000 1.0000 2.3562 +-1.0357 1.0357 2.3562 +-1.0714 1.0714 2.3562 +-1.1071 1.1071 2.3562 +-1.1429 1.1429 2.3562 +-1.1786 1.1786 2.3562 +-1.2143 1.2143 2.3562 +-1.2500 1.2500 2.3562 +-1.2857 1.2857 2.3562 +-1.3214 1.3214 2.3562 +-1.3571 1.3571 2.3562 +-1.3929 1.3929 2.3562 +-1.4286 1.4286 2.3562 +-1.4643 1.4643 2.3562 +-1.5000 1.5000 2.3562 +primID: 2 +startangle_c: 6 +endpose_c: -18 13 7 +additionalactioncostmult: 2 +turning_radius: 6.9307 +intermediateposes: 45 +0.0000 0.0000 2.3562 +-0.0359 0.0357 2.3635 +-0.0721 0.0712 2.3708 +-0.1086 0.1064 2.3781 +-0.1453 0.1414 2.3854 +-0.1823 0.1761 2.3928 +-0.2195 0.2105 2.4001 +-0.2570 0.2446 2.4074 +-0.2947 0.2785 2.4147 +-0.3327 0.3120 2.4220 +-0.3709 0.3453 2.4293 +-0.4093 0.3784 2.4366 +-0.4480 0.4111 2.4439 +-0.4869 0.4436 2.4513 +-0.5261 0.4757 2.4586 +-0.5655 0.5076 2.4659 +-0.6051 0.5392 2.4732 +-0.6450 0.5705 2.4805 +-0.6851 0.6015 2.4878 +-0.7254 0.6322 2.4951 +-0.7659 0.6627 2.5024 +-0.8067 0.6928 2.5098 +-0.8477 0.7226 2.5171 +-0.8889 0.7521 2.5244 +-0.9303 0.7813 2.5317 +-0.9719 0.8103 2.5390 +-1.0137 0.8389 2.5463 +-1.0558 0.8672 2.5536 +-1.0980 0.8952 2.5609 +-1.1405 0.9229 2.5683 +-1.1831 0.9502 2.5756 +-1.2260 0.9773 2.5829 +-1.2690 1.0040 2.5902 +-1.3122 1.0305 2.5975 +-1.3557 1.0566 2.6048 +-1.3993 1.0824 2.6121 +-1.4431 1.1079 2.6194 +-1.4871 1.1330 2.6268 +-1.5313 1.1579 2.6341 +-1.5756 1.1824 2.6414 +-1.6201 1.2065 2.6487 +-1.6649 1.2304 2.6560 +-1.7097 1.2539 2.6633 +-1.7548 1.2771 2.6706 +-1.8000 1.3000 2.6779 +primID: 3 +startangle_c: 6 +endpose_c: -13 18 5 +additionalactioncostmult: 2 +turning_radius: -6.9307 +intermediateposes: 45 +0.0000 0.0000 2.3562 +-0.0357 0.0359 2.3489 +-0.0712 0.0721 2.3416 +-0.1064 0.1086 2.3343 +-0.1414 0.1453 2.3269 +-0.1761 0.1823 2.3196 +-0.2105 0.2195 2.3123 +-0.2446 0.2570 2.3050 +-0.2785 0.2947 2.2977 +-0.3120 0.3327 2.2904 +-0.3453 0.3709 2.2831 +-0.3784 0.4093 2.2758 +-0.4111 0.4480 2.2684 +-0.4436 0.4869 2.2611 +-0.4757 0.5261 2.2538 +-0.5076 0.5655 2.2465 +-0.5392 0.6051 2.2392 +-0.5705 0.6450 2.2319 +-0.6015 0.6851 2.2246 +-0.6322 0.7254 2.2173 +-0.6627 0.7659 2.2099 +-0.6928 0.8067 2.2026 +-0.7226 0.8477 2.1953 +-0.7521 0.8889 2.1880 +-0.7813 0.9303 2.1807 +-0.8103 0.9719 2.1734 +-0.8389 1.0137 2.1661 +-0.8672 1.0558 2.1588 +-0.8952 1.0980 2.1514 +-0.9229 1.1405 2.1441 +-0.9502 1.1831 2.1368 +-0.9773 1.2260 2.1295 +-1.0040 1.2690 2.1222 +-1.0305 1.3122 2.1149 +-1.0566 1.3557 2.1076 +-1.0824 1.3993 2.1003 +-1.1079 1.4431 2.0929 +-1.1330 1.4871 2.0856 +-1.1579 1.5313 2.0783 +-1.1824 1.5756 2.0710 +-1.2065 1.6201 2.0637 +-1.2304 1.6649 2.0564 +-1.2539 1.7097 2.0491 +-1.2771 1.7548 2.0418 +-1.3000 1.8000 2.0344 +primID: 4 +startangle_c: 6 +endpose_c: 0 0 7 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 6 +0.0000 0.0000 2.3562 +0.0000 0.0000 2.4205 +0.0000 0.0000 2.4849 +0.0000 0.0000 2.5492 +0.0000 0.0000 2.6136 +0.0000 0.0000 2.6779 +primID: 5 +startangle_c: 6 +endpose_c: 1 -1 6 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 3 +0.0000 0.0000 2.3562 +0.0500 -0.0500 2.3562 +0.1000 -0.1000 2.3562 +primID: 6 +startangle_c: 6 +endpose_c: 16 -16 6 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 46 +0.0000 0.0000 2.3562 +0.0356 -0.0356 2.3562 +0.0711 -0.0711 2.3562 +0.1067 -0.1067 2.3562 +0.1422 -0.1422 2.3562 +0.1778 -0.1778 2.3562 +0.2133 -0.2133 2.3562 +0.2489 -0.2489 2.3562 +0.2844 -0.2844 2.3562 +0.3200 -0.3200 2.3562 +0.3556 -0.3556 2.3562 +0.3911 -0.3911 2.3562 +0.4267 -0.4267 2.3562 +0.4622 -0.4622 2.3562 +0.4978 -0.4978 2.3562 +0.5333 -0.5333 2.3562 +0.5689 -0.5689 2.3562 +0.6044 -0.6044 2.3562 +0.6400 -0.6400 2.3562 +0.6756 -0.6756 2.3562 +0.7111 -0.7111 2.3562 +0.7467 -0.7467 2.3562 +0.7822 -0.7822 2.3562 +0.8178 -0.8178 2.3562 +0.8533 -0.8533 2.3562 +0.8889 -0.8889 2.3562 +0.9244 -0.9244 2.3562 +0.9600 -0.9600 2.3562 +0.9956 -0.9956 2.3562 +1.0311 -1.0311 2.3562 +1.0667 -1.0667 2.3562 +1.1022 -1.1022 2.3562 +1.1378 -1.1378 2.3562 +1.1733 -1.1733 2.3562 +1.2089 -1.2089 2.3562 +1.2444 -1.2444 2.3562 +1.2800 -1.2800 2.3562 +1.3156 -1.3156 2.3562 +1.3511 -1.3511 2.3562 +1.3867 -1.3867 2.3562 +1.4222 -1.4222 2.3562 +1.4578 -1.4578 2.3562 +1.4933 -1.4933 2.3562 +1.5289 -1.5289 2.3562 +1.5644 -1.5644 2.3562 +1.6000 -1.6000 2.3562 +primID: 7 +startangle_c: 6 +endpose_c: 18 -13 7 +additionalactioncostmult: 3 +turning_radius: -6.9307 +intermediateposes: 45 +0.0000 0.0000 2.3562 +0.0359 -0.0357 2.3635 +0.0721 -0.0712 2.3708 +0.1086 -0.1064 2.3781 +0.1453 -0.1414 2.3854 +0.1823 -0.1761 2.3928 +0.2195 -0.2105 2.4001 +0.2570 -0.2446 2.4074 +0.2947 -0.2785 2.4147 +0.3327 -0.3120 2.4220 +0.3709 -0.3453 2.4293 +0.4093 -0.3784 2.4366 +0.4480 -0.4111 2.4439 +0.4869 -0.4436 2.4513 +0.5261 -0.4757 2.4586 +0.5655 -0.5076 2.4659 +0.6051 -0.5392 2.4732 +0.6450 -0.5705 2.4805 +0.6851 -0.6015 2.4878 +0.7254 -0.6322 2.4951 +0.7659 -0.6627 2.5024 +0.8067 -0.6928 2.5098 +0.8477 -0.7226 2.5171 +0.8889 -0.7521 2.5244 +0.9303 -0.7813 2.5317 +0.9719 -0.8103 2.5390 +1.0137 -0.8389 2.5463 +1.0558 -0.8672 2.5536 +1.0980 -0.8952 2.5609 +1.1405 -0.9229 2.5683 +1.1831 -0.9502 2.5756 +1.2260 -0.9773 2.5829 +1.2690 -1.0040 2.5902 +1.3122 -1.0305 2.5975 +1.3557 -1.0566 2.6048 +1.3993 -1.0824 2.6121 +1.4431 -1.1079 2.6194 +1.4871 -1.1330 2.6268 +1.5313 -1.1579 2.6341 +1.5756 -1.1824 2.6414 +1.6201 -1.2065 2.6487 +1.6649 -1.2304 2.6560 +1.7097 -1.2539 2.6633 +1.7548 -1.2771 2.6706 +1.8000 -1.3000 2.6779 +primID: 8 +startangle_c: 6 +endpose_c: 13 -18 5 +additionalactioncostmult: 3 +turning_radius: 6.9307 +intermediateposes: 45 +0.0000 0.0000 2.3562 +0.0357 -0.0359 2.3489 +0.0712 -0.0721 2.3416 +0.1064 -0.1086 2.3343 +0.1414 -0.1453 2.3269 +0.1761 -0.1823 2.3196 +0.2105 -0.2195 2.3123 +0.2446 -0.2570 2.3050 +0.2785 -0.2947 2.2977 +0.3120 -0.3327 2.2904 +0.3453 -0.3709 2.2831 +0.3784 -0.4093 2.2758 +0.4111 -0.4480 2.2684 +0.4436 -0.4869 2.2611 +0.4757 -0.5261 2.2538 +0.5076 -0.5655 2.2465 +0.5392 -0.6051 2.2392 +0.5705 -0.6450 2.2319 +0.6015 -0.6851 2.2246 +0.6322 -0.7254 2.2173 +0.6627 -0.7659 2.2099 +0.6928 -0.8067 2.2026 +0.7226 -0.8477 2.1953 +0.7521 -0.8889 2.1880 +0.7813 -0.9303 2.1807 +0.8103 -0.9719 2.1734 +0.8389 -1.0137 2.1661 +0.8672 -1.0558 2.1588 +0.8952 -1.0980 2.1514 +0.9229 -1.1405 2.1441 +0.9502 -1.1831 2.1368 +0.9773 -1.2260 2.1295 +1.0040 -1.2690 2.1222 +1.0305 -1.3122 2.1149 +1.0566 -1.3557 2.1076 +1.0824 -1.3993 2.1003 +1.1079 -1.4431 2.0929 +1.1330 -1.4871 2.0856 +1.1579 -1.5313 2.0783 +1.1824 -1.5756 2.0710 +1.2065 -1.6201 2.0637 +1.2304 -1.6649 2.0564 +1.2539 -1.7097 2.0491 +1.2771 -1.7548 2.0418 +1.3000 -1.8000 2.0344 +primID: 9 +startangle_c: 6 +endpose_c: 0 0 5 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 6 +0.0000 0.0000 2.3562 +0.0000 0.0000 2.2918 +0.0000 0.0000 2.2275 +0.0000 0.0000 2.1631 +0.0000 0.0000 2.0988 +0.0000 0.0000 2.0344 +primID: 0 +startangle_c: 7 +endpose_c: -2 1 7 +additionalactioncostmult: 1 +turning_radius: -0.0000 +intermediateposes: 5 +0.0000 0.0000 2.6779 +-0.0500 0.0250 2.6779 +-0.1000 0.0500 2.6779 +-0.1500 0.0750 2.6779 +-0.2000 0.1000 2.6779 +primID: 1 +startangle_c: 7 +endpose_c: -18 9 7 +additionalactioncostmult: 1 +turning_radius: -0.0000 +intermediateposes: 41 +0.0000 0.0000 2.6779 +-0.0450 0.0225 2.6779 +-0.0900 0.0450 2.6779 +-0.1350 0.0675 2.6779 +-0.1800 0.0900 2.6779 +-0.2250 0.1125 2.6779 +-0.2700 0.1350 2.6779 +-0.3150 0.1575 2.6779 +-0.3600 0.1800 2.6779 +-0.4050 0.2025 2.6779 +-0.4500 0.2250 2.6779 +-0.4950 0.2475 2.6779 +-0.5400 0.2700 2.6779 +-0.5850 0.2925 2.6779 +-0.6300 0.3150 2.6779 +-0.6750 0.3375 2.6779 +-0.7200 0.3600 2.6779 +-0.7650 0.3825 2.6779 +-0.8100 0.4050 2.6779 +-0.8550 0.4275 2.6779 +-0.9000 0.4500 2.6779 +-0.9450 0.4725 2.6779 +-0.9900 0.4950 2.6779 +-1.0350 0.5175 2.6779 +-1.0800 0.5400 2.6779 +-1.1250 0.5625 2.6779 +-1.1700 0.5850 2.6779 +-1.2150 0.6075 2.6779 +-1.2600 0.6300 2.6779 +-1.3050 0.6525 2.6779 +-1.3500 0.6750 2.6779 +-1.3950 0.6975 2.6779 +-1.4400 0.7200 2.6779 +-1.4850 0.7425 2.6779 +-1.5300 0.7650 2.6779 +-1.5750 0.7875 2.6779 +-1.6200 0.8100 2.6779 +-1.6650 0.8325 2.6779 +-1.7100 0.8550 2.6779 +-1.7550 0.8775 2.6779 +-1.8000 0.9000 2.6779 +primID: 2 +startangle_c: 7 +endpose_c: -18 13 6 +additionalactioncostmult: 2 +turning_radius: -6.9307 +intermediateposes: 45 +0.0000 0.0000 2.6779 +-0.0452 0.0229 2.6706 +-0.0903 0.0461 2.6633 +-0.1351 0.0696 2.6560 +-0.1799 0.0935 2.6487 +-0.2244 0.1176 2.6414 +-0.2687 0.1421 2.6341 +-0.3129 0.1670 2.6268 +-0.3569 0.1921 2.6194 +-0.4007 0.2176 2.6121 +-0.4443 0.2434 2.6048 +-0.4878 0.2695 2.5975 +-0.5310 0.2960 2.5902 +-0.5740 0.3227 2.5829 +-0.6169 0.3498 2.5756 +-0.6595 0.3771 2.5683 +-0.7020 0.4048 2.5609 +-0.7442 0.4328 2.5536 +-0.7863 0.4611 2.5463 +-0.8281 0.4897 2.5390 +-0.8697 0.5187 2.5317 +-0.9111 0.5479 2.5244 +-0.9523 0.5774 2.5171 +-0.9933 0.6072 2.5098 +-1.0341 0.6373 2.5024 +-1.0746 0.6678 2.4951 +-1.1149 0.6985 2.4878 +-1.1550 0.7295 2.4805 +-1.1949 0.7608 2.4732 +-1.2345 0.7924 2.4659 +-1.2739 0.8243 2.4586 +-1.3131 0.8564 2.4513 +-1.3520 0.8889 2.4439 +-1.3907 0.9216 2.4366 +-1.4291 0.9547 2.4293 +-1.4673 0.9880 2.4220 +-1.5053 1.0215 2.4147 +-1.5430 1.0554 2.4074 +-1.5805 1.0895 2.4001 +-1.6177 1.1239 2.3928 +-1.6547 1.1586 2.3854 +-1.6914 1.1936 2.3781 +-1.7279 1.2288 2.3708 +-1.7641 1.2643 2.3635 +-1.8000 1.3000 2.3562 +primID: 3 +startangle_c: 7 +endpose_c: -17 4 8 +additionalactioncostmult: 2 +turning_radius: 3.8007 +intermediateposes: 35 +0.0000 0.0000 2.6779 +-0.0465 0.0228 2.6916 +-0.0934 0.0450 2.7052 +-0.1405 0.0666 2.7189 +-0.1879 0.0875 2.7325 +-0.2356 0.1077 2.7461 +-0.2836 0.1273 2.7598 +-0.3318 0.1463 2.7734 +-0.3803 0.1646 2.7870 +-0.4290 0.1822 2.8007 +-0.4780 0.1991 2.8143 +-0.5272 0.2154 2.8279 +-0.5766 0.2310 2.8416 +-0.6262 0.2460 2.8552 +-0.6761 0.2603 2.8689 +-0.7261 0.2738 2.8825 +-0.7763 0.2867 2.8961 +-0.8266 0.2990 2.9098 +-0.8772 0.3105 2.9234 +-0.9279 0.3213 2.9370 +-0.9787 0.3315 2.9507 +-1.0296 0.3409 2.9643 +-1.0807 0.3497 2.9780 +-1.1319 0.3577 2.9916 +-1.1832 0.3651 3.0052 +-1.2346 0.3717 3.0189 +-1.2861 0.3777 3.0325 +-1.3377 0.3830 3.0461 +-1.3893 0.3875 3.0598 +-1.4410 0.3914 3.0734 +-1.4928 0.3945 3.0870 +-1.5445 0.3969 3.1007 +-1.5963 0.3987 3.1143 +-1.6482 0.3997 3.1280 +-1.7000 0.4000 3.1416 +primID: 4 +startangle_c: 7 +endpose_c: 0 0 6 +additionalactioncostmult: 5 +turning_radius: -0.0000 +intermediateposes: 6 +0.0000 0.0000 2.6779 +0.0000 0.0000 2.6136 +0.0000 0.0000 2.5492 +0.0000 0.0000 2.4849 +0.0000 0.0000 2.4205 +0.0000 0.0000 2.3562 +primID: 5 +startangle_c: 7 +endpose_c: 2 -1 7 +additionalactioncostmult: 5 +turning_radius: -0.0000 +intermediateposes: 5 +0.0000 0.0000 2.6779 +0.0500 -0.0250 2.6779 +0.1000 -0.0500 2.6779 +0.1500 -0.0750 2.6779 +0.2000 -0.1000 2.6779 +primID: 6 +startangle_c: 7 +endpose_c: 18 -9 7 +additionalactioncostmult: 5 +turning_radius: -0.0000 +intermediateposes: 41 +0.0000 0.0000 2.6779 +0.0450 -0.0225 2.6779 +0.0900 -0.0450 2.6779 +0.1350 -0.0675 2.6779 +0.1800 -0.0900 2.6779 +0.2250 -0.1125 2.6779 +0.2700 -0.1350 2.6779 +0.3150 -0.1575 2.6779 +0.3600 -0.1800 2.6779 +0.4050 -0.2025 2.6779 +0.4500 -0.2250 2.6779 +0.4950 -0.2475 2.6779 +0.5400 -0.2700 2.6779 +0.5850 -0.2925 2.6779 +0.6300 -0.3150 2.6779 +0.6750 -0.3375 2.6779 +0.7200 -0.3600 2.6779 +0.7650 -0.3825 2.6779 +0.8100 -0.4050 2.6779 +0.8550 -0.4275 2.6779 +0.9000 -0.4500 2.6779 +0.9450 -0.4725 2.6779 +0.9900 -0.4950 2.6779 +1.0350 -0.5175 2.6779 +1.0800 -0.5400 2.6779 +1.1250 -0.5625 2.6779 +1.1700 -0.5850 2.6779 +1.2150 -0.6075 2.6779 +1.2600 -0.6300 2.6779 +1.3050 -0.6525 2.6779 +1.3500 -0.6750 2.6779 +1.3950 -0.6975 2.6779 +1.4400 -0.7200 2.6779 +1.4850 -0.7425 2.6779 +1.5300 -0.7650 2.6779 +1.5750 -0.7875 2.6779 +1.6200 -0.8100 2.6779 +1.6650 -0.8325 2.6779 +1.7100 -0.8550 2.6779 +1.7550 -0.8775 2.6779 +1.8000 -0.9000 2.6779 +primID: 7 +startangle_c: 7 +endpose_c: 18 -13 6 +additionalactioncostmult: 3 +turning_radius: 6.9307 +intermediateposes: 45 +0.0000 0.0000 2.6779 +0.0452 -0.0229 2.6706 +0.0903 -0.0461 2.6633 +0.1351 -0.0696 2.6560 +0.1799 -0.0935 2.6487 +0.2244 -0.1176 2.6414 +0.2687 -0.1421 2.6341 +0.3129 -0.1670 2.6268 +0.3569 -0.1921 2.6194 +0.4007 -0.2176 2.6121 +0.4443 -0.2434 2.6048 +0.4878 -0.2695 2.5975 +0.5310 -0.2960 2.5902 +0.5740 -0.3227 2.5829 +0.6169 -0.3498 2.5756 +0.6595 -0.3771 2.5683 +0.7020 -0.4048 2.5609 +0.7442 -0.4328 2.5536 +0.7863 -0.4611 2.5463 +0.8281 -0.4897 2.5390 +0.8697 -0.5187 2.5317 +0.9111 -0.5479 2.5244 +0.9523 -0.5774 2.5171 +0.9933 -0.6072 2.5098 +1.0341 -0.6373 2.5024 +1.0746 -0.6678 2.4951 +1.1149 -0.6985 2.4878 +1.1550 -0.7295 2.4805 +1.1949 -0.7608 2.4732 +1.2345 -0.7924 2.4659 +1.2739 -0.8243 2.4586 +1.3131 -0.8564 2.4513 +1.3520 -0.8889 2.4439 +1.3907 -0.9216 2.4366 +1.4291 -0.9547 2.4293 +1.4673 -0.9880 2.4220 +1.5053 -1.0215 2.4147 +1.5430 -1.0554 2.4074 +1.5805 -1.0895 2.4001 +1.6177 -1.1239 2.3928 +1.6547 -1.1586 2.3854 +1.6914 -1.1936 2.3781 +1.7279 -1.2288 2.3708 +1.7641 -1.2643 2.3635 +1.8000 -1.3000 2.3562 +primID: 8 +startangle_c: 7 +endpose_c: 17 -4 8 +additionalactioncostmult: 3 +turning_radius: -3.8007 +intermediateposes: 35 +0.0000 0.0000 2.6779 +0.0465 -0.0228 2.6916 +0.0934 -0.0450 2.7052 +0.1405 -0.0666 2.7189 +0.1879 -0.0875 2.7325 +0.2356 -0.1077 2.7461 +0.2836 -0.1273 2.7598 +0.3318 -0.1463 2.7734 +0.3803 -0.1646 2.7870 +0.4290 -0.1822 2.8007 +0.4780 -0.1991 2.8143 +0.5272 -0.2154 2.8279 +0.5766 -0.2310 2.8416 +0.6262 -0.2460 2.8552 +0.6761 -0.2603 2.8689 +0.7261 -0.2738 2.8825 +0.7763 -0.2867 2.8961 +0.8266 -0.2990 2.9098 +0.8772 -0.3105 2.9234 +0.9279 -0.3213 2.9370 +0.9787 -0.3315 2.9507 +1.0296 -0.3409 2.9643 +1.0807 -0.3497 2.9780 +1.1319 -0.3577 2.9916 +1.1832 -0.3651 3.0052 +1.2346 -0.3717 3.0189 +1.2861 -0.3777 3.0325 +1.3377 -0.3830 3.0461 +1.3893 -0.3875 3.0598 +1.4410 -0.3914 3.0734 +1.4928 -0.3945 3.0870 +1.5445 -0.3969 3.1007 +1.5963 -0.3987 3.1143 +1.6482 -0.3997 3.1280 +1.7000 -0.4000 3.1416 +primID: 9 +startangle_c: 7 +endpose_c: 0 0 8 +additionalactioncostmult: 5 +turning_radius: -0.0000 +intermediateposes: 9 +0.0000 0.0000 2.6779 +0.0000 0.0000 2.7359 +0.0000 0.0000 2.7939 +0.0000 0.0000 2.8518 +0.0000 0.0000 2.9098 +0.0000 0.0000 2.9677 +0.0000 0.0000 3.0257 +0.0000 0.0000 3.0836 +0.0000 0.0000 3.1416 +primID: 0 +startangle_c: 8 +endpose_c: -1 0 8 +additionalactioncostmult: 1 +turning_radius: 0.0000 +intermediateposes: 3 +0.0000 0.0000 3.1416 +-0.0500 0.0000 3.1416 +-0.1000 0.0000 3.1416 +primID: 1 +startangle_c: 8 +endpose_c: -17 0 8 +additionalactioncostmult: 1 +turning_radius: 0.0000 +intermediateposes: 35 +0.0000 0.0000 3.1416 +-0.0500 0.0000 3.1416 +-0.1000 0.0000 3.1416 +-0.1500 0.0000 3.1416 +-0.2000 0.0000 3.1416 +-0.2500 0.0000 3.1416 +-0.3000 0.0000 3.1416 +-0.3500 0.0000 3.1416 +-0.4000 0.0000 3.1416 +-0.4500 0.0000 3.1416 +-0.5000 0.0000 3.1416 +-0.5500 0.0000 3.1416 +-0.6000 0.0000 3.1416 +-0.6500 0.0000 3.1416 +-0.7000 0.0000 3.1416 +-0.7500 0.0000 3.1416 +-0.8000 0.0000 3.1416 +-0.8500 0.0000 3.1416 +-0.9000 0.0000 3.1416 +-0.9500 0.0000 3.1416 +-1.0000 0.0000 3.1416 +-1.0500 0.0000 3.1416 +-1.1000 0.0000 3.1416 +-1.1500 0.0000 3.1416 +-1.2000 0.0000 3.1416 +-1.2500 0.0000 3.1416 +-1.3000 0.0000 3.1416 +-1.3500 0.0000 3.1416 +-1.4000 0.0000 3.1416 +-1.4500 0.0000 3.1416 +-1.5000 0.0000 3.1416 +-1.5500 0.0000 3.1416 +-1.6000 0.0000 3.1416 +-1.6500 0.0000 3.1416 +-1.7000 0.0000 3.1416 +primID: 2 +startangle_c: 8 +endpose_c: -17 -4 9 +additionalactioncostmult: 2 +turning_radius: 3.8007 +intermediateposes: 35 +0.0000 0.0000 3.1416 +-0.0518 -0.0003 3.1552 +-0.1037 -0.0013 3.1689 +-0.1555 -0.0031 3.1825 +-0.2072 -0.0055 3.1961 +-0.2590 -0.0086 3.2098 +-0.3107 -0.0125 3.2234 +-0.3623 -0.0170 3.2370 +-0.4139 -0.0223 3.2507 +-0.4654 -0.0283 3.2643 +-0.5168 -0.0349 3.2780 +-0.5681 -0.0423 3.2916 +-0.6193 -0.0503 3.3052 +-0.6704 -0.0591 3.3189 +-0.7213 -0.0685 3.3325 +-0.7721 -0.0787 3.3461 +-0.8228 -0.0895 3.3598 +-0.8734 -0.1010 3.3734 +-0.9237 -0.1133 3.3871 +-0.9739 -0.1262 3.4007 +-1.0239 -0.1397 3.4143 +-1.0738 -0.1540 3.4280 +-1.1234 -0.1690 3.4416 +-1.1728 -0.1846 3.4552 +-1.2220 -0.2009 3.4689 +-1.2710 -0.2178 3.4825 +-1.3197 -0.2354 3.4961 +-1.3682 -0.2537 3.5098 +-1.4164 -0.2727 3.5234 +-1.4644 -0.2923 3.5371 +-1.5121 -0.3125 3.5507 +-1.5595 -0.3334 3.5643 +-1.6066 -0.3550 3.5780 +-1.6535 -0.3772 3.5916 +-1.7000 -0.4000 3.6052 +primID: 3 +startangle_c: 8 +endpose_c: -17 4 7 +additionalactioncostmult: 2 +turning_radius: -3.8007 +intermediateposes: 35 +0.0000 0.0000 3.1416 +-0.0518 0.0003 3.1280 +-0.1037 0.0013 3.1143 +-0.1555 0.0031 3.1007 +-0.2072 0.0055 3.0870 +-0.2590 0.0086 3.0734 +-0.3107 0.0125 3.0598 +-0.3623 0.0170 3.0461 +-0.4139 0.0223 3.0325 +-0.4654 0.0283 3.0189 +-0.5168 0.0349 3.0052 +-0.5681 0.0423 2.9916 +-0.6193 0.0503 2.9780 +-0.6704 0.0591 2.9643 +-0.7213 0.0685 2.9507 +-0.7721 0.0787 2.9370 +-0.8228 0.0895 2.9234 +-0.8734 0.1010 2.9098 +-0.9237 0.1133 2.8961 +-0.9739 0.1262 2.8825 +-1.0239 0.1397 2.8689 +-1.0738 0.1540 2.8552 +-1.1234 0.1690 2.8416 +-1.1728 0.1846 2.8279 +-1.2220 0.2009 2.8143 +-1.2710 0.2178 2.8007 +-1.3197 0.2354 2.7870 +-1.3682 0.2537 2.7734 +-1.4164 0.2727 2.7598 +-1.4644 0.2923 2.7461 +-1.5121 0.3125 2.7325 +-1.5595 0.3334 2.7189 +-1.6066 0.3550 2.7052 +-1.6535 0.3772 2.6916 +-1.7000 0.4000 2.6779 +primID: 4 +startangle_c: 8 +endpose_c: 0 0 9 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 9 +0.0000 0.0000 3.1416 +0.0000 0.0000 3.1995 +0.0000 0.0000 3.2575 +0.0000 0.0000 3.3155 +0.0000 0.0000 3.3734 +0.0000 0.0000 3.4314 +0.0000 0.0000 3.4893 +0.0000 0.0000 3.5473 +0.0000 0.0000 3.6052 +primID: 5 +startangle_c: 8 +endpose_c: 1 0 8 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 3 +0.0000 0.0000 3.1416 +0.0500 0.0000 3.1416 +0.1000 0.0000 3.1416 +primID: 6 +startangle_c: 8 +endpose_c: 17 0 8 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 35 +0.0000 0.0000 3.1416 +0.0500 0.0000 3.1416 +0.1000 0.0000 3.1416 +0.1500 0.0000 3.1416 +0.2000 0.0000 3.1416 +0.2500 0.0000 3.1416 +0.3000 0.0000 3.1416 +0.3500 0.0000 3.1416 +0.4000 0.0000 3.1416 +0.4500 0.0000 3.1416 +0.5000 0.0000 3.1416 +0.5500 0.0000 3.1416 +0.6000 0.0000 3.1416 +0.6500 0.0000 3.1416 +0.7000 0.0000 3.1416 +0.7500 0.0000 3.1416 +0.8000 0.0000 3.1416 +0.8500 0.0000 3.1416 +0.9000 0.0000 3.1416 +0.9500 0.0000 3.1416 +1.0000 0.0000 3.1416 +1.0500 0.0000 3.1416 +1.1000 0.0000 3.1416 +1.1500 0.0000 3.1416 +1.2000 0.0000 3.1416 +1.2500 0.0000 3.1416 +1.3000 0.0000 3.1416 +1.3500 0.0000 3.1416 +1.4000 0.0000 3.1416 +1.4500 0.0000 3.1416 +1.5000 0.0000 3.1416 +1.5500 0.0000 3.1416 +1.6000 0.0000 3.1416 +1.6500 0.0000 3.1416 +1.7000 0.0000 3.1416 +primID: 7 +startangle_c: 8 +endpose_c: 17 4 9 +additionalactioncostmult: 3 +turning_radius: -3.8007 +intermediateposes: 35 +0.0000 0.0000 3.1416 +0.0518 0.0003 3.1552 +0.1037 0.0013 3.1689 +0.1555 0.0031 3.1825 +0.2072 0.0055 3.1961 +0.2590 0.0086 3.2098 +0.3107 0.0125 3.2234 +0.3623 0.0170 3.2370 +0.4139 0.0223 3.2507 +0.4654 0.0283 3.2643 +0.5168 0.0349 3.2780 +0.5681 0.0423 3.2916 +0.6193 0.0503 3.3052 +0.6704 0.0591 3.3189 +0.7213 0.0685 3.3325 +0.7721 0.0787 3.3461 +0.8228 0.0895 3.3598 +0.8734 0.1010 3.3734 +0.9237 0.1133 3.3871 +0.9739 0.1262 3.4007 +1.0239 0.1397 3.4143 +1.0738 0.1540 3.4280 +1.1234 0.1690 3.4416 +1.1728 0.1846 3.4552 +1.2220 0.2009 3.4689 +1.2710 0.2178 3.4825 +1.3197 0.2354 3.4961 +1.3682 0.2537 3.5098 +1.4164 0.2727 3.5234 +1.4644 0.2923 3.5371 +1.5121 0.3125 3.5507 +1.5595 0.3334 3.5643 +1.6066 0.3550 3.5780 +1.6535 0.3772 3.5916 +1.7000 0.4000 3.6052 +primID: 8 +startangle_c: 8 +endpose_c: 17 -4 7 +additionalactioncostmult: 3 +turning_radius: 3.8007 +intermediateposes: 35 +0.0000 0.0000 3.1416 +0.0518 -0.0003 3.1280 +0.1037 -0.0013 3.1143 +0.1555 -0.0031 3.1007 +0.2072 -0.0055 3.0870 +0.2590 -0.0086 3.0734 +0.3107 -0.0125 3.0598 +0.3623 -0.0170 3.0461 +0.4139 -0.0223 3.0325 +0.4654 -0.0283 3.0189 +0.5168 -0.0349 3.0052 +0.5681 -0.0423 2.9916 +0.6193 -0.0503 2.9780 +0.6704 -0.0591 2.9643 +0.7213 -0.0685 2.9507 +0.7721 -0.0787 2.9370 +0.8228 -0.0895 2.9234 +0.8734 -0.1010 2.9098 +0.9237 -0.1133 2.8961 +0.9739 -0.1262 2.8825 +1.0239 -0.1397 2.8689 +1.0738 -0.1540 2.8552 +1.1234 -0.1690 2.8416 +1.1728 -0.1846 2.8279 +1.2220 -0.2009 2.8143 +1.2710 -0.2178 2.8007 +1.3197 -0.2354 2.7870 +1.3682 -0.2537 2.7734 +1.4164 -0.2727 2.7598 +1.4644 -0.2923 2.7461 +1.5121 -0.3125 2.7325 +1.5595 -0.3334 2.7189 +1.6066 -0.3550 2.7052 +1.6535 -0.3772 2.6916 +1.7000 -0.4000 2.6779 +primID: 9 +startangle_c: 8 +endpose_c: 0 0 7 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 9 +0.0000 0.0000 3.1416 +0.0000 0.0000 3.0836 +0.0000 0.0000 3.0257 +0.0000 0.0000 2.9677 +0.0000 0.0000 2.9098 +0.0000 0.0000 2.8518 +0.0000 0.0000 2.7939 +0.0000 0.0000 2.7359 +0.0000 0.0000 2.6779 +primID: 0 +startangle_c: 9 +endpose_c: -2 -1 9 +additionalactioncostmult: 1 +turning_radius: 0.0000 +intermediateposes: 5 +0.0000 0.0000 3.6052 +-0.0500 -0.0250 3.6052 +-0.1000 -0.0500 3.6052 +-0.1500 -0.0750 3.6052 +-0.2000 -0.1000 3.6052 +primID: 1 +startangle_c: 9 +endpose_c: -18 -9 9 +additionalactioncostmult: 1 +turning_radius: 0.0000 +intermediateposes: 41 +0.0000 0.0000 3.6052 +-0.0450 -0.0225 3.6052 +-0.0900 -0.0450 3.6052 +-0.1350 -0.0675 3.6052 +-0.1800 -0.0900 3.6052 +-0.2250 -0.1125 3.6052 +-0.2700 -0.1350 3.6052 +-0.3150 -0.1575 3.6052 +-0.3600 -0.1800 3.6052 +-0.4050 -0.2025 3.6052 +-0.4500 -0.2250 3.6052 +-0.4950 -0.2475 3.6052 +-0.5400 -0.2700 3.6052 +-0.5850 -0.2925 3.6052 +-0.6300 -0.3150 3.6052 +-0.6750 -0.3375 3.6052 +-0.7200 -0.3600 3.6052 +-0.7650 -0.3825 3.6052 +-0.8100 -0.4050 3.6052 +-0.8550 -0.4275 3.6052 +-0.9000 -0.4500 3.6052 +-0.9450 -0.4725 3.6052 +-0.9900 -0.4950 3.6052 +-1.0350 -0.5175 3.6052 +-1.0800 -0.5400 3.6052 +-1.1250 -0.5625 3.6052 +-1.1700 -0.5850 3.6052 +-1.2150 -0.6075 3.6052 +-1.2600 -0.6300 3.6052 +-1.3050 -0.6525 3.6052 +-1.3500 -0.6750 3.6052 +-1.3950 -0.6975 3.6052 +-1.4400 -0.7200 3.6052 +-1.4850 -0.7425 3.6052 +-1.5300 -0.7650 3.6052 +-1.5750 -0.7875 3.6052 +-1.6200 -0.8100 3.6052 +-1.6650 -0.8325 3.6052 +-1.7100 -0.8550 3.6052 +-1.7550 -0.8775 3.6052 +-1.8000 -0.9000 3.6052 +primID: 2 +startangle_c: 9 +endpose_c: -18 -13 10 +additionalactioncostmult: 2 +turning_radius: 6.9307 +intermediateposes: 45 +0.0000 0.0000 3.6052 +-0.0452 -0.0229 3.6126 +-0.0903 -0.0461 3.6199 +-0.1351 -0.0696 3.6272 +-0.1799 -0.0935 3.6345 +-0.2244 -0.1176 3.6418 +-0.2687 -0.1421 3.6491 +-0.3129 -0.1670 3.6564 +-0.3569 -0.1921 3.6637 +-0.4007 -0.2176 3.6711 +-0.4443 -0.2434 3.6784 +-0.4878 -0.2695 3.6857 +-0.5310 -0.2960 3.6930 +-0.5740 -0.3227 3.7003 +-0.6169 -0.3498 3.7076 +-0.6595 -0.3771 3.7149 +-0.7020 -0.4048 3.7222 +-0.7442 -0.4328 3.7296 +-0.7863 -0.4611 3.7369 +-0.8281 -0.4897 3.7442 +-0.8697 -0.5187 3.7515 +-0.9111 -0.5479 3.7588 +-0.9523 -0.5774 3.7661 +-0.9933 -0.6072 3.7734 +-1.0341 -0.6373 3.7807 +-1.0746 -0.6678 3.7881 +-1.1149 -0.6985 3.7954 +-1.1550 -0.7295 3.8027 +-1.1949 -0.7608 3.8100 +-1.2345 -0.7924 3.8173 +-1.2739 -0.8243 3.8246 +-1.3131 -0.8564 3.8319 +-1.3520 -0.8889 3.8392 +-1.3907 -0.9216 3.8466 +-1.4291 -0.9547 3.8539 +-1.4673 -0.9880 3.8612 +-1.5053 -1.0215 3.8685 +-1.5430 -1.0554 3.8758 +-1.5805 -1.0895 3.8831 +-1.6177 -1.1239 3.8904 +-1.6547 -1.1586 3.8977 +-1.6914 -1.1936 3.9051 +-1.7279 -1.2288 3.9124 +-1.7641 -1.2643 3.9197 +-1.8000 -1.3000 3.9270 +primID: 3 +startangle_c: 9 +endpose_c: -17 -4 8 +additionalactioncostmult: 2 +turning_radius: -3.8007 +intermediateposes: 35 +0.0000 0.0000 3.6052 +-0.0465 -0.0228 3.5916 +-0.0934 -0.0450 3.5780 +-0.1405 -0.0666 3.5643 +-0.1879 -0.0875 3.5507 +-0.2356 -0.1077 3.5371 +-0.2836 -0.1273 3.5234 +-0.3318 -0.1463 3.5098 +-0.3803 -0.1646 3.4961 +-0.4290 -0.1822 3.4825 +-0.4780 -0.1991 3.4689 +-0.5272 -0.2154 3.4552 +-0.5766 -0.2310 3.4416 +-0.6262 -0.2460 3.4280 +-0.6761 -0.2603 3.4143 +-0.7261 -0.2738 3.4007 +-0.7763 -0.2867 3.3871 +-0.8266 -0.2990 3.3734 +-0.8772 -0.3105 3.3598 +-0.9279 -0.3213 3.3461 +-0.9787 -0.3315 3.3325 +-1.0296 -0.3409 3.3189 +-1.0807 -0.3497 3.3052 +-1.1319 -0.3577 3.2916 +-1.1832 -0.3651 3.2780 +-1.2346 -0.3717 3.2643 +-1.2861 -0.3777 3.2507 +-1.3377 -0.3830 3.2370 +-1.3893 -0.3875 3.2234 +-1.4410 -0.3914 3.2098 +-1.4928 -0.3945 3.1961 +-1.5445 -0.3969 3.1825 +-1.5963 -0.3987 3.1689 +-1.6482 -0.3997 3.1552 +-1.7000 -0.4000 3.1416 +primID: 4 +startangle_c: 9 +endpose_c: 0 0 10 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 6 +0.0000 0.0000 3.6052 +0.0000 0.0000 3.6696 +0.0000 0.0000 3.7339 +0.0000 0.0000 3.7983 +0.0000 0.0000 3.8626 +0.0000 0.0000 3.9270 +primID: 5 +startangle_c: 9 +endpose_c: 2 1 9 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 5 +0.0000 0.0000 3.6052 +0.0500 0.0250 3.6052 +0.1000 0.0500 3.6052 +0.1500 0.0750 3.6052 +0.2000 0.1000 3.6052 +primID: 6 +startangle_c: 9 +endpose_c: 18 9 9 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 41 +0.0000 0.0000 3.6052 +0.0450 0.0225 3.6052 +0.0900 0.0450 3.6052 +0.1350 0.0675 3.6052 +0.1800 0.0900 3.6052 +0.2250 0.1125 3.6052 +0.2700 0.1350 3.6052 +0.3150 0.1575 3.6052 +0.3600 0.1800 3.6052 +0.4050 0.2025 3.6052 +0.4500 0.2250 3.6052 +0.4950 0.2475 3.6052 +0.5400 0.2700 3.6052 +0.5850 0.2925 3.6052 +0.6300 0.3150 3.6052 +0.6750 0.3375 3.6052 +0.7200 0.3600 3.6052 +0.7650 0.3825 3.6052 +0.8100 0.4050 3.6052 +0.8550 0.4275 3.6052 +0.9000 0.4500 3.6052 +0.9450 0.4725 3.6052 +0.9900 0.4950 3.6052 +1.0350 0.5175 3.6052 +1.0800 0.5400 3.6052 +1.1250 0.5625 3.6052 +1.1700 0.5850 3.6052 +1.2150 0.6075 3.6052 +1.2600 0.6300 3.6052 +1.3050 0.6525 3.6052 +1.3500 0.6750 3.6052 +1.3950 0.6975 3.6052 +1.4400 0.7200 3.6052 +1.4850 0.7425 3.6052 +1.5300 0.7650 3.6052 +1.5750 0.7875 3.6052 +1.6200 0.8100 3.6052 +1.6650 0.8325 3.6052 +1.7100 0.8550 3.6052 +1.7550 0.8775 3.6052 +1.8000 0.9000 3.6052 +primID: 7 +startangle_c: 9 +endpose_c: 18 13 10 +additionalactioncostmult: 3 +turning_radius: -6.9307 +intermediateposes: 45 +0.0000 0.0000 3.6052 +0.0452 0.0229 3.6126 +0.0903 0.0461 3.6199 +0.1351 0.0696 3.6272 +0.1799 0.0935 3.6345 +0.2244 0.1176 3.6418 +0.2687 0.1421 3.6491 +0.3129 0.1670 3.6564 +0.3569 0.1921 3.6637 +0.4007 0.2176 3.6711 +0.4443 0.2434 3.6784 +0.4878 0.2695 3.6857 +0.5310 0.2960 3.6930 +0.5740 0.3227 3.7003 +0.6169 0.3498 3.7076 +0.6595 0.3771 3.7149 +0.7020 0.4048 3.7222 +0.7442 0.4328 3.7296 +0.7863 0.4611 3.7369 +0.8281 0.4897 3.7442 +0.8697 0.5187 3.7515 +0.9111 0.5479 3.7588 +0.9523 0.5774 3.7661 +0.9933 0.6072 3.7734 +1.0341 0.6373 3.7807 +1.0746 0.6678 3.7881 +1.1149 0.6985 3.7954 +1.1550 0.7295 3.8027 +1.1949 0.7608 3.8100 +1.2345 0.7924 3.8173 +1.2739 0.8243 3.8246 +1.3131 0.8564 3.8319 +1.3520 0.8889 3.8392 +1.3907 0.9216 3.8466 +1.4291 0.9547 3.8539 +1.4673 0.9880 3.8612 +1.5053 1.0215 3.8685 +1.5430 1.0554 3.8758 +1.5805 1.0895 3.8831 +1.6177 1.1239 3.8904 +1.6547 1.1586 3.8977 +1.6914 1.1936 3.9051 +1.7279 1.2288 3.9124 +1.7641 1.2643 3.9197 +1.8000 1.3000 3.9270 +primID: 8 +startangle_c: 9 +endpose_c: 17 4 8 +additionalactioncostmult: 3 +turning_radius: 3.8007 +intermediateposes: 35 +0.0000 0.0000 3.6052 +0.0465 0.0228 3.5916 +0.0934 0.0450 3.5780 +0.1405 0.0666 3.5643 +0.1879 0.0875 3.5507 +0.2356 0.1077 3.5371 +0.2836 0.1273 3.5234 +0.3318 0.1463 3.5098 +0.3803 0.1646 3.4961 +0.4290 0.1822 3.4825 +0.4780 0.1991 3.4689 +0.5272 0.2154 3.4552 +0.5766 0.2310 3.4416 +0.6262 0.2460 3.4280 +0.6761 0.2603 3.4143 +0.7261 0.2738 3.4007 +0.7763 0.2867 3.3871 +0.8266 0.2990 3.3734 +0.8772 0.3105 3.3598 +0.9279 0.3213 3.3461 +0.9787 0.3315 3.3325 +1.0296 0.3409 3.3189 +1.0807 0.3497 3.3052 +1.1319 0.3577 3.2916 +1.1832 0.3651 3.2780 +1.2346 0.3717 3.2643 +1.2861 0.3777 3.2507 +1.3377 0.3830 3.2370 +1.3893 0.3875 3.2234 +1.4410 0.3914 3.2098 +1.4928 0.3945 3.1961 +1.5445 0.3969 3.1825 +1.5963 0.3987 3.1689 +1.6482 0.3997 3.1552 +1.7000 0.4000 3.1416 +primID: 9 +startangle_c: 9 +endpose_c: 0 0 8 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 9 +0.0000 0.0000 3.6052 +0.0000 0.0000 3.5473 +0.0000 0.0000 3.4893 +0.0000 0.0000 3.4314 +0.0000 0.0000 3.3734 +0.0000 0.0000 3.3155 +0.0000 0.0000 3.2575 +0.0000 0.0000 3.1995 +0.0000 0.0000 3.1416 +primID: 0 +startangle_c: 10 +endpose_c: -1 -1 10 +additionalactioncostmult: 1 +turning_radius: 0.0000 +intermediateposes: 3 +0.0000 0.0000 3.9270 +-0.0500 -0.0500 3.9270 +-0.1000 -0.1000 3.9270 +primID: 1 +startangle_c: 10 +endpose_c: -15 -15 10 +additionalactioncostmult: 1 +turning_radius: 0.0000 +intermediateposes: 43 +0.0000 0.0000 3.9270 +-0.0357 -0.0357 3.9270 +-0.0714 -0.0714 3.9270 +-0.1071 -0.1071 3.9270 +-0.1429 -0.1429 3.9270 +-0.1786 -0.1786 3.9270 +-0.2143 -0.2143 3.9270 +-0.2500 -0.2500 3.9270 +-0.2857 -0.2857 3.9270 +-0.3214 -0.3214 3.9270 +-0.3571 -0.3571 3.9270 +-0.3929 -0.3929 3.9270 +-0.4286 -0.4286 3.9270 +-0.4643 -0.4643 3.9270 +-0.5000 -0.5000 3.9270 +-0.5357 -0.5357 3.9270 +-0.5714 -0.5714 3.9270 +-0.6071 -0.6071 3.9270 +-0.6429 -0.6429 3.9270 +-0.6786 -0.6786 3.9270 +-0.7143 -0.7143 3.9270 +-0.7500 -0.7500 3.9270 +-0.7857 -0.7857 3.9270 +-0.8214 -0.8214 3.9270 +-0.8571 -0.8571 3.9270 +-0.8929 -0.8929 3.9270 +-0.9286 -0.9286 3.9270 +-0.9643 -0.9643 3.9270 +-1.0000 -1.0000 3.9270 +-1.0357 -1.0357 3.9270 +-1.0714 -1.0714 3.9270 +-1.1071 -1.1071 3.9270 +-1.1429 -1.1429 3.9270 +-1.1786 -1.1786 3.9270 +-1.2143 -1.2143 3.9270 +-1.2500 -1.2500 3.9270 +-1.2857 -1.2857 3.9270 +-1.3214 -1.3214 3.9270 +-1.3571 -1.3571 3.9270 +-1.3929 -1.3929 3.9270 +-1.4286 -1.4286 3.9270 +-1.4643 -1.4643 3.9270 +-1.5000 -1.5000 3.9270 +primID: 2 +startangle_c: 10 +endpose_c: -13 -18 11 +additionalactioncostmult: 2 +turning_radius: 6.9307 +intermediateposes: 45 +0.0000 0.0000 3.9270 +-0.0357 -0.0359 3.9343 +-0.0712 -0.0721 3.9416 +-0.1064 -0.1086 3.9489 +-0.1414 -0.1453 3.9562 +-0.1761 -0.1823 3.9636 +-0.2105 -0.2195 3.9709 +-0.2446 -0.2570 3.9782 +-0.2785 -0.2947 3.9855 +-0.3120 -0.3327 3.9928 +-0.3453 -0.3709 4.0001 +-0.3784 -0.4093 4.0074 +-0.4111 -0.4480 4.0147 +-0.4436 -0.4869 4.0221 +-0.4757 -0.5261 4.0294 +-0.5076 -0.5655 4.0367 +-0.5392 -0.6051 4.0440 +-0.5705 -0.6450 4.0513 +-0.6015 -0.6851 4.0586 +-0.6322 -0.7254 4.0659 +-0.6627 -0.7659 4.0732 +-0.6928 -0.8067 4.0806 +-0.7226 -0.8477 4.0879 +-0.7521 -0.8889 4.0952 +-0.7813 -0.9303 4.1025 +-0.8103 -0.9719 4.1098 +-0.8389 -1.0137 4.1171 +-0.8672 -1.0558 4.1244 +-0.8952 -1.0980 4.1317 +-0.9229 -1.1405 4.1391 +-0.9502 -1.1831 4.1464 +-0.9773 -1.2260 4.1537 +-1.0040 -1.2690 4.1610 +-1.0305 -1.3122 4.1683 +-1.0566 -1.3557 4.1756 +-1.0824 -1.3993 4.1829 +-1.1079 -1.4431 4.1902 +-1.1330 -1.4871 4.1976 +-1.1579 -1.5313 4.2049 +-1.1824 -1.5756 4.2122 +-1.2065 -1.6201 4.2195 +-1.2304 -1.6649 4.2268 +-1.2539 -1.7097 4.2341 +-1.2771 -1.7548 4.2414 +-1.3000 -1.8000 4.2487 +primID: 3 +startangle_c: 10 +endpose_c: -18 -13 9 +additionalactioncostmult: 2 +turning_radius: -6.9307 +intermediateposes: 45 +0.0000 0.0000 3.9270 +-0.0359 -0.0357 3.9197 +-0.0721 -0.0712 3.9124 +-0.1086 -0.1064 3.9051 +-0.1453 -0.1414 3.8977 +-0.1823 -0.1761 3.8904 +-0.2195 -0.2105 3.8831 +-0.2570 -0.2446 3.8758 +-0.2947 -0.2785 3.8685 +-0.3327 -0.3120 3.8612 +-0.3709 -0.3453 3.8539 +-0.4093 -0.3784 3.8466 +-0.4480 -0.4111 3.8392 +-0.4869 -0.4436 3.8319 +-0.5261 -0.4757 3.8246 +-0.5655 -0.5076 3.8173 +-0.6051 -0.5392 3.8100 +-0.6450 -0.5705 3.8027 +-0.6851 -0.6015 3.7954 +-0.7254 -0.6322 3.7881 +-0.7659 -0.6627 3.7807 +-0.8067 -0.6928 3.7734 +-0.8477 -0.7226 3.7661 +-0.8889 -0.7521 3.7588 +-0.9303 -0.7813 3.7515 +-0.9719 -0.8103 3.7442 +-1.0137 -0.8389 3.7369 +-1.0558 -0.8672 3.7296 +-1.0980 -0.8952 3.7222 +-1.1405 -0.9229 3.7149 +-1.1831 -0.9502 3.7076 +-1.2260 -0.9773 3.7003 +-1.2690 -1.0040 3.6930 +-1.3122 -1.0305 3.6857 +-1.3557 -1.0566 3.6784 +-1.3993 -1.0824 3.6711 +-1.4431 -1.1079 3.6637 +-1.4871 -1.1330 3.6564 +-1.5313 -1.1579 3.6491 +-1.5756 -1.1824 3.6418 +-1.6201 -1.2065 3.6345 +-1.6649 -1.2304 3.6272 +-1.7097 -1.2539 3.6199 +-1.7548 -1.2771 3.6126 +-1.8000 -1.3000 3.6052 +primID: 4 +startangle_c: 10 +endpose_c: 0 0 11 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 6 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.9913 +0.0000 0.0000 4.0557 +0.0000 0.0000 4.1200 +0.0000 0.0000 4.1844 +0.0000 0.0000 4.2487 +primID: 5 +startangle_c: 10 +endpose_c: 1 1 10 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 3 +0.0000 0.0000 3.9270 +0.0500 0.0500 3.9270 +0.1000 0.1000 3.9270 +primID: 6 +startangle_c: 10 +endpose_c: 16 16 10 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 46 +0.0000 0.0000 3.9270 +0.0356 0.0356 3.9270 +0.0711 0.0711 3.9270 +0.1067 0.1067 3.9270 +0.1422 0.1422 3.9270 +0.1778 0.1778 3.9270 +0.2133 0.2133 3.9270 +0.2489 0.2489 3.9270 +0.2844 0.2844 3.9270 +0.3200 0.3200 3.9270 +0.3556 0.3556 3.9270 +0.3911 0.3911 3.9270 +0.4267 0.4267 3.9270 +0.4622 0.4622 3.9270 +0.4978 0.4978 3.9270 +0.5333 0.5333 3.9270 +0.5689 0.5689 3.9270 +0.6044 0.6044 3.9270 +0.6400 0.6400 3.9270 +0.6756 0.6756 3.9270 +0.7111 0.7111 3.9270 +0.7467 0.7467 3.9270 +0.7822 0.7822 3.9270 +0.8178 0.8178 3.9270 +0.8533 0.8533 3.9270 +0.8889 0.8889 3.9270 +0.9244 0.9244 3.9270 +0.9600 0.9600 3.9270 +0.9956 0.9956 3.9270 +1.0311 1.0311 3.9270 +1.0667 1.0667 3.9270 +1.1022 1.1022 3.9270 +1.1378 1.1378 3.9270 +1.1733 1.1733 3.9270 +1.2089 1.2089 3.9270 +1.2444 1.2444 3.9270 +1.2800 1.2800 3.9270 +1.3156 1.3156 3.9270 +1.3511 1.3511 3.9270 +1.3867 1.3867 3.9270 +1.4222 1.4222 3.9270 +1.4578 1.4578 3.9270 +1.4933 1.4933 3.9270 +1.5289 1.5289 3.9270 +1.5644 1.5644 3.9270 +1.6000 1.6000 3.9270 +primID: 7 +startangle_c: 10 +endpose_c: 13 18 11 +additionalactioncostmult: 3 +turning_radius: -6.9307 +intermediateposes: 45 +0.0000 0.0000 3.9270 +0.0357 0.0359 3.9343 +0.0712 0.0721 3.9416 +0.1064 0.1086 3.9489 +0.1414 0.1453 3.9562 +0.1761 0.1823 3.9636 +0.2105 0.2195 3.9709 +0.2446 0.2570 3.9782 +0.2785 0.2947 3.9855 +0.3120 0.3327 3.9928 +0.3453 0.3709 4.0001 +0.3784 0.4093 4.0074 +0.4111 0.4480 4.0147 +0.4436 0.4869 4.0221 +0.4757 0.5261 4.0294 +0.5076 0.5655 4.0367 +0.5392 0.6051 4.0440 +0.5705 0.6450 4.0513 +0.6015 0.6851 4.0586 +0.6322 0.7254 4.0659 +0.6627 0.7659 4.0732 +0.6928 0.8067 4.0806 +0.7226 0.8477 4.0879 +0.7521 0.8889 4.0952 +0.7813 0.9303 4.1025 +0.8103 0.9719 4.1098 +0.8389 1.0137 4.1171 +0.8672 1.0558 4.1244 +0.8952 1.0980 4.1317 +0.9229 1.1405 4.1391 +0.9502 1.1831 4.1464 +0.9773 1.2260 4.1537 +1.0040 1.2690 4.1610 +1.0305 1.3122 4.1683 +1.0566 1.3557 4.1756 +1.0824 1.3993 4.1829 +1.1079 1.4431 4.1902 +1.1330 1.4871 4.1976 +1.1579 1.5313 4.2049 +1.1824 1.5756 4.2122 +1.2065 1.6201 4.2195 +1.2304 1.6649 4.2268 +1.2539 1.7097 4.2341 +1.2771 1.7548 4.2414 +1.3000 1.8000 4.2487 +primID: 8 +startangle_c: 10 +endpose_c: 18 13 9 +additionalactioncostmult: 3 +turning_radius: 6.9307 +intermediateposes: 45 +0.0000 0.0000 3.9270 +0.0359 0.0357 3.9197 +0.0721 0.0712 3.9124 +0.1086 0.1064 3.9051 +0.1453 0.1414 3.8977 +0.1823 0.1761 3.8904 +0.2195 0.2105 3.8831 +0.2570 0.2446 3.8758 +0.2947 0.2785 3.8685 +0.3327 0.3120 3.8612 +0.3709 0.3453 3.8539 +0.4093 0.3784 3.8466 +0.4480 0.4111 3.8392 +0.4869 0.4436 3.8319 +0.5261 0.4757 3.8246 +0.5655 0.5076 3.8173 +0.6051 0.5392 3.8100 +0.6450 0.5705 3.8027 +0.6851 0.6015 3.7954 +0.7254 0.6322 3.7881 +0.7659 0.6627 3.7807 +0.8067 0.6928 3.7734 +0.8477 0.7226 3.7661 +0.8889 0.7521 3.7588 +0.9303 0.7813 3.7515 +0.9719 0.8103 3.7442 +1.0137 0.8389 3.7369 +1.0558 0.8672 3.7296 +1.0980 0.8952 3.7222 +1.1405 0.9229 3.7149 +1.1831 0.9502 3.7076 +1.2260 0.9773 3.7003 +1.2690 1.0040 3.6930 +1.3122 1.0305 3.6857 +1.3557 1.0566 3.6784 +1.3993 1.0824 3.6711 +1.4431 1.1079 3.6637 +1.4871 1.1330 3.6564 +1.5313 1.1579 3.6491 +1.5756 1.1824 3.6418 +1.6201 1.2065 3.6345 +1.6649 1.2304 3.6272 +1.7097 1.2539 3.6199 +1.7548 1.2771 3.6126 +1.8000 1.3000 3.6052 +primID: 9 +startangle_c: 10 +endpose_c: 0 0 9 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 6 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.8626 +0.0000 0.0000 3.7983 +0.0000 0.0000 3.7339 +0.0000 0.0000 3.6696 +0.0000 0.0000 3.6052 +primID: 0 +startangle_c: 11 +endpose_c: -1 -2 11 +additionalactioncostmult: 1 +turning_radius: -0.0000 +intermediateposes: 5 +0.0000 0.0000 4.2487 +-0.0250 -0.0500 4.2487 +-0.0500 -0.1000 4.2487 +-0.0750 -0.1500 4.2487 +-0.1000 -0.2000 4.2487 +primID: 1 +startangle_c: 11 +endpose_c: -9 -18 11 +additionalactioncostmult: 1 +turning_radius: -0.0000 +intermediateposes: 41 +0.0000 0.0000 4.2487 +-0.0225 -0.0450 4.2487 +-0.0450 -0.0900 4.2487 +-0.0675 -0.1350 4.2487 +-0.0900 -0.1800 4.2487 +-0.1125 -0.2250 4.2487 +-0.1350 -0.2700 4.2487 +-0.1575 -0.3150 4.2487 +-0.1800 -0.3600 4.2487 +-0.2025 -0.4050 4.2487 +-0.2250 -0.4500 4.2487 +-0.2475 -0.4950 4.2487 +-0.2700 -0.5400 4.2487 +-0.2925 -0.5850 4.2487 +-0.3150 -0.6300 4.2487 +-0.3375 -0.6750 4.2487 +-0.3600 -0.7200 4.2487 +-0.3825 -0.7650 4.2487 +-0.4050 -0.8100 4.2487 +-0.4275 -0.8550 4.2487 +-0.4500 -0.9000 4.2487 +-0.4725 -0.9450 4.2487 +-0.4950 -0.9900 4.2487 +-0.5175 -1.0350 4.2487 +-0.5400 -1.0800 4.2487 +-0.5625 -1.1250 4.2487 +-0.5850 -1.1700 4.2487 +-0.6075 -1.2150 4.2487 +-0.6300 -1.2600 4.2487 +-0.6525 -1.3050 4.2487 +-0.6750 -1.3500 4.2487 +-0.6975 -1.3950 4.2487 +-0.7200 -1.4400 4.2487 +-0.7425 -1.4850 4.2487 +-0.7650 -1.5300 4.2487 +-0.7875 -1.5750 4.2487 +-0.8100 -1.6200 4.2487 +-0.8325 -1.6650 4.2487 +-0.8550 -1.7100 4.2487 +-0.8775 -1.7550 4.2487 +-0.9000 -1.8000 4.2487 +primID: 2 +startangle_c: 11 +endpose_c: -13 -18 10 +additionalactioncostmult: 2 +turning_radius: -6.9307 +intermediateposes: 45 +0.0000 0.0000 4.2487 +-0.0229 -0.0452 4.2414 +-0.0461 -0.0903 4.2341 +-0.0696 -0.1351 4.2268 +-0.0935 -0.1799 4.2195 +-0.1176 -0.2244 4.2122 +-0.1421 -0.2687 4.2049 +-0.1670 -0.3129 4.1976 +-0.1921 -0.3569 4.1902 +-0.2176 -0.4007 4.1829 +-0.2434 -0.4443 4.1756 +-0.2695 -0.4878 4.1683 +-0.2960 -0.5310 4.1610 +-0.3227 -0.5740 4.1537 +-0.3498 -0.6169 4.1464 +-0.3771 -0.6595 4.1391 +-0.4048 -0.7020 4.1317 +-0.4328 -0.7442 4.1244 +-0.4611 -0.7863 4.1171 +-0.4897 -0.8281 4.1098 +-0.5187 -0.8697 4.1025 +-0.5479 -0.9111 4.0952 +-0.5774 -0.9523 4.0879 +-0.6072 -0.9933 4.0806 +-0.6373 -1.0341 4.0732 +-0.6678 -1.0746 4.0659 +-0.6985 -1.1149 4.0586 +-0.7295 -1.1550 4.0513 +-0.7608 -1.1949 4.0440 +-0.7924 -1.2345 4.0367 +-0.8243 -1.2739 4.0294 +-0.8564 -1.3131 4.0221 +-0.8889 -1.3520 4.0147 +-0.9216 -1.3907 4.0074 +-0.9547 -1.4291 4.0001 +-0.9880 -1.4673 3.9928 +-1.0215 -1.5053 3.9855 +-1.0554 -1.5430 3.9782 +-1.0895 -1.5805 3.9709 +-1.1239 -1.6177 3.9636 +-1.1586 -1.6547 3.9562 +-1.1936 -1.6914 3.9489 +-1.2288 -1.7279 3.9416 +-1.2643 -1.7641 3.9343 +-1.3000 -1.8000 3.9270 +primID: 3 +startangle_c: 11 +endpose_c: -4 -17 12 +additionalactioncostmult: 2 +turning_radius: 3.8007 +intermediateposes: 35 +0.0000 0.0000 4.2487 +-0.0228 -0.0465 4.2624 +-0.0450 -0.0934 4.2760 +-0.0666 -0.1405 4.2897 +-0.0875 -0.1879 4.3033 +-0.1077 -0.2356 4.3169 +-0.1273 -0.2836 4.3306 +-0.1463 -0.3318 4.3442 +-0.1646 -0.3803 4.3578 +-0.1822 -0.4290 4.3715 +-0.1991 -0.4780 4.3851 +-0.2154 -0.5272 4.3987 +-0.2310 -0.5766 4.4124 +-0.2460 -0.6262 4.4260 +-0.2603 -0.6761 4.4397 +-0.2738 -0.7261 4.4533 +-0.2867 -0.7763 4.4669 +-0.2990 -0.8266 4.4806 +-0.3105 -0.8772 4.4942 +-0.3213 -0.9279 4.5078 +-0.3315 -0.9787 4.5215 +-0.3409 -1.0296 4.5351 +-0.3497 -1.0807 4.5487 +-0.3577 -1.1319 4.5624 +-0.3651 -1.1832 4.5760 +-0.3717 -1.2346 4.5897 +-0.3777 -1.2861 4.6033 +-0.3830 -1.3377 4.6169 +-0.3875 -1.3893 4.6306 +-0.3914 -1.4410 4.6442 +-0.3945 -1.4928 4.6578 +-0.3969 -1.5445 4.6715 +-0.3987 -1.5963 4.6851 +-0.3997 -1.6482 4.6988 +-0.4000 -1.7000 4.7124 +primID: 4 +startangle_c: 11 +endpose_c: 0 0 10 +additionalactioncostmult: 5 +turning_radius: -0.0000 +intermediateposes: 6 +0.0000 0.0000 4.2487 +0.0000 0.0000 4.1844 +0.0000 0.0000 4.1200 +0.0000 0.0000 4.0557 +0.0000 0.0000 3.9913 +0.0000 0.0000 3.9270 +primID: 5 +startangle_c: 11 +endpose_c: 1 2 11 +additionalactioncostmult: 5 +turning_radius: -0.0000 +intermediateposes: 5 +0.0000 0.0000 4.2487 +0.0250 0.0500 4.2487 +0.0500 0.1000 4.2487 +0.0750 0.1500 4.2487 +0.1000 0.2000 4.2487 +primID: 6 +startangle_c: 11 +endpose_c: 9 18 11 +additionalactioncostmult: 5 +turning_radius: -0.0000 +intermediateposes: 41 +0.0000 0.0000 4.2487 +0.0225 0.0450 4.2487 +0.0450 0.0900 4.2487 +0.0675 0.1350 4.2487 +0.0900 0.1800 4.2487 +0.1125 0.2250 4.2487 +0.1350 0.2700 4.2487 +0.1575 0.3150 4.2487 +0.1800 0.3600 4.2487 +0.2025 0.4050 4.2487 +0.2250 0.4500 4.2487 +0.2475 0.4950 4.2487 +0.2700 0.5400 4.2487 +0.2925 0.5850 4.2487 +0.3150 0.6300 4.2487 +0.3375 0.6750 4.2487 +0.3600 0.7200 4.2487 +0.3825 0.7650 4.2487 +0.4050 0.8100 4.2487 +0.4275 0.8550 4.2487 +0.4500 0.9000 4.2487 +0.4725 0.9450 4.2487 +0.4950 0.9900 4.2487 +0.5175 1.0350 4.2487 +0.5400 1.0800 4.2487 +0.5625 1.1250 4.2487 +0.5850 1.1700 4.2487 +0.6075 1.2150 4.2487 +0.6300 1.2600 4.2487 +0.6525 1.3050 4.2487 +0.6750 1.3500 4.2487 +0.6975 1.3950 4.2487 +0.7200 1.4400 4.2487 +0.7425 1.4850 4.2487 +0.7650 1.5300 4.2487 +0.7875 1.5750 4.2487 +0.8100 1.6200 4.2487 +0.8325 1.6650 4.2487 +0.8550 1.7100 4.2487 +0.8775 1.7550 4.2487 +0.9000 1.8000 4.2487 +primID: 7 +startangle_c: 11 +endpose_c: 13 18 10 +additionalactioncostmult: 3 +turning_radius: 6.9307 +intermediateposes: 45 +0.0000 0.0000 4.2487 +0.0229 0.0452 4.2414 +0.0461 0.0903 4.2341 +0.0696 0.1351 4.2268 +0.0935 0.1799 4.2195 +0.1176 0.2244 4.2122 +0.1421 0.2687 4.2049 +0.1670 0.3129 4.1976 +0.1921 0.3569 4.1902 +0.2176 0.4007 4.1829 +0.2434 0.4443 4.1756 +0.2695 0.4878 4.1683 +0.2960 0.5310 4.1610 +0.3227 0.5740 4.1537 +0.3498 0.6169 4.1464 +0.3771 0.6595 4.1391 +0.4048 0.7020 4.1317 +0.4328 0.7442 4.1244 +0.4611 0.7863 4.1171 +0.4897 0.8281 4.1098 +0.5187 0.8697 4.1025 +0.5479 0.9111 4.0952 +0.5774 0.9523 4.0879 +0.6072 0.9933 4.0806 +0.6373 1.0341 4.0732 +0.6678 1.0746 4.0659 +0.6985 1.1149 4.0586 +0.7295 1.1550 4.0513 +0.7608 1.1949 4.0440 +0.7924 1.2345 4.0367 +0.8243 1.2739 4.0294 +0.8564 1.3131 4.0221 +0.8889 1.3520 4.0147 +0.9216 1.3907 4.0074 +0.9547 1.4291 4.0001 +0.9880 1.4673 3.9928 +1.0215 1.5053 3.9855 +1.0554 1.5430 3.9782 +1.0895 1.5805 3.9709 +1.1239 1.6177 3.9636 +1.1586 1.6547 3.9562 +1.1936 1.6914 3.9489 +1.2288 1.7279 3.9416 +1.2643 1.7641 3.9343 +1.3000 1.8000 3.9270 +primID: 8 +startangle_c: 11 +endpose_c: 4 17 12 +additionalactioncostmult: 3 +turning_radius: -3.8007 +intermediateposes: 35 +0.0000 0.0000 4.2487 +0.0228 0.0465 4.2624 +0.0450 0.0934 4.2760 +0.0666 0.1405 4.2897 +0.0875 0.1879 4.3033 +0.1077 0.2356 4.3169 +0.1273 0.2836 4.3306 +0.1463 0.3318 4.3442 +0.1646 0.3803 4.3578 +0.1822 0.4290 4.3715 +0.1991 0.4780 4.3851 +0.2154 0.5272 4.3987 +0.2310 0.5766 4.4124 +0.2460 0.6262 4.4260 +0.2603 0.6761 4.4397 +0.2738 0.7261 4.4533 +0.2867 0.7763 4.4669 +0.2990 0.8266 4.4806 +0.3105 0.8772 4.4942 +0.3213 0.9279 4.5078 +0.3315 0.9787 4.5215 +0.3409 1.0296 4.5351 +0.3497 1.0807 4.5487 +0.3577 1.1319 4.5624 +0.3651 1.1832 4.5760 +0.3717 1.2346 4.5897 +0.3777 1.2861 4.6033 +0.3830 1.3377 4.6169 +0.3875 1.3893 4.6306 +0.3914 1.4410 4.6442 +0.3945 1.4928 4.6578 +0.3969 1.5445 4.6715 +0.3987 1.5963 4.6851 +0.3997 1.6482 4.6988 +0.4000 1.7000 4.7124 +primID: 9 +startangle_c: 11 +endpose_c: 0 0 12 +additionalactioncostmult: 5 +turning_radius: -0.0000 +intermediateposes: 9 +0.0000 0.0000 4.2487 +0.0000 0.0000 4.3067 +0.0000 0.0000 4.3647 +0.0000 0.0000 4.4226 +0.0000 0.0000 4.4806 +0.0000 0.0000 4.5385 +0.0000 0.0000 4.5965 +0.0000 0.0000 4.6544 +0.0000 0.0000 4.7124 +primID: 0 +startangle_c: 12 +endpose_c: 0 -1 12 +additionalactioncostmult: 1 +turning_radius: 0.0000 +intermediateposes: 3 +0.0000 0.0000 4.7124 +0.0000 -0.0500 4.7124 +0.0000 -0.1000 4.7124 +primID: 1 +startangle_c: 12 +endpose_c: 0 -17 12 +additionalactioncostmult: 1 +turning_radius: 0.0000 +intermediateposes: 35 +0.0000 0.0000 4.7124 +0.0000 -0.0500 4.7124 +0.0000 -0.1000 4.7124 +0.0000 -0.1500 4.7124 +0.0000 -0.2000 4.7124 +0.0000 -0.2500 4.7124 +0.0000 -0.3000 4.7124 +0.0000 -0.3500 4.7124 +0.0000 -0.4000 4.7124 +0.0000 -0.4500 4.7124 +0.0000 -0.5000 4.7124 +0.0000 -0.5500 4.7124 +0.0000 -0.6000 4.7124 +0.0000 -0.6500 4.7124 +0.0000 -0.7000 4.7124 +0.0000 -0.7500 4.7124 +0.0000 -0.8000 4.7124 +0.0000 -0.8500 4.7124 +0.0000 -0.9000 4.7124 +0.0000 -0.9500 4.7124 +0.0000 -1.0000 4.7124 +0.0000 -1.0500 4.7124 +0.0000 -1.1000 4.7124 +0.0000 -1.1500 4.7124 +0.0000 -1.2000 4.7124 +0.0000 -1.2500 4.7124 +0.0000 -1.3000 4.7124 +0.0000 -1.3500 4.7124 +0.0000 -1.4000 4.7124 +0.0000 -1.4500 4.7124 +0.0000 -1.5000 4.7124 +0.0000 -1.5500 4.7124 +0.0000 -1.6000 4.7124 +0.0000 -1.6500 4.7124 +0.0000 -1.7000 4.7124 +primID: 2 +startangle_c: 12 +endpose_c: 4 -17 13 +additionalactioncostmult: 2 +turning_radius: 3.8007 +intermediateposes: 35 +0.0000 0.0000 4.7124 +0.0003 -0.0518 4.7260 +0.0013 -0.1037 4.7397 +0.0031 -0.1555 4.7533 +0.0055 -0.2072 4.7669 +0.0086 -0.2590 4.7806 +0.0125 -0.3107 4.7942 +0.0170 -0.3623 4.8078 +0.0223 -0.4139 4.8215 +0.0283 -0.4654 4.8351 +0.0349 -0.5168 4.8488 +0.0423 -0.5681 4.8624 +0.0503 -0.6193 4.8760 +0.0591 -0.6704 4.8897 +0.0685 -0.7213 4.9033 +0.0787 -0.7721 4.9169 +0.0895 -0.8228 4.9306 +0.1010 -0.8734 4.9442 +0.1133 -0.9237 4.9578 +0.1262 -0.9739 4.9715 +0.1397 -1.0239 4.9851 +0.1540 -1.0738 4.9988 +0.1690 -1.1234 5.0124 +0.1846 -1.1728 5.0260 +0.2009 -1.2220 5.0397 +0.2178 -1.2710 5.0533 +0.2354 -1.3197 5.0669 +0.2537 -1.3682 5.0806 +0.2727 -1.4164 5.0942 +0.2923 -1.4644 5.1079 +0.3125 -1.5121 5.1215 +0.3334 -1.5595 5.1351 +0.3550 -1.6066 5.1488 +0.3772 -1.6535 5.1624 +0.4000 -1.7000 5.1760 +primID: 3 +startangle_c: 12 +endpose_c: -4 -17 11 +additionalactioncostmult: 2 +turning_radius: -3.8007 +intermediateposes: 35 +0.0000 0.0000 4.7124 +-0.0003 -0.0518 4.6988 +-0.0013 -0.1037 4.6851 +-0.0031 -0.1555 4.6715 +-0.0055 -0.2072 4.6578 +-0.0086 -0.2590 4.6442 +-0.0125 -0.3107 4.6306 +-0.0170 -0.3623 4.6169 +-0.0223 -0.4139 4.6033 +-0.0283 -0.4654 4.5897 +-0.0349 -0.5168 4.5760 +-0.0423 -0.5681 4.5624 +-0.0503 -0.6193 4.5487 +-0.0591 -0.6704 4.5351 +-0.0685 -0.7213 4.5215 +-0.0787 -0.7721 4.5078 +-0.0895 -0.8228 4.4942 +-0.1010 -0.8734 4.4806 +-0.1133 -0.9237 4.4669 +-0.1262 -0.9739 4.4533 +-0.1397 -1.0239 4.4397 +-0.1540 -1.0738 4.4260 +-0.1690 -1.1234 4.4124 +-0.1846 -1.1728 4.3987 +-0.2009 -1.2220 4.3851 +-0.2178 -1.2710 4.3715 +-0.2354 -1.3197 4.3578 +-0.2537 -1.3682 4.3442 +-0.2727 -1.4164 4.3306 +-0.2923 -1.4644 4.3169 +-0.3125 -1.5121 4.3033 +-0.3334 -1.5595 4.2897 +-0.3550 -1.6066 4.2760 +-0.3772 -1.6535 4.2624 +-0.4000 -1.7000 4.2487 +primID: 4 +startangle_c: 12 +endpose_c: 0 0 13 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 9 +0.0000 0.0000 4.7124 +0.0000 0.0000 4.7703 +0.0000 0.0000 4.8283 +0.0000 0.0000 4.8863 +0.0000 0.0000 4.9442 +0.0000 0.0000 5.0022 +0.0000 0.0000 5.0601 +0.0000 0.0000 5.1181 +0.0000 0.0000 5.1760 +primID: 5 +startangle_c: 12 +endpose_c: 0 1 12 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 3 +0.0000 0.0000 4.7124 +0.0000 0.0500 4.7124 +0.0000 0.1000 4.7124 +primID: 6 +startangle_c: 12 +endpose_c: 0 17 12 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 35 +0.0000 0.0000 4.7124 +0.0000 0.0500 4.7124 +0.0000 0.1000 4.7124 +0.0000 0.1500 4.7124 +0.0000 0.2000 4.7124 +0.0000 0.2500 4.7124 +0.0000 0.3000 4.7124 +0.0000 0.3500 4.7124 +0.0000 0.4000 4.7124 +0.0000 0.4500 4.7124 +0.0000 0.5000 4.7124 +0.0000 0.5500 4.7124 +0.0000 0.6000 4.7124 +0.0000 0.6500 4.7124 +0.0000 0.7000 4.7124 +0.0000 0.7500 4.7124 +0.0000 0.8000 4.7124 +0.0000 0.8500 4.7124 +0.0000 0.9000 4.7124 +0.0000 0.9500 4.7124 +0.0000 1.0000 4.7124 +0.0000 1.0500 4.7124 +0.0000 1.1000 4.7124 +0.0000 1.1500 4.7124 +0.0000 1.2000 4.7124 +0.0000 1.2500 4.7124 +0.0000 1.3000 4.7124 +0.0000 1.3500 4.7124 +0.0000 1.4000 4.7124 +0.0000 1.4500 4.7124 +0.0000 1.5000 4.7124 +0.0000 1.5500 4.7124 +0.0000 1.6000 4.7124 +0.0000 1.6500 4.7124 +0.0000 1.7000 4.7124 +primID: 7 +startangle_c: 12 +endpose_c: -4 17 13 +additionalactioncostmult: 3 +turning_radius: -3.8007 +intermediateposes: 35 +0.0000 0.0000 4.7124 +-0.0003 0.0518 4.7260 +-0.0013 0.1037 4.7397 +-0.0031 0.1555 4.7533 +-0.0055 0.2072 4.7669 +-0.0086 0.2590 4.7806 +-0.0125 0.3107 4.7942 +-0.0170 0.3623 4.8078 +-0.0223 0.4139 4.8215 +-0.0283 0.4654 4.8351 +-0.0349 0.5168 4.8488 +-0.0423 0.5681 4.8624 +-0.0503 0.6193 4.8760 +-0.0591 0.6704 4.8897 +-0.0685 0.7213 4.9033 +-0.0787 0.7721 4.9169 +-0.0895 0.8228 4.9306 +-0.1010 0.8734 4.9442 +-0.1133 0.9237 4.9578 +-0.1262 0.9739 4.9715 +-0.1397 1.0239 4.9851 +-0.1540 1.0738 4.9988 +-0.1690 1.1234 5.0124 +-0.1846 1.1728 5.0260 +-0.2009 1.2220 5.0397 +-0.2178 1.2710 5.0533 +-0.2354 1.3197 5.0669 +-0.2537 1.3682 5.0806 +-0.2727 1.4164 5.0942 +-0.2923 1.4644 5.1079 +-0.3125 1.5121 5.1215 +-0.3334 1.5595 5.1351 +-0.3550 1.6066 5.1488 +-0.3772 1.6535 5.1624 +-0.4000 1.7000 5.1760 +primID: 8 +startangle_c: 12 +endpose_c: 4 17 11 +additionalactioncostmult: 3 +turning_radius: 3.8007 +intermediateposes: 35 +0.0000 0.0000 4.7124 +0.0003 0.0518 4.6988 +0.0013 0.1037 4.6851 +0.0031 0.1555 4.6715 +0.0055 0.2072 4.6578 +0.0086 0.2590 4.6442 +0.0125 0.3107 4.6306 +0.0170 0.3623 4.6169 +0.0223 0.4139 4.6033 +0.0283 0.4654 4.5897 +0.0349 0.5168 4.5760 +0.0423 0.5681 4.5624 +0.0503 0.6193 4.5487 +0.0591 0.6704 4.5351 +0.0685 0.7213 4.5215 +0.0787 0.7721 4.5078 +0.0895 0.8228 4.4942 +0.1010 0.8734 4.4806 +0.1133 0.9237 4.4669 +0.1262 0.9739 4.4533 +0.1397 1.0239 4.4397 +0.1540 1.0738 4.4260 +0.1690 1.1234 4.4124 +0.1846 1.1728 4.3987 +0.2009 1.2220 4.3851 +0.2178 1.2710 4.3715 +0.2354 1.3197 4.3578 +0.2537 1.3682 4.3442 +0.2727 1.4164 4.3306 +0.2923 1.4644 4.3169 +0.3125 1.5121 4.3033 +0.3334 1.5595 4.2897 +0.3550 1.6066 4.2760 +0.3772 1.6535 4.2624 +0.4000 1.7000 4.2487 +primID: 9 +startangle_c: 12 +endpose_c: 0 0 11 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 9 +0.0000 0.0000 4.7124 +0.0000 0.0000 4.6544 +0.0000 0.0000 4.5965 +0.0000 0.0000 4.5385 +0.0000 0.0000 4.4806 +0.0000 0.0000 4.4226 +0.0000 0.0000 4.3647 +0.0000 0.0000 4.3067 +0.0000 0.0000 4.2487 +primID: 0 +startangle_c: 13 +endpose_c: 1 -2 13 +additionalactioncostmult: 1 +turning_radius: 0.0000 +intermediateposes: 5 +0.0000 0.0000 5.1760 +0.0250 -0.0500 5.1760 +0.0500 -0.1000 5.1760 +0.0750 -0.1500 5.1760 +0.1000 -0.2000 5.1760 +primID: 1 +startangle_c: 13 +endpose_c: 9 -18 13 +additionalactioncostmult: 1 +turning_radius: 0.0000 +intermediateposes: 41 +0.0000 0.0000 5.1760 +0.0225 -0.0450 5.1760 +0.0450 -0.0900 5.1760 +0.0675 -0.1350 5.1760 +0.0900 -0.1800 5.1760 +0.1125 -0.2250 5.1760 +0.1350 -0.2700 5.1760 +0.1575 -0.3150 5.1760 +0.1800 -0.3600 5.1760 +0.2025 -0.4050 5.1760 +0.2250 -0.4500 5.1760 +0.2475 -0.4950 5.1760 +0.2700 -0.5400 5.1760 +0.2925 -0.5850 5.1760 +0.3150 -0.6300 5.1760 +0.3375 -0.6750 5.1760 +0.3600 -0.7200 5.1760 +0.3825 -0.7650 5.1760 +0.4050 -0.8100 5.1760 +0.4275 -0.8550 5.1760 +0.4500 -0.9000 5.1760 +0.4725 -0.9450 5.1760 +0.4950 -0.9900 5.1760 +0.5175 -1.0350 5.1760 +0.5400 -1.0800 5.1760 +0.5625 -1.1250 5.1760 +0.5850 -1.1700 5.1760 +0.6075 -1.2150 5.1760 +0.6300 -1.2600 5.1760 +0.6525 -1.3050 5.1760 +0.6750 -1.3500 5.1760 +0.6975 -1.3950 5.1760 +0.7200 -1.4400 5.1760 +0.7425 -1.4850 5.1760 +0.7650 -1.5300 5.1760 +0.7875 -1.5750 5.1760 +0.8100 -1.6200 5.1760 +0.8325 -1.6650 5.1760 +0.8550 -1.7100 5.1760 +0.8775 -1.7550 5.1760 +0.9000 -1.8000 5.1760 +primID: 2 +startangle_c: 13 +endpose_c: 13 -18 14 +additionalactioncostmult: 2 +turning_radius: 6.9307 +intermediateposes: 45 +0.0000 0.0000 5.1760 +0.0229 -0.0452 5.1833 +0.0461 -0.0903 5.1907 +0.0696 -0.1351 5.1980 +0.0935 -0.1799 5.2053 +0.1176 -0.2244 5.2126 +0.1421 -0.2687 5.2199 +0.1670 -0.3129 5.2272 +0.1921 -0.3569 5.2345 +0.2176 -0.4007 5.2418 +0.2434 -0.4443 5.2492 +0.2695 -0.4878 5.2565 +0.2960 -0.5310 5.2638 +0.3227 -0.5740 5.2711 +0.3498 -0.6169 5.2784 +0.3771 -0.6595 5.2857 +0.4048 -0.7020 5.2930 +0.4328 -0.7442 5.3003 +0.4611 -0.7863 5.3077 +0.4897 -0.8281 5.3150 +0.5187 -0.8697 5.3223 +0.5479 -0.9111 5.3296 +0.5774 -0.9523 5.3369 +0.6072 -0.9933 5.3442 +0.6373 -1.0341 5.3515 +0.6678 -1.0746 5.3588 +0.6985 -1.1149 5.3662 +0.7295 -1.1550 5.3735 +0.7608 -1.1949 5.3808 +0.7924 -1.2345 5.3881 +0.8243 -1.2739 5.3954 +0.8564 -1.3131 5.4027 +0.8889 -1.3520 5.4100 +0.9216 -1.3907 5.4173 +0.9547 -1.4291 5.4247 +0.9880 -1.4673 5.4320 +1.0215 -1.5053 5.4393 +1.0554 -1.5430 5.4466 +1.0895 -1.5805 5.4539 +1.1239 -1.6177 5.4612 +1.1586 -1.6547 5.4685 +1.1936 -1.6914 5.4758 +1.2288 -1.7279 5.4832 +1.2643 -1.7641 5.4905 +1.3000 -1.8000 5.4978 +primID: 3 +startangle_c: 13 +endpose_c: 4 -17 12 +additionalactioncostmult: 2 +turning_radius: -3.8007 +intermediateposes: 35 +0.0000 0.0000 5.1760 +0.0228 -0.0465 5.1624 +0.0450 -0.0934 5.1488 +0.0666 -0.1405 5.1351 +0.0875 -0.1879 5.1215 +0.1077 -0.2356 5.1079 +0.1273 -0.2836 5.0942 +0.1463 -0.3318 5.0806 +0.1646 -0.3803 5.0669 +0.1822 -0.4290 5.0533 +0.1991 -0.4780 5.0397 +0.2154 -0.5272 5.0260 +0.2310 -0.5766 5.0124 +0.2460 -0.6262 4.9988 +0.2603 -0.6761 4.9851 +0.2738 -0.7261 4.9715 +0.2867 -0.7763 4.9578 +0.2990 -0.8266 4.9442 +0.3105 -0.8772 4.9306 +0.3213 -0.9279 4.9169 +0.3315 -0.9787 4.9033 +0.3409 -1.0296 4.8897 +0.3497 -1.0807 4.8760 +0.3577 -1.1319 4.8624 +0.3651 -1.1832 4.8488 +0.3717 -1.2346 4.8351 +0.3777 -1.2861 4.8215 +0.3830 -1.3377 4.8078 +0.3875 -1.3893 4.7942 +0.3914 -1.4410 4.7806 +0.3945 -1.4928 4.7669 +0.3969 -1.5445 4.7533 +0.3987 -1.5963 4.7397 +0.3997 -1.6482 4.7260 +0.4000 -1.7000 4.7124 +primID: 4 +startangle_c: 13 +endpose_c: 0 0 14 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 6 +0.0000 0.0000 5.1760 +0.0000 0.0000 5.2404 +0.0000 0.0000 5.3047 +0.0000 0.0000 5.3691 +0.0000 0.0000 5.4334 +0.0000 0.0000 5.4978 +primID: 5 +startangle_c: 13 +endpose_c: -1 2 13 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 5 +0.0000 0.0000 5.1760 +-0.0250 0.0500 5.1760 +-0.0500 0.1000 5.1760 +-0.0750 0.1500 5.1760 +-0.1000 0.2000 5.1760 +primID: 6 +startangle_c: 13 +endpose_c: -9 18 13 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 41 +0.0000 0.0000 5.1760 +-0.0225 0.0450 5.1760 +-0.0450 0.0900 5.1760 +-0.0675 0.1350 5.1760 +-0.0900 0.1800 5.1760 +-0.1125 0.2250 5.1760 +-0.1350 0.2700 5.1760 +-0.1575 0.3150 5.1760 +-0.1800 0.3600 5.1760 +-0.2025 0.4050 5.1760 +-0.2250 0.4500 5.1760 +-0.2475 0.4950 5.1760 +-0.2700 0.5400 5.1760 +-0.2925 0.5850 5.1760 +-0.3150 0.6300 5.1760 +-0.3375 0.6750 5.1760 +-0.3600 0.7200 5.1760 +-0.3825 0.7650 5.1760 +-0.4050 0.8100 5.1760 +-0.4275 0.8550 5.1760 +-0.4500 0.9000 5.1760 +-0.4725 0.9450 5.1760 +-0.4950 0.9900 5.1760 +-0.5175 1.0350 5.1760 +-0.5400 1.0800 5.1760 +-0.5625 1.1250 5.1760 +-0.5850 1.1700 5.1760 +-0.6075 1.2150 5.1760 +-0.6300 1.2600 5.1760 +-0.6525 1.3050 5.1760 +-0.6750 1.3500 5.1760 +-0.6975 1.3950 5.1760 +-0.7200 1.4400 5.1760 +-0.7425 1.4850 5.1760 +-0.7650 1.5300 5.1760 +-0.7875 1.5750 5.1760 +-0.8100 1.6200 5.1760 +-0.8325 1.6650 5.1760 +-0.8550 1.7100 5.1760 +-0.8775 1.7550 5.1760 +-0.9000 1.8000 5.1760 +primID: 7 +startangle_c: 13 +endpose_c: -13 18 14 +additionalactioncostmult: 3 +turning_radius: -6.9307 +intermediateposes: 45 +0.0000 0.0000 5.1760 +-0.0229 0.0452 5.1833 +-0.0461 0.0903 5.1907 +-0.0696 0.1351 5.1980 +-0.0935 0.1799 5.2053 +-0.1176 0.2244 5.2126 +-0.1421 0.2687 5.2199 +-0.1670 0.3129 5.2272 +-0.1921 0.3569 5.2345 +-0.2176 0.4007 5.2418 +-0.2434 0.4443 5.2492 +-0.2695 0.4878 5.2565 +-0.2960 0.5310 5.2638 +-0.3227 0.5740 5.2711 +-0.3498 0.6169 5.2784 +-0.3771 0.6595 5.2857 +-0.4048 0.7020 5.2930 +-0.4328 0.7442 5.3003 +-0.4611 0.7863 5.3077 +-0.4897 0.8281 5.3150 +-0.5187 0.8697 5.3223 +-0.5479 0.9111 5.3296 +-0.5774 0.9523 5.3369 +-0.6072 0.9933 5.3442 +-0.6373 1.0341 5.3515 +-0.6678 1.0746 5.3588 +-0.6985 1.1149 5.3662 +-0.7295 1.1550 5.3735 +-0.7608 1.1949 5.3808 +-0.7924 1.2345 5.3881 +-0.8243 1.2739 5.3954 +-0.8564 1.3131 5.4027 +-0.8889 1.3520 5.4100 +-0.9216 1.3907 5.4173 +-0.9547 1.4291 5.4247 +-0.9880 1.4673 5.4320 +-1.0215 1.5053 5.4393 +-1.0554 1.5430 5.4466 +-1.0895 1.5805 5.4539 +-1.1239 1.6177 5.4612 +-1.1586 1.6547 5.4685 +-1.1936 1.6914 5.4758 +-1.2288 1.7279 5.4832 +-1.2643 1.7641 5.4905 +-1.3000 1.8000 5.4978 +primID: 8 +startangle_c: 13 +endpose_c: -4 17 12 +additionalactioncostmult: 3 +turning_radius: 3.8007 +intermediateposes: 35 +0.0000 0.0000 5.1760 +-0.0228 0.0465 5.1624 +-0.0450 0.0934 5.1488 +-0.0666 0.1405 5.1351 +-0.0875 0.1879 5.1215 +-0.1077 0.2356 5.1079 +-0.1273 0.2836 5.0942 +-0.1463 0.3318 5.0806 +-0.1646 0.3803 5.0669 +-0.1822 0.4290 5.0533 +-0.1991 0.4780 5.0397 +-0.2154 0.5272 5.0260 +-0.2310 0.5766 5.0124 +-0.2460 0.6262 4.9988 +-0.2603 0.6761 4.9851 +-0.2738 0.7261 4.9715 +-0.2867 0.7763 4.9578 +-0.2990 0.8266 4.9442 +-0.3105 0.8772 4.9306 +-0.3213 0.9279 4.9169 +-0.3315 0.9787 4.9033 +-0.3409 1.0296 4.8897 +-0.3497 1.0807 4.8760 +-0.3577 1.1319 4.8624 +-0.3651 1.1832 4.8488 +-0.3717 1.2346 4.8351 +-0.3777 1.2861 4.8215 +-0.3830 1.3377 4.8078 +-0.3875 1.3893 4.7942 +-0.3914 1.4410 4.7806 +-0.3945 1.4928 4.7669 +-0.3969 1.5445 4.7533 +-0.3987 1.5963 4.7397 +-0.3997 1.6482 4.7260 +-0.4000 1.7000 4.7124 +primID: 9 +startangle_c: 13 +endpose_c: 0 0 12 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 9 +0.0000 0.0000 5.1760 +0.0000 0.0000 5.1181 +0.0000 0.0000 5.0601 +0.0000 0.0000 5.0022 +0.0000 0.0000 4.9442 +0.0000 0.0000 4.8863 +0.0000 0.0000 4.8283 +0.0000 0.0000 4.7703 +0.0000 0.0000 4.7124 +primID: 0 +startangle_c: 14 +endpose_c: 1 -1 14 +additionalactioncostmult: 1 +turning_radius: 0.0000 +intermediateposes: 3 +0.0000 0.0000 5.4978 +0.0500 -0.0500 5.4978 +0.1000 -0.1000 5.4978 +primID: 1 +startangle_c: 14 +endpose_c: 15 -15 14 +additionalactioncostmult: 1 +turning_radius: 0.0000 +intermediateposes: 43 +0.0000 0.0000 5.4978 +0.0357 -0.0357 5.4978 +0.0714 -0.0714 5.4978 +0.1071 -0.1071 5.4978 +0.1429 -0.1429 5.4978 +0.1786 -0.1786 5.4978 +0.2143 -0.2143 5.4978 +0.2500 -0.2500 5.4978 +0.2857 -0.2857 5.4978 +0.3214 -0.3214 5.4978 +0.3571 -0.3571 5.4978 +0.3929 -0.3929 5.4978 +0.4286 -0.4286 5.4978 +0.4643 -0.4643 5.4978 +0.5000 -0.5000 5.4978 +0.5357 -0.5357 5.4978 +0.5714 -0.5714 5.4978 +0.6071 -0.6071 5.4978 +0.6429 -0.6429 5.4978 +0.6786 -0.6786 5.4978 +0.7143 -0.7143 5.4978 +0.7500 -0.7500 5.4978 +0.7857 -0.7857 5.4978 +0.8214 -0.8214 5.4978 +0.8571 -0.8571 5.4978 +0.8929 -0.8929 5.4978 +0.9286 -0.9286 5.4978 +0.9643 -0.9643 5.4978 +1.0000 -1.0000 5.4978 +1.0357 -1.0357 5.4978 +1.0714 -1.0714 5.4978 +1.1071 -1.1071 5.4978 +1.1429 -1.1429 5.4978 +1.1786 -1.1786 5.4978 +1.2143 -1.2143 5.4978 +1.2500 -1.2500 5.4978 +1.2857 -1.2857 5.4978 +1.3214 -1.3214 5.4978 +1.3571 -1.3571 5.4978 +1.3929 -1.3929 5.4978 +1.4286 -1.4286 5.4978 +1.4643 -1.4643 5.4978 +1.5000 -1.5000 5.4978 +primID: 2 +startangle_c: 14 +endpose_c: 18 -13 15 +additionalactioncostmult: 2 +turning_radius: 6.9307 +intermediateposes: 45 +0.0000 0.0000 5.4978 +0.0359 -0.0357 5.5051 +0.0721 -0.0712 5.5124 +0.1086 -0.1064 5.5197 +0.1453 -0.1414 5.5270 +0.1823 -0.1761 5.5343 +0.2195 -0.2105 5.5417 +0.2570 -0.2446 5.5490 +0.2947 -0.2785 5.5563 +0.3327 -0.3120 5.5636 +0.3709 -0.3453 5.5709 +0.4093 -0.3784 5.5782 +0.4480 -0.4111 5.5855 +0.4869 -0.4436 5.5928 +0.5261 -0.4757 5.6002 +0.5655 -0.5076 5.6075 +0.6051 -0.5392 5.6148 +0.6450 -0.5705 5.6221 +0.6851 -0.6015 5.6294 +0.7254 -0.6322 5.6367 +0.7659 -0.6627 5.6440 +0.8067 -0.6928 5.6513 +0.8477 -0.7226 5.6587 +0.8889 -0.7521 5.6660 +0.9303 -0.7813 5.6733 +0.9719 -0.8103 5.6806 +1.0137 -0.8389 5.6879 +1.0558 -0.8672 5.6952 +1.0980 -0.8952 5.7025 +1.1405 -0.9229 5.7099 +1.1831 -0.9502 5.7172 +1.2260 -0.9773 5.7245 +1.2690 -1.0040 5.7318 +1.3122 -1.0305 5.7391 +1.3557 -1.0566 5.7464 +1.3993 -1.0824 5.7537 +1.4431 -1.1079 5.7610 +1.4871 -1.1330 5.7684 +1.5313 -1.1579 5.7757 +1.5756 -1.1824 5.7830 +1.6201 -1.2065 5.7903 +1.6649 -1.2304 5.7976 +1.7097 -1.2539 5.8049 +1.7548 -1.2771 5.8122 +1.8000 -1.3000 5.8195 +primID: 3 +startangle_c: 14 +endpose_c: 13 -18 13 +additionalactioncostmult: 2 +turning_radius: -6.9307 +intermediateposes: 45 +0.0000 0.0000 5.4978 +0.0357 -0.0359 5.4905 +0.0712 -0.0721 5.4832 +0.1064 -0.1086 5.4758 +0.1414 -0.1453 5.4685 +0.1761 -0.1823 5.4612 +0.2105 -0.2195 5.4539 +0.2446 -0.2570 5.4466 +0.2785 -0.2947 5.4393 +0.3120 -0.3327 5.4320 +0.3453 -0.3709 5.4247 +0.3784 -0.4093 5.4173 +0.4111 -0.4480 5.4100 +0.4436 -0.4869 5.4027 +0.4757 -0.5261 5.3954 +0.5076 -0.5655 5.3881 +0.5392 -0.6051 5.3808 +0.5705 -0.6450 5.3735 +0.6015 -0.6851 5.3662 +0.6322 -0.7254 5.3588 +0.6627 -0.7659 5.3515 +0.6928 -0.8067 5.3442 +0.7226 -0.8477 5.3369 +0.7521 -0.8889 5.3296 +0.7813 -0.9303 5.3223 +0.8103 -0.9719 5.3150 +0.8389 -1.0137 5.3077 +0.8672 -1.0558 5.3003 +0.8952 -1.0980 5.2930 +0.9229 -1.1405 5.2857 +0.9502 -1.1831 5.2784 +0.9773 -1.2260 5.2711 +1.0040 -1.2690 5.2638 +1.0305 -1.3122 5.2565 +1.0566 -1.3557 5.2492 +1.0824 -1.3993 5.2418 +1.1079 -1.4431 5.2345 +1.1330 -1.4871 5.2272 +1.1579 -1.5313 5.2199 +1.1824 -1.5756 5.2126 +1.2065 -1.6201 5.2053 +1.2304 -1.6649 5.1980 +1.2539 -1.7097 5.1907 +1.2771 -1.7548 5.1833 +1.3000 -1.8000 5.1760 +primID: 4 +startangle_c: 14 +endpose_c: 0 0 15 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 6 +0.0000 0.0000 5.4978 +0.0000 0.0000 5.5621 +0.0000 0.0000 5.6265 +0.0000 0.0000 5.6908 +0.0000 0.0000 5.7552 +0.0000 0.0000 5.8195 +primID: 5 +startangle_c: 14 +endpose_c: -1 1 14 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 3 +0.0000 0.0000 5.4978 +-0.0500 0.0500 5.4978 +-0.1000 0.1000 5.4978 +primID: 6 +startangle_c: 14 +endpose_c: -16 16 14 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 46 +0.0000 0.0000 5.4978 +-0.0356 0.0356 5.4978 +-0.0711 0.0711 5.4978 +-0.1067 0.1067 5.4978 +-0.1422 0.1422 5.4978 +-0.1778 0.1778 5.4978 +-0.2133 0.2133 5.4978 +-0.2489 0.2489 5.4978 +-0.2844 0.2844 5.4978 +-0.3200 0.3200 5.4978 +-0.3556 0.3556 5.4978 +-0.3911 0.3911 5.4978 +-0.4267 0.4267 5.4978 +-0.4622 0.4622 5.4978 +-0.4978 0.4978 5.4978 +-0.5333 0.5333 5.4978 +-0.5689 0.5689 5.4978 +-0.6044 0.6044 5.4978 +-0.6400 0.6400 5.4978 +-0.6756 0.6756 5.4978 +-0.7111 0.7111 5.4978 +-0.7467 0.7467 5.4978 +-0.7822 0.7822 5.4978 +-0.8178 0.8178 5.4978 +-0.8533 0.8533 5.4978 +-0.8889 0.8889 5.4978 +-0.9244 0.9244 5.4978 +-0.9600 0.9600 5.4978 +-0.9956 0.9956 5.4978 +-1.0311 1.0311 5.4978 +-1.0667 1.0667 5.4978 +-1.1022 1.1022 5.4978 +-1.1378 1.1378 5.4978 +-1.1733 1.1733 5.4978 +-1.2089 1.2089 5.4978 +-1.2444 1.2444 5.4978 +-1.2800 1.2800 5.4978 +-1.3156 1.3156 5.4978 +-1.3511 1.3511 5.4978 +-1.3867 1.3867 5.4978 +-1.4222 1.4222 5.4978 +-1.4578 1.4578 5.4978 +-1.4933 1.4933 5.4978 +-1.5289 1.5289 5.4978 +-1.5644 1.5644 5.4978 +-1.6000 1.6000 5.4978 +primID: 7 +startangle_c: 14 +endpose_c: -18 13 15 +additionalactioncostmult: 3 +turning_radius: -6.9307 +intermediateposes: 45 +0.0000 0.0000 5.4978 +-0.0359 0.0357 5.5051 +-0.0721 0.0712 5.5124 +-0.1086 0.1064 5.5197 +-0.1453 0.1414 5.5270 +-0.1823 0.1761 5.5343 +-0.2195 0.2105 5.5417 +-0.2570 0.2446 5.5490 +-0.2947 0.2785 5.5563 +-0.3327 0.3120 5.5636 +-0.3709 0.3453 5.5709 +-0.4093 0.3784 5.5782 +-0.4480 0.4111 5.5855 +-0.4869 0.4436 5.5928 +-0.5261 0.4757 5.6002 +-0.5655 0.5076 5.6075 +-0.6051 0.5392 5.6148 +-0.6450 0.5705 5.6221 +-0.6851 0.6015 5.6294 +-0.7254 0.6322 5.6367 +-0.7659 0.6627 5.6440 +-0.8067 0.6928 5.6513 +-0.8477 0.7226 5.6587 +-0.8889 0.7521 5.6660 +-0.9303 0.7813 5.6733 +-0.9719 0.8103 5.6806 +-1.0137 0.8389 5.6879 +-1.0558 0.8672 5.6952 +-1.0980 0.8952 5.7025 +-1.1405 0.9229 5.7099 +-1.1831 0.9502 5.7172 +-1.2260 0.9773 5.7245 +-1.2690 1.0040 5.7318 +-1.3122 1.0305 5.7391 +-1.3557 1.0566 5.7464 +-1.3993 1.0824 5.7537 +-1.4431 1.1079 5.7610 +-1.4871 1.1330 5.7684 +-1.5313 1.1579 5.7757 +-1.5756 1.1824 5.7830 +-1.6201 1.2065 5.7903 +-1.6649 1.2304 5.7976 +-1.7097 1.2539 5.8049 +-1.7548 1.2771 5.8122 +-1.8000 1.3000 5.8195 +primID: 8 +startangle_c: 14 +endpose_c: -13 18 13 +additionalactioncostmult: 3 +turning_radius: 6.9307 +intermediateposes: 45 +0.0000 0.0000 5.4978 +-0.0357 0.0359 5.4905 +-0.0712 0.0721 5.4832 +-0.1064 0.1086 5.4758 +-0.1414 0.1453 5.4685 +-0.1761 0.1823 5.4612 +-0.2105 0.2195 5.4539 +-0.2446 0.2570 5.4466 +-0.2785 0.2947 5.4393 +-0.3120 0.3327 5.4320 +-0.3453 0.3709 5.4247 +-0.3784 0.4093 5.4173 +-0.4111 0.4480 5.4100 +-0.4436 0.4869 5.4027 +-0.4757 0.5261 5.3954 +-0.5076 0.5655 5.3881 +-0.5392 0.6051 5.3808 +-0.5705 0.6450 5.3735 +-0.6015 0.6851 5.3662 +-0.6322 0.7254 5.3588 +-0.6627 0.7659 5.3515 +-0.6928 0.8067 5.3442 +-0.7226 0.8477 5.3369 +-0.7521 0.8889 5.3296 +-0.7813 0.9303 5.3223 +-0.8103 0.9719 5.3150 +-0.8389 1.0137 5.3077 +-0.8672 1.0558 5.3003 +-0.8952 1.0980 5.2930 +-0.9229 1.1405 5.2857 +-0.9502 1.1831 5.2784 +-0.9773 1.2260 5.2711 +-1.0040 1.2690 5.2638 +-1.0305 1.3122 5.2565 +-1.0566 1.3557 5.2492 +-1.0824 1.3993 5.2418 +-1.1079 1.4431 5.2345 +-1.1330 1.4871 5.2272 +-1.1579 1.5313 5.2199 +-1.1824 1.5756 5.2126 +-1.2065 1.6201 5.2053 +-1.2304 1.6649 5.1980 +-1.2539 1.7097 5.1907 +-1.2771 1.7548 5.1833 +-1.3000 1.8000 5.1760 +primID: 9 +startangle_c: 14 +endpose_c: 0 0 13 +additionalactioncostmult: 5 +turning_radius: 0.0000 +intermediateposes: 6 +0.0000 0.0000 5.4978 +0.0000 0.0000 5.4334 +0.0000 0.0000 5.3691 +0.0000 0.0000 5.3047 +0.0000 0.0000 5.2404 +0.0000 0.0000 5.1760 +primID: 0 +startangle_c: 15 +endpose_c: 2 -1 15 +additionalactioncostmult: 1 +turning_radius: -0.0000 +intermediateposes: 5 +0.0000 0.0000 5.8195 +0.0500 -0.0250 5.8195 +0.1000 -0.0500 5.8195 +0.1500 -0.0750 5.8195 +0.2000 -0.1000 5.8195 +primID: 1 +startangle_c: 15 +endpose_c: 18 -9 15 +additionalactioncostmult: 1 +turning_radius: -0.0000 +intermediateposes: 41 +0.0000 0.0000 5.8195 +0.0450 -0.0225 5.8195 +0.0900 -0.0450 5.8195 +0.1350 -0.0675 5.8195 +0.1800 -0.0900 5.8195 +0.2250 -0.1125 5.8195 +0.2700 -0.1350 5.8195 +0.3150 -0.1575 5.8195 +0.3600 -0.1800 5.8195 +0.4050 -0.2025 5.8195 +0.4500 -0.2250 5.8195 +0.4950 -0.2475 5.8195 +0.5400 -0.2700 5.8195 +0.5850 -0.2925 5.8195 +0.6300 -0.3150 5.8195 +0.6750 -0.3375 5.8195 +0.7200 -0.3600 5.8195 +0.7650 -0.3825 5.8195 +0.8100 -0.4050 5.8195 +0.8550 -0.4275 5.8195 +0.9000 -0.4500 5.8195 +0.9450 -0.4725 5.8195 +0.9900 -0.4950 5.8195 +1.0350 -0.5175 5.8195 +1.0800 -0.5400 5.8195 +1.1250 -0.5625 5.8195 +1.1700 -0.5850 5.8195 +1.2150 -0.6075 5.8195 +1.2600 -0.6300 5.8195 +1.3050 -0.6525 5.8195 +1.3500 -0.6750 5.8195 +1.3950 -0.6975 5.8195 +1.4400 -0.7200 5.8195 +1.4850 -0.7425 5.8195 +1.5300 -0.7650 5.8195 +1.5750 -0.7875 5.8195 +1.6200 -0.8100 5.8195 +1.6650 -0.8325 5.8195 +1.7100 -0.8550 5.8195 +1.7550 -0.8775 5.8195 +1.8000 -0.9000 5.8195 +primID: 2 +startangle_c: 15 +endpose_c: 18 -13 14 +additionalactioncostmult: 2 +turning_radius: -6.9307 +intermediateposes: 45 +0.0000 0.0000 5.8195 +0.0452 -0.0229 5.8122 +0.0903 -0.0461 5.8049 +0.1351 -0.0696 5.7976 +0.1799 -0.0935 5.7903 +0.2244 -0.1176 5.7830 +0.2687 -0.1421 5.7757 +0.3129 -0.1670 5.7684 +0.3569 -0.1921 5.7610 +0.4007 -0.2176 5.7537 +0.4443 -0.2434 5.7464 +0.4878 -0.2695 5.7391 +0.5310 -0.2960 5.7318 +0.5740 -0.3227 5.7245 +0.6169 -0.3498 5.7172 +0.6595 -0.3771 5.7099 +0.7020 -0.4048 5.7025 +0.7442 -0.4328 5.6952 +0.7863 -0.4611 5.6879 +0.8281 -0.4897 5.6806 +0.8697 -0.5187 5.6733 +0.9111 -0.5479 5.6660 +0.9523 -0.5774 5.6587 +0.9933 -0.6072 5.6513 +1.0341 -0.6373 5.6440 +1.0746 -0.6678 5.6367 +1.1149 -0.6985 5.6294 +1.1550 -0.7295 5.6221 +1.1949 -0.7608 5.6148 +1.2345 -0.7924 5.6075 +1.2739 -0.8243 5.6002 +1.3131 -0.8564 5.5928 +1.3520 -0.8889 5.5855 +1.3907 -0.9216 5.5782 +1.4291 -0.9547 5.5709 +1.4673 -0.9880 5.5636 +1.5053 -1.0215 5.5563 +1.5430 -1.0554 5.5490 +1.5805 -1.0895 5.5417 +1.6177 -1.1239 5.5343 +1.6547 -1.1586 5.5270 +1.6914 -1.1936 5.5197 +1.7279 -1.2288 5.5124 +1.7641 -1.2643 5.5051 +1.8000 -1.3000 5.4978 +primID: 3 +startangle_c: 15 +endpose_c: 17 -4 0 +additionalactioncostmult: 2 +turning_radius: 3.8007 +intermediateposes: 35 +0.0000 0.0000 5.8195 +0.0465 -0.0228 5.8332 +0.0934 -0.0450 5.8468 +0.1405 -0.0666 5.8604 +0.1879 -0.0875 5.8741 +0.2356 -0.1077 5.8877 +0.2836 -0.1273 5.9014 +0.3318 -0.1463 5.9150 +0.3803 -0.1646 5.9286 +0.4290 -0.1822 5.9423 +0.4780 -0.1991 5.9559 +0.5272 -0.2154 5.9695 +0.5766 -0.2310 5.9832 +0.6262 -0.2460 5.9968 +0.6761 -0.2603 6.0105 +0.7261 -0.2738 6.0241 +0.7763 -0.2867 6.0377 +0.8266 -0.2990 6.0514 +0.8772 -0.3105 6.0650 +0.9279 -0.3213 6.0786 +0.9787 -0.3315 6.0923 +1.0296 -0.3409 6.1059 +1.0807 -0.3497 6.1195 +1.1319 -0.3577 6.1332 +1.1832 -0.3651 6.1468 +1.2346 -0.3717 6.1605 +1.2861 -0.3777 6.1741 +1.3377 -0.3830 6.1877 +1.3893 -0.3875 6.2014 +1.4410 -0.3914 6.2150 +1.4928 -0.3945 6.2286 +1.5445 -0.3969 6.2423 +1.5963 -0.3987 6.2559 +1.6482 -0.3997 6.2695 +1.7000 -0.4000 6.2832 +primID: 4 +startangle_c: 15 +endpose_c: 0 0 14 +additionalactioncostmult: 5 +turning_radius: -0.0000 +intermediateposes: 6 +0.0000 0.0000 5.8195 +0.0000 0.0000 5.7552 +0.0000 0.0000 5.6908 +0.0000 0.0000 5.6265 +0.0000 0.0000 5.5621 +0.0000 0.0000 5.4978 +primID: 5 +startangle_c: 15 +endpose_c: -2 1 15 +additionalactioncostmult: 5 +turning_radius: -0.0000 +intermediateposes: 5 +0.0000 0.0000 5.8195 +-0.0500 0.0250 5.8195 +-0.1000 0.0500 5.8195 +-0.1500 0.0750 5.8195 +-0.2000 0.1000 5.8195 +primID: 6 +startangle_c: 15 +endpose_c: -18 9 15 +additionalactioncostmult: 5 +turning_radius: -0.0000 +intermediateposes: 41 +0.0000 0.0000 5.8195 +-0.0450 0.0225 5.8195 +-0.0900 0.0450 5.8195 +-0.1350 0.0675 5.8195 +-0.1800 0.0900 5.8195 +-0.2250 0.1125 5.8195 +-0.2700 0.1350 5.8195 +-0.3150 0.1575 5.8195 +-0.3600 0.1800 5.8195 +-0.4050 0.2025 5.8195 +-0.4500 0.2250 5.8195 +-0.4950 0.2475 5.8195 +-0.5400 0.2700 5.8195 +-0.5850 0.2925 5.8195 +-0.6300 0.3150 5.8195 +-0.6750 0.3375 5.8195 +-0.7200 0.3600 5.8195 +-0.7650 0.3825 5.8195 +-0.8100 0.4050 5.8195 +-0.8550 0.4275 5.8195 +-0.9000 0.4500 5.8195 +-0.9450 0.4725 5.8195 +-0.9900 0.4950 5.8195 +-1.0350 0.5175 5.8195 +-1.0800 0.5400 5.8195 +-1.1250 0.5625 5.8195 +-1.1700 0.5850 5.8195 +-1.2150 0.6075 5.8195 +-1.2600 0.6300 5.8195 +-1.3050 0.6525 5.8195 +-1.3500 0.6750 5.8195 +-1.3950 0.6975 5.8195 +-1.4400 0.7200 5.8195 +-1.4850 0.7425 5.8195 +-1.5300 0.7650 5.8195 +-1.5750 0.7875 5.8195 +-1.6200 0.8100 5.8195 +-1.6650 0.8325 5.8195 +-1.7100 0.8550 5.8195 +-1.7550 0.8775 5.8195 +-1.8000 0.9000 5.8195 +primID: 7 +startangle_c: 15 +endpose_c: -18 13 14 +additionalactioncostmult: 3 +turning_radius: 6.9307 +intermediateposes: 45 +0.0000 0.0000 5.8195 +-0.0452 0.0229 5.8122 +-0.0903 0.0461 5.8049 +-0.1351 0.0696 5.7976 +-0.1799 0.0935 5.7903 +-0.2244 0.1176 5.7830 +-0.2687 0.1421 5.7757 +-0.3129 0.1670 5.7684 +-0.3569 0.1921 5.7610 +-0.4007 0.2176 5.7537 +-0.4443 0.2434 5.7464 +-0.4878 0.2695 5.7391 +-0.5310 0.2960 5.7318 +-0.5740 0.3227 5.7245 +-0.6169 0.3498 5.7172 +-0.6595 0.3771 5.7099 +-0.7020 0.4048 5.7025 +-0.7442 0.4328 5.6952 +-0.7863 0.4611 5.6879 +-0.8281 0.4897 5.6806 +-0.8697 0.5187 5.6733 +-0.9111 0.5479 5.6660 +-0.9523 0.5774 5.6587 +-0.9933 0.6072 5.6513 +-1.0341 0.6373 5.6440 +-1.0746 0.6678 5.6367 +-1.1149 0.6985 5.6294 +-1.1550 0.7295 5.6221 +-1.1949 0.7608 5.6148 +-1.2345 0.7924 5.6075 +-1.2739 0.8243 5.6002 +-1.3131 0.8564 5.5928 +-1.3520 0.8889 5.5855 +-1.3907 0.9216 5.5782 +-1.4291 0.9547 5.5709 +-1.4673 0.9880 5.5636 +-1.5053 1.0215 5.5563 +-1.5430 1.0554 5.5490 +-1.5805 1.0895 5.5417 +-1.6177 1.1239 5.5343 +-1.6547 1.1586 5.5270 +-1.6914 1.1936 5.5197 +-1.7279 1.2288 5.5124 +-1.7641 1.2643 5.5051 +-1.8000 1.3000 5.4978 +primID: 8 +startangle_c: 15 +endpose_c: -17 4 0 +additionalactioncostmult: 3 +turning_radius: -3.8007 +intermediateposes: 35 +0.0000 0.0000 5.8195 +-0.0465 0.0228 5.8332 +-0.0934 0.0450 5.8468 +-0.1405 0.0666 5.8604 +-0.1879 0.0875 5.8741 +-0.2356 0.1077 5.8877 +-0.2836 0.1273 5.9014 +-0.3318 0.1463 5.9150 +-0.3803 0.1646 5.9286 +-0.4290 0.1822 5.9423 +-0.4780 0.1991 5.9559 +-0.5272 0.2154 5.9695 +-0.5766 0.2310 5.9832 +-0.6262 0.2460 5.9968 +-0.6761 0.2603 6.0105 +-0.7261 0.2738 6.0241 +-0.7763 0.2867 6.0377 +-0.8266 0.2990 6.0514 +-0.8772 0.3105 6.0650 +-0.9279 0.3213 6.0786 +-0.9787 0.3315 6.0923 +-1.0296 0.3409 6.1059 +-1.0807 0.3497 6.1195 +-1.1319 0.3577 6.1332 +-1.1832 0.3651 6.1468 +-1.2346 0.3717 6.1605 +-1.2861 0.3777 6.1741 +-1.3377 0.3830 6.1877 +-1.3893 0.3875 6.2014 +-1.4410 0.3914 6.2150 +-1.4928 0.3945 6.2286 +-1.5445 0.3969 6.2423 +-1.5963 0.3987 6.2559 +-1.6482 0.3997 6.2695 +-1.7000 0.4000 6.2832 +primID: 9 +startangle_c: 15 +endpose_c: 0 0 0 +additionalactioncostmult: 5 +turning_radius: -0.0000 +intermediateposes: 116 +0.0000 0.0000 5.8195 +0.0000 0.0000 5.8236 +0.0000 0.0000 5.8276 +0.0000 0.0000 5.8316 +0.0000 0.0000 5.8357 +0.0000 0.0000 5.8397 +0.0000 0.0000 5.8437 +0.0000 0.0000 5.8478 +0.0000 0.0000 5.8518 +0.0000 0.0000 5.8558 +0.0000 0.0000 5.8599 +0.0000 0.0000 5.8639 +0.0000 0.0000 5.8679 +0.0000 0.0000 5.8720 +0.0000 0.0000 5.8760 +0.0000 0.0000 5.8800 +0.0000 0.0000 5.8840 +0.0000 0.0000 5.8881 +0.0000 0.0000 5.8921 +0.0000 0.0000 5.8961 +0.0000 0.0000 5.9002 +0.0000 0.0000 5.9042 +0.0000 0.0000 5.9082 +0.0000 0.0000 5.9123 +0.0000 0.0000 5.9163 +0.0000 0.0000 5.9203 +0.0000 0.0000 5.9244 +0.0000 0.0000 5.9284 +0.0000 0.0000 5.9324 +0.0000 0.0000 5.9365 +0.0000 0.0000 5.9405 +0.0000 0.0000 5.9445 +0.0000 0.0000 5.9486 +0.0000 0.0000 5.9526 +0.0000 0.0000 5.9566 +0.0000 0.0000 5.9606 +0.0000 0.0000 5.9647 +0.0000 0.0000 5.9687 +0.0000 0.0000 5.9727 +0.0000 0.0000 5.9768 +0.0000 0.0000 5.9808 +0.0000 0.0000 5.9848 +0.0000 0.0000 5.9889 +0.0000 0.0000 5.9929 +0.0000 0.0000 5.9969 +0.0000 0.0000 6.0010 +0.0000 0.0000 6.0050 +0.0000 0.0000 6.0090 +0.0000 0.0000 6.0131 +0.0000 0.0000 6.0171 +0.0000 0.0000 6.0211 +0.0000 0.0000 6.0252 +0.0000 0.0000 6.0292 +0.0000 0.0000 6.0332 +0.0000 0.0000 6.0373 +0.0000 0.0000 6.0413 +0.0000 0.0000 6.0453 +0.0000 0.0000 6.0493 +0.0000 0.0000 6.0534 +0.0000 0.0000 6.0574 +0.0000 0.0000 6.0614 +0.0000 0.0000 6.0655 +0.0000 0.0000 6.0695 +0.0000 0.0000 6.0735 +0.0000 0.0000 6.0776 +0.0000 0.0000 6.0816 +0.0000 0.0000 6.0856 +0.0000 0.0000 6.0897 +0.0000 0.0000 6.0937 +0.0000 0.0000 6.0977 +0.0000 0.0000 6.1018 +0.0000 0.0000 6.1058 +0.0000 0.0000 6.1098 +0.0000 0.0000 6.1139 +0.0000 0.0000 6.1179 +0.0000 0.0000 6.1219 +0.0000 0.0000 6.1259 +0.0000 0.0000 6.1300 +0.0000 0.0000 6.1340 +0.0000 0.0000 6.1380 +0.0000 0.0000 6.1421 +0.0000 0.0000 6.1461 +0.0000 0.0000 6.1501 +0.0000 0.0000 6.1542 +0.0000 0.0000 6.1582 +0.0000 0.0000 6.1622 +0.0000 0.0000 6.1663 +0.0000 0.0000 6.1703 +0.0000 0.0000 6.1743 +0.0000 0.0000 6.1784 +0.0000 0.0000 6.1824 +0.0000 0.0000 6.1864 +0.0000 0.0000 6.1905 +0.0000 0.0000 6.1945 +0.0000 0.0000 6.1985 +0.0000 0.0000 6.2026 +0.0000 0.0000 6.2066 +0.0000 0.0000 6.2106 +0.0000 0.0000 6.2146 +0.0000 0.0000 6.2187 +0.0000 0.0000 6.2227 +0.0000 0.0000 6.2267 +0.0000 0.0000 6.2308 +0.0000 0.0000 6.2348 +0.0000 0.0000 6.2388 +0.0000 0.0000 6.2429 +0.0000 0.0000 6.2469 +0.0000 0.0000 6.2509 +0.0000 0.0000 6.2550 +0.0000 0.0000 6.2590 +0.0000 0.0000 6.2630 +0.0000 0.0000 6.2671 +0.0000 0.0000 6.2711 +0.0000 0.0000 6.2751 +0.0000 0.0000 6.2792 +0.0000 0.0000 6.2832 diff --git a/navigations/sbpl/matlab/mprim/pr2.mprim b/navigations/sbpl/matlab/mprim/pr2.mprim new file mode 100755 index 0000000..b34485f --- /dev/null +++ b/navigations/sbpl/matlab/mprim/pr2.mprim @@ -0,0 +1,1683 @@ +resolution_m: 0.025000 +numberofangles: 16 +totalnumberofprimitives: 112 +primID: 0 +startangle_c: 0 +endpose_c: 1 0 0 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0028 0.0000 0.0000 +0.0056 0.0000 0.0000 +0.0083 0.0000 0.0000 +0.0111 0.0000 0.0000 +0.0139 0.0000 0.0000 +0.0167 0.0000 0.0000 +0.0194 0.0000 0.0000 +0.0222 0.0000 0.0000 +0.0250 0.0000 0.0000 +primID: 1 +startangle_c: 0 +endpose_c: 8 0 0 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0222 0.0000 0.0000 +0.0444 0.0000 0.0000 +0.0667 0.0000 0.0000 +0.0889 0.0000 0.0000 +0.1111 0.0000 0.0000 +0.1333 0.0000 0.0000 +0.1556 0.0000 0.0000 +0.1778 0.0000 0.0000 +0.2000 0.0000 0.0000 +primID: 2 +startangle_c: 0 +endpose_c: -1 0 0 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 0.0000 +-0.0028 0.0000 0.0000 +-0.0056 0.0000 0.0000 +-0.0083 0.0000 0.0000 +-0.0111 0.0000 0.0000 +-0.0139 0.0000 0.0000 +-0.0167 0.0000 0.0000 +-0.0194 0.0000 0.0000 +-0.0222 0.0000 0.0000 +-0.0250 0.0000 0.0000 +primID: 3 +startangle_c: 0 +endpose_c: 8 1 1 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0226 -0.0000 0.0000 +0.0452 -0.0000 0.0000 +0.0678 -0.0000 0.0000 +0.0903 0.0004 0.0488 +0.1128 0.0023 0.1176 +0.1352 0.0057 0.1864 +0.1572 0.0106 0.2551 +0.1789 0.0171 0.3239 +0.2000 0.0250 0.3927 +primID: 4 +startangle_c: 0 +endpose_c: 8 -1 -1 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0226 0.0000 0.0000 +0.0452 0.0000 0.0000 +0.0678 0.0000 0.0000 +0.0903 -0.0004 -0.0488 +0.1128 -0.0023 -0.1176 +0.1352 -0.0057 -0.1864 +0.1572 -0.0106 -0.2551 +0.1789 -0.0171 -0.3239 +0.2000 -0.0250 -0.3927 +primID: 5 +startangle_c: 0 +endpose_c: 0 0 1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0000 0.0000 0.0436 +0.0000 0.0000 0.0873 +0.0000 0.0000 0.1309 +0.0000 0.0000 0.1745 +0.0000 0.0000 0.2182 +0.0000 0.0000 0.2618 +0.0000 0.0000 0.3054 +0.0000 0.0000 0.3491 +0.0000 0.0000 0.3927 +primID: 6 +startangle_c: 0 +endpose_c: 0 0 -1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0000 0.0000 -0.0436 +0.0000 0.0000 -0.0873 +0.0000 0.0000 -0.1309 +0.0000 0.0000 -0.1745 +0.0000 0.0000 -0.2182 +0.0000 0.0000 -0.2618 +0.0000 0.0000 -0.3054 +0.0000 0.0000 -0.3491 +0.0000 0.0000 -0.3927 +primID: 0 +startangle_c: 1 +endpose_c: 2 1 1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0056 0.0028 0.3927 +0.0111 0.0056 0.3927 +0.0167 0.0083 0.3927 +0.0222 0.0111 0.3927 +0.0278 0.0139 0.3927 +0.0333 0.0167 0.3927 +0.0389 0.0194 0.3927 +0.0444 0.0222 0.3927 +0.0500 0.0250 0.3927 +primID: 1 +startangle_c: 1 +endpose_c: 6 3 1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0167 0.0083 0.3927 +0.0333 0.0167 0.3927 +0.0500 0.0250 0.3927 +0.0667 0.0333 0.3927 +0.0833 0.0417 0.3927 +0.1000 0.0500 0.3927 +0.1167 0.0583 0.3927 +0.1333 0.0667 0.3927 +0.1500 0.0750 0.3927 +primID: 2 +startangle_c: 1 +endpose_c: -2 -1 1 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 0.3927 +-0.0056 -0.0028 0.3927 +-0.0111 -0.0056 0.3927 +-0.0167 -0.0083 0.3927 +-0.0222 -0.0111 0.3927 +-0.0278 -0.0139 0.3927 +-0.0333 -0.0167 0.3927 +-0.0389 -0.0194 0.3927 +-0.0444 -0.0222 0.3927 +-0.0500 -0.0250 0.3927 +primID: 3 +startangle_c: 1 +endpose_c: 5 4 2 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0149 0.0092 0.4230 +0.0296 0.0189 0.4533 +0.0440 0.0291 0.4836 +0.0582 0.0398 0.5139 +0.0722 0.0509 0.5442 +0.0858 0.0625 0.5745 +0.0992 0.0746 0.6048 +0.1123 0.0871 0.6351 +0.1250 0.1000 0.6654 +primID: 4 +startangle_c: 1 +endpose_c: 7 2 0 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0188 0.0078 0.3927 +0.0377 0.0156 0.3927 +0.0565 0.0234 0.3927 +0.0754 0.0312 0.3736 +0.0946 0.0379 0.2989 +0.1143 0.0432 0.2242 +0.1344 0.0470 0.1494 +0.1546 0.0492 0.0747 +0.1750 0.0500 0.0000 +primID: 5 +startangle_c: 1 +endpose_c: 0 0 2 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0000 0.0000 0.4363 +0.0000 0.0000 0.4800 +0.0000 0.0000 0.5236 +0.0000 0.0000 0.5672 +0.0000 0.0000 0.6109 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.6981 +0.0000 0.0000 0.7418 +0.0000 0.0000 0.7854 +primID: 6 +startangle_c: 1 +endpose_c: 0 0 0 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0000 0.0000 0.3491 +0.0000 0.0000 0.3054 +0.0000 0.0000 0.2618 +0.0000 0.0000 0.2182 +0.0000 0.0000 0.1745 +0.0000 0.0000 0.1309 +0.0000 0.0000 0.0873 +0.0000 0.0000 0.0436 +0.0000 0.0000 0.0000 +primID: 0 +startangle_c: 2 +endpose_c: 1 1 2 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0028 0.0028 0.7854 +0.0056 0.0056 0.7854 +0.0083 0.0083 0.7854 +0.0111 0.0111 0.7854 +0.0139 0.0139 0.7854 +0.0167 0.0167 0.7854 +0.0194 0.0194 0.7854 +0.0222 0.0222 0.7854 +0.0250 0.0250 0.7854 +primID: 1 +startangle_c: 2 +endpose_c: 6 6 2 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0167 0.0167 0.7854 +0.0333 0.0333 0.7854 +0.0500 0.0500 0.7854 +0.0667 0.0667 0.7854 +0.0833 0.0833 0.7854 +0.1000 0.1000 0.7854 +0.1167 0.1167 0.7854 +0.1333 0.1333 0.7854 +0.1500 0.1500 0.7854 +primID: 2 +startangle_c: 2 +endpose_c: -1 -1 2 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 0.7854 +-0.0028 -0.0028 0.7854 +-0.0056 -0.0056 0.7854 +-0.0083 -0.0083 0.7854 +-0.0111 -0.0111 0.7854 +-0.0139 -0.0139 0.7854 +-0.0167 -0.0167 0.7854 +-0.0194 -0.0194 0.7854 +-0.0222 -0.0222 0.7854 +-0.0250 -0.0250 0.7854 +primID: 3 +startangle_c: 2 +endpose_c: 5 7 3 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0170 0.0170 0.7854 +0.0339 0.0342 0.8151 +0.0500 0.0522 0.8669 +0.0651 0.0709 0.9188 +0.0792 0.0904 0.9707 +0.0923 0.1107 1.0225 +0.1043 0.1315 1.0744 +0.1152 0.1530 1.1262 +0.1250 0.1750 1.1781 +primID: 4 +startangle_c: 2 +endpose_c: 7 5 1 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0170 0.0170 0.7854 +0.0342 0.0339 0.7557 +0.0522 0.0500 0.7039 +0.0709 0.0651 0.6520 +0.0904 0.0792 0.6001 +0.1107 0.0923 0.5483 +0.1315 0.1043 0.4964 +0.1530 0.1152 0.4446 +0.1750 0.1250 0.3927 +primID: 5 +startangle_c: 2 +endpose_c: 0 0 3 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0000 0.0000 0.8290 +0.0000 0.0000 0.8727 +0.0000 0.0000 0.9163 +0.0000 0.0000 0.9599 +0.0000 0.0000 1.0036 +0.0000 0.0000 1.0472 +0.0000 0.0000 1.0908 +0.0000 0.0000 1.1345 +0.0000 0.0000 1.1781 +primID: 6 +startangle_c: 2 +endpose_c: 0 0 1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0000 0.0000 0.7418 +0.0000 0.0000 0.6981 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.6109 +0.0000 0.0000 0.5672 +0.0000 0.0000 0.5236 +0.0000 0.0000 0.4800 +0.0000 0.0000 0.4363 +0.0000 0.0000 0.3927 +primID: 0 +startangle_c: 3 +endpose_c: 1 2 3 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0028 0.0056 1.1781 +0.0056 0.0111 1.1781 +0.0083 0.0167 1.1781 +0.0111 0.0222 1.1781 +0.0139 0.0278 1.1781 +0.0167 0.0333 1.1781 +0.0194 0.0389 1.1781 +0.0222 0.0444 1.1781 +0.0250 0.0500 1.1781 +primID: 1 +startangle_c: 3 +endpose_c: 3 6 3 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0083 0.0167 1.1781 +0.0167 0.0333 1.1781 +0.0250 0.0500 1.1781 +0.0333 0.0667 1.1781 +0.0417 0.0833 1.1781 +0.0500 0.1000 1.1781 +0.0583 0.1167 1.1781 +0.0667 0.1333 1.1781 +0.0750 0.1500 1.1781 +primID: 2 +startangle_c: 3 +endpose_c: -1 -2 3 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 1.1781 +-0.0028 -0.0056 1.1781 +-0.0056 -0.0111 1.1781 +-0.0083 -0.0167 1.1781 +-0.0111 -0.0222 1.1781 +-0.0139 -0.0278 1.1781 +-0.0167 -0.0333 1.1781 +-0.0194 -0.0389 1.1781 +-0.0222 -0.0444 1.1781 +-0.0250 -0.0500 1.1781 +primID: 3 +startangle_c: 3 +endpose_c: 4 5 2 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0092 0.0149 1.1478 +0.0189 0.0296 1.1175 +0.0291 0.0440 1.0872 +0.0398 0.0582 1.0569 +0.0509 0.0722 1.0266 +0.0625 0.0858 0.9963 +0.0746 0.0992 0.9660 +0.0871 0.1123 0.9357 +0.1000 0.1250 0.9054 +primID: 4 +startangle_c: 3 +endpose_c: 2 7 4 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0078 0.0188 1.1781 +0.0156 0.0377 1.1781 +0.0234 0.0565 1.1781 +0.0312 0.0754 1.1972 +0.0379 0.0946 1.2719 +0.0432 0.1143 1.3466 +0.0470 0.1344 1.4214 +0.0492 0.1546 1.4961 +0.0500 0.1750 1.5708 +primID: 5 +startangle_c: 3 +endpose_c: 0 0 2 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0000 0.0000 1.1345 +0.0000 0.0000 1.0908 +0.0000 0.0000 1.0472 +0.0000 0.0000 1.0036 +0.0000 0.0000 0.9599 +0.0000 0.0000 0.9163 +0.0000 0.0000 0.8727 +0.0000 0.0000 0.8290 +0.0000 0.0000 0.7854 +primID: 6 +startangle_c: 3 +endpose_c: 0 0 4 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0000 0.0000 1.2217 +0.0000 0.0000 1.2654 +0.0000 0.0000 1.3090 +0.0000 0.0000 1.3526 +0.0000 0.0000 1.3963 +0.0000 0.0000 1.4399 +0.0000 0.0000 1.4835 +0.0000 0.0000 1.5272 +0.0000 0.0000 1.5708 +primID: 0 +startangle_c: 4 +endpose_c: 0 1 4 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0028 1.5708 +0.0000 0.0056 1.5708 +0.0000 0.0083 1.5708 +0.0000 0.0111 1.5708 +0.0000 0.0139 1.5708 +0.0000 0.0167 1.5708 +0.0000 0.0194 1.5708 +0.0000 0.0222 1.5708 +0.0000 0.0250 1.5708 +primID: 1 +startangle_c: 4 +endpose_c: 0 8 4 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0222 1.5708 +0.0000 0.0444 1.5708 +0.0000 0.0667 1.5708 +0.0000 0.0889 1.5708 +0.0000 0.1111 1.5708 +0.0000 0.1333 1.5708 +0.0000 0.1556 1.5708 +0.0000 0.1778 1.5708 +0.0000 0.2000 1.5708 +primID: 2 +startangle_c: 4 +endpose_c: 0 -1 4 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 -0.0028 1.5708 +0.0000 -0.0056 1.5708 +0.0000 -0.0083 1.5708 +0.0000 -0.0111 1.5708 +0.0000 -0.0139 1.5708 +0.0000 -0.0167 1.5708 +0.0000 -0.0194 1.5708 +0.0000 -0.0222 1.5708 +0.0000 -0.0250 1.5708 +primID: 3 +startangle_c: 4 +endpose_c: -1 8 5 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0226 1.5708 +0.0000 0.0452 1.5708 +0.0000 0.0678 1.5708 +-0.0004 0.0903 1.6196 +-0.0023 0.1128 1.6884 +-0.0057 0.1352 1.7572 +-0.0106 0.1572 1.8259 +-0.0171 0.1789 1.8947 +-0.0250 0.2000 1.9635 +primID: 4 +startangle_c: 4 +endpose_c: 1 8 3 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 1.5708 +-0.0000 0.0226 1.5708 +-0.0000 0.0452 1.5708 +-0.0000 0.0678 1.5708 +0.0004 0.0903 1.5220 +0.0023 0.1128 1.4532 +0.0057 0.1352 1.3844 +0.0106 0.1572 1.3156 +0.0171 0.1789 1.2469 +0.0250 0.2000 1.1781 +primID: 5 +startangle_c: 4 +endpose_c: 0 0 5 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0000 1.6144 +0.0000 0.0000 1.6581 +0.0000 0.0000 1.7017 +0.0000 0.0000 1.7453 +0.0000 0.0000 1.7890 +0.0000 0.0000 1.8326 +0.0000 0.0000 1.8762 +0.0000 0.0000 1.9199 +0.0000 0.0000 1.9635 +primID: 6 +startangle_c: 4 +endpose_c: 0 0 3 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0000 1.5272 +0.0000 0.0000 1.4835 +0.0000 0.0000 1.4399 +0.0000 0.0000 1.3963 +0.0000 0.0000 1.3526 +0.0000 0.0000 1.3090 +0.0000 0.0000 1.2654 +0.0000 0.0000 1.2217 +0.0000 0.0000 1.1781 +primID: 0 +startangle_c: 5 +endpose_c: -1 2 5 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0028 0.0056 1.9635 +-0.0056 0.0111 1.9635 +-0.0083 0.0167 1.9635 +-0.0111 0.0222 1.9635 +-0.0139 0.0278 1.9635 +-0.0167 0.0333 1.9635 +-0.0194 0.0389 1.9635 +-0.0222 0.0444 1.9635 +-0.0250 0.0500 1.9635 +primID: 1 +startangle_c: 5 +endpose_c: -3 6 5 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0083 0.0167 1.9635 +-0.0167 0.0333 1.9635 +-0.0250 0.0500 1.9635 +-0.0333 0.0667 1.9635 +-0.0417 0.0833 1.9635 +-0.0500 0.1000 1.9635 +-0.0583 0.1167 1.9635 +-0.0667 0.1333 1.9635 +-0.0750 0.1500 1.9635 +primID: 2 +startangle_c: 5 +endpose_c: 1 -2 5 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0028 -0.0056 1.9635 +0.0056 -0.0111 1.9635 +0.0083 -0.0167 1.9635 +0.0111 -0.0222 1.9635 +0.0139 -0.0278 1.9635 +0.0167 -0.0333 1.9635 +0.0194 -0.0389 1.9635 +0.0222 -0.0444 1.9635 +0.0250 -0.0500 1.9635 +primID: 3 +startangle_c: 5 +endpose_c: -4 5 6 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0092 0.0149 1.9938 +-0.0189 0.0296 2.0241 +-0.0291 0.0440 2.0544 +-0.0398 0.0582 2.0847 +-0.0509 0.0722 2.1150 +-0.0625 0.0858 2.1453 +-0.0746 0.0992 2.1756 +-0.0871 0.1123 2.2059 +-0.1000 0.1250 2.2362 +primID: 4 +startangle_c: 5 +endpose_c: -2 7 4 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0078 0.0188 1.9635 +-0.0156 0.0377 1.9635 +-0.0234 0.0565 1.9635 +-0.0312 0.0754 1.9444 +-0.0379 0.0946 1.8697 +-0.0432 0.1143 1.7950 +-0.0470 0.1344 1.7202 +-0.0492 0.1546 1.6455 +-0.0500 0.1750 1.5708 +primID: 5 +startangle_c: 5 +endpose_c: 0 0 6 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0000 0.0000 2.0071 +0.0000 0.0000 2.0508 +0.0000 0.0000 2.0944 +0.0000 0.0000 2.1380 +0.0000 0.0000 2.1817 +0.0000 0.0000 2.2253 +0.0000 0.0000 2.2689 +0.0000 0.0000 2.3126 +0.0000 0.0000 2.3562 +primID: 6 +startangle_c: 5 +endpose_c: 0 0 4 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0000 0.0000 1.9199 +0.0000 0.0000 1.8762 +0.0000 0.0000 1.8326 +0.0000 0.0000 1.7890 +0.0000 0.0000 1.7453 +0.0000 0.0000 1.7017 +0.0000 0.0000 1.6581 +0.0000 0.0000 1.6144 +0.0000 0.0000 1.5708 +primID: 0 +startangle_c: 6 +endpose_c: -1 1 6 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0028 0.0028 2.3562 +-0.0056 0.0056 2.3562 +-0.0083 0.0083 2.3562 +-0.0111 0.0111 2.3562 +-0.0139 0.0139 2.3562 +-0.0167 0.0167 2.3562 +-0.0194 0.0194 2.3562 +-0.0222 0.0222 2.3562 +-0.0250 0.0250 2.3562 +primID: 1 +startangle_c: 6 +endpose_c: -6 6 6 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0167 0.0167 2.3562 +-0.0333 0.0333 2.3562 +-0.0500 0.0500 2.3562 +-0.0667 0.0667 2.3562 +-0.0833 0.0833 2.3562 +-0.1000 0.1000 2.3562 +-0.1167 0.1167 2.3562 +-0.1333 0.1333 2.3562 +-0.1500 0.1500 2.3562 +primID: 2 +startangle_c: 6 +endpose_c: 1 -1 6 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0028 -0.0028 2.3562 +0.0056 -0.0056 2.3562 +0.0083 -0.0083 2.3562 +0.0111 -0.0111 2.3562 +0.0139 -0.0139 2.3562 +0.0167 -0.0167 2.3562 +0.0194 -0.0194 2.3562 +0.0222 -0.0222 2.3562 +0.0250 -0.0250 2.3562 +primID: 3 +startangle_c: 6 +endpose_c: -7 5 7 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0170 0.0170 2.3562 +-0.0342 0.0339 2.3859 +-0.0522 0.0500 2.4377 +-0.0709 0.0651 2.4896 +-0.0904 0.0792 2.5415 +-0.1107 0.0923 2.5933 +-0.1315 0.1043 2.6452 +-0.1530 0.1152 2.6970 +-0.1750 0.1250 2.7489 +primID: 4 +startangle_c: 6 +endpose_c: -5 7 5 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0170 0.0170 2.3562 +-0.0339 0.0342 2.3265 +-0.0500 0.0522 2.2747 +-0.0651 0.0709 2.2228 +-0.0792 0.0904 2.1709 +-0.0923 0.1107 2.1191 +-0.1043 0.1315 2.0672 +-0.1152 0.1530 2.0154 +-0.1250 0.1750 1.9635 +primID: 5 +startangle_c: 6 +endpose_c: 0 0 7 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0000 0.0000 2.3998 +0.0000 0.0000 2.4435 +0.0000 0.0000 2.4871 +0.0000 0.0000 2.5307 +0.0000 0.0000 2.5744 +0.0000 0.0000 2.6180 +0.0000 0.0000 2.6616 +0.0000 0.0000 2.7053 +0.0000 0.0000 2.7489 +primID: 6 +startangle_c: 6 +endpose_c: 0 0 5 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0000 0.0000 2.3126 +0.0000 0.0000 2.2689 +0.0000 0.0000 2.2253 +0.0000 0.0000 2.1817 +0.0000 0.0000 2.1380 +0.0000 0.0000 2.0944 +0.0000 0.0000 2.0508 +0.0000 0.0000 2.0071 +0.0000 0.0000 1.9635 +primID: 0 +startangle_c: 7 +endpose_c: -2 1 7 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0056 0.0028 2.7489 +-0.0111 0.0056 2.7489 +-0.0167 0.0083 2.7489 +-0.0222 0.0111 2.7489 +-0.0278 0.0139 2.7489 +-0.0333 0.0167 2.7489 +-0.0389 0.0194 2.7489 +-0.0444 0.0222 2.7489 +-0.0500 0.0250 2.7489 +primID: 1 +startangle_c: 7 +endpose_c: -6 3 7 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0167 0.0083 2.7489 +-0.0333 0.0167 2.7489 +-0.0500 0.0250 2.7489 +-0.0667 0.0333 2.7489 +-0.0833 0.0417 2.7489 +-0.1000 0.0500 2.7489 +-0.1167 0.0583 2.7489 +-0.1333 0.0667 2.7489 +-0.1500 0.0750 2.7489 +primID: 2 +startangle_c: 7 +endpose_c: 2 -1 7 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0056 -0.0028 2.7489 +0.0111 -0.0056 2.7489 +0.0167 -0.0083 2.7489 +0.0222 -0.0111 2.7489 +0.0278 -0.0139 2.7489 +0.0333 -0.0167 2.7489 +0.0389 -0.0194 2.7489 +0.0444 -0.0222 2.7489 +0.0500 -0.0250 2.7489 +primID: 3 +startangle_c: 7 +endpose_c: -5 4 6 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0149 0.0092 2.7186 +-0.0296 0.0189 2.6883 +-0.0440 0.0291 2.6580 +-0.0582 0.0398 2.6277 +-0.0722 0.0509 2.5974 +-0.0858 0.0625 2.5671 +-0.0992 0.0746 2.5368 +-0.1123 0.0871 2.5065 +-0.1250 0.1000 2.4762 +primID: 4 +startangle_c: 7 +endpose_c: -7 2 8 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0188 0.0078 2.7489 +-0.0377 0.0156 2.7489 +-0.0565 0.0234 2.7489 +-0.0754 0.0312 2.7680 +-0.0946 0.0379 2.8427 +-0.1143 0.0432 2.9174 +-0.1344 0.0470 2.9921 +-0.1546 0.0492 3.0669 +-0.1750 0.0500 3.1416 +primID: 5 +startangle_c: 7 +endpose_c: 0 0 6 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0000 0.0000 2.7053 +0.0000 0.0000 2.6616 +0.0000 0.0000 2.6180 +0.0000 0.0000 2.5744 +0.0000 0.0000 2.5307 +0.0000 0.0000 2.4871 +0.0000 0.0000 2.4435 +0.0000 0.0000 2.3998 +0.0000 0.0000 2.3562 +primID: 6 +startangle_c: 7 +endpose_c: 0 0 8 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0000 0.0000 2.7925 +0.0000 0.0000 2.8362 +0.0000 0.0000 2.8798 +0.0000 0.0000 2.9234 +0.0000 0.0000 2.9671 +0.0000 0.0000 3.0107 +0.0000 0.0000 3.0543 +0.0000 0.0000 3.0980 +0.0000 0.0000 3.1416 +primID: 0 +startangle_c: 8 +endpose_c: -1 0 8 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0028 0.0000 3.1416 +-0.0056 0.0000 3.1416 +-0.0083 0.0000 3.1416 +-0.0111 0.0000 3.1416 +-0.0139 0.0000 3.1416 +-0.0167 0.0000 3.1416 +-0.0194 0.0000 3.1416 +-0.0222 0.0000 3.1416 +-0.0250 0.0000 3.1416 +primID: 1 +startangle_c: 8 +endpose_c: -8 0 8 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0222 0.0000 3.1416 +-0.0444 0.0000 3.1416 +-0.0667 0.0000 3.1416 +-0.0889 0.0000 3.1416 +-0.1111 0.0000 3.1416 +-0.1333 0.0000 3.1416 +-0.1556 0.0000 3.1416 +-0.1778 0.0000 3.1416 +-0.2000 0.0000 3.1416 +primID: 2 +startangle_c: 8 +endpose_c: 1 0 8 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0028 0.0000 3.1416 +0.0056 0.0000 3.1416 +0.0083 0.0000 3.1416 +0.0111 0.0000 3.1416 +0.0139 0.0000 3.1416 +0.0167 0.0000 3.1416 +0.0194 0.0000 3.1416 +0.0222 0.0000 3.1416 +0.0250 0.0000 3.1416 +primID: 3 +startangle_c: 8 +endpose_c: -8 -1 9 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0226 0.0000 3.1416 +-0.0452 0.0000 3.1416 +-0.0678 0.0000 3.1416 +-0.0903 -0.0004 3.1904 +-0.1128 -0.0023 3.2592 +-0.1352 -0.0057 3.3280 +-0.1572 -0.0106 3.3967 +-0.1789 -0.0171 3.4655 +-0.2000 -0.0250 3.5343 +primID: 4 +startangle_c: 8 +endpose_c: -8 1 7 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0226 0.0000 3.1416 +-0.0452 0.0000 3.1416 +-0.0678 0.0000 3.1416 +-0.0903 0.0004 3.0928 +-0.1128 0.0023 3.0240 +-0.1352 0.0057 2.9552 +-0.1572 0.0106 2.8864 +-0.1789 0.0171 2.8177 +-0.2000 0.0250 2.7489 +primID: 5 +startangle_c: 8 +endpose_c: 0 0 9 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0000 0.0000 3.1852 +0.0000 0.0000 3.2289 +0.0000 0.0000 3.2725 +0.0000 0.0000 3.3161 +0.0000 0.0000 3.3598 +0.0000 0.0000 3.4034 +0.0000 0.0000 3.4470 +0.0000 0.0000 3.4907 +0.0000 0.0000 3.5343 +primID: 6 +startangle_c: 8 +endpose_c: 0 0 7 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0000 0.0000 3.0980 +0.0000 0.0000 3.0543 +0.0000 0.0000 3.0107 +0.0000 0.0000 2.9671 +0.0000 0.0000 2.9234 +0.0000 0.0000 2.8798 +0.0000 0.0000 2.8362 +0.0000 0.0000 2.7925 +0.0000 0.0000 2.7489 +primID: 0 +startangle_c: 9 +endpose_c: -2 -1 9 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0056 -0.0028 3.5343 +-0.0111 -0.0056 3.5343 +-0.0167 -0.0083 3.5343 +-0.0222 -0.0111 3.5343 +-0.0278 -0.0139 3.5343 +-0.0333 -0.0167 3.5343 +-0.0389 -0.0194 3.5343 +-0.0444 -0.0222 3.5343 +-0.0500 -0.0250 3.5343 +primID: 1 +startangle_c: 9 +endpose_c: -6 -3 9 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0167 -0.0083 3.5343 +-0.0333 -0.0167 3.5343 +-0.0500 -0.0250 3.5343 +-0.0667 -0.0333 3.5343 +-0.0833 -0.0417 3.5343 +-0.1000 -0.0500 3.5343 +-0.1167 -0.0583 3.5343 +-0.1333 -0.0667 3.5343 +-0.1500 -0.0750 3.5343 +primID: 2 +startangle_c: 9 +endpose_c: 2 1 9 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0056 0.0028 3.5343 +0.0111 0.0056 3.5343 +0.0167 0.0083 3.5343 +0.0222 0.0111 3.5343 +0.0278 0.0139 3.5343 +0.0333 0.0167 3.5343 +0.0389 0.0194 3.5343 +0.0444 0.0222 3.5343 +0.0500 0.0250 3.5343 +primID: 3 +startangle_c: 9 +endpose_c: -5 -4 10 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0149 -0.0092 3.5646 +-0.0296 -0.0189 3.5949 +-0.0440 -0.0291 3.6252 +-0.0582 -0.0398 3.6555 +-0.0722 -0.0509 3.6858 +-0.0858 -0.0625 3.7161 +-0.0992 -0.0746 3.7464 +-0.1123 -0.0871 3.7767 +-0.1250 -0.1000 3.8070 +primID: 4 +startangle_c: 9 +endpose_c: -7 -2 8 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0188 -0.0078 3.5343 +-0.0377 -0.0156 3.5343 +-0.0565 -0.0234 3.5343 +-0.0754 -0.0312 3.5152 +-0.0946 -0.0379 3.4405 +-0.1143 -0.0432 3.3658 +-0.1344 -0.0470 3.2910 +-0.1546 -0.0492 3.2163 +-0.1750 -0.0500 3.1416 +primID: 5 +startangle_c: 9 +endpose_c: 0 0 10 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0000 0.0000 3.5779 +0.0000 0.0000 3.6216 +0.0000 0.0000 3.6652 +0.0000 0.0000 3.7088 +0.0000 0.0000 3.7525 +0.0000 0.0000 3.7961 +0.0000 0.0000 3.8397 +0.0000 0.0000 3.8834 +0.0000 0.0000 3.9270 +primID: 6 +startangle_c: 9 +endpose_c: 0 0 8 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0000 0.0000 3.4907 +0.0000 0.0000 3.4470 +0.0000 0.0000 3.4034 +0.0000 0.0000 3.3598 +0.0000 0.0000 3.3161 +0.0000 0.0000 3.2725 +0.0000 0.0000 3.2289 +0.0000 0.0000 3.1852 +0.0000 0.0000 3.1416 +primID: 0 +startangle_c: 10 +endpose_c: -1 -1 10 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0028 -0.0028 3.9270 +-0.0056 -0.0056 3.9270 +-0.0083 -0.0083 3.9270 +-0.0111 -0.0111 3.9270 +-0.0139 -0.0139 3.9270 +-0.0167 -0.0167 3.9270 +-0.0194 -0.0194 3.9270 +-0.0222 -0.0222 3.9270 +-0.0250 -0.0250 3.9270 +primID: 1 +startangle_c: 10 +endpose_c: -6 -6 10 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0167 -0.0167 3.9270 +-0.0333 -0.0333 3.9270 +-0.0500 -0.0500 3.9270 +-0.0667 -0.0667 3.9270 +-0.0833 -0.0833 3.9270 +-0.1000 -0.1000 3.9270 +-0.1167 -0.1167 3.9270 +-0.1333 -0.1333 3.9270 +-0.1500 -0.1500 3.9270 +primID: 2 +startangle_c: 10 +endpose_c: 1 1 10 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0028 0.0028 3.9270 +0.0056 0.0056 3.9270 +0.0083 0.0083 3.9270 +0.0111 0.0111 3.9270 +0.0139 0.0139 3.9270 +0.0167 0.0167 3.9270 +0.0194 0.0194 3.9270 +0.0222 0.0222 3.9270 +0.0250 0.0250 3.9270 +primID: 3 +startangle_c: 10 +endpose_c: -5 -7 11 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0170 -0.0170 3.9270 +-0.0339 -0.0342 3.9567 +-0.0500 -0.0522 4.0085 +-0.0651 -0.0709 4.0604 +-0.0792 -0.0904 4.1123 +-0.0923 -0.1107 4.1641 +-0.1043 -0.1315 4.2160 +-0.1152 -0.1530 4.2678 +-0.1250 -0.1750 4.3197 +primID: 4 +startangle_c: 10 +endpose_c: -7 -5 9 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0170 -0.0170 3.9270 +-0.0342 -0.0339 3.8973 +-0.0522 -0.0500 3.8455 +-0.0709 -0.0651 3.7936 +-0.0904 -0.0792 3.7417 +-0.1107 -0.0923 3.6899 +-0.1315 -0.1043 3.6380 +-0.1530 -0.1152 3.5862 +-0.1750 -0.1250 3.5343 +primID: 5 +startangle_c: 10 +endpose_c: 0 0 11 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.9706 +0.0000 0.0000 4.0143 +0.0000 0.0000 4.0579 +0.0000 0.0000 4.1015 +0.0000 0.0000 4.1452 +0.0000 0.0000 4.1888 +0.0000 0.0000 4.2324 +0.0000 0.0000 4.2761 +0.0000 0.0000 4.3197 +primID: 6 +startangle_c: 10 +endpose_c: 0 0 9 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.8834 +0.0000 0.0000 3.8397 +0.0000 0.0000 3.7961 +0.0000 0.0000 3.7525 +0.0000 0.0000 3.7088 +0.0000 0.0000 3.6652 +0.0000 0.0000 3.6216 +0.0000 0.0000 3.5779 +0.0000 0.0000 3.5343 +primID: 0 +startangle_c: 11 +endpose_c: -1 -2 11 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0028 -0.0056 4.3197 +-0.0056 -0.0111 4.3197 +-0.0083 -0.0167 4.3197 +-0.0111 -0.0222 4.3197 +-0.0139 -0.0278 4.3197 +-0.0167 -0.0333 4.3197 +-0.0194 -0.0389 4.3197 +-0.0222 -0.0444 4.3197 +-0.0250 -0.0500 4.3197 +primID: 1 +startangle_c: 11 +endpose_c: -3 -6 11 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0083 -0.0167 4.3197 +-0.0167 -0.0333 4.3197 +-0.0250 -0.0500 4.3197 +-0.0333 -0.0667 4.3197 +-0.0417 -0.0833 4.3197 +-0.0500 -0.1000 4.3197 +-0.0583 -0.1167 4.3197 +-0.0667 -0.1333 4.3197 +-0.0750 -0.1500 4.3197 +primID: 2 +startangle_c: 11 +endpose_c: 1 2 11 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0028 0.0056 4.3197 +0.0056 0.0111 4.3197 +0.0083 0.0167 4.3197 +0.0111 0.0222 4.3197 +0.0139 0.0278 4.3197 +0.0167 0.0333 4.3197 +0.0194 0.0389 4.3197 +0.0222 0.0444 4.3197 +0.0250 0.0500 4.3197 +primID: 3 +startangle_c: 11 +endpose_c: -4 -5 10 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0092 -0.0149 4.2894 +-0.0189 -0.0296 4.2591 +-0.0291 -0.0440 4.2288 +-0.0398 -0.0582 4.1985 +-0.0509 -0.0722 4.1682 +-0.0625 -0.0858 4.1379 +-0.0746 -0.0992 4.1076 +-0.0871 -0.1123 4.0773 +-0.1000 -0.1250 4.0470 +primID: 4 +startangle_c: 11 +endpose_c: -2 -7 12 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0078 -0.0188 4.3197 +-0.0156 -0.0377 4.3197 +-0.0234 -0.0565 4.3197 +-0.0312 -0.0754 4.3388 +-0.0379 -0.0946 4.4135 +-0.0432 -0.1143 4.4882 +-0.0470 -0.1344 4.5629 +-0.0492 -0.1546 4.6377 +-0.0500 -0.1750 4.7124 +primID: 5 +startangle_c: 11 +endpose_c: 0 0 10 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0000 0.0000 4.2761 +0.0000 0.0000 4.2324 +0.0000 0.0000 4.1888 +0.0000 0.0000 4.1452 +0.0000 0.0000 4.1015 +0.0000 0.0000 4.0579 +0.0000 0.0000 4.0143 +0.0000 0.0000 3.9706 +0.0000 0.0000 3.9270 +primID: 6 +startangle_c: 11 +endpose_c: 0 0 12 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0000 0.0000 4.3633 +0.0000 0.0000 4.4070 +0.0000 0.0000 4.4506 +0.0000 0.0000 4.4942 +0.0000 0.0000 4.5379 +0.0000 0.0000 4.5815 +0.0000 0.0000 4.6251 +0.0000 0.0000 4.6688 +0.0000 0.0000 4.7124 +primID: 0 +startangle_c: 12 +endpose_c: 0 -1 12 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0028 4.7124 +0.0000 -0.0056 4.7124 +0.0000 -0.0083 4.7124 +0.0000 -0.0111 4.7124 +0.0000 -0.0139 4.7124 +0.0000 -0.0167 4.7124 +0.0000 -0.0194 4.7124 +0.0000 -0.0222 4.7124 +0.0000 -0.0250 4.7124 +primID: 1 +startangle_c: 12 +endpose_c: 0 -8 12 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0222 4.7124 +0.0000 -0.0444 4.7124 +0.0000 -0.0667 4.7124 +0.0000 -0.0889 4.7124 +0.0000 -0.1111 4.7124 +0.0000 -0.1333 4.7124 +0.0000 -0.1556 4.7124 +0.0000 -0.1778 4.7124 +0.0000 -0.2000 4.7124 +primID: 2 +startangle_c: 12 +endpose_c: 0 1 12 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0028 4.7124 +0.0000 0.0056 4.7124 +0.0000 0.0083 4.7124 +0.0000 0.0111 4.7124 +0.0000 0.0139 4.7124 +0.0000 0.0167 4.7124 +0.0000 0.0194 4.7124 +0.0000 0.0222 4.7124 +0.0000 0.0250 4.7124 +primID: 3 +startangle_c: 12 +endpose_c: 1 -8 13 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 4.7124 +-0.0000 -0.0226 4.7124 +-0.0000 -0.0452 4.7124 +-0.0000 -0.0678 4.7124 +0.0004 -0.0903 4.7612 +0.0023 -0.1128 4.8300 +0.0057 -0.1352 4.8988 +0.0106 -0.1572 4.9675 +0.0171 -0.1789 5.0363 +0.0250 -0.2000 5.1051 +primID: 4 +startangle_c: 12 +endpose_c: -1 -8 11 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 4.7124 +-0.0000 -0.0226 4.7124 +-0.0000 -0.0452 4.7124 +-0.0000 -0.0678 4.7124 +-0.0004 -0.0903 4.6636 +-0.0023 -0.1128 4.5948 +-0.0057 -0.1352 4.5260 +-0.0106 -0.1572 4.4572 +-0.0171 -0.1789 4.3885 +-0.0250 -0.2000 4.3197 +primID: 5 +startangle_c: 12 +endpose_c: 0 0 13 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0000 4.7560 +0.0000 0.0000 4.7997 +0.0000 0.0000 4.8433 +0.0000 0.0000 4.8869 +0.0000 0.0000 4.9306 +0.0000 0.0000 4.9742 +0.0000 0.0000 5.0178 +0.0000 0.0000 5.0615 +0.0000 0.0000 5.1051 +primID: 6 +startangle_c: 12 +endpose_c: 0 0 11 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0000 4.6688 +0.0000 0.0000 4.6251 +0.0000 0.0000 4.5815 +0.0000 0.0000 4.5379 +0.0000 0.0000 4.4942 +0.0000 0.0000 4.4506 +0.0000 0.0000 4.4070 +0.0000 0.0000 4.3633 +0.0000 0.0000 4.3197 +primID: 0 +startangle_c: 13 +endpose_c: 1 -2 13 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0028 -0.0056 5.1051 +0.0056 -0.0111 5.1051 +0.0083 -0.0167 5.1051 +0.0111 -0.0222 5.1051 +0.0139 -0.0278 5.1051 +0.0167 -0.0333 5.1051 +0.0194 -0.0389 5.1051 +0.0222 -0.0444 5.1051 +0.0250 -0.0500 5.1051 +primID: 1 +startangle_c: 13 +endpose_c: 3 -6 13 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0083 -0.0167 5.1051 +0.0167 -0.0333 5.1051 +0.0250 -0.0500 5.1051 +0.0333 -0.0667 5.1051 +0.0417 -0.0833 5.1051 +0.0500 -0.1000 5.1051 +0.0583 -0.1167 5.1051 +0.0667 -0.1333 5.1051 +0.0750 -0.1500 5.1051 +primID: 2 +startangle_c: 13 +endpose_c: -1 2 13 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 5.1051 +-0.0028 0.0056 5.1051 +-0.0056 0.0111 5.1051 +-0.0083 0.0167 5.1051 +-0.0111 0.0222 5.1051 +-0.0139 0.0278 5.1051 +-0.0167 0.0333 5.1051 +-0.0194 0.0389 5.1051 +-0.0222 0.0444 5.1051 +-0.0250 0.0500 5.1051 +primID: 3 +startangle_c: 13 +endpose_c: 4 -5 14 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0092 -0.0149 5.1354 +0.0189 -0.0296 5.1657 +0.0291 -0.0440 5.1960 +0.0398 -0.0582 5.2263 +0.0509 -0.0722 5.2566 +0.0625 -0.0858 5.2869 +0.0746 -0.0992 5.3172 +0.0871 -0.1123 5.3475 +0.1000 -0.1250 5.3778 +primID: 4 +startangle_c: 13 +endpose_c: 2 -7 12 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0078 -0.0188 5.1051 +0.0156 -0.0377 5.1051 +0.0234 -0.0565 5.1051 +0.0312 -0.0754 5.0860 +0.0379 -0.0946 5.0113 +0.0432 -0.1143 4.9366 +0.0470 -0.1344 4.8618 +0.0492 -0.1546 4.7871 +0.0500 -0.1750 4.7124 +primID: 5 +startangle_c: 13 +endpose_c: 0 0 14 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0000 0.0000 5.1487 +0.0000 0.0000 5.1924 +0.0000 0.0000 5.2360 +0.0000 0.0000 5.2796 +0.0000 0.0000 5.3233 +0.0000 0.0000 5.3669 +0.0000 0.0000 5.4105 +0.0000 0.0000 5.4542 +0.0000 0.0000 5.4978 +primID: 6 +startangle_c: 13 +endpose_c: 0 0 12 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0000 0.0000 5.0615 +0.0000 0.0000 5.0178 +0.0000 0.0000 4.9742 +0.0000 0.0000 4.9306 +0.0000 0.0000 4.8869 +0.0000 0.0000 4.8433 +0.0000 0.0000 4.7997 +0.0000 0.0000 4.7560 +0.0000 0.0000 4.7124 +primID: 0 +startangle_c: 14 +endpose_c: 1 -1 14 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0028 -0.0028 5.4978 +0.0056 -0.0056 5.4978 +0.0083 -0.0083 5.4978 +0.0111 -0.0111 5.4978 +0.0139 -0.0139 5.4978 +0.0167 -0.0167 5.4978 +0.0194 -0.0194 5.4978 +0.0222 -0.0222 5.4978 +0.0250 -0.0250 5.4978 +primID: 1 +startangle_c: 14 +endpose_c: 6 -6 14 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0167 -0.0167 5.4978 +0.0333 -0.0333 5.4978 +0.0500 -0.0500 5.4978 +0.0667 -0.0667 5.4978 +0.0833 -0.0833 5.4978 +0.1000 -0.1000 5.4978 +0.1167 -0.1167 5.4978 +0.1333 -0.1333 5.4978 +0.1500 -0.1500 5.4978 +primID: 2 +startangle_c: 14 +endpose_c: -1 1 14 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 5.4978 +-0.0028 0.0028 5.4978 +-0.0056 0.0056 5.4978 +-0.0083 0.0083 5.4978 +-0.0111 0.0111 5.4978 +-0.0139 0.0139 5.4978 +-0.0167 0.0167 5.4978 +-0.0194 0.0194 5.4978 +-0.0222 0.0222 5.4978 +-0.0250 0.0250 5.4978 +primID: 3 +startangle_c: 14 +endpose_c: 7 -5 15 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0170 -0.0170 5.4978 +0.0342 -0.0339 5.5275 +0.0522 -0.0500 5.5793 +0.0709 -0.0651 5.6312 +0.0904 -0.0792 5.6830 +0.1107 -0.0923 5.7349 +0.1315 -0.1043 5.7868 +0.1530 -0.1152 5.8386 +0.1750 -0.1250 5.8905 +primID: 4 +startangle_c: 14 +endpose_c: 5 -7 13 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0170 -0.0170 5.4978 +0.0339 -0.0342 5.4681 +0.0500 -0.0522 5.4162 +0.0651 -0.0709 5.3644 +0.0792 -0.0904 5.3125 +0.0923 -0.1107 5.2607 +0.1043 -0.1315 5.2088 +0.1152 -0.1530 5.1569 +0.1250 -0.1750 5.1051 +primID: 5 +startangle_c: 14 +endpose_c: 0 0 15 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0000 0.0000 5.5414 +0.0000 0.0000 5.5851 +0.0000 0.0000 5.6287 +0.0000 0.0000 5.6723 +0.0000 0.0000 5.7160 +0.0000 0.0000 5.7596 +0.0000 0.0000 5.8032 +0.0000 0.0000 5.8469 +0.0000 0.0000 5.8905 +primID: 6 +startangle_c: 14 +endpose_c: 0 0 13 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0000 0.0000 5.4542 +0.0000 0.0000 5.4105 +0.0000 0.0000 5.3669 +0.0000 0.0000 5.3233 +0.0000 0.0000 5.2796 +0.0000 0.0000 5.2360 +0.0000 0.0000 5.1924 +0.0000 0.0000 5.1487 +0.0000 0.0000 5.1051 +primID: 0 +startangle_c: 15 +endpose_c: 2 -1 15 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0056 -0.0028 5.8905 +0.0111 -0.0056 5.8905 +0.0167 -0.0083 5.8905 +0.0222 -0.0111 5.8905 +0.0278 -0.0139 5.8905 +0.0333 -0.0167 5.8905 +0.0389 -0.0194 5.8905 +0.0444 -0.0222 5.8905 +0.0500 -0.0250 5.8905 +primID: 1 +startangle_c: 15 +endpose_c: 6 -3 15 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0167 -0.0083 5.8905 +0.0333 -0.0167 5.8905 +0.0500 -0.0250 5.8905 +0.0667 -0.0333 5.8905 +0.0833 -0.0417 5.8905 +0.1000 -0.0500 5.8905 +0.1167 -0.0583 5.8905 +0.1333 -0.0667 5.8905 +0.1500 -0.0750 5.8905 +primID: 2 +startangle_c: 15 +endpose_c: -2 1 15 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 5.8905 +-0.0056 0.0028 5.8905 +-0.0111 0.0056 5.8905 +-0.0167 0.0083 5.8905 +-0.0222 0.0111 5.8905 +-0.0278 0.0139 5.8905 +-0.0333 0.0167 5.8905 +-0.0389 0.0194 5.8905 +-0.0444 0.0222 5.8905 +-0.0500 0.0250 5.8905 +primID: 3 +startangle_c: 15 +endpose_c: 5 -4 14 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0149 -0.0092 5.8602 +0.0296 -0.0189 5.8299 +0.0440 -0.0291 5.7996 +0.0582 -0.0398 5.7693 +0.0722 -0.0509 5.7390 +0.0858 -0.0625 5.7087 +0.0992 -0.0746 5.6784 +0.1123 -0.0871 5.6481 +0.1250 -0.1000 5.6178 +primID: 4 +startangle_c: 15 +endpose_c: 7 -2 0 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0188 -0.0078 5.8905 +0.0377 -0.0156 5.8905 +0.0565 -0.0234 5.8905 +0.0754 -0.0312 5.9096 +0.0946 -0.0379 5.9843 +0.1143 -0.0432 6.0590 +0.1344 -0.0470 6.1337 +0.1546 -0.0492 6.2085 +0.1750 -0.0500 6.2832 +primID: 5 +startangle_c: 15 +endpose_c: 0 0 14 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0000 0.0000 5.8469 +0.0000 0.0000 5.8032 +0.0000 0.0000 5.7596 +0.0000 0.0000 5.7160 +0.0000 0.0000 5.6723 +0.0000 0.0000 5.6287 +0.0000 0.0000 5.5851 +0.0000 0.0000 5.5414 +0.0000 0.0000 5.4978 +primID: 6 +startangle_c: 15 +endpose_c: 0 0 0 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0000 0.0000 5.9341 +0.0000 0.0000 5.9778 +0.0000 0.0000 6.0214 +0.0000 0.0000 6.0650 +0.0000 0.0000 6.1087 +0.0000 0.0000 6.1523 +0.0000 0.0000 6.1959 +0.0000 0.0000 6.2396 +0.0000 0.0000 0.0000 diff --git a/navigations/sbpl/matlab/mprim/pr2_10cm.mprim b/navigations/sbpl/matlab/mprim/pr2_10cm.mprim new file mode 100755 index 0000000..284db22 --- /dev/null +++ b/navigations/sbpl/matlab/mprim/pr2_10cm.mprim @@ -0,0 +1,3843 @@ +resolution_m: 0.100000 +numberofangles: 16 +totalnumberofprimitives: 256 +primID: 0 +startangle_c: 0 +endpose_c: 1 0 0 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0111 0.0000 0.0000 +0.0222 0.0000 0.0000 +0.0333 0.0000 0.0000 +0.0444 0.0000 0.0000 +0.0556 0.0000 0.0000 +0.0667 0.0000 0.0000 +0.0778 0.0000 0.0000 +0.0889 0.0000 0.0000 +0.1000 0.0000 0.0000 +primID: 1 +startangle_c: 0 +endpose_c: 4 0 0 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0444 0.0000 0.0000 +0.0889 0.0000 0.0000 +0.1333 0.0000 0.0000 +0.1778 0.0000 0.0000 +0.2222 0.0000 0.0000 +0.2667 0.0000 0.0000 +0.3111 0.0000 0.0000 +0.3556 0.0000 0.0000 +0.4000 0.0000 0.0000 +primID: 2 +startangle_c: 0 +endpose_c: 8 0 0 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0889 0.0000 0.0000 +0.1778 0.0000 0.0000 +0.2667 0.0000 0.0000 +0.3556 0.0000 0.0000 +0.4444 0.0000 0.0000 +0.5333 0.0000 0.0000 +0.6222 0.0000 0.0000 +0.7111 0.0000 0.0000 +0.8000 0.0000 0.0000 +primID: 3 +startangle_c: 0 +endpose_c: 6 2 0 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0667 0.0222 0.0000 +0.1333 0.0444 0.0000 +0.2000 0.0667 0.0000 +0.2667 0.0889 0.0000 +0.3333 0.1111 0.0000 +0.4000 0.1333 0.0000 +0.4667 0.1556 0.0000 +0.5333 0.1778 0.0000 +0.6000 0.2000 0.0000 +primID: 4 +startangle_c: 0 +endpose_c: 6 -2 0 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0667 -0.0222 0.0000 +0.1333 -0.0444 0.0000 +0.2000 -0.0667 0.0000 +0.2667 -0.0889 0.0000 +0.3333 -0.1111 0.0000 +0.4000 -0.1333 0.0000 +0.4667 -0.1556 0.0000 +0.5333 -0.1778 0.0000 +0.6000 -0.2000 0.0000 +primID: 5 +startangle_c: 0 +endpose_c: 2 3 0 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0222 0.0333 0.0000 +0.0444 0.0667 0.0000 +0.0667 0.1000 0.0000 +0.0889 0.1333 0.0000 +0.1111 0.1667 0.0000 +0.1333 0.2000 0.0000 +0.1556 0.2333 0.0000 +0.1778 0.2667 0.0000 +0.2000 0.3000 0.0000 +primID: 6 +startangle_c: 0 +endpose_c: 2 -3 0 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0222 -0.0333 0.0000 +0.0444 -0.0667 0.0000 +0.0667 -0.1000 0.0000 +0.0889 -0.1333 0.0000 +0.1111 -0.1667 0.0000 +0.1333 -0.2000 0.0000 +0.1556 -0.2333 0.0000 +0.1778 -0.2667 0.0000 +0.2000 -0.3000 0.0000 +primID: 7 +startangle_c: 0 +endpose_c: -5 0 0 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 0.0000 +-0.0556 0.0000 0.0000 +-0.1111 0.0000 0.0000 +-0.1667 0.0000 0.0000 +-0.2222 0.0000 0.0000 +-0.2778 0.0000 0.0000 +-0.3333 0.0000 0.0000 +-0.3889 0.0000 0.0000 +-0.4444 0.0000 0.0000 +-0.5000 0.0000 0.0000 +primID: 8 +startangle_c: 0 +endpose_c: 6 2 1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0667 0.0222 0.0436 +0.1333 0.0444 0.0873 +0.2000 0.0667 0.1309 +0.2667 0.0889 0.1745 +0.3333 0.1111 0.2182 +0.4000 0.1333 0.2618 +0.4667 0.1556 0.3054 +0.5333 0.1778 0.3491 +0.6000 0.2000 0.3927 +primID: 9 +startangle_c: 0 +endpose_c: 6 -2 -1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0667 -0.0222 -0.0436 +0.1333 -0.0444 -0.0873 +0.2000 -0.0667 -0.1309 +0.2667 -0.0889 -0.1745 +0.3333 -0.1111 -0.2182 +0.4000 -0.1333 -0.2618 +0.4667 -0.1556 -0.3054 +0.5333 -0.1778 -0.3491 +0.6000 -0.2000 -0.3927 +primID: 10 +startangle_c: 0 +endpose_c: 4 3 2 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0444 0.0333 0.0873 +0.0889 0.0667 0.1745 +0.1333 0.1000 0.2618 +0.1778 0.1333 0.3491 +0.2222 0.1667 0.4363 +0.2667 0.2000 0.5236 +0.3111 0.2333 0.6109 +0.3556 0.2667 0.6981 +0.4000 0.3000 0.7854 +primID: 11 +startangle_c: 0 +endpose_c: 4 -3 -2 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0444 -0.0333 -0.0873 +0.0889 -0.0667 -0.1745 +0.1333 -0.1000 -0.2618 +0.1778 -0.1333 -0.3491 +0.2222 -0.1667 -0.4363 +0.2667 -0.2000 -0.5236 +0.3111 -0.2333 -0.6109 +0.3556 -0.2667 -0.6981 +0.4000 -0.3000 -0.7854 +primID: 12 +startangle_c: 0 +endpose_c: 0 0 1 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0000 0.0000 0.0436 +0.0000 0.0000 0.0873 +0.0000 0.0000 0.1309 +0.0000 0.0000 0.1745 +0.0000 0.0000 0.2182 +0.0000 0.0000 0.2618 +0.0000 0.0000 0.3054 +0.0000 0.0000 0.3491 +0.0000 0.0000 0.3927 +primID: 13 +startangle_c: 0 +endpose_c: 0 0 -1 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0000 0.0000 -0.0436 +0.0000 0.0000 -0.0873 +0.0000 0.0000 -0.1309 +0.0000 0.0000 -0.1745 +0.0000 0.0000 -0.2182 +0.0000 0.0000 -0.2618 +0.0000 0.0000 -0.3054 +0.0000 0.0000 -0.3491 +0.0000 0.0000 -0.3927 +primID: 14 +startangle_c: 0 +endpose_c: 0 0 3 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0000 0.0000 0.1309 +0.0000 0.0000 0.2618 +0.0000 0.0000 0.3927 +0.0000 0.0000 0.5236 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.7854 +0.0000 0.0000 0.9163 +0.0000 0.0000 1.0472 +0.0000 0.0000 1.1781 +primID: 15 +startangle_c: 0 +endpose_c: 0 0 -3 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0000 0.0000 -0.1309 +0.0000 0.0000 -0.2618 +0.0000 0.0000 -0.3927 +0.0000 0.0000 -0.5236 +0.0000 0.0000 -0.6545 +0.0000 0.0000 -0.7854 +0.0000 0.0000 -0.9163 +0.0000 0.0000 -1.0472 +0.0000 0.0000 -1.1781 +primID: 0 +startangle_c: 1 +endpose_c: 2 1 1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0222 0.0111 0.3927 +0.0444 0.0222 0.3927 +0.0667 0.0333 0.3927 +0.0889 0.0444 0.3927 +0.1111 0.0556 0.3927 +0.1333 0.0667 0.3927 +0.1556 0.0778 0.3927 +0.1778 0.0889 0.3927 +0.2000 0.1000 0.3927 +primID: 1 +startangle_c: 1 +endpose_c: 4 2 1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0444 0.0222 0.3927 +0.0889 0.0444 0.3927 +0.1333 0.0667 0.3927 +0.1778 0.0889 0.3927 +0.2222 0.1111 0.3927 +0.2667 0.1333 0.3927 +0.3111 0.1556 0.3927 +0.3556 0.1778 0.3927 +0.4000 0.2000 0.3927 +primID: 2 +startangle_c: 1 +endpose_c: 6 3 1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0667 0.0333 0.3927 +0.1333 0.0667 0.3927 +0.2000 0.1000 0.3927 +0.2667 0.1333 0.3927 +0.3333 0.1667 0.3927 +0.4000 0.2000 0.3927 +0.4667 0.2333 0.3927 +0.5333 0.2667 0.3927 +0.6000 0.3000 0.3927 +primID: 3 +startangle_c: 1 +endpose_c: 4 4 1 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0444 0.0444 0.3927 +0.0889 0.0889 0.3927 +0.1333 0.1333 0.3927 +0.1778 0.1778 0.3927 +0.2222 0.2222 0.3927 +0.2667 0.2667 0.3927 +0.3111 0.3111 0.3927 +0.3556 0.3556 0.3927 +0.4000 0.4000 0.3927 +primID: 4 +startangle_c: 1 +endpose_c: 6 2 1 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0667 0.0222 0.3927 +0.1333 0.0444 0.3927 +0.2000 0.0667 0.3927 +0.2667 0.0889 0.3927 +0.3333 0.1111 0.3927 +0.4000 0.1333 0.3927 +0.4667 0.1556 0.3927 +0.5333 0.1778 0.3927 +0.6000 0.2000 0.3927 +primID: 5 +startangle_c: 1 +endpose_c: 0 3 1 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0000 0.0333 0.3927 +0.0000 0.0667 0.3927 +0.0000 0.1000 0.3927 +0.0000 0.1333 0.3927 +0.0000 0.1667 0.3927 +0.0000 0.2000 0.3927 +0.0000 0.2333 0.3927 +0.0000 0.2667 0.3927 +0.0000 0.3000 0.3927 +primID: 6 +startangle_c: 1 +endpose_c: 4 -1 1 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0444 -0.0111 0.3927 +0.0889 -0.0222 0.3927 +0.1333 -0.0333 0.3927 +0.1778 -0.0444 0.3927 +0.2222 -0.0556 0.3927 +0.2667 -0.0667 0.3927 +0.3111 -0.0778 0.3927 +0.3556 -0.0889 0.3927 +0.4000 -0.1000 0.3927 +primID: 7 +startangle_c: 1 +endpose_c: -4 -2 1 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 0.3927 +-0.0444 -0.0222 0.3927 +-0.0889 -0.0444 0.3927 +-0.1333 -0.0667 0.3927 +-0.1778 -0.0889 0.3927 +-0.2222 -0.1111 0.3927 +-0.2667 -0.1333 0.3927 +-0.3111 -0.1556 0.3927 +-0.3556 -0.1778 0.3927 +-0.4000 -0.2000 0.3927 +primID: 8 +startangle_c: 1 +endpose_c: 4 4 2 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0444 0.0444 0.4363 +0.0889 0.0889 0.4800 +0.1333 0.1333 0.5236 +0.1778 0.1778 0.5672 +0.2222 0.2222 0.6109 +0.2667 0.2667 0.6545 +0.3111 0.3111 0.6981 +0.3556 0.3556 0.7418 +0.4000 0.4000 0.7854 +primID: 9 +startangle_c: 1 +endpose_c: 6 2 0 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0667 0.0222 0.3491 +0.1333 0.0444 0.3054 +0.2000 0.0667 0.2618 +0.2667 0.0889 0.2182 +0.3333 0.1111 0.1745 +0.4000 0.1333 0.1309 +0.4667 0.1556 0.0873 +0.5333 0.1778 0.0436 +0.6000 0.2000 0.0000 +primID: 10 +startangle_c: 1 +endpose_c: 2 4 3 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0222 0.0444 0.4800 +0.0444 0.0889 0.5672 +0.0667 0.1333 0.6545 +0.0889 0.1778 0.7418 +0.1111 0.2222 0.8290 +0.1333 0.2667 0.9163 +0.1556 0.3111 1.0036 +0.1778 0.3556 1.0908 +0.2000 0.4000 1.1781 +primID: 11 +startangle_c: 1 +endpose_c: 6 0 -1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0667 0.0000 0.3054 +0.1333 0.0000 0.2182 +0.2000 0.0000 0.1309 +0.2667 0.0000 0.0436 +0.3333 0.0000 -0.0436 +0.4000 0.0000 -0.1309 +0.4667 0.0000 -0.2182 +0.5333 0.0000 -0.3054 +0.6000 0.0000 -0.3927 +primID: 12 +startangle_c: 1 +endpose_c: 0 0 2 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0000 0.0000 0.4363 +0.0000 0.0000 0.4800 +0.0000 0.0000 0.5236 +0.0000 0.0000 0.5672 +0.0000 0.0000 0.6109 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.6981 +0.0000 0.0000 0.7418 +0.0000 0.0000 0.7854 +primID: 13 +startangle_c: 1 +endpose_c: 0 0 0 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0000 0.0000 0.3491 +0.0000 0.0000 0.3054 +0.0000 0.0000 0.2618 +0.0000 0.0000 0.2182 +0.0000 0.0000 0.1745 +0.0000 0.0000 0.1309 +0.0000 0.0000 0.0873 +0.0000 0.0000 0.0436 +0.0000 0.0000 0.0000 +primID: 14 +startangle_c: 1 +endpose_c: 0 0 4 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0000 0.0000 0.5236 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.7854 +0.0000 0.0000 0.9163 +0.0000 0.0000 1.0472 +0.0000 0.0000 1.1781 +0.0000 0.0000 1.3090 +0.0000 0.0000 1.4399 +0.0000 0.0000 1.5708 +primID: 15 +startangle_c: 1 +endpose_c: 0 0 -2 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0000 0.0000 0.2618 +0.0000 0.0000 0.1309 +0.0000 0.0000 0.0000 +0.0000 0.0000 -0.1309 +0.0000 0.0000 -0.2618 +0.0000 0.0000 -0.3927 +0.0000 0.0000 -0.5236 +0.0000 0.0000 -0.6545 +0.0000 0.0000 -0.7854 +primID: 0 +startangle_c: 2 +endpose_c: 1 1 2 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0111 0.0111 0.7854 +0.0222 0.0222 0.7854 +0.0333 0.0333 0.7854 +0.0444 0.0444 0.7854 +0.0556 0.0556 0.7854 +0.0667 0.0667 0.7854 +0.0778 0.0778 0.7854 +0.0889 0.0889 0.7854 +0.1000 0.1000 0.7854 +primID: 1 +startangle_c: 2 +endpose_c: 3 3 2 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0333 0.0333 0.7854 +0.0667 0.0667 0.7854 +0.1000 0.1000 0.7854 +0.1333 0.1333 0.7854 +0.1667 0.1667 0.7854 +0.2000 0.2000 0.7854 +0.2333 0.2333 0.7854 +0.2667 0.2667 0.7854 +0.3000 0.3000 0.7854 +primID: 2 +startangle_c: 2 +endpose_c: 6 6 2 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0667 0.0667 0.7854 +0.1333 0.1333 0.7854 +0.2000 0.2000 0.7854 +0.2667 0.2667 0.7854 +0.3333 0.3333 0.7854 +0.4000 0.4000 0.7854 +0.4667 0.4667 0.7854 +0.5333 0.5333 0.7854 +0.6000 0.6000 0.7854 +primID: 3 +startangle_c: 2 +endpose_c: 2 6 2 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0222 0.0667 0.7854 +0.0444 0.1333 0.7854 +0.0667 0.2000 0.7854 +0.0889 0.2667 0.7854 +0.1111 0.3333 0.7854 +0.1333 0.4000 0.7854 +0.1556 0.4667 0.7854 +0.1778 0.5333 0.7854 +0.2000 0.6000 0.7854 +primID: 4 +startangle_c: 2 +endpose_c: 6 2 2 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0667 0.0222 0.7854 +0.1333 0.0444 0.7854 +0.2000 0.0667 0.7854 +0.2667 0.0889 0.7854 +0.3333 0.1111 0.7854 +0.4000 0.1333 0.7854 +0.4667 0.1556 0.7854 +0.5333 0.1778 0.7854 +0.6000 0.2000 0.7854 +primID: 5 +startangle_c: 2 +endpose_c: 0 4 2 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0000 0.0444 0.7854 +0.0000 0.0889 0.7854 +0.0000 0.1333 0.7854 +0.0000 0.1778 0.7854 +0.0000 0.2222 0.7854 +0.0000 0.2667 0.7854 +0.0000 0.3111 0.7854 +0.0000 0.3556 0.7854 +0.0000 0.4000 0.7854 +primID: 6 +startangle_c: 2 +endpose_c: 4 0 2 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0444 0.0000 0.7854 +0.0889 0.0000 0.7854 +0.1333 0.0000 0.7854 +0.1778 0.0000 0.7854 +0.2222 0.0000 0.7854 +0.2667 0.0000 0.7854 +0.3111 0.0000 0.7854 +0.3556 0.0000 0.7854 +0.4000 0.0000 0.7854 +primID: 7 +startangle_c: 2 +endpose_c: -4 -4 2 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 0.7854 +-0.0444 -0.0444 0.7854 +-0.0889 -0.0889 0.7854 +-0.1333 -0.1333 0.7854 +-0.1778 -0.1778 0.7854 +-0.2222 -0.2222 0.7854 +-0.2667 -0.2667 0.7854 +-0.3111 -0.3111 0.7854 +-0.3556 -0.3556 0.7854 +-0.4000 -0.4000 0.7854 +primID: 8 +startangle_c: 2 +endpose_c: 2 6 3 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0222 0.0667 0.8290 +0.0444 0.1333 0.8727 +0.0667 0.2000 0.9163 +0.0889 0.2667 0.9599 +0.1111 0.3333 1.0036 +0.1333 0.4000 1.0472 +0.1556 0.4667 1.0908 +0.1778 0.5333 1.1345 +0.2000 0.6000 1.1781 +primID: 9 +startangle_c: 2 +endpose_c: 6 2 1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0667 0.0222 0.7418 +0.1333 0.0444 0.6981 +0.2000 0.0667 0.6545 +0.2667 0.0889 0.6109 +0.3333 0.1111 0.5672 +0.4000 0.1333 0.5236 +0.4667 0.1556 0.4800 +0.5333 0.1778 0.4363 +0.6000 0.2000 0.3927 +primID: 10 +startangle_c: 2 +endpose_c: 1 5 4 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0111 0.0556 0.8727 +0.0222 0.1111 0.9599 +0.0333 0.1667 1.0472 +0.0444 0.2222 1.1345 +0.0556 0.2778 1.2217 +0.0667 0.3333 1.3090 +0.0778 0.3889 1.3963 +0.0889 0.4444 1.4835 +0.1000 0.5000 1.5708 +primID: 11 +startangle_c: 2 +endpose_c: 5 1 0 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0556 0.0111 0.6981 +0.1111 0.0222 0.6109 +0.1667 0.0333 0.5236 +0.2222 0.0444 0.4363 +0.2778 0.0556 0.3491 +0.3333 0.0667 0.2618 +0.3889 0.0778 0.1745 +0.4444 0.0889 0.0873 +0.5000 0.1000 0.0000 +primID: 12 +startangle_c: 2 +endpose_c: 0 0 3 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0000 0.0000 0.8290 +0.0000 0.0000 0.8727 +0.0000 0.0000 0.9163 +0.0000 0.0000 0.9599 +0.0000 0.0000 1.0036 +0.0000 0.0000 1.0472 +0.0000 0.0000 1.0908 +0.0000 0.0000 1.1345 +0.0000 0.0000 1.1781 +primID: 13 +startangle_c: 2 +endpose_c: 0 0 1 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0000 0.0000 0.7418 +0.0000 0.0000 0.6981 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.6109 +0.0000 0.0000 0.5672 +0.0000 0.0000 0.5236 +0.0000 0.0000 0.4800 +0.0000 0.0000 0.4363 +0.0000 0.0000 0.3927 +primID: 14 +startangle_c: 2 +endpose_c: 0 0 5 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0000 0.0000 0.9163 +0.0000 0.0000 1.0472 +0.0000 0.0000 1.1781 +0.0000 0.0000 1.3090 +0.0000 0.0000 1.4399 +0.0000 0.0000 1.5708 +0.0000 0.0000 1.7017 +0.0000 0.0000 1.8326 +0.0000 0.0000 1.9635 +primID: 15 +startangle_c: 2 +endpose_c: 0 0 -1 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.5236 +0.0000 0.0000 0.3927 +0.0000 0.0000 0.2618 +0.0000 0.0000 0.1309 +0.0000 0.0000 0.0000 +0.0000 0.0000 -0.1309 +0.0000 0.0000 -0.2618 +0.0000 0.0000 -0.3927 +primID: 0 +startangle_c: 3 +endpose_c: 1 2 3 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0111 0.0222 1.1781 +0.0222 0.0444 1.1781 +0.0333 0.0667 1.1781 +0.0444 0.0889 1.1781 +0.0556 0.1111 1.1781 +0.0667 0.1333 1.1781 +0.0778 0.1556 1.1781 +0.0889 0.1778 1.1781 +0.1000 0.2000 1.1781 +primID: 1 +startangle_c: 3 +endpose_c: 2 4 3 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0222 0.0444 1.1781 +0.0444 0.0889 1.1781 +0.0667 0.1333 1.1781 +0.0889 0.1778 1.1781 +0.1111 0.2222 1.1781 +0.1333 0.2667 1.1781 +0.1556 0.3111 1.1781 +0.1778 0.3556 1.1781 +0.2000 0.4000 1.1781 +primID: 2 +startangle_c: 3 +endpose_c: 3 6 3 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0333 0.0667 1.1781 +0.0667 0.1333 1.1781 +0.1000 0.2000 1.1781 +0.1333 0.2667 1.1781 +0.1667 0.3333 1.1781 +0.2000 0.4000 1.1781 +0.2333 0.4667 1.1781 +0.2667 0.5333 1.1781 +0.3000 0.6000 1.1781 +primID: 3 +startangle_c: 3 +endpose_c: 4 4 3 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0444 0.0444 1.1781 +0.0889 0.0889 1.1781 +0.1333 0.1333 1.1781 +0.1778 0.1778 1.1781 +0.2222 0.2222 1.1781 +0.2667 0.2667 1.1781 +0.3111 0.3111 1.1781 +0.3556 0.3556 1.1781 +0.4000 0.4000 1.1781 +primID: 4 +startangle_c: 3 +endpose_c: 2 6 3 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0222 0.0667 1.1781 +0.0444 0.1333 1.1781 +0.0667 0.2000 1.1781 +0.0889 0.2667 1.1781 +0.1111 0.3333 1.1781 +0.1333 0.4000 1.1781 +0.1556 0.4667 1.1781 +0.1778 0.5333 1.1781 +0.2000 0.6000 1.1781 +primID: 5 +startangle_c: 3 +endpose_c: 3 0 3 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0333 0.0000 1.1781 +0.0667 0.0000 1.1781 +0.1000 0.0000 1.1781 +0.1333 0.0000 1.1781 +0.1667 0.0000 1.1781 +0.2000 0.0000 1.1781 +0.2333 0.0000 1.1781 +0.2667 0.0000 1.1781 +0.3000 0.0000 1.1781 +primID: 6 +startangle_c: 3 +endpose_c: -1 4 3 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.1781 +-0.0111 0.0444 1.1781 +-0.0222 0.0889 1.1781 +-0.0333 0.1333 1.1781 +-0.0444 0.1778 1.1781 +-0.0556 0.2222 1.1781 +-0.0667 0.2667 1.1781 +-0.0778 0.3111 1.1781 +-0.0889 0.3556 1.1781 +-0.1000 0.4000 1.1781 +primID: 7 +startangle_c: 3 +endpose_c: -2 -4 3 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 1.1781 +-0.0222 -0.0444 1.1781 +-0.0444 -0.0889 1.1781 +-0.0667 -0.1333 1.1781 +-0.0889 -0.1778 1.1781 +-0.1111 -0.2222 1.1781 +-0.1333 -0.2667 1.1781 +-0.1556 -0.3111 1.1781 +-0.1778 -0.3556 1.1781 +-0.2000 -0.4000 1.1781 +primID: 8 +startangle_c: 3 +endpose_c: 4 4 2 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0444 0.0444 1.1345 +0.0889 0.0889 1.0908 +0.1333 0.1333 1.0472 +0.1778 0.1778 1.0036 +0.2222 0.2222 0.9599 +0.2667 0.2667 0.9163 +0.3111 0.3111 0.8727 +0.3556 0.3556 0.8290 +0.4000 0.4000 0.7854 +primID: 9 +startangle_c: 3 +endpose_c: 2 6 4 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0222 0.0667 1.2217 +0.0444 0.1333 1.2654 +0.0667 0.2000 1.3090 +0.0889 0.2667 1.3526 +0.1111 0.3333 1.3963 +0.1333 0.4000 1.4399 +0.1556 0.4667 1.4835 +0.1778 0.5333 1.5272 +0.2000 0.6000 1.5708 +primID: 10 +startangle_c: 3 +endpose_c: 4 2 1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0444 0.0222 1.0908 +0.0889 0.0444 1.0036 +0.1333 0.0667 0.9163 +0.1778 0.0889 0.8290 +0.2222 0.1111 0.7418 +0.2667 0.1333 0.6545 +0.3111 0.1556 0.5672 +0.3556 0.1778 0.4800 +0.4000 0.2000 0.3927 +primID: 11 +startangle_c: 3 +endpose_c: 0 6 5 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0000 0.0667 1.2654 +0.0000 0.1333 1.3526 +0.0000 0.2000 1.4399 +0.0000 0.2667 1.5272 +0.0000 0.3333 1.6144 +0.0000 0.4000 1.7017 +0.0000 0.4667 1.7890 +0.0000 0.5333 1.8762 +0.0000 0.6000 1.9635 +primID: 12 +startangle_c: 3 +endpose_c: 0 0 2 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0000 0.0000 1.1345 +0.0000 0.0000 1.0908 +0.0000 0.0000 1.0472 +0.0000 0.0000 1.0036 +0.0000 0.0000 0.9599 +0.0000 0.0000 0.9163 +0.0000 0.0000 0.8727 +0.0000 0.0000 0.8290 +0.0000 0.0000 0.7854 +primID: 13 +startangle_c: 3 +endpose_c: 0 0 4 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0000 0.0000 1.2217 +0.0000 0.0000 1.2654 +0.0000 0.0000 1.3090 +0.0000 0.0000 1.3526 +0.0000 0.0000 1.3963 +0.0000 0.0000 1.4399 +0.0000 0.0000 1.4835 +0.0000 0.0000 1.5272 +0.0000 0.0000 1.5708 +primID: 14 +startangle_c: 3 +endpose_c: 0 0 0 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0000 0.0000 1.0472 +0.0000 0.0000 0.9163 +0.0000 0.0000 0.7854 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.5236 +0.0000 0.0000 0.3927 +0.0000 0.0000 0.2618 +0.0000 0.0000 0.1309 +0.0000 0.0000 0.0000 +primID: 15 +startangle_c: 3 +endpose_c: 0 0 6 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0000 0.0000 1.3090 +0.0000 0.0000 1.4399 +0.0000 0.0000 1.5708 +0.0000 0.0000 1.7017 +0.0000 0.0000 1.8326 +0.0000 0.0000 1.9635 +0.0000 0.0000 2.0944 +0.0000 0.0000 2.2253 +0.0000 0.0000 2.3562 +primID: 0 +startangle_c: 4 +endpose_c: 0 1 4 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0111 1.5708 +0.0000 0.0222 1.5708 +0.0000 0.0333 1.5708 +0.0000 0.0444 1.5708 +0.0000 0.0556 1.5708 +0.0000 0.0667 1.5708 +0.0000 0.0778 1.5708 +0.0000 0.0889 1.5708 +0.0000 0.1000 1.5708 +primID: 1 +startangle_c: 4 +endpose_c: 0 4 4 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0444 1.5708 +0.0000 0.0889 1.5708 +0.0000 0.1333 1.5708 +0.0000 0.1778 1.5708 +0.0000 0.2222 1.5708 +0.0000 0.2667 1.5708 +0.0000 0.3111 1.5708 +0.0000 0.3556 1.5708 +0.0000 0.4000 1.5708 +primID: 2 +startangle_c: 4 +endpose_c: 0 8 4 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0889 1.5708 +0.0000 0.1778 1.5708 +0.0000 0.2667 1.5708 +0.0000 0.3556 1.5708 +0.0000 0.4444 1.5708 +0.0000 0.5333 1.5708 +0.0000 0.6222 1.5708 +0.0000 0.7111 1.5708 +0.0000 0.8000 1.5708 +primID: 3 +startangle_c: 4 +endpose_c: -2 6 4 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.5708 +-0.0222 0.0667 1.5708 +-0.0444 0.1333 1.5708 +-0.0667 0.2000 1.5708 +-0.0889 0.2667 1.5708 +-0.1111 0.3333 1.5708 +-0.1333 0.4000 1.5708 +-0.1556 0.4667 1.5708 +-0.1778 0.5333 1.5708 +-0.2000 0.6000 1.5708 +primID: 4 +startangle_c: 4 +endpose_c: 2 6 4 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0222 0.0667 1.5708 +0.0444 0.1333 1.5708 +0.0667 0.2000 1.5708 +0.0889 0.2667 1.5708 +0.1111 0.3333 1.5708 +0.1333 0.4000 1.5708 +0.1556 0.4667 1.5708 +0.1778 0.5333 1.5708 +0.2000 0.6000 1.5708 +primID: 5 +startangle_c: 4 +endpose_c: -3 2 4 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.5708 +-0.0333 0.0222 1.5708 +-0.0667 0.0444 1.5708 +-0.1000 0.0667 1.5708 +-0.1333 0.0889 1.5708 +-0.1667 0.1111 1.5708 +-0.2000 0.1333 1.5708 +-0.2333 0.1556 1.5708 +-0.2667 0.1778 1.5708 +-0.3000 0.2000 1.5708 +primID: 6 +startangle_c: 4 +endpose_c: 3 2 4 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0333 0.0222 1.5708 +0.0667 0.0444 1.5708 +0.1000 0.0667 1.5708 +0.1333 0.0889 1.5708 +0.1667 0.1111 1.5708 +0.2000 0.1333 1.5708 +0.2333 0.1556 1.5708 +0.2667 0.1778 1.5708 +0.3000 0.2000 1.5708 +primID: 7 +startangle_c: 4 +endpose_c: 0 -5 4 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 -0.0556 1.5708 +0.0000 -0.1111 1.5708 +0.0000 -0.1667 1.5708 +0.0000 -0.2222 1.5708 +0.0000 -0.2778 1.5708 +0.0000 -0.3333 1.5708 +0.0000 -0.3889 1.5708 +0.0000 -0.4444 1.5708 +0.0000 -0.5000 1.5708 +primID: 8 +startangle_c: 4 +endpose_c: -2 6 5 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.5708 +-0.0222 0.0667 1.6144 +-0.0444 0.1333 1.6581 +-0.0667 0.2000 1.7017 +-0.0889 0.2667 1.7453 +-0.1111 0.3333 1.7890 +-0.1333 0.4000 1.8326 +-0.1556 0.4667 1.8762 +-0.1778 0.5333 1.9199 +-0.2000 0.6000 1.9635 +primID: 9 +startangle_c: 4 +endpose_c: 2 6 3 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0222 0.0667 1.5272 +0.0444 0.1333 1.4835 +0.0667 0.2000 1.4399 +0.0889 0.2667 1.3963 +0.1111 0.3333 1.3526 +0.1333 0.4000 1.3090 +0.1556 0.4667 1.2654 +0.1778 0.5333 1.2217 +0.2000 0.6000 1.1781 +primID: 10 +startangle_c: 4 +endpose_c: -3 4 6 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.5708 +-0.0333 0.0444 1.6581 +-0.0667 0.0889 1.7453 +-0.1000 0.1333 1.8326 +-0.1333 0.1778 1.9199 +-0.1667 0.2222 2.0071 +-0.2000 0.2667 2.0944 +-0.2333 0.3111 2.1817 +-0.2667 0.3556 2.2689 +-0.3000 0.4000 2.3562 +primID: 11 +startangle_c: 4 +endpose_c: 3 4 2 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0333 0.0444 1.4835 +0.0667 0.0889 1.3963 +0.1000 0.1333 1.3090 +0.1333 0.1778 1.2217 +0.1667 0.2222 1.1345 +0.2000 0.2667 1.0472 +0.2333 0.3111 0.9599 +0.2667 0.3556 0.8727 +0.3000 0.4000 0.7854 +primID: 12 +startangle_c: 4 +endpose_c: 0 0 5 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0000 1.6144 +0.0000 0.0000 1.6581 +0.0000 0.0000 1.7017 +0.0000 0.0000 1.7453 +0.0000 0.0000 1.7890 +0.0000 0.0000 1.8326 +0.0000 0.0000 1.8762 +0.0000 0.0000 1.9199 +0.0000 0.0000 1.9635 +primID: 13 +startangle_c: 4 +endpose_c: 0 0 3 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0000 1.5272 +0.0000 0.0000 1.4835 +0.0000 0.0000 1.4399 +0.0000 0.0000 1.3963 +0.0000 0.0000 1.3526 +0.0000 0.0000 1.3090 +0.0000 0.0000 1.2654 +0.0000 0.0000 1.2217 +0.0000 0.0000 1.1781 +primID: 14 +startangle_c: 4 +endpose_c: 0 0 7 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0000 1.7017 +0.0000 0.0000 1.8326 +0.0000 0.0000 1.9635 +0.0000 0.0000 2.0944 +0.0000 0.0000 2.2253 +0.0000 0.0000 2.3562 +0.0000 0.0000 2.4871 +0.0000 0.0000 2.6180 +0.0000 0.0000 2.7489 +primID: 15 +startangle_c: 4 +endpose_c: 0 0 1 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0000 1.4399 +0.0000 0.0000 1.3090 +0.0000 0.0000 1.1781 +0.0000 0.0000 1.0472 +0.0000 0.0000 0.9163 +0.0000 0.0000 0.7854 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.5236 +0.0000 0.0000 0.3927 +primID: 0 +startangle_c: 5 +endpose_c: -1 2 5 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0111 0.0222 1.9635 +-0.0222 0.0444 1.9635 +-0.0333 0.0667 1.9635 +-0.0444 0.0889 1.9635 +-0.0556 0.1111 1.9635 +-0.0667 0.1333 1.9635 +-0.0778 0.1556 1.9635 +-0.0889 0.1778 1.9635 +-0.1000 0.2000 1.9635 +primID: 1 +startangle_c: 5 +endpose_c: -2 4 5 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0222 0.0444 1.9635 +-0.0444 0.0889 1.9635 +-0.0667 0.1333 1.9635 +-0.0889 0.1778 1.9635 +-0.1111 0.2222 1.9635 +-0.1333 0.2667 1.9635 +-0.1556 0.3111 1.9635 +-0.1778 0.3556 1.9635 +-0.2000 0.4000 1.9635 +primID: 2 +startangle_c: 5 +endpose_c: -3 6 5 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0333 0.0667 1.9635 +-0.0667 0.1333 1.9635 +-0.1000 0.2000 1.9635 +-0.1333 0.2667 1.9635 +-0.1667 0.3333 1.9635 +-0.2000 0.4000 1.9635 +-0.2333 0.4667 1.9635 +-0.2667 0.5333 1.9635 +-0.3000 0.6000 1.9635 +primID: 3 +startangle_c: 5 +endpose_c: -4 4 5 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0444 0.0444 1.9635 +-0.0889 0.0889 1.9635 +-0.1333 0.1333 1.9635 +-0.1778 0.1778 1.9635 +-0.2222 0.2222 1.9635 +-0.2667 0.2667 1.9635 +-0.3111 0.3111 1.9635 +-0.3556 0.3556 1.9635 +-0.4000 0.4000 1.9635 +primID: 4 +startangle_c: 5 +endpose_c: -2 6 5 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0222 0.0667 1.9635 +-0.0444 0.1333 1.9635 +-0.0667 0.2000 1.9635 +-0.0889 0.2667 1.9635 +-0.1111 0.3333 1.9635 +-0.1333 0.4000 1.9635 +-0.1556 0.4667 1.9635 +-0.1778 0.5333 1.9635 +-0.2000 0.6000 1.9635 +primID: 5 +startangle_c: 5 +endpose_c: -3 0 5 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0333 0.0000 1.9635 +-0.0667 0.0000 1.9635 +-0.1000 0.0000 1.9635 +-0.1333 0.0000 1.9635 +-0.1667 0.0000 1.9635 +-0.2000 0.0000 1.9635 +-0.2333 0.0000 1.9635 +-0.2667 0.0000 1.9635 +-0.3000 0.0000 1.9635 +primID: 6 +startangle_c: 5 +endpose_c: 1 4 5 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0111 0.0444 1.9635 +0.0222 0.0889 1.9635 +0.0333 0.1333 1.9635 +0.0444 0.1778 1.9635 +0.0556 0.2222 1.9635 +0.0667 0.2667 1.9635 +0.0778 0.3111 1.9635 +0.0889 0.3556 1.9635 +0.1000 0.4000 1.9635 +primID: 7 +startangle_c: 5 +endpose_c: 2 -4 5 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0222 -0.0444 1.9635 +0.0444 -0.0889 1.9635 +0.0667 -0.1333 1.9635 +0.0889 -0.1778 1.9635 +0.1111 -0.2222 1.9635 +0.1333 -0.2667 1.9635 +0.1556 -0.3111 1.9635 +0.1778 -0.3556 1.9635 +0.2000 -0.4000 1.9635 +primID: 8 +startangle_c: 5 +endpose_c: -4 4 6 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0444 0.0444 2.0071 +-0.0889 0.0889 2.0508 +-0.1333 0.1333 2.0944 +-0.1778 0.1778 2.1380 +-0.2222 0.2222 2.1817 +-0.2667 0.2667 2.2253 +-0.3111 0.3111 2.2689 +-0.3556 0.3556 2.3126 +-0.4000 0.4000 2.3562 +primID: 9 +startangle_c: 5 +endpose_c: -2 6 4 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0222 0.0667 1.9199 +-0.0444 0.1333 1.8762 +-0.0667 0.2000 1.8326 +-0.0889 0.2667 1.7890 +-0.1111 0.3333 1.7453 +-0.1333 0.4000 1.7017 +-0.1556 0.4667 1.6581 +-0.1778 0.5333 1.6144 +-0.2000 0.6000 1.5708 +primID: 10 +startangle_c: 5 +endpose_c: -4 2 7 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0444 0.0222 2.0508 +-0.0889 0.0444 2.1380 +-0.1333 0.0667 2.2253 +-0.1778 0.0889 2.3126 +-0.2222 0.1111 2.3998 +-0.2667 0.1333 2.4871 +-0.3111 0.1556 2.5744 +-0.3556 0.1778 2.6616 +-0.4000 0.2000 2.7489 +primID: 11 +startangle_c: 5 +endpose_c: 0 6 3 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0000 0.0667 1.8762 +0.0000 0.1333 1.7890 +0.0000 0.2000 1.7017 +0.0000 0.2667 1.6144 +0.0000 0.3333 1.5272 +0.0000 0.4000 1.4399 +0.0000 0.4667 1.3526 +0.0000 0.5333 1.2654 +0.0000 0.6000 1.1781 +primID: 12 +startangle_c: 5 +endpose_c: 0 0 6 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0000 0.0000 2.0071 +0.0000 0.0000 2.0508 +0.0000 0.0000 2.0944 +0.0000 0.0000 2.1380 +0.0000 0.0000 2.1817 +0.0000 0.0000 2.2253 +0.0000 0.0000 2.2689 +0.0000 0.0000 2.3126 +0.0000 0.0000 2.3562 +primID: 13 +startangle_c: 5 +endpose_c: 0 0 4 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0000 0.0000 1.9199 +0.0000 0.0000 1.8762 +0.0000 0.0000 1.8326 +0.0000 0.0000 1.7890 +0.0000 0.0000 1.7453 +0.0000 0.0000 1.7017 +0.0000 0.0000 1.6581 +0.0000 0.0000 1.6144 +0.0000 0.0000 1.5708 +primID: 14 +startangle_c: 5 +endpose_c: 0 0 8 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0000 0.0000 2.0944 +0.0000 0.0000 2.2253 +0.0000 0.0000 2.3562 +0.0000 0.0000 2.4871 +0.0000 0.0000 2.6180 +0.0000 0.0000 2.7489 +0.0000 0.0000 2.8798 +0.0000 0.0000 3.0107 +0.0000 0.0000 3.1416 +primID: 15 +startangle_c: 5 +endpose_c: 0 0 2 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0000 0.0000 1.8326 +0.0000 0.0000 1.7017 +0.0000 0.0000 1.5708 +0.0000 0.0000 1.4399 +0.0000 0.0000 1.3090 +0.0000 0.0000 1.1781 +0.0000 0.0000 1.0472 +0.0000 0.0000 0.9163 +0.0000 0.0000 0.7854 +primID: 0 +startangle_c: 6 +endpose_c: -1 1 6 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0111 0.0111 2.3562 +-0.0222 0.0222 2.3562 +-0.0333 0.0333 2.3562 +-0.0444 0.0444 2.3562 +-0.0556 0.0556 2.3562 +-0.0667 0.0667 2.3562 +-0.0778 0.0778 2.3562 +-0.0889 0.0889 2.3562 +-0.1000 0.1000 2.3562 +primID: 1 +startangle_c: 6 +endpose_c: -3 3 6 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0333 0.0333 2.3562 +-0.0667 0.0667 2.3562 +-0.1000 0.1000 2.3562 +-0.1333 0.1333 2.3562 +-0.1667 0.1667 2.3562 +-0.2000 0.2000 2.3562 +-0.2333 0.2333 2.3562 +-0.2667 0.2667 2.3562 +-0.3000 0.3000 2.3562 +primID: 2 +startangle_c: 6 +endpose_c: -6 6 6 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0667 0.0667 2.3562 +-0.1333 0.1333 2.3562 +-0.2000 0.2000 2.3562 +-0.2667 0.2667 2.3562 +-0.3333 0.3333 2.3562 +-0.4000 0.4000 2.3562 +-0.4667 0.4667 2.3562 +-0.5333 0.5333 2.3562 +-0.6000 0.6000 2.3562 +primID: 3 +startangle_c: 6 +endpose_c: -6 2 6 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0667 0.0222 2.3562 +-0.1333 0.0444 2.3562 +-0.2000 0.0667 2.3562 +-0.2667 0.0889 2.3562 +-0.3333 0.1111 2.3562 +-0.4000 0.1333 2.3562 +-0.4667 0.1556 2.3562 +-0.5333 0.1778 2.3562 +-0.6000 0.2000 2.3562 +primID: 4 +startangle_c: 6 +endpose_c: -2 6 6 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0222 0.0667 2.3562 +-0.0444 0.1333 2.3562 +-0.0667 0.2000 2.3562 +-0.0889 0.2667 2.3562 +-0.1111 0.3333 2.3562 +-0.1333 0.4000 2.3562 +-0.1556 0.4667 2.3562 +-0.1778 0.5333 2.3562 +-0.2000 0.6000 2.3562 +primID: 5 +startangle_c: 6 +endpose_c: -4 0 6 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0444 0.0000 2.3562 +-0.0889 0.0000 2.3562 +-0.1333 0.0000 2.3562 +-0.1778 0.0000 2.3562 +-0.2222 0.0000 2.3562 +-0.2667 0.0000 2.3562 +-0.3111 0.0000 2.3562 +-0.3556 0.0000 2.3562 +-0.4000 0.0000 2.3562 +primID: 6 +startangle_c: 6 +endpose_c: 0 4 6 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0000 0.0444 2.3562 +0.0000 0.0889 2.3562 +0.0000 0.1333 2.3562 +0.0000 0.1778 2.3562 +0.0000 0.2222 2.3562 +0.0000 0.2667 2.3562 +0.0000 0.3111 2.3562 +0.0000 0.3556 2.3562 +0.0000 0.4000 2.3562 +primID: 7 +startangle_c: 6 +endpose_c: 4 -4 6 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0444 -0.0444 2.3562 +0.0889 -0.0889 2.3562 +0.1333 -0.1333 2.3562 +0.1778 -0.1778 2.3562 +0.2222 -0.2222 2.3562 +0.2667 -0.2667 2.3562 +0.3111 -0.3111 2.3562 +0.3556 -0.3556 2.3562 +0.4000 -0.4000 2.3562 +primID: 8 +startangle_c: 6 +endpose_c: -6 2 7 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0667 0.0222 2.3998 +-0.1333 0.0444 2.4435 +-0.2000 0.0667 2.4871 +-0.2667 0.0889 2.5307 +-0.3333 0.1111 2.5744 +-0.4000 0.1333 2.6180 +-0.4667 0.1556 2.6616 +-0.5333 0.1778 2.7053 +-0.6000 0.2000 2.7489 +primID: 9 +startangle_c: 6 +endpose_c: -2 6 5 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0222 0.0667 2.3126 +-0.0444 0.1333 2.2689 +-0.0667 0.2000 2.2253 +-0.0889 0.2667 2.1817 +-0.1111 0.3333 2.1380 +-0.1333 0.4000 2.0944 +-0.1556 0.4667 2.0508 +-0.1778 0.5333 2.0071 +-0.2000 0.6000 1.9635 +primID: 10 +startangle_c: 6 +endpose_c: -5 1 8 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0556 0.0111 2.4435 +-0.1111 0.0222 2.5307 +-0.1667 0.0333 2.6180 +-0.2222 0.0444 2.7053 +-0.2778 0.0556 2.7925 +-0.3333 0.0667 2.8798 +-0.3889 0.0778 2.9671 +-0.4444 0.0889 3.0543 +-0.5000 0.1000 3.1416 +primID: 11 +startangle_c: 6 +endpose_c: -1 5 4 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0111 0.0556 2.2689 +-0.0222 0.1111 2.1817 +-0.0333 0.1667 2.0944 +-0.0444 0.2222 2.0071 +-0.0556 0.2778 1.9199 +-0.0667 0.3333 1.8326 +-0.0778 0.3889 1.7453 +-0.0889 0.4444 1.6581 +-0.1000 0.5000 1.5708 +primID: 12 +startangle_c: 6 +endpose_c: 0 0 7 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0000 0.0000 2.3998 +0.0000 0.0000 2.4435 +0.0000 0.0000 2.4871 +0.0000 0.0000 2.5307 +0.0000 0.0000 2.5744 +0.0000 0.0000 2.6180 +0.0000 0.0000 2.6616 +0.0000 0.0000 2.7053 +0.0000 0.0000 2.7489 +primID: 13 +startangle_c: 6 +endpose_c: 0 0 5 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0000 0.0000 2.3126 +0.0000 0.0000 2.2689 +0.0000 0.0000 2.2253 +0.0000 0.0000 2.1817 +0.0000 0.0000 2.1380 +0.0000 0.0000 2.0944 +0.0000 0.0000 2.0508 +0.0000 0.0000 2.0071 +0.0000 0.0000 1.9635 +primID: 14 +startangle_c: 6 +endpose_c: 0 0 9 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0000 0.0000 2.4871 +0.0000 0.0000 2.6180 +0.0000 0.0000 2.7489 +0.0000 0.0000 2.8798 +0.0000 0.0000 3.0107 +0.0000 0.0000 3.1416 +0.0000 0.0000 3.2725 +0.0000 0.0000 3.4034 +0.0000 0.0000 3.5343 +primID: 15 +startangle_c: 6 +endpose_c: 0 0 3 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0000 0.0000 2.2253 +0.0000 0.0000 2.0944 +0.0000 0.0000 1.9635 +0.0000 0.0000 1.8326 +0.0000 0.0000 1.7017 +0.0000 0.0000 1.5708 +0.0000 0.0000 1.4399 +0.0000 0.0000 1.3090 +0.0000 0.0000 1.1781 +primID: 0 +startangle_c: 7 +endpose_c: -2 1 7 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0222 0.0111 2.7489 +-0.0444 0.0222 2.7489 +-0.0667 0.0333 2.7489 +-0.0889 0.0444 2.7489 +-0.1111 0.0556 2.7489 +-0.1333 0.0667 2.7489 +-0.1556 0.0778 2.7489 +-0.1778 0.0889 2.7489 +-0.2000 0.1000 2.7489 +primID: 1 +startangle_c: 7 +endpose_c: -4 2 7 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0444 0.0222 2.7489 +-0.0889 0.0444 2.7489 +-0.1333 0.0667 2.7489 +-0.1778 0.0889 2.7489 +-0.2222 0.1111 2.7489 +-0.2667 0.1333 2.7489 +-0.3111 0.1556 2.7489 +-0.3556 0.1778 2.7489 +-0.4000 0.2000 2.7489 +primID: 2 +startangle_c: 7 +endpose_c: -6 3 7 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0667 0.0333 2.7489 +-0.1333 0.0667 2.7489 +-0.2000 0.1000 2.7489 +-0.2667 0.1333 2.7489 +-0.3333 0.1667 2.7489 +-0.4000 0.2000 2.7489 +-0.4667 0.2333 2.7489 +-0.5333 0.2667 2.7489 +-0.6000 0.3000 2.7489 +primID: 3 +startangle_c: 7 +endpose_c: -4 4 7 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0444 0.0444 2.7489 +-0.0889 0.0889 2.7489 +-0.1333 0.1333 2.7489 +-0.1778 0.1778 2.7489 +-0.2222 0.2222 2.7489 +-0.2667 0.2667 2.7489 +-0.3111 0.3111 2.7489 +-0.3556 0.3556 2.7489 +-0.4000 0.4000 2.7489 +primID: 4 +startangle_c: 7 +endpose_c: -6 2 7 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0667 0.0222 2.7489 +-0.1333 0.0444 2.7489 +-0.2000 0.0667 2.7489 +-0.2667 0.0889 2.7489 +-0.3333 0.1111 2.7489 +-0.4000 0.1333 2.7489 +-0.4667 0.1556 2.7489 +-0.5333 0.1778 2.7489 +-0.6000 0.2000 2.7489 +primID: 5 +startangle_c: 7 +endpose_c: 0 3 7 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0000 0.0333 2.7489 +0.0000 0.0667 2.7489 +0.0000 0.1000 2.7489 +0.0000 0.1333 2.7489 +0.0000 0.1667 2.7489 +0.0000 0.2000 2.7489 +0.0000 0.2333 2.7489 +0.0000 0.2667 2.7489 +0.0000 0.3000 2.7489 +primID: 6 +startangle_c: 7 +endpose_c: -4 -1 7 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0444 -0.0111 2.7489 +-0.0889 -0.0222 2.7489 +-0.1333 -0.0333 2.7489 +-0.1778 -0.0444 2.7489 +-0.2222 -0.0556 2.7489 +-0.2667 -0.0667 2.7489 +-0.3111 -0.0778 2.7489 +-0.3556 -0.0889 2.7489 +-0.4000 -0.1000 2.7489 +primID: 7 +startangle_c: 7 +endpose_c: 4 -2 7 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0444 -0.0222 2.7489 +0.0889 -0.0444 2.7489 +0.1333 -0.0667 2.7489 +0.1778 -0.0889 2.7489 +0.2222 -0.1111 2.7489 +0.2667 -0.1333 2.7489 +0.3111 -0.1556 2.7489 +0.3556 -0.1778 2.7489 +0.4000 -0.2000 2.7489 +primID: 8 +startangle_c: 7 +endpose_c: -4 4 6 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0444 0.0444 2.7053 +-0.0889 0.0889 2.6616 +-0.1333 0.1333 2.6180 +-0.1778 0.1778 2.5744 +-0.2222 0.2222 2.5307 +-0.2667 0.2667 2.4871 +-0.3111 0.3111 2.4435 +-0.3556 0.3556 2.3998 +-0.4000 0.4000 2.3562 +primID: 9 +startangle_c: 7 +endpose_c: -6 2 8 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0667 0.0222 2.7925 +-0.1333 0.0444 2.8362 +-0.2000 0.0667 2.8798 +-0.2667 0.0889 2.9234 +-0.3333 0.1111 2.9671 +-0.4000 0.1333 3.0107 +-0.4667 0.1556 3.0543 +-0.5333 0.1778 3.0980 +-0.6000 0.2000 3.1416 +primID: 10 +startangle_c: 7 +endpose_c: -2 4 5 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0222 0.0444 2.6616 +-0.0444 0.0889 2.5744 +-0.0667 0.1333 2.4871 +-0.0889 0.1778 2.3998 +-0.1111 0.2222 2.3126 +-0.1333 0.2667 2.2253 +-0.1556 0.3111 2.1380 +-0.1778 0.3556 2.0508 +-0.2000 0.4000 1.9635 +primID: 11 +startangle_c: 7 +endpose_c: -6 0 9 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0667 0.0000 2.8362 +-0.1333 0.0000 2.9234 +-0.2000 0.0000 3.0107 +-0.2667 0.0000 3.0980 +-0.3333 0.0000 3.1852 +-0.4000 0.0000 3.2725 +-0.4667 0.0000 3.3598 +-0.5333 0.0000 3.4470 +-0.6000 0.0000 3.5343 +primID: 12 +startangle_c: 7 +endpose_c: 0 0 6 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0000 0.0000 2.7053 +0.0000 0.0000 2.6616 +0.0000 0.0000 2.6180 +0.0000 0.0000 2.5744 +0.0000 0.0000 2.5307 +0.0000 0.0000 2.4871 +0.0000 0.0000 2.4435 +0.0000 0.0000 2.3998 +0.0000 0.0000 2.3562 +primID: 13 +startangle_c: 7 +endpose_c: 0 0 8 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0000 0.0000 2.7925 +0.0000 0.0000 2.8362 +0.0000 0.0000 2.8798 +0.0000 0.0000 2.9234 +0.0000 0.0000 2.9671 +0.0000 0.0000 3.0107 +0.0000 0.0000 3.0543 +0.0000 0.0000 3.0980 +0.0000 0.0000 3.1416 +primID: 14 +startangle_c: 7 +endpose_c: 0 0 4 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0000 0.0000 2.6180 +0.0000 0.0000 2.4871 +0.0000 0.0000 2.3562 +0.0000 0.0000 2.2253 +0.0000 0.0000 2.0944 +0.0000 0.0000 1.9635 +0.0000 0.0000 1.8326 +0.0000 0.0000 1.7017 +0.0000 0.0000 1.5708 +primID: 15 +startangle_c: 7 +endpose_c: 0 0 10 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0000 0.0000 2.8798 +0.0000 0.0000 3.0107 +0.0000 0.0000 3.1416 +0.0000 0.0000 3.2725 +0.0000 0.0000 3.4034 +0.0000 0.0000 3.5343 +0.0000 0.0000 3.6652 +0.0000 0.0000 3.7961 +0.0000 0.0000 3.9270 +primID: 0 +startangle_c: 8 +endpose_c: -1 0 8 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0111 0.0000 3.1416 +-0.0222 0.0000 3.1416 +-0.0333 0.0000 3.1416 +-0.0444 0.0000 3.1416 +-0.0556 0.0000 3.1416 +-0.0667 0.0000 3.1416 +-0.0778 0.0000 3.1416 +-0.0889 0.0000 3.1416 +-0.1000 0.0000 3.1416 +primID: 1 +startangle_c: 8 +endpose_c: -4 0 8 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0444 0.0000 3.1416 +-0.0889 0.0000 3.1416 +-0.1333 0.0000 3.1416 +-0.1778 0.0000 3.1416 +-0.2222 0.0000 3.1416 +-0.2667 0.0000 3.1416 +-0.3111 0.0000 3.1416 +-0.3556 0.0000 3.1416 +-0.4000 0.0000 3.1416 +primID: 2 +startangle_c: 8 +endpose_c: -8 0 8 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0889 0.0000 3.1416 +-0.1778 0.0000 3.1416 +-0.2667 0.0000 3.1416 +-0.3556 0.0000 3.1416 +-0.4444 0.0000 3.1416 +-0.5333 0.0000 3.1416 +-0.6222 0.0000 3.1416 +-0.7111 0.0000 3.1416 +-0.8000 0.0000 3.1416 +primID: 3 +startangle_c: 8 +endpose_c: -6 -2 8 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0667 -0.0222 3.1416 +-0.1333 -0.0444 3.1416 +-0.2000 -0.0667 3.1416 +-0.2667 -0.0889 3.1416 +-0.3333 -0.1111 3.1416 +-0.4000 -0.1333 3.1416 +-0.4667 -0.1556 3.1416 +-0.5333 -0.1778 3.1416 +-0.6000 -0.2000 3.1416 +primID: 4 +startangle_c: 8 +endpose_c: -6 2 8 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0667 0.0222 3.1416 +-0.1333 0.0444 3.1416 +-0.2000 0.0667 3.1416 +-0.2667 0.0889 3.1416 +-0.3333 0.1111 3.1416 +-0.4000 0.1333 3.1416 +-0.4667 0.1556 3.1416 +-0.5333 0.1778 3.1416 +-0.6000 0.2000 3.1416 +primID: 5 +startangle_c: 8 +endpose_c: -2 -3 8 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0222 -0.0333 3.1416 +-0.0444 -0.0667 3.1416 +-0.0667 -0.1000 3.1416 +-0.0889 -0.1333 3.1416 +-0.1111 -0.1667 3.1416 +-0.1333 -0.2000 3.1416 +-0.1556 -0.2333 3.1416 +-0.1778 -0.2667 3.1416 +-0.2000 -0.3000 3.1416 +primID: 6 +startangle_c: 8 +endpose_c: -2 3 8 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0222 0.0333 3.1416 +-0.0444 0.0667 3.1416 +-0.0667 0.1000 3.1416 +-0.0889 0.1333 3.1416 +-0.1111 0.1667 3.1416 +-0.1333 0.2000 3.1416 +-0.1556 0.2333 3.1416 +-0.1778 0.2667 3.1416 +-0.2000 0.3000 3.1416 +primID: 7 +startangle_c: 8 +endpose_c: 5 0 8 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0556 0.0000 3.1416 +0.1111 0.0000 3.1416 +0.1667 0.0000 3.1416 +0.2222 0.0000 3.1416 +0.2778 0.0000 3.1416 +0.3333 0.0000 3.1416 +0.3889 0.0000 3.1416 +0.4444 0.0000 3.1416 +0.5000 0.0000 3.1416 +primID: 8 +startangle_c: 8 +endpose_c: -6 -2 9 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0667 -0.0222 3.1852 +-0.1333 -0.0444 3.2289 +-0.2000 -0.0667 3.2725 +-0.2667 -0.0889 3.3161 +-0.3333 -0.1111 3.3598 +-0.4000 -0.1333 3.4034 +-0.4667 -0.1556 3.4470 +-0.5333 -0.1778 3.4907 +-0.6000 -0.2000 3.5343 +primID: 9 +startangle_c: 8 +endpose_c: -6 2 7 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0667 0.0222 3.0980 +-0.1333 0.0444 3.0543 +-0.2000 0.0667 3.0107 +-0.2667 0.0889 2.9671 +-0.3333 0.1111 2.9234 +-0.4000 0.1333 2.8798 +-0.4667 0.1556 2.8362 +-0.5333 0.1778 2.7925 +-0.6000 0.2000 2.7489 +primID: 10 +startangle_c: 8 +endpose_c: -4 -3 10 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0444 -0.0333 3.2289 +-0.0889 -0.0667 3.3161 +-0.1333 -0.1000 3.4034 +-0.1778 -0.1333 3.4907 +-0.2222 -0.1667 3.5779 +-0.2667 -0.2000 3.6652 +-0.3111 -0.2333 3.7525 +-0.3556 -0.2667 3.8397 +-0.4000 -0.3000 3.9270 +primID: 11 +startangle_c: 8 +endpose_c: -4 3 6 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0444 0.0333 3.0543 +-0.0889 0.0667 2.9671 +-0.1333 0.1000 2.8798 +-0.1778 0.1333 2.7925 +-0.2222 0.1667 2.7053 +-0.2667 0.2000 2.6180 +-0.3111 0.2333 2.5307 +-0.3556 0.2667 2.4435 +-0.4000 0.3000 2.3562 +primID: 12 +startangle_c: 8 +endpose_c: 0 0 9 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0000 0.0000 3.1852 +0.0000 0.0000 3.2289 +0.0000 0.0000 3.2725 +0.0000 0.0000 3.3161 +0.0000 0.0000 3.3598 +0.0000 0.0000 3.4034 +0.0000 0.0000 3.4470 +0.0000 0.0000 3.4907 +0.0000 0.0000 3.5343 +primID: 13 +startangle_c: 8 +endpose_c: 0 0 7 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0000 0.0000 3.0980 +0.0000 0.0000 3.0543 +0.0000 0.0000 3.0107 +0.0000 0.0000 2.9671 +0.0000 0.0000 2.9234 +0.0000 0.0000 2.8798 +0.0000 0.0000 2.8362 +0.0000 0.0000 2.7925 +0.0000 0.0000 2.7489 +primID: 14 +startangle_c: 8 +endpose_c: 0 0 11 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0000 0.0000 3.2725 +0.0000 0.0000 3.4034 +0.0000 0.0000 3.5343 +0.0000 0.0000 3.6652 +0.0000 0.0000 3.7961 +0.0000 0.0000 3.9270 +0.0000 0.0000 4.0579 +0.0000 0.0000 4.1888 +0.0000 0.0000 4.3197 +primID: 15 +startangle_c: 8 +endpose_c: 0 0 5 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0000 0.0000 3.0107 +0.0000 0.0000 2.8798 +0.0000 0.0000 2.7489 +0.0000 0.0000 2.6180 +0.0000 0.0000 2.4871 +0.0000 0.0000 2.3562 +0.0000 0.0000 2.2253 +0.0000 0.0000 2.0944 +0.0000 0.0000 1.9635 +primID: 0 +startangle_c: 9 +endpose_c: -2 -1 9 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0222 -0.0111 3.5343 +-0.0444 -0.0222 3.5343 +-0.0667 -0.0333 3.5343 +-0.0889 -0.0444 3.5343 +-0.1111 -0.0556 3.5343 +-0.1333 -0.0667 3.5343 +-0.1556 -0.0778 3.5343 +-0.1778 -0.0889 3.5343 +-0.2000 -0.1000 3.5343 +primID: 1 +startangle_c: 9 +endpose_c: -4 -2 9 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0444 -0.0222 3.5343 +-0.0889 -0.0444 3.5343 +-0.1333 -0.0667 3.5343 +-0.1778 -0.0889 3.5343 +-0.2222 -0.1111 3.5343 +-0.2667 -0.1333 3.5343 +-0.3111 -0.1556 3.5343 +-0.3556 -0.1778 3.5343 +-0.4000 -0.2000 3.5343 +primID: 2 +startangle_c: 9 +endpose_c: -6 -3 9 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0667 -0.0333 3.5343 +-0.1333 -0.0667 3.5343 +-0.2000 -0.1000 3.5343 +-0.2667 -0.1333 3.5343 +-0.3333 -0.1667 3.5343 +-0.4000 -0.2000 3.5343 +-0.4667 -0.2333 3.5343 +-0.5333 -0.2667 3.5343 +-0.6000 -0.3000 3.5343 +primID: 3 +startangle_c: 9 +endpose_c: -4 -4 9 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0444 -0.0444 3.5343 +-0.0889 -0.0889 3.5343 +-0.1333 -0.1333 3.5343 +-0.1778 -0.1778 3.5343 +-0.2222 -0.2222 3.5343 +-0.2667 -0.2667 3.5343 +-0.3111 -0.3111 3.5343 +-0.3556 -0.3556 3.5343 +-0.4000 -0.4000 3.5343 +primID: 4 +startangle_c: 9 +endpose_c: -6 -2 9 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0667 -0.0222 3.5343 +-0.1333 -0.0444 3.5343 +-0.2000 -0.0667 3.5343 +-0.2667 -0.0889 3.5343 +-0.3333 -0.1111 3.5343 +-0.4000 -0.1333 3.5343 +-0.4667 -0.1556 3.5343 +-0.5333 -0.1778 3.5343 +-0.6000 -0.2000 3.5343 +primID: 5 +startangle_c: 9 +endpose_c: 0 -3 9 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0000 -0.0333 3.5343 +0.0000 -0.0667 3.5343 +0.0000 -0.1000 3.5343 +0.0000 -0.1333 3.5343 +0.0000 -0.1667 3.5343 +0.0000 -0.2000 3.5343 +0.0000 -0.2333 3.5343 +0.0000 -0.2667 3.5343 +0.0000 -0.3000 3.5343 +primID: 6 +startangle_c: 9 +endpose_c: -4 1 9 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0444 0.0111 3.5343 +-0.0889 0.0222 3.5343 +-0.1333 0.0333 3.5343 +-0.1778 0.0444 3.5343 +-0.2222 0.0556 3.5343 +-0.2667 0.0667 3.5343 +-0.3111 0.0778 3.5343 +-0.3556 0.0889 3.5343 +-0.4000 0.1000 3.5343 +primID: 7 +startangle_c: 9 +endpose_c: 4 2 9 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0444 0.0222 3.5343 +0.0889 0.0444 3.5343 +0.1333 0.0667 3.5343 +0.1778 0.0889 3.5343 +0.2222 0.1111 3.5343 +0.2667 0.1333 3.5343 +0.3111 0.1556 3.5343 +0.3556 0.1778 3.5343 +0.4000 0.2000 3.5343 +primID: 8 +startangle_c: 9 +endpose_c: -4 -4 10 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0444 -0.0444 3.5779 +-0.0889 -0.0889 3.6216 +-0.1333 -0.1333 3.6652 +-0.1778 -0.1778 3.7088 +-0.2222 -0.2222 3.7525 +-0.2667 -0.2667 3.7961 +-0.3111 -0.3111 3.8397 +-0.3556 -0.3556 3.8834 +-0.4000 -0.4000 3.9270 +primID: 9 +startangle_c: 9 +endpose_c: -6 -2 8 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0667 -0.0222 3.4907 +-0.1333 -0.0444 3.4470 +-0.2000 -0.0667 3.4034 +-0.2667 -0.0889 3.3598 +-0.3333 -0.1111 3.3161 +-0.4000 -0.1333 3.2725 +-0.4667 -0.1556 3.2289 +-0.5333 -0.1778 3.1852 +-0.6000 -0.2000 3.1416 +primID: 10 +startangle_c: 9 +endpose_c: -2 -4 11 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0222 -0.0444 3.6216 +-0.0444 -0.0889 3.7088 +-0.0667 -0.1333 3.7961 +-0.0889 -0.1778 3.8834 +-0.1111 -0.2222 3.9706 +-0.1333 -0.2667 4.0579 +-0.1556 -0.3111 4.1452 +-0.1778 -0.3556 4.2324 +-0.2000 -0.4000 4.3197 +primID: 11 +startangle_c: 9 +endpose_c: -6 0 7 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0667 0.0000 3.4470 +-0.1333 0.0000 3.3598 +-0.2000 0.0000 3.2725 +-0.2667 0.0000 3.1852 +-0.3333 0.0000 3.0980 +-0.4000 0.0000 3.0107 +-0.4667 0.0000 2.9234 +-0.5333 0.0000 2.8362 +-0.6000 0.0000 2.7489 +primID: 12 +startangle_c: 9 +endpose_c: 0 0 10 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0000 0.0000 3.5779 +0.0000 0.0000 3.6216 +0.0000 0.0000 3.6652 +0.0000 0.0000 3.7088 +0.0000 0.0000 3.7525 +0.0000 0.0000 3.7961 +0.0000 0.0000 3.8397 +0.0000 0.0000 3.8834 +0.0000 0.0000 3.9270 +primID: 13 +startangle_c: 9 +endpose_c: 0 0 8 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0000 0.0000 3.4907 +0.0000 0.0000 3.4470 +0.0000 0.0000 3.4034 +0.0000 0.0000 3.3598 +0.0000 0.0000 3.3161 +0.0000 0.0000 3.2725 +0.0000 0.0000 3.2289 +0.0000 0.0000 3.1852 +0.0000 0.0000 3.1416 +primID: 14 +startangle_c: 9 +endpose_c: 0 0 12 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0000 0.0000 3.6652 +0.0000 0.0000 3.7961 +0.0000 0.0000 3.9270 +0.0000 0.0000 4.0579 +0.0000 0.0000 4.1888 +0.0000 0.0000 4.3197 +0.0000 0.0000 4.4506 +0.0000 0.0000 4.5815 +0.0000 0.0000 4.7124 +primID: 15 +startangle_c: 9 +endpose_c: 0 0 6 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0000 0.0000 3.4034 +0.0000 0.0000 3.2725 +0.0000 0.0000 3.1416 +0.0000 0.0000 3.0107 +0.0000 0.0000 2.8798 +0.0000 0.0000 2.7489 +0.0000 0.0000 2.6180 +0.0000 0.0000 2.4871 +0.0000 0.0000 2.3562 +primID: 0 +startangle_c: 10 +endpose_c: -1 -1 10 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0111 -0.0111 3.9270 +-0.0222 -0.0222 3.9270 +-0.0333 -0.0333 3.9270 +-0.0444 -0.0444 3.9270 +-0.0556 -0.0556 3.9270 +-0.0667 -0.0667 3.9270 +-0.0778 -0.0778 3.9270 +-0.0889 -0.0889 3.9270 +-0.1000 -0.1000 3.9270 +primID: 1 +startangle_c: 10 +endpose_c: -3 -3 10 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0333 -0.0333 3.9270 +-0.0667 -0.0667 3.9270 +-0.1000 -0.1000 3.9270 +-0.1333 -0.1333 3.9270 +-0.1667 -0.1667 3.9270 +-0.2000 -0.2000 3.9270 +-0.2333 -0.2333 3.9270 +-0.2667 -0.2667 3.9270 +-0.3000 -0.3000 3.9270 +primID: 2 +startangle_c: 10 +endpose_c: -6 -6 10 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0667 -0.0667 3.9270 +-0.1333 -0.1333 3.9270 +-0.2000 -0.2000 3.9270 +-0.2667 -0.2667 3.9270 +-0.3333 -0.3333 3.9270 +-0.4000 -0.4000 3.9270 +-0.4667 -0.4667 3.9270 +-0.5333 -0.5333 3.9270 +-0.6000 -0.6000 3.9270 +primID: 3 +startangle_c: 10 +endpose_c: -2 -6 10 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0222 -0.0667 3.9270 +-0.0444 -0.1333 3.9270 +-0.0667 -0.2000 3.9270 +-0.0889 -0.2667 3.9270 +-0.1111 -0.3333 3.9270 +-0.1333 -0.4000 3.9270 +-0.1556 -0.4667 3.9270 +-0.1778 -0.5333 3.9270 +-0.2000 -0.6000 3.9270 +primID: 4 +startangle_c: 10 +endpose_c: -6 -2 10 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0667 -0.0222 3.9270 +-0.1333 -0.0444 3.9270 +-0.2000 -0.0667 3.9270 +-0.2667 -0.0889 3.9270 +-0.3333 -0.1111 3.9270 +-0.4000 -0.1333 3.9270 +-0.4667 -0.1556 3.9270 +-0.5333 -0.1778 3.9270 +-0.6000 -0.2000 3.9270 +primID: 5 +startangle_c: 10 +endpose_c: 0 -4 10 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0000 -0.0444 3.9270 +0.0000 -0.0889 3.9270 +0.0000 -0.1333 3.9270 +0.0000 -0.1778 3.9270 +0.0000 -0.2222 3.9270 +0.0000 -0.2667 3.9270 +0.0000 -0.3111 3.9270 +0.0000 -0.3556 3.9270 +0.0000 -0.4000 3.9270 +primID: 6 +startangle_c: 10 +endpose_c: -4 0 10 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0444 0.0000 3.9270 +-0.0889 0.0000 3.9270 +-0.1333 0.0000 3.9270 +-0.1778 0.0000 3.9270 +-0.2222 0.0000 3.9270 +-0.2667 0.0000 3.9270 +-0.3111 0.0000 3.9270 +-0.3556 0.0000 3.9270 +-0.4000 0.0000 3.9270 +primID: 7 +startangle_c: 10 +endpose_c: 4 4 10 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0444 0.0444 3.9270 +0.0889 0.0889 3.9270 +0.1333 0.1333 3.9270 +0.1778 0.1778 3.9270 +0.2222 0.2222 3.9270 +0.2667 0.2667 3.9270 +0.3111 0.3111 3.9270 +0.3556 0.3556 3.9270 +0.4000 0.4000 3.9270 +primID: 8 +startangle_c: 10 +endpose_c: -2 -6 11 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0222 -0.0667 3.9706 +-0.0444 -0.1333 4.0143 +-0.0667 -0.2000 4.0579 +-0.0889 -0.2667 4.1015 +-0.1111 -0.3333 4.1452 +-0.1333 -0.4000 4.1888 +-0.1556 -0.4667 4.2324 +-0.1778 -0.5333 4.2761 +-0.2000 -0.6000 4.3197 +primID: 9 +startangle_c: 10 +endpose_c: -6 -2 9 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0667 -0.0222 3.8834 +-0.1333 -0.0444 3.8397 +-0.2000 -0.0667 3.7961 +-0.2667 -0.0889 3.7525 +-0.3333 -0.1111 3.7088 +-0.4000 -0.1333 3.6652 +-0.4667 -0.1556 3.6216 +-0.5333 -0.1778 3.5779 +-0.6000 -0.2000 3.5343 +primID: 10 +startangle_c: 10 +endpose_c: -1 -5 12 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0111 -0.0556 4.0143 +-0.0222 -0.1111 4.1015 +-0.0333 -0.1667 4.1888 +-0.0444 -0.2222 4.2761 +-0.0556 -0.2778 4.3633 +-0.0667 -0.3333 4.4506 +-0.0778 -0.3889 4.5379 +-0.0889 -0.4444 4.6251 +-0.1000 -0.5000 4.7124 +primID: 11 +startangle_c: 10 +endpose_c: -5 -1 8 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0556 -0.0111 3.8397 +-0.1111 -0.0222 3.7525 +-0.1667 -0.0333 3.6652 +-0.2222 -0.0444 3.5779 +-0.2778 -0.0556 3.4907 +-0.3333 -0.0667 3.4034 +-0.3889 -0.0778 3.3161 +-0.4444 -0.0889 3.2289 +-0.5000 -0.1000 3.1416 +primID: 12 +startangle_c: 10 +endpose_c: 0 0 11 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.9706 +0.0000 0.0000 4.0143 +0.0000 0.0000 4.0579 +0.0000 0.0000 4.1015 +0.0000 0.0000 4.1452 +0.0000 0.0000 4.1888 +0.0000 0.0000 4.2324 +0.0000 0.0000 4.2761 +0.0000 0.0000 4.3197 +primID: 13 +startangle_c: 10 +endpose_c: 0 0 9 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.8834 +0.0000 0.0000 3.8397 +0.0000 0.0000 3.7961 +0.0000 0.0000 3.7525 +0.0000 0.0000 3.7088 +0.0000 0.0000 3.6652 +0.0000 0.0000 3.6216 +0.0000 0.0000 3.5779 +0.0000 0.0000 3.5343 +primID: 14 +startangle_c: 10 +endpose_c: 0 0 13 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0000 0.0000 4.0579 +0.0000 0.0000 4.1888 +0.0000 0.0000 4.3197 +0.0000 0.0000 4.4506 +0.0000 0.0000 4.5815 +0.0000 0.0000 4.7124 +0.0000 0.0000 4.8433 +0.0000 0.0000 4.9742 +0.0000 0.0000 5.1051 +primID: 15 +startangle_c: 10 +endpose_c: 0 0 7 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.7961 +0.0000 0.0000 3.6652 +0.0000 0.0000 3.5343 +0.0000 0.0000 3.4034 +0.0000 0.0000 3.2725 +0.0000 0.0000 3.1416 +0.0000 0.0000 3.0107 +0.0000 0.0000 2.8798 +0.0000 0.0000 2.7489 +primID: 0 +startangle_c: 11 +endpose_c: -1 -2 11 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0111 -0.0222 4.3197 +-0.0222 -0.0444 4.3197 +-0.0333 -0.0667 4.3197 +-0.0444 -0.0889 4.3197 +-0.0556 -0.1111 4.3197 +-0.0667 -0.1333 4.3197 +-0.0778 -0.1556 4.3197 +-0.0889 -0.1778 4.3197 +-0.1000 -0.2000 4.3197 +primID: 1 +startangle_c: 11 +endpose_c: -2 -4 11 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0222 -0.0444 4.3197 +-0.0444 -0.0889 4.3197 +-0.0667 -0.1333 4.3197 +-0.0889 -0.1778 4.3197 +-0.1111 -0.2222 4.3197 +-0.1333 -0.2667 4.3197 +-0.1556 -0.3111 4.3197 +-0.1778 -0.3556 4.3197 +-0.2000 -0.4000 4.3197 +primID: 2 +startangle_c: 11 +endpose_c: -3 -6 11 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0333 -0.0667 4.3197 +-0.0667 -0.1333 4.3197 +-0.1000 -0.2000 4.3197 +-0.1333 -0.2667 4.3197 +-0.1667 -0.3333 4.3197 +-0.2000 -0.4000 4.3197 +-0.2333 -0.4667 4.3197 +-0.2667 -0.5333 4.3197 +-0.3000 -0.6000 4.3197 +primID: 3 +startangle_c: 11 +endpose_c: -4 -4 11 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0444 -0.0444 4.3197 +-0.0889 -0.0889 4.3197 +-0.1333 -0.1333 4.3197 +-0.1778 -0.1778 4.3197 +-0.2222 -0.2222 4.3197 +-0.2667 -0.2667 4.3197 +-0.3111 -0.3111 4.3197 +-0.3556 -0.3556 4.3197 +-0.4000 -0.4000 4.3197 +primID: 4 +startangle_c: 11 +endpose_c: -2 -6 11 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0222 -0.0667 4.3197 +-0.0444 -0.1333 4.3197 +-0.0667 -0.2000 4.3197 +-0.0889 -0.2667 4.3197 +-0.1111 -0.3333 4.3197 +-0.1333 -0.4000 4.3197 +-0.1556 -0.4667 4.3197 +-0.1778 -0.5333 4.3197 +-0.2000 -0.6000 4.3197 +primID: 5 +startangle_c: 11 +endpose_c: -3 0 11 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0333 0.0000 4.3197 +-0.0667 0.0000 4.3197 +-0.1000 0.0000 4.3197 +-0.1333 0.0000 4.3197 +-0.1667 0.0000 4.3197 +-0.2000 0.0000 4.3197 +-0.2333 0.0000 4.3197 +-0.2667 0.0000 4.3197 +-0.3000 0.0000 4.3197 +primID: 6 +startangle_c: 11 +endpose_c: 1 -4 11 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0111 -0.0444 4.3197 +0.0222 -0.0889 4.3197 +0.0333 -0.1333 4.3197 +0.0444 -0.1778 4.3197 +0.0556 -0.2222 4.3197 +0.0667 -0.2667 4.3197 +0.0778 -0.3111 4.3197 +0.0889 -0.3556 4.3197 +0.1000 -0.4000 4.3197 +primID: 7 +startangle_c: 11 +endpose_c: 2 4 11 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0222 0.0444 4.3197 +0.0444 0.0889 4.3197 +0.0667 0.1333 4.3197 +0.0889 0.1778 4.3197 +0.1111 0.2222 4.3197 +0.1333 0.2667 4.3197 +0.1556 0.3111 4.3197 +0.1778 0.3556 4.3197 +0.2000 0.4000 4.3197 +primID: 8 +startangle_c: 11 +endpose_c: -4 -4 10 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0444 -0.0444 4.2761 +-0.0889 -0.0889 4.2324 +-0.1333 -0.1333 4.1888 +-0.1778 -0.1778 4.1452 +-0.2222 -0.2222 4.1015 +-0.2667 -0.2667 4.0579 +-0.3111 -0.3111 4.0143 +-0.3556 -0.3556 3.9706 +-0.4000 -0.4000 3.9270 +primID: 9 +startangle_c: 11 +endpose_c: -2 -6 12 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0222 -0.0667 4.3633 +-0.0444 -0.1333 4.4070 +-0.0667 -0.2000 4.4506 +-0.0889 -0.2667 4.4942 +-0.1111 -0.3333 4.5379 +-0.1333 -0.4000 4.5815 +-0.1556 -0.4667 4.6251 +-0.1778 -0.5333 4.6688 +-0.2000 -0.6000 4.7124 +primID: 10 +startangle_c: 11 +endpose_c: -4 -2 9 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0444 -0.0222 4.2324 +-0.0889 -0.0444 4.1452 +-0.1333 -0.0667 4.0579 +-0.1778 -0.0889 3.9706 +-0.2222 -0.1111 3.8834 +-0.2667 -0.1333 3.7961 +-0.3111 -0.1556 3.7088 +-0.3556 -0.1778 3.6216 +-0.4000 -0.2000 3.5343 +primID: 11 +startangle_c: 11 +endpose_c: 0 -6 13 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0000 -0.0667 4.4070 +0.0000 -0.1333 4.4942 +0.0000 -0.2000 4.5815 +0.0000 -0.2667 4.6688 +0.0000 -0.3333 4.7560 +0.0000 -0.4000 4.8433 +0.0000 -0.4667 4.9306 +0.0000 -0.5333 5.0178 +0.0000 -0.6000 5.1051 +primID: 12 +startangle_c: 11 +endpose_c: 0 0 10 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0000 0.0000 4.2761 +0.0000 0.0000 4.2324 +0.0000 0.0000 4.1888 +0.0000 0.0000 4.1452 +0.0000 0.0000 4.1015 +0.0000 0.0000 4.0579 +0.0000 0.0000 4.0143 +0.0000 0.0000 3.9706 +0.0000 0.0000 3.9270 +primID: 13 +startangle_c: 11 +endpose_c: 0 0 12 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0000 0.0000 4.3633 +0.0000 0.0000 4.4070 +0.0000 0.0000 4.4506 +0.0000 0.0000 4.4942 +0.0000 0.0000 4.5379 +0.0000 0.0000 4.5815 +0.0000 0.0000 4.6251 +0.0000 0.0000 4.6688 +0.0000 0.0000 4.7124 +primID: 14 +startangle_c: 11 +endpose_c: 0 0 8 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0000 0.0000 4.1888 +0.0000 0.0000 4.0579 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.7961 +0.0000 0.0000 3.6652 +0.0000 0.0000 3.5343 +0.0000 0.0000 3.4034 +0.0000 0.0000 3.2725 +0.0000 0.0000 3.1416 +primID: 15 +startangle_c: 11 +endpose_c: 0 0 14 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0000 0.0000 4.4506 +0.0000 0.0000 4.5815 +0.0000 0.0000 4.7124 +0.0000 0.0000 4.8433 +0.0000 0.0000 4.9742 +0.0000 0.0000 5.1051 +0.0000 0.0000 5.2360 +0.0000 0.0000 5.3669 +0.0000 0.0000 5.4978 +primID: 0 +startangle_c: 12 +endpose_c: 0 -1 12 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0111 4.7124 +0.0000 -0.0222 4.7124 +0.0000 -0.0333 4.7124 +0.0000 -0.0444 4.7124 +0.0000 -0.0556 4.7124 +0.0000 -0.0667 4.7124 +0.0000 -0.0778 4.7124 +0.0000 -0.0889 4.7124 +0.0000 -0.1000 4.7124 +primID: 1 +startangle_c: 12 +endpose_c: 0 -4 12 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0444 4.7124 +0.0000 -0.0889 4.7124 +0.0000 -0.1333 4.7124 +0.0000 -0.1778 4.7124 +0.0000 -0.2222 4.7124 +0.0000 -0.2667 4.7124 +0.0000 -0.3111 4.7124 +0.0000 -0.3556 4.7124 +0.0000 -0.4000 4.7124 +primID: 2 +startangle_c: 12 +endpose_c: 0 -8 12 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0889 4.7124 +0.0000 -0.1778 4.7124 +0.0000 -0.2667 4.7124 +0.0000 -0.3556 4.7124 +0.0000 -0.4444 4.7124 +0.0000 -0.5333 4.7124 +0.0000 -0.6222 4.7124 +0.0000 -0.7111 4.7124 +0.0000 -0.8000 4.7124 +primID: 3 +startangle_c: 12 +endpose_c: 2 -6 12 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0222 -0.0667 4.7124 +0.0444 -0.1333 4.7124 +0.0667 -0.2000 4.7124 +0.0889 -0.2667 4.7124 +0.1111 -0.3333 4.7124 +0.1333 -0.4000 4.7124 +0.1556 -0.4667 4.7124 +0.1778 -0.5333 4.7124 +0.2000 -0.6000 4.7124 +primID: 4 +startangle_c: 12 +endpose_c: -2 -6 12 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 4.7124 +-0.0222 -0.0667 4.7124 +-0.0444 -0.1333 4.7124 +-0.0667 -0.2000 4.7124 +-0.0889 -0.2667 4.7124 +-0.1111 -0.3333 4.7124 +-0.1333 -0.4000 4.7124 +-0.1556 -0.4667 4.7124 +-0.1778 -0.5333 4.7124 +-0.2000 -0.6000 4.7124 +primID: 5 +startangle_c: 12 +endpose_c: 3 -2 12 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0333 -0.0222 4.7124 +0.0667 -0.0444 4.7124 +0.1000 -0.0667 4.7124 +0.1333 -0.0889 4.7124 +0.1667 -0.1111 4.7124 +0.2000 -0.1333 4.7124 +0.2333 -0.1556 4.7124 +0.2667 -0.1778 4.7124 +0.3000 -0.2000 4.7124 +primID: 6 +startangle_c: 12 +endpose_c: -3 -2 12 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 4.7124 +-0.0333 -0.0222 4.7124 +-0.0667 -0.0444 4.7124 +-0.1000 -0.0667 4.7124 +-0.1333 -0.0889 4.7124 +-0.1667 -0.1111 4.7124 +-0.2000 -0.1333 4.7124 +-0.2333 -0.1556 4.7124 +-0.2667 -0.1778 4.7124 +-0.3000 -0.2000 4.7124 +primID: 7 +startangle_c: 12 +endpose_c: 0 5 12 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0556 4.7124 +0.0000 0.1111 4.7124 +0.0000 0.1667 4.7124 +0.0000 0.2222 4.7124 +0.0000 0.2778 4.7124 +0.0000 0.3333 4.7124 +0.0000 0.3889 4.7124 +0.0000 0.4444 4.7124 +0.0000 0.5000 4.7124 +primID: 8 +startangle_c: 12 +endpose_c: 2 -6 13 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0222 -0.0667 4.7560 +0.0444 -0.1333 4.7997 +0.0667 -0.2000 4.8433 +0.0889 -0.2667 4.8869 +0.1111 -0.3333 4.9306 +0.1333 -0.4000 4.9742 +0.1556 -0.4667 5.0178 +0.1778 -0.5333 5.0615 +0.2000 -0.6000 5.1051 +primID: 9 +startangle_c: 12 +endpose_c: -2 -6 11 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.7124 +-0.0222 -0.0667 4.6688 +-0.0444 -0.1333 4.6251 +-0.0667 -0.2000 4.5815 +-0.0889 -0.2667 4.5379 +-0.1111 -0.3333 4.4942 +-0.1333 -0.4000 4.4506 +-0.1556 -0.4667 4.4070 +-0.1778 -0.5333 4.3633 +-0.2000 -0.6000 4.3197 +primID: 10 +startangle_c: 12 +endpose_c: 3 -4 14 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0333 -0.0444 4.7997 +0.0667 -0.0889 4.8869 +0.1000 -0.1333 4.9742 +0.1333 -0.1778 5.0615 +0.1667 -0.2222 5.1487 +0.2000 -0.2667 5.2360 +0.2333 -0.3111 5.3233 +0.2667 -0.3556 5.4105 +0.3000 -0.4000 5.4978 +primID: 11 +startangle_c: 12 +endpose_c: -3 -4 10 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.7124 +-0.0333 -0.0444 4.6251 +-0.0667 -0.0889 4.5379 +-0.1000 -0.1333 4.4506 +-0.1333 -0.1778 4.3633 +-0.1667 -0.2222 4.2761 +-0.2000 -0.2667 4.1888 +-0.2333 -0.3111 4.1015 +-0.2667 -0.3556 4.0143 +-0.3000 -0.4000 3.9270 +primID: 12 +startangle_c: 12 +endpose_c: 0 0 13 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0000 4.7560 +0.0000 0.0000 4.7997 +0.0000 0.0000 4.8433 +0.0000 0.0000 4.8869 +0.0000 0.0000 4.9306 +0.0000 0.0000 4.9742 +0.0000 0.0000 5.0178 +0.0000 0.0000 5.0615 +0.0000 0.0000 5.1051 +primID: 13 +startangle_c: 12 +endpose_c: 0 0 11 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0000 4.6688 +0.0000 0.0000 4.6251 +0.0000 0.0000 4.5815 +0.0000 0.0000 4.5379 +0.0000 0.0000 4.4942 +0.0000 0.0000 4.4506 +0.0000 0.0000 4.4070 +0.0000 0.0000 4.3633 +0.0000 0.0000 4.3197 +primID: 14 +startangle_c: 12 +endpose_c: 0 0 15 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0000 4.8433 +0.0000 0.0000 4.9742 +0.0000 0.0000 5.1051 +0.0000 0.0000 5.2360 +0.0000 0.0000 5.3669 +0.0000 0.0000 5.4978 +0.0000 0.0000 5.6287 +0.0000 0.0000 5.7596 +0.0000 0.0000 5.8905 +primID: 15 +startangle_c: 12 +endpose_c: 0 0 9 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0000 4.5815 +0.0000 0.0000 4.4506 +0.0000 0.0000 4.3197 +0.0000 0.0000 4.1888 +0.0000 0.0000 4.0579 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.7961 +0.0000 0.0000 3.6652 +0.0000 0.0000 3.5343 +primID: 0 +startangle_c: 13 +endpose_c: 1 -2 13 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0111 -0.0222 5.1051 +0.0222 -0.0444 5.1051 +0.0333 -0.0667 5.1051 +0.0444 -0.0889 5.1051 +0.0556 -0.1111 5.1051 +0.0667 -0.1333 5.1051 +0.0778 -0.1556 5.1051 +0.0889 -0.1778 5.1051 +0.1000 -0.2000 5.1051 +primID: 1 +startangle_c: 13 +endpose_c: 2 -4 13 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0222 -0.0444 5.1051 +0.0444 -0.0889 5.1051 +0.0667 -0.1333 5.1051 +0.0889 -0.1778 5.1051 +0.1111 -0.2222 5.1051 +0.1333 -0.2667 5.1051 +0.1556 -0.3111 5.1051 +0.1778 -0.3556 5.1051 +0.2000 -0.4000 5.1051 +primID: 2 +startangle_c: 13 +endpose_c: 3 -6 13 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0333 -0.0667 5.1051 +0.0667 -0.1333 5.1051 +0.1000 -0.2000 5.1051 +0.1333 -0.2667 5.1051 +0.1667 -0.3333 5.1051 +0.2000 -0.4000 5.1051 +0.2333 -0.4667 5.1051 +0.2667 -0.5333 5.1051 +0.3000 -0.6000 5.1051 +primID: 3 +startangle_c: 13 +endpose_c: 4 -4 13 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0444 -0.0444 5.1051 +0.0889 -0.0889 5.1051 +0.1333 -0.1333 5.1051 +0.1778 -0.1778 5.1051 +0.2222 -0.2222 5.1051 +0.2667 -0.2667 5.1051 +0.3111 -0.3111 5.1051 +0.3556 -0.3556 5.1051 +0.4000 -0.4000 5.1051 +primID: 4 +startangle_c: 13 +endpose_c: 2 -6 13 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0222 -0.0667 5.1051 +0.0444 -0.1333 5.1051 +0.0667 -0.2000 5.1051 +0.0889 -0.2667 5.1051 +0.1111 -0.3333 5.1051 +0.1333 -0.4000 5.1051 +0.1556 -0.4667 5.1051 +0.1778 -0.5333 5.1051 +0.2000 -0.6000 5.1051 +primID: 5 +startangle_c: 13 +endpose_c: 3 0 13 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0333 0.0000 5.1051 +0.0667 0.0000 5.1051 +0.1000 0.0000 5.1051 +0.1333 0.0000 5.1051 +0.1667 0.0000 5.1051 +0.2000 0.0000 5.1051 +0.2333 0.0000 5.1051 +0.2667 0.0000 5.1051 +0.3000 0.0000 5.1051 +primID: 6 +startangle_c: 13 +endpose_c: -1 -4 13 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.1051 +-0.0111 -0.0444 5.1051 +-0.0222 -0.0889 5.1051 +-0.0333 -0.1333 5.1051 +-0.0444 -0.1778 5.1051 +-0.0556 -0.2222 5.1051 +-0.0667 -0.2667 5.1051 +-0.0778 -0.3111 5.1051 +-0.0889 -0.3556 5.1051 +-0.1000 -0.4000 5.1051 +primID: 7 +startangle_c: 13 +endpose_c: -2 4 13 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 5.1051 +-0.0222 0.0444 5.1051 +-0.0444 0.0889 5.1051 +-0.0667 0.1333 5.1051 +-0.0889 0.1778 5.1051 +-0.1111 0.2222 5.1051 +-0.1333 0.2667 5.1051 +-0.1556 0.3111 5.1051 +-0.1778 0.3556 5.1051 +-0.2000 0.4000 5.1051 +primID: 8 +startangle_c: 13 +endpose_c: 4 -4 14 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0444 -0.0444 5.1487 +0.0889 -0.0889 5.1924 +0.1333 -0.1333 5.2360 +0.1778 -0.1778 5.2796 +0.2222 -0.2222 5.3233 +0.2667 -0.2667 5.3669 +0.3111 -0.3111 5.4105 +0.3556 -0.3556 5.4542 +0.4000 -0.4000 5.4978 +primID: 9 +startangle_c: 13 +endpose_c: 2 -6 12 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0222 -0.0667 5.0615 +0.0444 -0.1333 5.0178 +0.0667 -0.2000 4.9742 +0.0889 -0.2667 4.9306 +0.1111 -0.3333 4.8869 +0.1333 -0.4000 4.8433 +0.1556 -0.4667 4.7997 +0.1778 -0.5333 4.7560 +0.2000 -0.6000 4.7124 +primID: 10 +startangle_c: 13 +endpose_c: 4 -2 15 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0444 -0.0222 5.1924 +0.0889 -0.0444 5.2796 +0.1333 -0.0667 5.3669 +0.1778 -0.0889 5.4542 +0.2222 -0.1111 5.5414 +0.2667 -0.1333 5.6287 +0.3111 -0.1556 5.7160 +0.3556 -0.1778 5.8032 +0.4000 -0.2000 5.8905 +primID: 11 +startangle_c: 13 +endpose_c: 0 -6 11 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0000 -0.0667 5.0178 +0.0000 -0.1333 4.9306 +0.0000 -0.2000 4.8433 +0.0000 -0.2667 4.7560 +0.0000 -0.3333 4.6688 +0.0000 -0.4000 4.5815 +0.0000 -0.4667 4.4942 +0.0000 -0.5333 4.4070 +0.0000 -0.6000 4.3197 +primID: 12 +startangle_c: 13 +endpose_c: 0 0 14 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0000 0.0000 5.1487 +0.0000 0.0000 5.1924 +0.0000 0.0000 5.2360 +0.0000 0.0000 5.2796 +0.0000 0.0000 5.3233 +0.0000 0.0000 5.3669 +0.0000 0.0000 5.4105 +0.0000 0.0000 5.4542 +0.0000 0.0000 5.4978 +primID: 13 +startangle_c: 13 +endpose_c: 0 0 12 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0000 0.0000 5.0615 +0.0000 0.0000 5.0178 +0.0000 0.0000 4.9742 +0.0000 0.0000 4.9306 +0.0000 0.0000 4.8869 +0.0000 0.0000 4.8433 +0.0000 0.0000 4.7997 +0.0000 0.0000 4.7560 +0.0000 0.0000 4.7124 +primID: 14 +startangle_c: 13 +endpose_c: 0 0 0 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0000 0.0000 4.5379 +0.0000 0.0000 3.9706 +0.0000 0.0000 3.4034 +0.0000 0.0000 2.8362 +0.0000 0.0000 2.2689 +0.0000 0.0000 1.7017 +0.0000 0.0000 1.1345 +0.0000 0.0000 0.5672 +0.0000 0.0000 0.0000 +primID: 15 +startangle_c: 13 +endpose_c: 0 0 10 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0000 0.0000 4.9742 +0.0000 0.0000 4.8433 +0.0000 0.0000 4.7124 +0.0000 0.0000 4.5815 +0.0000 0.0000 4.4506 +0.0000 0.0000 4.3197 +0.0000 0.0000 4.1888 +0.0000 0.0000 4.0579 +0.0000 0.0000 3.9270 +primID: 0 +startangle_c: 14 +endpose_c: 1 -1 14 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0111 -0.0111 5.4978 +0.0222 -0.0222 5.4978 +0.0333 -0.0333 5.4978 +0.0444 -0.0444 5.4978 +0.0556 -0.0556 5.4978 +0.0667 -0.0667 5.4978 +0.0778 -0.0778 5.4978 +0.0889 -0.0889 5.4978 +0.1000 -0.1000 5.4978 +primID: 1 +startangle_c: 14 +endpose_c: 3 -3 14 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0333 -0.0333 5.4978 +0.0667 -0.0667 5.4978 +0.1000 -0.1000 5.4978 +0.1333 -0.1333 5.4978 +0.1667 -0.1667 5.4978 +0.2000 -0.2000 5.4978 +0.2333 -0.2333 5.4978 +0.2667 -0.2667 5.4978 +0.3000 -0.3000 5.4978 +primID: 2 +startangle_c: 14 +endpose_c: 6 -6 14 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0667 -0.0667 5.4978 +0.1333 -0.1333 5.4978 +0.2000 -0.2000 5.4978 +0.2667 -0.2667 5.4978 +0.3333 -0.3333 5.4978 +0.4000 -0.4000 5.4978 +0.4667 -0.4667 5.4978 +0.5333 -0.5333 5.4978 +0.6000 -0.6000 5.4978 +primID: 3 +startangle_c: 14 +endpose_c: 6 -2 14 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0667 -0.0222 5.4978 +0.1333 -0.0444 5.4978 +0.2000 -0.0667 5.4978 +0.2667 -0.0889 5.4978 +0.3333 -0.1111 5.4978 +0.4000 -0.1333 5.4978 +0.4667 -0.1556 5.4978 +0.5333 -0.1778 5.4978 +0.6000 -0.2000 5.4978 +primID: 4 +startangle_c: 14 +endpose_c: 2 -6 14 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0222 -0.0667 5.4978 +0.0444 -0.1333 5.4978 +0.0667 -0.2000 5.4978 +0.0889 -0.2667 5.4978 +0.1111 -0.3333 5.4978 +0.1333 -0.4000 5.4978 +0.1556 -0.4667 5.4978 +0.1778 -0.5333 5.4978 +0.2000 -0.6000 5.4978 +primID: 5 +startangle_c: 14 +endpose_c: 4 0 14 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0444 0.0000 5.4978 +0.0889 0.0000 5.4978 +0.1333 0.0000 5.4978 +0.1778 0.0000 5.4978 +0.2222 0.0000 5.4978 +0.2667 0.0000 5.4978 +0.3111 0.0000 5.4978 +0.3556 0.0000 5.4978 +0.4000 0.0000 5.4978 +primID: 6 +startangle_c: 14 +endpose_c: 0 -4 14 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0000 -0.0444 5.4978 +0.0000 -0.0889 5.4978 +0.0000 -0.1333 5.4978 +0.0000 -0.1778 5.4978 +0.0000 -0.2222 5.4978 +0.0000 -0.2667 5.4978 +0.0000 -0.3111 5.4978 +0.0000 -0.3556 5.4978 +0.0000 -0.4000 5.4978 +primID: 7 +startangle_c: 14 +endpose_c: -4 4 14 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 5.4978 +-0.0444 0.0444 5.4978 +-0.0889 0.0889 5.4978 +-0.1333 0.1333 5.4978 +-0.1778 0.1778 5.4978 +-0.2222 0.2222 5.4978 +-0.2667 0.2667 5.4978 +-0.3111 0.3111 5.4978 +-0.3556 0.3556 5.4978 +-0.4000 0.4000 5.4978 +primID: 8 +startangle_c: 14 +endpose_c: 6 -2 15 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0667 -0.0222 5.5414 +0.1333 -0.0444 5.5851 +0.2000 -0.0667 5.6287 +0.2667 -0.0889 5.6723 +0.3333 -0.1111 5.7160 +0.4000 -0.1333 5.7596 +0.4667 -0.1556 5.8032 +0.5333 -0.1778 5.8469 +0.6000 -0.2000 5.8905 +primID: 9 +startangle_c: 14 +endpose_c: 2 -6 13 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0222 -0.0667 5.4542 +0.0444 -0.1333 5.4105 +0.0667 -0.2000 5.3669 +0.0889 -0.2667 5.3233 +0.1111 -0.3333 5.2796 +0.1333 -0.4000 5.2360 +0.1556 -0.4667 5.1924 +0.1778 -0.5333 5.1487 +0.2000 -0.6000 5.1051 +primID: 10 +startangle_c: 14 +endpose_c: 5 -1 0 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0556 -0.0111 4.8869 +0.1111 -0.0222 4.2761 +0.1667 -0.0333 3.6652 +0.2222 -0.0444 3.0543 +0.2778 -0.0556 2.4435 +0.3333 -0.0667 1.8326 +0.3889 -0.0778 1.2217 +0.4444 -0.0889 0.6109 +0.5000 -0.1000 0.0000 +primID: 11 +startangle_c: 14 +endpose_c: 1 -5 12 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0111 -0.0556 5.4105 +0.0222 -0.1111 5.3233 +0.0333 -0.1667 5.2360 +0.0444 -0.2222 5.1487 +0.0556 -0.2778 5.0615 +0.0667 -0.3333 4.9742 +0.0778 -0.3889 4.8869 +0.0889 -0.4444 4.7997 +0.1000 -0.5000 4.7124 +primID: 12 +startangle_c: 14 +endpose_c: 0 0 15 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0000 0.0000 5.5414 +0.0000 0.0000 5.5851 +0.0000 0.0000 5.6287 +0.0000 0.0000 5.6723 +0.0000 0.0000 5.7160 +0.0000 0.0000 5.7596 +0.0000 0.0000 5.8032 +0.0000 0.0000 5.8469 +0.0000 0.0000 5.8905 +primID: 13 +startangle_c: 14 +endpose_c: 0 0 13 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0000 0.0000 5.4542 +0.0000 0.0000 5.4105 +0.0000 0.0000 5.3669 +0.0000 0.0000 5.3233 +0.0000 0.0000 5.2796 +0.0000 0.0000 5.2360 +0.0000 0.0000 5.1924 +0.0000 0.0000 5.1487 +0.0000 0.0000 5.1051 +primID: 14 +startangle_c: 14 +endpose_c: 0 0 1 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0000 0.0000 4.9306 +0.0000 0.0000 4.3633 +0.0000 0.0000 3.7961 +0.0000 0.0000 3.2289 +0.0000 0.0000 2.6616 +0.0000 0.0000 2.0944 +0.0000 0.0000 1.5272 +0.0000 0.0000 0.9599 +0.0000 0.0000 0.3927 +primID: 15 +startangle_c: 14 +endpose_c: 0 0 11 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0000 0.0000 5.3669 +0.0000 0.0000 5.2360 +0.0000 0.0000 5.1051 +0.0000 0.0000 4.9742 +0.0000 0.0000 4.8433 +0.0000 0.0000 4.7124 +0.0000 0.0000 4.5815 +0.0000 0.0000 4.4506 +0.0000 0.0000 4.3197 +primID: 0 +startangle_c: 15 +endpose_c: 2 -1 15 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0222 -0.0111 5.8905 +0.0444 -0.0222 5.8905 +0.0667 -0.0333 5.8905 +0.0889 -0.0444 5.8905 +0.1111 -0.0556 5.8905 +0.1333 -0.0667 5.8905 +0.1556 -0.0778 5.8905 +0.1778 -0.0889 5.8905 +0.2000 -0.1000 5.8905 +primID: 1 +startangle_c: 15 +endpose_c: 4 -2 15 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0444 -0.0222 5.8905 +0.0889 -0.0444 5.8905 +0.1333 -0.0667 5.8905 +0.1778 -0.0889 5.8905 +0.2222 -0.1111 5.8905 +0.2667 -0.1333 5.8905 +0.3111 -0.1556 5.8905 +0.3556 -0.1778 5.8905 +0.4000 -0.2000 5.8905 +primID: 2 +startangle_c: 15 +endpose_c: 6 -3 15 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0667 -0.0333 5.8905 +0.1333 -0.0667 5.8905 +0.2000 -0.1000 5.8905 +0.2667 -0.1333 5.8905 +0.3333 -0.1667 5.8905 +0.4000 -0.2000 5.8905 +0.4667 -0.2333 5.8905 +0.5333 -0.2667 5.8905 +0.6000 -0.3000 5.8905 +primID: 3 +startangle_c: 15 +endpose_c: 4 -4 15 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0444 -0.0444 5.8905 +0.0889 -0.0889 5.8905 +0.1333 -0.1333 5.8905 +0.1778 -0.1778 5.8905 +0.2222 -0.2222 5.8905 +0.2667 -0.2667 5.8905 +0.3111 -0.3111 5.8905 +0.3556 -0.3556 5.8905 +0.4000 -0.4000 5.8905 +primID: 4 +startangle_c: 15 +endpose_c: 6 -2 15 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0667 -0.0222 5.8905 +0.1333 -0.0444 5.8905 +0.2000 -0.0667 5.8905 +0.2667 -0.0889 5.8905 +0.3333 -0.1111 5.8905 +0.4000 -0.1333 5.8905 +0.4667 -0.1556 5.8905 +0.5333 -0.1778 5.8905 +0.6000 -0.2000 5.8905 +primID: 5 +startangle_c: 15 +endpose_c: 0 -3 15 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0000 -0.0333 5.8905 +0.0000 -0.0667 5.8905 +0.0000 -0.1000 5.8905 +0.0000 -0.1333 5.8905 +0.0000 -0.1667 5.8905 +0.0000 -0.2000 5.8905 +0.0000 -0.2333 5.8905 +0.0000 -0.2667 5.8905 +0.0000 -0.3000 5.8905 +primID: 6 +startangle_c: 15 +endpose_c: 4 1 15 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0444 0.0111 5.8905 +0.0889 0.0222 5.8905 +0.1333 0.0333 5.8905 +0.1778 0.0444 5.8905 +0.2222 0.0556 5.8905 +0.2667 0.0667 5.8905 +0.3111 0.0778 5.8905 +0.3556 0.0889 5.8905 +0.4000 0.1000 5.8905 +primID: 7 +startangle_c: 15 +endpose_c: -4 2 15 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 5.8905 +-0.0444 0.0222 5.8905 +-0.0889 0.0444 5.8905 +-0.1333 0.0667 5.8905 +-0.1778 0.0889 5.8905 +-0.2222 0.1111 5.8905 +-0.2667 0.1333 5.8905 +-0.3111 0.1556 5.8905 +-0.3556 0.1778 5.8905 +-0.4000 0.2000 5.8905 +primID: 8 +startangle_c: 15 +endpose_c: 4 -4 14 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0444 -0.0444 5.8469 +0.0889 -0.0889 5.8032 +0.1333 -0.1333 5.7596 +0.1778 -0.1778 5.7160 +0.2222 -0.2222 5.6723 +0.2667 -0.2667 5.6287 +0.3111 -0.3111 5.5851 +0.3556 -0.3556 5.5414 +0.4000 -0.4000 5.4978 +primID: 9 +startangle_c: 15 +endpose_c: 6 -2 0 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0667 -0.0222 5.9341 +0.1333 -0.0444 5.9778 +0.2000 -0.0667 6.0214 +0.2667 -0.0889 6.0650 +0.3333 -0.1111 6.1087 +0.4000 -0.1333 6.1523 +0.4667 -0.1556 6.1959 +0.5333 -0.1778 6.2396 +0.6000 -0.2000 0.0000 +primID: 10 +startangle_c: 15 +endpose_c: 2 -4 13 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0222 -0.0444 5.8032 +0.0444 -0.0889 5.7160 +0.0667 -0.1333 5.6287 +0.0889 -0.1778 5.5414 +0.1111 -0.2222 5.4542 +0.1333 -0.2667 5.3669 +0.1556 -0.3111 5.2796 +0.1778 -0.3556 5.1924 +0.2000 -0.4000 5.1051 +primID: 11 +startangle_c: 15 +endpose_c: 6 0 1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0667 0.0000 5.2796 +0.1333 0.0000 4.6688 +0.2000 0.0000 4.0579 +0.2667 0.0000 3.4470 +0.3333 0.0000 2.8362 +0.4000 0.0000 2.2253 +0.4667 0.0000 1.6144 +0.5333 0.0000 1.0036 +0.6000 0.0000 0.3927 +primID: 12 +startangle_c: 15 +endpose_c: 0 0 14 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0000 0.0000 5.8469 +0.0000 0.0000 5.8032 +0.0000 0.0000 5.7596 +0.0000 0.0000 5.7160 +0.0000 0.0000 5.6723 +0.0000 0.0000 5.6287 +0.0000 0.0000 5.5851 +0.0000 0.0000 5.5414 +0.0000 0.0000 5.4978 +primID: 13 +startangle_c: 15 +endpose_c: 0 0 0 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0000 0.0000 5.9341 +0.0000 0.0000 5.9778 +0.0000 0.0000 6.0214 +0.0000 0.0000 6.0650 +0.0000 0.0000 6.1087 +0.0000 0.0000 6.1523 +0.0000 0.0000 6.1959 +0.0000 0.0000 6.2396 +0.0000 0.0000 0.0000 +primID: 14 +startangle_c: 15 +endpose_c: 0 0 12 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0000 0.0000 5.7596 +0.0000 0.0000 5.6287 +0.0000 0.0000 5.4978 +0.0000 0.0000 5.3669 +0.0000 0.0000 5.2360 +0.0000 0.0000 5.1051 +0.0000 0.0000 4.9742 +0.0000 0.0000 4.8433 +0.0000 0.0000 4.7124 +primID: 15 +startangle_c: 15 +endpose_c: 0 0 2 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0000 0.0000 5.3233 +0.0000 0.0000 4.7560 +0.0000 0.0000 4.1888 +0.0000 0.0000 3.6216 +0.0000 0.0000 3.0543 +0.0000 0.0000 2.4871 +0.0000 0.0000 1.9199 +0.0000 0.0000 1.3526 +0.0000 0.0000 0.7854 diff --git a/navigations/sbpl/matlab/mprim/pr2_all_2.5cm_20turncost.mprim b/navigations/sbpl/matlab/mprim/pr2_all_2.5cm_20turncost.mprim new file mode 100755 index 0000000..d5c56d2 --- /dev/null +++ b/navigations/sbpl/matlab/mprim/pr2_all_2.5cm_20turncost.mprim @@ -0,0 +1,3123 @@ +resolution_m: 0.025000 +numberofangles: 16 +totalnumberofprimitives: 208 +primID: 0 +startangle_c: 0 +endpose_c: 1 0 0 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0028 0.0000 0.0000 +0.0056 0.0000 0.0000 +0.0083 0.0000 0.0000 +0.0111 0.0000 0.0000 +0.0139 0.0000 0.0000 +0.0167 0.0000 0.0000 +0.0194 0.0000 0.0000 +0.0222 0.0000 0.0000 +0.0250 0.0000 0.0000 +primID: 1 +startangle_c: 0 +endpose_c: 8 0 0 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0222 0.0000 0.0000 +0.0444 0.0000 0.0000 +0.0667 0.0000 0.0000 +0.0889 0.0000 0.0000 +0.1111 0.0000 0.0000 +0.1333 0.0000 0.0000 +0.1556 0.0000 0.0000 +0.1778 0.0000 0.0000 +0.2000 0.0000 0.0000 +primID: 2 +startangle_c: 0 +endpose_c: -1 0 0 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 0.0000 +-0.0028 0.0000 0.0000 +-0.0056 0.0000 0.0000 +-0.0083 0.0000 0.0000 +-0.0111 0.0000 0.0000 +-0.0139 0.0000 0.0000 +-0.0167 0.0000 0.0000 +-0.0194 0.0000 0.0000 +-0.0222 0.0000 0.0000 +-0.0250 0.0000 0.0000 +primID: 3 +startangle_c: 0 +endpose_c: 8 1 1 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0226 -0.0000 0.0000 +0.0452 -0.0000 0.0000 +0.0678 -0.0000 0.0000 +0.0903 0.0004 0.0488 +0.1128 0.0023 0.1176 +0.1352 0.0057 0.1864 +0.1572 0.0106 0.2551 +0.1789 0.0171 0.3239 +0.2000 0.0250 0.3927 +primID: 4 +startangle_c: 0 +endpose_c: 8 -1 -1 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0226 0.0000 0.0000 +0.0452 0.0000 0.0000 +0.0678 0.0000 0.0000 +0.0903 -0.0004 -0.0488 +0.1128 -0.0023 -0.1176 +0.1352 -0.0057 -0.1864 +0.1572 -0.0106 -0.2551 +0.1789 -0.0171 -0.3239 +0.2000 -0.0250 -0.3927 +primID: 5 +startangle_c: 0 +endpose_c: 0 0 1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0000 0.0000 0.0436 +0.0000 0.0000 0.0873 +0.0000 0.0000 0.1309 +0.0000 0.0000 0.1745 +0.0000 0.0000 0.2182 +0.0000 0.0000 0.2618 +0.0000 0.0000 0.3054 +0.0000 0.0000 0.3491 +0.0000 0.0000 0.3927 +primID: 6 +startangle_c: 0 +endpose_c: 0 0 -1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0000 0.0000 -0.0436 +0.0000 0.0000 -0.0873 +0.0000 0.0000 -0.1309 +0.0000 0.0000 -0.1745 +0.0000 0.0000 -0.2182 +0.0000 0.0000 -0.2618 +0.0000 0.0000 -0.3054 +0.0000 0.0000 -0.3491 +0.0000 0.0000 -0.3927 +primID: 7 +startangle_c: 0 +endpose_c: 0 1 0 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0000 0.0028 0.0000 +0.0000 0.0056 0.0000 +0.0000 0.0083 0.0000 +0.0000 0.0111 0.0000 +0.0000 0.0139 0.0000 +0.0000 0.0167 0.0000 +0.0000 0.0194 0.0000 +0.0000 0.0222 0.0000 +0.0000 0.0250 0.0000 +primID: 8 +startangle_c: 0 +endpose_c: 0 -1 0 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0000 -0.0028 0.0000 +0.0000 -0.0056 0.0000 +0.0000 -0.0083 0.0000 +0.0000 -0.0111 0.0000 +0.0000 -0.0139 0.0000 +0.0000 -0.0167 0.0000 +0.0000 -0.0194 0.0000 +0.0000 -0.0222 0.0000 +0.0000 -0.0250 0.0000 +primID: 9 +startangle_c: 0 +endpose_c: -8 -1 1 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 0.0000 +-0.0226 0.0000 0.0000 +-0.0452 0.0000 0.0000 +-0.0678 0.0000 0.0000 +-0.0903 -0.0004 0.0488 +-0.1128 -0.0023 0.1176 +-0.1352 -0.0057 0.1864 +-0.1572 -0.0106 0.2551 +-0.1789 -0.0171 0.3239 +-0.2000 -0.0250 0.3927 +primID: 10 +startangle_c: 0 +endpose_c: -8 1 -1 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 0.0000 +-0.0226 -0.0000 0.0000 +-0.0452 -0.0000 0.0000 +-0.0678 -0.0000 0.0000 +-0.0903 0.0004 -0.0488 +-0.1128 0.0023 -0.1176 +-0.1352 0.0057 -0.1864 +-0.1572 0.0106 -0.2551 +-0.1789 0.0171 -0.3239 +-0.2000 0.0250 -0.3927 +primID: 11 +startangle_c: 0 +endpose_c: 8 1 0 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0222 0.0028 0.0000 +0.0444 0.0056 0.0000 +0.0667 0.0083 0.0000 +0.0889 0.0111 0.0000 +0.1111 0.0139 0.0000 +0.1333 0.0167 0.0000 +0.1556 0.0194 0.0000 +0.1778 0.0222 0.0000 +0.2000 0.0250 0.0000 +primID: 12 +startangle_c: 0 +endpose_c: 8 -1 0 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0222 -0.0028 0.0000 +0.0444 -0.0056 0.0000 +0.0667 -0.0083 0.0000 +0.0889 -0.0111 0.0000 +0.1111 -0.0139 0.0000 +0.1333 -0.0167 0.0000 +0.1556 -0.0194 0.0000 +0.1778 -0.0222 0.0000 +0.2000 -0.0250 0.0000 +primID: 0 +startangle_c: 1 +endpose_c: 2 1 1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0056 0.0028 0.3927 +0.0111 0.0056 0.3927 +0.0167 0.0083 0.3927 +0.0222 0.0111 0.3927 +0.0278 0.0139 0.3927 +0.0333 0.0167 0.3927 +0.0389 0.0194 0.3927 +0.0444 0.0222 0.3927 +0.0500 0.0250 0.3927 +primID: 1 +startangle_c: 1 +endpose_c: 6 3 1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0167 0.0083 0.3927 +0.0333 0.0167 0.3927 +0.0500 0.0250 0.3927 +0.0667 0.0333 0.3927 +0.0833 0.0417 0.3927 +0.1000 0.0500 0.3927 +0.1167 0.0583 0.3927 +0.1333 0.0667 0.3927 +0.1500 0.0750 0.3927 +primID: 2 +startangle_c: 1 +endpose_c: -2 -1 1 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 0.3927 +-0.0056 -0.0028 0.3927 +-0.0111 -0.0056 0.3927 +-0.0167 -0.0083 0.3927 +-0.0222 -0.0111 0.3927 +-0.0278 -0.0139 0.3927 +-0.0333 -0.0167 0.3927 +-0.0389 -0.0194 0.3927 +-0.0444 -0.0222 0.3927 +-0.0500 -0.0250 0.3927 +primID: 3 +startangle_c: 1 +endpose_c: 5 4 2 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0149 0.0092 0.4230 +0.0296 0.0189 0.4533 +0.0440 0.0291 0.4836 +0.0582 0.0398 0.5139 +0.0722 0.0509 0.5442 +0.0858 0.0625 0.5745 +0.0992 0.0746 0.6048 +0.1123 0.0871 0.6351 +0.1250 0.1000 0.6654 +primID: 4 +startangle_c: 1 +endpose_c: 7 2 0 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0188 0.0078 0.3927 +0.0377 0.0156 0.3927 +0.0565 0.0234 0.3927 +0.0754 0.0312 0.3736 +0.0946 0.0379 0.2989 +0.1143 0.0432 0.2242 +0.1344 0.0470 0.1494 +0.1546 0.0492 0.0747 +0.1750 0.0500 0.0000 +primID: 5 +startangle_c: 1 +endpose_c: 0 0 2 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0000 0.0000 0.4363 +0.0000 0.0000 0.4800 +0.0000 0.0000 0.5236 +0.0000 0.0000 0.5672 +0.0000 0.0000 0.6109 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.6981 +0.0000 0.0000 0.7418 +0.0000 0.0000 0.7854 +primID: 6 +startangle_c: 1 +endpose_c: 0 0 0 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0000 0.0000 0.3491 +0.0000 0.0000 0.3054 +0.0000 0.0000 0.2618 +0.0000 0.0000 0.2182 +0.0000 0.0000 0.1745 +0.0000 0.0000 0.1309 +0.0000 0.0000 0.0873 +0.0000 0.0000 0.0436 +0.0000 0.0000 0.0000 +primID: 7 +startangle_c: 1 +endpose_c: -1 2 1 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.3927 +-0.0028 0.0056 0.3927 +-0.0056 0.0111 0.3927 +-0.0083 0.0167 0.3927 +-0.0111 0.0222 0.3927 +-0.0139 0.0278 0.3927 +-0.0167 0.0333 0.3927 +-0.0194 0.0389 0.3927 +-0.0222 0.0444 0.3927 +-0.0250 0.0500 0.3927 +primID: 8 +startangle_c: 1 +endpose_c: 1 -2 1 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0028 -0.0056 0.3927 +0.0056 -0.0111 0.3927 +0.0083 -0.0167 0.3927 +0.0111 -0.0222 0.3927 +0.0139 -0.0278 0.3927 +0.0167 -0.0333 0.3927 +0.0194 -0.0389 0.3927 +0.0222 -0.0444 0.3927 +0.0250 -0.0500 0.3927 +primID: 9 +startangle_c: 1 +endpose_c: -5 -4 2 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 0.3927 +-0.0149 -0.0092 0.4230 +-0.0296 -0.0189 0.4533 +-0.0440 -0.0291 0.4836 +-0.0582 -0.0398 0.5139 +-0.0722 -0.0509 0.5442 +-0.0858 -0.0625 0.5745 +-0.0992 -0.0746 0.6048 +-0.1123 -0.0871 0.6351 +-0.1250 -0.1000 0.6654 +primID: 10 +startangle_c: 1 +endpose_c: -7 -2 0 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 0.3927 +-0.0188 -0.0078 0.3927 +-0.0377 -0.0156 0.3927 +-0.0565 -0.0234 0.3927 +-0.0754 -0.0312 0.3736 +-0.0946 -0.0379 0.2989 +-0.1143 -0.0432 0.2242 +-0.1344 -0.0470 0.1494 +-0.1546 -0.0492 0.0747 +-0.1750 -0.0500 0.0000 +primID: 11 +startangle_c: 1 +endpose_c: 5 4 1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0139 0.0111 0.3927 +0.0278 0.0222 0.3927 +0.0417 0.0333 0.3927 +0.0556 0.0444 0.3927 +0.0694 0.0556 0.3927 +0.0833 0.0667 0.3927 +0.0972 0.0778 0.3927 +0.1111 0.0889 0.3927 +0.1250 0.1000 0.3927 +primID: 12 +startangle_c: 1 +endpose_c: 7 2 1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0194 0.0056 0.3927 +0.0389 0.0111 0.3927 +0.0583 0.0167 0.3927 +0.0778 0.0222 0.3927 +0.0972 0.0278 0.3927 +0.1167 0.0333 0.3927 +0.1361 0.0389 0.3927 +0.1556 0.0444 0.3927 +0.1750 0.0500 0.3927 +primID: 0 +startangle_c: 2 +endpose_c: 1 1 2 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0028 0.0028 0.7854 +0.0056 0.0056 0.7854 +0.0083 0.0083 0.7854 +0.0111 0.0111 0.7854 +0.0139 0.0139 0.7854 +0.0167 0.0167 0.7854 +0.0194 0.0194 0.7854 +0.0222 0.0222 0.7854 +0.0250 0.0250 0.7854 +primID: 1 +startangle_c: 2 +endpose_c: 6 6 2 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0167 0.0167 0.7854 +0.0333 0.0333 0.7854 +0.0500 0.0500 0.7854 +0.0667 0.0667 0.7854 +0.0833 0.0833 0.7854 +0.1000 0.1000 0.7854 +0.1167 0.1167 0.7854 +0.1333 0.1333 0.7854 +0.1500 0.1500 0.7854 +primID: 2 +startangle_c: 2 +endpose_c: -1 -1 2 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 0.7854 +-0.0028 -0.0028 0.7854 +-0.0056 -0.0056 0.7854 +-0.0083 -0.0083 0.7854 +-0.0111 -0.0111 0.7854 +-0.0139 -0.0139 0.7854 +-0.0167 -0.0167 0.7854 +-0.0194 -0.0194 0.7854 +-0.0222 -0.0222 0.7854 +-0.0250 -0.0250 0.7854 +primID: 3 +startangle_c: 2 +endpose_c: 5 7 3 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0170 0.0170 0.7854 +0.0339 0.0342 0.8151 +0.0500 0.0522 0.8669 +0.0651 0.0709 0.9188 +0.0792 0.0904 0.9707 +0.0923 0.1107 1.0225 +0.1043 0.1315 1.0744 +0.1152 0.1530 1.1262 +0.1250 0.1750 1.1781 +primID: 4 +startangle_c: 2 +endpose_c: 7 5 1 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0170 0.0170 0.7854 +0.0342 0.0339 0.7557 +0.0522 0.0500 0.7039 +0.0709 0.0651 0.6520 +0.0904 0.0792 0.6001 +0.1107 0.0923 0.5483 +0.1315 0.1043 0.4964 +0.1530 0.1152 0.4446 +0.1750 0.1250 0.3927 +primID: 5 +startangle_c: 2 +endpose_c: 0 0 3 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0000 0.0000 0.8290 +0.0000 0.0000 0.8727 +0.0000 0.0000 0.9163 +0.0000 0.0000 0.9599 +0.0000 0.0000 1.0036 +0.0000 0.0000 1.0472 +0.0000 0.0000 1.0908 +0.0000 0.0000 1.1345 +0.0000 0.0000 1.1781 +primID: 6 +startangle_c: 2 +endpose_c: 0 0 1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0000 0.0000 0.7418 +0.0000 0.0000 0.6981 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.6109 +0.0000 0.0000 0.5672 +0.0000 0.0000 0.5236 +0.0000 0.0000 0.4800 +0.0000 0.0000 0.4363 +0.0000 0.0000 0.3927 +primID: 7 +startangle_c: 2 +endpose_c: -1 1 2 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.7854 +-0.0028 0.0028 0.7854 +-0.0056 0.0056 0.7854 +-0.0083 0.0083 0.7854 +-0.0111 0.0111 0.7854 +-0.0139 0.0139 0.7854 +-0.0167 0.0167 0.7854 +-0.0194 0.0194 0.7854 +-0.0222 0.0222 0.7854 +-0.0250 0.0250 0.7854 +primID: 8 +startangle_c: 2 +endpose_c: 1 -1 2 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0028 -0.0028 0.7854 +0.0056 -0.0056 0.7854 +0.0083 -0.0083 0.7854 +0.0111 -0.0111 0.7854 +0.0139 -0.0139 0.7854 +0.0167 -0.0167 0.7854 +0.0194 -0.0194 0.7854 +0.0222 -0.0222 0.7854 +0.0250 -0.0250 0.7854 +primID: 9 +startangle_c: 2 +endpose_c: -5 -7 3 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 0.7854 +-0.0170 -0.0170 0.7854 +-0.0339 -0.0342 0.8151 +-0.0500 -0.0522 0.8669 +-0.0651 -0.0709 0.9188 +-0.0792 -0.0904 0.9707 +-0.0923 -0.1107 1.0225 +-0.1043 -0.1315 1.0744 +-0.1152 -0.1530 1.1262 +-0.1250 -0.1750 1.1781 +primID: 10 +startangle_c: 2 +endpose_c: -7 -5 1 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 0.7854 +-0.0170 -0.0170 0.7854 +-0.0342 -0.0339 0.7557 +-0.0522 -0.0500 0.7039 +-0.0709 -0.0651 0.6520 +-0.0904 -0.0792 0.6001 +-0.1107 -0.0923 0.5483 +-0.1315 -0.1043 0.4964 +-0.1530 -0.1152 0.4446 +-0.1750 -0.1250 0.3927 +primID: 11 +startangle_c: 2 +endpose_c: 5 7 2 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0139 0.0194 0.7854 +0.0278 0.0389 0.7854 +0.0417 0.0583 0.7854 +0.0556 0.0778 0.7854 +0.0694 0.0972 0.7854 +0.0833 0.1167 0.7854 +0.0972 0.1361 0.7854 +0.1111 0.1556 0.7854 +0.1250 0.1750 0.7854 +primID: 12 +startangle_c: 2 +endpose_c: 7 5 2 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0194 0.0139 0.7854 +0.0389 0.0278 0.7854 +0.0583 0.0417 0.7854 +0.0778 0.0556 0.7854 +0.0972 0.0694 0.7854 +0.1167 0.0833 0.7854 +0.1361 0.0972 0.7854 +0.1556 0.1111 0.7854 +0.1750 0.1250 0.7854 +primID: 0 +startangle_c: 3 +endpose_c: 1 2 3 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0028 0.0056 1.1781 +0.0056 0.0111 1.1781 +0.0083 0.0167 1.1781 +0.0111 0.0222 1.1781 +0.0139 0.0278 1.1781 +0.0167 0.0333 1.1781 +0.0194 0.0389 1.1781 +0.0222 0.0444 1.1781 +0.0250 0.0500 1.1781 +primID: 1 +startangle_c: 3 +endpose_c: 3 6 3 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0083 0.0167 1.1781 +0.0167 0.0333 1.1781 +0.0250 0.0500 1.1781 +0.0333 0.0667 1.1781 +0.0417 0.0833 1.1781 +0.0500 0.1000 1.1781 +0.0583 0.1167 1.1781 +0.0667 0.1333 1.1781 +0.0750 0.1500 1.1781 +primID: 2 +startangle_c: 3 +endpose_c: -1 -2 3 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 1.1781 +-0.0028 -0.0056 1.1781 +-0.0056 -0.0111 1.1781 +-0.0083 -0.0167 1.1781 +-0.0111 -0.0222 1.1781 +-0.0139 -0.0278 1.1781 +-0.0167 -0.0333 1.1781 +-0.0194 -0.0389 1.1781 +-0.0222 -0.0444 1.1781 +-0.0250 -0.0500 1.1781 +primID: 3 +startangle_c: 3 +endpose_c: 4 5 2 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0092 0.0149 1.1478 +0.0189 0.0296 1.1175 +0.0291 0.0440 1.0872 +0.0398 0.0582 1.0569 +0.0509 0.0722 1.0266 +0.0625 0.0858 0.9963 +0.0746 0.0992 0.9660 +0.0871 0.1123 0.9357 +0.1000 0.1250 0.9054 +primID: 4 +startangle_c: 3 +endpose_c: 2 7 4 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0078 0.0188 1.1781 +0.0156 0.0377 1.1781 +0.0234 0.0565 1.1781 +0.0312 0.0754 1.1972 +0.0379 0.0946 1.2719 +0.0432 0.1143 1.3466 +0.0470 0.1344 1.4214 +0.0492 0.1546 1.4961 +0.0500 0.1750 1.5708 +primID: 5 +startangle_c: 3 +endpose_c: 0 0 2 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0000 0.0000 1.1345 +0.0000 0.0000 1.0908 +0.0000 0.0000 1.0472 +0.0000 0.0000 1.0036 +0.0000 0.0000 0.9599 +0.0000 0.0000 0.9163 +0.0000 0.0000 0.8727 +0.0000 0.0000 0.8290 +0.0000 0.0000 0.7854 +primID: 6 +startangle_c: 3 +endpose_c: 0 0 4 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0000 0.0000 1.2217 +0.0000 0.0000 1.2654 +0.0000 0.0000 1.3090 +0.0000 0.0000 1.3526 +0.0000 0.0000 1.3963 +0.0000 0.0000 1.4399 +0.0000 0.0000 1.4835 +0.0000 0.0000 1.5272 +0.0000 0.0000 1.5708 +primID: 7 +startangle_c: 3 +endpose_c: 2 -1 3 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0056 -0.0028 1.1781 +0.0111 -0.0056 1.1781 +0.0167 -0.0083 1.1781 +0.0222 -0.0111 1.1781 +0.0278 -0.0139 1.1781 +0.0333 -0.0167 1.1781 +0.0389 -0.0194 1.1781 +0.0444 -0.0222 1.1781 +0.0500 -0.0250 1.1781 +primID: 8 +startangle_c: 3 +endpose_c: -2 1 3 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.1781 +-0.0056 0.0028 1.1781 +-0.0111 0.0056 1.1781 +-0.0167 0.0083 1.1781 +-0.0222 0.0111 1.1781 +-0.0278 0.0139 1.1781 +-0.0333 0.0167 1.1781 +-0.0389 0.0194 1.1781 +-0.0444 0.0222 1.1781 +-0.0500 0.0250 1.1781 +primID: 9 +startangle_c: 3 +endpose_c: -4 -5 2 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 1.1781 +-0.0092 -0.0149 1.1478 +-0.0189 -0.0296 1.1175 +-0.0291 -0.0440 1.0872 +-0.0398 -0.0582 1.0569 +-0.0509 -0.0722 1.0266 +-0.0625 -0.0858 0.9963 +-0.0746 -0.0992 0.9660 +-0.0871 -0.1123 0.9357 +-0.1000 -0.1250 0.9054 +primID: 10 +startangle_c: 3 +endpose_c: -2 -7 4 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 1.1781 +-0.0078 -0.0188 1.1781 +-0.0156 -0.0377 1.1781 +-0.0234 -0.0565 1.1781 +-0.0312 -0.0754 1.1972 +-0.0379 -0.0946 1.2719 +-0.0432 -0.1143 1.3466 +-0.0470 -0.1344 1.4214 +-0.0492 -0.1546 1.4961 +-0.0500 -0.1750 1.5708 +primID: 11 +startangle_c: 3 +endpose_c: 4 5 3 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0111 0.0139 1.1781 +0.0222 0.0278 1.1781 +0.0333 0.0417 1.1781 +0.0444 0.0556 1.1781 +0.0556 0.0694 1.1781 +0.0667 0.0833 1.1781 +0.0778 0.0972 1.1781 +0.0889 0.1111 1.1781 +0.1000 0.1250 1.1781 +primID: 12 +startangle_c: 3 +endpose_c: 2 7 3 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0056 0.0194 1.1781 +0.0111 0.0389 1.1781 +0.0167 0.0583 1.1781 +0.0222 0.0778 1.1781 +0.0278 0.0972 1.1781 +0.0333 0.1167 1.1781 +0.0389 0.1361 1.1781 +0.0444 0.1556 1.1781 +0.0500 0.1750 1.1781 +primID: 0 +startangle_c: 4 +endpose_c: 0 1 4 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0028 1.5708 +0.0000 0.0056 1.5708 +0.0000 0.0083 1.5708 +0.0000 0.0111 1.5708 +0.0000 0.0139 1.5708 +0.0000 0.0167 1.5708 +0.0000 0.0194 1.5708 +0.0000 0.0222 1.5708 +0.0000 0.0250 1.5708 +primID: 1 +startangle_c: 4 +endpose_c: 0 8 4 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0222 1.5708 +0.0000 0.0444 1.5708 +0.0000 0.0667 1.5708 +0.0000 0.0889 1.5708 +0.0000 0.1111 1.5708 +0.0000 0.1333 1.5708 +0.0000 0.1556 1.5708 +0.0000 0.1778 1.5708 +0.0000 0.2000 1.5708 +primID: 2 +startangle_c: 4 +endpose_c: 0 -1 4 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 -0.0028 1.5708 +0.0000 -0.0056 1.5708 +0.0000 -0.0083 1.5708 +0.0000 -0.0111 1.5708 +0.0000 -0.0139 1.5708 +0.0000 -0.0167 1.5708 +0.0000 -0.0194 1.5708 +0.0000 -0.0222 1.5708 +0.0000 -0.0250 1.5708 +primID: 3 +startangle_c: 4 +endpose_c: -1 8 5 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0226 1.5708 +0.0000 0.0452 1.5708 +0.0000 0.0678 1.5708 +-0.0004 0.0903 1.6196 +-0.0023 0.1128 1.6884 +-0.0057 0.1352 1.7572 +-0.0106 0.1572 1.8259 +-0.0171 0.1789 1.8947 +-0.0250 0.2000 1.9635 +primID: 4 +startangle_c: 4 +endpose_c: 1 8 3 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.5708 +-0.0000 0.0226 1.5708 +-0.0000 0.0452 1.5708 +-0.0000 0.0678 1.5708 +0.0004 0.0903 1.5220 +0.0023 0.1128 1.4532 +0.0057 0.1352 1.3844 +0.0106 0.1572 1.3156 +0.0171 0.1789 1.2469 +0.0250 0.2000 1.1781 +primID: 5 +startangle_c: 4 +endpose_c: 0 0 5 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0000 1.6144 +0.0000 0.0000 1.6581 +0.0000 0.0000 1.7017 +0.0000 0.0000 1.7453 +0.0000 0.0000 1.7890 +0.0000 0.0000 1.8326 +0.0000 0.0000 1.8762 +0.0000 0.0000 1.9199 +0.0000 0.0000 1.9635 +primID: 6 +startangle_c: 4 +endpose_c: 0 0 3 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0000 1.5272 +0.0000 0.0000 1.4835 +0.0000 0.0000 1.4399 +0.0000 0.0000 1.3963 +0.0000 0.0000 1.3526 +0.0000 0.0000 1.3090 +0.0000 0.0000 1.2654 +0.0000 0.0000 1.2217 +0.0000 0.0000 1.1781 +primID: 7 +startangle_c: 4 +endpose_c: -1 0 4 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.5708 +-0.0028 0.0000 1.5708 +-0.0056 0.0000 1.5708 +-0.0083 0.0000 1.5708 +-0.0111 0.0000 1.5708 +-0.0139 0.0000 1.5708 +-0.0167 0.0000 1.5708 +-0.0194 0.0000 1.5708 +-0.0222 0.0000 1.5708 +-0.0250 0.0000 1.5708 +primID: 8 +startangle_c: 4 +endpose_c: 1 0 4 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0028 0.0000 1.5708 +0.0056 0.0000 1.5708 +0.0083 0.0000 1.5708 +0.0111 0.0000 1.5708 +0.0139 0.0000 1.5708 +0.0167 0.0000 1.5708 +0.0194 0.0000 1.5708 +0.0222 0.0000 1.5708 +0.0250 0.0000 1.5708 +primID: 9 +startangle_c: 4 +endpose_c: 1 -8 5 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 1.5708 +-0.0000 -0.0226 1.5708 +-0.0000 -0.0452 1.5708 +-0.0000 -0.0678 1.5708 +0.0004 -0.0903 1.6196 +0.0023 -0.1128 1.6884 +0.0057 -0.1352 1.7572 +0.0106 -0.1572 1.8259 +0.0171 -0.1789 1.8947 +0.0250 -0.2000 1.9635 +primID: 10 +startangle_c: 4 +endpose_c: -1 -8 3 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 -0.0226 1.5708 +0.0000 -0.0452 1.5708 +0.0000 -0.0678 1.5708 +-0.0004 -0.0903 1.5220 +-0.0023 -0.1128 1.4532 +-0.0057 -0.1352 1.3844 +-0.0106 -0.1572 1.3156 +-0.0171 -0.1789 1.2469 +-0.0250 -0.2000 1.1781 +primID: 11 +startangle_c: 4 +endpose_c: -1 8 4 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.5708 +-0.0028 0.0222 1.5708 +-0.0056 0.0444 1.5708 +-0.0083 0.0667 1.5708 +-0.0111 0.0889 1.5708 +-0.0139 0.1111 1.5708 +-0.0167 0.1333 1.5708 +-0.0194 0.1556 1.5708 +-0.0222 0.1778 1.5708 +-0.0250 0.2000 1.5708 +primID: 12 +startangle_c: 4 +endpose_c: 1 8 4 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0028 0.0222 1.5708 +0.0056 0.0444 1.5708 +0.0083 0.0667 1.5708 +0.0111 0.0889 1.5708 +0.0139 0.1111 1.5708 +0.0167 0.1333 1.5708 +0.0194 0.1556 1.5708 +0.0222 0.1778 1.5708 +0.0250 0.2000 1.5708 +primID: 0 +startangle_c: 5 +endpose_c: -1 2 5 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0028 0.0056 1.9635 +-0.0056 0.0111 1.9635 +-0.0083 0.0167 1.9635 +-0.0111 0.0222 1.9635 +-0.0139 0.0278 1.9635 +-0.0167 0.0333 1.9635 +-0.0194 0.0389 1.9635 +-0.0222 0.0444 1.9635 +-0.0250 0.0500 1.9635 +primID: 1 +startangle_c: 5 +endpose_c: -3 6 5 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0083 0.0167 1.9635 +-0.0167 0.0333 1.9635 +-0.0250 0.0500 1.9635 +-0.0333 0.0667 1.9635 +-0.0417 0.0833 1.9635 +-0.0500 0.1000 1.9635 +-0.0583 0.1167 1.9635 +-0.0667 0.1333 1.9635 +-0.0750 0.1500 1.9635 +primID: 2 +startangle_c: 5 +endpose_c: 1 -2 5 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0028 -0.0056 1.9635 +0.0056 -0.0111 1.9635 +0.0083 -0.0167 1.9635 +0.0111 -0.0222 1.9635 +0.0139 -0.0278 1.9635 +0.0167 -0.0333 1.9635 +0.0194 -0.0389 1.9635 +0.0222 -0.0444 1.9635 +0.0250 -0.0500 1.9635 +primID: 3 +startangle_c: 5 +endpose_c: -4 5 6 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0092 0.0149 1.9938 +-0.0189 0.0296 2.0241 +-0.0291 0.0440 2.0544 +-0.0398 0.0582 2.0847 +-0.0509 0.0722 2.1150 +-0.0625 0.0858 2.1453 +-0.0746 0.0992 2.1756 +-0.0871 0.1123 2.2059 +-0.1000 0.1250 2.2362 +primID: 4 +startangle_c: 5 +endpose_c: -2 7 4 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0078 0.0188 1.9635 +-0.0156 0.0377 1.9635 +-0.0234 0.0565 1.9635 +-0.0312 0.0754 1.9444 +-0.0379 0.0946 1.8697 +-0.0432 0.1143 1.7950 +-0.0470 0.1344 1.7202 +-0.0492 0.1546 1.6455 +-0.0500 0.1750 1.5708 +primID: 5 +startangle_c: 5 +endpose_c: 0 0 6 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0000 0.0000 2.0071 +0.0000 0.0000 2.0508 +0.0000 0.0000 2.0944 +0.0000 0.0000 2.1380 +0.0000 0.0000 2.1817 +0.0000 0.0000 2.2253 +0.0000 0.0000 2.2689 +0.0000 0.0000 2.3126 +0.0000 0.0000 2.3562 +primID: 6 +startangle_c: 5 +endpose_c: 0 0 4 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0000 0.0000 1.9199 +0.0000 0.0000 1.8762 +0.0000 0.0000 1.8326 +0.0000 0.0000 1.7890 +0.0000 0.0000 1.7453 +0.0000 0.0000 1.7017 +0.0000 0.0000 1.6581 +0.0000 0.0000 1.6144 +0.0000 0.0000 1.5708 +primID: 7 +startangle_c: 5 +endpose_c: -2 -1 5 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0056 -0.0028 1.9635 +-0.0111 -0.0056 1.9635 +-0.0167 -0.0083 1.9635 +-0.0222 -0.0111 1.9635 +-0.0278 -0.0139 1.9635 +-0.0333 -0.0167 1.9635 +-0.0389 -0.0194 1.9635 +-0.0444 -0.0222 1.9635 +-0.0500 -0.0250 1.9635 +primID: 8 +startangle_c: 5 +endpose_c: 2 1 5 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0056 0.0028 1.9635 +0.0111 0.0056 1.9635 +0.0167 0.0083 1.9635 +0.0222 0.0111 1.9635 +0.0278 0.0139 1.9635 +0.0333 0.0167 1.9635 +0.0389 0.0194 1.9635 +0.0444 0.0222 1.9635 +0.0500 0.0250 1.9635 +primID: 9 +startangle_c: 5 +endpose_c: 4 -5 6 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0092 -0.0149 1.9938 +0.0189 -0.0296 2.0241 +0.0291 -0.0440 2.0544 +0.0398 -0.0582 2.0847 +0.0509 -0.0722 2.1150 +0.0625 -0.0858 2.1453 +0.0746 -0.0992 2.1756 +0.0871 -0.1123 2.2059 +0.1000 -0.1250 2.2362 +primID: 10 +startangle_c: 5 +endpose_c: 2 -7 4 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0078 -0.0188 1.9635 +0.0156 -0.0377 1.9635 +0.0234 -0.0565 1.9635 +0.0312 -0.0754 1.9444 +0.0379 -0.0946 1.8697 +0.0432 -0.1143 1.7950 +0.0470 -0.1344 1.7202 +0.0492 -0.1546 1.6455 +0.0500 -0.1750 1.5708 +primID: 11 +startangle_c: 5 +endpose_c: -4 5 5 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0111 0.0139 1.9635 +-0.0222 0.0278 1.9635 +-0.0333 0.0417 1.9635 +-0.0444 0.0556 1.9635 +-0.0556 0.0694 1.9635 +-0.0667 0.0833 1.9635 +-0.0778 0.0972 1.9635 +-0.0889 0.1111 1.9635 +-0.1000 0.1250 1.9635 +primID: 12 +startangle_c: 5 +endpose_c: -2 7 5 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0056 0.0194 1.9635 +-0.0111 0.0389 1.9635 +-0.0167 0.0583 1.9635 +-0.0222 0.0778 1.9635 +-0.0278 0.0972 1.9635 +-0.0333 0.1167 1.9635 +-0.0389 0.1361 1.9635 +-0.0444 0.1556 1.9635 +-0.0500 0.1750 1.9635 +primID: 0 +startangle_c: 6 +endpose_c: -1 1 6 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0028 0.0028 2.3562 +-0.0056 0.0056 2.3562 +-0.0083 0.0083 2.3562 +-0.0111 0.0111 2.3562 +-0.0139 0.0139 2.3562 +-0.0167 0.0167 2.3562 +-0.0194 0.0194 2.3562 +-0.0222 0.0222 2.3562 +-0.0250 0.0250 2.3562 +primID: 1 +startangle_c: 6 +endpose_c: -6 6 6 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0167 0.0167 2.3562 +-0.0333 0.0333 2.3562 +-0.0500 0.0500 2.3562 +-0.0667 0.0667 2.3562 +-0.0833 0.0833 2.3562 +-0.1000 0.1000 2.3562 +-0.1167 0.1167 2.3562 +-0.1333 0.1333 2.3562 +-0.1500 0.1500 2.3562 +primID: 2 +startangle_c: 6 +endpose_c: 1 -1 6 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0028 -0.0028 2.3562 +0.0056 -0.0056 2.3562 +0.0083 -0.0083 2.3562 +0.0111 -0.0111 2.3562 +0.0139 -0.0139 2.3562 +0.0167 -0.0167 2.3562 +0.0194 -0.0194 2.3562 +0.0222 -0.0222 2.3562 +0.0250 -0.0250 2.3562 +primID: 3 +startangle_c: 6 +endpose_c: -7 5 7 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0170 0.0170 2.3562 +-0.0342 0.0339 2.3859 +-0.0522 0.0500 2.4377 +-0.0709 0.0651 2.4896 +-0.0904 0.0792 2.5415 +-0.1107 0.0923 2.5933 +-0.1315 0.1043 2.6452 +-0.1530 0.1152 2.6970 +-0.1750 0.1250 2.7489 +primID: 4 +startangle_c: 6 +endpose_c: -5 7 5 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0170 0.0170 2.3562 +-0.0339 0.0342 2.3265 +-0.0500 0.0522 2.2747 +-0.0651 0.0709 2.2228 +-0.0792 0.0904 2.1709 +-0.0923 0.1107 2.1191 +-0.1043 0.1315 2.0672 +-0.1152 0.1530 2.0154 +-0.1250 0.1750 1.9635 +primID: 5 +startangle_c: 6 +endpose_c: 0 0 7 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0000 0.0000 2.3998 +0.0000 0.0000 2.4435 +0.0000 0.0000 2.4871 +0.0000 0.0000 2.5307 +0.0000 0.0000 2.5744 +0.0000 0.0000 2.6180 +0.0000 0.0000 2.6616 +0.0000 0.0000 2.7053 +0.0000 0.0000 2.7489 +primID: 6 +startangle_c: 6 +endpose_c: 0 0 5 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0000 0.0000 2.3126 +0.0000 0.0000 2.2689 +0.0000 0.0000 2.2253 +0.0000 0.0000 2.1817 +0.0000 0.0000 2.1380 +0.0000 0.0000 2.0944 +0.0000 0.0000 2.0508 +0.0000 0.0000 2.0071 +0.0000 0.0000 1.9635 +primID: 7 +startangle_c: 6 +endpose_c: -1 -1 6 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0028 -0.0028 2.3562 +-0.0056 -0.0056 2.3562 +-0.0083 -0.0083 2.3562 +-0.0111 -0.0111 2.3562 +-0.0139 -0.0139 2.3562 +-0.0167 -0.0167 2.3562 +-0.0194 -0.0194 2.3562 +-0.0222 -0.0222 2.3562 +-0.0250 -0.0250 2.3562 +primID: 8 +startangle_c: 6 +endpose_c: 1 1 6 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0028 0.0028 2.3562 +0.0056 0.0056 2.3562 +0.0083 0.0083 2.3562 +0.0111 0.0111 2.3562 +0.0139 0.0139 2.3562 +0.0167 0.0167 2.3562 +0.0194 0.0194 2.3562 +0.0222 0.0222 2.3562 +0.0250 0.0250 2.3562 +primID: 9 +startangle_c: 6 +endpose_c: 7 -5 7 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0170 -0.0170 2.3562 +0.0342 -0.0339 2.3859 +0.0522 -0.0500 2.4377 +0.0709 -0.0651 2.4896 +0.0904 -0.0792 2.5415 +0.1107 -0.0923 2.5933 +0.1315 -0.1043 2.6452 +0.1530 -0.1152 2.6970 +0.1750 -0.1250 2.7489 +primID: 10 +startangle_c: 6 +endpose_c: 5 -7 5 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0170 -0.0170 2.3562 +0.0339 -0.0342 2.3265 +0.0500 -0.0522 2.2747 +0.0651 -0.0709 2.2228 +0.0792 -0.0904 2.1709 +0.0923 -0.1107 2.1191 +0.1043 -0.1315 2.0672 +0.1152 -0.1530 2.0154 +0.1250 -0.1750 1.9635 +primID: 11 +startangle_c: 6 +endpose_c: -7 5 6 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0194 0.0139 2.3562 +-0.0389 0.0278 2.3562 +-0.0583 0.0417 2.3562 +-0.0778 0.0556 2.3562 +-0.0972 0.0694 2.3562 +-0.1167 0.0833 2.3562 +-0.1361 0.0972 2.3562 +-0.1556 0.1111 2.3562 +-0.1750 0.1250 2.3562 +primID: 12 +startangle_c: 6 +endpose_c: -5 7 6 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0139 0.0194 2.3562 +-0.0278 0.0389 2.3562 +-0.0417 0.0583 2.3562 +-0.0556 0.0778 2.3562 +-0.0694 0.0972 2.3562 +-0.0833 0.1167 2.3562 +-0.0972 0.1361 2.3562 +-0.1111 0.1556 2.3562 +-0.1250 0.1750 2.3562 +primID: 0 +startangle_c: 7 +endpose_c: -2 1 7 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0056 0.0028 2.7489 +-0.0111 0.0056 2.7489 +-0.0167 0.0083 2.7489 +-0.0222 0.0111 2.7489 +-0.0278 0.0139 2.7489 +-0.0333 0.0167 2.7489 +-0.0389 0.0194 2.7489 +-0.0444 0.0222 2.7489 +-0.0500 0.0250 2.7489 +primID: 1 +startangle_c: 7 +endpose_c: -6 3 7 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0167 0.0083 2.7489 +-0.0333 0.0167 2.7489 +-0.0500 0.0250 2.7489 +-0.0667 0.0333 2.7489 +-0.0833 0.0417 2.7489 +-0.1000 0.0500 2.7489 +-0.1167 0.0583 2.7489 +-0.1333 0.0667 2.7489 +-0.1500 0.0750 2.7489 +primID: 2 +startangle_c: 7 +endpose_c: 2 -1 7 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0056 -0.0028 2.7489 +0.0111 -0.0056 2.7489 +0.0167 -0.0083 2.7489 +0.0222 -0.0111 2.7489 +0.0278 -0.0139 2.7489 +0.0333 -0.0167 2.7489 +0.0389 -0.0194 2.7489 +0.0444 -0.0222 2.7489 +0.0500 -0.0250 2.7489 +primID: 3 +startangle_c: 7 +endpose_c: -5 4 6 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0149 0.0092 2.7186 +-0.0296 0.0189 2.6883 +-0.0440 0.0291 2.6580 +-0.0582 0.0398 2.6277 +-0.0722 0.0509 2.5974 +-0.0858 0.0625 2.5671 +-0.0992 0.0746 2.5368 +-0.1123 0.0871 2.5065 +-0.1250 0.1000 2.4762 +primID: 4 +startangle_c: 7 +endpose_c: -7 2 8 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0188 0.0078 2.7489 +-0.0377 0.0156 2.7489 +-0.0565 0.0234 2.7489 +-0.0754 0.0312 2.7680 +-0.0946 0.0379 2.8427 +-0.1143 0.0432 2.9174 +-0.1344 0.0470 2.9921 +-0.1546 0.0492 3.0669 +-0.1750 0.0500 3.1416 +primID: 5 +startangle_c: 7 +endpose_c: 0 0 6 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0000 0.0000 2.7053 +0.0000 0.0000 2.6616 +0.0000 0.0000 2.6180 +0.0000 0.0000 2.5744 +0.0000 0.0000 2.5307 +0.0000 0.0000 2.4871 +0.0000 0.0000 2.4435 +0.0000 0.0000 2.3998 +0.0000 0.0000 2.3562 +primID: 6 +startangle_c: 7 +endpose_c: 0 0 8 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0000 0.0000 2.7925 +0.0000 0.0000 2.8362 +0.0000 0.0000 2.8798 +0.0000 0.0000 2.9234 +0.0000 0.0000 2.9671 +0.0000 0.0000 3.0107 +0.0000 0.0000 3.0543 +0.0000 0.0000 3.0980 +0.0000 0.0000 3.1416 +primID: 7 +startangle_c: 7 +endpose_c: 1 2 7 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0028 0.0056 2.7489 +0.0056 0.0111 2.7489 +0.0083 0.0167 2.7489 +0.0111 0.0222 2.7489 +0.0139 0.0278 2.7489 +0.0167 0.0333 2.7489 +0.0194 0.0389 2.7489 +0.0222 0.0444 2.7489 +0.0250 0.0500 2.7489 +primID: 8 +startangle_c: 7 +endpose_c: -1 -2 7 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0028 -0.0056 2.7489 +-0.0056 -0.0111 2.7489 +-0.0083 -0.0167 2.7489 +-0.0111 -0.0222 2.7489 +-0.0139 -0.0278 2.7489 +-0.0167 -0.0333 2.7489 +-0.0194 -0.0389 2.7489 +-0.0222 -0.0444 2.7489 +-0.0250 -0.0500 2.7489 +primID: 9 +startangle_c: 7 +endpose_c: 5 -4 6 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0149 -0.0092 2.7186 +0.0296 -0.0189 2.6883 +0.0440 -0.0291 2.6580 +0.0582 -0.0398 2.6277 +0.0722 -0.0509 2.5974 +0.0858 -0.0625 2.5671 +0.0992 -0.0746 2.5368 +0.1123 -0.0871 2.5065 +0.1250 -0.1000 2.4762 +primID: 10 +startangle_c: 7 +endpose_c: 7 -2 8 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0188 -0.0078 2.7489 +0.0377 -0.0156 2.7489 +0.0565 -0.0234 2.7489 +0.0754 -0.0312 2.7680 +0.0946 -0.0379 2.8427 +0.1143 -0.0432 2.9174 +0.1344 -0.0470 2.9921 +0.1546 -0.0492 3.0669 +0.1750 -0.0500 3.1416 +primID: 11 +startangle_c: 7 +endpose_c: -5 4 7 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0139 0.0111 2.7489 +-0.0278 0.0222 2.7489 +-0.0417 0.0333 2.7489 +-0.0556 0.0444 2.7489 +-0.0694 0.0556 2.7489 +-0.0833 0.0667 2.7489 +-0.0972 0.0778 2.7489 +-0.1111 0.0889 2.7489 +-0.1250 0.1000 2.7489 +primID: 12 +startangle_c: 7 +endpose_c: -7 2 7 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0194 0.0056 2.7489 +-0.0389 0.0111 2.7489 +-0.0583 0.0167 2.7489 +-0.0778 0.0222 2.7489 +-0.0972 0.0278 2.7489 +-0.1167 0.0333 2.7489 +-0.1361 0.0389 2.7489 +-0.1556 0.0444 2.7489 +-0.1750 0.0500 2.7489 +primID: 0 +startangle_c: 8 +endpose_c: -1 0 8 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0028 0.0000 3.1416 +-0.0056 0.0000 3.1416 +-0.0083 0.0000 3.1416 +-0.0111 0.0000 3.1416 +-0.0139 0.0000 3.1416 +-0.0167 0.0000 3.1416 +-0.0194 0.0000 3.1416 +-0.0222 0.0000 3.1416 +-0.0250 0.0000 3.1416 +primID: 1 +startangle_c: 8 +endpose_c: -8 0 8 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0222 0.0000 3.1416 +-0.0444 0.0000 3.1416 +-0.0667 0.0000 3.1416 +-0.0889 0.0000 3.1416 +-0.1111 0.0000 3.1416 +-0.1333 0.0000 3.1416 +-0.1556 0.0000 3.1416 +-0.1778 0.0000 3.1416 +-0.2000 0.0000 3.1416 +primID: 2 +startangle_c: 8 +endpose_c: 1 0 8 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0028 0.0000 3.1416 +0.0056 0.0000 3.1416 +0.0083 0.0000 3.1416 +0.0111 0.0000 3.1416 +0.0139 0.0000 3.1416 +0.0167 0.0000 3.1416 +0.0194 0.0000 3.1416 +0.0222 0.0000 3.1416 +0.0250 0.0000 3.1416 +primID: 3 +startangle_c: 8 +endpose_c: -8 -1 9 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0226 0.0000 3.1416 +-0.0452 0.0000 3.1416 +-0.0678 0.0000 3.1416 +-0.0903 -0.0004 3.1904 +-0.1128 -0.0023 3.2592 +-0.1352 -0.0057 3.3280 +-0.1572 -0.0106 3.3967 +-0.1789 -0.0171 3.4655 +-0.2000 -0.0250 3.5343 +primID: 4 +startangle_c: 8 +endpose_c: -8 1 7 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0226 0.0000 3.1416 +-0.0452 0.0000 3.1416 +-0.0678 0.0000 3.1416 +-0.0903 0.0004 3.0928 +-0.1128 0.0023 3.0240 +-0.1352 0.0057 2.9552 +-0.1572 0.0106 2.8864 +-0.1789 0.0171 2.8177 +-0.2000 0.0250 2.7489 +primID: 5 +startangle_c: 8 +endpose_c: 0 0 9 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0000 0.0000 3.1852 +0.0000 0.0000 3.2289 +0.0000 0.0000 3.2725 +0.0000 0.0000 3.3161 +0.0000 0.0000 3.3598 +0.0000 0.0000 3.4034 +0.0000 0.0000 3.4470 +0.0000 0.0000 3.4907 +0.0000 0.0000 3.5343 +primID: 6 +startangle_c: 8 +endpose_c: 0 0 7 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0000 0.0000 3.0980 +0.0000 0.0000 3.0543 +0.0000 0.0000 3.0107 +0.0000 0.0000 2.9671 +0.0000 0.0000 2.9234 +0.0000 0.0000 2.8798 +0.0000 0.0000 2.8362 +0.0000 0.0000 2.7925 +0.0000 0.0000 2.7489 +primID: 7 +startangle_c: 8 +endpose_c: 0 -1 8 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0000 -0.0028 3.1416 +0.0000 -0.0056 3.1416 +0.0000 -0.0083 3.1416 +0.0000 -0.0111 3.1416 +0.0000 -0.0139 3.1416 +0.0000 -0.0167 3.1416 +0.0000 -0.0194 3.1416 +0.0000 -0.0222 3.1416 +0.0000 -0.0250 3.1416 +primID: 8 +startangle_c: 8 +endpose_c: 0 1 8 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0000 0.0028 3.1416 +0.0000 0.0056 3.1416 +0.0000 0.0083 3.1416 +0.0000 0.0111 3.1416 +0.0000 0.0139 3.1416 +0.0000 0.0167 3.1416 +0.0000 0.0194 3.1416 +0.0000 0.0222 3.1416 +0.0000 0.0250 3.1416 +primID: 9 +startangle_c: 8 +endpose_c: 8 1 9 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0226 -0.0000 3.1416 +0.0452 -0.0000 3.1416 +0.0678 -0.0000 3.1416 +0.0903 0.0004 3.1904 +0.1128 0.0023 3.2592 +0.1352 0.0057 3.3280 +0.1572 0.0106 3.3967 +0.1789 0.0171 3.4655 +0.2000 0.0250 3.5343 +primID: 10 +startangle_c: 8 +endpose_c: 8 -1 7 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0226 -0.0000 3.1416 +0.0452 -0.0000 3.1416 +0.0678 -0.0000 3.1416 +0.0903 -0.0004 3.0928 +0.1128 -0.0023 3.0240 +0.1352 -0.0057 2.9552 +0.1572 -0.0106 2.8864 +0.1789 -0.0171 2.8177 +0.2000 -0.0250 2.7489 +primID: 11 +startangle_c: 8 +endpose_c: -8 -1 8 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0222 -0.0028 3.1416 +-0.0444 -0.0056 3.1416 +-0.0667 -0.0083 3.1416 +-0.0889 -0.0111 3.1416 +-0.1111 -0.0139 3.1416 +-0.1333 -0.0167 3.1416 +-0.1556 -0.0194 3.1416 +-0.1778 -0.0222 3.1416 +-0.2000 -0.0250 3.1416 +primID: 12 +startangle_c: 8 +endpose_c: -8 1 8 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0222 0.0028 3.1416 +-0.0444 0.0056 3.1416 +-0.0667 0.0083 3.1416 +-0.0889 0.0111 3.1416 +-0.1111 0.0139 3.1416 +-0.1333 0.0167 3.1416 +-0.1556 0.0194 3.1416 +-0.1778 0.0222 3.1416 +-0.2000 0.0250 3.1416 +primID: 0 +startangle_c: 9 +endpose_c: -2 -1 9 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0056 -0.0028 3.5343 +-0.0111 -0.0056 3.5343 +-0.0167 -0.0083 3.5343 +-0.0222 -0.0111 3.5343 +-0.0278 -0.0139 3.5343 +-0.0333 -0.0167 3.5343 +-0.0389 -0.0194 3.5343 +-0.0444 -0.0222 3.5343 +-0.0500 -0.0250 3.5343 +primID: 1 +startangle_c: 9 +endpose_c: -6 -3 9 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0167 -0.0083 3.5343 +-0.0333 -0.0167 3.5343 +-0.0500 -0.0250 3.5343 +-0.0667 -0.0333 3.5343 +-0.0833 -0.0417 3.5343 +-0.1000 -0.0500 3.5343 +-0.1167 -0.0583 3.5343 +-0.1333 -0.0667 3.5343 +-0.1500 -0.0750 3.5343 +primID: 2 +startangle_c: 9 +endpose_c: 2 1 9 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0056 0.0028 3.5343 +0.0111 0.0056 3.5343 +0.0167 0.0083 3.5343 +0.0222 0.0111 3.5343 +0.0278 0.0139 3.5343 +0.0333 0.0167 3.5343 +0.0389 0.0194 3.5343 +0.0444 0.0222 3.5343 +0.0500 0.0250 3.5343 +primID: 3 +startangle_c: 9 +endpose_c: -5 -4 10 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0149 -0.0092 3.5646 +-0.0296 -0.0189 3.5949 +-0.0440 -0.0291 3.6252 +-0.0582 -0.0398 3.6555 +-0.0722 -0.0509 3.6858 +-0.0858 -0.0625 3.7161 +-0.0992 -0.0746 3.7464 +-0.1123 -0.0871 3.7767 +-0.1250 -0.1000 3.8070 +primID: 4 +startangle_c: 9 +endpose_c: -7 -2 8 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0188 -0.0078 3.5343 +-0.0377 -0.0156 3.5343 +-0.0565 -0.0234 3.5343 +-0.0754 -0.0312 3.5152 +-0.0946 -0.0379 3.4405 +-0.1143 -0.0432 3.3658 +-0.1344 -0.0470 3.2910 +-0.1546 -0.0492 3.2163 +-0.1750 -0.0500 3.1416 +primID: 5 +startangle_c: 9 +endpose_c: 0 0 10 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0000 0.0000 3.5779 +0.0000 0.0000 3.6216 +0.0000 0.0000 3.6652 +0.0000 0.0000 3.7088 +0.0000 0.0000 3.7525 +0.0000 0.0000 3.7961 +0.0000 0.0000 3.8397 +0.0000 0.0000 3.8834 +0.0000 0.0000 3.9270 +primID: 6 +startangle_c: 9 +endpose_c: 0 0 8 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0000 0.0000 3.4907 +0.0000 0.0000 3.4470 +0.0000 0.0000 3.4034 +0.0000 0.0000 3.3598 +0.0000 0.0000 3.3161 +0.0000 0.0000 3.2725 +0.0000 0.0000 3.2289 +0.0000 0.0000 3.1852 +0.0000 0.0000 3.1416 +primID: 7 +startangle_c: 9 +endpose_c: 1 -2 9 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0028 -0.0056 3.5343 +0.0056 -0.0111 3.5343 +0.0083 -0.0167 3.5343 +0.0111 -0.0222 3.5343 +0.0139 -0.0278 3.5343 +0.0167 -0.0333 3.5343 +0.0194 -0.0389 3.5343 +0.0222 -0.0444 3.5343 +0.0250 -0.0500 3.5343 +primID: 8 +startangle_c: 9 +endpose_c: -1 2 9 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0028 0.0056 3.5343 +-0.0056 0.0111 3.5343 +-0.0083 0.0167 3.5343 +-0.0111 0.0222 3.5343 +-0.0139 0.0278 3.5343 +-0.0167 0.0333 3.5343 +-0.0194 0.0389 3.5343 +-0.0222 0.0444 3.5343 +-0.0250 0.0500 3.5343 +primID: 9 +startangle_c: 9 +endpose_c: 5 4 10 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0149 0.0092 3.5646 +0.0296 0.0189 3.5949 +0.0440 0.0291 3.6252 +0.0582 0.0398 3.6555 +0.0722 0.0509 3.6858 +0.0858 0.0625 3.7161 +0.0992 0.0746 3.7464 +0.1123 0.0871 3.7767 +0.1250 0.1000 3.8070 +primID: 10 +startangle_c: 9 +endpose_c: 7 2 8 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0188 0.0078 3.5343 +0.0377 0.0156 3.5343 +0.0565 0.0234 3.5343 +0.0754 0.0312 3.5152 +0.0946 0.0379 3.4405 +0.1143 0.0432 3.3658 +0.1344 0.0470 3.2910 +0.1546 0.0492 3.2163 +0.1750 0.0500 3.1416 +primID: 11 +startangle_c: 9 +endpose_c: -5 -4 9 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0139 -0.0111 3.5343 +-0.0278 -0.0222 3.5343 +-0.0417 -0.0333 3.5343 +-0.0556 -0.0444 3.5343 +-0.0694 -0.0556 3.5343 +-0.0833 -0.0667 3.5343 +-0.0972 -0.0778 3.5343 +-0.1111 -0.0889 3.5343 +-0.1250 -0.1000 3.5343 +primID: 12 +startangle_c: 9 +endpose_c: -7 -2 9 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0194 -0.0056 3.5343 +-0.0389 -0.0111 3.5343 +-0.0583 -0.0167 3.5343 +-0.0778 -0.0222 3.5343 +-0.0972 -0.0278 3.5343 +-0.1167 -0.0333 3.5343 +-0.1361 -0.0389 3.5343 +-0.1556 -0.0444 3.5343 +-0.1750 -0.0500 3.5343 +primID: 0 +startangle_c: 10 +endpose_c: -1 -1 10 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0028 -0.0028 3.9270 +-0.0056 -0.0056 3.9270 +-0.0083 -0.0083 3.9270 +-0.0111 -0.0111 3.9270 +-0.0139 -0.0139 3.9270 +-0.0167 -0.0167 3.9270 +-0.0194 -0.0194 3.9270 +-0.0222 -0.0222 3.9270 +-0.0250 -0.0250 3.9270 +primID: 1 +startangle_c: 10 +endpose_c: -6 -6 10 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0167 -0.0167 3.9270 +-0.0333 -0.0333 3.9270 +-0.0500 -0.0500 3.9270 +-0.0667 -0.0667 3.9270 +-0.0833 -0.0833 3.9270 +-0.1000 -0.1000 3.9270 +-0.1167 -0.1167 3.9270 +-0.1333 -0.1333 3.9270 +-0.1500 -0.1500 3.9270 +primID: 2 +startangle_c: 10 +endpose_c: 1 1 10 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0028 0.0028 3.9270 +0.0056 0.0056 3.9270 +0.0083 0.0083 3.9270 +0.0111 0.0111 3.9270 +0.0139 0.0139 3.9270 +0.0167 0.0167 3.9270 +0.0194 0.0194 3.9270 +0.0222 0.0222 3.9270 +0.0250 0.0250 3.9270 +primID: 3 +startangle_c: 10 +endpose_c: -5 -7 11 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0170 -0.0170 3.9270 +-0.0339 -0.0342 3.9567 +-0.0500 -0.0522 4.0085 +-0.0651 -0.0709 4.0604 +-0.0792 -0.0904 4.1123 +-0.0923 -0.1107 4.1641 +-0.1043 -0.1315 4.2160 +-0.1152 -0.1530 4.2678 +-0.1250 -0.1750 4.3197 +primID: 4 +startangle_c: 10 +endpose_c: -7 -5 9 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0170 -0.0170 3.9270 +-0.0342 -0.0339 3.8973 +-0.0522 -0.0500 3.8455 +-0.0709 -0.0651 3.7936 +-0.0904 -0.0792 3.7417 +-0.1107 -0.0923 3.6899 +-0.1315 -0.1043 3.6380 +-0.1530 -0.1152 3.5862 +-0.1750 -0.1250 3.5343 +primID: 5 +startangle_c: 10 +endpose_c: 0 0 11 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.9706 +0.0000 0.0000 4.0143 +0.0000 0.0000 4.0579 +0.0000 0.0000 4.1015 +0.0000 0.0000 4.1452 +0.0000 0.0000 4.1888 +0.0000 0.0000 4.2324 +0.0000 0.0000 4.2761 +0.0000 0.0000 4.3197 +primID: 6 +startangle_c: 10 +endpose_c: 0 0 9 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.8834 +0.0000 0.0000 3.8397 +0.0000 0.0000 3.7961 +0.0000 0.0000 3.7525 +0.0000 0.0000 3.7088 +0.0000 0.0000 3.6652 +0.0000 0.0000 3.6216 +0.0000 0.0000 3.5779 +0.0000 0.0000 3.5343 +primID: 7 +startangle_c: 10 +endpose_c: 1 -1 10 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0028 -0.0028 3.9270 +0.0056 -0.0056 3.9270 +0.0083 -0.0083 3.9270 +0.0111 -0.0111 3.9270 +0.0139 -0.0139 3.9270 +0.0167 -0.0167 3.9270 +0.0194 -0.0194 3.9270 +0.0222 -0.0222 3.9270 +0.0250 -0.0250 3.9270 +primID: 8 +startangle_c: 10 +endpose_c: -1 1 10 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0028 0.0028 3.9270 +-0.0056 0.0056 3.9270 +-0.0083 0.0083 3.9270 +-0.0111 0.0111 3.9270 +-0.0139 0.0139 3.9270 +-0.0167 0.0167 3.9270 +-0.0194 0.0194 3.9270 +-0.0222 0.0222 3.9270 +-0.0250 0.0250 3.9270 +primID: 9 +startangle_c: 10 +endpose_c: 5 7 11 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0170 0.0170 3.9270 +0.0339 0.0342 3.9567 +0.0500 0.0522 4.0085 +0.0651 0.0709 4.0604 +0.0792 0.0904 4.1123 +0.0923 0.1107 4.1641 +0.1043 0.1315 4.2160 +0.1152 0.1530 4.2678 +0.1250 0.1750 4.3197 +primID: 10 +startangle_c: 10 +endpose_c: 7 5 9 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0170 0.0170 3.9270 +0.0342 0.0339 3.8973 +0.0522 0.0500 3.8455 +0.0709 0.0651 3.7936 +0.0904 0.0792 3.7417 +0.1107 0.0923 3.6899 +0.1315 0.1043 3.6380 +0.1530 0.1152 3.5862 +0.1750 0.1250 3.5343 +primID: 11 +startangle_c: 10 +endpose_c: -5 -7 10 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0139 -0.0194 3.9270 +-0.0278 -0.0389 3.9270 +-0.0417 -0.0583 3.9270 +-0.0556 -0.0778 3.9270 +-0.0694 -0.0972 3.9270 +-0.0833 -0.1167 3.9270 +-0.0972 -0.1361 3.9270 +-0.1111 -0.1556 3.9270 +-0.1250 -0.1750 3.9270 +primID: 12 +startangle_c: 10 +endpose_c: -7 -5 10 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0194 -0.0139 3.9270 +-0.0389 -0.0278 3.9270 +-0.0583 -0.0417 3.9270 +-0.0778 -0.0556 3.9270 +-0.0972 -0.0694 3.9270 +-0.1167 -0.0833 3.9270 +-0.1361 -0.0972 3.9270 +-0.1556 -0.1111 3.9270 +-0.1750 -0.1250 3.9270 +primID: 0 +startangle_c: 11 +endpose_c: -1 -2 11 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0028 -0.0056 4.3197 +-0.0056 -0.0111 4.3197 +-0.0083 -0.0167 4.3197 +-0.0111 -0.0222 4.3197 +-0.0139 -0.0278 4.3197 +-0.0167 -0.0333 4.3197 +-0.0194 -0.0389 4.3197 +-0.0222 -0.0444 4.3197 +-0.0250 -0.0500 4.3197 +primID: 1 +startangle_c: 11 +endpose_c: -3 -6 11 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0083 -0.0167 4.3197 +-0.0167 -0.0333 4.3197 +-0.0250 -0.0500 4.3197 +-0.0333 -0.0667 4.3197 +-0.0417 -0.0833 4.3197 +-0.0500 -0.1000 4.3197 +-0.0583 -0.1167 4.3197 +-0.0667 -0.1333 4.3197 +-0.0750 -0.1500 4.3197 +primID: 2 +startangle_c: 11 +endpose_c: 1 2 11 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0028 0.0056 4.3197 +0.0056 0.0111 4.3197 +0.0083 0.0167 4.3197 +0.0111 0.0222 4.3197 +0.0139 0.0278 4.3197 +0.0167 0.0333 4.3197 +0.0194 0.0389 4.3197 +0.0222 0.0444 4.3197 +0.0250 0.0500 4.3197 +primID: 3 +startangle_c: 11 +endpose_c: -4 -5 10 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0092 -0.0149 4.2894 +-0.0189 -0.0296 4.2591 +-0.0291 -0.0440 4.2288 +-0.0398 -0.0582 4.1985 +-0.0509 -0.0722 4.1682 +-0.0625 -0.0858 4.1379 +-0.0746 -0.0992 4.1076 +-0.0871 -0.1123 4.0773 +-0.1000 -0.1250 4.0470 +primID: 4 +startangle_c: 11 +endpose_c: -2 -7 12 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0078 -0.0188 4.3197 +-0.0156 -0.0377 4.3197 +-0.0234 -0.0565 4.3197 +-0.0312 -0.0754 4.3388 +-0.0379 -0.0946 4.4135 +-0.0432 -0.1143 4.4882 +-0.0470 -0.1344 4.5629 +-0.0492 -0.1546 4.6377 +-0.0500 -0.1750 4.7124 +primID: 5 +startangle_c: 11 +endpose_c: 0 0 10 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0000 0.0000 4.2761 +0.0000 0.0000 4.2324 +0.0000 0.0000 4.1888 +0.0000 0.0000 4.1452 +0.0000 0.0000 4.1015 +0.0000 0.0000 4.0579 +0.0000 0.0000 4.0143 +0.0000 0.0000 3.9706 +0.0000 0.0000 3.9270 +primID: 6 +startangle_c: 11 +endpose_c: 0 0 12 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0000 0.0000 4.3633 +0.0000 0.0000 4.4070 +0.0000 0.0000 4.4506 +0.0000 0.0000 4.4942 +0.0000 0.0000 4.5379 +0.0000 0.0000 4.5815 +0.0000 0.0000 4.6251 +0.0000 0.0000 4.6688 +0.0000 0.0000 4.7124 +primID: 7 +startangle_c: 11 +endpose_c: -2 1 11 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0056 0.0028 4.3197 +-0.0111 0.0056 4.3197 +-0.0167 0.0083 4.3197 +-0.0222 0.0111 4.3197 +-0.0278 0.0139 4.3197 +-0.0333 0.0167 4.3197 +-0.0389 0.0194 4.3197 +-0.0444 0.0222 4.3197 +-0.0500 0.0250 4.3197 +primID: 8 +startangle_c: 11 +endpose_c: 2 -1 11 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0056 -0.0028 4.3197 +0.0111 -0.0056 4.3197 +0.0167 -0.0083 4.3197 +0.0222 -0.0111 4.3197 +0.0278 -0.0139 4.3197 +0.0333 -0.0167 4.3197 +0.0389 -0.0194 4.3197 +0.0444 -0.0222 4.3197 +0.0500 -0.0250 4.3197 +primID: 9 +startangle_c: 11 +endpose_c: 4 5 10 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0092 0.0149 4.2894 +0.0189 0.0296 4.2591 +0.0291 0.0440 4.2288 +0.0398 0.0582 4.1985 +0.0509 0.0722 4.1682 +0.0625 0.0858 4.1379 +0.0746 0.0992 4.1076 +0.0871 0.1123 4.0773 +0.1000 0.1250 4.0470 +primID: 10 +startangle_c: 11 +endpose_c: 2 7 12 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0078 0.0188 4.3197 +0.0156 0.0377 4.3197 +0.0234 0.0565 4.3197 +0.0312 0.0754 4.3388 +0.0379 0.0946 4.4135 +0.0432 0.1143 4.4882 +0.0470 0.1344 4.5629 +0.0492 0.1546 4.6377 +0.0500 0.1750 4.7124 +primID: 11 +startangle_c: 11 +endpose_c: -4 -5 11 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0111 -0.0139 4.3197 +-0.0222 -0.0278 4.3197 +-0.0333 -0.0417 4.3197 +-0.0444 -0.0556 4.3197 +-0.0556 -0.0694 4.3197 +-0.0667 -0.0833 4.3197 +-0.0778 -0.0972 4.3197 +-0.0889 -0.1111 4.3197 +-0.1000 -0.1250 4.3197 +primID: 12 +startangle_c: 11 +endpose_c: -2 -7 11 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0056 -0.0194 4.3197 +-0.0111 -0.0389 4.3197 +-0.0167 -0.0583 4.3197 +-0.0222 -0.0778 4.3197 +-0.0278 -0.0972 4.3197 +-0.0333 -0.1167 4.3197 +-0.0389 -0.1361 4.3197 +-0.0444 -0.1556 4.3197 +-0.0500 -0.1750 4.3197 +primID: 0 +startangle_c: 12 +endpose_c: 0 -1 12 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0028 4.7124 +0.0000 -0.0056 4.7124 +0.0000 -0.0083 4.7124 +0.0000 -0.0111 4.7124 +0.0000 -0.0139 4.7124 +0.0000 -0.0167 4.7124 +0.0000 -0.0194 4.7124 +0.0000 -0.0222 4.7124 +0.0000 -0.0250 4.7124 +primID: 1 +startangle_c: 12 +endpose_c: 0 -8 12 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0222 4.7124 +0.0000 -0.0444 4.7124 +0.0000 -0.0667 4.7124 +0.0000 -0.0889 4.7124 +0.0000 -0.1111 4.7124 +0.0000 -0.1333 4.7124 +0.0000 -0.1556 4.7124 +0.0000 -0.1778 4.7124 +0.0000 -0.2000 4.7124 +primID: 2 +startangle_c: 12 +endpose_c: 0 1 12 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0028 4.7124 +0.0000 0.0056 4.7124 +0.0000 0.0083 4.7124 +0.0000 0.0111 4.7124 +0.0000 0.0139 4.7124 +0.0000 0.0167 4.7124 +0.0000 0.0194 4.7124 +0.0000 0.0222 4.7124 +0.0000 0.0250 4.7124 +primID: 3 +startangle_c: 12 +endpose_c: 1 -8 13 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.7124 +-0.0000 -0.0226 4.7124 +-0.0000 -0.0452 4.7124 +-0.0000 -0.0678 4.7124 +0.0004 -0.0903 4.7612 +0.0023 -0.1128 4.8300 +0.0057 -0.1352 4.8988 +0.0106 -0.1572 4.9675 +0.0171 -0.1789 5.0363 +0.0250 -0.2000 5.1051 +primID: 4 +startangle_c: 12 +endpose_c: -1 -8 11 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.7124 +-0.0000 -0.0226 4.7124 +-0.0000 -0.0452 4.7124 +-0.0000 -0.0678 4.7124 +-0.0004 -0.0903 4.6636 +-0.0023 -0.1128 4.5948 +-0.0057 -0.1352 4.5260 +-0.0106 -0.1572 4.4572 +-0.0171 -0.1789 4.3885 +-0.0250 -0.2000 4.3197 +primID: 5 +startangle_c: 12 +endpose_c: 0 0 13 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0000 4.7560 +0.0000 0.0000 4.7997 +0.0000 0.0000 4.8433 +0.0000 0.0000 4.8869 +0.0000 0.0000 4.9306 +0.0000 0.0000 4.9742 +0.0000 0.0000 5.0178 +0.0000 0.0000 5.0615 +0.0000 0.0000 5.1051 +primID: 6 +startangle_c: 12 +endpose_c: 0 0 11 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0000 4.6688 +0.0000 0.0000 4.6251 +0.0000 0.0000 4.5815 +0.0000 0.0000 4.5379 +0.0000 0.0000 4.4942 +0.0000 0.0000 4.4506 +0.0000 0.0000 4.4070 +0.0000 0.0000 4.3633 +0.0000 0.0000 4.3197 +primID: 7 +startangle_c: 12 +endpose_c: 1 0 12 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0028 0.0000 4.7124 +0.0056 0.0000 4.7124 +0.0083 0.0000 4.7124 +0.0111 0.0000 4.7124 +0.0139 0.0000 4.7124 +0.0167 0.0000 4.7124 +0.0194 0.0000 4.7124 +0.0222 0.0000 4.7124 +0.0250 0.0000 4.7124 +primID: 8 +startangle_c: 12 +endpose_c: -1 0 12 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 4.7124 +-0.0028 0.0000 4.7124 +-0.0056 0.0000 4.7124 +-0.0083 0.0000 4.7124 +-0.0111 0.0000 4.7124 +-0.0139 0.0000 4.7124 +-0.0167 0.0000 4.7124 +-0.0194 0.0000 4.7124 +-0.0222 0.0000 4.7124 +-0.0250 0.0000 4.7124 +primID: 9 +startangle_c: 12 +endpose_c: -1 8 13 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0226 4.7124 +0.0000 0.0452 4.7124 +0.0000 0.0678 4.7124 +-0.0004 0.0903 4.7612 +-0.0023 0.1128 4.8300 +-0.0057 0.1352 4.8988 +-0.0106 0.1572 4.9675 +-0.0171 0.1789 5.0363 +-0.0250 0.2000 5.1051 +primID: 10 +startangle_c: 12 +endpose_c: 1 8 11 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0226 4.7124 +0.0000 0.0452 4.7124 +0.0000 0.0678 4.7124 +0.0004 0.0903 4.6636 +0.0023 0.1128 4.5948 +0.0057 0.1352 4.5260 +0.0106 0.1572 4.4572 +0.0171 0.1789 4.3885 +0.0250 0.2000 4.3197 +primID: 11 +startangle_c: 12 +endpose_c: 1 -8 12 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0028 -0.0222 4.7124 +0.0056 -0.0444 4.7124 +0.0083 -0.0667 4.7124 +0.0111 -0.0889 4.7124 +0.0139 -0.1111 4.7124 +0.0167 -0.1333 4.7124 +0.0194 -0.1556 4.7124 +0.0222 -0.1778 4.7124 +0.0250 -0.2000 4.7124 +primID: 12 +startangle_c: 12 +endpose_c: -1 -8 12 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.7124 +-0.0028 -0.0222 4.7124 +-0.0056 -0.0444 4.7124 +-0.0083 -0.0667 4.7124 +-0.0111 -0.0889 4.7124 +-0.0139 -0.1111 4.7124 +-0.0167 -0.1333 4.7124 +-0.0194 -0.1556 4.7124 +-0.0222 -0.1778 4.7124 +-0.0250 -0.2000 4.7124 +primID: 0 +startangle_c: 13 +endpose_c: 1 -2 13 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0028 -0.0056 5.1051 +0.0056 -0.0111 5.1051 +0.0083 -0.0167 5.1051 +0.0111 -0.0222 5.1051 +0.0139 -0.0278 5.1051 +0.0167 -0.0333 5.1051 +0.0194 -0.0389 5.1051 +0.0222 -0.0444 5.1051 +0.0250 -0.0500 5.1051 +primID: 1 +startangle_c: 13 +endpose_c: 3 -6 13 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0083 -0.0167 5.1051 +0.0167 -0.0333 5.1051 +0.0250 -0.0500 5.1051 +0.0333 -0.0667 5.1051 +0.0417 -0.0833 5.1051 +0.0500 -0.1000 5.1051 +0.0583 -0.1167 5.1051 +0.0667 -0.1333 5.1051 +0.0750 -0.1500 5.1051 +primID: 2 +startangle_c: 13 +endpose_c: -1 2 13 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 5.1051 +-0.0028 0.0056 5.1051 +-0.0056 0.0111 5.1051 +-0.0083 0.0167 5.1051 +-0.0111 0.0222 5.1051 +-0.0139 0.0278 5.1051 +-0.0167 0.0333 5.1051 +-0.0194 0.0389 5.1051 +-0.0222 0.0444 5.1051 +-0.0250 0.0500 5.1051 +primID: 3 +startangle_c: 13 +endpose_c: 4 -5 14 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0092 -0.0149 5.1354 +0.0189 -0.0296 5.1657 +0.0291 -0.0440 5.1960 +0.0398 -0.0582 5.2263 +0.0509 -0.0722 5.2566 +0.0625 -0.0858 5.2869 +0.0746 -0.0992 5.3172 +0.0871 -0.1123 5.3475 +0.1000 -0.1250 5.3778 +primID: 4 +startangle_c: 13 +endpose_c: 2 -7 12 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0078 -0.0188 5.1051 +0.0156 -0.0377 5.1051 +0.0234 -0.0565 5.1051 +0.0312 -0.0754 5.0860 +0.0379 -0.0946 5.0113 +0.0432 -0.1143 4.9366 +0.0470 -0.1344 4.8618 +0.0492 -0.1546 4.7871 +0.0500 -0.1750 4.7124 +primID: 5 +startangle_c: 13 +endpose_c: 0 0 14 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0000 0.0000 5.1487 +0.0000 0.0000 5.1924 +0.0000 0.0000 5.2360 +0.0000 0.0000 5.2796 +0.0000 0.0000 5.3233 +0.0000 0.0000 5.3669 +0.0000 0.0000 5.4105 +0.0000 0.0000 5.4542 +0.0000 0.0000 5.4978 +primID: 6 +startangle_c: 13 +endpose_c: 0 0 12 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0000 0.0000 5.0615 +0.0000 0.0000 5.0178 +0.0000 0.0000 4.9742 +0.0000 0.0000 4.9306 +0.0000 0.0000 4.8869 +0.0000 0.0000 4.8433 +0.0000 0.0000 4.7997 +0.0000 0.0000 4.7560 +0.0000 0.0000 4.7124 +primID: 7 +startangle_c: 13 +endpose_c: 2 1 13 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0056 0.0028 5.1051 +0.0111 0.0056 5.1051 +0.0167 0.0083 5.1051 +0.0222 0.0111 5.1051 +0.0278 0.0139 5.1051 +0.0333 0.0167 5.1051 +0.0389 0.0194 5.1051 +0.0444 0.0222 5.1051 +0.0500 0.0250 5.1051 +primID: 8 +startangle_c: 13 +endpose_c: -2 -1 13 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.1051 +-0.0056 -0.0028 5.1051 +-0.0111 -0.0056 5.1051 +-0.0167 -0.0083 5.1051 +-0.0222 -0.0111 5.1051 +-0.0278 -0.0139 5.1051 +-0.0333 -0.0167 5.1051 +-0.0389 -0.0194 5.1051 +-0.0444 -0.0222 5.1051 +-0.0500 -0.0250 5.1051 +primID: 9 +startangle_c: 13 +endpose_c: -4 5 14 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 5.1051 +-0.0092 0.0149 5.1354 +-0.0189 0.0296 5.1657 +-0.0291 0.0440 5.1960 +-0.0398 0.0582 5.2263 +-0.0509 0.0722 5.2566 +-0.0625 0.0858 5.2869 +-0.0746 0.0992 5.3172 +-0.0871 0.1123 5.3475 +-0.1000 0.1250 5.3778 +primID: 10 +startangle_c: 13 +endpose_c: -2 7 12 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 5.1051 +-0.0078 0.0188 5.1051 +-0.0156 0.0377 5.1051 +-0.0234 0.0565 5.1051 +-0.0312 0.0754 5.0860 +-0.0379 0.0946 5.0113 +-0.0432 0.1143 4.9366 +-0.0470 0.1344 4.8618 +-0.0492 0.1546 4.7871 +-0.0500 0.1750 4.7124 +primID: 11 +startangle_c: 13 +endpose_c: 4 -5 13 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0111 -0.0139 5.1051 +0.0222 -0.0278 5.1051 +0.0333 -0.0417 5.1051 +0.0444 -0.0556 5.1051 +0.0556 -0.0694 5.1051 +0.0667 -0.0833 5.1051 +0.0778 -0.0972 5.1051 +0.0889 -0.1111 5.1051 +0.1000 -0.1250 5.1051 +primID: 12 +startangle_c: 13 +endpose_c: 2 -7 13 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0056 -0.0194 5.1051 +0.0111 -0.0389 5.1051 +0.0167 -0.0583 5.1051 +0.0222 -0.0778 5.1051 +0.0278 -0.0972 5.1051 +0.0333 -0.1167 5.1051 +0.0389 -0.1361 5.1051 +0.0444 -0.1556 5.1051 +0.0500 -0.1750 5.1051 +primID: 0 +startangle_c: 14 +endpose_c: 1 -1 14 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0028 -0.0028 5.4978 +0.0056 -0.0056 5.4978 +0.0083 -0.0083 5.4978 +0.0111 -0.0111 5.4978 +0.0139 -0.0139 5.4978 +0.0167 -0.0167 5.4978 +0.0194 -0.0194 5.4978 +0.0222 -0.0222 5.4978 +0.0250 -0.0250 5.4978 +primID: 1 +startangle_c: 14 +endpose_c: 6 -6 14 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0167 -0.0167 5.4978 +0.0333 -0.0333 5.4978 +0.0500 -0.0500 5.4978 +0.0667 -0.0667 5.4978 +0.0833 -0.0833 5.4978 +0.1000 -0.1000 5.4978 +0.1167 -0.1167 5.4978 +0.1333 -0.1333 5.4978 +0.1500 -0.1500 5.4978 +primID: 2 +startangle_c: 14 +endpose_c: -1 1 14 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 5.4978 +-0.0028 0.0028 5.4978 +-0.0056 0.0056 5.4978 +-0.0083 0.0083 5.4978 +-0.0111 0.0111 5.4978 +-0.0139 0.0139 5.4978 +-0.0167 0.0167 5.4978 +-0.0194 0.0194 5.4978 +-0.0222 0.0222 5.4978 +-0.0250 0.0250 5.4978 +primID: 3 +startangle_c: 14 +endpose_c: 7 -5 15 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0170 -0.0170 5.4978 +0.0342 -0.0339 5.5275 +0.0522 -0.0500 5.5793 +0.0709 -0.0651 5.6312 +0.0904 -0.0792 5.6830 +0.1107 -0.0923 5.7349 +0.1315 -0.1043 5.7868 +0.1530 -0.1152 5.8386 +0.1750 -0.1250 5.8905 +primID: 4 +startangle_c: 14 +endpose_c: 5 -7 13 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0170 -0.0170 5.4978 +0.0339 -0.0342 5.4681 +0.0500 -0.0522 5.4162 +0.0651 -0.0709 5.3644 +0.0792 -0.0904 5.3125 +0.0923 -0.1107 5.2607 +0.1043 -0.1315 5.2088 +0.1152 -0.1530 5.1569 +0.1250 -0.1750 5.1051 +primID: 5 +startangle_c: 14 +endpose_c: 0 0 15 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0000 0.0000 5.5414 +0.0000 0.0000 5.5851 +0.0000 0.0000 5.6287 +0.0000 0.0000 5.6723 +0.0000 0.0000 5.7160 +0.0000 0.0000 5.7596 +0.0000 0.0000 5.8032 +0.0000 0.0000 5.8469 +0.0000 0.0000 5.8905 +primID: 6 +startangle_c: 14 +endpose_c: 0 0 13 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0000 0.0000 5.4542 +0.0000 0.0000 5.4105 +0.0000 0.0000 5.3669 +0.0000 0.0000 5.3233 +0.0000 0.0000 5.2796 +0.0000 0.0000 5.2360 +0.0000 0.0000 5.1924 +0.0000 0.0000 5.1487 +0.0000 0.0000 5.1051 +primID: 7 +startangle_c: 14 +endpose_c: 1 1 14 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0028 0.0028 5.4978 +0.0056 0.0056 5.4978 +0.0083 0.0083 5.4978 +0.0111 0.0111 5.4978 +0.0139 0.0139 5.4978 +0.0167 0.0167 5.4978 +0.0194 0.0194 5.4978 +0.0222 0.0222 5.4978 +0.0250 0.0250 5.4978 +primID: 8 +startangle_c: 14 +endpose_c: -1 -1 14 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.4978 +-0.0028 -0.0028 5.4978 +-0.0056 -0.0056 5.4978 +-0.0083 -0.0083 5.4978 +-0.0111 -0.0111 5.4978 +-0.0139 -0.0139 5.4978 +-0.0167 -0.0167 5.4978 +-0.0194 -0.0194 5.4978 +-0.0222 -0.0222 5.4978 +-0.0250 -0.0250 5.4978 +primID: 9 +startangle_c: 14 +endpose_c: -7 5 15 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 5.4978 +-0.0170 0.0170 5.4978 +-0.0342 0.0339 5.5275 +-0.0522 0.0500 5.5793 +-0.0709 0.0651 5.6312 +-0.0904 0.0792 5.6830 +-0.1107 0.0923 5.7349 +-0.1315 0.1043 5.7868 +-0.1530 0.1152 5.8386 +-0.1750 0.1250 5.8905 +primID: 10 +startangle_c: 14 +endpose_c: -5 7 13 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 5.4978 +-0.0170 0.0170 5.4978 +-0.0339 0.0342 5.4681 +-0.0500 0.0522 5.4162 +-0.0651 0.0709 5.3644 +-0.0792 0.0904 5.3125 +-0.0923 0.1107 5.2607 +-0.1043 0.1315 5.2088 +-0.1152 0.1530 5.1569 +-0.1250 0.1750 5.1051 +primID: 11 +startangle_c: 14 +endpose_c: 7 -5 14 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0194 -0.0139 5.4978 +0.0389 -0.0278 5.4978 +0.0583 -0.0417 5.4978 +0.0778 -0.0556 5.4978 +0.0972 -0.0694 5.4978 +0.1167 -0.0833 5.4978 +0.1361 -0.0972 5.4978 +0.1556 -0.1111 5.4978 +0.1750 -0.1250 5.4978 +primID: 12 +startangle_c: 14 +endpose_c: 5 -7 14 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0139 -0.0194 5.4978 +0.0278 -0.0389 5.4978 +0.0417 -0.0583 5.4978 +0.0556 -0.0778 5.4978 +0.0694 -0.0972 5.4978 +0.0833 -0.1167 5.4978 +0.0972 -0.1361 5.4978 +0.1111 -0.1556 5.4978 +0.1250 -0.1750 5.4978 +primID: 0 +startangle_c: 15 +endpose_c: 2 -1 15 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0056 -0.0028 5.8905 +0.0111 -0.0056 5.8905 +0.0167 -0.0083 5.8905 +0.0222 -0.0111 5.8905 +0.0278 -0.0139 5.8905 +0.0333 -0.0167 5.8905 +0.0389 -0.0194 5.8905 +0.0444 -0.0222 5.8905 +0.0500 -0.0250 5.8905 +primID: 1 +startangle_c: 15 +endpose_c: 6 -3 15 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0167 -0.0083 5.8905 +0.0333 -0.0167 5.8905 +0.0500 -0.0250 5.8905 +0.0667 -0.0333 5.8905 +0.0833 -0.0417 5.8905 +0.1000 -0.0500 5.8905 +0.1167 -0.0583 5.8905 +0.1333 -0.0667 5.8905 +0.1500 -0.0750 5.8905 +primID: 2 +startangle_c: 15 +endpose_c: -2 1 15 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 5.8905 +-0.0056 0.0028 5.8905 +-0.0111 0.0056 5.8905 +-0.0167 0.0083 5.8905 +-0.0222 0.0111 5.8905 +-0.0278 0.0139 5.8905 +-0.0333 0.0167 5.8905 +-0.0389 0.0194 5.8905 +-0.0444 0.0222 5.8905 +-0.0500 0.0250 5.8905 +primID: 3 +startangle_c: 15 +endpose_c: 5 -4 14 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0149 -0.0092 5.8602 +0.0296 -0.0189 5.8299 +0.0440 -0.0291 5.7996 +0.0582 -0.0398 5.7693 +0.0722 -0.0509 5.7390 +0.0858 -0.0625 5.7087 +0.0992 -0.0746 5.6784 +0.1123 -0.0871 5.6481 +0.1250 -0.1000 5.6178 +primID: 4 +startangle_c: 15 +endpose_c: 7 -2 0 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0188 -0.0078 5.8905 +0.0377 -0.0156 5.8905 +0.0565 -0.0234 5.8905 +0.0754 -0.0312 5.9096 +0.0946 -0.0379 5.9843 +0.1143 -0.0432 6.0590 +0.1344 -0.0470 6.1337 +0.1546 -0.0492 6.2085 +0.1750 -0.0500 6.2832 +primID: 5 +startangle_c: 15 +endpose_c: 0 0 14 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0000 0.0000 5.8469 +0.0000 0.0000 5.8032 +0.0000 0.0000 5.7596 +0.0000 0.0000 5.7160 +0.0000 0.0000 5.6723 +0.0000 0.0000 5.6287 +0.0000 0.0000 5.5851 +0.0000 0.0000 5.5414 +0.0000 0.0000 5.4978 +primID: 6 +startangle_c: 15 +endpose_c: 0 0 0 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0000 0.0000 5.9341 +0.0000 0.0000 5.9778 +0.0000 0.0000 6.0214 +0.0000 0.0000 6.0650 +0.0000 0.0000 6.1087 +0.0000 0.0000 6.1523 +0.0000 0.0000 6.1959 +0.0000 0.0000 6.2396 +0.0000 0.0000 0.0000 +primID: 7 +startangle_c: 15 +endpose_c: -1 -2 15 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.8905 +-0.0028 -0.0056 5.8905 +-0.0056 -0.0111 5.8905 +-0.0083 -0.0167 5.8905 +-0.0111 -0.0222 5.8905 +-0.0139 -0.0278 5.8905 +-0.0167 -0.0333 5.8905 +-0.0194 -0.0389 5.8905 +-0.0222 -0.0444 5.8905 +-0.0250 -0.0500 5.8905 +primID: 8 +startangle_c: 15 +endpose_c: 1 2 15 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0028 0.0056 5.8905 +0.0056 0.0111 5.8905 +0.0083 0.0167 5.8905 +0.0111 0.0222 5.8905 +0.0139 0.0278 5.8905 +0.0167 0.0333 5.8905 +0.0194 0.0389 5.8905 +0.0222 0.0444 5.8905 +0.0250 0.0500 5.8905 +primID: 9 +startangle_c: 15 +endpose_c: -5 4 14 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 5.8905 +-0.0149 0.0092 5.8602 +-0.0296 0.0189 5.8299 +-0.0440 0.0291 5.7996 +-0.0582 0.0398 5.7693 +-0.0722 0.0509 5.7390 +-0.0858 0.0625 5.7087 +-0.0992 0.0746 5.6784 +-0.1123 0.0871 5.6481 +-0.1250 0.1000 5.6178 +primID: 10 +startangle_c: 15 +endpose_c: -7 2 0 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 5.8905 +-0.0188 0.0078 5.8905 +-0.0377 0.0156 5.8905 +-0.0565 0.0234 5.8905 +-0.0754 0.0312 5.9096 +-0.0946 0.0379 5.9843 +-0.1143 0.0432 6.0590 +-0.1344 0.0470 6.1337 +-0.1546 0.0492 6.2085 +-0.1750 0.0500 6.2832 +primID: 11 +startangle_c: 15 +endpose_c: 5 -4 15 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0139 -0.0111 5.8905 +0.0278 -0.0222 5.8905 +0.0417 -0.0333 5.8905 +0.0556 -0.0444 5.8905 +0.0694 -0.0556 5.8905 +0.0833 -0.0667 5.8905 +0.0972 -0.0778 5.8905 +0.1111 -0.0889 5.8905 +0.1250 -0.1000 5.8905 +primID: 12 +startangle_c: 15 +endpose_c: 7 -2 15 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0194 -0.0056 5.8905 +0.0389 -0.0111 5.8905 +0.0583 -0.0167 5.8905 +0.0778 -0.0222 5.8905 +0.0972 -0.0278 5.8905 +0.1167 -0.0333 5.8905 +0.1361 -0.0389 5.8905 +0.1556 -0.0444 5.8905 +0.1750 -0.0500 5.8905 diff --git a/navigations/sbpl/matlab/mprim/pr2_unicycle_10cm.mprim b/navigations/sbpl/matlab/mprim/pr2_unicycle_10cm.mprim new file mode 100755 index 0000000..fbf25b7 --- /dev/null +++ b/navigations/sbpl/matlab/mprim/pr2_unicycle_10cm.mprim @@ -0,0 +1,1203 @@ +resolution_m: 0.100000 +numberofangles: 16 +totalnumberofprimitives: 80 +primID: 0 +startangle_c: 0 +endpose_c: 1 0 0 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0111 0.0000 0.0000 +0.0222 0.0000 0.0000 +0.0333 0.0000 0.0000 +0.0444 0.0000 0.0000 +0.0556 0.0000 0.0000 +0.0667 0.0000 0.0000 +0.0778 0.0000 0.0000 +0.0889 0.0000 0.0000 +0.1000 0.0000 0.0000 +primID: 1 +startangle_c: 0 +endpose_c: 8 0 0 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0889 0.0000 0.0000 +0.1778 0.0000 0.0000 +0.2667 0.0000 0.0000 +0.3556 0.0000 0.0000 +0.4444 0.0000 0.0000 +0.5333 0.0000 0.0000 +0.6222 0.0000 0.0000 +0.7111 0.0000 0.0000 +0.8000 0.0000 0.0000 +primID: 2 +startangle_c: 0 +endpose_c: -1 0 0 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 0.0000 +-0.0111 0.0000 0.0000 +-0.0222 0.0000 0.0000 +-0.0333 0.0000 0.0000 +-0.0444 0.0000 0.0000 +-0.0556 0.0000 0.0000 +-0.0667 0.0000 0.0000 +-0.0778 0.0000 0.0000 +-0.0889 0.0000 0.0000 +-0.1000 0.0000 0.0000 +primID: 3 +startangle_c: 0 +endpose_c: 8 1 1 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0904 -0.0000 0.0000 +0.1807 -0.0000 0.0000 +0.2711 -0.0000 0.0000 +0.3614 0.0016 0.0488 +0.4514 0.0091 0.1176 +0.5407 0.0227 0.1864 +0.6288 0.0425 0.2551 +0.7154 0.0683 0.3239 +0.8000 0.1000 0.3927 +primID: 4 +startangle_c: 0 +endpose_c: 8 -1 -1 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0904 0.0000 0.0000 +0.1807 0.0000 0.0000 +0.2711 0.0000 0.0000 +0.3614 -0.0016 -0.0488 +0.4514 -0.0091 -0.1176 +0.5407 -0.0227 -0.1864 +0.6288 -0.0425 -0.2551 +0.7154 -0.0683 -0.3239 +0.8000 -0.1000 -0.3927 +primID: 0 +startangle_c: 1 +endpose_c: 2 1 1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0222 0.0111 0.3927 +0.0444 0.0222 0.3927 +0.0667 0.0333 0.3927 +0.0889 0.0444 0.3927 +0.1111 0.0556 0.3927 +0.1333 0.0667 0.3927 +0.1556 0.0778 0.3927 +0.1778 0.0889 0.3927 +0.2000 0.1000 0.3927 +primID: 1 +startangle_c: 1 +endpose_c: 6 3 1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0667 0.0333 0.3927 +0.1333 0.0667 0.3927 +0.2000 0.1000 0.3927 +0.2667 0.1333 0.3927 +0.3333 0.1667 0.3927 +0.4000 0.2000 0.3927 +0.4667 0.2333 0.3927 +0.5333 0.2667 0.3927 +0.6000 0.3000 0.3927 +primID: 2 +startangle_c: 1 +endpose_c: -2 -1 1 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 0.3927 +-0.0222 -0.0111 0.3927 +-0.0444 -0.0222 0.3927 +-0.0667 -0.0333 0.3927 +-0.0889 -0.0444 0.3927 +-0.1111 -0.0556 0.3927 +-0.1333 -0.0667 0.3927 +-0.1556 -0.0778 0.3927 +-0.1778 -0.0889 0.3927 +-0.2000 -0.1000 0.3927 +primID: 3 +startangle_c: 1 +endpose_c: 5 4 2 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0596 0.0369 0.4230 +0.1184 0.0757 0.4533 +0.1762 0.1165 0.4836 +0.2330 0.1592 0.5139 +0.2887 0.2037 0.5442 +0.3433 0.2501 0.5745 +0.3968 0.2983 0.6048 +0.4490 0.3483 0.6351 +0.5000 0.4000 0.6654 +primID: 4 +startangle_c: 1 +endpose_c: 7 2 0 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0754 0.0312 0.3927 +0.1507 0.0624 0.3927 +0.2261 0.0937 0.3927 +0.3015 0.1247 0.3736 +0.3785 0.1516 0.2989 +0.4573 0.1727 0.2242 +0.5375 0.1878 0.1494 +0.6185 0.1970 0.0747 +0.7000 0.2000 0.0000 +primID: 0 +startangle_c: 2 +endpose_c: 1 1 2 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0111 0.0111 0.7854 +0.0222 0.0222 0.7854 +0.0333 0.0333 0.7854 +0.0444 0.0444 0.7854 +0.0556 0.0556 0.7854 +0.0667 0.0667 0.7854 +0.0778 0.0778 0.7854 +0.0889 0.0889 0.7854 +0.1000 0.1000 0.7854 +primID: 1 +startangle_c: 2 +endpose_c: 6 6 2 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0667 0.0667 0.7854 +0.1333 0.1333 0.7854 +0.2000 0.2000 0.7854 +0.2667 0.2667 0.7854 +0.3333 0.3333 0.7854 +0.4000 0.4000 0.7854 +0.4667 0.4667 0.7854 +0.5333 0.5333 0.7854 +0.6000 0.6000 0.7854 +primID: 2 +startangle_c: 2 +endpose_c: -1 -1 2 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 0.7854 +-0.0111 -0.0111 0.7854 +-0.0222 -0.0222 0.7854 +-0.0333 -0.0333 0.7854 +-0.0444 -0.0444 0.7854 +-0.0556 -0.0556 0.7854 +-0.0667 -0.0667 0.7854 +-0.0778 -0.0778 0.7854 +-0.0889 -0.0889 0.7854 +-0.1000 -0.1000 0.7854 +primID: 3 +startangle_c: 2 +endpose_c: 5 7 3 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0681 0.0681 0.7854 +0.1357 0.1368 0.8151 +0.1999 0.2086 0.8669 +0.2603 0.2837 0.9188 +0.3168 0.3617 0.9707 +0.3691 0.4426 1.0225 +0.4172 0.5261 1.0744 +0.4608 0.6120 1.1262 +0.5000 0.7000 1.1781 +primID: 4 +startangle_c: 2 +endpose_c: 7 5 1 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0681 0.0681 0.7854 +0.1368 0.1357 0.7557 +0.2086 0.1999 0.7039 +0.2837 0.2603 0.6520 +0.3617 0.3168 0.6001 +0.4426 0.3691 0.5483 +0.5261 0.4172 0.4964 +0.6120 0.4608 0.4446 +0.7000 0.5000 0.3927 +primID: 0 +startangle_c: 3 +endpose_c: 1 2 3 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0111 0.0222 1.1781 +0.0222 0.0444 1.1781 +0.0333 0.0667 1.1781 +0.0444 0.0889 1.1781 +0.0556 0.1111 1.1781 +0.0667 0.1333 1.1781 +0.0778 0.1556 1.1781 +0.0889 0.1778 1.1781 +0.1000 0.2000 1.1781 +primID: 1 +startangle_c: 3 +endpose_c: 3 6 3 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0333 0.0667 1.1781 +0.0667 0.1333 1.1781 +0.1000 0.2000 1.1781 +0.1333 0.2667 1.1781 +0.1667 0.3333 1.1781 +0.2000 0.4000 1.1781 +0.2333 0.4667 1.1781 +0.2667 0.5333 1.1781 +0.3000 0.6000 1.1781 +primID: 2 +startangle_c: 3 +endpose_c: -1 -2 3 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 1.1781 +-0.0111 -0.0222 1.1781 +-0.0222 -0.0444 1.1781 +-0.0333 -0.0667 1.1781 +-0.0444 -0.0889 1.1781 +-0.0556 -0.1111 1.1781 +-0.0667 -0.1333 1.1781 +-0.0778 -0.1556 1.1781 +-0.0889 -0.1778 1.1781 +-0.1000 -0.2000 1.1781 +primID: 3 +startangle_c: 3 +endpose_c: 4 5 2 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0369 0.0596 1.1478 +0.0757 0.1184 1.1175 +0.1165 0.1762 1.0872 +0.1592 0.2330 1.0569 +0.2037 0.2887 1.0266 +0.2501 0.3433 0.9963 +0.2983 0.3968 0.9660 +0.3483 0.4490 0.9357 +0.4000 0.5000 0.9054 +primID: 4 +startangle_c: 3 +endpose_c: 2 7 4 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0312 0.0754 1.1781 +0.0624 0.1507 1.1781 +0.0937 0.2261 1.1781 +0.1247 0.3015 1.1972 +0.1516 0.3785 1.2719 +0.1727 0.4573 1.3466 +0.1878 0.5375 1.4214 +0.1970 0.6185 1.4961 +0.2000 0.7000 1.5708 +primID: 0 +startangle_c: 4 +endpose_c: 0 1 4 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0111 1.5708 +0.0000 0.0222 1.5708 +0.0000 0.0333 1.5708 +0.0000 0.0444 1.5708 +0.0000 0.0556 1.5708 +0.0000 0.0667 1.5708 +0.0000 0.0778 1.5708 +0.0000 0.0889 1.5708 +0.0000 0.1000 1.5708 +primID: 1 +startangle_c: 4 +endpose_c: 0 8 4 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0889 1.5708 +0.0000 0.1778 1.5708 +0.0000 0.2667 1.5708 +0.0000 0.3556 1.5708 +0.0000 0.4444 1.5708 +0.0000 0.5333 1.5708 +0.0000 0.6222 1.5708 +0.0000 0.7111 1.5708 +0.0000 0.8000 1.5708 +primID: 2 +startangle_c: 4 +endpose_c: 0 -1 4 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 -0.0111 1.5708 +0.0000 -0.0222 1.5708 +0.0000 -0.0333 1.5708 +0.0000 -0.0444 1.5708 +0.0000 -0.0556 1.5708 +0.0000 -0.0667 1.5708 +0.0000 -0.0778 1.5708 +0.0000 -0.0889 1.5708 +0.0000 -0.1000 1.5708 +primID: 3 +startangle_c: 4 +endpose_c: -1 8 5 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0904 1.5708 +0.0000 0.1807 1.5708 +0.0000 0.2711 1.5708 +-0.0016 0.3614 1.6196 +-0.0091 0.4514 1.6884 +-0.0227 0.5407 1.7572 +-0.0425 0.6288 1.8259 +-0.0683 0.7154 1.8947 +-0.1000 0.8000 1.9635 +primID: 4 +startangle_c: 4 +endpose_c: 1 8 3 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.5708 +-0.0000 0.0904 1.5708 +-0.0000 0.1807 1.5708 +-0.0000 0.2711 1.5708 +0.0016 0.3614 1.5220 +0.0091 0.4514 1.4532 +0.0227 0.5407 1.3844 +0.0425 0.6288 1.3156 +0.0683 0.7154 1.2469 +0.1000 0.8000 1.1781 +primID: 0 +startangle_c: 5 +endpose_c: -1 2 5 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0111 0.0222 1.9635 +-0.0222 0.0444 1.9635 +-0.0333 0.0667 1.9635 +-0.0444 0.0889 1.9635 +-0.0556 0.1111 1.9635 +-0.0667 0.1333 1.9635 +-0.0778 0.1556 1.9635 +-0.0889 0.1778 1.9635 +-0.1000 0.2000 1.9635 +primID: 1 +startangle_c: 5 +endpose_c: -3 6 5 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0333 0.0667 1.9635 +-0.0667 0.1333 1.9635 +-0.1000 0.2000 1.9635 +-0.1333 0.2667 1.9635 +-0.1667 0.3333 1.9635 +-0.2000 0.4000 1.9635 +-0.2333 0.4667 1.9635 +-0.2667 0.5333 1.9635 +-0.3000 0.6000 1.9635 +primID: 2 +startangle_c: 5 +endpose_c: 1 -2 5 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0111 -0.0222 1.9635 +0.0222 -0.0444 1.9635 +0.0333 -0.0667 1.9635 +0.0444 -0.0889 1.9635 +0.0556 -0.1111 1.9635 +0.0667 -0.1333 1.9635 +0.0778 -0.1556 1.9635 +0.0889 -0.1778 1.9635 +0.1000 -0.2000 1.9635 +primID: 3 +startangle_c: 5 +endpose_c: -4 5 6 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0369 0.0596 1.9938 +-0.0757 0.1184 2.0241 +-0.1165 0.1762 2.0544 +-0.1592 0.2330 2.0847 +-0.2037 0.2887 2.1150 +-0.2501 0.3433 2.1453 +-0.2983 0.3968 2.1756 +-0.3483 0.4490 2.2059 +-0.4000 0.5000 2.2362 +primID: 4 +startangle_c: 5 +endpose_c: -2 7 4 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0312 0.0754 1.9635 +-0.0624 0.1507 1.9635 +-0.0937 0.2261 1.9635 +-0.1247 0.3015 1.9444 +-0.1516 0.3785 1.8697 +-0.1727 0.4573 1.7950 +-0.1878 0.5375 1.7202 +-0.1970 0.6185 1.6455 +-0.2000 0.7000 1.5708 +primID: 0 +startangle_c: 6 +endpose_c: -1 1 6 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0111 0.0111 2.3562 +-0.0222 0.0222 2.3562 +-0.0333 0.0333 2.3562 +-0.0444 0.0444 2.3562 +-0.0556 0.0556 2.3562 +-0.0667 0.0667 2.3562 +-0.0778 0.0778 2.3562 +-0.0889 0.0889 2.3562 +-0.1000 0.1000 2.3562 +primID: 1 +startangle_c: 6 +endpose_c: -6 6 6 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0667 0.0667 2.3562 +-0.1333 0.1333 2.3562 +-0.2000 0.2000 2.3562 +-0.2667 0.2667 2.3562 +-0.3333 0.3333 2.3562 +-0.4000 0.4000 2.3562 +-0.4667 0.4667 2.3562 +-0.5333 0.5333 2.3562 +-0.6000 0.6000 2.3562 +primID: 2 +startangle_c: 6 +endpose_c: 1 -1 6 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0111 -0.0111 2.3562 +0.0222 -0.0222 2.3562 +0.0333 -0.0333 2.3562 +0.0444 -0.0444 2.3562 +0.0556 -0.0556 2.3562 +0.0667 -0.0667 2.3562 +0.0778 -0.0778 2.3562 +0.0889 -0.0889 2.3562 +0.1000 -0.1000 2.3562 +primID: 3 +startangle_c: 6 +endpose_c: -7 5 7 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0681 0.0681 2.3562 +-0.1368 0.1357 2.3859 +-0.2086 0.1999 2.4377 +-0.2837 0.2603 2.4896 +-0.3617 0.3168 2.5415 +-0.4426 0.3691 2.5933 +-0.5261 0.4172 2.6452 +-0.6120 0.4608 2.6970 +-0.7000 0.5000 2.7489 +primID: 4 +startangle_c: 6 +endpose_c: -5 7 5 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0681 0.0681 2.3562 +-0.1357 0.1368 2.3265 +-0.1999 0.2086 2.2747 +-0.2603 0.2837 2.2228 +-0.3168 0.3617 2.1709 +-0.3691 0.4426 2.1191 +-0.4172 0.5261 2.0672 +-0.4608 0.6120 2.0154 +-0.5000 0.7000 1.9635 +primID: 0 +startangle_c: 7 +endpose_c: -2 1 7 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0222 0.0111 2.7489 +-0.0444 0.0222 2.7489 +-0.0667 0.0333 2.7489 +-0.0889 0.0444 2.7489 +-0.1111 0.0556 2.7489 +-0.1333 0.0667 2.7489 +-0.1556 0.0778 2.7489 +-0.1778 0.0889 2.7489 +-0.2000 0.1000 2.7489 +primID: 1 +startangle_c: 7 +endpose_c: -6 3 7 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0667 0.0333 2.7489 +-0.1333 0.0667 2.7489 +-0.2000 0.1000 2.7489 +-0.2667 0.1333 2.7489 +-0.3333 0.1667 2.7489 +-0.4000 0.2000 2.7489 +-0.4667 0.2333 2.7489 +-0.5333 0.2667 2.7489 +-0.6000 0.3000 2.7489 +primID: 2 +startangle_c: 7 +endpose_c: 2 -1 7 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0222 -0.0111 2.7489 +0.0444 -0.0222 2.7489 +0.0667 -0.0333 2.7489 +0.0889 -0.0444 2.7489 +0.1111 -0.0556 2.7489 +0.1333 -0.0667 2.7489 +0.1556 -0.0778 2.7489 +0.1778 -0.0889 2.7489 +0.2000 -0.1000 2.7489 +primID: 3 +startangle_c: 7 +endpose_c: -5 4 6 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0596 0.0369 2.7186 +-0.1184 0.0757 2.6883 +-0.1762 0.1165 2.6580 +-0.2330 0.1592 2.6277 +-0.2887 0.2037 2.5974 +-0.3433 0.2501 2.5671 +-0.3968 0.2983 2.5368 +-0.4490 0.3483 2.5065 +-0.5000 0.4000 2.4762 +primID: 4 +startangle_c: 7 +endpose_c: -7 2 8 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0754 0.0312 2.7489 +-0.1507 0.0624 2.7489 +-0.2261 0.0937 2.7489 +-0.3015 0.1247 2.7680 +-0.3785 0.1516 2.8427 +-0.4573 0.1727 2.9174 +-0.5375 0.1878 2.9921 +-0.6185 0.1970 3.0669 +-0.7000 0.2000 3.1416 +primID: 0 +startangle_c: 8 +endpose_c: -1 0 8 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0111 0.0000 3.1416 +-0.0222 0.0000 3.1416 +-0.0333 0.0000 3.1416 +-0.0444 0.0000 3.1416 +-0.0556 0.0000 3.1416 +-0.0667 0.0000 3.1416 +-0.0778 0.0000 3.1416 +-0.0889 0.0000 3.1416 +-0.1000 0.0000 3.1416 +primID: 1 +startangle_c: 8 +endpose_c: -8 0 8 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0889 0.0000 3.1416 +-0.1778 0.0000 3.1416 +-0.2667 0.0000 3.1416 +-0.3556 0.0000 3.1416 +-0.4444 0.0000 3.1416 +-0.5333 0.0000 3.1416 +-0.6222 0.0000 3.1416 +-0.7111 0.0000 3.1416 +-0.8000 0.0000 3.1416 +primID: 2 +startangle_c: 8 +endpose_c: 1 0 8 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0111 0.0000 3.1416 +0.0222 0.0000 3.1416 +0.0333 0.0000 3.1416 +0.0444 0.0000 3.1416 +0.0556 0.0000 3.1416 +0.0667 0.0000 3.1416 +0.0778 0.0000 3.1416 +0.0889 0.0000 3.1416 +0.1000 0.0000 3.1416 +primID: 3 +startangle_c: 8 +endpose_c: -8 -1 9 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0904 0.0000 3.1416 +-0.1807 0.0000 3.1416 +-0.2711 0.0000 3.1416 +-0.3614 -0.0016 3.1904 +-0.4514 -0.0091 3.2592 +-0.5407 -0.0227 3.3280 +-0.6288 -0.0425 3.3967 +-0.7154 -0.0683 3.4655 +-0.8000 -0.1000 3.5343 +primID: 4 +startangle_c: 8 +endpose_c: -8 1 7 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0904 0.0000 3.1416 +-0.1807 0.0000 3.1416 +-0.2711 0.0000 3.1416 +-0.3614 0.0016 3.0928 +-0.4514 0.0091 3.0240 +-0.5407 0.0227 2.9552 +-0.6288 0.0425 2.8864 +-0.7154 0.0683 2.8177 +-0.8000 0.1000 2.7489 +primID: 0 +startangle_c: 9 +endpose_c: -2 -1 9 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0222 -0.0111 3.5343 +-0.0444 -0.0222 3.5343 +-0.0667 -0.0333 3.5343 +-0.0889 -0.0444 3.5343 +-0.1111 -0.0556 3.5343 +-0.1333 -0.0667 3.5343 +-0.1556 -0.0778 3.5343 +-0.1778 -0.0889 3.5343 +-0.2000 -0.1000 3.5343 +primID: 1 +startangle_c: 9 +endpose_c: -6 -3 9 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0667 -0.0333 3.5343 +-0.1333 -0.0667 3.5343 +-0.2000 -0.1000 3.5343 +-0.2667 -0.1333 3.5343 +-0.3333 -0.1667 3.5343 +-0.4000 -0.2000 3.5343 +-0.4667 -0.2333 3.5343 +-0.5333 -0.2667 3.5343 +-0.6000 -0.3000 3.5343 +primID: 2 +startangle_c: 9 +endpose_c: 2 1 9 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0222 0.0111 3.5343 +0.0444 0.0222 3.5343 +0.0667 0.0333 3.5343 +0.0889 0.0444 3.5343 +0.1111 0.0556 3.5343 +0.1333 0.0667 3.5343 +0.1556 0.0778 3.5343 +0.1778 0.0889 3.5343 +0.2000 0.1000 3.5343 +primID: 3 +startangle_c: 9 +endpose_c: -5 -4 10 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0596 -0.0369 3.5646 +-0.1184 -0.0757 3.5949 +-0.1762 -0.1165 3.6252 +-0.2330 -0.1592 3.6555 +-0.2887 -0.2037 3.6858 +-0.3433 -0.2501 3.7161 +-0.3968 -0.2983 3.7464 +-0.4490 -0.3483 3.7767 +-0.5000 -0.4000 3.8070 +primID: 4 +startangle_c: 9 +endpose_c: -7 -2 8 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0754 -0.0312 3.5343 +-0.1507 -0.0624 3.5343 +-0.2261 -0.0937 3.5343 +-0.3015 -0.1247 3.5152 +-0.3785 -0.1516 3.4405 +-0.4573 -0.1727 3.3658 +-0.5375 -0.1878 3.2910 +-0.6185 -0.1970 3.2163 +-0.7000 -0.2000 3.1416 +primID: 0 +startangle_c: 10 +endpose_c: -1 -1 10 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0111 -0.0111 3.9270 +-0.0222 -0.0222 3.9270 +-0.0333 -0.0333 3.9270 +-0.0444 -0.0444 3.9270 +-0.0556 -0.0556 3.9270 +-0.0667 -0.0667 3.9270 +-0.0778 -0.0778 3.9270 +-0.0889 -0.0889 3.9270 +-0.1000 -0.1000 3.9270 +primID: 1 +startangle_c: 10 +endpose_c: -6 -6 10 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0667 -0.0667 3.9270 +-0.1333 -0.1333 3.9270 +-0.2000 -0.2000 3.9270 +-0.2667 -0.2667 3.9270 +-0.3333 -0.3333 3.9270 +-0.4000 -0.4000 3.9270 +-0.4667 -0.4667 3.9270 +-0.5333 -0.5333 3.9270 +-0.6000 -0.6000 3.9270 +primID: 2 +startangle_c: 10 +endpose_c: 1 1 10 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0111 0.0111 3.9270 +0.0222 0.0222 3.9270 +0.0333 0.0333 3.9270 +0.0444 0.0444 3.9270 +0.0556 0.0556 3.9270 +0.0667 0.0667 3.9270 +0.0778 0.0778 3.9270 +0.0889 0.0889 3.9270 +0.1000 0.1000 3.9270 +primID: 3 +startangle_c: 10 +endpose_c: -5 -7 11 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0681 -0.0681 3.9270 +-0.1357 -0.1368 3.9567 +-0.1999 -0.2086 4.0085 +-0.2603 -0.2837 4.0604 +-0.3168 -0.3617 4.1123 +-0.3691 -0.4426 4.1641 +-0.4172 -0.5261 4.2160 +-0.4608 -0.6120 4.2678 +-0.5000 -0.7000 4.3197 +primID: 4 +startangle_c: 10 +endpose_c: -7 -5 9 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0681 -0.0681 3.9270 +-0.1368 -0.1357 3.8973 +-0.2086 -0.1999 3.8455 +-0.2837 -0.2603 3.7936 +-0.3617 -0.3168 3.7417 +-0.4426 -0.3691 3.6899 +-0.5261 -0.4172 3.6380 +-0.6120 -0.4608 3.5862 +-0.7000 -0.5000 3.5343 +primID: 0 +startangle_c: 11 +endpose_c: -1 -2 11 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0111 -0.0222 4.3197 +-0.0222 -0.0444 4.3197 +-0.0333 -0.0667 4.3197 +-0.0444 -0.0889 4.3197 +-0.0556 -0.1111 4.3197 +-0.0667 -0.1333 4.3197 +-0.0778 -0.1556 4.3197 +-0.0889 -0.1778 4.3197 +-0.1000 -0.2000 4.3197 +primID: 1 +startangle_c: 11 +endpose_c: -3 -6 11 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0333 -0.0667 4.3197 +-0.0667 -0.1333 4.3197 +-0.1000 -0.2000 4.3197 +-0.1333 -0.2667 4.3197 +-0.1667 -0.3333 4.3197 +-0.2000 -0.4000 4.3197 +-0.2333 -0.4667 4.3197 +-0.2667 -0.5333 4.3197 +-0.3000 -0.6000 4.3197 +primID: 2 +startangle_c: 11 +endpose_c: 1 2 11 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0111 0.0222 4.3197 +0.0222 0.0444 4.3197 +0.0333 0.0667 4.3197 +0.0444 0.0889 4.3197 +0.0556 0.1111 4.3197 +0.0667 0.1333 4.3197 +0.0778 0.1556 4.3197 +0.0889 0.1778 4.3197 +0.1000 0.2000 4.3197 +primID: 3 +startangle_c: 11 +endpose_c: -4 -5 10 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0369 -0.0596 4.2894 +-0.0757 -0.1184 4.2591 +-0.1165 -0.1762 4.2288 +-0.1592 -0.2330 4.1985 +-0.2037 -0.2887 4.1682 +-0.2501 -0.3433 4.1379 +-0.2983 -0.3968 4.1076 +-0.3483 -0.4490 4.0773 +-0.4000 -0.5000 4.0470 +primID: 4 +startangle_c: 11 +endpose_c: -2 -7 12 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0312 -0.0754 4.3197 +-0.0624 -0.1507 4.3197 +-0.0937 -0.2261 4.3197 +-0.1247 -0.3015 4.3388 +-0.1516 -0.3785 4.4135 +-0.1727 -0.4573 4.4882 +-0.1878 -0.5375 4.5629 +-0.1970 -0.6185 4.6377 +-0.2000 -0.7000 4.7124 +primID: 0 +startangle_c: 12 +endpose_c: 0 -1 12 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0111 4.7124 +0.0000 -0.0222 4.7124 +0.0000 -0.0333 4.7124 +0.0000 -0.0444 4.7124 +0.0000 -0.0556 4.7124 +0.0000 -0.0667 4.7124 +0.0000 -0.0778 4.7124 +0.0000 -0.0889 4.7124 +0.0000 -0.1000 4.7124 +primID: 1 +startangle_c: 12 +endpose_c: 0 -8 12 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0889 4.7124 +0.0000 -0.1778 4.7124 +0.0000 -0.2667 4.7124 +0.0000 -0.3556 4.7124 +0.0000 -0.4444 4.7124 +0.0000 -0.5333 4.7124 +0.0000 -0.6222 4.7124 +0.0000 -0.7111 4.7124 +0.0000 -0.8000 4.7124 +primID: 2 +startangle_c: 12 +endpose_c: 0 1 12 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0111 4.7124 +0.0000 0.0222 4.7124 +0.0000 0.0333 4.7124 +0.0000 0.0444 4.7124 +0.0000 0.0556 4.7124 +0.0000 0.0667 4.7124 +0.0000 0.0778 4.7124 +0.0000 0.0889 4.7124 +0.0000 0.1000 4.7124 +primID: 3 +startangle_c: 12 +endpose_c: 1 -8 13 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 4.7124 +-0.0000 -0.0904 4.7124 +-0.0000 -0.1807 4.7124 +-0.0000 -0.2711 4.7124 +0.0016 -0.3614 4.7612 +0.0091 -0.4514 4.8300 +0.0227 -0.5407 4.8988 +0.0425 -0.6288 4.9675 +0.0683 -0.7154 5.0363 +0.1000 -0.8000 5.1051 +primID: 4 +startangle_c: 12 +endpose_c: -1 -8 11 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 4.7124 +-0.0000 -0.0904 4.7124 +-0.0000 -0.1807 4.7124 +-0.0000 -0.2711 4.7124 +-0.0016 -0.3614 4.6636 +-0.0091 -0.4514 4.5948 +-0.0227 -0.5407 4.5260 +-0.0425 -0.6288 4.4572 +-0.0683 -0.7154 4.3885 +-0.1000 -0.8000 4.3197 +primID: 0 +startangle_c: 13 +endpose_c: 1 -2 13 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0111 -0.0222 5.1051 +0.0222 -0.0444 5.1051 +0.0333 -0.0667 5.1051 +0.0444 -0.0889 5.1051 +0.0556 -0.1111 5.1051 +0.0667 -0.1333 5.1051 +0.0778 -0.1556 5.1051 +0.0889 -0.1778 5.1051 +0.1000 -0.2000 5.1051 +primID: 1 +startangle_c: 13 +endpose_c: 3 -6 13 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0333 -0.0667 5.1051 +0.0667 -0.1333 5.1051 +0.1000 -0.2000 5.1051 +0.1333 -0.2667 5.1051 +0.1667 -0.3333 5.1051 +0.2000 -0.4000 5.1051 +0.2333 -0.4667 5.1051 +0.2667 -0.5333 5.1051 +0.3000 -0.6000 5.1051 +primID: 2 +startangle_c: 13 +endpose_c: -1 2 13 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 5.1051 +-0.0111 0.0222 5.1051 +-0.0222 0.0444 5.1051 +-0.0333 0.0667 5.1051 +-0.0444 0.0889 5.1051 +-0.0556 0.1111 5.1051 +-0.0667 0.1333 5.1051 +-0.0778 0.1556 5.1051 +-0.0889 0.1778 5.1051 +-0.1000 0.2000 5.1051 +primID: 3 +startangle_c: 13 +endpose_c: 4 -5 14 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0369 -0.0596 5.1354 +0.0757 -0.1184 5.1657 +0.1165 -0.1762 5.1960 +0.1592 -0.2330 5.2263 +0.2037 -0.2887 5.2566 +0.2501 -0.3433 5.2869 +0.2983 -0.3968 5.3172 +0.3483 -0.4490 5.3475 +0.4000 -0.5000 5.3778 +primID: 4 +startangle_c: 13 +endpose_c: 2 -7 12 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0312 -0.0754 5.1051 +0.0624 -0.1507 5.1051 +0.0937 -0.2261 5.1051 +0.1247 -0.3015 5.0860 +0.1516 -0.3785 5.0113 +0.1727 -0.4573 4.9366 +0.1878 -0.5375 4.8618 +0.1970 -0.6185 4.7871 +0.2000 -0.7000 4.7124 +primID: 0 +startangle_c: 14 +endpose_c: 1 -1 14 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0111 -0.0111 5.4978 +0.0222 -0.0222 5.4978 +0.0333 -0.0333 5.4978 +0.0444 -0.0444 5.4978 +0.0556 -0.0556 5.4978 +0.0667 -0.0667 5.4978 +0.0778 -0.0778 5.4978 +0.0889 -0.0889 5.4978 +0.1000 -0.1000 5.4978 +primID: 1 +startangle_c: 14 +endpose_c: 6 -6 14 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0667 -0.0667 5.4978 +0.1333 -0.1333 5.4978 +0.2000 -0.2000 5.4978 +0.2667 -0.2667 5.4978 +0.3333 -0.3333 5.4978 +0.4000 -0.4000 5.4978 +0.4667 -0.4667 5.4978 +0.5333 -0.5333 5.4978 +0.6000 -0.6000 5.4978 +primID: 2 +startangle_c: 14 +endpose_c: -1 1 14 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 5.4978 +-0.0111 0.0111 5.4978 +-0.0222 0.0222 5.4978 +-0.0333 0.0333 5.4978 +-0.0444 0.0444 5.4978 +-0.0556 0.0556 5.4978 +-0.0667 0.0667 5.4978 +-0.0778 0.0778 5.4978 +-0.0889 0.0889 5.4978 +-0.1000 0.1000 5.4978 +primID: 3 +startangle_c: 14 +endpose_c: 7 -5 15 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0681 -0.0681 5.4978 +0.1368 -0.1357 5.5275 +0.2086 -0.1999 5.5793 +0.2837 -0.2603 5.6312 +0.3617 -0.3168 5.6830 +0.4426 -0.3691 5.7349 +0.5261 -0.4172 5.7868 +0.6120 -0.4608 5.8386 +0.7000 -0.5000 5.8905 +primID: 4 +startangle_c: 14 +endpose_c: 5 -7 13 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0681 -0.0681 5.4978 +0.1357 -0.1368 5.4681 +0.1999 -0.2086 5.4162 +0.2603 -0.2837 5.3644 +0.3168 -0.3617 5.3125 +0.3691 -0.4426 5.2607 +0.4172 -0.5261 5.2088 +0.4608 -0.6120 5.1569 +0.5000 -0.7000 5.1051 +primID: 0 +startangle_c: 15 +endpose_c: 2 -1 15 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0222 -0.0111 5.8905 +0.0444 -0.0222 5.8905 +0.0667 -0.0333 5.8905 +0.0889 -0.0444 5.8905 +0.1111 -0.0556 5.8905 +0.1333 -0.0667 5.8905 +0.1556 -0.0778 5.8905 +0.1778 -0.0889 5.8905 +0.2000 -0.1000 5.8905 +primID: 1 +startangle_c: 15 +endpose_c: 6 -3 15 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0667 -0.0333 5.8905 +0.1333 -0.0667 5.8905 +0.2000 -0.1000 5.8905 +0.2667 -0.1333 5.8905 +0.3333 -0.1667 5.8905 +0.4000 -0.2000 5.8905 +0.4667 -0.2333 5.8905 +0.5333 -0.2667 5.8905 +0.6000 -0.3000 5.8905 +primID: 2 +startangle_c: 15 +endpose_c: -2 1 15 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 5.8905 +-0.0222 0.0111 5.8905 +-0.0444 0.0222 5.8905 +-0.0667 0.0333 5.8905 +-0.0889 0.0444 5.8905 +-0.1111 0.0556 5.8905 +-0.1333 0.0667 5.8905 +-0.1556 0.0778 5.8905 +-0.1778 0.0889 5.8905 +-0.2000 0.1000 5.8905 +primID: 3 +startangle_c: 15 +endpose_c: 5 -4 14 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0596 -0.0369 5.8602 +0.1184 -0.0757 5.8299 +0.1762 -0.1165 5.7996 +0.2330 -0.1592 5.7693 +0.2887 -0.2037 5.7390 +0.3433 -0.2501 5.7087 +0.3968 -0.2983 5.6784 +0.4490 -0.3483 5.6481 +0.5000 -0.4000 5.6178 +primID: 4 +startangle_c: 15 +endpose_c: 7 -2 0 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0754 -0.0312 5.8905 +0.1507 -0.0624 5.8905 +0.2261 -0.0937 5.8905 +0.3015 -0.1247 5.9096 +0.3785 -0.1516 5.9843 +0.4573 -0.1727 6.0590 +0.5375 -0.1878 6.1337 +0.6185 -0.1970 6.2085 +0.7000 -0.2000 6.2832 diff --git a/navigations/sbpl/matlab/mprim/pr2sides.mprim b/navigations/sbpl/matlab/mprim/pr2sides.mprim new file mode 100755 index 0000000..555cdbd --- /dev/null +++ b/navigations/sbpl/matlab/mprim/pr2sides.mprim @@ -0,0 +1,2163 @@ +resolution_m: 0.025000 +numberofangles: 16 +totalnumberofprimitives: 144 +primID: 0 +startangle_c: 0 +endpose_c: 1 0 0 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0028 0.0000 0.0000 +0.0056 0.0000 0.0000 +0.0083 0.0000 0.0000 +0.0111 0.0000 0.0000 +0.0139 0.0000 0.0000 +0.0167 0.0000 0.0000 +0.0194 0.0000 0.0000 +0.0222 0.0000 0.0000 +0.0250 0.0000 0.0000 +primID: 1 +startangle_c: 0 +endpose_c: 8 0 0 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0222 0.0000 0.0000 +0.0444 0.0000 0.0000 +0.0667 0.0000 0.0000 +0.0889 0.0000 0.0000 +0.1111 0.0000 0.0000 +0.1333 0.0000 0.0000 +0.1556 0.0000 0.0000 +0.1778 0.0000 0.0000 +0.2000 0.0000 0.0000 +primID: 2 +startangle_c: 0 +endpose_c: -1 0 0 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 0.0000 +-0.0028 0.0000 0.0000 +-0.0056 0.0000 0.0000 +-0.0083 0.0000 0.0000 +-0.0111 0.0000 0.0000 +-0.0139 0.0000 0.0000 +-0.0167 0.0000 0.0000 +-0.0194 0.0000 0.0000 +-0.0222 0.0000 0.0000 +-0.0250 0.0000 0.0000 +primID: 3 +startangle_c: 0 +endpose_c: 8 1 1 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0226 -0.0000 0.0000 +0.0452 -0.0000 0.0000 +0.0678 -0.0000 0.0000 +0.0903 0.0004 0.0488 +0.1128 0.0023 0.1176 +0.1352 0.0057 0.1864 +0.1572 0.0106 0.2551 +0.1789 0.0171 0.3239 +0.2000 0.0250 0.3927 +primID: 4 +startangle_c: 0 +endpose_c: 8 -1 -1 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0226 0.0000 0.0000 +0.0452 0.0000 0.0000 +0.0678 0.0000 0.0000 +0.0903 -0.0004 -0.0488 +0.1128 -0.0023 -0.1176 +0.1352 -0.0057 -0.1864 +0.1572 -0.0106 -0.2551 +0.1789 -0.0171 -0.3239 +0.2000 -0.0250 -0.3927 +primID: 5 +startangle_c: 0 +endpose_c: 0 0 1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0000 0.0000 0.0436 +0.0000 0.0000 0.0873 +0.0000 0.0000 0.1309 +0.0000 0.0000 0.1745 +0.0000 0.0000 0.2182 +0.0000 0.0000 0.2618 +0.0000 0.0000 0.3054 +0.0000 0.0000 0.3491 +0.0000 0.0000 0.3927 +primID: 6 +startangle_c: 0 +endpose_c: 0 0 -1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0000 0.0000 -0.0436 +0.0000 0.0000 -0.0873 +0.0000 0.0000 -0.1309 +0.0000 0.0000 -0.1745 +0.0000 0.0000 -0.2182 +0.0000 0.0000 -0.2618 +0.0000 0.0000 -0.3054 +0.0000 0.0000 -0.3491 +0.0000 0.0000 -0.3927 +primID: 7 +startangle_c: 0 +endpose_c: 0 1 0 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0000 0.0028 0.0000 +0.0000 0.0056 0.0000 +0.0000 0.0083 0.0000 +0.0000 0.0111 0.0000 +0.0000 0.0139 0.0000 +0.0000 0.0167 0.0000 +0.0000 0.0194 0.0000 +0.0000 0.0222 0.0000 +0.0000 0.0250 0.0000 +primID: 8 +startangle_c: 0 +endpose_c: 0 -1 0 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0000 -0.0028 0.0000 +0.0000 -0.0056 0.0000 +0.0000 -0.0083 0.0000 +0.0000 -0.0111 0.0000 +0.0000 -0.0139 0.0000 +0.0000 -0.0167 0.0000 +0.0000 -0.0194 0.0000 +0.0000 -0.0222 0.0000 +0.0000 -0.0250 0.0000 +primID: 0 +startangle_c: 1 +endpose_c: 2 1 1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0056 0.0028 0.3927 +0.0111 0.0056 0.3927 +0.0167 0.0083 0.3927 +0.0222 0.0111 0.3927 +0.0278 0.0139 0.3927 +0.0333 0.0167 0.3927 +0.0389 0.0194 0.3927 +0.0444 0.0222 0.3927 +0.0500 0.0250 0.3927 +primID: 1 +startangle_c: 1 +endpose_c: 6 3 1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0167 0.0083 0.3927 +0.0333 0.0167 0.3927 +0.0500 0.0250 0.3927 +0.0667 0.0333 0.3927 +0.0833 0.0417 0.3927 +0.1000 0.0500 0.3927 +0.1167 0.0583 0.3927 +0.1333 0.0667 0.3927 +0.1500 0.0750 0.3927 +primID: 2 +startangle_c: 1 +endpose_c: -2 -1 1 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 0.3927 +-0.0056 -0.0028 0.3927 +-0.0111 -0.0056 0.3927 +-0.0167 -0.0083 0.3927 +-0.0222 -0.0111 0.3927 +-0.0278 -0.0139 0.3927 +-0.0333 -0.0167 0.3927 +-0.0389 -0.0194 0.3927 +-0.0444 -0.0222 0.3927 +-0.0500 -0.0250 0.3927 +primID: 3 +startangle_c: 1 +endpose_c: 5 4 2 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0149 0.0092 0.4230 +0.0296 0.0189 0.4533 +0.0440 0.0291 0.4836 +0.0582 0.0398 0.5139 +0.0722 0.0509 0.5442 +0.0858 0.0625 0.5745 +0.0992 0.0746 0.6048 +0.1123 0.0871 0.6351 +0.1250 0.1000 0.6654 +primID: 4 +startangle_c: 1 +endpose_c: 7 2 0 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0188 0.0078 0.3927 +0.0377 0.0156 0.3927 +0.0565 0.0234 0.3927 +0.0754 0.0312 0.3736 +0.0946 0.0379 0.2989 +0.1143 0.0432 0.2242 +0.1344 0.0470 0.1494 +0.1546 0.0492 0.0747 +0.1750 0.0500 0.0000 +primID: 5 +startangle_c: 1 +endpose_c: 0 0 2 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0000 0.0000 0.4363 +0.0000 0.0000 0.4800 +0.0000 0.0000 0.5236 +0.0000 0.0000 0.5672 +0.0000 0.0000 0.6109 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.6981 +0.0000 0.0000 0.7418 +0.0000 0.0000 0.7854 +primID: 6 +startangle_c: 1 +endpose_c: 0 0 0 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0000 0.0000 0.3491 +0.0000 0.0000 0.3054 +0.0000 0.0000 0.2618 +0.0000 0.0000 0.2182 +0.0000 0.0000 0.1745 +0.0000 0.0000 0.1309 +0.0000 0.0000 0.0873 +0.0000 0.0000 0.0436 +0.0000 0.0000 0.0000 +primID: 7 +startangle_c: 1 +endpose_c: -1 2 1 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.3927 +-0.0028 0.0056 0.3927 +-0.0056 0.0111 0.3927 +-0.0083 0.0167 0.3927 +-0.0111 0.0222 0.3927 +-0.0139 0.0278 0.3927 +-0.0167 0.0333 0.3927 +-0.0194 0.0389 0.3927 +-0.0222 0.0444 0.3927 +-0.0250 0.0500 0.3927 +primID: 8 +startangle_c: 1 +endpose_c: 1 -2 1 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0028 -0.0056 0.3927 +0.0056 -0.0111 0.3927 +0.0083 -0.0167 0.3927 +0.0111 -0.0222 0.3927 +0.0139 -0.0278 0.3927 +0.0167 -0.0333 0.3927 +0.0194 -0.0389 0.3927 +0.0222 -0.0444 0.3927 +0.0250 -0.0500 0.3927 +primID: 0 +startangle_c: 2 +endpose_c: 1 1 2 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0028 0.0028 0.7854 +0.0056 0.0056 0.7854 +0.0083 0.0083 0.7854 +0.0111 0.0111 0.7854 +0.0139 0.0139 0.7854 +0.0167 0.0167 0.7854 +0.0194 0.0194 0.7854 +0.0222 0.0222 0.7854 +0.0250 0.0250 0.7854 +primID: 1 +startangle_c: 2 +endpose_c: 6 6 2 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0167 0.0167 0.7854 +0.0333 0.0333 0.7854 +0.0500 0.0500 0.7854 +0.0667 0.0667 0.7854 +0.0833 0.0833 0.7854 +0.1000 0.1000 0.7854 +0.1167 0.1167 0.7854 +0.1333 0.1333 0.7854 +0.1500 0.1500 0.7854 +primID: 2 +startangle_c: 2 +endpose_c: -1 -1 2 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 0.7854 +-0.0028 -0.0028 0.7854 +-0.0056 -0.0056 0.7854 +-0.0083 -0.0083 0.7854 +-0.0111 -0.0111 0.7854 +-0.0139 -0.0139 0.7854 +-0.0167 -0.0167 0.7854 +-0.0194 -0.0194 0.7854 +-0.0222 -0.0222 0.7854 +-0.0250 -0.0250 0.7854 +primID: 3 +startangle_c: 2 +endpose_c: 5 7 3 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0170 0.0170 0.7854 +0.0339 0.0342 0.8151 +0.0500 0.0522 0.8669 +0.0651 0.0709 0.9188 +0.0792 0.0904 0.9707 +0.0923 0.1107 1.0225 +0.1043 0.1315 1.0744 +0.1152 0.1530 1.1262 +0.1250 0.1750 1.1781 +primID: 4 +startangle_c: 2 +endpose_c: 7 5 1 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0170 0.0170 0.7854 +0.0342 0.0339 0.7557 +0.0522 0.0500 0.7039 +0.0709 0.0651 0.6520 +0.0904 0.0792 0.6001 +0.1107 0.0923 0.5483 +0.1315 0.1043 0.4964 +0.1530 0.1152 0.4446 +0.1750 0.1250 0.3927 +primID: 5 +startangle_c: 2 +endpose_c: 0 0 3 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0000 0.0000 0.8290 +0.0000 0.0000 0.8727 +0.0000 0.0000 0.9163 +0.0000 0.0000 0.9599 +0.0000 0.0000 1.0036 +0.0000 0.0000 1.0472 +0.0000 0.0000 1.0908 +0.0000 0.0000 1.1345 +0.0000 0.0000 1.1781 +primID: 6 +startangle_c: 2 +endpose_c: 0 0 1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0000 0.0000 0.7418 +0.0000 0.0000 0.6981 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.6109 +0.0000 0.0000 0.5672 +0.0000 0.0000 0.5236 +0.0000 0.0000 0.4800 +0.0000 0.0000 0.4363 +0.0000 0.0000 0.3927 +primID: 7 +startangle_c: 2 +endpose_c: -1 1 2 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.7854 +-0.0028 0.0028 0.7854 +-0.0056 0.0056 0.7854 +-0.0083 0.0083 0.7854 +-0.0111 0.0111 0.7854 +-0.0139 0.0139 0.7854 +-0.0167 0.0167 0.7854 +-0.0194 0.0194 0.7854 +-0.0222 0.0222 0.7854 +-0.0250 0.0250 0.7854 +primID: 8 +startangle_c: 2 +endpose_c: 1 -1 2 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0028 -0.0028 0.7854 +0.0056 -0.0056 0.7854 +0.0083 -0.0083 0.7854 +0.0111 -0.0111 0.7854 +0.0139 -0.0139 0.7854 +0.0167 -0.0167 0.7854 +0.0194 -0.0194 0.7854 +0.0222 -0.0222 0.7854 +0.0250 -0.0250 0.7854 +primID: 0 +startangle_c: 3 +endpose_c: 1 2 3 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0028 0.0056 1.1781 +0.0056 0.0111 1.1781 +0.0083 0.0167 1.1781 +0.0111 0.0222 1.1781 +0.0139 0.0278 1.1781 +0.0167 0.0333 1.1781 +0.0194 0.0389 1.1781 +0.0222 0.0444 1.1781 +0.0250 0.0500 1.1781 +primID: 1 +startangle_c: 3 +endpose_c: 3 6 3 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0083 0.0167 1.1781 +0.0167 0.0333 1.1781 +0.0250 0.0500 1.1781 +0.0333 0.0667 1.1781 +0.0417 0.0833 1.1781 +0.0500 0.1000 1.1781 +0.0583 0.1167 1.1781 +0.0667 0.1333 1.1781 +0.0750 0.1500 1.1781 +primID: 2 +startangle_c: 3 +endpose_c: -1 -2 3 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 1.1781 +-0.0028 -0.0056 1.1781 +-0.0056 -0.0111 1.1781 +-0.0083 -0.0167 1.1781 +-0.0111 -0.0222 1.1781 +-0.0139 -0.0278 1.1781 +-0.0167 -0.0333 1.1781 +-0.0194 -0.0389 1.1781 +-0.0222 -0.0444 1.1781 +-0.0250 -0.0500 1.1781 +primID: 3 +startangle_c: 3 +endpose_c: 4 5 2 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0092 0.0149 1.1478 +0.0189 0.0296 1.1175 +0.0291 0.0440 1.0872 +0.0398 0.0582 1.0569 +0.0509 0.0722 1.0266 +0.0625 0.0858 0.9963 +0.0746 0.0992 0.9660 +0.0871 0.1123 0.9357 +0.1000 0.1250 0.9054 +primID: 4 +startangle_c: 3 +endpose_c: 2 7 4 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0078 0.0188 1.1781 +0.0156 0.0377 1.1781 +0.0234 0.0565 1.1781 +0.0312 0.0754 1.1972 +0.0379 0.0946 1.2719 +0.0432 0.1143 1.3466 +0.0470 0.1344 1.4214 +0.0492 0.1546 1.4961 +0.0500 0.1750 1.5708 +primID: 5 +startangle_c: 3 +endpose_c: 0 0 2 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0000 0.0000 1.1345 +0.0000 0.0000 1.0908 +0.0000 0.0000 1.0472 +0.0000 0.0000 1.0036 +0.0000 0.0000 0.9599 +0.0000 0.0000 0.9163 +0.0000 0.0000 0.8727 +0.0000 0.0000 0.8290 +0.0000 0.0000 0.7854 +primID: 6 +startangle_c: 3 +endpose_c: 0 0 4 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0000 0.0000 1.2217 +0.0000 0.0000 1.2654 +0.0000 0.0000 1.3090 +0.0000 0.0000 1.3526 +0.0000 0.0000 1.3963 +0.0000 0.0000 1.4399 +0.0000 0.0000 1.4835 +0.0000 0.0000 1.5272 +0.0000 0.0000 1.5708 +primID: 7 +startangle_c: 3 +endpose_c: 2 -1 3 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0056 -0.0028 1.1781 +0.0111 -0.0056 1.1781 +0.0167 -0.0083 1.1781 +0.0222 -0.0111 1.1781 +0.0278 -0.0139 1.1781 +0.0333 -0.0167 1.1781 +0.0389 -0.0194 1.1781 +0.0444 -0.0222 1.1781 +0.0500 -0.0250 1.1781 +primID: 8 +startangle_c: 3 +endpose_c: -2 1 3 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.1781 +-0.0056 0.0028 1.1781 +-0.0111 0.0056 1.1781 +-0.0167 0.0083 1.1781 +-0.0222 0.0111 1.1781 +-0.0278 0.0139 1.1781 +-0.0333 0.0167 1.1781 +-0.0389 0.0194 1.1781 +-0.0444 0.0222 1.1781 +-0.0500 0.0250 1.1781 +primID: 0 +startangle_c: 4 +endpose_c: 0 1 4 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0028 1.5708 +0.0000 0.0056 1.5708 +0.0000 0.0083 1.5708 +0.0000 0.0111 1.5708 +0.0000 0.0139 1.5708 +0.0000 0.0167 1.5708 +0.0000 0.0194 1.5708 +0.0000 0.0222 1.5708 +0.0000 0.0250 1.5708 +primID: 1 +startangle_c: 4 +endpose_c: 0 8 4 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0222 1.5708 +0.0000 0.0444 1.5708 +0.0000 0.0667 1.5708 +0.0000 0.0889 1.5708 +0.0000 0.1111 1.5708 +0.0000 0.1333 1.5708 +0.0000 0.1556 1.5708 +0.0000 0.1778 1.5708 +0.0000 0.2000 1.5708 +primID: 2 +startangle_c: 4 +endpose_c: 0 -1 4 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 -0.0028 1.5708 +0.0000 -0.0056 1.5708 +0.0000 -0.0083 1.5708 +0.0000 -0.0111 1.5708 +0.0000 -0.0139 1.5708 +0.0000 -0.0167 1.5708 +0.0000 -0.0194 1.5708 +0.0000 -0.0222 1.5708 +0.0000 -0.0250 1.5708 +primID: 3 +startangle_c: 4 +endpose_c: -1 8 5 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0226 1.5708 +0.0000 0.0452 1.5708 +0.0000 0.0678 1.5708 +-0.0004 0.0903 1.6196 +-0.0023 0.1128 1.6884 +-0.0057 0.1352 1.7572 +-0.0106 0.1572 1.8259 +-0.0171 0.1789 1.8947 +-0.0250 0.2000 1.9635 +primID: 4 +startangle_c: 4 +endpose_c: 1 8 3 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 1.5708 +-0.0000 0.0226 1.5708 +-0.0000 0.0452 1.5708 +-0.0000 0.0678 1.5708 +0.0004 0.0903 1.5220 +0.0023 0.1128 1.4532 +0.0057 0.1352 1.3844 +0.0106 0.1572 1.3156 +0.0171 0.1789 1.2469 +0.0250 0.2000 1.1781 +primID: 5 +startangle_c: 4 +endpose_c: 0 0 5 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0000 1.6144 +0.0000 0.0000 1.6581 +0.0000 0.0000 1.7017 +0.0000 0.0000 1.7453 +0.0000 0.0000 1.7890 +0.0000 0.0000 1.8326 +0.0000 0.0000 1.8762 +0.0000 0.0000 1.9199 +0.0000 0.0000 1.9635 +primID: 6 +startangle_c: 4 +endpose_c: 0 0 3 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0000 1.5272 +0.0000 0.0000 1.4835 +0.0000 0.0000 1.4399 +0.0000 0.0000 1.3963 +0.0000 0.0000 1.3526 +0.0000 0.0000 1.3090 +0.0000 0.0000 1.2654 +0.0000 0.0000 1.2217 +0.0000 0.0000 1.1781 +primID: 7 +startangle_c: 4 +endpose_c: -1 0 4 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.5708 +-0.0028 0.0000 1.5708 +-0.0056 0.0000 1.5708 +-0.0083 0.0000 1.5708 +-0.0111 0.0000 1.5708 +-0.0139 0.0000 1.5708 +-0.0167 0.0000 1.5708 +-0.0194 0.0000 1.5708 +-0.0222 0.0000 1.5708 +-0.0250 0.0000 1.5708 +primID: 8 +startangle_c: 4 +endpose_c: 1 0 4 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0028 0.0000 1.5708 +0.0056 0.0000 1.5708 +0.0083 0.0000 1.5708 +0.0111 0.0000 1.5708 +0.0139 0.0000 1.5708 +0.0167 0.0000 1.5708 +0.0194 0.0000 1.5708 +0.0222 0.0000 1.5708 +0.0250 0.0000 1.5708 +primID: 0 +startangle_c: 5 +endpose_c: -1 2 5 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0028 0.0056 1.9635 +-0.0056 0.0111 1.9635 +-0.0083 0.0167 1.9635 +-0.0111 0.0222 1.9635 +-0.0139 0.0278 1.9635 +-0.0167 0.0333 1.9635 +-0.0194 0.0389 1.9635 +-0.0222 0.0444 1.9635 +-0.0250 0.0500 1.9635 +primID: 1 +startangle_c: 5 +endpose_c: -3 6 5 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0083 0.0167 1.9635 +-0.0167 0.0333 1.9635 +-0.0250 0.0500 1.9635 +-0.0333 0.0667 1.9635 +-0.0417 0.0833 1.9635 +-0.0500 0.1000 1.9635 +-0.0583 0.1167 1.9635 +-0.0667 0.1333 1.9635 +-0.0750 0.1500 1.9635 +primID: 2 +startangle_c: 5 +endpose_c: 1 -2 5 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0028 -0.0056 1.9635 +0.0056 -0.0111 1.9635 +0.0083 -0.0167 1.9635 +0.0111 -0.0222 1.9635 +0.0139 -0.0278 1.9635 +0.0167 -0.0333 1.9635 +0.0194 -0.0389 1.9635 +0.0222 -0.0444 1.9635 +0.0250 -0.0500 1.9635 +primID: 3 +startangle_c: 5 +endpose_c: -4 5 6 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0092 0.0149 1.9938 +-0.0189 0.0296 2.0241 +-0.0291 0.0440 2.0544 +-0.0398 0.0582 2.0847 +-0.0509 0.0722 2.1150 +-0.0625 0.0858 2.1453 +-0.0746 0.0992 2.1756 +-0.0871 0.1123 2.2059 +-0.1000 0.1250 2.2362 +primID: 4 +startangle_c: 5 +endpose_c: -2 7 4 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0078 0.0188 1.9635 +-0.0156 0.0377 1.9635 +-0.0234 0.0565 1.9635 +-0.0312 0.0754 1.9444 +-0.0379 0.0946 1.8697 +-0.0432 0.1143 1.7950 +-0.0470 0.1344 1.7202 +-0.0492 0.1546 1.6455 +-0.0500 0.1750 1.5708 +primID: 5 +startangle_c: 5 +endpose_c: 0 0 6 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0000 0.0000 2.0071 +0.0000 0.0000 2.0508 +0.0000 0.0000 2.0944 +0.0000 0.0000 2.1380 +0.0000 0.0000 2.1817 +0.0000 0.0000 2.2253 +0.0000 0.0000 2.2689 +0.0000 0.0000 2.3126 +0.0000 0.0000 2.3562 +primID: 6 +startangle_c: 5 +endpose_c: 0 0 4 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0000 0.0000 1.9199 +0.0000 0.0000 1.8762 +0.0000 0.0000 1.8326 +0.0000 0.0000 1.7890 +0.0000 0.0000 1.7453 +0.0000 0.0000 1.7017 +0.0000 0.0000 1.6581 +0.0000 0.0000 1.6144 +0.0000 0.0000 1.5708 +primID: 7 +startangle_c: 5 +endpose_c: -2 -1 5 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0056 -0.0028 1.9635 +-0.0111 -0.0056 1.9635 +-0.0167 -0.0083 1.9635 +-0.0222 -0.0111 1.9635 +-0.0278 -0.0139 1.9635 +-0.0333 -0.0167 1.9635 +-0.0389 -0.0194 1.9635 +-0.0444 -0.0222 1.9635 +-0.0500 -0.0250 1.9635 +primID: 8 +startangle_c: 5 +endpose_c: 2 1 5 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0056 0.0028 1.9635 +0.0111 0.0056 1.9635 +0.0167 0.0083 1.9635 +0.0222 0.0111 1.9635 +0.0278 0.0139 1.9635 +0.0333 0.0167 1.9635 +0.0389 0.0194 1.9635 +0.0444 0.0222 1.9635 +0.0500 0.0250 1.9635 +primID: 0 +startangle_c: 6 +endpose_c: -1 1 6 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0028 0.0028 2.3562 +-0.0056 0.0056 2.3562 +-0.0083 0.0083 2.3562 +-0.0111 0.0111 2.3562 +-0.0139 0.0139 2.3562 +-0.0167 0.0167 2.3562 +-0.0194 0.0194 2.3562 +-0.0222 0.0222 2.3562 +-0.0250 0.0250 2.3562 +primID: 1 +startangle_c: 6 +endpose_c: -6 6 6 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0167 0.0167 2.3562 +-0.0333 0.0333 2.3562 +-0.0500 0.0500 2.3562 +-0.0667 0.0667 2.3562 +-0.0833 0.0833 2.3562 +-0.1000 0.1000 2.3562 +-0.1167 0.1167 2.3562 +-0.1333 0.1333 2.3562 +-0.1500 0.1500 2.3562 +primID: 2 +startangle_c: 6 +endpose_c: 1 -1 6 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0028 -0.0028 2.3562 +0.0056 -0.0056 2.3562 +0.0083 -0.0083 2.3562 +0.0111 -0.0111 2.3562 +0.0139 -0.0139 2.3562 +0.0167 -0.0167 2.3562 +0.0194 -0.0194 2.3562 +0.0222 -0.0222 2.3562 +0.0250 -0.0250 2.3562 +primID: 3 +startangle_c: 6 +endpose_c: -7 5 7 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0170 0.0170 2.3562 +-0.0342 0.0339 2.3859 +-0.0522 0.0500 2.4377 +-0.0709 0.0651 2.4896 +-0.0904 0.0792 2.5415 +-0.1107 0.0923 2.5933 +-0.1315 0.1043 2.6452 +-0.1530 0.1152 2.6970 +-0.1750 0.1250 2.7489 +primID: 4 +startangle_c: 6 +endpose_c: -5 7 5 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0170 0.0170 2.3562 +-0.0339 0.0342 2.3265 +-0.0500 0.0522 2.2747 +-0.0651 0.0709 2.2228 +-0.0792 0.0904 2.1709 +-0.0923 0.1107 2.1191 +-0.1043 0.1315 2.0672 +-0.1152 0.1530 2.0154 +-0.1250 0.1750 1.9635 +primID: 5 +startangle_c: 6 +endpose_c: 0 0 7 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0000 0.0000 2.3998 +0.0000 0.0000 2.4435 +0.0000 0.0000 2.4871 +0.0000 0.0000 2.5307 +0.0000 0.0000 2.5744 +0.0000 0.0000 2.6180 +0.0000 0.0000 2.6616 +0.0000 0.0000 2.7053 +0.0000 0.0000 2.7489 +primID: 6 +startangle_c: 6 +endpose_c: 0 0 5 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0000 0.0000 2.3126 +0.0000 0.0000 2.2689 +0.0000 0.0000 2.2253 +0.0000 0.0000 2.1817 +0.0000 0.0000 2.1380 +0.0000 0.0000 2.0944 +0.0000 0.0000 2.0508 +0.0000 0.0000 2.0071 +0.0000 0.0000 1.9635 +primID: 7 +startangle_c: 6 +endpose_c: -1 -1 6 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0028 -0.0028 2.3562 +-0.0056 -0.0056 2.3562 +-0.0083 -0.0083 2.3562 +-0.0111 -0.0111 2.3562 +-0.0139 -0.0139 2.3562 +-0.0167 -0.0167 2.3562 +-0.0194 -0.0194 2.3562 +-0.0222 -0.0222 2.3562 +-0.0250 -0.0250 2.3562 +primID: 8 +startangle_c: 6 +endpose_c: 1 1 6 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0028 0.0028 2.3562 +0.0056 0.0056 2.3562 +0.0083 0.0083 2.3562 +0.0111 0.0111 2.3562 +0.0139 0.0139 2.3562 +0.0167 0.0167 2.3562 +0.0194 0.0194 2.3562 +0.0222 0.0222 2.3562 +0.0250 0.0250 2.3562 +primID: 0 +startangle_c: 7 +endpose_c: -2 1 7 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0056 0.0028 2.7489 +-0.0111 0.0056 2.7489 +-0.0167 0.0083 2.7489 +-0.0222 0.0111 2.7489 +-0.0278 0.0139 2.7489 +-0.0333 0.0167 2.7489 +-0.0389 0.0194 2.7489 +-0.0444 0.0222 2.7489 +-0.0500 0.0250 2.7489 +primID: 1 +startangle_c: 7 +endpose_c: -6 3 7 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0167 0.0083 2.7489 +-0.0333 0.0167 2.7489 +-0.0500 0.0250 2.7489 +-0.0667 0.0333 2.7489 +-0.0833 0.0417 2.7489 +-0.1000 0.0500 2.7489 +-0.1167 0.0583 2.7489 +-0.1333 0.0667 2.7489 +-0.1500 0.0750 2.7489 +primID: 2 +startangle_c: 7 +endpose_c: 2 -1 7 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0056 -0.0028 2.7489 +0.0111 -0.0056 2.7489 +0.0167 -0.0083 2.7489 +0.0222 -0.0111 2.7489 +0.0278 -0.0139 2.7489 +0.0333 -0.0167 2.7489 +0.0389 -0.0194 2.7489 +0.0444 -0.0222 2.7489 +0.0500 -0.0250 2.7489 +primID: 3 +startangle_c: 7 +endpose_c: -5 4 6 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0149 0.0092 2.7186 +-0.0296 0.0189 2.6883 +-0.0440 0.0291 2.6580 +-0.0582 0.0398 2.6277 +-0.0722 0.0509 2.5974 +-0.0858 0.0625 2.5671 +-0.0992 0.0746 2.5368 +-0.1123 0.0871 2.5065 +-0.1250 0.1000 2.4762 +primID: 4 +startangle_c: 7 +endpose_c: -7 2 8 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0188 0.0078 2.7489 +-0.0377 0.0156 2.7489 +-0.0565 0.0234 2.7489 +-0.0754 0.0312 2.7680 +-0.0946 0.0379 2.8427 +-0.1143 0.0432 2.9174 +-0.1344 0.0470 2.9921 +-0.1546 0.0492 3.0669 +-0.1750 0.0500 3.1416 +primID: 5 +startangle_c: 7 +endpose_c: 0 0 6 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0000 0.0000 2.7053 +0.0000 0.0000 2.6616 +0.0000 0.0000 2.6180 +0.0000 0.0000 2.5744 +0.0000 0.0000 2.5307 +0.0000 0.0000 2.4871 +0.0000 0.0000 2.4435 +0.0000 0.0000 2.3998 +0.0000 0.0000 2.3562 +primID: 6 +startangle_c: 7 +endpose_c: 0 0 8 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0000 0.0000 2.7925 +0.0000 0.0000 2.8362 +0.0000 0.0000 2.8798 +0.0000 0.0000 2.9234 +0.0000 0.0000 2.9671 +0.0000 0.0000 3.0107 +0.0000 0.0000 3.0543 +0.0000 0.0000 3.0980 +0.0000 0.0000 3.1416 +primID: 7 +startangle_c: 7 +endpose_c: 1 2 7 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0028 0.0056 2.7489 +0.0056 0.0111 2.7489 +0.0083 0.0167 2.7489 +0.0111 0.0222 2.7489 +0.0139 0.0278 2.7489 +0.0167 0.0333 2.7489 +0.0194 0.0389 2.7489 +0.0222 0.0444 2.7489 +0.0250 0.0500 2.7489 +primID: 8 +startangle_c: 7 +endpose_c: -1 -2 7 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0028 -0.0056 2.7489 +-0.0056 -0.0111 2.7489 +-0.0083 -0.0167 2.7489 +-0.0111 -0.0222 2.7489 +-0.0139 -0.0278 2.7489 +-0.0167 -0.0333 2.7489 +-0.0194 -0.0389 2.7489 +-0.0222 -0.0444 2.7489 +-0.0250 -0.0500 2.7489 +primID: 0 +startangle_c: 8 +endpose_c: -1 0 8 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0028 0.0000 3.1416 +-0.0056 0.0000 3.1416 +-0.0083 0.0000 3.1416 +-0.0111 0.0000 3.1416 +-0.0139 0.0000 3.1416 +-0.0167 0.0000 3.1416 +-0.0194 0.0000 3.1416 +-0.0222 0.0000 3.1416 +-0.0250 0.0000 3.1416 +primID: 1 +startangle_c: 8 +endpose_c: -8 0 8 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0222 0.0000 3.1416 +-0.0444 0.0000 3.1416 +-0.0667 0.0000 3.1416 +-0.0889 0.0000 3.1416 +-0.1111 0.0000 3.1416 +-0.1333 0.0000 3.1416 +-0.1556 0.0000 3.1416 +-0.1778 0.0000 3.1416 +-0.2000 0.0000 3.1416 +primID: 2 +startangle_c: 8 +endpose_c: 1 0 8 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0028 0.0000 3.1416 +0.0056 0.0000 3.1416 +0.0083 0.0000 3.1416 +0.0111 0.0000 3.1416 +0.0139 0.0000 3.1416 +0.0167 0.0000 3.1416 +0.0194 0.0000 3.1416 +0.0222 0.0000 3.1416 +0.0250 0.0000 3.1416 +primID: 3 +startangle_c: 8 +endpose_c: -8 -1 9 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0226 0.0000 3.1416 +-0.0452 0.0000 3.1416 +-0.0678 0.0000 3.1416 +-0.0903 -0.0004 3.1904 +-0.1128 -0.0023 3.2592 +-0.1352 -0.0057 3.3280 +-0.1572 -0.0106 3.3967 +-0.1789 -0.0171 3.4655 +-0.2000 -0.0250 3.5343 +primID: 4 +startangle_c: 8 +endpose_c: -8 1 7 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0226 0.0000 3.1416 +-0.0452 0.0000 3.1416 +-0.0678 0.0000 3.1416 +-0.0903 0.0004 3.0928 +-0.1128 0.0023 3.0240 +-0.1352 0.0057 2.9552 +-0.1572 0.0106 2.8864 +-0.1789 0.0171 2.8177 +-0.2000 0.0250 2.7489 +primID: 5 +startangle_c: 8 +endpose_c: 0 0 9 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0000 0.0000 3.1852 +0.0000 0.0000 3.2289 +0.0000 0.0000 3.2725 +0.0000 0.0000 3.3161 +0.0000 0.0000 3.3598 +0.0000 0.0000 3.4034 +0.0000 0.0000 3.4470 +0.0000 0.0000 3.4907 +0.0000 0.0000 3.5343 +primID: 6 +startangle_c: 8 +endpose_c: 0 0 7 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0000 0.0000 3.0980 +0.0000 0.0000 3.0543 +0.0000 0.0000 3.0107 +0.0000 0.0000 2.9671 +0.0000 0.0000 2.9234 +0.0000 0.0000 2.8798 +0.0000 0.0000 2.8362 +0.0000 0.0000 2.7925 +0.0000 0.0000 2.7489 +primID: 7 +startangle_c: 8 +endpose_c: 0 -1 8 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0000 -0.0028 3.1416 +0.0000 -0.0056 3.1416 +0.0000 -0.0083 3.1416 +0.0000 -0.0111 3.1416 +0.0000 -0.0139 3.1416 +0.0000 -0.0167 3.1416 +0.0000 -0.0194 3.1416 +0.0000 -0.0222 3.1416 +0.0000 -0.0250 3.1416 +primID: 8 +startangle_c: 8 +endpose_c: 0 1 8 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0000 0.0028 3.1416 +0.0000 0.0056 3.1416 +0.0000 0.0083 3.1416 +0.0000 0.0111 3.1416 +0.0000 0.0139 3.1416 +0.0000 0.0167 3.1416 +0.0000 0.0194 3.1416 +0.0000 0.0222 3.1416 +0.0000 0.0250 3.1416 +primID: 0 +startangle_c: 9 +endpose_c: -2 -1 9 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0056 -0.0028 3.5343 +-0.0111 -0.0056 3.5343 +-0.0167 -0.0083 3.5343 +-0.0222 -0.0111 3.5343 +-0.0278 -0.0139 3.5343 +-0.0333 -0.0167 3.5343 +-0.0389 -0.0194 3.5343 +-0.0444 -0.0222 3.5343 +-0.0500 -0.0250 3.5343 +primID: 1 +startangle_c: 9 +endpose_c: -6 -3 9 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0167 -0.0083 3.5343 +-0.0333 -0.0167 3.5343 +-0.0500 -0.0250 3.5343 +-0.0667 -0.0333 3.5343 +-0.0833 -0.0417 3.5343 +-0.1000 -0.0500 3.5343 +-0.1167 -0.0583 3.5343 +-0.1333 -0.0667 3.5343 +-0.1500 -0.0750 3.5343 +primID: 2 +startangle_c: 9 +endpose_c: 2 1 9 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0056 0.0028 3.5343 +0.0111 0.0056 3.5343 +0.0167 0.0083 3.5343 +0.0222 0.0111 3.5343 +0.0278 0.0139 3.5343 +0.0333 0.0167 3.5343 +0.0389 0.0194 3.5343 +0.0444 0.0222 3.5343 +0.0500 0.0250 3.5343 +primID: 3 +startangle_c: 9 +endpose_c: -5 -4 10 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0149 -0.0092 3.5646 +-0.0296 -0.0189 3.5949 +-0.0440 -0.0291 3.6252 +-0.0582 -0.0398 3.6555 +-0.0722 -0.0509 3.6858 +-0.0858 -0.0625 3.7161 +-0.0992 -0.0746 3.7464 +-0.1123 -0.0871 3.7767 +-0.1250 -0.1000 3.8070 +primID: 4 +startangle_c: 9 +endpose_c: -7 -2 8 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0188 -0.0078 3.5343 +-0.0377 -0.0156 3.5343 +-0.0565 -0.0234 3.5343 +-0.0754 -0.0312 3.5152 +-0.0946 -0.0379 3.4405 +-0.1143 -0.0432 3.3658 +-0.1344 -0.0470 3.2910 +-0.1546 -0.0492 3.2163 +-0.1750 -0.0500 3.1416 +primID: 5 +startangle_c: 9 +endpose_c: 0 0 10 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0000 0.0000 3.5779 +0.0000 0.0000 3.6216 +0.0000 0.0000 3.6652 +0.0000 0.0000 3.7088 +0.0000 0.0000 3.7525 +0.0000 0.0000 3.7961 +0.0000 0.0000 3.8397 +0.0000 0.0000 3.8834 +0.0000 0.0000 3.9270 +primID: 6 +startangle_c: 9 +endpose_c: 0 0 8 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0000 0.0000 3.4907 +0.0000 0.0000 3.4470 +0.0000 0.0000 3.4034 +0.0000 0.0000 3.3598 +0.0000 0.0000 3.3161 +0.0000 0.0000 3.2725 +0.0000 0.0000 3.2289 +0.0000 0.0000 3.1852 +0.0000 0.0000 3.1416 +primID: 7 +startangle_c: 9 +endpose_c: 1 -2 9 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0028 -0.0056 3.5343 +0.0056 -0.0111 3.5343 +0.0083 -0.0167 3.5343 +0.0111 -0.0222 3.5343 +0.0139 -0.0278 3.5343 +0.0167 -0.0333 3.5343 +0.0194 -0.0389 3.5343 +0.0222 -0.0444 3.5343 +0.0250 -0.0500 3.5343 +primID: 8 +startangle_c: 9 +endpose_c: -1 2 9 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0028 0.0056 3.5343 +-0.0056 0.0111 3.5343 +-0.0083 0.0167 3.5343 +-0.0111 0.0222 3.5343 +-0.0139 0.0278 3.5343 +-0.0167 0.0333 3.5343 +-0.0194 0.0389 3.5343 +-0.0222 0.0444 3.5343 +-0.0250 0.0500 3.5343 +primID: 0 +startangle_c: 10 +endpose_c: -1 -1 10 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0028 -0.0028 3.9270 +-0.0056 -0.0056 3.9270 +-0.0083 -0.0083 3.9270 +-0.0111 -0.0111 3.9270 +-0.0139 -0.0139 3.9270 +-0.0167 -0.0167 3.9270 +-0.0194 -0.0194 3.9270 +-0.0222 -0.0222 3.9270 +-0.0250 -0.0250 3.9270 +primID: 1 +startangle_c: 10 +endpose_c: -6 -6 10 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0167 -0.0167 3.9270 +-0.0333 -0.0333 3.9270 +-0.0500 -0.0500 3.9270 +-0.0667 -0.0667 3.9270 +-0.0833 -0.0833 3.9270 +-0.1000 -0.1000 3.9270 +-0.1167 -0.1167 3.9270 +-0.1333 -0.1333 3.9270 +-0.1500 -0.1500 3.9270 +primID: 2 +startangle_c: 10 +endpose_c: 1 1 10 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0028 0.0028 3.9270 +0.0056 0.0056 3.9270 +0.0083 0.0083 3.9270 +0.0111 0.0111 3.9270 +0.0139 0.0139 3.9270 +0.0167 0.0167 3.9270 +0.0194 0.0194 3.9270 +0.0222 0.0222 3.9270 +0.0250 0.0250 3.9270 +primID: 3 +startangle_c: 10 +endpose_c: -5 -7 11 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0170 -0.0170 3.9270 +-0.0339 -0.0342 3.9567 +-0.0500 -0.0522 4.0085 +-0.0651 -0.0709 4.0604 +-0.0792 -0.0904 4.1123 +-0.0923 -0.1107 4.1641 +-0.1043 -0.1315 4.2160 +-0.1152 -0.1530 4.2678 +-0.1250 -0.1750 4.3197 +primID: 4 +startangle_c: 10 +endpose_c: -7 -5 9 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0170 -0.0170 3.9270 +-0.0342 -0.0339 3.8973 +-0.0522 -0.0500 3.8455 +-0.0709 -0.0651 3.7936 +-0.0904 -0.0792 3.7417 +-0.1107 -0.0923 3.6899 +-0.1315 -0.1043 3.6380 +-0.1530 -0.1152 3.5862 +-0.1750 -0.1250 3.5343 +primID: 5 +startangle_c: 10 +endpose_c: 0 0 11 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.9706 +0.0000 0.0000 4.0143 +0.0000 0.0000 4.0579 +0.0000 0.0000 4.1015 +0.0000 0.0000 4.1452 +0.0000 0.0000 4.1888 +0.0000 0.0000 4.2324 +0.0000 0.0000 4.2761 +0.0000 0.0000 4.3197 +primID: 6 +startangle_c: 10 +endpose_c: 0 0 9 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.8834 +0.0000 0.0000 3.8397 +0.0000 0.0000 3.7961 +0.0000 0.0000 3.7525 +0.0000 0.0000 3.7088 +0.0000 0.0000 3.6652 +0.0000 0.0000 3.6216 +0.0000 0.0000 3.5779 +0.0000 0.0000 3.5343 +primID: 7 +startangle_c: 10 +endpose_c: 1 -1 10 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0028 -0.0028 3.9270 +0.0056 -0.0056 3.9270 +0.0083 -0.0083 3.9270 +0.0111 -0.0111 3.9270 +0.0139 -0.0139 3.9270 +0.0167 -0.0167 3.9270 +0.0194 -0.0194 3.9270 +0.0222 -0.0222 3.9270 +0.0250 -0.0250 3.9270 +primID: 8 +startangle_c: 10 +endpose_c: -1 1 10 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0028 0.0028 3.9270 +-0.0056 0.0056 3.9270 +-0.0083 0.0083 3.9270 +-0.0111 0.0111 3.9270 +-0.0139 0.0139 3.9270 +-0.0167 0.0167 3.9270 +-0.0194 0.0194 3.9270 +-0.0222 0.0222 3.9270 +-0.0250 0.0250 3.9270 +primID: 0 +startangle_c: 11 +endpose_c: -1 -2 11 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0028 -0.0056 4.3197 +-0.0056 -0.0111 4.3197 +-0.0083 -0.0167 4.3197 +-0.0111 -0.0222 4.3197 +-0.0139 -0.0278 4.3197 +-0.0167 -0.0333 4.3197 +-0.0194 -0.0389 4.3197 +-0.0222 -0.0444 4.3197 +-0.0250 -0.0500 4.3197 +primID: 1 +startangle_c: 11 +endpose_c: -3 -6 11 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0083 -0.0167 4.3197 +-0.0167 -0.0333 4.3197 +-0.0250 -0.0500 4.3197 +-0.0333 -0.0667 4.3197 +-0.0417 -0.0833 4.3197 +-0.0500 -0.1000 4.3197 +-0.0583 -0.1167 4.3197 +-0.0667 -0.1333 4.3197 +-0.0750 -0.1500 4.3197 +primID: 2 +startangle_c: 11 +endpose_c: 1 2 11 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0028 0.0056 4.3197 +0.0056 0.0111 4.3197 +0.0083 0.0167 4.3197 +0.0111 0.0222 4.3197 +0.0139 0.0278 4.3197 +0.0167 0.0333 4.3197 +0.0194 0.0389 4.3197 +0.0222 0.0444 4.3197 +0.0250 0.0500 4.3197 +primID: 3 +startangle_c: 11 +endpose_c: -4 -5 10 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0092 -0.0149 4.2894 +-0.0189 -0.0296 4.2591 +-0.0291 -0.0440 4.2288 +-0.0398 -0.0582 4.1985 +-0.0509 -0.0722 4.1682 +-0.0625 -0.0858 4.1379 +-0.0746 -0.0992 4.1076 +-0.0871 -0.1123 4.0773 +-0.1000 -0.1250 4.0470 +primID: 4 +startangle_c: 11 +endpose_c: -2 -7 12 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0078 -0.0188 4.3197 +-0.0156 -0.0377 4.3197 +-0.0234 -0.0565 4.3197 +-0.0312 -0.0754 4.3388 +-0.0379 -0.0946 4.4135 +-0.0432 -0.1143 4.4882 +-0.0470 -0.1344 4.5629 +-0.0492 -0.1546 4.6377 +-0.0500 -0.1750 4.7124 +primID: 5 +startangle_c: 11 +endpose_c: 0 0 10 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0000 0.0000 4.2761 +0.0000 0.0000 4.2324 +0.0000 0.0000 4.1888 +0.0000 0.0000 4.1452 +0.0000 0.0000 4.1015 +0.0000 0.0000 4.0579 +0.0000 0.0000 4.0143 +0.0000 0.0000 3.9706 +0.0000 0.0000 3.9270 +primID: 6 +startangle_c: 11 +endpose_c: 0 0 12 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0000 0.0000 4.3633 +0.0000 0.0000 4.4070 +0.0000 0.0000 4.4506 +0.0000 0.0000 4.4942 +0.0000 0.0000 4.5379 +0.0000 0.0000 4.5815 +0.0000 0.0000 4.6251 +0.0000 0.0000 4.6688 +0.0000 0.0000 4.7124 +primID: 7 +startangle_c: 11 +endpose_c: -2 1 11 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0056 0.0028 4.3197 +-0.0111 0.0056 4.3197 +-0.0167 0.0083 4.3197 +-0.0222 0.0111 4.3197 +-0.0278 0.0139 4.3197 +-0.0333 0.0167 4.3197 +-0.0389 0.0194 4.3197 +-0.0444 0.0222 4.3197 +-0.0500 0.0250 4.3197 +primID: 8 +startangle_c: 11 +endpose_c: 2 -1 11 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0056 -0.0028 4.3197 +0.0111 -0.0056 4.3197 +0.0167 -0.0083 4.3197 +0.0222 -0.0111 4.3197 +0.0278 -0.0139 4.3197 +0.0333 -0.0167 4.3197 +0.0389 -0.0194 4.3197 +0.0444 -0.0222 4.3197 +0.0500 -0.0250 4.3197 +primID: 0 +startangle_c: 12 +endpose_c: 0 -1 12 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0028 4.7124 +0.0000 -0.0056 4.7124 +0.0000 -0.0083 4.7124 +0.0000 -0.0111 4.7124 +0.0000 -0.0139 4.7124 +0.0000 -0.0167 4.7124 +0.0000 -0.0194 4.7124 +0.0000 -0.0222 4.7124 +0.0000 -0.0250 4.7124 +primID: 1 +startangle_c: 12 +endpose_c: 0 -8 12 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0222 4.7124 +0.0000 -0.0444 4.7124 +0.0000 -0.0667 4.7124 +0.0000 -0.0889 4.7124 +0.0000 -0.1111 4.7124 +0.0000 -0.1333 4.7124 +0.0000 -0.1556 4.7124 +0.0000 -0.1778 4.7124 +0.0000 -0.2000 4.7124 +primID: 2 +startangle_c: 12 +endpose_c: 0 1 12 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0028 4.7124 +0.0000 0.0056 4.7124 +0.0000 0.0083 4.7124 +0.0000 0.0111 4.7124 +0.0000 0.0139 4.7124 +0.0000 0.0167 4.7124 +0.0000 0.0194 4.7124 +0.0000 0.0222 4.7124 +0.0000 0.0250 4.7124 +primID: 3 +startangle_c: 12 +endpose_c: 1 -8 13 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 4.7124 +-0.0000 -0.0226 4.7124 +-0.0000 -0.0452 4.7124 +-0.0000 -0.0678 4.7124 +0.0004 -0.0903 4.7612 +0.0023 -0.1128 4.8300 +0.0057 -0.1352 4.8988 +0.0106 -0.1572 4.9675 +0.0171 -0.1789 5.0363 +0.0250 -0.2000 5.1051 +primID: 4 +startangle_c: 12 +endpose_c: -1 -8 11 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 4.7124 +-0.0000 -0.0226 4.7124 +-0.0000 -0.0452 4.7124 +-0.0000 -0.0678 4.7124 +-0.0004 -0.0903 4.6636 +-0.0023 -0.1128 4.5948 +-0.0057 -0.1352 4.5260 +-0.0106 -0.1572 4.4572 +-0.0171 -0.1789 4.3885 +-0.0250 -0.2000 4.3197 +primID: 5 +startangle_c: 12 +endpose_c: 0 0 13 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0000 4.7560 +0.0000 0.0000 4.7997 +0.0000 0.0000 4.8433 +0.0000 0.0000 4.8869 +0.0000 0.0000 4.9306 +0.0000 0.0000 4.9742 +0.0000 0.0000 5.0178 +0.0000 0.0000 5.0615 +0.0000 0.0000 5.1051 +primID: 6 +startangle_c: 12 +endpose_c: 0 0 11 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0000 4.6688 +0.0000 0.0000 4.6251 +0.0000 0.0000 4.5815 +0.0000 0.0000 4.5379 +0.0000 0.0000 4.4942 +0.0000 0.0000 4.4506 +0.0000 0.0000 4.4070 +0.0000 0.0000 4.3633 +0.0000 0.0000 4.3197 +primID: 7 +startangle_c: 12 +endpose_c: 1 0 12 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0028 0.0000 4.7124 +0.0056 0.0000 4.7124 +0.0083 0.0000 4.7124 +0.0111 0.0000 4.7124 +0.0139 0.0000 4.7124 +0.0167 0.0000 4.7124 +0.0194 0.0000 4.7124 +0.0222 0.0000 4.7124 +0.0250 0.0000 4.7124 +primID: 8 +startangle_c: 12 +endpose_c: -1 0 12 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 4.7124 +-0.0028 0.0000 4.7124 +-0.0056 0.0000 4.7124 +-0.0083 0.0000 4.7124 +-0.0111 0.0000 4.7124 +-0.0139 0.0000 4.7124 +-0.0167 0.0000 4.7124 +-0.0194 0.0000 4.7124 +-0.0222 0.0000 4.7124 +-0.0250 0.0000 4.7124 +primID: 0 +startangle_c: 13 +endpose_c: 1 -2 13 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0028 -0.0056 5.1051 +0.0056 -0.0111 5.1051 +0.0083 -0.0167 5.1051 +0.0111 -0.0222 5.1051 +0.0139 -0.0278 5.1051 +0.0167 -0.0333 5.1051 +0.0194 -0.0389 5.1051 +0.0222 -0.0444 5.1051 +0.0250 -0.0500 5.1051 +primID: 1 +startangle_c: 13 +endpose_c: 3 -6 13 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0083 -0.0167 5.1051 +0.0167 -0.0333 5.1051 +0.0250 -0.0500 5.1051 +0.0333 -0.0667 5.1051 +0.0417 -0.0833 5.1051 +0.0500 -0.1000 5.1051 +0.0583 -0.1167 5.1051 +0.0667 -0.1333 5.1051 +0.0750 -0.1500 5.1051 +primID: 2 +startangle_c: 13 +endpose_c: -1 2 13 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 5.1051 +-0.0028 0.0056 5.1051 +-0.0056 0.0111 5.1051 +-0.0083 0.0167 5.1051 +-0.0111 0.0222 5.1051 +-0.0139 0.0278 5.1051 +-0.0167 0.0333 5.1051 +-0.0194 0.0389 5.1051 +-0.0222 0.0444 5.1051 +-0.0250 0.0500 5.1051 +primID: 3 +startangle_c: 13 +endpose_c: 4 -5 14 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0092 -0.0149 5.1354 +0.0189 -0.0296 5.1657 +0.0291 -0.0440 5.1960 +0.0398 -0.0582 5.2263 +0.0509 -0.0722 5.2566 +0.0625 -0.0858 5.2869 +0.0746 -0.0992 5.3172 +0.0871 -0.1123 5.3475 +0.1000 -0.1250 5.3778 +primID: 4 +startangle_c: 13 +endpose_c: 2 -7 12 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0078 -0.0188 5.1051 +0.0156 -0.0377 5.1051 +0.0234 -0.0565 5.1051 +0.0312 -0.0754 5.0860 +0.0379 -0.0946 5.0113 +0.0432 -0.1143 4.9366 +0.0470 -0.1344 4.8618 +0.0492 -0.1546 4.7871 +0.0500 -0.1750 4.7124 +primID: 5 +startangle_c: 13 +endpose_c: 0 0 14 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0000 0.0000 5.1487 +0.0000 0.0000 5.1924 +0.0000 0.0000 5.2360 +0.0000 0.0000 5.2796 +0.0000 0.0000 5.3233 +0.0000 0.0000 5.3669 +0.0000 0.0000 5.4105 +0.0000 0.0000 5.4542 +0.0000 0.0000 5.4978 +primID: 6 +startangle_c: 13 +endpose_c: 0 0 12 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0000 0.0000 5.0615 +0.0000 0.0000 5.0178 +0.0000 0.0000 4.9742 +0.0000 0.0000 4.9306 +0.0000 0.0000 4.8869 +0.0000 0.0000 4.8433 +0.0000 0.0000 4.7997 +0.0000 0.0000 4.7560 +0.0000 0.0000 4.7124 +primID: 7 +startangle_c: 13 +endpose_c: 2 1 13 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0056 0.0028 5.1051 +0.0111 0.0056 5.1051 +0.0167 0.0083 5.1051 +0.0222 0.0111 5.1051 +0.0278 0.0139 5.1051 +0.0333 0.0167 5.1051 +0.0389 0.0194 5.1051 +0.0444 0.0222 5.1051 +0.0500 0.0250 5.1051 +primID: 8 +startangle_c: 13 +endpose_c: -2 -1 13 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.1051 +-0.0056 -0.0028 5.1051 +-0.0111 -0.0056 5.1051 +-0.0167 -0.0083 5.1051 +-0.0222 -0.0111 5.1051 +-0.0278 -0.0139 5.1051 +-0.0333 -0.0167 5.1051 +-0.0389 -0.0194 5.1051 +-0.0444 -0.0222 5.1051 +-0.0500 -0.0250 5.1051 +primID: 0 +startangle_c: 14 +endpose_c: 1 -1 14 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0028 -0.0028 5.4978 +0.0056 -0.0056 5.4978 +0.0083 -0.0083 5.4978 +0.0111 -0.0111 5.4978 +0.0139 -0.0139 5.4978 +0.0167 -0.0167 5.4978 +0.0194 -0.0194 5.4978 +0.0222 -0.0222 5.4978 +0.0250 -0.0250 5.4978 +primID: 1 +startangle_c: 14 +endpose_c: 6 -6 14 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0167 -0.0167 5.4978 +0.0333 -0.0333 5.4978 +0.0500 -0.0500 5.4978 +0.0667 -0.0667 5.4978 +0.0833 -0.0833 5.4978 +0.1000 -0.1000 5.4978 +0.1167 -0.1167 5.4978 +0.1333 -0.1333 5.4978 +0.1500 -0.1500 5.4978 +primID: 2 +startangle_c: 14 +endpose_c: -1 1 14 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 5.4978 +-0.0028 0.0028 5.4978 +-0.0056 0.0056 5.4978 +-0.0083 0.0083 5.4978 +-0.0111 0.0111 5.4978 +-0.0139 0.0139 5.4978 +-0.0167 0.0167 5.4978 +-0.0194 0.0194 5.4978 +-0.0222 0.0222 5.4978 +-0.0250 0.0250 5.4978 +primID: 3 +startangle_c: 14 +endpose_c: 7 -5 15 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0170 -0.0170 5.4978 +0.0342 -0.0339 5.5275 +0.0522 -0.0500 5.5793 +0.0709 -0.0651 5.6312 +0.0904 -0.0792 5.6830 +0.1107 -0.0923 5.7349 +0.1315 -0.1043 5.7868 +0.1530 -0.1152 5.8386 +0.1750 -0.1250 5.8905 +primID: 4 +startangle_c: 14 +endpose_c: 5 -7 13 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0170 -0.0170 5.4978 +0.0339 -0.0342 5.4681 +0.0500 -0.0522 5.4162 +0.0651 -0.0709 5.3644 +0.0792 -0.0904 5.3125 +0.0923 -0.1107 5.2607 +0.1043 -0.1315 5.2088 +0.1152 -0.1530 5.1569 +0.1250 -0.1750 5.1051 +primID: 5 +startangle_c: 14 +endpose_c: 0 0 15 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0000 0.0000 5.5414 +0.0000 0.0000 5.5851 +0.0000 0.0000 5.6287 +0.0000 0.0000 5.6723 +0.0000 0.0000 5.7160 +0.0000 0.0000 5.7596 +0.0000 0.0000 5.8032 +0.0000 0.0000 5.8469 +0.0000 0.0000 5.8905 +primID: 6 +startangle_c: 14 +endpose_c: 0 0 13 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0000 0.0000 5.4542 +0.0000 0.0000 5.4105 +0.0000 0.0000 5.3669 +0.0000 0.0000 5.3233 +0.0000 0.0000 5.2796 +0.0000 0.0000 5.2360 +0.0000 0.0000 5.1924 +0.0000 0.0000 5.1487 +0.0000 0.0000 5.1051 +primID: 7 +startangle_c: 14 +endpose_c: 1 1 14 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0028 0.0028 5.4978 +0.0056 0.0056 5.4978 +0.0083 0.0083 5.4978 +0.0111 0.0111 5.4978 +0.0139 0.0139 5.4978 +0.0167 0.0167 5.4978 +0.0194 0.0194 5.4978 +0.0222 0.0222 5.4978 +0.0250 0.0250 5.4978 +primID: 8 +startangle_c: 14 +endpose_c: -1 -1 14 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.4978 +-0.0028 -0.0028 5.4978 +-0.0056 -0.0056 5.4978 +-0.0083 -0.0083 5.4978 +-0.0111 -0.0111 5.4978 +-0.0139 -0.0139 5.4978 +-0.0167 -0.0167 5.4978 +-0.0194 -0.0194 5.4978 +-0.0222 -0.0222 5.4978 +-0.0250 -0.0250 5.4978 +primID: 0 +startangle_c: 15 +endpose_c: 2 -1 15 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0056 -0.0028 5.8905 +0.0111 -0.0056 5.8905 +0.0167 -0.0083 5.8905 +0.0222 -0.0111 5.8905 +0.0278 -0.0139 5.8905 +0.0333 -0.0167 5.8905 +0.0389 -0.0194 5.8905 +0.0444 -0.0222 5.8905 +0.0500 -0.0250 5.8905 +primID: 1 +startangle_c: 15 +endpose_c: 6 -3 15 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0167 -0.0083 5.8905 +0.0333 -0.0167 5.8905 +0.0500 -0.0250 5.8905 +0.0667 -0.0333 5.8905 +0.0833 -0.0417 5.8905 +0.1000 -0.0500 5.8905 +0.1167 -0.0583 5.8905 +0.1333 -0.0667 5.8905 +0.1500 -0.0750 5.8905 +primID: 2 +startangle_c: 15 +endpose_c: -2 1 15 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 5.8905 +-0.0056 0.0028 5.8905 +-0.0111 0.0056 5.8905 +-0.0167 0.0083 5.8905 +-0.0222 0.0111 5.8905 +-0.0278 0.0139 5.8905 +-0.0333 0.0167 5.8905 +-0.0389 0.0194 5.8905 +-0.0444 0.0222 5.8905 +-0.0500 0.0250 5.8905 +primID: 3 +startangle_c: 15 +endpose_c: 5 -4 14 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0149 -0.0092 5.8602 +0.0296 -0.0189 5.8299 +0.0440 -0.0291 5.7996 +0.0582 -0.0398 5.7693 +0.0722 -0.0509 5.7390 +0.0858 -0.0625 5.7087 +0.0992 -0.0746 5.6784 +0.1123 -0.0871 5.6481 +0.1250 -0.1000 5.6178 +primID: 4 +startangle_c: 15 +endpose_c: 7 -2 0 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0188 -0.0078 5.8905 +0.0377 -0.0156 5.8905 +0.0565 -0.0234 5.8905 +0.0754 -0.0312 5.9096 +0.0946 -0.0379 5.9843 +0.1143 -0.0432 6.0590 +0.1344 -0.0470 6.1337 +0.1546 -0.0492 6.2085 +0.1750 -0.0500 6.2832 +primID: 5 +startangle_c: 15 +endpose_c: 0 0 14 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0000 0.0000 5.8469 +0.0000 0.0000 5.8032 +0.0000 0.0000 5.7596 +0.0000 0.0000 5.7160 +0.0000 0.0000 5.6723 +0.0000 0.0000 5.6287 +0.0000 0.0000 5.5851 +0.0000 0.0000 5.5414 +0.0000 0.0000 5.4978 +primID: 6 +startangle_c: 15 +endpose_c: 0 0 0 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0000 0.0000 5.9341 +0.0000 0.0000 5.9778 +0.0000 0.0000 6.0214 +0.0000 0.0000 6.0650 +0.0000 0.0000 6.1087 +0.0000 0.0000 6.1523 +0.0000 0.0000 6.1959 +0.0000 0.0000 6.2396 +0.0000 0.0000 0.0000 +primID: 7 +startangle_c: 15 +endpose_c: -1 -2 15 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.8905 +-0.0028 -0.0056 5.8905 +-0.0056 -0.0111 5.8905 +-0.0083 -0.0167 5.8905 +-0.0111 -0.0222 5.8905 +-0.0139 -0.0278 5.8905 +-0.0167 -0.0333 5.8905 +-0.0194 -0.0389 5.8905 +-0.0222 -0.0444 5.8905 +-0.0250 -0.0500 5.8905 +primID: 8 +startangle_c: 15 +endpose_c: 1 2 15 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0028 0.0056 5.8905 +0.0056 0.0111 5.8905 +0.0083 0.0167 5.8905 +0.0111 0.0222 5.8905 +0.0139 0.0278 5.8905 +0.0167 0.0333 5.8905 +0.0194 0.0389 5.8905 +0.0222 0.0444 5.8905 +0.0250 0.0500 5.8905 diff --git a/navigations/sbpl/matlab/mprim/unicycle_backonlystraight.mprim b/navigations/sbpl/matlab/mprim/unicycle_backonlystraight.mprim new file mode 100755 index 0000000..8de0417 --- /dev/null +++ b/navigations/sbpl/matlab/mprim/unicycle_backonlystraight.mprim @@ -0,0 +1,1683 @@ +resolution_m: 0.025000 +numberofangles: 16 +totalnumberofprimitives: 112 +primID: 0 +startangle_c: 0 +endpose_c: 1 0 0 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0028 0.0000 0.0000 +0.0056 0.0000 0.0000 +0.0083 0.0000 0.0000 +0.0111 0.0000 0.0000 +0.0139 0.0000 0.0000 +0.0167 0.0000 0.0000 +0.0194 0.0000 0.0000 +0.0222 0.0000 0.0000 +0.0250 0.0000 0.0000 +primID: 1 +startangle_c: 0 +endpose_c: 8 0 0 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0222 0.0000 0.0000 +0.0444 0.0000 0.0000 +0.0667 0.0000 0.0000 +0.0889 0.0000 0.0000 +0.1111 0.0000 0.0000 +0.1333 0.0000 0.0000 +0.1556 0.0000 0.0000 +0.1778 0.0000 0.0000 +0.2000 0.0000 0.0000 +primID: 2 +startangle_c: 0 +endpose_c: -1 0 0 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 0.0000 +-0.0028 0.0000 0.0000 +-0.0056 0.0000 0.0000 +-0.0083 0.0000 0.0000 +-0.0111 0.0000 0.0000 +-0.0139 0.0000 0.0000 +-0.0167 0.0000 0.0000 +-0.0194 0.0000 0.0000 +-0.0222 0.0000 0.0000 +-0.0250 0.0000 0.0000 +primID: 3 +startangle_c: 0 +endpose_c: 8 1 1 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0226 -0.0000 0.0000 +0.0452 -0.0000 0.0000 +0.0678 -0.0000 0.0000 +0.0903 0.0004 0.0488 +0.1128 0.0023 0.1176 +0.1352 0.0057 0.1864 +0.1572 0.0106 0.2551 +0.1789 0.0171 0.3239 +0.2000 0.0250 0.3927 +primID: 4 +startangle_c: 0 +endpose_c: 8 -1 -1 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0226 0.0000 0.0000 +0.0452 0.0000 0.0000 +0.0678 0.0000 0.0000 +0.0903 -0.0004 -0.0488 +0.1128 -0.0023 -0.1176 +0.1352 -0.0057 -0.1864 +0.1572 -0.0106 -0.2551 +0.1789 -0.0171 -0.3239 +0.2000 -0.0250 -0.3927 +primID: 5 +startangle_c: 0 +endpose_c: 0 0 1 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0000 0.0000 0.0436 +0.0000 0.0000 0.0873 +0.0000 0.0000 0.1309 +0.0000 0.0000 0.1745 +0.0000 0.0000 0.2182 +0.0000 0.0000 0.2618 +0.0000 0.0000 0.3054 +0.0000 0.0000 0.3491 +0.0000 0.0000 0.3927 +primID: 6 +startangle_c: 0 +endpose_c: 0 0 -1 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0000 0.0000 -0.0436 +0.0000 0.0000 -0.0873 +0.0000 0.0000 -0.1309 +0.0000 0.0000 -0.1745 +0.0000 0.0000 -0.2182 +0.0000 0.0000 -0.2618 +0.0000 0.0000 -0.3054 +0.0000 0.0000 -0.3491 +0.0000 0.0000 -0.3927 +primID: 0 +startangle_c: 1 +endpose_c: 2 1 1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0056 0.0028 0.3927 +0.0111 0.0056 0.3927 +0.0167 0.0083 0.3927 +0.0222 0.0111 0.3927 +0.0278 0.0139 0.3927 +0.0333 0.0167 0.3927 +0.0389 0.0194 0.3927 +0.0444 0.0222 0.3927 +0.0500 0.0250 0.3927 +primID: 1 +startangle_c: 1 +endpose_c: 6 3 1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0167 0.0083 0.3927 +0.0333 0.0167 0.3927 +0.0500 0.0250 0.3927 +0.0667 0.0333 0.3927 +0.0833 0.0417 0.3927 +0.1000 0.0500 0.3927 +0.1167 0.0583 0.3927 +0.1333 0.0667 0.3927 +0.1500 0.0750 0.3927 +primID: 2 +startangle_c: 1 +endpose_c: -2 -1 1 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 0.3927 +-0.0056 -0.0028 0.3927 +-0.0111 -0.0056 0.3927 +-0.0167 -0.0083 0.3927 +-0.0222 -0.0111 0.3927 +-0.0278 -0.0139 0.3927 +-0.0333 -0.0167 0.3927 +-0.0389 -0.0194 0.3927 +-0.0444 -0.0222 0.3927 +-0.0500 -0.0250 0.3927 +primID: 3 +startangle_c: 1 +endpose_c: 5 4 2 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0149 0.0092 0.4230 +0.0296 0.0189 0.4533 +0.0440 0.0291 0.4836 +0.0582 0.0398 0.5139 +0.0722 0.0509 0.5442 +0.0858 0.0625 0.5745 +0.0992 0.0746 0.6048 +0.1123 0.0871 0.6351 +0.1250 0.1000 0.6654 +primID: 4 +startangle_c: 1 +endpose_c: 7 2 0 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0188 0.0078 0.3927 +0.0377 0.0156 0.3927 +0.0565 0.0234 0.3927 +0.0754 0.0312 0.3736 +0.0946 0.0379 0.2989 +0.1143 0.0432 0.2242 +0.1344 0.0470 0.1494 +0.1546 0.0492 0.0747 +0.1750 0.0500 0.0000 +primID: 5 +startangle_c: 1 +endpose_c: 0 0 2 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0000 0.0000 0.4363 +0.0000 0.0000 0.4800 +0.0000 0.0000 0.5236 +0.0000 0.0000 0.5672 +0.0000 0.0000 0.6109 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.6981 +0.0000 0.0000 0.7418 +0.0000 0.0000 0.7854 +primID: 6 +startangle_c: 1 +endpose_c: 0 0 0 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0000 0.0000 0.3491 +0.0000 0.0000 0.3054 +0.0000 0.0000 0.2618 +0.0000 0.0000 0.2182 +0.0000 0.0000 0.1745 +0.0000 0.0000 0.1309 +0.0000 0.0000 0.0873 +0.0000 0.0000 0.0436 +0.0000 0.0000 0.0000 +primID: 0 +startangle_c: 2 +endpose_c: 1 1 2 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0028 0.0028 0.7854 +0.0056 0.0056 0.7854 +0.0083 0.0083 0.7854 +0.0111 0.0111 0.7854 +0.0139 0.0139 0.7854 +0.0167 0.0167 0.7854 +0.0194 0.0194 0.7854 +0.0222 0.0222 0.7854 +0.0250 0.0250 0.7854 +primID: 1 +startangle_c: 2 +endpose_c: 6 6 2 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0167 0.0167 0.7854 +0.0333 0.0333 0.7854 +0.0500 0.0500 0.7854 +0.0667 0.0667 0.7854 +0.0833 0.0833 0.7854 +0.1000 0.1000 0.7854 +0.1167 0.1167 0.7854 +0.1333 0.1333 0.7854 +0.1500 0.1500 0.7854 +primID: 2 +startangle_c: 2 +endpose_c: -1 -1 2 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 0.7854 +-0.0028 -0.0028 0.7854 +-0.0056 -0.0056 0.7854 +-0.0083 -0.0083 0.7854 +-0.0111 -0.0111 0.7854 +-0.0139 -0.0139 0.7854 +-0.0167 -0.0167 0.7854 +-0.0194 -0.0194 0.7854 +-0.0222 -0.0222 0.7854 +-0.0250 -0.0250 0.7854 +primID: 3 +startangle_c: 2 +endpose_c: 5 7 3 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0170 0.0170 0.7854 +0.0339 0.0342 0.8151 +0.0500 0.0522 0.8669 +0.0651 0.0709 0.9188 +0.0792 0.0904 0.9707 +0.0923 0.1107 1.0225 +0.1043 0.1315 1.0744 +0.1152 0.1530 1.1262 +0.1250 0.1750 1.1781 +primID: 4 +startangle_c: 2 +endpose_c: 7 5 1 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0170 0.0170 0.7854 +0.0342 0.0339 0.7557 +0.0522 0.0500 0.7039 +0.0709 0.0651 0.6520 +0.0904 0.0792 0.6001 +0.1107 0.0923 0.5483 +0.1315 0.1043 0.4964 +0.1530 0.1152 0.4446 +0.1750 0.1250 0.3927 +primID: 5 +startangle_c: 2 +endpose_c: 0 0 3 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0000 0.0000 0.8290 +0.0000 0.0000 0.8727 +0.0000 0.0000 0.9163 +0.0000 0.0000 0.9599 +0.0000 0.0000 1.0036 +0.0000 0.0000 1.0472 +0.0000 0.0000 1.0908 +0.0000 0.0000 1.1345 +0.0000 0.0000 1.1781 +primID: 6 +startangle_c: 2 +endpose_c: 0 0 1 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0000 0.0000 0.7418 +0.0000 0.0000 0.6981 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.6109 +0.0000 0.0000 0.5672 +0.0000 0.0000 0.5236 +0.0000 0.0000 0.4800 +0.0000 0.0000 0.4363 +0.0000 0.0000 0.3927 +primID: 0 +startangle_c: 3 +endpose_c: 1 2 3 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0028 0.0056 1.1781 +0.0056 0.0111 1.1781 +0.0083 0.0167 1.1781 +0.0111 0.0222 1.1781 +0.0139 0.0278 1.1781 +0.0167 0.0333 1.1781 +0.0194 0.0389 1.1781 +0.0222 0.0444 1.1781 +0.0250 0.0500 1.1781 +primID: 1 +startangle_c: 3 +endpose_c: 3 6 3 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0083 0.0167 1.1781 +0.0167 0.0333 1.1781 +0.0250 0.0500 1.1781 +0.0333 0.0667 1.1781 +0.0417 0.0833 1.1781 +0.0500 0.1000 1.1781 +0.0583 0.1167 1.1781 +0.0667 0.1333 1.1781 +0.0750 0.1500 1.1781 +primID: 2 +startangle_c: 3 +endpose_c: -1 -2 3 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 1.1781 +-0.0028 -0.0056 1.1781 +-0.0056 -0.0111 1.1781 +-0.0083 -0.0167 1.1781 +-0.0111 -0.0222 1.1781 +-0.0139 -0.0278 1.1781 +-0.0167 -0.0333 1.1781 +-0.0194 -0.0389 1.1781 +-0.0222 -0.0444 1.1781 +-0.0250 -0.0500 1.1781 +primID: 3 +startangle_c: 3 +endpose_c: 4 5 2 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0092 0.0149 1.1478 +0.0189 0.0296 1.1175 +0.0291 0.0440 1.0872 +0.0398 0.0582 1.0569 +0.0509 0.0722 1.0266 +0.0625 0.0858 0.9963 +0.0746 0.0992 0.9660 +0.0871 0.1123 0.9357 +0.1000 0.1250 0.9054 +primID: 4 +startangle_c: 3 +endpose_c: 2 7 4 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0078 0.0188 1.1781 +0.0156 0.0377 1.1781 +0.0234 0.0565 1.1781 +0.0312 0.0754 1.1972 +0.0379 0.0946 1.2719 +0.0432 0.1143 1.3466 +0.0470 0.1344 1.4214 +0.0492 0.1546 1.4961 +0.0500 0.1750 1.5708 +primID: 5 +startangle_c: 3 +endpose_c: 0 0 2 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0000 0.0000 1.1345 +0.0000 0.0000 1.0908 +0.0000 0.0000 1.0472 +0.0000 0.0000 1.0036 +0.0000 0.0000 0.9599 +0.0000 0.0000 0.9163 +0.0000 0.0000 0.8727 +0.0000 0.0000 0.8290 +0.0000 0.0000 0.7854 +primID: 6 +startangle_c: 3 +endpose_c: 0 0 4 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0000 0.0000 1.2217 +0.0000 0.0000 1.2654 +0.0000 0.0000 1.3090 +0.0000 0.0000 1.3526 +0.0000 0.0000 1.3963 +0.0000 0.0000 1.4399 +0.0000 0.0000 1.4835 +0.0000 0.0000 1.5272 +0.0000 0.0000 1.5708 +primID: 0 +startangle_c: 4 +endpose_c: 0 1 4 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0028 1.5708 +0.0000 0.0056 1.5708 +0.0000 0.0083 1.5708 +0.0000 0.0111 1.5708 +0.0000 0.0139 1.5708 +0.0000 0.0167 1.5708 +0.0000 0.0194 1.5708 +0.0000 0.0222 1.5708 +0.0000 0.0250 1.5708 +primID: 1 +startangle_c: 4 +endpose_c: 0 8 4 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0222 1.5708 +0.0000 0.0444 1.5708 +0.0000 0.0667 1.5708 +0.0000 0.0889 1.5708 +0.0000 0.1111 1.5708 +0.0000 0.1333 1.5708 +0.0000 0.1556 1.5708 +0.0000 0.1778 1.5708 +0.0000 0.2000 1.5708 +primID: 2 +startangle_c: 4 +endpose_c: 0 -1 4 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 -0.0028 1.5708 +0.0000 -0.0056 1.5708 +0.0000 -0.0083 1.5708 +0.0000 -0.0111 1.5708 +0.0000 -0.0139 1.5708 +0.0000 -0.0167 1.5708 +0.0000 -0.0194 1.5708 +0.0000 -0.0222 1.5708 +0.0000 -0.0250 1.5708 +primID: 3 +startangle_c: 4 +endpose_c: -1 8 5 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0226 1.5708 +0.0000 0.0452 1.5708 +0.0000 0.0678 1.5708 +-0.0004 0.0903 1.6196 +-0.0023 0.1128 1.6884 +-0.0057 0.1352 1.7572 +-0.0106 0.1572 1.8259 +-0.0171 0.1789 1.8947 +-0.0250 0.2000 1.9635 +primID: 4 +startangle_c: 4 +endpose_c: 1 8 3 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.5708 +-0.0000 0.0226 1.5708 +-0.0000 0.0452 1.5708 +-0.0000 0.0678 1.5708 +0.0004 0.0903 1.5220 +0.0023 0.1128 1.4532 +0.0057 0.1352 1.3844 +0.0106 0.1572 1.3156 +0.0171 0.1789 1.2469 +0.0250 0.2000 1.1781 +primID: 5 +startangle_c: 4 +endpose_c: 0 0 5 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0000 1.6144 +0.0000 0.0000 1.6581 +0.0000 0.0000 1.7017 +0.0000 0.0000 1.7453 +0.0000 0.0000 1.7890 +0.0000 0.0000 1.8326 +0.0000 0.0000 1.8762 +0.0000 0.0000 1.9199 +0.0000 0.0000 1.9635 +primID: 6 +startangle_c: 4 +endpose_c: 0 0 3 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0000 1.5272 +0.0000 0.0000 1.4835 +0.0000 0.0000 1.4399 +0.0000 0.0000 1.3963 +0.0000 0.0000 1.3526 +0.0000 0.0000 1.3090 +0.0000 0.0000 1.2654 +0.0000 0.0000 1.2217 +0.0000 0.0000 1.1781 +primID: 0 +startangle_c: 5 +endpose_c: -1 2 5 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0028 0.0056 1.9635 +-0.0056 0.0111 1.9635 +-0.0083 0.0167 1.9635 +-0.0111 0.0222 1.9635 +-0.0139 0.0278 1.9635 +-0.0167 0.0333 1.9635 +-0.0194 0.0389 1.9635 +-0.0222 0.0444 1.9635 +-0.0250 0.0500 1.9635 +primID: 1 +startangle_c: 5 +endpose_c: -3 6 5 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0083 0.0167 1.9635 +-0.0167 0.0333 1.9635 +-0.0250 0.0500 1.9635 +-0.0333 0.0667 1.9635 +-0.0417 0.0833 1.9635 +-0.0500 0.1000 1.9635 +-0.0583 0.1167 1.9635 +-0.0667 0.1333 1.9635 +-0.0750 0.1500 1.9635 +primID: 2 +startangle_c: 5 +endpose_c: 1 -2 5 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0028 -0.0056 1.9635 +0.0056 -0.0111 1.9635 +0.0083 -0.0167 1.9635 +0.0111 -0.0222 1.9635 +0.0139 -0.0278 1.9635 +0.0167 -0.0333 1.9635 +0.0194 -0.0389 1.9635 +0.0222 -0.0444 1.9635 +0.0250 -0.0500 1.9635 +primID: 3 +startangle_c: 5 +endpose_c: -4 5 6 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0092 0.0149 1.9938 +-0.0189 0.0296 2.0241 +-0.0291 0.0440 2.0544 +-0.0398 0.0582 2.0847 +-0.0509 0.0722 2.1150 +-0.0625 0.0858 2.1453 +-0.0746 0.0992 2.1756 +-0.0871 0.1123 2.2059 +-0.1000 0.1250 2.2362 +primID: 4 +startangle_c: 5 +endpose_c: -2 7 4 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0078 0.0188 1.9635 +-0.0156 0.0377 1.9635 +-0.0234 0.0565 1.9635 +-0.0312 0.0754 1.9444 +-0.0379 0.0946 1.8697 +-0.0432 0.1143 1.7950 +-0.0470 0.1344 1.7202 +-0.0492 0.1546 1.6455 +-0.0500 0.1750 1.5708 +primID: 5 +startangle_c: 5 +endpose_c: 0 0 6 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0000 0.0000 2.0071 +0.0000 0.0000 2.0508 +0.0000 0.0000 2.0944 +0.0000 0.0000 2.1380 +0.0000 0.0000 2.1817 +0.0000 0.0000 2.2253 +0.0000 0.0000 2.2689 +0.0000 0.0000 2.3126 +0.0000 0.0000 2.3562 +primID: 6 +startangle_c: 5 +endpose_c: 0 0 4 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0000 0.0000 1.9199 +0.0000 0.0000 1.8762 +0.0000 0.0000 1.8326 +0.0000 0.0000 1.7890 +0.0000 0.0000 1.7453 +0.0000 0.0000 1.7017 +0.0000 0.0000 1.6581 +0.0000 0.0000 1.6144 +0.0000 0.0000 1.5708 +primID: 0 +startangle_c: 6 +endpose_c: -1 1 6 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0028 0.0028 2.3562 +-0.0056 0.0056 2.3562 +-0.0083 0.0083 2.3562 +-0.0111 0.0111 2.3562 +-0.0139 0.0139 2.3562 +-0.0167 0.0167 2.3562 +-0.0194 0.0194 2.3562 +-0.0222 0.0222 2.3562 +-0.0250 0.0250 2.3562 +primID: 1 +startangle_c: 6 +endpose_c: -6 6 6 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0167 0.0167 2.3562 +-0.0333 0.0333 2.3562 +-0.0500 0.0500 2.3562 +-0.0667 0.0667 2.3562 +-0.0833 0.0833 2.3562 +-0.1000 0.1000 2.3562 +-0.1167 0.1167 2.3562 +-0.1333 0.1333 2.3562 +-0.1500 0.1500 2.3562 +primID: 2 +startangle_c: 6 +endpose_c: 1 -1 6 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0028 -0.0028 2.3562 +0.0056 -0.0056 2.3562 +0.0083 -0.0083 2.3562 +0.0111 -0.0111 2.3562 +0.0139 -0.0139 2.3562 +0.0167 -0.0167 2.3562 +0.0194 -0.0194 2.3562 +0.0222 -0.0222 2.3562 +0.0250 -0.0250 2.3562 +primID: 3 +startangle_c: 6 +endpose_c: -7 5 7 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0170 0.0170 2.3562 +-0.0342 0.0339 2.3859 +-0.0522 0.0500 2.4377 +-0.0709 0.0651 2.4896 +-0.0904 0.0792 2.5415 +-0.1107 0.0923 2.5933 +-0.1315 0.1043 2.6452 +-0.1530 0.1152 2.6970 +-0.1750 0.1250 2.7489 +primID: 4 +startangle_c: 6 +endpose_c: -5 7 5 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0170 0.0170 2.3562 +-0.0339 0.0342 2.3265 +-0.0500 0.0522 2.2747 +-0.0651 0.0709 2.2228 +-0.0792 0.0904 2.1709 +-0.0923 0.1107 2.1191 +-0.1043 0.1315 2.0672 +-0.1152 0.1530 2.0154 +-0.1250 0.1750 1.9635 +primID: 5 +startangle_c: 6 +endpose_c: 0 0 7 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0000 0.0000 2.3998 +0.0000 0.0000 2.4435 +0.0000 0.0000 2.4871 +0.0000 0.0000 2.5307 +0.0000 0.0000 2.5744 +0.0000 0.0000 2.6180 +0.0000 0.0000 2.6616 +0.0000 0.0000 2.7053 +0.0000 0.0000 2.7489 +primID: 6 +startangle_c: 6 +endpose_c: 0 0 5 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0000 0.0000 2.3126 +0.0000 0.0000 2.2689 +0.0000 0.0000 2.2253 +0.0000 0.0000 2.1817 +0.0000 0.0000 2.1380 +0.0000 0.0000 2.0944 +0.0000 0.0000 2.0508 +0.0000 0.0000 2.0071 +0.0000 0.0000 1.9635 +primID: 0 +startangle_c: 7 +endpose_c: -2 1 7 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0056 0.0028 2.7489 +-0.0111 0.0056 2.7489 +-0.0167 0.0083 2.7489 +-0.0222 0.0111 2.7489 +-0.0278 0.0139 2.7489 +-0.0333 0.0167 2.7489 +-0.0389 0.0194 2.7489 +-0.0444 0.0222 2.7489 +-0.0500 0.0250 2.7489 +primID: 1 +startangle_c: 7 +endpose_c: -6 3 7 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0167 0.0083 2.7489 +-0.0333 0.0167 2.7489 +-0.0500 0.0250 2.7489 +-0.0667 0.0333 2.7489 +-0.0833 0.0417 2.7489 +-0.1000 0.0500 2.7489 +-0.1167 0.0583 2.7489 +-0.1333 0.0667 2.7489 +-0.1500 0.0750 2.7489 +primID: 2 +startangle_c: 7 +endpose_c: 2 -1 7 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0056 -0.0028 2.7489 +0.0111 -0.0056 2.7489 +0.0167 -0.0083 2.7489 +0.0222 -0.0111 2.7489 +0.0278 -0.0139 2.7489 +0.0333 -0.0167 2.7489 +0.0389 -0.0194 2.7489 +0.0444 -0.0222 2.7489 +0.0500 -0.0250 2.7489 +primID: 3 +startangle_c: 7 +endpose_c: -5 4 6 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0149 0.0092 2.7186 +-0.0296 0.0189 2.6883 +-0.0440 0.0291 2.6580 +-0.0582 0.0398 2.6277 +-0.0722 0.0509 2.5974 +-0.0858 0.0625 2.5671 +-0.0992 0.0746 2.5368 +-0.1123 0.0871 2.5065 +-0.1250 0.1000 2.4762 +primID: 4 +startangle_c: 7 +endpose_c: -7 2 8 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0188 0.0078 2.7489 +-0.0377 0.0156 2.7489 +-0.0565 0.0234 2.7489 +-0.0754 0.0312 2.7680 +-0.0946 0.0379 2.8427 +-0.1143 0.0432 2.9174 +-0.1344 0.0470 2.9921 +-0.1546 0.0492 3.0669 +-0.1750 0.0500 3.1416 +primID: 5 +startangle_c: 7 +endpose_c: 0 0 6 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0000 0.0000 2.7053 +0.0000 0.0000 2.6616 +0.0000 0.0000 2.6180 +0.0000 0.0000 2.5744 +0.0000 0.0000 2.5307 +0.0000 0.0000 2.4871 +0.0000 0.0000 2.4435 +0.0000 0.0000 2.3998 +0.0000 0.0000 2.3562 +primID: 6 +startangle_c: 7 +endpose_c: 0 0 8 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0000 0.0000 2.7925 +0.0000 0.0000 2.8362 +0.0000 0.0000 2.8798 +0.0000 0.0000 2.9234 +0.0000 0.0000 2.9671 +0.0000 0.0000 3.0107 +0.0000 0.0000 3.0543 +0.0000 0.0000 3.0980 +0.0000 0.0000 3.1416 +primID: 0 +startangle_c: 8 +endpose_c: -1 0 8 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0028 0.0000 3.1416 +-0.0056 0.0000 3.1416 +-0.0083 0.0000 3.1416 +-0.0111 0.0000 3.1416 +-0.0139 0.0000 3.1416 +-0.0167 0.0000 3.1416 +-0.0194 0.0000 3.1416 +-0.0222 0.0000 3.1416 +-0.0250 0.0000 3.1416 +primID: 1 +startangle_c: 8 +endpose_c: -8 0 8 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0222 0.0000 3.1416 +-0.0444 0.0000 3.1416 +-0.0667 0.0000 3.1416 +-0.0889 0.0000 3.1416 +-0.1111 0.0000 3.1416 +-0.1333 0.0000 3.1416 +-0.1556 0.0000 3.1416 +-0.1778 0.0000 3.1416 +-0.2000 0.0000 3.1416 +primID: 2 +startangle_c: 8 +endpose_c: 1 0 8 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0028 0.0000 3.1416 +0.0056 0.0000 3.1416 +0.0083 0.0000 3.1416 +0.0111 0.0000 3.1416 +0.0139 0.0000 3.1416 +0.0167 0.0000 3.1416 +0.0194 0.0000 3.1416 +0.0222 0.0000 3.1416 +0.0250 0.0000 3.1416 +primID: 3 +startangle_c: 8 +endpose_c: -8 -1 9 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0226 0.0000 3.1416 +-0.0452 0.0000 3.1416 +-0.0678 0.0000 3.1416 +-0.0903 -0.0004 3.1904 +-0.1128 -0.0023 3.2592 +-0.1352 -0.0057 3.3280 +-0.1572 -0.0106 3.3967 +-0.1789 -0.0171 3.4655 +-0.2000 -0.0250 3.5343 +primID: 4 +startangle_c: 8 +endpose_c: -8 1 7 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0226 0.0000 3.1416 +-0.0452 0.0000 3.1416 +-0.0678 0.0000 3.1416 +-0.0903 0.0004 3.0928 +-0.1128 0.0023 3.0240 +-0.1352 0.0057 2.9552 +-0.1572 0.0106 2.8864 +-0.1789 0.0171 2.8177 +-0.2000 0.0250 2.7489 +primID: 5 +startangle_c: 8 +endpose_c: 0 0 9 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0000 0.0000 3.1852 +0.0000 0.0000 3.2289 +0.0000 0.0000 3.2725 +0.0000 0.0000 3.3161 +0.0000 0.0000 3.3598 +0.0000 0.0000 3.4034 +0.0000 0.0000 3.4470 +0.0000 0.0000 3.4907 +0.0000 0.0000 3.5343 +primID: 6 +startangle_c: 8 +endpose_c: 0 0 7 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0000 0.0000 3.0980 +0.0000 0.0000 3.0543 +0.0000 0.0000 3.0107 +0.0000 0.0000 2.9671 +0.0000 0.0000 2.9234 +0.0000 0.0000 2.8798 +0.0000 0.0000 2.8362 +0.0000 0.0000 2.7925 +0.0000 0.0000 2.7489 +primID: 0 +startangle_c: 9 +endpose_c: -2 -1 9 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0056 -0.0028 3.5343 +-0.0111 -0.0056 3.5343 +-0.0167 -0.0083 3.5343 +-0.0222 -0.0111 3.5343 +-0.0278 -0.0139 3.5343 +-0.0333 -0.0167 3.5343 +-0.0389 -0.0194 3.5343 +-0.0444 -0.0222 3.5343 +-0.0500 -0.0250 3.5343 +primID: 1 +startangle_c: 9 +endpose_c: -6 -3 9 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0167 -0.0083 3.5343 +-0.0333 -0.0167 3.5343 +-0.0500 -0.0250 3.5343 +-0.0667 -0.0333 3.5343 +-0.0833 -0.0417 3.5343 +-0.1000 -0.0500 3.5343 +-0.1167 -0.0583 3.5343 +-0.1333 -0.0667 3.5343 +-0.1500 -0.0750 3.5343 +primID: 2 +startangle_c: 9 +endpose_c: 2 1 9 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0056 0.0028 3.5343 +0.0111 0.0056 3.5343 +0.0167 0.0083 3.5343 +0.0222 0.0111 3.5343 +0.0278 0.0139 3.5343 +0.0333 0.0167 3.5343 +0.0389 0.0194 3.5343 +0.0444 0.0222 3.5343 +0.0500 0.0250 3.5343 +primID: 3 +startangle_c: 9 +endpose_c: -5 -4 10 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0149 -0.0092 3.5646 +-0.0296 -0.0189 3.5949 +-0.0440 -0.0291 3.6252 +-0.0582 -0.0398 3.6555 +-0.0722 -0.0509 3.6858 +-0.0858 -0.0625 3.7161 +-0.0992 -0.0746 3.7464 +-0.1123 -0.0871 3.7767 +-0.1250 -0.1000 3.8070 +primID: 4 +startangle_c: 9 +endpose_c: -7 -2 8 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0188 -0.0078 3.5343 +-0.0377 -0.0156 3.5343 +-0.0565 -0.0234 3.5343 +-0.0754 -0.0312 3.5152 +-0.0946 -0.0379 3.4405 +-0.1143 -0.0432 3.3658 +-0.1344 -0.0470 3.2910 +-0.1546 -0.0492 3.2163 +-0.1750 -0.0500 3.1416 +primID: 5 +startangle_c: 9 +endpose_c: 0 0 10 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0000 0.0000 3.5779 +0.0000 0.0000 3.6216 +0.0000 0.0000 3.6652 +0.0000 0.0000 3.7088 +0.0000 0.0000 3.7525 +0.0000 0.0000 3.7961 +0.0000 0.0000 3.8397 +0.0000 0.0000 3.8834 +0.0000 0.0000 3.9270 +primID: 6 +startangle_c: 9 +endpose_c: 0 0 8 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0000 0.0000 3.4907 +0.0000 0.0000 3.4470 +0.0000 0.0000 3.4034 +0.0000 0.0000 3.3598 +0.0000 0.0000 3.3161 +0.0000 0.0000 3.2725 +0.0000 0.0000 3.2289 +0.0000 0.0000 3.1852 +0.0000 0.0000 3.1416 +primID: 0 +startangle_c: 10 +endpose_c: -1 -1 10 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0028 -0.0028 3.9270 +-0.0056 -0.0056 3.9270 +-0.0083 -0.0083 3.9270 +-0.0111 -0.0111 3.9270 +-0.0139 -0.0139 3.9270 +-0.0167 -0.0167 3.9270 +-0.0194 -0.0194 3.9270 +-0.0222 -0.0222 3.9270 +-0.0250 -0.0250 3.9270 +primID: 1 +startangle_c: 10 +endpose_c: -6 -6 10 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0167 -0.0167 3.9270 +-0.0333 -0.0333 3.9270 +-0.0500 -0.0500 3.9270 +-0.0667 -0.0667 3.9270 +-0.0833 -0.0833 3.9270 +-0.1000 -0.1000 3.9270 +-0.1167 -0.1167 3.9270 +-0.1333 -0.1333 3.9270 +-0.1500 -0.1500 3.9270 +primID: 2 +startangle_c: 10 +endpose_c: 1 1 10 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0028 0.0028 3.9270 +0.0056 0.0056 3.9270 +0.0083 0.0083 3.9270 +0.0111 0.0111 3.9270 +0.0139 0.0139 3.9270 +0.0167 0.0167 3.9270 +0.0194 0.0194 3.9270 +0.0222 0.0222 3.9270 +0.0250 0.0250 3.9270 +primID: 3 +startangle_c: 10 +endpose_c: -5 -7 11 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0170 -0.0170 3.9270 +-0.0339 -0.0342 3.9567 +-0.0500 -0.0522 4.0085 +-0.0651 -0.0709 4.0604 +-0.0792 -0.0904 4.1123 +-0.0923 -0.1107 4.1641 +-0.1043 -0.1315 4.2160 +-0.1152 -0.1530 4.2678 +-0.1250 -0.1750 4.3197 +primID: 4 +startangle_c: 10 +endpose_c: -7 -5 9 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0170 -0.0170 3.9270 +-0.0342 -0.0339 3.8973 +-0.0522 -0.0500 3.8455 +-0.0709 -0.0651 3.7936 +-0.0904 -0.0792 3.7417 +-0.1107 -0.0923 3.6899 +-0.1315 -0.1043 3.6380 +-0.1530 -0.1152 3.5862 +-0.1750 -0.1250 3.5343 +primID: 5 +startangle_c: 10 +endpose_c: 0 0 11 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.9706 +0.0000 0.0000 4.0143 +0.0000 0.0000 4.0579 +0.0000 0.0000 4.1015 +0.0000 0.0000 4.1452 +0.0000 0.0000 4.1888 +0.0000 0.0000 4.2324 +0.0000 0.0000 4.2761 +0.0000 0.0000 4.3197 +primID: 6 +startangle_c: 10 +endpose_c: 0 0 9 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.8834 +0.0000 0.0000 3.8397 +0.0000 0.0000 3.7961 +0.0000 0.0000 3.7525 +0.0000 0.0000 3.7088 +0.0000 0.0000 3.6652 +0.0000 0.0000 3.6216 +0.0000 0.0000 3.5779 +0.0000 0.0000 3.5343 +primID: 0 +startangle_c: 11 +endpose_c: -1 -2 11 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0028 -0.0056 4.3197 +-0.0056 -0.0111 4.3197 +-0.0083 -0.0167 4.3197 +-0.0111 -0.0222 4.3197 +-0.0139 -0.0278 4.3197 +-0.0167 -0.0333 4.3197 +-0.0194 -0.0389 4.3197 +-0.0222 -0.0444 4.3197 +-0.0250 -0.0500 4.3197 +primID: 1 +startangle_c: 11 +endpose_c: -3 -6 11 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0083 -0.0167 4.3197 +-0.0167 -0.0333 4.3197 +-0.0250 -0.0500 4.3197 +-0.0333 -0.0667 4.3197 +-0.0417 -0.0833 4.3197 +-0.0500 -0.1000 4.3197 +-0.0583 -0.1167 4.3197 +-0.0667 -0.1333 4.3197 +-0.0750 -0.1500 4.3197 +primID: 2 +startangle_c: 11 +endpose_c: 1 2 11 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0028 0.0056 4.3197 +0.0056 0.0111 4.3197 +0.0083 0.0167 4.3197 +0.0111 0.0222 4.3197 +0.0139 0.0278 4.3197 +0.0167 0.0333 4.3197 +0.0194 0.0389 4.3197 +0.0222 0.0444 4.3197 +0.0250 0.0500 4.3197 +primID: 3 +startangle_c: 11 +endpose_c: -4 -5 10 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0092 -0.0149 4.2894 +-0.0189 -0.0296 4.2591 +-0.0291 -0.0440 4.2288 +-0.0398 -0.0582 4.1985 +-0.0509 -0.0722 4.1682 +-0.0625 -0.0858 4.1379 +-0.0746 -0.0992 4.1076 +-0.0871 -0.1123 4.0773 +-0.1000 -0.1250 4.0470 +primID: 4 +startangle_c: 11 +endpose_c: -2 -7 12 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0078 -0.0188 4.3197 +-0.0156 -0.0377 4.3197 +-0.0234 -0.0565 4.3197 +-0.0312 -0.0754 4.3388 +-0.0379 -0.0946 4.4135 +-0.0432 -0.1143 4.4882 +-0.0470 -0.1344 4.5629 +-0.0492 -0.1546 4.6377 +-0.0500 -0.1750 4.7124 +primID: 5 +startangle_c: 11 +endpose_c: 0 0 10 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0000 0.0000 4.2761 +0.0000 0.0000 4.2324 +0.0000 0.0000 4.1888 +0.0000 0.0000 4.1452 +0.0000 0.0000 4.1015 +0.0000 0.0000 4.0579 +0.0000 0.0000 4.0143 +0.0000 0.0000 3.9706 +0.0000 0.0000 3.9270 +primID: 6 +startangle_c: 11 +endpose_c: 0 0 12 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0000 0.0000 4.3633 +0.0000 0.0000 4.4070 +0.0000 0.0000 4.4506 +0.0000 0.0000 4.4942 +0.0000 0.0000 4.5379 +0.0000 0.0000 4.5815 +0.0000 0.0000 4.6251 +0.0000 0.0000 4.6688 +0.0000 0.0000 4.7124 +primID: 0 +startangle_c: 12 +endpose_c: 0 -1 12 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0028 4.7124 +0.0000 -0.0056 4.7124 +0.0000 -0.0083 4.7124 +0.0000 -0.0111 4.7124 +0.0000 -0.0139 4.7124 +0.0000 -0.0167 4.7124 +0.0000 -0.0194 4.7124 +0.0000 -0.0222 4.7124 +0.0000 -0.0250 4.7124 +primID: 1 +startangle_c: 12 +endpose_c: 0 -8 12 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0222 4.7124 +0.0000 -0.0444 4.7124 +0.0000 -0.0667 4.7124 +0.0000 -0.0889 4.7124 +0.0000 -0.1111 4.7124 +0.0000 -0.1333 4.7124 +0.0000 -0.1556 4.7124 +0.0000 -0.1778 4.7124 +0.0000 -0.2000 4.7124 +primID: 2 +startangle_c: 12 +endpose_c: 0 1 12 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0028 4.7124 +0.0000 0.0056 4.7124 +0.0000 0.0083 4.7124 +0.0000 0.0111 4.7124 +0.0000 0.0139 4.7124 +0.0000 0.0167 4.7124 +0.0000 0.0194 4.7124 +0.0000 0.0222 4.7124 +0.0000 0.0250 4.7124 +primID: 3 +startangle_c: 12 +endpose_c: 1 -8 13 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 4.7124 +-0.0000 -0.0226 4.7124 +-0.0000 -0.0452 4.7124 +-0.0000 -0.0678 4.7124 +0.0004 -0.0903 4.7612 +0.0023 -0.1128 4.8300 +0.0057 -0.1352 4.8988 +0.0106 -0.1572 4.9675 +0.0171 -0.1789 5.0363 +0.0250 -0.2000 5.1051 +primID: 4 +startangle_c: 12 +endpose_c: -1 -8 11 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 4.7124 +-0.0000 -0.0226 4.7124 +-0.0000 -0.0452 4.7124 +-0.0000 -0.0678 4.7124 +-0.0004 -0.0903 4.6636 +-0.0023 -0.1128 4.5948 +-0.0057 -0.1352 4.5260 +-0.0106 -0.1572 4.4572 +-0.0171 -0.1789 4.3885 +-0.0250 -0.2000 4.3197 +primID: 5 +startangle_c: 12 +endpose_c: 0 0 13 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0000 4.7560 +0.0000 0.0000 4.7997 +0.0000 0.0000 4.8433 +0.0000 0.0000 4.8869 +0.0000 0.0000 4.9306 +0.0000 0.0000 4.9742 +0.0000 0.0000 5.0178 +0.0000 0.0000 5.0615 +0.0000 0.0000 5.1051 +primID: 6 +startangle_c: 12 +endpose_c: 0 0 11 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0000 4.6688 +0.0000 0.0000 4.6251 +0.0000 0.0000 4.5815 +0.0000 0.0000 4.5379 +0.0000 0.0000 4.4942 +0.0000 0.0000 4.4506 +0.0000 0.0000 4.4070 +0.0000 0.0000 4.3633 +0.0000 0.0000 4.3197 +primID: 0 +startangle_c: 13 +endpose_c: 1 -2 13 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0028 -0.0056 5.1051 +0.0056 -0.0111 5.1051 +0.0083 -0.0167 5.1051 +0.0111 -0.0222 5.1051 +0.0139 -0.0278 5.1051 +0.0167 -0.0333 5.1051 +0.0194 -0.0389 5.1051 +0.0222 -0.0444 5.1051 +0.0250 -0.0500 5.1051 +primID: 1 +startangle_c: 13 +endpose_c: 3 -6 13 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0083 -0.0167 5.1051 +0.0167 -0.0333 5.1051 +0.0250 -0.0500 5.1051 +0.0333 -0.0667 5.1051 +0.0417 -0.0833 5.1051 +0.0500 -0.1000 5.1051 +0.0583 -0.1167 5.1051 +0.0667 -0.1333 5.1051 +0.0750 -0.1500 5.1051 +primID: 2 +startangle_c: 13 +endpose_c: -1 2 13 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 5.1051 +-0.0028 0.0056 5.1051 +-0.0056 0.0111 5.1051 +-0.0083 0.0167 5.1051 +-0.0111 0.0222 5.1051 +-0.0139 0.0278 5.1051 +-0.0167 0.0333 5.1051 +-0.0194 0.0389 5.1051 +-0.0222 0.0444 5.1051 +-0.0250 0.0500 5.1051 +primID: 3 +startangle_c: 13 +endpose_c: 4 -5 14 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0092 -0.0149 5.1354 +0.0189 -0.0296 5.1657 +0.0291 -0.0440 5.1960 +0.0398 -0.0582 5.2263 +0.0509 -0.0722 5.2566 +0.0625 -0.0858 5.2869 +0.0746 -0.0992 5.3172 +0.0871 -0.1123 5.3475 +0.1000 -0.1250 5.3778 +primID: 4 +startangle_c: 13 +endpose_c: 2 -7 12 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0078 -0.0188 5.1051 +0.0156 -0.0377 5.1051 +0.0234 -0.0565 5.1051 +0.0312 -0.0754 5.0860 +0.0379 -0.0946 5.0113 +0.0432 -0.1143 4.9366 +0.0470 -0.1344 4.8618 +0.0492 -0.1546 4.7871 +0.0500 -0.1750 4.7124 +primID: 5 +startangle_c: 13 +endpose_c: 0 0 14 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0000 0.0000 5.1487 +0.0000 0.0000 5.1924 +0.0000 0.0000 5.2360 +0.0000 0.0000 5.2796 +0.0000 0.0000 5.3233 +0.0000 0.0000 5.3669 +0.0000 0.0000 5.4105 +0.0000 0.0000 5.4542 +0.0000 0.0000 5.4978 +primID: 6 +startangle_c: 13 +endpose_c: 0 0 12 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0000 0.0000 5.0615 +0.0000 0.0000 5.0178 +0.0000 0.0000 4.9742 +0.0000 0.0000 4.9306 +0.0000 0.0000 4.8869 +0.0000 0.0000 4.8433 +0.0000 0.0000 4.7997 +0.0000 0.0000 4.7560 +0.0000 0.0000 4.7124 +primID: 0 +startangle_c: 14 +endpose_c: 1 -1 14 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0028 -0.0028 5.4978 +0.0056 -0.0056 5.4978 +0.0083 -0.0083 5.4978 +0.0111 -0.0111 5.4978 +0.0139 -0.0139 5.4978 +0.0167 -0.0167 5.4978 +0.0194 -0.0194 5.4978 +0.0222 -0.0222 5.4978 +0.0250 -0.0250 5.4978 +primID: 1 +startangle_c: 14 +endpose_c: 6 -6 14 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0167 -0.0167 5.4978 +0.0333 -0.0333 5.4978 +0.0500 -0.0500 5.4978 +0.0667 -0.0667 5.4978 +0.0833 -0.0833 5.4978 +0.1000 -0.1000 5.4978 +0.1167 -0.1167 5.4978 +0.1333 -0.1333 5.4978 +0.1500 -0.1500 5.4978 +primID: 2 +startangle_c: 14 +endpose_c: -1 1 14 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 5.4978 +-0.0028 0.0028 5.4978 +-0.0056 0.0056 5.4978 +-0.0083 0.0083 5.4978 +-0.0111 0.0111 5.4978 +-0.0139 0.0139 5.4978 +-0.0167 0.0167 5.4978 +-0.0194 0.0194 5.4978 +-0.0222 0.0222 5.4978 +-0.0250 0.0250 5.4978 +primID: 3 +startangle_c: 14 +endpose_c: 7 -5 15 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0170 -0.0170 5.4978 +0.0342 -0.0339 5.5275 +0.0522 -0.0500 5.5793 +0.0709 -0.0651 5.6312 +0.0904 -0.0792 5.6830 +0.1107 -0.0923 5.7349 +0.1315 -0.1043 5.7868 +0.1530 -0.1152 5.8386 +0.1750 -0.1250 5.8905 +primID: 4 +startangle_c: 14 +endpose_c: 5 -7 13 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0170 -0.0170 5.4978 +0.0339 -0.0342 5.4681 +0.0500 -0.0522 5.4162 +0.0651 -0.0709 5.3644 +0.0792 -0.0904 5.3125 +0.0923 -0.1107 5.2607 +0.1043 -0.1315 5.2088 +0.1152 -0.1530 5.1569 +0.1250 -0.1750 5.1051 +primID: 5 +startangle_c: 14 +endpose_c: 0 0 15 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0000 0.0000 5.5414 +0.0000 0.0000 5.5851 +0.0000 0.0000 5.6287 +0.0000 0.0000 5.6723 +0.0000 0.0000 5.7160 +0.0000 0.0000 5.7596 +0.0000 0.0000 5.8032 +0.0000 0.0000 5.8469 +0.0000 0.0000 5.8905 +primID: 6 +startangle_c: 14 +endpose_c: 0 0 13 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0000 0.0000 5.4542 +0.0000 0.0000 5.4105 +0.0000 0.0000 5.3669 +0.0000 0.0000 5.3233 +0.0000 0.0000 5.2796 +0.0000 0.0000 5.2360 +0.0000 0.0000 5.1924 +0.0000 0.0000 5.1487 +0.0000 0.0000 5.1051 +primID: 0 +startangle_c: 15 +endpose_c: 2 -1 15 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0056 -0.0028 5.8905 +0.0111 -0.0056 5.8905 +0.0167 -0.0083 5.8905 +0.0222 -0.0111 5.8905 +0.0278 -0.0139 5.8905 +0.0333 -0.0167 5.8905 +0.0389 -0.0194 5.8905 +0.0444 -0.0222 5.8905 +0.0500 -0.0250 5.8905 +primID: 1 +startangle_c: 15 +endpose_c: 6 -3 15 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0167 -0.0083 5.8905 +0.0333 -0.0167 5.8905 +0.0500 -0.0250 5.8905 +0.0667 -0.0333 5.8905 +0.0833 -0.0417 5.8905 +0.1000 -0.0500 5.8905 +0.1167 -0.0583 5.8905 +0.1333 -0.0667 5.8905 +0.1500 -0.0750 5.8905 +primID: 2 +startangle_c: 15 +endpose_c: -2 1 15 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 5.8905 +-0.0056 0.0028 5.8905 +-0.0111 0.0056 5.8905 +-0.0167 0.0083 5.8905 +-0.0222 0.0111 5.8905 +-0.0278 0.0139 5.8905 +-0.0333 0.0167 5.8905 +-0.0389 0.0194 5.8905 +-0.0444 0.0222 5.8905 +-0.0500 0.0250 5.8905 +primID: 3 +startangle_c: 15 +endpose_c: 5 -4 14 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0149 -0.0092 5.8602 +0.0296 -0.0189 5.8299 +0.0440 -0.0291 5.7996 +0.0582 -0.0398 5.7693 +0.0722 -0.0509 5.7390 +0.0858 -0.0625 5.7087 +0.0992 -0.0746 5.6784 +0.1123 -0.0871 5.6481 +0.1250 -0.1000 5.6178 +primID: 4 +startangle_c: 15 +endpose_c: 7 -2 0 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0188 -0.0078 5.8905 +0.0377 -0.0156 5.8905 +0.0565 -0.0234 5.8905 +0.0754 -0.0312 5.9096 +0.0946 -0.0379 5.9843 +0.1143 -0.0432 6.0590 +0.1344 -0.0470 6.1337 +0.1546 -0.0492 6.2085 +0.1750 -0.0500 6.2832 +primID: 5 +startangle_c: 15 +endpose_c: 0 0 14 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0000 0.0000 5.8469 +0.0000 0.0000 5.8032 +0.0000 0.0000 5.7596 +0.0000 0.0000 5.7160 +0.0000 0.0000 5.6723 +0.0000 0.0000 5.6287 +0.0000 0.0000 5.5851 +0.0000 0.0000 5.5414 +0.0000 0.0000 5.4978 +primID: 6 +startangle_c: 15 +endpose_c: 0 0 0 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0000 0.0000 5.9341 +0.0000 0.0000 5.9778 +0.0000 0.0000 6.0214 +0.0000 0.0000 6.0650 +0.0000 0.0000 6.1087 +0.0000 0.0000 6.1523 +0.0000 0.0000 6.1959 +0.0000 0.0000 6.2396 +0.0000 0.0000 0.0000 diff --git a/navigations/sbpl/matlab/mprim/unicycle_noturninplace.mprim b/navigations/sbpl/matlab/mprim/unicycle_noturninplace.mprim new file mode 100755 index 0000000..5ab6833 --- /dev/null +++ b/navigations/sbpl/matlab/mprim/unicycle_noturninplace.mprim @@ -0,0 +1,1203 @@ +resolution_m: 0.025000 +numberofangles: 16 +totalnumberofprimitives: 80 +primID: 0 +startangle_c: 0 +endpose_c: 1 0 0 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0028 0.0000 0.0000 +0.0056 0.0000 0.0000 +0.0083 0.0000 0.0000 +0.0111 0.0000 0.0000 +0.0139 0.0000 0.0000 +0.0167 0.0000 0.0000 +0.0194 0.0000 0.0000 +0.0222 0.0000 0.0000 +0.0250 0.0000 0.0000 +primID: 1 +startangle_c: 0 +endpose_c: 8 0 0 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0222 0.0000 0.0000 +0.0444 0.0000 0.0000 +0.0667 0.0000 0.0000 +0.0889 0.0000 0.0000 +0.1111 0.0000 0.0000 +0.1333 0.0000 0.0000 +0.1556 0.0000 0.0000 +0.1778 0.0000 0.0000 +0.2000 0.0000 0.0000 +primID: 2 +startangle_c: 0 +endpose_c: -1 0 0 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 0.0000 +-0.0028 0.0000 0.0000 +-0.0056 0.0000 0.0000 +-0.0083 0.0000 0.0000 +-0.0111 0.0000 0.0000 +-0.0139 0.0000 0.0000 +-0.0167 0.0000 0.0000 +-0.0194 0.0000 0.0000 +-0.0222 0.0000 0.0000 +-0.0250 0.0000 0.0000 +primID: 3 +startangle_c: 0 +endpose_c: 8 1 1 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0226 -0.0000 0.0000 +0.0452 -0.0000 0.0000 +0.0678 -0.0000 0.0000 +0.0903 0.0004 0.0488 +0.1128 0.0023 0.1176 +0.1352 0.0057 0.1864 +0.1572 0.0106 0.2551 +0.1789 0.0171 0.3239 +0.2000 0.0250 0.3927 +primID: 4 +startangle_c: 0 +endpose_c: 8 -1 -1 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0226 0.0000 0.0000 +0.0452 0.0000 0.0000 +0.0678 0.0000 0.0000 +0.0903 -0.0004 -0.0488 +0.1128 -0.0023 -0.1176 +0.1352 -0.0057 -0.1864 +0.1572 -0.0106 -0.2551 +0.1789 -0.0171 -0.3239 +0.2000 -0.0250 -0.3927 +primID: 0 +startangle_c: 1 +endpose_c: 2 1 1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0056 0.0028 0.3927 +0.0111 0.0056 0.3927 +0.0167 0.0083 0.3927 +0.0222 0.0111 0.3927 +0.0278 0.0139 0.3927 +0.0333 0.0167 0.3927 +0.0389 0.0194 0.3927 +0.0444 0.0222 0.3927 +0.0500 0.0250 0.3927 +primID: 1 +startangle_c: 1 +endpose_c: 6 3 1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0167 0.0083 0.3927 +0.0333 0.0167 0.3927 +0.0500 0.0250 0.3927 +0.0667 0.0333 0.3927 +0.0833 0.0417 0.3927 +0.1000 0.0500 0.3927 +0.1167 0.0583 0.3927 +0.1333 0.0667 0.3927 +0.1500 0.0750 0.3927 +primID: 2 +startangle_c: 1 +endpose_c: -2 -1 1 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 0.3927 +-0.0056 -0.0028 0.3927 +-0.0111 -0.0056 0.3927 +-0.0167 -0.0083 0.3927 +-0.0222 -0.0111 0.3927 +-0.0278 -0.0139 0.3927 +-0.0333 -0.0167 0.3927 +-0.0389 -0.0194 0.3927 +-0.0444 -0.0222 0.3927 +-0.0500 -0.0250 0.3927 +primID: 3 +startangle_c: 1 +endpose_c: 5 4 2 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0149 0.0092 0.4230 +0.0296 0.0189 0.4533 +0.0440 0.0291 0.4836 +0.0582 0.0398 0.5139 +0.0722 0.0509 0.5442 +0.0858 0.0625 0.5745 +0.0992 0.0746 0.6048 +0.1123 0.0871 0.6351 +0.1250 0.1000 0.6654 +primID: 4 +startangle_c: 1 +endpose_c: 7 2 0 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0188 0.0078 0.3927 +0.0377 0.0156 0.3927 +0.0565 0.0234 0.3927 +0.0754 0.0312 0.3736 +0.0946 0.0379 0.2989 +0.1143 0.0432 0.2242 +0.1344 0.0470 0.1494 +0.1546 0.0492 0.0747 +0.1750 0.0500 0.0000 +primID: 0 +startangle_c: 2 +endpose_c: 1 1 2 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0028 0.0028 0.7854 +0.0056 0.0056 0.7854 +0.0083 0.0083 0.7854 +0.0111 0.0111 0.7854 +0.0139 0.0139 0.7854 +0.0167 0.0167 0.7854 +0.0194 0.0194 0.7854 +0.0222 0.0222 0.7854 +0.0250 0.0250 0.7854 +primID: 1 +startangle_c: 2 +endpose_c: 6 6 2 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0167 0.0167 0.7854 +0.0333 0.0333 0.7854 +0.0500 0.0500 0.7854 +0.0667 0.0667 0.7854 +0.0833 0.0833 0.7854 +0.1000 0.1000 0.7854 +0.1167 0.1167 0.7854 +0.1333 0.1333 0.7854 +0.1500 0.1500 0.7854 +primID: 2 +startangle_c: 2 +endpose_c: -1 -1 2 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 0.7854 +-0.0028 -0.0028 0.7854 +-0.0056 -0.0056 0.7854 +-0.0083 -0.0083 0.7854 +-0.0111 -0.0111 0.7854 +-0.0139 -0.0139 0.7854 +-0.0167 -0.0167 0.7854 +-0.0194 -0.0194 0.7854 +-0.0222 -0.0222 0.7854 +-0.0250 -0.0250 0.7854 +primID: 3 +startangle_c: 2 +endpose_c: 5 7 3 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0170 0.0170 0.7854 +0.0339 0.0342 0.8151 +0.0500 0.0522 0.8669 +0.0651 0.0709 0.9188 +0.0792 0.0904 0.9707 +0.0923 0.1107 1.0225 +0.1043 0.1315 1.0744 +0.1152 0.1530 1.1262 +0.1250 0.1750 1.1781 +primID: 4 +startangle_c: 2 +endpose_c: 7 5 1 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0170 0.0170 0.7854 +0.0342 0.0339 0.7557 +0.0522 0.0500 0.7039 +0.0709 0.0651 0.6520 +0.0904 0.0792 0.6001 +0.1107 0.0923 0.5483 +0.1315 0.1043 0.4964 +0.1530 0.1152 0.4446 +0.1750 0.1250 0.3927 +primID: 0 +startangle_c: 3 +endpose_c: 1 2 3 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0028 0.0056 1.1781 +0.0056 0.0111 1.1781 +0.0083 0.0167 1.1781 +0.0111 0.0222 1.1781 +0.0139 0.0278 1.1781 +0.0167 0.0333 1.1781 +0.0194 0.0389 1.1781 +0.0222 0.0444 1.1781 +0.0250 0.0500 1.1781 +primID: 1 +startangle_c: 3 +endpose_c: 3 6 3 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0083 0.0167 1.1781 +0.0167 0.0333 1.1781 +0.0250 0.0500 1.1781 +0.0333 0.0667 1.1781 +0.0417 0.0833 1.1781 +0.0500 0.1000 1.1781 +0.0583 0.1167 1.1781 +0.0667 0.1333 1.1781 +0.0750 0.1500 1.1781 +primID: 2 +startangle_c: 3 +endpose_c: -1 -2 3 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 1.1781 +-0.0028 -0.0056 1.1781 +-0.0056 -0.0111 1.1781 +-0.0083 -0.0167 1.1781 +-0.0111 -0.0222 1.1781 +-0.0139 -0.0278 1.1781 +-0.0167 -0.0333 1.1781 +-0.0194 -0.0389 1.1781 +-0.0222 -0.0444 1.1781 +-0.0250 -0.0500 1.1781 +primID: 3 +startangle_c: 3 +endpose_c: 4 5 2 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0092 0.0149 1.1478 +0.0189 0.0296 1.1175 +0.0291 0.0440 1.0872 +0.0398 0.0582 1.0569 +0.0509 0.0722 1.0266 +0.0625 0.0858 0.9963 +0.0746 0.0992 0.9660 +0.0871 0.1123 0.9357 +0.1000 0.1250 0.9054 +primID: 4 +startangle_c: 3 +endpose_c: 2 7 4 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0078 0.0188 1.1781 +0.0156 0.0377 1.1781 +0.0234 0.0565 1.1781 +0.0312 0.0754 1.1972 +0.0379 0.0946 1.2719 +0.0432 0.1143 1.3466 +0.0470 0.1344 1.4214 +0.0492 0.1546 1.4961 +0.0500 0.1750 1.5708 +primID: 0 +startangle_c: 4 +endpose_c: 0 1 4 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0028 1.5708 +0.0000 0.0056 1.5708 +0.0000 0.0083 1.5708 +0.0000 0.0111 1.5708 +0.0000 0.0139 1.5708 +0.0000 0.0167 1.5708 +0.0000 0.0194 1.5708 +0.0000 0.0222 1.5708 +0.0000 0.0250 1.5708 +primID: 1 +startangle_c: 4 +endpose_c: 0 8 4 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0222 1.5708 +0.0000 0.0444 1.5708 +0.0000 0.0667 1.5708 +0.0000 0.0889 1.5708 +0.0000 0.1111 1.5708 +0.0000 0.1333 1.5708 +0.0000 0.1556 1.5708 +0.0000 0.1778 1.5708 +0.0000 0.2000 1.5708 +primID: 2 +startangle_c: 4 +endpose_c: 0 -1 4 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 -0.0028 1.5708 +0.0000 -0.0056 1.5708 +0.0000 -0.0083 1.5708 +0.0000 -0.0111 1.5708 +0.0000 -0.0139 1.5708 +0.0000 -0.0167 1.5708 +0.0000 -0.0194 1.5708 +0.0000 -0.0222 1.5708 +0.0000 -0.0250 1.5708 +primID: 3 +startangle_c: 4 +endpose_c: -1 8 5 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0226 1.5708 +0.0000 0.0452 1.5708 +0.0000 0.0678 1.5708 +-0.0004 0.0903 1.6196 +-0.0023 0.1128 1.6884 +-0.0057 0.1352 1.7572 +-0.0106 0.1572 1.8259 +-0.0171 0.1789 1.8947 +-0.0250 0.2000 1.9635 +primID: 4 +startangle_c: 4 +endpose_c: 1 8 3 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.5708 +-0.0000 0.0226 1.5708 +-0.0000 0.0452 1.5708 +-0.0000 0.0678 1.5708 +0.0004 0.0903 1.5220 +0.0023 0.1128 1.4532 +0.0057 0.1352 1.3844 +0.0106 0.1572 1.3156 +0.0171 0.1789 1.2469 +0.0250 0.2000 1.1781 +primID: 0 +startangle_c: 5 +endpose_c: -1 2 5 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0028 0.0056 1.9635 +-0.0056 0.0111 1.9635 +-0.0083 0.0167 1.9635 +-0.0111 0.0222 1.9635 +-0.0139 0.0278 1.9635 +-0.0167 0.0333 1.9635 +-0.0194 0.0389 1.9635 +-0.0222 0.0444 1.9635 +-0.0250 0.0500 1.9635 +primID: 1 +startangle_c: 5 +endpose_c: -3 6 5 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0083 0.0167 1.9635 +-0.0167 0.0333 1.9635 +-0.0250 0.0500 1.9635 +-0.0333 0.0667 1.9635 +-0.0417 0.0833 1.9635 +-0.0500 0.1000 1.9635 +-0.0583 0.1167 1.9635 +-0.0667 0.1333 1.9635 +-0.0750 0.1500 1.9635 +primID: 2 +startangle_c: 5 +endpose_c: 1 -2 5 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0028 -0.0056 1.9635 +0.0056 -0.0111 1.9635 +0.0083 -0.0167 1.9635 +0.0111 -0.0222 1.9635 +0.0139 -0.0278 1.9635 +0.0167 -0.0333 1.9635 +0.0194 -0.0389 1.9635 +0.0222 -0.0444 1.9635 +0.0250 -0.0500 1.9635 +primID: 3 +startangle_c: 5 +endpose_c: -4 5 6 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0092 0.0149 1.9938 +-0.0189 0.0296 2.0241 +-0.0291 0.0440 2.0544 +-0.0398 0.0582 2.0847 +-0.0509 0.0722 2.1150 +-0.0625 0.0858 2.1453 +-0.0746 0.0992 2.1756 +-0.0871 0.1123 2.2059 +-0.1000 0.1250 2.2362 +primID: 4 +startangle_c: 5 +endpose_c: -2 7 4 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0078 0.0188 1.9635 +-0.0156 0.0377 1.9635 +-0.0234 0.0565 1.9635 +-0.0312 0.0754 1.9444 +-0.0379 0.0946 1.8697 +-0.0432 0.1143 1.7950 +-0.0470 0.1344 1.7202 +-0.0492 0.1546 1.6455 +-0.0500 0.1750 1.5708 +primID: 0 +startangle_c: 6 +endpose_c: -1 1 6 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0028 0.0028 2.3562 +-0.0056 0.0056 2.3562 +-0.0083 0.0083 2.3562 +-0.0111 0.0111 2.3562 +-0.0139 0.0139 2.3562 +-0.0167 0.0167 2.3562 +-0.0194 0.0194 2.3562 +-0.0222 0.0222 2.3562 +-0.0250 0.0250 2.3562 +primID: 1 +startangle_c: 6 +endpose_c: -6 6 6 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0167 0.0167 2.3562 +-0.0333 0.0333 2.3562 +-0.0500 0.0500 2.3562 +-0.0667 0.0667 2.3562 +-0.0833 0.0833 2.3562 +-0.1000 0.1000 2.3562 +-0.1167 0.1167 2.3562 +-0.1333 0.1333 2.3562 +-0.1500 0.1500 2.3562 +primID: 2 +startangle_c: 6 +endpose_c: 1 -1 6 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0028 -0.0028 2.3562 +0.0056 -0.0056 2.3562 +0.0083 -0.0083 2.3562 +0.0111 -0.0111 2.3562 +0.0139 -0.0139 2.3562 +0.0167 -0.0167 2.3562 +0.0194 -0.0194 2.3562 +0.0222 -0.0222 2.3562 +0.0250 -0.0250 2.3562 +primID: 3 +startangle_c: 6 +endpose_c: -7 5 7 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0170 0.0170 2.3562 +-0.0342 0.0339 2.3859 +-0.0522 0.0500 2.4377 +-0.0709 0.0651 2.4896 +-0.0904 0.0792 2.5415 +-0.1107 0.0923 2.5933 +-0.1315 0.1043 2.6452 +-0.1530 0.1152 2.6970 +-0.1750 0.1250 2.7489 +primID: 4 +startangle_c: 6 +endpose_c: -5 7 5 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0170 0.0170 2.3562 +-0.0339 0.0342 2.3265 +-0.0500 0.0522 2.2747 +-0.0651 0.0709 2.2228 +-0.0792 0.0904 2.1709 +-0.0923 0.1107 2.1191 +-0.1043 0.1315 2.0672 +-0.1152 0.1530 2.0154 +-0.1250 0.1750 1.9635 +primID: 0 +startangle_c: 7 +endpose_c: -2 1 7 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0056 0.0028 2.7489 +-0.0111 0.0056 2.7489 +-0.0167 0.0083 2.7489 +-0.0222 0.0111 2.7489 +-0.0278 0.0139 2.7489 +-0.0333 0.0167 2.7489 +-0.0389 0.0194 2.7489 +-0.0444 0.0222 2.7489 +-0.0500 0.0250 2.7489 +primID: 1 +startangle_c: 7 +endpose_c: -6 3 7 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0167 0.0083 2.7489 +-0.0333 0.0167 2.7489 +-0.0500 0.0250 2.7489 +-0.0667 0.0333 2.7489 +-0.0833 0.0417 2.7489 +-0.1000 0.0500 2.7489 +-0.1167 0.0583 2.7489 +-0.1333 0.0667 2.7489 +-0.1500 0.0750 2.7489 +primID: 2 +startangle_c: 7 +endpose_c: 2 -1 7 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0056 -0.0028 2.7489 +0.0111 -0.0056 2.7489 +0.0167 -0.0083 2.7489 +0.0222 -0.0111 2.7489 +0.0278 -0.0139 2.7489 +0.0333 -0.0167 2.7489 +0.0389 -0.0194 2.7489 +0.0444 -0.0222 2.7489 +0.0500 -0.0250 2.7489 +primID: 3 +startangle_c: 7 +endpose_c: -5 4 6 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0149 0.0092 2.7186 +-0.0296 0.0189 2.6883 +-0.0440 0.0291 2.6580 +-0.0582 0.0398 2.6277 +-0.0722 0.0509 2.5974 +-0.0858 0.0625 2.5671 +-0.0992 0.0746 2.5368 +-0.1123 0.0871 2.5065 +-0.1250 0.1000 2.4762 +primID: 4 +startangle_c: 7 +endpose_c: -7 2 8 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0188 0.0078 2.7489 +-0.0377 0.0156 2.7489 +-0.0565 0.0234 2.7489 +-0.0754 0.0312 2.7680 +-0.0946 0.0379 2.8427 +-0.1143 0.0432 2.9174 +-0.1344 0.0470 2.9921 +-0.1546 0.0492 3.0669 +-0.1750 0.0500 3.1416 +primID: 0 +startangle_c: 8 +endpose_c: -1 0 8 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0028 0.0000 3.1416 +-0.0056 0.0000 3.1416 +-0.0083 0.0000 3.1416 +-0.0111 0.0000 3.1416 +-0.0139 0.0000 3.1416 +-0.0167 0.0000 3.1416 +-0.0194 0.0000 3.1416 +-0.0222 0.0000 3.1416 +-0.0250 0.0000 3.1416 +primID: 1 +startangle_c: 8 +endpose_c: -8 0 8 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0222 0.0000 3.1416 +-0.0444 0.0000 3.1416 +-0.0667 0.0000 3.1416 +-0.0889 0.0000 3.1416 +-0.1111 0.0000 3.1416 +-0.1333 0.0000 3.1416 +-0.1556 0.0000 3.1416 +-0.1778 0.0000 3.1416 +-0.2000 0.0000 3.1416 +primID: 2 +startangle_c: 8 +endpose_c: 1 0 8 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0028 0.0000 3.1416 +0.0056 0.0000 3.1416 +0.0083 0.0000 3.1416 +0.0111 0.0000 3.1416 +0.0139 0.0000 3.1416 +0.0167 0.0000 3.1416 +0.0194 0.0000 3.1416 +0.0222 0.0000 3.1416 +0.0250 0.0000 3.1416 +primID: 3 +startangle_c: 8 +endpose_c: -8 -1 9 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0226 0.0000 3.1416 +-0.0452 0.0000 3.1416 +-0.0678 0.0000 3.1416 +-0.0903 -0.0004 3.1904 +-0.1128 -0.0023 3.2592 +-0.1352 -0.0057 3.3280 +-0.1572 -0.0106 3.3967 +-0.1789 -0.0171 3.4655 +-0.2000 -0.0250 3.5343 +primID: 4 +startangle_c: 8 +endpose_c: -8 1 7 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0226 0.0000 3.1416 +-0.0452 0.0000 3.1416 +-0.0678 0.0000 3.1416 +-0.0903 0.0004 3.0928 +-0.1128 0.0023 3.0240 +-0.1352 0.0057 2.9552 +-0.1572 0.0106 2.8864 +-0.1789 0.0171 2.8177 +-0.2000 0.0250 2.7489 +primID: 0 +startangle_c: 9 +endpose_c: -2 -1 9 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0056 -0.0028 3.5343 +-0.0111 -0.0056 3.5343 +-0.0167 -0.0083 3.5343 +-0.0222 -0.0111 3.5343 +-0.0278 -0.0139 3.5343 +-0.0333 -0.0167 3.5343 +-0.0389 -0.0194 3.5343 +-0.0444 -0.0222 3.5343 +-0.0500 -0.0250 3.5343 +primID: 1 +startangle_c: 9 +endpose_c: -6 -3 9 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0167 -0.0083 3.5343 +-0.0333 -0.0167 3.5343 +-0.0500 -0.0250 3.5343 +-0.0667 -0.0333 3.5343 +-0.0833 -0.0417 3.5343 +-0.1000 -0.0500 3.5343 +-0.1167 -0.0583 3.5343 +-0.1333 -0.0667 3.5343 +-0.1500 -0.0750 3.5343 +primID: 2 +startangle_c: 9 +endpose_c: 2 1 9 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0056 0.0028 3.5343 +0.0111 0.0056 3.5343 +0.0167 0.0083 3.5343 +0.0222 0.0111 3.5343 +0.0278 0.0139 3.5343 +0.0333 0.0167 3.5343 +0.0389 0.0194 3.5343 +0.0444 0.0222 3.5343 +0.0500 0.0250 3.5343 +primID: 3 +startangle_c: 9 +endpose_c: -5 -4 10 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0149 -0.0092 3.5646 +-0.0296 -0.0189 3.5949 +-0.0440 -0.0291 3.6252 +-0.0582 -0.0398 3.6555 +-0.0722 -0.0509 3.6858 +-0.0858 -0.0625 3.7161 +-0.0992 -0.0746 3.7464 +-0.1123 -0.0871 3.7767 +-0.1250 -0.1000 3.8070 +primID: 4 +startangle_c: 9 +endpose_c: -7 -2 8 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0188 -0.0078 3.5343 +-0.0377 -0.0156 3.5343 +-0.0565 -0.0234 3.5343 +-0.0754 -0.0312 3.5152 +-0.0946 -0.0379 3.4405 +-0.1143 -0.0432 3.3658 +-0.1344 -0.0470 3.2910 +-0.1546 -0.0492 3.2163 +-0.1750 -0.0500 3.1416 +primID: 0 +startangle_c: 10 +endpose_c: -1 -1 10 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0028 -0.0028 3.9270 +-0.0056 -0.0056 3.9270 +-0.0083 -0.0083 3.9270 +-0.0111 -0.0111 3.9270 +-0.0139 -0.0139 3.9270 +-0.0167 -0.0167 3.9270 +-0.0194 -0.0194 3.9270 +-0.0222 -0.0222 3.9270 +-0.0250 -0.0250 3.9270 +primID: 1 +startangle_c: 10 +endpose_c: -6 -6 10 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0167 -0.0167 3.9270 +-0.0333 -0.0333 3.9270 +-0.0500 -0.0500 3.9270 +-0.0667 -0.0667 3.9270 +-0.0833 -0.0833 3.9270 +-0.1000 -0.1000 3.9270 +-0.1167 -0.1167 3.9270 +-0.1333 -0.1333 3.9270 +-0.1500 -0.1500 3.9270 +primID: 2 +startangle_c: 10 +endpose_c: 1 1 10 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0028 0.0028 3.9270 +0.0056 0.0056 3.9270 +0.0083 0.0083 3.9270 +0.0111 0.0111 3.9270 +0.0139 0.0139 3.9270 +0.0167 0.0167 3.9270 +0.0194 0.0194 3.9270 +0.0222 0.0222 3.9270 +0.0250 0.0250 3.9270 +primID: 3 +startangle_c: 10 +endpose_c: -5 -7 11 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0170 -0.0170 3.9270 +-0.0339 -0.0342 3.9567 +-0.0500 -0.0522 4.0085 +-0.0651 -0.0709 4.0604 +-0.0792 -0.0904 4.1123 +-0.0923 -0.1107 4.1641 +-0.1043 -0.1315 4.2160 +-0.1152 -0.1530 4.2678 +-0.1250 -0.1750 4.3197 +primID: 4 +startangle_c: 10 +endpose_c: -7 -5 9 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0170 -0.0170 3.9270 +-0.0342 -0.0339 3.8973 +-0.0522 -0.0500 3.8455 +-0.0709 -0.0651 3.7936 +-0.0904 -0.0792 3.7417 +-0.1107 -0.0923 3.6899 +-0.1315 -0.1043 3.6380 +-0.1530 -0.1152 3.5862 +-0.1750 -0.1250 3.5343 +primID: 0 +startangle_c: 11 +endpose_c: -1 -2 11 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0028 -0.0056 4.3197 +-0.0056 -0.0111 4.3197 +-0.0083 -0.0167 4.3197 +-0.0111 -0.0222 4.3197 +-0.0139 -0.0278 4.3197 +-0.0167 -0.0333 4.3197 +-0.0194 -0.0389 4.3197 +-0.0222 -0.0444 4.3197 +-0.0250 -0.0500 4.3197 +primID: 1 +startangle_c: 11 +endpose_c: -3 -6 11 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0083 -0.0167 4.3197 +-0.0167 -0.0333 4.3197 +-0.0250 -0.0500 4.3197 +-0.0333 -0.0667 4.3197 +-0.0417 -0.0833 4.3197 +-0.0500 -0.1000 4.3197 +-0.0583 -0.1167 4.3197 +-0.0667 -0.1333 4.3197 +-0.0750 -0.1500 4.3197 +primID: 2 +startangle_c: 11 +endpose_c: 1 2 11 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0028 0.0056 4.3197 +0.0056 0.0111 4.3197 +0.0083 0.0167 4.3197 +0.0111 0.0222 4.3197 +0.0139 0.0278 4.3197 +0.0167 0.0333 4.3197 +0.0194 0.0389 4.3197 +0.0222 0.0444 4.3197 +0.0250 0.0500 4.3197 +primID: 3 +startangle_c: 11 +endpose_c: -4 -5 10 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0092 -0.0149 4.2894 +-0.0189 -0.0296 4.2591 +-0.0291 -0.0440 4.2288 +-0.0398 -0.0582 4.1985 +-0.0509 -0.0722 4.1682 +-0.0625 -0.0858 4.1379 +-0.0746 -0.0992 4.1076 +-0.0871 -0.1123 4.0773 +-0.1000 -0.1250 4.0470 +primID: 4 +startangle_c: 11 +endpose_c: -2 -7 12 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0078 -0.0188 4.3197 +-0.0156 -0.0377 4.3197 +-0.0234 -0.0565 4.3197 +-0.0312 -0.0754 4.3388 +-0.0379 -0.0946 4.4135 +-0.0432 -0.1143 4.4882 +-0.0470 -0.1344 4.5629 +-0.0492 -0.1546 4.6377 +-0.0500 -0.1750 4.7124 +primID: 0 +startangle_c: 12 +endpose_c: 0 -1 12 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0028 4.7124 +0.0000 -0.0056 4.7124 +0.0000 -0.0083 4.7124 +0.0000 -0.0111 4.7124 +0.0000 -0.0139 4.7124 +0.0000 -0.0167 4.7124 +0.0000 -0.0194 4.7124 +0.0000 -0.0222 4.7124 +0.0000 -0.0250 4.7124 +primID: 1 +startangle_c: 12 +endpose_c: 0 -8 12 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0222 4.7124 +0.0000 -0.0444 4.7124 +0.0000 -0.0667 4.7124 +0.0000 -0.0889 4.7124 +0.0000 -0.1111 4.7124 +0.0000 -0.1333 4.7124 +0.0000 -0.1556 4.7124 +0.0000 -0.1778 4.7124 +0.0000 -0.2000 4.7124 +primID: 2 +startangle_c: 12 +endpose_c: 0 1 12 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0028 4.7124 +0.0000 0.0056 4.7124 +0.0000 0.0083 4.7124 +0.0000 0.0111 4.7124 +0.0000 0.0139 4.7124 +0.0000 0.0167 4.7124 +0.0000 0.0194 4.7124 +0.0000 0.0222 4.7124 +0.0000 0.0250 4.7124 +primID: 3 +startangle_c: 12 +endpose_c: 1 -8 13 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 4.7124 +-0.0000 -0.0226 4.7124 +-0.0000 -0.0452 4.7124 +-0.0000 -0.0678 4.7124 +0.0004 -0.0903 4.7612 +0.0023 -0.1128 4.8300 +0.0057 -0.1352 4.8988 +0.0106 -0.1572 4.9675 +0.0171 -0.1789 5.0363 +0.0250 -0.2000 5.1051 +primID: 4 +startangle_c: 12 +endpose_c: -1 -8 11 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 4.7124 +-0.0000 -0.0226 4.7124 +-0.0000 -0.0452 4.7124 +-0.0000 -0.0678 4.7124 +-0.0004 -0.0903 4.6636 +-0.0023 -0.1128 4.5948 +-0.0057 -0.1352 4.5260 +-0.0106 -0.1572 4.4572 +-0.0171 -0.1789 4.3885 +-0.0250 -0.2000 4.3197 +primID: 0 +startangle_c: 13 +endpose_c: 1 -2 13 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0028 -0.0056 5.1051 +0.0056 -0.0111 5.1051 +0.0083 -0.0167 5.1051 +0.0111 -0.0222 5.1051 +0.0139 -0.0278 5.1051 +0.0167 -0.0333 5.1051 +0.0194 -0.0389 5.1051 +0.0222 -0.0444 5.1051 +0.0250 -0.0500 5.1051 +primID: 1 +startangle_c: 13 +endpose_c: 3 -6 13 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0083 -0.0167 5.1051 +0.0167 -0.0333 5.1051 +0.0250 -0.0500 5.1051 +0.0333 -0.0667 5.1051 +0.0417 -0.0833 5.1051 +0.0500 -0.1000 5.1051 +0.0583 -0.1167 5.1051 +0.0667 -0.1333 5.1051 +0.0750 -0.1500 5.1051 +primID: 2 +startangle_c: 13 +endpose_c: -1 2 13 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 5.1051 +-0.0028 0.0056 5.1051 +-0.0056 0.0111 5.1051 +-0.0083 0.0167 5.1051 +-0.0111 0.0222 5.1051 +-0.0139 0.0278 5.1051 +-0.0167 0.0333 5.1051 +-0.0194 0.0389 5.1051 +-0.0222 0.0444 5.1051 +-0.0250 0.0500 5.1051 +primID: 3 +startangle_c: 13 +endpose_c: 4 -5 14 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0092 -0.0149 5.1354 +0.0189 -0.0296 5.1657 +0.0291 -0.0440 5.1960 +0.0398 -0.0582 5.2263 +0.0509 -0.0722 5.2566 +0.0625 -0.0858 5.2869 +0.0746 -0.0992 5.3172 +0.0871 -0.1123 5.3475 +0.1000 -0.1250 5.3778 +primID: 4 +startangle_c: 13 +endpose_c: 2 -7 12 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0078 -0.0188 5.1051 +0.0156 -0.0377 5.1051 +0.0234 -0.0565 5.1051 +0.0312 -0.0754 5.0860 +0.0379 -0.0946 5.0113 +0.0432 -0.1143 4.9366 +0.0470 -0.1344 4.8618 +0.0492 -0.1546 4.7871 +0.0500 -0.1750 4.7124 +primID: 0 +startangle_c: 14 +endpose_c: 1 -1 14 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0028 -0.0028 5.4978 +0.0056 -0.0056 5.4978 +0.0083 -0.0083 5.4978 +0.0111 -0.0111 5.4978 +0.0139 -0.0139 5.4978 +0.0167 -0.0167 5.4978 +0.0194 -0.0194 5.4978 +0.0222 -0.0222 5.4978 +0.0250 -0.0250 5.4978 +primID: 1 +startangle_c: 14 +endpose_c: 6 -6 14 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0167 -0.0167 5.4978 +0.0333 -0.0333 5.4978 +0.0500 -0.0500 5.4978 +0.0667 -0.0667 5.4978 +0.0833 -0.0833 5.4978 +0.1000 -0.1000 5.4978 +0.1167 -0.1167 5.4978 +0.1333 -0.1333 5.4978 +0.1500 -0.1500 5.4978 +primID: 2 +startangle_c: 14 +endpose_c: -1 1 14 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 5.4978 +-0.0028 0.0028 5.4978 +-0.0056 0.0056 5.4978 +-0.0083 0.0083 5.4978 +-0.0111 0.0111 5.4978 +-0.0139 0.0139 5.4978 +-0.0167 0.0167 5.4978 +-0.0194 0.0194 5.4978 +-0.0222 0.0222 5.4978 +-0.0250 0.0250 5.4978 +primID: 3 +startangle_c: 14 +endpose_c: 7 -5 15 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0170 -0.0170 5.4978 +0.0342 -0.0339 5.5275 +0.0522 -0.0500 5.5793 +0.0709 -0.0651 5.6312 +0.0904 -0.0792 5.6830 +0.1107 -0.0923 5.7349 +0.1315 -0.1043 5.7868 +0.1530 -0.1152 5.8386 +0.1750 -0.1250 5.8905 +primID: 4 +startangle_c: 14 +endpose_c: 5 -7 13 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0170 -0.0170 5.4978 +0.0339 -0.0342 5.4681 +0.0500 -0.0522 5.4162 +0.0651 -0.0709 5.3644 +0.0792 -0.0904 5.3125 +0.0923 -0.1107 5.2607 +0.1043 -0.1315 5.2088 +0.1152 -0.1530 5.1569 +0.1250 -0.1750 5.1051 +primID: 0 +startangle_c: 15 +endpose_c: 2 -1 15 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0056 -0.0028 5.8905 +0.0111 -0.0056 5.8905 +0.0167 -0.0083 5.8905 +0.0222 -0.0111 5.8905 +0.0278 -0.0139 5.8905 +0.0333 -0.0167 5.8905 +0.0389 -0.0194 5.8905 +0.0444 -0.0222 5.8905 +0.0500 -0.0250 5.8905 +primID: 1 +startangle_c: 15 +endpose_c: 6 -3 15 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0167 -0.0083 5.8905 +0.0333 -0.0167 5.8905 +0.0500 -0.0250 5.8905 +0.0667 -0.0333 5.8905 +0.0833 -0.0417 5.8905 +0.1000 -0.0500 5.8905 +0.1167 -0.0583 5.8905 +0.1333 -0.0667 5.8905 +0.1500 -0.0750 5.8905 +primID: 2 +startangle_c: 15 +endpose_c: -2 1 15 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 5.8905 +-0.0056 0.0028 5.8905 +-0.0111 0.0056 5.8905 +-0.0167 0.0083 5.8905 +-0.0222 0.0111 5.8905 +-0.0278 0.0139 5.8905 +-0.0333 0.0167 5.8905 +-0.0389 0.0194 5.8905 +-0.0444 0.0222 5.8905 +-0.0500 0.0250 5.8905 +primID: 3 +startangle_c: 15 +endpose_c: 5 -4 14 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0149 -0.0092 5.8602 +0.0296 -0.0189 5.8299 +0.0440 -0.0291 5.7996 +0.0582 -0.0398 5.7693 +0.0722 -0.0509 5.7390 +0.0858 -0.0625 5.7087 +0.0992 -0.0746 5.6784 +0.1123 -0.0871 5.6481 +0.1250 -0.1000 5.6178 +primID: 4 +startangle_c: 15 +endpose_c: 7 -2 0 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0188 -0.0078 5.8905 +0.0377 -0.0156 5.8905 +0.0565 -0.0234 5.8905 +0.0754 -0.0312 5.9096 +0.0946 -0.0379 5.9843 +0.1143 -0.0432 6.0590 +0.1344 -0.0470 6.1337 +0.1546 -0.0492 6.2085 +0.1750 -0.0500 6.2832 diff --git a/navigations/sbpl/matlab/visualization/plot_3Dpath.m b/navigations/sbpl/matlab/visualization/plot_3Dpath.m new file mode 100755 index 0000000..f06ad52 --- /dev/null +++ b/navigations/sbpl/matlab/visualization/plot_3Dpath.m @@ -0,0 +1,122 @@ +% /* +% * Copyright (c) 2008, Maxim Likhachev +% * All rights reserved. +% * +% * Redistribution and use in source and binary forms, with or without +% * modification, are permitted provided that the following conditions are met: +% * +% * * Redistributions of source code must retain the above copyright +% * notice, this list of conditions and the following disclaimer. +% * * Redistributions in binary form must reproduce the above copyright +% * notice, this list of conditions and the following disclaimer in the +% * documentation and/or other materials provided with the distribution. +% * * Neither the name of the Carnegie Mellon University nor the names of its +% * contributors may be used to endorse or promote products derived from +% * this software without specific prior written permission. +% * +% * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +% * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +% * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +% * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +% * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +% * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +% * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +% * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +% * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +% * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +% * POSSIBILITY OF SUCH DAMAGE. +% */ +function[] = plot_3Dpath(solfilename, mapfilename, resolution) + +% +%Plots a 3D path overlaid on top of the map. +%Resolution should be in meters +% +%written by Maxim Likhachev +%--------------------------------------------------- +% + +%close all; + +obsthresh = 254; + +robot_width = 0.6; +robot_length = 1.5; + +vehicle = [-robot_length/2.0 -robot_width/2.0 + robot_length/2.0 -robot_width/2.0 + robot_length/2.0 robot_width/2.0 + -robot_length/2.0 robot_width/2.0]; + + +cellsize = resolution; +x = load(solfilename); + +%now read in map +fmap = fopen(mapfilename, 'r'); +xsize = -1; +ysize = -1; +while(feof(fmap) ~= 1) + s = fscanf(fmap, '%s', 1); + if (strcmp('environment:',s) == 1) + break; + elseif (strcmp('discretization(cells):', s) == 1) + xsize = fscanf(fmap, '%d', 1); + ysize = fscanf(fmap, '%d', 1); + end; +end; +%read the environment itself +fprintf(1, 'reading in map of size %d by %d\n', xsize, ysize); +map = fscanf(fmap, '%d', [xsize, ysize]); +map = map'; %correct matlab loading order + +figure(3); +%h = plot(x(:,1),x(:,2), 'k'); +%h = plot(x(:,2),size(map,1)*cellsize-x(:,1), 'k'); +h = plot(x(:,1),size(map,1)*cellsize-x(:,2), 'k'); +set(h,'LineWidth',3); +hold on; + +h = text(x(1,1), size(map,1)*cellsize-x(1,2), 'START'); +set(h,'LineWidth',5); +h = text(x(size(x,1),1), size(map,1)*cellsize-x(size(x,1),2), 'GOAL'); +set(h,'LineWidth',5); + +%plot vehicle +%for pind = 1:ceil(length(x)/40):length(x) +for pind = 1:5:length(x) + for i = 1:4 + xstartrot = vehicle(i,1)*cos(x(pind,3)) - vehicle(i,2)*sin(x(pind,3)) + x(pind,1); + ystartrot = vehicle(i,1)*sin(x(pind,3)) + vehicle(i,2)*cos(x(pind,3)) + x(pind,2); + if i < 4 + xendrot = vehicle(i+1,1)*cos(x(pind,3)) - vehicle(i+1,2)*sin(x(pind,3)) + x(pind,1);; + yendrot = vehicle(i+1,1)*sin(x(pind,3)) + vehicle(i+1,2)*cos(x(pind,3)) + x(pind,2);; + else + xendrot = vehicle(1,1)*cos(x(pind,3)) - vehicle(1,2)*sin(x(pind,3)) + x(pind,1);; + yendrot = vehicle(1,1)*sin(x(pind,3)) + vehicle(1,2)*cos(x(pind,3)) + x(pind,2);; + end; +%%% plot([xstartrot xendrot], [ystartrot yendrot]); +%%% plot([ystartrot yendrot], [size(map,1)*cellsize-xstartrot size(map,1)*cellsize-xendrot]); + plot([xstartrot xendrot], [size(map,1)*cellsize-ystartrot size(map,1)*cellsize-yendrot]); + end; +end; + +if 1 +for row = 1:size(map,1) + for col = 1:size(map,2) + if(map(row,col) >= obsthresh) +% plot(col*cellsize,row*cellsize,'x'); + plot(col*cellsize, (size(map,1)-row)*cellsize,'x'); + elseif(map(row,col) > 0) + %plot(col*cellsize, (size(map,1)-row)*cellsize,'.'); + end; + end; +end; +end; + +%%fplot('2',[6 40 0 5]); +%%fplot('18',[6 40 0 5]); +%%plot(6*ones(length([2:18]),1), [2:18]); + +%axis([min(x(:,1))-1 max(x(:,1))+1 min(x(:,2))-1 max(x(:,2))+1]); +%axis([-1 5 -1 5]); diff --git a/navigations/sbpl/sbpl-config-tree-export.cmake.in b/navigations/sbpl/sbpl-config-tree-export.cmake.in new file mode 100755 index 0000000..ec1b2d8 --- /dev/null +++ b/navigations/sbpl/sbpl-config-tree-export.cmake.in @@ -0,0 +1,15 @@ +# - Config file for the sbpl package +# It defines the following variables +# SBPL_INCLUDE_DIRS - include directories for sbpl +# SBPL_LIBRARIES - libraries to link against + +get_filename_component(SBPL_CMAKE_DIR "${CMAKE_CURRENT_LIST_FILE}" PATH) +set(SBPL_INCLUDE_DIRS "@CONF_INCLUDE_DIRS@") + +# Our library dependencies (contains definitions for IMPORTED targets) +if (NOT TARGET sbpl AND NOT sbpl_BINARY_DIR) + include("${SBPL_CMAKE_DIR}/sbpl-targets.cmake") +endif() + +# These are IMPORTED targets created by sbpl-targets.cmake +set(SBPL_LIBRARIES sbpl) diff --git a/navigations/sbpl/sbpl-config-version.cmake.in b/navigations/sbpl/sbpl-config-version.cmake.in new file mode 100755 index 0000000..f1db335 --- /dev/null +++ b/navigations/sbpl/sbpl-config-version.cmake.in @@ -0,0 +1,11 @@ +set(PACKAGE_VERSION "@SBPL_VERSION@") + +# Check whether the requested PACKAGE_FIND_VERSION is compatible +if("${PACKAGE_VERSION}" VERSION_LESS "${PACKAGE_FIND_VERSION}") + set(PACKAGE_VERSION_COMPATIBLE FALSE) +else() + set(PACKAGE_VERSION_COMPATIBLE TRUE) + if ("${PACKAGE_VERSION}" VERSION_EQUAL "${PACKAGE_FIND_VERSION}") + set(PACKAGE_VERSION_EXACT TRUE) + endif() +endif() \ No newline at end of file diff --git a/navigations/sbpl/sbpl-config.cmake.in b/navigations/sbpl/sbpl-config.cmake.in new file mode 100755 index 0000000..69d8fd4 --- /dev/null +++ b/navigations/sbpl/sbpl-config.cmake.in @@ -0,0 +1,30 @@ +# =================================================================================== +# The SBPL CMake configuration file +# +# ** File generated automatically, do not modify ** +# +# Usage from an external project: +# In your CMakeLists.txt, add these lines: +# +# FIND_PACKAGE(sbpl REQUIRED ) +# INCLUDE_DIRECTORIES(${SBPL_INCLUDE_DIRS}) +# TARGET_LINK_LIBRARIES(MY_TARGET_NAME ${SBPL_LIBRARIES}) +# +# This file will define the following variables: +# - SBPL_LIBRARIES : The list of libraries to links against as absolute path +# - SBPL_LIBRARY_DIRS : The directory where lib files are. Calling +# LINK_DIRECTORIES with this path is NOT needed. +# - SBPL_INCLUDE_DIRS : The SBPL include directories. +# +# Based on the example CMake Tutorial +# http://www.vtk.org/Wiki/CMake/Tutorials/How_to_create_a_ProjectConfig.cmake_file +# and OpenCVConfig.cmake.in from OpenCV +# =================================================================================== + + +set(SBPL_INCLUDE_DIRS "@SBPL_INCLUDE_DIR@") +set(SBPL_LIBRARY_DIRS "@SBPL_LIB_DIR@") + + +# Set library names as absolute paths: +set(SBPL_LIBRARIES "@SBPL_LIB_DIR@/libsbpl@CMAKE_SHARED_LIBRARY_SUFFIX@") \ No newline at end of file diff --git a/navigations/sbpl/sbpl.pc.in b/navigations/sbpl/sbpl.pc.in new file mode 100755 index 0000000..87955d6 --- /dev/null +++ b/navigations/sbpl/sbpl.pc.in @@ -0,0 +1,12 @@ +# This file was generated by CMake for @PROJECT_NAME@ +exec_prefix=@CMAKE_INSTALL_PREFIX@ +libdir=@SBPL_LIB_DIR@ +includedir=@SBPL_INCLUDE_DIR@ + +Name: @PKG_NAME@ +Description: @PKG_DESC@ +Version: @SBPL_VERSION@ +Requires: @PKG_EXTERNAL_DEPS@ +Libs: -L${libdir} @PKG_SBPL_LIBS@ +Cflags: -I${includedir} + diff --git a/navigations/sbpl/src/discrete_space_information/environment_XXX.cpp b/navigations/sbpl/src/discrete_space_information/environment_XXX.cpp new file mode 100755 index 0000000..399b182 --- /dev/null +++ b/navigations/sbpl/src/discrete_space_information/environment_XXX.cpp @@ -0,0 +1,429 @@ +/* + * Copyright (c) 2008, Maxim Likhachev + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Carnegie Mellon University nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include + +#include + +#include +#include +#include + +using namespace std; + +//extern clock_t time3_addallout; +//extern clock_t time_gethash; +//extern clock_t time_createhash; + +//function prototypes + +//-------------------problem specific and local functions--------------------- + +static unsigned int inthash(unsigned int key) +{ + key += (key << 12); + key ^= (key >> 22); + key += (key << 4); + key ^= (key >> 9); + key += (key << 10); + key ^= (key >> 2); + key += (key << 7); + key ^= (key >> 12); + return key; +} + +//examples of hash functions: map state coordinates onto a hash value +//#define GETHASHBIN(X, Y) (Y*WIDTH_Y+X) +//here we have state coord: +unsigned int EnvironmentXXX::GETHASHBIN(unsigned int X1, unsigned int X2, unsigned int X3, unsigned int X4) +{ + return inthash((inthash(X1) + (inthash(X2) << 1) + (inthash(X3) << 2) + (inthash(X4) << 3))) & + (EnvXXX.HashTableSize - 1); +} + +void EnvironmentXXX::PrintHashTableHist() +{ + int s0 = 0, s1 = 0, s50 = 0, s100 = 0, s200 = 0, s300 = 0, slarge = 0; + + for (int j = 0; j < (int)EnvXXX.HashTableSize; j++) { + if ((int)EnvXXX.Coord2StateIDHashTable[j].size() == 0) + s0++; + else if ((int)EnvXXX.Coord2StateIDHashTable[j].size() < 50) + s1++; + else if ((int)EnvXXX.Coord2StateIDHashTable[j].size() < 100) + s50++; + else if ((int)EnvXXX.Coord2StateIDHashTable[j].size() < 200) + s100++; + else if ((int)EnvXXX.Coord2StateIDHashTable[j].size() < 300) + s200++; + else if ((int)EnvXXX.Coord2StateIDHashTable[j].size() < 400) + s300++; + else + slarge++; + } + SBPL_PRINTF("hash table histogram: 0:%d, <50:%d, <100:%d, <200:%d, <300:%d, <400:%d >400:%d\n", s0, s1, s50, s100, + s200, s300, slarge); +} + +void EnvironmentXXX::ReadConfiguration(FILE* fCfg) +{ + //read in the configuration of environment and initialize EnvCfg structure +} + +void EnvironmentXXX::InitializeEnvConfig() +{ + //aditional to configuration file initialization of EnvCfg if necessary +} + +EnvXXXHashEntry_t* EnvironmentXXX::GetHashEntry(unsigned int X1, unsigned int X2, unsigned int X3, unsigned int X4) +{ + //clock_t currenttime = clock(); + + int binid = GETHASHBIN(X1, X2, X3, X4); + +#if DEBUG + if ((int)EnvXXX.Coord2StateIDHashTable[binid].size() > 500) + { + SBPL_PRINTF("WARNING: Hash table has a bin %d (X1=%d X2=%d X3=%d X4=%d) of size %d\n", + binid, X1, X2, X3, X4, (int)EnvXXX.Coord2StateIDHashTable[binid].size()); + + PrintHashTableHist(); + } +#endif + + //iterate over the states in the bin and select the perfect match + for (int ind = 0; ind < (int)EnvXXX.Coord2StateIDHashTable[binid].size(); ind++) { + if (EnvXXX.Coord2StateIDHashTable[binid][ind]->X1 == X1 && + EnvXXX.Coord2StateIDHashTable[binid][ind]->X2 == X2 && + EnvXXX.Coord2StateIDHashTable[binid][ind]->X3 == X3 && + EnvXXX.Coord2StateIDHashTable[binid][ind]->X4 == X4) + { + //time_gethash += clock()-currenttime; + return EnvXXX.Coord2StateIDHashTable[binid][ind]; + } + } + + //time_gethash += clock()-currenttime; + + return NULL; +} + +EnvXXXHashEntry_t* EnvironmentXXX::CreateNewHashEntry(unsigned int X1, unsigned int X2, unsigned int X3, + unsigned int X4) +{ + int i; + + //clock_t currenttime = clock(); + + EnvXXXHashEntry_t* HashEntry = new EnvXXXHashEntry_t; + + HashEntry->X1 = X1; + HashEntry->X2 = X2; + HashEntry->X3 = X3; + HashEntry->X4 = X4; + + HashEntry->stateID = EnvXXX.StateID2CoordTable.size(); + + //insert into the tables + EnvXXX.StateID2CoordTable.push_back(HashEntry); + + //get the hash table bin + i = GETHASHBIN(HashEntry->X1, HashEntry->X2, HashEntry->X3, HashEntry->X4); + + //insert the entry into the bin + EnvXXX.Coord2StateIDHashTable[i].push_back(HashEntry); + + //insert into and initialize the mappings + int* entry = new int[NUMOFINDICES_STATEID2IND]; + StateID2IndexMapping.push_back(entry); + for (i = 0; i < NUMOFINDICES_STATEID2IND; i++) { + StateID2IndexMapping[HashEntry->stateID][i] = -1; + } + + if (HashEntry->stateID != (int)StateID2IndexMapping.size() - 1) { + throw SBPL_Exception("ERROR in Env... function: last state has incorrect stateID"); + } + + //time_createhash += clock()-currenttime; + + return HashEntry; +} + +void EnvironmentXXX::CreateStartandGoalStates() +{ + EnvXXXHashEntry_t* HashEntry; + + //create start state + unsigned int X1 = 0; + unsigned int X2 = 0; + unsigned int X3 = 0; + unsigned int X4 = 0; + HashEntry = CreateNewHashEntry(X1, X2, X3, X4); + EnvXXX.startstateid = HashEntry->stateID; + + //create goal state + X1 = X2 = X3 = X4 = 1; + HashEntry = CreateNewHashEntry(X1, X2, X3, X4); + EnvXXX.goalstateid = HashEntry->stateID; +} + +void EnvironmentXXX::InitializeEnvironment() +{ + + //initialize the map from Coord to StateID + EnvXXX.HashTableSize = 32 * 1024; //should be power of two + EnvXXX.Coord2StateIDHashTable = new vector [EnvXXX.HashTableSize]; + + //initialize the map from StateID to Coord + EnvXXX.StateID2CoordTable.clear(); + + //create start and goal states + CreateStartandGoalStates(); +} + +void EnvironmentXXX::AddAllOutcomes(unsigned int SourceX1, unsigned int SourceX2, unsigned int SourceX3, + unsigned int SourceX4, CMDPACTION* action, int cost) +{ + EnvXXXHashEntry_t* OutHashEntry; + int i; + float CumProb = 0.0; + + //iterate over outcomes + for (i = 0; i < 2; i++) { + unsigned int newX1 = SourceX1 + i; + unsigned int newX2 = SourceX2 + i; + unsigned int newX3 = SourceX3 + i; + unsigned int newX4 = SourceX4 + i; + + //add the outcome + if ((OutHashEntry = GetHashEntry(newX1, newX2, newX3, newX4)) == NULL) { + //have to create a new entry + OutHashEntry = CreateNewHashEntry(newX1, newX2, newX3, newX4); + } + float Prob = 0.5; //probability of the outcome + action->AddOutcome(OutHashEntry->stateID, cost, Prob); + CumProb += Prob; + + } //while + + if (CumProb != 1.0) { + std::stringstream ss("ERROR in EnvXXX... function: prob. of all action outcomes="); + ss << CumProb; + throw SBPL_Exception(ss.str()); + } +} + +//------------------------------------------------------------------------------ + +//------------------------------Heuristic computation-------------------------- + +void EnvironmentXXX::ComputeHeuristicValues() +{ + //whatever necessary pre-computation of heuristic values is done here + SBPL_PRINTF("Precomputing heuristics\n"); + + SBPL_PRINTF("done\n"); +} + +//-----------interface with outside functions----------------------------------- + +bool EnvironmentXXX::InitializeEnv(const char* sEnvFile) +{ + FILE* fCfg = fopen(sEnvFile, "r"); + if (fCfg == NULL) { + std::stringstream ss("ERROR: unable to open "); + ss << sEnvFile; + throw SBPL_Exception(ss.str()); + } + ReadConfiguration(fCfg); + fclose(fCfg); + + //Initialize other parameters of the environment + InitializeEnvConfig(); + + //initialize Environment + InitializeEnvironment(); + + //pre-compute heuristics + ComputeHeuristicValues(); + + return true; +} + +bool EnvironmentXXX::InitializeMDPCfg(MDPConfig *MDPCfg) +{ + //initialize MDPCfg with the start and goal ids + MDPCfg->goalstateid = EnvXXX.goalstateid; + MDPCfg->startstateid = EnvXXX.startstateid; + + return true; +} + +int EnvironmentXXX::GetFromToHeuristic(int FromStateID, int ToStateID) +{ +#if USE_HEUR==0 + return 0; +#endif + +#if DEBUG + if(FromStateID >= (int)EnvXXX.StateID2CoordTable.size() || + ToStateID >= (int)EnvXXX.StateID2CoordTable.size()) + { + throw SBPL_Exception("ERROR in EnvXXX... function: stateID illegal"); + } +#endif + + //define this function if it is used in the planner + + throw SBPL_Exception("ERROR in EnvXXX.. function: FromToHeuristic is undefined"); + + return 0; +} + +int EnvironmentXXX::GetGoalHeuristic(int stateID) +{ +#if USE_HEUR==0 + return 0; +#endif + +#if DEBUG + if (stateID >= (int)EnvXXX.StateID2CoordTable.size()) { + throw SBPL_Exception("ERROR in EnvXXX... function: stateID illegal"); + } +#endif + + //define this function if it used in the planner (heuristic forward search would use it) + + throw SBPL_Exception("ERROR in EnvXXX.. function: GetGoalHeuristic is undefined"); +} + +int EnvironmentXXX::GetStartHeuristic(int stateID) +{ +#if USE_HEUR==0 + return 0; +#endif + +#if DEBUG + if (stateID >= (int)EnvXXX.StateID2CoordTable.size()) { + throw SBPL_Exception("ERROR in EnvXXX... function: stateID illegal"); + } +#endif + + //define this function if it used in the planner (heuristic backward search would use it) + + throw SBPL_Exception("ERROR in EnvXXX.. function: GetStartHeuristic is undefined"); + + return 0; +} + +void EnvironmentXXX::SetAllActionsandAllOutcomes(CMDPSTATE* state) +{ + +#if DEBUG + if (state->StateID >= (int)EnvXXX.StateID2CoordTable.size()) { + throw SBPL_Exception("ERROR in EnvXXX... function: stateID illegal"); + } + + if ((int)state->Actions.size() != 0) { + throw SBPL_Exception("ERROR in Env_setAllActionsandAllOutcomes: actions already exist for the state"); + } +#endif + + //if it is goal then no successors + if (state->StateID == EnvXXX.goalstateid) return; + + //get values for the state + EnvXXXHashEntry_t* HashEntry = EnvXXX.StateID2CoordTable[state->StateID]; + + //iterate through the actions for the state + for (int aind = 0; aind < XXX_MAXACTIONSWIDTH; aind++) { + int cost = 1; + + //Add Action + CMDPACTION* action = state->AddAction(aind); + + //clock_t currenttime = clock(); + //add all the outcomes to the action + AddAllOutcomes(HashEntry->X1, HashEntry->X2, HashEntry->X3, HashEntry->X4, action, cost); + + //you can break if the number of actual actions is smaller than the maximum possible + + //time3_addallout += clock()-currenttime; + } +} + +void EnvironmentXXX::SetAllPreds(CMDPSTATE* state) +{ + //implement this if the planner needs access to predecessors + + throw SBPL_Exception("ERROR in EnvXXX... function: SetAllPreds is undefined"); +} + +void EnvironmentXXX::GetSuccs(int SourceStateID, vector* SuccIDV, vector* CostV) +{ + throw SBPL_Exception("ERROR in EnvXXX... function: GetSuccs is undefined"); +} + +void EnvironmentXXX::GetPreds(int TargetStateID, vector* PredIDV, vector* CostV) +{ + throw SBPL_Exception("ERROR in EnvXXX... function: GetPreds is undefined"); +} + +int EnvironmentXXX::SizeofCreatedEnv() +{ + return (int)EnvXXX.StateID2CoordTable.size(); +} + +void EnvironmentXXX::PrintState(int stateID, bool bVerbose, FILE* fOut /*=NULL*/) +{ +#if DEBUG + if(stateID >= (int)EnvXXX.StateID2CoordTable.size()) + { + throw SBPL_Exception("ERROR in EnvXXX... function: stateID illegal (2)"); + } +#endif + + if (fOut == NULL) fOut = stdout; + + EnvXXXHashEntry_t* HashEntry = EnvXXX.StateID2CoordTable[stateID]; + + if (stateID == EnvXXX.goalstateid) { + SBPL_FPRINTF(fOut, "the state is a goal state\n"); + } + + SBPL_FPRINTF(fOut, "X1=%d X2=%d X3=%d X4=%d\n", HashEntry->X1, HashEntry->X2, HashEntry->X3, HashEntry->X4); +} + +void EnvironmentXXX::PrintEnv_Config(FILE* fOut) +{ + //implement this if the planner needs to print out EnvXXX. configuration + throw SBPL_Exception("ERROR in EnvXXX... function: PrintEnv_Config is undefined"); +} + +//------------------------------------------------------------------------------ diff --git a/navigations/sbpl/src/discrete_space_information/environment_nav2D.cpp b/navigations/sbpl/src/discrete_space_information/environment_nav2D.cpp new file mode 100755 index 0000000..2f49af9 --- /dev/null +++ b/navigations/sbpl/src/discrete_space_information/environment_nav2D.cpp @@ -0,0 +1,1288 @@ +/* + * Copyright (c) 2008, Maxim Likhachev + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Carnegie Mellon University nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include +#include +#include +#include + +#include +#include +#include +#include + +using namespace std; + +#if TIME_DEBUG +static clock_t time3_addallout = 0; +static clock_t time_gethash = 0; +static clock_t time_createhash = 0; +static clock_t time_getsuccs = 0; +#endif + +//-------------------constructor-------------------------------------------- +EnvironmentNAV2D::EnvironmentNAV2D() +{ + EnvNAV2DCfg.obsthresh = ENVNAV2D_DEFAULTOBSTHRESH; + + EnvNAV2DCfg.numofdirs = 8; + EnvNAV2D.bInitialized = false; +} + +//-------------------problem specific and local functions--------------------- + +static unsigned int inthash(unsigned int key) +{ + key += (key << 12); + key ^= (key >> 22); + key += (key << 4); + key ^= (key >> 9); + key += (key << 10); + key ^= (key >> 2); + key += (key << 7); + key ^= (key >> 12); + return key; +} + +//examples of hash functions: map state coordinates onto a hash value +//#define GETHASHBIN(X, Y) (Y*WIDTH_Y+X) +//here we have state coord: +unsigned int EnvironmentNAV2D::GETHASHBIN(unsigned int X1, unsigned int X2) +{ + return inthash(inthash(X1) + (inthash(X2) << 1)) & (EnvNAV2D.HashTableSize - 1); +} + +void EnvironmentNAV2D::PrintHashTableHist() +{ + int s0 = 0, s1 = 0, s50 = 0, s100 = 0, s200 = 0, s300 = 0, slarge = 0; + + for (int j = 0; j < EnvNAV2D.HashTableSize; j++) { + if ((int)EnvNAV2D.Coord2StateIDHashTable[j].size() == 0) + s0++; + else if ((int)EnvNAV2D.Coord2StateIDHashTable[j].size() < 50) + s1++; + else if ((int)EnvNAV2D.Coord2StateIDHashTable[j].size() < 100) + s50++; + else if ((int)EnvNAV2D.Coord2StateIDHashTable[j].size() < 200) + s100++; + else if ((int)EnvNAV2D.Coord2StateIDHashTable[j].size() < 300) + s200++; + else if ((int)EnvNAV2D.Coord2StateIDHashTable[j].size() < 400) + s300++; + else + slarge++; + } + SBPL_PRINTF("hash table histogram: 0:%d, <50:%d, <100:%d, <200:%d, <300:%d, <400:%d >400:%d\n", s0, s1, s50, s100, + s200, s300, slarge); +} + +void EnvironmentNAV2D::SetConfiguration(int width, int height, const unsigned char* mapdata, int startx, int starty, + int goalx, int goaly) +{ + EnvNAV2DCfg.EnvWidth_c = width; + EnvNAV2DCfg.EnvHeight_c = height; + EnvNAV2DCfg.StartX_c = startx; + EnvNAV2DCfg.StartY_c = starty; + + if (EnvNAV2DCfg.StartX_c < 0 || EnvNAV2DCfg.StartX_c >= EnvNAV2DCfg.EnvWidth_c) { + throw SBPL_Exception("illegal start coordinates"); + } + if (EnvNAV2DCfg.StartY_c < 0 || EnvNAV2DCfg.StartY_c >= EnvNAV2DCfg.EnvHeight_c) { + throw SBPL_Exception("illegal start coordinates"); + } + + EnvNAV2DCfg.EndX_c = goalx; + EnvNAV2DCfg.EndY_c = goaly; + + //allocate the 2D environment + EnvNAV2DCfg.Grid2D = new unsigned char*[EnvNAV2DCfg.EnvWidth_c]; + for (int x = 0; x < EnvNAV2DCfg.EnvWidth_c; x++) { + EnvNAV2DCfg.Grid2D[x] = new unsigned char[EnvNAV2DCfg.EnvHeight_c]; + } + + //environment: + if (0 == mapdata) { + for (int y = 0; y < EnvNAV2DCfg.EnvHeight_c; y++) { + for (int x = 0; x < EnvNAV2DCfg.EnvWidth_c; x++) { + EnvNAV2DCfg.Grid2D[x][y] = 0; + } + } + } + else { + for (int y = 0; y < EnvNAV2DCfg.EnvHeight_c; y++) { + for (int x = 0; x < EnvNAV2DCfg.EnvWidth_c; x++) { + unsigned char cval = mapdata[x + y * width]; + EnvNAV2DCfg.Grid2D[x][y] = cval; + } + } + } +} + +void EnvironmentNAV2D::ReadConfiguration(FILE* fCfg) +{ + //read in the configuration of environment and initialize EnvNAV2DCfg structure + char sTemp[1024], sTemp1[1024]; + int dTemp; + int x, y; + + //discretization(cells) + if (fscanf(fCfg, "%s", sTemp) != 1) { + throw SBPL_Exception("ran out of env file early"); + } + if (fscanf(fCfg, "%s", sTemp) != 1) { + throw SBPL_Exception("ran out of env file early"); + } + EnvNAV2DCfg.EnvWidth_c = atoi(sTemp); + if (fscanf(fCfg, "%s", sTemp) != 1) { + throw SBPL_Exception("ran out of env file early"); + } + EnvNAV2DCfg.EnvHeight_c = atoi(sTemp); + + //obsthresh: + if (fscanf(fCfg, "%s", sTemp) != 1) { + throw SBPL_Exception("ran out of env file early"); + } + strcpy(sTemp1, "obsthresh:"); + if (strcmp(sTemp1, sTemp) != 0) { + std::stringstream ss("configuration file has incorrect format"); + ss << "Expected " << sTemp1 << " got " << sTemp; + throw SBPL_Exception(ss.str()); + } + if (fscanf(fCfg, "%s", sTemp) != 1) { + throw SBPL_Exception("ran out of env file early"); + } + EnvNAV2DCfg.obsthresh = (int)(atof(sTemp)); + SBPL_PRINTF("obsthresh = %d\n", EnvNAV2DCfg.obsthresh); + + //start(cells): + if (fscanf(fCfg, "%s", sTemp) != 1) { + throw SBPL_Exception("ran out of env file early"); + } + if (fscanf(fCfg, "%s", sTemp) != 1) { + throw SBPL_Exception("ran out of env file early"); + } + EnvNAV2DCfg.StartX_c = atoi(sTemp); + if (fscanf(fCfg, "%s", sTemp) != 1) { + throw SBPL_Exception("ran out of env file early"); + } + EnvNAV2DCfg.StartY_c = atoi(sTemp); + + if (EnvNAV2DCfg.StartX_c < 0 || EnvNAV2DCfg.StartX_c >= EnvNAV2DCfg.EnvWidth_c) { + throw SBPL_Exception("illegal start coordinates"); + } + if (EnvNAV2DCfg.StartY_c < 0 || EnvNAV2DCfg.StartY_c >= EnvNAV2DCfg.EnvHeight_c) { + throw SBPL_Exception("illegal start coordinates"); + } + + //end(cells): + if (fscanf(fCfg, "%s", sTemp) != 1) { + throw SBPL_Exception("ran out of env file early"); + } + if (fscanf(fCfg, "%s", sTemp) != 1) { + throw SBPL_Exception("ran out of env file early"); + } + EnvNAV2DCfg.EndX_c = atoi(sTemp); + if (fscanf(fCfg, "%s", sTemp) != 1) { + throw SBPL_Exception("ran out of env file early"); + } + EnvNAV2DCfg.EndY_c = atoi(sTemp); + + if (EnvNAV2DCfg.EndX_c < 0 || EnvNAV2DCfg.EndX_c >= EnvNAV2DCfg.EnvWidth_c) { + throw SBPL_Exception("illegal end coordinates"); + } + if (EnvNAV2DCfg.EndY_c < 0 || EnvNAV2DCfg.EndY_c >= EnvNAV2DCfg.EnvHeight_c) { + throw SBPL_Exception("illegal end coordinates"); + } + + //allocate the 2D environment + EnvNAV2DCfg.Grid2D = new unsigned char*[EnvNAV2DCfg.EnvWidth_c]; + for (x = 0; x < EnvNAV2DCfg.EnvWidth_c; x++) { + EnvNAV2DCfg.Grid2D[x] = new unsigned char[EnvNAV2DCfg.EnvHeight_c]; + } + + //environment: + if (fscanf(fCfg, "%s", sTemp) != 1) { + throw SBPL_Exception("ran out of env file early"); + } + for (y = 0; y < EnvNAV2DCfg.EnvHeight_c; y++) + for (x = 0; x < EnvNAV2DCfg.EnvWidth_c; x++) { + if (fscanf(fCfg, "%d", &dTemp) != 1) { + throw SBPL_Exception("incorrect format of config file"); + } + EnvNAV2DCfg.Grid2D[x][y] = dTemp; + } + + SBPL_PRINTF("start has cost=%d goal has cost=%d\n", EnvNAV2DCfg.Grid2D[EnvNAV2DCfg.StartX_c][EnvNAV2DCfg.StartY_c], + EnvNAV2DCfg.Grid2D[EnvNAV2DCfg.EndX_c][EnvNAV2DCfg.EndY_c]); +} + +void EnvironmentNAV2D::InitializeEnvConfig() +{ + //aditional to configuration file initialization of EnvNAV2DCfg if necessary + + /* + //actions + EnvNAV2DCfg.dXY[0][0] = -1; + EnvNAV2DCfg.dXY[0][1] = -1; + EnvNAV2DCfg.dXY[1][0] = -1; + EnvNAV2DCfg.dXY[1][1] = 0; + EnvNAV2DCfg.dXY[2][0] = -1; + EnvNAV2DCfg.dXY[2][1] = 1; + EnvNAV2DCfg.dXY[3][0] = 0; + EnvNAV2DCfg.dXY[3][1] = -1; + EnvNAV2DCfg.dXY[4][0] = 0; + EnvNAV2DCfg.dXY[4][1] = 1; + EnvNAV2DCfg.dXY[5][0] = 1; + EnvNAV2DCfg.dXY[5][1] = -1; + EnvNAV2DCfg.dXY[6][0] = 1; + EnvNAV2DCfg.dXY[6][1] = 0; + EnvNAV2DCfg.dXY[7][0] = 1; + EnvNAV2DCfg.dXY[7][1] = 1; + */ + Computedxy(); +} + +void EnvironmentNAV2D::Computedxy() +{ + //initialize some constants for 2D search + EnvNAV2DCfg.dx_[0] = 1; + EnvNAV2DCfg.dy_[0] = 1; + EnvNAV2DCfg.dxintersects_[0][0] = 0; + EnvNAV2DCfg.dyintersects_[0][0] = 1; + EnvNAV2DCfg.dxintersects_[0][1] = 1; + EnvNAV2DCfg.dyintersects_[0][1] = 0; + + EnvNAV2DCfg.dx_[1] = 1; + EnvNAV2DCfg.dy_[1] = 0; + EnvNAV2DCfg.dxintersects_[1][0] = 0; + EnvNAV2DCfg.dyintersects_[1][0] = 0; + EnvNAV2DCfg.dxintersects_[1][1] = 0; + EnvNAV2DCfg.dyintersects_[1][1] = 0; + + EnvNAV2DCfg.dx_[2] = 1; + EnvNAV2DCfg.dy_[2] = -1; + EnvNAV2DCfg.dxintersects_[2][0] = 0; + EnvNAV2DCfg.dyintersects_[2][0] = -1; + EnvNAV2DCfg.dxintersects_[2][1] = 1; + EnvNAV2DCfg.dyintersects_[2][1] = 0; + + EnvNAV2DCfg.dx_[3] = 0; + EnvNAV2DCfg.dy_[3] = 1; + EnvNAV2DCfg.dxintersects_[3][0] = 0; + EnvNAV2DCfg.dyintersects_[3][0] = 0; + EnvNAV2DCfg.dxintersects_[3][1] = 0; + EnvNAV2DCfg.dyintersects_[3][1] = 0; + + EnvNAV2DCfg.dx_[4] = 0; + EnvNAV2DCfg.dy_[4] = -1; + EnvNAV2DCfg.dxintersects_[4][0] = 0; + EnvNAV2DCfg.dyintersects_[4][0] = 0; + EnvNAV2DCfg.dxintersects_[4][1] = 0; + EnvNAV2DCfg.dyintersects_[4][1] = 0; + + EnvNAV2DCfg.dx_[5] = -1; + EnvNAV2DCfg.dy_[5] = 1; + EnvNAV2DCfg.dxintersects_[5][0] = 0; + EnvNAV2DCfg.dyintersects_[5][0] = 1; + EnvNAV2DCfg.dxintersects_[5][1] = -1; + EnvNAV2DCfg.dyintersects_[5][1] = 0; + + EnvNAV2DCfg.dx_[6] = -1; + EnvNAV2DCfg.dy_[6] = 0; + EnvNAV2DCfg.dxintersects_[6][0] = 0; + EnvNAV2DCfg.dyintersects_[6][0] = 0; + EnvNAV2DCfg.dxintersects_[6][1] = 0; + EnvNAV2DCfg.dyintersects_[6][1] = 0; + + EnvNAV2DCfg.dx_[7] = -1; + EnvNAV2DCfg.dy_[7] = -1; + EnvNAV2DCfg.dxintersects_[7][0] = 0; + EnvNAV2DCfg.dyintersects_[7][0] = -1; + EnvNAV2DCfg.dxintersects_[7][1] = -1; + EnvNAV2DCfg.dyintersects_[7][1] = 0; + + //Note: these actions have to be starting at 8 and through 15, since they + //get multiplied correspondingly in Dijkstra's search based on index + EnvNAV2DCfg.dx_[8] = 2; + EnvNAV2DCfg.dy_[8] = 1; + EnvNAV2DCfg.dxintersects_[8][0] = 1; + EnvNAV2DCfg.dyintersects_[8][0] = 0; + EnvNAV2DCfg.dxintersects_[8][1] = 1; + EnvNAV2DCfg.dyintersects_[8][1] = 1; + + EnvNAV2DCfg.dx_[9] = 1; + EnvNAV2DCfg.dy_[9] = 2; + EnvNAV2DCfg.dxintersects_[9][0] = 0; + EnvNAV2DCfg.dyintersects_[9][0] = 1; + EnvNAV2DCfg.dxintersects_[9][1] = 1; + EnvNAV2DCfg.dyintersects_[9][1] = 1; + + EnvNAV2DCfg.dx_[10] = -1; + EnvNAV2DCfg.dy_[10] = 2; + EnvNAV2DCfg.dxintersects_[10][0] = 0; + EnvNAV2DCfg.dyintersects_[10][0] = 1; + EnvNAV2DCfg.dxintersects_[10][1] = -1; + EnvNAV2DCfg.dyintersects_[10][1] = 1; + + EnvNAV2DCfg.dx_[11] = -2; + EnvNAV2DCfg.dy_[11] = 1; + EnvNAV2DCfg.dxintersects_[11][0] = -1; + EnvNAV2DCfg.dyintersects_[11][0] = 0; + EnvNAV2DCfg.dxintersects_[11][1] = -1; + EnvNAV2DCfg.dyintersects_[11][1] = 1; + + EnvNAV2DCfg.dx_[12] = -2; + EnvNAV2DCfg.dy_[12] = -1; + EnvNAV2DCfg.dxintersects_[12][0] = -1; + EnvNAV2DCfg.dyintersects_[12][0] = 0; + EnvNAV2DCfg.dxintersects_[12][1] = -1; + EnvNAV2DCfg.dyintersects_[12][1] = -1; + + EnvNAV2DCfg.dx_[13] = -1; + EnvNAV2DCfg.dy_[13] = -2; + EnvNAV2DCfg.dxintersects_[13][0] = 0; + EnvNAV2DCfg.dyintersects_[13][0] = -1; + EnvNAV2DCfg.dxintersects_[13][1] = -1; + EnvNAV2DCfg.dyintersects_[13][1] = -1; + + EnvNAV2DCfg.dx_[14] = 1; + EnvNAV2DCfg.dy_[14] = -2; + EnvNAV2DCfg.dxintersects_[14][0] = 0; + EnvNAV2DCfg.dyintersects_[14][0] = -1; + EnvNAV2DCfg.dxintersects_[14][1] = 1; + EnvNAV2DCfg.dyintersects_[14][1] = -1; + + EnvNAV2DCfg.dx_[15] = 2; + EnvNAV2DCfg.dy_[15] = -1; + EnvNAV2DCfg.dxintersects_[15][0] = 1; + EnvNAV2DCfg.dyintersects_[15][0] = 0; + EnvNAV2DCfg.dxintersects_[15][1] = 1; + EnvNAV2DCfg.dyintersects_[15][1] = -1; + + //compute distances + for (int dind = 0; dind < ENVNAV2D_MAXDIRS; dind++) { + if (EnvNAV2DCfg.dx_[dind] != 0 && EnvNAV2DCfg.dy_[dind] != 0) { + if (dind <= 7) + //the cost of a diagonal move in millimeters + EnvNAV2DCfg.dxy_distance_mm_[dind] = (int)ceil(ENVNAV2D_COSTMULT * 1.414); + else + //the cost of a move to 1,2 or 2,1 or so on in millimeters + EnvNAV2DCfg.dxy_distance_mm_[dind] = (int)ceil(ENVNAV2D_COSTMULT * 2.236); + } + else + EnvNAV2DCfg.dxy_distance_mm_[dind] = ENVNAV2D_COSTMULT; //the cost of a horizontal move in millimeters + } +} + +EnvNAV2DHashEntry_t* EnvironmentNAV2D::GetHashEntry(int X, int Y) +{ +#if TIME_DEBUG + clock_t currenttime = clock(); +#endif + + int binid = GETHASHBIN(X, Y); + +#if DEBUG + if ((int)EnvNAV2D.Coord2StateIDHashTable[binid].size() > 500) { + SBPL_PRINTF("WARNING: Hash table has a bin %d (X=%d Y=%d) of size %u\n", + binid, X, Y, (unsigned)EnvNAV2D.Coord2StateIDHashTable[binid].size()); + + PrintHashTableHist(); + } +#endif + + //iterate over the states in the bin and select the perfect match + for (int ind = 0; ind < (int)EnvNAV2D.Coord2StateIDHashTable[binid].size(); ind++) { + if (EnvNAV2D.Coord2StateIDHashTable[binid][ind]->X == X && + EnvNAV2D.Coord2StateIDHashTable[binid][ind]->Y == Y) + { +#if TIME_DEBUG + time_gethash += clock()-currenttime; +#endif + return EnvNAV2D.Coord2StateIDHashTable[binid][ind]; + } + } + +#if TIME_DEBUG + time_gethash += clock()-currenttime; +#endif + + return NULL; +} + +EnvNAV2DHashEntry_t* EnvironmentNAV2D::CreateNewHashEntry(int X, int Y) +{ + int i; + +#if TIME_DEBUG + clock_t currenttime = clock(); +#endif + + EnvNAV2DHashEntry_t* HashEntry = new EnvNAV2DHashEntry_t; + + HashEntry->X = X; + HashEntry->Y = Y; + + HashEntry->stateID = EnvNAV2D.StateID2CoordTable.size(); + + //insert into the tables + EnvNAV2D.StateID2CoordTable.push_back(HashEntry); + + //get the hash table bin + i = GETHASHBIN(HashEntry->X, HashEntry->Y); + + //insert the entry into the bin + EnvNAV2D.Coord2StateIDHashTable[i].push_back(HashEntry); + + //insert into and initialize the mappings + int* entry = new int[NUMOFINDICES_STATEID2IND]; + StateID2IndexMapping.push_back(entry); + for (i = 0; i < NUMOFINDICES_STATEID2IND; i++) { + StateID2IndexMapping[HashEntry->stateID][i] = -1; + } + + if (HashEntry->stateID != (int)StateID2IndexMapping.size() - 1) { + throw SBPL_Exception("Env: function: last state has incorrect stateID"); + } + +#if TIME_DEBUG + time_createhash += clock()-currenttime; +#endif + + return HashEntry; +} + +bool EnvironmentNAV2D::IsValidCell(int X, int Y) +{ + return (X >= 0 && X < EnvNAV2DCfg.EnvWidth_c && Y >= 0 && Y < EnvNAV2DCfg.EnvHeight_c && + EnvNAV2DCfg.Grid2D[X][Y] < EnvNAV2DCfg.obsthresh); +} + +bool EnvironmentNAV2D::IsWithinMapCell(int X, int Y) +{ + return (X >= 0 && X < EnvNAV2DCfg.EnvWidth_c && Y >= 0 && Y < EnvNAV2DCfg.EnvHeight_c); +} + +EnvironmentNAV2D::~EnvironmentNAV2D() +{ + if (EnvNAV2D.Coord2StateIDHashTable != NULL) { + delete[] EnvNAV2D.Coord2StateIDHashTable; + } + + for (unsigned int i = 0; i < EnvNAV2D.StateID2CoordTable.size(); ++i) { + if (EnvNAV2D.StateID2CoordTable[i] != NULL) delete EnvNAV2D.StateID2CoordTable[i]; + } + + if (EnvNAV2DCfg.Grid2D != NULL) { + for (int x = 0; x < EnvNAV2DCfg.EnvWidth_c; x++) { + if (EnvNAV2DCfg.Grid2D[x] != NULL) delete[] EnvNAV2DCfg.Grid2D[x]; + } + delete[] EnvNAV2DCfg.Grid2D; + } +} + +void EnvironmentNAV2D::InitializeEnvironment() +{ + EnvNAV2DHashEntry_t* HashEntry; + + //initialize the map from Coord to StateID + EnvNAV2D.HashTableSize = 64 * 1024; //should be power of two + EnvNAV2D.Coord2StateIDHashTable = new vector [EnvNAV2D.HashTableSize]; + + //initialize the map from StateID to Coord + EnvNAV2D.StateID2CoordTable.clear(); + + //create start state + if ((HashEntry = GetHashEntry(EnvNAV2DCfg.StartX_c, EnvNAV2DCfg.StartY_c)) == NULL) { + HashEntry = CreateNewHashEntry(EnvNAV2DCfg.StartX_c, EnvNAV2DCfg.StartY_c); + } + EnvNAV2D.startstateid = HashEntry->stateID; + + //create goal state + if ((HashEntry = GetHashEntry(EnvNAV2DCfg.EndX_c, EnvNAV2DCfg.EndY_c)) == NULL) { + HashEntry = CreateNewHashEntry(EnvNAV2DCfg.EndX_c, EnvNAV2DCfg.EndY_c); + } + EnvNAV2D.goalstateid = HashEntry->stateID; + + EnvNAV2D.bInitialized = true; +} + +static int EuclideanDistance(int X1, int Y1, int X2, int Y2) +{ + int sqdist = ((X1 - X2) * (X1 - X2) + (Y1 - Y2) * (Y1 - Y2)); + double dist = sqrt((double)sqdist); + return (int)(ENVNAV2D_COSTMULT * dist); +} + +//generates nNumofNeighs random neighbors of cell at distance nDist_c (measured in cells) +//it will also generate goal if within this distance as an additional neighbor +//bSuccs is set to true if we are computing successor states, otherwise it is Preds +void EnvironmentNAV2D::GetRandomNeighs(int stateID, std::vector* NeighIDV, std::vector* CLowV, + int nNumofNeighs, int nDist_c, bool bSuccs) +{ + //clear the successor array + NeighIDV->clear(); + CLowV->clear(); + + //get X, Y for the states + EnvNAV2DHashEntry_t* HashEntry = EnvNAV2D.StateID2CoordTable[stateID]; + int X = HashEntry->X; + int Y = HashEntry->Y; + + //iterate through random actions + for (int i = 0, nAttempts = 0; i < nNumofNeighs && nAttempts < 5 * nNumofNeighs; i++, nAttempts++) { + int dX = 0; + int dY = 0; + + //pick a direction + float fDir = (float)(2 * PI_CONST * (((double)rand()) / RAND_MAX)); + + //compute the successor that result from following this direction until + //one of the coordinates reaches the desired distance + //decide whether |dX| = dist or |dY| = dist + float fRadius = 0; + if (fabs(cos(fDir)) > fabs(sin(fDir))) { + fRadius = (float)((nDist_c + 0.5) / fabs(cos(fDir))); + } + else { + fRadius = (float)((nDist_c + 0.5) / fabs(sin(fDir))); + } + + dX = (int)(fRadius * cos(fDir)); + dY = (int)(fRadius * sin(fDir)); + + if ((fabs((float)dX) < nDist_c && fabs((float)dY) < nDist_c) || fabs((float)dX) > nDist_c || + fabs((float)dY) > nDist_c) + { + std::stringstream ss("ERROR in EnvNav2D genneighs function:"); + ss << " dx=" << dX; + ss << " dy=" << dY; + throw SBPL_Exception(ss.str()); + } + + //get the coords of the state + int newX = X + dX; + int newY = Y + dY; + + //skip the invalid cells + if (!IsValidCell(newX, newY)) { + i--; + continue; + } + + //get the state + EnvNAV2DHashEntry_t* OutHashEntry; + if ((OutHashEntry = GetHashEntry(newX, newY)) == NULL) { + //have to create a new entry + OutHashEntry = CreateNewHashEntry(newX, newY); + } + + //compute clow + int clow; + if (bSuccs) + clow = GetFromToHeuristic(stateID, OutHashEntry->stateID); + else + clow = GetFromToHeuristic(OutHashEntry->stateID, stateID); + + //insert it into the list + NeighIDV->push_back(OutHashEntry->stateID); + CLowV->push_back(clow); + } + + //see if the goal/start belongs to the inside area and if yes then add it to Neighs as well + int desX_c = EnvNAV2DCfg.EndX_c; + int desY_c = EnvNAV2DCfg.EndY_c; + int desstateID = EnvNAV2D.goalstateid; + if (bSuccs == false) { + desX_c = EnvNAV2DCfg.StartX_c; + desY_c = EnvNAV2DCfg.StartY_c; + desstateID = EnvNAV2D.startstateid; + } + //add it if within the distance + if (abs(desX_c - X) <= nDist_c && abs(desY_c - Y) <= nDist_c) { + //compute clow + int clow; + if (bSuccs) + clow = GetFromToHeuristic(stateID, desstateID); + else + clow = GetFromToHeuristic(desstateID, stateID); + + NeighIDV->push_back(desstateID); + CLowV->push_back(clow); + } +} + +//------------------------------------------------------------------------------ + +//------------------------------Heuristic computation-------------------------- + +void EnvironmentNAV2D::ComputeHeuristicValues() +{ + //whatever necessary pre-computation of heuristic values is done here + SBPL_PRINTF("Precomputing heuristics...\n"); + + SBPL_PRINTF("done\n"); +} + +//-----------interface with outside functions----------------------------------- + +bool EnvironmentNAV2D::InitializeEnv(const char* sEnvFile) +{ + FILE* fCfg = fopen(sEnvFile, "r"); + if (fCfg == NULL) { + SBPL_ERROR("ERROR: unable to open %s\n", sEnvFile); + std::stringstream ss("ERROR: unable to open "); ss << sEnvFile; + throw SBPL_Exception(ss.str()); + } + ReadConfiguration(fCfg); + fclose(fCfg); + + InitGeneral(); + + return true; +} + +bool EnvironmentNAV2D::InitializeEnv(int width, int height, const unsigned char* mapdata, unsigned char obsthresh) +{ + return InitializeEnv(width, height, mapdata, 0, 0, 0, 0, // just use (0,0) for start and goal + obsthresh); +} + +bool EnvironmentNAV2D::InitializeEnv(int width, int height, const unsigned char* mapdata, int startx, int starty, + int goalx, int goaly, unsigned char obsthresh) +{ + SBPL_PRINTF("env: initialized with width=%d height=%d, start=%d %d, goal=%d %d, obsthresh=%d\n", width, height, + startx, starty, goalx, goaly, obsthresh); + + EnvNAV2DCfg.obsthresh = obsthresh; + + SetConfiguration(width, height, mapdata, startx, starty, goalx, goaly); + + InitGeneral(); + + return true; +} + +bool EnvironmentNAV2D::InitGeneral() +{ + //Initialize other parameters of the environment + InitializeEnvConfig(); + + //initialize Environment + InitializeEnvironment(); + + //pre-compute heuristics + ComputeHeuristicValues(); + + return true; +} + +bool EnvironmentNAV2D::InitializeMDPCfg(MDPConfig *MDPCfg) +{ + //initialize MDPCfg with the start and goal ids + MDPCfg->goalstateid = EnvNAV2D.goalstateid; + MDPCfg->startstateid = EnvNAV2D.startstateid; + + return true; +} + +int EnvironmentNAV2D::GetFromToHeuristic(int FromStateID, int ToStateID) +{ +#if USE_HEUR==0 + return 0; +#endif + +#if DEBUG + if (FromStateID >= (int)EnvNAV2D.StateID2CoordTable.size() || + ToStateID >= (int)EnvNAV2D.StateID2CoordTable.size()) + { + throw SBPL_Exception("EnvNAV2D... function: stateID illegal"); + } +#endif + + //get X, Y for the state + EnvNAV2DHashEntry_t* FromHashEntry = EnvNAV2D.StateID2CoordTable[FromStateID]; + EnvNAV2DHashEntry_t* ToHashEntry = EnvNAV2D.StateID2CoordTable[ToStateID]; + + return EuclideanDistance(FromHashEntry->X, FromHashEntry->Y, ToHashEntry->X, ToHashEntry->Y); +} + +int EnvironmentNAV2D::GetGoalHeuristic(int stateID) +{ +#if USE_HEUR==0 + return 0; +#endif + +#if DEBUG + if (stateID >= (int)EnvNAV2D.StateID2CoordTable.size()) { + throw SBPL_Exception("EnvNAV2D... function: stateID illegal"); + } +#endif + + //define this function if it used in the planner (heuristic forward search would use it) + return GetFromToHeuristic(stateID, EnvNAV2D.goalstateid); +} + +int EnvironmentNAV2D::GetStartHeuristic(int stateID) +{ +#if USE_HEUR==0 + return 0; +#endif + +#if DEBUG + if (stateID >= (int)EnvNAV2D.StateID2CoordTable.size()) { + throw SBPL_Exception("EnvNAV2D... function: stateID illegal"); + } +#endif + + //define this function if it used in the planner (heuristic backward search would use it) + return GetFromToHeuristic(EnvNAV2D.startstateid, stateID); +} + +void EnvironmentNAV2D::SetAllActionsandAllOutcomes(CMDPSTATE* state) +{ + int cost; + +#if DEBUG + if (state->StateID >= (int)EnvNAV2D.StateID2CoordTable.size()) { + SBPL_ERROR("ERROR in Env... function: stateID illegal\n"); + throw SBPL_Exception("Env: function: stateID illegal"); + } + + if ((int)state->Actions.size() != 0) { + throw SBPL_Exception("Env setAllActionsandAllOutcomes: actions already exist for the state"); + } +#endif + + //goal state should be absorbing + if (state->StateID == EnvNAV2D.goalstateid) return; + + //get X, Y for the state + EnvNAV2DHashEntry_t* HashEntry = EnvNAV2D.StateID2CoordTable[state->StateID]; + + //iterate through actions + bool bTestBounds = false; + if (HashEntry->X <= 1 || HashEntry->X >= EnvNAV2DCfg.EnvWidth_c - 2 || HashEntry->Y <= 1 || + HashEntry->Y >= EnvNAV2DCfg.EnvHeight_c - 2) + { + bTestBounds = true; + } + for (int aind = 0; aind < EnvNAV2DCfg.numofdirs; aind++) { + int newX = HashEntry->X + EnvNAV2DCfg.dx_[aind]; + int newY = HashEntry->Y + EnvNAV2DCfg.dy_[aind]; + + //skip the invalid cells + if (bTestBounds) { + if (!IsValidCell(newX, newY)) continue; + } + + //compute cost multiplier + int costmult = EnvNAV2DCfg.Grid2D[newX][newY]; + //for diagonal move, take max over adjacent cells + if (newX != HashEntry->X && newY != HashEntry->Y && aind <= 7) { + //check two more cells through which the action goes + costmult = __max(costmult, EnvNAV2DCfg.Grid2D[HashEntry->X][newY]); + costmult = __max(costmult, EnvNAV2DCfg.Grid2D[newX][HashEntry->Y]); + } + else if (aind > 7) { + //check two more cells through which the action goes + costmult = __max(costmult, + EnvNAV2DCfg.Grid2D[HashEntry->X + EnvNAV2DCfg.dxintersects_[aind][0]][HashEntry->Y + + EnvNAV2DCfg.dyintersects_[aind][0]]); + costmult = __max(costmult, + EnvNAV2DCfg.Grid2D[HashEntry->X + EnvNAV2DCfg.dxintersects_[aind][1]][HashEntry->Y + + EnvNAV2DCfg.dyintersects_[aind][1]]); + } + + //check that it is valid + if (costmult >= EnvNAV2DCfg.obsthresh) continue; + + //otherwise compute the actual cost + cost = (costmult + 1) * EnvNAV2DCfg.dxy_distance_mm_[aind]; + + //add the action + CMDPACTION* action = state->AddAction(aind); + +#if TIME_DEBUG + clock_t currenttime = clock(); +#endif + + EnvNAV2DHashEntry_t* OutHashEntry; + if ((OutHashEntry = GetHashEntry(newX, newY)) == NULL) { + //have to create a new entry + OutHashEntry = CreateNewHashEntry(newX, newY); + } + action->AddOutcome(OutHashEntry->stateID, cost, 1.0); + +#if TIME_DEBUG + time3_addallout += clock()-currenttime; +#endif + } +} + +void EnvironmentNAV2D::SetAllPreds(CMDPSTATE* state) +{ + //implement this if the planner needs access to predecessors + throw SBPL_Exception("EnvNAV2D: function: SetAllPreds is undefined"); +} + +void EnvironmentNAV2D::GetSuccs(int SourceStateID, vector* SuccIDV, vector* CostV) +{ + int aind; + +#if TIME_DEBUG + clock_t currenttime = clock(); +#endif + + //clear the successor array + SuccIDV->clear(); + CostV->clear(); + SuccIDV->reserve(EnvNAV2DCfg.numofdirs); + CostV->reserve(EnvNAV2DCfg.numofdirs); + + //goal state should be absorbing + if (SourceStateID == EnvNAV2D.goalstateid) return; + + //get X, Y for the state + EnvNAV2DHashEntry_t* HashEntry = EnvNAV2D.StateID2CoordTable[SourceStateID]; + + //iterate through actions + bool bTestBounds = false; + if (HashEntry->X <= 1 || HashEntry->X >= EnvNAV2DCfg.EnvWidth_c - 2 || HashEntry->Y <= 1 || + HashEntry->Y >= EnvNAV2DCfg.EnvHeight_c - 2) + { + bTestBounds = true; + } + for (aind = 0; aind < EnvNAV2DCfg.numofdirs; aind++) { + int newX = HashEntry->X + EnvNAV2DCfg.dx_[aind]; + int newY = HashEntry->Y + EnvNAV2DCfg.dy_[aind]; + + //skip the invalid cells + if (bTestBounds) { + if (!IsValidCell(newX, newY)) continue; + } + + int costmult = EnvNAV2DCfg.Grid2D[newX][newY]; + + //for diagonal move, take max over adjacent cells + if (newX != HashEntry->X && newY != HashEntry->Y && aind <= 7) { + costmult = __max(costmult, EnvNAV2DCfg.Grid2D[HashEntry->X][newY]); + costmult = __max(costmult, EnvNAV2DCfg.Grid2D[newX][HashEntry->Y]); + } + else if (aind > 7) { + //check two more cells through which the action goes + costmult = __max(costmult, + EnvNAV2DCfg.Grid2D[HashEntry->X + EnvNAV2DCfg.dxintersects_[aind][0]][HashEntry->Y + + EnvNAV2DCfg.dyintersects_[aind][0]]); + costmult = __max(costmult, + EnvNAV2DCfg.Grid2D[HashEntry->X + EnvNAV2DCfg.dxintersects_[aind][1]][HashEntry->Y + + EnvNAV2DCfg.dyintersects_[aind][1]]); + } + + //check that it is valid + if (costmult >= EnvNAV2DCfg.obsthresh) continue; + + //otherwise compute the actual cost + int cost = (costmult + 1) * EnvNAV2DCfg.dxy_distance_mm_[aind]; + + EnvNAV2DHashEntry_t* OutHashEntry; + if ((OutHashEntry = GetHashEntry(newX, newY)) == NULL) { + //have to create a new entry + OutHashEntry = CreateNewHashEntry(newX, newY); + } + + SuccIDV->push_back(OutHashEntry->stateID); + CostV->push_back(cost); + } + +#if TIME_DEBUG + time_getsuccs += clock()-currenttime; +#endif +} + +void EnvironmentNAV2D::GetPreds(int TargetStateID, vector* PredIDV, vector* CostV) +{ + int aind; + +#if TIME_DEBUG + clock_t currenttime = clock(); +#endif + + //clear the successor array + PredIDV->clear(); + CostV->clear(); + PredIDV->reserve(EnvNAV2DCfg.numofdirs); + CostV->reserve(EnvNAV2DCfg.numofdirs); + + //get X, Y for the state + EnvNAV2DHashEntry_t* HashEntry = EnvNAV2D.StateID2CoordTable[TargetStateID]; + + //no predecessors if obstacle + if (EnvNAV2DCfg.Grid2D[HashEntry->X][HashEntry->Y] >= EnvNAV2DCfg.obsthresh) return; + + int targetcostmult = EnvNAV2DCfg.Grid2D[HashEntry->X][HashEntry->Y]; + + //iterate through actions + bool bTestBounds = false; + if (HashEntry->X <= 1 || HashEntry->X >= EnvNAV2DCfg.EnvWidth_c - 2 || HashEntry->Y <= 1 || + HashEntry->Y >= EnvNAV2DCfg.EnvHeight_c - 2) + { + bTestBounds = true; + } + for (aind = 0; aind < EnvNAV2DCfg.numofdirs; aind++) { + // the actions are undirected, so we can use the same array of actions as in getsuccs case + int predX = HashEntry->X + EnvNAV2DCfg.dx_[aind]; + int predY = HashEntry->Y + EnvNAV2DCfg.dy_[aind]; + + // skip the invalid cells + if (bTestBounds) { + if (!IsValidCell(predX, predY)) continue; + } + + // compute costmult + int costmult = targetcostmult; + // for diagonal move, take max over adjacent cells + if (predX != HashEntry->X && predY != HashEntry->Y && aind <= 7) { + costmult = __max(costmult, EnvNAV2DCfg.Grid2D[HashEntry->X][predY]); + costmult = __max(costmult, EnvNAV2DCfg.Grid2D[predX][HashEntry->Y]); + } + else if (aind > 7) { + // check two more cells through which the action goes since actions + // are undirected, we don't have to figure out what are the + // intersecting cells on moving from to . it is + // the same cells as moving from to , which is + // action aind + costmult = __max(costmult, + EnvNAV2DCfg.Grid2D[HashEntry->X + EnvNAV2DCfg.dxintersects_[aind][0]][HashEntry->Y + + EnvNAV2DCfg.dyintersects_[aind][0]]); + costmult = __max(costmult, + EnvNAV2DCfg.Grid2D[HashEntry->X + EnvNAV2DCfg.dxintersects_[aind][1]][HashEntry->Y + + EnvNAV2DCfg.dyintersects_[aind][1]]); + } + + // check that it is valid + if (costmult >= EnvNAV2DCfg.obsthresh) continue; + + // otherwise compute the actual cost (once again we use the fact that + // actions are undirected to determine the cost) + int cost = (costmult + 1) * EnvNAV2DCfg.dxy_distance_mm_[aind]; + + EnvNAV2DHashEntry_t* OutHashEntry; + if ((OutHashEntry = GetHashEntry(predX, predY)) == NULL) { + // have to create a new entry + OutHashEntry = CreateNewHashEntry(predX, predY); + } + + PredIDV->push_back(OutHashEntry->stateID); + CostV->push_back(cost); + } + +#if TIME_DEBUG + time_getsuccs += clock()-currenttime; +#endif +} + +int EnvironmentNAV2D::SizeofCreatedEnv() +{ + return (int)EnvNAV2D.StateID2CoordTable.size(); +} + +void EnvironmentNAV2D::PrintState(int stateID, bool bVerbose, FILE* fOut /*=NULL*/) +{ +#if DEBUG + if (stateID >= (int)EnvNAV2D.StateID2CoordTable.size()) { + throw SBPL_Exception("ERROR in EnvNAV2D... function: stateID illegal (2)"); + } +#endif + + if (fOut == NULL) fOut = stdout; + + EnvNAV2DHashEntry_t* HashEntry = EnvNAV2D.StateID2CoordTable[stateID]; + + if (stateID == EnvNAV2D.goalstateid && bVerbose) { + SBPL_FPRINTF(fOut, "the state is a goal state\n"); + } + + if (bVerbose) + SBPL_FPRINTF(fOut, "X=%d Y=%d\n", HashEntry->X, HashEntry->Y); + else + SBPL_FPRINTF(fOut, "%d %d\n", HashEntry->X, HashEntry->Y); +} + +void EnvironmentNAV2D::GetCoordFromState(int stateID, int& x, int& y) const +{ + EnvNAV2DHashEntry_t* HashEntry = EnvNAV2D.StateID2CoordTable[stateID]; + x = HashEntry->X; + y = HashEntry->Y; +} + +int EnvironmentNAV2D::GetStateFromCoord(int x, int y) +{ + EnvNAV2DHashEntry_t* OutHashEntry; + if ((OutHashEntry = GetHashEntry(x, y)) == NULL) { + //have to create a new entry + OutHashEntry = CreateNewHashEntry(x, y); + } + return OutHashEntry->stateID; +} + +const EnvNAV2DConfig_t* EnvironmentNAV2D::GetEnvNavConfig() +{ + return &EnvNAV2DCfg; +} + +//returns the stateid if success, and -1 otherwise +int EnvironmentNAV2D::SetGoal(int x, int y) +{ + if (!IsWithinMapCell(x, y)) { + SBPL_ERROR("ERROR: trying to set a goal cell %d %d that is outside of map\n", x, y); + return -1; + } + + if (!IsValidCell(x, y)) { + SBPL_PRINTF("WARNING: goal cell is invalid\n"); + } + + EnvNAV2DHashEntry_t* OutHashEntry; + if ((OutHashEntry = GetHashEntry(x, y)) == NULL) { + //have to create a new entry + OutHashEntry = CreateNewHashEntry(x, y); + } + EnvNAV2D.goalstateid = OutHashEntry->stateID; + EnvNAV2DCfg.EndX_c = x; + EnvNAV2DCfg.EndY_c = y; + + return EnvNAV2D.goalstateid; +} + +void EnvironmentNAV2D::SetGoalTolerance(double tol_x, double tol_y, double tol_theta) +{ + // not used yet +} + +//returns the stateid if success, and -1 otherwise +int EnvironmentNAV2D::SetStart(int x, int y) +{ + if (!IsWithinMapCell(x, y)) { + SBPL_ERROR("ERROR: trying to set a start cell %d %d that is outside of map\n", x, y); + return -1; + } + + if (!IsValidCell(x, y)) { + SBPL_PRINTF("WARNING: start cell is invalid\n"); + } + + EnvNAV2DHashEntry_t* OutHashEntry; + if ((OutHashEntry = GetHashEntry(x, y)) == NULL) { + //have to create a new entry + OutHashEntry = CreateNewHashEntry(x, y); + } + EnvNAV2D.startstateid = OutHashEntry->stateID; + EnvNAV2DCfg.StartX_c = x; + EnvNAV2DCfg.StartY_c = y; + + return EnvNAV2D.startstateid; +} + +bool EnvironmentNAV2D::UpdateCost(int x, int y, unsigned char newcost) +{ + EnvNAV2DCfg.Grid2D[x][y] = newcost; + + return true; +} + +void EnvironmentNAV2D::PrintEnv_Config(FILE* fOut) +{ + //implement this if the planner needs to print out EnvNAV2D. configuration + + throw SBPL_Exception("ERROR in EnvNAV2D... function: PrintEnv_Config is undefined"); +} + +void EnvironmentNAV2D::PrintTimeStat(FILE* fOut) +{ +#if TIME_DEBUG + SBPL_FPRINTF(fOut, + "time3_addallout = %f secs, time_gethash = %f secs, time_createhash = %f secs, time_getsuccs = %f\n", + time3_addallout/(double)CLOCKS_PER_SEC, time_gethash/(double)CLOCKS_PER_SEC, + time_createhash/(double)CLOCKS_PER_SEC, time_getsuccs/(double)CLOCKS_PER_SEC); +#endif +} + +void EnvironmentNAV2D::GetPredsofChangedEdges(vector const * changedcellsV, + vector *preds_of_changededgesIDV) +{ + nav2dcell_t cell; + int aind; + + for (int i = 0; i < (int)changedcellsV->size(); i++) { + cell = changedcellsV->at(i); + preds_of_changededgesIDV->push_back(GetStateFromCoord(cell.x, cell.y)); + + for (aind = 0; aind < EnvNAV2DCfg.numofdirs; aind++) { + //the actions are undirected, so we can use the same array of actions as in getsuccs case + int affx = cell.x + EnvNAV2DCfg.dx_[aind]; + int affy = cell.y + EnvNAV2DCfg.dy_[aind]; + if (affx < 0 || affx >= EnvNAV2DCfg.EnvWidth_c || affy < 0 || affy >= EnvNAV2DCfg.EnvHeight_c) continue; + preds_of_changededgesIDV->push_back(GetStateFromCoord(affx, affy)); + } + } +} + +// identical to GetPredsofChangedEdges except for changing "preds" +// into "succs"... can probably have just one method. +void EnvironmentNAV2D::GetSuccsofChangedEdges(vector const * changedcellsV, + vector *succs_of_changededgesIDV) +{ + nav2dcell_t cell; + int aind; + + for (int i = 0; i < (int)changedcellsV->size(); i++) { + cell = changedcellsV->at(i); + succs_of_changededgesIDV->push_back(GetStateFromCoord(cell.x, cell.y)); + for (aind = 0; aind < EnvNAV2DCfg.numofdirs; aind++) { + int affx = cell.x + EnvNAV2DCfg.dx_[aind]; + int affy = cell.y + EnvNAV2DCfg.dy_[aind]; + if (affx < 0 || affx >= EnvNAV2DCfg.EnvWidth_c || affy < 0 || affy >= EnvNAV2DCfg.EnvHeight_c) continue; + succs_of_changededgesIDV->push_back(GetStateFromCoord(affx, affy)); + } + } +} + +bool EnvironmentNAV2D::IsObstacle(int x, int y) +{ + return (EnvNAV2DCfg.Grid2D[x][y] >= EnvNAV2DCfg.obsthresh); +} + +unsigned char EnvironmentNAV2D::GetMapCost(int x, int y) +{ + return EnvNAV2DCfg.Grid2D[x][y]; +} + +void EnvironmentNAV2D::GetEnvParms(int *size_x, int *size_y, int* startx, int* starty, int* goalx, int* goaly, + unsigned char* obsthresh) +{ + *size_x = EnvNAV2DCfg.EnvWidth_c; + *size_y = EnvNAV2DCfg.EnvHeight_c; + + *startx = EnvNAV2DCfg.StartX_c; + *starty = EnvNAV2DCfg.StartY_c; + *goalx = EnvNAV2DCfg.EndX_c; + *goaly = EnvNAV2DCfg.EndY_c; + + *obsthresh = EnvNAV2DCfg.obsthresh; +} + +bool EnvironmentNAV2D::SetEnvParameter(const char* parameter, int value) +{ + if (EnvNAV2D.bInitialized == true) { + SBPL_ERROR("ERROR: all parameters must be set before initialization of the environment\n"); + return false; + } + + SBPL_PRINTF("setting parameter %s to %d\n", parameter, value); + + if (strcmp(parameter, "is16connected") == 0) { + if (value != 0) + EnvNAV2DCfg.numofdirs = 16; + else + EnvNAV2DCfg.numofdirs = 8; + } + else { + SBPL_ERROR("ERROR: invalid parameter %s\n", parameter); + return false; + } + + return true; +} + +//returns true if two states meet the same condition - see environment.h for more info +bool EnvironmentNAV2D::AreEquivalent(int StateID1, int StateID2) +{ +#if DEBUG + if (StateID1 >= (int)EnvNAV2D.StateID2CoordTable.size() || StateID2 >= (int)EnvNAV2D.StateID2CoordTable.size()) { + throw SBPL_Exception("ERROR in EnvNAV2D... function: stateID illegal (2)"); + } +#endif + + //get X, Y for the states + EnvNAV2DHashEntry_t* HashEntry1 = EnvNAV2D.StateID2CoordTable[StateID1]; + EnvNAV2DHashEntry_t* HashEntry2 = EnvNAV2D.StateID2CoordTable[StateID2]; + + if (HashEntry1->X == HashEntry2->X && HashEntry1->Y == HashEntry2->Y) return true; + + return false; +} + +//generate succs at some domain-dependent distance - see environment.h for more info +void EnvironmentNAV2D::GetRandomSuccsatDistance(int SourceStateID, std::vector* SuccIDV, std::vector* CLowV) +{ + //number of random neighbors + int nNumofNeighs = 10; + //distance at which the neighbors are generated + int nDist_c = 100; + +#if DEBUG + if (SourceStateID >= (int)EnvNAV2D.StateID2CoordTable.size()) { + throw SBPL_Exception("ERROR in EnvNAV2DGetRandSuccs... function: stateID illegal"); + } +#endif + + //goal state should be absorbing + if (SourceStateID == EnvNAV2D.goalstateid) return; + + //get the successors + bool bSuccs = true; + GetRandomNeighs(SourceStateID, SuccIDV, CLowV, nNumofNeighs, nDist_c, bSuccs); +} + +//generate preds at some domain-dependent distance - see environment.h for more info +void EnvironmentNAV2D::GetRandomPredsatDistance(int TargetStateID, std::vector* PredIDV, std::vector* CLowV) +{ + //number of random neighbors + int nNumofNeighs = 10; + //distance at which the neighbors are generated + int nDist_c = 5; //TODO-was100; + +#if DEBUG + if (TargetStateID >= (int)EnvNAV2D.StateID2CoordTable.size()) { + throw SBPL_Exception("ERROR in EnvNAV2DGetRandSuccs... function: stateID illegal"); + } +#endif + + //start state does not have start state + if (TargetStateID == EnvNAV2D.startstateid) + return; + + //get the predecessors + bool bSuccs = false; + GetRandomNeighs(TargetStateID, PredIDV, CLowV, nNumofNeighs, nDist_c, bSuccs); +} + +//------------------------------------------------------------------------------ diff --git a/navigations/sbpl/src/discrete_space_information/environment_nav2Duu.cpp b/navigations/sbpl/src/discrete_space_information/environment_nav2Duu.cpp new file mode 100755 index 0000000..cd09c04 --- /dev/null +++ b/navigations/sbpl/src/discrete_space_information/environment_nav2Duu.cpp @@ -0,0 +1,710 @@ +/* + * Copyright (c) 2009, Maxim Likhachev + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Carnegie Mellon University nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include +#include + +#include +#include +#include + +using namespace std; + +//extern clock_t time3_addallout; +//extern clock_t time_gethash; +//extern clock_t time_createhash; + +#define NAV2DUU_ERR_EPS 0.00001 + +//function prototypes + +//-------------------constructors--------------------- +EnvironmentNAV2DUU::EnvironmentNAV2DUU() +{ + EnvNAV2DUU.bInitialized = false; +} + +//----------------------------------------------------- + +//-------------------problem specific and local functions--------------------- + +void EnvironmentNAV2DUU::ReadConfiguration(FILE* fCfg) +{ + //read in the configuration of environment and initialize EnvCfg structure + char sTemp[1024], sTemp1[1024]; + //int dTemp; + int x, y; + float fTemp; + + //discretization(cells) + if (fscanf(fCfg, "%s", sTemp) != 1) { + throw SBPL_Exception("ERROR: ran out of env file early"); + } + strcpy(sTemp1, "discretization(cells):"); + if (strcmp(sTemp1, sTemp) != 0) { + std::stringstream ss("ERROR: configuration file has incorrect format. Expected "); + ss << sTemp1 << " got " << sTemp; + throw SBPL_Exception(ss.str()); + } + if (fscanf(fCfg, "%s", sTemp) != 1) { + throw SBPL_Exception("ERROR: ran out of env file early"); + } + EnvNAV2DUUCfg.EnvWidth_c = atoi(sTemp); + if (fscanf(fCfg, "%s", sTemp) != 1) { + throw SBPL_Exception("ERROR: ran out of env file early"); + } + EnvNAV2DUUCfg.EnvHeight_c = atoi(sTemp); + + //obsthresh: + if (fscanf(fCfg, "%s", sTemp) != 1) { + throw SBPL_Exception("ERROR: ran out of env file early"); + } + strcpy(sTemp1, "obsthresh:"); + if (strcmp(sTemp1, sTemp) != 0) { + std::stringstream ss("ERROR: configuration file has incorrect format. Expected "); + ss << sTemp1 << " got " << sTemp; + throw SBPL_Exception(ss.str()); + } + if (fscanf(fCfg, "%s", sTemp) != 1) { + throw SBPL_Exception("ERROR: ran out of env file early"); + } + EnvNAV2DUUCfg.obsthresh = (int)(atof(sTemp)); + + //start(cells): + if (fscanf(fCfg, "%s", sTemp) != 1) { + throw SBPL_Exception("ERROR: ran out of env file early"); + } + if (fscanf(fCfg, "%s", sTemp) != 1) { + throw SBPL_Exception("ERROR: ran out of env file early"); + } + EnvNAV2DUUCfg.StartX_c = atoi(sTemp); + if (fscanf(fCfg, "%s", sTemp) != 1) { + throw SBPL_Exception("ERROR: ran out of env file early"); + } + EnvNAV2DUUCfg.StartY_c = atoi(sTemp); + + if (EnvNAV2DUUCfg.StartX_c < 0 || EnvNAV2DUUCfg.StartX_c >= EnvNAV2DUUCfg.EnvWidth_c) { + throw SBPL_Exception("ERROR: illegal start coordinates"); + } + if (EnvNAV2DUUCfg.StartY_c < 0 || EnvNAV2DUUCfg.StartY_c >= EnvNAV2DUUCfg.EnvHeight_c) { + throw SBPL_Exception("ERROR: illegal start coordinates"); + } + + //end(cells): + if (fscanf(fCfg, "%s", sTemp) != 1) { + throw SBPL_Exception("ERROR: ran out of env file early"); + } + if (fscanf(fCfg, "%s", sTemp) != 1) { + throw SBPL_Exception("ERROR: ran out of env file early"); + } + EnvNAV2DUUCfg.EndX_c = atoi(sTemp); + if (fscanf(fCfg, "%s", sTemp) != 1) { + throw SBPL_Exception("ERROR: ran out of env file early"); + } + EnvNAV2DUUCfg.EndY_c = atoi(sTemp); + + if (EnvNAV2DUUCfg.EndX_c < 0 || EnvNAV2DUUCfg.EndX_c >= EnvNAV2DUUCfg.EnvWidth_c) { + throw SBPL_Exception("ERROR: illegal end coordinates"); + } + if (EnvNAV2DUUCfg.EndY_c < 0 || EnvNAV2DUUCfg.EndY_c >= EnvNAV2DUUCfg.EnvHeight_c) { + throw SBPL_Exception("ERROR: illegal end coordinates"); + } + + //allocate the 2D environment and corresponding uncertainty matrix + EnvNAV2DUUCfg.Grid2D = new unsigned char*[EnvNAV2DUUCfg.EnvWidth_c]; + EnvNAV2DUUCfg.UncertaintyGrid2D = new float*[EnvNAV2DUUCfg.EnvWidth_c]; + for (x = 0; x < EnvNAV2DUUCfg.EnvWidth_c; x++) { + EnvNAV2DUUCfg.Grid2D[x] = new unsigned char[EnvNAV2DUUCfg.EnvHeight_c]; + EnvNAV2DUUCfg.UncertaintyGrid2D[x] = new float[EnvNAV2DUUCfg.EnvHeight_c]; + } + + //environment: + EnvNAV2DUUCfg.sizeofH = 0; + if (fscanf(fCfg, "%s", sTemp) != 1) { + throw SBPL_Exception("ERROR: ran out of env file early"); + } + for (y = 0; y < EnvNAV2DUUCfg.EnvHeight_c; y++) + for (x = 0; x < EnvNAV2DUUCfg.EnvWidth_c; x++) { + if (fscanf(fCfg, "%f", &fTemp) != 1) { + throw SBPL_Exception("ERROR: incorrect format of config file"); + } + + if (fTemp > 1.0 - NAV2DUU_ERR_EPS || fTemp < NAV2DUU_ERR_EPS) { + //we assume that the value is just a cost + EnvNAV2DUUCfg.Grid2D[x][y] = (int)fTemp; + if (EnvNAV2DUUCfg.Grid2D[x][y] >= EnvNAV2DUUCfg.obsthresh) + EnvNAV2DUUCfg.UncertaintyGrid2D[x][y] = 1.0; + else + EnvNAV2DUUCfg.UncertaintyGrid2D[x][y] = 0.0; + } + else { + //the value is probability of being free + EnvNAV2DUUCfg.Grid2D[x][y] = 0; //assume cost is 0 if traversable + EnvNAV2DUUCfg.UncertaintyGrid2D[x][y] = fTemp; + EnvNAV2DUUCfg.sizeofH++; + } + } + + EnvNAV2DUUCfg.sizeofS = this->EnvNAV2DUUCfg.EnvWidth_c * this->EnvNAV2DUUCfg.EnvHeight_c; + + SBPL_PRINTF("total size of environment=%d, number of unknown cells=%d\n", EnvNAV2DUUCfg.sizeofS, + EnvNAV2DUUCfg.sizeofH); +} + +//mapdata and uncertaintymapdata is assumed to be organized into a linear array with y being major: map[x+y*width] +void EnvironmentNAV2DUU::SetConfiguration(int width, int height, const unsigned char* mapdata, + const float* uncertaintymapdata) +{ + EnvNAV2DUUCfg.EnvWidth_c = width; + EnvNAV2DUUCfg.EnvHeight_c = height; + + int x, y; + + //set start and goal to zeros for now + EnvNAV2DUUCfg.StartX_c = 0; + EnvNAV2DUUCfg.StartY_c = 0; + EnvNAV2DUUCfg.EndX_c = 0; + EnvNAV2DUUCfg.EndY_c = 0; + + //environment: + //allocate the 2D environment and corresponding uncertainty matrix + EnvNAV2DUUCfg.Grid2D = new unsigned char*[EnvNAV2DUUCfg.EnvWidth_c]; + EnvNAV2DUUCfg.UncertaintyGrid2D = new float*[EnvNAV2DUUCfg.EnvWidth_c]; + for (x = 0; x < EnvNAV2DUUCfg.EnvWidth_c; x++) { + EnvNAV2DUUCfg.Grid2D[x] = new unsigned char[EnvNAV2DUUCfg.EnvHeight_c]; + EnvNAV2DUUCfg.UncertaintyGrid2D[x] = new float[EnvNAV2DUUCfg.EnvHeight_c]; + } + + //initialize the mape + EnvNAV2DUUCfg.sizeofH = 0; + for (y = 0; y < EnvNAV2DUUCfg.EnvHeight_c; y++) { + for (x = 0; x < EnvNAV2DUUCfg.EnvWidth_c; x++) { + if (mapdata == NULL) { + //special case - all is traversable + EnvNAV2DUUCfg.Grid2D[x][y] = 0; + EnvNAV2DUUCfg.UncertaintyGrid2D[x][y] = 0; + } + else { + EnvNAV2DUUCfg.Grid2D[x][y] = mapdata[x + y * width]; + EnvNAV2DUUCfg.UncertaintyGrid2D[x][y] = uncertaintymapdata[x + y * width]; + if (EnvNAV2DUUCfg.UncertaintyGrid2D[x][y] >= NAV2DUU_ERR_EPS && EnvNAV2DUUCfg.UncertaintyGrid2D[x][y] + <= (1.0 - NAV2DUU_ERR_EPS)) EnvNAV2DUUCfg.sizeofH++; + } + } + } + + EnvNAV2DUUCfg.sizeofS = this->EnvNAV2DUUCfg.EnvWidth_c * this->EnvNAV2DUUCfg.EnvHeight_c; + + SBPL_PRINTF("total size of environment=%d, number of unknown cells=%d\n", EnvNAV2DUUCfg.sizeofS, + EnvNAV2DUUCfg.sizeofH); +} + +void EnvironmentNAV2DUU::InitializeEnvironment() +{ + //initialize goal/start IDs + EnvNAV2DUU.startstateid = ENVNAV2DUU_XYTOSTATEID(EnvNAV2DUUCfg.StartX_c, EnvNAV2DUUCfg.StartY_c); + EnvNAV2DUU.goalstateid = ENVNAV2DUU_XYTOSTATEID(EnvNAV2DUUCfg.EndX_c, EnvNAV2DUUCfg.EndY_c); + + //environment initialized + EnvNAV2DUU.bInitialized = true; +} + +void EnvironmentNAV2DUU::InitializeEnvConfig() +{ + //aditional to configuration file initialization if necessary + Computedxy(); + + //compute IDs of hidden variables + int x, y; + int idcount = 0; + EnvNAV2DUUCfg.HiddenVariableXY2ID = new int*[EnvNAV2DUUCfg.EnvWidth_c]; + for (x = 0; x < EnvNAV2DUUCfg.EnvWidth_c; x++) { + EnvNAV2DUUCfg.HiddenVariableXY2ID[x] = new int[EnvNAV2DUUCfg.EnvHeight_c]; + for (y = 0; y < EnvNAV2DUUCfg.EnvWidth_c; y++) { + if (EnvNAV2DUUCfg.UncertaintyGrid2D[x][y] >= NAV2DUU_ERR_EPS && EnvNAV2DUUCfg.UncertaintyGrid2D[x][y] + <= (1.0 - NAV2DUU_ERR_EPS)) { + EnvNAV2DUUCfg.HiddenVariableXY2ID[x][y] = idcount; + idcount++; + } + else + EnvNAV2DUUCfg.HiddenVariableXY2ID[x][y] = -1; + } + } + + if (idcount != EnvNAV2DUUCfg.sizeofH) { + throw SBPL_Exception("ERROR: idcount not equal to sizeofH"); + } +} + +int EnvironmentNAV2DUU::SizeofCreatedEnv() +{ + return EnvNAV2DUUCfg.sizeofS; +} + +int EnvironmentNAV2DUU::SizeofH() +{ + return EnvNAV2DUUCfg.sizeofH; +} + +bool EnvironmentNAV2DUU::IsValidRobotPosition(int X, int Y) +{ + return (X >= 0 && X < EnvNAV2DUUCfg.EnvWidth_c && Y >= 0 && Y < EnvNAV2DUUCfg.EnvHeight_c && + EnvNAV2DUUCfg.Grid2D[X][Y] < EnvNAV2DUUCfg.obsthresh && + EnvNAV2DUUCfg.UncertaintyGrid2D[X][Y] < NAV2DUU_ERR_EPS); +} + +bool EnvironmentNAV2DUU::IsWithinMapCell(int X, int Y) +{ + return (X >= 0 && X < EnvNAV2DUUCfg.EnvWidth_c && Y >= 0 && Y < EnvNAV2DUUCfg.EnvHeight_c); +} + +void EnvironmentNAV2DUU::Computedxy() +{ + //initialize some constants for 2D search + EnvNAV2DUUCfg.dx_[0] = 1; + EnvNAV2DUUCfg.dy_[0] = 1; + EnvNAV2DUUCfg.dxintersects_[0][0] = 0; + EnvNAV2DUUCfg.dyintersects_[0][0] = 1; + EnvNAV2DUUCfg.dxintersects_[0][1] = 1; + EnvNAV2DUUCfg.dyintersects_[0][1] = 0; + EnvNAV2DUUCfg.dx_[1] = 1; + EnvNAV2DUUCfg.dy_[1] = 0; + EnvNAV2DUUCfg.dxintersects_[1][0] = 0; + EnvNAV2DUUCfg.dyintersects_[1][0] = 0; + EnvNAV2DUUCfg.dxintersects_[1][1] = 0; + EnvNAV2DUUCfg.dyintersects_[1][1] = 0; + EnvNAV2DUUCfg.dx_[2] = 1; + EnvNAV2DUUCfg.dy_[2] = -1; + EnvNAV2DUUCfg.dxintersects_[2][0] = 0; + EnvNAV2DUUCfg.dyintersects_[2][0] = -1; + EnvNAV2DUUCfg.dxintersects_[2][1] = 1; + EnvNAV2DUUCfg.dyintersects_[2][1] = 0; + EnvNAV2DUUCfg.dx_[3] = 0; + EnvNAV2DUUCfg.dy_[3] = 1; + EnvNAV2DUUCfg.dxintersects_[3][0] = 0; + EnvNAV2DUUCfg.dyintersects_[3][0] = 0; + EnvNAV2DUUCfg.dxintersects_[3][1] = 0; + EnvNAV2DUUCfg.dyintersects_[3][1] = 0; + EnvNAV2DUUCfg.dx_[4] = 0; + EnvNAV2DUUCfg.dy_[4] = -1; + EnvNAV2DUUCfg.dxintersects_[4][0] = 0; + EnvNAV2DUUCfg.dyintersects_[4][0] = 0; + EnvNAV2DUUCfg.dxintersects_[4][1] = 0; + EnvNAV2DUUCfg.dyintersects_[4][1] = 0; + EnvNAV2DUUCfg.dx_[5] = -1; + EnvNAV2DUUCfg.dy_[5] = 1; + EnvNAV2DUUCfg.dxintersects_[5][0] = 0; + EnvNAV2DUUCfg.dyintersects_[5][0] = 1; + EnvNAV2DUUCfg.dxintersects_[5][1] = -1; + EnvNAV2DUUCfg.dyintersects_[5][1] = 0; + EnvNAV2DUUCfg.dx_[6] = -1; + EnvNAV2DUUCfg.dy_[6] = 0; + EnvNAV2DUUCfg.dxintersects_[6][0] = 0; + EnvNAV2DUUCfg.dyintersects_[6][0] = 0; + EnvNAV2DUUCfg.dxintersects_[6][1] = 0; + EnvNAV2DUUCfg.dyintersects_[6][1] = 0; + EnvNAV2DUUCfg.dx_[7] = -1; + EnvNAV2DUUCfg.dy_[7] = -1; + EnvNAV2DUUCfg.dxintersects_[7][0] = 0; + EnvNAV2DUUCfg.dyintersects_[7][0] = -1; + EnvNAV2DUUCfg.dxintersects_[7][1] = -1; + EnvNAV2DUUCfg.dyintersects_[7][1] = 0; + + //compute distances + for (int dind = 0; dind < ENVNAV2DUU_MAXDIRS; dind++) { + + if (EnvNAV2DUUCfg.dx_[dind] != 0 && EnvNAV2DUUCfg.dy_[dind] != 0) { + if (dind <= 7) { + //the cost of a diagonal move in millimeters + EnvNAV2DUUCfg.dxy_distance_mm_[dind] = (int)(ENVNAV2DUU_COSTMULT * 1.414); + } + else { + //the cost of a move to 1,2 or 2,1 or so on in millimeters + EnvNAV2DUUCfg.dxy_distance_mm_[dind] = (int)(ENVNAV2DUU_COSTMULT * 2.236); + } + } + else + EnvNAV2DUUCfg.dxy_distance_mm_[dind] = ENVNAV2DUU_COSTMULT; //the cost of a horizontal move in millimeters + } +} + +/* +void EnvironmentNAV2DUU::ComputeReversedxy() +{ + int revaind; + + //iterate over actions + for (int aind = 0; aind < NAVLSENV_ROBOTNAVACTIONSWIDTH; aind++) + { + //get the cell location and reverse it + int dX = -EnvNAVLSCfg.dXY[aind][0]; + int dY = -EnvNAVLSCfg.dXY[aind][1]; + + //find the index that corresponds to these offsets + for (revaind = 0; revaind < NAVLSENV_ROBOTNAVACTIONSWIDTH; revaind++) + { + if(EnvNAVLSCfg.dXY[revaind][0] == dX && EnvNAVLSCfg.dXY[revaind][1] == dY) + { + EnvNAVLSCfg.reversedXY[aind] = revaind; + break; + } + } + + if(revaind == NAVLSENV_ROBOTNAVACTIONSWIDTH) + { + SBPL_ERROR("ERROR: can not determine a reversed index for aind=%d (dX=%d dY=%d)\n", + aind, EnvNAVLSCfg.dXY[aind][0], EnvNAVLSCfg.dXY[aind][1]); + } + } +} +*/ + +//------------------------------------------------------------------------------ + +//------------------------------Heuristic computation-------------------------- + +void EnvironmentNAV2DUU::ComputeHeuristicValues() +{ + //whatever necessary pre-computation of heuristic values is done here + SBPL_PRINTF("Precomputing heuristics\n"); + + SBPL_PRINTF("done\n"); +} + +//------------------------------------------------------------------------------ + +//-----------------Printing Routines-------------------------------------------- + +void EnvironmentNAV2DUU::PrintState(int stateID, bool bVerbose, FILE* fOut /*=NULL*/) +{ +#if DEBUG + if (stateID >= this->EnvNAV2DUUCfg.EnvWidth_c*this->EnvNAV2DUUCfg.EnvHeight_c) { + throw SBPL_Exception("ERROR in EnvNAV2DUU... function: st ateID illegal (2)"); + } +#endif + + if (fOut == NULL) fOut = stdout; + + if (stateID == EnvNAV2DUU.goalstateid && bVerbose) { + SBPL_FPRINTF(fOut, "the state is a goal state\n"); + } + + if (bVerbose) + SBPL_FPRINTF(fOut, "X=%d Y=%d\n", ENVNAV2DUU_STATEIDTOX(stateID), ENVNAV2DUU_STATEIDTOY(stateID)); + else + SBPL_FPRINTF(fOut, "%d %d\n", ENVNAV2DUU_STATEIDTOX(stateID), ENVNAV2DUU_STATEIDTOY(stateID)); +} + +void EnvironmentNAV2DUU::PrintEnv_Config(FILE* fOut) +{ + //implement this if the planner needs to print out EnvNAV2DUU. configuration + throw SBPL_Exception("ERROR in EnvNAV2DUU... function: PrintEnv_Config is undefined"); +} + +//------------------------------------------------------------------------------- + + +//-----------interface with outside functions----------------------------------- + +bool EnvironmentNAV2DUU::InitializeEnv(const char* sEnvFile) +{ + FILE* fCfg = fopen(sEnvFile, "r"); + if (fCfg == NULL) { + std::stringstream ss("ERROR: unable to open "); + ss << sEnvFile; + throw SBPL_Exception(ss.str()); + } + ReadConfiguration(fCfg); + fclose(fCfg); + + InitGeneral(); + + return true; +} + +bool EnvironmentNAV2DUU::InitializeEnv(int width, int height, const unsigned char* mapdata, + const float* uncertaintymapdata, unsigned char obsthresh) +{ + SBPL_PRINTF("env: initialized with width=%d height=%d, obsthresh=%d\n", width, height, obsthresh); + + EnvNAV2DUUCfg.obsthresh = obsthresh; + + SetConfiguration(width, height, mapdata, uncertaintymapdata); + + InitGeneral(); + + return true; +} + +bool EnvironmentNAV2DUU::InitGeneral() +{ + //initialize other variables in Cfg + InitializeEnvConfig(); + + //initialize Environment + InitializeEnvironment(); + + //pre-compute heuristics + ComputeHeuristicValues(); + + return true; +} + +bool EnvironmentNAV2DUU::InitializeMDPCfg(MDPConfig *MDPCfg) +{ + //initialize MDPCfg with the start and goal ids + MDPCfg->goalstateid = EnvNAV2DUU.goalstateid; + MDPCfg->startstateid = EnvNAV2DUU.startstateid; + + return true; +} + +int EnvironmentNAV2DUU::GetFromToHeuristic(int FromStateID, int ToStateID) +{ +#if USE_HEUR==0 + return 0; +#endif + + //define this function if it is used in the planner + + throw SBPL_Exception("ERROR in EnvNAV2DUU.. function: FromToHeuristic is undefined"); + + return 0; +} + +int EnvironmentNAV2DUU::GetGoalHeuristic(int stateID) +{ +#if USE_HEUR==0 + return 0; +#endif + + //define this function if it used in the planner (heuristic forward search would use it) + + throw SBPL_Exception("ERROR in EnvNAV2DUU..function: GetGoalHeuristic is undefined"); +} + +int EnvironmentNAV2DUU::GetStartHeuristic(int stateID) +{ +#if USE_HEUR==0 + return 0; +#endif + + //define this function if it used in the planner (heuristic backward search would use it) + + throw SBPL_Exception("ERROR in EnvNAV2DUU.. function: GetStartHeuristic is undefined"); + + return 0; +} + +void EnvironmentNAV2DUU::GetPreds(int stateID, const vector* updatedhvaluesV, + vector* IncomingDetActionV, vector* IncomingStochActionV, + vector* StochActionNonpreferredOutcomeV) +{ + int aind; + + //get state coords + int destx = ENVNAV2DUU_STATEIDTOX(stateID); + int desty = ENVNAV2DUU_STATEIDTOY(stateID); + + //clear succs + IncomingDetActionV->clear(); + IncomingStochActionV->clear(); + StochActionNonpreferredOutcomeV->clear(); + + //check that the destination is valid + if (!IsWithinMapCell(destx, desty) || EnvNAV2DUUCfg.Grid2D[destx][desty] >= EnvNAV2DUUCfg.obsthresh) return; + + //see if the destination was originally uncertain + bool bDet = false; + //no need to worry about ==1.0 since obstacles are rejected above + if (EnvNAV2DUUCfg.UncertaintyGrid2D[destx][desty] < NAV2DUU_ERR_EPS) + bDet = true; + + //if yes, then figure out the probability of being an obstacle + float ProbObs = EnvNAV2DUUCfg.UncertaintyGrid2D[destx][desty]; + int desth_ID = EnvNAV2DUUCfg.HiddenVariableXY2ID[destx][desty]; + bool bFreeh = false; + + //iterate over updated h-values to make sure dest cell is not in there + for (int hind = 0; hind < (int)updatedhvaluesV->size(); hind++) { + if (updatedhvaluesV->at(hind).Prob < NAV2DUU_ERR_EPS) bFreeh = true; //there are elements that are free + + if (updatedhvaluesV->at(hind).h_ID == desth_ID) { + ProbObs = updatedhvaluesV->at(hind).Prob; //found + } + } + + //if now known to be an obstacle, then no preds + if (ProbObs > 1.0 - NAV2DUU_ERR_EPS) + return; + else if (ProbObs < NAV2DUU_ERR_EPS) bDet = false; //now it is a deterministic cell + + //get the destination costmult + int destcostmult = EnvNAV2DUUCfg.Grid2D[destx][desty]; + +#if DEBUG + if (EnvNAV2DUUCfg.numofdirs > 8) { + throw SBPL_Exception("ERROR: number of directions can not exceed 8 for now"); + } +#endif + + //iterate over neighbors + for (aind = 0; aind < EnvNAV2DUUCfg.numofdirs; aind++) { + //the actions are undirected, so we can use the same array of actions as in getsuccs case + int predX = destx + EnvNAV2DUUCfg.dx_[aind]; + int predY = desty + EnvNAV2DUUCfg.dy_[aind]; + + //skip the invalid cells + if (!IsWithinMapCell(predX, predY) || EnvNAV2DUUCfg.Grid2D[predX][predY] >= EnvNAV2DUUCfg.obsthresh) continue; + + //running costmult + int costmult = destcostmult; + + //get the costmultiplier of pred and update total costmult + costmult = __max(costmult, EnvNAV2DUUCfg.Grid2D[predX][predY]); + + //if diagonal move + if (predX != destx && predY != desty) { + //check intersecting cells to make sure they are not uncertain + if (EnvNAV2DUUCfg.UncertaintyGrid2D[destx][predY] >= NAV2DUU_ERR_EPS) { + if (!bFreeh) continue; + + //check that it is not known to be free. Otherwise - invalid move + int tempID = EnvNAV2DUUCfg.HiddenVariableXY2ID[destx][predY]; + bool btempfree = false; + for (int hind = 0; hind < (int)updatedhvaluesV->size(); hind++) { + if (updatedhvaluesV->at(hind).h_ID == tempID) { + if (updatedhvaluesV->at(hind).Prob < NAV2DUU_ERR_EPS) { + btempfree = true; + break; + } + } + } + if (!btempfree) continue; + } + + if (EnvNAV2DUUCfg.UncertaintyGrid2D[predX][desty] >= NAV2DUU_ERR_EPS) { + if (!bFreeh) continue; + + //check that it is not known to be free. Otherwise - invalid move + int tempID = EnvNAV2DUUCfg.HiddenVariableXY2ID[predX][desty]; + bool btempfree = false; + for (int hind = 0; hind < (int)updatedhvaluesV->size(); hind++) { + if (updatedhvaluesV->at(hind).h_ID == tempID) { + if (updatedhvaluesV->at(hind).Prob < NAV2DUU_ERR_EPS) { + btempfree = true; + break; + } + } + } + if (!btempfree) continue; + } + + //compute the costmultiplier of intersect cells and update total costmult + costmult = __max(costmult, EnvNAV2DUUCfg.Grid2D[destx][predY]); + costmult = __max(costmult, EnvNAV2DUUCfg.Grid2D[predX][desty]); + } + + //make sure cost is still valid + if (costmult >= EnvNAV2DUUCfg.obsthresh) continue; + + //otherwise compute the actual cost (once again we use the fact that + //actions are undirected to determine the cost) + int cost = (((int)costmult) + 1) * EnvNAV2DUUCfg.dxy_distance_mm_[aind]; + + //create action + int predstateID = ENVNAV2DUU_XYTOSTATEID(predX, predY); + CMDPACTION action(aind, predstateID); //TODO-use reverseindex + + if (bDet) { + //if dest is known - then form a deterministic action + action.AddOutcome(stateID, cost, 1.0); + IncomingDetActionV->push_back(action); + } + else { + //if dest is unknown - then form a stoch action and compute the corresponding belief part + action.AddOutcome(stateID, cost, 1 - ProbObs); //preferred outcome + action.AddOutcome(predstateID, 2 * cost, ProbObs); //non-preferred outcome (stateID is untraversable) + IncomingStochActionV->push_back(action); + //also insert the corresponding hidden variable value + sbpl_BinaryHiddenVar_t hval; + hval.h_ID = desth_ID; + hval.Prob = 1; //known to be an obstacle + StochActionNonpreferredOutcomeV->push_back(hval); + } + } +} + +//returns the stateid if success, and -1 otherwise +int EnvironmentNAV2DUU::SetGoal(int x, int y) +{ + if (!IsWithinMapCell(x, y)) { + SBPL_ERROR("ERROR: trying to set a goal cell %d %d that is outside of map\n", x, y); + return -1; + } + + if (!IsValidRobotPosition(x, y)) { + SBPL_PRINTF("WARNING: goal cell is invalid\n"); + } + + EnvNAV2DUU.goalstateid = ENVNAV2DUU_XYTOSTATEID(x, y); + EnvNAV2DUUCfg.EndX_c = x; + EnvNAV2DUUCfg.EndY_c = y; + + return EnvNAV2DUU.goalstateid; +} + +//returns the stateid if success, and -1 otherwise +int EnvironmentNAV2DUU::SetStart(int x, int y) +{ + if (!IsWithinMapCell(x, y)) { + SBPL_ERROR("ERROR: trying to set a start cell %d %d that is outside of map\n", x, y); + return -1; + } + + if (!IsValidRobotPosition(x, y)) { + SBPL_PRINTF("WARNING: start cell is invalid\n"); + } + + EnvNAV2DUU.startstateid = ENVNAV2DUU_XYTOSTATEID(x, y); + EnvNAV2DUUCfg.StartX_c = x; + EnvNAV2DUUCfg.StartY_c = y; + + return EnvNAV2DUU.startstateid; +} + +bool EnvironmentNAV2DUU::UpdateCost(int x, int y, unsigned char newcost) +{ + EnvNAV2DUUCfg.Grid2D[x][y] = newcost; + + return true; +} + +//------------------------------------------------------------------------------ diff --git a/navigations/sbpl/src/discrete_space_information/environment_navxythetalat.cpp b/navigations/sbpl/src/discrete_space_information/environment_navxythetalat.cpp new file mode 100755 index 0000000..d4f6533 --- /dev/null +++ b/navigations/sbpl/src/discrete_space_information/environment_navxythetalat.cpp @@ -0,0 +1,3410 @@ +/* + * Copyright (c) 2008, Maxim Likhachev + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Carnegie Mellon University nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include +#include +#include +#include +#include +#include +#include + +#if TIME_DEBUG +static clock_t time3_addallout = 0; +static clock_t time_gethash = 0; +static clock_t time_createhash = 0; +static clock_t time_getsuccs = 0; +#endif + +static long int checks = 0; + +#define XYTHETA2INDEX(X,Y,THETA) (THETA + X*EnvNAVXYTHETALATCfg.NumThetaDirs + \ + Y*EnvNAVXYTHETALATCfg.EnvWidth_c*EnvNAVXYTHETALATCfg.NumThetaDirs) + +EnvironmentNAVXYTHETALATTICE::EnvironmentNAVXYTHETALATTICE() +{ + EnvNAVXYTHETALATCfg.obsthresh = ENVNAVXYTHETALAT_DEFAULTOBSTHRESH; + // the value that pretty much makes it disabled + EnvNAVXYTHETALATCfg.cost_inscribed_thresh = EnvNAVXYTHETALATCfg.obsthresh; + // the value that pretty much makes it disabled + EnvNAVXYTHETALATCfg.cost_possibly_circumscribed_thresh = -1; + + grid2Dsearchfromstart = NULL; + grid2Dsearchfromgoal = NULL; + bNeedtoRecomputeStartHeuristics = true; + bNeedtoRecomputeGoalHeuristics = true; + iteration = 0; + bucketsize = 0; // fixed bucket size + blocksize = 1; + bUseNonUniformAngles = false; + + EnvNAVXYTHETALAT.bInitialized = false; + + EnvNAVXYTHETALATCfg.actionwidth = NAVXYTHETALAT_DEFAULT_ACTIONWIDTH; + + EnvNAVXYTHETALATCfg.NumThetaDirs = NAVXYTHETALAT_THETADIRS; + + // no memory allocated in cfg yet + EnvNAVXYTHETALATCfg.Grid2D = NULL; + EnvNAVXYTHETALATCfg.ActionsV = NULL; + EnvNAVXYTHETALATCfg.PredActionsV = NULL; +} + +EnvironmentNAVXYTHETALATTICE::~EnvironmentNAVXYTHETALATTICE() +{ + SBPL_PRINTF("destroying XYTHETALATTICE\n"); + if (grid2Dsearchfromstart != NULL) { + delete grid2Dsearchfromstart; + } + grid2Dsearchfromstart = NULL; + + if (grid2Dsearchfromgoal != NULL) { + delete grid2Dsearchfromgoal; + } + grid2Dsearchfromgoal = NULL; + + if (EnvNAVXYTHETALATCfg.Grid2D != NULL) { + for (int x = 0; x < EnvNAVXYTHETALATCfg.EnvWidth_c; x++) { + delete[] EnvNAVXYTHETALATCfg.Grid2D[x]; + } + delete[] EnvNAVXYTHETALATCfg.Grid2D; + EnvNAVXYTHETALATCfg.Grid2D = NULL; + } + + //delete actions + if (EnvNAVXYTHETALATCfg.ActionsV != NULL) { + for (int tind = 0; tind < EnvNAVXYTHETALATCfg.NumThetaDirs; tind++) { + delete[] EnvNAVXYTHETALATCfg.ActionsV[tind]; + } + delete[] EnvNAVXYTHETALATCfg.ActionsV; + EnvNAVXYTHETALATCfg.ActionsV = NULL; + } + if (EnvNAVXYTHETALATCfg.PredActionsV != NULL) { + delete[] EnvNAVXYTHETALATCfg.PredActionsV; + EnvNAVXYTHETALATCfg.PredActionsV = NULL; + } +} + +static unsigned int inthash(unsigned int key) +{ + key += (key << 12); + key ^= (key >> 22); + key += (key << 4); + key ^= (key >> 9); + key += (key << 10); + key ^= (key >> 2); + key += (key << 7); + key ^= (key >> 12); + return key; +} + +void EnvironmentNAVXYTHETALATTICE::SetConfiguration( + int width, int height, const unsigned char* mapdata, + int startx, int starty, int starttheta, + int goalx, int goaly, int goaltheta, + double cellsize_m, + double nominalvel_mpersecs, + double timetoturn45degsinplace_secs, + const std::vector& robot_perimeterV) +{ + EnvNAVXYTHETALATCfg.EnvWidth_c = width; + EnvNAVXYTHETALATCfg.EnvHeight_c = height; + EnvNAVXYTHETALATCfg.StartX_c = startx; + EnvNAVXYTHETALATCfg.StartY_c = starty; + EnvNAVXYTHETALATCfg.StartTheta = starttheta; + + if (EnvNAVXYTHETALATCfg.StartX_c < 0 || + EnvNAVXYTHETALATCfg.StartX_c >= EnvNAVXYTHETALATCfg.EnvWidth_c) + { + throw SBPL_Exception("ERROR: illegal start coordinates"); + } + if (EnvNAVXYTHETALATCfg.StartY_c < 0 || + EnvNAVXYTHETALATCfg.StartY_c >= EnvNAVXYTHETALATCfg.EnvHeight_c) + { + throw SBPL_Exception("ERROR: illegal start coordinates"); + } + if (EnvNAVXYTHETALATCfg.StartTheta < 0 || + EnvNAVXYTHETALATCfg.StartTheta >= EnvNAVXYTHETALATCfg.NumThetaDirs) + { + throw SBPL_Exception("ERROR: illegal start coordinates for theta"); + } + + EnvNAVXYTHETALATCfg.EndX_c = goalx; + EnvNAVXYTHETALATCfg.EndY_c = goaly; + EnvNAVXYTHETALATCfg.EndTheta = goaltheta; + + if (EnvNAVXYTHETALATCfg.EndX_c < 0 || + EnvNAVXYTHETALATCfg.EndX_c >= EnvNAVXYTHETALATCfg.EnvWidth_c) + { + throw SBPL_Exception("ERROR: illegal goal coordinates"); + } + if (EnvNAVXYTHETALATCfg.EndY_c < 0 || + EnvNAVXYTHETALATCfg.EndY_c >= EnvNAVXYTHETALATCfg.EnvHeight_c) + { + throw SBPL_Exception("ERROR: illegal goal coordinates"); + } + if (EnvNAVXYTHETALATCfg.EndTheta < 0 || + EnvNAVXYTHETALATCfg.EndTheta >= EnvNAVXYTHETALATCfg.NumThetaDirs) + { + throw SBPL_Exception("ERROR: illegal goal coordinates for theta"); + } + + EnvNAVXYTHETALATCfg.FootprintPolygon = robot_perimeterV; + + EnvNAVXYTHETALATCfg.nominalvel_mpersecs = nominalvel_mpersecs; + EnvNAVXYTHETALATCfg.cellsize_m = cellsize_m; + EnvNAVXYTHETALATCfg.timetoturn45degsinplace_secs = timetoturn45degsinplace_secs; + + // unallocate the 2D environment + if (EnvNAVXYTHETALATCfg.Grid2D != NULL) { + for (int x = 0; x < EnvNAVXYTHETALATCfg.EnvWidth_c; x++) { + delete[] EnvNAVXYTHETALATCfg.Grid2D[x]; + } + delete[] EnvNAVXYTHETALATCfg.Grid2D; + EnvNAVXYTHETALATCfg.Grid2D = NULL; + } + + // allocate the 2D environment + EnvNAVXYTHETALATCfg.Grid2D = new unsigned char*[EnvNAVXYTHETALATCfg.EnvWidth_c]; + for (int x = 0; x < EnvNAVXYTHETALATCfg.EnvWidth_c; x++) { + EnvNAVXYTHETALATCfg.Grid2D[x] = new unsigned char[EnvNAVXYTHETALATCfg.EnvHeight_c]; + } + + // environment: + if (0 == mapdata) { + for (int y = 0; y < EnvNAVXYTHETALATCfg.EnvHeight_c; y++) { + for (int x = 0; x < EnvNAVXYTHETALATCfg.EnvWidth_c; x++) { + EnvNAVXYTHETALATCfg.Grid2D[x][y] = 0; + } + } + } + else { + for (int y = 0; y < EnvNAVXYTHETALATCfg.EnvHeight_c; y++) { + for (int x = 0; x < EnvNAVXYTHETALATCfg.EnvWidth_c; x++) { + EnvNAVXYTHETALATCfg.Grid2D[x][y] = mapdata[x + y * width]; + } + } + } +} + +void EnvironmentNAVXYTHETALATTICE::ReadConfiguration(FILE* fCfg) +{ + // read in the configuration of environment and initialize + // EnvNAVXYTHETALATCfg structure + char sTemp[1024], sTemp1[1024]; + int dTemp; + int x, y; + + // discretization(cells) + if (fscanf(fCfg, "%s", sTemp) != 1) { + throw SBPL_Exception("ERROR: ran out of env file early (discretization)"); + } + strcpy(sTemp1, "discretization(cells):"); + if (strcmp(sTemp1, sTemp) != 0) { + std::stringstream ss; + ss << "ERROR: configuration file has incorrect format (discretization)" << + " Expected " << sTemp1 << " got " << sTemp; + throw SBPL_Exception(ss.str()); + } + if (fscanf(fCfg, "%s", sTemp) != 1) { + throw SBPL_Exception("ERROR: ran out of env file early (discretization)"); + } + EnvNAVXYTHETALATCfg.EnvWidth_c = atoi(sTemp); + if (fscanf(fCfg, "%s", sTemp) != 1) { + throw SBPL_Exception("ERROR: ran out of env file early (discretization)"); + } + EnvNAVXYTHETALATCfg.EnvHeight_c = atoi(sTemp); + + // Scan for optional NumThetaDirs parameter. Check for following obsthresh. + if (fscanf(fCfg, "%s", sTemp) != 1) { + throw SBPL_Exception("ERROR: ran out of env file early"); + } + strcpy(sTemp1, "NumThetaDirs:"); + if (strcmp(sTemp1, sTemp) != 0) { + // optional NumThetaDirs not available; default is NAVXYTHETALAT_THETADIRS (16) + strcpy(sTemp1, "obsthresh:"); + if (strcmp(sTemp1, sTemp) != 0) { + std::stringstream ss; + ss << "ERROR: configuration file has incorrect format" << + " Expected " << sTemp1 << " got " << sTemp; + throw SBPL_Exception(ss.str()); + } + else { + EnvNAVXYTHETALATCfg.NumThetaDirs = NAVXYTHETALAT_THETADIRS; + } + } + else { + if (fscanf(fCfg, "%s", sTemp) != 1) { + throw SBPL_Exception("ERROR: ran out of env file early (NumThetaDirs)"); + } + EnvNAVXYTHETALATCfg.NumThetaDirs = atoi(sTemp); + + //obsthresh: + if (fscanf(fCfg, "%s", sTemp) != 1) { + throw SBPL_Exception("ERROR: ran out of env file early (obsthresh)"); + } + strcpy(sTemp1, "obsthresh:"); + if (strcmp(sTemp1, sTemp) != 0) { + std::stringstream ss; + ss << "ERROR: configuration file has incorrect format" << + " Expected " << sTemp1 << " got " << sTemp << + " see existing examples of env files for the right format of heading"; + throw SBPL_Exception(ss.str()); + } + } + + // obsthresh + if (fscanf(fCfg, "%s", sTemp) != 1) { + throw SBPL_Exception("ERROR: ran out of env file early"); + } + EnvNAVXYTHETALATCfg.obsthresh = atoi(sTemp); + SBPL_PRINTF("obsthresh = %d\n", EnvNAVXYTHETALATCfg.obsthresh); + + //cost_inscribed_thresh: + if (fscanf(fCfg, "%s", sTemp) != 1) { + throw SBPL_Exception("ERROR: ran out of env file early"); + } + strcpy(sTemp1, "cost_inscribed_thresh:"); + if (strcmp(sTemp1, sTemp) != 0) { + std::stringstream ss; + ss << "ERROR: configuration file has incorrect format" << + " Expected " << sTemp1 << " got " << sTemp << + " see existing examples of env files for the right format of heading"; + throw SBPL_Exception(ss.str()); + } + if (fscanf(fCfg, "%s", sTemp) != 1) { + throw SBPL_Exception("ERROR: ran out of env file early"); + } + EnvNAVXYTHETALATCfg.cost_inscribed_thresh = atoi(sTemp); + SBPL_PRINTF("cost_inscribed_thresh = %d\n", EnvNAVXYTHETALATCfg.cost_inscribed_thresh); + + //cost_possibly_circumscribed_thresh: + if (fscanf(fCfg, "%s", sTemp) != 1) { + throw SBPL_Exception("ERROR: ran out of env file early"); + } + strcpy(sTemp1, "cost_possibly_circumscribed_thresh:"); + if (strcmp(sTemp1, sTemp) != 0) { + std::stringstream ss; + ss << "ERROR: configuration file has incorrect format" << + " Expected " << sTemp1 << " got " << sTemp << + " see existing examples of env files for the right format of heading"; + throw SBPL_Exception(ss.str()); + } + if (fscanf(fCfg, "%s", sTemp) != 1) { + throw SBPL_Exception("ERROR: ran out of env file early"); + } + EnvNAVXYTHETALATCfg.cost_possibly_circumscribed_thresh = atoi(sTemp); + SBPL_PRINTF("cost_possibly_circumscribed_thresh = %d\n", EnvNAVXYTHETALATCfg.cost_possibly_circumscribed_thresh); + + //cellsize + if (fscanf(fCfg, "%s", sTemp) != 1) { + throw SBPL_Exception("ERROR: ran out of env file early"); + } + strcpy(sTemp1, "cellsize(meters):"); + if (strcmp(sTemp1, sTemp) != 0) { + std::stringstream ss; + ss << "ERROR: configuration file has incorrect format" << + " Expected " << sTemp1 << " got " << sTemp; + throw SBPL_Exception(ss.str()); + } + if (fscanf(fCfg, "%s", sTemp) != 1) { + throw SBPL_Exception("ERROR: ran out of env file early"); + } + EnvNAVXYTHETALATCfg.cellsize_m = atof(sTemp); + + //speeds + if (fscanf(fCfg, "%s", sTemp) != 1) { + throw SBPL_Exception("ERROR: ran out of env file early"); + } + strcpy(sTemp1, "nominalvel(mpersecs):"); + if (strcmp(sTemp1, sTemp) != 0) { + std::stringstream ss; + ss << "ERROR: configuration file has incorrect format" << + " Expected " << sTemp1 << " got " << sTemp; + throw SBPL_Exception(ss.str()); + } + if (fscanf(fCfg, "%s", sTemp) != 1) { + throw SBPL_Exception("ERROR: ran out of env file early"); + } + EnvNAVXYTHETALATCfg.nominalvel_mpersecs = atof(sTemp); + if (fscanf(fCfg, "%s", sTemp) != 1) { + throw SBPL_Exception("ERROR: ran out of env file early"); + } + strcpy(sTemp1, "timetoturn45degsinplace(secs):"); + if (strcmp(sTemp1, sTemp) != 0) { + std::stringstream ss; + ss << "ERROR: configuration file has incorrect format" << + " Expected " << sTemp1 << " got " << sTemp; + throw SBPL_Exception(ss.str()); + } + if (fscanf(fCfg, "%s", sTemp) != 1) { + throw SBPL_Exception("ERROR: ran out of env file early"); + } + EnvNAVXYTHETALATCfg.timetoturn45degsinplace_secs = atof(sTemp); + + // start(meters,rads): + if (fscanf(fCfg, "%s", sTemp) != 1) { + throw SBPL_Exception("ERROR: ran out of env file early"); + } + if (fscanf(fCfg, "%s", sTemp) != 1) { + throw SBPL_Exception("ERROR: ran out of env file early"); + } + EnvNAVXYTHETALATCfg.StartX_c = CONTXY2DISC(atof(sTemp), EnvNAVXYTHETALATCfg.cellsize_m); + if (fscanf(fCfg, "%s", sTemp) != 1) { + throw SBPL_Exception("ERROR: ran out of env file early"); + } + EnvNAVXYTHETALATCfg.StartY_c = CONTXY2DISC(atof(sTemp), EnvNAVXYTHETALATCfg.cellsize_m); + if (fscanf(fCfg, "%s", sTemp) != 1) { + throw SBPL_Exception("ERROR: ran out of env file early"); + } + + EnvNAVXYTHETALATCfg.StartTheta_rad = atof(sTemp); + + if (EnvNAVXYTHETALATCfg.StartX_c < 0 || + EnvNAVXYTHETALATCfg.StartX_c >= EnvNAVXYTHETALATCfg.EnvWidth_c) + { + throw SBPL_Exception("ERROR: illegal start coordinates"); + } + if (EnvNAVXYTHETALATCfg.StartY_c < 0 || + EnvNAVXYTHETALATCfg.StartY_c >= EnvNAVXYTHETALATCfg.EnvHeight_c) + { + throw SBPL_Exception("ERROR: illegal start coordinates"); + } + + // end(meters,rads): + if (fscanf(fCfg, "%s", sTemp) != 1) { + throw SBPL_Exception("ERROR: ran out of env file early"); + } + if (fscanf(fCfg, "%s", sTemp) != 1) { + throw SBPL_Exception("ERROR: ran out of env file early"); + } + EnvNAVXYTHETALATCfg.EndX_c = CONTXY2DISC(atof(sTemp), EnvNAVXYTHETALATCfg.cellsize_m); + if (fscanf(fCfg, "%s", sTemp) != 1) { + throw SBPL_Exception("ERROR: ran out of env file early"); + } + EnvNAVXYTHETALATCfg.EndY_c = CONTXY2DISC(atof(sTemp), EnvNAVXYTHETALATCfg.cellsize_m); + if (fscanf(fCfg, "%s", sTemp) != 1) { + throw SBPL_Exception("ERROR: ran out of env file early"); + } + + EnvNAVXYTHETALATCfg.EndTheta_rad = atof(sTemp); + + if (EnvNAVXYTHETALATCfg.EndX_c < 0 || + EnvNAVXYTHETALATCfg.EndX_c >= EnvNAVXYTHETALATCfg.EnvWidth_c) + { + throw SBPL_Exception("ERROR: illegal end coordinates"); + } + if (EnvNAVXYTHETALATCfg.EndY_c < 0 || + EnvNAVXYTHETALATCfg.EndY_c >= EnvNAVXYTHETALATCfg.EnvHeight_c) + { + throw SBPL_Exception("ERROR: illegal end coordinates"); + } + + // unallocate the 2d environment + if (EnvNAVXYTHETALATCfg.Grid2D != NULL) { + for (x = 0; x < EnvNAVXYTHETALATCfg.EnvWidth_c; x++) { + delete[] EnvNAVXYTHETALATCfg.Grid2D[x]; + } + delete[] EnvNAVXYTHETALATCfg.Grid2D; + EnvNAVXYTHETALATCfg.Grid2D = NULL; + } + + // allocate the 2D environment + EnvNAVXYTHETALATCfg.Grid2D = new unsigned char*[EnvNAVXYTHETALATCfg.EnvWidth_c]; + for (x = 0; x < EnvNAVXYTHETALATCfg.EnvWidth_c; x++) { + EnvNAVXYTHETALATCfg.Grid2D[x] = new unsigned char[EnvNAVXYTHETALATCfg.EnvHeight_c]; + } + + // environment: + if (fscanf(fCfg, "%s", sTemp) != 1) { + throw SBPL_Exception("ERROR: ran out of env file early"); + } + for (y = 0; y < EnvNAVXYTHETALATCfg.EnvHeight_c; y++) { + for (x = 0; x < EnvNAVXYTHETALATCfg.EnvWidth_c; x++) { + if (fscanf(fCfg, "%d", &dTemp) != 1) { + throw SBPL_Exception("ERROR: incorrect format of config file"); + } + EnvNAVXYTHETALATCfg.Grid2D[x][y] = dTemp; + } + } +} + +bool EnvironmentNAVXYTHETALATTICE::ReadinCell( + sbpl_xy_theta_cell_t* cell, + FILE* fIn) +{ + char sTemp[60]; + + if (fscanf(fIn, "%s", sTemp) == 0) { + return false; + } + cell->x = atoi(sTemp); + if (fscanf(fIn, "%s", sTemp) == 0) { + return false; + } + cell->y = atoi(sTemp); + if (fscanf(fIn, "%s", sTemp) == 0) { + return false; + } + cell->theta = atoi(sTemp); + + // normalize the angle + cell->theta = normalizeDiscAngle(cell->theta); + // cell->theta = NORMALIZEDISCTHETA(cell->theta, EnvNAVXYTHETALATCfg.NumThetaDirs); + + return true; +} + +bool EnvironmentNAVXYTHETALATTICE::ReadinPose( + sbpl_xy_theta_pt_t* pose, + FILE* fIn) +{ + char sTemp[60]; + + if (fscanf(fIn, "%s", sTemp) == 0) { + return false; + } + pose->x = atof(sTemp); + if (fscanf(fIn, "%s", sTemp) == 0) { + return false; + } + pose->y = atof(sTemp); + if (fscanf(fIn, "%s", sTemp) == 0) { + return false; + } + pose->theta = atof(sTemp); + + pose->theta = normalizeAngle(pose->theta); + + return true; +} + +int EnvironmentNAVXYTHETALATTICE::normalizeDiscAngle(int theta) const +{ + if (bUseNonUniformAngles) { + if (theta < 0) { + theta += EnvNAVXYTHETALATCfg.NumThetaDirs; + } + if (theta >= EnvNAVXYTHETALATCfg.NumThetaDirs) { + theta -= EnvNAVXYTHETALATCfg.NumThetaDirs; + } + } + else { + theta = NORMALIZEDISCTHETA(theta, EnvNAVXYTHETALATCfg.NumThetaDirs); + } + return theta; +} + +double EnvironmentNAVXYTHETALATTICE::DiscTheta2ContNew(int theta) const +{ + if (bUseNonUniformAngles) { + return DiscTheta2ContFromSet(theta); + } + else { + return DiscTheta2Cont(theta, EnvNAVXYTHETALATCfg.NumThetaDirs); + } +} + +int EnvironmentNAVXYTHETALATTICE::ContTheta2DiscNew(double theta) const +{ + if (bUseNonUniformAngles) { + return ContTheta2DiscFromSet(theta); + } + else { + return ContTheta2Disc(theta, EnvNAVXYTHETALATCfg.NumThetaDirs); + } +} + +double EnvironmentNAVXYTHETALATTICE::DiscTheta2ContFromSet(int theta) const +{ + theta = normalizeDiscAngle(theta); + + // ThetaDirs should contain extra angle (2PI) for overlap + if (EnvNAVXYTHETALATCfg.NumThetaDirs >= (int)EnvNAVXYTHETALATCfg.ThetaDirs.size()) { + throw SBPL_Exception("ERROR: list of bin angles are not properly set to use function DiscTheta2ConfFromSet"); + } + + if (theta > EnvNAVXYTHETALATCfg.NumThetaDirs || theta < 0) { + std::stringstream ss; + ss << "ERROR: discrete value theta " << theta << " out of range"; + throw SBPL_Exception(ss.str()); + } + return EnvNAVXYTHETALATCfg.ThetaDirs[theta]; +} + +int EnvironmentNAVXYTHETALATTICE::ContTheta2DiscFromSet(double theta) const +{ + theta = normalizeAngle(theta); + // ThetaDirs should contain extra angle (2PI) for overlap + if (EnvNAVXYTHETALATCfg.NumThetaDirs >= (int) EnvNAVXYTHETALATCfg.ThetaDirs.size()) { + throw SBPL_Exception("ERROR: list of bin angles are not properly set to use function ContTheta2DiscFromSet"); + } + + int lower_bound_ind = -1; + int upper_bound_ind = -1; + for (int i = 1; i < (int) EnvNAVXYTHETALATCfg.ThetaDirs.size(); i++) { + if ((EnvNAVXYTHETALATCfg.ThetaDirs[i]) >= theta) { + lower_bound_ind = i - 1; + upper_bound_ind = i; + break; + } + } + + // Critical error if could not find bin location from given angle + if (lower_bound_ind == -1) { + std::stringstream ss; + ss << "ERROR: unable to find bin index for angle " << theta; + throw SBPL_Exception(ss.str()); + } + + // Get closest angle of two + double angle_low = EnvNAVXYTHETALATCfg.ThetaDirs[lower_bound_ind]; + double angle_up = EnvNAVXYTHETALATCfg.ThetaDirs[upper_bound_ind]; + double diff_low = fabs(theta - angle_low); + double diff_up = fabs(theta - angle_up); + + if (diff_low < diff_up) { + return lower_bound_ind; + } + else { + // Wrap upper bound index around when it reaches last index (assumed to be 2PI) + if (upper_bound_ind == EnvNAVXYTHETALATCfg.NumThetaDirs) { + upper_bound_ind = 0; + } + return upper_bound_ind; + } +} + +bool EnvironmentNAVXYTHETALATTICE::ReadinMotionPrimitive( + SBPL_xytheta_mprimitive* pMotPrim, + FILE* fIn) +{ + char sTemp[1024]; + int dTemp; + char sExpected[1024]; + int numofIntermPoses; + float fTemp; + + // read in actionID + strcpy(sExpected, "primID:"); + if (fscanf(fIn, "%s", sTemp) == 0) { + return false; + } + if (strcmp(sTemp, sExpected) != 0) { + SBPL_ERROR("ERROR: expected %s but got %s\n", sExpected, sTemp); + fflush(stdout); + return false; + } + if (fscanf(fIn, "%d", &pMotPrim->motprimID) != 1) { + return false; + } + + // read in start angle + strcpy(sExpected, "startangle_c:"); + if (fscanf(fIn, "%s", sTemp) == 0) { + return false; + } + if (strcmp(sTemp, sExpected) != 0) { + SBPL_ERROR("ERROR: expected %s but got %s\n", sExpected, sTemp); + return false; + } + if (fscanf(fIn, "%d", &dTemp) == 0) { + SBPL_ERROR("ERROR reading startangle\n"); + return false; + } + pMotPrim->starttheta_c = dTemp; + + // read in end pose + strcpy(sExpected, "endpose_c:"); + if (fscanf(fIn, "%s", sTemp) == 0) { + return false; + } + if (strcmp(sTemp, sExpected) != 0) { + SBPL_ERROR("ERROR: expected %s but got %s\n", sExpected, sTemp); + return false; + } + + if (ReadinCell(&pMotPrim->endcell, fIn) == false) { + SBPL_ERROR("ERROR: failed to read in endsearchpose\n"); + return false; + } + + // read in action cost + strcpy(sExpected, "additionalactioncostmult:"); + if (fscanf(fIn, "%s", sTemp) == 0) { + return false; + } + if (strcmp(sTemp, sExpected) != 0) { + SBPL_ERROR("ERROR: expected %s but got %s\n", sExpected, sTemp); + return false; + } + if (fscanf(fIn, "%d", &dTemp) != 1) { + return false; + } + pMotPrim->additionalactioncostmult = dTemp; + + if (bUseNonUniformAngles) { + // read in action turning radius + strcpy(sExpected, "turning_radius:"); + if (fscanf(fIn, "%s", sTemp) == 0) { + return false; + } + if (strcmp(sTemp, sExpected) != 0) { + SBPL_ERROR("ERROR: expected %s but got %s\n", sExpected, sTemp); + return false; + } + if (fscanf(fIn, "%f", &fTemp) != 1) { + return false; + } + pMotPrim->turning_radius = fTemp; + } + + // read in intermediate poses + strcpy(sExpected, "intermediateposes:"); + if (fscanf(fIn, "%s", sTemp) == 0) { + return false; + } + if (strcmp(sTemp, sExpected) != 0) { + SBPL_ERROR("ERROR: expected %s but got %s\n", sExpected, sTemp); + return false; + } + if (fscanf(fIn, "%d", &numofIntermPoses) != 1) { + return false; + } + // all intermposes should be with respect to 0,0 as starting pose since it + // will be added later and should be done after the action is rotated by + // initial orientation + for (int i = 0; i < numofIntermPoses; i++) { + sbpl_xy_theta_pt_t intermpose; + if (ReadinPose(&intermpose, fIn) == false) { + SBPL_ERROR("ERROR: failed to read in intermediate poses\n"); + return false; + } + pMotPrim->intermptV.push_back(intermpose); + } + + // Check that the last pose of the motion matches (within lattice + // resolution) the designated end pose of the primitive + sbpl_xy_theta_pt_t sourcepose; + sourcepose.x = DISCXY2CONT(0, EnvNAVXYTHETALATCfg.cellsize_m); + sourcepose.y = DISCXY2CONT(0, EnvNAVXYTHETALATCfg.cellsize_m); + sourcepose.theta = DiscTheta2ContNew(pMotPrim->starttheta_c); + double mp_endx_m = sourcepose.x + pMotPrim->intermptV[pMotPrim->intermptV.size() - 1].x; + double mp_endy_m = sourcepose.y + pMotPrim->intermptV[pMotPrim->intermptV.size() - 1].y; + double mp_endtheta_rad = pMotPrim->intermptV[pMotPrim->intermptV.size() - 1].theta; + + int endtheta_c; + int endx_c = CONTXY2DISC(mp_endx_m, EnvNAVXYTHETALATCfg.cellsize_m); + int endy_c = CONTXY2DISC(mp_endy_m, EnvNAVXYTHETALATCfg.cellsize_m); + endtheta_c = ContTheta2DiscNew(mp_endtheta_rad); + if (endx_c != pMotPrim->endcell.x || + endy_c != pMotPrim->endcell.y || + endtheta_c != pMotPrim->endcell.theta) + { + SBPL_ERROR( "ERROR: incorrect primitive %d with startangle=%d " + "last interm point %f %f %f does not match end pose %d %d %d\n", + pMotPrim->motprimID, pMotPrim->starttheta_c, + pMotPrim->intermptV[pMotPrim->intermptV.size() - 1].x, + pMotPrim->intermptV[pMotPrim->intermptV.size() - 1].y, + pMotPrim->intermptV[pMotPrim->intermptV.size() - 1].theta, + pMotPrim->endcell.x, pMotPrim->endcell.y, + pMotPrim->endcell.theta); + SBPL_FFLUSH(stdout); + return false; + } + + return true; +} + +bool EnvironmentNAVXYTHETALATTICE::ReadMotionPrimitives(FILE* fMotPrims) +{ + char sTemp[1024], sExpected[1024]; + float fTemp; + int dTemp; + int totalNumofActions = 0; + + SBPL_INFO("Reading in motion primitives..."); + fflush(stdout); + + //read in the resolution + strcpy(sExpected, "resolution_m:"); + if (fscanf(fMotPrims, "%s", sTemp) == 0) { + return false; + } + if (strcmp(sTemp, sExpected) != 0) { + SBPL_ERROR("ERROR: expected %s but got %s\n", sExpected, sTemp); + fflush(stdout); + return false; + } + if (fscanf(fMotPrims, "%f", &fTemp) == 0) { + return false; + } + if (fabs(fTemp - EnvNAVXYTHETALATCfg.cellsize_m) > ERR_EPS) { + SBPL_ERROR("ERROR: invalid resolution %f (instead of %f) in the dynamics file\n", fTemp, EnvNAVXYTHETALATCfg.cellsize_m); + fflush(stdout); + return false; + } + SBPL_INFO("resolution_m: %f\n", fTemp); + + if (fscanf(fMotPrims, "%s", sTemp) == 0) { + return false; + } + SBPL_INFO("sTemp: %s\n", sTemp); + if (strncmp(sTemp, "min_turning_radius_m:", 21) == 0) { + bUseNonUniformAngles = true; + } + SBPL_INFO("bUseNonUniformAngles = %d", bUseNonUniformAngles); + + if (bUseNonUniformAngles) { + float min_turn_rad; + strcpy(sExpected, "min_turning_radius_m:"); + if (strcmp(sTemp, sExpected) != 0) { + SBPL_ERROR("ERROR: expected %s but got %s\n", sExpected, sTemp); + fflush(stdout); + return false; + } + if (fscanf(fMotPrims, "%f", &min_turn_rad) == 0) { + return false; + } + SBPL_PRINTF("min_turn_rad: %f\n", min_turn_rad); + fflush(stdout); + if (fscanf(fMotPrims, "%s", sTemp) == 0) { + return false; + } + } + + // read in the angular resolution + strcpy(sExpected, "numberofangles:"); + if (strcmp(sTemp, sExpected) != 0) { + SBPL_ERROR("ERROR: expected %s but got %s\n", sExpected, sTemp); + return false; + } + if (fscanf(fMotPrims, "%d", &dTemp) == 0) { + return false; + } + if (dTemp != EnvNAVXYTHETALATCfg.NumThetaDirs) { + SBPL_ERROR("ERROR: invalid angular resolution %d angles (instead of %d angles) in the motion primitives file\n", dTemp, EnvNAVXYTHETALATCfg.NumThetaDirs); + return false; + } + SBPL_PRINTF("numberofangles: %d\n", dTemp); + EnvNAVXYTHETALATCfg.NumThetaDirs = dTemp; + + if (bUseNonUniformAngles) { + // read in angles + EnvNAVXYTHETALATCfg.ThetaDirs.clear(); + for (int i = 0; i < EnvNAVXYTHETALATCfg.NumThetaDirs; i++) + { + std::ostringstream string_angle_index; + string_angle_index << i; + std::string angle_string = "angle:" + string_angle_index.str(); + + float angle; + strcpy(sExpected, angle_string.c_str()); + if (fscanf(fMotPrims, "%s", sTemp) == 0) { + return false; + } + if (strcmp(sTemp, sExpected) != 0) { + SBPL_ERROR("ERROR: expected %s but got %s\n", sExpected, sTemp); + return false; + } + if (fscanf(fMotPrims, "%f", &angle) == 0) { + return false; + } + SBPL_PRINTF("%s %f\n", angle_string.c_str(), angle); + EnvNAVXYTHETALATCfg.ThetaDirs.push_back(angle); + } + EnvNAVXYTHETALATCfg.ThetaDirs.push_back(2.0 * M_PI); // Add 2 PI at end for overlap + } + + // read in the total number of actions + strcpy(sExpected, "totalnumberofprimitives:"); + if (fscanf(fMotPrims, "%s", sTemp) == 0) { + return false; + } + if (strcmp(sTemp, sExpected) != 0) { + SBPL_ERROR("ERROR: expected %s but got %s\n", sExpected, sTemp); + return false; + } + if (fscanf(fMotPrims, "%d", &totalNumofActions) == 0) { + return false; + } + SBPL_PRINTF("totalnumberofprimitives: %d\n", totalNumofActions); + + // Read in motion primitive for each action + for (int i = 0; i < totalNumofActions; i++) { + SBPL_xytheta_mprimitive motprim; + + if (!EnvironmentNAVXYTHETALATTICE::ReadinMotionPrimitive(&motprim, fMotPrims)) { + return false; + } + + EnvNAVXYTHETALATCfg.mprimV.push_back(motprim); + } + SBPL_PRINTF("done"); + SBPL_FFLUSH(stdout); + return true; +} + +void EnvironmentNAVXYTHETALATTICE::ComputeReplanningDataforAction( + EnvNAVXYTHETALATAction_t* action) +{ + int j; + + // iterate over all the cells involved in the action + sbpl_xy_theta_cell_t startcell3d, endcell3d; + for (int i = 0; i < (int)action->intersectingcellsV.size(); i++) { + // compute the translated affected search Pose - what state has an + // outgoing action whose intersecting cell is at 0,0 + startcell3d.theta = action->starttheta; + startcell3d.x = -action->intersectingcellsV.at(i).x; + startcell3d.y = -action->intersectingcellsV.at(i).y; + + // compute the translated affected search Pose - what state has an + // incoming action whose intersecting cell is at 0,0 + if (bUseNonUniformAngles) { + endcell3d.theta = normalizeDiscAngle(action->endtheta); + } + else { + endcell3d.theta = NORMALIZEDISCTHETA(action->endtheta, EnvNAVXYTHETALATCfg.NumThetaDirs); + } + endcell3d.x = startcell3d.x + action->dX; + endcell3d.y = startcell3d.y + action->dY; + + //store the cells if not already there + for (j = 0; j < (int)affectedsuccstatesV.size(); j++) { + if (affectedsuccstatesV.at(j) == endcell3d) { + break; + } + } + if (j == (int)affectedsuccstatesV.size()) { + affectedsuccstatesV.push_back(endcell3d); + } + + for (j = 0; j < (int)affectedpredstatesV.size(); j++) { + if (affectedpredstatesV.at(j) == startcell3d) { + break; + } + } + if (j == (int)affectedpredstatesV.size()) { + affectedpredstatesV.push_back(startcell3d); + } + } // over intersecting cells + + // add the centers since with h2d we are using these in cost computations + // ---intersecting cell = origin + // compute the translated affected search Pose - what state has an outgoing + // action whose intersecting cell is at 0,0 + startcell3d.theta = action->starttheta; + startcell3d.x = -0; + startcell3d.y = -0; + + // compute the translated affected search Pose - what state has an incoming + // action whose intersecting cell is at 0,0 + if (bUseNonUniformAngles) { + endcell3d.theta = normalizeDiscAngle(action->endtheta); + } + else { + endcell3d.theta = NORMALIZEDISCTHETA(action->endtheta, EnvNAVXYTHETALATCfg.NumThetaDirs); + } + endcell3d.x = startcell3d.x + action->dX; + endcell3d.y = startcell3d.y + action->dY; + + //store the cells if not already there + for (j = 0; j < (int)affectedsuccstatesV.size(); j++) { + if (affectedsuccstatesV.at(j) == endcell3d) { + break; + } + } + if (j == (int)affectedsuccstatesV.size()) { + affectedsuccstatesV.push_back(endcell3d); + } + + for (j = 0; j < (int)affectedpredstatesV.size(); j++) { + if (affectedpredstatesV.at(j) == startcell3d) { + break; + } + } + if (j == (int)affectedpredstatesV.size()) { + affectedpredstatesV.push_back(startcell3d); + } + + //---intersecting cell = outcome state + // compute the translated affected search Pose - what state has an outgoing + // action whose intersecting cell is at 0,0 + startcell3d.theta = action->starttheta; + startcell3d.x = -action->dX; + startcell3d.y = -action->dY; + + // compute the translated affected search Pose - what state has an incoming + // action whose intersecting cell is at 0,0 + if (bUseNonUniformAngles) { + endcell3d.theta = normalizeDiscAngle(action->endtheta); + } + else { + endcell3d.theta = NORMALIZEDISCTHETA(action->endtheta, EnvNAVXYTHETALATCfg.NumThetaDirs); + } + endcell3d.x = startcell3d.x + action->dX; + endcell3d.y = startcell3d.y + action->dY; + + for (j = 0; j < (int)affectedsuccstatesV.size(); j++) { + if (affectedsuccstatesV.at(j) == endcell3d) { + break; + } + } + if (j == (int)affectedsuccstatesV.size()) { + affectedsuccstatesV.push_back(endcell3d); + } + + for (j = 0; j < (int)affectedpredstatesV.size(); j++) { + if (affectedpredstatesV.at(j) == startcell3d) { + break; + } + } + if (j == (int)affectedpredstatesV.size()) { + affectedpredstatesV.push_back(startcell3d); + } +} + +// computes all the 3D states whose outgoing actions are potentially affected +// when cell (0,0) changes its status it also does the same for the 3D states +// whose incoming actions are potentially affected when cell (0,0) changes its +// status +void EnvironmentNAVXYTHETALATTICE::ComputeReplanningData() +{ + // iterate over all actions + // orientations + for (int tind = 0; tind < EnvNAVXYTHETALATCfg.NumThetaDirs; tind++) { + // actions + for (int aind = 0; aind < EnvNAVXYTHETALATCfg.actionwidth; aind++) { + // compute replanning data for this action + ComputeReplanningDataforAction(&EnvNAVXYTHETALATCfg.ActionsV[tind][aind]); + } + } +} + +// here motionprimitivevector contains actions only for 0 angle +void EnvironmentNAVXYTHETALATTICE::PrecomputeActionswithBaseMotionPrimitive( + std::vector* motionprimitiveV) +{ + SBPL_PRINTF("Pre-computing action data using base motion primitives...\n"); + EnvNAVXYTHETALATCfg.ActionsV = new EnvNAVXYTHETALATAction_t*[EnvNAVXYTHETALATCfg.NumThetaDirs]; + EnvNAVXYTHETALATCfg.PredActionsV = new std::vector [EnvNAVXYTHETALATCfg.NumThetaDirs]; + std::vector footprint; + + //iterate over source angles + for (int tind = 0; tind < EnvNAVXYTHETALATCfg.NumThetaDirs; tind++) { + SBPL_PRINTF("pre-computing for angle %d out of %d angles\n", tind, EnvNAVXYTHETALATCfg.NumThetaDirs); + EnvNAVXYTHETALATCfg.ActionsV[tind] = new EnvNAVXYTHETALATAction_t[motionprimitiveV->size()]; + + //compute sourcepose + sbpl_xy_theta_pt_t sourcepose; + sourcepose.x = DISCXY2CONT(0, EnvNAVXYTHETALATCfg.cellsize_m); + sourcepose.y = DISCXY2CONT(0, EnvNAVXYTHETALATCfg.cellsize_m); + sourcepose.theta = DiscTheta2ContNew(tind); + //sourcepose.theta = DiscTheta2Cont(tind, EnvNAVXYTHETALATCfg.NumThetaDirs); + + //iterate over motion primitives + for (size_t aind = 0; aind < motionprimitiveV->size(); aind++) { + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].aind = aind; + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].starttheta = tind; + double mp_endx_m = motionprimitiveV->at(aind).intermptV[motionprimitiveV->at(aind).intermptV.size() - 1].x; + double mp_endy_m = motionprimitiveV->at(aind).intermptV[motionprimitiveV->at(aind).intermptV.size() - 1].y; + double mp_endtheta_rad = + motionprimitiveV->at(aind).intermptV[motionprimitiveV->at(aind).intermptV.size() - 1].theta; + + double endx = sourcepose.x + (mp_endx_m * cos(sourcepose.theta) - mp_endy_m * sin(sourcepose.theta)); + double endy = sourcepose.y + (mp_endx_m * sin(sourcepose.theta) + mp_endy_m * cos(sourcepose.theta)); + + int endx_c = CONTXY2DISC(endx, EnvNAVXYTHETALATCfg.cellsize_m); + int endy_c = CONTXY2DISC(endy, EnvNAVXYTHETALATCfg.cellsize_m); + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].endtheta = ContTheta2DiscNew(mp_endtheta_rad + sourcepose.theta); + //EnvNAVXYTHETALATCfg.ActionsV[tind][aind].endtheta = ContTheta2Disc(mp_endtheta_rad + sourcepose.theta, EnvNAVXYTHETALATCfg.NumThetaDirs); + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].dX = endx_c; + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].dY = endy_c; + + if (EnvNAVXYTHETALATCfg.ActionsV[tind][aind].dY != 0 || EnvNAVXYTHETALATCfg.ActionsV[tind][aind].dX != 0) + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].cost = (int)(ceil(NAVXYTHETALAT_COSTMULT_MTOMM + * EnvNAVXYTHETALATCfg.cellsize_m / EnvNAVXYTHETALATCfg.nominalvel_mpersecs + * sqrt((double)(EnvNAVXYTHETALATCfg.ActionsV[tind][aind].dX + * EnvNAVXYTHETALATCfg.ActionsV[tind][aind].dX + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].dY + * EnvNAVXYTHETALATCfg.ActionsV[tind][aind].dY)))); + else + //cost of turn in place + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].cost = (int)(NAVXYTHETALAT_COSTMULT_MTOMM + * EnvNAVXYTHETALATCfg.timetoturn45degsinplace_secs + * fabs(computeMinUnsignedAngleDiff(mp_endtheta_rad, 0)) / (PI_CONST / 4.0)); + + //compute and store interm points as well as intersecting cells + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].intersectingcellsV.clear(); + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].intermptV.clear(); + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].interm3DcellsV.clear(); + sbpl_xy_theta_cell_t previnterm3Dcell; + previnterm3Dcell.theta = previnterm3Dcell.x = previnterm3Dcell.y = 0; + + for (int pind = 0; pind < (int)motionprimitiveV->at(aind).intermptV.size(); pind++) { + sbpl_xy_theta_pt_t intermpt = motionprimitiveV->at(aind).intermptV[pind]; + + //rotate it appropriately + double rotx = intermpt.x * cos(sourcepose.theta) - intermpt.y * sin(sourcepose.theta); + double roty = intermpt.x * sin(sourcepose.theta) + intermpt.y * cos(sourcepose.theta); + intermpt.x = rotx; + intermpt.y = roty; + intermpt.theta = normalizeAngle(sourcepose.theta + intermpt.theta); + + //store it (they are with reference to 0,0,stattheta (not + //sourcepose.x,sourcepose.y,starttheta (that is, half-bin)) + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].intermptV.push_back(intermpt); + } + //now compute the intersecting cells for this motion (including ignoring the source footprint) + get_2d_motion_cells(EnvNAVXYTHETALATCfg.FootprintPolygon, + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].intermptV, + &EnvNAVXYTHETALATCfg.ActionsV[tind][aind].intersectingcellsV, + EnvNAVXYTHETALATCfg.cellsize_m); + +#if DEBUG + SBPL_FPRINTF(fDeb, + "action tind=%d aind=%d: dX=%d dY=%d endtheta=%d (%.2f degs -> %.2f degs) " + "cost=%d (mprim: %.2f %.2f %.2f)\n", + tind, + (int)aind, + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].dX, + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].dY, + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].endtheta, + sourcepose.theta * 180.0 / PI_CONST, + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].intermptV[EnvNAVXYTHETALATCfg.ActionsV[tind][aind].intermptV.size() - 1].theta * 180.0 / PI_CONST, + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].cost, + mp_endx_m, + mp_endy_m, + mp_endtheta_rad); +#endif + + //add to the list of backward actions + int targettheta = EnvNAVXYTHETALATCfg.ActionsV[tind][aind].endtheta; + if (targettheta < 0) targettheta = targettheta + EnvNAVXYTHETALATCfg.NumThetaDirs; + EnvNAVXYTHETALATCfg.PredActionsV[targettheta].push_back(&(EnvNAVXYTHETALATCfg.ActionsV[tind][aind])); + } + } + + //set number of actions + EnvNAVXYTHETALATCfg.actionwidth = motionprimitiveV->size(); + + //now compute replanning data + ComputeReplanningData(); + + SBPL_PRINTF("done pre-computing action data based on motion primitives\n"); +} + +// here motionprimitivevector contains actions for all angles +void EnvironmentNAVXYTHETALATTICE::PrecomputeActionswithCompleteMotionPrimitive( + std::vector* motionprimitiveV) +{ + SBPL_PRINTF("Pre-computing action data using motion primitives for every angle...\n"); + EnvNAVXYTHETALATCfg.ActionsV = new EnvNAVXYTHETALATAction_t*[EnvNAVXYTHETALATCfg.NumThetaDirs]; + EnvNAVXYTHETALATCfg.PredActionsV = new std::vector[EnvNAVXYTHETALATCfg.NumThetaDirs]; + std::vector footprint; + + if (motionprimitiveV->size() % EnvNAVXYTHETALATCfg.NumThetaDirs != 0) { + throw SBPL_Exception("ERROR: motionprimitives should be uniform across actions"); + } + + EnvNAVXYTHETALATCfg.actionwidth = ((int)motionprimitiveV->size()) / EnvNAVXYTHETALATCfg.NumThetaDirs; + + // iterate over source angles + int maxnumofactions = 0; + for (int tind = 0; tind < EnvNAVXYTHETALATCfg.NumThetaDirs; tind++) { + SBPL_PRINTF("pre-computing for angle %d out of %d angles\n", tind, EnvNAVXYTHETALATCfg.NumThetaDirs); + + EnvNAVXYTHETALATCfg.ActionsV[tind] = new EnvNAVXYTHETALATAction_t[EnvNAVXYTHETALATCfg.actionwidth]; + + // compute sourcepose + sbpl_xy_theta_pt_t sourcepose; + sourcepose.x = DISCXY2CONT(0, EnvNAVXYTHETALATCfg.cellsize_m); + sourcepose.y = DISCXY2CONT(0, EnvNAVXYTHETALATCfg.cellsize_m); + sourcepose.theta = DiscTheta2ContNew(tind); + + // iterate over motion primitives + int numofactions = 0; + int aind = -1; + for (int mind = 0; mind < (int)motionprimitiveV->size(); mind++) { + //find a motion primitive for this angle + if (motionprimitiveV->at(mind).starttheta_c != tind) { + continue; + } + + aind++; + numofactions++; + + // action index + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].aind = aind; + + // start angle + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].starttheta = tind; + + // compute dislocation + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].endtheta = motionprimitiveV->at(mind).endcell.theta; + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].dX = motionprimitiveV->at(mind).endcell.x; + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].dY = motionprimitiveV->at(mind).endcell.y; + + // compute and store interm points as well as intersecting cells + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].intersectingcellsV.clear(); + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].intermptV.clear(); + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].interm3DcellsV.clear(); + + sbpl_xy_theta_cell_t previnterm3Dcell; + previnterm3Dcell.x = 0; + previnterm3Dcell.y = 0; + + // Compute all the intersected cells for this action (intermptV and interm3DcellsV) + for (int pind = 0; pind < (int)motionprimitiveV->at(mind).intermptV.size(); pind++) { + sbpl_xy_theta_pt_t intermpt = motionprimitiveV->at(mind).intermptV[pind]; + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].intermptV.push_back(intermpt); + + // also compute the intermediate discrete cells if not there already + sbpl_xy_theta_pt_t pose; + pose.x = intermpt.x + sourcepose.x; + pose.y = intermpt.y + sourcepose.y; + pose.theta = intermpt.theta; + + sbpl_xy_theta_cell_t intermediate2dCell; + intermediate2dCell.x = CONTXY2DISC(pose.x, EnvNAVXYTHETALATCfg.cellsize_m); + intermediate2dCell.y = CONTXY2DISC(pose.y, EnvNAVXYTHETALATCfg.cellsize_m); + + // add unique cells to the list + if (EnvNAVXYTHETALATCfg.ActionsV[tind][aind].interm3DcellsV.size() == 0 || + intermediate2dCell.x != previnterm3Dcell.x || + intermediate2dCell.y != previnterm3Dcell.y) + { + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].interm3DcellsV.push_back(intermediate2dCell); + } + + previnterm3Dcell = intermediate2dCell; + } + + // compute linear and angular time + double linear_distance = 0; + for (unsigned int i = 1; i < EnvNAVXYTHETALATCfg.ActionsV[tind][aind].intermptV.size(); i++) { + double x0 = EnvNAVXYTHETALATCfg.ActionsV[tind][aind].intermptV[i - 1].x; + double y0 = EnvNAVXYTHETALATCfg.ActionsV[tind][aind].intermptV[i - 1].y; + double x1 = EnvNAVXYTHETALATCfg.ActionsV[tind][aind].intermptV[i].x; + double y1 = EnvNAVXYTHETALATCfg.ActionsV[tind][aind].intermptV[i].y; + double dx = x1 - x0; + double dy = y1 - y0; + linear_distance += sqrt(dx * dx + dy * dy); + } + double linear_time = linear_distance / EnvNAVXYTHETALATCfg.nominalvel_mpersecs; + double angular_distance; + angular_distance = fabs(computeMinUnsignedAngleDiff( + DiscTheta2ContNew(EnvNAVXYTHETALATCfg.ActionsV[tind][aind].endtheta), + DiscTheta2ContNew(EnvNAVXYTHETALATCfg.ActionsV[tind][aind].starttheta))); + + double angular_time = angular_distance / ((PI_CONST / 4.0) / + EnvNAVXYTHETALATCfg.timetoturn45degsinplace_secs); + // make the cost the max of the two times + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].cost = + (int)(ceil(NAVXYTHETALAT_COSTMULT_MTOMM * std::max(linear_time, angular_time))); + // use any additional cost multiplier + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].cost *= motionprimitiveV->at(mind).additionalactioncostmult; + + // now compute the intersecting cells for this motion (including ignoring the source footprint) + get_2d_motion_cells( + EnvNAVXYTHETALATCfg.FootprintPolygon, + motionprimitiveV->at(mind).intermptV, + &EnvNAVXYTHETALATCfg.ActionsV[tind][aind].intersectingcellsV, + EnvNAVXYTHETALATCfg.cellsize_m); + +#if DEBUG + SBPL_FPRINTF(fDeb, + "action tind=%2d aind=%2d: dX=%3d dY=%3d endtheta=%3d (%6.2f degs -> %6.2f degs) " + "cost=%4d (mprimID %3d: %3d %3d %3d) numofintermcells = %d numofintercells=%d\n", + tind, + aind, + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].dX, + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].dY, + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].endtheta, + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].intermptV[0].theta * 180 / PI_CONST, + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].intermptV[EnvNAVXYTHETALATCfg.ActionsV[tind][aind].intermptV.size() - 1].theta * 180 / PI_CONST, EnvNAVXYTHETALATCfg.ActionsV[tind][aind].cost, + motionprimitiveV->at(mind).motprimID, motionprimitiveV->at(mind).endcell.x, + motionprimitiveV->at(mind).endcell.y, motionprimitiveV->at(mind).endcell.theta, + (int)EnvNAVXYTHETALATCfg.ActionsV[tind][aind].interm3DcellsV.size(), + (int)EnvNAVXYTHETALATCfg.ActionsV[tind][aind].intersectingcellsV.size()); +#endif + + // add to the list of backward actions + int targettheta = EnvNAVXYTHETALATCfg.ActionsV[tind][aind].endtheta; + if (targettheta < 0) { + targettheta = targettheta + EnvNAVXYTHETALATCfg.NumThetaDirs; + } + EnvNAVXYTHETALATCfg.PredActionsV[targettheta].push_back(&(EnvNAVXYTHETALATCfg.ActionsV[tind][aind])); + } + + if (maxnumofactions < numofactions) { + maxnumofactions = numofactions; + } + } + + // at this point we don't allow nonuniform number of actions + if (motionprimitiveV->size() != (size_t)(EnvNAVXYTHETALATCfg.NumThetaDirs * maxnumofactions)) { + std::stringstream ss; + ss << "ERROR: nonuniform number of actions is not supported" << + " (maxnumofactions=" << maxnumofactions << " while motprims=" << + motionprimitiveV->size() << " thetas=" << + EnvNAVXYTHETALATCfg.NumThetaDirs; + throw SBPL_Exception(ss.str()); + } + + // now compute replanning data + ComputeReplanningData(); + + SBPL_PRINTF("done pre-computing action data based on motion primitives\n"); +} + +void EnvironmentNAVXYTHETALATTICE::DeprecatedPrecomputeActions() +{ + SBPL_PRINTF("Use of DeprecatedPrecomputeActions() is deprecated and probably doesn't work!\n"); + + // construct list of actions + SBPL_PRINTF("Pre-computing action data using the motion primitives for a 3D kinematic planning...\n"); + EnvNAVXYTHETALATCfg.ActionsV = new EnvNAVXYTHETALATAction_t*[EnvNAVXYTHETALATCfg.NumThetaDirs]; + EnvNAVXYTHETALATCfg.PredActionsV = new std::vector [EnvNAVXYTHETALATCfg.NumThetaDirs]; + std::vector footprint; + // iterate over source angles + for (int tind = 0; tind < EnvNAVXYTHETALATCfg.NumThetaDirs; tind++) { + SBPL_PRINTF("processing angle %d\n", tind); + EnvNAVXYTHETALATCfg.ActionsV[tind] = new EnvNAVXYTHETALATAction_t[EnvNAVXYTHETALATCfg.actionwidth]; + + // compute sourcepose + sbpl_xy_theta_pt_t sourcepose; + sourcepose.x = DISCXY2CONT(0, EnvNAVXYTHETALATCfg.cellsize_m); + sourcepose.y = DISCXY2CONT(0, EnvNAVXYTHETALATCfg.cellsize_m); + sourcepose.theta = DiscTheta2ContNew(tind); + + // the construction assumes that the robot first turns and then goes + // along this new theta + int aind = 0; + for (; aind < 3; aind++) { + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].aind = aind; + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].starttheta = tind; + // -1,0,1 + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].endtheta = (tind + aind - 1) % EnvNAVXYTHETALATCfg.NumThetaDirs; + double angle = DiscTheta2ContNew(EnvNAVXYTHETALATCfg.ActionsV[tind][aind].endtheta); + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].dX = (int)(cos(angle) + 0.5 * (cos(angle) > 0 ? 1 : -1)); + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].dY = (int)(sin(angle) + 0.5 * (sin(angle) > 0 ? 1 : -1)); + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].cost = (int)(ceil(NAVXYTHETALAT_COSTMULT_MTOMM * + EnvNAVXYTHETALATCfg.cellsize_m / EnvNAVXYTHETALATCfg.nominalvel_mpersecs * + sqrt((double)(EnvNAVXYTHETALATCfg.ActionsV[tind][aind].dX * + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].dX + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].dY * + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].dY)))); + + // compute intersecting cells + sbpl_xy_theta_pt_t pose; + pose.x = DISCXY2CONT(EnvNAVXYTHETALATCfg.ActionsV[tind][aind].dX, EnvNAVXYTHETALATCfg.cellsize_m); + pose.y = DISCXY2CONT(EnvNAVXYTHETALATCfg.ActionsV[tind][aind].dY, EnvNAVXYTHETALATCfg.cellsize_m); + pose.theta = angle; + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].intermptV.clear(); + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].intersectingcellsV.clear(); + get_2d_footprint_cells( + EnvNAVXYTHETALATCfg.FootprintPolygon, + &EnvNAVXYTHETALATCfg.ActionsV[tind][aind].intersectingcellsV, + pose, + EnvNAVXYTHETALATCfg.cellsize_m); + RemoveSourceFootprint(sourcepose, &EnvNAVXYTHETALATCfg.ActionsV[tind][aind].intersectingcellsV); + +#if DEBUG + SBPL_PRINTF("action tind=%d aind=%d: endtheta=%d (%f) dX=%d dY=%d cost=%d\n", + tind, aind, EnvNAVXYTHETALATCfg.ActionsV[tind][aind].endtheta, angle, + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].dX, EnvNAVXYTHETALATCfg.ActionsV[tind][aind].dY, + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].cost); +#endif + + // add to the list of backward actions + int targettheta = EnvNAVXYTHETALATCfg.ActionsV[tind][aind].endtheta; + if (targettheta < 0) { + targettheta = targettheta + EnvNAVXYTHETALATCfg.NumThetaDirs; + } + EnvNAVXYTHETALATCfg.PredActionsV[targettheta].push_back(&(EnvNAVXYTHETALATCfg.ActionsV[tind][aind])); + } + + // decrease and increase angle without movement + aind = 3; + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].aind = aind; + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].starttheta = tind; + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].endtheta = tind - 1; + if (EnvNAVXYTHETALATCfg.ActionsV[tind][aind].endtheta < 0) { + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].endtheta += EnvNAVXYTHETALATCfg.NumThetaDirs; + } + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].dX = 0; + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].dY = 0; + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].cost = + (int)(NAVXYTHETALAT_COSTMULT_MTOMM * EnvNAVXYTHETALATCfg.timetoturn45degsinplace_secs); + + // compute intersecting cells + sbpl_xy_theta_pt_t pose; + pose.x = DISCXY2CONT(EnvNAVXYTHETALATCfg.ActionsV[tind][aind].dX, EnvNAVXYTHETALATCfg.cellsize_m); + pose.y = DISCXY2CONT(EnvNAVXYTHETALATCfg.ActionsV[tind][aind].dY, EnvNAVXYTHETALATCfg.cellsize_m); + pose.theta = DiscTheta2ContNew(EnvNAVXYTHETALATCfg.ActionsV[tind][aind].endtheta); + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].intermptV.clear(); + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].intersectingcellsV.clear(); + get_2d_footprint_cells( + EnvNAVXYTHETALATCfg.FootprintPolygon, + &EnvNAVXYTHETALATCfg.ActionsV[tind][aind].intersectingcellsV, + pose, + EnvNAVXYTHETALATCfg.cellsize_m); + RemoveSourceFootprint(sourcepose, &EnvNAVXYTHETALATCfg.ActionsV[tind][aind].intersectingcellsV); + +#if DEBUG + SBPL_PRINTF("action tind=%d aind=%d: endtheta=%d (%f) dX=%d dY=%d cost=%d\n", + tind, aind, EnvNAVXYTHETALATCfg.ActionsV[tind][aind].endtheta, + DiscTheta2ContNew(EnvNAVXYTHETALATCfg.ActionsV[tind][aind].endtheta), + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].dX, EnvNAVXYTHETALATCfg.ActionsV[tind][aind].dY, + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].cost); +#endif + + // add to the list of backward actions + int targettheta = EnvNAVXYTHETALATCfg.ActionsV[tind][aind].endtheta; + if (targettheta < 0) { + targettheta = targettheta + EnvNAVXYTHETALATCfg.NumThetaDirs; + } + EnvNAVXYTHETALATCfg.PredActionsV[targettheta].push_back(&(EnvNAVXYTHETALATCfg.ActionsV[tind][aind])); + + aind = 4; + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].aind = aind; + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].starttheta = tind; + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].endtheta = (tind + 1) % EnvNAVXYTHETALATCfg.NumThetaDirs; + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].dX = 0; + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].dY = 0; + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].cost = + (int)(NAVXYTHETALAT_COSTMULT_MTOMM * EnvNAVXYTHETALATCfg.timetoturn45degsinplace_secs); + + // compute intersecting cells + pose.x = DISCXY2CONT(EnvNAVXYTHETALATCfg.ActionsV[tind][aind].dX, EnvNAVXYTHETALATCfg.cellsize_m); + pose.y = DISCXY2CONT(EnvNAVXYTHETALATCfg.ActionsV[tind][aind].dY, EnvNAVXYTHETALATCfg.cellsize_m); + pose.theta = DiscTheta2ContNew(EnvNAVXYTHETALATCfg.ActionsV[tind][aind].endtheta); + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].intermptV.clear(); + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].intersectingcellsV.clear(); + get_2d_footprint_cells( + EnvNAVXYTHETALATCfg.FootprintPolygon, + &EnvNAVXYTHETALATCfg.ActionsV[tind][aind].intersectingcellsV, + pose, + EnvNAVXYTHETALATCfg.cellsize_m); + RemoveSourceFootprint(sourcepose, &EnvNAVXYTHETALATCfg.ActionsV[tind][aind].intersectingcellsV); + +#if DEBUG + SBPL_PRINTF("action tind=%d aind=%d: endtheta=%d (%f) dX=%d dY=%d cost=%d\n", + tind, aind, EnvNAVXYTHETALATCfg.ActionsV[tind][aind].endtheta, DiscTheta2ContNew(EnvNAVXYTHETALATCfg.ActionsV[tind][aind].endtheta), + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].dX, EnvNAVXYTHETALATCfg.ActionsV[tind][aind].dY, + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].cost); +#endif + + // add to the list of backward actions + targettheta = EnvNAVXYTHETALATCfg.ActionsV[tind][aind].endtheta; + if (targettheta < 0) targettheta = targettheta + EnvNAVXYTHETALATCfg.NumThetaDirs; + EnvNAVXYTHETALATCfg.PredActionsV[targettheta].push_back(&(EnvNAVXYTHETALATCfg.ActionsV[tind][aind])); + } + + // now compute replanning data + ComputeReplanningData(); + + SBPL_PRINTF("done pre-computing action data\n"); +} + +void EnvironmentNAVXYTHETALATTICE::InitializeEnvConfig(std::vector* motionprimitiveV) +{ + // additional to configuration file initialization of EnvNAVXYTHETALATCfg if + // necessary + + // dXY dirs + EnvNAVXYTHETALATCfg.dXY[0][0] = -1; + EnvNAVXYTHETALATCfg.dXY[0][1] = -1; + EnvNAVXYTHETALATCfg.dXY[1][0] = -1; + EnvNAVXYTHETALATCfg.dXY[1][1] = 0; + EnvNAVXYTHETALATCfg.dXY[2][0] = -1; + EnvNAVXYTHETALATCfg.dXY[2][1] = 1; + EnvNAVXYTHETALATCfg.dXY[3][0] = 0; + EnvNAVXYTHETALATCfg.dXY[3][1] = -1; + EnvNAVXYTHETALATCfg.dXY[4][0] = 0; + EnvNAVXYTHETALATCfg.dXY[4][1] = 1; + EnvNAVXYTHETALATCfg.dXY[5][0] = 1; + EnvNAVXYTHETALATCfg.dXY[5][1] = -1; + EnvNAVXYTHETALATCfg.dXY[6][0] = 1; + EnvNAVXYTHETALATCfg.dXY[6][1] = 0; + EnvNAVXYTHETALATCfg.dXY[7][0] = 1; + EnvNAVXYTHETALATCfg.dXY[7][1] = 1; + + sbpl_xy_theta_pt_t temppose; + temppose.x = 0.0; + temppose.y = 0.0; + temppose.theta = 0.0; + std::vector footprint; + get_2d_footprint_cells( + EnvNAVXYTHETALATCfg.FootprintPolygon, + &footprint, + temppose, + EnvNAVXYTHETALATCfg.cellsize_m); + SBPL_PRINTF("number of cells in footprint of the robot = %d\n", (unsigned int)footprint.size()); + + for (std::vector::iterator it = footprint.begin(); it != footprint.end(); ++it) { + SBPL_PRINTF("Footprint cell at (%d, %d)\n", it->x, it->y); + } + +#if DEBUG + SBPL_FPRINTF(fDeb, "footprint cells (size=%d):\n", (int)footprint.size()); + for(int i = 0; i < (int) footprint.size(); i++) + { + SBPL_FPRINTF(fDeb, "%d %d (cont: %.3f %.3f)\n", footprint.at(i).x, footprint.at(i).y, + DISCXY2CONT(footprint.at(i).x, EnvNAVXYTHETALATCfg.cellsize_m), + DISCXY2CONT(footprint.at(i).y, EnvNAVXYTHETALATCfg.cellsize_m)); + } +#endif + + if (motionprimitiveV == NULL) { + DeprecatedPrecomputeActions(); + } + else { + PrecomputeActionswithCompleteMotionPrimitive(motionprimitiveV); + } +} + +bool EnvironmentNAVXYTHETALATTICE::IsValidCell(int X, int Y) +{ + return (X >= 0 && X < EnvNAVXYTHETALATCfg.EnvWidth_c && + Y >= 0 && Y < EnvNAVXYTHETALATCfg.EnvHeight_c && + EnvNAVXYTHETALATCfg.Grid2D[X][Y] < EnvNAVXYTHETALATCfg.obsthresh); +} + +bool EnvironmentNAVXYTHETALATTICE::IsWithinMapCell(int X, int Y) +{ + return (X >= 0 && X < EnvNAVXYTHETALATCfg.EnvWidth_c && + Y >= 0 && Y < EnvNAVXYTHETALATCfg.EnvHeight_c); +} + +bool EnvironmentNAVXYTHETALATTICE::IsValidConfiguration(int X, int Y, int Theta) +{ + std::vector footprint; + sbpl_xy_theta_pt_t pose; + + // compute continuous pose + pose.x = DISCXY2CONT(X, EnvNAVXYTHETALATCfg.cellsize_m); + pose.y = DISCXY2CONT(Y, EnvNAVXYTHETALATCfg.cellsize_m); + pose.theta = DiscTheta2ContNew(Theta); + + // compute footprint cells + get_2d_footprint_cells( + EnvNAVXYTHETALATCfg.FootprintPolygon, + &footprint, + pose, + EnvNAVXYTHETALATCfg.cellsize_m); + + // iterate over all footprint cells + for (int find = 0; find < (int)footprint.size(); find++) { + int x = footprint.at(find).x; + int y = footprint.at(find).y; + + if (x < 0 || x >= EnvNAVXYTHETALATCfg.EnvWidth_c || + y < 0 || y >= EnvNAVXYTHETALATCfg.EnvHeight_c || + EnvNAVXYTHETALATCfg.Grid2D[x][y] >= EnvNAVXYTHETALATCfg.obsthresh) + { + return false; + } + } + + return true; +} + +int EnvironmentNAVXYTHETALATTICE::GetActionCost( + int SourceX, int SourceY, int SourceTheta, + EnvNAVXYTHETALATAction_t* action) +{ + sbpl_2Dcell_t cell; + sbpl_xy_theta_cell_t interm3Dcell; + int i; + + // TODO - go over bounding box (minpt and maxpt) to test validity and skip + // testing boundaries below, also order intersect cells so that the four + // farthest pts go first + + if (!IsValidCell(SourceX, SourceY)) { + return INFINITECOST; + } + if (!IsValidCell(SourceX + action->dX, SourceY + action->dY)) { + return INFINITECOST; + } + + if (EnvNAVXYTHETALATCfg.Grid2D[SourceX + action->dX][SourceY + action->dY] >= + EnvNAVXYTHETALATCfg.cost_inscribed_thresh) + { + return INFINITECOST; + } + + // need to iterate over discretized center cells and compute cost based on them + unsigned char maxcellcost = 0; + for (i = 0; i < (int)action->interm3DcellsV.size(); i++) { + interm3Dcell = action->interm3DcellsV.at(i); + interm3Dcell.x = interm3Dcell.x + SourceX; + interm3Dcell.y = interm3Dcell.y + SourceY; + + if (interm3Dcell.x < 0 || interm3Dcell.x >= EnvNAVXYTHETALATCfg.EnvWidth_c || + interm3Dcell.y < 0 || interm3Dcell.y >= EnvNAVXYTHETALATCfg.EnvHeight_c) + { + return INFINITECOST; + } + + maxcellcost = __max(maxcellcost, EnvNAVXYTHETALATCfg.Grid2D[interm3Dcell.x][interm3Dcell.y]); + + // check that the robot is NOT in the cell at which there is no valid orientation + if (maxcellcost >= EnvNAVXYTHETALATCfg.cost_inscribed_thresh) { + return INFINITECOST; + } + } + + // check collisions that for the particular footprint orientation along the action + if (EnvNAVXYTHETALATCfg.FootprintPolygon.size() > 1 && + (int)maxcellcost >= EnvNAVXYTHETALATCfg.cost_possibly_circumscribed_thresh) + { + checks++; + + for (i = 0; i < (int)action->intersectingcellsV.size(); i++) { + // get the cell in the map + cell = action->intersectingcellsV.at(i); + cell.x = cell.x + SourceX; + cell.y = cell.y + SourceY; + + // check validity + if (!IsValidCell(cell.x, cell.y)) { + return INFINITECOST; + } + +// cost computation changed: cost = max(cost of centers of the robot along +// action) intersecting cells are only used for collision checking +// if (EnvNAVXYTHETALATCfg.Grid2D[cell.x][cell.y] > currentmaxcost) { +// currentmaxcost = EnvNAVXYTHETALATCfg.Grid2D[cell.x][cell.y]; +// } + } + } + + // to ensure consistency of h2D: + maxcellcost = __max(maxcellcost, EnvNAVXYTHETALATCfg.Grid2D[SourceX][SourceY]); + int currentmaxcost = (int)__max( + maxcellcost, + EnvNAVXYTHETALATCfg.Grid2D[SourceX + action->dX][SourceY + action->dY]); + + // use cell cost as multiplicative factor + return action->cost * (currentmaxcost + 1); +} + +double EnvironmentNAVXYTHETALATTICE::EuclideanDistance_m(int X1, int Y1, int X2, int Y2) +{ + int sqdist = ((X1 - X2) * (X1 - X2) + (Y1 - Y2) * (Y1 - Y2)); + return EnvNAVXYTHETALATCfg.cellsize_m * sqrt((double)sqdist); +} + +// calculates a set of cells that correspond to the specified footprint adds +// points to it (does not clear it beforehand) +void EnvironmentNAVXYTHETALATTICE::CalculateFootprintForPose( + sbpl_xy_theta_pt_t pose, std::vector* footprint, + const std::vector& FootprintPolygon) +{ + int pind; + + // handle special case where footprint is just a point + if (FootprintPolygon.size() <= 1) { + sbpl_2Dcell_t cell; + cell.x = CONTXY2DISC(pose.x, EnvNAVXYTHETALATCfg.cellsize_m); + cell.y = CONTXY2DISC(pose.y, EnvNAVXYTHETALATCfg.cellsize_m); + + for (pind = 0; pind < (int)footprint->size(); pind++) { + if (cell.x == footprint->at(pind).x && cell.y == footprint->at(pind).y) break; + } + if (pind == (int)footprint->size()) { + footprint->push_back(cell); + } + return; + } + + std::vector bounding_polygon; + unsigned int find; + double max_x = -INFINITECOST, min_x = INFINITECOST, max_y = -INFINITECOST, min_y = INFINITECOST; + sbpl_2Dpt_t pt(0, 0); + for (find = 0; find < FootprintPolygon.size(); find++) { + // rotate and translate the corner of the robot + pt = FootprintPolygon[find]; + + // rotate and translate the point + sbpl_2Dpt_t corner; + corner.x = cos(pose.theta) * pt.x - sin(pose.theta) * pt.y + pose.x; + corner.y = sin(pose.theta) * pt.x + cos(pose.theta) * pt.y + pose.y; + bounding_polygon.push_back(corner); + if (corner.x < min_x || find == 0) { + min_x = corner.x; + } + if (corner.x > max_x || find == 0) { + max_x = corner.x; + } + if (corner.y < min_y || find == 0) { + min_y = corner.y; + } + if (corner.y > max_y || find == 0) { + max_y = corner.y; + } + } + + // initialize previous values to something that will fail the if condition + // during the first iteration in the for loop + int prev_discrete_x = CONTXY2DISC(pt.x, EnvNAVXYTHETALATCfg.cellsize_m) + 1; + int prev_discrete_y = CONTXY2DISC(pt.y, EnvNAVXYTHETALATCfg.cellsize_m) + 1; + int prev_inside = 0; + int discrete_x; + int discrete_y; + + for (double x = min_x; x <= max_x; x += EnvNAVXYTHETALATCfg.cellsize_m / 3) { + for (double y = min_y; y <= max_y; y += EnvNAVXYTHETALATCfg.cellsize_m / 3) { + pt.x = x; + pt.y = y; + discrete_x = CONTXY2DISC(pt.x, EnvNAVXYTHETALATCfg.cellsize_m); + discrete_y = CONTXY2DISC(pt.y, EnvNAVXYTHETALATCfg.cellsize_m); + + // see if we just tested this point + if (discrete_x != prev_discrete_x || discrete_y != prev_discrete_y || prev_inside == 0) { + + if (IsInsideFootprint(pt, &bounding_polygon)) { + // convert to a grid point + + sbpl_2Dcell_t cell; + cell.x = discrete_x; + cell.y = discrete_y; + + // insert point if not there already + for (pind = 0; pind < (int)footprint->size(); pind++) { + if (cell.x == footprint->at(pind).x && cell.y == footprint->at(pind).y) break; + } + if (pind == (int)footprint->size()) { + footprint->push_back(cell); + } + + prev_inside = 1; + + } + else { + prev_inside = 0; + } + + } + else { + + } + + prev_discrete_x = discrete_x; + prev_discrete_y = discrete_y; + } // over x_min...x_max + } +} + +// calculates a set of cells that correspond to the footprint of the base adds +// points to it (does not clear it beforehand) +void EnvironmentNAVXYTHETALATTICE::CalculateFootprintForPose( + sbpl_xy_theta_pt_t pose, + std::vector* footprint) +{ + CalculateFootprintForPose(pose, footprint, EnvNAVXYTHETALATCfg.FootprintPolygon); +} + +// removes a set of cells that correspond to the specified footprint at the +// sourcepose adds points to it (does not clear it beforehand) +void EnvironmentNAVXYTHETALATTICE::RemoveSourceFootprint( + sbpl_xy_theta_pt_t sourcepose, + std::vector* footprint, + const std::vector& FootprintPolygon) +{ + std::vector sourcefootprint; + + // compute source footprint + get_2d_footprint_cells(FootprintPolygon, &sourcefootprint, sourcepose, EnvNAVXYTHETALATCfg.cellsize_m); + + // now remove the source cells from the footprint + for (int sind = 0; sind < (int)sourcefootprint.size(); sind++) { + for (int find = 0; find < (int)footprint->size(); find++) { + if (sourcefootprint.at(sind).x == footprint->at(find).x && sourcefootprint.at(sind).y + == footprint->at(find).y) { + footprint->erase(footprint->begin() + find); + break; + } + } // over footprint + } // over source +} + +// removes a set of cells that correspond to the footprint of the base at the +// sourcepose adds points to it (does not clear it beforehand) +void EnvironmentNAVXYTHETALATTICE::RemoveSourceFootprint( + sbpl_xy_theta_pt_t sourcepose, + std::vector* footprint) +{ + RemoveSourceFootprint(sourcepose, footprint, EnvNAVXYTHETALATCfg.FootprintPolygon); +} + +void EnvironmentNAVXYTHETALATTICE::EnsureHeuristicsUpdated(bool bGoalHeuristics) +{ + if (bNeedtoRecomputeStartHeuristics && !bGoalHeuristics) { + grid2Dsearchfromstart->search( + EnvNAVXYTHETALATCfg.Grid2D, + EnvNAVXYTHETALATCfg.cost_inscribed_thresh, + EnvNAVXYTHETALATCfg.StartX_c, EnvNAVXYTHETALATCfg.StartY_c, + EnvNAVXYTHETALATCfg.EndX_c, EnvNAVXYTHETALATCfg.EndY_c, + SBPL_2DGRIDSEARCH_TERM_CONDITION_TWOTIMESOPTPATH); + bNeedtoRecomputeStartHeuristics = false; + SBPL_PRINTF("2dsolcost_infullunits=%d\n", (int)(grid2Dsearchfromstart->getlowerboundoncostfromstart_inmm(EnvNAVXYTHETALATCfg.EndX_c, EnvNAVXYTHETALATCfg.EndY_c) / EnvNAVXYTHETALATCfg.nominalvel_mpersecs)); + } + + if (bNeedtoRecomputeGoalHeuristics && bGoalHeuristics) { + grid2Dsearchfromgoal->search( + EnvNAVXYTHETALATCfg.Grid2D, + EnvNAVXYTHETALATCfg.cost_inscribed_thresh, + EnvNAVXYTHETALATCfg.EndX_c, EnvNAVXYTHETALATCfg.EndY_c, + EnvNAVXYTHETALATCfg.StartX_c, EnvNAVXYTHETALATCfg.StartY_c, + SBPL_2DGRIDSEARCH_TERM_CONDITION_TWOTIMESOPTPATH); + bNeedtoRecomputeGoalHeuristics = false; + SBPL_PRINTF("2dsolcost_infullunits=%d\n", (int)(grid2Dsearchfromgoal->getlowerboundoncostfromstart_inmm(EnvNAVXYTHETALATCfg.StartX_c, EnvNAVXYTHETALATCfg.StartY_c) / EnvNAVXYTHETALATCfg.nominalvel_mpersecs)); + } +} + +void EnvironmentNAVXYTHETALATTICE::ComputeHeuristicValues() +{ + // whatever necessary pre-computation of heuristic values is done here + SBPL_PRINTF("Precomputing heuristics...\n"); + + // allocated 2D grid searches + grid2Dsearchfromstart = new SBPL2DGridSearch( + EnvNAVXYTHETALATCfg.EnvWidth_c, EnvNAVXYTHETALATCfg.EnvHeight_c, + (float)EnvNAVXYTHETALATCfg.cellsize_m, blocksize, bucketsize); + grid2Dsearchfromgoal = new SBPL2DGridSearch( + EnvNAVXYTHETALATCfg.EnvWidth_c, EnvNAVXYTHETALATCfg.EnvHeight_c, + (float)EnvNAVXYTHETALATCfg.cellsize_m, blocksize, bucketsize); + + // set OPEN type to sliding buckets + grid2Dsearchfromstart->setOPENdatastructure(SBPL_2DGRIDSEARCH_OPENTYPE_SLIDINGBUCKETS); + grid2Dsearchfromgoal->setOPENdatastructure(SBPL_2DGRIDSEARCH_OPENTYPE_SLIDINGBUCKETS); + + SBPL_PRINTF("done\n"); +} + +bool EnvironmentNAVXYTHETALATTICE::CheckQuant(FILE* fOut) +{ + for (double theta = -10; theta < 10; + theta += 2.0 * PI_CONST / EnvNAVXYTHETALATCfg.NumThetaDirs * 0.01) + { + int nTheta, nnewTheta; + double newTheta; + nTheta = ContTheta2DiscNew(theta); + newTheta = DiscTheta2ContNew(nTheta); + nnewTheta = ContTheta2DiscNew(newTheta); + + SBPL_FPRINTF(fOut, "theta=%f(%f)->%d->%f->%d\n", theta, theta * 180 / PI_CONST, nTheta, newTheta, nnewTheta); + + if (nTheta != nnewTheta) { + SBPL_ERROR("ERROR: invalid quantization\n"); + return false; + } + } + + return true; +} + +bool EnvironmentNAVXYTHETALATTICE::InitializeEnv( + const char* sEnvFile, + const std::vector& perimeterptsV, + const char* sMotPrimFile) +{ + EnvNAVXYTHETALATCfg.FootprintPolygon = perimeterptsV; + + SBPL_INFO("InitializeEnv start: sEnvFile=%s sMotPrimFile=%s\n", sEnvFile, sMotPrimFile); + fflush(stdout); + + FILE* fCfg = fopen(sEnvFile, "r"); + if (fCfg == NULL) { + std::stringstream ss; + ss << "ERROR: unable to open " << sEnvFile; + throw SBPL_Exception(ss.str()); + } + + ReadConfiguration(fCfg); + fclose(fCfg); + + if (sMotPrimFile != NULL) { + FILE* fMotPrim = fopen(sMotPrimFile, "r"); + if (fMotPrim == NULL) { + std::stringstream ss; + ss << "ERROR: unable to open " << sMotPrimFile; + throw SBPL_Exception(ss.str()); + } + if (ReadMotionPrimitives(fMotPrim) == false) { + throw SBPL_Exception("ERROR: failed to read in motion primitive file"); + } + + EnvNAVXYTHETALATCfg.StartTheta = ContTheta2DiscNew(EnvNAVXYTHETALATCfg.StartTheta_rad); + if (EnvNAVXYTHETALATCfg.StartTheta < 0 || + EnvNAVXYTHETALATCfg.StartTheta >= EnvNAVXYTHETALATCfg.NumThetaDirs) + { + throw new SBPL_Exception("ERROR: illegal start coordinates for theta"); + } + EnvNAVXYTHETALATCfg.EndTheta = ContTheta2DiscNew(EnvNAVXYTHETALATCfg.EndTheta_rad); + if (EnvNAVXYTHETALATCfg.EndTheta < 0 || + EnvNAVXYTHETALATCfg.EndTheta >= EnvNAVXYTHETALATCfg.NumThetaDirs) + { + throw new SBPL_Exception("ERROR: illegal goal coordinates for theta"); + } + + InitGeneral(&EnvNAVXYTHETALATCfg.mprimV); + fclose(fMotPrim); + } + else { + InitGeneral( NULL); + } + + SBPL_PRINTF("size of env: %d by %d\n", EnvNAVXYTHETALATCfg.EnvWidth_c, EnvNAVXYTHETALATCfg.EnvHeight_c); + + return true; +} + +bool EnvironmentNAVXYTHETALATTICE::InitializeEnv(const char* sEnvFile) +{ + FILE* fCfg = fopen(sEnvFile, "r"); + if (fCfg == NULL) { + SBPL_ERROR("ERROR: unable to open %s\n", sEnvFile); + throw SBPL_Exception(); + } + ReadConfiguration(fCfg); + fclose(fCfg); + + InitGeneral( NULL); + + return true; +} + +bool EnvironmentNAVXYTHETALATTICE::InitializeEnv( + int width, + int height, + const std::vector& perimeterptsV, + double cellsize_m, + double nominalvel_mpersecs, + double timetoturn45degsinplace_secs, + unsigned char obsthresh, + const char* sMotPrimFile, + EnvNAVXYTHETALAT_InitParms params) +{ + EnvNAVXYTHETALATCfg.NumThetaDirs = params.numThetas; + + return InitializeEnv( + width, height, + params.mapdata, + params.startx, params.starty, params.starttheta, + params.goalx, params.goaly, params.goaltheta, + params.goaltol_x, params.goaltol_y, params.goaltol_theta, + perimeterptsV, + cellsize_m, + nominalvel_mpersecs, timetoturn45degsinplace_secs, + obsthresh, + sMotPrimFile); +} + +bool EnvironmentNAVXYTHETALATTICE::InitializeEnv( + int width, + int height, + const unsigned char* mapdata, + double startx, double starty, double starttheta, + double goalx, double goaly, double goaltheta, + double goaltol_x, double goaltol_y, double goaltol_theta, + const std::vector & perimeterptsV, + double cellsize_m, + double nominalvel_mpersecs, + double timetoturn45degsinplace_secs, + unsigned char obsthresh, + const char* sMotPrimFile) +{ + SBPL_PRINTF("env: initialize with width=%d height=%d start=%.3f %.3f %.3f " + "goalx=%.3f %.3f %.3f cellsize=%.3f nomvel=%.3f timetoturn=%.3f, obsthresh=%d\n", + width, height, startx, starty, starttheta, goalx, goaly, goaltheta, cellsize_m, nominalvel_mpersecs, + timetoturn45degsinplace_secs, obsthresh); + + SBPL_PRINTF("NOTE: goaltol parameters currently unused\n"); + + SBPL_PRINTF("perimeter has size=%d\n", (unsigned int)perimeterptsV.size()); + + for (int i = 0; i < (int)perimeterptsV.size(); i++) { + SBPL_PRINTF("perimeter(%d) = %.4f %.4f\n", i, perimeterptsV.at(i).x, perimeterptsV.at(i).y); + } + + EnvNAVXYTHETALATCfg.obsthresh = obsthresh; + EnvNAVXYTHETALATCfg.cellsize_m = cellsize_m; + EnvNAVXYTHETALATCfg.StartTheta_rad = starttheta; + EnvNAVXYTHETALATCfg.EndTheta_rad = goaltheta; + + // TODO - need to set the tolerance as well + + if (sMotPrimFile != NULL) { + FILE* fMotPrim = fopen(sMotPrimFile, "r"); + if (fMotPrim == NULL) { + std::stringstream ss; + ss << "ERROR: unable to open " << sMotPrimFile; + throw SBPL_Exception(ss.str()); + } + + if (ReadMotionPrimitives(fMotPrim) == false) { + throw SBPL_Exception("ERROR: failed to read in motion primitive file"); + } + fclose(fMotPrim); + } + + EnvNAVXYTHETALATCfg.StartTheta = ContTheta2DiscNew(EnvNAVXYTHETALATCfg.StartTheta_rad); + if (EnvNAVXYTHETALATCfg.StartTheta < 0 || + EnvNAVXYTHETALATCfg.StartTheta >= EnvNAVXYTHETALATCfg.NumThetaDirs) + { + throw new SBPL_Exception("ERROR: illegal start coordinates for theta"); + } + EnvNAVXYTHETALATCfg.EndTheta = ContTheta2DiscNew(EnvNAVXYTHETALATCfg.EndTheta_rad); + if (EnvNAVXYTHETALATCfg.EndTheta < 0 || + EnvNAVXYTHETALATCfg.EndTheta >= EnvNAVXYTHETALATCfg.NumThetaDirs) + { + throw new SBPL_Exception("ERROR: illegal goal coordiantes for theta"); + } + + SetConfiguration( + width, height, mapdata, + CONTXY2DISC(startx, cellsize_m), CONTXY2DISC(starty, cellsize_m), EnvNAVXYTHETALATCfg.StartTheta, + CONTXY2DISC(goalx, cellsize_m), CONTXY2DISC(goaly, cellsize_m), EnvNAVXYTHETALATCfg.EndTheta, + cellsize_m, + nominalvel_mpersecs, timetoturn45degsinplace_secs, + perimeterptsV); + + if (EnvNAVXYTHETALATCfg.mprimV.size() != 0) { + InitGeneral(&EnvNAVXYTHETALATCfg.mprimV); + } + else { + InitGeneral( NULL); + } + + return true; +} + +bool EnvironmentNAVXYTHETALATTICE::InitGeneral( + std::vector* motionprimitiveV) +{ + // Initialize other parameters of the environment + InitializeEnvConfig(motionprimitiveV); + + // initialize Environment + InitializeEnvironment(); + + // pre-compute heuristics + ComputeHeuristicValues(); + + return true; +} + +bool EnvironmentNAVXYTHETALATTICE::InitializeMDPCfg(MDPConfig* MDPCfg) +{ + // initialize MDPCfg with the start and goal ids + MDPCfg->goalstateid = EnvNAVXYTHETALAT.goalstateid; + MDPCfg->startstateid = EnvNAVXYTHETALAT.startstateid; + + return true; +} + +void EnvironmentNAVXYTHETALATTICE::PrintHeuristicValues() +{ + const char* heur = "heur.txt"; + FILE* fHeur = SBPL_FOPEN(heur, "w"); + if (fHeur == NULL) { + throw SBPL_Exception("ERROR: could not open debug file to write heuristic"); + } + SBPL2DGridSearch* grid2Dsearch = NULL; + + for (int i = 0; i < 2; i++) { + if (i == 0 && grid2Dsearchfromstart != NULL) { + grid2Dsearch = grid2Dsearchfromstart; + SBPL_FPRINTF(fHeur, "start heuristics:\n"); + } + else if (i == 1 && grid2Dsearchfromgoal != NULL) { + grid2Dsearch = grid2Dsearchfromgoal; + SBPL_FPRINTF(fHeur, "goal heuristics:\n"); + } + else { + continue; + } + + for (int y = 0; y < EnvNAVXYTHETALATCfg.EnvHeight_c; y++) { + for (int x = 0; x < EnvNAVXYTHETALATCfg.EnvWidth_c; x++) { + if (grid2Dsearch->getlowerboundoncostfromstart_inmm(x, y) < INFINITECOST) { + SBPL_FPRINTF(fHeur, "%5d ", grid2Dsearch->getlowerboundoncostfromstart_inmm(x, y)); + } + else { + SBPL_FPRINTF(fHeur, "XXXXX "); + } + } + SBPL_FPRINTF(fHeur, "\n"); + } + } + SBPL_FCLOSE(fHeur); +} + +void EnvironmentNAVXYTHETALATTICE::SetAllPreds(CMDPSTATE* state) +{ + // implement this if the planner needs access to predecessors + throw SBPL_Exception("ERROR in EnvNAVXYTHETALAT... function: SetAllPreds is undefined"); +} + +void EnvironmentNAVXYTHETALATTICE::GetSuccs( + int SourceStateID, + std::vector* SuccIDV, + std::vector* CostV) +{ + GetSuccs(SourceStateID, SuccIDV, CostV, NULL); +} +void EnvironmentNAVXYTHETALATTICE::GetLazySuccs( + int SourceStateID, + std::vector* SuccIDV, + std::vector* CostV, + std::vector* isTrueCost) +{ + GetLazySuccs(SourceStateID, SuccIDV, CostV, isTrueCost, NULL); +} + +void EnvironmentNAVXYTHETALATTICE::GetSuccsWithUniqueIds( + int SourceStateID, + std::vector* SuccIDV, + std::vector* CostV) +{ + GetSuccsWithUniqueIds(SourceStateID, SuccIDV, CostV, NULL); +} + +void EnvironmentNAVXYTHETALATTICE::GetLazySuccsWithUniqueIds( + int SourceStateID, + std::vector* SuccIDV, + std::vector* CostV, + std::vector* isTrueCost) +{ + GetLazySuccsWithUniqueIds(SourceStateID, SuccIDV, CostV, isTrueCost, NULL); +} + +const EnvNAVXYTHETALATConfig_t* EnvironmentNAVXYTHETALATTICE::GetEnvNavConfig() +{ + return &EnvNAVXYTHETALATCfg; +} + +bool EnvironmentNAVXYTHETALATTICE::UpdateCost( + int x, + int y, + unsigned char newcost) +{ + EnvNAVXYTHETALATCfg.Grid2D[x][y] = newcost; + + bNeedtoRecomputeStartHeuristics = true; + bNeedtoRecomputeGoalHeuristics = true; + + return true; +} + +bool EnvironmentNAVXYTHETALATTICE::SetMap(const unsigned char* mapdata) +{ + int xind = -1, yind = -1; + + for (xind = 0; xind < EnvNAVXYTHETALATCfg.EnvWidth_c; xind++) { + for (yind = 0; yind < EnvNAVXYTHETALATCfg.EnvHeight_c; yind++) { + EnvNAVXYTHETALATCfg.Grid2D[xind][yind] = mapdata[xind + yind * EnvNAVXYTHETALATCfg.EnvWidth_c]; + } + } + + bNeedtoRecomputeStartHeuristics = true; + bNeedtoRecomputeGoalHeuristics = true; + + return true; +} + +void EnvironmentNAVXYTHETALATTICE::PrintEnv_Config(FILE* fOut) +{ + // implement this if the planner needs to print out EnvNAVXYTHETALAT. configuration + throw SBPL_Exception("ERROR in EnvNAVXYTHETALAT... function: PrintEnv_Config is undefined"); +} + +void EnvironmentNAVXYTHETALATTICE::Set2DBlockSize(int BlockSize) +{ + blocksize = BlockSize; +} + +void EnvironmentNAVXYTHETALATTICE::Set2DBucketSize(int BucketSize) +{ + bucketsize = BucketSize; +} + +void EnvironmentNAVXYTHETALATTICE::PrintTimeStat(FILE* fOut) +{ +#if TIME_DEBUG + SBPL_FPRINTF(fOut, "time3_addallout = %f secs, time_gethash = %f secs, time_createhash = %f secs, " + "time_getsuccs = %f\n", + time3_addallout/(double)CLOCKS_PER_SEC, time_gethash/(double)CLOCKS_PER_SEC, + time_createhash/(double)CLOCKS_PER_SEC, time_getsuccs/(double)CLOCKS_PER_SEC); +#endif +} + +bool EnvironmentNAVXYTHETALATTICE::IsObstacle(int x, int y) +{ +#if DEBUG + SBPL_FPRINTF(fDeb, "Status of cell %d %d is queried. Its cost=%d\n", x,y,EnvNAVXYTHETALATCfg.Grid2D[x][y]); +#endif + + return EnvNAVXYTHETALATCfg.Grid2D[x][y] >= EnvNAVXYTHETALATCfg.obsthresh; +} + +void EnvironmentNAVXYTHETALATTICE::GetEnvParms( + int *size_x, int *size_y, int* num_thetas, + double* startx, double* starty, double* starttheta, + double* goalx, double* goaly, double* goaltheta, + double* cellsize_m, + double* nominalvel_mpersecs, + double* timetoturn45degsinplace_secs, + unsigned char* obsthresh, + std::vector* mprimitiveV) +{ + *num_thetas = EnvNAVXYTHETALATCfg.NumThetaDirs; + GetEnvParms( + size_x, size_y, + startx, starty, starttheta, + goalx, goaly, goaltheta, + cellsize_m, + nominalvel_mpersecs, timetoturn45degsinplace_secs, + obsthresh, + mprimitiveV); +} + +void EnvironmentNAVXYTHETALATTICE::GetEnvParms( + int* size_x, int* size_y, + double* startx, double* starty, double* starttheta, + double* goalx, double* goaly, double* goaltheta, + double* cellsize_m, + double* nominalvel_mpersecs, double* timetoturn45degsinplace_secs, + unsigned char* obsthresh, + std::vector* mprimitiveV) +{ + *size_x = EnvNAVXYTHETALATCfg.EnvWidth_c; + *size_y = EnvNAVXYTHETALATCfg.EnvHeight_c; + + *startx = DISCXY2CONT(EnvNAVXYTHETALATCfg.StartX_c, EnvNAVXYTHETALATCfg.cellsize_m); + *starty = DISCXY2CONT(EnvNAVXYTHETALATCfg.StartY_c, EnvNAVXYTHETALATCfg.cellsize_m); + *starttheta = DiscTheta2ContNew(EnvNAVXYTHETALATCfg.StartTheta); + *goalx = DISCXY2CONT(EnvNAVXYTHETALATCfg.EndX_c, EnvNAVXYTHETALATCfg.cellsize_m); + *goaly = DISCXY2CONT(EnvNAVXYTHETALATCfg.EndY_c, EnvNAVXYTHETALATCfg.cellsize_m); + *goaltheta = DiscTheta2ContNew(EnvNAVXYTHETALATCfg.EndTheta); + + *cellsize_m = EnvNAVXYTHETALATCfg.cellsize_m; + *nominalvel_mpersecs = EnvNAVXYTHETALATCfg.nominalvel_mpersecs; + *timetoturn45degsinplace_secs = EnvNAVXYTHETALATCfg.timetoturn45degsinplace_secs; + + *obsthresh = EnvNAVXYTHETALATCfg.obsthresh; + + *mprimitiveV = EnvNAVXYTHETALATCfg.mprimV; +} + +bool EnvironmentNAVXYTHETALATTICE::PoseContToDisc( + double px, double py, double pth, int &ix, int &iy, int &ith) const +{ + ix = CONTXY2DISC(px, EnvNAVXYTHETALATCfg.cellsize_m); + iy = CONTXY2DISC(py, EnvNAVXYTHETALATCfg.cellsize_m); + ith = ContTheta2DiscNew(pth); + return (pth >= -2 * PI_CONST) && (pth <= 2 * PI_CONST) && + (ix >= 0) && (ix < EnvNAVXYTHETALATCfg.EnvWidth_c) && + (iy >= 0) && (iy < EnvNAVXYTHETALATCfg.EnvHeight_c); +} + +bool EnvironmentNAVXYTHETALATTICE::PoseDiscToCont( + int ix, int iy, int ith, double &px, double &py, double &pth) const +{ + px = DISCXY2CONT(ix, EnvNAVXYTHETALATCfg.cellsize_m); + py = DISCXY2CONT(iy, EnvNAVXYTHETALATCfg.cellsize_m); + pth = normalizeAngle(DiscTheta2ContNew(ith)); + return (ith >= 0) && (ith < EnvNAVXYTHETALATCfg.NumThetaDirs) && + (ix >= 0) && (ix < EnvNAVXYTHETALATCfg.EnvWidth_c) && + (iy >= 0) && (iy < EnvNAVXYTHETALATCfg.EnvHeight_c); +} + +unsigned char EnvironmentNAVXYTHETALATTICE::GetMapCost(int x, int y) +{ + return EnvNAVXYTHETALATCfg.Grid2D[x][y]; +} + +bool EnvironmentNAVXYTHETALATTICE::SetEnvParameter( + const char* parameter, + int value) +{ + if (EnvNAVXYTHETALAT.bInitialized) { + SBPL_ERROR("ERROR: all parameters must be set before initialization of the environment\n"); + return false; + } + + SBPL_PRINTF("setting parameter %s to %d\n", parameter, value); + + if (strcmp(parameter, "cost_inscribed_thresh") == 0) { + if (value < 0 || value > 255) { + SBPL_ERROR("ERROR: invalid value %d for parameter %s\n", value, parameter); + return false; + } + EnvNAVXYTHETALATCfg.cost_inscribed_thresh = (unsigned char)value; + } + else if (strcmp(parameter, "cost_possibly_circumscribed_thresh") == 0) { + if (value < 0 || value > 255) { + SBPL_ERROR("ERROR: invalid value %d for parameter %s\n", value, parameter); + return false; + } + EnvNAVXYTHETALATCfg.cost_possibly_circumscribed_thresh = value; + } + else if (strcmp(parameter, "cost_obsthresh") == 0) { + if (value < 0 || value > 255) { + SBPL_ERROR("ERROR: invalid value %d for parameter %s\n", value, parameter); + return false; + } + EnvNAVXYTHETALATCfg.obsthresh = (unsigned char)value; + } + else { + SBPL_ERROR("ERROR: invalid parameter %s\n", parameter); + return false; + } + + return true; +} + +int EnvironmentNAVXYTHETALATTICE::GetEnvParameter(const char* parameter) +{ + if (strcmp(parameter, "cost_inscribed_thresh") == 0) { + return (int)EnvNAVXYTHETALATCfg.cost_inscribed_thresh; + } + else if (strcmp(parameter, "cost_possibly_circumscribed_thresh") == 0) { + return (int)EnvNAVXYTHETALATCfg.cost_possibly_circumscribed_thresh; + } + else if (strcmp(parameter, "cost_obsthresh") == 0) { + return (int)EnvNAVXYTHETALATCfg.obsthresh; + } + else { + std::stringstream ss; + ss << "ERROR: invalid parameter " << parameter; + throw SBPL_Exception(ss.str()); + } +} + +EnvironmentNAVXYTHETALAT::~EnvironmentNAVXYTHETALAT() +{ + SBPL_PRINTF("destroying XYTHETALAT\n"); + + // delete the states themselves first + for (int i = 0; i < (int)StateID2CoordTable.size(); i++) { + delete StateID2CoordTable.at(i); + StateID2CoordTable.at(i) = NULL; + } + StateID2CoordTable.clear(); + + // delete hashtable + if (Coord2StateIDHashTable != NULL) { + delete[] Coord2StateIDHashTable; + Coord2StateIDHashTable = NULL; + } + if (Coord2StateIDHashTable_lookup != NULL) { + delete[] Coord2StateIDHashTable_lookup; + Coord2StateIDHashTable_lookup = NULL; + } +} + +void EnvironmentNAVXYTHETALAT::GetCoordFromState( + int stateID, int& x, int& y, int& theta) const +{ + EnvNAVXYTHETALATHashEntry_t* HashEntry = StateID2CoordTable[stateID]; + x = HashEntry->X; + y = HashEntry->Y; + theta = HashEntry->Theta; +} + +int EnvironmentNAVXYTHETALAT::GetStateFromCoord(int x, int y, int theta) +{ + EnvNAVXYTHETALATHashEntry_t* OutHashEntry; + if ((OutHashEntry = (this->*GetHashEntry)(x, y, theta)) == NULL) { + // have to create a new entry + OutHashEntry = (this->*CreateNewHashEntry)(x, y, theta); + } + return OutHashEntry->stateID; +} + +void EnvironmentNAVXYTHETALAT::GetActionsFromStateIDPath( + std::vector* stateIDPath, + std::vector* action_list) +{ + std::vector actionV; + std::vector CostV; + std::vector SuccIDV; + int targetx_c, targety_c, targettheta_c; + int sourcex_c, sourcey_c, sourcetheta_c; + + SBPL_PRINTF("checks=%ld\n", checks); + + action_list->clear(); + + for (int pind = 0; pind < (int)(stateIDPath->size()) - 1; pind++) { + int sourceID = stateIDPath->at(pind); + int targetID = stateIDPath->at(pind + 1); + + // get successors and pick the target via the cheapest action + SuccIDV.clear(); + CostV.clear(); + actionV.clear(); + GetSuccs(sourceID, &SuccIDV, &CostV, &actionV); + + int bestcost = INFINITECOST; + int bestsind = -1; + + for (int sind = 0; sind < (int)SuccIDV.size(); sind++) { + if (SuccIDV[sind] == targetID && CostV[sind] <= bestcost) { + bestcost = CostV[sind]; + bestsind = sind; + } + } + if (bestsind == -1) { + SBPL_ERROR("ERROR: successor not found for transition"); + GetCoordFromState(sourceID, sourcex_c, sourcey_c, sourcetheta_c); + GetCoordFromState(targetID, targetx_c, targety_c, targettheta_c); + SBPL_PRINTF("%d %d %d -> %d %d %d\n", sourcex_c, sourcey_c, sourcetheta_c, targetx_c, targety_c, targettheta_c); + throw SBPL_Exception("ERROR: successor not found for transition"); + } + +#if DEBUG + SBPL_FPRINTF(fDeb, "Start: %.3f %.3f %.3f Target: %.3f %.3f %.3f Prim ID, Start Theta: %d %d\n", + sourcex_c, sourcey_c, sourcetheta_c, + targetx_c, targety_c, targettheta_c, + actionV[bestsind]->aind, actionV[bestsind]->starttheta); +#endif + + action_list->push_back(*(actionV[bestsind])); + } +} + +void EnvironmentNAVXYTHETALAT::ConvertStateIDPathintoXYThetaPath( + std::vector* stateIDPath, + std::vector* xythetaPath) +{ + std::vector actionV; + std::vector CostV; + std::vector SuccIDV; + int targetx_c, targety_c, targettheta_c; + int sourcex_c, sourcey_c, sourcetheta_c; + + SBPL_PRINTF("checks=%ld\n", checks); + + xythetaPath->clear(); + +#if DEBUG + SBPL_FPRINTF(fDeb, "converting stateid path into coordinates:\n"); +#endif + + for (int pind = 0; pind < (int)(stateIDPath->size()) - 1; pind++) { + int sourceID = stateIDPath->at(pind); + int targetID = stateIDPath->at(pind + 1); + +#if DEBUG + GetCoordFromState(sourceID, sourcex_c, sourcey_c, sourcetheta_c); +#endif + + // get successors and pick the target via the cheapest action + SuccIDV.clear(); + CostV.clear(); + actionV.clear(); + GetSuccs(sourceID, &SuccIDV, &CostV, &actionV); + + int bestcost = INFINITECOST; + int bestsind = -1; + +#if DEBUG + GetCoordFromState(sourceID, sourcex_c, sourcey_c, sourcetheta_c); + GetCoordFromState(targetID, targetx_c, targety_c, targettheta_c); + SBPL_FPRINTF(fDeb, "looking for %d %d %d -> %d %d %d (numofsuccs=%d)\n", sourcex_c, sourcey_c, sourcetheta_c, targetx_c, targety_c, targettheta_c, (int)SuccIDV.size()); +#endif + + for (int sind = 0; sind < (int)SuccIDV.size(); sind++) { +#if DEBUG + int x_c, y_c, theta_c; + GetCoordFromState(SuccIDV[sind], x_c, y_c, theta_c); + SBPL_FPRINTF(fDeb, "succ: %d %d %d\n", x_c, y_c, theta_c); +#endif + if (SuccIDV[sind] == targetID && CostV[sind] <= bestcost) { + bestcost = CostV[sind]; + bestsind = sind; + } + } + if (bestsind == -1) { + SBPL_ERROR("ERROR: successor not found for transition"); + GetCoordFromState(sourceID, sourcex_c, sourcey_c, sourcetheta_c); + GetCoordFromState(targetID, targetx_c, targety_c, targettheta_c); + SBPL_PRINTF("%d %d %d -> %d %d %d\n", sourcex_c, sourcey_c, sourcetheta_c, targetx_c, targety_c, targettheta_c); + throw SBPL_Exception("ERROR: successor not found for transition"); + } + + // now push in the actual path + GetCoordFromState(sourceID, sourcex_c, sourcey_c, sourcetheta_c); + double sourcex, sourcey; + sourcex = DISCXY2CONT(sourcex_c, EnvNAVXYTHETALATCfg.cellsize_m); + sourcey = DISCXY2CONT(sourcey_c, EnvNAVXYTHETALATCfg.cellsize_m); + // TODO - when there are no motion primitives we should still print source state + for (int ipind = 0; ipind < ((int)actionV[bestsind]->intermptV.size()) - 1; ipind++) { + // translate appropriately + sbpl_xy_theta_pt_t intermpt = actionV[bestsind]->intermptV[ipind]; + intermpt.x += sourcex; + intermpt.y += sourcey; + +#if DEBUG + int nx = CONTXY2DISC(intermpt.x, EnvNAVXYTHETALATCfg.cellsize_m); + int ny = CONTXY2DISC(intermpt.y, EnvNAVXYTHETALATCfg.cellsize_m); + int ntheta; + ntheta = ContTheta2DiscNew(intermpt.theta); + + SBPL_FPRINTF(fDeb, "%.3f %.3f %.3f (%d %d %d cost=%d) ", intermpt.x, intermpt.y, intermpt.theta, nx, ny, ntheta, EnvNAVXYTHETALATCfg.Grid2D[nx][ny]); + + if (ipind == 0) { + SBPL_FPRINTF(fDeb, "first (heur=%d)\n", GetStartHeuristic(sourceID)); + } + else { + SBPL_FPRINTF(fDeb, "\n"); + } +#endif + // store + xythetaPath->push_back(intermpt); + } + } +} + +// returns the stateid if success, and -1 otherwise +int EnvironmentNAVXYTHETALAT::SetGoal(double x_m, double y_m, double theta_rad) +{ + int x = CONTXY2DISC(x_m, EnvNAVXYTHETALATCfg.cellsize_m); + int y = CONTXY2DISC(y_m, EnvNAVXYTHETALATCfg.cellsize_m); + int theta = ContTheta2DiscNew(theta_rad); + + SBPL_PRINTF("env: setting goal to %.3f %.3f %.3f (%d %d %d)\n", x_m, y_m, theta_rad, x, y, theta); + + if (!IsWithinMapCell(x, y)) { + SBPL_ERROR("ERROR: trying to set a goal cell %d %d that is outside of map\n", x, y); + return -1; + } + + if (!IsValidConfiguration(x, y, theta)) { + SBPL_PRINTF("WARNING: goal configuration is invalid\n"); + } + + EnvNAVXYTHETALATHashEntry_t* OutHashEntry; + if ((OutHashEntry = (this->*GetHashEntry)(x, y, theta)) == NULL) { + // have to create a new entry + OutHashEntry = (this->*CreateNewHashEntry)(x, y, theta); + } + + // need to recompute start heuristics? + if (EnvNAVXYTHETALAT.goalstateid != OutHashEntry->stateID) { + // because termination condition may not plan all the way to the new goal + bNeedtoRecomputeStartHeuristics = true; + + // because goal heuristics change + bNeedtoRecomputeGoalHeuristics = true; + } + + EnvNAVXYTHETALAT.goalstateid = OutHashEntry->stateID; + + EnvNAVXYTHETALATCfg.EndX_c = x; + EnvNAVXYTHETALATCfg.EndY_c = y; + EnvNAVXYTHETALATCfg.EndTheta = theta; + + return EnvNAVXYTHETALAT.goalstateid; +} + +// returns the stateid if success, and -1 otherwise +int EnvironmentNAVXYTHETALAT::SetStart(double x_m, double y_m, double theta_rad) +{ + int x = CONTXY2DISC(x_m, EnvNAVXYTHETALATCfg.cellsize_m); + int y = CONTXY2DISC(y_m, EnvNAVXYTHETALATCfg.cellsize_m); + int theta = ContTheta2DiscNew(theta_rad); + + if (!IsWithinMapCell(x, y)) { + SBPL_ERROR("ERROR: trying to set a start cell %d %d that is outside of map\n", x, y); + return -1; + } + + SBPL_PRINTF("env: setting start to %.3f %.3f %.3f (%d %d %d)\n", x_m, y_m, theta_rad, x, y, theta); + + if (!IsValidConfiguration(x, y, theta)) { + SBPL_PRINTF("WARNING: start configuration %d %d %d is invalid\n", x, y, theta); + } + + EnvNAVXYTHETALATHashEntry_t* OutHashEntry; + if ((OutHashEntry = (this->*GetHashEntry)(x, y, theta)) == NULL) { + // have to create a new entry + OutHashEntry = (this->*CreateNewHashEntry)(x, y, theta); + } + + // need to recompute start heuristics? + if (EnvNAVXYTHETALAT.startstateid != OutHashEntry->stateID) { + bNeedtoRecomputeStartHeuristics = true; + // because termination condition can be not all states TODO - make it dependent on term. condition + bNeedtoRecomputeGoalHeuristics = true; + } + + // set start + EnvNAVXYTHETALAT.startstateid = OutHashEntry->stateID; + EnvNAVXYTHETALATCfg.StartX_c = x; + EnvNAVXYTHETALATCfg.StartY_c = y; + EnvNAVXYTHETALATCfg.StartTheta = theta; + + return EnvNAVXYTHETALAT.startstateid; +} + +void EnvironmentNAVXYTHETALAT::PrintState( + int stateID, + bool bVerbose, + FILE* fOut) +{ +#if DEBUG + if (stateID >= (int)StateID2CoordTable.size()) { + SBPL_ERROR("ERROR in EnvNAVXYTHETALAT... function: stateID illegal (2)\n"); + throw SBPL_Exception(); + } +#endif + + if (fOut == NULL) { + fOut = stdout; + } + + EnvNAVXYTHETALATHashEntry_t* HashEntry = StateID2CoordTable[stateID]; + + if (stateID == EnvNAVXYTHETALAT.goalstateid && bVerbose) { + SBPL_FPRINTF(fOut, "the state is a goal state\n"); + } + + if (bVerbose) { + SBPL_FPRINTF(fOut, "X=%d Y=%d Theta=%d\n", HashEntry->X, HashEntry->Y, HashEntry->Theta); + } + else + { + SBPL_FPRINTF(fOut, "%.3f %.3f %.3f\n", DISCXY2CONT(HashEntry->X, EnvNAVXYTHETALATCfg.cellsize_m), DISCXY2CONT(HashEntry->Y, EnvNAVXYTHETALATCfg.cellsize_m), DiscTheta2ContNew(HashEntry->Theta)); + } +} + +EnvNAVXYTHETALATHashEntry_t* EnvironmentNAVXYTHETALAT::GetHashEntry_lookup( + int X, int Y, int Theta) +{ + if (X < 0 || X >= EnvNAVXYTHETALATCfg.EnvWidth_c || + Y < 0 || Y >= EnvNAVXYTHETALATCfg.EnvHeight_c || + Theta < 0 || Theta >= EnvNAVXYTHETALATCfg.NumThetaDirs) + { + return NULL; + } + int index = XYTHETA2INDEX(X,Y,Theta); + return Coord2StateIDHashTable_lookup[index]; +} + +EnvNAVXYTHETALATHashEntry_t* +EnvironmentNAVXYTHETALAT::GetHashEntry_hash(int X, int Y, int Theta) +{ +#if TIME_DEBUG + clock_t currenttime = clock(); +#endif + + int binid = GETHASHBIN(X, Y, Theta); + +#if DEBUG + if ((int)Coord2StateIDHashTable[binid].size() > 5) { + SBPL_FPRINTF(fDeb, "WARNING: Hash table has a bin %d (X=%d Y=%d) of size %d\n", binid, X, Y, (int)Coord2StateIDHashTable[binid].size()); + + PrintHashTableHist(fDeb); + } +#endif + + // iterate over the states in the bin and select the perfect match + std::vector* binV = &Coord2StateIDHashTable[binid]; + for (int ind = 0; ind < (int)binV->size(); ind++) { + EnvNAVXYTHETALATHashEntry_t* hashentry = binV->at(ind); + if (hashentry->X == X && hashentry->Y == Y && hashentry->Theta == Theta) { +#if TIME_DEBUG + time_gethash += clock()-currenttime; +#endif + return hashentry; + } + } + +#if TIME_DEBUG + time_gethash += clock()-currenttime; +#endif + + return NULL; +} + +EnvNAVXYTHETALATHashEntry_t* +EnvironmentNAVXYTHETALAT::CreateNewHashEntry_lookup(int X, int Y, int Theta) +{ + int i; + +#if TIME_DEBUG + clock_t currenttime = clock(); +#endif + + EnvNAVXYTHETALATHashEntry_t* HashEntry = new EnvNAVXYTHETALATHashEntry_t; + + HashEntry->X = X; + HashEntry->Y = Y; + HashEntry->Theta = Theta; + HashEntry->iteration = 0; + + HashEntry->stateID = StateID2CoordTable.size(); + + // insert into the tables + StateID2CoordTable.push_back(HashEntry); + + int index = XYTHETA2INDEX(X,Y,Theta); + +#if DEBUG + if (Coord2StateIDHashTable_lookup[index] != NULL) { + throw SBPL_Exception("ERROR: creating hash entry for non-NULL hashentry"); + } +#endif + + Coord2StateIDHashTable_lookup[index] = HashEntry; + + // insert into and initialize the mappings + int* entry = new int[NUMOFINDICES_STATEID2IND]; + StateID2IndexMapping.push_back(entry); + for (i = 0; i < NUMOFINDICES_STATEID2IND; i++) { + StateID2IndexMapping[HashEntry->stateID][i] = -1; + } + + if (HashEntry->stateID != (int)StateID2IndexMapping.size() - 1) { + throw SBPL_Exception("ERROR in Env... function: last state has incorrect stateID"); + } + +#if TIME_DEBUG + time_createhash += clock()-currenttime; +#endif + + return HashEntry; +} + +EnvNAVXYTHETALATHashEntry_t* +EnvironmentNAVXYTHETALAT::CreateNewHashEntry_hash(int X, int Y, int Theta) +{ + int i; + +#if TIME_DEBUG + clock_t currenttime = clock(); +#endif + + EnvNAVXYTHETALATHashEntry_t* HashEntry = new EnvNAVXYTHETALATHashEntry_t; + + HashEntry->X = X; + HashEntry->Y = Y; + HashEntry->Theta = Theta; + HashEntry->iteration = 0; + + HashEntry->stateID = StateID2CoordTable.size(); + + // insert into the tables + StateID2CoordTable.push_back(HashEntry); + + // get the hash table bin + i = GETHASHBIN(HashEntry->X, HashEntry->Y, HashEntry->Theta); + + // insert the entry into the bin + Coord2StateIDHashTable[i].push_back(HashEntry); + + // insert into and initialize the mappings + int* entry = new int[NUMOFINDICES_STATEID2IND]; + StateID2IndexMapping.push_back(entry); + for (i = 0; i < NUMOFINDICES_STATEID2IND; i++) { + StateID2IndexMapping[HashEntry->stateID][i] = -1; + } + + if (HashEntry->stateID != (int)StateID2IndexMapping.size() - 1) { + throw SBPL_Exception("ERROR in Env... function: last state has incorrect stateID"); + } + +#if TIME_DEBUG + time_createhash += clock() - currenttime; +#endif + + return HashEntry; +} + +void EnvironmentNAVXYTHETALAT::GetSuccs( + int SourceStateID, + std::vector* SuccIDV, + std::vector* CostV, + std::vector* actionV) +{ + int aind; + +#if TIME_DEBUG + clock_t currenttime = clock(); +#endif + + // clear the successor array + SuccIDV->clear(); + CostV->clear(); + SuccIDV->reserve(EnvNAVXYTHETALATCfg.actionwidth); + CostV->reserve(EnvNAVXYTHETALATCfg.actionwidth); + if (actionV != NULL) { + actionV->clear(); + actionV->reserve(EnvNAVXYTHETALATCfg.actionwidth); + } + + // goal state should be absorbing + if (SourceStateID == EnvNAVXYTHETALAT.goalstateid) return; + + // get X, Y for the state + EnvNAVXYTHETALATHashEntry_t* HashEntry = StateID2CoordTable[SourceStateID]; + + // iterate through actions + for (aind = 0; aind < EnvNAVXYTHETALATCfg.actionwidth; aind++) { + EnvNAVXYTHETALATAction_t* nav3daction = &EnvNAVXYTHETALATCfg.ActionsV[(unsigned int)HashEntry->Theta][aind]; + int newX = HashEntry->X + nav3daction->dX; + int newY = HashEntry->Y + nav3daction->dY; + int newTheta = normalizeDiscAngle(nav3daction->endtheta); + + // skip the invalid cells + if (!IsValidCell(newX, newY)) { + continue; + } + + // get cost + int cost = GetActionCost(HashEntry->X, HashEntry->Y, HashEntry->Theta, nav3daction); + if (cost >= INFINITECOST) { + continue; + } + + EnvNAVXYTHETALATHashEntry_t* OutHashEntry; + if ((OutHashEntry = (this->*GetHashEntry)(newX, newY, newTheta)) == NULL) { + // have to create a new entry + OutHashEntry = (this->*CreateNewHashEntry)(newX, newY, newTheta); + } + + SuccIDV->push_back(OutHashEntry->stateID); + CostV->push_back(cost); + if (actionV != NULL) { + actionV->push_back(nav3daction); + } + } + +#if TIME_DEBUG + time_getsuccs += clock()-currenttime; +#endif +} + +void EnvironmentNAVXYTHETALAT::GetPreds( + int TargetStateID, + std::vector* PredIDV, + std::vector* CostV) +{ + //TODO- to support tolerance, need: + // a) generate preds for goal state based on all possible goal state variable settings, + // b) change goal check condition in gethashentry c) change + // getpredsofchangedcells and getsuccsofchangedcells functions + + int aind; + +#if TIME_DEBUG + clock_t currenttime = clock(); +#endif + + // get X, Y for the state + EnvNAVXYTHETALATHashEntry_t* HashEntry = StateID2CoordTable[TargetStateID]; + + // clear the successor array + PredIDV->clear(); + CostV->clear(); + PredIDV->reserve(EnvNAVXYTHETALATCfg.PredActionsV[(unsigned int)HashEntry->Theta].size()); + CostV->reserve(EnvNAVXYTHETALATCfg.PredActionsV[(unsigned int)HashEntry->Theta].size()); + + // iterate through actions + std::vector* actionsV = &EnvNAVXYTHETALATCfg.PredActionsV[(unsigned int)HashEntry->Theta]; + for (aind = 0; aind < (int)EnvNAVXYTHETALATCfg.PredActionsV[(unsigned int)HashEntry->Theta].size(); aind++) { + + EnvNAVXYTHETALATAction_t* nav3daction = actionsV->at(aind); + + int predX = HashEntry->X - nav3daction->dX; + int predY = HashEntry->Y - nav3daction->dY; + int predTheta = nav3daction->starttheta; + + // skip the invalid cells + if (!IsValidCell(predX, predY)) { + continue; + } + + // get cost + int cost = GetActionCost(predX, predY, predTheta, nav3daction); + if (cost >= INFINITECOST) { + continue; + } + + EnvNAVXYTHETALATHashEntry_t* OutHashEntry; + if ((OutHashEntry = (this->*GetHashEntry)(predX, predY, predTheta)) == NULL) { + // have to create a new entry + OutHashEntry = (this->*CreateNewHashEntry)(predX, predY, predTheta); + } + + PredIDV->push_back(OutHashEntry->stateID); + CostV->push_back(cost); + } + +#if TIME_DEBUG + time_getsuccs += clock()-currenttime; +#endif +} + +void EnvironmentNAVXYTHETALAT::SetAllActionsandAllOutcomes(CMDPSTATE* state) +{ + int cost; + +#if DEBUG + if (state->StateID >= (int)StateID2CoordTable.size()) { + throw SBPL_Exception("ERROR in Env... function: stateID illegal"); + } + + if ((int)state->Actions.size() != 0) { + throw SBPL_Exception("ERROR in Env_setAllActionsandAllOutcomes: actions already exist for the state"); + } +#endif + + // goal state should be absorbing + if (state->StateID == EnvNAVXYTHETALAT.goalstateid) { + return; + } + + // get X, Y for the state + EnvNAVXYTHETALATHashEntry_t* HashEntry = StateID2CoordTable[state->StateID]; + + // iterate through actions + for (int aind = 0; aind < EnvNAVXYTHETALATCfg.actionwidth; aind++) { + EnvNAVXYTHETALATAction_t* nav3daction = &EnvNAVXYTHETALATCfg.ActionsV[(unsigned int)HashEntry->Theta][aind]; + int newX = HashEntry->X + nav3daction->dX; + int newY = HashEntry->Y + nav3daction->dY; + int newTheta = normalizeDiscAngle(nav3daction->endtheta); + + // skip the invalid cells + if (!IsValidCell(newX, newY)) { + continue; + } + + // get cost + cost = GetActionCost(HashEntry->X, HashEntry->Y, HashEntry->Theta, nav3daction); + if (cost >= INFINITECOST) { + continue; + } + + // add the action + CMDPACTION* action = state->AddAction(aind); + +#if TIME_DEBUG + clock_t currenttime = clock(); +#endif + + EnvNAVXYTHETALATHashEntry_t* OutHashEntry; + if ((OutHashEntry = (this->*GetHashEntry)(newX, newY, newTheta)) == NULL) { + // have to create a new entry + OutHashEntry = (this->*CreateNewHashEntry)(newX, newY, newTheta); + } + action->AddOutcome(OutHashEntry->stateID, cost, 1.0); + +#if TIME_DEBUG + time3_addallout += clock()-currenttime; +#endif + } +} + +void EnvironmentNAVXYTHETALAT::GetPredsofChangedEdges( + std::vector const* changedcellsV, + std::vector* preds_of_changededgesIDV) +{ + nav2dcell_t cell; + sbpl_xy_theta_cell_t affectedcell; + EnvNAVXYTHETALATHashEntry_t* affectedHashEntry; + + // increment iteration for processing savings + iteration++; + + for (int i = 0; i < (int)changedcellsV->size(); i++) { + cell = changedcellsV->at(i); + + // now iterate over all states that could potentially be affected + for (int sind = 0; sind < (int)affectedpredstatesV.size(); sind++) { + affectedcell = affectedpredstatesV.at(sind); + + // translate to correct for the offset + affectedcell.x = affectedcell.x + cell.x; + affectedcell.y = affectedcell.y + cell.y; + + // insert only if it was actually generated + affectedHashEntry = (this->*GetHashEntry)(affectedcell.x, affectedcell.y, affectedcell.theta); + if (affectedHashEntry != NULL && affectedHashEntry->iteration < iteration) { + preds_of_changededgesIDV->push_back(affectedHashEntry->stateID); + affectedHashEntry->iteration = iteration; // mark as already inserted + } + } + } +} + +void EnvironmentNAVXYTHETALAT::GetSuccsofChangedEdges( + std::vector const* changedcellsV, + std::vector* succs_of_changededgesIDV) +{ + nav2dcell_t cell; + sbpl_xy_theta_cell_t affectedcell; + EnvNAVXYTHETALATHashEntry_t* affectedHashEntry; + + throw SBPL_Exception("ERROR: getsuccs is not supported currently"); + + // increment iteration for processing savings + iteration++; + + // TODO - check + for (int i = 0; i < (int)changedcellsV->size(); i++) { + cell = changedcellsV->at(i); + + // now iterate over all states that could potentially be affected + for (int sind = 0; sind < (int)affectedsuccstatesV.size(); sind++) { + affectedcell = affectedsuccstatesV.at(sind); + + // translate to correct for the offset + affectedcell.x = affectedcell.x + cell.x; + affectedcell.y = affectedcell.y + cell.y; + + // insert only if it was actually generated + affectedHashEntry = (this->*GetHashEntry)(affectedcell.x, affectedcell.y, affectedcell.theta); + if (affectedHashEntry != NULL && affectedHashEntry->iteration < iteration) { + succs_of_changededgesIDV->push_back(affectedHashEntry->stateID); + // mark as already inserted + affectedHashEntry->iteration = iteration; + } + } + } +} + +void EnvironmentNAVXYTHETALAT::InitializeEnvironment() +{ + EnvNAVXYTHETALATHashEntry_t* HashEntry; + + int maxsize = EnvNAVXYTHETALATCfg.EnvWidth_c * EnvNAVXYTHETALATCfg.EnvHeight_c * EnvNAVXYTHETALATCfg.NumThetaDirs; + + if (maxsize <= SBPL_XYTHETALAT_MAXSTATESFORLOOKUP) { + SBPL_PRINTF("environment stores states in lookup table\n"); + + Coord2StateIDHashTable_lookup = new EnvNAVXYTHETALATHashEntry_t*[maxsize]; + for (int i = 0; i < maxsize; i++) { + Coord2StateIDHashTable_lookup[i] = NULL; + } + GetHashEntry = &EnvironmentNAVXYTHETALAT::GetHashEntry_lookup; + CreateNewHashEntry = &EnvironmentNAVXYTHETALAT::CreateNewHashEntry_lookup; + + // not using hash table + HashTableSize = 0; + Coord2StateIDHashTable = NULL; + } + else { + SBPL_PRINTF("environment stores states in hashtable\n"); + + // initialize the map from Coord to StateID + HashTableSize = 4 * 1024 * 1024; // should be power of two + Coord2StateIDHashTable = new std::vector[HashTableSize]; + GetHashEntry = &EnvironmentNAVXYTHETALAT::GetHashEntry_hash; + CreateNewHashEntry = &EnvironmentNAVXYTHETALAT::CreateNewHashEntry_hash; + + // not using hash + Coord2StateIDHashTable_lookup = NULL; + } + + // initialize the map from StateID to Coord + StateID2CoordTable.clear(); + + // create start state + if (NULL == (HashEntry = (this->*GetHashEntry)( + EnvNAVXYTHETALATCfg.StartX_c, + EnvNAVXYTHETALATCfg.StartY_c, + EnvNAVXYTHETALATCfg.StartTheta))) + { + // have to create a new entry + HashEntry = (this->*CreateNewHashEntry)( + EnvNAVXYTHETALATCfg.StartX_c, + EnvNAVXYTHETALATCfg.StartY_c, + EnvNAVXYTHETALATCfg.StartTheta); + } + EnvNAVXYTHETALAT.startstateid = HashEntry->stateID; + + // create goal state + if ((HashEntry = (this->*GetHashEntry)( + EnvNAVXYTHETALATCfg.EndX_c, + EnvNAVXYTHETALATCfg.EndY_c, + EnvNAVXYTHETALATCfg.EndTheta)) == NULL) + { + // have to create a new entry + HashEntry = (this->*CreateNewHashEntry)( + EnvNAVXYTHETALATCfg.EndX_c, + EnvNAVXYTHETALATCfg.EndY_c, + EnvNAVXYTHETALATCfg.EndTheta); + } + EnvNAVXYTHETALAT.goalstateid = HashEntry->stateID; + + // initialized + EnvNAVXYTHETALAT.bInitialized = true; +} + +// examples of hash functions: map state coordinates onto a hash value +// #define GETHASHBIN(X, Y) (Y*WIDTH_Y+X) +// here we have state coord: +unsigned int EnvironmentNAVXYTHETALAT::GETHASHBIN( + unsigned int X1, + unsigned int X2, + unsigned int Theta) +{ + return inthash(inthash(X1) + (inthash(X2) << 1) + (inthash(Theta) << 2)) & (HashTableSize - 1); +} + +void EnvironmentNAVXYTHETALAT::PrintHashTableHist(FILE* fOut) +{ + int s0 = 0, s1 = 0, s50 = 0, s100 = 0, s200 = 0, s300 = 0, slarge = 0; + + for (int j = 0; j < HashTableSize; j++) { + if ((int)Coord2StateIDHashTable[j].size() == 0) + s0++; + else if ((int)Coord2StateIDHashTable[j].size() < 5) + s1++; + else if ((int)Coord2StateIDHashTable[j].size() < 25) + s50++; + else if ((int)Coord2StateIDHashTable[j].size() < 50) + s100++; + else if ((int)Coord2StateIDHashTable[j].size() < 100) + s200++; + else if ((int)Coord2StateIDHashTable[j].size() < 400) + s300++; + else + slarge++; + } + SBPL_FPRINTF(fOut, "hash table histogram: 0:%d, <5:%d, <25:%d, <50:%d, <100:%d, <400:%d, >400:%d\n", s0, s1, s50, + s100, s200, s300, slarge); +} + +int EnvironmentNAVXYTHETALAT::GetFromToHeuristic(int FromStateID, int ToStateID) +{ +#if USE_HEUR==0 + return 0; +#endif + +#if DEBUG + if (FromStateID >= (int)StateID2CoordTable.size() || + ToStateID >= (int)StateID2CoordTable.size()) + { + SBPL_ERROR("ERROR in EnvNAVXYTHETALAT... function: stateID illegal\n"); + throw SBPL_Exception(); + } +#endif + + // get X, Y for the state + EnvNAVXYTHETALATHashEntry_t* FromHashEntry = StateID2CoordTable[FromStateID]; + EnvNAVXYTHETALATHashEntry_t* ToHashEntry = StateID2CoordTable[ToStateID]; + + // TODO - check if one of the gridsearches already computed and then use it. + + return (int)(NAVXYTHETALAT_COSTMULT_MTOMM * + EuclideanDistance_m(FromHashEntry->X, FromHashEntry->Y, ToHashEntry->X, ToHashEntry->Y) / + EnvNAVXYTHETALATCfg.nominalvel_mpersecs); + +} + +int EnvironmentNAVXYTHETALAT::GetGoalHeuristic(int stateID) +{ +#if USE_HEUR==0 + return 0; +#endif + +#if DEBUG + if (stateID >= (int)StateID2CoordTable.size()) { + throw SBPL_Exception("ERROR in EnvNAVXYTHETALAT... function: stateID illegal"); + } +#endif + + EnvNAVXYTHETALATHashEntry_t* HashEntry = StateID2CoordTable[stateID]; + // computes distances from start state that is grid2D, so it is EndX_c EndY_c + int h2D = grid2Dsearchfromgoal->getlowerboundoncostfromstart_inmm(HashEntry->X, HashEntry->Y); + int hEuclid = (int)(NAVXYTHETALAT_COSTMULT_MTOMM * + EuclideanDistance_m(HashEntry->X, HashEntry->Y, EnvNAVXYTHETALATCfg.EndX_c, EnvNAVXYTHETALATCfg.EndY_c)); + + // define this function if it is used in the planner (heuristic backward search would use it) + return (int)(((double)__max(h2D, hEuclid)) / EnvNAVXYTHETALATCfg.nominalvel_mpersecs); +} + +int EnvironmentNAVXYTHETALAT::GetStartHeuristic(int stateID) +{ +#if USE_HEUR==0 + return 0; +#endif + +#if DEBUG + if (stateID >= (int)StateID2CoordTable.size()) { + throw SBPL_Exception("ERROR in EnvNAVXYTHETALAT... function: stateID illegal"); + } +#endif + + EnvNAVXYTHETALATHashEntry_t* HashEntry = StateID2CoordTable[stateID]; + int h2D = grid2Dsearchfromstart->getlowerboundoncostfromstart_inmm(HashEntry->X, HashEntry->Y); + int hEuclid = (int)(NAVXYTHETALAT_COSTMULT_MTOMM * + EuclideanDistance_m(EnvNAVXYTHETALATCfg.StartX_c, EnvNAVXYTHETALATCfg.StartY_c, HashEntry->X, HashEntry->Y)); + + // define this function if it is used in the planner (heuristic backward search would use it) + return (int)(((double)__max(h2D, hEuclid)) / EnvNAVXYTHETALATCfg.nominalvel_mpersecs); +} + +int EnvironmentNAVXYTHETALAT::SizeofCreatedEnv() +{ + return (int)StateID2CoordTable.size(); +} + +const EnvNAVXYTHETALATHashEntry_t* +EnvironmentNAVXYTHETALAT::GetStateEntry(int state_id) const +{ + if (state_id >= 0 && state_id < (int)StateID2CoordTable.size()) { + return StateID2CoordTable[state_id]; + } + else { + return NULL; + } +} + +//------------------------------------------------------------------------------ + + +void EnvironmentNAVXYTHETALAT::GetLazySuccs( + int SourceStateID, + std::vector* SuccIDV, + std::vector* CostV, + std::vector* isTrueCost, + std::vector* actionV) +{ + int aind; + +#if TIME_DEBUG + clock_t currenttime = clock(); +#endif + + // clear the successor array + SuccIDV->clear(); + CostV->clear(); + SuccIDV->reserve(EnvNAVXYTHETALATCfg.actionwidth); + CostV->reserve(EnvNAVXYTHETALATCfg.actionwidth); + isTrueCost->reserve(EnvNAVXYTHETALATCfg.actionwidth); + if (actionV != NULL) { + actionV->clear(); + actionV->reserve(EnvNAVXYTHETALATCfg.actionwidth); + } + + // goal state should be absorbing + if (SourceStateID == EnvNAVXYTHETALAT.goalstateid) { + return; + } + + // get X, Y for the state + EnvNAVXYTHETALATHashEntry_t* HashEntry = StateID2CoordTable[SourceStateID]; + + // iterate through actions + for (aind = 0; aind < EnvNAVXYTHETALATCfg.actionwidth; aind++) { + EnvNAVXYTHETALATAction_t* nav3daction = &EnvNAVXYTHETALATCfg.ActionsV[(unsigned int)HashEntry->Theta][aind]; + int newX = HashEntry->X + nav3daction->dX; + int newY = HashEntry->Y + nav3daction->dY; + int newTheta = normalizeDiscAngle(nav3daction->endtheta); + + // skip the invalid cells + if (!IsValidCell(newX, newY)) { + continue; + } + + // if we are supposed to return the action, then don't do lazy + if (!actionV) { + EnvNAVXYTHETALATHashEntry_t* OutHashEntry; + if ((OutHashEntry = (this->*GetHashEntry)(newX, newY, newTheta)) == NULL) { + OutHashEntry = (this->*CreateNewHashEntry)(newX, newY, newTheta); + } + SuccIDV->push_back(OutHashEntry->stateID); + CostV->push_back(nav3daction->cost); + isTrueCost->push_back(false); + continue; + } + + // get cost + int cost = GetActionCost(HashEntry->X, HashEntry->Y, HashEntry->Theta, nav3daction); + if (cost >= INFINITECOST) { + continue; + } + + EnvNAVXYTHETALATHashEntry_t* OutHashEntry; + if ((OutHashEntry = (this->*GetHashEntry)(newX, newY, newTheta)) == NULL) { + // have to create a new entry + OutHashEntry = (this->*CreateNewHashEntry)(newX, newY, newTheta); + } + + SuccIDV->push_back(OutHashEntry->stateID); + CostV->push_back(cost); + isTrueCost->push_back(true); + if (actionV != NULL) { + actionV->push_back(nav3daction); + } + } + +#if TIME_DEBUG + time_getsuccs += clock()-currenttime; +#endif +} + +int EnvironmentNAVXYTHETALAT::GetTrueCost(int parentID, int childID) +{ + EnvNAVXYTHETALATHashEntry_t* fromHash = StateID2CoordTable[parentID]; + EnvNAVXYTHETALATHashEntry_t* toHash = StateID2CoordTable[childID]; + + for (int i = 0; i < EnvNAVXYTHETALATCfg.actionwidth; i++) { + EnvNAVXYTHETALATAction_t* nav3daction = &EnvNAVXYTHETALATCfg.ActionsV[(unsigned int)fromHash->Theta][i]; + int newX = fromHash->X + nav3daction->dX; + int newY = fromHash->Y + nav3daction->dY; + int newTheta = normalizeDiscAngle(nav3daction->endtheta); + + // skip the invalid cells + if (!IsValidCell(newX, newY)) { + continue; + } + + EnvNAVXYTHETALATHashEntry_t* hash; + if ((hash = (this->*GetHashEntry)(newX, newY, newTheta)) == NULL) { + continue; + } + if (hash->stateID != toHash->stateID) { + continue; + } + + // get cost + int cost = GetActionCost(fromHash->X, fromHash->Y, fromHash->Theta, nav3daction); + + if (cost >= INFINITECOST) { + return -1; + } + return cost; + } + throw SBPL_Exception("This should never happen! we didn't find the state we need to get the true cost for!"); + return -1; +} + +void EnvironmentNAVXYTHETALAT::GetSuccsWithUniqueIds( + int SourceStateID, + std::vector* SuccIDV, + std::vector* CostV, + std::vector* actionV) +{ + GetSuccs(SourceStateID, SuccIDV, CostV, actionV); +} + +void EnvironmentNAVXYTHETALAT::GetLazySuccsWithUniqueIds( + int SourceStateID, + std::vector* SuccIDV, + std::vector* CostV, + std::vector* isTrueCost, + std::vector* actionV) +{ + GetLazySuccs(SourceStateID, SuccIDV, CostV, isTrueCost, actionV); +} + +bool EnvironmentNAVXYTHETALAT::isGoal(int id) +{ + return EnvNAVXYTHETALAT.goalstateid == id; +} + +void EnvironmentNAVXYTHETALAT::GetLazyPreds( + int TargetStateID, + std::vector* PredIDV, + std::vector* CostV, + std::vector* isTrueCost) +{ + int aind; + +#if TIME_DEBUG + clock_t currenttime = clock(); +#endif + + // get X, Y for the state + EnvNAVXYTHETALATHashEntry_t* HashEntry = StateID2CoordTable[TargetStateID]; + + // clear the successor array + PredIDV->clear(); + CostV->clear(); + PredIDV->reserve(EnvNAVXYTHETALATCfg.PredActionsV[(unsigned int)HashEntry->Theta].size()); + CostV->reserve(EnvNAVXYTHETALATCfg.PredActionsV[(unsigned int)HashEntry->Theta].size()); + + // iterate through actions + std::vector* actionsV = &EnvNAVXYTHETALATCfg.PredActionsV[(unsigned int)HashEntry->Theta]; + for (aind = 0; aind < (int)EnvNAVXYTHETALATCfg.PredActionsV[(unsigned int)HashEntry->Theta].size(); aind++) + { + EnvNAVXYTHETALATAction_t* nav3daction = actionsV->at(aind); + + int predX = HashEntry->X - nav3daction->dX; + int predY = HashEntry->Y - nav3daction->dY; + int predTheta = nav3daction->starttheta; + + //skip the invalid cells + if (!IsValidCell(predX, predY)) { + continue; + } + + EnvNAVXYTHETALATHashEntry_t* OutHashEntry; + if ((OutHashEntry = (this->*GetHashEntry)(predX, predY, predTheta)) == NULL) { + OutHashEntry = (this->*CreateNewHashEntry)(predX, predY, predTheta); + } + + PredIDV->push_back(OutHashEntry->stateID); + CostV->push_back(nav3daction->cost); + isTrueCost->push_back(false); + } + +#if TIME_DEBUG + time_getsuccs += clock()-currenttime; +#endif +} + +void EnvironmentNAVXYTHETALAT::GetPredsWithUniqueIds( + int TargetStateID, + std::vector* PredIDV, + std::vector* CostV) +{ + GetPreds(TargetStateID, PredIDV, CostV); +} + +void EnvironmentNAVXYTHETALAT::GetLazyPredsWithUniqueIds( + int TargetStateID, + std::vector* PredIDV, + std::vector* CostV, + std::vector* isTrueCost) +{ + GetLazyPreds(TargetStateID, PredIDV, CostV, isTrueCost); +} diff --git a/navigations/sbpl/src/discrete_space_information/environment_navxythetamlevlat.cpp b/navigations/sbpl/src/discrete_space_information/environment_navxythetamlevlat.cpp new file mode 100755 index 0000000..8074125 --- /dev/null +++ b/navigations/sbpl/src/discrete_space_information/environment_navxythetamlevlat.cpp @@ -0,0 +1,482 @@ +/* + * Copyright (c) 2008, Maxim Likhachev + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Carnegie Mellon University nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include +#include +#include + +using namespace std; + +#if TIME_DEBUG +static clock_t time3_addallout = 0; +static clock_t time_gethash = 0; +static clock_t time_createhash = 0; +static clock_t time_getsuccs = 0; +#endif + +static long int checks = 0; + +//-----------------constructors/destructors------------------------------- + +EnvironmentNAVXYTHETAMLEVLAT::EnvironmentNAVXYTHETAMLEVLAT() +{ + numofadditionalzlevs = 0; //by default there is only base level, no additional levels + AddLevelFootprintPolygonV = NULL; + AdditionalInfoinActionsV = NULL; + AddLevelGrid2D = NULL; + AddLevel_cost_possibly_circumscribed_thresh = NULL; + AddLevel_cost_inscribed_thresh = NULL; +} + +EnvironmentNAVXYTHETAMLEVLAT::~EnvironmentNAVXYTHETAMLEVLAT() +{ + if (AddLevelFootprintPolygonV != NULL) { + delete[] AddLevelFootprintPolygonV; + AddLevelFootprintPolygonV = NULL; + } + + if (AdditionalInfoinActionsV != NULL) { + for (int tind = 0; tind < EnvNAVXYTHETALATCfg.NumThetaDirs; tind++) { + for (int aind = 0; aind < EnvNAVXYTHETALATCfg.actionwidth; aind++) { + delete[] AdditionalInfoinActionsV[tind][aind].intersectingcellsV; + } + delete[] AdditionalInfoinActionsV[tind]; + } + delete[] AdditionalInfoinActionsV; + AdditionalInfoinActionsV = NULL; + } + + if (AddLevelGrid2D != NULL) { + for (int levelind = 0; levelind < numofadditionalzlevs; levelind++) { + for (int xind = 0; xind < EnvNAVXYTHETALATCfg.EnvWidth_c; xind++) { + delete[] AddLevelGrid2D[levelind][xind]; + } + delete[] AddLevelGrid2D[levelind]; + } + delete[] AddLevelGrid2D; + AddLevelGrid2D = NULL; + } + + if (AddLevel_cost_possibly_circumscribed_thresh != NULL) { + delete[] AddLevel_cost_possibly_circumscribed_thresh; + AddLevel_cost_possibly_circumscribed_thresh = NULL; + } + + if (AddLevel_cost_inscribed_thresh != NULL) { + delete[] AddLevel_cost_inscribed_thresh; + AddLevel_cost_inscribed_thresh = NULL; + } + + //reset the number of additional levels + numofadditionalzlevs = 0; +} + +//--------------------------------------------------------------------- + +//-------------------problem specific and local functions--------------------- + +//returns true if cell is traversable and within map limits - it checks against all levels including the base one +bool EnvironmentNAVXYTHETAMLEVLAT::IsValidCell(int X, int Y) +{ + int levelind; + + if (!EnvironmentNAVXYTHETALAT::IsValidCell(X, Y)) return false; + + //iterate through the additional levels + for (levelind = 0; levelind < numofadditionalzlevs; levelind++) { + if (AddLevelGrid2D[levelind][X][Y] >= EnvNAVXYTHETALATCfg.obsthresh) return false; + } + //otherwise the cell is valid at all levels + return true; +} + +// returns true if cell is traversable and within map limits for a particular level +bool EnvironmentNAVXYTHETAMLEVLAT::IsValidCell(int X, int Y, int levind) +{ + return (X >= 0 && X < EnvNAVXYTHETALATCfg.EnvWidth_c && Y >= 0 && Y < EnvNAVXYTHETALATCfg.EnvHeight_c && levind < + numofadditionalzlevs && AddLevelGrid2D[levind][X][Y] < EnvNAVXYTHETALATCfg.obsthresh); +} + +//returns true if cell is untraversable at all levels +bool EnvironmentNAVXYTHETAMLEVLAT::IsObstacle(int X, int Y) +{ + int levelind; + + if (EnvironmentNAVXYTHETALAT::IsObstacle(X, Y)) return true; + + //iterate through the additional levels + for (levelind = 0; levelind < numofadditionalzlevs; levelind++) { + if (AddLevelGrid2D[levelind][X][Y] >= EnvNAVXYTHETALATCfg.obsthresh) return true; + } + //otherwise the cell is obstacle-free at all cells + return false; +} + +//returns true if cell is untraversable in level # levelnum. If levelnum = -1, then it checks all levels +bool EnvironmentNAVXYTHETAMLEVLAT::IsObstacle(int X, int Y, int levind) +{ +#if DEBUG + if(levind >= numofadditionalzlevs) + { + SBPL_ERROR("ERROR: IsObstacle invoked at level %d\n", levind); + SBPL_FPRINTF(fDeb, "ERROR: IsObstacle invoked at level %d\n", levind); + return false; + } +#endif + + return (AddLevelGrid2D[levind][X][Y] >= EnvNAVXYTHETALATCfg.obsthresh); +} + +// returns the maximum over all levels of the cost corresponding to the cell +unsigned char EnvironmentNAVXYTHETAMLEVLAT::GetMapCost(int X, int Y) +{ + unsigned char mapcost = EnvNAVXYTHETALATCfg.Grid2D[X][Y]; + + for (int levind = 0; levind < numofadditionalzlevs; levind++) { + mapcost = __max(mapcost, AddLevelGrid2D[levind][X][Y]); + } + + return mapcost; +} + +// returns the cost corresponding to the cell at level levind +unsigned char EnvironmentNAVXYTHETAMLEVLAT::GetMapCost(int X, int Y, int levind) +{ +#if DEBUG + if(levind >= numofadditionalzlevs) + { + SBPL_ERROR("ERROR: GetMapCost invoked at level %d\n", levind); + SBPL_FPRINTF(fDeb, "ERROR: GetMapCost invoked at level %d\n", levind); + return false; + } +#endif + + return AddLevelGrid2D[levind][X][Y]; +} + +//returns false if robot intersects obstacles or lies outside of the map. +bool EnvironmentNAVXYTHETAMLEVLAT::IsValidConfiguration(int X, int Y, int Theta) +{ + //check the base footprint first + if (!EnvironmentNAVXYTHETALAT::IsValidConfiguration(X, Y, Theta)) return false; + + //check the remaining levels now + vector footprint; + sbpl_xy_theta_pt_t pose; + + //compute continuous pose + pose.x = DISCXY2CONT(X, EnvNAVXYTHETALATCfg.cellsize_m); + pose.y = DISCXY2CONT(Y, EnvNAVXYTHETALATCfg.cellsize_m); + pose.theta = DiscTheta2Cont(Theta, EnvNAVXYTHETALATCfg.NumThetaDirs); + + //iterate over additional levels + for (int levind = 0; levind < numofadditionalzlevs; levind++) { + + //compute footprint cells + footprint.clear(); + get_2d_footprint_cells(AddLevelFootprintPolygonV[levind], &footprint, pose, EnvNAVXYTHETALATCfg.cellsize_m); + + //iterate over all footprint cells + for (int find = 0; find < (int)footprint.size(); find++) { + int x = footprint.at(find).x; + int y = footprint.at(find).y; + + if (x < 0 || x >= EnvNAVXYTHETALATCfg.EnvWidth_c || y < 0 || y >= EnvNAVXYTHETALATCfg.EnvHeight_c + || AddLevelGrid2D[levind][x][y] >= EnvNAVXYTHETALATCfg.obsthresh) { + return false; + } + } + } + + return true; +} + +int EnvironmentNAVXYTHETAMLEVLAT::GetActionCost(int SourceX, int SourceY, int SourceTheta, + EnvNAVXYTHETALATAction_t* action) +{ + int basecost = EnvironmentNAVXYTHETALAT::GetActionCost(SourceX, SourceY, SourceTheta, action); + + if (basecost >= INFINITECOST) return INFINITECOST; + + int addcost = GetActionCostacrossAddLevels(SourceX, SourceY, SourceTheta, action); + + return __max(basecost, addcost); +} + +int EnvironmentNAVXYTHETAMLEVLAT::GetActionCostacrossAddLevels(int SourceX, int SourceY, int SourceTheta, + EnvNAVXYTHETALATAction_t* action) +{ + sbpl_2Dcell_t cell; + sbpl_xy_theta_cell_t interm3Dcell; + int i, levelind = -1; + + if (!IsValidCell(SourceX, SourceY)) return INFINITECOST; + if (!IsValidCell(SourceX + action->dX, SourceY + action->dY)) return INFINITECOST; + + //case of no levels + if (numofadditionalzlevs == 0) return 0; + + //iterate through the additional levels + for (levelind = 0; levelind < numofadditionalzlevs; levelind++) { + if (AddLevelGrid2D[levelind][SourceX + action->dX][SourceY + action->dY] + >= AddLevel_cost_inscribed_thresh[levelind]) return INFINITECOST; + } + + //need to iterate over discretized center cells and compute cost based on them + unsigned char maxcellcost = 0; + unsigned char* maxcellcostateachlevel = new unsigned char[numofadditionalzlevs]; + for (levelind = 0; levelind < numofadditionalzlevs; levelind++) { + maxcellcostateachlevel[levelind] = 0; + } + + for (i = 0; i < (int)action->interm3DcellsV.size() && maxcellcost < EnvNAVXYTHETALATCfg.obsthresh; i++) { + interm3Dcell = action->interm3DcellsV.at(i); + interm3Dcell.x = interm3Dcell.x + SourceX; + interm3Dcell.y = interm3Dcell.y + SourceY; + + if (interm3Dcell.x < 0 || interm3Dcell.x >= EnvNAVXYTHETALATCfg.EnvWidth_c || interm3Dcell.y < 0 || + interm3Dcell.y >= EnvNAVXYTHETALATCfg.EnvHeight_c) + { + maxcellcost = EnvNAVXYTHETALATCfg.obsthresh; + break; + } + + for (levelind = 0; levelind < numofadditionalzlevs; levelind++) { + maxcellcost = __max(maxcellcost, AddLevelGrid2D[levelind][interm3Dcell.x][interm3Dcell.y]); + maxcellcostateachlevel[levelind] = __max(maxcellcostateachlevel[levelind], + AddLevelGrid2D[levelind][interm3Dcell.x][interm3Dcell.y]); + //check that the robot is NOT in the cell at which there is no valid orientation + if (maxcellcostateachlevel[levelind] >= AddLevel_cost_inscribed_thresh[levelind]) { + maxcellcost = EnvNAVXYTHETALATCfg.obsthresh; + maxcellcostateachlevel[levelind] = EnvNAVXYTHETALATCfg.obsthresh; + break; + } + } + } + + //check collisions that for the particular footprint orientation along the action + for (levelind = 0; levelind < numofadditionalzlevs && (int)maxcellcost < EnvNAVXYTHETALATCfg.obsthresh; + levelind++) + { + if (AddLevelFootprintPolygonV[levelind].size() > 1 && (int)maxcellcostateachlevel[levelind] >= + AddLevel_cost_possibly_circumscribed_thresh[levelind]) + { + checks++; + + //get intersecting cells for this level + vector* intersectingcellsV = + &AdditionalInfoinActionsV[(unsigned int)action->starttheta][action->aind].intersectingcellsV[levelind]; + for (i = 0; i < (int)intersectingcellsV->size(); i++) { + //get the cell in the map + cell = intersectingcellsV->at(i); + cell.x = cell.x + SourceX; + cell.y = cell.y + SourceY; + + //check validity + if (!IsValidCell(cell.x, cell.y, levelind)) { + maxcellcost = EnvNAVXYTHETALATCfg.obsthresh; + break; + } + + //if(AddLevelGrid2D[levelind][cell.x][cell.y] > maxcellcost) + ////cost computation changed: cost = max(cost of centers of + //the robot along action) + // maxcellcost = AddLevelGrid2D[levelind][cell.x][cell.y]; + // //intersecting cells are only used for collision checking + } + } + } + + //no need to max it with grid2D to ensure consistency of h2D since it is done for the base class + + //clean up + delete[] maxcellcostateachlevel; + + if (maxcellcost >= EnvNAVXYTHETALATCfg.obsthresh) + return INFINITECOST; + else + return action->cost * (((int)maxcellcost) + 1); //use cell cost as multiplicative factor +} + +//--------------------------------------------------------------------- + +//------------debugging functions--------------------------------------------- + +//----------------------------------------------------------------------------- + +//-----------interface with outside functions----------------------------------- + +/* + initialization of additional levels. 0 is the original one. All additional ones will start with index 1 + */ +bool EnvironmentNAVXYTHETAMLEVLAT::InitializeAdditionalLevels(int numofadditionalzlevs_in, + const vector* perimeterptsV, + unsigned char* cost_inscribed_thresh_in, + unsigned char* cost_possibly_circumscribed_thresh_in) +{ + int levelind = -1, xind = -1, yind = -1; + sbpl_xy_theta_pt_t temppose; + temppose.x = 0.0; + temppose.y = 0.0; + temppose.theta = 0.0; + vector footprint; + + numofadditionalzlevs = numofadditionalzlevs_in; + SBPL_PRINTF("Planning with additional z levels. Number of additional z levels = %d\n", numofadditionalzlevs); + + //allocate memory and set FootprintPolygons for additional levels + AddLevelFootprintPolygonV = new vector [numofadditionalzlevs]; + for (levelind = 0; levelind < numofadditionalzlevs; levelind++) { + AddLevelFootprintPolygonV[levelind] = perimeterptsV[levelind]; + } + + //print out the size of a footprint for each additional level + for (levelind = 0; levelind < numofadditionalzlevs; levelind++) { + footprint.clear(); + get_2d_footprint_cells(AddLevelFootprintPolygonV[levelind], &footprint, temppose, + EnvNAVXYTHETALATCfg.cellsize_m); + SBPL_PRINTF("number of cells in footprint for additional level %d = %d\n", levelind, + (unsigned int)footprint.size()); + } + + //compute additional levels action info + SBPL_PRINTF("pre-computing action data for additional levels:\n"); + AdditionalInfoinActionsV = new EnvNAVXYTHETAMLEVLATAddInfoAction_t*[EnvNAVXYTHETALATCfg.NumThetaDirs]; + for (int tind = 0; tind < EnvNAVXYTHETALATCfg.NumThetaDirs; tind++) { + SBPL_PRINTF("pre-computing for angle %d out of %d angles\n", tind, EnvNAVXYTHETALATCfg.NumThetaDirs); + + //compute sourcepose + sbpl_xy_theta_pt_t sourcepose; + sourcepose.x = DISCXY2CONT(0, EnvNAVXYTHETALATCfg.cellsize_m); + sourcepose.y = DISCXY2CONT(0, EnvNAVXYTHETALATCfg.cellsize_m); + sourcepose.theta = DiscTheta2Cont(tind, EnvNAVXYTHETALATCfg.NumThetaDirs); + + AdditionalInfoinActionsV[tind] = new EnvNAVXYTHETAMLEVLATAddInfoAction_t[EnvNAVXYTHETALATCfg.actionwidth]; + + //iterate over actions for each angle + for (int aind = 0; aind < EnvNAVXYTHETALATCfg.actionwidth; aind++) { + EnvNAVXYTHETALATAction_t* nav3daction = &EnvNAVXYTHETALATCfg.ActionsV[tind][aind]; + + //initialize delta variables + AdditionalInfoinActionsV[tind][aind].dX = nav3daction->dX; + AdditionalInfoinActionsV[tind][aind].dY = nav3daction->dY; + AdditionalInfoinActionsV[tind][aind].starttheta = tind; + AdditionalInfoinActionsV[tind][aind].endtheta = nav3daction->endtheta; + + //finally, create the footprint for the action for each level + AdditionalInfoinActionsV[tind][aind].intersectingcellsV = new vector [numofadditionalzlevs]; + for (levelind = 0; levelind < numofadditionalzlevs; levelind++) { + get_2d_motion_cells(AddLevelFootprintPolygonV[levelind], + EnvNAVXYTHETALATCfg.ActionsV[tind][aind].intermptV, + &AdditionalInfoinActionsV[tind][aind].intersectingcellsV[levelind], + EnvNAVXYTHETALATCfg.cellsize_m); + } + } + } + + //create maps for additional levels and initialize to zeros (freespace) + AddLevelGrid2D = new unsigned char**[numofadditionalzlevs]; + for (levelind = 0; levelind < numofadditionalzlevs; levelind++) { + AddLevelGrid2D[levelind] = new unsigned char*[EnvNAVXYTHETALATCfg.EnvWidth_c]; + for (xind = 0; xind < EnvNAVXYTHETALATCfg.EnvWidth_c; xind++) { + AddLevelGrid2D[levelind][xind] = new unsigned char[EnvNAVXYTHETALATCfg.EnvHeight_c]; + for (yind = 0; yind < EnvNAVXYTHETALATCfg.EnvHeight_c; yind++) { + AddLevelGrid2D[levelind][xind][yind] = 0; + } + } + } + + //create inscribed and circumscribed cost thresholds + AddLevel_cost_possibly_circumscribed_thresh = new unsigned char[numofadditionalzlevs]; + AddLevel_cost_inscribed_thresh = new unsigned char[numofadditionalzlevs]; + for (levelind = 0; levelind < numofadditionalzlevs; levelind++) { + AddLevel_cost_possibly_circumscribed_thresh[levelind] = cost_possibly_circumscribed_thresh_in[levelind]; + AddLevel_cost_inscribed_thresh[levelind] = cost_inscribed_thresh_in[levelind]; + } + + return true; +} + +//set 2D map for the additional level levind +bool EnvironmentNAVXYTHETAMLEVLAT::Set2DMapforAddLev(const unsigned char* mapdata, int levind) +{ + int xind = -1, yind = -1; + + if (AddLevelGrid2D == NULL) { + SBPL_ERROR("ERROR: failed to set2Dmap because the map was not allocated previously\n"); + return false; + } + + for (xind = 0; xind < EnvNAVXYTHETALATCfg.EnvWidth_c; xind++) { + for (yind = 0; yind < EnvNAVXYTHETALATCfg.EnvHeight_c; yind++) { + AddLevelGrid2D[levind][xind][yind] = mapdata[xind + yind * EnvNAVXYTHETALATCfg.EnvWidth_c]; + } + } + + return true; +} + +//set 2D map for the additional level levind +//the version of Set2DMapforAddLev that takes newmap as 2D array instead of one linear array +bool EnvironmentNAVXYTHETAMLEVLAT::Set2DMapforAddLev(const unsigned char** NewGrid2D, int levind) +{ + int xind = -1, yind = -1; + + if (AddLevelGrid2D == NULL) { + SBPL_ERROR("ERROR: failed to set2Dmap because the map was not allocated previously\n"); + return false; + } + + for (xind = 0; xind < EnvNAVXYTHETALATCfg.EnvWidth_c; xind++) { + for (yind = 0; yind < EnvNAVXYTHETALATCfg.EnvHeight_c; yind++) { + AddLevelGrid2D[levind][xind][yind] = NewGrid2D[xind][yind]; + } + } + + return true; +} + +/* + update the traversability of a cell in addtional level zlev (this is not to update basic level) + */ +bool EnvironmentNAVXYTHETAMLEVLAT::UpdateCostinAddLev(int x, int y, unsigned char newcost, int zlev) +{ +#if DEBUG + //SBPL_FPRINTF(fDeb, "Cost updated for cell %d %d at level %d from old cost=%d to new cost=%d\n", x, y, zlev, AddLevelGrid2D[zlev][x][y], newcost); +#endif + + AddLevelGrid2D[zlev][x][y] = newcost; + + //no need to update heuristics because at this point it is computed solely based on the basic level + + return true; +} + +//------------------------------------------------------------------------------ diff --git a/navigations/sbpl/src/discrete_space_information/environment_robarm.cpp b/navigations/sbpl/src/discrete_space_information/environment_robarm.cpp new file mode 100755 index 0000000..54ae989 --- /dev/null +++ b/navigations/sbpl/src/discrete_space_information/environment_robarm.cpp @@ -0,0 +1,1546 @@ +/* + * Copyright (c) 2008, Maxim Likhachev + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Carnegie Mellon University nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include + +using namespace std; + +#define COSTMULT 1000 + +//static clock_t time3_addallout = 0; +//static clock_t time_gethash = 0; +//static clock_t time_createhash = 0; + +#define XYTO2DIND(x,y) ((x) + (y)*EnvROBARMCfg.EnvWidth_c) + +#define DIRECTIONS 8 +int dx[DIRECTIONS] = {1, 1, 1, 0, 0, -1, -1, -1}; +int dy[DIRECTIONS] = {1, 0, -1, 1, -1, -1, 0, 1}; + +//-------------------state access functions--------------------- + +static unsigned int inthash(unsigned int key) +{ + key += (key << 12); + key ^= (key >> 22); + key += (key << 4); + key ^= (key >> 9); + key += (key << 10); + key ^= (key >> 2); + key += (key << 7); + key ^= (key >> 12); + return key; +} + +//examples of hash functions: map state coordinates onto a hash value +//#define GETHASHBIN(X, Y) (Y*WIDTH_Y+X) +//here we have state coord: +unsigned int EnvironmentROBARM::GETHASHBIN(short unsigned int* coord, int numofcoord) +{ + int val = 0; + + for (int i = 0; i < numofcoord; i++) { + val += inthash(coord[i]) << i; + } + + return inthash(val) & (EnvROBARM.HashTableSize - 1); +} + +void EnvironmentROBARM::PrintHashTableHist() +{ + int s0 = 0, s1 = 0, s50 = 0, s100 = 0, s200 = 0, s300 = 0, slarge = 0; + + for (int j = 0; j < EnvROBARM.HashTableSize; j++) { + if ((int)EnvROBARM.Coord2StateIDHashTable[j].size() == 0) + s0++; + else if ((int)EnvROBARM.Coord2StateIDHashTable[j].size() < 50) + s1++; + else if ((int)EnvROBARM.Coord2StateIDHashTable[j].size() < 100) + s50++; + else if ((int)EnvROBARM.Coord2StateIDHashTable[j].size() < 200) + s100++; + else if ((int)EnvROBARM.Coord2StateIDHashTable[j].size() < 300) + s200++; + else if ((int)EnvROBARM.Coord2StateIDHashTable[j].size() < 400) + s300++; + else + slarge++; + } + SBPL_PRINTF("hash table histogram: 0:%d, <50:%d, <100:%d, <200:%d, <300:%d, <400:%d >400:%d\n", s0, s1, s50, s100, + s200, s300, slarge); +} + +EnvROBARMHashEntry_t* EnvironmentROBARM::GetHashEntry(short unsigned int* coord, int numofcoord, bool bIsGoal) +{ + //clock_t currenttime = clock(); + + //if it is goal + if (bIsGoal) { + return EnvROBARM.goalHashEntry; + } + + int binid = GETHASHBIN(coord, numofcoord); + +#if DEBUG + if ((int)EnvROBARM.Coord2StateIDHashTable[binid].size() > 500) + { + SBPL_PRINTF("WARNING: Hash table has a bin %d (coord0=%d) of size %d\n", + binid, coord[0], (int)EnvROBARM.Coord2StateIDHashTable[binid].size()); + + PrintHashTableHist(); + } +#endif + + //iterate over the states in the bin and select the perfect match + for (int ind = 0; ind < (int)EnvROBARM.Coord2StateIDHashTable[binid].size(); ind++) { + int j = 0; + for (j = 0; j < numofcoord; j++) { + if (EnvROBARM.Coord2StateIDHashTable[binid][ind]->coord[j] != coord[j]) { + break; + } + } + if (j == numofcoord) { + //time_gethash += clock()-currenttime; + return EnvROBARM.Coord2StateIDHashTable[binid][ind]; + } + } + + //time_gethash += clock()-currenttime; + + return NULL; +} + +EnvROBARMHashEntry_t* EnvironmentROBARM::CreateNewHashEntry(short unsigned int* coord, int numofcoord, + short unsigned int endeffx, short unsigned int endeffy) +{ + int i; + + //clock_t currenttime = clock(); + + EnvROBARMHashEntry_t* HashEntry = new EnvROBARMHashEntry_t; + + memcpy(HashEntry->coord, coord, numofcoord * sizeof(short unsigned int)); + HashEntry->endeffx = endeffx; + HashEntry->endeffy = endeffy; + + HashEntry->stateID = EnvROBARM.StateID2CoordTable.size(); + + //insert into the tables + EnvROBARM.StateID2CoordTable.push_back(HashEntry); + + //get the hash table bin + i = GETHASHBIN(HashEntry->coord, numofcoord); + + //insert the entry into the bin + EnvROBARM.Coord2StateIDHashTable[i].push_back(HashEntry); + + //insert into and initialize the mappings + int* entry = new int[NUMOFINDICES_STATEID2IND]; + StateID2IndexMapping.push_back(entry); + for (i = 0; i < NUMOFINDICES_STATEID2IND; i++) { + StateID2IndexMapping[HashEntry->stateID][i] = -1; + } + + if (HashEntry->stateID != (int)StateID2IndexMapping.size() - 1) { + throw SBPL_Exception("ERROR in Env... function: last state has incorrect stateID"); + } + + //time_createhash += clock()-currenttime; + + return HashEntry; +} + +//----------------------------------------------------------------------------- + +//---------------heuristic values computation------------------------- + +int EnvironmentROBARM::distanceincoord(unsigned short* statecoord1, unsigned short* statecoord2) +{ + int totaldiff = 0; + + for (int i = 0; i < NUMOFLINKS; i++) { + int diff = abs(statecoord1[i] - statecoord2[i]); + //totaldiff += __min(diff, RobArmStateSpace.anglevals[i] - diff); + totaldiff = __max(totaldiff, __min(diff, EnvROBARMCfg.anglevals[i] - diff)); + } + + return totaldiff; +} + +void EnvironmentROBARM::ReInitializeState2D(State2D* state) +{ + state->g = INFINITECOST; + state->iterationclosed = 0; +} + +void EnvironmentROBARM::InitializeState2D(State2D* state, short unsigned int x, short unsigned int y) +{ + state->g = INFINITECOST; + state->iterationclosed = 0; + state->x = x; + state->y = y; +} + +/* +void EnvironmentROBARM::Search2DwithHeap(State** statespace, int searchstartx, int searchstarty) +{ + CKey key; + CHeap* heap; + State* ExpState; + int newx, newy,x,y; + + //create a heap + heap = new CHeap; + + //initialize to infinity all + for (x = 0; x < EnvROBARMCfg.EnvWidth_c; x++) + { + for (y = 0; y < EnvROBARMCfg.EnvHeight_c; y++) + { + HeurGrid[x][y] = INFINITECOST; + ReInitializeState2D(&statespace[x][y]); + } + } + + //initialization + statespace[searchstartx][searchstarty].g = 0; + key.key[0] = 0; + heap->insertheap(&statespace[searchstartx][searchstarty], key); + + //expand all of the states + while(!heap->emptyheap()) + { + //get the state to expand + ExpState = heap->deleteminheap(); + + //set the corresponding heuristics + HeurGrid[ExpState->statecoord[0]][ExpState->statecoord[1]] = ExpState->g; + + //iterate through neighbors + for(int d = 0; d < DIRECTIONS; d++) + { + newx = ExpState->statecoord[0] + dx[d]; + newy = ExpState->statecoord[1] + dy[d]; + + //make sure it is inside the map + if(0 > newx || newx >= EnvROBARMCfg.EnvWidth_c || + 0 > newy || newy >= EnvROBARMCfg.EnvHeight_c) + continue; + + if(statespace[newx][newy].g > ExpState->g + 1 && + EnvROBARMCfg.Grid2D[newx][newy] == 0) + { + statespace[newx][newy].g = ExpState->g + 1; + key.key[0] = statespace[newx][newy].g; + if(statespace[newx][newy].heapindex == 0) + heap->insertheap(&statespace[newx][newy], key); + else + heap->updateheap(&statespace[newx][newy], key); + } + } + } + + //delete the heap + delete heap; +} +*/ + +void EnvironmentROBARM::Search2DwithQueue(State2D** statespace, int* HeurGrid, int searchstartx, int searchstarty) +{ + State2D* ExpState; + int newx, newy, x, y; + + //create a queue + queue Queue; + + //initialize to infinity all + for (x = 0; x < EnvROBARMCfg.EnvWidth_c; x++) { + for (y = 0; y < EnvROBARMCfg.EnvHeight_c; y++) { + HeurGrid[XYTO2DIND(x,y)] = INFINITECOST; + ReInitializeState2D(&statespace[x][y]); + } + } + + //initialization + statespace[searchstartx][searchstarty].g = 0; + Queue.push(&statespace[searchstartx][searchstarty]); + + //expand all of the states + while ((int)Queue.size() > 0) { + //get the state to expand + ExpState = Queue.front(); + Queue.pop(); + + //it may be that the state is already closed + if (ExpState->iterationclosed == 1) continue; + + //close it + ExpState->iterationclosed = 1; + + //set the corresponding heuristics + HeurGrid[XYTO2DIND(ExpState->x, ExpState->y)] = ExpState->g; + + //iterate through neighbors + for (int d = 0; d < DIRECTIONS; d++) { + newx = ExpState->x + dx[d]; + newy = ExpState->y + dy[d]; + + //make sure it is inside the map and has no obstacle + if (0 > newx || newx >= EnvROBARMCfg.EnvWidth_c || 0 > newy || newy >= EnvROBARMCfg.EnvHeight_c + || EnvROBARMCfg.Grid2D[newx][newy] == 1) continue; + + //check + if (statespace[newx][newy].g != INFINITECOST && statespace[newx][newy].g > ExpState->g + 1) { + throw SBPL_Exception("ERROR: incorrect heuristic computation"); + } + + if (statespace[newx][newy].iterationclosed == 0 && statespace[newx][newy].g == INFINITECOST) { + //insert into the stack + Queue.push(&statespace[newx][newy]); + + //set the g-value + statespace[newx][newy].g = ExpState->g + 1; + } + } + } +} + +void EnvironmentROBARM::Create2DStateSpace(State2D*** statespace2D) +{ + int x, y; + + //allocate a statespace for 2D search + *statespace2D = new State2D*[EnvROBARMCfg.EnvWidth_c]; + for (x = 0; x < EnvROBARMCfg.EnvWidth_c; x++) { + (*statespace2D)[x] = new State2D[EnvROBARMCfg.EnvHeight_c]; + for (y = 0; y < EnvROBARMCfg.EnvWidth_c; y++) { + InitializeState2D(&(*statespace2D)[x][y], x, y); + } + } +} + +void EnvironmentROBARM::Delete2DStateSpace(State2D*** statespace2D) +{ + int x; + + //delete the 2D statespace + for (x = 0; x < EnvROBARMCfg.EnvWidth_c; x++) { + delete[] (*statespace2D)[x]; + } + delete *statespace2D; +} + +void EnvironmentROBARM::ComputeHeuristicValues() +{ + int i; + + SBPL_PRINTF("Running 2D BFS to compute heuristics\n"); + + //allocate memory + int hsize = XYTO2DIND(EnvROBARMCfg.EnvWidth_c-1, EnvROBARMCfg.EnvHeight_c-1) + 1; + EnvROBARM.Heur = new int*[hsize]; + for (i = 0; i < hsize; i++) { + EnvROBARM.Heur[i] = new int[hsize]; + } + + //now compute the heuristics for each goal location + + State2D** statespace2D; + Create2DStateSpace(&statespace2D); + + for (int x = 0; x < EnvROBARMCfg.EnvWidth_c; x++) { + for (int y = 0; y < EnvROBARMCfg.EnvHeight_c; y++) { + int hind = XYTO2DIND(x,y); + + //perform the search for pathcosts to x,y and store values in Heur[hind] + Search2DwithQueue(statespace2D, &EnvROBARM.Heur[hind][0], x, y); + } + //SBPL_PRINTF("h for %d computed\n", x); + } + Delete2DStateSpace(&statespace2D); + + SBPL_PRINTF("done\n"); +} + +//---------------------------------------------------------------------- + +//--------------printing routines--------------------------------------- + +/* +void EnvironmentROBARM::PrintHeurGrid() +{ + int x,y; + + for (x = 0; x < EnvROBARMCfg.EnvWidth_c; x++) + { + for (y = 0; y < EnvROBARMCfg.EnvHeight_c; y++) + { + SBPL_PRINTF("HeurGrid[%d][%d]=%u\n", x,y,HeurGrid[x][y]); + } + SBPL_PRINTF("\n"); + } +} +*/ + +void EnvironmentROBARM::printangles(FILE* fOut, short unsigned int* coord, bool bGoal, bool bVerbose, bool bLocal) +{ + double angles[NUMOFLINKS]; + int i; + short unsigned int x, y; + + ComputeContAngles(coord, angles); + if (bVerbose) SBPL_FPRINTF(fOut, "angles: "); + for (i = 0; i < NUMOFLINKS; i++) { + if (!bLocal) + SBPL_FPRINTF(fOut, "%f ", angles[i]); + else { + if (i > 0) + SBPL_FPRINTF(fOut, "%f ", angles[i] - angles[i - 1]); + else + SBPL_FPRINTF(fOut, "%f ", angles[i]); + } + } + ComputeEndEffectorPos(angles, &x, &y); + if (bGoal) { + x = EnvROBARMCfg.EndEffGoalX_c; + y = EnvROBARMCfg.EndEffGoalY_c; + } + if (bVerbose) + SBPL_FPRINTF(fOut, "endeff: %d %d", x, y); + else + SBPL_FPRINTF(fOut, "%d %d", x, y); + + SBPL_FPRINTF(fOut, "\n"); +} + +/* +void EnvironmentROBARM::PrintPathRec(State* currentstate, State* searchstartstate, int* cost) +{ + if(currentstate == searchstartstate) + { + return; + } + + if(currentstate->g > currentstate->v) + { + SBPL_ERROR("ERROR: an underconsistent state is encountered on the path\n"); + +#if PLANNER_TYPE == ARA_PLANNER_TYPE + PrintState(currentstate, stdout); +#endif + throw SBPL_Exception(); + } + + //cost of the transition to the previous state + *cost = *cost + currentstate->costtobestnextstate; + if(*cost > 100000 || currentstate->g < currentstate->bestnextstate->v + + currentstate->costtobestnextstate || + !IsValidCoord(currentstate->bestnextstate->statecoord)) + { +#if PLANNER_TYPE == ARA_PLANNER_TYPE + SBPL_PRINTF("currentstate\n"); + PrintState(currentstate, stdout); + SBPL_PRINTF("nextstate\n"); + PrintState(currentstate->bestnextstate, stdout); +#endif + SBPL_PRINTF("next statecoord IsValid=%d\n", + IsValidCoord(currentstate->bestnextstate->statecoord)); + SBPL_ERROR("ERROR: cost of the path too high=%d or incorrect transition\n", *cost); + throw SBPL_Exception(); + } + //transition itself + currentstate = currentstate->bestnextstate; + + //proceed recursively +#if FORWARD_SEARCH + PrintPathRec(currentstate, searchstartstate, cost); + printangles(fSol, currentstate); +#else + printangles(fSol, currentstate); + PrintPathRec(currentstate, searchstartstate, cost); +#endif +} + +//prints found path and some statistics +int EnvironmentROBARM::PrintPathStat(double erreps, int* pathcost) +{ + State *goalstate, *startstate; + short unsigned int coord[NUMOFLINKS]; + int cost = 0; + int inconssize; + + goalstate = RobArmStateSpace.goalstate; + + ComputeCoord(RobArmStateSpace.currentangle, coord); + startstate = GetState(coord); + +#if FORWARD_SEARCH + if(goalstate == NULL || goalstate->bestnextstate == NULL) + { + SBPL_PRINTF("No path is found\n"); + *pathcost = INFINITECOST; + return 0; + } + PrintPathRec(goalstate, startstate, &cost); + printangles(fSol, goalstate); +#else + if(startstate == NULL || startstate->bestnextstate == NULL) + { + SBPL_PRINTF("No path is found\n"); + *pathcost = INFINITECOST; + return 0; + } + int goalh = Heuristic(goalstate, startstate); + if(startstate->g+startstate->h < goalh) + { + SBPL_ERROR("ERROR: invalid heuristic. goalh(updated)=%d startg=%d\n", + goalh, startstate->g); +#if PLANNER_TYPE == ARA_PLANNER_TYPE + PrintState(startstate, stdout); +#endif + throw SBPL_Exception(); + } + else + SBPL_PRINTF("goalh=%d startg=%d\n", goalstate->h, startstate->g); + printangles(fSol, startstate); + PrintPathRec(startstate, goalstate, &cost); +#endif + + SBPL_FPRINTF(fSol, "path cost=%d at eps=%f\n", cost, erreps); + SBPL_PRINTF("path cost=%d\n", cost); + +#if PLANNER_TYPE == ANYASTAR_PLANNER_TYPE + inconssize = 0; +#else + inconssize = RobArmStateSpace.inconslist->currentsize; +#endif + + SBPL_PRINTF("open size=%d, incons size=%d\n", + RobArmStateSpace.heap->currentsize, inconssize); + SBPL_FPRINTF(fSol, "open size=%d, incons size=%d\n", + RobArmStateSpace.heap->currentsize, inconssize); + + SBPL_FPRINTF(fSol1, "**************\n"); + SBPL_FFLUSH(fStat); + + *pathcost = cost; + + return 1; +} + +void EnvironmentROBARM::PrintInfo() +{ + int i; + unsigned int statespace_size = 1; + double fsize = 1.0; + + SBPL_FPRINTF(fSol, "statespace dim=%d size= <", NUMOFLINKS); + SBPL_FPRINTF(fSol1, "%d\n", NUMOFLINKS); + for(i = 0; i < NUMOFLINKS; i++) + { + statespace_size *= RobArmStateSpace.anglevals[i]; + SBPL_FPRINTF(fSol, "%d ", RobArmStateSpace.anglevals[i]); + SBPL_FPRINTF(fSol1, "%f ", EnvROBARMCfg.LinkLength_m[i]); + fsize = fsize*RobArmStateSpace.anglevals[i]; + } + SBPL_FPRINTF(fSol, "> => %g\n", fsize); + SBPL_FPRINTF(fSol1, "\n"); + + SBPL_PRINTF("dimensionality: %d statespace: %u (over 10^%d)\n", NUMOFLINKS, statespace_size, + (int)(log10(fsize))); +} + +void PrintCoord(short unsigned int coord[NUMOFLINKS], FILE* fOut) +{ + for(int i = 0; i < NUMOFLINKS; i++) + SBPL_FPRINTF(fOut, "%d ", coord[i]); + SBPL_FPRINTF(fOut, "\n"); +} +*/ + +//---------------------------------------------------------------------- + +//--------------------Additional domain specific functions-------------------------------------------------- + +void EnvironmentROBARM::ReadConfiguration(FILE* fCfg) +{ + char sTemp[1024]; + int dTemp; + int x, y, i; + + //environmentsize(meters) + if (fscanf(fCfg, "%s", sTemp) != 1) { + throw SBPL_Exception("ERROR: ran out of env file early"); + } + if (fscanf(fCfg, "%s", sTemp) != 1) { + throw SBPL_Exception("ERROR: ran out of env file early"); + } + EnvROBARMCfg.EnvWidth_m = atof(sTemp); + if (fscanf(fCfg, "%s", sTemp) != 1) { + throw SBPL_Exception("ERROR: ran out of env file early"); + } + EnvROBARMCfg.EnvHeight_m = atof(sTemp); + + //discretization(cells) + if (fscanf(fCfg, "%s", sTemp) != 1) { + throw SBPL_Exception("ERROR: ran out of env file early"); + } + if (fscanf(fCfg, "%s", sTemp) != 1) { + throw SBPL_Exception("ERROR: ran out of env file early"); + } + EnvROBARMCfg.EnvWidth_c = atoi(sTemp); + if (fscanf(fCfg, "%s", sTemp) != 1) { + throw SBPL_Exception("ERROR: ran out of env file early"); + } + EnvROBARMCfg.EnvHeight_c = atoi(sTemp); + + //basex(cells): + if (fscanf(fCfg, "%s", sTemp) != 1) { + throw SBPL_Exception("ERROR: ran out of env file early"); + } + if (fscanf(fCfg, "%s", sTemp) != 1) { + throw SBPL_Exception("ERROR: ran out of env file early"); + } + EnvROBARMCfg.BaseX_c = atoi(sTemp); + + //linklengths(meters): + if (fscanf(fCfg, "%s", sTemp) != 1) { + throw SBPL_Exception("ERROR: ran out of env file early"); + } + for (i = 0; i < NUMOFLINKS; i++) { + if (fscanf(fCfg, "%s", sTemp) != 1) { + throw SBPL_Exception("ERROR: ran out of env file early"); + } + EnvROBARMCfg.LinkLength_m[i] = atof(sTemp); + } + + //linkstartangles(degrees): + if (fscanf(fCfg, "%s", sTemp) != 1) { + throw SBPL_Exception("ERROR: ran out of env file early"); + } + for (i = 0; i < NUMOFLINKS; i++) { + if (fscanf(fCfg, "%s", sTemp) != 1) { + throw SBPL_Exception("ERROR: ran out of env file early"); + } + EnvROBARMCfg.LinkStartAngles_d[i] = atoi(sTemp); + } + + //endeffectorgoal(cells) or linkgoalangles(degrees): + if (fscanf(fCfg, "%s", sTemp) != 1) { + throw SBPL_Exception("ERROR: ran out of env file early"); + } + if (strcmp(sTemp, "endeffectorgoal(cells):") == 0) { + //only endeffector is specified + if (fscanf(fCfg, "%s", sTemp) != 1) { + throw SBPL_Exception("ERROR: ran out of env file early"); + } + EnvROBARMCfg.EndEffGoalX_c = atoi(sTemp); + if (fscanf(fCfg, "%s", sTemp) != 1) { + throw SBPL_Exception("ERROR: ran out of env file early"); + } + EnvROBARMCfg.EndEffGoalY_c = atoi(sTemp); + + //set goalangle to invalid number + EnvROBARMCfg.LinkGoalAngles_d[0] = INVALID_NUMBER; + } + else if (strcmp(sTemp, "linkgoalangles(degrees):") == 0) { + double goalangles[NUMOFLINKS]; + + //linkgoalangles(degrees): 90.0 180.0 90.0 + for (i = 0; i < NUMOFLINKS; i++) { + if (fscanf(fCfg, "%s", sTemp) != 1) { + throw SBPL_Exception("ERROR: ran out of env file early"); + } + EnvROBARMCfg.LinkGoalAngles_d[i] = atoi(sTemp); + } + //compute endeffectorgoal(cells): + for (i = 0; i < NUMOFLINKS; i++) { + goalangles[i] = PI_CONST * (EnvROBARMCfg.LinkGoalAngles_d[i] / 180.0); + } + ComputeEndEffectorPos(goalangles, &EnvROBARMCfg.EndEffGoalX_c, &EnvROBARMCfg.EndEffGoalY_c); + } + else { + std::stringstream ss("ERROR: invalid string encountered="); + ss << sTemp; + throw SBPL_Exception(ss.str()); + } + + //allocate the 2D environment + EnvROBARMCfg.Grid2D = new char*[EnvROBARMCfg.EnvWidth_c]; + for (x = 0; x < EnvROBARMCfg.EnvWidth_c; x++) { + EnvROBARMCfg.Grid2D[x] = new char[EnvROBARMCfg.EnvHeight_c]; + } + + //environment: + if (fscanf(fCfg, "%s", sTemp) != 1) { + throw SBPL_Exception("ERROR: ran out of env file early"); + } + for (y = 0; y < EnvROBARMCfg.EnvHeight_c; y++) + for (x = 0; x < EnvROBARMCfg.EnvWidth_c; x++) { + if (fscanf(fCfg, "%d", &dTemp) != 1) { + throw SBPL_Exception("ERROR: incorrect format of config file"); + } + EnvROBARMCfg.Grid2D[x][y] = dTemp; + } + + //set additional parameters + EnvROBARMCfg.GridCellWidth = EnvROBARMCfg.EnvWidth_m / EnvROBARMCfg.EnvWidth_c; + if (EnvROBARMCfg.GridCellWidth != EnvROBARMCfg.EnvHeight_m / EnvROBARMCfg.EnvHeight_c) { + throw SBPL_Exception("ERROR: The cell should be square"); + } +} + +void EnvironmentROBARM::DiscretizeAngles() +{ + int i; + double HalfGridCell = EnvROBARMCfg.GridCellWidth / 2.0; + + for (i = 0; i < NUMOFLINKS; i++) { + EnvROBARMCfg.angledelta[i] = 2 * asin(HalfGridCell / EnvROBARMCfg.LinkLength_m[i]); + EnvROBARMCfg.anglevals[i] = (int)(2.0 * PI_CONST / EnvROBARMCfg.angledelta[i] + 0.99999999); + } +} + +//angles are counterclokwise from 0 to 360 in radians, 0 is the center of bin 0, ... +void EnvironmentROBARM::ComputeContAngles(short unsigned int coord[NUMOFLINKS], double angle[NUMOFLINKS]) +{ + int i; + + for (i = 0; i < NUMOFLINKS; i++) { + angle[i] = coord[i] * EnvROBARMCfg.angledelta[i]; + } +} + +void EnvironmentROBARM::ComputeCoord(double angle[NUMOFLINKS], short unsigned int coord[NUMOFLINKS]) +{ + int i; + + for (i = 0; i < NUMOFLINKS; i++) { + coord[i] = (int)((angle[i] + EnvROBARMCfg.angledelta[i] * 0.5) / EnvROBARMCfg.angledelta[i]); + if (coord[i] == EnvROBARMCfg.anglevals[i]) coord[i] = 0; + } +} + +unsigned int EnvironmentROBARM::GetHeurBasedonCoord(short unsigned int coord[NUMOFLINKS]) +{ + short unsigned int endeffx, endeffy; + double angles[NUMOFLINKS]; + unsigned int h; + + ComputeContAngles(coord, angles); + ComputeEndEffectorPos(angles, &endeffx, &endeffy); + +#if INFORMED + h = HeurGrid[endeffx][endeffy]; +#else + h = 0; +#endif + + return h; +} + +void EnvironmentROBARM::Cell2ContXY(int x, int y, double *pX, double *pY) +{ + *pX = x * EnvROBARMCfg.GridCellWidth + EnvROBARMCfg.GridCellWidth * 0.5; + *pY = y * EnvROBARMCfg.GridCellWidth + EnvROBARMCfg.GridCellWidth * 0.5; +} + +void EnvironmentROBARM::ContXY2Cell(double x, double y, short unsigned int* pX, short unsigned int *pY) +{ + //take the nearest cell + *pX = (int)(x / EnvROBARMCfg.GridCellWidth); + if (x < 0) *pX = 0; + if (*pX >= EnvROBARMCfg.EnvWidth_c) *pX = EnvROBARMCfg.EnvWidth_c - 1; + + *pY = (int)(y / EnvROBARMCfg.GridCellWidth); + if (y < 0) *pY = 0; + if (*pY >= EnvROBARMCfg.EnvHeight_c) *pY = EnvROBARMCfg.EnvHeight_c - 1; +} + +//returns 1 if end effector within space, 0 otherwise +int EnvironmentROBARM::ComputeEndEffectorPos(double angles[NUMOFLINKS], short unsigned int* pX, short unsigned int* pY) +{ + double x, y; + int i; + int retval = 1; + + //start with the base + Cell2ContXY(EnvROBARMCfg.BaseX_c, EnvROBARMCfg.EnvHeight_c - 1, &x, &y); + + //translate the point along each link + for (i = 0; i < NUMOFLINKS; i++) { + x = x + EnvROBARMCfg.LinkLength_m[i] * cos(angles[i]); + y = y - EnvROBARMCfg.LinkLength_m[i] * sin(angles[i]); + } + + if (x < 0 || x >= EnvROBARMCfg.EnvWidth_m || y < 0 || y >= EnvROBARMCfg.EnvHeight_m) retval = 0; + + ContXY2Cell(x, y, pX, pY); + + //return 1; + return retval; +} + +//if pTestedCells is NULL, then the tested points are not saved and it is more +//efficient as it returns as soon as it sees first invalid point +int EnvironmentROBARM::IsValidLineSegment(double x0, double y0, double x1, double y1, char **Grid2D, + vector* pTestedCells) + +{ + bresenham_param_t params; + int nX, nY; + short unsigned int nX0, nY0, nX1, nY1; + int retvalue = 1; + CELLV tempcell; + + //make sure the line segment is inside the environment + if (x0 < 0 || x0 >= EnvROBARMCfg.EnvWidth_m || x1 < 0 || x1 >= EnvROBARMCfg.EnvWidth_m || y0 < 0 || + y0 >= EnvROBARMCfg.EnvHeight_m || y1 < 0 || y1 >= EnvROBARMCfg.EnvHeight_m) + { + return 0; + } + + ContXY2Cell(x0, y0, &nX0, &nY0); + ContXY2Cell(x1, y1, &nX1, &nY1); + + //iterate through the points on the segment + get_bresenham_parameters(nX0, nY0, nX1, nY1, ¶ms); + do { + get_current_point(¶ms, &nX, &nY); + if (Grid2D[nX][nY] == 1) { + if (pTestedCells == NULL) + return 0; + else + retvalue = 0; + } + + //insert the tested point + if (pTestedCells) { + tempcell.bIsObstacle = (Grid2D[nX][nY] == 1); + tempcell.x = nX; + tempcell.y = nY; + pTestedCells->push_back(tempcell); + } + } + while (get_next_point(¶ms)); + + return retvalue; +} + +int EnvironmentROBARM::IsValidCoord(short unsigned int coord[NUMOFLINKS], char** Grid2D /*=NULL*/, + vector* pTestedCells /*=NULL*/) +{ + double angles[NUMOFLINKS]; + int retvalue = 1; + + if (Grid2D == NULL) Grid2D = EnvROBARMCfg.Grid2D; + +#if ENDEFF_CHECK_ONLY + int endeffx, endeffy; + + //just check whether end effector is in valid position + ComputeContAngles(coord, angles); + if(ComputeEndEffectorPos(angles, &endeffx, &endeffy) == false) + return 0; + + //check that it is inside the grid + if(endeffx < 0 || endeffx >= EnvROBARMCfg.EnvWidth_c || + endeffy < 0 || endeffy >= EnvROBARMCfg.EnvHeight_c) + { + return 0; + } + + if(pTestedCells) + { + CELLV tempcell; + tempcell.IsObstacle = Grid2D[endeffx][endeffy]; + tempcell.x = endeffx; + tempcell.y = endeffy; + + pTestedCells->push_back(tempcell); + } + + //check end effector + if(Grid2D[endeffx][endeffy] == 1) + return 0; +#else + double x0, y0, x1, y1; + int i; + + //full check of all the links + ComputeContAngles(coord, angles); + + //iterate through all the links + Cell2ContXY(EnvROBARMCfg.BaseX_c, EnvROBARMCfg.EnvHeight_c - 1, &x1, &y1); + for (i = 0; i < NUMOFLINKS; i++) { + //compute the corresponding line segment + x0 = x1; + y0 = y1; + x1 = x0 + EnvROBARMCfg.LinkLength_m[i] * cos(angles[i]); + y1 = y0 - EnvROBARMCfg.LinkLength_m[i] * sin(angles[i]); + + //check the validity of the corresponding line segment + if (!IsValidLineSegment(x0, y0, x1, y1, Grid2D, pTestedCells)) { + if (pTestedCells == NULL) + return 0; + else + retvalue = 0; + } + } + +#endif + + return retvalue; +} + +int EnvironmentROBARM::cost(short unsigned int state1coord[], short unsigned int state2coord[]) +{ + + if (!IsValidCoord(state1coord) || !IsValidCoord(state2coord)) return INFINITECOST; + +#if UNIFORM_COST + return 1; +#else + int i; + //the cost becomes higher as we are closer to the base + for (i = 0; i < NUMOFLINKS; i++) { + if (state1coord[i] != state2coord[i]) return (NUMOFLINKS - i); + //return (NUMOFLINKS-i)*(NUMOFLINKS-i); + } + +// SBPL_ERROR("ERROR: cost on the same states is called:\n"); +// printangles(stdout, state1coord); +// printangles(stdout, state2coord); + + throw SBPL_Exception("ERROR: cost on the same states is called"); + +#endif +} + +void EnvironmentROBARM::InitializeEnvConfig() +{ + //find the discretization for each angle and store the discretization + DiscretizeAngles(); +} + +bool EnvironmentROBARM::InitializeEnvironment() +{ + short unsigned int coord[NUMOFLINKS]; + double startangles[NUMOFLINKS]; + double angles[NUMOFLINKS]; + int i; + short unsigned int endeffx, endeffy; + + //initialize the map from Coord to StateID + EnvROBARM.HashTableSize = 32 * 1024; //should be power of two + EnvROBARM.Coord2StateIDHashTable = new vector [EnvROBARM.HashTableSize]; + + //initialize the map from StateID to Coord + EnvROBARM.StateID2CoordTable.clear(); + + //initialize the angles of the start states + for (i = 0; i < NUMOFLINKS; i++) { + startangles[i] = PI_CONST * (EnvROBARMCfg.LinkStartAngles_d[i] / 180.0); + } + + ComputeCoord(startangles, coord); + ComputeContAngles(coord, angles); + ComputeEndEffectorPos(angles, &endeffx, &endeffy); + + //create the start state + EnvROBARM.startHashEntry = CreateNewHashEntry(coord, NUMOFLINKS, endeffx, endeffy); + + //create the goal state + //initialize the coord of goal state + for (i = 0; i < NUMOFLINKS; i++) { + coord[i] = 0; + } + EnvROBARM.goalHashEntry = CreateNewHashEntry(coord, NUMOFLINKS, EnvROBARMCfg.EndEffGoalX_c, + EnvROBARMCfg.EndEffGoalY_c); + + //check the validity of both goal and start configurations + //testing for EnvROBARMCfg.EndEffGoalX_c < 0 and EnvROBARMCfg.EndEffGoalY_c < 0 is useless since they are unsigned + if (!IsValidCoord(EnvROBARM.startHashEntry->coord) || EnvROBARMCfg.EndEffGoalX_c >= EnvROBARMCfg.EnvWidth_c + || EnvROBARMCfg.EndEffGoalY_c >= EnvROBARMCfg.EnvHeight_c) { + SBPL_PRINTF("Either start or goal configuration is invalid\n"); + return false; + } + + //for now heuristics are not set + EnvROBARM.Heur = NULL; + + return true; +} + +//---------------------------------------------------------------------- + +//-----------interface with outside functions----------------------------------- + +bool EnvironmentROBARM::InitializeEnv(const char* sEnvFile) +{ + FILE* fCfg = fopen(sEnvFile, "r"); + if (fCfg == NULL) { + std::stringstream ss("ERROR: unable to open "); + ss << sEnvFile; + throw SBPL_Exception(ss.str()); + } + ReadConfiguration(fCfg); + fclose(fCfg); + + //Initialize other parameters of the environment + InitializeEnvConfig(); + + //initialize Environment + if (InitializeEnvironment() == false) return false; + + //pre-compute heuristics + ComputeHeuristicValues(); + + return true; +} + +bool EnvironmentROBARM::InitializeMDPCfg(MDPConfig *MDPCfg) +{ + //initialize MDPCfg with the start and goal ids + MDPCfg->goalstateid = EnvROBARM.goalHashEntry->stateID; + MDPCfg->startstateid = EnvROBARM.startHashEntry->stateID; + + return true; +} + +int EnvironmentROBARM::GetFromToHeuristic(int FromStateID, int ToStateID) +{ +#if USE_HEUR==0 + return 0; +#endif + +#if DEBUG + if(FromStateID >= (int)EnvROBARM.StateID2CoordTable.size() + || ToStateID >= (int)EnvROBARM.StateID2CoordTable.size()) + { + throw SBPL_Exception("ERROR in EnvROBARM... function: stateID illegal"); + } +#endif + + //get X, Y for the state + EnvROBARMHashEntry_t* FromHashEntry = EnvROBARM.StateID2CoordTable[FromStateID]; + EnvROBARMHashEntry_t* ToHashEntry = EnvROBARM.StateID2CoordTable[ToStateID]; + + int h = + EnvROBARM.Heur[XYTO2DIND(ToHashEntry->endeffx, ToHashEntry->endeffy)][XYTO2DIND(FromHashEntry->endeffx, FromHashEntry->endeffy)]; + + /* + if(ToStateID != EnvROBARM.goalHashEntry->stateID) + { + //also consider the distanceincoord + + //get the heuristic based on angles + unsigned int hangles = distanceincoord(FromHashEntry->coord, ToHashEntry->coord); + + //the heuristic is the max of the two + h = __max(h, hangles); + } + */ + + return h; +} + +int EnvironmentROBARM::GetGoalHeuristic(int stateID) +{ +#if USE_HEUR==0 + return 0; +#endif + +#if DEBUG + if (stateID >= (int)EnvROBARM.StateID2CoordTable.size()) { + throw SBPL_Exception("ERROR in EnvROBARM... function: stateID illegal"); + } +#endif + + //define this function if it used in the planner (heuristic forward search would use it) + return GetFromToHeuristic(stateID, EnvROBARM.goalHashEntry->stateID); +} + +int EnvironmentROBARM::GetStartHeuristic(int stateID) +{ +#if USE_HEUR==0 + return 0; +#endif + +#if DEBUG + if (stateID >= (int)EnvROBARM.StateID2CoordTable.size()) { + throw SBPL_Exception("ERROR in EnvROBARM... function: stateID illegal"); + } +#endif + + //define this function if it used in the planner (heuristic backward search would use it) + + throw SBPL_Exception("ERROR in EnvROBARM.. function: GetStartHeuristic undefined"); + + return 0; +} + +void EnvironmentROBARM::SetAllPreds(CMDPSTATE* state) +{ + //implement this if the planner needs access to predecessors + + throw SBPL_Exception("ERROR in EnvROBARM... function: SetAllPreds is undefined"); +} + +int EnvironmentROBARM::SizeofCreatedEnv() +{ + return EnvROBARM.StateID2CoordTable.size(); +} + +void EnvironmentROBARM::PrintState(int stateID, bool bVerbose, FILE* fOut /*=NULL*/) +{ + +#if DEBUG + if(stateID >= (int)EnvROBARM.StateID2CoordTable.size()) + { + throw SBPL_Exception("ERROR in EnvROBARM... function: stateID illegal (2)"); + } +#endif + + if (fOut == NULL) fOut = stdout; + + EnvROBARMHashEntry_t* HashEntry = EnvROBARM.StateID2CoordTable[stateID]; + + bool bGoal = false; + if (stateID == EnvROBARM.goalHashEntry->stateID) bGoal = true; + + if (stateID == EnvROBARM.goalHashEntry->stateID && bVerbose) { + SBPL_FPRINTF(fOut, "the state is a goal state\n"); + bGoal = true; + } + + printangles(fOut, HashEntry->coord, bGoal, bVerbose, false); +} + +//get the goal as a successor of source state at given cost +//if costtogoal = -1 then the succ is chosen +void EnvironmentROBARM::PrintSuccGoal(int SourceStateID, int costtogoal, bool bVerbose, bool bLocal /*=false*/, + FILE* fOut /*=NULL*/) +{ + short unsigned int succcoord[NUMOFLINKS]; + double angles[NUMOFLINKS]; + short unsigned int endeffx, endeffy; + int i, inc; + + if (fOut == NULL) fOut = stdout; + + EnvROBARMHashEntry_t* HashEntry = EnvROBARM.StateID2CoordTable[SourceStateID]; + + //default coords of successor + for (i = 0; i < NUMOFLINKS; i++) + succcoord[i] = HashEntry->coord[i]; + + //iterate through successors of s + for (i = 0; i < NUMOFLINKS; i++) { + //increase and decrease in ith angle + for (inc = -1; inc < 2; inc = inc + 2) { + if (inc == -1) { + if (HashEntry->coord[i] == 0) + succcoord[i] = EnvROBARMCfg.anglevals[i] - 1; + else + succcoord[i] = HashEntry->coord[i] + inc; + } + else { + succcoord[i] = (HashEntry->coord[i] + inc) % EnvROBARMCfg.anglevals[i]; + } + + //skip invalid successors + if (!IsValidCoord(succcoord)) continue; + + ComputeContAngles(succcoord, angles); + ComputeEndEffectorPos(angles, &endeffx, &endeffy); + if (endeffx == EnvROBARMCfg.EndEffGoalX_c && endeffy == EnvROBARMCfg.EndEffGoalY_c) { + if (cost(HashEntry->coord, succcoord) == costtogoal || costtogoal == -1) { + if (bVerbose) SBPL_FPRINTF(fOut, "the state is a goal state\n"); + printangles(fOut, succcoord, true, bVerbose, bLocal); + return; + } + } + } + + //restore it back + succcoord[i] = HashEntry->coord[i]; + } +} + +void EnvironmentROBARM::PrintEnv_Config(FILE* fOut) +{ + //implement this if the planner needs to print out EnvROBARM. configuration + + throw SBPL_Exception("ERROR in EnvROBARM... function: PrintEnv_Config is undefined"); +} + +void EnvironmentROBARM::PrintHeader(FILE* fOut) +{ + SBPL_FPRINTF(fOut, "%d\n", NUMOFLINKS); + for (int i = 0; i < NUMOFLINKS; i++) + SBPL_FPRINTF(fOut, "%.3f ", EnvROBARMCfg.LinkLength_m[i]); + SBPL_FPRINTF(fOut, "\n"); +} + +void EnvironmentROBARM::SetAllActionsandAllOutcomes(CMDPSTATE* state) +{ + throw SBPL_Exception("ERROR in EnvROBARM..function: SetAllActionsandAllOutcomes is undefined"); +} + +void EnvironmentROBARM::GetSuccs(int SourceStateID, vector* SuccIDV, vector* CostV) +{ + int i, inc; + short unsigned int succcoord[NUMOFLINKS]; + double angles[NUMOFLINKS]; + + //clear the successor array + SuccIDV->clear(); + CostV->clear(); + + //goal state should be absorbing + if (SourceStateID == EnvROBARM.goalHashEntry->stateID) return; + + //get X, Y for the state + EnvROBARMHashEntry_t* HashEntry = EnvROBARM.StateID2CoordTable[SourceStateID]; + + //default coords of successor + for (i = 0; i < NUMOFLINKS; i++) + succcoord[i] = HashEntry->coord[i]; + + //iterate through successors of s + for (i = 0; i < NUMOFLINKS; i++) { + //increase and decrease in ith angle + for (inc = -1; inc < 2; inc = inc + 2) { + if (inc == -1) { + if (HashEntry->coord[i] == 0) + succcoord[i] = EnvROBARMCfg.anglevals[i] - 1; + else + succcoord[i] = HashEntry->coord[i] + inc; + } + else { + succcoord[i] = (HashEntry->coord[i] + inc) % EnvROBARMCfg.anglevals[i]; + } + + //skip invalid successors + if (!IsValidCoord(succcoord)) continue; + + //get the successor + EnvROBARMHashEntry_t* OutHashEntry; + bool bSuccisGoal = false; + short unsigned int endeffx = 0, endeffy = 0; + bool bEndEffComputed = false; + if (abs(HashEntry->endeffx - EnvROBARMCfg.EndEffGoalX_c) < 3 || abs(HashEntry->endeffy + - EnvROBARMCfg.EndEffGoalY_c) < 3) { + //do a strict checks on the endeff coordinates of the successor + ComputeContAngles(succcoord, angles); + ComputeEndEffectorPos(angles, &endeffx, &endeffy); + if (endeffx == EnvROBARMCfg.EndEffGoalX_c && endeffy == EnvROBARMCfg.EndEffGoalY_c) { + bSuccisGoal = true; + //SBPL_PRINTF("goal succ is generated\n"); + } + bEndEffComputed = true; + } + + if ((OutHashEntry = GetHashEntry(succcoord, NUMOFLINKS, bSuccisGoal)) == NULL) { + if (bEndEffComputed == false) { + ComputeContAngles(succcoord, angles); + ComputeEndEffectorPos(angles, &endeffx, &endeffy); + } + + //have to create a new entry + OutHashEntry = CreateNewHashEntry(succcoord, NUMOFLINKS, endeffx, endeffy); + } + SuccIDV->push_back(OutHashEntry->stateID); + CostV->push_back(cost(HashEntry->coord, succcoord)); + } + + //restore it back + succcoord[i] = HashEntry->coord[i]; + } +} + +void EnvironmentROBARM::GetPreds(int TargetStateID, vector* PredIDV, vector* CostV) +{ + throw SBPL_Exception("ERROR in EnvROBARM... function: GetPreds is undefined"); +} + +//generate succs at some domain-dependent distance - see environment.h for more info +void EnvironmentROBARM::GetRandomSuccsatDistance(int SourceStateID, std::vector* SuccIDV, std::vector* CLowV) +{ + short unsigned int coord[NUMOFLINKS]; + short unsigned int endeffx, endeffy; + double angles[NUMOFLINKS]; + + //clear the successor array + SuccIDV->clear(); + CLowV->clear(); + + //the number of successors + int numofsuccs = ROBARM_NUMOFRANDSUCCSATDIST; + + //goal state should be absorbing + if (SourceStateID == EnvROBARM.goalHashEntry->stateID) return; + + //get X, Y for the state + EnvROBARMHashEntry_t* HashEntry = EnvROBARM.StateID2CoordTable[SourceStateID]; + + //iterate through random actions + for (int succind = 0; succind < numofsuccs; succind++) { + //pick the coordinate that will have dist = longactiondist + int maxcoordind = (int)(NUMOFLINKS * (((double)rand()) / RAND_MAX)); + + //now iterate over the coordinates + for (int cind = 0; cind < NUMOFLINKS; cind++) { + + if (cind == maxcoordind) { + //we know the magnitude and just need to set sign + if ((((double)rand()) / RAND_MAX) > 0.5) { + //positive sign + coord[cind] = (HashEntry->coord[cind] + ROBARM_LONGACTIONDIST_CELLS) % EnvROBARMCfg.anglevals[cind]; + } + else { + //negative sign + if (HashEntry->coord[cind] < ROBARM_LONGACTIONDIST_CELLS) + coord[cind] = HashEntry->coord[cind] + EnvROBARMCfg.anglevals[cind] - + ROBARM_LONGACTIONDIST_CELLS; + else + coord[cind] = HashEntry->coord[cind] - ROBARM_LONGACTIONDIST_CELLS; + //if(coord[cind] < 0) + //{ + // SBPL_ERROR("ERROR: ROBARM_LONGACTIONDIST_CELLS is too large for dim %d\n", cind); + // throw SBPL_Exception(); + //} + } + } + else { + //any value within ROBARM_LONGACTIONDIST_CELLS from the center + int offset = (int)(ROBARM_LONGACTIONDIST_CELLS * (((double)rand()) / RAND_MAX)); + if ((((double)rand()) / RAND_MAX) > 0.5) offset = -offset; + + //we know the magnitude and just need to set sign + if (offset >= 0) { + //positive sign + coord[cind] = (HashEntry->coord[cind] + offset) % EnvROBARMCfg.anglevals[cind]; + } + else { + //negative sign + coord[cind] = (HashEntry->coord[cind] + offset); + if (HashEntry->coord[cind] < -offset) coord[cind] = HashEntry->coord[cind] + + EnvROBARMCfg.anglevals[cind] + offset; + //if(coord[cind] < 0) + //{ + // SBPL_ERROR("ERROR: ROBARM_LONGACTIONDIST_CELLS is too large for dim %d\n", cind); + // throw SBPL_Exception(); + //} + } + }//else random offset + }//over coordinates + + //skip the invalid sample + if (!IsValidCoord(coord)) continue; + + //clock_t currenttime = clock(); + + //compute end effector + ComputeContAngles(coord, angles); + ComputeEndEffectorPos(angles, &endeffx, &endeffy); + + //skip the ones whose end-effector is outside + if (abs(HashEntry->endeffx - endeffx) > ROBARM_LONGACTIONDIST_CELLS || abs(HashEntry->endeffy - endeffy) + > ROBARM_LONGACTIONDIST_CELLS) continue; + + bool bIsGoal = false; + if (endeffx == EnvROBARMCfg.EndEffGoalX_c && endeffy == EnvROBARMCfg.EndEffGoalY_c) { + bIsGoal = true; + //SBPL_PRINTF("goal succ is generated\n"); + } + + EnvROBARMHashEntry_t* OutHashEntry = NULL; + if ((OutHashEntry = GetHashEntry(coord, NUMOFLINKS, bIsGoal)) == NULL) { + //have to create a new entry + OutHashEntry = CreateNewHashEntry(coord, NUMOFLINKS, endeffx, endeffy); + } + + //compute clow + int clow; + clow = EnvironmentROBARM::GetFromToHeuristic(HashEntry->stateID, OutHashEntry->stateID); + + SuccIDV->push_back(OutHashEntry->stateID); + CLowV->push_back(clow); + + //time3_addallout += clock()-currenttime; + } + + //see if the goal belongs to the inside area and if yes then add it to SUCCS as well + if (abs(EnvROBARMCfg.EndEffGoalX_c - HashEntry->endeffx) <= ROBARM_LONGACTIONDIST_CELLS && + abs(EnvROBARMCfg.EndEffGoalY_c - HashEntry->endeffy) <= ROBARM_LONGACTIONDIST_CELLS) + { + EnvROBARMHashEntry_t* OutHashEntry = EnvROBARM.goalHashEntry; + + int clow = EnvironmentROBARM::GetFromToHeuristic(HashEntry->stateID, OutHashEntry->stateID); + + SuccIDV->push_back(OutHashEntry->stateID); + CLowV->push_back(clow); + } +} + +int EnvironmentROBARM::GetEdgeCost(int FromStateID, int ToStateID) +{ +#if DEBUG + if(FromStateID >= (int)EnvROBARM.StateID2CoordTable.size() || + ToStateID >= (int)EnvROBARM.StateID2CoordTable.size()) + { + throw SBPL_Exception("ERROR in EnvROBARM... function: stateID illegal"); + } +#endif + + //get X, Y for the state + EnvROBARMHashEntry_t* FromHashEntry = EnvROBARM.StateID2CoordTable[FromStateID]; + EnvROBARMHashEntry_t* ToHashEntry = EnvROBARM.StateID2CoordTable[ToStateID]; + + return cost(FromHashEntry->coord, ToHashEntry->coord); +} + +int EnvironmentROBARM::GetRandomState() +{ + short unsigned int coord[NUMOFLINKS]; + double angles[NUMOFLINKS]; + short unsigned int endeffx, endeffy; + EnvROBARMHashEntry_t* HashEntry = NULL; + + SBPL_PRINTF("picking a random state...\n"); + while (1) { + //iterate over links + for (int i = 0; i < NUMOFLINKS; i++) { + //give it a shot + coord[i] = (short unsigned int)(EnvROBARMCfg.anglevals[i] * (((double)rand()) / (((double)RAND_MAX) + 1))); + } + + /* + //iterate over links + double endx[NUMOFLINKS]; + double endy[NUMOFLINKS]; + double x0, y0, x1, y1; + + for(int i = 0; i < NUMOFLINKS; i++) + { + int j = 0; + + //set the start of the link + if(i == 0) + Cell2ContXY(EnvROBARMCfg.BaseX_c, EnvROBARMCfg.EnvHeight_c-1,&x0,&y0); + else + { + x0 = endx[i-1]; + y0 = endy[i-1]; + } + + //try to set the angle + int numoftrials = 100; + for(j = 0; j < numoftrials; j++) + { + //give it a shot + coord[i] = EnvROBARMCfg.anglevals[i]*(((double)rand())/(RAND_MAX+1)); + + //check the new link + ComputeContAngles(coord, angles); + x1 = x0 + EnvROBARMCfg.LinkLength_m[i]*cos(angles[i]); + y1 = y0 - EnvROBARMCfg.LinkLength_m[i]*sin(angles[i]); + + //check the validity of the corresponding line segment + if(IsValidLineSegment(x0,y0,x1,y1, EnvROBARMCfg.Grid2D, NULL)) + { + break; + } + } + + //see if we found it + if(j == numoftrials) + { + //failed, reset + SBPL_PRINTF("have to reset\n"); + break; + } + else + { + endx[i] = x1; + endy[i] = y1; + } + } + */ + + //if not valid then try something else + if (!IsValidCoord(coord)) { + //SBPL_ERROR("ERROR: we could not have gotten an invalid sample\n"); + continue; + } + else + //done - found + break; + } + SBPL_PRINTF("done\n"); + + //compute end effector + ComputeContAngles(coord, angles); + ComputeEndEffectorPos(angles, &endeffx, &endeffy); + bool bIsGoal = false; + if (endeffx == EnvROBARMCfg.EndEffGoalX_c && endeffy == EnvROBARMCfg.EndEffGoalY_c) { + bIsGoal = true; + //SBPL_PRINTF("goal succ is generated\n"); + } + + if ((HashEntry = GetHashEntry(coord, NUMOFLINKS, bIsGoal)) == NULL) { + //have to create a new entry + HashEntry = CreateNewHashEntry(coord, NUMOFLINKS, endeffx, endeffy); + } + + return HashEntry->stateID; +} + +bool EnvironmentROBARM::AreEquivalent(int State1ID, int State2ID) +{ + EnvROBARMHashEntry_t* HashEntry1 = EnvROBARM.StateID2CoordTable[State1ID]; + EnvROBARMHashEntry_t* HashEntry2 = EnvROBARM.StateID2CoordTable[State2ID]; + + return (HashEntry1->endeffx == HashEntry2->endeffx && HashEntry1->endeffy == HashEntry2->endeffy); +} + +//------------------------------------------------------------------------------ diff --git a/navigations/sbpl/src/heuristics/embedded_heuristic.cpp b/navigations/sbpl/src/heuristics/embedded_heuristic.cpp new file mode 100755 index 0000000..c1d05a0 --- /dev/null +++ b/navigations/sbpl/src/heuristics/embedded_heuristic.cpp @@ -0,0 +1,50 @@ +/* + * Copyright (c) 2015, Maxim Likhachev + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Carnegie Mellon University nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include + +EmbeddedHeuristic::EmbeddedHeuristic(DiscreteSpaceInformation* environment) : + Heuristic(environment) +{ +} + +int EmbeddedHeuristic::GetGoalHeuristic(int state_id) +{ + return m_environment->GetGoalHeuristic(state_id); +} + +int EmbeddedHeuristic::GetStartHeuristic(int state_id) +{ + return m_environment->GetStartHeuristic(state_id); +} + +int EmbeddedHeuristic::GetFromToHeuristic(int from_id, int to_id) +{ + return m_environment->GetFromToHeuristic(from_id, to_id); +} diff --git a/navigations/sbpl/src/include/sbpl/config.h b/navigations/sbpl/src/include/sbpl/config.h new file mode 100755 index 0000000..53f3564 --- /dev/null +++ b/navigations/sbpl/src/include/sbpl/config.h @@ -0,0 +1,134 @@ +/* + * Copyright (c) 2008, Maxim Likhachev + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Carnegie Mellon University nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + + #include + #ifdef ROS + #include + #endif + +#ifndef __CONFIG_H_ +#define __CONFIG_H_ + +/** + * \brief if set, then heuristic is used if available + */ +#define USE_HEUR 1 + +/** + * \brief memory debugging (available for vc++) + */ +#ifdef WIN32 +#define MEM_CHECK 0 +#endif + +/** + * \brief regular debugging + */ +#define DEBUG 0 + +/** + * \brief timing debugging + */ +#define TIME_DEBUG 0 + +/** + * \brief small epsilon for various floating error checking + */ +#define ERR_EPS 0.0000001 + +#define SBPL_LEVEL_NONE 0 +#define SBPL_LEVEL_DEBUG 1 +#define SBPL_LEVEL_INFO 2 +#define SBPL_LEVEL_WARN 3 +#define SBPL_LEVEL_ERROR 4 +#define SBPL_LEVEL_FATAL 5 + +typedef int (*SBPL_PRINT_TEXT_FP)(int level, const char*); +typedef int (*SBPL_FFLUSH_TEXT_FP)(FILE*); + +void SET_SBPL_PRINT_TEXT_FP(SBPL_PRINT_TEXT_FP fptr); +void SET_SBPL_FFLUSH_TEXT_FP(SBPL_FFLUSH_TEXT_FP fptr); + +int SBPL_PRINTALL(int level, const char* format, ...); +int SBPL_FPRINTALL(FILE* file, const char* format, ...); +int SBPL_FFLUSHALL(FILE* file); + +// Standard Output Logger Macros +#ifdef ROS +#define SBPL_DEBUG ROS_DEBUG +#define SBPL_DEBUG_NAMED(a,...) ROS_DEBUG_NAMED("SBPL_" #a,__VA_ARGS__) +#define SBPL_INFO ROS_INFO +#define SBPL_WARN ROS_WARN +#define SBPL_ERROR ROS_ERROR +#define SBPL_FATAL ROS_FATAL +#else + #if DEBUG +#define SBPL_DEBUG(...) SBPL_PRINTALL(SBPL_LEVEL_DEBUG, __VA_ARGS__) +#define SBPL_DEBUG_NAMED(file, ...) SBPL_FPRINTALL(file, __VA_ARGS__) +#define SBPL_INFO(...) SBPL_PRINTALL(SBPL_LEVEL_INFO, __VA_ARGS__) +#define SBPL_WARN(...) SBPL_PRINTALL(SBPL_LEVEL_WARN, __VA_ARGS__) +#define SBPL_ERROR(...) SBPL_PRINTALL(SBPL_LEVEL_ERROR, __VA_ARGS__) +#define SBPL_FATAL(...) SBPL_PRINTALL(SBPL_LEVEL_FATAL, __VA_ARGS__) + #else +#define SBPL_DEBUG(...) +#define SBPL_DEBUG_NAMED(file, ...) +#define SBPL_INFO(...) +#define SBPL_WARN(...) +#define SBPL_ERROR(...) +#define SBPL_FATAL(...) + #endif +#endif + +// File Output Logger Macros +#ifdef ROS +#define SBPL_DEBUG_NAMED(a,...) ROS_DEBUG_NAMED("SBPL_" #a,__VA_ARGS__) + +#define SBPL_FOPEN(...) (FILE*)1 +#define SBPL_FCLOSE(...) +#define SBPL_PRINTF ROS_DEBUG +#define SBPL_FPRINTF(a,...) ROS_DEBUG_NAMED("SBPL_" #a,__VA_ARGS__) +#define SBPL_FFLUSH(...) +#else + #if DEBUG +#define SBPL_FOPEN fopen +#define SBPL_FCLOSE fclose +#define SBPL_PRINTF(...) SBPL_PRINTALL(SBPL_LEVEL_NONE, __VA_ARGS__) +#define SBPL_FPRINTF(file, ...) SBPL_FPRINTALL(file, __VA_ARGS__) +#define SBPL_FFLUSH(file) SBPL_FFLUSHALL(file) + #else +#define SBPL_FOPEN(file, ...) (FILE*)1 +#define SBPL_FCLOSE(...) +#define SBPL_PRINTF(...) +#define SBPL_FPRINTF(file, ...) +#define SBPL_FFLUSH(file) + #endif +#endif + +#endif + diff --git a/navigations/sbpl/src/include/sbpl/discrete_space_information/environment.h b/navigations/sbpl/src/include/sbpl/discrete_space_information/environment.h new file mode 100755 index 0000000..018e284 --- /dev/null +++ b/navigations/sbpl/src/include/sbpl/discrete_space_information/environment.h @@ -0,0 +1,297 @@ +/* + * Copyright (c) 2008, Maxim Likhachev + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Carnegie Mellon University nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef __ENVIRONMENT_H_ +#define __ENVIRONMENT_H_ + +#include +#include +#include +#include + +class CMDPSTATE; +struct MDPConfig; + +/** + * \brief base class for environments defining planning graphs + * + * It is independent of the graph search used + * The main means of communication between environment and graph search is + * through stateID. Each state is uniquely defined by stateID and graph + * search is ONLY aware of stateIDs. It doesn't know anything about + * the actual state variables. Environment, on the * other hand, maintains a + * mapping from stateID to actual state variables (coordinates) using + * StateID2IndexMapping array + */ +class DiscreteSpaceInformation +{ +public: + /** + * \brief mapping from hashentry stateID (used in environment to contain + * the coordinates of a state, say x,y or x,y,theta) + * to an array of state indices used in searches. + * + * If a single search is done, then it is a single entry. So + * StateID2IndexMapping[100][0] = 5 means that hashentry with stateID 100 + * is mapped onto search index = 5 in search 0 The value of -1 means that + * no search state has been created yet for this hashentry + */ + std::vector StateID2IndexMapping; + + /** + * \brief debugging file + */ + FILE* fDeb; + + /** + * \brief initialization environment from file (see .cfg files for examples) + */ + virtual bool InitializeEnv(const char* sEnvFile) = 0; + + /** + * \brief initialization of MDP data structure + */ + virtual bool InitializeMDPCfg(MDPConfig *MDPCfg) = 0; + + /** + * \brief heuristic estimate from state FromStateID to state ToStateID + */ + virtual int GetFromToHeuristic(int FromStateID, int ToStateID) = 0; + + /** + * \brief heuristic estimate from state with stateID to goal state + */ + virtual int GetGoalHeuristic(int stateID) = 0; + + /** + * \brief heuristic estimate from start state to state with stateID + */ + virtual int GetStartHeuristic(int stateID) = 0; + + /** \brief depending on the search used, it may call GetSuccs function + * (for forward search) or GetPreds function (for backward search) + * or both (for incremental search). At least one of this functions should + * be implemented (otherwise, there will be no search to run) Some searches + * may also use SetAllActionsandAllOutcomes or SetAllPreds functions if they + * keep the pointers to successors (predecessors) but most searches do not + * require this, so it is not necessary to support this + */ + virtual void GetSuccs(int SourceStateID, std::vector* SuccIDV, std::vector* CostV) = 0; + + /** + * \brief This version is used with lazy planners. The environment must tell which successors have + * been evaluated fully (and therefore their true cost is being returned) or if it has not been. + * If a successor's cost is not true, then the cost must not overestimate the true cost. + */ + virtual void GetLazySuccs(int SourceStateID, std::vector* SuccIDV, std::vector* CostV, std::vector* isTrueCost){ + throw SBPL_Exception("ERROR: GetLazySuccs is not implemented for this environment"); + }; + + /** + * \brief This version of GetSuccs is needed for E-Graphs. It always returns a unique ID for + * every successor. Generally, this function operates the same as the usual GetSuccs + * and only has different behavior when dealing with an underspecified goal condition + * so that several different states will have to map to the same id number (most planners + * in sbpl use a single goal id number to identify the goal). This function is used + * in conjunction with isGoal. + */ + virtual void GetSuccsWithUniqueIds(int SourceStateID, std::vector* SuccIDV, std::vector* CostV){ + throw SBPL_Exception("ERROR: GetSuccsWithUniqueIds is not implemented for this environment"); + }; + + /** + * \brief The lazy version of GetSuccsUniqueIds. + */ + virtual void GetLazySuccsWithUniqueIds(int SourceStateID, std::vector* SuccIDV, std::vector* CostV, std::vector* isTrueCost){ + throw SBPL_Exception("ERROR: GetLazySuccsWithUniqueIds (lazy) is not implemented for this environment"); + }; + + /** + * \brief Used with lazy planners. This evaluates a edge fully that had previously been provided by GetSuccs + * without a "true cost". If the edge is found to be invalid, it should return -1 + */ + virtual int GetTrueCost(int parentID, int childID){ + throw SBPL_Exception("ERROR: GetTrueCost (used for lazy planning) is not implemented for this environment"); + return -1; + }; + + /** + * \brief This function is generally used with E-Graphs (in conjunction with GetSuccsWithUniqueIds). + */ + virtual bool isGoal(int id){ + throw SBPL_Exception("ERROR: isGoal is not implemented for this environment"); + return false; + }; + + /** + * \brief see comments for GetSuccs functon + */ + virtual void GetPreds(int TargetStateID, std::vector* PredIDV, std::vector* CostV) = 0; + + /** + * \brief see comments for GetSuccs functon + */ + virtual void GetLazyPreds(int TargetStateID, std::vector* PredIDV, std::vector* CostV, std::vector* isTrueCost){ + throw SBPL_Exception("ERROR: GetLazyPreds is not implemented for this environment"); + }; + + /** + * \brief see comments for GetSuccs functon + */ + virtual void GetPredsWithUniqueIds(int TargetStateID, std::vector* PredIDV, std::vector* CostV){ + SBPL_ERROR("ERROR: GetPredsWithUniqueIds is not implemented for this environment!\n"); + throw SBPL_Exception("ERROR: GetPredsWithUniqueIds is not implemented for this environment"); + }; + + /** + * \brief see comments for GetSuccs functon + */ + virtual void GetLazyPredsWithUniqueIds(int TargetStateID, std::vector* PredIDV, std::vector* CostV, std::vector* isTrueCost){ + SBPL_ERROR("ERROR: GetLazyPredsWithUniqueIds is not implemented for this environment!\n"); + throw SBPL_Exception("ERROR: GetLazyPredsWithUniqueIds is not implemented for this environment"); + }; + + /** + * \brief see comments for GetSuccs functon + */ + virtual void SetAllActionsandAllOutcomes(CMDPSTATE* state) = 0; + + /** + * \brief see comments for GetSuccs functon + */ + virtual void SetAllPreds(CMDPSTATE* state) = 0; + + /** + * \brief returns the number of states (hashentries) created + */ + virtual int SizeofCreatedEnv() = 0; + + /** + * \brief prints the state variables for a state with stateID + */ + virtual void PrintState(int stateID, bool bVerbose, FILE* fOut = NULL) = 0; + + /** + * \brief prints environment config file + */ + virtual void PrintEnv_Config(FILE* fOut) = 0; + + /** + * \brief sets a parameter to a value. The set of supported parameters depends on the particular environment + */ + virtual bool SetEnvParameter(const char* parameter, int value) + { + SBPL_ERROR("ERROR: Environment has no parameters that can be set via SetEnvParameter function\n"); + return false; + } + + /** NOTE - for debugging door planner - ben 8.31.09 */ + virtual std::vector GetExpandedStates() + { + SBPL_ERROR("Error: Not yet defined for any environment other than door environment.\n"); + std::vector list; + return list; + } + + /** \brief returns true if two states meet the same condition, brief this + * is used in some planners to figure out if two states are the same in + * some lower-dimensional manifold for example, in robotarm planning, two + * states could be equivalent if their end effectors are at the same + * position unless overwritten in a child class, this function is not + * implemented + */ + virtual bool AreEquivalent(int StateID1, int StateID2) + { + throw SBPL_Exception("ERROR: environment does not support calls to AreEquivalent function"); + } + + /** \brief the following two functions generate succs/preds at some + * domain-dependent distance. The number of generated succs/preds is up + * to the environment. NOTE: they MUST generate goal state as a succ/pred if + * it is within the distance from the state CLowV is the corresponding + * vector of lower bounds on the costs from the state to the successor + * states (or vice versa for preds function) unless overwritten in a child + * class, this function is not implemented + */ + virtual void GetRandomSuccsatDistance(int SourceStateID, std::vector* SuccIDV, std::vector* CLowV) + { + throw SBPL_Exception("ERROR: environment does not support calls to GetRandomSuccsatDistance function"); + } + + /** + * \brief see comments for GetRandomSuccsatDistance + */ + virtual void GetRandomPredsatDistance(int TargetStateID, std::vector* PredIDV, std::vector* CLowV) + { + throw SBPL_Exception("ERROR: environment does not support calls to GetRandomPredsatDistance function"); + } + + /** + * \brief checks the heuristics for consistency (some environments do not support this debugging call) + */ + virtual void EnsureHeuristicsUpdated(bool bGoalHeuristics) + { + // by default the heuristics are up-to-date, but in some cases, the + // heuristics are computed only when really needed. For example, + // xytheta environment uses 2D gridsearch as heuristics, and then + // re-computes them only when this function is called. This minimizes + // the number of times heuristics are re-computed which is an expensive + // operation if bGoalHeuristics == true, then it updates goal + // heuristics (for forward search), otherwise it updates start + // heuristics (for backward search) + } + + /** + * \brief destructor + */ + virtual ~DiscreteSpaceInformation() + { + SBPL_PRINTF("destroying discretespaceinformation\n"); + for (unsigned int i = 0; i < StateID2IndexMapping.size(); ++i) { + if (StateID2IndexMapping[i] != NULL) delete[] StateID2IndexMapping[i]; + } + SBPL_FCLOSE(fDeb); + } + + /** + * \brief constructor + */ + DiscreteSpaceInformation() + { +#if !defined(ROS) && DEBUG + const char* envdebug = "envdebug.txt"; +#endif + if ((fDeb = SBPL_FOPEN(envdebug, "w")) == NULL) { + throw SBPL_Exception("ERROR: failed to open debug file for environment"); + } + } +}; + +#endif + diff --git a/navigations/sbpl/src/include/sbpl/discrete_space_information/environment_XXX.h b/navigations/sbpl/src/include/sbpl/discrete_space_information/environment_XXX.h new file mode 100755 index 0000000..f84690a --- /dev/null +++ b/navigations/sbpl/src/include/sbpl/discrete_space_information/environment_XXX.h @@ -0,0 +1,178 @@ +/* + * Copyright (c) 2008, Maxim Likhachev + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Carnegie Mellon University nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef __ENVIRONMENT_XXX_H_ +#define __ENVIRONMENT_XXX_H_ + +#include +#include +#include + +#define XXX_MAXACTIONSWIDTH 9 + +class CMDPACTION; +class CMDPSTATE; +class MDPConfig; + +typedef struct ENV_XXX_CONFIG +{ + //parameters that are read from the configuration file + unsigned int StartX1; + unsigned int StartX2; + unsigned int StartX3; + unsigned int StartX4; + unsigned int GoalX1; + unsigned int GoalX2; + unsigned int GoalX3; + unsigned int GoalX4; + + //derived and initialized elsewhere parameters +} EnvXXXConfig_t; + +typedef struct ENVXXXHASHENTRY +{ + int stateID; + unsigned int X1; + unsigned int X2; + unsigned int X3; + unsigned int X4; +} EnvXXXHashEntry_t; + +typedef struct +{ + int startstateid; + int goalstateid; + + //hash table of size x_size*y_size. Maps from coords to stateId + int HashTableSize; + std::vector* Coord2StateIDHashTable; + + //vector that maps from stateID to coords + std::vector StateID2CoordTable; + + //any additional variables +} EnvironmentXXX_t; + +/** \brief this is just an example of environment and can be used (copy and + * paste) for creating a more complex environment + */ +class EnvironmentXXX : public DiscreteSpaceInformation +{ +public: + /** + * \brief see comments on the same function in the parent class + */ + virtual bool InitializeEnv(const char* sEnvFile); + + /** + * \brief see comments on the same function in the parent class + */ + virtual bool InitializeMDPCfg(MDPConfig *MDPCfg); + + /** + * \brief see comments on the same function in the parent class + */ + virtual int GetFromToHeuristic(int FromStateID, int ToStateID); + + /** + * \brief see comments on the same function in the parent class + */ + virtual int GetGoalHeuristic(int stateID); + + /** + * \brief see comments on the same function in the parent class + */ + virtual int GetStartHeuristic(int stateID); + + /** + * \brief see comments on the same function in the parent class + */ + virtual void SetAllActionsandAllOutcomes(CMDPSTATE* state); + + /** + * \brief see comments on the same function in the parent class + */ + virtual void SetAllPreds(CMDPSTATE* state); + + /** + * \brief see comments on the same function in the parent class + */ + virtual void GetSuccs(int SourceStateID, std::vector* SuccIDV, std::vector* CostV); + + /** + * \brief see comments on the same function in the parent class + */ + virtual void GetPreds(int TargetStateID, std::vector* PredIDV, std::vector* CostV); + + /** + * \brief see comments on the same function in the parent class + */ + virtual int SizeofCreatedEnv(); + + /** + * \brief see comments on the same function in the parent class + */ + virtual void PrintState(int stateID, bool bVerbose, FILE* fOut = NULL); + + /** + * \brief see comments on the same function in the parent class + */ + virtual void PrintEnv_Config(FILE* fOut); + + ~EnvironmentXXX() { } + +protected: + //member variables + EnvXXXConfig_t EnvXXXCfg; + EnvironmentXXX_t EnvXXX; + + virtual void ReadConfiguration(FILE* fCfg); + + virtual void InitializeEnvConfig(); + + virtual unsigned int GETHASHBIN(unsigned int X1, unsigned int X2, unsigned int X3, unsigned int X4); + + virtual void PrintHashTableHist(); + + virtual EnvXXXHashEntry_t* GetHashEntry(unsigned int X1, unsigned int X2, unsigned int X3, unsigned int X4); + + virtual EnvXXXHashEntry_t* CreateNewHashEntry(unsigned int X1, unsigned int X2, unsigned int X3, unsigned int X4); + + virtual void CreateStartandGoalStates(); + + virtual void InitializeEnvironment(); + + virtual void AddAllOutcomes(unsigned int SourceX1, unsigned int SourceX2, unsigned int SourceX3, + unsigned int SourceX4, CMDPACTION* action, int cost); + + virtual void ComputeHeuristicValues(); +}; + +#endif + diff --git a/navigations/sbpl/src/include/sbpl/discrete_space_information/environment_nav2D.h b/navigations/sbpl/src/include/sbpl/discrete_space_information/environment_nav2D.h new file mode 100755 index 0000000..c13ee3b --- /dev/null +++ b/navigations/sbpl/src/include/sbpl/discrete_space_information/environment_nav2D.h @@ -0,0 +1,391 @@ +/* + * Copyright (c) 2008, Maxim Likhachev + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Carnegie Mellon University nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef __ENVIRONMENT_NAV2D_H_ +#define __ENVIRONMENT_NAV2D_H_ + +#include +#include +#include +#include + +#define ENVNAV2D_COSTMULT 1000 +#define ENVNAV2D_DEFAULTOBSTHRESH 1 //253-for willow garage //see explanation of the value below +#define ENVNAV2D_MAXDIRS 16 //TODO-debugmax - crashes for 8 in debug mode + +class CMDPSTATE; +class MDPConfig; + +//configuration parameters +typedef struct ENV_NAV2D_CONFIG +{ + ENV_NAV2D_CONFIG() + { + Grid2D = NULL; + } + + int EnvWidth_c; + int EnvHeight_c; + int StartX_c; + int StartY_c; + int EndX_c; + int EndY_c; + unsigned char** Grid2D; + //the value at which and above which cells are obstacles in the maps sent from outside + //the default is defined above + unsigned char obsthresh; + + int dx_[ENVNAV2D_MAXDIRS]; + int dy_[ENVNAV2D_MAXDIRS]; + //the intermediate cells through which the actions go + int dxintersects_[ENVNAV2D_MAXDIRS][2]; + int dyintersects_[ENVNAV2D_MAXDIRS][2]; + //distances of transitions + int dxy_distance_mm_[ENVNAV2D_MAXDIRS]; + + int numofdirs; //for now either 8 or 16 (default is 8) +} EnvNAV2DConfig_t; + +typedef struct ENVHASHENTRY +{ + int stateID; + int X; + int Y; +} EnvNAV2DHashEntry_t; + +//variables that dynamically change (e.g., array of states, ...) +typedef struct ENVNAV2D +{ + ENVNAV2D() + { + Coord2StateIDHashTable = NULL; + } + + int startstateid; + int goalstateid; + + bool bInitialized; + + //hash table of size x_size*y_size. Maps from coords to stateId + int HashTableSize; + std::vector* Coord2StateIDHashTable; + + //vector that maps from stateID to coords + std::vector StateID2CoordTable; + + //any additional variables +} EnvironmentNAV2D_t; + +/** + * \brief 2D (x,y) grid planning problem. For general structure see comments + * on parent class DiscreteSpaceInformation + */ +class EnvironmentNAV2D : public DiscreteSpaceInformation +{ +public: + /** + * \brief see comments on the same function in the parent class + */ + virtual bool InitializeEnv(const char* sEnvFile); + + /** + *\brief see comments on the same function in the parent class + */ + virtual bool InitializeMDPCfg(MDPConfig *MDPCfg); + + /** + * \brief see comments on the same function in the parent class + */ + virtual int GetFromToHeuristic(int FromStateID, int ToStateID); + + /** + * \brief see comments on the same function in the parent class + */ + virtual int GetGoalHeuristic(int stateID); + + /** + * \brief see comments on the same function in the parent class + */ + virtual int GetStartHeuristic(int stateID); + + /** + * \brief see comments on the same function in the parent class + */ + virtual void SetAllActionsandAllOutcomes(CMDPSTATE* state); + + /** + * \brief see comments on the same function in the parent class + */ + virtual void SetAllPreds(CMDPSTATE* state); + + /** + * \brief see comments on the same function in the parent class + */ + virtual void GetSuccs(int SourceStateID, std::vector* SuccIDV, std::vector* CostV); + + + virtual void GetLazySuccs(int SourceStateID, std::vector* SuccIDV, std::vector* CostV, std::vector* isTrueCost){ + GetSuccs(SourceStateID, SuccIDV, CostV); + isTrueCost->resize(SuccIDV->size(),true); + }; + virtual void GetSuccsWithUniqueIds(int SourceStateID, std::vector* SuccIDV, std::vector* CostV){ + GetSuccs(SourceStateID, SuccIDV, CostV); + }; + virtual void GetLazySuccsWithUniqueIds(int SourceStateID, std::vector* SuccIDV, std::vector* CostV, std::vector* isTrueCost){ + GetLazySuccs(SourceStateID, SuccIDV, CostV, isTrueCost); + }; + + virtual int GetTrueCost(int parentID, int childID){return -1;};//FIXME: this shouldn't ever be called because we always return true cost... + + virtual bool isGoal(int id){ + return EnvNAV2D.goalstateid == id; + }; + + virtual void GetLazyPreds(int TargetStateID, std::vector* PredIDV, std::vector* CostV, std::vector* isTrueCost){ + GetPreds(TargetStateID, PredIDV, CostV); + isTrueCost->resize(PredIDV->size(),true); + }; + virtual void GetPredsWithUniqueIds(int TargetStateID, std::vector* PredIDV, std::vector* CostV){ + GetPreds(TargetStateID, PredIDV, CostV); + }; + virtual void GetLazyPredsWithUniqueIds(int TargetStateID, std::vector* PredIDV, std::vector* CostV, std::vector* isTrueCost){ + GetLazyPreds(TargetStateID, PredIDV, CostV, isTrueCost); + }; + + /** + * \brief see comments on the same function in the parent class + */ + virtual void GetPreds(int TargetStateID, std::vector* PredIDV, std::vector* CostV); + + /** + * \brief see comments on the same function in the parent class + */ + virtual int SizeofCreatedEnv(); + + /** + * \brief see comments on the same function in the parent class + */ + virtual void PrintState(int stateID, bool bVerbose, FILE* fOut = NULL); + + /** + * \brief see comments on the same function in the parent class + */ + virtual void PrintEnv_Config(FILE* fOut); + + /** + * \brief initialize environment. Gridworld is defined as matrix A of + * size width by height. + * So, internally, it is accessed as A[x][y] with x ranging from 0 to + * width-1 and and y from 0 to height-1. Each element in A[x][y] is unsigned + * char. A[x][y] = 0 corresponds to fully traversable and cost is just + * Euclidean distance. The cost of transition between two neighboring cells + * is EuclideanDistance*(max(A[sourcex][sourcey],A[targetx][targety])+1). If + * A[x][y] >= obsthresh, then in the above equation it is assumed to be + * infinite. mapdata is a pointer to the values of A. If it is null, then A + * is initialized to all zeros. Mapping is: A[x][y] = mapdata[x+y*width] + * start/goal are given by startx, starty, goalx,goaly. If they are not + * known yet, just set them to 0. Later setgoal/setstart can be executed + * finally obsthresh defined obstacle threshold, as mentioned above + */ + virtual bool InitializeEnv(int width, int height, + + /** if mapdata is NULL the grid is initialized to all freespace */ + const unsigned char* mapdata, int startx, int starty, int goalx, int goaly, unsigned char obsthresh); + + /** + * \brief a short version of environment initialization. Here start and goal coordinates will be set to 0s + * + * if mapdata is NULL the grid is initialized to all freespace + */ + virtual bool InitializeEnv(int width, int height, const unsigned char* mapdata, unsigned char obsthresh); + + /** + * \brief set start location + */ + virtual int SetStart(int x, int y); + + /** + * \brief set goal location + */ + virtual int SetGoal(int x, int y); + + /** + * \brief currently, this is not used + */ + virtual void SetGoalTolerance(double tol_x, double tol_y, double tol_theta); /**< not used yet */ + + /** + * \brief update the traversability of a cell + */ + virtual bool UpdateCost(int x, int y, unsigned char newcost); + + /** \brief this function fill in Predecessor/Successor states of edges + * whose costs changed + * It takes in an array of cells whose traversability changed, and returns + * (in vector preds_of_changededgesIDV) the IDs of all states that have + * outgoing edges that go through the changed cells + */ + virtual void GetPredsofChangedEdges(std::vector const * changedcellsV, + std::vector *preds_of_changededgesIDV); + + /** + * \brief same as GetPredsofChangedEdges, but returns successor states. + * Both functions need to be present for incremental search + */ + virtual void GetSuccsofChangedEdges(std::vector const * changedcellsV, + std::vector *succs_of_changededgesIDV); + + /** + * \brief returns true if two states meet the same condition - see + * environment.h for more info + */ + virtual bool AreEquivalent(int StateID1, int StateID2); + + /** + * \brief generates succs at some domain-dependent distance - see + * environment.h for more info used by certain searches such as R* + */ + virtual void GetRandomSuccsatDistance(int SourceStateID, std::vector* SuccIDV, std::vector* CLowV); + + /** + * \brief generates preds at some domain-dependent distance - see + * environment.h for more info + * used by certain searches such as R* + */ + virtual void GetRandomPredsatDistance(int TargetStateID, std::vector* PredIDV, std::vector* CLowV); + + /** + * \brief generates nNumofNeighs random neighbors of cell at + * distance nDist_c (measured in cells) + * it will also generate goal if within this distance as an additional + * neighbor + */ + virtual void GetRandomNeighs(int stateID, std::vector* NeighIDV, std::vector* CLowV, int nNumofNeighs, + int nDist_c, bool bSuccs); + + /** + * \brief a direct way to set the configuration of environment - see + * InitializeEnv function for details about the parameters + * it is not a full way to initialize environment. To fully initialize, one + * needs to executed InitGeneral in addition. + * + * if mapdata is NULL the grid is initialized to all freespace + */ + virtual void SetConfiguration(int width, int height, const unsigned char* mapdata, + int startx, int starty, + int goalx, int goaly); + + /** + * \brief performs initialization of environments. It is usually called + * in from InitializeEnv. But if SetConfiguration is used, then one + * should call InitGeneral by himself + */ + virtual bool InitGeneral(); + + /** + * \brief returns the actual associated with state of stateID + */ + virtual void GetCoordFromState(int stateID, int& x, int& y) const; + + /** + * \brief returns a stateID associated with coordinates + */ + virtual int GetStateFromCoord(int x, int y); + + /** + * \brief returns true if is obstacle (used by the value of this + * cell and obsthresh) + */ + virtual bool IsObstacle(int x, int y); + + /** + * \brief returns the cost associated with cell, i.e., A[x][y] + */ + virtual unsigned char GetMapCost(int x, int y); + + /** + * \brief returns the parameters associated with the current environment. + * This is useful for setting up a copy of an environment (i.e., second + * planning problem) + */ + virtual void GetEnvParms(int *size_x, int *size_y, int* startx, int* starty, int* goalx, int* goaly, + unsigned char* obsthresh); + + /** + * \brief way to set up various parameters. For a list of parameters, see + * the body of the function - it is pretty straightforward + */ + virtual bool SetEnvParameter(const char* parameter, int value); + + /** + * \brief access to internal configuration data structure + */ + virtual const EnvNAV2DConfig_t* GetEnvNavConfig(); + + EnvironmentNAV2D(); + ~EnvironmentNAV2D(); + + /** + * \brief print some time statistics + */ + virtual void PrintTimeStat(FILE* fOut); + + /** + * \brief checks X,Y against map boundaries + */ + virtual bool IsWithinMapCell(int X, int Y); + +protected: + //member data + EnvNAV2DConfig_t EnvNAV2DCfg; + EnvironmentNAV2D_t EnvNAV2D; + + virtual void ReadConfiguration(FILE* fCfg); + + virtual void InitializeEnvConfig(); + + virtual unsigned int GETHASHBIN(unsigned int X, unsigned int Y); + + virtual void PrintHashTableHist(); + + virtual EnvNAV2DHashEntry_t* GetHashEntry(int X, int Y); + + virtual EnvNAV2DHashEntry_t* CreateNewHashEntry(int X, int Y); + + virtual void InitializeEnvironment(); + + virtual void ComputeHeuristicValues(); + + virtual bool IsValidCell(int X, int Y); + + virtual void Computedxy(); +}; + +#endif + diff --git a/navigations/sbpl/src/include/sbpl/discrete_space_information/environment_nav2Duu.h b/navigations/sbpl/src/include/sbpl/discrete_space_information/environment_nav2Duu.h new file mode 100755 index 0000000..986040b --- /dev/null +++ b/navigations/sbpl/src/include/sbpl/discrete_space_information/environment_nav2Duu.h @@ -0,0 +1,252 @@ +/* + * Copyright (c) 2009, Maxim Likhachev + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Carnegie Mellon University nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef __ENVIRONMENT_NAV2DUU_H_ +#define __ENVIRONMENT_NAV2DUU_H_ + +#include +#include +#include +#include +#include +#include +#include + +#define ENVNAV2DUU_COSTMULT 1000 +#define NAV2DUU_MAXACTIONSWIDTH 9 +#define ENVNAV2DUU_MAXDIRS 8 + +class CMDPACTION; +class CMDPSTATE; +class MDPConfig; + +typedef struct ENV_NAV2DUU_CONFIG +{ + //parameters that are read from the configuration file + int EnvWidth_c; + int EnvHeight_c; + int StartX_c; + int StartY_c; + int EndX_c; + int EndY_c; + //cost matrix + unsigned char** Grid2D; + //the value at which and above which cells are obstacles in the maps sent from outside + //the default is defined above + unsigned char obsthresh; + //uncertainty matrix (0 defines P(obstacle) = 0, and 1.0 defines P(obstacle) = 1) + float** UncertaintyGrid2D; + //matrix of hidden variable IDs + int** HiddenVariableXY2ID; + + //derived and initialized elsewhere parameters + + //possible transitions + int dx_[ENVNAV2DUU_MAXDIRS]; + int dy_[ENVNAV2DUU_MAXDIRS]; + //distances of transitions + int dxy_distance_mm_[ENVNAV2DUU_MAXDIRS]; + //the intermediate cells through which the actions go + int dxintersects_[ENVNAV2D_MAXDIRS][2]; + int dyintersects_[ENVNAV2D_MAXDIRS][2]; + int numofdirs; //for now can only be 8 + + //size of environment, number of hidden variables + int sizeofS; + int sizeofH; +} EnvNAV2DUUConfig_t; + +#define NAVNAV2DUU_MAXWIDTHHEIGH 1024 +#define ENVNAV2DUU_STATEIDTOY(stateID) (stateID%NAVNAV2DUU_MAXWIDTHHEIGH) +#define ENVNAV2DUU_STATEIDTOX(stateID) (stateID/NAVNAV2DUU_MAXWIDTHHEIGH) +#define ENVNAV2DUU_XYTOSTATEID(X, Y) (X*NAVNAV2DUU_MAXWIDTHHEIGH + Y) + +typedef struct +{ + int startstateid; + int goalstateid; + + //any additional variables + bool bInitialized; +} EnvironmentNAV2DUU_t; + +/** + * \brief this class is NOT fully yet implemented, please do not use it! + */ +class EnvironmentNAV2DUU : public DiscreteSpaceInformation +{ +public: + /** + * \brief see comments on the same function in the parent class + */ + virtual bool InitializeEnv(const char* sEnvFile); + + /** + * \brief initialize environment. Gridworld is defined as matrix A of + * size width by height. + * So, internally, it is accessed as A[x][y] with x ranging from 0 to + * width-1 and and y from 0 to height-1. Each element in A[x][y] is unsigned + * char. A[x][y] = 0 corresponds to fully traversable and cost is just + * Euclidean distance. The cost of transition between two neighboring cells + * is EuclideanDistance*(max(A[sourcex][sourcey],A[targetx][targety])+1). If + * A[x][y] >= obsthresh, then in the above equation it is assumed to be + * infinite. mapdata is a pointer to the values of A. If it is null, then A + * is initialized to all zeros. Mapping is: A[x][y] = mapdata[x+y*width] + * start/goal are given by startx, starty, goalx,goaly. If they are not + * known yet, just set them to 0. Later setgoal/setstart can be executed + * finally obsthresh defined obstacle threshold, as mentioned above + * uncertaintymapdata is set up in the same way as mapdata in terms of the + * order in terms of the values, uncertaintymapdata specifies probabilities + * of being obstructed + */ + virtual bool InitializeEnv(int width, int height, const unsigned char* mapdata, const float* uncertaintymapdata, + unsigned char obsthresh); + + /** + * \brief set start location + */ + virtual int SetStart(int x, int y); + + /** + * \brief set goal location + */ + virtual int SetGoal(int x, int y); + + /** + * \brief update the traversability of a cell + */ + virtual bool UpdateCost(int x, int y, unsigned char newcost); + + /** + * \brief see comments on the same function in the parent class + */ + virtual bool InitializeMDPCfg(MDPConfig *MDPCfg); + + /** + * \brief see comments on the same function in the parent class + */ + virtual int GetFromToHeuristic(int FromStateID, int ToStateID); + + /** + * \brief see comments on the same function in the parent class + */ + virtual int GetGoalHeuristic(int stateID); + + /** + * \brief see comments on the same function in the parent class + */ + virtual int GetStartHeuristic(int stateID); + + /** + * \brief see comments on the same function in the parent class + */ + virtual void PrintState(int stateID, bool bVerbose, FILE* fOut = NULL); + + /** + * \brief see comments on the same function in the parent class + */ + virtual void PrintEnv_Config(FILE* fOut); + + EnvironmentNAV2DUU(); + + ~EnvironmentNAV2DUU() + { + } + + /** + * \brief not fully implemented yet + */ + virtual void GetPreds(int stateID, const std::vector* updatedhvaluesV, + std::vector* IncomingDetActionV, std::vector* IncomingStochActionV, + std::vector* StochActionNonpreferredOutcomeV); + + /** + * \brief not fully implemented yet + */ + virtual void SetAllActionsandAllOutcomes(CMDPSTATE* state) + { + throw SBPL_Exception("ERROR: SetAllActionsandAllOutcomes not supported in NAV2D_UNDER_UNCERTAINTY"); + } + + /** + * \brief not fully implemented yet + */ + virtual void SetAllPreds(CMDPSTATE* state) + { + throw SBPL_Exception("ERROR: SetAllPreds not supported in NAV2D_UNDER_UNCERTAINTY"); + } + + /** + * \brief not fully implemented yet + */ + virtual void GetSuccs(int SourceStateID, std::vector* SuccIDV, std::vector* CostV) + { + throw SBPL_Exception("ERROR: GetSuccs not supported in NAV2D_UNDER_UNCERTAINTY"); + } + + /** + * \brief not fully implemented yet + */ + virtual void GetPreds(int TargetStateID, std::vector* PredIDV, std::vector* CostV) + { + throw SBPL_Exception("ERROR: GetPreds not supported in NAV2D_UNDER_UNCERTAINTY"); + } + + /** + * \brief not fully implemented yet + */ + virtual int SizeofCreatedEnv(); + + /** + * \brief not fully implemented yet + */ + virtual int SizeofH(); + +protected: + //member variables + EnvNAV2DUUConfig_t EnvNAV2DUUCfg; + EnvironmentNAV2DUU_t EnvNAV2DUU; + + //mapdata and uncertaintymapdata is assumed to be organized into a linear array with y being major: map[x+y*width] + virtual void SetConfiguration(int width, int height, const unsigned char* mapdata, const float* uncertaintymapdata); + + virtual void ReadConfiguration(FILE* fCfg); + virtual void InitializeEnvConfig(); + virtual void InitializeEnvironment(); + virtual void ComputeHeuristicValues(); + virtual bool InitGeneral(); + + virtual bool IsValidRobotPosition(int X, int Y); + virtual bool IsWithinMapCell(int X, int Y); + + virtual void Computedxy(); +}; + +#endif + diff --git a/navigations/sbpl/src/include/sbpl/discrete_space_information/environment_navxythetalat.h b/navigations/sbpl/src/include/sbpl/discrete_space_information/environment_navxythetalat.h new file mode 100755 index 0000000..0899108 --- /dev/null +++ b/navigations/sbpl/src/include/sbpl/discrete_space_information/environment_navxythetalat.h @@ -0,0 +1,688 @@ +/* + * Copyright (c) 2008, Maxim Likhachev + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Carnegie Mellon University nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef __ENVIRONMENT_NAVXYTHETALAT_H_ +#define __ENVIRONMENT_NAVXYTHETALAT_H_ + +#include +#include +#include + +#include +#include + +// Define to test against in client code. Signals that Set2DBlockSize and +// Set2DBucketSize are available in EnvironmentNAVXYTHETALATTICE +#define SBPL_CUSTOM_2D_OPTIONS 1 + +//eight-connected grid +#define NAVXYTHETALAT_DXYWIDTH 8 +#define ENVNAVXYTHETALAT_DEFAULTOBSTHRESH 254 //see explanation of the value below +//maximum number of states for storing them into lookup (as opposed to hash) +#define SBPL_XYTHETALAT_MAXSTATESFORLOOKUP 100000000 +//definition of theta orientations +//0 - is aligned with X-axis in the positive direction (1,0 in polar coordinates) +//theta increases as we go counterclockwise +//number of theta values - should be power of 2 +#define NAVXYTHETALAT_THETADIRS 16 +//number of actions per x,y,theta state +//decrease, increase, same angle while moving plus decrease, increase angle while standing. +#define NAVXYTHETALAT_DEFAULT_ACTIONWIDTH 5 +#define NAVXYTHETALAT_COSTMULT_MTOMM 1000 + +class CMDPSTATE; +class MDPConfig; +class SBPL2DGridSearch; + +struct EnvNAVXYTHETALATAction_t +{ + unsigned char aind; //index of the action (unique for given starttheta) + char starttheta; + char dX; + char dY; + char endtheta; + unsigned int cost; + std::vector intersectingcellsV; + //start at 0,0,starttheta and end at endcell in continuous domain with half-bin less to account for 0,0 start + std::vector intermptV; + //start at 0,0,starttheta and end at endcell in discrete domain + std::vector interm3DcellsV; + + int motprimID; + double turning_radius; + +}; + +struct EnvNAVXYTHETALATHashEntry_t +{ + int stateID; + int X; + int Y; + char Theta; + int iteration; +}; + +struct SBPL_xytheta_mprimitive +{ + int motprimID; + unsigned char starttheta_c; + int additionalactioncostmult; + sbpl_xy_theta_cell_t endcell; + double turning_radius; + //intermptV start at 0,0,starttheta and end at endcell in continuous + //domain with half-bin less to account for 0,0 start + std::vector intermptV; +}; + +//variables that dynamically change (e.g., array of states, ...) +struct EnvironmentNAVXYTHETALAT_t +{ + int startstateid; + int goalstateid; + + bool bInitialized; + + //any additional variables +}; + +//configuration parameters +struct EnvNAVXYTHETALATConfig_t +{ + int EnvWidth_c; + int EnvHeight_c; + int NumThetaDirs; + int StartX_c; + int StartY_c; + int StartTheta; + int EndX_c; + int EndY_c; + int EndTheta; + unsigned char** Grid2D; + + std::vector ThetaDirs; + double StartTheta_rad; + double EndTheta_rad; + double min_turning_radius_m; + + // the value at which and above which cells are obstacles in the maps sent from outside + // the default is defined above + unsigned char obsthresh; + + // the value at which and above which until obsthresh (not including it) + // cells have the nearest obstacle at distance smaller than or equal to + // the inner circle of the robot. In other words, the robot is definitely + // colliding with the obstacle, independently of its orientation + // if no such cost is known, then it should be set to obsthresh (if center + // of the robot collides with obstacle, then the whole robot collides with + // it independently of its rotation) + unsigned char cost_inscribed_thresh; + + // the value at which and above which until cost_inscribed_thresh (not including it) cells + // **may** have a nearest osbtacle within the distance that is in between + // the robot inner circle and the robot outer circle + // any cost below this value means that the robot will NOT collide with any + // obstacle, independently of its orientation + // if no such cost is known, then it should be set to 0 or -1 (then no cell + // cost will be lower than it, and therefore the robot's footprint will + // always be checked) + int cost_possibly_circumscribed_thresh; // it has to be integer, because -1 means that it is not provided. + + double nominalvel_mpersecs; + + //double nominalangvel_radpersecs; + + double timetoturn45degsinplace_secs; + + double cellsize_m; + + int dXY[NAVXYTHETALAT_DXYWIDTH][2]; + + //array of actions, ActionsV[i][j] - jth action for sourcetheta = i + EnvNAVXYTHETALATAction_t** ActionsV; + //PredActionsV[i] - vector of pointers to the actions that result in a state with theta = i + std::vector* PredActionsV; + + int actionwidth; //number of motion primitives + std::vector mprimV; + + std::vector FootprintPolygon; +}; + +class EnvNAVXYTHETALAT_InitParms +{ +public: + unsigned int numThetas; + const unsigned char* mapdata; + double startx; + double starty; + double starttheta; + double goalx; + double goaly; + double goaltheta; + double goaltol_x; + double goaltol_y; + double goaltol_theta; +}; + +/** \brief 3D (x,y,theta) planning using lattice-based graph problem. For + * general structure see comments on parent class DiscreteSpaceInformation + * For info on lattice-based planning used here, you can check out the paper: + * Maxim Likhachev and Dave Ferguson, " Planning Long Dynamically-Feasible + * Maneuvers for Autonomous Vehicles", IJRR'09 + */ +class EnvironmentNAVXYTHETALATTICE : public DiscreteSpaceInformation +{ +public: + EnvironmentNAVXYTHETALATTICE(); + + /** + * \brief initialization of environment from file. See .cfg files for + * examples it also takes the perimeter of the robot with respect to some + * reference point centered at x=0,y=0 and orientation = 0 (along x axis). + * The perimeter is defined in meters as a sequence of vertices of a + * polygon defining the perimeter. If vector is of zero size, then robot + * is assumed to be point robot (you may want to inflate all obstacles by + * its actual radius) Motion primitives file defines the motion primitives + * available to the robot + */ + virtual bool InitializeEnv(const char* sEnvFile, const std::vector& perimeterptsV, + const char* sMotPrimFile); + + // ?? virtual bool InitializeEnv(const ENVNAVXYTHETAVELOLAT_InitParms & params); + + /** + * \brief see comments on the same function in the parent class + */ + virtual bool InitializeEnv(const char* sEnvFile); + + /** + * \brief way to set up various parameters. For a list of parameters, see + * the body of the function - it is pretty straightforward + */ + virtual bool SetEnvParameter(const char* parameter, int value); + + /** + * \brief returns the value of specific parameter - see function body for the list of parameters + */ + virtual int GetEnvParameter(const char* parameter); + + /** + * \brief see comments on the same function in the parent class + */ + virtual bool InitializeMDPCfg(MDPConfig *MDPCfg); + + /** + * \brief see comments on the same function in the parent class + */ + virtual int GetFromToHeuristic(int FromStateID, int ToStateID) = 0; + + /** + * \brief see comments on the same function in the parent class + */ + virtual int GetGoalHeuristic(int stateID) = 0; + + /** + * \brief see comments on the same function in the parent class + */ + virtual int GetStartHeuristic(int stateID) = 0; + + /** + * \brief see comments on the same function in the parent class + */ + virtual void SetAllActionsandAllOutcomes(CMDPSTATE* state) = 0; + + /** + * \brief see comments on the same function in the parent class + */ + virtual void SetAllPreds(CMDPSTATE* state); + + /** + * \brief see comments on the same function in the parent class + */ + virtual void GetSuccs(int SourceStateID, std::vector* SuccIDV, std::vector* CostV); + virtual void GetLazySuccs(int SourceStateID, std::vector* SuccIDV, std::vector* CostV, std::vector* isTrueCost); + virtual void GetSuccsWithUniqueIds(int SourceStateID, std::vector* SuccIDV, std::vector* CostV); + virtual void GetLazySuccsWithUniqueIds(int SourceStateID, std::vector* SuccIDV, std::vector* CostV, std::vector* isTrueCost); + + /** + * \brief see comments on the same function in the parent class + */ + virtual void GetPreds(int TargetStateID, std::vector* PredIDV, std::vector* CostV) = 0; + + /** + * \brief see comments on the same function in the parent class + */ + virtual void EnsureHeuristicsUpdated(bool bGoalHeuristics); + + /** + * \brief see comments on the same function in the parent class + */ + virtual void PrintEnv_Config(FILE* fOut); + + /** + * \brief set the block size for the 2D heuristic. A block size of 1 is the default and will result in + * a single cell in the 2D heuristic search corresponding to 1 cell from the source map. + * A block size of 2 will result in a single cell in the 2D heuristic search corresponding to + * a 2x2 set of blocks from the source map with a cost of the max of the 2x2 source cells. + */ + virtual void Set2DBlockSize(int BlockSize); + + /** + * @brief Set2DBucketSize Set the initial size of the CSlidingBuckets used for the fringe priority list + * @param BucketSize + */ + virtual void Set2DBucketSize(int BucketSize); + + virtual double DiscTheta2ContNew(int theta) const; + + virtual int ContTheta2DiscNew(double theta) const; + + virtual double DiscTheta2ContFromSet(int theta) const; + + virtual int ContTheta2DiscFromSet(double theta) const; + + virtual int normalizeDiscAngle(int theta) const; + + /** + * \brief initialize environment. Gridworld is defined as matrix A of size width by height. + * So, internally, it is accessed as A[x][y] with x ranging from 0 to width-1 and and y from 0 to height-1 + * Each element in A[x][y] is unsigned char. A[x][y] = 0 corresponds to + * fully traversable and cost is just Euclidean distance + * The cost of transition between two neighboring cells is + * EuclideanDistance*(max(A[sourcex][sourcey],A[targetx][targety])+1) + * f A[x][y] >= obsthresh, then in the above equation it is assumed to be infinite. + * The cost also incorporates the length of a motion primitive and its cost_multiplier (see getcost function) + * mapdata is a pointer to the values of A. If it is null, then A is + * initialized to all zeros. Mapping is: A[x][y] = mapdata[x+y*width] + * start/goal are given by startx, starty, starttheta, goalx,goaly, goaltheta in meters/radians. + * If they are not known yet, just set them to 0. Later setgoal/setstart can be executed + * finally obsthresh defined obstacle threshold, as mentioned above + * goaltolerances are currently ignored + * for explanation of perimeter, see comments for InitializeEnv function that reads all from file + * cellsize is discretization in meters + * nominalvel_mpersecs is assumed velocity of vehicle while moving forward in m/sec + * timetoturn45degsinplace_secs is rotational velocity in secs/45 degrees turn + */ + virtual bool InitializeEnv(int width, int height, + /** if mapdata is NULL the grid is initialized to all freespace */ + const unsigned char* mapdata, + double startx, double starty, double starttheta, + double goalx, double goaly, double goaltheta, + double goaltol_x, double goaltol_y, double goaltol_theta, + const std::vector& perimeterptsV, double cellsize_m, + double nominalvel_mpersecs, double timetoturn45degsinplace_secs, + unsigned char obsthresh, const char* sMotPrimFile); + + /** + * \brief Same as the above InitializeEnv except that only the parameters + * that area really needed are required. The additional (optional) + * parameters may be given in the params object (including the ability to + * specify the number of thetas) + */ + virtual bool InitializeEnv(int width, int height, const std::vector & perimeterptsV, double cellsize_m, + double nominalvel_mpersecs, double timetoturn45degsinplace_secs, + unsigned char obsthresh, const char* sMotPrimFile, EnvNAVXYTHETALAT_InitParms params); + + /** + * \brief update the traversability of a cell + */ + virtual bool UpdateCost(int x, int y, unsigned char newcost); + + /** + * \brief re-setting the whole 2D map + * transform from linear array mapdata to the 2D matrix used internally: Grid2D[x][y] = mapdata[x+y*width] + */ + virtual bool SetMap(const unsigned char* mapdata); + + /** + * \brief this function fill in Predecessor/Successor states of edges whose costs changed + * It takes in an array of cells whose traversability changed, and + * returns (in vector preds_of_changededgesIDV) the IDs of all + * states that have outgoing edges that go through the changed + * cells + */ + virtual void GetPredsofChangedEdges(std::vector const * changedcellsV, + std::vector *preds_of_changededgesIDV) = 0; + /** + * \brief same as GetPredsofChangedEdges, but returns successor states. + * Both functions need to be present for incremental search + */ + virtual void GetSuccsofChangedEdges(std::vector const * changedcellsV, + std::vector *succs_of_changededgesIDV) = 0; + + /** + * returns true if cell is untraversable + */ + virtual bool IsObstacle(int x, int y); + + /** + * \brief returns false if robot intersects obstacles or lies outside of + * the map. Note this is pretty expensive operation since it computes the + * footprint of the robot based on its x,y,theta + */ + virtual bool IsValidConfiguration(int X, int Y, int Theta); + + /** + * \brief returns environment parameters. Useful for creating a copy environment + */ + virtual void GetEnvParms(int *size_x, int *size_y, double* startx, double* starty, double* starttheta, + double* goalx, double* goaly, double* goaltheta, double* cellsize_m, + double* nominalvel_mpersecs, double* timetoturn45degsinplace_secs, + unsigned char* obsthresh, std::vector* motionprimitiveV); + + /** + * \brief returns environment parameters. Useful for creating a copy environment + */ + virtual void GetEnvParms(int *size_x, int *size_y, int* num_thetas, double* startx, double* starty, + double* starttheta, double* goalx, double* goaly, double* goaltheta, double* cellsize_m, + double* nominalvel_mpersecs, double* timetoturn45degsinplace_secs, + unsigned char* obsthresh, std::vector* motionprimitiveV); + + /** + * \brief get internal configuration data structure + */ + virtual const EnvNAVXYTHETALATConfig_t* GetEnvNavConfig(); + + virtual ~EnvironmentNAVXYTHETALATTICE(); + + /** + * \brief prints time statistics + */ + virtual void PrintTimeStat(FILE* fOut); + + /** + * \brief returns the cost corresponding to the cell + */ + virtual unsigned char GetMapCost(int x, int y); + + /** + * \brief returns true if cell is within map + */ + virtual bool IsWithinMapCell(int X, int Y); + + /** + * \brief Transform a pose into discretized form. The angle 'pth' is + * considered to be valid if it lies between -2pi and 2pi (some + * people will prefer 0<=pth<2pi, others -pi affectedsuccstatesV; //arrays of states whose outgoing actions cross cell 0,0 + std::vector affectedpredstatesV; //arrays of states whose incoming actions cross cell 0,0 + int iteration; + int blocksize; // 2D block size + int bucketsize; // 2D bucket size + + bool bUseNonUniformAngles; + + //2D search for heuristic computations + bool bNeedtoRecomputeStartHeuristics; //set whenever grid2Dsearchfromstart needs to be re-executed + bool bNeedtoRecomputeGoalHeuristics; //set whenever grid2Dsearchfromgoal needs to be re-executed + SBPL2DGridSearch* grid2Dsearchfromstart; //computes h-values that estimate distances from start x,y to all cells + SBPL2DGridSearch* grid2Dsearchfromgoal; //computes h-values that estimate distances to goal x,y from all cells + + virtual void ReadConfiguration(FILE* fCfg); + + virtual void InitializeEnvConfig(std::vector* motionprimitiveV); + + virtual bool CheckQuant(FILE* fOut); + + virtual void SetConfiguration(int width, int height, + /** if mapdata is NULL the grid is initialized to all freespace */ + const unsigned char* mapdata, + int startx, int starty, int starttheta, + int goalx, int goaly, int goaltheta, + double cellsize_m, double nominalvel_mpersecs, double timetoturn45degsinplace_secs, + const std::vector & robot_perimeterV); + + virtual bool InitGeneral(std::vector* motionprimitiveV); + virtual void PrecomputeActionswithBaseMotionPrimitive(std::vector* motionprimitiveV); + virtual void PrecomputeActionswithCompleteMotionPrimitive(std::vector* motionprimitiveV); + virtual void DeprecatedPrecomputeActions(); + + virtual void InitializeEnvironment() = 0; + + virtual void ComputeHeuristicValues(); + + virtual bool IsValidCell(int X, int Y); + + virtual void CalculateFootprintForPose(sbpl_xy_theta_pt_t pose, std::vector* footprint); + virtual void CalculateFootprintForPose(sbpl_xy_theta_pt_t pose, std::vector* footprint, + const std::vector& FootprintPolygon); + virtual void RemoveSourceFootprint(sbpl_xy_theta_pt_t sourcepose, std::vector* footprint); + virtual void RemoveSourceFootprint(sbpl_xy_theta_pt_t sourcepose, std::vector* footprint, + const std::vector& FootprintPolygon); + + virtual void GetSuccs(int SourceStateID, std::vector* SuccIDV, std::vector* CostV, + std::vector* actionindV = NULL) = 0; + virtual void GetLazySuccs(int SourceStateID, std::vector* SuccIDV, std::vector* CostV, std::vector* isTrueCost, std::vector* actionindV = NULL) = 0; + virtual void GetSuccsWithUniqueIds(int SourceStateID, std::vector* SuccIDV, std::vector* CostV, std::vector* actionindV = NULL) = 0; + virtual void GetLazySuccsWithUniqueIds(int SourceStateID, std::vector* SuccIDV, std::vector* CostV, std::vector* isTrueCost, std::vector* actionindV = NULL) = 0; + virtual int GetTrueCost(int parentID, int childID) = 0; + virtual bool isGoal(int id) = 0; + + virtual double EuclideanDistance_m(int X1, int Y1, int X2, int Y2); + + virtual void ComputeReplanningData(); + virtual void ComputeReplanningDataforAction(EnvNAVXYTHETALATAction_t* action); + + virtual bool ReadMotionPrimitives(FILE* fMotPrims); + virtual bool ReadinMotionPrimitive(SBPL_xytheta_mprimitive* pMotPrim, FILE* fIn); + virtual bool ReadinCell(sbpl_xy_theta_cell_t* cell, FILE* fIn); + virtual bool ReadinPose(sbpl_xy_theta_pt_t* pose, FILE* fIn); + + virtual void PrintHeuristicValues(); +}; + +class EnvironmentNAVXYTHETALAT : public EnvironmentNAVXYTHETALATTICE +{ +public: + EnvironmentNAVXYTHETALAT() + { + HashTableSize = 0; + Coord2StateIDHashTable = NULL; + Coord2StateIDHashTable_lookup = NULL; + } + + ~EnvironmentNAVXYTHETALAT(); + + /** + * \brief sets start in meters/radians + */ + virtual int SetStart(double x, double y, double theta); + + /** + * \brief sets goal in meters/radians + */ + virtual int SetGoal(double x, double y, double theta); + + /** + * \brief sets goal tolerance. (Note goal tolerance is ignored currently) + */ + virtual void SetGoalTolerance(double tol_x, double tol_y, double tol_theta) { /**< not used yet */ } + + /** + * \brief returns state coordinates of state with ID=stateID + */ + virtual void GetCoordFromState(int stateID, int& x, int& y, int& theta) const; + + /** + * \brief returns stateID for a state with coords x,y,theta + */ + virtual int GetStateFromCoord(int x, int y, int theta); + + /** + * \brief returns the actions / motion primitives of the passed path. + */ + virtual void GetActionsFromStateIDPath(std::vector* stateIDPath, + std::vector* action_list); + + /** \brief converts a path given by stateIDs into a sequence of + * coordinates. Note that since motion primitives are short actions + * represented as a sequence of points, + * the path returned by this function contains much more points than the + * number of points in the input path. The returned coordinates are in + * meters,meters,radians + */ + virtual void ConvertStateIDPathintoXYThetaPath(std::vector* stateIDPath, + std::vector* xythetaPath); + + /** + * \brief prints state info (coordinates) into file + */ + virtual void PrintState(int stateID, bool bVerbose, FILE* fOut = NULL); + + /** + * \brief returns all predecessors states and corresponding costs of actions + */ + virtual void GetPreds(int TargetStateID, std::vector* PredIDV, std::vector* CostV); + virtual void GetLazyPreds(int TargetStateID, std::vector* PredIDV, std::vector* CostV, std::vector* isTrueCost); + virtual void GetPredsWithUniqueIds(int TargetStateID, std::vector* PredIDV, std::vector* CostV); + virtual void GetLazyPredsWithUniqueIds(int TargetStateID, std::vector* PredIDV, std::vector* CostV, std::vector* isTrueCost); + + /** + * \brief returns all successors states, costs of corresponding actions + * and pointers to corresponding actions, each of which is a motion + * primitive + * if actionindV is NULL, then pointers to actions are not returned + */ + virtual void GetSuccs(int SourceStateID, std::vector* SuccIDV, std::vector* CostV, + std::vector* actionindV = NULL); + + virtual void GetLazySuccs(int SourceStateID, std::vector* SuccIDV, std::vector* CostV, std::vector* isTrueCost, std::vector* actionindV = NULL); + virtual void GetSuccsWithUniqueIds(int SourceStateID, std::vector* SuccIDV, std::vector* CostV, std::vector* actionindV = NULL); + virtual void GetLazySuccsWithUniqueIds(int SourceStateID, std::vector* SuccIDV, std::vector* CostV, std::vector* isTrueCost, std::vector* actionindV = NULL); + virtual int GetTrueCost(int parentID, int childID); + virtual bool isGoal(int id); + + + /** \brief this function fill in Predecessor/Successor states of edges + * whose costs changed + * It takes in an array of cells whose traversability changed, and returns + * (in vector preds_of_changededgesIDV) the IDs of all states that have + * outgoing edges that go through the changed cells + */ + virtual void GetPredsofChangedEdges(std::vector const * changedcellsV, + std::vector *preds_of_changededgesIDV); + + /** + * \brief same as GetPredsofChangedEdges, but returns successor states. + * Both functions need to be present for incremental search + */ + virtual void GetSuccsofChangedEdges(std::vector const * changedcellsV, + std::vector *succs_of_changededgesIDV); + + /** + * \brief see comments on the same function in the parent class + */ + virtual void SetAllActionsandAllOutcomes(CMDPSTATE* state); + + /** + * \brief see comments on the same function in the parent class + */ + virtual int GetFromToHeuristic(int FromStateID, int ToStateID); + + /** + * \brief see comments on the same function in the parent class + */ + virtual int GetGoalHeuristic(int stateID); + + /** + * \brief see comments on the same function in the parent class + */ + virtual int GetStartHeuristic(int stateID); + + /** + * \brief see comments on the same function in the parent class + */ + virtual int SizeofCreatedEnv(); + + /** + * \brief see comments on the same function in the parent class + */ + virtual void PrintVars() { } + + const EnvNAVXYTHETALATHashEntry_t* GetStateEntry(int state_id) const; + +protected: + //hash table of size x_size*y_size. Maps from coords to stateId + int HashTableSize; + std::vector* Coord2StateIDHashTable; + //vector that maps from stateID to coords + std::vector StateID2CoordTable; + + EnvNAVXYTHETALATHashEntry_t** Coord2StateIDHashTable_lookup; + + virtual unsigned int GETHASHBIN(unsigned int X, unsigned int Y, unsigned int Theta); + + virtual EnvNAVXYTHETALATHashEntry_t* GetHashEntry_hash(int X, int Y, int Theta); + virtual EnvNAVXYTHETALATHashEntry_t* CreateNewHashEntry_hash(int X, int Y, int Theta); + virtual EnvNAVXYTHETALATHashEntry_t* GetHashEntry_lookup(int X, int Y, int Theta); + virtual EnvNAVXYTHETALATHashEntry_t* CreateNewHashEntry_lookup(int X, int Y, int Theta); + + //pointers to functions + EnvNAVXYTHETALATHashEntry_t* (EnvironmentNAVXYTHETALAT::*GetHashEntry)(int X, int Y, int Theta); + EnvNAVXYTHETALATHashEntry_t* (EnvironmentNAVXYTHETALAT::*CreateNewHashEntry)(int X, int Y, int Theta); + + virtual void InitializeEnvironment(); + + virtual void PrintHashTableHist(FILE* fOut); +}; + +#endif diff --git a/navigations/sbpl/src/include/sbpl/discrete_space_information/environment_navxythetamlevlat.h b/navigations/sbpl/src/include/sbpl/discrete_space_information/environment_navxythetamlevlat.h new file mode 100755 index 0000000..a06c08a --- /dev/null +++ b/navigations/sbpl/src/include/sbpl/discrete_space_information/environment_navxythetamlevlat.h @@ -0,0 +1,195 @@ +/* + * Copyright (c) 2008, Maxim Likhachev + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Carnegie Mellon University nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef __ENVIRONMENT_NAVXYTHETAMLEVLAT_H_ +#define __ENVIRONMENT_NAVXYTHETAMLEVLAT_H_ + +#include +#include +#include +#include + +// these structures contain footprints for the additional levels +// each of these structures corresponds to one of the EnvNAVXYTHETALATAction_t structures +typedef struct +{ + char starttheta; // should be equal to the corresponding EnvNAVXYTHETALATAction_t structure + char dX; // should be equal to the corresponding EnvNAVXYTHETALATAction_t structure + char dY; // should be equal to the corresponding EnvNAVXYTHETALATAction_t structure + char endtheta; // should be equal to the corresponding EnvNAVXYTHETALATAction_t structure + std::vector* intersectingcellsV; // one footprint per additional level +} EnvNAVXYTHETAMLEVLATAddInfoAction_t; + +/** + * \brief This is x,y,theta lattice planning but with multiple levels in z. + * In other words, it is for doing collision checking in 3D (x,y,z). The z + * level is split into numofzlevs levels. If numofzlevs = 1, then it + * defaults to the original x,y,theta lattice planning defined in + * EnvironmentNAVXYTHETALAT. Otherwise, it uses numofzlevs footprints of the + * robot and corresponding costmaps. It assumes that they correspond to each + * other and are projections of the robot and corresponding z regions of the + * 3D map. + */ +class EnvironmentNAVXYTHETAMLEVLAT : public EnvironmentNAVXYTHETALAT +{ +public: + /** + * \brief initialization of additional levels. 0 is the original one. All additional ones will start with index 1 + * For each level, it also takes cost thresholds for cells lying + * within inner radius of the robot (inscribed) and outside of the + * inner circle but within outer radius (possibly_circumscribed). + * See environment_navxythetalat.h for the explanation of these + * parameters. + */ + bool InitializeAdditionalLevels(int numofadditionalzlevs, const std::vector* perimeterptsV, + unsigned char* cost_inscribed_thresh, + unsigned char* cost_possibly_circumscribed_thresh); + + /** + * \brief setting 2D map for the additional level at levind index + * (indices are zero-based and are only used to index the additional levels) + * you can not use this function to set 2D map for the base level + * transform from linear array mapdata to the 2D matrix used internally: Grid2D[x][y] = mapdata[x+y*width] + */ + bool Set2DMapforAddLev(const unsigned char* mapdata, int levind); + + /** + * \brief set 2D map for the additional level levind + * The version of Set2DMapforAddLev that takes newmap as 2D array instead of one linear array + */ + bool Set2DMapforAddLev(const unsigned char** NewGrid2D, int levind); + + /** + * \brief update the traversability of a cell in level zlev + */ + bool UpdateCostinAddLev(int x, int y, unsigned char newcost, int zlev); + + /** + * \brief incremental planning not supported + */ + virtual void GetPredsofChangedEdges(std::vector const * changedcellsV, + std::vector *preds_of_changededgesIDV) + { + throw SBPL_Exception("ERROR: GetPredsofChangedEdges function not supported"); + } + + /** + * \brief incremental planning not supported + */ + virtual void GetSuccsofChangedEdges(std::vector const * changedcellsV, + std::vector *succs_of_changededgesIDV) + { + throw SBPL_Exception("ERROR: GetSuccsofChangedEdges function not supported"); + } + + /** + * returns true if cell is traversable and within map limits - it checks against all levels including the base one + */ + bool IsValidCell(int X, int Y); + + /** + * returns true if cell is traversable and within map limits for a particular level + */ + bool IsValidCell(int X, int Y, int levind); + + /** + * returns true if cell is untraversable at any level + */ + bool IsObstacle(int x, int y); + + /** + * returns true if cell is untraversable at level levelnum. + */ + bool IsObstacle(int x, int y, int levind); + + /** + * \brief returns false if robot intersects obstacles or lies outside of the map. + * Note this is pretty expensive operation since it computes the footprint + * of the robot based on its x,y,theta + */ + bool IsValidConfiguration(int X, int Y, int Theta); + + /** + * \brief returns the maximum over all levels of the cost corresponding to the cell + */ + unsigned char GetMapCost(int X, int Y); + + /** + * \brief returns the cost corresponding to the cell at level levind + */ + unsigned char GetMapCost(int X, int Y, int levind); + + EnvironmentNAVXYTHETAMLEVLAT(); + ~EnvironmentNAVXYTHETAMLEVLAT(); + +protected: + /** + * \brief number of additional levels. If it is 0, then there is only one level - base level + */ + int numofadditionalzlevs; + + /** + * \brief footprints for the additional levels + */ + std::vector* AddLevelFootprintPolygonV; + + /** + * \brief array of additional info in actions, + * AdditionalInfoinActionsV[i][j] - jth action for sourcetheta = i + * basically, each Additional info structure will contain numofadditionalzlevs additional intersecting + * cells vector intersectingcellsV + */ + EnvNAVXYTHETAMLEVLATAddInfoAction_t** AdditionalInfoinActionsV; + + /** + * \brief 2D maps for additional levels. + * AddLevelGrid2D[lind][x][y] refers to cell on the additional level lind + */ + unsigned char*** AddLevelGrid2D; + + /** + * \brief inscribed cost thresholds for additional levels + * see environment_navxythetalat.h file for the explanation of this threshold + */ + unsigned char* AddLevel_cost_inscribed_thresh; + /** + * \brief possibly_circumscribed cost thresholds for additional levels + * see environment_navxythetalat.h file for the explanation of this threshold + */ + unsigned char* AddLevel_cost_possibly_circumscribed_thresh; + + virtual int GetActionCost(int SourceX, int SourceY, int SourceTheta, EnvNAVXYTHETALATAction_t* action); + + virtual int GetActionCostacrossAddLevels(int SourceX, int SourceY, int SourceTheta, + EnvNAVXYTHETALATAction_t* action); + +}; + +#endif + diff --git a/navigations/sbpl/src/include/sbpl/discrete_space_information/environment_precomputed_adjacency_list.h b/navigations/sbpl/src/include/sbpl/discrete_space_information/environment_precomputed_adjacency_list.h new file mode 100755 index 0000000..4c40859 --- /dev/null +++ b/navigations/sbpl/src/include/sbpl/discrete_space_information/environment_precomputed_adjacency_list.h @@ -0,0 +1,404 @@ +/* + * Copyright (c) 2008, Maxim Likhachev + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Carnegie Mellon University nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef __PRECOMPUTED_ADJACENCY_LIST_H_ +#define __PRECOMPUTED_ADJACENCY_LIST_H_ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +struct Adjacency +{ + int neighbor; + int cost; +}; +typedef std::list Adjacencies; +typedef Adjacencies::iterator AdjListIterator; + +/** + * \brief SBPL Environment represented as an adjacency list graph. + * + * \tparam Coords Coords must be a type that 1) has operator<< and + * heuristicDistanceTo (const Coords&) const defined on it 2) can be used as a + * key of an STL map + * + * Nodes of the graph are labelled with Coords. Edges have integer costs + * attached to them. ARA* planning is done on this graph, and the function + * heuristicDistanceTo is used as the admissible heuristic. + */ +template +class AdjacencyListSBPLEnv : public DiscreteSpaceInformation +{ +public: + AdjacencyListSBPLEnv(); + void writeToStream(std::ostream& str = std::cout); + + /** + * \brief Add point to roadmap. Does not check for duplicates. + */ + void addPoint(const Coords& c); + + /** + * \brief Does the roadmap contain this point? + */ + bool hasPoint(const Coords& c); + + /** + * \brief Remove the last N points added using addPoint (and all their incident edges) in O(N) time + */ + void removeLastPoints(unsigned int n = 1); + + /** + * \post An undirected edge exists between c1 and c2 with the given cost + * cost, if not provided, defaults to the heuristic cost between c1 and c2 + */ + void setCost(const Coords& c1, const Coords& c2, int cost); + void setCost(const Coords& c1, const Coords& c2); + + void setStartState(const Coords& c); + void setGoalState(const Coords& c); + + /** + * \brief Use ARA* to find an optimal path between the currently set start and goal states + * \return Vector of states on the path + * \post solution_cost will hold the cost of the returned solution + */ + std::vector findOptimalPath(int* solution_cost); + + // Inherited DiscreteSpaceInformation ops + bool InitializeEnv(const char* sEnvFile); + bool InitializeMDPCfg(MDPConfig *MDPCfg); + int GetFromToHeuristic(int FromStateID, int ToStateID); + int GetGoalHeuristic(int stateID); + int GetStartHeuristic(int stateID); + void SetAllActionsandAllOutcomes(CMDPSTATE* state); + void SetAllPreds(CMDPSTATE* state); + void GetSuccs(int SourceStateID, std::vector* SuccIDV, std::vector* CostV); + void GetPreds(int TargetStateID, std::vector* PredIDV, std::vector* CostV); + int SizeofCreatedEnv(); + void PrintState(int stateID, bool bVerbose, FILE* fOut = NULL); + void PrintEnv_Config(FILE* fOut); + +private: + void resetStateId2IndexMapping(void); + + // Members + std::vector points_; + std::map pointIds_; + std::vector adjacency_vector_; + int startStateId_; + int goalStateId_; +}; + +template +AdjacencyListSBPLEnv::AdjacencyListSBPLEnv() : + startStateId_(-1), goalStateId_(-1) +{ +} + +template +void AdjacencyListSBPLEnv::writeToStream(std::ostream& str) +{ + int numStates = points_.size(); + str << "Adjacency list SBPL Env " << endl; + for (unsigned int i = 0; i < points_.size(); i++) { + str << i << ". " << points_[i] << ". Neighbors: "; + for (AdjListIterator iter = adjacency_vector_[i].begin(); iter != adjacency_vector_[i].end(); iter++) { + if (iter->neighbor < numStates) { + str << "[" << points_[iter->neighbor] << " " << iter->cost << "] "; + } + else { + str << "[To-Be-Deleted Edge] "; + } + } + str << endl; + } +} + +template +void AdjacencyListSBPLEnv::addPoint(const Coords& c) +{ + pointIds_[c] = points_.size(); + Adjacencies a; + points_.push_back(c); + adjacency_vector_.push_back(a); + + int* entry = new int[NUMOFINDICES_STATEID2IND]; + for (unsigned int i = 0; i < NUMOFINDICES_STATEID2IND; i++) { + entry[i] = -1; + } + StateID2IndexMapping.push_back(entry); +} + +template +bool AdjacencyListSBPLEnv::hasPoint(const Coords& c) +{ + return !(pointIds_.find(c) == pointIds_.end()); +} + +template +void AdjacencyListSBPLEnv::removeLastPoints(unsigned int n) +{ + assert(n <= points_.size()); + for (unsigned int i = 0; i < n; i++) { + int num_points = points_.size(); + Adjacencies& a = adjacency_vector_.back(); + + // Iterate over neighbors of this currently-being-deleted point + for (Adjacencies::iterator adj_iter = a.begin(); adj_iter != a.end(); adj_iter++) { + assert(adj_iter->neighbor < num_points); + Adjacencies& neighbor_adjacency_list = adjacency_vector_[adj_iter->neighbor]; + + // Iterate over neighbors of the neighbor + for (Adjacencies::iterator neighbor_adj_iter = neighbor_adjacency_list.begin(); neighbor_adj_iter + != neighbor_adjacency_list.end(); neighbor_adj_iter++) { + + // When we find the entry for the current point, remove it and exit inner loop + if (neighbor_adj_iter->neighbor == num_points - 1) { + neighbor_adjacency_list.erase(neighbor_adj_iter); + break; + } + } + } + adjacency_vector_.pop_back(); + pointIds_.erase(points_.back()); + points_.pop_back(); + } +} + +template +void AdjacencyListSBPLEnv::setCost(const Coords& c1, const Coords& c2) +{ + setCost(c1, c2, c1.heuristicDistanceTo(c2)); +} + +template +void AdjacencyListSBPLEnv::setCost(const Coords& c1, const Coords& c2, int cost) +{ + // Figure out indices of the given points + typename std::map::iterator i1 = pointIds_.find(c1); + typename std::map::iterator i2 = pointIds_.find(c2); + int index1 = i1->second; + int index2 = i2->second; + + // Loop over which direction edge to add + for (unsigned int j = 0; j < 2; j++) { + int ind1, ind2; + if (j == 0) { + ind1 = index1; + ind2 = index2; + } + else { + ind1 = index2; + ind2 = index1; + } + + // Now set cost of edge from ind1 to ind2 + Adjacencies& adj = adjacency_vector_[ind1]; + + AdjListIterator i, last = adj.end(); + for (i = adj.begin(); (i != last) && (i->neighbor != ind2); i++) + ; + + // If edge does not exist add it, else just set the cost of the existing edge + if (i == last) { + Adjacency a; + a.neighbor = ind2; + a.cost = cost; + adj.insert(i, a); + } + else { + i->cost = cost; + } + } +} + +template +void AdjacencyListSBPLEnv::setStartState(const Coords& c) +{ + typename std::map::iterator i = pointIds_.find(c); + assert(i != pointIds_.end()); + startStateId_ = i->second; +} + +template +void AdjacencyListSBPLEnv::setGoalState(const Coords& c) +{ + typename std::map::iterator i = pointIds_.find(c); + assert(i != pointIds_.end()); + goalStateId_ = i->second; +} + +template +bool AdjacencyListSBPLEnv::InitializeMDPCfg(MDPConfig *MDPCfg) +{ + MDPCfg->goalstateid = goalStateId_; + MDPCfg->startstateid = startStateId_; + return true; +} + +template +int AdjacencyListSBPLEnv::GetFromToHeuristic(int FromStateID, int ToStateID) +{ + return points_[FromStateID].heuristicDistanceTo(points_[ToStateID]); +} + +template +int AdjacencyListSBPLEnv::GetGoalHeuristic(int stateID) +{ + return GetFromToHeuristic(stateID, goalStateId_); +} + +template +int AdjacencyListSBPLEnv::GetStartHeuristic(int stateID) +{ + return GetFromToHeuristic(startStateId_, stateID); +} + +template +void AdjacencyListSBPLEnv::PrintState(int stateID, bool bVerbose, FILE* fOut) +{ + // Note we're ignoring the fOut argument + std::cout << points_[stateID] << endl; +} + +template +void AdjacencyListSBPLEnv::PrintEnv_Config(FILE* fOut) +{ + // Note we're ignoring the fOut argument + std::cout << "Adjacency list env" << endl; +} + +template +int AdjacencyListSBPLEnv::SizeofCreatedEnv() +{ + return points_.size(); +} + +template +bool AdjacencyListSBPLEnv::InitializeEnv(const char* sEnvFile) +{ + // Nothing to do in initialization + return true; +} + +template +void AdjacencyListSBPLEnv::SetAllActionsandAllOutcomes(CMDPSTATE* state) +{ + // goal state is absorbing + if (state->StateID == goalStateId_) { + return; + } + + Adjacencies& v = adjacency_vector_[state->StateID]; + int actionIndex = 0; + + for (AdjListIterator i = v.begin(); i != v.end(); i++) { + CMDPACTION* action = state->AddAction(actionIndex); + action->AddOutcome(i->neighbor, i->cost, 1.0); + } +} + +template +void AdjacencyListSBPLEnv::SetAllPreds(CMDPSTATE* state) +{ + throw SBPL_Exception("Error: SetAllPreds not implemented for adjacency list"); +} + +template +void AdjacencyListSBPLEnv::GetSuccs(int SourceStateID, std::vector* SuccIDV, std::vector* CostV) +{ + SuccIDV->clear(); + CostV->clear(); + + if (SourceStateID == goalStateId_) { + return; + } + + Adjacencies& v = adjacency_vector_[SourceStateID]; + for (AdjListIterator i = v.begin(); i != v.end(); i++) { + SuccIDV->push_back(i->neighbor); + CostV->push_back(i->cost); + } +} + +template +void AdjacencyListSBPLEnv::GetPreds(int TargetStateID, std::vector* PredIDV, std::vector* CostV) +{ + throw SBPL_Exception("Error: GetPreds not currently implemented for adjacency list"); +} + +template +std::vector AdjacencyListSBPLEnv::findOptimalPath(int* solution_cost) +{ + // Initialize ARA planner + ARAPlanner p(this, true); + p.set_start(startStateId_); + p.set_goal(goalStateId_); + p.set_initialsolution_eps(1.0); + std::vector solution; + p.replan(1.0, &solution, solution_cost); + + std::vector solutionPoints; + for (unsigned int i = 0; i < solution.size(); i++) { + solutionPoints.push_back(points_[solution[i]]); + } + + resetStateId2IndexMapping(); + + return solutionPoints; +} + +// There's some side effect where you have to reset this every time you call the ARA planner +template +void AdjacencyListSBPLEnv::resetStateId2IndexMapping(void) +{ + for (unsigned int i = 0; i < StateID2IndexMapping.size(); i++) { + for (unsigned int j = 0; j < NUMOFINDICES_STATEID2IND; j++) { + StateID2IndexMapping[i][j] = -1; + } + } +} + +#endif + +// Local variables: +// mode:c++ +// End: diff --git a/navigations/sbpl/src/include/sbpl/discrete_space_information/environment_robarm.h b/navigations/sbpl/src/include/sbpl/discrete_space_information/environment_robarm.h new file mode 100755 index 0000000..ba442c1 --- /dev/null +++ b/navigations/sbpl/src/include/sbpl/discrete_space_information/environment_robarm.h @@ -0,0 +1,232 @@ +/* + * Copyright (c) 2008, Maxim Likhachev + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Carnegie Mellon University nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef __ENVIRONMENT_ROBARM_H_ +#define __ENVIRONMENT_ROBARM_H_ + +#include +#include + +#define NUMOFLINKS 6 +//for R* max. distance in coord to a sample point. It should be exactly this, +//for one of the coordinates and this or smaller for the rest +#define ROBARM_LONGACTIONDIST_CELLS 30 +//# of random successors at distance defined above, used by R* search +#define ROBARM_NUMOFRANDSUCCSATDIST 10 +//if cleared then the intersection of the whole arm against obstacles +//and bounds is checked +#define ENDEFF_CHECK_ONLY 0 +#define UNIFORM_COST 1 //all the actions have the same costs when set +#define INVALID_NUMBER 999 + +class CMDPSTATE; +class MDPConfig; + +typedef struct +{ + short unsigned int x; + short unsigned int y; + bool bIsObstacle; +} CELLV; + +//state structure +typedef struct STATE2D_t +{ + unsigned int g; + short unsigned int iterationclosed; + short unsigned int x; + short unsigned int y; +} State2D; + +typedef struct ENV_ROBARM_CONFIG +{ + double EnvWidth_m; + double EnvHeight_m; + int EnvWidth_c; + int EnvHeight_c; + int BaseX_c; + short unsigned int EndEffGoalX_c; + short unsigned int EndEffGoalY_c; + double LinkLength_m[NUMOFLINKS]; + double LinkStartAngles_d[NUMOFLINKS]; + double LinkGoalAngles_d[NUMOFLINKS]; + char** Grid2D; + double GridCellWidth; + + double angledelta[NUMOFLINKS]; + int anglevals[NUMOFLINKS]; +} EnvROBARMConfig_t; + +typedef struct ENVROBARMHASHENTRY +{ + int stateID; + //state coordinates + short unsigned int coord[NUMOFLINKS]; + short unsigned int endeffx; + short unsigned int endeffy; +} EnvROBARMHashEntry_t; + +typedef struct +{ + EnvROBARMHashEntry_t* goalHashEntry; + EnvROBARMHashEntry_t* startHashEntry; + + //Maps from coords to stateId + int HashTableSize; + std::vector* Coord2StateIDHashTable; + + //vector that maps from stateID to coords + std::vector StateID2CoordTable; + + //any additional variables + int** Heur; //h[fromx][fromy][tox][toy] = Heur[to][from], where to= tox+toy*width_c, from = fromx+fromy*width_c +} EnvironmentROBARM_t; + +/** + * \brief planar kinematic robot arm of variable number of degrees of freedom + */ +class EnvironmentROBARM : public DiscreteSpaceInformation +{ +public: + /** + * \brief initialize environment from a file (see .cfg files in robotarm directory for example) + */ + virtual bool InitializeEnv(const char* sEnvFile); + + /** + * \brief initialize MDP config with IDs of start/goal + */ + virtual bool InitializeMDPCfg(MDPConfig *MDPCfg); + + /** + * \brief see comments on the same function in the parent class + */ + virtual int GetFromToHeuristic(int FromStateID, int ToStateID); + + /** + * \brief see comments on the same function in the parent class + */ + virtual int GetGoalHeuristic(int stateID); + + /** + * \brief see comments on the same function in the parent class + */ + virtual int GetStartHeuristic(int stateID); + + /** + * \brief see comments on the same function in the parent class + */ + virtual void SetAllActionsandAllOutcomes(CMDPSTATE* state); + + /** + * \brief see comments on the same function in the parent class + */ + virtual void SetAllPreds(CMDPSTATE* state); + + /** + * \brief see comments on the same function in the parent class + */ + virtual void GetSuccs(int SourceStateID, std::vector* SuccIDV, std::vector* CostV); + + /** + * \brief see comments on the same function in the parent class + */ + virtual void GetPreds(int TargetStateID, std::vector* PredIDV, std::vector* CostV); + + /** + * \brief see comments on the same function in the parent class + */ + virtual int SizeofCreatedEnv(); + + /** + * \brief see comments on the same function in the parent class + */ + virtual void PrintState(int stateID, bool bVerbose, FILE* fOut = NULL); + + /** + * \brief see comments on the same function in the parent class + */ + virtual void PrintEnv_Config(FILE* fOut); + + ~EnvironmentROBARM() { } + +protected: + //member data + EnvROBARMConfig_t EnvROBARMCfg; + EnvironmentROBARM_t EnvROBARM; + + virtual void ComputeContAngles(short unsigned int coord[NUMOFLINKS], double angle[NUMOFLINKS]); + virtual void ComputeCoord(double angle[NUMOFLINKS], short unsigned int coord[NUMOFLINKS]); + virtual int ComputeEndEffectorPos(double angles[NUMOFLINKS], short unsigned int* pX, short unsigned int* pY); + virtual int IsValidCoord(short unsigned int coord[NUMOFLINKS], char** Grid2D = NULL, + std::vector* pTestedCells = NULL); + virtual int distanceincoord(unsigned short* statecoord1, unsigned short* statecoord2); + virtual void ReInitializeState2D(State2D* state); + virtual void InitializeState2D(State2D* state, short unsigned int x, short unsigned int y); + virtual void Search2DwithQueue(State2D** statespace, int* HeurGrid, int searchstartx, int searchstarty); + virtual void Create2DStateSpace(State2D*** statespace2D); + virtual void Delete2DStateSpace(State2D*** statespace2D); + virtual void printangles(FILE* fOut, short unsigned int* coord, bool bGoal, bool bVerbose, bool bLocal); + virtual void DiscretizeAngles(); + virtual void Cell2ContXY(int x, int y, double *pX, double *pY); + virtual void ContXY2Cell(double x, double y, short unsigned int* pX, short unsigned int *pY); + virtual int IsValidLineSegment(double x0, double y0, double x1, double y1, char **Grid2D, + std::vector* pTestedCells); + virtual void GetRandomSuccsatDistance(int SourceStateID, std::vector* SuccIDV, std::vector* CLowV); + virtual unsigned int GetHeurBasedonCoord(short unsigned int coord[NUMOFLINKS]); + virtual void PrintHeader(FILE* fOut); + virtual int cost(short unsigned int state1coord[], short unsigned int state2coord[]); + + virtual void ReadConfiguration(FILE* fCfg); + + virtual void InitializeEnvConfig(); + + virtual unsigned int GETHASHBIN(short unsigned int* coord, int numofcoord); + + virtual void PrintHashTableHist(); + + virtual EnvROBARMHashEntry_t* GetHashEntry(short unsigned int* coord, int numofcoord, bool bIsGoal); + + virtual EnvROBARMHashEntry_t* CreateNewHashEntry(short unsigned int* coord, int numofcoord, + short unsigned int endeffx, short unsigned int endeffy); + + virtual bool InitializeEnvironment(); + + virtual void ComputeHeuristicValues(); + + virtual int GetEdgeCost(int FromStateID, int ToStateID); + virtual int GetRandomState(); + virtual bool AreEquivalent(int State1ID, int State2ID); + + virtual void PrintSuccGoal(int SourceStateID, int costtogoal, bool bVerbose, bool bLocal /*=false*/, + FILE* fOut /*=NULL*/); +}; + +#endif + diff --git a/navigations/sbpl/src/include/sbpl/headers.h b/navigations/sbpl/src/include/sbpl/headers.h new file mode 100755 index 0000000..fc1f82a --- /dev/null +++ b/navigations/sbpl/src/include/sbpl/headers.h @@ -0,0 +1,76 @@ +/* + * Copyright (c) 2008, Maxim Likhachev + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Carnegie Mellon University nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef __HEADERS_H_ +#define __HEADERS_H_ + +#include +#include + +#if MEM_CHECK == 1 +#define _CRTDBG_MAP_ALLOC +#define CRTDBG_MAP_ALLOC +#endif + +#include //have to go after the defines above +#if MEM_CHECK == 1 +#include +#endif + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#endif + diff --git a/navigations/sbpl/src/include/sbpl/heuristics/embedded_heuristic.h b/navigations/sbpl/src/include/sbpl/heuristics/embedded_heuristic.h new file mode 100755 index 0000000..8b2e873 --- /dev/null +++ b/navigations/sbpl/src/include/sbpl/heuristics/embedded_heuristic.h @@ -0,0 +1,46 @@ +/* + * Copyright (c) 2015, Maxim Likhachev + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Carnegie Mellon University nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef sbpl_EmbeddedHeuristic_h +#define sbpl_EmbeddedHeuristic_h + +#include + +class EmbeddedHeuristic : public Heuristic +{ +public: + + EmbeddedHeuristic(DiscreteSpaceInformation* environment); + + int GetGoalHeuristic(int state_id); + int GetStartHeuristic(int state_id); + int GetFromToHeuristic(int from_id, int to_id); +}; + +#endif diff --git a/navigations/sbpl/src/include/sbpl/heuristics/heuristic.h b/navigations/sbpl/src/include/sbpl/heuristics/heuristic.h new file mode 100755 index 0000000..1585c85 --- /dev/null +++ b/navigations/sbpl/src/include/sbpl/heuristics/heuristic.h @@ -0,0 +1,54 @@ +/* + * Copyright (c) 2015, Maxim Likhachev + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Carnegie Mellon University nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef sbpl_Heuristic_h +#define sbpl_Heuristic_h + +#include + +class Heuristic +{ +public: + + Heuristic(DiscreteSpaceInformation* environment) : + m_environment(environment) + { } + + virtual ~Heuristic() { } + + virtual int GetGoalHeuristic(int state_id) = 0; + virtual int GetStartHeuristic(int state_id) = 0; + virtual int GetFromToHeuristic(int from_id, int to_id) = 0; + +protected: + + DiscreteSpaceInformation* m_environment; +}; + +#endif diff --git a/navigations/sbpl/src/include/sbpl/planners/ANAplanner.h b/navigations/sbpl/src/include/sbpl/planners/ANAplanner.h new file mode 100755 index 0000000..1d5db78 --- /dev/null +++ b/navigations/sbpl/src/include/sbpl/planners/ANAplanner.h @@ -0,0 +1,272 @@ +/* + * This code was used for generating experimental data for the purpose of understanding the performance of + * the Anytime Nonparametric A* (ANA*) algorithm. + * The authors of this algorithm are Jur van den Berg, Rajat Shah, Arthur Huang and Ken Goldberg. + * The code is available at http://goldberg.berkeley.edu/ana/ + * + */ + +#ifndef __anaPLANNER_H_ +#define __anaPLANNER_H_ + +#include +#include +#include +#include + +//---configuration---- +//control of EPS +//initial suboptimality bound (cost solution <= cost(eps*cost optimal solution) +#define ana_DEFAULT_INITIAL_EPS 100000.0 +//as planning time exist, ana* decreases epsilon bound +#define ana_DECREASE_EPS 0.2 +//final epsilon bound +#define ana_FINAL_EPS 1.0 +//--------------------- +#define ana_INCONS_LIST_ID 0 + +class CHeap; +class DiscreteSpaceInformation; +class StateChangeQuery; + +//------------------------------------------------------------- + +/** + * \brief state structure used in ana* search tree + */ +typedef class anaSEARCHSTATEDATA : public AbstractSearchState +{ +public: + /** + * \brief the MDP state itself + */ + CMDPSTATE* MDPstate; + /** + * \brief ana* relevant data + */ + unsigned int v; + /** + * \brief ana* relevant data + */ + unsigned int g; + /** + * \brief ana* relevant data + */ + short unsigned int iterationclosed; + /** + * \brief ana* relevant data + */ + short unsigned int callnumberaccessed; + /** + * \brief ana* relevant data + */ + short unsigned int numofexpands; + /** + * \brief best predecessor and the action from it, used only in forward searches + */ + CMDPSTATE *bestpredstate; + /** + * \brief the next state if executing best action + */ + CMDPSTATE *bestnextstate; + unsigned int costtobestnextstate; + int h; + +public: + anaSEARCHSTATEDATA() { } + ~anaSEARCHSTATEDATA() { } +} anaState; + +/** + * \brief the statespace of ana* + */ +typedef struct anaSEARCHSTATESPACE +{ + unsigned int G; + + double eps; + double eps_satisfied; + CHeap* heap; + + short unsigned int searchiteration; + short unsigned int callnumber; + CMDPSTATE* searchgoalstate; + CMDPSTATE* searchstartstate; + + CMDP searchMDP; + + bool bReevaluatefvals; + bool bReinitializeSearchStateSpace; + bool bNewSearchIteration; +} anaSearchStateSpace_t; + +/** + * \brief ana* planner + */ +class anaPlanner : public SBPLPlanner +{ +public: + /** + * \brief replan a path within the allocated time, return the solution in the vector + */ + int replan(double allocated_time_secs, std::vector* solution_stateIDs_V); + + /** + * \brief replan a path within the allocated time, return the solution in + * the vector, also returns solution cost + */ + int replan(double allocated_time_sec, std::vector* solution_stateIDs_V, int* solcost); + + /** + * \brief set the goal state + */ + int set_goal(int goal_stateID); + + /** + * \brief set the start state + */ + int set_start(int start_stateID); + + /** + * \brief inform the search about the new edge costs + */ + void costs_changed(StateChangeQuery const & stateChange); + + /** + * \brief inform the search about the new edge costs - + * \note since ana* is non-incremental, it is sufficient (and more + * efficient) to just inform ana* of the fact that some costs changed + */ + void costs_changed(); + + /** + * \brief set a flag to get rid of the previous search efforts, release + * the memory and re-initialize the search, when the next replan is called + */ + int force_planning_from_scratch(); + + /** + * \brief you can either search forwards or backwards + */ + int set_search_mode(bool bSearchUntilFirstSolution); + + /** + * \brief returns the suboptimality bound on the currently found solution + */ + virtual double get_solution_eps() const { return pSearchStateSpace_->eps_satisfied; } + + /** + * \brief returns the number of states expanded so far + */ + virtual int get_n_expands() const { return searchexpands; } + + /** + * \brief returns the value of the initial epsilon (suboptimality bound) used + */ + virtual void set_initialsolution_eps(double initialsolution_eps) { finitial_eps = initialsolution_eps; } + + /** + * \brief prints out the search path into a file + */ + void print_searchpath(FILE* fOut); + + /** + * \brief constructor + */ + anaPlanner(DiscreteSpaceInformation* environment, bool bforwardsearch); + + /** + * \brief destructor + */ + ~anaPlanner(); + +private: + //member variables + double finitial_eps; + MDPConfig* MDPCfg_; + + bool bforwardsearch; //if true, then search proceeds forward, otherwise backward + + bool bsearchuntilfirstsolution; //if true, then search until first solution only (see planner.h for search modes) + + anaSearchStateSpace_t* pSearchStateSpace_; + + unsigned int searchexpands; + int MaxMemoryCounter; + clock_t TimeStarted; + FILE *fDeb; + + void Initialize_searchinfo(CMDPSTATE* state, anaSearchStateSpace_t* pSearchStateSpace); + + CMDPSTATE* CreateState(int stateID, anaSearchStateSpace_t* pSearchStateSpace); + + CMDPSTATE* GetState(int stateID, anaSearchStateSpace_t* pSearchStateSpace); + + int ComputeHeuristic(CMDPSTATE* MDPstate, anaSearchStateSpace_t* pSearchStateSpace); + + //initialization of a state + void InitializeSearchStateInfo(anaState* state, anaSearchStateSpace_t* pSearchStateSpace); + + //re-initialization of a state + void ReInitializeSearchStateInfo(anaState* state, anaSearchStateSpace_t* pSearchStateSpace); + + void DeleteSearchStateData(anaState* state); + + // NEW FUNCTION + double get_e_value(anaSearchStateSpace_t* pSearchStateSpace, int stateID); + + //used for backward search + void UpdatePreds(anaState* state, anaSearchStateSpace_t* pSearchStateSpace); + + //used for forward search + void UpdateSuccs(anaState* state, anaSearchStateSpace_t* pSearchStateSpace); + + int GetGVal(int StateID, anaSearchStateSpace_t* pSearchStateSpace); + + //returns 1 if the solution is found, 0 if the solution does not exist and 2 if it ran out of time + int ImprovePath(anaSearchStateSpace_t* pSearchStateSpace, double MaxNumofSecs); + + void BuildNewOPENList(anaSearchStateSpace_t* pSearchStateSpace); + + void Reevaluatefvals(anaSearchStateSpace_t* pSearchStateSpace); + + //creates (allocates memory) search state space + //does not initialize search statespace + int CreateSearchStateSpace(anaSearchStateSpace_t* pSearchStateSpace); + + //deallocates memory used by SearchStateSpace + void DeleteSearchStateSpace(anaSearchStateSpace_t* pSearchStateSpace); + + //debugging + void PrintSearchState(anaState* state, FILE* fOut); + + //reset properly search state space + //needs to be done before deleting states + int ResetSearchStateSpace(anaSearchStateSpace_t* pSearchStateSpace); + + //initialization before each search + void ReInitializeSearchStateSpace(anaSearchStateSpace_t* pSearchStateSpace); + + //very first initialization + int InitializeSearchStateSpace(anaSearchStateSpace_t* pSearchStateSpace); + + int SetSearchGoalState(int SearchGoalStateID, anaSearchStateSpace_t* pSearchStateSpace); + + int SetSearchStartState(int SearchStartStateID, anaSearchStateSpace_t* pSearchStateSpace); + + //reconstruct path functions are only relevant for forward search + int ReconstructPath(anaSearchStateSpace_t* pSearchStateSpace); + + void PrintSearchPath(anaSearchStateSpace_t* pSearchStateSpace, FILE* fOut); + + int getHeurValue(anaSearchStateSpace_t* pSearchStateSpace, int StateID); + + //get path + std::vector GetSearchPath(anaSearchStateSpace_t* pSearchStateSpace, int& solcost); + + bool Search(anaSearchStateSpace_t* pSearchStateSpace, std::vector& pathIds, int & PathCost, bool bFirstSolution, + bool bOptimalSolution, double MaxNumofSecs); +}; + +#endif + diff --git a/navigations/sbpl/src/include/sbpl/planners/adplanner.h b/navigations/sbpl/src/include/sbpl/planners/adplanner.h new file mode 100755 index 0000000..b6fb34f --- /dev/null +++ b/navigations/sbpl/src/include/sbpl/planners/adplanner.h @@ -0,0 +1,371 @@ +/* + * Copyright (c) 2008, Maxim Likhachev + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Carnegie Mellon University nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef __ADPLANNER_H_ +#define __ADPLANNER_H_ + +#include +#include +#include +#include +#include + +//---configuration---- +//control of EPS +//initial suboptimality bound (cost solution <= cost(eps*cost optimal solution) +#define AD_DEFAULT_INITIAL_EPS 10.0 +//as planning time exist, AD* decreases epsilon bound +#define AD_DECREASE_EPS 0.2 +//final epsilon bound +#define AD_FINAL_EPS 1.0 +//--------------------- +#define AD_INCONS_LIST_ID 0 + +class CHeap; +class CList; +class DiscreteSpaceInformation; +class MDPConfig; +class StateChangeQuery; + +//------------------------------------------------------------- + +/** + * \brief generic state structure in the search tree generated by AD* + */ +typedef class ADSEARCHSTATEDATA : public AbstractSearchState +{ +public: + /** + * \brief the MDP state itself (pointer to the graph represented as MDPstates) + */ + CMDPSTATE* MDPstate; + /** + * \brief AD* relevant data + */ + unsigned int v; + /** + * \brief AD* relevant data + */ + unsigned int g; + /** + * \brief AD* relevant data + */ + short unsigned int iterationclosed; + /** + * \brief AD* relevant data + */ + short unsigned int callnumberaccessed; + +#if DEBUG + /** + * \brief AD* relevant data + */ + short unsigned int numofexpands; +#endif + + /** \brief best predecessor and the action from it, used only in forward searches + */ + CMDPSTATE *bestpredstate; + + /** \brief the next state if executing best action + */ + CMDPSTATE *bestnextstate; + unsigned int costtobestnextstate; + int h; + +public: + ADSEARCHSTATEDATA() { } + ~ADSEARCHSTATEDATA() { } +} ADState; + +/** + * \brief statespace of AD* + */ +typedef struct ADSEARCHSTATESPACE +{ + double eps; + double eps_satisfied; + CHeap* heap; + CList* inconslist; + short unsigned int searchiteration; + short unsigned int callnumber; + CMDPSTATE* searchgoalstate; + CMDPSTATE* searchstartstate; + + CMDP searchMDP; + + bool bReevaluatefvals; + bool bReinitializeSearchStateSpace; + bool bRebuildOpenList; +} ADSearchStateSpace_t; + +/** + * \brief Anytime D* search planner: all states are uniquely defined by stateIDs + */ +class ADPlanner : public SBPLPlanner +{ +public: + /** + * \brief replan a path within the allocated time, return the solution in the vector + */ + virtual int replan(double allocated_time_secs, std::vector* solution_stateIDs_V); + + /** + * \brief replan a path within the allocated time, return the solution in + * the vector, also returns solution cost + */ + virtual int replan(double allocated_time_secs, std::vector* solution_stateIDs_V, int* solcost); + + /** + * \brief works same as replan function with time and solution states, but + * it let's you fill out all the parameters for the search + */ + virtual int replan(std::vector* solution_stateIDs_V, ReplanParams params); + + /** + * \brief works same as replan function with time, solution states, and + * cost, but it let's you fill out all the parameters for the search + */ + virtual int replan(std::vector* solution_stateIDs_V, ReplanParams params, int* solcost); + + /** + * \brief set the goal state + */ + virtual int set_goal(int goal_stateID); + + /** + * \brief set the start state + */ + virtual int set_start(int start_stateID); + + /** + * \brief set a flag to get rid of the previous search efforts, and + * re-initialize the search, when the next replan is called + */ + virtual int force_planning_from_scratch(); + + /** + * \brief Gets rid of the previous search efforts, release the memory and + * re-initialize the search. + */ + virtual int force_planning_from_scratch_and_free_memory(); + + /** + * \brief you can either search forwards or backwards + */ + virtual int set_search_mode(bool bSearchUntilFirstSolution); + + /** + * \brief inform the search about the new edge costs + */ + virtual void costs_changed(StateChangeQuery const & stateChange); + + /** + * \brief direct form of informing the search about the new edge costs + * + * \param succsIDV array of successors of changed edges + * \note this is used when the search is run forwards + */ + virtual void update_succs_of_changededges(std::vector* succsIDV); + + /** + * \brief direct form of informing the search about the new edge costs + * + * \param predsIDV array of predecessors of changed edges + * \note this is used when the search is run backwards + */ + virtual void update_preds_of_changededges(std::vector* predsIDV); + + /** + * \brief returns the suboptimality bound on the currently found solution + */ + virtual double get_solution_eps() const { return pSearchStateSpace_->eps_satisfied; } + + /** + * \brief returns the number of states expanded so far + */ + virtual int get_n_expands() const { return searchexpands; } + + /** + * \brief returns the initial epsilon + */ + virtual double get_initial_eps() { return finitial_eps; } + + /** + * \brief returns the time taken to find the first solution + */ + virtual double get_initial_eps_planning_time() { return finitial_eps_planning_time; } + + /** + * \brief returns the time taken to get the final solution + */ + virtual double get_final_eps_planning_time() { return final_eps_planning_time; } + + /** + * \brief returns the number of expands to find the first solution + */ + virtual int get_n_expands_init_solution() { return num_of_expands_initial_solution; } + + /** + * \brief returns the final epsilon achieved during the search + */ + virtual double get_final_epsilon() { return final_eps; } + + /** + * \brief returns the value of the initial epsilon (suboptimality bound) used + */ + virtual void set_initialsolution_eps(double initialsolution_eps) { finitial_eps = initialsolution_eps; } + + /** + * \brief fills out a vector of stats from the search + */ + virtual void get_search_stats(std::vector* s); + + /** + * \brief constructor + */ + ADPlanner(DiscreteSpaceInformation* environment, bool bForwardSearch); + + /** + * \brief destructor + */ + ~ADPlanner(); + +protected: + //member variables + double finitial_eps, finitial_eps_planning_time, final_eps_planning_time, final_eps, dec_eps, final_epsilon; + double repair_time; + bool use_repair_time; + int num_of_expands_initial_solution; + MDPConfig* MDPCfg_; + + std::vector stats; + + bool bforwardsearch; + bool bsearchuntilfirstsolution; //if true, then search until first solution (see planner.h for search modes) + + ADSearchStateSpace_t* pSearchStateSpace_; + + unsigned int searchexpands; + int MaxMemoryCounter; + clock_t TimeStarted; + FILE *fDeb; + + //member functions + virtual void Initialize_searchinfo(CMDPSTATE* state, ADSearchStateSpace_t* pSearchStateSpace); + + virtual CMDPSTATE* CreateState(int stateID, ADSearchStateSpace_t* pSearchStateSpace); + + virtual CMDPSTATE* GetState(int stateID, ADSearchStateSpace_t* pSearchStateSpace); + + virtual int ComputeHeuristic(CMDPSTATE* MDPstate, ADSearchStateSpace_t* pSearchStateSpace); + + //initialization of a state + virtual void InitializeSearchStateInfo(ADState* state, ADSearchStateSpace_t* pSearchStateSpace); + + //re-initialization of a state + virtual void ReInitializeSearchStateInfo(ADState* state, ADSearchStateSpace_t* pSearchStateSpace); + + virtual void DeleteSearchStateData(ADState* state); + + //used for backward search + virtual void UpdatePredsofOverconsState(ADState* state, ADSearchStateSpace_t* pSearchStateSpace); + virtual void UpdatePredsofUnderconsState(ADState* state, ADSearchStateSpace_t* pSearchStateSpace); + + //used for forward search + virtual void UpdateSuccsofOverconsState(ADState* state, ADSearchStateSpace_t* pSearchStateSpace); + virtual void UpdateSuccsofUnderconsState(ADState* state, ADSearchStateSpace_t* pSearchStateSpace); + + virtual void UpdateSetMembership(ADState* state); + virtual void Recomputegval(ADState* state); + + virtual int GetGVal(int StateID, ADSearchStateSpace_t* pSearchStateSpace); + + //returns 1 if the solution is found, 0 if the solution does not exist and 2 if it ran out of time + virtual int ComputePath(ADSearchStateSpace_t* pSearchStateSpace, double MaxNumofSecs); + + virtual void BuildNewOPENList(ADSearchStateSpace_t* pSearchStateSpace); + + virtual void Reevaluatefvals(ADSearchStateSpace_t* pSearchStateSpace); + virtual void Reevaluatehvals(ADSearchStateSpace_t* pSearchStateSpace); + + //creates (allocates memory) search state space + //does not initialize search statespace + virtual int CreateSearchStateSpace(ADSearchStateSpace_t* pSearchStateSpace); + + //deallocates memory used by SearchStateSpace + virtual void DeleteSearchStateSpace(ADSearchStateSpace_t* pSearchStateSpace); + + //reset properly search state space + //needs to be done before deleting states + virtual int ResetSearchStateSpace(ADSearchStateSpace_t* pSearchStateSpace); + + //initialization before each search + virtual void ReInitializeSearchStateSpace(ADSearchStateSpace_t* pSearchStateSpace); + + //very first initialization + virtual int InitializeSearchStateSpace(ADSearchStateSpace_t* pSearchStateSpace); + + virtual int SetSearchGoalState(int SearchGoalStateID, ADSearchStateSpace_t* pSearchStateSpace); + + virtual int SetSearchStartState(int SearchStartStateID, ADSearchStateSpace_t* pSearchStateSpace); + + //reconstruct path functions are only relevant for forward search + virtual int ReconstructPath(ADSearchStateSpace_t* pSearchStateSpace); + + virtual void PrintSearchState(ADState* searchstateinfo, FILE* fOut); + virtual void PrintSearchPath(ADSearchStateSpace_t* pSearchStateSpace, FILE* fOut); + + virtual int getHeurValue(ADSearchStateSpace_t* pSearchStateSpace, int StateID); + + //get path + virtual std::vector GetSearchPath(ADSearchStateSpace_t* pSearchStateSpace, int& solcost); + + virtual bool Search(ADSearchStateSpace_t* pSearchStateSpace, std::vector& pathIds, int & PathCost, + bool bFirstSolution, bool bOptimalSolution, double MaxNumofSecs); + + virtual CKey ComputeKey(ADState* state); + + virtual void Update_SearchSuccs_of_ChangedEdges(std::vector const * statesIDV); +}; + +/** + * \brief See comments in sbpl/src/planners/planner.h about the what and why of + * this class. + */ +class StateChangeQuery +{ +public: + virtual ~StateChangeQuery() { } + virtual std::vector const * getPredecessors() const = 0; + virtual std::vector const * getSuccessors() const = 0; +}; + +#endif + diff --git a/navigations/sbpl/src/include/sbpl/planners/araplanner.h b/navigations/sbpl/src/include/sbpl/planners/araplanner.h new file mode 100755 index 0000000..461f74a --- /dev/null +++ b/navigations/sbpl/src/include/sbpl/planners/araplanner.h @@ -0,0 +1,368 @@ +/* + * Copyright (c) 2008, Maxim Likhachev + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Carnegie Mellon University nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef __ARAPLANNER_H_ +#define __ARAPLANNER_H_ + +#include +#include +#include +#include +#include + +//---configuration---- +//control of EPS +//initial suboptimality bound (cost solution <= cost(eps*cost optimal solution) +#define ARA_DEFAULT_INITIAL_EPS 5.0 +//as planning time exist, ARA* decreases epsilon bound +#define ARA_DECREASE_EPS 0.2 +//final epsilon bound +#define ARA_FINAL_EPS 1.0 +//--------------------- +#define ARA_INCONS_LIST_ID 0 + +class CHeap; +class CList; +class DiscreteSpaceInformation; +class MDPConfig; +class StateChangeQuery; + +//------------------------------------------------------------- + +/** + * \brief state structure used in ARA* search tree + */ +typedef class ARASEARCHSTATEDATA : public AbstractSearchState +{ +public: + /** + * \brief the MDP state itself + */ + CMDPSTATE* MDPstate; + /** + * \brief ARA* relevant data + */ + unsigned int v; + /** + * \brief ARA* relevant data + */ + unsigned int g; + /** + * \brief ARA* relevant data + */ + short unsigned int iterationclosed; + /** + * \brief ARA* relevant data + */ + short unsigned int callnumberaccessed; + +#if DEBUG + /** + * \brief ARA* relevant data + */ + short unsigned int numofexpands; +#endif + + /** + * \brief best predecessor and the action from it, used only in forward searches + */ + CMDPSTATE *bestpredstate; + /** + * \brief the next state if executing best action + */ + CMDPSTATE *bestnextstate; + unsigned int costtobestnextstate; + int h; + +public: + ARASEARCHSTATEDATA() { } + ~ARASEARCHSTATEDATA() { } +} ARAState; + +/** + * \brief the statespace of ARA* + */ +typedef struct ARASEARCHSTATESPACE +{ + double eps; + double eps_satisfied; + CHeap* heap; + CList* inconslist; + short unsigned int searchiteration; + short unsigned int callnumber; + CMDPSTATE* searchgoalstate; + CMDPSTATE* searchstartstate; + + CMDP searchMDP; + + bool bReevaluatefvals; + bool bReinitializeSearchStateSpace; + bool bNewSearchIteration; +} ARASearchStateSpace_t; + +/** + * \brief ARA* planner + */ +class ARAPlanner : public SBPLPlanner +{ +public: + /** + * \brief replan a path within the allocated time, return the solution in the vector + */ + virtual int replan(double allocated_time_secs, std::vector* solution_stateIDs_V); + + /** + * \brief replan a path within the allocated time, return the solution in the vector, also returns solution cost + */ + virtual int replan(double allocated_time_sec, std::vector* solution_stateIDs_V, int* solcost); + + /** + * \brief works same as replan function with time and solution states, but + * it let's you fill out all the parameters for the search + */ + virtual int replan(std::vector* solution_stateIDs_V, ReplanParams params); + + /** + * \brief works same as replan function with time, solution states, and + * cost, but it let's you fill out all the parameters for the search + */ + virtual int replan(std::vector* solution_stateIDs_V, ReplanParams params, int* solcost); + + /** + * \brief set the goal state + */ + virtual int set_goal(int goal_stateID); + + /** + * \brief set the start state + */ + virtual int set_start(int start_stateID); + + /** + * \brief inform the search about the new edge costs + */ + virtual void costs_changed(StateChangeQuery const & stateChange); + + /** + * \brief inform the search about the new edge costs - + * \note since ARA* is non-incremental, it is sufficient (and more + * efficient) to just inform ARA* of the fact that some costs changed + */ + virtual void costs_changed(); + + /** + * \brief set a flag to get rid of the previous search efforts, and + * re-initialize the search, when the next replan is called + */ + virtual int force_planning_from_scratch(); + + /** + * \brief Gets rid of the previous search efforts, release the memory and re-initialize the search. + */ + virtual int force_planning_from_scratch_and_free_memory(); + + /** + * \brief you can either search forwards or backwards + */ + virtual int set_search_mode(bool bSearchUntilFirstSolution); + + /** + * \brief returns the suboptimality bound on the currently found solution + */ + virtual double get_solution_eps() const { return pSearchStateSpace_->eps_satisfied; } + + /** + * \brief returns the number of states expanded so far + */ + virtual int get_n_expands() const { return searchexpands; } + + /** + * \brief sets the value of the initial epsilon (suboptimality bound) used + */ + virtual void set_initialsolution_eps(double initialsolution_eps) { finitial_eps = initialsolution_eps; } + + /** + * \brief sets the value to decrease from eps at each iteration + */ + virtual void set_eps_step(double eps) { dec_eps = eps; } + + /** + * \brief prints out the search path into a file + */ + virtual void print_searchpath(FILE* fOut); + + /** + * \brief Compute the suboptimality bound for the most recent solution. + * + * The suboptimality bound of the solution may be provably less than the + * value of epsilon satisfied during the most recent planning iteration. + * This suboptimality bound is computed as the ratio between the current + * g-value for the goal and the minimum un-weighted f-value of a locally + * inconsistent state. + * + * \return The suboptimality bound of the most recently computed solution + */ + double compute_suboptimality(); + + /** + * \brief constructor + */ + ARAPlanner(DiscreteSpaceInformation* environment, bool bforwardsearch); + + /** + * \brief destructor + */ + ~ARAPlanner(); + + /** + * \brief returns the initial epsilon + */ + virtual double get_initial_eps() { return finitial_eps; } + + /** + * \brief returns the time taken to find the first solution + */ + virtual double get_initial_eps_planning_time() { return finitial_eps_planning_time; } + + /** + * \brief returns the time taken to get the final solution + */ + virtual double get_final_eps_planning_time() { return final_eps_planning_time; } + + /** + * \brief Return the number of expands to find the first solution or -1 if no solution has been found. + */ + virtual int get_n_expands_init_solution() { return num_of_expands_initial_solution; } + + /** + * \brief returns the final epsilon achieved during the search + */ + virtual double get_final_epsilon() { return final_eps; } + + /** + * \brief fills out a vector of stats from the search + */ + virtual void get_search_stats(std::vector* s); + +protected: + //member variables + double finitial_eps, finitial_eps_planning_time, final_eps_planning_time, final_eps, dec_eps, final_epsilon; + double repair_time; + bool use_repair_time; + + std::vector stats; + + int num_of_expands_initial_solution; + + MDPConfig* MDPCfg_; + + bool bforwardsearch; //if true, then search proceeds forward, otherwise backward + + bool bsearchuntilfirstsolution; //if true, then search until first solution only (see planner.h for search modes) + + ARASearchStateSpace_t* pSearchStateSpace_; + + unsigned int searchexpands; + int MaxMemoryCounter; + clock_t TimeStarted; + FILE *fDeb; + + //member functions + virtual void Initialize_searchinfo(CMDPSTATE* state, ARASearchStateSpace_t* pSearchStateSpace); + + virtual CMDPSTATE* CreateState(int stateID, ARASearchStateSpace_t* pSearchStateSpace); + + virtual CMDPSTATE* GetState(int stateID, ARASearchStateSpace_t* pSearchStateSpace); + + virtual int ComputeHeuristic(CMDPSTATE* MDPstate, ARASearchStateSpace_t* pSearchStateSpace); + + //initialization of a state + virtual void InitializeSearchStateInfo(ARAState* state, ARASearchStateSpace_t* pSearchStateSpace); + + //re-initialization of a state + virtual void ReInitializeSearchStateInfo(ARAState* state, ARASearchStateSpace_t* pSearchStateSpace); + + virtual void DeleteSearchStateData(ARAState* state); + + //used for backward search + virtual void UpdatePreds(ARAState* state, ARASearchStateSpace_t* pSearchStateSpace); + + //used for forward search + virtual void UpdateSuccs(ARAState* state, ARASearchStateSpace_t* pSearchStateSpace); + + virtual int GetGVal(int StateID, ARASearchStateSpace_t* pSearchStateSpace); + + //returns 1 if the solution is found, 0 if the solution does not exist and 2 if it ran out of time + virtual int ImprovePath(ARASearchStateSpace_t* pSearchStateSpace, double MaxNumofSecs); + + virtual void BuildNewOPENList(ARASearchStateSpace_t* pSearchStateSpace); + + virtual void Reevaluatefvals(ARASearchStateSpace_t* pSearchStateSpace); + virtual void Reevaluatehvals(ARASearchStateSpace_t* pSearchStateSpace); + + //creates (allocates memory) search state space + //does not initialize search statespace + virtual int CreateSearchStateSpace(ARASearchStateSpace_t* pSearchStateSpace); + + //deallocates memory used by SearchStateSpace + virtual void DeleteSearchStateSpace(ARASearchStateSpace_t* pSearchStateSpace); + + //debugging + virtual void PrintSearchState(ARAState* state, FILE* fOut); + + //reset properly search state space + //needs to be done before deleting states + virtual int ResetSearchStateSpace(ARASearchStateSpace_t* pSearchStateSpace); + + //initialization before each search + virtual void ReInitializeSearchStateSpace(ARASearchStateSpace_t* pSearchStateSpace); + + //very first initialization + virtual int InitializeSearchStateSpace(ARASearchStateSpace_t* pSearchStateSpace); + + virtual int SetSearchGoalState(int SearchGoalStateID, ARASearchStateSpace_t* pSearchStateSpace); + + virtual int SetSearchStartState(int SearchStartStateID, ARASearchStateSpace_t* pSearchStateSpace); + + //reconstruct path functions are only relevant for forward search + virtual int ReconstructPath(ARASearchStateSpace_t* pSearchStateSpace); + + virtual void PrintSearchPath(ARASearchStateSpace_t* pSearchStateSpace, FILE* fOut); + + virtual int getHeurValue(ARASearchStateSpace_t* pSearchStateSpace, int StateID); + + //get path + virtual std::vector GetSearchPath(ARASearchStateSpace_t* pSearchStateSpace, int& solcost); + + virtual bool Search(ARASearchStateSpace_t* pSearchStateSpace, std::vector& pathIds, int & PathCost, + bool bFirstSolution, bool bOptimalSolution, double MaxNumofSecs); +}; + +#endif + diff --git a/navigations/sbpl/src/include/sbpl/planners/lazyARA.h b/navigations/sbpl/src/include/sbpl/planners/lazyARA.h new file mode 100755 index 0000000..3569393 --- /dev/null +++ b/navigations/sbpl/src/include/sbpl/planners/lazyARA.h @@ -0,0 +1,191 @@ +/* + * Copyright (c) 2013, Mike Phillips and Maxim Likhachev + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Carnegie Mellon University nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef _LAZY_ARA_PLANNER_H_ +#define _LAZY_ARA_PLANNER_H_ + +#include "../../sbpl/headers.h" +#include + +class LazyListElement; + +class LazyARAState: public AbstractSearchState +{ +public: + + int id; + unsigned int v; + unsigned int g; + int h; + short unsigned int iteration_closed; + short unsigned int replan_number; + LazyARAState* best_parent; + LazyARAState* expanded_best_parent; + bool in_incons; + std::priority_queue lazyList; + bool isTrueCost; +}; + +class LazyListElement +{ +public: + + LazyListElement(LazyARAState* p, int ec, bool itc) + { + parent = p; + edgeCost = ec; + isTrueCost = itc; + } + + bool operator< (const LazyListElement& other) const + { + return (parent->v + edgeCost > other.parent->v + other.edgeCost); + } + LazyARAState* parent; + int edgeCost; + bool isTrueCost; +}; + +class LazyARAPlanner : public SBPLPlanner +{ +public: + + virtual int replan(double allocated_time_secs, std::vector* solution_stateIDs_V); + virtual int replan(double allocated_time_sec, std::vector* solution_stateIDs_V, int* solcost); + virtual int replan(int start, int goal, std::vector* solution_stateIDs_V, ReplanParams params, int* solcost); + virtual int replan(std::vector* solution_stateIDs_V, ReplanParams params); + virtual int replan(std::vector* solution_stateIDs_V, ReplanParams params, int* solcost); + + virtual int set_goal(int goal_stateID); + virtual int set_start(int start_stateID); + + virtual void costs_changed(StateChangeQuery const & stateChange) { return; } + virtual void costs_changed() { return; } + + virtual int force_planning_from_scratch() { return 1; } + virtual int force_planning_from_scratch_and_free_memory() + { + freeMemory(); + return 1; + } + + virtual int set_search_mode(bool bSearchUntilFirstSolution) + { + params.return_first_solution = bSearchUntilFirstSolution; + return 1; + } + + virtual void set_initialsolution_eps(double initialsolution_eps) + { + params.initial_eps = initialsolution_eps; + } + + LazyARAPlanner(DiscreteSpaceInformation* environment, bool bforwardsearch); + ~LazyARAPlanner(); + + virtual void get_search_stats(std::vector* s); + + double get_initial_eps() { + if (stats.empty()) return -1; return stats.front().eps; + } + + double get_solution_eps() const { + if (stats.empty()) return -1; return stats.back().eps; + } + + double get_final_epsilon() { + if (stats.empty()) return -1; return stats.back().eps; + } + + double get_initial_eps_planning_time() { + if (stats.empty()) return -1; return stats.front().time; + } + + double get_final_eps_planning_time() { + if (stats.empty()) return -1; return totalPlanTime; + } + + int get_n_expands_init_solution() { + if (stats.empty()) return -1; return stats.front().expands; + } + + int get_n_expands() const { + if (stats.empty()) return -1; return totalExpands; + } + +protected: + + // data structures (open and incons lists) + CHeap heap; + std::vector incons; + std::vector states; + + // params + ReplanParams params; + bool bforwardsearch; // if true, then search proceeds forward, otherwise backward + LazyARAState* goal_state; + LazyARAState* start_state; + int goal_state_id; + int start_state_id; + + // search member variables + double eps; + double eps_satisfied; + int search_expands; + clock_t TimeStarted; + short unsigned int search_iteration; + short unsigned int replan_number; + bool use_repair_time; + + // stats + std::vector stats; + unsigned int totalExpands; + double totalTime; + double totalPlanTime; + double reconstructTime; + + virtual LazyARAState* GetState(int id); + virtual void ExpandState(LazyARAState* parent); + virtual void EvaluateState(LazyARAState* parent); + void getNextLazyElement(LazyARAState* state); + void insertLazyList(LazyARAState* state, LazyARAState* parent, int edgeCost, bool isTrueCost); + void putStateInHeap(LazyARAState* state); + void freeMemory(); + + virtual int ImprovePath(); + + virtual std::vector GetSearchPath(int& solcost); + + virtual bool outOfTime(); + virtual void initializeSearch(); + virtual void prepareNextSearchIteration(); + virtual bool Search(std::vector& pathIds, int & PathCost); +}; + +#endif diff --git a/navigations/sbpl/src/include/sbpl/planners/mhaplanner.h b/navigations/sbpl/src/include/sbpl/planners/mhaplanner.h new file mode 100755 index 0000000..a61c552 --- /dev/null +++ b/navigations/sbpl/src/include/sbpl/planners/mhaplanner.h @@ -0,0 +1,214 @@ +/* + * Copyright (c) 2015, Maxim Likhachev + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Carnegie Mellon University nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef sbpl_MHAPlanner_h +#define sbpl_MHAPlanner_h + +#include +#include +#include + +struct MHASearchState +{ + int call_number; + int state_id; + int g; + MHASearchState* bp; + + bool closed_in_anc; + bool closed_in_add; + + struct HeapData + { + AbstractSearchState open_state; + int h; + }; + + HeapData od[1]; // overallocated for additional n heuristics +}; + +class MHAPlanner : public SBPLPlanner +{ +public: + + MHAPlanner( + DiscreteSpaceInformation* environment, + Heuristic* hanchor, + Heuristic** heurs, + int hcount); + + virtual ~MHAPlanner(); + + virtual int set_start(int start_stateID); + virtual int set_goal(int goal_stateID); + + /// \sa SBPLPlanner::replan(double, std::vector*) + virtual int replan( + double allocated_time_sec, + std::vector* solution_stateIDs_V); + + /// \sa SBPLPlanner::replan(double, std::vector*, int*) + virtual int replan( + double allocated_time_sec, + std::vector* solution_stateIDs_V, + int* solcost); + + /// \sa SBPLPlanner::replan(std::vector, ReplanParams) + virtual int replan( + std::vector* solution_stateIDs_V, + ReplanParams params); + + /// \sa SBPLPlanner::replan(std::vector*, ReplanParams, int*) + virtual int replan( + std::vector* solution_stateIDs_V, + ReplanParams params, + int* solcost); + + /// \sa SBPLPlanner::force_planning_from_scratch() + /// \return 1 on success; 0 otherwise + virtual int force_planning_from_scratch(); + + /// \sa SBPLPlanner::force_planning_from_scratch_and_free_memory() + /// \return 1 on success; 0 otherwise + virtual int force_planning_from_scratch_and_free_memory(); + + virtual void costs_changed(StateChangeQuery const & stateChange); + + /// \sa ARAPlanner::costs_changed() + virtual void costs_changed(); + + /// \name Search Parameter Accessors + ///@{ + + /// \sa SBPLPlanner::set_search_mode(bool) + virtual int set_search_mode(bool bSearchUntilFirstSolution); + /// \sa SBPLPlanner::set_initialsolution_eps(double) + virtual void set_initialsolution_eps(double eps); + + /// \sa SBPLPlanner::get_initial_eps() + virtual double get_initial_eps(); + + ///@} + + /// \name Search Statistics + ///@{ + + /// \sa SBPLPlanner::get_solution_eps() const + virtual double get_solution_eps() const; + /// \sa SBPLPlanner::get_final_epsilon() + virtual double get_final_epsilon(); + + /// \sa SBPLPlanner::get_final_eps_planning_time + virtual double get_final_eps_planning_time(); + /// \sa SBPLPlanner::get_initial_eps_planning_time + virtual double get_initial_eps_planning_time(); + + /// \sa SBPLPlanner::get_n_expands() const + virtual int get_n_expands() const; + ///\sa SBPLPlanner::get_n_expands_init_solution() + virtual int get_n_expands_init_solution(); + /// \sa SBPLPlanner::get_search_states(std::vector*) + virtual void get_search_stats(std::vector* s); + + ///@} + + /// \name Homogeneous accessor methods for search mode and timing parameters + // @{ + + void set_initial_eps(double eps) { return set_initialsolution_eps(eps); } + void set_initial_mha_eps(double eps_mha); + void set_final_eps(double eps); + void set_dec_eps(double eps); + void set_max_expansions(int expansion_count); + void set_max_time(double max_time); + + // double get_initial_eps(); + double get_initial_mha_eps() const; + double get_final_eps() const; + double get_dec_eps() const; + int get_max_expansions() const; + double get_max_time() const; + + ///@} + +private: + + // Related objects + Heuristic* m_hanchor; + Heuristic** m_heurs; + int m_hcount; ///< number of additional heuristics used + + ReplanParams m_params; + double m_initial_eps_mha; + int m_max_expansions; + + double m_eps; ///< current w_1 + double m_eps_mha; ///< current w_2 + + /// suboptimality bound satisfied by the last search + double m_eps_satisfied; + + int m_num_expansions; ///< current number of expansion + double m_elapsed; ///< current amount of seconds + + int m_call_number; + + MHASearchState* m_start_state; + MHASearchState* m_goal_state; + + std::vector m_search_states; + + CHeap* m_open; ///< sequence of (m_hcount + 1) open lists + + bool check_params(const ReplanParams& params); + + bool time_limit_reached() const; + + int num_heuristics() const { return m_hcount + 1; } + MHASearchState* get_state(int state_id); + void init_state(MHASearchState* state, size_t mha_state_idx, int state_id); + void reinit_state(MHASearchState* state); + void reinit_search(); + void clear_open_lists(); + void clear(); + int compute_key(MHASearchState* state, int hidx); + void expand(MHASearchState* state, int hidx); + MHASearchState* state_from_open_state(AbstractSearchState* open_state); + int compute_heuristic(int state_id, int hidx); + int get_minf(CHeap& pq) const; + void insert_or_update(MHASearchState* state, int hidx, int f); + + void extract_path(std::vector* solution_path, int* solcost); + + bool closed_in_anc_search(MHASearchState* state) const; + bool closed_in_add_search(MHASearchState* state) const; + bool closed_in_any_search(MHASearchState* state) const; +}; + +#endif diff --git a/navigations/sbpl/src/include/sbpl/planners/planner.h b/navigations/sbpl/src/include/sbpl/planners/planner.h new file mode 100755 index 0000000..96ac1a8 --- /dev/null +++ b/navigations/sbpl/src/include/sbpl/planners/planner.h @@ -0,0 +1,351 @@ +/* + * Copyright (c) 2008, Maxim Likhachev + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Carnegie Mellon University nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef __PLANNER_H_ +#define __PLANNER_H_ + +#include +#include +#include + +#define GETSTATEIND(stateid, mapid) StateID2IndexMapping[mapid][stateid] + +//indices for the StateID2Index mapping +enum STATEID2IND +{ + STATEID2IND_SLOT0 = 0, STATEID2IND_SLOT1,//add more slots if necessary + NUMOFINDICES_STATEID2IND +}; + +//use the slots above for the mutually exclusive algorithms +#define VIMDP_STATEID2IND STATEID2IND_SLOT0 +#define ARAMDP_STATEID2IND STATEID2IND_SLOT0 +#define ADMDP_STATEID2IND STATEID2IND_SLOT0 +#define RSTARMDP_STATEID2IND STATEID2IND_SLOT0 +#define RSTARMDP_LSEARCH_STATEID2IND STATEID2IND_SLOT1 +#define anaMDP_STATEID2IND STATEID2IND_SLOT0 +#define MHAMDP_STATEID2IND STATEID2IND_SLOT0 + +//for example +//#define YYYPLANNER_STATEID2IND STATEID2IND_SLOT0 +//#define YYYPLANNER_STATEID2IND STATEID2IND_SLOT1 + +class DiscreteSpaceInformation; +/** + * Utility for unified notification of cost changes + * across all SBPLPlanner subtypes. Ideally we would have a simple + * unified interface, such as std::vector, but the + * current separation of planner and environment representation code + * would be violated if we just included that here. + + * At the moment, ADPlanner is the only one who really uses the + * detailed information provided by ChangedCellsGetter, so we define + * that class in sbpl/src/planners/ADStar/adplanner.h (to be moved up + * the hierarchy when we generalize). + */ +class StateChangeQuery; + +/** + * \brief a parameter class for planners + */ +class ReplanParams +{ +public: + /** + * \brief constructor which sets some default values for the parameters + * \param time The maximum planning time + */ + ReplanParams(double time) + { + max_time = time; + initial_eps = 5.0; + final_eps = 1.0; + dec_eps = 0.2; + return_first_solution = false; + repair_time = -1; + } + + /** + * \brief the initial epsilon. (for anytime planners) the default value is 5.0 + */ + double initial_eps; + + /** + * \brief the final epsilon. (for anytime planners) the default value is 1.0 (optimal solution) + */ + double final_eps; + + /** + * \brief the amount epsilon decreases by between searches. (for anytime planners) By default this is 0.2 + */ + double dec_eps; + + /** + * \brief should the planner return after the finding first solution? + * (this will cause the planner to ignore all time limits) By default this + * is false. + */ + bool return_first_solution; + + /** + * \brief The planner will use all of this time planning unless it reaches + * a solution for final_eps before the time is up + */ + double max_time; + + /** + * \brief If this time out is not positive, it is ignored (this is the + * default). If the planner finds a first solution (in under maxTime of + * course) the time out for the planner becomes the minimum of maxTime and + * repairTime (clearly repairTime is useless if it is larger than + * maxTime). This second timer is useful because you often want a + * solution in a short amount of time (repairTime) where you are willing + * to let the planner improve the solution, but you are willing to wait a + * longer amount of time (maxTime) to get the first solution. + */ + double repair_time; +}; + +class PlannerStats +{ +public: + double eps; + int cost; + double time; + int expands; +}; + +typedef enum +{ + //different state types if you have more than one type inside a single planner + ABSTRACT_STATE = 0, ABSTRACT_STATEACTIONPAIR, ABSTRACT_GENERALSTATE +} AbstractSearchStateType_t; + +/** + * \brief base class for a search state + */ +class AbstractSearchState +{ +public: + /** + * \brief each state can be a member of at most two lists + * indices of lists are given in planner.h (e.g., STATEID2IND_SLOT0) + */ + struct listelement* listelem[2]; + /** + * \brief index of the state in the heap, typically used for membership in OPEN + */ + int heapindex; + /** + * \brief type of state. usually it will be general state + */ + AbstractSearchStateType_t StateType; + +public: + AbstractSearchState() + { + StateType = ABSTRACT_GENERALSTATE; + listelem[0] = listelem[1] = NULL; + } + ~AbstractSearchState() { } +}; + +/** + * \brief pure virtual base class for a generic planner + */ +class SBPLPlanner +{ +public: + /** + * \brief returns 1 if solution is found, 0 otherwise will replan + * incrementally if possible (e.g., as supported by the planner and not + * forced to replan from scratch) takes in the time available for planner + * and returns a sequence of stateIDs that corresponds to the solution + */ + virtual int replan(double allocated_time_sec, std::vector* solution_stateIDs_V) = 0; + + /** + * \brief works same as replan function with two parameters, but also returns the cost of the solution + */ + virtual int replan(double allocated_time_sec, std::vector* solution_stateIDs_V, int* solcost) = 0; + + /** + * \brief works same as replan function with time and solution states, but + * it let's you fill out all the parameters for the search + */ + virtual int replan(std::vector* solution_stateIDs_V, ReplanParams params) + { + SBPL_ERROR("replan using ReplanParams is unimplemented for this planner\n"); + return 0; + } + + /** + * \brief works same as replan function with time, solution states, and + * cost, but it let's you fill out all the parameters for the search + */ + virtual int replan(std::vector* solution_stateIDs_V, ReplanParams params, int* solcost) + { + SBPL_ERROR("replan using ReplanParams is unimplemented for this planner\n"); + return 0; + } + + /** + * \brief sets the goal of search (planner will automatically decide whether it needs to replan from scratch) + */ + virtual int set_goal(int goal_stateID) = 0; + + /** + * \brief sets the start of search (planner will automatically decide whether it needs to replan from scratch) + */ + virtual int set_start(int start_stateID) = 0; + + /** + * \brief forgets previous planning efforts and starts planning from scratch next time replan is called + */ + virtual int force_planning_from_scratch() = 0; + + /** + * \brief forgets previous planning efforts and starts planning from scratch next time replan is called + */ + virtual int force_planning_from_scratch_and_free_memory() + { + SBPL_ERROR("planning from scratch and free memory is unimplemented for this planner\n"); + return 0; + } + + /** + * \brief sets the mode for searching + * + * if bSearchUntilFirstSolution is false, then planner searches for at most + * allocatime_time_sec, independently of whether it finds a solution or not + * (default mode) if bSearchUntilFirstSolution is true, then planner + * searches until it finds the first solution. It may be faster than + * allocated_time or it may be longer In other words, in the latter case, + * the planner does not spend time on improving the solution even if time + * permits, but may also take longer than allocated_time before returning + * So, normally bSearchUntilFirstSolution should be set to false. + */ + virtual int set_search_mode(bool bSearchUntilFirstSolution) = 0; + + /** + * \brief Notifies the planner that costs have changed. May need to be + * specialized for different subclasses in terms of what to + * do here + */ + virtual void costs_changed(StateChangeQuery const & stateChange) = 0; + + /** + * \return The "epsilon" value of the solution last computed by + * replan(), if such an epsilon is used by the planner. The base class + * implementation returns -1 to express that it has no such thing. + */ + virtual double get_solution_eps() const + { + SBPL_ERROR("get_solution_eps is unimplemented for this planner\n"); + return -1; + } + + /** + * \return The number of states expanded during the last replan() + * operation, or -1 if this information is not available. + */ + virtual int get_n_expands() const + { + SBPL_ERROR("get_n_expands is unimplemented for this planner\n"); + return -1; + } + + /** + * \brief returns the initial epsilon + */ + virtual double get_initial_eps() + { + SBPL_ERROR("get_initial_eps is unimplemented for this planner\n"); + return -1; + } + + /** + * \brief returns the time taken to find the first solution + */ + virtual double get_initial_eps_planning_time() + { + SBPL_ERROR("get_initial_eps_planning_time is unimplemented for this planner\n"); + return -1; + } + + /** + * \brief returns the time taken to get the final solution + */ + virtual double get_final_eps_planning_time() + { + SBPL_ERROR("get_final_eps_planning_time is unimplemented for this planner\n"); + return -1; + } + + /** + * \brief returns the number of expands to find the first solution + */ + virtual int get_n_expands_init_solution() + { + SBPL_ERROR("get_n_expands_init_solution is unimplemented for this planner\n"); + return -1; + } + + /** + * \brief returns the final epsilon achieved during the search + */ + virtual double get_final_epsilon() + { + SBPL_ERROR("get_final_epsilon is unimplemented for this planner\n"); + return -1; + } + + /** + * \brief fills out a vector of stats from the search + */ + virtual void get_search_stats(std::vector* s) + { + SBPL_ERROR("get_search_stats is unimplemented for this planner\n"); + } + + /** + * \brief setting initial solution eps + * This parameter is ignored in planners that don't have a notion of eps + * In ARA* / AD*: (cost(initialsolution) <= eps*cost(optimalsolution)) + */ + virtual void set_initialsolution_eps(double initialsolution_eps) { } + + virtual ~SBPLPlanner() { } + +protected: + DiscreteSpaceInformation *environment_; +}; + +#endif + diff --git a/navigations/sbpl/src/include/sbpl/planners/ppcpplanner.h b/navigations/sbpl/src/include/sbpl/planners/ppcpplanner.h new file mode 100755 index 0000000..aa77932 --- /dev/null +++ b/navigations/sbpl/src/include/sbpl/planners/ppcpplanner.h @@ -0,0 +1,195 @@ +/* + * Copyright (c) 2009, Maxim Likhachev + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Carnegie Mellon University nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef __PPCPPLANNER_H_ +#define __PPCPPLANNER_H_ + +#include +#include +#include +#include +#include + +class DiscreteSpaceInformation; +class StateChangeQuery; + +/** + * \brief a state for PPCP + */ +typedef class PPCPPLANNERSTATEDATA : public AbstractSearchState +{ +public: + /** + * \brief the MDP state itself + */ + CMDPSTATE* MDPstate; + /** + * \brief planner relevant data + */ + int v; + /** + * \brief planner relevant data + */ + unsigned int iteration; + + /** + * \brief best action + */ + CMDPACTION *bestnextaction; + +private: + //probability of reaching this state (intermediate variable used by the algorithm) + float Pc; + +public: + PPCPPLANNERSTATEDATA() { } + ~PPCPPLANNERSTATEDATA() { } +} PPCPState; + +/** + * \brief PPCP statespace + */ +typedef struct PPCPSTATESPACE +{ + /** + * \brief MDP + */ + CMDP MDP; + /** + * \brief pointer to start state + */ + CMDPSTATE* StartState; + /** + * \brief pointer to goal state + */ + CMDPSTATE* GoalState; + + int iteration; + int searchiteration; + + //TODO - vector CurrentPolicy; //current policy + double currentpolicyconfidence; + + /** + * \brief set when it is necessary to reset the planner + */ + bool bReinitializeSearchStateSpace; +} PPCPStateSpace_t; + +/** + * \brief PPCP planner + * in explanations, S signifies a fully observable part of the state space H + * signifies hidden variables + */ +class PPCPPlanner : public SBPLPlanner +{ +public: + /** + * \brief planning (replanning) function. Takes in time available for + * planning + * + * returns policy, expected cost of the solution policy, and probability of + * successfully reaching the goal (it is < 1, whenever PPCP ran out of time + * before full convergence + */ + int replan(double allocated_time_secs, std::vector* SolutionPolicy, + float* ExpectedCost, float* ProbofReachGoal); + + /** + * \brief constructors + */ + PPCPPlanner(DiscreteSpaceInformation* environment, int sizeofS, int sizeofH); + + /** + * \brief destructor + */ + ~PPCPPlanner(); + + /** + * \brief setting goal state in S + */ + int set_goal(int goal_stateID); + + /** + * \brief setting start state in S + */ + int set_start(int start_stateID); + + /** + * \brief not supported version of replan + */ + int replan(double allocated_time_sec, std::vector* solution_stateIDs_V) + { + throw SBPL_Exception("ERROR: this version of replan not supported in PPCP planner"); + } + + /** + * \brief not supported version of replan + */ + int replan(double allocated_time_sec, std::vector* solution_stateIDs_V, int* solcost) + { + throw SBPL_Exception("ERROR: this version of replan not supported in PPCP planner"); + } + + /** + * \brief forgets previous planning efforts and starts planning from scratch next time replan is called + */ + int force_planning_from_scratch(); + + /** + * \brief sets how to search - not supported in PPCP + */ + int set_search_mode(bool bSearchUntilFirstSolution) + { + throw SBPL_Exception("ERROR: set_search_mode not supported in PPCP planner"); + } + + /** + * \brief Notifies the planner that costs have changed. May need to be + * specialized for different subclasses in terms of what to + * do here + */ + void costs_changed(StateChangeQuery const & stateChange); + + /** + * \brief notifies the planner that costs have changed + */ + void costs_changed(); + +private: + //member variables + PPCPStateSpace_t* pStateSpace; + FILE* fDeb; + + //deallocates memory used by SearchStateSpace + void DeleteStateSpace(PPCPStateSpace_t* pStateSpace); + int CreateSearchStateSpace(PPCPStateSpace_t* pStateSpace); +}; + +#endif diff --git a/navigations/sbpl/src/include/sbpl/planners/rstarplanner.h b/navigations/sbpl/src/include/sbpl/planners/rstarplanner.h new file mode 100755 index 0000000..01bb333 --- /dev/null +++ b/navigations/sbpl/src/include/sbpl/planners/rstarplanner.h @@ -0,0 +1,479 @@ +/* + * Copyright (c) 2008, Maxim Likhachev + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Carnegie Mellon University nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef __RSTARPLANNER_H_ +#define __RSTARPLANNER_H_ + +#include +#include +#include +#include +#include +#include + +//---configuration---- +//control of EPS +#define RSTAR_DEFAULT_INITIAL_EPS 3.0 +#define RSTAR_DECREASE_EPS 0.2 +#define RSTAR_FINAL_EPS 1.0 + +//the number of states to expand for local search in RSTAR before it declares a hard case and postpones its processing +#define RSTAR_EXPTHRESH 1000 +//--------------------- +#define RSTAR_INCONS_LIST_ID 0 + +class CList; +class StateChangeQuery; + +//------------------------------------------------------------- + +/** + * \brief high level states in R* search + * \note in other words, state structure for high level states in Gamma graph + */ +typedef class RSTARSEARCHSTATEDATA : public AbstractSearchState +{ +public: + /** + * \brief the MDP state itself + */ + CMDPSTATE* MDPstate; + /** + * \brief RSTAR* relevant data + */ + unsigned int g; + /** + * \brief RSTAR* relevant data + */ + short unsigned int iterationclosed; + /** + * \brief RSTAR* relevant data + */ + short unsigned int callnumberaccessed; + + /** + * \brief best predecessor and the action from it + * + * \note note that in R* bestpredaction refers to best predecessor in the + * high-level graph constructed by R* this graph is ALWAYS rooted at + * searchstart and directed towards searchgoal independently of the actual + * direction of search (from start to goal or from goal to start) thus + * sourcestate for the action is always at the state closer to the start of + * the search tree + */ + CMDPACTION *bestpredaction; + + /** + * \brief set of predecessor actions together with some info + */ + std::vector predactionV; + + /** + * \brief RSTAR* relevant data - heuristics + */ + int h; + +public: + RSTARSEARCHSTATEDATA() { } + ~RSTARSEARCHSTATEDATA() { } +} RSTARState; + +/** + * \brief action in Gamma graph. Each action in Gamma graph corresponds to a path + */ +typedef struct RSTARACTIONDATA_T +{ + /** + * \brief lower bound on the cost of the path + */ + int clow; + /** + * \brief number of expansions done so far to compute the path that represents this action + */ + int exp; + /** + * \brief path that the action represents + * + * \note the path is always stored as a valid path w.r.t. the original graph + * (not search tree) so if the search is forward, then the path is from + * source to target and otherwise, the path is from target toward source + */ + std::vector pathIDs; +} RSTARACTIONDATA; + +/** + * \brief low-level (local) search state in R* + */ +typedef class RSTARLSEARCHSTATEDATA : public AbstractSearchState +{ +public: + /** + * \brief the MDP state itself + */ + CMDPSTATE* MDPstate; + /** + * \brief planner relevant data - g-value + */ + int g; + + /** + * \brief planner relevant data + */ + unsigned int iteration; + /** + * \brief planner relevant data + */ + unsigned int iterationclosed; + + /** + * \brief best predecessors according to the search tree (so, in backward search these are actual successors) + */ + CMDPSTATE* bestpredstate; + /** + * \brief the cost of the best action from the best preds to this state + */ + int bestpredstateactioncost; + +public: + RSTARLSEARCHSTATEDATA() { } + ~RSTARLSEARCHSTATEDATA() { } +} RSTARLSearchState; + +/** + * \brief local search statespace in R* + */ +class RSTARLSEARCHSTATESPACE +{ +public: + /** + * \brief graph constructed by local search + */ + CMDP MDP; + /** + * \brief start state + */ + CMDPSTATE* StartState; + /** + * \brief goal state + */ + CMDPSTATE* GoalState; + /** + * \brief search-related variable + */ + int iteration; + + /** + * \brief open list + */ + CHeap* OPEN; + /** + * \brief incons list - used for suboptimal search + */ + CList* INCONS; + +public: + RSTARLSEARCHSTATESPACE() + { + OPEN = NULL; + INCONS = NULL; + StartState = NULL; + GoalState = NULL; + } + + ~RSTARLSEARCHSTATESPACE() + { + if (OPEN != NULL) delete OPEN; + } +}; + +typedef class RSTARLSEARCHSTATESPACE RSTARLSearchStateSpace_t; + +/** + * \brief statespace + */ +typedef struct RSTARSEARCHSTATESPACE +{ + /** + * \brief required epsilon + */ + double eps; + /** + * \brief epsilon that is satisfied + */ + double eps_satisfied; + /** + * \brief open list + */ + CHeap* OPEN; + + /** + * \brief searchiteration gets incremented with every R* search (and reset upon every increment of callnumber) + */ + short unsigned int searchiteration; + /** + * \brief callnumber gets incremented with every call to R* (so, it can + * be multiple number of times within planning times since R* is executed + * multiple times) + */ + short unsigned int callnumber; + /** + * \brief search goal state (not necessarily the actual start state, it depends on search direction) + */ + CMDPSTATE* searchgoalstate; + /** + * \brief search start state + */ + CMDPSTATE* searchstartstate; + + /** + * \brief graph constructed by high-level search + */ + CMDP searchMDP; + + /** + * \brief need to reevaluate fvals + */ + bool bReevaluatefvals; + /** + * \brief need to reinitialize search space + */ + bool bReinitializeSearchStateSpace; + /** + * \brief set when it is a new search iteration + */ + bool bNewSearchIteration; +} RSTARSearchStateSpace_t; + +/** + * \brief RSTAR* planner + */ +class RSTARPlanner : public SBPLPlanner +{ +public: + /** + * \brief replan a path within the allocated time, return the solution in the vector + */ + int replan(double allocated_time_secs, std::vector* solution_stateIDs_V); + + /** + * \brief replan a path within the allocated time, return the solution in the vector, also returns solution cost + */ + int replan(double allocated_time_sec, std::vector* solution_stateIDs_V, int* solcost); + + /** + * \brief set the goal state + */ + int set_goal(int goal_stateID); + + /** + * \brief set the start state + */ + int set_start(int start_stateID); + + /** + * \brief inform the search about the new edge costs + */ + void costs_changed(StateChangeQuery const & stateChange); + + /** + * \brief inform the search about the new edge costs - + * + * \note since R* is non-incremental, it is sufficient (and more efficient) + * to just inform R* of the fact that some costs changed + */ + void costs_changed(); + + /** + * \brief set a flag to get rid of the previous search efforts, release + * the memory and re-initialize the search, when the next replan is called + */ + int force_planning_from_scratch(); + + /** + * \brief you can either search forwards or backwards + */ + int set_search_mode(bool bSearchUntilFirstSolution); + + /** + * \brief obtain probabilistic eps suboptimality bound + */ + virtual double get_solution_probabilisticeps() const { return pSearchStateSpace->eps_satisfied; } + + /** + * \brief get number of high level expands + */ + virtual int get_highlevel_expands() const { return highlevel_searchexpands; } + + /** + * \brief get number of low level expands + */ + virtual int get_lowlevel_expands() const { return lowlevel_searchexpands; } + + /** + * \brief set initial solution epsilon that R* will try to satisfy (probabilistically) + */ + virtual void set_initialsolution_eps(double initialsolution_eps) { finitial_eps = initialsolution_eps; } + + /** + * \brief sets the value to decrease from eps at each iteration + */ + virtual void set_eps_step(double eps) { dec_eps = eps; } + + /** + * \brief sets the number of states to expand for local search in RSTAR before + * it declares a hard case and postpones its processing. + */ + virtual void set_local_expand_thres(unsigned thres) { local_expand_thres = thres; } + + /** + * \brief returns the initial epsilon used by the search + */ + double get_initial_eps() { return finitial_eps; } + + /** + * \brief returns the final epsilon achieved during the search + */ + double get_final_epsilon() + { + if (pSearchStateSpace != NULL) + return pSearchStateSpace->eps_satisfied; + else + return INFINITECOST; + } + + /** + * \brief print out search path + */ + void print_searchpath(FILE* fOut); + + /** + * \brief constructor + */ + RSTARPlanner(DiscreteSpaceInformation* environment, bool bforwardsearch); + + /** + * \brief destructor + */ + ~RSTARPlanner(); + +private: + //member variables + double finitial_eps; + double dec_eps; + double final_epsilon; + double local_expand_thres; + + bool bforwardsearch; //if true, then search proceeds forward, otherwise backward + + bool bsearchuntilfirstsolution; //if true, then search until first solution only (see planner.h for search modes) + + RSTARSearchStateSpace_t* pSearchStateSpace; + RSTARLSearchStateSpace_t* pLSearchStateSpace; + + unsigned int highlevel_searchexpands; + unsigned int lowlevel_searchexpands; + int MaxMemoryCounter; + clock_t TimeStarted; + FILE *fDeb; + + //member functions + void Initialize_searchinfo(CMDPSTATE* state); + CMDPSTATE* CreateState(int stateID); + CMDPSTATE* GetState(int stateID); + + int ComputeHeuristic(CMDPSTATE* MDPstate); + + //initialization of a state + void InitializeSearchStateInfo(RSTARState* state); + + //re-initialization of a state + void ReInitializeSearchStateInfo(RSTARState* state); + + void DeleteSearchStateData(RSTARState* state); + void DeleteSearchActionData(RSTARACTIONDATA* actiondata); + + int GetGVal(int StateID); + + //returns 1 if the solution is found, 0 if the solution does not exist and 2 if it ran out of time + int ImprovePath(double MaxNumofSecs); + + //note this does NOT re-compute heuristics, only re-orders OPEN list based on current eps and h-vals + void Reevaluatefvals(); + + //creates (allocates memory) search state space + //does not initialize search statespace + int CreateSearchStateSpace(); + + //deallocates memory used by SearchStateSpace + void DeleteSearchStateSpace(); + + //debugging + void PrintSearchState(RSTARState* state, FILE* fOut); + + //reset properly search state space + //needs to be done before deleting states + int ResetSearchStateSpace(); + + //initialization before each search + void ReInitializeSearchStateSpace(); + + //very first initialization + int InitializeSearchStateSpace(); + + //setting start/goal + int SetSearchGoalState(int SearchGoalStateID); + int SetSearchStartState(int SearchStartStateID); + + int getHeurValue(int StateID); + + //get path + std::vector GetSearchPath(int& solcost); + void PrintSearchPath(FILE* fOut); + + //the actual search + bool Search(std::vector& pathIds, int & PathCost, bool bFirstSolution, bool bOptimalSolution, + double MaxNumofSecs); + //local search + bool ComputeLocalPath(int StartStateID, int GoalStateID, int maxc, int maxe, int *pCost, int *pCostLow, int *pExp, + std::vector* pPathIDs, int* pNewGoalStateID, double maxnumofsecs); + + //global search functions + void SetBestPredecessor(RSTARState* rstarState, RSTARState* rstarPredState, CMDPACTION* action); + CKey ComputeKey(RSTARState* rstarState); + + //local search functions + void Initialize_rstarlsearchdata(CMDPSTATE* state); + CMDPSTATE* CreateLSearchState(int stateID); + CMDPSTATE* GetLSearchState(int stateID); + bool DestroyLocalSearchMemory(); + CKey LocalSearchComputeKey(RSTARLSearchState* rstarlsearchState); +}; + +#endif + diff --git a/navigations/sbpl/src/include/sbpl/planners/viplanner.h b/navigations/sbpl/src/include/sbpl/planners/viplanner.h new file mode 100755 index 0000000..a45672f --- /dev/null +++ b/navigations/sbpl/src/include/sbpl/planners/viplanner.h @@ -0,0 +1,131 @@ +/* + * Copyright (c) 2008, Maxim Likhachev + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Carnegie Mellon University nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef __VIPLANNER_H_ +#define __VIPLANNER_H_ + +#include +#include +#include +#include + +#define MDP_ERRDELTA 0.01 + +class DiscreteSpaceInformation; +class MDPConfig; + +struct VIPLANNER_T +{ + CMDP MDP; + CMDPSTATE* StartState; + CMDPSTATE* GoalState; + int iteration; +}; + +/** + * \brief Value Iteration state + */ +typedef class VIPLANNERSTATEDATA : public AbstractSearchState +{ +public: + /** + * \brief the MDP state itself + */ + CMDPSTATE* MDPstate; + /** + * \brief planner relevant data + */ + float v; + float Pc; + unsigned int iteration; + + /** + * \brief best action + */ + CMDPACTION *bestnextaction; + +public: + VIPLANNERSTATEDATA() { } + ~VIPLANNERSTATEDATA() { } +} VIState; + +/** + * \brief value iteration planner + */ +class VIPlanner : public SBPLPlanner +{ +public: + /** + * \brief replan a path within the allocated time, return the policy in the solution vector + */ + virtual int replan(double allocated_time_secs, std::vector* solution_stateIDs_V); + + /** + * \brief constructors + */ + VIPlanner(DiscreteSpaceInformation* environment, MDPConfig* MDP_cfg) + { + environment_ = environment; + MDPCfg_ = MDP_cfg; + } + + /** + * \brief destructor + */ + ~VIPlanner(); + +protected: + //member variables + MDPConfig* MDPCfg_; + VIPLANNER_T viPlanner; + + virtual void Initialize_vidata(CMDPSTATE* state); + + virtual CMDPSTATE* CreateState(int stateID); + + virtual CMDPSTATE* GetState(int stateID); + + virtual void PrintVIData(); + + virtual void PrintStatHeader(FILE* fOut); + + virtual void PrintStat(FILE* fOut, clock_t starttime); + + virtual void PrintPolicy(FILE* fPolicy); + + virtual void backup(CMDPSTATE* state); + + virtual void perform_iteration_backward(); + + virtual void perform_iteration_forward(); + + virtual void InitializePlanner(); +}; + +#endif diff --git a/navigations/sbpl/src/include/sbpl/sbpl_exception.h b/navigations/sbpl/src/include/sbpl/sbpl_exception.h new file mode 100755 index 0000000..cc35981 --- /dev/null +++ b/navigations/sbpl/src/include/sbpl/sbpl_exception.h @@ -0,0 +1,61 @@ +/* + * Copyright (c) 2008, Maxim Likhachev + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Carnegie Mellon University nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef SBPL_EXCEPTION_H +#define SBPL_EXCEPTION_H + +#include +#include + +#include + +class SBPL_Exception : public std::runtime_error +{ +public: + + explicit SBPL_Exception( + const std::string& what_arg = "SBPL has encountered a fatal error!") + : + std::runtime_error(what_arg) + { + SBPL_ERROR("%s\n", what_arg.c_str()); + } + + explicit SBPL_Exception(const char* what_arg) : + std::runtime_error(what_arg) + { + SBPL_ERROR("%s\n", what_arg); + } + + virtual ~SBPL_Exception() throw() { } + +private: +}; + +#endif diff --git a/navigations/sbpl/src/include/sbpl/utils/2Dgridsearch.h b/navigations/sbpl/src/include/sbpl/utils/2Dgridsearch.h new file mode 100755 index 0000000..89d5867 --- /dev/null +++ b/navigations/sbpl/src/include/sbpl/utils/2Dgridsearch.h @@ -0,0 +1,233 @@ +/* + * Copyright (c) 2008, Maxim Likhachev + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Carnegie Mellon University nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef __2DGRIDSEARCH_H_ +#define __2DGRIDSEARCH_H_ + +#include +#include +#include +#include + +#define SBPL_2DGRIDSEARCH_NUMOF2DDIRS 16 + +#define SBPL_2DSEARCH_OPEN_LIST_ID 0 + +// Forward declaration needed to allow instance of CIntHeap* +class CIntHeap; +class CSlidingBucket; + +enum SBPL_2DGRIDSEARCH_TERM_CONDITION +{ + SBPL_2DGRIDSEARCH_TERM_CONDITION_OPTPATHFOUND, + SBPL_2DGRIDSEARCH_TERM_CONDITION_20PERCENTOVEROPTPATH, + SBPL_2DGRIDSEARCH_TERM_CONDITION_TWOTIMESOPTPATH, + SBPL_2DGRIDSEARCH_TERM_CONDITION_THREETIMESOPTPATH, + SBPL_2DGRIDSEARCH_TERM_CONDITION_ALLCELLS +}; + +enum SBPL_2DGRIDSEARCH_OPENTYPE +{ + SBPL_2DGRIDSEARCH_OPENTYPE_HEAP, SBPL_2DGRIDSEARCH_OPENTYPE_SLIDINGBUCKETS +}; + +//#define SBPL_2DGRIDSEARCH_HEUR2D(x,y) ((int)(1000*cellSize_m_*sqrt((double)((x-goalX_)*(x-goalX_)+(y-goalY_)*(y-goalY_))))) +#define SBPL_2DGRIDSEARCH_HEUR2D(x,y) ((int)(1000*cellSize_m_*__max(abs(x-goalX_),abs(y-goalY_)))) + +/** + * \brief search state corresponding to each 2D cell + */ +class SBPL_2DGridSearchState : public AbstractSearchState +{ +public: + /** + * \brief coordinates + */ + int x, y; + + /** + * \brief search relevant data + */ + int g; + /** + * \brief iteration at which the state was accessed (generated) last + */ + int iterationaccessed; + +public: + SBPL_2DGridSearchState() { iterationaccessed = 0; } + ~SBPL_2DGridSearchState() { } +}; + +/** + * \brief 2D search itself + */ +class SBPL2DGridSearch +{ +public: + /** + * @brief SBPL2DGridSearch Create a search space for 2D grids + * @param width_x grid width + * @param height_y grid height + * @param cellsize_m resolution + * @param downsample edge length of block in main grid that corresponds to a single cell in this grid + * @param initial_dynamic_bucket_size Initial dynamic bucket size, set to 0 for fixed size + */ + SBPL2DGridSearch(int width_x, int height_y, float cellsize_m, int downsample=1, int initial_dynamic_bucket_size=32); + ~SBPL2DGridSearch() + { + destroy(); + } + + /** + * \brief the priority data structure used - it affects efficiency (can be + * either heap or sliding buckets, see definition of + * SBPL_2DGRIDSEARCH_OPENTYPE) + */ + bool setOPENdatastructure(SBPL_2DGRIDSEARCH_OPENTYPE OPENtype); + + /** + * \brief destroys the search and clears all memory + */ + void destroy(); + + /** \brief performs search itself. All costs are given as cost(cell1, + * cell2) = Euclidean distance*1000*(max(cell1,cell2)+1) for adjacent + * cells. + * \note It is infinite if max(cell1,cell2) >= obsthresh For cells that are + * not adjacent (which may happen if 16 connected grid is ON), then max is + * taken over all the cells center line goes through Search is done from + * start to goal. termination_condition specifies when to stop the search. + * In particular, one may specify to run it until OPEN is empty. In this + * case, the values of all states will be computed. + */ + bool search(unsigned char** Grid2D, unsigned char obsthresh, int startx_c, int starty_c, int goalx_c, int goaly_c, + SBPL_2DGRIDSEARCH_TERM_CONDITION termination_condition); + + /** + * \brief print all the values + */ + void printvalues(); + + /** + * \brief returns the computed distance from the start to . If not computed, then returns lower bound on it. + */ + inline int getlowerboundoncostfromstart_inmm(int x, int y) + { + x /= downsample_; // local x + y /= downsample_; // local y + if (term_condition_usedlast == SBPL_2DGRIDSEARCH_TERM_CONDITION_OPTPATHFOUND) { + //heuristic search + int h = SBPL_2DGRIDSEARCH_HEUR2D(x,y); + //the logic is that if s wasn't expanded, then g(s) + h(s) >= + //maxcomputed_fval => g(s) >= maxcomputed_fval - h(s) + return ((searchStates2D_[x][y].iterationaccessed == iteration_ && + searchStates2D_[x][y].g + h <= largestcomputedoptf_) ? searchStates2D_[x][y].g : + largestcomputedoptf_ < INFINITECOST ? largestcomputedoptf_ - h : + INFINITECOST); + } + else { + //Dijkstra's search + //the logic is that if s wasn't expanded, then g(s) >= maxcomputed_fval => g(s) >= maxcomputed_fval - h(s) + return ((searchStates2D_[x][y].iterationaccessed == iteration_ && + searchStates2D_[x][y].g <= largestcomputedoptf_) ? searchStates2D_[x][y].g : + largestcomputedoptf_); + } + } + + /** + * \brief returns largest optimal g-value computed by search - a lower + * bound on the state values of unexpanded states + */ + int getlargestcomputedoptimalf_inmm() { return largestcomputedoptf_; } + +private: + inline bool withinMap(int x, int y) + { + return (x >= 0 && y >= 0 && x < width_ && y < height_); + } + + void computedxy(); + inline void initializeSearchState2D(SBPL_2DGridSearchState* state2D); + bool createSearchStates2D(void); + + /// Pointer to getCost function appropriate for resample size + unsigned char (*getCost)(unsigned char**, int, int, int); + + bool search_withheap(unsigned char** Grid2D, unsigned char obsthresh, int startx_c, int starty_c, int goalx_c, + int goaly_c, SBPL_2DGRIDSEARCH_TERM_CONDITION termination_condition); + bool search_exp(unsigned char** Grid2D, unsigned char obsthresh, int startx_c, int starty_c, int goalx_c, + int goaly_c); + bool search_withbuckets(unsigned char** Grid2D, unsigned char obsthresh, int startx_c, int starty_c, int goalx_c, + int goaly_c); + bool search_withslidingbuckets(unsigned char** Grid2D, unsigned char obsthresh, int startx_c, int starty_c, + int goalx_c, int goaly_c, SBPL_2DGRIDSEARCH_TERM_CONDITION termination_condition); + + //2D search data + int initial_dynamic_bucket_size_; + CSlidingBucket* OPEN2DBLIST_; + CIntHeap* OPEN2D_; + SBPL_2DGridSearchState** searchStates2D_; + int dx_[SBPL_2DGRIDSEARCH_NUMOF2DDIRS]; + int dy_[SBPL_2DGRIDSEARCH_NUMOF2DDIRS]; + //the intermediate cells through which the actions go + //(for all the ones with the first index <=7, there are none(they go to direct neighbors) -> initialized to -1) + int dx0intersects_[SBPL_2DGRIDSEARCH_NUMOF2DDIRS]; + int dx1intersects_[SBPL_2DGRIDSEARCH_NUMOF2DDIRS]; + int dy0intersects_[SBPL_2DGRIDSEARCH_NUMOF2DDIRS]; + int dy1intersects_[SBPL_2DGRIDSEARCH_NUMOF2DDIRS]; + //distances of transitions + int dxy_distance_mm_[SBPL_2DGRIDSEARCH_NUMOF2DDIRS]; + + //OPEN data structure type + SBPL_2DGRIDSEARCH_OPENTYPE OPENtype_; + + //start and goal configurations + int startX_, startY_; + int goalX_, goalY_; + + //map parameters + int width_, height_; + float cellSize_m_; + + //search iteration + int iteration_; + + // the size of the block edge in the main gid that corresponds to 1 cell in the 2D grid + int downsample_; + + //largest optimal g-value computed by search + int largestcomputedoptf_; + + //termination criterion used in the search + SBPL_2DGRIDSEARCH_TERM_CONDITION term_condition_usedlast; +}; + +#endif + diff --git a/navigations/sbpl/src/include/sbpl/utils/heap.h b/navigations/sbpl/src/include/sbpl/utils/heap.h new file mode 100755 index 0000000..294f67b --- /dev/null +++ b/navigations/sbpl/src/include/sbpl/utils/heap.h @@ -0,0 +1,139 @@ +/* + * Copyright (c) 2008, Maxim Likhachev + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Carnegie Mellon University nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef __HEAP_H_ +#define __HEAP_H_ + +#include +#include + +//the maximum size of the heap +#define HEAPSIZE 20000000 +#define HEAPSIZE_INIT 5000 + +struct HEAPELEMENT +{ + AbstractSearchState *heapstate; + CKey key; +}; + +typedef struct HEAPELEMENT heapelement; + +class CHeap +{ + //data +public: + int percolates; //for counting purposes + heapelement* heap; + int currentsize; + int allocated; + + //constructors +public: + CHeap(); + ~CHeap(); + + //functions +public: + bool emptyheap(); + bool fullheap(); + bool inheap(AbstractSearchState *AbstractSearchState); + CKey getkeyheap(AbstractSearchState *AbstractSearchState); + void makeemptyheap(); + void insertheap(AbstractSearchState *AbstractSearchState, CKey key); + void deleteheap(AbstractSearchState *AbstractSearchState); + void updateheap(AbstractSearchState *AbstractSearchState, CKey NewKey); + AbstractSearchState *getminheap(); + AbstractSearchState *getminheap(CKey& ReturnKey); + CKey getminkeyheap(); + AbstractSearchState *deleteminheap(); + void makeheap(); + void insert_unsafe(AbstractSearchState* state, CKey key); + void updateheap_unsafe(AbstractSearchState* AbstractSearchState, CKey NewKey); + void deleteheap_unsafe(AbstractSearchState* AbstractSearchState); + +private: + void percolatedown(int hole, heapelement tmp); + void percolateup(int hole, heapelement tmp); + void percolateupordown(int hole, heapelement tmp); + + void growheap(); + void sizecheck(); +}; + +struct HEAPINTELEMENT +{ + AbstractSearchState *heapstate; + int key; +}; + +typedef struct HEAPINTELEMENT heapintelement; + +class CIntHeap +{ + //data +public: + int percolates; //for counting purposes + heapintelement* heap; + int currentsize; + int allocated; + + //constructors +public: + CIntHeap(); + CIntHeap(int initial_size); + ~CIntHeap(); + + //functions +public: + bool emptyheap(); + bool fullheap(); + bool inheap(AbstractSearchState *AbstractSearchState); + int getkeyheap(AbstractSearchState *AbstractSearchState); + void makeemptyheap(); + void insertheap(AbstractSearchState *AbstractSearchState, int key); + void deleteheap(AbstractSearchState *AbstractSearchState); + void updateheap(AbstractSearchState *AbstractSearchState, int NewKey); + AbstractSearchState *getminheap(); + AbstractSearchState *getminheap(int& ReturnKey); + int getminkeyheap(); + AbstractSearchState *deleteminheap(); + void makeheap(); + +private: + void percolatedown(int hole, heapintelement tmp); + void percolateup(int hole, heapintelement tmp); + void percolateupordown(int hole, heapintelement tmp); + + void growheap(); + void sizecheck(); +}; + +#endif + diff --git a/navigations/sbpl/src/include/sbpl/utils/key.h b/navigations/sbpl/src/include/sbpl/utils/key.h new file mode 100755 index 0000000..066246c --- /dev/null +++ b/navigations/sbpl/src/include/sbpl/utils/key.h @@ -0,0 +1,184 @@ +/* + * Copyright (c) 2008, Maxim Likhachev + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Carnegie Mellon University nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef __KEY_H_ +#define __KEY_H_ + +#define KEY_SIZE 2 + +#define INFINITECOST 1000000000 + +class CKey +{ + //data +public: + long int key[KEY_SIZE]; + + //constructors +public: + CKey() + { +#if KEY_SIZE == 1 + key[0] = 0; +#elif KEY_SIZE == 2 + key[0] = 0; + key[1] = 0; +#else + for(int i = 0; i < KEY_SIZE; i++) + { + key[i] = 0; + } +#endif + } + + ~CKey() { } + + //functions +public: + void SetKeytoInfinity() + { + for (int i = 0; i < KEY_SIZE; i++) { + key[i] = INFINITECOST; + } + } + + void SetKeytoZero() + { + for (int i = 0; i < KEY_SIZE; i++) { + key[i] = 0; + } + } + + void operator =(CKey RHSKey) + { + //iterate through the keys + //the 0ht is the most important key +#if KEY_SIZE == 1 + key[0] = RHSKey.key[0]; +#elif KEY_SIZE == 2 + key[0] = RHSKey.key[0]; + key[1] = RHSKey.key[1]; +#else + for(int i = 0; i < KEY_SIZE; i++) + key[i] = RHSKey.key[i]; +#endif + } + + CKey operator -(const CKey& RHSKey) const + { + CKey RetKey; + + //iterate through the keys + //the 0ht is the most important key + for (int i = 0; i < KEY_SIZE; i++) + RetKey.key[i] = key[i] - RHSKey.key[i]; + + return RetKey; + } + + bool operator >(CKey& RHSKey) + { + //iterate through the keys + //the 0ht is the most important key +#if KEY_SIZE == 1 + return (key[0] > RHSKey.key[0]); +#elif KEY_SIZE == 2 + return (key[0] > RHSKey.key[0] || (key[0] == RHSKey.key[0] && key[1] > RHSKey.key[1])); +#else + for(int i = 0; i < KEY_SIZE; i++) + { + //compare the current key + if(key[i] > RHSKey.key[i]) + return true; + else if(key[i] < RHSKey.key[i]) + return false; + } + //all are equal + return false; +#endif + } + + bool operator ==(CKey& RHSKey) + { + //iterate through the keys + //the 0ht is the most important key +#if KEY_SIZE == 1 + return (key[0] == RHSKey.key[0]); +#elif KEY_SIZE == 2 + return (key[0] == RHSKey.key[0] && key[1] == RHSKey.key[1]); +#else + + for(int i = 0; i < KEY_SIZE; i++) + { + //compare the current key + if(key[i] != RHSKey.key[i]) + return false; + } + + //all are equal + return true; +#endif + } + + bool operator !=(CKey& RHSKey) + { + return !(*this == RHSKey); + } + + bool operator <(CKey& RHSKey) + { + //iterate through the keys + //the 0ht is the most important key +#if KEY_SIZE == 1 + return (key[0] < RHSKey.key[0]); +#elif KEY_SIZE == 2 + return (key[0] < RHSKey.key[0] || (key[0] == RHSKey.key[0] && key[1] < RHSKey.key[1])); +#else + for(int i = 0; i < KEY_SIZE; i++) + { + //compare the current key + if(key[i] < RHSKey.key[i]) + return true; + else if(key[i] > RHSKey.key[i]) + return false; + } + //all are equal + return false; +#endif + } + + bool operator >=(CKey& RHSKey) { return !(*this < RHSKey); } + + bool operator <=(CKey& RHSKey) { return !(*this > RHSKey); } + + long int operator [](int i) { return key[i]; } +}; + +#endif + diff --git a/navigations/sbpl/src/include/sbpl/utils/list.h b/navigations/sbpl/src/include/sbpl/utils/list.h new file mode 100755 index 0000000..efb73d1 --- /dev/null +++ b/navigations/sbpl/src/include/sbpl/utils/list.h @@ -0,0 +1,682 @@ +/* + * Copyright (c) 2008, Maxim Likhachev + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Carnegie Mellon University nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef __LIST_H_ +#define __LIST_H_ + +#include +#include + +#include +#include + +//the maximum size of the heap +#define LISTSIZE 5000000 + +struct listelement +{ + AbstractSearchState *liststate; + struct listelement *prev; + struct listelement *next; +}; + +typedef struct listelement listelement; + +class CList +{ + //data +public: + listelement* firstelement; + listelement* lastelement; + int currentsize; + + //constructors +public: + CList() + { + firstelement = NULL; + lastelement = NULL; + currentsize = 0; + } + + ~CList() + { + } + + //functions +public: + bool empty() { return (currentsize == 0); } + + bool full() { return (currentsize >= LISTSIZE); } + + bool in(AbstractSearchState *AbstractSearchState1, int listindex) + { + return (AbstractSearchState1->listelem[listindex] != NULL); + } + + void makeemptylist(int listindex) + { + while (firstelement != NULL) + remove(firstelement->liststate, listindex); + } + + void insert(AbstractSearchState *AbstractSearchState1, int listindex) + { + if (currentsize >= LISTSIZE) { + throw SBPL_Exception("ERROR: list is full"); + } + if (AbstractSearchState1->listelem[listindex] != NULL) { + throw SBPL_Exception("ERROR: insert: element is already in the list"); + } + listelement *insertelem = (listelement*)malloc(sizeof(listelement)); + insertelem->liststate = AbstractSearchState1; + insertelem->prev = NULL; + insertelem->next = firstelement; + if (firstelement != NULL) firstelement->prev = insertelem; + firstelement = insertelem; + if (lastelement == NULL) //if this is the first element to be inserted into the list + lastelement = insertelem; + AbstractSearchState1->listelem[listindex] = insertelem; + currentsize++; + } + + void insertinfront(AbstractSearchState *AbstractSearchState1, int listindex) + { + insert(AbstractSearchState1, listindex); + } + + void remove(AbstractSearchState *AbstractSearchState1, int listindex) + { + if (currentsize == 0 || AbstractSearchState1->listelem[listindex] == NULL) { + throw SBPL_Exception("ERROR: delete: list does not contain the element"); + } + if (AbstractSearchState1->listelem[listindex]->prev != NULL && AbstractSearchState1->listelem[listindex]->next + != NULL) { + //in the middle of the list + AbstractSearchState1->listelem[listindex]->prev->next = AbstractSearchState1->listelem[listindex]->next; + AbstractSearchState1->listelem[listindex]->next->prev = AbstractSearchState1->listelem[listindex]->prev; + } + else if (AbstractSearchState1->listelem[listindex]->prev != NULL) { + //at the end of the list + AbstractSearchState1->listelem[listindex]->prev->next = NULL; + lastelement = AbstractSearchState1->listelem[listindex]->prev; + } + else if (AbstractSearchState1->listelem[listindex]->next != NULL) { + //at the beginning of the list + AbstractSearchState1->listelem[listindex]->next->prev = NULL; + firstelement = AbstractSearchState1->listelem[listindex]->next; + } + else { + //the only element in the list + firstelement = NULL; + lastelement = NULL; + } + //delete + free(AbstractSearchState1->listelem[listindex]); + AbstractSearchState1->listelem[listindex] = NULL; + currentsize--; + } + + AbstractSearchState *getfirst() + { + if (firstelement == NULL) + return NULL; + else + return firstelement->liststate; + } + + AbstractSearchState *getlast() + { + if (lastelement == NULL) + return NULL; + else + return lastelement->liststate; + } + + AbstractSearchState *getnext(AbstractSearchState* AbstractSearchState1, int listindex) + { + if (AbstractSearchState1->listelem[listindex]->next == NULL) + return NULL; + else + return AbstractSearchState1->listelem[listindex]->next->liststate; + } +}; + +class CBucket +{ + //data +public: + //buckets are from first_priority to numofbuckets-3. Bucket numofbucket-2 + //contains elements with higher finite priorities (unordered). Last bucket + //contains infinite priority elements + std::vector* bucketV; + //contains the priorities of elements in the numofbuckets-2 bucket (mixed priorities) + std::vector assortedpriorityV; + int firstpriority; + int numofbuckets; + int currentminelement_bucketind; + int currentminelement_priority; + int currentminelement_bucketVind; //index within the bucket + + int maxassortedpriorityVsize; + + //constructors +public: + CBucket(int first_priority, int max_bucketed_priority) + { + bucketV = NULL; + firstpriority = 0; + numofbuckets = 0; + currentminelement_bucketind = INFINITECOST; + currentminelement_priority = INFINITECOST; + currentminelement_bucketVind = INFINITECOST; + maxassortedpriorityVsize = 0; + + reset(first_priority, max_bucketed_priority); + } + + ~CBucket() + { + if (bucketV != NULL) { + makeemptybucketV(); + + delete[] bucketV; + bucketV = NULL; + firstpriority = 0; + numofbuckets = 0; + + } + } + + //functions +public: + bool empty() + { + return (currentminelement_bucketind == INFINITECOST); + } + + bool reset(int first_priority, int max_bucketed_priority) + { + //delete the old ones + if (numofbuckets != 0) { + makeemptybucketV(); + + delete[] bucketV; + bucketV = NULL; + firstpriority = 0; + numofbuckets = 0; + } + + //compute the number of buckets + numofbuckets = max_bucketed_priority - first_priority + 1; //this is how many priorities are one per buckets + numofbuckets += 2; //one bucket for (max_bucketed_priority; infinity) and one bucket for infinity + + //allocate memory + bucketV = new std::vector [numofbuckets]; + + //currently all empty + currentminelement_bucketind = INFINITECOST; + currentminelement_priority = INFINITECOST; + currentminelement_bucketVind = INFINITECOST; + + //reset statistics + maxassortedpriorityVsize = 0; + + return true; + } + + void makeemptybucketV() + { + for (int i = 0; i < numofbuckets; i++) { + for (int eind = 0; eind < (int)bucketV[i].size(); eind++) { + bucketV[i].at(eind)->heapindex = -1; + } + } + assortedpriorityV.clear(); //clear the assorted priorities array + + //currently all empty + currentminelement_bucketind = INFINITECOST; + currentminelement_priority = INFINITECOST; + currentminelement_bucketVind = INFINITECOST; + + } + + AbstractSearchState *getminelement() + { + if (currentminelement_bucketind == INFINITECOST) + return NULL; +#if DEBUG + else if(currentminelement_bucketind >= numofbuckets) + { + throw SBPL_Exception("ERROR: currentminelement_bucketind is invalid"); + } + else if((int)bucketV[currentminelement_bucketind].size() <= currentminelement_bucketVind) + { + throw SBPL_Exception("ERROR: failed to get minelement"); + } +#endif + else { + return bucketV[currentminelement_bucketind].at(currentminelement_bucketVind); + } + + } + + AbstractSearchState *popminelement() + { + if (currentminelement_bucketind == INFINITECOST) + return NULL; +#if DEBUG + else if(currentminelement_bucketind >= numofbuckets) + { + throw SBPL_Exception("ERROR: currentminelement_bucketind is invalid"); + } + else if((int)bucketV[currentminelement_bucketind].size() <= currentminelement_bucketVind) + { + throw SBPL_Exception("ERROR: failed to get minelement"); + } +#endif + else { + AbstractSearchState* AbstractSearchState1 = + bucketV[currentminelement_bucketind].at(currentminelement_bucketVind); + removestategivenbucketindex(AbstractSearchState1, currentminelement_bucketind); + return AbstractSearchState1; + } + + } + + int getminpriority() + { + return currentminelement_priority; + } + + void remove(AbstractSearchState *AbstractSearchState1, int priorityattimeofinsertion) + { + //compute bucketindex + int bucketindex = priorityattimeofinsertion - firstpriority; + if (priorityattimeofinsertion == INFINITECOST) + bucketindex = numofbuckets - 1; + else if (bucketindex > numofbuckets - 2) bucketindex = numofbuckets - 2; + + removestategivenbucketindex(AbstractSearchState1, bucketindex); + } + + void insert(AbstractSearchState *AbstractSearchState1, int priority) + { + //compute bucket index + int bucketindex = priority - firstpriority; + if (priority == INFINITECOST) { + bucketindex = numofbuckets - 1; + } + else if (bucketindex >= numofbuckets - 2) { + bucketindex = numofbuckets - 2; //overflow bucket + } + + //insert the element itself + bucketV[bucketindex].push_back(AbstractSearchState1); + AbstractSearchState1->heapindex = (int)bucketV[bucketindex].size() - 1; + + if (bucketindex == numofbuckets - 2) { + assortedpriorityV.push_back(priority); + + if (maxassortedpriorityVsize < (int)assortedpriorityV.size()) maxassortedpriorityVsize + = (int)assortedpriorityV.size(); + } + + //re-compute minelement if necessary + if (priority < currentminelement_priority || currentminelement_priority == INFINITECOST) { + recomputeminelementupfrombucket(bucketindex); + } + } + +private: + void removestategivenbucketindex(AbstractSearchState *AbstractSearchState1, int bucketindex) + { + int removeelemind = AbstractSearchState1->heapindex; + int lastelemind = (int)bucketV[bucketindex].size() - 1; + + //put into its place the last element in the bucket + if (bucketindex == numofbuckets - 2) assortedpriorityV.at(removeelemind) = assortedpriorityV.at(lastelemind); + bucketV[bucketindex].at(lastelemind)->heapindex = removeelemind; + bucketV[bucketindex].at(removeelemind) = bucketV[bucketindex].at(lastelemind); + + //clear the element itself + AbstractSearchState1->heapindex = -1; + + //remove the last element + bucketV[bucketindex].pop_back(); + + //re-compute minelement if necessary + if (bucketindex == currentminelement_bucketind && ((int)bucketV[bucketindex].size() == 0 || + currentminelement_bucketind == numofbuckets - 2)) + { + recomputeminelementupfrombucket(bucketindex); + } + } + + void recomputeminelementupfrombucket(int startbucketindex) + { + //first find non-empty bucket + int bind = -1; + for (bind = startbucketindex; bind < numofbuckets; bind++) { + if ((int)bucketV[bind].size() != 0) break; + } + + if (bind < numofbuckets - 2) { + //normal bucket + currentminelement_bucketind = bind; + currentminelement_priority = firstpriority + bind; + currentminelement_bucketVind = 0; + } + else if (bind == (numofbuckets - 2)) { + //assorted priorities + currentminelement_bucketind = bind; + currentminelement_priority = INFINITECOST; + currentminelement_bucketVind = INFINITECOST; + for (int eind = 0; eind < (int)bucketV[bind].size(); eind++) { + if (currentminelement_priority > assortedpriorityV.at(eind)) { + currentminelement_priority = assortedpriorityV.at(eind); + currentminelement_bucketVind = eind; + } + } + if (currentminelement_priority == INFINITECOST) { + throw SBPL_Exception("ERROR: in recomputemin in buckets"); + } + } + else if (bind == (numofbuckets - 1)) { + //bucket with infinite priorities + currentminelement_bucketind = bind; + currentminelement_priority = INFINITECOST; + currentminelement_bucketVind = 0; + } + else { + currentminelement_bucketind = INFINITECOST; + currentminelement_priority = INFINITECOST; + currentminelement_bucketVind = INFINITECOST; + } + + } +}; + +class CSlidingBucket +{ + //data +public: + //fixed size buckets. Each bucket is of size bucketsize, and there are numofbuckets buckets. + //all unoccupied buckets are supposed to be set to NULL + AbstractSearchState*** bucketV; + int* lastelementindexV; //index of the last element for each bucket + int numofbuckets; + int bucketsize; + int currentminelement_bindex; //index of the bucket of the current min element + int currentminelement_index; //index of the current minelement in the bucket + int currentmaxelement_priority; //the maxelement priority in the list + int currentminelement_priority; //the priority of the current minelement + int currentfirstbucket_bindex; //index of the bucket that corresponds to the first bucket in the list (lowest priority) + int currentfirstbucket_priority; //priority of the first bucket in the list + int* dynamicsize; //the size of bucket + int initialdynamicsize; //initial size of dynamic sized buckets or 0 for fixed size buckets + + //constructors +public: + // an initial_dynamic_size of 0 will use fixed size buckets + CSlidingBucket(int num_of_buckets, int bucket_size, int initial_dynamic_size=0) + { + numofbuckets = num_of_buckets; + bucketsize = bucket_size; + initialdynamicsize = std::max(0, initial_dynamic_size); + + //allocate memory + bucketV = new AbstractSearchState**[numofbuckets]; + lastelementindexV = new int[numofbuckets]; + if(initialdynamicsize) + { + dynamicsize = new int[numofbuckets]; + for (int i = 0; i < numofbuckets; i++) { + dynamicsize[i] = 0; + } + } + for (int i = 0; i < numofbuckets; i++) { + lastelementindexV[i] = -1; + bucketV[i] = NULL; + } + + currentminelement_bindex = currentfirstbucket_bindex = 0; + currentminelement_index = -1; + currentmaxelement_priority = currentminelement_priority = currentfirstbucket_priority = 0; + } + + ~CSlidingBucket() + { + for (int i = 0; i < numofbuckets; i++) { + if (bucketV[i] != NULL) { + if(initialdynamicsize) + free(bucketV[i]); + else + delete[] bucketV[i]; + bucketV[i] = NULL; + } + } + if(initialdynamicsize) + delete [] dynamicsize; + + delete[] bucketV; + bucketV = NULL; + delete[] lastelementindexV; + } + + //functions +public: + inline bool empty() + { + return (currentminelement_index == -1 && currentmaxelement_priority == currentminelement_priority); + } + + inline int getminkey() + { + return currentminelement_priority; + } + + void reset() + { + currentminelement_bindex = currentfirstbucket_bindex = 0; + currentminelement_index = -1; + currentmaxelement_priority = currentminelement_priority = currentfirstbucket_priority = 0; + for (int i = 0; i < numofbuckets; i++) { + lastelementindexV[i] = -1; + if (bucketV[i] == NULL) continue; + if(initialdynamicsize) + { + for (int eind = 0; eind < dynamicsize[i]; eind++) + bucketV[i][eind] = NULL; + } + else + { + for (int eind = 0; eind < bucketsize; eind++) + bucketV[i][eind] = NULL; + } + } + + } + + AbstractSearchState *popminelement() + { + if (currentminelement_index == -1 && currentmaxelement_priority == currentminelement_priority) + return NULL; + else { + AbstractSearchState* currentelement = NULL; + if (currentminelement_index == -1 || bucketV[currentminelement_bindex] == NULL + || bucketV[currentminelement_bindex][currentminelement_index] == NULL) + currentelement = recomputeandreturnmin(); + else + currentelement = bucketV[currentminelement_bindex][currentminelement_index]; + + //delete the element + bucketV[currentminelement_bindex][currentminelement_index] = NULL; + + //reset the first bucket to the element that was just delete + currentfirstbucket_bindex = currentminelement_bindex; + currentfirstbucket_priority = currentminelement_priority; + + //recomputemin + recomputeandreturnmin(); + + return currentelement; + } + } + + AbstractSearchState *getminelement() + { + if (currentminelement_index == -1 && currentmaxelement_priority == currentminelement_priority) + return NULL; + else { + AbstractSearchState* currentelement = NULL; + if (currentminelement_index == -1 || bucketV[currentminelement_bindex] == NULL + || bucketV[currentminelement_bindex][currentminelement_index] == NULL) + currentelement = recomputeandreturnmin(); + else + currentelement = bucketV[currentminelement_bindex][currentminelement_index]; + + return currentelement; + } + } + + void insert(AbstractSearchState *AbstractSearchState1, int priority) + { + //compute the index of the bucket where to put it in + int bucket_increment = (priority - currentfirstbucket_priority); + int bucket_index = (currentfirstbucket_bindex + bucket_increment) % numofbuckets; + + if (bucket_increment >= numofbuckets || bucket_increment < 0) { + std::stringstream ss; + ss << "ERROR: invalid priority=" << priority << + " (currentfirstbucket_priority=" << + currentfirstbucket_priority << + ") used with sliding buckets"; + throw SBPL_Exception(ss.str()); + } + + //insert the element + lastelementindexV[bucket_index]++; + + if (lastelementindexV[bucket_index] == bucketsize) { + std::stringstream ss; + ss << "ERROR: bucket " << bucket_index << " is full (size=" << bucketsize << ")"; + throw SBPL_Exception(ss.str()); + } + + if (bucketV[bucket_index] == NULL) createbucket(bucket_index); + + if(initialdynamicsize) + { + // resize the bucket if needed + if(lastelementindexV[bucket_index] >= dynamicsize[bucket_index]) + { + const int new_size = std::min(dynamicsize[bucket_index]*2, bucketsize); + + if(new_size != dynamicsize[bucket_index]) + { + bucketV[bucket_index] = (AbstractSearchState**) realloc(bucketV[bucket_index], sizeof(AbstractSearchState*) * new_size); + + for(int i=dynamicsize[bucket_index]; i currentmaxelement_priority) currentmaxelement_priority = priority; + if (priority < currentminelement_priority) { + currentminelement_priority = priority; + currentminelement_bindex = bucket_index; + } + + //special case for the only entry + if (currentminelement_bindex == bucket_index && currentminelement_index == -1) { + currentminelement_index = 0; + } + } + +private: + AbstractSearchState *recomputeandreturnmin() + { + if (currentminelement_index == -1 && currentmaxelement_priority == currentminelement_priority) return NULL; + while (currentminelement_index == -1 || bucketV[currentminelement_bindex] == NULL || + bucketV[currentminelement_bindex][currentminelement_index] == NULL) + { + //try incrementing element index + if (currentminelement_index < lastelementindexV[currentminelement_bindex]) + currentminelement_index++; + else { + //there are no more elements left in this bucket + lastelementindexV[currentminelement_bindex] = -1; + + //if it was the last bucket, then that is it + if (currentminelement_priority == currentmaxelement_priority) { + currentminelement_index = -1; + currentmaxelement_priority = currentminelement_priority; + return NULL; + } + + //try incrementing bucket index + currentminelement_bindex = (currentminelement_bindex + 1) % numofbuckets; + currentminelement_index = 0; + currentminelement_priority++; + } + } + return bucketV[currentminelement_bindex][currentminelement_index]; + } + + void createbucket(int bucketindex) + { + if (bucketV[bucketindex] != NULL) { + throw SBPL_Exception("ERROR: trying to create a non-null bucket"); + } + + if(initialdynamicsize) + { + dynamicsize[bucketindex] = initialdynamicsize; + bucketV[bucketindex] = (AbstractSearchState**) malloc(sizeof(AbstractSearchState*) * dynamicsize[bucketindex] ); + for (int eind = 0; eind < dynamicsize[bucketindex]; eind++) + bucketV[bucketindex][eind] = NULL; + } + else + { + bucketV[bucketindex] = new AbstractSearchState*[bucketsize]; + for (int eind = 0; eind < bucketsize; eind++) + bucketV[bucketindex][eind] = NULL; + } + } +}; + +#endif diff --git a/navigations/sbpl/src/include/sbpl/utils/mdp.h b/navigations/sbpl/src/include/sbpl/utils/mdp.h new file mode 100755 index 0000000..98812aa --- /dev/null +++ b/navigations/sbpl/src/include/sbpl/utils/mdp.h @@ -0,0 +1,142 @@ +/* + * Copyright (c) 2008, Maxim Likhachev + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Carnegie Mellon University nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef __MDP_H_ +#define __MDP_H_ + +#include +#include +#include +#include + +#define EPS_ERROR 0.000001 + +//the maximum size of the heap +#define MAXSTATESPACESIZE 20000000 + +class CMDPSTATE; +class CMDPACTION +{ +public: + //data + int ActionID; + int SourceStateID; + std::vector SuccsID; + std::vector Costs; + std::vector SuccsProb; + void* PlannerSpecificData; + + //constructors + CMDPACTION(int ID, int sourcestateid) + { + ActionID = ID; + SourceStateID = sourcestateid; + PlannerSpecificData = NULL; + } + + ~CMDPACTION() + { + if (PlannerSpecificData != NULL) { + const char* msg = "ERROR: state deletion: planner specific data is not deleted"; + SBPL_FPRINTF(stderr, "%s\n", msg); + throw SBPL_Exception(msg); + } + } + + //functions + bool Delete(); + bool IsValid(); + void AddOutcome(int OutcomeStateID, int OutcomeCost, float OutcomeProb); + int GetIndofMostLikelyOutcome(); + int GetIndofOutcome(int OutcomeID); + bool DeleteAllOutcomes(); + + //operators + void operator =(const CMDPACTION& rhsaction); +}; + +class CMDPSTATE +{ +public: + //data + int StateID; + std::vector Actions; + std::vector PredsID; + void* PlannerSpecificData; + + //constructors + CMDPSTATE(int ID) + { + StateID = ID; + PlannerSpecificData = NULL; + } + + ~CMDPSTATE() + { + if (PlannerSpecificData != NULL) { + const char* msg = "ERROR: state deletion: planner specific data is not deleted"; + SBPL_FPRINTF(stderr, "%s\n", msg); + throw SBPL_Exception(msg); + } + } + + //functions + bool Delete(); + CMDPACTION* AddAction(int ID); + bool ContainsPred(int stateID); + bool AddPred(int stateID); + bool RemovePred(int stateID); + bool RemoveAllActions(); + CMDPACTION* GetAction(int actionID); + + //operators + void operator =(const CMDPSTATE& rhsstate); +}; + +class CMDP +{ +public: + //data + std::vector StateArray; + + //constructors + CMDP() { } + ~CMDP() { } + + //functions + bool empty(); + bool full(); + //creates numofstates states. Their ids are their orderings for Original, Thresholded & Search MDPs + bool Create(int numofstates); + bool Delete(); + void Print(FILE* fOut); + CMDPSTATE* AddState(int StateID); +}; + +#endif diff --git a/navigations/sbpl/src/include/sbpl/utils/mdpconfig.h b/navigations/sbpl/src/include/sbpl/utils/mdpconfig.h new file mode 100755 index 0000000..3c103ba --- /dev/null +++ b/navigations/sbpl/src/include/sbpl/utils/mdpconfig.h @@ -0,0 +1,39 @@ +/* + * Copyright (c) 2008, Maxim Likhachev + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Carnegie Mellon University nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef __MDPCONFIG_H_ +#define __MDPCONFIG_H_ + +struct MDPConfig +{ + int startstateid; + int goalstateid; +}; + +#endif diff --git a/navigations/sbpl/src/include/sbpl/utils/sbpl_bfs_2d.h b/navigations/sbpl/src/include/sbpl/utils/sbpl_bfs_2d.h new file mode 100755 index 0000000..fc1d638 --- /dev/null +++ b/navigations/sbpl/src/include/sbpl/utils/sbpl_bfs_2d.h @@ -0,0 +1,221 @@ +/* + * Copyright (c) 2008, Maxim Likhachev + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Carnegie Mellon University nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef SBPL_BFS_2D +#define SBPL_BFS_2D + +#include +#include + +class sbpl_bfs_2d +{ +private: + class bfs_cell_2d + { + public: + bfs_cell_2d() + { + x = 0; + y = 0; + } + + bfs_cell_2d(int tempX, int tempY) + { + x = tempX; + y = tempY; + } + + int x; + int y; + }; + +public: + sbpl_bfs_2d(unsigned int sx, unsigned int sy, int obs_thresh, int fifo_size = -1) : + NUM_ACTIONS(8) + { + size_x_ = sx; + size_y_ = sy; + thresh_ = obs_thresh; + + //initialize the fifo + if (fifo_size < 0) fifo_size = 2 * sx + 2 * sy; + q_ = new sbpl_fifo (fifo_size); + + //initialize the distance grid + dist_ = new int*[size_x_]; + for (int x = 0; x < size_x_; x++) + dist_[x] = new int[size_y_]; + + //initialize the actions + dx = new int[NUM_ACTIONS]; + dy = new int[NUM_ACTIONS]; + int idx = 0; + for (int x = -1; x <= 1; x++) { + for (int y = -1; y <= 1; y++) { + if (!x && !y) continue; + dx[idx] = x; + dy[idx] = y; + idx++; + } + } + + } + + ~sbpl_bfs_2d() + { + //delete the fifo + delete q_; + + //delete the distance grid + for (int x = 0; x < size_x_; x++) + delete[] dist_[x]; + delete[] dist_; + + //delete the actions + delete[] dx; + delete[] dy; + } + + bool compute_distance_from_point(int** grid, int x, int y) + { + if (x < 0 || x >= size_x_ || y < 0 || y >= size_y_) { + printf("ERROR[compute_distance_from_point]: point is out of bounds!\n"); + return false; + } + q_->clear(); + clear_distances(); + + bfs_cell_2d c(x, y); + q_->insert(c); + dist_[x][y] = 0; + + compute_distances(grid); + return true; + } + + bool compute_distance_from_points(int** grid, std::vector x, std::vector y) + { + if (x.size() != y.size()) { + printf("ERROR[compute_distance_from_points]: size of x and y coordinates must agree!\n"); + return false; + } + q_->clear(); + clear_distances(); + + for (unsigned int i = 0; i < x.size(); i++) { + if (x[i] < 0 || x[i] >= size_x_ || y[i] < 0 || y[i] >= size_y_) { + printf("ERROR[compute_distance_from_points]: point is out of bounds!\n"); + return false; + } + bfs_cell_2d c(x[i], y[i]); + q_->insert(c); + dist_[x[i]][y[i]] = 0; + } + + compute_distances(grid); + return true; + } + + void compute_distance_from_obs(int** grid) + { + q_->clear(); + clear_distances(); + + for (int x = 0; x < size_x_; x++) { + for (int y = 0; y < size_y_; y++) { + if (grid[x][y] >= thresh_) { + bfs_cell_2d c(x, y); + q_->insert(c); + dist_[x][y] = 0; + } + } + } + + compute_distances(grid); + } + + void clear_distances() + { + for (int x = 0; x < size_x_; x++) + for (int y = 0; y < size_y_; y++) + dist_[x][y] = -1; + } + + void compute_distances(int** grid) + { + bfs_cell_2d c; + while (!q_->empty()) { + q_->remove(&c); + int cost = dist_[c.x][c.y] + 1; + if (c.x == 0 || c.x == size_x_ - 1 || c.y == 0 || c.y == size_y_ - 1) { + //we are on a boundary so we have to bounds check each successor + for (int i = 0; i < NUM_ACTIONS; i++) { + int x = c.x + dx[i]; + int y = c.y + dy[i]; + if (x < 0 || x >= size_x_ || y < 0 || y >= size_y_) continue; + if (dist_[x][y] < 0 && grid[x][y] < thresh_) { + dist_[x][y] = cost; + bfs_cell_2d temp(x, y); + q_->insert(temp); + } + } + } + else { + //we are not near a boundary so no bounds check is required + for (int i = 0; i < NUM_ACTIONS; i++) { + int x = c.x + dx[i]; + int y = c.y + dy[i]; + if (dist_[x][y] < 0 && grid[x][y] < thresh_) { + dist_[x][y] = cost; + bfs_cell_2d temp(x, y); + q_->insert(temp); + } + } + } + } + } + + int get_distance(unsigned int x, unsigned int y) + { + return dist_[x][y]; + } + +private: + int** dist_; + sbpl_fifo* q_; + int size_x_; + int size_y_; + int thresh_; + + const int NUM_ACTIONS; + int* dx; + int* dy; +}; + +#endif diff --git a/navigations/sbpl/src/include/sbpl/utils/sbpl_bfs_3d.h b/navigations/sbpl/src/include/sbpl/utils/sbpl_bfs_3d.h new file mode 100755 index 0000000..fcf26e0 --- /dev/null +++ b/navigations/sbpl/src/include/sbpl/utils/sbpl_bfs_3d.h @@ -0,0 +1,242 @@ +/* + * Copyright (c) 2008, Maxim Likhachev + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Carnegie Mellon University nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef SBPL_BFS_3D +#define SBPL_BFS_3D + +#include +#include + +class sbpl_bfs_3d +{ +private: + class bfs_cell_3d + { + public: + bfs_cell_3d() + { + x = 0; + y = 0; + z = 0; + } + bfs_cell_3d(int tempX, int tempY, int tempZ) + { + x = tempX; + y = tempY; + z = tempZ; + } + ; + int x; + int y; + int z; + }; + +public: + sbpl_bfs_3d(unsigned int sx, unsigned int sy, unsigned int sz, int obs_thresh, int fifo_size = -1) : + NUM_ACTIONS(26) + { + size_x_ = sx; + size_y_ = sy; + size_z_ = sz; + thresh_ = obs_thresh; + + //initialize the fifo + if (fifo_size < 0) fifo_size = 2 * sx * sy + 2 * sx * sz + 2 * sy * sz; + q_ = new sbpl_fifo (fifo_size); + + //initialize the distance grid + dist_ = new int**[size_x_]; + for (int x = 0; x < size_x_; x++) { + dist_[x] = new int*[size_y_]; + for (int y = 0; y < size_y_; y++) + dist_[x][y] = new int[size_z_]; + } + + //initialize the actions + dx = new int[NUM_ACTIONS]; + dy = new int[NUM_ACTIONS]; + dz = new int[NUM_ACTIONS]; + int idx = 0; + for (int x = -1; x <= 1; x++) { + for (int y = -1; y <= 1; y++) { + for (int z = -1; z <= 1; z++) { + if (!x && !y && !z) continue; + dx[idx] = x; + dy[idx] = y; + dz[idx] = z; + idx++; + } + } + } + + } + + ~sbpl_bfs_3d() + { + //delete the fifo + delete q_; + + //delete the distance grid + for (int x = 0; x < size_x_; x++) { + for (int y = 0; y < size_y_; y++) + delete[] dist_[x][y]; + delete[] dist_[x]; + } + delete[] dist_; + + //delete the actions + delete[] dx; + delete[] dy; + delete[] dz; + } + + bool compute_distance_from_point(int*** grid, int x, int y, int z) + { + if (x < 0 || x >= size_x_ || y < 0 || y >= size_y_ || z < 0 || z >= size_z_) { + printf("ERROR[compute_distance_from_point]: point is out of bounds!\n"); + return false; + } + q_->clear(); + clear_distances(); + + bfs_cell_3d c(x, y, z); + q_->insert(c); + dist_[x][y][z] = 0; + + compute_distances(grid); + return true; + } + + bool compute_distance_from_points(int*** grid, std::vector x, std::vector y, std::vector z) + { + if (x.size() != y.size() || x.size() != z.size()) { + printf("ERROR[compute_distance_from_points]: size of x, y, and z coordinates must agree!\n"); + return false; + } + q_->clear(); + clear_distances(); + + for (unsigned int i = 0; i < x.size(); i++) { + if (x[i] < 0 || x[i] >= size_x_ || y[i] < 0 || y[i] >= size_y_ || z[i] < 0 || z[i] >= size_z_) { + printf("ERROR[compute_distance_from_points]: point is out of bounds!\n"); + return false; + } + bfs_cell_3d c(x[i], y[i], z[i]); + q_->insert(c); + dist_[x[i]][y[i]][z[i]] = 0; + } + + compute_distances(grid); + return true; + } + + void compute_distance_from_obs(int*** grid) + { + q_->clear(); + clear_distances(); + + for (int x = 0; x < size_x_; x++) { + for (int y = 0; y < size_y_; y++) { + for (int z = 0; z < size_z_; z++) { + if (grid[x][y][z] >= thresh_) { + bfs_cell_3d c(x, y, z); + q_->insert(c); + dist_[x][y][z] = 0; + } + } + } + } + + compute_distances(grid); + } + + void clear_distances() + { + for (int x = 0; x < size_x_; x++) + for (int y = 0; y < size_y_; y++) + for (int z = 0; z < size_z_; z++) + dist_[x][y][z] = -1; + } + + void compute_distances(int*** grid) + { + bfs_cell_3d c; + while (!q_->empty()) { + q_->remove(&c); + int cost = dist_[c.x][c.y][c.z] + 1; + if (c.x == 0 || c.x == size_x_ - 1 || c.y == 0 || c.y == size_y_ - 1 || c.z == 0 || c.z == size_z_ - 1) { + //we are on a boundary so we have to bounds check each successor + for (int i = 0; i < NUM_ACTIONS; i++) { + int x = c.x + dx[i]; + int y = c.y + dy[i]; + int z = c.z + dz[i]; + if (x < 0 || x >= size_x_ || y < 0 || y >= size_y_ || z < 0 || z >= size_z_) continue; + if (dist_[x][y][z] < 0 && grid[x][y][z] < thresh_) { + dist_[x][y][z] = cost; + bfs_cell_3d temp(x, y, z); + q_->insert(temp); + } + } + } + else { + //we are not near a boundary so no bounds check is required + for (int i = 0; i < NUM_ACTIONS; i++) { + int x = c.x + dx[i]; + int y = c.y + dy[i]; + int z = c.z + dz[i]; + if (dist_[x][y][z] < 0 && grid[x][y][z] < thresh_) { + dist_[x][y][z] = cost; + bfs_cell_3d temp(x, y, z); + q_->insert(temp); + } + } + } + } + } + + int get_distance(unsigned int x, unsigned int y, unsigned int z) + { + return dist_[x][y][z]; + } + +private: + int*** dist_; + sbpl_fifo* q_; + int size_x_; + int size_y_; + int size_z_; + int thresh_; + + const int NUM_ACTIONS; + int* dx; + int* dy; + int* dz; +}; + +#endif diff --git a/navigations/sbpl/src/include/sbpl/utils/sbpl_fifo.h b/navigations/sbpl/src/include/sbpl/utils/sbpl_fifo.h new file mode 100755 index 0000000..dae8644 --- /dev/null +++ b/navigations/sbpl/src/include/sbpl/utils/sbpl_fifo.h @@ -0,0 +1,95 @@ +/* + * Copyright (c) 2008, Maxim Likhachev + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Carnegie Mellon University nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef SBPL_FIFO +#define SBPL_FIFO + +#include + +template +class sbpl_fifo +{ +public: + sbpl_fifo(unsigned int size) + { + q_ = new T[size]; + head_ = 0; + tail_ = 0; + size_ = size; + } + + ~sbpl_fifo() + { + delete[] q_; + } + + bool insert(T val) + { + int t_val = tail_; + if (t_val == head_ + 1 || (t_val == 0 && head_ + 1 == size_)) { + printf("ERROR: Trying to insert when FIFO is full!\n"); + return false; + } + q_[head_] = val; + head_++; + if (head_ == size_) head_ = 0; + return true; + } + + bool remove(T* val) + { + if (head_ == tail_) { + printf("ERROR: Trying to remove when FIFO is empty!\n"); + return false; + } + *val = q_[tail_]; + tail_++; + if (tail_ == size_) tail_ = 0; + return true; + } + + bool empty() + { + return head_ == tail_; + } + + void clear() + { + head_ = 0; + tail_ = 0; + } + +private: + int head_; + int tail_; + int size_; + T* q_; +}; + +#endif diff --git a/navigations/sbpl/src/include/sbpl/utils/utils.h b/navigations/sbpl/src/include/sbpl/utils/utils.h new file mode 100755 index 0000000..462ed6b --- /dev/null +++ b/navigations/sbpl/src/include/sbpl/utils/utils.h @@ -0,0 +1,303 @@ +/* + * Copyright (c) 2008, Maxim Likhachev + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Carnegie Mellon University nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef __UTILS_H_ +#define __UTILS_H_ + +#include +#include +#include + +#ifndef WIN32 +#define __max(x,y) (x>y?x:y) +#define __min(x,y) (x>y?y:x) +#endif + +#define nav2dcell_t sbpl_2Dcell_t +#define EnvNAVXYTHETALAT2Dpt_t sbpl_2Dcell_t +#define EnvNAVXYTHETALAT3Dpt_t sbpl_xy_theta_pt_t +#define EnvNAVXYTHETALAT3Dcell_t sbpl_xy_theta_cell_t + +#define NORMALIZEDISCTHETA(THETA, THETADIRS) (((THETA >= 0) ?\ + ((THETA) % (THETADIRS)) :\ + (((THETA) % (THETADIRS) + THETADIRS) % THETADIRS))) + +#define CONTXY2DISC(X, CELLSIZE) (((X)>=0)?((int)((X)/(CELLSIZE))):((int)((X)/(CELLSIZE))-1)) +#define DISCXY2CONT(X, CELLSIZE) ((X)*(CELLSIZE) + (CELLSIZE)/2.0) + +#define PI_CONST 3.141592653589793238462643383279502884 + +#define UNKNOWN_COST 1000000 + +class CMDP; +class PlannerStats; + +typedef struct +{ + int X1, Y1; + int X2, Y2; + int Increment; + int UsingYIndex; + int DeltaX, DeltaY; + int DTerm; + int IncrE, IncrNE; + int XIndex, YIndex; + int Flipped; +} bresenham_param_t; + +class sbpl_2Dcell_t +{ +public: + sbpl_2Dcell_t() + { + x = 0; + y = 0; + } + + sbpl_2Dcell_t(int x_, int y_) + { + x = x_; + y = y_; + } + + bool operator==(const sbpl_2Dcell_t cell) const + { + return x == cell.x && y == cell.y; + } + + bool operator<(const sbpl_2Dcell_t cell) const + { + return x < cell.x || (x == cell.x && y < cell.y); + } + + int x; + int y; +}; + +class sbpl_2Dpt_t +{ +public: + sbpl_2Dpt_t() + { + x = 0; + y = 0; + } + + sbpl_2Dpt_t(double x_, double y_) + { + x = x_; + y = y_; + } + + bool operator==(const sbpl_2Dpt_t p) const + { + return x == p.x && y == p.y; + } + + bool operator<(const sbpl_2Dpt_t p) const + { + return x < p.x || (x == p.x && y < p.y); + } + + double x; + double y; +}; + +class sbpl_xy_theta_cell_t +{ +public: + sbpl_xy_theta_cell_t() + { + x = 0; + y = 0; + theta = 0; + } + + sbpl_xy_theta_cell_t(int x_, int y_, int theta_) + { + x = x_; + y = y_; + theta = theta_; + } + + bool operator==(const sbpl_xy_theta_cell_t cell) const + { + return x == cell.x && y == cell.y && theta == cell.theta; + } + + bool operator<(const sbpl_xy_theta_cell_t cell) const + { + return x < cell.x || (x == cell.x && (y < cell.y || (y == cell.y && theta < cell.theta))); + } + + int x; + int y; + int theta; +}; + +class sbpl_xy_theta_pt_t +{ +public: + sbpl_xy_theta_pt_t() + { + x = 0; + y = 0; + theta = 0; + } + + sbpl_xy_theta_pt_t(double x_, double y_, double theta_) + { + x = x_; + y = y_; + theta = theta_; + } + + bool operator==(const sbpl_xy_theta_pt_t p) const + { + return x == p.x && y == p.y && theta == p.theta; + } + + bool operator<(const sbpl_xy_theta_pt_t p) const + { + return x < p.x || (x == p.x && (y < p.y || (y == p.y && theta < p.theta))); + } + + double x; + double y; + double theta; +}; + +typedef struct BINARYHIDDENVARIABLE +{ + int h_ID; //ID of the variable + unsigned char Prob; + +} sbpl_BinaryHiddenVar_t; + +typedef struct BELIEFSTATEWITHBINARYHVALS +{ + int s_ID; //ID of S part of state-space + //vector of updated h-values, the rest are the same as at the start state + std::vector updatedhvaluesV; +} sbpl_BeliefStatewithBinaryh_t; + +typedef struct POLICYBELIEFSTATEWITHBINARYHVALS +{ + sbpl_BeliefStatewithBinaryh_t BeliefState; //current belief state + + int nextpolicyactionID; //ID of the next policy action if exists (otherwise -1) + //indices of the outcome states of the policy action. If outcome state is not in the policy, then it is -1 + std::vector outcomestateIndexV; +} sbpl_PolicyStatewithBinaryh_t; + +//function prototypes +#if MEM_CHECK == 1 +void DisableMemCheck(); +void EnableMemCheck(); +#endif +void CheckMDP(CMDP* mdp); +void PrintMatrix(int** matrix, int rows, int cols, FILE* fOut); +void EvaluatePolicy(CMDP* PolicyMDP, int StartStateID, int GoalStateID, double* PolValue, bool* bFullPolicy, + double* Pcgoal, int* nMerges, bool* bCycles); +int ComputeNumofStochasticActions(CMDP* pMDP); + +/** + * \brief one of the three functions that correspond to bresenham algorithm of + * path following this function computes bresenham parameters given the + * start and end points on the line segment + */ +void get_bresenham_parameters(int p1x, int p1y, int p2x, int p2y, bresenham_param_t* params); + +/** + * \brief one of the three functions that correspond to bresenham algorithm of + * path following returns current cell on the line segment + */ +void get_current_point(bresenham_param_t* params, int* x, int* y); + +/** + * \brief one of the three functions that correspond to bresenham algorithm of + * path following moves to the next point + */ +int get_next_point(bresenham_param_t* params); + +/** + * \brief converts discretized version of angle into continuous (radians) + * + * \note maps 0->0, 1->delta, 2->2*delta, ... + */ +double DiscTheta2Cont(int nTheta, int NUMOFANGLEVALS); + +/** + * \brief converts continuous (radians) version of angle into discrete + * + * \note maps 0->0, [delta/2, 3/2*delta)->1, [3/2*delta, 5/2*delta)->2,... + */ +int ContTheta2Disc(double fTheta, int NUMOFANGLEVALS); + +/** + * \note counterclockwise is positive + * \param angle input angle should be in radians + * \return output is an angle in the range of from 0 to 2*PI + */ +double normalizeAngle(double angle); + +/** + * \brief computes minimum unsigned difference between two angles in radians + */ +double computeMinUnsignedAngleDiff(double angle1, double angle2); + +/** + * \brief returns true if 2D point is within the specified polygon given by + * ordered sequence of 2D points (last point is automatically connected to the + * first) + */ +bool IsInsideFootprint(sbpl_2Dpt_t pt, std::vector* bounding_polygon); + +/** + * \brief computes 8-connected distances - performs distance transform in two linear passes + */ +void computeDistancestoNonfreeAreas(unsigned char** Grid2D, int width_x, int height_y, unsigned char obsthresh, + float** disttoObs_incells, float** disttoNonfree_incells); + +void get_2d_motion_cells(std::vector polygon, std::vector poses, + std::vector* cells, double res); + +void get_2d_footprint_cells(std::vector polygon, std::vector* cells, + sbpl_xy_theta_pt_t pose, double res); +void get_2d_footprint_cells(std::vector polygon, std::set* cells, sbpl_xy_theta_pt_t pose, + double res); + +void writePlannerStats(std::vector s, FILE* fout); + +#if 0 +void CheckSearchMDP(CMDP* mdp, int ExcludeSuccStateID = -1); +void CheckSearchPredSucc(CMDPSTATE* state, int ExcludeSuccStateID = -1); +#endif + +#endif diff --git a/navigations/sbpl/src/planners/ANAplanner.cpp b/navigations/sbpl/src/planners/ANAplanner.cpp new file mode 100755 index 0000000..cfde376 --- /dev/null +++ b/navigations/sbpl/src/planners/ANAplanner.cpp @@ -0,0 +1,1121 @@ +/* + * This code was used for generating experimental data for the purpose of understanding the performance of + * the Anytime Nonparametric A* (ANA*) algorithm. + * The authors of this algorithm are Jur van den Berg, Rajat Shah, Arthur Huang and Ken Goldberg. + * The code is available at http://goldberg.berkeley.edu/ana/ + * + */ + +#include +#include + +#include +#include +#include +#include + +using namespace std; + +//----------------------------------------------------------------------------------------------------- + +anaPlanner::anaPlanner(DiscreteSpaceInformation* environment, bool bSearchForward) +{ + bforwardsearch = bSearchForward; + + environment_ = environment; + + bsearchuntilfirstsolution = false; + finitial_eps = ana_DEFAULT_INITIAL_EPS; + searchexpands = 0; + MaxMemoryCounter = 0; + + fDeb = fopen("debug.txt", "w"); + + pSearchStateSpace_ = new anaSearchStateSpace_t; + + //create the ana planner + if (CreateSearchStateSpace(pSearchStateSpace_) != 1) { + printf("ERROR: failed to create statespace\n"); + return; + } + + //set the start and goal states + if (InitializeSearchStateSpace(pSearchStateSpace_) != 1) { + printf("ERROR: failed to create statespace\n"); + return; + } +} + +anaPlanner::~anaPlanner() +{ + if (pSearchStateSpace_ != NULL) { + //delete the statespace + DeleteSearchStateSpace( pSearchStateSpace_); + delete pSearchStateSpace_; + } + fclose( fDeb); +} + +void anaPlanner::Initialize_searchinfo(CMDPSTATE* state, anaSearchStateSpace_t* pSearchStateSpace) +{ + anaState* searchstateinfo = (anaState*)state->PlannerSpecificData; + + searchstateinfo->MDPstate = state; + InitializeSearchStateInfo(searchstateinfo, pSearchStateSpace); +} + +CMDPSTATE* anaPlanner::CreateState(int stateID, anaSearchStateSpace_t* pSearchStateSpace) +{ + CMDPSTATE* state = NULL; + +#if DEBUG + if(environment_->StateID2IndexMapping[stateID][anaMDP_STATEID2IND] != -1) + { + printf("ERROR in CreateState: state already created\n"); + exit(1); + } +#endif + + //adds to the tail a state + state = pSearchStateSpace->searchMDP.AddState(stateID); + + //remember the index of the state + environment_->StateID2IndexMapping[stateID][anaMDP_STATEID2IND] = + pSearchStateSpace->searchMDP.StateArray.size() - 1; + +#if DEBUG + if (state != + pSearchStateSpace->searchMDP.StateArray[environment_->StateID2IndexMapping[stateID][anaMDP_STATEID2IND]]) + { + printf("ERROR in CreateState: invalid state index\n"); + exit(1); + } +#endif + + //create search specific info + state->PlannerSpecificData = (anaState*)malloc(sizeof(anaState)); + Initialize_searchinfo(state, pSearchStateSpace); + MaxMemoryCounter += sizeof(anaState); + + return state; +} + +CMDPSTATE* anaPlanner::GetState(int stateID, anaSearchStateSpace_t* pSearchStateSpace) +{ + if (stateID >= (int)environment_->StateID2IndexMapping.size()) { + std::stringstream ss; ss << "ERROR in GetState: stateID " << stateID << " is invalid"; + throw SBPL_Exception(ss.str()); + } + + if (environment_->StateID2IndexMapping[stateID][anaMDP_STATEID2IND] == -1) + return CreateState(stateID, pSearchStateSpace); + else + return pSearchStateSpace->searchMDP.StateArray[environment_->StateID2IndexMapping[stateID][anaMDP_STATEID2IND]]; +} + +//----------------------------------------------------------------------------------------------------- + +int anaPlanner::ComputeHeuristic(CMDPSTATE* MDPstate, anaSearchStateSpace_t* pSearchStateSpace) +{ + //compute heuristic for search + + if (bforwardsearch) { + +#if MEM_CHECK == 1 + //int WasEn = DisableMemCheck(); +#endif + + //forward search: heur = distance from state to searchgoal which is Goal anaState + int retv = environment_->GetGoalHeuristic(MDPstate->StateID); + +#if MEM_CHECK == 1 + //if (WasEn) + // EnableMemCheck(); +#endif + + return retv; + + } + else { + //backward search: heur = distance from searchgoal to state + return environment_->GetStartHeuristic(MDPstate->StateID); + } +} + +//initialization of a state +void anaPlanner::InitializeSearchStateInfo(anaState* state, anaSearchStateSpace_t* pSearchStateSpace) +{ + state->g = INFINITECOST; + state->v = INFINITECOST; + state->iterationclosed = 0; + state->callnumberaccessed = pSearchStateSpace->callnumber; + state->bestnextstate = NULL; + state->costtobestnextstate = INFINITECOST; + state->heapindex = 0; + state->listelem[ana_INCONS_LIST_ID] = 0; + state->numofexpands = 0; + + state->bestpredstate = NULL; + + //compute heuristics +#if USE_HEUR + if(pSearchStateSpace->searchgoalstate != NULL) + state->h = ComputeHeuristic(state->MDPstate, pSearchStateSpace); + else + state->h = 0; +#else + state->h = 0; +#endif +} + +//re-initialization of a state +void anaPlanner::ReInitializeSearchStateInfo(anaState* state, anaSearchStateSpace_t* pSearchStateSpace) +{ + state->g = INFINITECOST; + state->v = INFINITECOST; + state->iterationclosed = 0; + state->callnumberaccessed = pSearchStateSpace->callnumber; + state->bestnextstate = NULL; + state->costtobestnextstate = INFINITECOST; + state->heapindex = 0; + state->listelem[ana_INCONS_LIST_ID] = 0; + state->numofexpands = 0; + + state->bestpredstate = NULL; + + //compute heuristics +#if USE_HEUR + + if (pSearchStateSpace->searchgoalstate != NULL) { + state->h = ComputeHeuristic(state->MDPstate, pSearchStateSpace); + } + else + state->h = 0; + +#else + + state->h = 0; + +#endif + +} + +void anaPlanner::DeleteSearchStateData(anaState* state) +{ + //no memory was allocated + MaxMemoryCounter = 0; + return; +} + +double anaPlanner::get_e_value(anaSearchStateSpace_t* pSearchStateSpace, int stateID) +{ + + CMDPSTATE* MDPstate = GetState(stateID, pSearchStateSpace); + anaState* searchstateinfo = (anaState*)MDPstate->PlannerSpecificData; + + //if(!(searchstateinfo->g > pSearchStateSpace->G)) { + if (searchstateinfo->h == 0) { + if (searchstateinfo->g >= pSearchStateSpace->G) { + return 0.0; + } + else { + return (double)INFINITECOST; + } + } + else { + return ((double)pSearchStateSpace->G - 1.0 * searchstateinfo->g) / (double)searchstateinfo->h; + + //return 0.5*(((double) pSearchStateSpace->G - 1.0*searchstateinfo->g) / (double) searchstateinfo->h); + + //return 1000 + (((double) pSearchStateSpace->G - 1.0*searchstateinfo->g) / (double) searchstateinfo->h); + } +} + +//used for backward search +void anaPlanner::UpdatePreds(anaState* state, anaSearchStateSpace_t* pSearchStateSpace) +{ + vector PredIDV; + vector CostV; + CKey key; + anaState *p; + + environment_->GetPreds(state->MDPstate->StateID, &PredIDV, &CostV); + + //iterate through predecessors of s + for (int pind = 0; pind < (int)PredIDV.size(); pind++) { + CMDPSTATE* PredMDPState = GetState(PredIDV[pind], pSearchStateSpace); + p = (anaState*)(PredMDPState->PlannerSpecificData); + if (p->callnumberaccessed != pSearchStateSpace->callnumber) ReInitializeSearchStateInfo(p, pSearchStateSpace); + + //see if we can improve the value of p + + if ((p->g > state->g + CostV[pind]) && (state->g + CostV[pind] + p->h < pSearchStateSpace->G)) { + p->g = state->g + CostV[pind]; + p->bestnextstate = state->MDPstate; + p->costtobestnextstate = CostV[pind]; + + key.key[0] = (long)-get_e_value(pSearchStateSpace, p->MDPstate->StateID); + if (pSearchStateSpace->heap->inheap(p)) { + pSearchStateSpace->heap->updateheap(p, key); + } + else { + pSearchStateSpace->heap->insertheap(p, key); + } + } + } +} + +//used for forward search +void anaPlanner::UpdateSuccs(anaState* state, anaSearchStateSpace_t* pSearchStateSpace) +{ + vector SuccIDV; + vector CostV; + CKey key; + anaState *n; + + environment_->GetSuccs(state->MDPstate->StateID, &SuccIDV, &CostV); + + //iterate through predecessors of s + for (int sind = 0; sind < (int)SuccIDV.size(); sind++) { + CMDPSTATE* SuccMDPState = GetState(SuccIDV[sind], pSearchStateSpace); + int cost = CostV[sind]; + + n = (anaState*)(SuccMDPState->PlannerSpecificData); + if (n->callnumberaccessed != pSearchStateSpace->callnumber) ReInitializeSearchStateInfo(n, pSearchStateSpace); + + //see if we can improve the value of n + //taking into account the cost of action + if ((n->g > state->g + cost) && ((state->g + cost + n->h) < pSearchStateSpace->G)) { + n->g = state->g + cost; + n->bestpredstate = state->MDPstate; + + key.key[0] = (long)-get_e_value(pSearchStateSpace, n->MDPstate->StateID); + /*if(key.key[0] >= -1) { + printf("inserting on Open with key =%d\n", key.key[0]); + }*/ + if (pSearchStateSpace->heap->inheap(n)) { + pSearchStateSpace->heap->updateheap(n, key); + } + else { + pSearchStateSpace->heap->insertheap(n, key); + } + } + } +} + +//TODO-debugmax - add obsthresh and other thresholds to other environments in 3dkin +int anaPlanner::GetGVal(int StateID, anaSearchStateSpace_t* pSearchStateSpace) +{ + CMDPSTATE* cmdp_state = GetState(StateID, pSearchStateSpace); + anaState* state = (anaState*)cmdp_state->PlannerSpecificData; + return state->g; +} + +//returns 1 if the solution is found, 0 if the solution does not exist and 2 if it ran out of time +int anaPlanner::ImprovePath(anaSearchStateSpace_t* pSearchStateSpace, double MaxNumofSecs) +{ + int expands; + anaState *state, *searchgoalstate; + CKey key, minkey; + //CKey goalkey; + + expands = 0; + + if (pSearchStateSpace->searchgoalstate == NULL) { + throw SBPL_Exception("ERROR searching: no goal state is set"); + } + + //goal state + searchgoalstate = (anaState*)(pSearchStateSpace->searchgoalstate->PlannerSpecificData); + if (searchgoalstate->callnumberaccessed != pSearchStateSpace->callnumber) { + ReInitializeSearchStateInfo( searchgoalstate, pSearchStateSpace); + } + + //set goal key + //goalkey.key[0] = -get_e_value(pSearchStateSpace, searchgoalstate->MDPstate->StateID); + //goalkey.key[1] = searchgoalstate->h; + + //expand states until done + minkey.key[0] = -(pSearchStateSpace->heap->getminkeyheap().key[0]); + CKey oldkey = minkey; + while (!pSearchStateSpace->heap->emptyheap() && + (clock() - TimeStarted) < MaxNumofSecs * (double)CLOCKS_PER_SEC) + //&& goalkey > minkey && minkey.key[0] <= INFINITECOST + { + /*if(minkey.key[0] < 10) { + printf("Key: %.2f\t", minkey.key[0]); + }*/ + //printf("%.2f\t", minkey.key[0]); + + //get the state + state = (anaState*)pSearchStateSpace->heap->deleteminheap(); + + if (state->MDPstate->StateID == searchgoalstate->MDPstate->StateID) { + pSearchStateSpace->G = state->g; + //minkey.key[0] = + //printf("search exited with a solution for eps=%.3f\n", pSearchStateSpace->eps); + //printf("eps=%f time_elapsed=%.3f\n", pSearchStateSpace->eps, double(clock()-TimeStarted)/CLOCKS_PER_SEC); + + searchexpands += expands; + return 1;// so that it does not declare it as run out of time + } + + //double e_val = floor(minkey.key[0]*100.0) / 100.0; + double e_val = minkey.key[0]; + //double save = pSearchStateSpace->eps; + if (e_val < pSearchStateSpace->eps) { // && e_val>=ana_FINAL_EPS + pSearchStateSpace->eps = minkey.key[0]; + //if(save - e_val > 0.01) + //printf("eps=%f time_elapsed=%.6f\n", pSearchStateSpace->eps, double(clock()-TimeStarted)/CLOCKS_PER_SEC); + } + +#if DEBUG + //fprintf(fDeb, "expanding state(%d): h=%d g=%u key=%u v=%u iterc=%d callnuma=%d expands=%d (g(goal)=%u)\n", + // state->MDPstate->StateID, state->h, state->g, state->g+(int)(pSearchStateSpace->eps*state->h), state->v, + // state->iterationclosed, state->callnumberaccessed, state->numofexpands, searchgoalstate->g); + //fprintf(fDeb, "expanding: "); + //PrintSearchState(state, fDeb); + if (state->listelem[ana_INCONS_LIST_ID] != NULL) { + fprintf(fDeb, "ERROR: expanding a state from inconslist\n"); + printf("ERROR: expanding a state from inconslist\n"); + exit(1); + } + //fflush(fDeb); +#endif + +#if DEBUG + if (minkey.key[0] < oldkey.key[0] && fabs(this->finitial_eps - 1.0) < ERR_EPS) { + //printf("WARN in search: the sequence of keys decreases\n"); + //exit(1); + } + oldkey = minkey; +#endif + + if (state->v == state->g) { + printf("ERROR: consistent state is being expanded\n"); +#if DEBUG + fprintf(fDeb, "ERROR: consistent state is being expanded\n"); + exit(1); +#endif + } + + //recompute state value + state->v = state->g; + state->iterationclosed = pSearchStateSpace->searchiteration; + + //new expand + expands++; + state->numofexpands++; + + if (bforwardsearch == false) + UpdatePreds(state, pSearchStateSpace); + else + UpdateSuccs(state, pSearchStateSpace); + + //recompute minkey + minkey.key[0] = -(pSearchStateSpace->heap->getminkeyheap().key[0]); + + //recompute goalkey if necessary + + pSearchStateSpace->G = searchgoalstate->g; + + if (expands % 100000 == 0 && expands > 0) { + //printf("expands so far=%u\n", expands); + } + + /*if(state->MDPstate->StateID == searchgoalstate->MDPstate->StateID) { + goalkey.key[0] = minkey.key[0]; + break; + }*/ + } + + int retv = 1; + if (searchgoalstate->g == INFINITECOST && pSearchStateSpace->heap->emptyheap()) { + printf("solution does not exist: search exited because heap is empty\n"); + retv = 0; + } + else if (!pSearchStateSpace->heap->emptyheap() && 0 < minkey.key[0]) { + printf("search exited because it ran out of time\n"); + //printf("Goalkey=%f and minkey=%f", goalkey.key[0], minkey.key[0]); + retv = 2; + } + else if (searchgoalstate->g == INFINITECOST && !pSearchStateSpace->heap->emptyheap()) { + printf("solution does not exist: search exited because all " + "candidates for expansion have infinite heuristics\n"); + retv = 0; + } + else { + //printf("eps=%.3f time=%.3f\n", pSearchStateSpace->eps, double(clock() - TimeStarted)/CLOCKS_PER_SEC); + retv = 3; + } + + //fprintf(fDeb, "expanded=%d\n", expands); + + searchexpands += expands; + + return retv; +} + +void anaPlanner::Reevaluatefvals(anaSearchStateSpace_t* pSearchStateSpace) +{ + CKey key; + int i; + CHeap* pheap = pSearchStateSpace->heap; + + //recompute priorities for states in OPEN and reorder it + for (i = 1; i <= pheap->currentsize; ++i) { + //anaState* state = (anaState*)pheap->heap[i].heapstate; + + // CHANGED - cast removed + + pheap->heap[i].key.key[0] = (long)-get_e_value(pSearchStateSpace, + ((anaState*)pheap->heap[i].heapstate)->MDPstate->StateID); + + //pheap->heap[i].key.key[1] = state->h; + } + pheap->makeheap(); + + pSearchStateSpace->bReevaluatefvals = false; +} + +//creates (allocates memory) search state space +//does not initialize search statespace +int anaPlanner::CreateSearchStateSpace(anaSearchStateSpace_t* pSearchStateSpace) +{ + //create a heap + pSearchStateSpace->heap = new CHeap; + //pSearchStateSpace->inconslist = new CHeap; + MaxMemoryCounter += sizeof(CHeap); + MaxMemoryCounter += sizeof(CList); + + pSearchStateSpace->searchgoalstate = NULL; + pSearchStateSpace->searchstartstate = NULL; + + searchexpands = 0; + + pSearchStateSpace->bReinitializeSearchStateSpace = false; + + return 1; +} + +//deallocates memory used by SearchStateSpace +void anaPlanner::DeleteSearchStateSpace(anaSearchStateSpace_t* pSearchStateSpace) +{ + if (pSearchStateSpace->heap != NULL) { + pSearchStateSpace->heap->makeemptyheap(); + delete pSearchStateSpace->heap; + pSearchStateSpace->heap = NULL; + } + + /* + if(pSearchStateSpace->inconslist != NULL) + { + pSearchStateSpace->inconslist->makeemptyheap(); + delete pSearchStateSpace->inconslist; + pSearchStateSpace->inconslist = NULL; + } + */ + + //delete the states themselves + int iend = (int)pSearchStateSpace->searchMDP.StateArray.size(); + for (int i = 0; i < iend; i++) { + CMDPSTATE* state = pSearchStateSpace->searchMDP.StateArray[i]; + if (state != NULL && state->PlannerSpecificData != NULL) { + DeleteSearchStateData((anaState*)state->PlannerSpecificData); + free((anaState*)state->PlannerSpecificData); + state->PlannerSpecificData = NULL; + } + } + pSearchStateSpace->searchMDP.Delete(); +} + +//reset properly search state space +//needs to be done before deleting states +int anaPlanner::ResetSearchStateSpace(anaSearchStateSpace_t* pSearchStateSpace) +{ + pSearchStateSpace->heap->makeemptyheap(); + // pSearchStateSpace->inconslist->makeemptyheap(); + + return 1; +} + +//initialization before each search +void anaPlanner::ReInitializeSearchStateSpace(anaSearchStateSpace_t* pSearchStateSpace) +{ + CKey key; + + //increase callnumber + pSearchStateSpace->callnumber++; + + //reset iteration + pSearchStateSpace->searchiteration = 0; + pSearchStateSpace->bNewSearchIteration = true; + pSearchStateSpace->G = INFINITECOST; + +#if DEBUG + fprintf(fDeb, "reinitializing search state-space (new call number=%d search iter=%d)\n", + pSearchStateSpace->callnumber,pSearchStateSpace->searchiteration ); +#endif + + pSearchStateSpace->heap->makeemptyheap(); + //pSearchStateSpace->inconslist->makeemptyheap(); + //reset + pSearchStateSpace->eps = this->finitial_eps; + pSearchStateSpace->eps_satisfied = INFINITECOST; + + //initialize start state + anaState* startstateinfo = (anaState*)(pSearchStateSpace->searchstartstate->PlannerSpecificData); + if (startstateinfo->callnumberaccessed != pSearchStateSpace->callnumber) { + ReInitializeSearchStateInfo( startstateinfo, pSearchStateSpace); + } + + startstateinfo->g = 0; + + //insert start state into the heap + + // CHANGED - long int cast removed + key.key[0] = (long)-get_e_value(pSearchStateSpace, startstateinfo->MDPstate->StateID); + + //key.key[1] = startstateinfo->h; + pSearchStateSpace->heap->insertheap(startstateinfo, key); + + pSearchStateSpace->bReinitializeSearchStateSpace = false; + pSearchStateSpace->bReevaluatefvals = false; +} + +//very first initialization +int anaPlanner::InitializeSearchStateSpace(anaSearchStateSpace_t* pSearchStateSpace) +{ + if (pSearchStateSpace->heap->currentsize != 0) { + throw SBPL_Exception("ERROR in InitializeSearchStateSpace: heap or list is not empty"); + } + + pSearchStateSpace->eps = this->finitial_eps; + pSearchStateSpace->eps_satisfied = INFINITECOST; + pSearchStateSpace->searchiteration = 0; + pSearchStateSpace->bNewSearchIteration = true; + pSearchStateSpace->callnumber = 0; + pSearchStateSpace->bReevaluatefvals = false; + + pSearchStateSpace->G = INFINITECOST; + + //create and set the search start state + pSearchStateSpace->searchgoalstate = NULL; + //pSearchStateSpace->searchstartstate = GetState(SearchStartStateID, pSearchStateSpace); + pSearchStateSpace->searchstartstate = NULL; + + pSearchStateSpace->bReinitializeSearchStateSpace = true; + + return 1; +} + +int anaPlanner::SetSearchGoalState(int SearchGoalStateID, anaSearchStateSpace_t* pSearchStateSpace) +{ + if (pSearchStateSpace->searchgoalstate == NULL || + pSearchStateSpace->searchgoalstate->StateID != SearchGoalStateID) + { + pSearchStateSpace->searchgoalstate = GetState(SearchGoalStateID, pSearchStateSpace); + + //should be new search iteration + pSearchStateSpace->eps_satisfied = INFINITECOST; + pSearchStateSpace->bNewSearchIteration = true; + pSearchStateSpace_->eps = this->finitial_eps; + + //recompute heuristic for the heap if heuristics is used +#if USE_HEUR + for(int i = 0; i < (int)pSearchStateSpace->searchMDP.StateArray.size(); i++) + { + CMDPSTATE* MDPstate = pSearchStateSpace->searchMDP.StateArray[i]; + anaState* state = (anaState*)MDPstate->PlannerSpecificData; + state->h = ComputeHeuristic(MDPstate, pSearchStateSpace); + } + + pSearchStateSpace->bReevaluatefvals = true; +#endif + } + + return 1; +} + +int anaPlanner::SetSearchStartState(int SearchStartStateID, anaSearchStateSpace_t* pSearchStateSpace) +{ + CMDPSTATE* MDPstate = GetState(SearchStartStateID, pSearchStateSpace); + + if (MDPstate != pSearchStateSpace->searchstartstate) { + pSearchStateSpace->searchstartstate = MDPstate; + pSearchStateSpace->bReinitializeSearchStateSpace = true; + } + + return 1; +} + +int anaPlanner::ReconstructPath(anaSearchStateSpace_t* pSearchStateSpace) +{ + if (bforwardsearch) //nothing to do, if search is backward + { + CMDPSTATE* MDPstate = pSearchStateSpace->searchgoalstate; + CMDPSTATE* PredMDPstate; + anaState *predstateinfo, *stateinfo; + +#if DEBUG + fprintf(fDeb, "reconstructing a path:\n"); +#endif + + while (MDPstate != pSearchStateSpace->searchstartstate) { + stateinfo = (anaState*)MDPstate->PlannerSpecificData; + +#if DEBUG + PrintSearchState(stateinfo, fDeb); +#endif + if (stateinfo->g == INFINITECOST) { + //printf("ERROR in ReconstructPath: g of the state on the path is INFINITE\n"); + //exit(1); + return -1; + } + + if (stateinfo->bestpredstate == NULL) { + throw SBPL_Exception("ERROR in ReconstructPath: bestpred is NULL"); + } + + //get the parent state + PredMDPstate = stateinfo->bestpredstate; + predstateinfo = (anaState*)PredMDPstate->PlannerSpecificData; + + //set its best next info + predstateinfo->bestnextstate = MDPstate; + + //check the decrease of g-values along the path + if (predstateinfo->v >= stateinfo->g) { + const char* msg = "ERROR in ReconstructPath: g-values are non-decreasing"; + SBPL_ERROR("%s\n", msg); + PrintSearchState(predstateinfo, fDeb); + throw SBPL_Exception(msg); + } + + //transition back + MDPstate = PredMDPstate; + } + } + + return 1; +} + +void anaPlanner::PrintSearchPath(anaSearchStateSpace_t* pSearchStateSpace, FILE* fOut) +{ + anaState* searchstateinfo; + CMDPSTATE* state; + int goalID; + int PathCost; + + if (bforwardsearch) { + state = pSearchStateSpace->searchstartstate; + goalID = pSearchStateSpace->searchgoalstate->StateID; + } + else { + state = pSearchStateSpace->searchgoalstate; + goalID = pSearchStateSpace->searchstartstate->StateID; + } + if (fOut == NULL) fOut = stdout; + + PathCost = ((anaState*)pSearchStateSpace->searchgoalstate->PlannerSpecificData)->g; + + fprintf(fOut, "Printing a path from state %d to the goal state %d\n", state->StateID, + pSearchStateSpace->searchgoalstate->StateID); + fprintf(fOut, "Path cost = %d:\n", PathCost); + + environment_->PrintState(state->StateID, false, fOut); + + int costFromStart = 0; + while (state->StateID != goalID) { + fprintf(fOut, "state %d ", state->StateID); + + if (state->PlannerSpecificData == NULL) { + fprintf(fOut, "path does not exist since search data does not exist\n"); + break; + } + + searchstateinfo = (anaState*)state->PlannerSpecificData; + + if (searchstateinfo->bestnextstate == NULL) { + fprintf(fOut, "path does not exist since bestnextstate == NULL\n"); + break; + } + if (searchstateinfo->g == INFINITECOST) { + fprintf(fOut, "path does not exist since bestnextstate == NULL\n"); + break; + } + + int costToGoal = PathCost - costFromStart; + int transcost = searchstateinfo->g - ((anaState*)(searchstateinfo->bestnextstate->PlannerSpecificData))->v; + if (bforwardsearch) transcost = -transcost; + + costFromStart += transcost; + + fprintf(fOut, "g=%d-->state %d, h = %d ctg = %d ", searchstateinfo->g, + searchstateinfo->bestnextstate->StateID, searchstateinfo->h, costToGoal); + + state = searchstateinfo->bestnextstate; + + environment_->PrintState(state->StateID, false, fOut); + } +} + +void anaPlanner::PrintSearchState(anaState* state, FILE* fOut) +{ + fprintf(fOut, "state %d: h=%d g=%u v=%u iterc=%d callnuma=%d expands=%d heapind=%d inconslist=%d\n", + state->MDPstate->StateID, state->h, state->g, state->v, state->iterationclosed, state->callnumberaccessed, + state->numofexpands, state->heapindex, state->listelem[ana_INCONS_LIST_ID] ? 1 : 0); + environment_->PrintState(state->MDPstate->StateID, true, fOut); +} + +int anaPlanner::getHeurValue(anaSearchStateSpace_t* pSearchStateSpace, int StateID) +{ + CMDPSTATE* MDPstate = GetState(StateID, pSearchStateSpace); + anaState* searchstateinfo = (anaState*)MDPstate->PlannerSpecificData; + return searchstateinfo->h; +} + +vector anaPlanner::GetSearchPath(anaSearchStateSpace_t* pSearchStateSpace, int& solcost) +{ + vector SuccIDV; + vector CostV; + vector wholePathIds; + anaState* searchstateinfo; + CMDPSTATE* state = NULL; + CMDPSTATE* goalstate = NULL; + CMDPSTATE* startstate = NULL; + + if (bforwardsearch) { + startstate = pSearchStateSpace->searchstartstate; + goalstate = pSearchStateSpace->searchgoalstate; + + //reconstruct the path by setting bestnextstate pointers appropriately + ReconstructPath(pSearchStateSpace); + } + else { + startstate = pSearchStateSpace->searchgoalstate; + goalstate = pSearchStateSpace->searchstartstate; + } + + state = startstate; + + wholePathIds.push_back(state->StateID); + solcost = 0; + + FILE* fOut = stdout; + while (state->StateID != goalstate->StateID) { + if (state->PlannerSpecificData == NULL) { + fprintf(fOut, "path does not exist since search data does not exist\n"); + break; + } + + searchstateinfo = (anaState*)state->PlannerSpecificData; + + if (searchstateinfo->bestnextstate == NULL) { + fprintf(fOut, "path does not exist since bestnextstate == NULL\n"); + break; + } + if (searchstateinfo->g == INFINITECOST) { + fprintf(fOut, "path does not exist since bestnextstate == NULL\n"); + break; + } + + environment_->GetSuccs(state->StateID, &SuccIDV, &CostV); + int actioncost = INFINITECOST; + for (int i = 0; i < (int)SuccIDV.size(); i++) { + + if (SuccIDV.at(i) == searchstateinfo->bestnextstate->StateID) actioncost = CostV.at(i); + + } + if (actioncost == INFINITECOST) printf("WARNING: actioncost = %d\n", actioncost); + + solcost += actioncost; + + //fprintf(fDeb, "actioncost=%d between states %d and %d\n", + // actioncost, state->StateID, searchstateinfo->bestnextstate->StateID); + //environment_->PrintState(state->StateID, false, fDeb); + //environment_->PrintState(searchstateinfo->bestnextstate->StateID, false, fDeb); + +#if DEBUG + anaState* nextstateinfo = (anaState*)(searchstateinfo->bestnextstate->PlannerSpecificData); + if(actioncost != abs((int)(searchstateinfo->g - nextstateinfo->g)) && pSearchStateSpace->eps_satisfied <= 1.001) + { + fprintf(fDeb, "ERROR: actioncost=%d is not matching the difference in g-values of %d\n", + actioncost, abs((int)(searchstateinfo->g - nextstateinfo->g))); + printf("ERROR: actioncost=%d is not matching the difference in g-values of %d\n", + actioncost,abs((int)(searchstateinfo->g - nextstateinfo->g))); + PrintSearchState(searchstateinfo, fDeb); + PrintSearchState(nextstateinfo, fDeb); + } +#endif + + state = searchstateinfo->bestnextstate; + + wholePathIds.push_back(state->StateID); + } + + return wholePathIds; +} + +bool anaPlanner::Search(anaSearchStateSpace_t* pSearchStateSpace, vector& pathIds, int & PathCost, + bool bFirstSolution, bool bOptimalSolution, double MaxNumofSecs) +{ + TimeStarted = clock(); + searchexpands = 0; + +#if DEBUG + fprintf(fDeb, "new search call (call number=%d)\n", pSearchStateSpace->callnumber); +#endif + + if (pSearchStateSpace->bReinitializeSearchStateSpace == true) { + //re-initialize state space + ReInitializeSearchStateSpace(pSearchStateSpace); + } + + if (bOptimalSolution) { + pSearchStateSpace->eps = 1; + MaxNumofSecs = INFINITECOST; + } + else if (bFirstSolution) { + MaxNumofSecs = INFINITECOST; + } + + //ensure heuristics are up-to-date + environment_->EnsureHeuristicsUpdated((bforwardsearch == true)); + + //the main loop of ana* + int prevexpands = 0; + clock_t loop_time; + + // CHANGE MADE TO WHILE LOOP to account for open.empty() == FALSE + while (!pSearchStateSpace->heap->emptyheap() && pSearchStateSpace->eps_satisfied > ana_FINAL_EPS && + (clock() - TimeStarted) < MaxNumofSecs * (double)CLOCKS_PER_SEC) + { + loop_time = clock(); + //decrease eps for all subsequent iterations + /*if(fabs(pSearchStateSpace->eps_satisfied - pSearchStateSpace->eps) < ERR_EPS && !bFirstSolution) + { + pSearchStateSpace->eps = pSearchStateSpace->eps - ana_DECREASE_EPS; + if(pSearchStateSpace->eps < ana_FINAL_EPS) + pSearchStateSpace->eps = ana_FINAL_EPS; + + //the priorities need to be updated + pSearchStateSpace->bReevaluatefvals = true; + + //it will be a new search + pSearchStateSpace->bNewSearchIteration = true; + + //build a new open list by merging it with incons one + BuildNewOPENList(pSearchStateSpace); + + }*/ + + pSearchStateSpace->searchiteration++; + pSearchStateSpace->bNewSearchIteration = false; + + //re-compute f-values if necessary and reorder the heap + //if(pSearchStateSpace->bReevaluatefvals) + // Reevaluatefvals(pSearchStateSpace); + + //improve or compute path + int retVal = ImprovePath(pSearchStateSpace, MaxNumofSecs); + anaState* state; + CKey key; + CHeap* open = pSearchStateSpace->heap; + //printf("states expanded: %d\t states considered: %d\t time elapsed: %f\n",searchexpands - prevexpands, pSearchStateSpace->heap->currentsize, double(clock() - TimeStarted)/CLOCKS_PER_SEC); + + double epsprime = 1.0; + for (int j = 1; j <= open->currentsize;) { + state = (anaState*)open->heap[j].heapstate; + double temp_eps = (double)((pSearchStateSpace->G * 1.0) / (double)(state->g + state->h)); + if (temp_eps > epsprime) { + epsprime = temp_eps; + } + double e_val = get_e_value(pSearchStateSpace, state->MDPstate->StateID); + if (e_val <= 1.0) { + + open->deleteheap_unsafe(state); + + } + else { + key.key[0] = (long)-e_val; + + open->updateheap_unsafe(state, key); + ++j; + } + pSearchStateSpace->eps_satisfied = epsprime; + } + open->makeheap(); + + //print the solution cost and eps bound + if (retVal == 1) { + //printf("suboptimality=%f expands=%d g(searchgoal)=%d loop_time=%.3f time_elapsed=%.3f memoryCounter=%d\n", pSearchStateSpace->eps_satisfied, searchexpands - prevexpands, ((anaState*)pSearchStateSpace->searchgoalstate->PlannerSpecificData)->g,double(clock()-loop_time)/CLOCKS_PER_SEC, double(clock() - TimeStarted)/CLOCKS_PER_SEC, MaxMemoryCounter); + + printf("suboptimality=%f g(searchgoal)=%d time_elapsed=%.3f memoryCounter=%d\n", + pSearchStateSpace->eps_satisfied, + ((anaState*)pSearchStateSpace->searchgoalstate->PlannerSpecificData)->g, double(clock() + - TimeStarted) / CLOCKS_PER_SEC, MaxMemoryCounter); + + //printf("states expanded: %d\t states considered: %d\t time elapsed: %f\n",searchexpands - prevexpands, pSearchStateSpace->heap->currentsize, double(clock() - TimeStarted)/CLOCKS_PER_SEC); + } + +#if DEBUG + fprintf(fDeb, "eps=%f expands=%d g(searchgoal)=%d time=%.3f\n", pSearchStateSpace->eps_satisfied, searchexpands - prevexpands, + ((anaState*)pSearchStateSpace->searchgoalstate->PlannerSpecificData)->g,double(clock()-loop_time)/CLOCKS_PER_SEC); + PrintSearchState((anaState*)pSearchStateSpace->searchgoalstate->PlannerSpecificData, fDeb); +#endif + prevexpands = searchexpands; + + //if just the first solution then we are done + if (bFirstSolution) break; + + //no solution exists + if (((anaState*)pSearchStateSpace->searchgoalstate->PlannerSpecificData)->g == INFINITECOST) break; + } + +#if DEBUG + fflush(fDeb); +#endif + + printf("Suboptimality = %.4f\n", pSearchStateSpace->eps_satisfied); + + PathCost = ((anaState*)pSearchStateSpace->searchgoalstate->PlannerSpecificData)->g; + MaxMemoryCounter += environment_->StateID2IndexMapping.size() * sizeof(int); + + printf("MaxMemoryCounter = %d\n", MaxMemoryCounter); + + int solcost = INFINITECOST; + bool ret = false; + if (PathCost == INFINITECOST) { + printf("could not find a solution\n"); + ret = false; + } + else { + printf("solution is found\n"); + pathIds = GetSearchPath(pSearchStateSpace, solcost); + ret = true; + } + + printf("total expands this call = %d, planning time = %.3f secs, solution cost=%d\n", searchexpands, (clock() + - TimeStarted) / ((double)CLOCKS_PER_SEC), solcost); + + //fprintf(fStat, "%d %d\n", searchexpands, solcost); + + return ret; +} + +//-----------------------------Interface function----------------------------------------------------- + +//returns 1 if found a solution, and 0 otherwise +int anaPlanner::replan(double allocated_time_secs, vector* solution_stateIDs_V) +{ + int solcost; + + return replan(allocated_time_secs, solution_stateIDs_V, &solcost); +} + +//returns 1 if found a solution, and 0 otherwise +int anaPlanner::replan(double allocated_time_secs, vector* solution_stateIDs_V, int* psolcost) +{ + vector pathIds; + bool bFound = false; + int PathCost; + //bool bFirstSolution = true; + bool bFirstSolution = this->bsearchuntilfirstsolution; + bool bOptimalSolution = false; + *psolcost = 0; + + printf("planner: replan called (bFirstSol=%d, bOptSol=%d)\n", bFirstSolution, bOptimalSolution); + + //plan + bFound = Search(pSearchStateSpace_, pathIds, PathCost, bFirstSolution, bOptimalSolution, allocated_time_secs); + if (!bFound) + { + printf("failed to find a solution\n"); + } + + //copy the solution + *solution_stateIDs_V = pathIds; + *psolcost = PathCost; + + return (int)bFound; + +} + +int anaPlanner::set_goal(int goal_stateID) +{ + printf("planner: setting goal to %d\n", goal_stateID); + environment_->PrintState(goal_stateID, true, stdout); + + if (bforwardsearch) { + if (SetSearchGoalState(goal_stateID, pSearchStateSpace_) != 1) { + printf("ERROR: failed to set search goal state\n"); + return 0; + } + } + else { + if (SetSearchStartState(goal_stateID, pSearchStateSpace_) != 1) { + printf("ERROR: failed to set search start state\n"); + return 0; + } + } + + return 1; +} + +int anaPlanner::set_start(int start_stateID) +{ + printf("planner: setting start to %d\n", start_stateID); + environment_->PrintState(start_stateID, true, stdout); + + if (bforwardsearch) { + + if (SetSearchStartState(start_stateID, pSearchStateSpace_) != 1) { + printf("ERROR: failed to set search start state\n"); + return 0; + } + } + else { + if (SetSearchGoalState(start_stateID, pSearchStateSpace_) != 1) { + printf("ERROR: failed to set search goal state\n"); + return 0; + } + } + + return 1; +} + +void anaPlanner::costs_changed(StateChangeQuery const & stateChange) +{ + pSearchStateSpace_->bReinitializeSearchStateSpace = true; +} + +void anaPlanner::costs_changed() +{ + pSearchStateSpace_->bReinitializeSearchStateSpace = true; +} + +int anaPlanner::force_planning_from_scratch() +{ + printf("planner: forceplanfromscratch set\n"); + + pSearchStateSpace_->bReinitializeSearchStateSpace = true; + + return 1; +} + +int anaPlanner::set_search_mode(bool bSearchUntilFirstSolution) +{ + printf("planner: search mode set to %d\n", bSearchUntilFirstSolution); + + bsearchuntilfirstsolution = bSearchUntilFirstSolution; + + return 1; +} + +void anaPlanner::print_searchpath(FILE* fOut) +{ + PrintSearchPath(pSearchStateSpace_, fOut); +} + +//--------------------------------------------------------------------------------------------------------- diff --git a/navigations/sbpl/src/planners/adplanner.cpp b/navigations/sbpl/src/planners/adplanner.cpp new file mode 100755 index 0000000..e32f0b4 --- /dev/null +++ b/navigations/sbpl/src/planners/adplanner.cpp @@ -0,0 +1,1470 @@ +/* + * Copyright (c) 2008, Maxim Likhachev + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Carnegie Mellon University nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include + +#include +#include +#include +#include +#include + +using namespace std; + +//----------------------------------------------------------------------------------------------------- + +ADPlanner::ADPlanner(DiscreteSpaceInformation* environment, bool bForwardSearch) +{ + environment_ = environment; + + bforwardsearch = bForwardSearch; + + bsearchuntilfirstsolution = false; + finitial_eps = AD_DEFAULT_INITIAL_EPS; + final_epsilon = AD_FINAL_EPS; + dec_eps = AD_DECREASE_EPS; + use_repair_time = false; + repair_time = INFINITECOST; + searchexpands = 0; + MaxMemoryCounter = 0; + +#ifndef ROS + const char* debug = "debug.txt"; +#endif + fDeb = SBPL_FOPEN(debug, "w"); + if (fDeb == NULL) { + throw SBPL_Exception("ERROR: could not open planner debug file"); + } + SBPL_PRINTF("debug on\n"); + + pSearchStateSpace_ = new ADSearchStateSpace_t; + + //create the AD planner + if (CreateSearchStateSpace(pSearchStateSpace_) != 1) { + SBPL_ERROR("ERROR: failed to create statespace\n"); + return; + } + + //set the start and goal states + if (InitializeSearchStateSpace(pSearchStateSpace_) != 1) { + SBPL_ERROR("ERROR: failed to create statespace\n"); + return; + } + + finitial_eps_planning_time = -1.0; + final_eps_planning_time = -1.0; + num_of_expands_initial_solution = 0; + final_eps = -1.0; +} + +ADPlanner::~ADPlanner() +{ + //delete the statespace + DeleteSearchStateSpace( pSearchStateSpace_); + delete pSearchStateSpace_; + + SBPL_FCLOSE( fDeb); +} + +void ADPlanner::Initialize_searchinfo(CMDPSTATE* state, ADSearchStateSpace_t* pSearchStateSpace) +{ + ADState* searchstateinfo = (ADState*)state->PlannerSpecificData; + + searchstateinfo->MDPstate = state; + InitializeSearchStateInfo(searchstateinfo, pSearchStateSpace); +} + +CMDPSTATE* ADPlanner::CreateState(int stateID, ADSearchStateSpace_t* pSearchStateSpace) +{ + CMDPSTATE* state = NULL; + +#if DEBUG + if (environment_->StateID2IndexMapping[stateID][ADMDP_STATEID2IND] != -1) { + throw SBPL_Exception("ERROR in CreateState: state already created"); + } +#endif + + //adds to the tail a state + state = pSearchStateSpace->searchMDP.AddState(stateID); + + //remember the index of the state + environment_->StateID2IndexMapping[stateID][ADMDP_STATEID2IND] = pSearchStateSpace->searchMDP.StateArray.size() - 1; + +#if DEBUG + if (state != + pSearchStateSpace->searchMDP.StateArray[environment_->StateID2IndexMapping[stateID][ADMDP_STATEID2IND]]) + { + throw SBPL_Exception("ERROR in CreateState: invalid state index"); + } +#endif + + //create search specific info + state->PlannerSpecificData = (ADState*)malloc(sizeof(ADState)); + Initialize_searchinfo(state, pSearchStateSpace); + MaxMemoryCounter += sizeof(ADState); + + return state; +} + +CMDPSTATE* ADPlanner::GetState(int stateID, ADSearchStateSpace_t* pSearchStateSpace) +{ + if (stateID >= (int)environment_->StateID2IndexMapping.size()) { + throw SBPL_Exception("ERROR in GetState: stateID is invalid"); + } + + if (environment_->StateID2IndexMapping[stateID][ADMDP_STATEID2IND] == -1) + return CreateState(stateID, pSearchStateSpace); + else + return pSearchStateSpace->searchMDP.StateArray[environment_->StateID2IndexMapping[stateID][ADMDP_STATEID2IND]]; +} + +//----------------------------------------------------------------------------------------------------- + +CKey ADPlanner::ComputeKey(ADState* state) +{ + CKey key; + + if (state->v >= state->g) { + key.key[0] = state->g + (int)(pSearchStateSpace_->eps * state->h); + key.key[1] = 1; + } + else { + key.key[0] = state->v + state->h; + key.key[1] = 0; + } + + return key; +} + +int ADPlanner::ComputeHeuristic(CMDPSTATE* MDPstate, ADSearchStateSpace_t* pSearchStateSpace) +{ + //compute heuristic for search + if (bforwardsearch) { +#if MEM_CHECK == 1 + //int WasEn = DisableMemCheck(); +#endif + + //forward search: heur = distance from state to searchgoal which is Goal ADState + int retv = environment_->GetGoalHeuristic(MDPstate->StateID); + +#if MEM_CHECK == 1 + //if (WasEn) + // EnableMemCheck(); +#endif + + return retv; + } + else { + //backward search: heur = distance from searchgoal to state + return environment_->GetStartHeuristic(MDPstate->StateID); + } +} + +//initialization of a state +void ADPlanner::InitializeSearchStateInfo(ADState* state, ADSearchStateSpace_t* pSearchStateSpace) +{ + state->g = INFINITECOST; + state->v = INFINITECOST; + state->iterationclosed = 0; + state->callnumberaccessed = pSearchStateSpace->callnumber; + state->bestnextstate = NULL; + state->costtobestnextstate = INFINITECOST; + state->heapindex = 0; + state->listelem[AD_INCONS_LIST_ID] = NULL; +#if DEBUG + state->numofexpands = 0; +#endif + state->bestpredstate = NULL; + + //compute heuristics +#if USE_HEUR + if(pSearchStateSpace->searchgoalstate != NULL) + state->h = ComputeHeuristic(state->MDPstate, pSearchStateSpace); + else + state->h = 0; +#else + state->h = 0; +#endif +} + +//re-initialization of a state +void ADPlanner::ReInitializeSearchStateInfo(ADState* state, ADSearchStateSpace_t* pSearchStateSpace) +{ + state->g = INFINITECOST; + state->v = INFINITECOST; + state->iterationclosed = 0; + state->callnumberaccessed = pSearchStateSpace->callnumber; + state->bestnextstate = NULL; + state->costtobestnextstate = INFINITECOST; + state->heapindex = 0; + state->listelem[AD_INCONS_LIST_ID] = NULL; +#if DEBUG + state->numofexpands = 0; +#endif + state->bestpredstate = NULL; + + //compute heuristics +#if USE_HEUR + if(pSearchStateSpace->searchgoalstate != NULL) + { + state->h = ComputeHeuristic(state->MDPstate, pSearchStateSpace); + } + else + state->h = 0; +#else + state->h = 0; +#endif +} + +void ADPlanner::DeleteSearchStateData(ADState* state) +{ + //no memory was allocated + MaxMemoryCounter = 0; + return; +} + +void ADPlanner::UpdateSetMembership(ADState* state) +{ + CKey key; + + if (state->v != state->g) { + if (state->iterationclosed != pSearchStateSpace_->searchiteration) { + key = ComputeKey(state); + if (state->heapindex == 0) { + //need to remove it because it can happen when updating edge costs and state is in incons + if (state->listelem[AD_INCONS_LIST_ID] != NULL) { + pSearchStateSpace_->inconslist->remove(state, AD_INCONS_LIST_ID); + } + + pSearchStateSpace_->heap->insertheap(state, key); + + } + else + pSearchStateSpace_->heap->updateheap(state, key); + } + else if (state->listelem[AD_INCONS_LIST_ID] == NULL) { + pSearchStateSpace_->inconslist->insert(state, AD_INCONS_LIST_ID); + } + } + else { + if (state->heapindex != 0) + pSearchStateSpace_->heap->deleteheap(state); + else if (state->listelem[AD_INCONS_LIST_ID] != NULL) { + pSearchStateSpace_->inconslist->remove(state, AD_INCONS_LIST_ID); + } + } +} + +void ADPlanner::Recomputegval(ADState* state) +{ + vector searchpredsIDV; //these are predecessors if search is done forward and successors otherwise + vector costV; + CKey key; + ADState *searchpredstate; + + if (bforwardsearch) + environment_->GetPreds(state->MDPstate->StateID, &searchpredsIDV, &costV); + else + environment_->GetSuccs(state->MDPstate->StateID, &searchpredsIDV, &costV); + + //iterate through predecessors of s and pick the best + state->g = INFINITECOST; + for (int pind = 0; pind < (int)searchpredsIDV.size(); pind++) { + //skip the states that do not exist - they can not be used to improve g-value anyway + if (environment_->StateID2IndexMapping[searchpredsIDV[pind]][ADMDP_STATEID2IND] == -1) continue; + + CMDPSTATE* predMDPState = GetState(searchpredsIDV[pind], pSearchStateSpace_); + int cost = costV[pind]; + searchpredstate = (ADState*)(predMDPState->PlannerSpecificData); + + //see if it can be used to improve + if (searchpredstate->callnumberaccessed == pSearchStateSpace_->callnumber && state->g > searchpredstate->v + + cost) { + if (bforwardsearch) { + state->g = searchpredstate->v + cost; + state->bestpredstate = predMDPState; + } + else { + state->g = searchpredstate->v + cost; + state->bestnextstate = predMDPState; + state->costtobestnextstate = cost; + } + } + } //over preds +} + +//used for backward search +void ADPlanner::UpdatePredsofOverconsState(ADState* state, ADSearchStateSpace_t* pSearchStateSpace) +{ + vector PredIDV; + vector CostV; + CKey key; + ADState *predstate; + + environment_->GetPreds(state->MDPstate->StateID, &PredIDV, &CostV); + + //iterate through predecessors of s + for (int pind = 0; pind < (int)PredIDV.size(); pind++) { + CMDPSTATE* PredMDPState = GetState(PredIDV[pind], pSearchStateSpace); + predstate = (ADState*)(PredMDPState->PlannerSpecificData); + if (predstate->callnumberaccessed != pSearchStateSpace->callnumber) { + ReInitializeSearchStateInfo(predstate, pSearchStateSpace); + } + + //see if we can improve the value of predstate + if (predstate->g > state->v + CostV[pind]) { +#if DEBUG + if (predstate->MDPstate->StateID == 679256) { + SBPL_FPRINTF(fDeb, "updating pred %d of overcons exp\n", predstate->MDPstate->StateID); + PrintSearchState(predstate, fDeb); + SBPL_FPRINTF(fDeb, "\n"); + } +#endif + + predstate->g = state->v + CostV[pind]; + predstate->bestnextstate = state->MDPstate; + predstate->costtobestnextstate = CostV[pind]; + + //update set membership + UpdateSetMembership(predstate); + +#if DEBUG + if (predstate->MDPstate->StateID == 679256) { + SBPL_FPRINTF(fDeb, "updated pred %d of overcons exp\n", predstate->MDPstate->StateID); + PrintSearchState(predstate, fDeb); + SBPL_FPRINTF(fDeb, "\n"); + } +#endif + } + } //for predecessors +} + +//used for forward search +void ADPlanner::UpdateSuccsofOverconsState(ADState* state, ADSearchStateSpace_t* pSearchStateSpace) +{ + vector SuccIDV; + vector CostV; + CKey key; + ADState *succstate; + + environment_->GetSuccs(state->MDPstate->StateID, &SuccIDV, &CostV); + + //iterate through predecessors of s + for (int sind = 0; sind < (int)SuccIDV.size(); sind++) { + CMDPSTATE* SuccMDPState = GetState(SuccIDV[sind], pSearchStateSpace); + int cost = CostV[sind]; + + succstate = (ADState*)(SuccMDPState->PlannerSpecificData); + if (succstate->callnumberaccessed != pSearchStateSpace->callnumber) { + ReInitializeSearchStateInfo(succstate, pSearchStateSpace); + } + + //see if we can improve the value of succstate + //taking into account the cost of action + if (succstate->g > state->v + cost) { + succstate->g = state->v + cost; + succstate->bestpredstate = state->MDPstate; + + //update set membership + UpdateSetMembership(succstate); + } //check for cost improvement + } //for actions +} + +//used for backward search +void ADPlanner::UpdatePredsofUnderconsState(ADState* state, ADSearchStateSpace_t* pSearchStateSpace) +{ + vector PredIDV; + vector CostV; + CKey key; + ADState *predstate; + + environment_->GetPreds(state->MDPstate->StateID, &PredIDV, &CostV); + + //iterate through predecessors of s + for (int pind = 0; pind < (int)PredIDV.size(); pind++) { + + CMDPSTATE* PredMDPState = GetState(PredIDV[pind], pSearchStateSpace); + predstate = (ADState*)(PredMDPState->PlannerSpecificData); + if (predstate->callnumberaccessed != pSearchStateSpace->callnumber) { + ReInitializeSearchStateInfo(predstate, pSearchStateSpace); + } + + if (predstate->bestnextstate == state->MDPstate) { + Recomputegval(predstate); + UpdateSetMembership(predstate); + +#if DEBUG + if(predstate->MDPstate->StateID == 679256) + { + SBPL_FPRINTF(fDeb, "updated pred %d of undercons exp\n", predstate->MDPstate->StateID); + PrintSearchState(predstate, fDeb); + SBPL_FPRINTF(fDeb, "\n"); + } +#endif + } + } //for predecessors +} + +//used for forward search +void ADPlanner::UpdateSuccsofUnderconsState(ADState* state, ADSearchStateSpace_t* pSearchStateSpace) +{ + vector SuccIDV; + vector CostV; + CKey key; + ADState *succstate; + + environment_->GetSuccs(state->MDPstate->StateID, &SuccIDV, &CostV); + + //iterate through predecessors of s + for (int sind = 0; sind < (int)SuccIDV.size(); sind++) { + CMDPSTATE* SuccMDPState = GetState(SuccIDV[sind], pSearchStateSpace); + succstate = (ADState*)(SuccMDPState->PlannerSpecificData); + + if (succstate->callnumberaccessed != pSearchStateSpace->callnumber) { + ReInitializeSearchStateInfo(succstate, pSearchStateSpace); + } + + if (succstate->bestpredstate == state->MDPstate) { + Recomputegval(succstate); + UpdateSetMembership(succstate); + } + } //for actions +} + +int ADPlanner::GetGVal(int StateID, ADSearchStateSpace_t* pSearchStateSpace) +{ + CMDPSTATE* cmdp_state = GetState(StateID, pSearchStateSpace); + ADState* state = (ADState*)cmdp_state->PlannerSpecificData; + return state->g; +} + +//returns 1 if the solution is found, 0 if the solution does not exist and 2 if it ran out of time +int ADPlanner::ComputePath(ADSearchStateSpace_t* pSearchStateSpace, double MaxNumofSecs) +{ + int expands; + ADState *state, *searchgoalstate; + CKey key, minkey; + CKey goalkey; + + expands = 0; + + if (pSearchStateSpace->searchgoalstate == NULL) { + throw SBPL_Exception("ERROR searching: no goal state is set"); + } + + //goal state + searchgoalstate = (ADState*)(pSearchStateSpace->searchgoalstate->PlannerSpecificData); + if (searchgoalstate->callnumberaccessed != pSearchStateSpace->callnumber) { + ReInitializeSearchStateInfo( searchgoalstate, pSearchStateSpace); + } + + //set goal key + goalkey = ComputeKey(searchgoalstate); + + //expand states until done + minkey = pSearchStateSpace->heap->getminkeyheap(); + CKey oldkey = minkey; + while (!pSearchStateSpace->heap->emptyheap() && minkey.key[0] < INFINITECOST && + (goalkey > minkey || searchgoalstate->g > searchgoalstate->v) && + (clock() - TimeStarted) < MaxNumofSecs * (double)CLOCKS_PER_SEC && + (pSearchStateSpace->eps_satisfied == INFINITECOST || + (clock() - TimeStarted) < repair_time * (double)CLOCKS_PER_SEC)) + { + //get the state + state = (ADState*)pSearchStateSpace->heap->deleteminheap(); + +#if DEBUG + CKey debkey = ComputeKey(state); + //SBPL_FPRINTF(fDeb, "expanding state(%d): g=%u v=%u h=%d key=[%d %d] iterc=%d callnuma=%d expands=%d (g(goal)=%u)\n", + // state->MDPstate->StateID, state->g, state->v, state->h, (int)debkey[0], (int)debkey[1], + // state->iterationclosed, state->callnumberaccessed, state->numofexpands, searchgoalstate->g); + if (state->MDPstate->StateID == 679256) { + SBPL_FPRINTF(fDeb, "expanding state %d with key=[%d %d]:\n", + state->MDPstate->StateID, (int)debkey[0], (int)debkey[1]); + PrintSearchState(state, fDeb); + environment_->PrintState(state->MDPstate->StateID, true, fDeb); + } + //SBPL_FFLUSH(fDeb); + if (state->listelem[AD_INCONS_LIST_ID] != NULL) { + throw SBPL_Exception("ERROR: expanding state from INCONS list"); + } +#endif + +#if DEBUG + if (minkey.key[0] < oldkey.key[0] && fabs(this->finitial_eps - 1.0) < ERR_EPS) { + SBPL_PRINTF("WARN in search: the sequence of keys decreases in an optimal search\n"); + //throw SBPL_Exception("WARN in search: the sequence of keys decreases in an optimal search"); + } + oldkey = minkey; +#endif + + if (state->v == state->g) { + throw SBPL_Exception("ERROR: consistent state is being expanded"); + } + + //new expand + expands++; +#if DEBUG + state->numofexpands++; +#endif + + if (state->v > state->g) { + //overconsistent expansion + + //recompute state value + state->v = state->g; + state->iterationclosed = pSearchStateSpace->searchiteration; + + if (!bforwardsearch) { + UpdatePredsofOverconsState(state, pSearchStateSpace); + } + else { + UpdateSuccsofOverconsState(state, pSearchStateSpace); + } + } + else { + //underconsistent expansion + + //force the state to be overconsistent + state->v = INFINITECOST; + + //update state membership + UpdateSetMembership(state); + + if (!bforwardsearch) { + UpdatePredsofUnderconsState(state, pSearchStateSpace); + } + else + UpdateSuccsofUnderconsState(state, pSearchStateSpace); + + } + + //recompute minkey + minkey = pSearchStateSpace->heap->getminkeyheap(); + + //recompute goalkey if necessary + goalkey = ComputeKey(searchgoalstate); + + if (expands % 100000 == 0 && expands > 0) { + SBPL_PRINTF("expands so far=%u\n", expands); + } + } + + int retv = 1; + if (searchgoalstate->g == INFINITECOST && pSearchStateSpace->heap->emptyheap()) { + SBPL_PRINTF("solution does not exist: search exited because heap is empty\n"); + +#if DEBUG + SBPL_FPRINTF(fDeb, "solution does not exist: search exited because heap is empty\n"); +#endif + + retv = 0; + } + else if (!pSearchStateSpace->heap->emptyheap() && (goalkey > minkey || searchgoalstate->g > searchgoalstate->v)) { + SBPL_PRINTF("search exited because it ran out of time\n"); +#if DEBUG + SBPL_FPRINTF(fDeb, "search exited because it ran out of time\n"); +#endif + retv = 2; + } + else if (searchgoalstate->g == INFINITECOST && !pSearchStateSpace->heap->emptyheap()) { + SBPL_PRINTF("solution does not exist: search exited because all candidates for expansion have infinite " + "heuristics\n"); +#if DEBUG + SBPL_FPRINTF(fDeb, "solution does not exist: search exited because all candidates for expansion have infinite " + "heuristics\n"); +#endif + retv = 0; + } + else { + SBPL_PRINTF("search exited with a solution for eps=%.3f\n", pSearchStateSpace->eps); +#if DEBUG + SBPL_FPRINTF(fDeb, "search exited with a solution for eps=%.3f\n", pSearchStateSpace->eps); +#endif + retv = 1; + } + + //SBPL_FPRINTF(fDeb, "expanded=%d\n", expands); + + searchexpands += expands; + + return retv; +} + +void ADPlanner::BuildNewOPENList(ADSearchStateSpace_t* pSearchStateSpace) +{ + ADState *state; + CKey key; + CHeap* pheap = pSearchStateSpace->heap; + CList* pinconslist = pSearchStateSpace->inconslist; + + //move incons into open + while (pinconslist->firstelement != NULL) { + state = (ADState*)pinconslist->firstelement->liststate; + + //compute f-value + key = ComputeKey(state); + + //insert into OPEN + if (state->heapindex == 0) + pheap->insertheap(state, key); + else + pheap->updateheap(state, key); //should never happen, but sometimes it does - somewhere there is a bug TODO + //remove from INCONS + pinconslist->remove(state, AD_INCONS_LIST_ID); + } + + pSearchStateSpace->bRebuildOpenList = false; +} + +void ADPlanner::Reevaluatefvals(ADSearchStateSpace_t* pSearchStateSpace) +{ + CKey key; + int i; + CHeap* pheap = pSearchStateSpace->heap; + +#if DEBUG + SBPL_FPRINTF(fDeb, "re-computing heap priorities\n"); +#endif + + //recompute priorities for states in OPEN and reorder it + for (i = 1; i <= pheap->currentsize; ++i) { + ADState* state = (ADState*)pheap->heap[i].heapstate; + pheap->heap[i].key = ComputeKey(state); + } + pheap->makeheap(); + + pSearchStateSpace->bReevaluatefvals = false; +} + +void ADPlanner::Reevaluatehvals(ADSearchStateSpace_t* pSearchStateSpace) +{ + for(int i = 0; i < (int)pSearchStateSpace->searchMDP.StateArray.size(); i++) + { + CMDPSTATE* MDPstate = pSearchStateSpace->searchMDP.StateArray[i]; + ADState* state = (ADState*)MDPstate->PlannerSpecificData; + state->h = ComputeHeuristic(MDPstate, pSearchStateSpace); + } +} + +//creates (allocates memory) search state space +//does not initialize search statespace +int ADPlanner::CreateSearchStateSpace(ADSearchStateSpace_t* pSearchStateSpace) +{ + //create a heap + pSearchStateSpace->heap = new CHeap; + pSearchStateSpace->inconslist = new CList; + MaxMemoryCounter += sizeof(CHeap); + MaxMemoryCounter += sizeof(CList); + + pSearchStateSpace->searchgoalstate = NULL; + pSearchStateSpace->searchstartstate = NULL; + + searchexpands = 0; + + pSearchStateSpace->bReinitializeSearchStateSpace = false; + + return 1; +} + +//deallocates memory used by SearchStateSpace +void ADPlanner::DeleteSearchStateSpace(ADSearchStateSpace_t* pSearchStateSpace) +{ + if (pSearchStateSpace->heap != NULL) { + pSearchStateSpace->heap->makeemptyheap(); + delete pSearchStateSpace->heap; + pSearchStateSpace->heap = NULL; + } + + if (pSearchStateSpace->inconslist != NULL) { + pSearchStateSpace->inconslist->makeemptylist(AD_INCONS_LIST_ID); + delete pSearchStateSpace->inconslist; + pSearchStateSpace->inconslist = NULL; + } + + //delete the states themselves + int iend = (int)pSearchStateSpace->searchMDP.StateArray.size(); + for (int i = 0; i < iend; i++) { + CMDPSTATE* state = pSearchStateSpace->searchMDP.StateArray[i]; + DeleteSearchStateData((ADState*)state->PlannerSpecificData); + free(state->PlannerSpecificData); // allocated with malloc() on line 199 of revision 19485 + state->PlannerSpecificData = NULL; + } + pSearchStateSpace->searchMDP.Delete(); +} + +//reset properly search state space +//needs to be done before deleting states +int ADPlanner::ResetSearchStateSpace(ADSearchStateSpace_t* pSearchStateSpace) +{ + pSearchStateSpace->heap->makeemptyheap(); + pSearchStateSpace->inconslist->makeemptylist(AD_INCONS_LIST_ID); + + return 1; +} + +//initialization before each search +void ADPlanner::ReInitializeSearchStateSpace(ADSearchStateSpace_t* pSearchStateSpace) +{ + CKey key; + + //increase callnumber + pSearchStateSpace->callnumber++; + + //reset iteration + pSearchStateSpace->searchiteration = 0; + +#if DEBUG + SBPL_FPRINTF(fDeb, "reinitializing search state-space (new call number=%d search iter=%d)\n", + pSearchStateSpace->callnumber,pSearchStateSpace->searchiteration ); +#endif + + pSearchStateSpace->heap->makeemptyheap(); + pSearchStateSpace->inconslist->makeemptylist(AD_INCONS_LIST_ID); + + //reset + pSearchStateSpace->eps = this->finitial_eps; + pSearchStateSpace->eps_satisfied = INFINITECOST; + + //initialize start state + ADState* startstateinfo = (ADState*)(pSearchStateSpace->searchstartstate->PlannerSpecificData); + if (startstateinfo->callnumberaccessed != pSearchStateSpace->callnumber) { + ReInitializeSearchStateInfo( startstateinfo, pSearchStateSpace); + } + + startstateinfo->g = 0; + + //insert start state into the heap + key = ComputeKey(startstateinfo); + pSearchStateSpace->heap->insertheap(startstateinfo, key); + + pSearchStateSpace->bReinitializeSearchStateSpace = false; + pSearchStateSpace->bReevaluatefvals = false; + pSearchStateSpace->bRebuildOpenList = false; +} + +//very first initialization +int ADPlanner::InitializeSearchStateSpace(ADSearchStateSpace_t* pSearchStateSpace) +{ + if (pSearchStateSpace->heap->currentsize != 0 || pSearchStateSpace->inconslist->currentsize != 0) { + throw SBPL_Exception("ERROR in InitializeSearchStateSpace: heap or list is not empty"); + } + + pSearchStateSpace->eps = this->finitial_eps; + pSearchStateSpace->eps_satisfied = INFINITECOST; + pSearchStateSpace->searchiteration = 0; + pSearchStateSpace->callnumber = 0; + pSearchStateSpace->bReevaluatefvals = false; + pSearchStateSpace->bRebuildOpenList = false; + + //create and set the search start state + pSearchStateSpace->searchgoalstate = NULL; + //pSearchStateSpace->searchstartstate = GetState(SearchStartStateID, pSearchStateSpace); + pSearchStateSpace->searchstartstate = NULL; + + pSearchStateSpace->bReinitializeSearchStateSpace = true; + + return 1; +} + +int ADPlanner::SetSearchGoalState(int SearchGoalStateID, ADSearchStateSpace_t* pSearchStateSpace) +{ + if (pSearchStateSpace->searchgoalstate == NULL || + pSearchStateSpace->searchgoalstate->StateID != SearchGoalStateID) + { + pSearchStateSpace->searchgoalstate = GetState(SearchGoalStateID, pSearchStateSpace); + + //current solution may be invalid + pSearchStateSpace->eps_satisfied = INFINITECOST; + pSearchStateSpace_->eps = this->finitial_eps; + + //it will be a new search iteration + pSearchStateSpace_->searchiteration++; + pSearchStateSpace_->bRebuildOpenList = true; + + +#if USE_HEUR + //recompute heuristic for the heap if heuristics are used + pSearchStateSpace->bReevaluatefvals = true; +#endif + } + + return 1; +} + +int ADPlanner::SetSearchStartState(int SearchStartStateID, ADSearchStateSpace_t* pSearchStateSpace) +{ + CMDPSTATE* MDPstate = GetState(SearchStartStateID, pSearchStateSpace); + + if (MDPstate != pSearchStateSpace->searchstartstate) { + pSearchStateSpace->searchstartstate = MDPstate; + pSearchStateSpace->bReinitializeSearchStateSpace = true; + } + + return 1; +} + +int ADPlanner::ReconstructPath(ADSearchStateSpace_t* pSearchStateSpace) +{ + //nothing to do, if search is backward + if (bforwardsearch) { + CMDPSTATE* MDPstate = pSearchStateSpace->searchgoalstate; + CMDPSTATE* PredMDPstate; + ADState *predstateinfo, *stateinfo; + + int steps = 0; + const int max_steps = 100000; + while (MDPstate != pSearchStateSpace->searchstartstate && steps < max_steps) { + steps++; + + stateinfo = (ADState*)MDPstate->PlannerSpecificData; + + if (stateinfo->g == INFINITECOST) { + //throw SBPL_Exception("ERROR in ReconstructPath: g of the state on the path is INFINITE"); + return -1; + } + + if (stateinfo->bestpredstate == NULL) { + throw SBPL_Exception("ERROR in ReconstructPath: bestpred is NULL"); + } + + //get the parent state + PredMDPstate = stateinfo->bestpredstate; + predstateinfo = (ADState*)PredMDPstate->PlannerSpecificData; + + //set its best next info + predstateinfo->bestnextstate = MDPstate; + + //check the decrease of g-values along the path + if (predstateinfo->v >= stateinfo->g) { + throw SBPL_Exception("ERROR in ReconstructPath: g-values are non-decreasing"); + } + + //transition back + MDPstate = PredMDPstate; + } + + if (MDPstate != pSearchStateSpace->searchstartstate) { + SBPL_ERROR("ERROR: Failed to reconstruct path (compute bestnextstate pointers): steps processed=%d\n", + steps); + return 0; + } + } + + return 1; +} + +void ADPlanner::PrintSearchState(ADState* searchstateinfo, FILE* fOut) +{ + CKey key = ComputeKey(searchstateinfo); +#if DEBUG + SBPL_FPRINTF(fOut, "g=%d v=%d h = %d heapindex=%d inconslist=%d key=[%d %d] iterc=%d callnuma=%d expands=%d (current callnum=%d iter=%d)", + searchstateinfo->g, searchstateinfo->v, searchstateinfo->h, searchstateinfo->heapindex, (searchstateinfo->listelem[AD_INCONS_LIST_ID] != NULL), + (int)key[0], (int)key[1], searchstateinfo->iterationclosed, searchstateinfo->callnumberaccessed, searchstateinfo->numofexpands, + this->pSearchStateSpace_->callnumber, this->pSearchStateSpace_->searchiteration); +#else + SBPL_FPRINTF(fOut, "g=%d v=%d h = %d heapindex=%d inconslist=%d key=[%d %d] iterc=%d callnuma=%d " + "(current callnum=%d iter=%d)", + searchstateinfo->g, searchstateinfo->v, searchstateinfo->h, searchstateinfo->heapindex, + (searchstateinfo->listelem[AD_INCONS_LIST_ID] != NULL), (int)key[0], (int)key[1], + searchstateinfo->iterationclosed, searchstateinfo->callnumberaccessed, + this->pSearchStateSpace_->callnumber, this->pSearchStateSpace_->searchiteration); +#endif +} + +void ADPlanner::PrintSearchPath(ADSearchStateSpace_t* pSearchStateSpace, FILE* fOut) +{ + ADState* searchstateinfo; + CMDPSTATE* state = pSearchStateSpace->searchgoalstate; + CMDPSTATE* nextstate = NULL; + + if (fOut == NULL) fOut = stdout; + + int PathCost = ((ADState*)pSearchStateSpace->searchgoalstate->PlannerSpecificData)->g; + + SBPL_FPRINTF(fOut, "Printing a path from state %d to the search start state %d\n", state->StateID, + pSearchStateSpace->searchstartstate->StateID); + SBPL_FPRINTF(fOut, "Path cost = %d:\n", PathCost); + + environment_->PrintState(state->StateID, true, fOut); + + int costFromStart = 0; + int steps = 0; + const int max_steps = 100000; + while (state->StateID != pSearchStateSpace->searchstartstate->StateID && steps < max_steps) { + steps++; + + SBPL_FPRINTF(fOut, "state %d ", state->StateID); + + if (state->PlannerSpecificData == NULL) { + SBPL_FPRINTF(fOut, "path does not exist since search data does not exist\n"); + break; + } + + searchstateinfo = (ADState*)state->PlannerSpecificData; + + if (bforwardsearch) + nextstate = searchstateinfo->bestpredstate; + else + nextstate = searchstateinfo->bestnextstate; + + if (nextstate == NULL) { + SBPL_FPRINTF(fOut, "path does not exist since nextstate == NULL\n"); + break; + } + if (searchstateinfo->g == INFINITECOST) { + SBPL_FPRINTF(fOut, "path does not exist since state->g == NULL\n"); + break; + } + + int costToGoal = PathCost - costFromStart; + if (!bforwardsearch) { + //otherwise this cost is not even set + costFromStart += searchstateinfo->costtobestnextstate; + } + +#if DEBUG + if (searchstateinfo->g > searchstateinfo->v) { + std::stringstream ss; ss << "ERROR: underconsistent state " << state->StateID << " is encountered"; + SBPL_FPRINTF(fOut, "%s\n", ss.str().c_str()); + throw SBPL_Exception(ss.str()); + } + + if (!bforwardsearch) { //otherwise this cost is not even set + if(nextstate->PlannerSpecificData != NULL && searchstateinfo->g < searchstateinfo->costtobestnextstate + ((ADState*)(nextstate->PlannerSpecificData))->g) + { + const char* msg = "ERROR: g(source) < c(source,target) + g(target)"; + SBPL_FPRINTF(fOut, "%s\n", msg); + throw SBPL_Exception(msg); + } + } +#endif + + //PrintSearchState(searchstateinfo, fOut); + SBPL_FPRINTF(fOut, "-->state %d ctg = %d ", nextstate->StateID, costToGoal); + + state = nextstate; + + environment_->PrintState(state->StateID, true, fOut); + } + + if (state->StateID != pSearchStateSpace->searchstartstate->StateID) { + SBPL_ERROR("ERROR: Failed to printsearchpath, max_steps reached\n"); + return; + } +} + +int ADPlanner::getHeurValue(ADSearchStateSpace_t* pSearchStateSpace, int StateID) +{ + CMDPSTATE* MDPstate = GetState(StateID, pSearchStateSpace); + ADState* searchstateinfo = (ADState*)MDPstate->PlannerSpecificData; + return searchstateinfo->h; +} + +vector ADPlanner::GetSearchPath(ADSearchStateSpace_t* pSearchStateSpace, int& solcost) +{ + vector SuccIDV; + vector CostV; + vector wholePathIds; + ADState* searchstateinfo; + CMDPSTATE* state = NULL; + CMDPSTATE* goalstate = NULL; + CMDPSTATE* startstate = NULL; + + if (bforwardsearch) { + startstate = pSearchStateSpace->searchstartstate; + goalstate = pSearchStateSpace->searchgoalstate; + + //reconstruct the path by setting bestnextstate pointers appropriately + if (ReconstructPath(pSearchStateSpace) != 1) { + solcost = INFINITECOST; + return wholePathIds; + } + } + else { + startstate = pSearchStateSpace->searchgoalstate; + goalstate = pSearchStateSpace->searchstartstate; + } + +#if DEBUG + //PrintSearchPath(pSearchStateSpace, fDeb); +#endif + + state = startstate; + + wholePathIds.push_back(state->StateID); + solcost = 0; + + FILE* fOut = stdout; + if (fOut == NULL) { + throw SBPL_Exception("ERROR: could not open file"); + } + int steps = 0; + const int max_steps = 100000; + while (state->StateID != goalstate->StateID && steps < max_steps) { + steps++; + + if (state->PlannerSpecificData == NULL) { + SBPL_FPRINTF(fOut, "path does not exist since search data does not exist\n"); + break; + } + + searchstateinfo = (ADState*)state->PlannerSpecificData; + + if (searchstateinfo->bestnextstate == NULL) { + SBPL_FPRINTF(fOut, "path does not exist since bestnextstate == NULL\n"); + break; + } + if (searchstateinfo->g == INFINITECOST) { + SBPL_FPRINTF(fOut, "path does not exist since bestnextstate == NULL\n"); + break; + } + + environment_->GetSuccs(state->StateID, &SuccIDV, &CostV); + int actioncost = INFINITECOST; + for (int i = 0; i < (int)SuccIDV.size(); i++) { + if (SuccIDV.at(i) == searchstateinfo->bestnextstate->StateID && CostV.at(i) < actioncost) actioncost + = CostV.at(i); + + } + solcost += actioncost; + + if (searchstateinfo->v < searchstateinfo->g) { + const char* msg = "ERROR: underconsistent state on the path"; + SBPL_ERROR("%s\n", msg); + PrintSearchState(searchstateinfo, stdout); + //SBPL_FPRINTF(fDeb, "ERROR: underconsistent state on the path\n"); + //PrintSearchState(searchstateinfo, fDeb); + throw SBPL_Exception(msg); + } + + //SBPL_FPRINTF(fDeb, "actioncost=%d between states %d and %d\n", + // actioncost, state->StateID, searchstateinfo->bestnextstate->StateID); + //environment_->PrintState(state->StateID, false, fDeb); + //environment_->PrintState(searchstateinfo->bestnextstate->StateID, false, fDeb); + + state = searchstateinfo->bestnextstate; + + wholePathIds.push_back(state->StateID); + } + + if (state->StateID != goalstate->StateID) { + SBPL_ERROR("ERROR: Failed to getsearchpath, steps processed=%d\n", steps); + wholePathIds.clear(); + solcost = INFINITECOST; + return wholePathIds; + } + + //PrintSearchPath(pSearchStateSpace, stdout); + + return wholePathIds; +} + +bool ADPlanner::Search(ADSearchStateSpace_t* pSearchStateSpace, vector& pathIds, int & PathCost, + bool bFirstSolution, bool bOptimalSolution, double MaxNumofSecs) +{ + CKey key; + TimeStarted = clock(); + searchexpands = 0; + double old_repair_time = repair_time; + if (!use_repair_time) repair_time = MaxNumofSecs; + +#if DEBUG + SBPL_FPRINTF(fDeb, "new search call (call number=%d)\n", pSearchStateSpace->callnumber); +#endif + + if (pSearchStateSpace->bReevaluatefvals) { + // costs have changed or a new goal has been set + environment_->EnsureHeuristicsUpdated(bforwardsearch); + Reevaluatehvals(pSearchStateSpace); + } + + + if (pSearchStateSpace->bReinitializeSearchStateSpace == true) { + //re-initialize state space + ReInitializeSearchStateSpace(pSearchStateSpace); + } + + if (bOptimalSolution) { + pSearchStateSpace->eps = 1; + MaxNumofSecs = INFINITECOST; + repair_time = INFINITECOST; + } + else if (bFirstSolution) { + MaxNumofSecs = INFINITECOST; + repair_time = INFINITECOST; + } + + //the main loop of AD* + stats.clear(); + int prevexpands = 0; + clock_t loop_time; + while (pSearchStateSpace->eps_satisfied > final_epsilon && + (clock() - TimeStarted) < MaxNumofSecs * (double)CLOCKS_PER_SEC && + (pSearchStateSpace->eps_satisfied == INFINITECOST || + (clock() - TimeStarted) < repair_time * (double)CLOCKS_PER_SEC)) + { + loop_time = clock(); + //it will be a new search iteration + if (pSearchStateSpace->searchiteration == 0) pSearchStateSpace->searchiteration++; + + //decrease eps for all subsequent iterations + if (fabs(pSearchStateSpace->eps_satisfied - pSearchStateSpace->eps) < ERR_EPS && !bFirstSolution) { + pSearchStateSpace->eps = pSearchStateSpace->eps - dec_eps; + if (pSearchStateSpace->eps < final_epsilon) pSearchStateSpace->eps = final_epsilon; + + pSearchStateSpace->bReevaluatefvals = true; + pSearchStateSpace->bRebuildOpenList = true; + + pSearchStateSpace->searchiteration++; + } + + //build a new open list by merging it with incons one + if (pSearchStateSpace->bRebuildOpenList) BuildNewOPENList(pSearchStateSpace); + + //re-compute f-values if necessary and reorder the heap + if (pSearchStateSpace->bReevaluatefvals) Reevaluatefvals(pSearchStateSpace); + + //improve or compute path + if (ComputePath(pSearchStateSpace, MaxNumofSecs) == 1) { + pSearchStateSpace->eps_satisfied = pSearchStateSpace->eps; + } + + //print the solution cost and eps bound + SBPL_PRINTF("eps=%f expands=%d g(sstart)=%d\n", pSearchStateSpace->eps_satisfied, searchexpands - prevexpands, + ((ADState*)pSearchStateSpace->searchgoalstate->PlannerSpecificData)->g); + + if (pSearchStateSpace->eps_satisfied == finitial_eps && pSearchStateSpace->eps == finitial_eps) { + finitial_eps_planning_time = double(clock() - loop_time) / CLOCKS_PER_SEC; + num_of_expands_initial_solution = searchexpands - prevexpands; + } + + if (stats.empty() || pSearchStateSpace->eps_satisfied != stats.back().eps) { + PlannerStats tempStat; + tempStat.eps = pSearchStateSpace->eps_satisfied; + tempStat.expands = searchexpands - prevexpands; + tempStat.time = double(clock() - loop_time) / CLOCKS_PER_SEC; + tempStat.cost = ((ADState*)pSearchStateSpace->searchgoalstate->PlannerSpecificData)->g; + stats.push_back(tempStat); + } + +#if DEBUG + SBPL_FPRINTF(fDeb, "eps=%f eps_sat=%f expands=%d g(sstart)=%d\n", pSearchStateSpace->eps, + pSearchStateSpace->eps_satisfied, searchexpands - prevexpands, + ((ADState*)pSearchStateSpace->searchgoalstate->PlannerSpecificData)->g); +#endif + prevexpands = searchexpands; + + //if just the first solution then we are done + if (bFirstSolution) break; + + //no solution exists + if (((ADState*)pSearchStateSpace->searchgoalstate->PlannerSpecificData)->g == INFINITECOST) break; + + } + repair_time = old_repair_time; + +#if DEBUG + SBPL_FFLUSH(fDeb); +#endif + + PathCost = ((ADState*)pSearchStateSpace->searchgoalstate->PlannerSpecificData)->g; + MaxMemoryCounter += environment_->StateID2IndexMapping.size() * sizeof(int); + + SBPL_PRINTF("MaxMemoryCounter = %d\n", MaxMemoryCounter); + + int solcost = INFINITECOST; + bool ret = false; + if (PathCost == INFINITECOST || pSearchStateSpace_->eps_satisfied == INFINITECOST) { + SBPL_PRINTF("could not find a solution\n"); + ret = false; + } + else { + SBPL_PRINTF("solution is found\n"); + + pathIds = GetSearchPath(pSearchStateSpace, solcost); + ret = true; + } + + SBPL_PRINTF("total expands this call = %d, planning time = %.3f secs, solution cost=%d\n", searchexpands, (clock() + - TimeStarted) / ((double)CLOCKS_PER_SEC), solcost); + final_eps_planning_time = (clock() - TimeStarted) / ((double)CLOCKS_PER_SEC); + final_eps = pSearchStateSpace->eps_satisfied; + + //SBPL_FPRINTF(fStat, "%d %d\n", searchexpands, solcost); + + return ret; + +} + +void ADPlanner::Update_SearchSuccs_of_ChangedEdges(vector const * statesIDV) +{ + SBPL_PRINTF("updating %d affected states\n", (unsigned int)statesIDV->size()); + + if (statesIDV->size() > environment_->StateID2IndexMapping.size() / 10) { + SBPL_PRINTF("skipping affected states and instead restarting planner from scratch\n"); + pSearchStateSpace_->bReinitializeSearchStateSpace = true; + } + + //it will be a new search iteration + pSearchStateSpace_->searchiteration++; + + //will need to rebuild open list + pSearchStateSpace_->bRebuildOpenList = true; + + //recompute heuristic for the heap + pSearchStateSpace_->bReevaluatefvals = true; + + int numofstatesaffected = 0; + for (int pind = 0; pind < (int)statesIDV->size(); pind++) { + int stateID = statesIDV->at(pind); + + //first check that the state exists (to avoid creation of additional states) + if (environment_->StateID2IndexMapping[stateID][ADMDP_STATEID2IND] == -1) continue; + + //now get the state + CMDPSTATE* state = GetState(stateID, pSearchStateSpace_); + ADState* searchstateinfo = (ADState*)state->PlannerSpecificData; + + //now check that the state is not start state and was created after last search reset + if (stateID != pSearchStateSpace_->searchstartstate->StateID && + searchstateinfo->callnumberaccessed == pSearchStateSpace_->callnumber) + { +#if DEBUG + SBPL_FPRINTF(fDeb, "updating affected state %d:\n", stateID); + PrintSearchState(searchstateinfo, fDeb); + SBPL_FPRINTF(fDeb, "\n"); +#endif + + //now we really do need to update it + Recomputegval(searchstateinfo); + UpdateSetMembership(searchstateinfo); + numofstatesaffected++; + +#if DEBUG + SBPL_FPRINTF(fDeb, "the state %d after update\n", stateID); + PrintSearchState(searchstateinfo, fDeb); + SBPL_FPRINTF(fDeb, "\n"); +#endif + } + } + + //TODO - check. I believe that there are cases when number of states + //generated is drastically smaller than the number of states really + //affected, which is a bug! + SBPL_PRINTF("%d states really affected (%d states generated total so far)\n", numofstatesaffected, + (int)environment_->StateID2IndexMapping.size()); + + //reset eps for which we know a path was computed + if (numofstatesaffected > 0) { + //make sure eps is reset appropriately + pSearchStateSpace_->eps = this->finitial_eps; + + //reset the satisfied eps + pSearchStateSpace_->eps_satisfied = INFINITECOST; + } +} + +//-----------------------------Interface function----------------------------------------------------- + +int ADPlanner::replan(vector* solution_stateIDs_V, ReplanParams params) +{ + int solcost; + return replan(solution_stateIDs_V, params, &solcost); +} + +int ADPlanner::replan(vector* solution_stateIDs_V, ReplanParams params, int* solcost) +{ + finitial_eps = params.initial_eps; + final_epsilon = params.final_eps; + dec_eps = params.dec_eps; + bsearchuntilfirstsolution = params.return_first_solution; + use_repair_time = params.repair_time > 0; + repair_time = params.repair_time; + return replan(params.max_time, solution_stateIDs_V, solcost); +} + +//returns 1 if found a solution, and 0 otherwise +int ADPlanner::replan(double allocated_time_secs, vector* solution_stateIDs_V) +{ + int solcost; + + return replan(allocated_time_secs, solution_stateIDs_V, &solcost); +} + +//returns 1 if found a solution, and 0 otherwise +int ADPlanner::replan(double allocated_time_secs, vector* solution_stateIDs_V, int* psolcost) +{ + vector pathIds; + int PathCost = 0; + bool bFound = false; + *psolcost = 0; + bool bOptimalSolution = false; + + SBPL_PRINTF("planner: replan called (bFirstSol=%d, bOptSol=%d)\n", bsearchuntilfirstsolution, bOptimalSolution); + + //plan for the first solution only + bFound = Search(pSearchStateSpace_, pathIds, PathCost, bsearchuntilfirstsolution, bOptimalSolution, allocated_time_secs); + if (!bFound) { + SBPL_PRINTF("failed to find a solution\n"); + } + + //copy the solution + *solution_stateIDs_V = pathIds; + *psolcost = PathCost; + + return (int)bFound; +} + +int ADPlanner::set_goal(int goal_stateID) +{ + SBPL_PRINTF("planner: setting goal to %d\n", goal_stateID); + environment_->PrintState(goal_stateID, true, stdout); + + if (bforwardsearch) { + if (SetSearchGoalState(goal_stateID, pSearchStateSpace_) != 1) { + SBPL_ERROR("ERROR: failed to set search goal state\n"); + return 0; + } + } + else { + if (SetSearchStartState(goal_stateID, pSearchStateSpace_) != 1) { + SBPL_ERROR("ERROR: failed to set search start state\n"); + return 0; + } + } + + return 1; +} + +int ADPlanner::set_start(int start_stateID) +{ + SBPL_PRINTF("planner: setting start to %d\n", start_stateID); + environment_->PrintState(start_stateID, true, stdout); + + if (bforwardsearch) { + if (SetSearchStartState(start_stateID, pSearchStateSpace_) != 1) { + SBPL_ERROR("ERROR: failed to set search start state\n"); + return 0; + } + } + else { + if (SetSearchGoalState(start_stateID, pSearchStateSpace_) != 1) { + SBPL_ERROR("ERROR: failed to set search goal state\n"); + return 0; + } + } + + return 1; +} + +void ADPlanner::update_succs_of_changededges(vector* succstatesIDV) +{ + SBPL_PRINTF("UpdateSuccs called on %d succs\n", (unsigned int)succstatesIDV->size()); + + Update_SearchSuccs_of_ChangedEdges(succstatesIDV); +} + +void ADPlanner::update_preds_of_changededges(vector* predstatesIDV) +{ + SBPL_PRINTF("UpdatePreds called on %d preds\n", (unsigned int)predstatesIDV->size()); + + Update_SearchSuccs_of_ChangedEdges(predstatesIDV); +} + +int ADPlanner::force_planning_from_scratch() +{ + SBPL_PRINTF("planner: forceplanfromscratch set\n"); + + pSearchStateSpace_->bReinitializeSearchStateSpace = true; + + return 1; +} + +int ADPlanner::force_planning_from_scratch_and_free_memory() +{ + SBPL_PRINTF("planner: forceplanfromscratch set\n"); + int start_id = -1; + int goal_id = -1; + if (pSearchStateSpace_->searchstartstate) start_id = pSearchStateSpace_->searchstartstate->StateID; + if (pSearchStateSpace_->searchgoalstate) goal_id = pSearchStateSpace_->searchgoalstate->StateID; + + if (!bforwardsearch) { + int temp = start_id; + start_id = goal_id; + goal_id = temp; + } + + DeleteSearchStateSpace( pSearchStateSpace_); + CreateSearchStateSpace(pSearchStateSpace_); + InitializeSearchStateSpace(pSearchStateSpace_); + for (unsigned int i = 0; i < environment_->StateID2IndexMapping.size(); i++) + for (int j = 0; j < NUMOFINDICES_STATEID2IND; j++) + environment_->StateID2IndexMapping[i][j] = -1; + + if (start_id >= 0) set_start(start_id); + if (goal_id >= 0) set_goal(goal_id); + return 1; +} + +int ADPlanner::set_search_mode(bool bSearchUntilFirstSolution) +{ + SBPL_PRINTF("planner: search mode set to %d\n", bSearchUntilFirstSolution); + + bsearchuntilfirstsolution = bSearchUntilFirstSolution; + + return 1; +} + +void ADPlanner::costs_changed(StateChangeQuery const & stateChange) +{ + //recompute f values + pSearchStateSpace_->bReevaluatefvals = true; + + //no processing if no search efforts anyway + if (pSearchStateSpace_->bReinitializeSearchStateSpace == true || pSearchStateSpace_->searchiteration == 0) return; + + if (bforwardsearch) + Update_SearchSuccs_of_ChangedEdges(stateChange.getSuccessors()); + else + Update_SearchSuccs_of_ChangedEdges(stateChange.getPredecessors()); +} + +//--------------------------------------------------------------------------------------------------------- + +void ADPlanner::get_search_stats(vector* s) +{ + s->clear(); + s->reserve(stats.size()); + for (unsigned int i = 0; i < stats.size(); i++) { + s->push_back(stats[i]); + } +} diff --git a/navigations/sbpl/src/planners/araplanner.cpp b/navigations/sbpl/src/planners/araplanner.cpp new file mode 100755 index 0000000..c63fd31 --- /dev/null +++ b/navigations/sbpl/src/planners/araplanner.cpp @@ -0,0 +1,1286 @@ +/* + * Copyright (c) 2008, Maxim Likhachev + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Carnegie Mellon University nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include + +#include +#include +#include +#include +#include + +#include +#include +#include +#include + +using namespace std; + +ARAPlanner::ARAPlanner(DiscreteSpaceInformation* environment, bool bSearchForward) +{ + bforwardsearch = bSearchForward; + + environment_ = environment; + + bsearchuntilfirstsolution = false; + finitial_eps = ARA_DEFAULT_INITIAL_EPS; + final_epsilon = ARA_FINAL_EPS; + dec_eps = ARA_DECREASE_EPS; + use_repair_time = false; + repair_time = INFINITECOST; + searchexpands = 0; + MaxMemoryCounter = 0; + +#ifndef ROS + const char* debug = "debug.txt"; +#endif + fDeb = SBPL_FOPEN(debug, "w"); + if (fDeb == NULL) { + throw SBPL_Exception("ERROR: could not open planner debug file"); + } + + pSearchStateSpace_ = new ARASearchStateSpace_t; + + //create the ARA planner + if (CreateSearchStateSpace(pSearchStateSpace_) != 1) { + SBPL_ERROR("ERROR: failed to create statespace\n"); + return; + } + + //set the start and goal states + if (InitializeSearchStateSpace(pSearchStateSpace_) != 1) { + SBPL_ERROR("ERROR: failed to create statespace\n"); + return; + } + finitial_eps_planning_time = -1.0; + final_eps_planning_time = -1.0; + num_of_expands_initial_solution = 0; + final_eps = -1.0; +} + +ARAPlanner::~ARAPlanner() +{ + if (pSearchStateSpace_ != NULL) { + //delete the statespace + DeleteSearchStateSpace( pSearchStateSpace_); + delete pSearchStateSpace_; + } + SBPL_FCLOSE( fDeb); +} + +void ARAPlanner::Initialize_searchinfo(CMDPSTATE* state, ARASearchStateSpace_t* pSearchStateSpace) +{ + ARAState* searchstateinfo = (ARAState*)state->PlannerSpecificData; + + searchstateinfo->MDPstate = state; + InitializeSearchStateInfo(searchstateinfo, pSearchStateSpace); +} + +CMDPSTATE* ARAPlanner::CreateState(int stateID, ARASearchStateSpace_t* pSearchStateSpace) +{ + CMDPSTATE* state = NULL; + +#if DEBUG + if (environment_->StateID2IndexMapping[stateID][ARAMDP_STATEID2IND] != -1) { + throw SBPL_Exception("ERROR in CreateState: state already created"); + } +#endif + + //adds to the tail a state + state = pSearchStateSpace->searchMDP.AddState(stateID); + + //remember the index of the state + environment_->StateID2IndexMapping[stateID][ARAMDP_STATEID2IND] = + pSearchStateSpace->searchMDP.StateArray.size() - 1; + +#if DEBUG + if(state != + pSearchStateSpace->searchMDP.StateArray[environment_->StateID2IndexMapping[stateID][ARAMDP_STATEID2IND]]) + { + throw SBPL_Exception("ERROR in CreateState: invalid state index"); + } +#endif + + //create search specific info + state->PlannerSpecificData = (ARAState*)malloc(sizeof(ARAState)); + Initialize_searchinfo(state, pSearchStateSpace); + MaxMemoryCounter += sizeof(ARAState); + + return state; +} + +CMDPSTATE* ARAPlanner::GetState(int stateID, ARASearchStateSpace_t* pSearchStateSpace) +{ + if (stateID >= (int)environment_->StateID2IndexMapping.size()) { + std::stringstream ss("ERROR int GetState: stateID "); + ss << stateID << " is invalid"; + throw SBPL_Exception(ss.str()); + } + + if (environment_->StateID2IndexMapping[stateID][ARAMDP_STATEID2IND] == -1) + return CreateState(stateID, pSearchStateSpace); + else + return pSearchStateSpace->searchMDP.StateArray[environment_->StateID2IndexMapping[stateID][ARAMDP_STATEID2IND]]; +} + +//----------------------------------------------------------------------------------------------------- + +int ARAPlanner::ComputeHeuristic(CMDPSTATE* MDPstate, ARASearchStateSpace_t* pSearchStateSpace) +{ + //compute heuristic for search + + if (bforwardsearch) { + +#if MEM_CHECK == 1 + //int WasEn = DisableMemCheck(); +#endif + + //forward search: heur = distance from state to searchgoal which is Goal ARAState + int retv = environment_->GetGoalHeuristic(MDPstate->StateID); + +#if MEM_CHECK == 1 + //if (WasEn) + // EnableMemCheck(); +#endif + + return retv; + + } + else { + //backward search: heur = distance from searchgoal to state + return environment_->GetStartHeuristic(MDPstate->StateID); + } +} + +// initialization of a state +void ARAPlanner::InitializeSearchStateInfo(ARAState* state, ARASearchStateSpace_t* pSearchStateSpace) +{ + state->g = INFINITECOST; + state->v = INFINITECOST; + state->iterationclosed = 0; + state->callnumberaccessed = pSearchStateSpace->callnumber; + state->bestnextstate = NULL; + state->costtobestnextstate = INFINITECOST; + state->heapindex = 0; + state->listelem[ARA_INCONS_LIST_ID] = 0; +#if DEBUG + state->numofexpands = 0; +#endif + + state->bestpredstate = NULL; + + //compute heuristics +#if USE_HEUR + if(pSearchStateSpace->searchgoalstate != NULL) + state->h = ComputeHeuristic(state->MDPstate, pSearchStateSpace); + else + state->h = 0; +#else + state->h = 0; +#endif +} + +//re-initialization of a state +void ARAPlanner::ReInitializeSearchStateInfo(ARAState* state, ARASearchStateSpace_t* pSearchStateSpace) +{ + state->g = INFINITECOST; + state->v = INFINITECOST; + state->iterationclosed = 0; + state->callnumberaccessed = pSearchStateSpace->callnumber; + state->bestnextstate = NULL; + state->costtobestnextstate = INFINITECOST; + state->heapindex = 0; + state->listelem[ARA_INCONS_LIST_ID] = 0; +#if DEBUG + state->numofexpands = 0; +#endif + + state->bestpredstate = NULL; + + //compute heuristics +#if USE_HEUR + + if(pSearchStateSpace->searchgoalstate != NULL) + { + state->h = ComputeHeuristic(state->MDPstate, pSearchStateSpace); + } + else + state->h = 0; + +#else + + state->h = 0; + +#endif +} + +void ARAPlanner::DeleteSearchStateData(ARAState* state) +{ + //no memory was allocated + MaxMemoryCounter = 0; + return; +} + +//used for backward search +void ARAPlanner::UpdatePreds(ARAState* state, ARASearchStateSpace_t* pSearchStateSpace) +{ + vector PredIDV; + vector CostV; + CKey key; + ARAState *predstate; + + environment_->GetPreds(state->MDPstate->StateID, &PredIDV, &CostV); + + //iterate through predecessors of s + for (int pind = 0; pind < (int)PredIDV.size(); pind++) { + CMDPSTATE* PredMDPState = GetState(PredIDV[pind], pSearchStateSpace); + predstate = (ARAState*)(PredMDPState->PlannerSpecificData); + if (predstate->callnumberaccessed != pSearchStateSpace->callnumber) { + ReInitializeSearchStateInfo(predstate, pSearchStateSpace); + } + + //see if we can improve the value of predstate + if (predstate->g > state->v + CostV[pind]) { + predstate->g = state->v + CostV[pind]; + predstate->bestnextstate = state->MDPstate; + predstate->costtobestnextstate = CostV[pind]; + + //re-insert into heap if not closed yet + if (predstate->iterationclosed != pSearchStateSpace->searchiteration) { + key.key[0] = predstate->g + (int)(pSearchStateSpace->eps * predstate->h); + //key.key[1] = predstate->h; + if (predstate->heapindex != 0) + pSearchStateSpace->heap->updateheap(predstate, key); + else + pSearchStateSpace->heap->insertheap(predstate, key); + } + //take care of incons list + else if (predstate->listelem[ARA_INCONS_LIST_ID] == NULL) { + pSearchStateSpace->inconslist->insert(predstate, ARA_INCONS_LIST_ID); + } + } + } //for predecessors +} + +//used for forward search +void ARAPlanner::UpdateSuccs(ARAState* state, ARASearchStateSpace_t* pSearchStateSpace) +{ + vector SuccIDV; + vector CostV; + CKey key; + ARAState *succstate; + + environment_->GetSuccs(state->MDPstate->StateID, &SuccIDV, &CostV); + + //iterate through predecessors of s + for (int sind = 0; sind < (int)SuccIDV.size(); sind++) { + CMDPSTATE* SuccMDPState = GetState(SuccIDV[sind], pSearchStateSpace); + int cost = CostV[sind]; + + succstate = (ARAState*)(SuccMDPState->PlannerSpecificData); + if (succstate->callnumberaccessed != pSearchStateSpace->callnumber) { + ReInitializeSearchStateInfo(succstate, pSearchStateSpace); + } + + //see if we can improve the value of succstate + //taking into account the cost of action + if (succstate->g > state->v + cost) { + succstate->g = state->v + cost; + succstate->bestpredstate = state->MDPstate; + + //re-insert into heap if not closed yet + if (succstate->iterationclosed != pSearchStateSpace->searchiteration) { + + key.key[0] = succstate->g + (int)(pSearchStateSpace->eps * succstate->h); + + //key.key[1] = succstate->h; + + if (succstate->heapindex != 0) + pSearchStateSpace->heap->updateheap(succstate, key); + else + pSearchStateSpace->heap->insertheap(succstate, key); + } + //take care of incons list + else if (succstate->listelem[ARA_INCONS_LIST_ID] == NULL) { + pSearchStateSpace->inconslist->insert(succstate, ARA_INCONS_LIST_ID); + } + } //check for cost improvement + } //for actions +} + +//TODO-debugmax - add obsthresh and other thresholds to other environments in 3dkin +int ARAPlanner::GetGVal(int StateID, ARASearchStateSpace_t* pSearchStateSpace) +{ + CMDPSTATE* cmdp_state = GetState(StateID, pSearchStateSpace); + ARAState* state = (ARAState*)cmdp_state->PlannerSpecificData; + return state->g; +} + +//returns 1 if the solution is found, 0 if the solution does not exist and 2 if it ran out of time +int ARAPlanner::ImprovePath(ARASearchStateSpace_t* pSearchStateSpace, double MaxNumofSecs) +{ + int expands; + ARAState *state, *searchgoalstate; + CKey key, minkey; + CKey goalkey; + + expands = 0; + + if (pSearchStateSpace->searchgoalstate == NULL) { + throw SBPL_Exception("ERROR searching: no goal state is set"); + } + + //goal state + searchgoalstate = (ARAState*)(pSearchStateSpace->searchgoalstate->PlannerSpecificData); + if (searchgoalstate->callnumberaccessed != pSearchStateSpace->callnumber) { + ReInitializeSearchStateInfo(searchgoalstate, pSearchStateSpace); + } + + //set goal key + goalkey.key[0] = searchgoalstate->g; + //goalkey.key[1] = searchgoalstate->h; + + //expand states until done + minkey = pSearchStateSpace->heap->getminkeyheap(); + CKey oldkey = minkey; + while (!pSearchStateSpace->heap->emptyheap() && minkey.key[0] < INFINITECOST && goalkey > minkey && + (clock() - TimeStarted) < MaxNumofSecs * (double)CLOCKS_PER_SEC && + (pSearchStateSpace->eps_satisfied == INFINITECOST || + (clock() - TimeStarted) < repair_time * (double)CLOCKS_PER_SEC)) + { + //get the state + state = (ARAState*)pSearchStateSpace->heap->deleteminheap(); + +#if DEBUG + SBPL_FPRINTF(fDeb, "expanding state(%d): h=%d g=%u key=%u v=%u iterc=%d callnuma=%d expands=%d (g(goal)=%u)\n", + state->MDPstate->StateID, state->h, state->g, state->g+(int)(pSearchStateSpace->eps*state->h), + state->v, state->iterationclosed, state->callnumberaccessed, state->numofexpands, + searchgoalstate->g); + SBPL_FPRINTF(fDeb, "expanding: "); + PrintSearchState(state, fDeb); + if (state->listelem[ARA_INCONS_LIST_ID] != NULL) { + SBPL_FPRINTF(fDeb, "ERROR: expanding a state from inconslist\n"); + throw SBPL_Exception("ERROR: expanding a state from inconslist"); + } + //SBPL_FFLUSH(fDeb); +#endif + +#if DEBUG + if (minkey.key[0] < oldkey.key[0] && fabs(this->finitial_eps - 1.0) < ERR_EPS) { + //throw SBPL_Exception("WARN in search: the sequence of keys decreases"); + } + oldkey = minkey; +#endif + + if (state->v == state->g) { + SBPL_ERROR("ERROR: consistent state is being expanded\n"); +#if DEBUG + SBPL_FPRINTF(fDeb, "ERROR: consistent state is being expanded\n"); + throw SBPL_Exception("ERROR: consistent state is being expanded"); +#endif + } + + //recompute state value + state->v = state->g; + state->iterationclosed = pSearchStateSpace->searchiteration; + + //new expand + expands++; +#if DEBUG + state->numofexpands++; +#endif + + if (bforwardsearch == false) + UpdatePreds(state, pSearchStateSpace); + else + UpdateSuccs(state, pSearchStateSpace); + + //recompute minkey + minkey = pSearchStateSpace->heap->getminkeyheap(); + + //recompute goalkey if necessary + if (goalkey.key[0] != (int)searchgoalstate->g) { + //SBPL_PRINTF("re-computing goal key\n"); + //recompute the goal key (heuristics should be zero) + goalkey.key[0] = searchgoalstate->g; + //goalkey.key[1] = searchgoalstate->h; + } + + if (expands % 100000 == 0 && expands > 0) { + SBPL_PRINTF("expands so far=%u\n", expands); + } + } + + int retv = 1; + if (searchgoalstate->g == INFINITECOST && pSearchStateSpace->heap->emptyheap()) { + SBPL_PRINTF("solution does not exist: search exited because heap is empty\n"); + retv = 0; + } + else if (!pSearchStateSpace->heap->emptyheap() && goalkey > minkey) { + SBPL_PRINTF("search exited because it ran out of time\n"); + retv = 2; + } + else if (searchgoalstate->g == INFINITECOST && !pSearchStateSpace->heap->emptyheap()) { + SBPL_PRINTF("solution does not exist: search exited because all candidates for expansion have " + "infinite heuristics\n"); + retv = 0; + } + else { + SBPL_PRINTF("search exited with a solution for eps=%.3f\n", pSearchStateSpace->eps); + retv = 1; + } + + //SBPL_FPRINTF(fDeb, "expanded=%d\n", expands); + + searchexpands += expands; + + return retv; +} + +void ARAPlanner::BuildNewOPENList(ARASearchStateSpace_t* pSearchStateSpace) +{ + ARAState *state; + CKey key; + CHeap* pheap = pSearchStateSpace->heap; + CList* pinconslist = pSearchStateSpace->inconslist; + + //move incons into open + while (pinconslist->firstelement != NULL) { + state = (ARAState*)pinconslist->firstelement->liststate; + + //compute f-value + key.key[0] = state->g + (int)(pSearchStateSpace->eps * state->h); + //key.key[1] = state->h; + + //insert into OPEN + pheap->insertheap(state, key); + //remove from INCONS + pinconslist->remove(state, ARA_INCONS_LIST_ID); + } +} + +void ARAPlanner::Reevaluatefvals(ARASearchStateSpace_t* pSearchStateSpace) +{ + CKey key; + int i; + CHeap* pheap = pSearchStateSpace->heap; + + //recompute priorities for states in OPEN and reorder it + for (i = 1; i <= pheap->currentsize; ++i) { + ARAState* state = (ARAState*)pheap->heap[i].heapstate; + pheap->heap[i].key.key[0] = state->g + (int)(pSearchStateSpace->eps * state->h); + //pheap->heap[i].key.key[1] = state->h; + } + pheap->makeheap(); + + pSearchStateSpace->bReevaluatefvals = false; +} + +void ARAPlanner::Reevaluatehvals(ARASearchStateSpace_t* pSearchStateSpace) +{ + for(int i = 0; i < (int)pSearchStateSpace->searchMDP.StateArray.size(); i++) + { + CMDPSTATE* MDPstate = pSearchStateSpace->searchMDP.StateArray[i]; + ARAState* state = (ARAState*)MDPstate->PlannerSpecificData; + state->h = ComputeHeuristic(MDPstate, pSearchStateSpace); + } +} + +//creates (allocates memory) search state space +//does not initialize search statespace +int ARAPlanner::CreateSearchStateSpace(ARASearchStateSpace_t* pSearchStateSpace) +{ + //create a heap + pSearchStateSpace->heap = new CHeap; + pSearchStateSpace->inconslist = new CList; + MaxMemoryCounter += sizeof(CHeap); + MaxMemoryCounter += sizeof(CList); + + pSearchStateSpace->searchgoalstate = NULL; + pSearchStateSpace->searchstartstate = NULL; + + searchexpands = 0; + num_of_expands_initial_solution = -1; + + pSearchStateSpace->bReinitializeSearchStateSpace = false; + + return 1; +} + +//deallocates memory used by SearchStateSpace +void ARAPlanner::DeleteSearchStateSpace(ARASearchStateSpace_t* pSearchStateSpace) +{ + if (pSearchStateSpace->heap != NULL) { + pSearchStateSpace->heap->makeemptyheap(); + delete pSearchStateSpace->heap; + pSearchStateSpace->heap = NULL; + } + + if (pSearchStateSpace->inconslist != NULL) { + pSearchStateSpace->inconslist->makeemptylist(ARA_INCONS_LIST_ID); + delete pSearchStateSpace->inconslist; + pSearchStateSpace->inconslist = NULL; + } + + //delete the states themselves + int iend = (int)pSearchStateSpace->searchMDP.StateArray.size(); + for (int i = 0; i < iend; i++) { + CMDPSTATE* state = pSearchStateSpace->searchMDP.StateArray[i]; + if (state != NULL && state->PlannerSpecificData != NULL) { + DeleteSearchStateData((ARAState*)state->PlannerSpecificData); + free((ARAState*)state->PlannerSpecificData); + state->PlannerSpecificData = NULL; + } + } + pSearchStateSpace->searchMDP.Delete(); +} + +//reset properly search state space +//needs to be done before deleting states +int ARAPlanner::ResetSearchStateSpace(ARASearchStateSpace_t* pSearchStateSpace) +{ + pSearchStateSpace->heap->makeemptyheap(); + pSearchStateSpace->inconslist->makeemptylist(ARA_INCONS_LIST_ID); + + return 1; +} + +//initialization before each search +void ARAPlanner::ReInitializeSearchStateSpace(ARASearchStateSpace_t* pSearchStateSpace) +{ + CKey key; + + //increase callnumber + pSearchStateSpace->callnumber++; + + //reset iteration + pSearchStateSpace->searchiteration = 0; + pSearchStateSpace->bNewSearchIteration = true; + +#if DEBUG + SBPL_FPRINTF(fDeb, "reinitializing search state-space (new call number=%d search iter=%d)\n", + pSearchStateSpace->callnumber,pSearchStateSpace->searchiteration ); +#endif + + pSearchStateSpace->heap->makeemptyheap(); + pSearchStateSpace->inconslist->makeemptylist(ARA_INCONS_LIST_ID); + + //reset + pSearchStateSpace->eps = this->finitial_eps; + pSearchStateSpace->eps_satisfied = INFINITECOST; + + //initialize start state + ARAState* startstateinfo = (ARAState*)(pSearchStateSpace->searchstartstate->PlannerSpecificData); + if (startstateinfo->callnumberaccessed != pSearchStateSpace->callnumber) { + ReInitializeSearchStateInfo(startstateinfo, pSearchStateSpace); + } + startstateinfo->g = 0; + + //initialize goal state + ARAState* searchgoalstate = (ARAState*)(pSearchStateSpace->searchgoalstate->PlannerSpecificData); + if (searchgoalstate->callnumberaccessed != pSearchStateSpace->callnumber) { + ReInitializeSearchStateInfo(searchgoalstate, pSearchStateSpace); + } + + //insert start state into the heap + key.key[0] = (long int)(pSearchStateSpace->eps * startstateinfo->h); + //key.key[1] = startstateinfo->h; + pSearchStateSpace->heap->insertheap(startstateinfo, key); + + pSearchStateSpace->bReinitializeSearchStateSpace = false; + pSearchStateSpace->bReevaluatefvals = false; +} + +//very first initialization +int ARAPlanner::InitializeSearchStateSpace(ARASearchStateSpace_t* pSearchStateSpace) +{ + if (pSearchStateSpace->heap->currentsize != 0 || pSearchStateSpace->inconslist->currentsize != 0) { + throw SBPL_Exception("ERROR in InitializeSearchStateSpace: heap or list is not empty"); + } + + pSearchStateSpace->eps = this->finitial_eps; + pSearchStateSpace->eps_satisfied = INFINITECOST; + pSearchStateSpace->searchiteration = 0; + pSearchStateSpace->bNewSearchIteration = true; + pSearchStateSpace->callnumber = 0; + pSearchStateSpace->bReevaluatefvals = false; + + //create and set the search start state + pSearchStateSpace->searchgoalstate = NULL; + //pSearchStateSpace->searchstartstate = GetState(SearchStartStateID, pSearchStateSpace); + pSearchStateSpace->searchstartstate = NULL; + + pSearchStateSpace->bReinitializeSearchStateSpace = true; + + return 1; +} + +int ARAPlanner::SetSearchGoalState(int SearchGoalStateID, ARASearchStateSpace_t* pSearchStateSpace) +{ + if (pSearchStateSpace->searchgoalstate == NULL || + pSearchStateSpace->searchgoalstate->StateID != SearchGoalStateID) + { + pSearchStateSpace->searchgoalstate = GetState(SearchGoalStateID, pSearchStateSpace); + + //should be new search iteration + pSearchStateSpace->eps_satisfied = INFINITECOST; + pSearchStateSpace->bNewSearchIteration = true; + pSearchStateSpace_->eps = this->finitial_eps; + +#if USE_HEUR + //recompute heuristic for the heap if heuristics is used + pSearchStateSpace->bReevaluatefvals = true; +#endif + } + + return 1; +} + +int ARAPlanner::SetSearchStartState(int SearchStartStateID, ARASearchStateSpace_t* pSearchStateSpace) +{ + CMDPSTATE* MDPstate = GetState(SearchStartStateID, pSearchStateSpace); + + if (MDPstate != pSearchStateSpace->searchstartstate) { + pSearchStateSpace->searchstartstate = MDPstate; + pSearchStateSpace->bReinitializeSearchStateSpace = true; + } + + return 1; +} + +int ARAPlanner::ReconstructPath(ARASearchStateSpace_t* pSearchStateSpace) +{ + if (bforwardsearch) //nothing to do, if search is backward + { + CMDPSTATE* MDPstate = pSearchStateSpace->searchgoalstate; + CMDPSTATE* PredMDPstate; + ARAState *predstateinfo, *stateinfo; + +#if DEBUG + SBPL_FPRINTF(fDeb, "reconstructing a path:\n"); +#endif + + while (MDPstate != pSearchStateSpace->searchstartstate) { + stateinfo = (ARAState*)MDPstate->PlannerSpecificData; + +#if DEBUG + PrintSearchState(stateinfo, fDeb); +#endif + if (stateinfo->g == INFINITECOST) { + //throw SBPL_Exception("ERROR in ReconstructPath: g of the state on the path is INFINITE"); + return -1; + } + + if (stateinfo->bestpredstate == NULL) { + SBPL_ERROR("ERROR in ReconstructPath: bestpred is NULL\n"); + throw SBPL_Exception("ERROR in ReconstructPath: bestpred is NULL"); + } + + //get the parent state + PredMDPstate = stateinfo->bestpredstate; + predstateinfo = (ARAState*)PredMDPstate->PlannerSpecificData; + + //set its best next info + predstateinfo->bestnextstate = MDPstate; + + //check the decrease of g-values along the path + if (predstateinfo->v >= stateinfo->g) { + SBPL_ERROR("ERROR in ReconstructPath: g-values are non-decreasing\n"); + PrintSearchState(predstateinfo, fDeb); + throw SBPL_Exception("ERROR in ReconstructPath: g-values are non-decreasing"); + } + + //transition back + MDPstate = PredMDPstate; + } + } + + return 1; +} + +void ARAPlanner::PrintSearchPath(ARASearchStateSpace_t* pSearchStateSpace, FILE* fOut) +{ + ARAState* searchstateinfo; + CMDPSTATE* state; + int goalID; + int PathCost; + + if (bforwardsearch) { + state = pSearchStateSpace->searchstartstate; + goalID = pSearchStateSpace->searchgoalstate->StateID; + } + else { + state = pSearchStateSpace->searchgoalstate; + goalID = pSearchStateSpace->searchstartstate->StateID; + } + if (fOut == NULL) fOut = stdout; + + PathCost = ((ARAState*)pSearchStateSpace->searchgoalstate->PlannerSpecificData)->g; + + SBPL_FPRINTF(fOut, "Printing a path from state %d to the goal state %d\n", state->StateID, + pSearchStateSpace->searchgoalstate->StateID); + SBPL_FPRINTF(fOut, "Path cost = %d:\n", PathCost); + + environment_->PrintState(state->StateID, false, fOut); + + int costFromStart = 0; + while (state->StateID != goalID) { + SBPL_FPRINTF(fOut, "state %d ", state->StateID); + + if (state->PlannerSpecificData == NULL) { + SBPL_FPRINTF(fOut, "path does not exist since search data does not exist\n"); + break; + } + + searchstateinfo = (ARAState*)state->PlannerSpecificData; + + if (searchstateinfo->bestnextstate == NULL) { + SBPL_FPRINTF(fOut, "path does not exist since bestnextstate == NULL\n"); + break; + } + if (searchstateinfo->g == INFINITECOST) { + SBPL_FPRINTF(fOut, "path does not exist since bestnextstate == NULL\n"); + break; + } + + int costToGoal = PathCost - costFromStart; + int transcost = searchstateinfo->g - ((ARAState*)(searchstateinfo->bestnextstate->PlannerSpecificData))->v; + if (bforwardsearch) transcost = -transcost; + + costFromStart += transcost; + + SBPL_FPRINTF(fOut, "g=%d-->state %d, h = %d ctg = %d ", searchstateinfo->g, + searchstateinfo->bestnextstate->StateID, searchstateinfo->h, costToGoal); + + state = searchstateinfo->bestnextstate; + + environment_->PrintState(state->StateID, false, fOut); + } +} + +void ARAPlanner::PrintSearchState(ARAState* state, FILE* fOut) +{ +#if DEBUG + SBPL_FPRINTF(fOut, "state %d: h=%d g=%u v=%u iterc=%d callnuma=%d expands=%d heapind=%d inconslist=%d\n", + state->MDPstate->StateID, state->h, state->g, state->v, + state->iterationclosed, state->callnumberaccessed, state->numofexpands, state->heapindex, + state->listelem[ARA_INCONS_LIST_ID] ? 1 : 0); +#else + SBPL_FPRINTF(fOut, "state %d: h=%d g=%u v=%u iterc=%d callnuma=%d heapind=%d inconslist=%d\n", + state->MDPstate->StateID, state->h, state->g, state->v, state->iterationclosed, + state->callnumberaccessed, state->heapindex, state->listelem[ARA_INCONS_LIST_ID] ? 1 : 0); +#endif + environment_->PrintState(state->MDPstate->StateID, true, fOut); +} + +int ARAPlanner::getHeurValue(ARASearchStateSpace_t* pSearchStateSpace, int StateID) +{ + CMDPSTATE* MDPstate = GetState(StateID, pSearchStateSpace); + ARAState* searchstateinfo = (ARAState*)MDPstate->PlannerSpecificData; + return searchstateinfo->h; +} + +vector ARAPlanner::GetSearchPath(ARASearchStateSpace_t* pSearchStateSpace, int& solcost) +{ + vector SuccIDV; + vector CostV; + vector wholePathIds; + ARAState* searchstateinfo; + CMDPSTATE* state = NULL; + CMDPSTATE* goalstate = NULL; + CMDPSTATE* startstate = NULL; + + if (bforwardsearch) { + startstate = pSearchStateSpace->searchstartstate; + goalstate = pSearchStateSpace->searchgoalstate; + + //reconstruct the path by setting bestnextstate pointers appropriately + ReconstructPath(pSearchStateSpace); + } + else { + startstate = pSearchStateSpace->searchgoalstate; + goalstate = pSearchStateSpace->searchstartstate; + } + + state = startstate; + + wholePathIds.push_back(state->StateID); + solcost = 0; + + FILE* fOut = stdout; + if (fOut == NULL) { + throw SBPL_Exception("ERROR: could not open file"); + } + while (state->StateID != goalstate->StateID) { + if (state->PlannerSpecificData == NULL) { + SBPL_FPRINTF(fOut, "path does not exist since search data does not exist\n"); + break; + } + + searchstateinfo = (ARAState*)state->PlannerSpecificData; + + if (searchstateinfo->bestnextstate == NULL) { + SBPL_FPRINTF(fOut, "path does not exist since bestnextstate == NULL\n"); + break; + } + if (searchstateinfo->g == INFINITECOST) { + SBPL_FPRINTF(fOut, "path does not exist since bestnextstate == NULL\n"); + break; + } + + environment_->GetSuccs(state->StateID, &SuccIDV, &CostV); + int actioncost = INFINITECOST; + for (int i = 0; i < (int)SuccIDV.size(); i++) { + if (SuccIDV.at(i) == searchstateinfo->bestnextstate->StateID && CostV.at(i) < actioncost) { + actioncost = CostV.at(i); + } + } + if (actioncost == INFINITECOST) SBPL_PRINTF("WARNING: actioncost = %d\n", actioncost); + + solcost += actioncost; + + //SBPL_FPRINTF(fDeb, "actioncost=%d between states %d and %d\n", + // actioncost, state->StateID, searchstateinfo->bestnextstate->StateID); + //environment_->PrintState(state->StateID, false, fDeb); + //environment_->PrintState(searchstateinfo->bestnextstate->StateID, false, fDeb); + +#if DEBUG + ARAState* nextstateinfo = (ARAState*)(searchstateinfo->bestnextstate->PlannerSpecificData); + if (actioncost != abs((int)(searchstateinfo->g - nextstateinfo->g)) && + pSearchStateSpace->eps_satisfied <= 1.001) + { + SBPL_FPRINTF(fDeb, "ERROR: actioncost=%d is not matching the difference in g-values of %d\n", + actioncost, abs((int)(searchstateinfo->g - nextstateinfo->g))); + SBPL_ERROR("ERROR: actioncost=%d is not matching the difference in g-values of %d\n", + actioncost,abs((int)(searchstateinfo->g - nextstateinfo->g))); + PrintSearchState(searchstateinfo, fDeb); + PrintSearchState(nextstateinfo, fDeb); + } +#endif + + state = searchstateinfo->bestnextstate; + + wholePathIds.push_back(state->StateID); + } + + return wholePathIds; +} + +bool ARAPlanner::Search(ARASearchStateSpace_t* pSearchStateSpace, vector& pathIds, int & PathCost, + bool bFirstSolution, bool bOptimalSolution, double MaxNumofSecs) +{ + CKey key; + TimeStarted = clock(); + searchexpands = 0; + num_of_expands_initial_solution = -1; + double old_repair_time = repair_time; + if (!use_repair_time) + repair_time = MaxNumofSecs; + +#if DEBUG + SBPL_FPRINTF(fDeb, "new search call (call number=%d)\n", pSearchStateSpace->callnumber); +#endif + + if (pSearchStateSpace->bReevaluatefvals) { + // costs have changed or a new goal has been set + environment_->EnsureHeuristicsUpdated(bforwardsearch); + Reevaluatehvals(pSearchStateSpace); + } + + if (pSearchStateSpace->bReinitializeSearchStateSpace) { + //re-initialize state space + ReInitializeSearchStateSpace(pSearchStateSpace); + } + + if (bOptimalSolution) { + pSearchStateSpace->eps = 1; + MaxNumofSecs = INFINITECOST; + repair_time = INFINITECOST; + } + else if (bFirstSolution) { + MaxNumofSecs = INFINITECOST; + repair_time = INFINITECOST; + } + + //the main loop of ARA* + stats.clear(); + int prevexpands = 0; + clock_t loop_time; + while (pSearchStateSpace->eps_satisfied > final_epsilon && + (clock() - TimeStarted) < MaxNumofSecs * (double)CLOCKS_PER_SEC && + (pSearchStateSpace->eps_satisfied == INFINITECOST || + (clock() - TimeStarted) < repair_time * (double)CLOCKS_PER_SEC)) + { + loop_time = clock(); + //decrease eps for all subsequent iterations + if (fabs(pSearchStateSpace->eps_satisfied - pSearchStateSpace->eps) < ERR_EPS && !bFirstSolution) { + pSearchStateSpace->eps = pSearchStateSpace->eps - dec_eps; + if (pSearchStateSpace->eps < final_epsilon) + pSearchStateSpace->eps = final_epsilon; + + //the priorities need to be updated + pSearchStateSpace->bReevaluatefvals = true; + + //it will be a new search + pSearchStateSpace->bNewSearchIteration = true; + } + + if (pSearchStateSpace->bNewSearchIteration) { + pSearchStateSpace->searchiteration++; + pSearchStateSpace->bNewSearchIteration = false; + BuildNewOPENList(pSearchStateSpace); + } + + //re-compute f-values if necessary and reorder the heap + if (pSearchStateSpace->bReevaluatefvals) + Reevaluatefvals(pSearchStateSpace); + + //improve or compute path + if (ImprovePath(pSearchStateSpace, MaxNumofSecs) == 1) { + pSearchStateSpace->eps_satisfied = pSearchStateSpace->eps; + } + + //print the solution cost and eps bound + SBPL_PRINTF("eps=%f expands=%d g(searchgoal)=%d time=%.3f\n", pSearchStateSpace->eps_satisfied, + searchexpands - prevexpands, + ((ARAState*)pSearchStateSpace->searchgoalstate->PlannerSpecificData)->g, + double(clock() - loop_time) / CLOCKS_PER_SEC); + + if (pSearchStateSpace->eps_satisfied == finitial_eps && pSearchStateSpace->eps == finitial_eps) { + finitial_eps_planning_time = double(clock() - loop_time) / CLOCKS_PER_SEC; + num_of_expands_initial_solution = searchexpands - prevexpands; + } + + if (stats.empty() || pSearchStateSpace->eps_satisfied != stats.back().eps) { + PlannerStats tempStat; + tempStat.eps = pSearchStateSpace->eps_satisfied; + tempStat.expands = searchexpands - prevexpands; + tempStat.time = double(clock() - loop_time) / CLOCKS_PER_SEC; + tempStat.cost = ((ARAState*)pSearchStateSpace->searchgoalstate->PlannerSpecificData)->g; + stats.push_back(tempStat); + } + +#if DEBUG + SBPL_FPRINTF(fDeb, "eps=%f expands=%d g(searchgoal)=%d time=%.3f\n", pSearchStateSpace->eps_satisfied, + searchexpands - prevexpands, + ((ARAState*)pSearchStateSpace->searchgoalstate->PlannerSpecificData)->g, + double(clock()-loop_time)/CLOCKS_PER_SEC); + PrintSearchState((ARAState*)pSearchStateSpace->searchgoalstate->PlannerSpecificData, fDeb); +#endif + prevexpands = searchexpands; + + //if just the first solution then we are done + if (bFirstSolution) + break; + + //no solution exists + if (((ARAState*)pSearchStateSpace->searchgoalstate->PlannerSpecificData)->g == INFINITECOST) + break; + } + repair_time = old_repair_time; + +#if DEBUG + SBPL_FFLUSH(fDeb); +#endif + + PathCost = ((ARAState*)pSearchStateSpace->searchgoalstate->PlannerSpecificData)->g; + MaxMemoryCounter += environment_->StateID2IndexMapping.size() * sizeof(int); + + SBPL_PRINTF("MaxMemoryCounter = %d\n", MaxMemoryCounter); + + int solcost = INFINITECOST; + bool ret = false; + if (PathCost == INFINITECOST) { + SBPL_PRINTF("could not find a solution\n"); + ret = false; + } + else { + SBPL_PRINTF("solution is found\n"); + pathIds = GetSearchPath(pSearchStateSpace, solcost); + ret = true; + } + + SBPL_PRINTF("total expands this call = %d, planning time = %.3f secs, solution cost=%d\n", + searchexpands, (clock() - TimeStarted) / ((double)CLOCKS_PER_SEC), solcost); + final_eps_planning_time = (clock() - TimeStarted) / ((double)CLOCKS_PER_SEC); + final_eps = pSearchStateSpace->eps_satisfied; + //SBPL_FPRINTF(fStat, "%d %d\n", searchexpands, solcost); + + return ret; +} + +//-----------------------------Interface function----------------------------------------------------- + +int ARAPlanner::replan(vector* solution_stateIDs_V, ReplanParams params) +{ + int solcost; + return replan(solution_stateIDs_V, params, &solcost); +} + +int ARAPlanner::replan(vector* solution_stateIDs_V, ReplanParams params, int* solcost) +{ + finitial_eps = params.initial_eps; + final_epsilon = params.final_eps; + dec_eps = params.dec_eps; + bsearchuntilfirstsolution = params.return_first_solution; + use_repair_time = params.repair_time > 0; + repair_time = params.repair_time; + return replan(params.max_time, solution_stateIDs_V, solcost); +} + +//returns 1 if found a solution, and 0 otherwise +int ARAPlanner::replan(double allocated_time_secs, vector* solution_stateIDs_V) +{ + int solcost; + + return replan(allocated_time_secs, solution_stateIDs_V, &solcost); +} + +//returns 1 if found a solution, and 0 otherwise +int ARAPlanner::replan(double allocated_time_secs, vector* solution_stateIDs_V, int* psolcost) +{ + vector pathIds; + bool bFound = false; + int PathCost; + bool bFirstSolution = this->bsearchuntilfirstsolution; + bool bOptimalSolution = false; + *psolcost = 0; + + SBPL_PRINTF("planner: replan called (bFirstSol=%d, bOptSol=%d)\n", bFirstSolution, bOptimalSolution); + + //plan + bFound = Search(pSearchStateSpace_, pathIds, PathCost, bFirstSolution, bOptimalSolution, allocated_time_secs); + if (!bFound) + { + SBPL_PRINTF("failed to find a solution\n"); + } + + //copy the solution + *solution_stateIDs_V = pathIds; + *psolcost = PathCost; + + return (int)bFound; +} + +int ARAPlanner::set_goal(int goal_stateID) +{ + SBPL_PRINTF("planner: setting goal to %d\n", goal_stateID); + environment_->PrintState(goal_stateID, true, stdout); + + if (bforwardsearch) { + if (SetSearchGoalState(goal_stateID, pSearchStateSpace_) != 1) { + SBPL_ERROR("ERROR: failed to set search goal state\n"); + return 0; + } + } + else { + if (SetSearchStartState(goal_stateID, pSearchStateSpace_) != 1) { + SBPL_ERROR("ERROR: failed to set search start state\n"); + return 0; + } + } + + return 1; +} + +int ARAPlanner::set_start(int start_stateID) +{ + SBPL_PRINTF("planner: setting start to %d\n", start_stateID); + environment_->PrintState(start_stateID, true, stdout); + + if (bforwardsearch) { + if (SetSearchStartState(start_stateID, pSearchStateSpace_) != 1) { + SBPL_ERROR("ERROR: failed to set search start state\n"); + return 0; + } + } + else { + if (SetSearchGoalState(start_stateID, pSearchStateSpace_) != 1) { + SBPL_ERROR("ERROR: failed to set search goal state\n"); + return 0; + } + } + + return 1; +} + +void ARAPlanner::costs_changed(StateChangeQuery const & stateChange) +{ + pSearchStateSpace_->bReevaluatefvals = true; + pSearchStateSpace_->bReinitializeSearchStateSpace = true; +} + +void ARAPlanner::costs_changed() +{ + pSearchStateSpace_->bReevaluatefvals = true; + pSearchStateSpace_->bReinitializeSearchStateSpace = true; +} + +int ARAPlanner::force_planning_from_scratch() +{ + SBPL_PRINTF("planner: forceplanfromscratch set\n"); + + pSearchStateSpace_->bReinitializeSearchStateSpace = true; + + return 1; +} + +int ARAPlanner::force_planning_from_scratch_and_free_memory() +{ + SBPL_PRINTF("planner: forceplanfromscratch set\n"); + int start_id = -1; + int goal_id = -1; + if (pSearchStateSpace_->searchstartstate) + start_id = pSearchStateSpace_->searchstartstate->StateID; + if (pSearchStateSpace_->searchgoalstate) + goal_id = pSearchStateSpace_->searchgoalstate->StateID; + + if (!bforwardsearch) { + int temp = start_id; + start_id = goal_id; + goal_id = temp; + } + + DeleteSearchStateSpace(pSearchStateSpace_); + CreateSearchStateSpace(pSearchStateSpace_); + InitializeSearchStateSpace(pSearchStateSpace_); + for (unsigned int i = 0; i < environment_->StateID2IndexMapping.size(); i++) + for (int j = 0; j < NUMOFINDICES_STATEID2IND; j++) + environment_->StateID2IndexMapping[i][j] = -1; + + if (start_id >= 0) + set_start(start_id); + if (goal_id >= 0) + set_goal(goal_id); + return 1; +} + +int ARAPlanner::set_search_mode(bool bSearchUntilFirstSolution) +{ + SBPL_PRINTF("planner: search mode set to %d\n", bSearchUntilFirstSolution); + + bsearchuntilfirstsolution = bSearchUntilFirstSolution; + + return 1; +} + +void ARAPlanner::print_searchpath(FILE* fOut) +{ + PrintSearchPath(pSearchStateSpace_, fOut); +} + +double ARAPlanner::compute_suboptimality() +{ + if (!pSearchStateSpace_) { + SBPL_ERROR("Search state space is NULL in compute_suboptimality()"); + return -1.0; + } + + // find the min cost from all paths that go through states in the incons + // list + int inconsListMin = std::numeric_limits::max(); + if (pSearchStateSpace_->inconslist) { + AbstractSearchState* currElem = + pSearchStateSpace_->inconslist->getfirst(); + while (currElem) { + // get the stateID of this state + ARAState* state = (ARAState*)currElem; + assert(state); + + // int stateID = state->MDPstate->StateID; + + // update the min to the f-value of this state if necessary + int h = state->h; + int g = state->g; + if (g + h < inconsListMin) { + inconsListMin = g + h; + } + + currElem = pSearchStateSpace_->inconslist->getnext( + currElem, ARAMDP_STATEID2IND); + } + } + + // find the min cost from all paths that go through states still in the open + // list + int openListMin = std::numeric_limits::max(); + if (pSearchStateSpace_->heap) { + for (int i = 1; i < pSearchStateSpace_->heap->currentsize; i++) { + AbstractSearchState* abstractState = + pSearchStateSpace_->heap->heap[i].heapstate; + if (!abstractState) { + SBPL_ERROR("heap element with keys %d and %d has NULL AbstractSearchState\n", (int)pSearchStateSpace_->heap->heap[i].key[0], (int)pSearchStateSpace_->heap->heap[i].key[1]); + continue; // return -1.0 ? + } + + ARAState* araState = (ARAState*)abstractState; + + int h = araState->h; + int g = araState->g; + if (g + h < openListMin) { + openListMin = g + h; + } + } + } + + SBPL_DEBUG("Done looking through INCONS and OPEN lists for state with minimum f-value\n"); + + int overallMin = openListMin < inconsListMin ? openListMin : inconsListMin; + SBPL_DEBUG("f_min = min(f_open_min = %d, f_incons_min = %d) = %d\n", openListMin, inconsListMin, overallMin); + + if (overallMin == std::numeric_limits::max()) { + SBPL_ERROR("Couldn't find a min f-value. Empty incons list or open list.\n"); + return -1.0; + } + + if (!pSearchStateSpace_->searchgoalstate) { + return -1.0; + } + + int goalGValue = GetGVal( + pSearchStateSpace_->searchgoalstate->StateID, pSearchStateSpace_); + double lowerBound = std::numeric_limits::max(); + if (overallMin != 0) { + lowerBound = double(goalGValue) / double(overallMin); + } + + SBPL_DEBUG("Lower Bound = %d / %d = %0.3f", goalGValue, overallMin, lowerBound); + SBPL_DEBUG("Eps Satisfied = %0.3f", pSearchStateSpace_->eps_satisfied); + + return std::max(1.0, std::min(pSearchStateSpace_->eps_satisfied, lowerBound)); +} + +void ARAPlanner::get_search_stats(vector* s) +{ + s->clear(); + s->reserve(stats.size()); + for (unsigned int i = 0; i < stats.size(); i++) { + s->push_back(stats[i]); + } +} diff --git a/navigations/sbpl/src/planners/lazyARA.cpp b/navigations/sbpl/src/planners/lazyARA.cpp new file mode 100755 index 0000000..c66a52e --- /dev/null +++ b/navigations/sbpl/src/planners/lazyARA.cpp @@ -0,0 +1,671 @@ +/* + * Copyright (c) 2013, Mike Phillips and Maxim Likhachev + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Carnegie Mellon University nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ +#include + +#include + +using namespace std; + +LazyARAPlanner::LazyARAPlanner( + DiscreteSpaceInformation* environment, + bool bSearchForward) +: + params(0.0) +{ + bforwardsearch = bSearchForward; + environment_ = environment; + replan_number = 0; + + goal_state_id = -1; + start_state_id = -1; +} + +LazyARAPlanner::~LazyARAPlanner() +{ + freeMemory(); +} + +void LazyARAPlanner::freeMemory() +{ + heap.makeemptyheap(); + incons.clear(); + stats.clear(); + for (unsigned int i = 0; i < states.size(); i++) { + if (states[i]) { + delete states[i]; + } + } + states.clear(); +} + +LazyARAState* LazyARAPlanner::GetState(int id) +{ + // if this stateID is out of bounds of our state vector then grow the list + if (id >= int(states.size())) { + for (int i = states.size(); i <= id; i++) { + states.push_back(NULL); + } + } + // if we have never seen this state then create one + if (states[id] == NULL) { + states[id] = new LazyARAState(); + states[id]->id = id; + states[id]->replan_number = -1; + } + // initialize the state if it hasn't been for this call to replan + LazyARAState* s = states[id]; + if (s->replan_number != replan_number) { + s->g = INFINITECOST; + s->v = INFINITECOST; + s->iteration_closed = -1; + s->replan_number = replan_number; + s->best_parent = NULL; + s->expanded_best_parent = NULL; + s->heapindex = 0; + s->in_incons = false; + s->isTrueCost = true; + // clear the lazy list + while (!s->lazyList.empty()) { + s->lazyList.pop(); + } + + //compute heuristics + if (bforwardsearch) { + s->h = environment_->GetGoalHeuristic(s->id); + } + else { + s->h = environment_->GetStartHeuristic(s->id); + } + } + return s; +} + +void LazyARAPlanner::ExpandState(LazyARAState* parent) +{ + SBPL_DEBUG("expand %d", parent->id); + vector children; + vector costs; + vector isTrueCost; + + if (bforwardsearch) { + environment_->GetLazySuccs(parent->id, &children, &costs, &isTrueCost); + } + else + environment_->GetLazyPreds(parent->id, &children, &costs, &isTrueCost); + + // iterate through children of the parent + for (int i = 0; i < (int)children.size(); i++) { + LazyARAState* child = GetState(children[i]); + insertLazyList(child, parent, costs[i], isTrueCost[i]); + } +} + +// assumptions: +// state is at the front of the open list +// it's minimum f-value is an underestimate (the edge cost from the parent is a guess and needs to be evaluated properly) +// it hasn't been expanded yet this iteration +void LazyARAPlanner::EvaluateState(LazyARAState* state) +{ + SBPL_DEBUG("evaluate %d (from %d)", state->id, state->best_parent->id); + LazyARAState* parent = state->best_parent; + + getNextLazyElement(state); + int trueCost; + if (bforwardsearch) { + trueCost = environment_->GetTrueCost(parent->id, state->id); + } + else { + trueCost = environment_->GetTrueCost(state->id, parent->id); + } + // if the evaluated true cost is valid (positive), insert it into the lazy list + if (trueCost > 0) { + SBPL_DEBUG(" edge is valid with cost %d added to parent->v=%d", trueCost, parent->v); + insertLazyList(state, parent, trueCost, true); + } + else{ + SBPL_DEBUG(" edge not valid"); + } +} + +// this should only be used with EvaluateState since it is assuming state hasn't +// been expanded yet (only evaluated) +void LazyARAPlanner::getNextLazyElement(LazyARAState* state) +{ + if (state->lazyList.empty()) { + state->g = INFINITECOST; + state->best_parent = NULL; + state->isTrueCost = true; + return; + } + LazyListElement elem = state->lazyList.top(); + state->lazyList.pop(); + state->g = elem.parent->v + elem.edgeCost; + state->best_parent = elem.parent; + state->isTrueCost = elem.isTrueCost; + // the new value is cheapest and if the value is also true then we want to + // throw out all the other options + if (state->isTrueCost) { + while (!state->lazyList.empty()) { + state->lazyList.pop(); + } + } + putStateInHeap(state); +} + +void LazyARAPlanner::insertLazyList( + LazyARAState* state, + LazyARAState* parent, + int edgeCost, + bool isTrueCost) +{ + SBPL_DEBUG("insertLazyList state->id=%d parent->id=%d state->g=%d parent->v=%d edgeCost=%d isTrueCost=%d\n", state->id, parent->id, state->g, parent->v, edgeCost, isTrueCost); + if (state->v <= parent->v + edgeCost) { + return; + } + else if (state->g <= parent->v + edgeCost){ + //if the best g-value we have is true and better, then the value we had dominates this one and we don't need it + if (state->isTrueCost) { + return; + } + //insert this guy into the lazy list + LazyListElement elem(parent, edgeCost, isTrueCost); + state->lazyList.push(elem); + } + else { + // the new guy is the cheapest so far + // should we save what was the previous best? + if (!isTrueCost && // the better guy's cost is not for sure + // state->g < INFINITECOST && // we actually have a previous best (we actually don't need this line because of the next one) + state->g < state->v) // we're not saving something we already expanded (and is stored in v and expanded_best_parent) + { + //we save it by putting it in the lazy list + LazyListElement elem(state->best_parent, state->g - state->best_parent->v, state->isTrueCost); + state->lazyList.push(elem); + } + + // the new guy is the cheapest + state->g = parent->v + edgeCost; + state->best_parent = parent; + state->isTrueCost = isTrueCost; + + // the new value is cheapest and if the value is also true then we want + // to throw out all the other options + if (isTrueCost) { + while (!state->lazyList.empty()) { + state->lazyList.pop(); + } + } + + // this function puts the state into the heap (or updates the position) + // if we haven't expanded. if we have expanded, it will put the state in + // the incons list (if we haven't already) + putStateInHeap(state); + } +} + +void LazyARAPlanner::putStateInHeap(LazyARAState* state) +{ + // we only allow one expansion per search iteration + // so insert into heap if not closed yet + if (state->iteration_closed != search_iteration) { + SBPL_DEBUG("put state %d in open with state->g=%d and state->isTrueCost=%d\n", state->id, state->g, state->isTrueCost); + CKey key; + key.key[0] = state->g + int(eps * state->h); + // if the state is already in the heap, just update its priority + if (state->heapindex != 0) { + heap.updateheap(state, key); + } + else { // otherwise add it to the heap + heap.insertheap(state, key); + } + } + // if the state has already been expanded once for this iteration then add + // it to the incons list so we can keep track of states that we know we have + // better costs for + else if (!state->in_incons) { + SBPL_DEBUG("put state %d in incons with state->g=%d and state->isTrueCost=%d\n", state->id, state->g, state->isTrueCost); + incons.push_back(state); + state->in_incons = true; + } +} + +// returns 1 if the solution is found, 0 if the solution does not exist and 2 if +// it ran out of time +int LazyARAPlanner::ImprovePath() +{ + // expand states until done + int expands = 0; + CKey min_key = heap.getminkeyheap(); + while (!heap.emptyheap() && + min_key.key[0] < INFINITECOST && + (goal_state->g > min_key.key[0] || !goal_state->isTrueCost) && + (goal_state->v > min_key.key[0]) && + !outOfTime()) + { + // get the state + LazyARAState* state = (LazyARAState*)heap.deleteminheap(); + + if (state->v == state->g) { + std::stringstream ss("ERROR: consistent state is being esxpanded "); + ss << "id=" << state->id; + ss << "v=" << state->v; + ss << "g=" << state->g; + ss << "isTrueCost=" << state->isTrueCost; + ss << "lazyListSize=" << state->lazyList.size(); + throw SBPL_Exception(ss.str()); + } + + if (state->isTrueCost) { + // mark the state as expanded + state->v = state->g; + state->expanded_best_parent = state->best_parent; + state->iteration_closed = search_iteration; + // expand the state + expands++; + ExpandState(state); + if (expands % 100000 == 0) { + SBPL_DEBUG("expands so far=%u", expands); + } + } + else { + // otherwise the state needs to be evaluated for its true cost + EvaluateState(state); + } + + // get the min key for the next iteration + min_key = heap.getminkeyheap(); + } + + search_expands += expands; + + if (goal_state->v < goal_state->g) { + goal_state->g = goal_state->v; + goal_state->best_parent = goal_state->expanded_best_parent; + } + + if (goal_state->g == INFINITECOST && (heap.emptyheap() || min_key.key[0] >= INFINITECOST)) { + return 0; // solution does not exists + } + if (!heap.emptyheap() && goal_state->g > min_key.key[0]) { + return 2; // search exited because it ran out of time + } + SBPL_DEBUG("search exited with a solution for eps=%.3f", eps); + if (goal_state->g < goal_state->v) { + goal_state->expanded_best_parent = goal_state->best_parent; + goal_state->v = goal_state->g; + } + return 1; +} + +vector LazyARAPlanner::GetSearchPath(int& solcost) +{ + vector SuccIDV; + vector CostV; + vector isTrueCost; + vector wholePathIds; + + LazyARAState* state = goal_state; + LazyARAState* final_state = start_state; + + // if the goal was not expanded but was generated (we don't have a bound on + // the solution) pretend that it was expanded for path reconstruction and + // revert the state afterward + bool goal_expanded = true; + if (goal_state->expanded_best_parent == NULL) { + goal_expanded = false; + goal_state->expanded_best_parent = goal_state->best_parent; + goal_state->v = goal_state->g; + } + + wholePathIds.push_back(state->id); + solcost = 0; + + while (state->id != final_state->id) { + if (state->expanded_best_parent == NULL) { + SBPL_DEBUG("a state along the path has no parent!"); + break; + } + if (state->v == INFINITECOST) { + SBPL_DEBUG("a state along the path has an infinite g-value!"); + SBPL_DEBUG("inf state = %d", state->id); + break; + } + + if (bforwardsearch) { + environment_->GetLazySuccs(state->expanded_best_parent->id, &SuccIDV, &CostV, &isTrueCost); + } + else { + environment_->GetLazyPreds(state->expanded_best_parent->id, &SuccIDV, &CostV, &isTrueCost); + } + int actioncost = INFINITECOST; + for (unsigned int i = 0; i < SuccIDV.size(); i++) { + if (SuccIDV[i] == state->id && CostV[i] < actioncost) { + actioncost = CostV[i]; + } + } + if (actioncost == INFINITECOST) { + SBPL_WARN("WARNING: actioncost = %d", actioncost); + } + solcost += actioncost; + + state = state->expanded_best_parent; + wholePathIds.push_back(state->id); + } + + // if we pretended that the goal was expanded for path reconstruction then + // revert the state now + if (!goal_expanded) { + goal_state->expanded_best_parent = NULL; + goal_state->v = INFINITECOST; + } + + // if we searched forward then the path reconstruction worked backward from + // the goal, so we have to reverse the path + if (bforwardsearch) { + // in place reverse + for (unsigned int i = 0; i < wholePathIds.size() / 2; i++) { + int other_idx = wholePathIds.size() - i - 1; + int temp = wholePathIds[i]; + wholePathIds[i] = wholePathIds[other_idx]; + wholePathIds[other_idx] = temp; + } + } + + return wholePathIds; +} + +bool LazyARAPlanner::outOfTime() +{ + // if we are supposed to run until the first solution, then we are never out + // of time + if (params.return_first_solution) { + return false; + } + double time_used = double(clock() - TimeStarted) / CLOCKS_PER_SEC; + if (time_used >= params.max_time) { + SBPL_DEBUG("out of max time"); + } + if (use_repair_time && eps_satisfied != INFINITECOST && time_used >= params.repair_time) { + SBPL_DEBUG("used all repair time..."); + } + // we are out of time if: + // we used up the max time limit OR + // we found some solution and used up the minimum time limit + return time_used >= params.max_time || + (use_repair_time && eps_satisfied != INFINITECOST && time_used >= params.repair_time); +} + +void LazyARAPlanner::initializeSearch() +{ + // it's a new search, so increment replan_number and reset the + // search_iteration + replan_number++; + search_iteration = 0; + search_expands = 0; + totalPlanTime = 0; + totalExpands = 0; + reconstructTime = 0; + totalTime = 0; + + // clear open list, incons list, and stats list + heap.makeemptyheap(); + incons.clear(); + stats.clear(); + + // initialize epsilon variable + eps = params.initial_eps; + eps_satisfied = INFINITECOST; + + // call get state to initialize the start and goal states + if (bforwardsearch) { + goal_state = GetState(goal_state_id); + start_state = GetState(start_state_id); + } + else { + start_state = GetState(goal_state_id); + goal_state = GetState(start_state_id); + } + + // put start state in the heap + start_state->g = 0; + CKey key; + key.key[0] = eps * start_state->h; + heap.insertheap(start_state, key); + + // ensure heuristics are up-to-date + environment_->EnsureHeuristicsUpdated((bforwardsearch == true)); +} + +bool LazyARAPlanner::Search(vector& pathIds, int& PathCost) +{ + CKey key; + TimeStarted = clock(); + + initializeSearch(); + + // the main loop of ARA* + while (eps_satisfied > params.final_eps && !outOfTime()) { + + // run weighted A* + clock_t before_time = clock(); + int before_expands = search_expands; + // ImprovePath returns: + // 1 if the solution is found + // 0 if the solution does not exist + // 2 if it ran out of time + int ret = ImprovePath(); + if (ret == 1) { + // solution found for this iteration + eps_satisfied = eps; + } + int delta_expands = search_expands - before_expands; + double delta_time = double(clock() - before_time) / CLOCKS_PER_SEC; + + // print the bound, expands, and time for that iteration + SBPL_DEBUG("bound=%f expands=%d cost=%d time=%.3f", eps_satisfied, delta_expands, goal_state->g, delta_time); + + // update stats + totalPlanTime += delta_time; + totalExpands += delta_expands; + PlannerStats tempStat; + tempStat.eps = eps_satisfied; + tempStat.expands = delta_expands; + tempStat.time = delta_time; + tempStat.cost = goal_state->g; + stats.push_back(tempStat); + + // no solution exists + if (ret == 0) { + SBPL_DEBUG("Solution does not exist"); + return false; + } + + // if we're just supposed to find the first solution or if we ran out of + // time, we're done + if (params.return_first_solution || ret == 2) { + break; + } + + prepareNextSearchIteration(); + } + + if (goal_state->g == INFINITECOST) { + SBPL_DEBUG("could not find a solution (ran out of time)"); + return false; + } + if (eps_satisfied == INFINITECOST) { + SBPL_DEBUG("WARNING: a solution was found but we don't have quality bound for it!"); + } + + SBPL_DEBUG("solution found"); + clock_t before_reconstruct = clock(); + pathIds = GetSearchPath(PathCost); + reconstructTime = double(clock() - before_reconstruct) / CLOCKS_PER_SEC; + totalTime = totalPlanTime + reconstructTime; + + return true; +} + +void LazyARAPlanner::prepareNextSearchIteration() +{ + //decrease epsilon + eps -= params.dec_eps; + if (eps < params.final_eps) { + eps = params.final_eps; + } + + // dump the inconsistent states into the open list + CKey key; + while (!incons.empty()) { + LazyARAState* s = incons.back(); + incons.pop_back(); + s->in_incons = false; + key.key[0] = s->g + int(eps * s->h); + heap.insertheap(s,key); + } + + // recompute priorities for states in OPEN and reorder it + for (int i = 1; i <= heap.currentsize; ++i){ + LazyARAState* state = (LazyARAState*)heap.heap[i].heapstate; + heap.heap[i].key.key[0] = state->g + int(eps * state->h); + } + heap.makeheap(); + + search_iteration++; +} + +//-----------------------------Interface function------------------------------- + +int LazyARAPlanner::replan( + double allocated_time_secs, + std::vector* solution_stateIDs_V) +{ + int solcost = 0; + return replan(allocated_time_secs, solution_stateIDs_V, &solcost); +} + +int LazyARAPlanner::replan( + double allocated_time_sec, + std::vector* solution_stateIDs_V, + int* solcost) +{ + params.max_time = allocated_time_sec; + return replan(solution_stateIDs_V, params, solcost); +} + +int LazyARAPlanner::replan( + vector* solution_stateIDs_V, + ReplanParams p) +{ + int solcost = 0; + return replan(solution_stateIDs_V, p, &solcost); +} + +int LazyARAPlanner::replan( + int start, + int goal, + vector* solution_stateIDs_V, + ReplanParams p, + int* solcost) +{ + set_start(start); + set_goal(goal); + return replan(solution_stateIDs_V, p, solcost); +} + +int LazyARAPlanner::replan( + vector* solution_stateIDs_V, + ReplanParams p, + int* solcost) +{ + SBPL_DEBUG("planner: replan called"); + params = p; + use_repair_time = params.repair_time >= 0; + + if (goal_state_id < 0) { + SBPL_ERROR("ERROR searching: no goal state set"); + return 0; + } + if (start_state_id < 0) { + SBPL_ERROR("ERROR searching: no start state set"); + return 0; + } + + // plan + vector pathIds; + int PathCost = 0; + bool solnFound = Search(pathIds, PathCost); + SBPL_DEBUG("total expands=%d planning time=%.3f reconstruct path time=%.3f total time=%.3f solution cost=%d", totalExpands, totalPlanTime, reconstructTime, totalTime, goal_state->g); + + // copy the solution + *solution_stateIDs_V = pathIds; + *solcost = PathCost; + + start_state_id = -1; + goal_state_id = -1; + + return (int)solnFound; +} + +int LazyARAPlanner::set_goal(int id) +{ + SBPL_DEBUG("planner: setting goal to %d", id); + if (bforwardsearch) { + goal_state_id = id; + } + else { + start_state_id = id; + } + return 1; +} + +int LazyARAPlanner::set_start(int id) +{ + SBPL_DEBUG("planner: setting start to %d", id); + if (bforwardsearch) { + start_state_id = id; + } + else { + goal_state_id = id; + } + return 1; +} + + +//------------------------------------------------------------------------------ + +void LazyARAPlanner::get_search_stats(vector* s) +{ + s->clear(); + s->reserve(stats.size()); + for (unsigned int i = 0; i < stats.size(); i++) { + s->push_back(stats[i]); + } +} + diff --git a/navigations/sbpl/src/planners/mhaplanner.cpp b/navigations/sbpl/src/planners/mhaplanner.cpp new file mode 100755 index 0000000..5ae86b9 --- /dev/null +++ b/navigations/sbpl/src/planners/mhaplanner.cpp @@ -0,0 +1,654 @@ +/* + * Copyright (c) 2015, Maxim Likhachev + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Carnegie Mellon University nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include + +#include +#include +#include +#include + +#include + +static double GetTime() +{ + return (double)clock() / (double)CLOCKS_PER_SEC; +} + +MHAPlanner::MHAPlanner( + DiscreteSpaceInformation* environment, + Heuristic* hanchor, + Heuristic** heurs, + int hcount) +: + SBPLPlanner(), +// environment_(environment), + m_hanchor(hanchor), + m_heurs(heurs), + m_hcount(hcount), + m_params(0.0), + m_initial_eps_mha(1.0), + m_max_expansions(0), + m_eps(1.0), + m_eps_mha(1.0), + m_eps_satisfied((double)INFINITECOST), + m_num_expansions(0), + m_elapsed(0.0), + m_call_number(0), // uninitialized + m_start_state(NULL), + m_goal_state(NULL), + m_search_states(), + m_open(NULL) +{ + environment_ = environment; + + m_open = new CHeap[hcount + 1]; + + // Overwrite default members for ReplanParams to represent a single optimal + // search + m_params.initial_eps = 1.0; + m_params.final_eps = 1.0; + m_params.dec_eps = 0.2; // NOTE: same initial epsilon delta as ARA* + m_params.return_first_solution = false; + m_params.max_time = 0.0; + m_params.repair_time = 0.0; + + /// Four Modes: + /// Search Until Solution Bounded + /// Search Until Solution Unbounded + /// Improve Solution Bounded + /// Improve Solution Unbounded +} + +MHAPlanner::~MHAPlanner() +{ + clear(); + + delete[] m_open; +} + +int MHAPlanner::set_start(int start_stateID) +{ + m_start_state = get_state(start_stateID); + if (!m_start_state) { + return 0; + } + else { + return 1; + } +} + +int MHAPlanner::set_goal(int goal_stateID) +{ + m_goal_state = get_state(goal_stateID); + if (!m_goal_state) { + return 0; + } + else { + return 1; + } +} + +int MHAPlanner::replan( + double allocated_time_sec, + std::vector* solution_stateIDs_V) +{ + int solcost; + return replan(allocated_time_sec, solution_stateIDs_V, &solcost); +} + +int MHAPlanner::replan( + double allocated_time_sec, + std::vector* solution_stateIDs_V, + int* solcost) +{ + ReplanParams params = m_params; + params.max_time = allocated_time_sec; + return replan(solution_stateIDs_V, params, solcost); +} + +int MHAPlanner::replan( + std::vector* solution_stateIDs_V, + ReplanParams params) +{ + int solcost; + return replan(solution_stateIDs_V, params, &solcost); +} + +int MHAPlanner::replan( + std::vector* solution_stateIDs_V, + ReplanParams params, + int* solcost) +{ + if (!check_params(params)) { // errors printed within + return 0; + } + + m_params = params; + + SBPL_INFO("Generic Search parameters:"); + SBPL_INFO(" Initial Epsilon: %0.3f", m_params.initial_eps); + SBPL_INFO(" Final Epsilon: %0.3f", m_params.final_eps); + SBPL_INFO(" Delta Epsilon: %0.3f", m_params.dec_eps); + SBPL_INFO(" Return First Solution: %s", m_params.return_first_solution ? "true" : "false"); + SBPL_INFO(" Max Time: %0.3f", m_params.max_time); + SBPL_INFO(" Repair Time: %0.3f", m_params.repair_time); + SBPL_INFO("MHA Search parameters:"); + SBPL_INFO(" MHA Epsilon: %0.3f", m_initial_eps_mha); + SBPL_INFO(" Max Expansions: %d", m_max_expansions); + + environment_->EnsureHeuristicsUpdated(true); // TODO: support backwards search + + // TODO: pick up from where last search left off and detect lazy + // reinitializations + reinit_search(); + + m_eps = m_params.initial_eps; + m_eps_mha = m_initial_eps_mha; + m_eps_satisfied = (double)INFINITECOST; + + // reset time limits + m_num_expansions = 0; + m_elapsed = 0.0; + + double start_time, end_time; + + start_time = GetTime(); + + ++m_call_number; + reinit_state(m_goal_state); + reinit_state(m_start_state); + m_start_state->g = 0; + + // insert start state into all heaps with key(start, i) as priority + for (int hidx = 0; hidx < num_heuristics(); ++hidx) { + CKey key; + key.key[0] = compute_key(m_start_state, hidx); + m_open[hidx].insertheap(&m_start_state->od[hidx].open_state, key); + SBPL_DEBUG("Inserted start state %d into search %d with f = %d", m_start_state->state_id, hidx, key.key[0]); + } + + end_time = GetTime(); + m_elapsed += (end_time - start_time); + + while (!m_open[0].emptyheap() && !time_limit_reached()) { + start_time = GetTime(); + + // special case for mha* without additional heuristics + if (num_heuristics() == 1) { + if (m_goal_state->g <= get_minf(m_open[0])) { + m_eps_satisfied = m_eps * m_eps_mha; + extract_path(solution_stateIDs_V, solcost); + return 1; + } + else { + MHASearchState* s = state_from_open_state(m_open[0].getminheap()); + expand(s, 0); + } + } + + for (int hidx = 1; hidx < num_heuristics(); ++hidx) { + if (m_open[0].emptyheap()) { + break; + } + + if (!m_open[hidx].emptyheap() && get_minf(m_open[hidx]) <= + m_eps_mha * get_minf(m_open[0])) + { + if (m_goal_state->g <= get_minf(m_open[hidx])) { + m_eps_satisfied = m_eps * m_eps_mha; + extract_path(solution_stateIDs_V, solcost); + return 1; + } + else { + MHASearchState* s = + state_from_open_state(m_open[hidx].getminheap()); + expand(s, hidx); + } + } + else { + if (m_goal_state->g <= get_minf(m_open[0])) { + m_eps_satisfied = m_eps * m_eps_mha; + extract_path(solution_stateIDs_V, solcost); + return 1; + } + else { + MHASearchState* s = + state_from_open_state(m_open[0].getminheap()); + expand(s, 0); + } + } + } + end_time = GetTime(); + m_elapsed += (end_time - start_time); + } + + if (m_open[0].emptyheap()) { + SBPL_DEBUG("Anchor search exhausted"); + } + if (time_limit_reached()) { + SBPL_DEBUG("Time limit reached"); + } + + return 0; +} + +int MHAPlanner::force_planning_from_scratch() +{ + return 0; +} + +int MHAPlanner::force_planning_from_scratch_and_free_memory() +{ + return 0; +} + +void MHAPlanner::costs_changed(StateChangeQuery const & stateChange) +{ +} + +void MHAPlanner::costs_changed() +{ +} + +int MHAPlanner::set_search_mode(bool bSearchUntilFirstSolution) +{ + return m_params.return_first_solution = bSearchUntilFirstSolution; +} + +void MHAPlanner::set_initialsolution_eps(double eps) +{ + m_params.initial_eps = eps; +} + +double MHAPlanner::get_initial_eps() +{ + return m_params.initial_eps; +} + +double MHAPlanner::get_solution_eps() const +{ + return m_eps_satisfied; +} + +double MHAPlanner::get_final_epsilon() +{ + return m_eps_satisfied; +} + +double MHAPlanner::get_final_eps_planning_time() +{ + return m_elapsed; +} + +double MHAPlanner::get_initial_eps_planning_time() +{ + return m_elapsed; +} + +int MHAPlanner::get_n_expands() const +{ + return m_num_expansions; +} + +int MHAPlanner::get_n_expands_init_solution() +{ + return m_num_expansions; +} + +void MHAPlanner::get_search_stats(std::vector* s) +{ +} + +void MHAPlanner::set_initial_mha_eps(double eps) +{ + m_initial_eps_mha = eps; +} + +void MHAPlanner::set_final_eps(double eps) +{ + m_params.final_eps = eps; +} + +void MHAPlanner::set_dec_eps(double eps) +{ + m_params.dec_eps = eps; +} + +void MHAPlanner::set_max_expansions(int expansion_count) +{ + m_max_expansions = expansion_count; +} + +void MHAPlanner::set_max_time(double max_time) +{ + m_params.max_time = max_time; +} + +double MHAPlanner::get_initial_mha_eps() const +{ + return m_initial_eps_mha; +} + +double MHAPlanner::get_final_eps() const +{ + return m_params.final_eps; +} + +double MHAPlanner::get_dec_eps() const +{ + return m_params.dec_eps; +} + +int MHAPlanner::get_max_expansions() const +{ + return m_max_expansions; +} + +double MHAPlanner::get_max_time() const +{ + return m_params.max_time; +} + +bool MHAPlanner::check_params(const ReplanParams& params) +{ + if (params.initial_eps < 1.0) { + SBPL_ERROR("Initial Epsilon must be greater than or equal to 1"); + return false; + } + + if (params.final_eps > params.initial_eps) { + SBPL_ERROR("Final Epsilon must be less than or equal to initial epsilon"); + return false; + } + + if (params.dec_eps <= 0.0) { + SBPL_ERROR("Delta epsilon must be strictly positive"); + return false; + } + + if (m_initial_eps_mha < 1.0) { + SBPL_ERROR("MHA Epsilon must be greater than or equal to 1"); + return false; + } + + if (params.return_first_solution && + params.max_time <= 0.0 && + m_max_expansions <= 0) + { + SBPL_ERROR("Max Time or Max Expansions must be positive"); + return false; + } + + return true; +} + +bool MHAPlanner::time_limit_reached() const +{ + if (m_params.return_first_solution) { + return false; + } + else if (m_params.max_time > 0.0 && m_elapsed >= m_params.max_time) { + return true; + } + else if (m_max_expansions > 0 && m_num_expansions >= m_max_expansions) { + return true; + } + else { + return false; + } +} + +MHASearchState* MHAPlanner::get_state(int state_id) +{ + assert(state_id >= 0 && state_id < environment_->StateID2IndexMapping.size()); + int* idxs = environment_->StateID2IndexMapping[state_id]; + if (idxs[MHAMDP_STATEID2IND] == -1) { + // overallocate search state for appropriate heuristic information + const size_t state_size = + sizeof(MHASearchState) + + sizeof(MHASearchState::HeapData) * (m_hcount); + MHASearchState* s = (MHASearchState*)malloc(state_size); + + const size_t mha_state_idx = m_search_states.size(); + init_state(s, mha_state_idx, state_id); + + // map graph state to search state + idxs[MHAMDP_STATEID2IND] = mha_state_idx; + m_search_states.push_back(s); + + return s; + } + else { + int ssidx = idxs[MHAMDP_STATEID2IND]; + return m_search_states[ssidx]; + } +} + +void MHAPlanner::clear() +{ + clear_open_lists(); + + // free states + for (size_t i = 0; i < m_search_states.size(); ++i) { + // unmap graph to search state + const int state_id = m_search_states[i]->state_id; + int* idxs = environment_->StateID2IndexMapping[state_id]; + idxs[MHAMDP_STATEID2IND] = -1; + + // free search state + free(m_search_states[i]); + } + + // empty state table + m_search_states.clear(); + + m_start_state = NULL; + m_goal_state = NULL; +} + +void MHAPlanner::init_state( + MHASearchState* state, + size_t mha_state_idx, + int state_id) +{ + state->call_number = 0; // not initialized for any iteration + state->state_id = state_id; + state->closed_in_anc = false; + state->closed_in_add = false; + for (int i = 0; i < num_heuristics(); ++i) { + state->od[i].open_state.heapindex = 0; + state->od[i].h = compute_heuristic(state->state_id, i); + // hijack list element pointers to map back to mha search state + assert(sizeof(state->od[i].open_state.listelem) >= sizeof(struct listelement*)); + reinterpret_cast(state->od[i].open_state.listelem[0]) = mha_state_idx; + } +} + +void MHAPlanner::reinit_state(MHASearchState* state) +{ + if (state->call_number != m_call_number) { + state->call_number = m_call_number; + state->g = INFINITECOST; + state->bp = NULL; + + state->closed_in_anc = false; + state->closed_in_add = false; + + for (int i = 0; i < num_heuristics(); ++i) { + state->od[i].open_state.heapindex = 0; + state->od[i].h = compute_heuristic(state->state_id, i); + } + } +} + +void MHAPlanner::reinit_search() +{ + clear_open_lists(); +} + +void MHAPlanner::clear_open_lists() +{ + for (int i = 0; i < num_heuristics(); ++i) { + m_open[i].makeemptyheap(); + } +} + +int MHAPlanner::compute_key(MHASearchState* state, int hidx) +{ + return state->g + m_eps * state->od[hidx].h; +} + +void MHAPlanner::expand(MHASearchState* state, int hidx) +{ + SBPL_DEBUG("Expanding state %d in search %d", state->state_id, hidx); + + assert(!closed_in_add_search(state) || !closed_in_anc_search(state)); + + if (hidx == 0) { + state->closed_in_anc = true; + } + else { + state->closed_in_add = true; + } + ++m_num_expansions; + + // remove s from all open lists + for (int temp_hidx = 0; temp_hidx < num_heuristics(); ++temp_hidx) { + if (m_open[temp_hidx].inheap(&state->od[temp_hidx].open_state)) { + m_open[temp_hidx].deleteheap(&state->od[temp_hidx].open_state); + } + } + + std::vector succ_ids; + std::vector costs; + environment_->GetSuccs(state->state_id, &succ_ids, &costs); + assert(succ_ids.size() == costs.size()); + + for (size_t sidx = 0; sidx < succ_ids.size(); ++sidx) { + const int cost = costs[sidx]; + MHASearchState* succ_state = get_state(succ_ids[sidx]); + reinit_state(succ_state); + + SBPL_DEBUG(" Successor %d", succ_state->state_id); + + int new_g = state->g + costs[sidx]; + if (new_g < succ_state->g) { + succ_state->g = new_g; + succ_state->bp = state; + if (!closed_in_anc_search(succ_state)) { + const int fanchor = compute_key(succ_state, 0); + insert_or_update(succ_state, 0, fanchor); + SBPL_DEBUG(" Update in search %d with f = %d", 0, fanchor); + + if (!closed_in_add_search(succ_state)) { + for (int temp_hidx = 1; temp_hidx < num_heuristics(); ++temp_hidx) { + int fn = compute_key(succ_state, temp_hidx); + if (fn <= m_eps_mha * fanchor) { + insert_or_update(succ_state, temp_hidx, fn); + SBPL_DEBUG(" Update in search %d with f = %d", temp_hidx, fn); + } + else { + SBPL_DEBUG(" Skipping update of in search %d (%0.3f > %0.3f)", temp_hidx, (double)fn, m_eps_mha * fanchor); + } + } + } + } + } + } + + assert(closed_in_any_search(state)); +} + +MHASearchState* MHAPlanner::state_from_open_state( + AbstractSearchState* open_state) +{ + const size_t ssidx = reinterpret_cast(open_state->listelem[0]); + return m_search_states[ssidx]; +} + +int MHAPlanner::compute_heuristic(int state_id, int hidx) +{ + if (hidx == 0) { + return m_hanchor->GetGoalHeuristic(state_id); + } + else { + return m_heurs[hidx - 1]->GetGoalHeuristic(state_id); + } +} + +int MHAPlanner::get_minf(CHeap& pq) const +{ + return pq.getminkeyheap().key[0]; +} + +void MHAPlanner::insert_or_update(MHASearchState* state, int hidx, int f) +{ + CKey new_key; + new_key.key[0] = f; + + if (state->od[hidx].open_state.heapindex != 0) { + m_open[hidx].updateheap(&state->od[hidx].open_state, new_key); + } + else { + m_open[hidx].insertheap(&state->od[hidx].open_state, new_key); + } +} + +void MHAPlanner::extract_path(std::vector* solution_path, int* solcost) +{ + SBPL_DEBUG("Extracting path"); + solution_path->clear(); + *solcost = 0; + for (MHASearchState* state = m_goal_state; state; state = state->bp) + { + solution_path->push_back(state->state_id); + if (state->bp) { + *solcost += (state->g - state->bp->g); + } + } + + // TODO: special cases for backward search + std::reverse(solution_path->begin(), solution_path->end()); +} + +bool MHAPlanner::closed_in_anc_search(MHASearchState* state) const +{ + return state->closed_in_anc; +} + +bool MHAPlanner::closed_in_add_search(MHASearchState* state) const +{ + return state->closed_in_add; +} + +bool MHAPlanner::closed_in_any_search(MHASearchState* state) const +{ + return state->closed_in_anc || state->closed_in_add; +} diff --git a/navigations/sbpl/src/planners/ppcpplanner.cpp b/navigations/sbpl/src/planners/ppcpplanner.cpp new file mode 100755 index 0000000..fe20dc5 --- /dev/null +++ b/navigations/sbpl/src/planners/ppcpplanner.cpp @@ -0,0 +1,135 @@ +/* + * Copyright (c) 2009, Maxim Likhachev + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Carnegie Mellon University nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include + +using namespace std; + +//----------------------------------------------------------------------------------------------------- + +PPCPPlanner::PPCPPlanner(DiscreteSpaceInformation* environment, int sizeofS, int sizeofH) +{ + environment_ = environment; + +#ifndef ROS + const char* debug = "debug.txt"; +#endif + fDeb = SBPL_FOPEN(debug, "w"); + if (fDeb == NULL) { + throw SBPL_Exception("ERROR: could not open planner debug file"); + } + + pStateSpace = new PPCPStateSpace_t; + + //TODO - create and initialize the state-space +} + +PPCPPlanner::~PPCPPlanner() +{ + if (pStateSpace != NULL) { + //delete the statespace + DeleteStateSpace( pStateSpace); + delete pStateSpace; + pStateSpace = NULL; + } + SBPL_FCLOSE( fDeb); +} + +//deallocates memory used by StateSpace +void PPCPPlanner::DeleteStateSpace(PPCPStateSpace_t* pStateSpace) +{ + //TODO - fill in +} + +//creates (allocates memory) search state space +//does not initialize search statespace +int PPCPPlanner::CreateSearchStateSpace(PPCPStateSpace_t* pStateSpace) +{ + //create a heap + pStateSpace->bReinitializeSearchStateSpace = true; + pStateSpace->currentpolicyconfidence = 0; + pStateSpace->GoalState = NULL; + pStateSpace->StartState = NULL; + pStateSpace->iteration = 0; + pStateSpace->searchiteration = 0; + + return 1; +} + +//-------------------------------------------------------------------------------------------------- + +//------------------------------------------------------------------------------------------------- + +//setting start state in S +int PPCPPlanner::set_goal(int goal_stateID) +{ + //TODO + return 1; +} + +//setting goal state in S +int PPCPPlanner::set_start(int start_stateID) +{ + //TODO + return 1; +} + +void PPCPPlanner::costs_changed(StateChangeQuery const & stateChange) +{ + SBPL_PRINTF("planner: costs_changed, state-space reset\n"); + + pStateSpace->bReinitializeSearchStateSpace = true; +} + +void PPCPPlanner::costs_changed() +{ + SBPL_PRINTF("planner: costs_changed, state-space reset\n"); + + pStateSpace->bReinitializeSearchStateSpace = true; +} + +int PPCPPlanner::force_planning_from_scratch() +{ + SBPL_PRINTF("planner: forceplanfromscratch set, state-space reset\n"); + + pStateSpace->bReinitializeSearchStateSpace = true; + + return 1; +} + +int PPCPPlanner::replan(double allocated_time_secs, vector* SolutionPolicy, + float* ExpectedCost, float* ProbofReachGoal) +{ + //TODO + return 0; +} + +//------------------------------------------------------------------------------------------------- + diff --git a/navigations/sbpl/src/planners/rstarplanner.cpp b/navigations/sbpl/src/planners/rstarplanner.cpp new file mode 100755 index 0000000..d5b4bfb --- /dev/null +++ b/navigations/sbpl/src/planners/rstarplanner.cpp @@ -0,0 +1,1463 @@ +/* + * Copyright (c) 2008, Maxim Likhachev + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Carnegie Mellon University nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include + +#include +#include +#include + +using namespace std; + +//TODO - define RSTAR_DEBUG_PRINTLOWLEVELEXP and RSTAR_DEBUG_PRINTHIGHLEVELEXP. Make them dependent on DEBUG +//use them to print expands into two separate file. + +//----------------------------------------------------------------------------------------------------- + +RSTARPlanner::RSTARPlanner(DiscreteSpaceInformation* environment, bool bSearchForward) +{ + bforwardsearch = bSearchForward; + + environment_ = environment; + + bsearchuntilfirstsolution = false; + finitial_eps = RSTAR_DEFAULT_INITIAL_EPS; + dec_eps = RSTAR_DECREASE_EPS; + final_epsilon = RSTAR_FINAL_EPS; + local_expand_thres = RSTAR_EXPTHRESH; + highlevel_searchexpands = 0; + lowlevel_searchexpands = 0; + MaxMemoryCounter = 0; + +#ifndef ROS + const char* debug = "debug.txt"; +#endif + fDeb = SBPL_FOPEN(debug, "w"); + if (fDeb == NULL) { + throw SBPL_Exception("ERROR: could not open planner debug file"); + } + SBPL_PRINTF("debug on\n"); + + //create global searchstatespace + pSearchStateSpace = new RSTARSearchStateSpace_t; + MaxMemoryCounter += sizeof(RSTARSearchStateSpace_t); + + //create local searchstatespace + pLSearchStateSpace = new RSTARLSearchStateSpace_t; + MaxMemoryCounter += sizeof(RSTARLSearchStateSpace_t); + + //create the RSTAR planner + if (CreateSearchStateSpace() != 1) { + SBPL_ERROR("ERROR: failed to create statespace\n"); + return; + } + + //set the start and goal states + if (InitializeSearchStateSpace() != 1) { + SBPL_ERROR("ERROR: failed to create statespace\n"); + return; + } +} + +RSTARPlanner::~RSTARPlanner() +{ + if (pSearchStateSpace != NULL) { + //delete the statespace + DeleteSearchStateSpace(); + delete pSearchStateSpace; + } + SBPL_FCLOSE( fDeb); +} + +void RSTARPlanner::Initialize_searchinfo(CMDPSTATE* state) +{ + RSTARState* searchstateinfo = (RSTARState*)state->PlannerSpecificData; + + searchstateinfo->MDPstate = state; + InitializeSearchStateInfo(searchstateinfo); +} + +CMDPSTATE* RSTARPlanner::CreateState(int stateID) +{ + CMDPSTATE* state = NULL; + +#if DEBUG + if(environment_->StateID2IndexMapping[stateID][RSTARMDP_STATEID2IND] != -1) + { + throw SBPL_Exception("ERROR in CreateState: state already created"); + } +#endif + + //adds to the tail a state + state = pSearchStateSpace->searchMDP.AddState(stateID); + + //remember the index of the state + environment_->StateID2IndexMapping[stateID][RSTARMDP_STATEID2IND] = + pSearchStateSpace->searchMDP.StateArray.size() - 1; + +#if DEBUG + if(state != + pSearchStateSpace->searchMDP.StateArray[environment_->StateID2IndexMapping[stateID][RSTARMDP_STATEID2IND]]) + { + throw SBPL_Exception("ERROR in CreateState: invalid state index"); + } +#endif + + //create search specific info + state->PlannerSpecificData = new RSTARState; + MaxMemoryCounter += sizeof(RSTARState); + Initialize_searchinfo(state); + + return state; +} + +CMDPSTATE* RSTARPlanner::GetState(int stateID) +{ + if (stateID >= (int)environment_->StateID2IndexMapping.size()) { + SBPL_ERROR("ERROR int GetState: stateID %d is invalid\n", stateID); + std::stringstream ss("ERROR int GetState: stateID "); + ss << stateID << " is invalid"; + throw SBPL_Exception(ss.str()); + } + + if (environment_->StateID2IndexMapping[stateID][RSTARMDP_STATEID2IND] == -1) + return CreateState(stateID); + else + return pSearchStateSpace->searchMDP.StateArray[environment_->StateID2IndexMapping[stateID][RSTARMDP_STATEID2IND]]; +} + +//----------------------------------------------------------------------------------------------------- + +//----------------------------------------functions related to local searches------------------------------------------- + +void RSTARPlanner::Initialize_rstarlsearchdata(CMDPSTATE* state) +{ + RSTARLSearchState* rstarlsearch_data = (RSTARLSearchState*)state->PlannerSpecificData; + + rstarlsearch_data->bestpredstate = NULL; + rstarlsearch_data->bestpredstateactioncost = 0; + rstarlsearch_data->iteration = 0; + rstarlsearch_data->iterationclosed = 0; + rstarlsearch_data->g = INFINITECOST; + rstarlsearch_data->heapindex = 0; + rstarlsearch_data->listelem[0] = NULL; + rstarlsearch_data->listelem[1] = NULL; + + //pointer to itself + rstarlsearch_data->MDPstate = state; +} + +CMDPSTATE* RSTARPlanner::CreateLSearchState(int stateID) +{ + CMDPSTATE* state = NULL; + +#if DEBUG + if (environment_->StateID2IndexMapping[stateID][RSTARMDP_LSEARCH_STATEID2IND] != -1) { + throw SBPL_Exception("ERROR in CreateState: state already created"); + } +#endif + + //adds to the tail a state + state = pLSearchStateSpace->MDP.AddState(stateID); + + //remember the index of the state + environment_->StateID2IndexMapping[stateID][RSTARMDP_LSEARCH_STATEID2IND] + = pLSearchStateSpace->MDP.StateArray.size() - 1; + +#if DEBUG + if(state != + pLSearchStateSpace->MDP.StateArray[environment_->StateID2IndexMapping[stateID][RSTARMDP_LSEARCH_STATEID2IND]]) + { + throw SBPL_Exception("ERROR in CreateState: invalid state index"); + } +#endif + + //create and initialize rstarlsearch_data + state->PlannerSpecificData = new RSTARLSearchState; + Initialize_rstarlsearchdata(state); + + return state; +} + +CMDPSTATE* RSTARPlanner::GetLSearchState(int stateID) +{ + if (stateID >= (int)environment_->StateID2IndexMapping.size()) { + throw SBPL_Exception("ERROR int GetLSearchState: stateID is invalid"); + } + + if (environment_->StateID2IndexMapping[stateID][RSTARMDP_LSEARCH_STATEID2IND] == -1) + return CreateLSearchState(stateID); + else + return pLSearchStateSpace->MDP.StateArray[environment_->StateID2IndexMapping[stateID][RSTARMDP_LSEARCH_STATEID2IND]]; +} + +CKey RSTARPlanner::LocalSearchComputeKey(RSTARLSearchState* rstarlsearchState) +{ + CKey retkey; + + int h; + if (bforwardsearch) + h = environment_->GetFromToHeuristic(rstarlsearchState->MDPstate->StateID, + pLSearchStateSpace->GoalState->StateID); + else + h = environment_->GetFromToHeuristic(pLSearchStateSpace->GoalState->StateID, + rstarlsearchState->MDPstate->StateID); + + retkey.key[0] = rstarlsearchState->g + (int)(pSearchStateSpace->eps * h); + + return retkey; +} + +bool RSTARPlanner::ComputeLocalPath(int StartStateID, int GoalStateID, int maxc, int maxe, int *pCost, int *pCostLow, + int *pExp, vector* pPathIDs, int* pNewGoalStateID, double maxnumofsecs) +{ + vector SuccIDV; + vector CostV; + + if (pLSearchStateSpace->OPEN == NULL) pLSearchStateSpace->OPEN = new CHeap; + if (pLSearchStateSpace->INCONS == NULL) pLSearchStateSpace->INCONS = new CList; + + int local_expands = 0; + *pNewGoalStateID = GoalStateID; + + //increase iteration + pLSearchStateSpace->iteration++; + + //set the start and goal states + pLSearchStateSpace->StartState = GetLSearchState(StartStateID); + pLSearchStateSpace->GoalState = GetLSearchState(GoalStateID); + + RSTARLSearchState* rstarlsearchstate = (RSTARLSearchState*)pLSearchStateSpace->StartState->PlannerSpecificData; + RSTARLSearchState* rstarlsearchgoalstate = (RSTARLSearchState*)pLSearchStateSpace->GoalState->PlannerSpecificData; + + //OPEN=0 (it shouldn't be necessary since the memory is cleared before each search) + pLSearchStateSpace->OPEN->makeemptyheap(); + pLSearchStateSpace->INCONS->makeemptylist(RSTAR_INCONS_LIST_ID); + + //CLOSED = 0 because iteration is increased + + //g(start) = 0 + rstarlsearchstate->g = 0; + + //insert start into open + pLSearchStateSpace->OPEN->insertheap(rstarlsearchstate, LocalSearchComputeKey(rstarlsearchstate)); + + //TODO - prove that min_{OPEN and INCONS} (g + eps*h) <= eps*c*. (proof: take min_{OPEN and INCONS} (g+h) <= c* and + //multiply both sides by eps and then bring eps into min and drop one by + //g. I still need to implement INCONS and minimum tracker for it - then + //change the minkey to min over two sets + while (rstarlsearchgoalstate->g > pLSearchStateSpace->OPEN->getminkeyheap().key[0] && local_expands < maxe && + pLSearchStateSpace->OPEN->getminkeyheap().key[0] <= maxc) + { + //pop the min element + rstarlsearchstate = (RSTARLSearchState*)pLSearchStateSpace->OPEN->deleteminheap(); + + //close the state + rstarlsearchstate->iterationclosed = pLSearchStateSpace->iteration; + + //expansion + local_expands++; + //environment_->PrintState(rstarlsearchstate->MDPstate->StateID, false, fLowLevelExp); + + //generate SUCCS state + SuccIDV.clear(); + CostV.clear(); + //this setting makes it to get all successors - since this is a deterministic search + if (bforwardsearch == false) + environment_->GetPreds(rstarlsearchstate->MDPstate->StateID, &SuccIDV, &CostV); + else + environment_->GetSuccs(rstarlsearchstate->MDPstate->StateID, &SuccIDV, &CostV); + + //iterate over states in SUCCS set + for (int i = 0; i < (int)SuccIDV.size(); i++) { + RSTARLSearchState* rstarlsearchSuccState = + (RSTARLSearchState*)GetLSearchState(SuccIDV.at(i))->PlannerSpecificData; + + //skip if the state is already closed - TODO fix this with INCONS + //list - it seems to make five times less expansions! + //if(rstarlsearchSuccState->iterationclosed == pLSearchStateSpace->iteration) + //continue; + + //see if we can improve g-value of successor + if (rstarlsearchstate->g + CostV[i] < rstarlsearchSuccState->g) { + rstarlsearchSuccState->bestpredstate = rstarlsearchstate->MDPstate; + rstarlsearchSuccState->bestpredstateactioncost = CostV[i]; + rstarlsearchSuccState->g = rstarlsearchstate->g + CostV[i]; + if (rstarlsearchSuccState->heapindex == 0) + pLSearchStateSpace->OPEN->insertheap(rstarlsearchSuccState, + LocalSearchComputeKey(rstarlsearchSuccState)); + else + pLSearchStateSpace->OPEN->updateheap(rstarlsearchSuccState, + LocalSearchComputeKey(rstarlsearchSuccState)); + + int goalStateID = pSearchStateSpace->searchgoalstate->StateID; + if (!environment_->AreEquivalent(rstarlsearchSuccState->MDPstate->StateID, goalStateID) && + environment_->AreEquivalent(rstarlsearchSuccState->MDPstate->StateID, + rstarlsearchgoalstate->MDPstate->StateID) && + rstarlsearchSuccState->g < rstarlsearchgoalstate->g) + { + //swap the goal + rstarlsearchgoalstate = rstarlsearchSuccState; + GoalStateID = rstarlsearchgoalstate->MDPstate->StateID; + } + } + } + + if (local_expands % 10000 == 0) { + if ((clock() - TimeStarted) >= maxnumofsecs * (double)CLOCKS_PER_SEC) { + SBPL_PRINTF("breaking local search because global planning time expires\n"); + break; + } + } + }//while + + lowlevel_searchexpands += local_expands; + SBPL_FPRINTF(fDeb, "local search: expands=%d\n", local_expands); + + //set the return path and other path related variables + vector tempPathID; + pPathIDs->clear(); + if (rstarlsearchgoalstate->g < INFINITECOST) { + int pathcost = 0; + + //path exists + rstarlsearchstate = rstarlsearchgoalstate; + while (rstarlsearchstate->bestpredstate != NULL && rstarlsearchstate->MDPstate + != pLSearchStateSpace->StartState) { + tempPathID.push_back(rstarlsearchstate->MDPstate->StateID); + pathcost += rstarlsearchstate->bestpredstateactioncost; + rstarlsearchstate = (RSTARLSearchState*)rstarlsearchstate->bestpredstate->PlannerSpecificData; + } + //store into pPathIDs so that the path is always forward path w.r.t. the original graph + //this requires us to reverse order in case of forward search + for (int i = 0; i < (int)tempPathID.size(); i++) { + if (bforwardsearch == false) + pPathIDs->push_back(tempPathID.at(i)); + else + pPathIDs->push_back(tempPathID.at(tempPathID.size() - i - 1)); + } + *pCost = pathcost; + *pCostLow = rstarlsearchgoalstate->g; + SBPL_FPRINTF(fDeb, "pathcost=%d while g=%d\n", pathcost, rstarlsearchgoalstate->g); + } + else { + *pCost = INFINITECOST; + *pCostLow = pLSearchStateSpace->OPEN->getminkeyheap().key[0]; + if (*pCostLow != pLSearchStateSpace->OPEN->getminkeyheap().key[0]) { + SBPL_FPRINTF(fDeb, "after localsearch clow=%d while keymin=%d\n", (int)(*pCostLow), + (int)pLSearchStateSpace->OPEN->getminkeyheap().key[0]); + } + } + + //set all other return variables + *pExp = local_expands; + *pNewGoalStateID = GoalStateID; + + return true; +} + +bool RSTARPlanner::DestroyLocalSearchMemory() +{ + pLSearchStateSpace->OPEN->currentsize = 0; + pLSearchStateSpace->StartState = pLSearchStateSpace->GoalState = NULL; + + //remove the states in the MDP itself + for (int i = 0; i < (int)pLSearchStateSpace->MDP.StateArray.size(); i++) { + CMDPSTATE* state = pLSearchStateSpace->MDP.StateArray.at(i); + RSTARLSearchState* rstarlsearchstatedata = (RSTARLSearchState*)state->PlannerSpecificData; + delete rstarlsearchstatedata; + state->PlannerSpecificData = NULL; + environment_->StateID2IndexMapping[state->StateID][RSTARMDP_LSEARCH_STATEID2IND] = -1; + } + //now we can delete the states themselves + if (pLSearchStateSpace->MDP.Delete() == false) { + throw SBPL_Exception("ERROR: failed to delete local search MDP"); + } + + //TODO - ask Env to delete the new memory allocated during the local + //search (usings the fact that stateID's for local search continuously and + //no states were allocated for global search before local search exits. + + return true; +} + +//---------------------------------------------------------------------------------------------------------------------- + +int RSTARPlanner::ComputeHeuristic(CMDPSTATE* MDPstate) +{ + //compute heuristic for search + + //the heuristics will be re-computed anyway when searchgoalstate is updated + if (pSearchStateSpace->searchgoalstate == NULL) return 0; + + if (bforwardsearch) { +#if MEM_CHECK == 1 + //int WasEn = DisableMemCheck(); +#endif + + //forward search: heur = distance from state to searchgoal which is Goal RSTARState + int retv = environment_->GetFromToHeuristic(MDPstate->StateID, pSearchStateSpace->searchgoalstate->StateID); + +#if MEM_CHECK == 1 + //if (WasEn) + // EnableMemCheck(); +#endif + + return retv; + } + else { + //backward search: heur = distance from searchgoal to state + return environment_->GetFromToHeuristic(pSearchStateSpace->searchgoalstate->StateID, MDPstate->StateID); + } +} + +//initialization of a state +void RSTARPlanner::InitializeSearchStateInfo(RSTARState* state) +{ + state->g = INFINITECOST; + state->iterationclosed = 0; + state->callnumberaccessed = pSearchStateSpace->callnumber; + state->heapindex = 0; + state->bestpredaction = NULL; + + //compute heuristics +#if USE_HEUR + if(pSearchStateSpace->searchgoalstate != NULL) + state->h = ComputeHeuristic(state->MDPstate); + else + state->h = 0; +#else + state->h = 0; +#endif + + state->predactionV.clear(); +} + +//re-initialization of a state +void RSTARPlanner::ReInitializeSearchStateInfo(RSTARState* state) +{ + state->g = INFINITECOST; + state->iterationclosed = 0; + state->callnumberaccessed = pSearchStateSpace->callnumber; + state->heapindex = 0; + + state->bestpredaction = NULL; + + //compute heuristics +#if USE_HEUR + + if(pSearchStateSpace->searchgoalstate != NULL) + { + state->h = ComputeHeuristic(state->MDPstate); + } + else + state->h = 0; + +#else + + state->h = 0; + +#endif + + state->predactionV.clear(); + for (int i = 0; i < (int)state->MDPstate->Actions.size(); i++) { + if (state->MDPstate->Actions.at(i)->PlannerSpecificData != NULL) { + DeleteSearchActionData((RSTARACTIONDATA*)state->MDPstate->Actions.at(i)->PlannerSpecificData); + delete (RSTARACTIONDATA*)(state->MDPstate->Actions.at(i)->PlannerSpecificData); + state->MDPstate->Actions.at(i)->PlannerSpecificData = NULL; + } + } + state->MDPstate->RemoveAllActions(); +} + +void RSTARPlanner::DeleteSearchStateData(RSTARState* state) +{ + //delete PlannerSpecificData for each action + state->predactionV.clear(); + for (int i = 0; i < (int)state->MDPstate->Actions.size(); i++) { + if (state->MDPstate->Actions.at(i)->PlannerSpecificData != NULL) { + DeleteSearchActionData((RSTARACTIONDATA*)state->MDPstate->Actions.at(i)->PlannerSpecificData); + delete (RSTARACTIONDATA*)state->MDPstate->Actions.at(i)->PlannerSpecificData; + state->MDPstate->Actions.at(i)->PlannerSpecificData = NULL; + } + } + state->MDPstate->RemoveAllActions(); + + return; +} + +void RSTARPlanner::DeleteSearchActionData(RSTARACTIONDATA* actiondata) +{ + //no memory was allocated for actiondata + + return; +} + +int RSTARPlanner::GetGVal(int StateID) +{ + CMDPSTATE* cmdp_state = GetState(StateID); + RSTARState* state = (RSTARState*)cmdp_state->PlannerSpecificData; + return state->g; +} + +void RSTARPlanner::SetBestPredecessor(RSTARState* rstarState, RSTARState* rstarPredState, CMDPACTION* action) +{ + rstarState->bestpredaction = action; + rstarState->g = rstarPredState->g + ((RSTARACTIONDATA*)(action->PlannerSpecificData))->clow; + if (rstarState->heapindex == 0) + pSearchStateSpace->OPEN->insertheap(rstarState, ComputeKey(rstarState)); + else + pSearchStateSpace->OPEN->updateheap(rstarState, ComputeKey(rstarState)); +} + +CKey RSTARPlanner::ComputeKey(RSTARState* rstarState) +{ + CKey retkey; + + int h, starttostateh; + if (bforwardsearch) { + h = environment_->GetFromToHeuristic(rstarState->MDPstate->StateID, + pSearchStateSpace->searchgoalstate->StateID); + starttostateh = environment_->GetFromToHeuristic(pSearchStateSpace->searchstartstate->StateID, + rstarState->MDPstate->StateID); + } + else { + h = environment_->GetFromToHeuristic(pSearchStateSpace->searchgoalstate->StateID, + rstarState->MDPstate->StateID); + starttostateh = environment_->GetFromToHeuristic(rstarState->MDPstate->StateID, + pSearchStateSpace->searchstartstate->StateID); + } + + //compute 2nd element of the key + retkey.key[1] = rstarState->g + (int)(pSearchStateSpace->eps * h); + + //compute the 1st element + if (rstarState->g > pSearchStateSpace->eps * starttostateh || + (rstarState->bestpredaction != NULL && + ((RSTARACTIONDATA*)rstarState->bestpredaction->PlannerSpecificData)->pathIDs.size() == 0 && + ((RSTARACTIONDATA*)rstarState->bestpredaction->PlannerSpecificData)->exp >= local_expand_thres)) + { + retkey.key[0] = 1; + } + else { + retkey.key[0] = 0; + } + + return retkey; +} + +//returns 1 if the solution is found, 0 if the solution does not exist and 2 if it ran out of time +int RSTARPlanner::ImprovePath(double MaxNumofSecs) +{ + int expands; + RSTARState *rstarstate, *searchgoalstate, *searchstartstate; + CKey key, minkey; + CKey goalkey; + + vector SuccIDV; + vector CLowV; + int highlevelexpands = 0; + + expands = 0; + + if (pSearchStateSpace->searchgoalstate == NULL) { + throw SBPL_Exception("ERROR searching: no goal state is set"); + } + + //goal state + searchgoalstate = (RSTARState*)(pSearchStateSpace->searchgoalstate->PlannerSpecificData); + if (searchgoalstate->callnumberaccessed != pSearchStateSpace->callnumber) { + ReInitializeSearchStateInfo( searchgoalstate); + } + + //get the start state + searchstartstate = (RSTARState*)(pSearchStateSpace->searchstartstate->PlannerSpecificData); + + //set goal key + if (searchgoalstate != searchstartstate) { + goalkey.key[0] = 1; + goalkey.key[1] = INFINITECOST; + } + else { + goalkey = ComputeKey(searchstartstate); + } + + //expand states until done + minkey = pSearchStateSpace->OPEN->getminkeyheap(); + while (!pSearchStateSpace->OPEN->emptyheap() && (clock() - TimeStarted) < MaxNumofSecs * (double)CLOCKS_PER_SEC) { + //recompute minkey + minkey = pSearchStateSpace->OPEN->getminkeyheap(); + + //recompute goalkey if necessary + goalkey = ComputeKey(searchgoalstate); + + if (goalkey < minkey) break; //termination condition + + //pop the min element + rstarstate = (RSTARState*)pSearchStateSpace->OPEN->deleteminheap(); + + SBPL_FPRINTF(fDeb, "ComputePath: selected state %d g=%d (AVOID=%d)\n", rstarstate->MDPstate->StateID, + rstarstate->g, (int)minkey.key[0]); + environment_->PrintState(rstarstate->MDPstate->StateID, true, fDeb); + + if (rstarstate->MDPstate != pSearchStateSpace->searchstartstate && + ((RSTARACTIONDATA*)rstarstate->bestpredaction->PlannerSpecificData)->pathIDs.size() == 0) + { + SBPL_FPRINTF(fDeb, "re-compute path\n"); + + int maxe = INFINITECOST; + int maxc = INFINITECOST; + + //predecessor + RSTARState* rstarpredstate = + (RSTARState*)GetState(rstarstate->bestpredaction->SourceStateID)->PlannerSpecificData; + CMDPACTION* computedaction = rstarstate->bestpredaction; + RSTARACTIONDATA* computedactiondata = (RSTARACTIONDATA*)computedaction->PlannerSpecificData; + + if (computedactiondata->exp < local_expand_thres) { + maxe = local_expand_thres; + } + else { + SBPL_PRINTF("Trying to compute hard-to-find path\n"); + SBPL_FPRINTF(fDeb, "Trying to compute hard-to-find path\n"); + /* TODO + CKey nextkey = rstarPlanner.OPEN->getminkeyheap(); + + if(bforwardsearch) + h = environment_->GetFromToHeuristic(rstarstate->MDPstate->StateID, + pSearchStateSpace->GoalState->StateID); + else + h = environment_->GetFromToHeuristic(pSearchStateSpace->GoalState->StateID, + rstarstate->MDPstate->StateID); + + maxc = nextkey[1] - + (rstarpredstate->g + rstarPlanner.epsilon*h) + RSTAR_COSTDELTA; + */ + } + + SBPL_FPRINTF(fDeb, "recomputing path from bp %d to state %d with maxc=%d maxe=%d\n", + rstarpredstate->MDPstate->StateID, rstarstate->MDPstate->StateID, maxc, maxe); + SBPL_FPRINTF(fDeb, "bp state:\n"); + environment_->PrintState(rstarpredstate->MDPstate->StateID, true, fDeb); + + //re-compute the path + int NewGoalStateID = rstarstate->MDPstate->StateID; + ComputeLocalPath(rstarpredstate->MDPstate->StateID, rstarstate->MDPstate->StateID, maxc, maxe, + &computedaction->Costs[0], &computedactiondata->clow, &computedactiondata->exp, + &computedactiondata->pathIDs, &NewGoalStateID, MaxNumofSecs); + + SBPL_FPRINTF(fDeb, "return values: pathcost=%d clow=%d exp=%d\n", computedaction->Costs[0], + computedactiondata->clow, computedactiondata->exp); + bool bSwitch = false; + if (NewGoalStateID != rstarstate->MDPstate->StateID) { + bSwitch = true; + SBPL_FPRINTF(fDeb, "targetstate was switched from %d to %d\n", rstarstate->MDPstate->StateID, + NewGoalStateID); + SBPL_FPRINTF(stdout, "targetstate was switched from %d to %d\n", rstarstate->MDPstate->StateID, + NewGoalStateID); + environment_->PrintState(NewGoalStateID, true, fDeb); + + RSTARState* rstarNewTargetState = (RSTARState*)GetState(NewGoalStateID)->PlannerSpecificData; + + //re-initialize the state if necessary + if (rstarNewTargetState->callnumberaccessed != pSearchStateSpace->callnumber) { + ReInitializeSearchStateInfo(rstarNewTargetState); + } + + SBPL_FPRINTF(fDeb, "predstate.g=%d actual actioncost=%d clow=%d newtartetstate.g=%d\n", + rstarpredstate->g, computedaction->Costs[0], + ((RSTARACTIONDATA*)computedaction->PlannerSpecificData)->clow, rstarNewTargetState->g); + + //add the successor to our graph + CMDPACTION* action = rstarpredstate->MDPstate->AddAction(rstarpredstate->MDPstate->Actions.size()); + action->AddOutcome(rstarNewTargetState->MDPstate->StateID, computedaction->Costs[0], 1.0); + action->PlannerSpecificData = new RSTARACTIONDATA; + MaxMemoryCounter += sizeof(RSTARACTIONDATA); + ((RSTARACTIONDATA*)action->PlannerSpecificData)->clow = computedactiondata->clow; + ((RSTARACTIONDATA*)action->PlannerSpecificData)->exp = computedactiondata->exp; + ((RSTARACTIONDATA*)action->PlannerSpecificData)->pathIDs = computedactiondata->pathIDs; + + //add the corresponding predaction + rstarNewTargetState->predactionV.push_back(action); + + //the action was not found to the old state + computedaction->Costs[0] = INFINITECOST; + if (bforwardsearch) + computedactiondata->clow = environment_->GetFromToHeuristic(rstarpredstate->MDPstate->StateID, + rstarstate->MDPstate->StateID); + else + computedactiondata->clow = environment_->GetFromToHeuristic(rstarstate->MDPstate->StateID, + rstarpredstate->MDPstate->StateID); + + computedactiondata->pathIDs.clear(); + + rstarstate = rstarNewTargetState; + computedaction = action; + computedactiondata = (RSTARACTIONDATA*)action->PlannerSpecificData; + } + + //clean up local search memory + DestroyLocalSearchMemory(); + + RSTARState* stateu = NULL; + CMDPACTION* utosaction = NULL; + int hfromstarttostate; + if (bforwardsearch) + hfromstarttostate = environment_->GetFromToHeuristic(searchstartstate->MDPstate->StateID, + rstarstate->MDPstate->StateID); + else + hfromstarttostate = environment_->GetFromToHeuristic(rstarstate->MDPstate->StateID, + searchstartstate->MDPstate->StateID); + if (computedactiondata->pathIDs.size() == 0 || + rstarpredstate->g + computedactiondata->clow > pSearchStateSpace->eps * hfromstarttostate) + { + SBPL_FPRINTF(fDeb, "selecting best pred\n"); + //SBPL_FPRINTF(stdout, "selecting best pred\n"); + + //select other best predecessor + unsigned int minQ = INFINITECOST; + for (int i = 0; i < (int)rstarstate->predactionV.size(); i++) { + CMDPACTION* predaction = rstarstate->predactionV.at(i); + rstarpredstate = (RSTARState*)GetState(predaction->SourceStateID)->PlannerSpecificData; + if (minQ >= rstarpredstate->g + ((RSTARACTIONDATA*)predaction->PlannerSpecificData)->clow) { + minQ = rstarpredstate->g + ((RSTARACTIONDATA*)predaction->PlannerSpecificData)->clow; + stateu = rstarpredstate; + utosaction = predaction; + } + } + if (stateu) SBPL_FPRINTF(fDeb, "best pred stateid: %d\n", stateu->MDPstate->StateID); + + //set the predecessor + if (minQ < INFINITECOST) SetBestPredecessor(rstarstate, stateu, utosaction); + } + else if (rstarpredstate->g + computedactiondata->clow < rstarstate->g || bSwitch == false) { + SBPL_FPRINTF(fDeb, "keeping the same computedaction\n"); + //SBPL_FPRINTF(stdout, "keeping the same best pred\n"); + + stateu = rstarpredstate; + utosaction = computedaction; + + //set the predecessor + SetBestPredecessor(rstarstate, stateu, utosaction); + } + else { + SBPL_FPRINTF(fDeb, "keeping the same bestpredaction even though switch of targetstates happened\n"); + } + } + else { + SBPL_FPRINTF(fDeb, "high-level normal expansion of state %d\n", rstarstate->MDPstate->StateID); + environment_->PrintState(rstarstate->MDPstate->StateID, true, fDeb); + highlevelexpands++; + + //close the state + rstarstate->iterationclosed = pSearchStateSpace->searchiteration; + + //expansion + expands++; + + //generate SUCCS state + SuccIDV.clear(); + CLowV.clear(); + if (bforwardsearch) + environment_->GetRandomSuccsatDistance(rstarstate->MDPstate->StateID, &SuccIDV, &CLowV); + else + environment_->GetRandomPredsatDistance(rstarstate->MDPstate->StateID, &SuccIDV, &CLowV); + + SBPL_FPRINTF(fDeb, "%d succs were generated at random\n", (unsigned int)SuccIDV.size()); + + //iterate over states in SUCCS set + int notclosed = 0; + for (int i = 0; i < (int)SuccIDV.size(); i++) { + RSTARState* rstarSuccState = (RSTARState*)GetState(SuccIDV.at(i))->PlannerSpecificData; + + SBPL_FPRINTF(fDeb, "succ %d:\n", i); + environment_->PrintState(rstarSuccState->MDPstate->StateID, true, fDeb); + + //re-initialize the state if necessary + if (rstarSuccState->callnumberaccessed != pSearchStateSpace->callnumber) { + ReInitializeSearchStateInfo(rstarSuccState); + } + + //skip if the state is already closed + if (rstarSuccState->iterationclosed == pSearchStateSpace->searchiteration) { + SBPL_FPRINTF(fDeb, "this succ was already closed -- skipping it\n"); + continue; + } + notclosed++; + + //if(rstarSuccState->MDPstate->StateID == 3838){ + // SBPL_FPRINTF(fDeb, "generating state %d with g=%d bp=%d:\n", + // rstarSuccState->MDPstate->StateID, rstarSuccState->g, + // (rstarSuccState->bestpredaction==NULL?-1:rstarSuccState->bestpredaction->SourceStateID)); + // Env_PrintState(rstarSuccState->MDPstate->StateID, true, false, fDeb); + //} + + //add the successor to our graph + CMDPACTION* action = rstarstate->MDPstate->AddAction(i); + action->AddOutcome(rstarSuccState->MDPstate->StateID, INFINITECOST, 1.0); + action->PlannerSpecificData = new RSTARACTIONDATA; + MaxMemoryCounter += sizeof(RSTARACTIONDATA); + ((RSTARACTIONDATA*)action->PlannerSpecificData)->clow = CLowV[i]; + ((RSTARACTIONDATA*)action->PlannerSpecificData)->exp = 0; + ((RSTARACTIONDATA*)action->PlannerSpecificData)->pathIDs.clear(); + + //add the corresponding predaction + rstarSuccState->predactionV.push_back(action); + + //see if we can improve g-value of successor + if (rstarSuccState->bestpredaction == NULL || rstarstate->g + CLowV[i] < rstarSuccState->g) + /* + (rstarstate->bestpredaction != NULL && + ((RSTARACTIONDATA*)rstarstate->bestpredaction->PlannerSpecificData)->pathIDs.size() == 0 && + ((RSTARACTIONDATA*)rstarstate->bestpredaction->PlannerSpecificData)->exp >= local_expand_thres) */ + { + SetBestPredecessor(rstarSuccState, rstarstate, action); + SBPL_FPRINTF(fDeb, "bestpred was set for the succ (clow=%d)\n", CLowV[i]); + } + else { + SBPL_FPRINTF(fDeb, "bestpred was NOT modified - old one is better\n"); + } + + } + //SBPL_PRINTF("%d successors were not closed\n", notclosed); + }//else + + //recompute minkey + minkey = pSearchStateSpace->OPEN->getminkeyheap(); + + //recompute goalkey if necessary + goalkey = ComputeKey(searchgoalstate); + + if (goalkey.key[0] == 1) { + SBPL_FPRINTF(fDeb, "goal state is AVOID\n"); + } + else + SBPL_FPRINTF(fDeb, "goal state is NON-AVOID\n"); + + if (expands % 10 == 0 && expands > 0) { + SBPL_PRINTF("high-level expands so far=%u\n", expands); + } + } + SBPL_PRINTF("main loop done\n"); + SBPL_FPRINTF(fDeb, "main loop done\n"); + + int retv = 1; + if (searchgoalstate->g == INFINITECOST && pSearchStateSpace->OPEN->emptyheap()) { + SBPL_PRINTF("solution does not exist: search exited because heap is empty\n"); + retv = 0; + } + else if (!pSearchStateSpace->OPEN->emptyheap() && goalkey > minkey) { + SBPL_PRINTF("search exited because it ran out of time\n"); + retv = 2; + } + else if (searchgoalstate->g == INFINITECOST && !pSearchStateSpace->OPEN->emptyheap()) { + SBPL_PRINTF( "solution does not exist: search exited because all candidates for expansion have " + "infinite heuristics\n"); + retv = 0; + } + else { + SBPL_PRINTF("search exited with a solution for eps=%.3f\n", pSearchStateSpace->eps); + retv = 1; + } + + SBPL_FPRINTF(fDeb, "high-level expanded=%d\n", expands); + + highlevel_searchexpands += expands; + + return retv; +} + +//note this does NOT re-compute heuristics, only re-orders OPEN list based on current eps and h-vals +void RSTARPlanner::Reevaluatefvals() +{ + CKey key; + int i; + CHeap* pheap = pSearchStateSpace->OPEN; + + //re-compute priorities for states in OPEN and reorder it + for (i = 1; i <= pheap->currentsize; ++i) { + RSTARState* state = (RSTARState*)pheap->heap[i].heapstate; + pheap->heap[i].key = ComputeKey(state); + } + pheap->makeheap(); + + pSearchStateSpace->bReevaluatefvals = false; +} + +//creates (allocates memory) search state space +//does not initialize search statespace +int RSTARPlanner::CreateSearchStateSpace() +{ + + //create a heap + pSearchStateSpace->OPEN = new CHeap; + MaxMemoryCounter += sizeof(CHeap); + //pSearchStateSpace->inconslist = new CList; + //MaxMemoryCounter += sizeof(CList); + + pSearchStateSpace->searchgoalstate = NULL; + pSearchStateSpace->searchstartstate = NULL; + + pSearchStateSpace->bReinitializeSearchStateSpace = false; + + return 1; +} + +//deallocates memory used by SearchStateSpace +void RSTARPlanner::DeleteSearchStateSpace() +{ + if (pSearchStateSpace->OPEN != NULL) { + pSearchStateSpace->OPEN->makeemptyheap(); + delete pSearchStateSpace->OPEN; + pSearchStateSpace->OPEN = NULL; + } + + //if(pSearchStateSpace->inconslist != NULL) + //{ + // pSearchStateSpace->inconslist->makeemptylist(RSTAR_INCONS_LIST_ID); + // delete pSearchStateSpace->inconslist; + // pSearchStateSpace->inconslist = NULL; + //} + + //delete the states themselves + int iend = (int)pSearchStateSpace->searchMDP.StateArray.size(); + for (int i = 0; i < iend; i++) { + CMDPSTATE* state = pSearchStateSpace->searchMDP.StateArray[i]; + if (state != NULL && state->PlannerSpecificData != NULL) { + DeleteSearchStateData((RSTARState*)state->PlannerSpecificData); + delete (RSTARState*)state->PlannerSpecificData; + state->PlannerSpecificData = NULL; + } + if (state != NULL) { + for (int aind = 0; aind < (int)state->Actions.size(); aind++) { + if (state->Actions[aind]->PlannerSpecificData != NULL) { + DeleteSearchActionData((RSTARACTIONDATA*)state->Actions[aind]->PlannerSpecificData); + delete (RSTARACTIONDATA*)state->Actions[aind]->PlannerSpecificData; + state->Actions[aind]->PlannerSpecificData = NULL; + } + }//over actions + } + } + + pSearchStateSpace->searchMDP.Delete(); +} + +//reset properly search state space +//needs to be done before deleting states +int RSTARPlanner::ResetSearchStateSpace() +{ + pSearchStateSpace->OPEN->makeemptyheap(); + //pSearchStateSpace->inconslist->makeemptylist(RSTAR_INCONS_LIST_ID); + + return 1; +} + +//initialization before each search +void RSTARPlanner::ReInitializeSearchStateSpace() +{ + //increase callnumber + pSearchStateSpace->callnumber++; + + //reset iteration + pSearchStateSpace->searchiteration = 0; + pSearchStateSpace->bNewSearchIteration = true; + +#if DEBUG + SBPL_FPRINTF(fDeb, "reinitializing search state-space (new call number=%d search iter=%d)\n", + pSearchStateSpace->callnumber,pSearchStateSpace->searchiteration); +#endif + + pSearchStateSpace->OPEN->makeemptyheap(); + //pSearchStateSpace->inconslist->makeemptylist(RSTAR_INCONS_LIST_ID); + + //initialize start state + RSTARState* startstateinfo = (RSTARState*)(pSearchStateSpace->searchstartstate->PlannerSpecificData); + if (startstateinfo->callnumberaccessed != pSearchStateSpace->callnumber) { + ReInitializeSearchStateInfo(startstateinfo); + } + + startstateinfo->g = 0; + + //insert start state into the heap + pSearchStateSpace->OPEN->insertheap(startstateinfo, ComputeKey(startstateinfo)); + + pSearchStateSpace->bReinitializeSearchStateSpace = false; + pSearchStateSpace->bReevaluatefvals = false; +} + +//very first initialization +int RSTARPlanner::InitializeSearchStateSpace() +{ + if (pSearchStateSpace->OPEN->currentsize != 0) + // || pSearchStateSpace->inconslist->currentsize != 0) + { + throw SBPL_Exception("ERROR in InitializeSearchStateSpace: OPEN or INCONS is not empty"); + } + + pSearchStateSpace->eps = this->finitial_eps; + pSearchStateSpace->eps_satisfied = INFINITECOST; + pSearchStateSpace->searchiteration = 0; + pSearchStateSpace->bNewSearchIteration = true; + pSearchStateSpace->callnumber = 0; + pSearchStateSpace->bReevaluatefvals = false; + + //create and set the search start state + pSearchStateSpace->searchgoalstate = NULL; + //pSearchStateSpace->searchstartstate = GetState(SearchStartStateID); + pSearchStateSpace->searchstartstate = NULL; + + pSearchStateSpace->bReinitializeSearchStateSpace = true; + + return 1; +} + +int RSTARPlanner::SetSearchGoalState(int SearchGoalStateID) +{ + if (pSearchStateSpace->searchgoalstate == NULL || + pSearchStateSpace->searchgoalstate->StateID != SearchGoalStateID) + { + pSearchStateSpace->searchgoalstate = GetState(SearchGoalStateID); + + //should be new search iteration + pSearchStateSpace->eps_satisfied = INFINITECOST; + pSearchStateSpace->bNewSearchIteration = true; + pSearchStateSpace->eps = this->finitial_eps; + + //recompute heuristic for the heap if heuristics are used +#if USE_HEUR + for(int i = 0; i < (int)pSearchStateSpace->searchMDP.StateArray.size(); i++) + { + CMDPSTATE* MDPstate = pSearchStateSpace->searchMDP.StateArray[i]; + RSTARState* state = (RSTARState*)MDPstate->PlannerSpecificData; + state->h = ComputeHeuristic(MDPstate); + } + + pSearchStateSpace->bReevaluatefvals = true; +#endif + } + + return 1; +} + +int RSTARPlanner::SetSearchStartState(int SearchStartStateID) +{ + CMDPSTATE* MDPstate = GetState(SearchStartStateID); + + if (MDPstate != pSearchStateSpace->searchstartstate) { + pSearchStateSpace->searchstartstate = MDPstate; + pSearchStateSpace->bReinitializeSearchStateSpace = true; + pSearchStateSpace->eps_satisfied = INFINITECOST; + } + + return 1; +} + +void RSTARPlanner::PrintSearchState(RSTARState* state, FILE* fOut) +{ + SBPL_FPRINTF(fOut, "state %d: h=%d g=%u iterc=%d callnuma=%d heapind=%d \n", state->MDPstate->StateID, state->h, + state->g, state->iterationclosed, state->callnumberaccessed, state->heapindex); + environment_->PrintState(state->MDPstate->StateID, true, fOut); +} + +int RSTARPlanner::getHeurValue(int StateID) +{ + CMDPSTATE* MDPstate = GetState(StateID); + RSTARState* searchstateinfo = (RSTARState*)MDPstate->PlannerSpecificData; + return searchstateinfo->h; +} + +vector RSTARPlanner::GetSearchPath(int& solcost) +{ + vector wholePathIds; + RSTARState* rstargoalstate = (RSTARState*)pSearchStateSpace->searchgoalstate->PlannerSpecificData; + + //set the return path and other path related variables + vector tempPathID; + + //initially no path + solcost = INFINITECOST; + wholePathIds.clear(); + + //special case when we are already at the goal + if (rstargoalstate->MDPstate == pSearchStateSpace->searchstartstate) { + solcost = 0; + return wholePathIds; + } + + if (rstargoalstate->g >= INFINITECOST || rstargoalstate->bestpredaction == NULL || + ((RSTARACTIONDATA*)rstargoalstate->bestpredaction->PlannerSpecificData)->pathIDs.size() == 0) + { + return wholePathIds; //no path to goal state was found + } + + //path exists + int pathcost = 0; + RSTARState* rstarstate = rstargoalstate; + while (rstarstate->bestpredaction != NULL && rstarstate->MDPstate != pSearchStateSpace->searchstartstate) { + //get action data + RSTARACTIONDATA* bestpredactiondata = (RSTARACTIONDATA*)rstarstate->bestpredaction->PlannerSpecificData; + + //get predecessor in the search tree + RSTARState* predstate = (RSTARState*)GetState(rstarstate->bestpredaction->SourceStateID)->PlannerSpecificData; + + //check validity + if (predstate->g + bestpredactiondata->clow != rstarstate->g) { + SBPL_ERROR("ERROR: clow(=%d) + predstate.g(=%d) = %d != succstate.g = %d (callnum=%d, iter=%d)\n", + bestpredactiondata->clow, predstate->g, bestpredactiondata->clow + predstate->g, rstarstate->g, + pSearchStateSpace->callnumber, pSearchStateSpace->searchiteration); + SBPL_PRINTF("predstate: "); + environment_->PrintState(predstate->MDPstate->StateID, true, stdout); + SBPL_PRINTF("succstate: "); + environment_->PrintState(rstarstate->MDPstate->StateID, true, stdout); + SBPL_PRINTF("PredState: stateID=%d g=%d calln=%d iterc=%d h=%d\n", predstate->MDPstate->StateID, + predstate->g, predstate->callnumberaccessed, predstate->iterationclosed, predstate->h); + SBPL_PRINTF("Succstate: stateID=%d g=%d calln=%d iterc=%d h=%d\n", rstarstate->MDPstate->StateID, + rstarstate->g, rstarstate->callnumberaccessed, rstarstate->iterationclosed, rstarstate->h); + fflush(fDeb); + + throw SBPL_Exception(); + } + + //store the action and its cost + tempPathID.push_back(rstarstate->bestpredaction); + pathcost += rstarstate->bestpredaction->Costs[0]; + + //go to the predecessor + rstarstate = predstate; + + //another check + if (pathcost + rstarstate->g > rstargoalstate->g) { + std::stringstream ss("ERROR: pathcost+rstarstate.g = "); + ss << pathcost + rstarstate->g << " > goalstate.g = " << rstargoalstate->g; + throw SBPL_Exception(ss.str()); + } + } + + //now recover the actual path + RSTARACTIONDATA* actiondata; + for (int aind = 0; aind < (int)tempPathID.size(); aind++) { + if (bforwardsearch) + //getting path in reverse + actiondata = (RSTARACTIONDATA*)tempPathID.at(tempPathID.size() - aind - 1)->PlannerSpecificData; + else + actiondata = (RSTARACTIONDATA*)tempPathID.at(aind)->PlannerSpecificData; //getting path in reverse + + //get the states that correspond to the high-level action + for (int j = 0; j < (int)actiondata->pathIDs.size(); j++) { + //note: path corresponding to the action is already in right direction + wholePathIds.push_back(actiondata->pathIDs.at(j)); + } + } + //add the goal state + if (bforwardsearch) + wholePathIds.push_back(rstargoalstate->MDPstate->StateID); + else + wholePathIds.push_back(pSearchStateSpace->searchstartstate->StateID); + + SBPL_FPRINTF(fDeb, "high-level pathcost=%d and high-level g(searchgoal)=%d\n", pathcost, rstargoalstate->g); + + //get the solcost + solcost = pathcost; + return wholePathIds; +} + +void RSTARPlanner::PrintSearchPath(FILE* fOut) +{ + vector pathIds; + int solcost; + + pathIds = GetSearchPath(solcost); + + SBPL_FPRINTF(fOut, "high-level solution cost = %d, solution length=%d\n", solcost, (unsigned int)pathIds.size()); + for (int sind = 0; sind < (int)pathIds.size(); sind++) { + environment_->PrintState(pathIds.at(sind), false, fOut); + } +} + +bool RSTARPlanner::Search(vector& pathIds, int & PathCost, bool bFirstSolution, bool bOptimalSolution, + double MaxNumofSecs) +{ + CKey key; + TimeStarted = clock(); + highlevel_searchexpands = 0; + lowlevel_searchexpands = 0; + + //reset the return values + PathCost = INFINITECOST; + pathIds.clear(); + + //bFirstSolution = false; //TODO-remove this but then fix crashing because later + //searches within cycle re-initialize g-vals and test path found fails if last search ran out of time + //so we need to save solutions between iterations + //also, we need to call change callnumber before each search + +#if DEBUG + SBPL_FPRINTF(fDeb, "new search call (call number=%d)\n", pSearchStateSpace->callnumber); +#endif + + //set epsilons + pSearchStateSpace->eps = this->finitial_eps; + pSearchStateSpace->eps_satisfied = INFINITECOST; + + if (pSearchStateSpace->bReinitializeSearchStateSpace == true) { + //re-initialize state space + ReInitializeSearchStateSpace(); + } + + if (bOptimalSolution) { + pSearchStateSpace->eps = 1; + MaxNumofSecs = INFINITECOST; + } + else if (bFirstSolution) { + MaxNumofSecs = INFINITECOST; + } + + //get the size of environment that is already allocated + int oldenvsize = environment_->StateID2IndexMapping.size() * sizeof(int); + + //the main loop of R* + int prevexpands = 0; + clock_t loop_time; + //TODO - change FINAL_EPS and DECREASE_EPS onto a parameter + while (pSearchStateSpace->eps_satisfied > final_epsilon && + (clock() - TimeStarted) < MaxNumofSecs * (double)CLOCKS_PER_SEC) + { + loop_time = clock(); + + //decrease eps for all subsequent iterations + if (fabs(pSearchStateSpace->eps_satisfied - pSearchStateSpace->eps) < ERR_EPS && !bFirstSolution) { + pSearchStateSpace->eps = pSearchStateSpace->eps - dec_eps; + if (pSearchStateSpace->eps < final_epsilon) pSearchStateSpace->eps = final_epsilon; + + //the priorities need to be updated + pSearchStateSpace->bReevaluatefvals = true; + + //it will be a new search. Since R* is non-incremental, it will have to be a new call + pSearchStateSpace->bNewSearchIteration = true; + pSearchStateSpace->bReinitializeSearchStateSpace = true; + } + + //if(pSearchStateSpace->bReinitializeSearchStateSpace == true){ + //re-initialize state space + ReInitializeSearchStateSpace(); //TODO - we have to do it currently since g-vals from old searches are invalid + //} + + if (pSearchStateSpace->bNewSearchIteration) { + pSearchStateSpace->searchiteration++; + pSearchStateSpace->bNewSearchIteration = false; + } + + //re-compute f-values if necessary and reorder the heap + if (pSearchStateSpace->bReevaluatefvals) Reevaluatefvals(); + + //improve or compute path + if (ImprovePath(MaxNumofSecs) == 1) { + pSearchStateSpace->eps_satisfied = pSearchStateSpace->eps; //note: eps is satisfied probabilistically + } + + //print the solution cost and eps bound + SBPL_PRINTF("eps=%f highlevel expands=%d g(searchgoal)=%d time=%.3f\n", pSearchStateSpace->eps_satisfied, + highlevel_searchexpands - prevexpands, + ((RSTARState*)pSearchStateSpace->searchgoalstate->PlannerSpecificData)->g, + double(clock() - loop_time) / CLOCKS_PER_SEC); + +#if DEBUG + SBPL_FPRINTF(fDeb, "eps=%f highlevel expands=%d g(searchgoal)=%d time=%.3f\n", + pSearchStateSpace->eps_satisfied, highlevel_searchexpands - prevexpands, + ((RSTARState*)pSearchStateSpace->searchgoalstate->PlannerSpecificData)->g, + double(clock()-loop_time)/CLOCKS_PER_SEC); + PrintSearchState((RSTARState*)pSearchStateSpace->searchgoalstate->PlannerSpecificData, fDeb); +#endif + prevexpands = highlevel_searchexpands; + + //keep track of the best solution so far + vector CurrentPathIds; + int CurrentPathCost = ((RSTARState*)pSearchStateSpace->searchgoalstate->PlannerSpecificData)->g; + if (CurrentPathCost == INFINITECOST || + ((RSTARACTIONDATA*)((RSTARState*)pSearchStateSpace->searchgoalstate->PlannerSpecificData)->bestpredaction->PlannerSpecificData)->pathIDs.size() == 0) + { + //the path to the goal is not found, it is just goal has been + //generated but the last edge to it wasn't computed yet + CurrentPathCost = INFINITECOST; + } + else { + //get the found path + CurrentPathIds = GetSearchPath(CurrentPathCost); + } + //keep track of the best solution + if (CurrentPathCost < PathCost) { + PathCost = CurrentPathCost; + pathIds = CurrentPathIds; + } + + //if just the first solution then we are done + if (bFirstSolution) break; + + //no solution exists + if (((RSTARState*)pSearchStateSpace->searchgoalstate->PlannerSpecificData)->g == INFINITECOST) break; + } + +#if DEBUG + SBPL_FFLUSH(fDeb); +#endif + + MaxMemoryCounter += (oldenvsize - environment_->StateID2IndexMapping.size() * sizeof(int)); + SBPL_PRINTF("MaxMemoryCounter = %d\n", MaxMemoryCounter); + + bool ret = false; + if (PathCost == INFINITECOST) { + SBPL_PRINTF("could not find a solution\n"); + ret = false; + } + else { + SBPL_PRINTF("solution is found\n"); + ret = true; + } + + SBPL_PRINTF("total highlevel expands this call = %d, planning time = %.3f secs, solution cost=%d\n", + highlevel_searchexpands, (clock() - TimeStarted) / ((double)CLOCKS_PER_SEC), PathCost); + + //SBPL_FPRINTF(fStat, "%d %d\n", highlevel_searchexpands, MinPathCost); + + return ret; +} + +//-----------------------------Interface function----------------------------------------------------- +//returns 1 if found a solution, and 0 otherwise +int RSTARPlanner::replan(double allocated_time_secs, vector* solution_stateIDs_V) +{ + int solcost; + + return replan(allocated_time_secs, solution_stateIDs_V, &solcost); +} + +//returns 1 if found a solution, and 0 otherwise +int RSTARPlanner::replan(double allocated_time_secs, vector* solution_stateIDs_V, int* psolcost) +{ + vector pathIds; + bool bFound = false; + int PathCost; + bool bFirstSolution = this->bsearchuntilfirstsolution; + bool bOptimalSolution = false; + *psolcost = 0; + + SBPL_PRINTF("planner: replan called (bFirstSol=%d, bOptSol=%d)\n", bFirstSolution, bOptimalSolution); + + //plan + bFound = Search(pathIds, PathCost, bFirstSolution, bOptimalSolution, allocated_time_secs); + if (!bFound) { + SBPL_PRINTF("failed to find a solution\n"); + } + + //copy the solution + *solution_stateIDs_V = pathIds; + *psolcost = PathCost; + + return (int)bFound; +} + +int RSTARPlanner::set_goal(int goal_stateID) +{ + SBPL_PRINTF("planner: setting goal to %d\n", goal_stateID); + environment_->PrintState(goal_stateID, true, stdout); + + if (bforwardsearch) { + if (SetSearchGoalState(goal_stateID) != 1) { + SBPL_ERROR("ERROR: failed to set search goal state\n"); + return 0; + } + } + else { + if (SetSearchStartState(goal_stateID) != 1) { + SBPL_ERROR("ERROR: failed to set search start state\n"); + return 0; + } + } + + return 1; +} + +int RSTARPlanner::set_start(int start_stateID) +{ + SBPL_PRINTF("planner: setting start to %d\n", start_stateID); + environment_->PrintState(start_stateID, true, stdout); + + if (bforwardsearch) { + if (SetSearchStartState(start_stateID) != 1) { + SBPL_ERROR("ERROR: failed to set search start state\n"); + return 0; + } + } + else { + if (SetSearchGoalState(start_stateID) != 1) { + SBPL_ERROR("ERROR: failed to set search goal state\n"); + return 0; + } + } + + return 1; +} + +void RSTARPlanner::costs_changed(StateChangeQuery const & stateChange) +{ + //since R* is non-incremental + pSearchStateSpace->bReinitializeSearchStateSpace = true; +} + +void RSTARPlanner::costs_changed() +{ + //since R* is non-incremental + pSearchStateSpace->bReinitializeSearchStateSpace = true; +} + +int RSTARPlanner::force_planning_from_scratch() +{ + SBPL_PRINTF("planner: forceplanfromscratch set\n"); + + pSearchStateSpace->bReinitializeSearchStateSpace = true; + + return 1; +} + +int RSTARPlanner::set_search_mode(bool bSearchUntilFirstSolution) +{ + SBPL_PRINTF("planner: search mode set to %d\n", bSearchUntilFirstSolution); + + bsearchuntilfirstsolution = bSearchUntilFirstSolution; + + return 1; +} + +void RSTARPlanner::print_searchpath(FILE* fOut) +{ + PrintSearchPath(fOut); +} + +//--------------------------------------------------------------------------------------------------------- diff --git a/navigations/sbpl/src/planners/viplanner.cpp b/navigations/sbpl/src/planners/viplanner.cpp new file mode 100755 index 0000000..a55bc12 --- /dev/null +++ b/navigations/sbpl/src/planners/viplanner.cpp @@ -0,0 +1,410 @@ +/* + * Copyright (c) 2008, Maxim Likhachev + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Carnegie Mellon University nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include +#include +#include +#include +#include + +using namespace std; + +static unsigned int g_backups; +static clock_t g_runtime = 0; +static double g_belldelta = INFINITECOST; + +VIPlanner::~VIPlanner() +{ + //delete the statespace +} + +void VIPlanner::Initialize_vidata(CMDPSTATE* state) +{ + VIState* vi_data = (VIState*)state->PlannerSpecificData; + + vi_data->bestnextaction = NULL; + vi_data->iteration = 0; + vi_data->v = (float)environment_->GetGoalHeuristic(state->StateID); +} + +CMDPSTATE* VIPlanner::CreateState(int stateID) +{ + CMDPSTATE* state = NULL; + +#if DEBUG + if (environment_->StateID2IndexMapping[stateID][VIMDP_STATEID2IND] != -1) { + throw SBPL_Exception("ERROR in CreateState: state already created"); + } +#endif + + //adds to the tail a state + state = viPlanner.MDP.AddState(stateID); + + //remember the index of the state + environment_->StateID2IndexMapping[stateID][VIMDP_STATEID2IND] = viPlanner.MDP.StateArray.size() - 1; + +#if DEBUG + if (state != viPlanner.MDP.StateArray[environment_->StateID2IndexMapping[stateID][VIMDP_STATEID2IND]]) { + throw SBPL_Exception("ERROR in CreateState: invalid state index"); + } +#endif + + //create and initialize vi_data + state->PlannerSpecificData = new VIState; + Initialize_vidata(state); + + return state; +} + +CMDPSTATE* VIPlanner::GetState(int stateID) +{ + if (stateID >= (int)environment_->StateID2IndexMapping.size()) { + throw SBPL_Exception("ERROR in GetState: stateID is invalid"); + } + + if (environment_->StateID2IndexMapping[stateID][VIMDP_STATEID2IND] == -1) + return CreateState(stateID); + else + return viPlanner.MDP.StateArray[environment_->StateID2IndexMapping[stateID][VIMDP_STATEID2IND]]; +} + +void VIPlanner::PrintVIData() +{ + SBPL_PRINTF("iteration %d: v(start) = %f\n", viPlanner.iteration, + ((VIState*)(viPlanner.StartState->PlannerSpecificData))->v); +} + +void VIPlanner::PrintStatHeader(FILE* fOut) +{ + SBPL_FPRINTF(fOut, "iteration backups v(start)\n"); +} + +void VIPlanner::PrintStat(FILE* fOut, clock_t starttime) +{ + SBPL_FPRINTF(fOut, "%d %d %f %f %d\n", viPlanner.iteration, g_backups, + ((double)(clock() - starttime)) / CLOCKS_PER_SEC, + ((VIState*)(viPlanner.StartState->PlannerSpecificData))->v, + (unsigned int)viPlanner.MDP.StateArray.size()); +} + +void VIPlanner::PrintPolicy(FILE* fPolicy) +{ + bool bPrintStatOnly = true; + vector WorkList; + CMDP PolicyforEvaluation; + + viPlanner.iteration++; + WorkList.push_back(viPlanner.StartState); + ((VIState*)viPlanner.StartState->PlannerSpecificData)->iteration = viPlanner.iteration; + double PolVal = 0.0; + double Conf = 0; + bool bCycles = false; + SBPL_PRINTF("Printing policy...\n"); + while ((int)WorkList.size() > 0) { + //pop the last state + CMDPSTATE* state = WorkList.at(WorkList.size() - 1); + WorkList.pop_back(); + VIState* statedata = (VIState*)state->PlannerSpecificData; + + CMDPSTATE* polstate = PolicyforEvaluation.AddState(state->StateID); + + //print state ID + if (!bPrintStatOnly) { + SBPL_FPRINTF(fPolicy, "%d\n", state->StateID); + environment_->PrintState(state->StateID, false, fPolicy); + + int h = environment_->GetGoalHeuristic(state->StateID); + SBPL_FPRINTF(fPolicy, "h=%d\n", h); + if (h > statedata->v) { + SBPL_FPRINTF(fPolicy, "WARNING h overestimates exp.cost\n"); + } + } + + if (state->StateID == viPlanner.GoalState->StateID) { + //goal state + if (!bPrintStatOnly) SBPL_FPRINTF(fPolicy, "0\n"); + Conf += ((VIState*)state->PlannerSpecificData)->Pc; + } + else if (statedata->bestnextaction == NULL) { + //unexplored + if (!bPrintStatOnly) { + //no outcome explored - stay in the same place + SBPL_FPRINTF(fPolicy, "%d %d %d\n", 1, 0, state->StateID); + } + } + else { + //get best action + CMDPACTION* action = statedata->bestnextaction; + + //add action to evaluation MDP + CMDPACTION* polaction = polstate->AddAction(action->ActionID); + + if (!bPrintStatOnly) SBPL_FPRINTF(fPolicy, "%d ", (unsigned int)action->SuccsID.size()); + + //print successors and insert them into the list + for (int i = 0; i < (int)action->SuccsID.size(); i++) { + if (!bPrintStatOnly) SBPL_FPRINTF(fPolicy, "%d %d ", action->Costs[i], action->SuccsID[i]); + polaction->AddOutcome(action->SuccsID[i], action->Costs[i], action->SuccsProb[i]); + + CMDPSTATE* succstate = GetState(action->SuccsID[i]); + if ((int)((VIState*)succstate->PlannerSpecificData)->iteration != viPlanner.iteration) { + ((VIState*)succstate->PlannerSpecificData)->iteration = viPlanner.iteration; + WorkList.push_back(succstate); + + ((VIState*)succstate->PlannerSpecificData)->Pc = action->SuccsProb[i] * + ((VIState*)state->PlannerSpecificData)->Pc; + PolVal += ((VIState*)succstate->PlannerSpecificData)->Pc * action->Costs[i]; + } + } + if (!bPrintStatOnly) SBPL_FPRINTF(fPolicy, "\n"); + } + }//while worklist not empty + SBPL_PRINTF("done\n"); + + //now evaluate the policy + double PolicyValue = -1; + bool bFullPolicy = false; + double Pcgoal = -1; + int nMerges = 0; + EvaluatePolicy(&PolicyforEvaluation, viPlanner.StartState->StateID, viPlanner.GoalState->StateID, &PolicyValue, + &bFullPolicy, &Pcgoal, &nMerges, &bCycles); + + SBPL_PRINTF("Policy value = %f FullPolicy=%d Merges=%d Cycles=%d\n", PolicyValue, bFullPolicy, nMerges, bCycles); + + if (!bFullPolicy) SBPL_PRINTF("WARN: POLICY IS ONLY PARTIAL\n"); + if (fabs(PolicyValue - ((VIState*)(viPlanner.StartState->PlannerSpecificData))->v) > MDP_ERRDELTA) { + SBPL_PRINTF("WARN: POLICY VALUE IS NOT CORRECT\n"); + } + + if (!bPrintStatOnly) + SBPL_FPRINTF(fPolicy, + "backups=%d runtime=%f vstart=%f policyvalue=%f fullpolicy=%d Pc(goal)=%f nMerges=%d bCyc=%d\n", + g_backups, (double)g_runtime / CLOCKS_PER_SEC, + ((VIState*)(viPlanner.StartState->PlannerSpecificData))->v, PolicyValue, bFullPolicy, Pcgoal, + nMerges, bCycles); + else + SBPL_FPRINTF(fPolicy, "%d %f %f %f %d %f %d %d\n", g_backups, (double)g_runtime / CLOCKS_PER_SEC, + ((VIState*)(viPlanner.StartState->PlannerSpecificData))->v, PolicyValue, bFullPolicy, Pcgoal, + nMerges, bCycles); +} + +void VIPlanner::backup(CMDPSTATE* state) +{ + int aind, oind; + CMDPSTATE* succstate; + + g_backups++; + + if (state == viPlanner.GoalState) { + ((VIState*)(state->PlannerSpecificData))->bestnextaction = NULL; + ((VIState*)(state->PlannerSpecificData))->v = 0; + return; + } + + //iterate through actions + double minactionQ = INFINITECOST; + CMDPACTION* minaction = NULL; + for (aind = 0; aind < (int)state->Actions.size(); aind++) { + double actionQ = 0; + CMDPACTION* action = state->Actions[aind]; + for (oind = 0; oind < (int)action->SuccsID.size(); oind++) { + succstate = GetState(action->SuccsID[oind]); + actionQ += action->SuccsProb[oind] * (action->Costs[oind] + + ((VIState*)(succstate->PlannerSpecificData))->v); + } + + if (minaction == NULL || actionQ < minactionQ) { + minactionQ = actionQ; + minaction = action; + } + } + + if (((VIState*)state->PlannerSpecificData)->bestnextaction == NULL) + g_belldelta = INFINITECOST; + else if (g_belldelta < fabs(((VIState*)state->PlannerSpecificData)->v - minactionQ)) + g_belldelta = fabs(((VIState*)state->PlannerSpecificData)->v - minactionQ); + + //set state values + ((VIState*)state->PlannerSpecificData)->bestnextaction = minaction; + ((VIState*)state->PlannerSpecificData)->v = (float)minactionQ; +} + +void VIPlanner::perform_iteration_backward() +{ + CMDPSTATE* state; + vector Worklist; + int aind, oind; + + //initialize the worklist + Worklist.push_back(viPlanner.GoalState->StateID); + + //backup all the states + while ((int)Worklist.size() > 0) { + //get the next state to process + state = GetState(Worklist[Worklist.size() - 1]); + Worklist.pop_back(); + + //add all actions to the state + if ((int)state->Actions.size() == 0) environment_->SetAllActionsandAllOutcomes(state); + + //backup the state + backup(state); + + //insert all the not yet processed successors into the worklist + for (aind = 0; aind < (int)state->Actions.size(); aind++) { + CMDPACTION* action = state->Actions[aind]; + for (oind = 0; oind < (int)action->SuccsID.size(); oind++) { + CMDPSTATE* succstate = GetState(action->SuccsID[oind]); + + //skip if already was in the queue + if ((int)((VIState*)succstate->PlannerSpecificData)->iteration != viPlanner.iteration) { + Worklist.push_back(succstate->StateID); + + //mark it + ((VIState*)succstate->PlannerSpecificData)->iteration = viPlanner.iteration; + } + } + } + + //it is not necessary to process the predecessors of the start state + if (state == viPlanner.StartState) continue; + + //add all predecessor ids to the state + if ((int)state->PredsID.size() == 0) environment_->SetAllPreds(state); + //insert all the not yet processed predecessors into the worklist + for (int pind = 0; pind < (int)state->PredsID.size(); pind++) { + CMDPSTATE* PredState = GetState(state->PredsID[pind]); + + //skip if already was in the queue + if ((int)((VIState*)PredState->PlannerSpecificData)->iteration != viPlanner.iteration) { + Worklist.push_back(PredState->StateID); + + //mark it + ((VIState*)PredState->PlannerSpecificData)->iteration = viPlanner.iteration; + } + } + } //until empty worklist +} + +void VIPlanner::perform_iteration_forward() +{ + CMDPSTATE* state = NULL; + vector Worklist; + int aind, oind; + + //initialize the worklist + Worklist.push_back(viPlanner.StartState); + + //backup all the states + while ((int)Worklist.size() > 0) { + //get the next state to process from the front + state = Worklist[Worklist.size() - 1]; + //Env_PrintState(state->StateID); + Worklist.pop_back(); + + //add all actions to the state + if ((int)state->Actions.size() == 0) environment_->SetAllActionsandAllOutcomes(state); + + //backup the state + backup(state); + + //insert all the not yet processed successors into the worklist + for (aind = 0; aind < (int)state->Actions.size(); aind++) { + //CMDPACTION* action = state->Actions[aind]; + CMDPACTION* action = ((VIState*)state->PlannerSpecificData)->bestnextaction; + for (oind = 0; action != NULL && oind < (int)action->SuccsID.size(); oind++) { + CMDPSTATE* succstate = GetState(action->SuccsID[oind]); + + //skip if already was in the queue + if ((int)((VIState*)succstate->PlannerSpecificData)->iteration != viPlanner.iteration) { + Worklist.push_back(succstate); + + //mark it + ((VIState*)succstate->PlannerSpecificData)->iteration = viPlanner.iteration; + } + } + } + } //until empty worklist +} + +void VIPlanner::InitializePlanner() +{ + viPlanner.iteration = 0; + + //create and set up goal and start states + viPlanner.StartState = GetState(MDPCfg_->startstateid); + viPlanner.GoalState = GetState(MDPCfg_->goalstateid); +} + +//the planning entry point +//returns 1 if path is found, 0 otherwise +int VIPlanner::replan(double allocatedtime, vector* solution_stateIDs_V) +{ +#ifndef ROS + const char* policy = "policy.txt"; + const char* stat = "stat.txt"; +#endif + FILE* fPolicy = SBPL_FOPEN(policy, "w"); + FILE* fStat = SBPL_FOPEN(stat, "w"); + + //initialization + InitializePlanner(); + + //start the timer + clock_t starttime = clock(); + + //--------------iterate------------------------------- + while (((clock() - starttime) / (double)CLOCKS_PER_SEC) < allocatedtime && g_belldelta > MDP_ERRDELTA) { + viPlanner.iteration++; + + g_belldelta = 0; + perform_iteration_forward(); + + if (viPlanner.iteration % 100 == 0) { + PrintStat(stdout, starttime); + PrintStat(fStat, starttime); + } + } + //------------------------------------------------------------------ + + g_runtime = clock() - starttime; + + PrintStat(stdout, starttime); + PrintStat(fStat, starttime); + SBPL_FFLUSH(fStat); + + PrintPolicy(fPolicy); + + SBPL_FCLOSE(fPolicy); + SBPL_FCLOSE(fStat); + + return 1; +} + diff --git a/navigations/sbpl/src/test/env1.cfg b/navigations/sbpl/src/test/env1.cfg new file mode 100755 index 0000000..1fa7219 --- /dev/null +++ b/navigations/sbpl/src/test/env1.cfg @@ -0,0 +1,19 @@ +discretization(cells): 15 15 +start(cells): 0 0 +end(cells): 14 14 +environment: +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 0 0 0 0 0 0 0 +0 0 0 0 0 0 1 1 1 1 1 1 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 +1 1 1 1 0 0 0 0 0 0 0 1 0 0 0 +1 1 1 1 0 0 0 0 0 0 0 1 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 +0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 diff --git a/navigations/sbpl/src/test/env1.cfg.out.valid b/navigations/sbpl/src/test/env1.cfg.out.valid new file mode 100755 index 0000000..154dfae --- /dev/null +++ b/navigations/sbpl/src/test/env1.cfg.out.valid @@ -0,0 +1,23 @@ +X=0 Y=0 +X=1 Y=1 +X=2 Y=2 +X=3 Y=3 +X=4 Y=4 +X=5 Y=5 +X=6 Y=5 +X=7 Y=5 +X=8 Y=5 +X=9 Y=5 +X=10 Y=5 +X=11 Y=5 +X=12 Y=5 +X=12 Y=6 +X=12 Y=7 +X=12 Y=8 +X=12 Y=9 +X=13 Y=10 +X=13 Y=11 +X=13 Y=12 +X=14 Y=13 +the state is a goal state +X=14 Y=14 diff --git a/navigations/sbpl/src/test/main.cpp b/navigations/sbpl/src/test/main.cpp new file mode 100755 index 0000000..4900f63 --- /dev/null +++ b/navigations/sbpl/src/test/main.cpp @@ -0,0 +1,1610 @@ +/* + * Copyright (c) 2008, Maxim Likhachev + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Carnegie Mellon University nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ +#include +#include +#include +#include +#include + +using namespace std; + +#include + +enum PlannerType +{ + INVALID_PLANNER_TYPE = -1, + PLANNER_TYPE_ADSTAR, + PLANNER_TYPE_ARASTAR, + PLANNER_TYPE_PPCP, + PLANNER_TYPE_RSTAR, + PLANNER_TYPE_VI, + PLANNER_TYPE_ANASTAR, + + NUM_PLANNER_TYPES +}; + +std::string PlannerTypeToStr(PlannerType plannerType) +{ + switch (plannerType) { + case PLANNER_TYPE_ADSTAR: + return std::string("adstar"); + case PLANNER_TYPE_ARASTAR: + return std::string("arastar"); + case PLANNER_TYPE_PPCP: + return std::string("ppcp"); + case PLANNER_TYPE_RSTAR: + return std::string("rstar"); + case PLANNER_TYPE_VI: + return std::string("vi"); + case PLANNER_TYPE_ANASTAR: + return std::string("anastar"); + default: + return std::string("invalid"); + } +} + +PlannerType StrToPlannerType(const char* str) +{ + if (!strcmp(str, "adstar")) { + return PLANNER_TYPE_ADSTAR; + } + else if (!strcmp(str, "arastar")) { + return PLANNER_TYPE_ARASTAR; + } + else if (!strcmp(str, "ppcp")) { + return PLANNER_TYPE_PPCP; + } + else if (!strcmp(str, "rstar")) { + return PLANNER_TYPE_RSTAR; + } + else if (!strcmp(str, "vi")) { + return PLANNER_TYPE_VI; + } + else if (!strcmp(str, "anastar")) { + return PLANNER_TYPE_ANASTAR; + } + else { + return INVALID_PLANNER_TYPE; + } +} + +enum EnvironmentType +{ + INVALID_ENV_TYPE = -1, ENV_TYPE_2D, ENV_TYPE_2DUU, ENV_TYPE_XYTHETA, ENV_TYPE_XYTHETAMLEV, ENV_TYPE_ROBARM, + + NUM_ENV_TYPES +}; + +std::string EnvironmentTypeToStr(EnvironmentType environmentType) +{ + switch (environmentType) { + case ENV_TYPE_2D: + return std::string("2d"); + case ENV_TYPE_2DUU: + return std::string("2duu"); + case ENV_TYPE_XYTHETA: + return std::string("xytheta"); + case ENV_TYPE_XYTHETAMLEV: + return std::string("xythetamlev"); + case ENV_TYPE_ROBARM: + return std::string("robarm"); + default: + return std::string("invalid"); + } +} + +EnvironmentType StrToEnvironmentType(const char* str) +{ + if (!strcmp(str, "2d")) { + return ENV_TYPE_2D; + } + else if (!strcmp(str, "2duu")) { + return ENV_TYPE_2DUU; + } + else if (!strcmp(str, "xytheta")) { + return ENV_TYPE_XYTHETA; + } + else if (!strcmp(str, "xythetamlev")) { + return ENV_TYPE_XYTHETAMLEV; + } + else if (!strcmp(str, "robarm")) { + return ENV_TYPE_ROBARM; + } + else { + return INVALID_ENV_TYPE; + } +} + +enum MainResultType +{ + INVALID_MAIN_RESULT = -1, + + MAIN_RESULT_SUCCESS = 0, + MAIN_RESULT_FAILURE = 1, + MAIN_RESULT_INSUFFICIENT_ARGS = 2, + MAIN_RESULT_INCORRECT_OPTIONS = 3, + MAIN_RESULT_UNSUPPORTED_ENV = 4, + + NUM_MAIN_RESULTS +}; + +/******************************************************************************* + * PrintUsage - Prints the proper usage of the sbpl test executable. + * + * @param argv The command-line arguments; used to determine the name of the + * test executable. + *******************************************************************************/ +void PrintUsage(char *argv[]) +{ + printf("USAGE: %s [-s] [--env=] [--planner=] [--search-dir=] [mot prims]\n", + argv[0]); + printf("See '%s -h' for help.\n", argv[0]); +} + +/******************************************************************************* + * PrintHelp - Prints a help prompt to the command line when the -h option is + * used. + * + * @param argv The command line arguments; used to determine the name of the + * test executable + *******************************************************************************/ +void PrintHelp(char** argv) +{ + printf("\n"); + printf("Search-Based Planning Library\n"); + printf("\n"); + printf(" %s -h\n", argv[0]); + printf(" %s [-s] [--env=] [--planner=] [--search-dir=] [mot prim]\n", + argv[0]); + printf("\n"); + printf("[-s] (optional) Find a solution for an example navigation\n"); + printf(" scenario where the robot only identifies obstacles as\n"); + printf(" it approaches them.\n"); + printf("[--env=] (optional) Select an environment type to choose what\n"); + printf(" example to run. The default is \"xytheta\".\n"); + printf(" One of 2d, xytheta, xythetamlev, robarm.\n"); + printf("[--planner=] (optional) Select a planner to use for the example.\n"); + printf(" The default is \"arastar\".\n"); + printf(" One of arastar, adstar, rstar, anastar.\n"); + printf("[--search-dir=] (optional) Select the type of search to run. The default\n"); + printf(" is \"backwards\".\n"); + printf(" One of backward, forward.\n"); + printf(" Config file representing the environment configuration.\n"); + printf(" See sbpl/env_examples/ for examples.\n"); + printf("[mot prim] (optional) Motion primitives file for x,y,theta lattice\n"); + printf(" planning. See sbpl/matlab/mprim/ for examples.\n"); + printf(" NOTE: resolution of motion primtives should match that\n"); + printf(" of the config file.\n"); + printf(" NOTE: optional use of these for x,y,theta planning is\n"); + printf(" deprecated.\n"); + printf("\n"); +} + +/******************************************************************************* + * CheckIsNavigating + * @brief Returns whether the -s option is being used. + * + * @param numOptions The number of options passed through the command line + * @param argv The command-line arguments + * @return whether the -s option was passed in on the cmd line + *******************************************************************************/ +bool CheckIsNavigating(int numOptions, char** argv) +{ + for (int i = 1; i < numOptions + 1; i++) { + if (strcmp(argv[i], "-s") == 0) { + return true; + } + } + return false; +} + +/******************************************************************************* + * CheckSearchDirection - + * @brief Returns the search direction being used + * + * @param numOptions The number of options passed through the command line + * @param argv The command-line arguments + * @return A string representing the search direction; "backward" by default + ******************************************************************************/ +std::string CheckSearchDirection(int numOptions, char** argv) +{ + int optionLength = strlen("--search-dir="); + for (int i = 1; i < numOptions + 1; i++) { + if (strncmp("--search-dir=", argv[i], optionLength) == 0) { + std::string s(&argv[i][optionLength]); + return s; + } + } + return std::string("backward"); +} + +/******************************************************************************* + * CheckEnvironmentType + * @brief Returns the environment being used + * + * @param numOptions The number of options passed through the command line + * @param argv The command-line arguments + * @return A string denoting the environment type; "xytheta" by default + *******************************************************************************/ +std::string CheckEnvironmentType(int numOptions, char** argv) +{ + int optionLength = strlen("--env="); + for (int i = 1; i < numOptions + 1; i++) { + if (strncmp("--env=", argv[i], optionLength) == 0) { + std::string s(&argv[i][optionLength]); + return s; + } + } + return std::string("xytheta"); +} + +/******************************************************************************* + * CheckPlannerType - Checks for a planner specifier passed in through the + * command line. This determines what planner to run in + * the example. If none is found, ARA* is assumed. + * + * @param numOptions The number of options passed through the command line + * @param argv The command-line arguments + * @return A string denoting the planner type; "arastar" by default + ******************************************************************************/ +std::string CheckPlannerType(int numOptions, char** argv) +{ + int optionLength = strlen("--planner="); + for (int i = 1; i < numOptions + 1; i++) { + if (strncmp("--planner=", argv[i], optionLength) == 0) { + std::string s(&argv[i][optionLength]); + return s; + } + } + return std::string("arastar"); +} + +/******************************************************************************* + * plan2d + * @brief An example of planning in two-dimensional space without motion primitives. + * + * @param plannerType The type of planner to be used in this example + * @param envCfgFilename The environment config file. See + * sbpl/env_examples/nav2d/ for examples + * @return 1 if the planner successfully found a solution; 0 otherwise + *******************************************************************************/ +int plan2d(PlannerType plannerType, char* envCfgFilename, bool forwardSearch) +{ + int bRet = 0; + double allocated_time_secs = 100.0; // in seconds + double initialEpsilon = 3.0; + MDPConfig MDPCfg; + bool bsearchuntilfirstsolution = false; + bool bforwardsearch = forwardSearch; + + // Initialize Environment (should be called before initializing anything else) + EnvironmentNAV2D environment_nav2D; + if (!environment_nav2D.InitializeEnv(envCfgFilename)) { + throw SBPL_Exception("ERROR: InitializeEnv failed"); + } + + // Initialize MDP Info + if (!environment_nav2D.InitializeMDPCfg(&MDPCfg)) { + throw SBPL_Exception("ERROR: InitializeMDPCfg failed"); + } + + // plan a path + vector solution_stateIDs_V; + + SBPLPlanner* planner = NULL; + switch (plannerType) { + case PLANNER_TYPE_ARASTAR: + printf("Initializing ARAPlanner...\n"); + planner = new ARAPlanner(&environment_nav2D, bforwardsearch); + break; + case PLANNER_TYPE_ADSTAR: + printf("Initializing ADPlanner...\n"); + planner = new ADPlanner(&environment_nav2D, bforwardsearch); + break; + case PLANNER_TYPE_RSTAR: + printf("Initializing RSTARPlanner...\n"); + planner = new RSTARPlanner(&environment_nav2D, bforwardsearch); + break; + case PLANNER_TYPE_ANASTAR: + printf("Initializing anaPlanner...\n"); + planner = new anaPlanner(&environment_nav2D, bforwardsearch); + break; + default: + printf("Invalid planner type\n"); + break; + } + + // set search mode + planner->set_search_mode(bsearchuntilfirstsolution); + + if (planner->set_start(MDPCfg.startstateid) == 0) { + throw SBPL_Exception("ERROR: failed to set start state"); + } + + if (planner->set_goal(MDPCfg.goalstateid) == 0) { + throw SBPL_Exception("ERROR: failed to set goal state"); + } + + planner->set_initialsolution_eps(initialEpsilon); + + printf("start planning...\n"); + bRet = planner->replan(allocated_time_secs, &solution_stateIDs_V); + printf("done planning\n"); + std::cout << "size of solution=" << solution_stateIDs_V.size() << std::endl; + + environment_nav2D.PrintTimeStat(stdout); + + const char* sol = "sol.txt"; + FILE* fSol = fopen(sol, "w"); + if (fSol == NULL) { + throw SBPL_Exception("ERROR: could not open solution file"); + } + for (unsigned int i = 0; i < solution_stateIDs_V.size(); i++) { + environment_nav2D.PrintState(solution_stateIDs_V[i], false, fSol); + } + fclose(fSol); + + environment_nav2D.PrintTimeStat(stdout); + + //print a path + if (bRet) { + //print the solution + printf("Solution is found\n"); + } + else { + printf("Solution does not exist\n"); + } + + fflush(NULL); + + delete planner; + + return bRet; +} + +/******************************************************************************* + * plan2duu + * @brief An examle of planning in two-dimensional space and under uncertainty. + * + * @param plannerType The type of planner to be used in this example + * @param envCfgFilename The environment config file. See + * sbpl/env_examples/nav2duu/ for examples + * @return 1 if the planner successfully found a solution; 0 otherwise + *******************************************************************************/ +int plan2duu(PlannerType plannerType, char* envCfgFilename) +{ + int bRet = 0; + double allocated_time_secs = 10.0; //in seconds + MDPConfig MDPCfg; + + //Initialize Environment (should be called before initializing anything else) + EnvironmentNAV2DUU environment_nav2Duu; + if (!environment_nav2Duu.InitializeEnv(envCfgFilename)) { + throw SBPL_Exception("ERROR: InitializeEnv failed"); + } + + //Initialize MDP Info + if (!environment_nav2Duu.InitializeMDPCfg(&MDPCfg)) { + throw SBPL_Exception("ERROR: InitializeMDPCfg failed"); + } + + //create the planner + PPCPPlanner planner(&environment_nav2Duu, environment_nav2Duu.SizeofCreatedEnv(), environment_nav2Duu.SizeofH()); + + //set start and goal + if (planner.set_start(MDPCfg.startstateid) == 0) { + throw SBPL_Exception("ERROR: failed to set start state"); + } + if (planner.set_goal(MDPCfg.goalstateid) == 0) { + throw SBPL_Exception("ERROR: failed to set goal state"); + } + + printf("start planning...\n"); + float ExpectedCost, ProbofReachGoal; + vector SolutionPolicy; + bRet = planner.replan(allocated_time_secs, &SolutionPolicy, &ExpectedCost, &ProbofReachGoal); + printf("done planning\n"); + + if (bRet) { + //print the solution + printf("Solution is found: exp. cost=%f probofreachgoal=%f\n", ExpectedCost, ProbofReachGoal); + } + else { + printf("Solution does not exist\n"); + } + + fflush(NULL); + + return bRet; +} + +/******************************************************************************* + * planxythetalat + * @brief An example of planning in three-dimensional space (x,y,theta) + * + * @param plannerType The type of planner to be used in this example + * @param envCfgFilename The environment config file. See + * sbpl/env_examples/nav3d/ for examples + * @param motPrimFilename The motion primitives file. See + * sbpl/matlab/mprim/ for examples + * @return 1 if the planner successfully found a solution; 0 otherwise + *******************************************************************************/ +int planxythetalat(PlannerType plannerType, char* envCfgFilename, char* motPrimFilename, bool forwardSearch) +{ + int bRet = 0; + double allocated_time_secs = 10.0; // in seconds + double initialEpsilon = 3.0; + MDPConfig MDPCfg; + bool bsearchuntilfirstsolution = false; + bool bforwardsearch = forwardSearch; + + // set the perimeter of the robot (it is given with 0,0,0 robot ref. point for which planning is done) + vector perimeterptsV; + sbpl_2Dpt_t pt_m; + double halfwidth = 0.01; //0.3; + double halflength = 0.01; //0.45; + pt_m.x = -halflength; + pt_m.y = -halfwidth; + perimeterptsV.push_back(pt_m); + pt_m.x = halflength; + pt_m.y = -halfwidth; + perimeterptsV.push_back(pt_m); + pt_m.x = halflength; + pt_m.y = halfwidth; + perimeterptsV.push_back(pt_m); + pt_m.x = -halflength; + pt_m.y = halfwidth; + perimeterptsV.push_back(pt_m); + + // clear the footprint + perimeterptsV.clear(); + + // Initialize Environment (should be called before initializing anything else) + EnvironmentNAVXYTHETALAT environment_navxythetalat; + + if (!environment_navxythetalat.InitializeEnv(envCfgFilename, perimeterptsV, motPrimFilename)) { + throw SBPL_Exception("ERROR: InitializeEnv failed"); + } + + // Initialize MDP Info + if (!environment_navxythetalat.InitializeMDPCfg(&MDPCfg)) { + throw SBPL_Exception("ERROR: InitializeMDPCfg failed"); + } + + // plan a path + vector solution_stateIDs_V; + + SBPLPlanner* planner = NULL; + switch (plannerType) { + case PLANNER_TYPE_ARASTAR: + printf("Initializing ARAPlanner...\n"); + planner = new ARAPlanner(&environment_navxythetalat, bforwardsearch); + break; + case PLANNER_TYPE_ADSTAR: + printf("Initializing ADPlanner...\n"); + planner = new ADPlanner(&environment_navxythetalat, bforwardsearch); + break; + case PLANNER_TYPE_RSTAR: + printf("Invalid configuration: xytheta environment does not support rstar planner...\n"); + return 0; + case PLANNER_TYPE_ANASTAR: + printf("Initializing anaPlanner...\n"); + planner = new anaPlanner(&environment_navxythetalat, bforwardsearch); + break; + default: + printf("Invalid planner type\n"); + break; + } + + // set planner properties + if (planner->set_start(MDPCfg.startstateid) == 0) { + printf("ERROR: failed to set start state\n"); + throw SBPL_Exception("ERROR: failed to set start state"); + } + if (planner->set_goal(MDPCfg.goalstateid) == 0) { + printf("ERROR: failed to set goal state\n"); + throw SBPL_Exception("ERROR: failed to set goal state"); + } + planner->set_initialsolution_eps(initialEpsilon); + planner->set_search_mode(bsearchuntilfirstsolution); + + // plan + printf("start planning...\n"); + bRet = planner->replan(allocated_time_secs, &solution_stateIDs_V); + printf("done planning\n"); + printf("size of solution=%d\n", (unsigned int)solution_stateIDs_V.size()); + + environment_navxythetalat.PrintTimeStat(stdout); + + // write solution to sol.txt + const char* sol = "sol.txt"; + FILE* fSol = fopen(sol, "w"); + if (fSol == NULL) { + throw SBPL_Exception("ERROR: could not open solution file"); + } + + // write the discrete solution to file + for (size_t i = 0; i < solution_stateIDs_V.size(); i++) { + int x; + int y; + int theta; + environment_navxythetalat.GetCoordFromState(solution_stateIDs_V[i], x, y, theta); + fprintf(fSol, "%d %d %d\t\t%.3f %.3f %.3f\n", x, y, theta, DISCXY2CONT(x, 0.1), DISCXY2CONT(y, 0.1), DiscTheta2Cont(theta, 16)); + } + + // write the continuous solution to file + vector xythetaPath; + environment_navxythetalat.ConvertStateIDPathintoXYThetaPath(&solution_stateIDs_V, &xythetaPath); + printf("solution size=%d\n", (unsigned int)xythetaPath.size()); + for (unsigned int i = 0; i < xythetaPath.size(); i++) { + fprintf(fSol, "%.3f %.3f %.3f\n", xythetaPath.at(i).x, xythetaPath.at(i).y, xythetaPath.at(i).theta); + } + fclose(fSol); + + environment_navxythetalat.PrintTimeStat(stdout); + + // print a path + if (bRet) { + // print the solution + printf("Solution is found\n"); + } + else { + printf("Solution does not exist\n"); + } + + fflush(NULL); + + delete planner; + + return bRet; +} + +/******************************************************************************* + * planxythetamlevlat + * @brief An example of planning with a multiple-level (x,y,theta) lattice + * + * @desc An example of planning with a multiple-level x,y,theta lattice (for + * example, a base and upper body). There are no additional degrees of + * freedom but each level may have a different footprint and should be + * checked against a corresponding costmap at its height. Useful for doing + * navigation of a tall ground robot operating in a cluttered 3d map. + * @param plannerType The type of planner to be used in this example + * @param envCfgFilename The environment config file. See + * sbpl/env_examples/nav3d/ for examples + * @param motPrimFilename The motion primitives file. See + * sbpl/matlab/mprim/ for examples + * @return 1 if the planner successfully found a solution; 0 otherwise + *******************************************************************************/ +int planxythetamlevlat(PlannerType plannerType, char* envCfgFilename, char* motPrimFilename, bool forwardSearch) +{ + int bRet = 0; + + double allocated_time_secs = 10.0; //in seconds + double initialEpsilon = 3.0; + MDPConfig MDPCfg; + bool bsearchuntilfirstsolution = false; + bool bforwardsearch = forwardSearch; + + //set the perimeter of the robot (it is given with 0,0,0 robot ref. point for which planning is done) + //this is for the default level - base level + vector perimeterptsV; + sbpl_2Dpt_t pt_m; + double halfwidth = 0.02; //0.3; + double halflength = 0.02; //0.45; + pt_m.x = -halflength; + pt_m.y = -halfwidth; + perimeterptsV.push_back(pt_m); + pt_m.x = halflength; + pt_m.y = -halfwidth; + perimeterptsV.push_back(pt_m); + pt_m.x = halflength; + pt_m.y = halfwidth; + perimeterptsV.push_back(pt_m); + pt_m.x = -halflength; + pt_m.y = halfwidth; + perimeterptsV.push_back(pt_m); + + //Initialize Environment (should be called before initializing anything else) + EnvironmentNAVXYTHETAMLEVLAT environment_navxythetalat; + + if (!environment_navxythetalat.InitializeEnv(envCfgFilename, perimeterptsV, motPrimFilename)) { + throw SBPL_Exception("ERROR: InitializeEnv failed"); + } + + //this is for the second level - upper body level + vector perimeterptsVV[2]; + perimeterptsVV[0].clear(); + halfwidth = 0.02; + halflength = 0.02; + pt_m.x = -halflength; + pt_m.y = -halfwidth; + perimeterptsVV[0].push_back(pt_m); + pt_m.x = halflength; + pt_m.y = -halfwidth; + perimeterptsVV[0].push_back(pt_m); + pt_m.x = halflength; + pt_m.y = halfwidth; + perimeterptsVV[0].push_back(pt_m); + pt_m.x = -halflength; + pt_m.y = halfwidth; + perimeterptsVV[0].push_back(pt_m); + + // perimeterptsV.clear(); + // perimeterptsVV[0].clear(); + + //enable the second level + int numofaddlevels = 1; + printf("Number of additional levels = %d\n", numofaddlevels); + unsigned char cost_inscribed_thresh_addlevels[2]; //size should be at least numofaddlevels + unsigned char cost_possibly_circumscribed_thresh_addlevels[2]; //size should be at least numofaddlevels + //no costs are indicative of whether a cell is within inner circle + cost_inscribed_thresh_addlevels[0] = 255; + //no costs are indicative of whether a cell is within outer circle + cost_possibly_circumscribed_thresh_addlevels[0] = 0; + //no costs are indicative of whether a cell is within inner circle + cost_inscribed_thresh_addlevels[1] = 255; + //no costs are indicative of whether a cell is within outer circle + cost_possibly_circumscribed_thresh_addlevels[1] = 0; + if (!environment_navxythetalat.InitializeAdditionalLevels(numofaddlevels, perimeterptsVV, + cost_inscribed_thresh_addlevels, + cost_possibly_circumscribed_thresh_addlevels)) + { + std::stringstream ss("ERROR: InitializeAdditionalLevels failed with numofaddlevels="); + ss << numofaddlevels; + throw SBPL_Exception(ss.str()); + } + + //set the map for the second level (index parameter for the additional levels and is zero based) + //for this example, we pass in the same map as the map for the base. In general, it can be a totally different map + //as it corresponds to a different level + //NOTE: this map has to have costs set correctly with respect to inner and outer radii of the robot + //if the second level of the robot has these radii different than at the base level, then costs + //should reflect this + //(see explanation for cost_possibly_circumscribed_thresh and + //cost_inscribed_thresh parameters in environment_navxythetalat.h file) + int addlevind = 0; + if (!environment_navxythetalat.Set2DMapforAddLev( + (const unsigned char**)(environment_navxythetalat.GetEnvNavConfig()->Grid2D), addlevind)) + { + std::stringstream ss("ERROR: Setting Map for the Additional Level failed with level "); + ss << addlevind; + throw SBPL_Exception(ss.str()); + } + + // Initialize MDP Info + if (!environment_navxythetalat.InitializeMDPCfg(&MDPCfg)) { + throw SBPL_Exception("ERROR: InitializeMDPCfg failed"); + } + + // plan a path + vector solution_stateIDs_V; + + SBPLPlanner* planner = NULL; + switch (plannerType) { + case PLANNER_TYPE_ARASTAR: + printf("Initializing ARAPlanner...\n"); + planner = new ARAPlanner(&environment_navxythetalat, bforwardsearch); + break; + case PLANNER_TYPE_ADSTAR: + printf("Initializing ADPlanner...\n"); + planner = new ADPlanner(&environment_navxythetalat, bforwardsearch); + break; + case PLANNER_TYPE_RSTAR: + printf("Invalid configuration: xytheta environment does not support rstar planner...\n"); + return 0; + case PLANNER_TYPE_ANASTAR: + printf("Initializing anaPlanner...\n"); + planner = new anaPlanner(&environment_navxythetalat, bforwardsearch); + break; + default: + printf("Invalid planner type\n"); + break; + } + + if (planner->set_start(MDPCfg.startstateid) == 0) { + printf("ERROR: failed to set start state\n"); + throw SBPL_Exception("ERROR: failed to set start state"); + } + + if (planner->set_goal(MDPCfg.goalstateid) == 0) { + printf("ERROR: failed to set goal state\n"); + throw SBPL_Exception("ERROR: failed to set goal state"); + } + planner->set_initialsolution_eps(initialEpsilon); + + //set search mode + planner->set_search_mode(bsearchuntilfirstsolution); + + printf("start planning...\n"); + bRet = planner->replan(allocated_time_secs, &solution_stateIDs_V); + printf("done planning\n"); + std::cout << "size of solution=" << solution_stateIDs_V.size() << std::endl; + + environment_navxythetalat.PrintTimeStat(stdout); + + const char* sol = "sol.txt"; + FILE* fSol = fopen(sol, "w"); + if (fSol == NULL) { + printf("ERROR: could not open solution file\n"); + throw SBPL_Exception("ERROR: could not open solution file"); + } + vector xythetaPath; + environment_navxythetalat.ConvertStateIDPathintoXYThetaPath(&solution_stateIDs_V, &xythetaPath); + printf("solution size=%d\n", (unsigned int)xythetaPath.size()); + for (unsigned int i = 0; i < xythetaPath.size(); i++) { + fprintf(fSol, "%.3f %.3f %.3f\n", xythetaPath.at(i).x, xythetaPath.at(i).y, xythetaPath.at(i).theta); + } + fclose(fSol); + + environment_navxythetalat.PrintTimeStat(stdout); + + //print a path + if (bRet) { + //print the solution + printf("Solution is found\n"); + } + else { + printf("Solution does not exist\n"); + } + + fflush(NULL); + + delete planner; + + return bRet; +} + +/******************************************************************************* + * planandnavigate2d + * @brief An example simulation of how a robot would use two-dimensional + * environment planning. + * + * @param planner The planner to be used in this example + * @param envCfgFilename The environment config file. See + * sbpl/env_examples/nav2d/ for examples + *******************************************************************************/ +int planandnavigate2d(PlannerType plannerType, char* envCfgFilename) +{ + double allocated_time_secs_foreachplan = 0.2; //in seconds + MDPConfig MDPCfg; + EnvironmentNAV2D environment_nav2D; + EnvironmentNAV2D trueenvironment_nav2D; + int size_x = -1, size_y = -1; + int startx = 0, starty = 0; + int goalx = -1, goaly = -1; + const char* sol = "sol.txt"; + FILE* fSol = fopen(sol, "w"); + if (fSol == NULL) { + throw SBPL_Exception("ERROR: could not open solution file"); + } + //int dx[8] = {-1, -1, -1, 0, 0, 1, 1, 1}; + //int dy[8] = {-1, 0, 1, -1, 1, -1, 0, 1}; + bool bPrint = false; + int x, y; + vector preds_of_changededgesIDV; + vector changedcellsV; + nav2dcell_t nav2dcell; + unsigned char obsthresh = 0; + srand(0); + int plantime_over1secs = 0, plantime_over0p5secs = 0, plantime_over0p1secs = 0, plantime_over0p05secs = 0, + plantime_below0p05secs = 0; + + //set parameters - should be done before initialization + if (!trueenvironment_nav2D.SetEnvParameter("is16connected", 1)) { + throw SBPL_Exception("ERROR: failed to set parameters"); + } + if (!environment_nav2D.SetEnvParameter("is16connected", 1)) { + throw SBPL_Exception("ERROR: failed to set parameters"); + } + + //initialize true map and robot map + if (!trueenvironment_nav2D.InitializeEnv(envCfgFilename)) { + throw SBPL_Exception("ERROR: InitializeEnv failed"); + } + trueenvironment_nav2D.GetEnvParms(&size_x, &size_y, &startx, &starty, &goalx, &goaly, &obsthresh); + unsigned char* map = (unsigned char*)calloc(size_x * size_y, sizeof(unsigned char)); + + //print the map + if (bPrint) printf("true map:\n"); + for (y = 0; bPrint && y < size_y; y++) { + for (x = 0; x < size_x; x++) { + printf("%d ", (int)trueenvironment_nav2D.IsObstacle(x, y)); + } + printf("\n"); + } + if (bPrint) printf("System Pause (return=%d)\n", system("pause")); + + //Initialize Environment (should be called before initializing anything else) + if (!environment_nav2D.InitializeEnv(size_x, size_y, map, startx, starty, goalx, goaly, obsthresh)) { + throw SBPL_Exception("ERROR: InitializeEnv failed"); + } + + //Initialize MDP Info + if (!environment_nav2D.InitializeMDPCfg(&MDPCfg)) { + throw SBPL_Exception("ERROR: InitializeMDPCfg failed"); + } + + //create a planner + vector solution_stateIDs_V; + bool bforwardsearch = false; + + SBPLPlanner* planner = NULL; + switch (plannerType) { + case PLANNER_TYPE_ARASTAR: + printf("Initializing ARAPlanner...\n"); + planner = new ARAPlanner(&environment_nav2D, bforwardsearch); + break; + case PLANNER_TYPE_ADSTAR: + printf("Initializing ADPlanner...\n"); + planner = new ADPlanner(&environment_nav2D, bforwardsearch); + break; + case PLANNER_TYPE_RSTAR: + printf("Initializing RSTARPlanner...\n"); + planner = new RSTARPlanner(&environment_nav2D, bforwardsearch); + break; + case PLANNER_TYPE_ANASTAR: + printf("Initializing anaPlanner...\n"); + planner = new anaPlanner(&environment_nav2D, bforwardsearch); + break; + default: + printf("Invalid planner type\n"); + break; + } + + planner->set_initialsolution_eps(2.0); + + //set the start and goal configurations + if (planner->set_start(MDPCfg.startstateid) == 0) { + printf("ERROR: failed to set start state\n"); + throw SBPL_Exception("ERROR: failed to set start state"); + } + if (planner->set_goal(MDPCfg.goalstateid) == 0) { + printf("ERROR: failed to set goal state\n"); + throw SBPL_Exception("ERROR: failed to set goal state"); + } + + //set search mode + planner->set_search_mode(false); + + //now comes the main loop + int goalthresh = 0; + while (abs(startx - goalx) > goalthresh || abs(starty - goaly) > goalthresh) { + + //simulate sensor data update + bool bChanges = false; + preds_of_changededgesIDV.clear(); + changedcellsV.clear(); + + int dX = 0; + int dY = 0; + for (dX = -2; dX <= 2; dX++) { + for (dY = -2; dY <= 2; dY++) { + int x = startx + dX; + int y = starty + dY; + if (x < 0 || x >= size_x || y < 0 || y >= size_y) { + continue; + } + int index = x + y * size_x; + unsigned char truecost = trueenvironment_nav2D.GetMapCost(x, y); + if (map[index] != truecost) { + map[index] = truecost; + environment_nav2D.UpdateCost(x, y, map[index]); + printf("setting cost[%d][%d] to %d\n", x, y, map[index]); + bChanges = true; + // store the changed cells + nav2dcell.x = x; + nav2dcell.y = y; + changedcellsV.push_back(nav2dcell); + } + } + } + + double TimeStarted = clock(); + + if (bChanges) { + if (dynamic_cast (planner) != NULL) { + ((ARAPlanner*)planner)->costs_changed(); //use by ARA* planner (non-incremental) + } + else if (dynamic_cast (planner) != NULL) { + //get the affected states + environment_nav2D.GetPredsofChangedEdges(&changedcellsV, &preds_of_changededgesIDV); + //let know the incremental planner about them + ((ADPlanner*)planner)->update_preds_of_changededges(&preds_of_changededgesIDV); + } + } + //planner.force_planning_from_scratch(); + + fprintf(fSol, "%d %d ", startx, starty); + + //plan a path + bool bPlanExists = false; + while (bPlanExists == false) { + printf("new planning...\n"); + bPlanExists = (planner->replan(allocated_time_secs_foreachplan, &solution_stateIDs_V) == 1); + printf("done with the solution of size=%d\n", (unsigned int)solution_stateIDs_V.size()); + environment_nav2D.PrintTimeStat(stdout); + if (bPlanExists == false) { + throw SBPL_Exception(); + } + + //for(unsigned int i = 0; i < solution_stateIDs_V.size(); i++) { + //environment_nav2D.PrintState(solution_stateIDs_V[i], true, fSol); + //} + //fprintf(fSol, "*********\n"); + } + + double plantime_secs = (clock() - TimeStarted) / ((double)CLOCKS_PER_SEC); + fprintf(fSol, "%.5f %.5f\n", plantime_secs, planner->get_solution_eps()); + fflush(fSol); + if (plantime_secs > 1.0) + plantime_over1secs++; + else if (plantime_secs > 0.5) + plantime_over0p5secs++; + else if (plantime_secs > 0.1) + plantime_over0p1secs++; + else if (plantime_secs > 0.05) + plantime_over0p05secs++; + else + plantime_below0p05secs++; + + //print the map + int startindex = startx + starty * size_x; + int goalindex = goalx + goaly * size_x; + for (y = 0; bPrint && y < size_y; y++) { + for (x = 0; x < size_x; x++) { + int index = x + y * size_x; + + //check to see if it is on the path + bool bOnthePath = false; + for (int j = 1; j < (int)solution_stateIDs_V.size(); j++) { + int newx, newy; + environment_nav2D.GetCoordFromState(solution_stateIDs_V[j], newx, newy); + if (x == newx && y == newy) bOnthePath = true; + } + + if (index != startindex && index != goalindex && !bOnthePath) + printf("%3d ", map[index]); + else if (index == startindex) + printf(" R "); + else if (index == goalindex) + printf(" G "); + else if (bOnthePath) + printf(" * "); + else + printf(" ? "); + } + printf("\n"); + } + if (bPrint) printf("System Pause (return=%d)\n", system("pause")); + + //move along the path + if (bPlanExists && (int)solution_stateIDs_V.size() > 1) { + //get coord of the successor + int newx, newy; + environment_nav2D.GetCoordFromState(solution_stateIDs_V[1], newx, newy); + + if (trueenvironment_nav2D.GetMapCost(newx, newy) >= obsthresh) { + throw SBPL_Exception("ERROR: robot is commanded to move into an obstacle"); + } + + //move + printf("moving from %d %d to %d %d\n", startx, starty, newx, newy); + startx = newx; + starty = newy; + + //update the environment + environment_nav2D.SetStart(startx, starty); + + //update the planner + if (planner->set_start(solution_stateIDs_V[1]) == 0) { + throw SBPL_Exception("ERROR: failed to update robot pose in the planner"); + } + } + + } + + //print stats + printf("stats: plantimes over 1 secs=%d; over 0.5 secs=%d; over 0.1 secs=%d; " + "over 0.05 secs=%d; below 0.05 secs=%d\n", + plantime_over1secs, plantime_over0p5secs, plantime_over0p1secs, plantime_over0p05secs, + plantime_below0p05secs); + fprintf(fSol, "stats: plantimes over 1 secs=%d; over 0.5; secs=%d; over 0.1 secs=%d; " + "over 0.05 secs=%d; below 0.05 secs=%d\n", + plantime_over1secs, plantime_over0p5secs, plantime_over0p1secs, plantime_over0p05secs, + plantime_below0p05secs); + + if (bPrint) printf("System Pause (return=%d)\n", system("pause")); + + fflush(NULL); + fclose(fSol); + + delete planner; + + return 1; +} + +/******************************************************************************* + * planandnavigatexythetalat + * @brief An example simulation of how a robot would use (x,y,theta) lattice + * planning. + * + * @param envCfgFilename The environment config file. See + * sbpl/env_examples/nav3d/ for examples + *******************************************************************************/ +int planandnavigatexythetalat(PlannerType plannerType, char* envCfgFilename, char* motPrimFilename, bool forwardSearch) +{ + double allocated_time_secs_foreachplan = 10.0; // in seconds + double initialEpsilon = 3.0; + bool bsearchuntilfirstsolution = false; + bool bforwardsearch = forwardSearch; + + double goaltol_x = 0.001, goaltol_y = 0.001, goaltol_theta = 0.001; + + bool bPrint = false; + bool bPrintMap = true; + + EnvironmentNAVXYTHETALAT environment_navxythetalat; + EnvironmentNAVXYTHETALAT trueenvironment_navxythetalat; + + // set the perimeter of the robot + // it is given with 0, 0, 0 robot ref. point for which planning is done. + vector perimeterptsV; + sbpl_2Dpt_t pt_m; + double halfwidth = 0.01; + double halflength = 0.01; + pt_m.x = -halflength; + pt_m.y = -halfwidth; + perimeterptsV.push_back(pt_m); + pt_m.x = halflength; + pt_m.y = -halfwidth; + perimeterptsV.push_back(pt_m); + pt_m.x = halflength; + pt_m.y = halfwidth; + perimeterptsV.push_back(pt_m); + pt_m.x = -halflength; + pt_m.y = halfwidth; + perimeterptsV.push_back(pt_m); + + // perimeterptsV.clear(); + + // initialize true map from the environment file without perimeter or motion primitives + if (!trueenvironment_navxythetalat.InitializeEnv(envCfgFilename)) { + throw SBPL_Exception("ERROR: InitializeEnv failed"); + } + + // environment parameters + int size_x = -1, size_y = -1, num_thetas = -1; + double startx = -1, starty = -1, starttheta = -1; + double goalx = -1, goaly = -1, goaltheta = -1; + double cellsize_m = 0.0, nominalvel_mpersecs = 0.0, timetoturn45degsinplace_secs = 0.0; + unsigned char obsthresh = 0; + vector motionprimitiveV; + + // additional environment parameters + unsigned char costinscribed_thresh = 0; + unsigned char costcircum_thresh = 0; + + // get environment parameters from the true environment + trueenvironment_navxythetalat.GetEnvParms(&size_x, &size_y, &num_thetas, &startx, &starty, &starttheta, &goalx, + &goaly, &goaltheta, &cellsize_m, &nominalvel_mpersecs, + &timetoturn45degsinplace_secs, &obsthresh, &motionprimitiveV); + costinscribed_thresh = trueenvironment_navxythetalat.GetEnvParameter("cost_inscribed_thresh"); + costcircum_thresh = trueenvironment_navxythetalat.GetEnvParameter("cost_possibly_circumscribed_thresh"); + + // print the map + if (bPrintMap) { + printf("true map:\n"); + for (int y = 0; y < size_y; y++) { + for (int x = 0; x < size_x; x++) { + printf("%3d ", trueenvironment_navxythetalat.GetMapCost(x, y)); + } + printf("\n"); + } + printf("System Pause (return=%d)\n", system("pause")); + } + + // create an empty map + unsigned char* map = new unsigned char[size_x * size_y]; + for (int i = 0; i < size_x * size_y; i++) { + map[i] = 0; + } + + // check the start and goal obtained from the true environment + printf("start: %f %f %f, goal: %f %f %f\n", startx, starty, starttheta, goalx, goaly, goaltheta); + + // set robot environment parameters (should be done before initialize function is called) + if (!environment_navxythetalat.SetEnvParameter("cost_inscribed_thresh", costinscribed_thresh)) { + throw SBPL_Exception("ERROR: failed to set parameters"); + } + if (!environment_navxythetalat.SetEnvParameter("cost_possibly_circumscribed_thresh", costcircum_thresh)) { + throw SBPL_Exception("ERROR: failed to set parameters"); + } + + // initialize environment (should be called before initializing anything else) + EnvNAVXYTHETALAT_InitParms params; + params.startx = startx; + params.starty = starty; + params.starttheta = starttheta; + params.goalx = goalx; + params.goaly = goaly; + params.goaltheta = goaltheta; + params.goaltol_x = goaltol_x; + params.goaltol_y = goaltol_y; + params.goaltol_theta = goaltol_theta; + params.mapdata = map; + params.numThetas = num_thetas; + + bool envInitialized = environment_navxythetalat.InitializeEnv(size_x, size_y, perimeterptsV, cellsize_m, + nominalvel_mpersecs, timetoturn45degsinplace_secs, + obsthresh, motPrimFilename, params); + + if (!envInitialized) { + throw SBPL_Exception("ERROR: InitializeEnv failed"); + } + + // set start and goal states + environment_navxythetalat.SetStart(startx, starty, starttheta); + environment_navxythetalat.SetGoal(goalx, goaly, goaltheta); + + MDPConfig MDPCfg; + + // initialize MDP info + if (!environment_navxythetalat.InitializeMDPCfg(&MDPCfg)) { + throw SBPL_Exception("ERROR: InitializeMDPCfg failed"); + } + + // create a planner + vector solution_stateIDs_V; + + SBPLPlanner* planner = NULL; + switch (plannerType) { + case PLANNER_TYPE_ARASTAR: + printf("Initializing ARAPlanner...\n"); + planner = new ARAPlanner(&environment_navxythetalat, bforwardsearch); + break; + case PLANNER_TYPE_ADSTAR: + printf("Initializing ADPlanner...\n"); + planner = new ADPlanner(&environment_navxythetalat, bforwardsearch); + break; + case PLANNER_TYPE_RSTAR: + printf("Invalid configuration: xytheta environment does not support rstar planner...\n"); + return 0; + case PLANNER_TYPE_ANASTAR: + printf("Initializing anaPlanner...\n"); + planner = new anaPlanner(&environment_navxythetalat, bforwardsearch); + break; + default: + printf("Invalid planner type\n"); + break; + } + + // set the start and goal states for the planner and other search variables + if (planner->set_start(MDPCfg.startstateid) == 0) { + throw SBPL_Exception("ERROR: failed to set start state"); + } + if (planner->set_goal(MDPCfg.goalstateid) == 0) { + throw SBPL_Exception("ERROR: failed to set goal state"); + } + planner->set_initialsolution_eps(initialEpsilon); + planner->set_search_mode(bsearchuntilfirstsolution); + + // compute sensing as a square surrounding the robot with length twice that of the + // longest motion primitive + vector sensecells; + double maxMotPrimLengthSquared = 0.0; + double maxMotPrimLength = 0.0; + const EnvNAVXYTHETALATConfig_t* cfg = environment_navxythetalat.GetEnvNavConfig(); + for (int i = 0; i < (int)cfg->mprimV.size(); i++) { + const SBPL_xytheta_mprimitive& mprim = cfg->mprimV.at(i); + int dx = mprim.endcell.x; + int dy = mprim.endcell.y; + if (dx * dx + dy * dy > maxMotPrimLengthSquared) { + std::cout << "Found a longer motion primitive with dx = " << dx << " and dy = " << dy + << " from starttheta = " << (int)mprim.starttheta_c << std::endl; + maxMotPrimLengthSquared = dx * dx + dy * dy; + } + } + maxMotPrimLength = sqrt((double)maxMotPrimLengthSquared); + std::cout << "Maximum motion primitive length: " << maxMotPrimLength << std::endl; + + int sensingRange = (int)ceil(maxMotPrimLength); + for (int x = -sensingRange; x <= sensingRange; x++) { + for (int y = -sensingRange; y <= sensingRange; y++) { + sensecells.push_back(sbpl_2Dcell_t(x, y)); + } + } + + // create a file to hold the solution vector + const char* sol = "sol.txt"; + FILE* fSol = fopen(sol, "w"); + if (fSol == NULL) { + throw SBPL_Exception("ERROR: could not open solution file"); + } + + // print the goal pose + int goalx_c = CONTXY2DISC(goalx, cellsize_m); + int goaly_c = CONTXY2DISC(goaly, cellsize_m); + int goaltheta_c = ContTheta2Disc(goaltheta, num_thetas); + printf("goal_c: %d %d %d\n", goalx_c, goaly_c, goaltheta_c); + + vector preds_of_changededgesIDV; + vector changedcellsV; + nav2dcell_t nav2dcell; + vector xythetaPath; + + // now comes the main loop + while (fabs(startx - goalx) > goaltol_x || fabs(starty - goaly) > goaltol_y || fabs(starttheta - goaltheta) + > goaltol_theta) { + //simulate sensor data update + bool bChanges = false; + preds_of_changededgesIDV.clear(); + changedcellsV.clear(); + + // simulate sensing the cells + for (int i = 0; i < (int)sensecells.size(); i++) { + int x = CONTXY2DISC(startx, cellsize_m) + sensecells.at(i).x; + int y = CONTXY2DISC(starty, cellsize_m) + sensecells.at(i).y; + + // ignore if outside the map + if (x < 0 || x >= size_x || y < 0 || y >= size_y) { + continue; + } + + int index = x + y * size_x; + unsigned char truecost = trueenvironment_navxythetalat.GetMapCost(x, y); + // update the cell if we haven't seen it before + if (map[index] != truecost) { + map[index] = truecost; + environment_navxythetalat.UpdateCost(x, y, map[index]); + printf("setting cost[%d][%d] to %d\n", x, y, map[index]); + bChanges = true; + // store the changed cells + nav2dcell.x = x; + nav2dcell.y = y; + changedcellsV.push_back(nav2dcell); + } + } + + double TimeStarted = clock(); + + // if necessary notify the planner of changes to costmap + if (bChanges) { + if (dynamic_cast (planner) != NULL) { + ((ARAPlanner*)planner)->costs_changed(); //use by ARA* planner (non-incremental) + } + else if (dynamic_cast (planner) != NULL) { + // get the affected states + environment_navxythetalat.GetPredsofChangedEdges(&changedcellsV, &preds_of_changededgesIDV); + // let know the incremental planner about them + //use by AD* planner (incremental) + ((ADPlanner*)planner)->update_preds_of_changededges(&preds_of_changededgesIDV); + printf("%d states were affected\n", (int)preds_of_changededgesIDV.size()); + } + } + + int startx_c = CONTXY2DISC(startx, cellsize_m); + int starty_c = CONTXY2DISC(starty, cellsize_m); + int starttheta_c = ContTheta2Disc(starttheta, num_thetas); + + // plan a path + bool bPlanExists = false; + + printf("new planning...\n"); + bPlanExists = (planner->replan(allocated_time_secs_foreachplan, &solution_stateIDs_V) == 1); + printf("done with the solution of size=%d and sol. eps=%f\n", (unsigned int)solution_stateIDs_V.size(), + planner->get_solution_eps()); + environment_navxythetalat.PrintTimeStat(stdout); + + // write the solution to sol.txt + fprintf(fSol, "plan time=%.5f eps=%.2f\n", (clock() - TimeStarted) / ((double)CLOCKS_PER_SEC), + planner->get_solution_eps()); + fflush(fSol); + + xythetaPath.clear(); + environment_navxythetalat.ConvertStateIDPathintoXYThetaPath(&solution_stateIDs_V, &xythetaPath); + printf("actual path (with intermediate poses) size=%d\n", (unsigned int)xythetaPath.size()); + for (unsigned int i = 0; i < xythetaPath.size(); i++) { + fprintf(fSol, "%.3f %.3f %.3f\n", xythetaPath.at(i).x, xythetaPath.at(i).y, xythetaPath.at(i).theta); + } + fprintf(fSol, "*********\n"); + + for (int j = 1; j < (int)solution_stateIDs_V.size(); j++) { + int newx, newy, newtheta = 0; + environment_navxythetalat.GetCoordFromState(solution_stateIDs_V[j], newx, newy, newtheta); + fprintf(fSol, "%d %d %d\n", newx, newy, newtheta); + } + fflush(fSol); + + // print the map (robot's view of the world and current plan) + int startindex = startx_c + starty_c * size_x; + int goalindex = goalx_c + goaly_c * size_x; + for (int y = 0; bPrintMap && y < size_y; y++) { + for (int x = 0; x < size_x; x++) { + int index = x + y * size_x; + int cost = map[index]; + cost = environment_navxythetalat.GetMapCost(x, y); + + // check to see if it is on the path + bool bOnthePath = false; + for (int j = 1; j < (int)solution_stateIDs_V.size(); j++) { + int newx, newy, newtheta = 0; + environment_navxythetalat.GetCoordFromState(solution_stateIDs_V[j], newx, newy, newtheta); + if (x == newx && y == newy) bOnthePath = true; + } + + if (index != startindex && index != goalindex && !bOnthePath) { + printf("%3d ", cost); + } + else if (index == startindex) { + printf(" X "); + } + else if (index == goalindex) { + printf(" G "); + } + else if (bOnthePath) { + printf(" * "); + } + else { + printf("? "); + } + } + printf("\n"); + } + + // move along the path + if (bPlanExists && (int)xythetaPath.size() > 1) { + //get coord of the successor + int newx, newy, newtheta; + + // move until we move into the end of motion primitive + environment_navxythetalat.GetCoordFromState(solution_stateIDs_V[1], newx, newy, newtheta); + + printf("moving from %d %d %d to %d %d %d\n", startx_c, starty_c, starttheta_c, newx, newy, newtheta); + + // this check is weak since true configuration does not know the actual perimeter of the robot + if (!trueenvironment_navxythetalat.IsValidConfiguration(newx, newy, newtheta)) { + throw SBPL_Exception("ERROR: robot is commanded to move into an invalid configuration according to true environment"); + } + + // move + startx = DISCXY2CONT(newx, cellsize_m); + starty = DISCXY2CONT(newy, cellsize_m); + starttheta = DiscTheta2Cont(newtheta, num_thetas); + + // update the environment + int newstartstateID = environment_navxythetalat.SetStart(startx, starty, starttheta); + + // update the planner + if (planner->set_start(newstartstateID) == 0) { + throw SBPL_Exception("ERROR: failed to update robot pose in the planner"); + } + } + else { + printf("No move is made\n"); + } + + if (bPrint) { + printf("System Pause (return=%d)\n", system("pause")); + } + } + + printf("goal reached!\n"); + + fflush(NULL); + fclose(fSol); + + delete[] map; + delete planner; + + return 1; +} + +/******************************************************************************* + * planrobarm - An example of planning a robot arm with six degrees-of-freedom. + * + * @param envCfgFilename The environment config file. See + * sbpl/env_examples/robarm for examples + * @return 1 if the planner successfully found a solution; 0 otherwise + *******************************************************************************/ +int planrobarm(PlannerType plannerType, char* envCfgFilename, bool forwardSearch) +{ + int bRet = 0; + double allocated_time_secs = 5.0; //in seconds + MDPConfig MDPCfg; + bool bforwardsearch = forwardSearch; + + //Initialize Environment (should be called before initializing anything else) + EnvironmentROBARM environment_robarm; + if (!environment_robarm.InitializeEnv(envCfgFilename)) { + throw SBPL_Exception("ERROR: InitializeEnv failed"); + } + + //Initialize MDP Info + if (!environment_robarm.InitializeMDPCfg(&MDPCfg)) { + throw SBPL_Exception("ERROR: InitializeMDPCfg failed"); + } + + //srand(1); + + //plan a path + vector solution_stateIDs_V; + + SBPLPlanner* planner = NULL; + switch (plannerType) { + case PLANNER_TYPE_ARASTAR: + printf("Initializing ARAPlanner...\n"); + planner = new ARAPlanner(&environment_robarm, bforwardsearch); + break; + case PLANNER_TYPE_ADSTAR: + printf("Initializing ADPlanner...\n"); + planner = new ADPlanner(&environment_robarm, bforwardsearch); + break; + case PLANNER_TYPE_RSTAR: + printf("Initializing RSTARPlanner...\n"); + planner = new RSTARPlanner(&environment_robarm, bforwardsearch); + break; + case PLANNER_TYPE_ANASTAR: + printf("Initializing anaPlanner...\n"); + planner = new anaPlanner(&environment_robarm, bforwardsearch); + break; + default: + printf("Invalid planner type\n"); + break; + } + + if (planner->set_start(MDPCfg.startstateid) == 0) { + throw SBPL_Exception("ERROR: failed to set start state"); + } + + if (planner->set_goal(MDPCfg.goalstateid) == 0) { + throw SBPL_Exception("ERROR: failed to set goal state"); + } + + printf("start planning...\n"); + bRet = planner->replan(allocated_time_secs, &solution_stateIDs_V); + printf("done planning\n"); + std::cout << "size of solution=" << solution_stateIDs_V.size() << std::endl; + + const char* sol = "sol.txt"; + FILE* fSol = fopen(sol, "w"); + if (fSol == NULL) { + throw SBPL_Exception("ERROR: could not open solution file"); + } + for (unsigned int i = 0; i < solution_stateIDs_V.size(); i++) { + environment_robarm.PrintState(solution_stateIDs_V[i], true, fSol); + } + fclose(fSol); + + //print a path + if (bRet) { + //print the solution + printf("Solution is found\n"); + } + else + printf("Solution does not exist\n"); + + fflush(NULL); + + delete planner; + + return bRet; +} + +/******************************************************************************* + * main - Parse command line arguments and launch one of the sbpl examples above. + * Launch sbpl with just the -h option for usage help. + * + * @param argc The number of command-line arguments + * @param argv The command-line arguments + *******************************************************************************/ +int main(int argc, char *argv[]) +{ + // Print help + if (argc == 2 && strcmp(argv[1], "-h") == 0) { + PrintHelp(argv); + return MAIN_RESULT_SUCCESS; + } + else if (argc < 2) { + PrintUsage(argv); + return MAIN_RESULT_INSUFFICIENT_ARGS; + } + + // Find the number of options passed in; cfg and motprim files come after all options + // options include any string starting with "-" + int numOptions = 0; + for (int i = 1; i < argc; i++) { + if (strncmp("-", argv[i], 1) == 0) { + numOptions++; + } + else { + break; + } + } + + // Check command line arguments to find environment type and whether or not to + // use one of the navigating examples. + bool navigating = CheckIsNavigating(numOptions, argv); + std::string environmentType = CheckEnvironmentType(numOptions, argv); + std::string plannerType = CheckPlannerType(numOptions, argv); + std::string searchDir = CheckSearchDirection(numOptions, argv); + + std::cout << "Environment: " << environmentType << "; Planner: " << plannerType << "; Search direction: " + << searchDir << std::endl; + + int envArgIdx = numOptions + 1; + EnvironmentType environment = StrToEnvironmentType(environmentType.c_str()); + PlannerType planner = StrToPlannerType(plannerType.c_str()); + bool forwardSearch = !strcmp(searchDir.c_str(), "forward"); + + bool usingMotionPrimitives = (argc == numOptions + 3); + char* motPrimFilename = usingMotionPrimitives ? argv[envArgIdx + 1] : NULL; + + // make sure we've been given valid a valid environment + if (environment == INVALID_ENV_TYPE || planner == INVALID_PLANNER_TYPE) { + PrintUsage(argv); + return MAIN_RESULT_INCORRECT_OPTIONS; + } + + // Launch the correct example given the planner and an environment file. + int plannerRes = 0; + switch (environment) { + case ENV_TYPE_2D: + if (navigating) { + plannerRes = planandnavigate2d(planner, argv[envArgIdx]); + } + else { + plannerRes = plan2d(planner, argv[envArgIdx], forwardSearch); + } + break; + case ENV_TYPE_2DUU: + printf("Warning: planning in two dimensions under uncertainty is not fully implemented!\n"); + plannerRes = plan2duu(planner, argv[envArgIdx]); + break; + case ENV_TYPE_XYTHETA: + if (navigating) { + plannerRes = planandnavigatexythetalat(planner, argv[envArgIdx], motPrimFilename, forwardSearch); + } + else { + plannerRes = planxythetalat(planner, argv[envArgIdx], motPrimFilename, forwardSearch); + } + break; + case ENV_TYPE_XYTHETAMLEV: + plannerRes = planxythetamlevlat(planner, argv[envArgIdx], motPrimFilename, forwardSearch); + break; + case ENV_TYPE_ROBARM: + plannerRes = planrobarm(planner, argv[envArgIdx], forwardSearch); + break; + default: + printf("Unsupported Environment Type...\n"); + PrintUsage(argv); + return MAIN_RESULT_UNSUPPORTED_ENV; + } + + return plannerRes == 1 ? MAIN_RESULT_SUCCESS : MAIN_RESULT_FAILURE; +} diff --git a/navigations/sbpl/src/test/module-tests.cpp b/navigations/sbpl/src/test/module-tests.cpp new file mode 100755 index 0000000..3cfe1ff --- /dev/null +++ b/navigations/sbpl/src/test/module-tests.cpp @@ -0,0 +1,106 @@ +/* + * Copyright (c) 2008, Maxim Likhachev + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Carnegie Mellon University nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include +#include +#include + +using namespace std; + +#include "../headers.h" + +static const std::string PATH_PREFIX("src/test/"); + +void diffTest(const std::string& outputStr) +{ + std::string validOutputStr(outputStr + ".valid"); + std::ifstream validFile(validOutputStr.c_str()); + // If there is no valid file then generate one. + if (!validFile.good()) { + std::ifstream newOutputFile(outputStr.c_str()); + std::stringbuf sbuf; + newOutputFile >> &sbuf; + std::ofstream newValidFile(validOutputStr.c_str()); + newValidFile << sbuf.str(); + } + else { // Verify output against the valid file. + std::stringbuf newStrBuf, validStrBuf; + std::ifstream fNew(outputStr.c_str()), fValid(validOutputStr.c_str()); + fNew >> &newStrBuf; + fValid >> &validStrBuf; + ASSERT_EQ(newStrBuf.str() == validStrBuf.str(), true); + } +} + +void runARAPlannerTest(const std::string& problem) +{ + try { + double allocated_time_secs = 0.5; // in seconds + MDPConfig MDPCfg; + EnvironmentNAV2D environment_nav2D; + std::string problemStr = PATH_PREFIX + problem; + ASSERT_EQ(environment_nav2D.InitializeEnv(problemStr.c_str()), true); + ASSERT_EQ(environment_nav2D.InitializeMDPCfg(&MDPCfg), true); + + // plan a path + vector solution_stateIDs_V; + ARAPlanner ara_planner(&environment_nav2D, false); + ASSERT_EQ(ara_planner.set_start(MDPCfg.startstateid), true); + ASSERT_EQ(ara_planner.set_goal(MDPCfg.goalstateid), true); + ASSERT_EQ(ara_planner.replan(allocated_time_secs, &solution_stateIDs_V), true); + + // output the path + std::string outputStr = problemStr + ".out"; + FILE* fSol = SBPL_FOPEN(outputStr.c_str(), "w"); + for (unsigned int i = 0; i < solution_stateIDs_V.size(); i++) { + environment_nav2D.PrintState(solution_stateIDs_V[i], true, fSol); + } + + SBPL_FCLOSE(fSol); + + // Now apply the file diff test + diffTest(outputStr); + } + catch (...) { + FAIL() << "Uncaught exception : " << "This is OK on OS X"; + } +} + +TEST(araplanner, env1) +{ + runARAPlannerTest("env1.cfg"); +} + +int main(int argc, char *argv[]) +{ + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} + diff --git a/navigations/sbpl/src/test/test_adjacency_list.cpp b/navigations/sbpl/src/test/test_adjacency_list.cpp new file mode 100755 index 0000000..ef041ad --- /dev/null +++ b/navigations/sbpl/src/test/test_adjacency_list.cpp @@ -0,0 +1,113 @@ +/* + * Copyright (c) 2008, Maxim Likhachev + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Carnegie Mellon University nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include +using namespace std; + +#include + +// 2d Points +struct Point2D +{ + Point2D(int newX, int newY) : + x(newX), y(newY) + { + } + + int heuristicDistanceTo(const Point2D& p) + { + int dx = p.x - x; + int dy = p.y - y; + int dist = ((int)sqrt(dx * dx + dy * dy)); + return dist; + } + + int x; + int y; +}; + +ostream& operator<<(ostream& stream, Point2D p) +{ + stream << "(" << p.x << ", " << p.y << ")"; + return stream; +} + +int operator<(const Point2D& p1, const Point2D& p2) +{ + return (p1.x < p2.x) || ((p1.x == p2.x) && (p1.y < p2.y)); +} + +void testPlanner(AdjacencyListSBPLEnv& e) +{ + int sol_cost; + e.writeToStream(); + vector solution = e.findOptimalPath(&sol_cost); + cout << "Returned plan is "; + for (unsigned int i = 0; i < solution.size(); i++) { + cout << solution[i] << " "; + } + cout << endl; +} + +int main(int, char**) +{ + AdjacencyListSBPLEnv e; + Point2D p1(0, 0); + Point2D p2(2, 1); + Point2D p3(1, 4); + Point2D p4(5, 5); + + e.addPoint(p1); + e.addPoint(p4); + e.addPoint(p3); + e.addPoint(p2); + + e.setCost(p1, p2, 4); + e.setCost(p1, p3, 6); + e.setCost(p3, p4, 5); + e.setCost(p2, p4, 15); + + e.setStartState(p1); + e.setGoalState(p4); + + // Initialize the MDPConfig (what does this do exactly?) + //MDPConfig c; + //e.InitializeMDPCfg(&c); + + // Tests + testPlanner(e); + e.setCost(p2, p4, 1); + testPlanner(e); + e.removeLastPoints(); + testPlanner(e); + e.writeToStream(); + return 0; +} + diff --git a/navigations/sbpl/src/utils/2Dgridsearch.cpp b/navigations/sbpl/src/utils/2Dgridsearch.cpp new file mode 100755 index 0000000..2fc0dda --- /dev/null +++ b/navigations/sbpl/src/utils/2Dgridsearch.cpp @@ -0,0 +1,882 @@ +/* + * Copyright (c) 2008, Maxim Likhachev + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Carnegie Mellon University nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include +#include + +#include +#include +#include + +using namespace std; + +// Creating custom getCost functions that will combine multiple cells in the main grid +// into a single cell in the 2D grid. +// Using templates for common cases so the compiler can generate faster code +template +unsigned char getCostT(unsigned char **Grid2D, int x, int y, int /*resample*/) +{ + if(N == 1) // the compiler will optimize out this if statement + { + return Grid2D[x][y]; + } + else + { + x *= N; + y *= N; + unsigned char maximum = Grid2D[x][y]; + for(int dy=0; dy; break; + case 2: getCost = &getCostT<2>; break; + case 3: getCost = &getCostT<3>; break; + case 4: getCost = &getCostT<4>; break; + case 5: getCost = &getCostT<5>; break; + default: + getCost = &getCostN; + } + + startX_ = -1; + startY_ = -1; + goalX_ = -1; + goalY_ = -1; + + largestcomputedoptf_ = 0; + + //compute dx, dy, dxintersects and dyintersects arrays + computedxy(); + + term_condition_usedlast = SBPL_2DGRIDSEARCH_TERM_CONDITION_ALLCELLS; + + //allocate memory + OPEN2D_ = new CIntHeap(width_ * height_); + if (!createSearchStates2D()) { + throw SBPL_Exception("ERROR: failed to create searchstatespace2D"); + } + + //by default, OPEN is implemented as heap + OPEN2DBLIST_ = NULL; + OPENtype_ = SBPL_2DGRIDSEARCH_OPENTYPE_HEAP; + + initial_dynamic_bucket_size_ = initial_dynamic_bucket_size; +} + +bool SBPL2DGridSearch::setOPENdatastructure(SBPL_2DGRIDSEARCH_OPENTYPE OPENtype) +{ + OPENtype_ = OPENtype; + + switch (OPENtype_) { + case SBPL_2DGRIDSEARCH_OPENTYPE_HEAP: + //this is the default, nothing else needs to be done + break; + case SBPL_2DGRIDSEARCH_OPENTYPE_SLIDINGBUCKETS: + SBPL_PRINTF("setting OPEN2D data structure to sliding buckets\n"); + if (OPEN2DBLIST_ == NULL) { + //create sliding buckets + //compute max distance for edge + int maxdistance = 0; + for (int dind = 0; dind < SBPL_2DGRIDSEARCH_NUMOF2DDIRS; dind++) { + maxdistance = __max(maxdistance, dxy_distance_mm_[dind]); + } + int bucketsize = __max(1000, this->width_ + this->height_); + int numofbuckets = 255 * maxdistance; + SBPL_PRINTF("creating sliding bucket-based OPEN2D %d buckets, each bucket of size %d ...", numofbuckets, + bucketsize); + OPEN2DBLIST_ = new CSlidingBucket(numofbuckets, bucketsize, initial_dynamic_bucket_size_); + SBPL_PRINTF("done\n"); + } + //delete other data structures + if (OPEN2D_ != NULL) { + OPEN2D_->makeemptyheap(); + delete OPEN2D_; + OPEN2D_ = NULL; + } + + break; + default: + std::stringstream ss("ERROR: unknown data structure type = "); + ss << OPENtype_ << " for OPEN2D"; + throw SBPL_Exception(ss.str()); + }; + + return true; +} + +bool SBPL2DGridSearch::createSearchStates2D(void) +{ + int x, y; + + if (searchStates2D_ != NULL) { + SBPL_ERROR("ERROR: We already have a non-NULL search states array\n"); + return false; + } + + searchStates2D_ = new SBPL_2DGridSearchState*[width_]; + for (x = 0; x < width_; x++) { + searchStates2D_[x] = new SBPL_2DGridSearchState[height_]; + for (y = 0; y < height_; y++) { + searchStates2D_[x][y].iterationaccessed = iteration_; + searchStates2D_[x][y].x = x; + searchStates2D_[x][y].y = y; + initializeSearchState2D(&searchStates2D_[x][y]); + } + } + return true; +} + +inline void SBPL2DGridSearch::initializeSearchState2D(SBPL_2DGridSearchState* state2D) +{ + state2D->g = INFINITECOST; + state2D->heapindex = 0; + state2D->iterationaccessed = iteration_; +} + +void SBPL2DGridSearch::destroy() +{ + // destroy the OPEN list: + if (OPEN2D_ != NULL) { + OPEN2D_->makeemptyheap(); + delete OPEN2D_; + OPEN2D_ = NULL; + } + + // destroy the 2D states: + if (searchStates2D_ != NULL) { + for (int x = 0; x < width_; x++) { + delete[] searchStates2D_[x]; + } + delete[] searchStates2D_; + searchStates2D_ = NULL; + } + + if (OPEN2DBLIST_ != NULL) { + delete OPEN2DBLIST_; + OPEN2DBLIST_ = NULL; + } +} + +void SBPL2DGridSearch::computedxy() +{ + //initialize some constants for 2D search + dx_[0] = 1; + dy_[0] = 1; + dx0intersects_[0] = -1; + dy0intersects_[0] = -1; + dx_[1] = 1; + dy_[1] = 0; + dx0intersects_[1] = -1; + dy0intersects_[1] = -1; + dx_[2] = 1; + dy_[2] = -1; + dx0intersects_[2] = -1; + dy0intersects_[2] = -1; + dx_[3] = 0; + dy_[3] = 1; + dx0intersects_[3] = -1; + dy0intersects_[3] = -1; + dx_[4] = 0; + dy_[4] = -1; + dx0intersects_[4] = -1; + dy0intersects_[4] = -1; + dx_[5] = -1; + dy_[5] = 1; + dx0intersects_[5] = -1; + dy0intersects_[5] = -1; + dx_[6] = -1; + dy_[6] = 0; + dx0intersects_[6] = -1; + dy0intersects_[6] = -1; + dx_[7] = -1; + dy_[7] = -1; + dx0intersects_[7] = -1; + dy0intersects_[7] = -1; + + //Note: these actions have to be starting at 8 and through 15, since they + //get multiplied correspondingly in Dijkstra's search based on index +#if SBPL_2DGRIDSEARCH_NUMOF2DDIRS == 16 + dx_[8] = 2; dy_[8] = 1; + dx0intersects_[8] = 1; dy0intersects_[8] = 0; dx1intersects_[8] = 1; dy1intersects_[8] = 1; + dx_[9] = 1; dy_[9] = 2; + dx0intersects_[9] = 0; dy0intersects_[9] = 1; dx1intersects_[9] = 1; dy1intersects_[9] = 1; + dx_[10] = -1; dy_[10] = 2; + dx0intersects_[10] = 0; dy0intersects_[10] = 1; dx1intersects_[10] = -1; dy1intersects_[10] = 1; + dx_[11] = -2; dy_[11] = 1; + dx0intersects_[11] = -1; dy0intersects_[11] = 0; dx1intersects_[11] = -1; dy1intersects_[11] = 1; + dx_[12] = -2; dy_[12] = -1; + dx0intersects_[12] = -1; dy0intersects_[12] = 0; dx1intersects_[12] = -1; dy1intersects_[12] = -1; + dx_[13] = -1; dy_[13] = -2; + dx0intersects_[13] = 0; dy0intersects_[13] = -1; dx1intersects_[13] = -1; dy1intersects_[13] = -1; + dx_[14] = 1; dy_[14] = -2; + dx0intersects_[14] = 0; dy0intersects_[14] = -1; dx1intersects_[14] = 1; dy1intersects_[14] = -1; + dx_[15] = 2; dy_[15] = -1; + dx0intersects_[15] = 1; dy0intersects_[15] = 0; dx1intersects_[15] = 1; dy1intersects_[15] = -1; +#endif + + //compute distances + for (int dind = 0; dind < SBPL_2DGRIDSEARCH_NUMOF2DDIRS; dind++) { + + if (dx_[dind] != 0 && dy_[dind] != 0) { + if (dind <= 7) + //the cost of a diagonal move in millimeters + dxy_distance_mm_[dind] = (int)(cellSize_m_ * 1414); + else + //the cost of a move to 1,2 or 2,1 or so on in millimeters + dxy_distance_mm_[dind] = (int)(cellSize_m_ * 2236); + } + else + dxy_distance_mm_[dind] = (int)(cellSize_m_ * 1000); //the cost of a horizontal move in millimeters + } +} + +//-------------------------------------------------------------------------------------------------------------------- + +//-----------------------------------------debugging functions---------------------------------------------------------- + +void SBPL2DGridSearch::printvalues() +{ + +} + +//-------------------------------------------------------------------------------------------------------------------- + +//-----------------------------------------main functions-------------------------------------------------------------- + +bool SBPL2DGridSearch::search(unsigned char** Grid2D, unsigned char obsthresh, int startx_c, int starty_c, int goalx_c, + int goaly_c, SBPL_2DGRIDSEARCH_TERM_CONDITION termination_condition) +{ + startx_c /= downsample_; + starty_c /= downsample_; + goalx_c /= downsample_; + goaly_c /= downsample_; + + switch (OPENtype_) { + case SBPL_2DGRIDSEARCH_OPENTYPE_HEAP: + return SBPL2DGridSearch::search_withheap(Grid2D, obsthresh, startx_c, starty_c, goalx_c, goaly_c, + termination_condition); + break; + case SBPL_2DGRIDSEARCH_OPENTYPE_SLIDINGBUCKETS: + return SBPL2DGridSearch::search_withslidingbuckets(Grid2D, obsthresh, startx_c, starty_c, goalx_c, goaly_c, + termination_condition); + break; + default: + std::stringstream ss("ERROR: unknown data structure type = "); + ss << OPENtype_ << " for OPEN2D"; + throw SBPL_Exception(ss.str()); + }; + return false; +} + +bool SBPL2DGridSearch::search_withheap(unsigned char** Grid2D, unsigned char obsthresh, int startx_c, int starty_c, + int goalx_c, int goaly_c, SBPL_2DGRIDSEARCH_TERM_CONDITION termination_condition) +{ + SBPL_2DGridSearchState *searchExpState = NULL; + SBPL_2DGridSearchState *searchPredState = NULL; + int numofExpands = 0; + int key; + + //get the current time + clock_t starttime = clock(); + + //closed = 0 + iteration_++; + + //init start and goal coordinates + startX_ = startx_c; + startY_ = starty_c; + goalX_ = goalx_c; + goalY_ = goaly_c; + + //clear the heap + OPEN2D_->makeemptyheap(); + + //set the term. condition + term_condition_usedlast = termination_condition; + + //check the validity of start/goal + if (!withinMap(startx_c, starty_c) || !withinMap(goalx_c, goaly_c)) { + SBPL_ERROR("ERROR: grid2Dsearch is called on invalid start (%d %d) or goal(%d %d)\n", startx_c, starty_c, + goalx_c, goaly_c); + return false; + } + + // initialize the start and goal states + searchExpState = &searchStates2D_[startX_][startY_]; + initializeSearchState2D(searchExpState); + initializeSearchState2D(&searchStates2D_[goalx_c][goaly_c]); + SBPL_2DGridSearchState* search2DGoalState = &searchStates2D_[goalx_c][goaly_c]; + + //seed the search + searchExpState->g = 0; + key = searchExpState->g; + if (termination_condition == SBPL_2DGRIDSEARCH_TERM_CONDITION_OPTPATHFOUND) + //use h-values only if we are NOT computing all state values + key = key + SBPL_2DGRIDSEARCH_HEUR2D(startX_, startY_); + + OPEN2D_->insertheap(searchExpState, key); + + //set the termination condition + float term_factor = 0.0; + switch (termination_condition) { + case SBPL_2DGRIDSEARCH_TERM_CONDITION_OPTPATHFOUND: + term_factor = 1; + break; + case SBPL_2DGRIDSEARCH_TERM_CONDITION_20PERCENTOVEROPTPATH: + term_factor = (float)(1.0 / 1.2); + break; + case SBPL_2DGRIDSEARCH_TERM_CONDITION_TWOTIMESOPTPATH: + term_factor = 0.5; + break; + case SBPL_2DGRIDSEARCH_TERM_CONDITION_THREETIMESOPTPATH: + term_factor = (float)(1.0 / 3.0); + break; + case SBPL_2DGRIDSEARCH_TERM_CONDITION_ALLCELLS: + term_factor = 0.0; + break; + default: + SBPL_ERROR("ERROR: incorrect termination factor for grid2Dsearch\n"); + term_factor = 0.0; + }; + + char *pbClosed = (char*)calloc(1, width_ * height_); + + //the main repetition of expansions + while (!OPEN2D_->emptyheap() && + __min(INFINITECOST, search2DGoalState->g) > term_factor * OPEN2D_->getminkeyheap()) + { + //get the next state for expansion + searchExpState = (SBPL_2DGridSearchState*)OPEN2D_->deleteminheap(); + numofExpands++; + + int exp_x = searchExpState->x; + int exp_y = searchExpState->y; + + //close the state + pbClosed[exp_x + width_ * exp_y] = 1; + + //iterate over successors + int expcost = getCost(Grid2D, exp_x, exp_y, downsample_); + for (int dir = 0; dir < SBPL_2DGRIDSEARCH_NUMOF2DDIRS; dir++) { + int newx = exp_x + dx_[dir]; + int newy = exp_y + dy_[dir]; + + //make sure it is inside the map and has no obstacle + if (!withinMap(newx, newy)) continue; + + if (pbClosed[newx + width_ * newy] == 1) continue; + + //compute the cost + int mapcost = __max(getCost(Grid2D, newx, newy, downsample_), expcost); + +#if SBPL_2DGRIDSEARCH_NUMOF2DDIRS > 8 + if(dir > 7) { + //check two more cells through which the action goes + mapcost = __max(mapcost, getCost(Grid2D, exp_x + dx0intersects_[dir], exp_y + dy0intersects_[dir], downsample_)); + mapcost = __max(mapcost, getCost(Grid2D, exp_x + dx1intersects_[dir], exp_y + dy1intersects_[dir], downsample_)); + } +#endif + + if (mapcost >= obsthresh) //obstacle encountered + continue; + int cost = (mapcost + 1) * dxy_distance_mm_[dir]; + + //get the predecessor + searchPredState = &searchStates2D_[newx][newy]; + + //update predecessor if necessary + if (searchPredState->iterationaccessed != iteration_ || searchPredState->g > cost + searchExpState->g) { + searchPredState->iterationaccessed = iteration_; + searchPredState->g = __min(INFINITECOST, cost + searchExpState->g); + key = searchPredState->g; + if (termination_condition == SBPL_2DGRIDSEARCH_TERM_CONDITION_OPTPATHFOUND) + //use h-values only if we are NOT computing all state values + key = key + SBPL_2DGRIDSEARCH_HEUR2D(searchPredState->x, searchPredState->y); + + if (searchPredState->heapindex == 0) + OPEN2D_->insertheap(searchPredState, key); + else + OPEN2D_->updateheap(searchPredState, key); + } + } //over successors + }//while + + //set lower bounds for the remaining states + if (!OPEN2D_->emptyheap()) + largestcomputedoptf_ = OPEN2D_->getminkeyheap(); + else + largestcomputedoptf_ = INFINITECOST; + + free(pbClosed); + + SBPL_PRINTF( "# of expands during 2dgridsearch=%d time=%d msecs 2Dsolcost_inmm=%d " + "largestoptfval=%d (start=%d %d goal=%d %d)\n", + numofExpands, (int)(((clock() - starttime) / (double)CLOCKS_PER_SEC) * 1000), + searchStates2D_[goalx_c][goaly_c].g, largestcomputedoptf_, startx_c, starty_c, goalx_c, goaly_c); + + return true; +} + +//experimental version +//have only one copy of a state in the list, but the order of expansions is +//BFS with possible re-expansions. Thus the order can be maintained by FIFO +//queue implemented by list (requires though the implementation of the lastelement in the list) +bool SBPL2DGridSearch::search_exp(unsigned char** Grid2D, unsigned char obsthresh, int startx_c, int starty_c, + int goalx_c, int goaly_c) +{ + SBPL_2DGridSearchState *searchExpState = NULL; + SBPL_2DGridSearchState *searchPredState = NULL; + int numofExpands = 0; + CList OPEN2DLIST; + + //get the current time + clock_t starttime = clock(); + + //closed = 0 + iteration_++; + + //init start and goal coordinates + startX_ = startx_c; + startY_ = starty_c; + goalX_ = goalx_c; + goalY_ = goaly_c; + + //check the validity of start/goal + if (!withinMap(startx_c, starty_c) || !withinMap(goalx_c, goaly_c)) { + SBPL_ERROR("ERROR: grid2Dsearch is called on invalid start (%d %d) or goal(%d %d)\n", startx_c, starty_c, + goalx_c, goaly_c); + return false; + } + + // initialize the start and goal states + searchExpState = &searchStates2D_[startX_][startY_]; + initializeSearchState2D(searchExpState); + //no initialization for the goal state - it will reset iteration_ variable + + //seed the search + searchExpState->g = 0; + searchExpState->listelem[SBPL_2DSEARCH_OPEN_LIST_ID] = NULL; + OPEN2DLIST.insertinfront(searchExpState, SBPL_2DSEARCH_OPEN_LIST_ID); + + //the main repetition of expansions + while (!OPEN2DLIST.empty()) { + //get the next state for expansion + searchExpState = (SBPL_2DGridSearchState*)OPEN2DLIST.getlast(); + OPEN2DLIST.remove(searchExpState, SBPL_2DSEARCH_OPEN_LIST_ID); + numofExpands++; + + int exp_x = searchExpState->x; + int exp_y = searchExpState->y; + + //iterate over successors + for (int dir = 0; dir < SBPL_2DGRIDSEARCH_NUMOF2DDIRS; dir++) { + int newx = exp_x + dx_[dir]; + int newy = exp_y + dy_[dir]; + + //make sure it is inside the map and has no obstacle + if (!withinMap(newx, newy)) continue; + + //compute the cost + int mapcost = __max( getCost(Grid2D, newx, newy, downsample_), getCost(Grid2D, exp_x, exp_y, downsample_)); + +#if SBPL_2DGRIDSEARCH_NUMOF2DDIRS > 8 + if(dir > 7) { + //check two more cells through which the action goes + mapcost = __max(mapcost, getCost(Grid2D, exp_x + dx0intersects_[dir], exp_y + dy0intersects_[dir], downsample_)); + mapcost = __max(mapcost, getCost(Grid2D, exp_x + dx1intersects_[dir], exp_y + dy1intersects_[dir], downsample_)); + } +#endif + + if (mapcost >= obsthresh) //obstacle encountered + continue; + int cost = (mapcost + 1) * dxy_distance_mm_[dir]; + + //get the predecessor + searchPredState = &searchStates2D_[newx][newy]; + + //clear the list + if (searchPredState->iterationaccessed != iteration_) searchPredState->listelem[SBPL_2DSEARCH_OPEN_LIST_ID] + = NULL; + + //update predecessor if necessary + if (searchPredState->iterationaccessed != iteration_ || searchPredState->g > cost + searchExpState->g) { + searchPredState->iterationaccessed = iteration_; + searchPredState->g = __min(INFINITECOST, cost + searchExpState->g); + + if (searchPredState->g >= INFINITECOST) { + throw SBPL_Exception("ERROR: infinite g"); + } + + //put it into the list if not there already + if (searchPredState->listelem[SBPL_2DSEARCH_OPEN_LIST_ID] == NULL) + OPEN2DLIST.insertinfront(searchPredState, SBPL_2DSEARCH_OPEN_LIST_ID); + //otherwise, the state remains where it is but it now has a new g-value + } + } //over successors + }//while + + //set lower bounds for the remaining states - none left since we exhausted the whole list + largestcomputedoptf_ = INFINITECOST; + + SBPL_PRINTF( "# of expands during 2dgridsearch=%d time=%d msecs 2Dsolcost_inmm=%d " + "largestoptfval=%d (start=%d %d goal=%d %d)\n", + numofExpands, (int)(((clock() - starttime) / (double)CLOCKS_PER_SEC) * 1000), + searchStates2D_[goalx_c][goaly_c].g, largestcomputedoptf_, startx_c, starty_c, goalx_c, goaly_c); + + return false; +} + +//experimental version +//OPEN list is implemented as a bucket list +bool SBPL2DGridSearch::search_withbuckets(unsigned char** Grid2D, unsigned char obsthresh, int startx_c, int starty_c, + int goalx_c, int goaly_c) +{ + SBPL_2DGridSearchState *searchExpState = NULL; + SBPL_2DGridSearchState *searchPredState = NULL; + int numofExpands = 0; + + //get the current time + clock_t starttime = clock(); + + //int max_bucketed_priority = obsthresh*10*__max(this->width_, this->height_); + int max_bucketed_priority = (int)(0.1 * obsthresh * dxy_distance_mm_[0] * __max(this->width_, this->height_)); + SBPL_PRINTF("bucket-based OPEN2D has up to %d bucketed priorities, the rest will be unsorted\n", + max_bucketed_priority); + CBucket OPEN2DBLIST(0, max_bucketed_priority); + + SBPL_PRINTF("OPEN2D allocation time=%d msecs\n", (int)(((clock() - starttime) / (double)CLOCKS_PER_SEC) * 1000)); + + //closed = 0 + iteration_++; + + //init start and goal coordinates + startX_ = startx_c; + startY_ = starty_c; + goalX_ = goalx_c; + goalY_ = goaly_c; + + //check the validity of start/goal + if (!withinMap(startx_c, starty_c) || !withinMap(goalx_c, goaly_c)) { + SBPL_ERROR("ERROR: grid2Dsearch is called on invalid start (%d %d) or goal(%d %d)\n", startx_c, starty_c, + goalx_c, goaly_c); + return false; + } + + // initialize the start and goal states + searchExpState = &searchStates2D_[startX_][startY_]; + initializeSearchState2D(searchExpState); + //no initialization for the goal state - it will reset iteration_ variable + + //seed the search + searchExpState->g = 0; + searchExpState->heapindex = -1; + OPEN2DBLIST.insert(searchExpState, searchExpState->g); + + //the main repetition of expansions + while (!OPEN2DBLIST.empty()) { + //get the next state for expansion + searchExpState = (SBPL_2DGridSearchState*)OPEN2DBLIST.popminelement(); + numofExpands++; + + int exp_x = searchExpState->x; + int exp_y = searchExpState->y; + + //iterate over successors + for (int dir = 0; dir < SBPL_2DGRIDSEARCH_NUMOF2DDIRS; dir++) { + int newx = exp_x + dx_[dir]; + int newy = exp_y + dy_[dir]; + + //make sure it is inside the map and has no obstacle + if (!withinMap(newx, newy)) continue; + + //compute the cost + int mapcost = __max( getCost(Grid2D, newx, newy, downsample_), getCost(Grid2D, exp_x, exp_y, downsample_)); + +#if SBPL_2DGRIDSEARCH_NUMOF2DDIRS > 8 + if(dir > 7) { + //check two more cells through which the action goes + mapcost = __max(mapcost, getCost(Grid2D, exp_x + dx0intersects_[dir], exp_y + dy0intersects_[dir], downsample_)); + mapcost = __max(mapcost, getCost(Grid2D, exp_x + dx1intersects_[dir], exp_y + dy1intersects_[dir], downsample_)); + } +#endif + + if (mapcost >= obsthresh) //obstacle encountered + continue; + int cost = (mapcost + 1) * dxy_distance_mm_[dir]; + + //get the predecessor + searchPredState = &searchStates2D_[newx][newy]; + + //clear the element from OPEN + if (searchPredState->iterationaccessed != iteration_) searchPredState->heapindex = -1; + + //update predecessor if necessary + if (searchPredState->iterationaccessed != iteration_ || searchPredState->g > cost + searchExpState->g) { + int oldstatepriority = searchPredState->g; + searchPredState->iterationaccessed = iteration_; + searchPredState->g = __min(INFINITECOST, cost + searchExpState->g); + + if (searchPredState->g >= INFINITECOST) { + throw SBPL_Exception("ERROR: infinite g"); + } + + //put it into the list if not there already + if (searchPredState->heapindex != -1) OPEN2DBLIST.remove(searchPredState, oldstatepriority); + OPEN2DBLIST.insert(searchPredState, searchPredState->g); + } + } //over successors + }//while + + //set lower bounds for the remaining states + if (!OPEN2DBLIST.empty()) + largestcomputedoptf_ = OPEN2DBLIST.getminpriority(); + else + largestcomputedoptf_ = INFINITECOST; + + SBPL_PRINTF( "# of expands during 2dgridsearch=%d time=%d msecs 2Dsolcost_inmm=%d " + "largestoptfval=%d bucketassortedarraymaxsize=%d (start=%d %d goal=%d %d)\n", + numofExpands, (int)(((clock() - starttime) / (double)CLOCKS_PER_SEC) * 1000), + searchStates2D_[goalx_c][goaly_c].g, largestcomputedoptf_, OPEN2DBLIST.maxassortedpriorityVsize, + startx_c, starty_c, goalx_c, goaly_c); + + return false; +} + +//experimental version +//OPEN list is implemented as a sliding bucket list +bool SBPL2DGridSearch::search_withslidingbuckets(unsigned char** Grid2D, unsigned char obsthresh, int startx_c, + int starty_c, int goalx_c, int goaly_c, + SBPL_2DGRIDSEARCH_TERM_CONDITION termination_condition) +{ + SBPL_2DGridSearchState *searchExpState = NULL; + SBPL_2DGridSearchState *searchPredState = NULL; + int numofExpands = 0; + +#if DEBUG +#ifndef ROS + const char* f2dgriddebug = "2dgriddebug.txt"; +#endif + FILE* f2Dsearch = SBPL_FOPEN(f2dgriddebug, "w"); +#endif + + //closed = 0 + iteration_++; + + //init start and goal coordinates + startX_ = startx_c; + startY_ = starty_c; + goalX_ = goalx_c; + goalY_ = goaly_c; + + //check the validity of start/goal + if (!withinMap(startx_c, starty_c) || !withinMap(goalx_c, goaly_c)) { + SBPL_ERROR("ERROR: grid2Dsearch is called on invalid start (%d %d) or goal(%d %d)\n", startx_c, starty_c, + goalx_c, goaly_c); +#if DEBUG + SBPL_FCLOSE(f2Dsearch); +#endif + return false; + } + + //reset OPEN + OPEN2DBLIST_->reset(); + + //set the term. condition + term_condition_usedlast = termination_condition; + + // initialize the start and goal states + searchExpState = &searchStates2D_[startX_][startY_]; + initializeSearchState2D(searchExpState); + initializeSearchState2D(&searchStates2D_[goalx_c][goaly_c]); + SBPL_2DGridSearchState* search2DGoalState = &searchStates2D_[goalx_c][goaly_c]; + + //seed the search + searchExpState->g = 0; + OPEN2DBLIST_->insert(searchExpState, searchExpState->g); + + //set the termination condition + float term_factor = 0.0; + switch (termination_condition) { + case SBPL_2DGRIDSEARCH_TERM_CONDITION_OPTPATHFOUND: + term_factor = 1; + break; + case SBPL_2DGRIDSEARCH_TERM_CONDITION_20PERCENTOVEROPTPATH: + term_factor = (float)(1.0 / 1.2); + break; + case SBPL_2DGRIDSEARCH_TERM_CONDITION_TWOTIMESOPTPATH: + term_factor = 0.5; + break; + case SBPL_2DGRIDSEARCH_TERM_CONDITION_THREETIMESOPTPATH: + term_factor = (float)(1.0 / 3.0); + break; + case SBPL_2DGRIDSEARCH_TERM_CONDITION_ALLCELLS: + term_factor = 0.0; + break; + default: + SBPL_ERROR("ERROR: incorrect termination factor for grid2Dsearch\n"); + term_factor = 0.0; + }; + + //get the current time + clock_t starttime = clock(); + + char *pbClosed = (char*)calloc(1, width_ * height_); + + //the main repetition of expansions + SBPL_PRINTF("2D search with sliding buckets and term_factor=%.3f\n", term_factor); + int prevg = 0; + while (!OPEN2DBLIST_->empty() && search2DGoalState->g > term_factor * OPEN2DBLIST_->getminkey()) { +#if DEBUG + SBPL_FPRINTF(f2Dsearch, "currentminelement_priority before pop=%d\n", OPEN2DBLIST_->getminkey()); +#endif + + //get the next state for expansion + searchExpState = (SBPL_2DGridSearchState*)OPEN2DBLIST_->popminelement(); + + if (searchExpState->g > OPEN2DBLIST_->getminkey()) { + SBPL_ERROR("ERROR: g=%d for state %d %d but minpriority=%d (prevg=%d)\n", searchExpState->g, + searchExpState->x, searchExpState->y, OPEN2DBLIST_->getminkey(), prevg); + } + prevg = searchExpState->g; + + int exp_x = searchExpState->x; + int exp_y = searchExpState->y; + + //close the state if it wasn't yet + if (pbClosed[exp_x + width_ * exp_y] == 1) continue; + pbClosed[exp_x + width_ * exp_y] = 1; + +#if DEBUG + SBPL_FPRINTF(f2Dsearch, "expanding state <%d %d> with g=%d " + "(currentminelement_priority=%d, currentfirstbucket_bindex=%d, currentfirstbucket_priority=%d)\n", + searchExpState->x, searchExpState->y, searchExpState->g, OPEN2DBLIST_->getminkey(), + OPEN2DBLIST_->currentfirstbucket_bindex, OPEN2DBLIST_->currentfirstbucket_priority); +#endif + + //expand + numofExpands++; + + //iterate over successors + int expcost = getCost(Grid2D, exp_x, exp_y, downsample_); + for (int dir = 0; dir < SBPL_2DGRIDSEARCH_NUMOF2DDIRS; dir++) { + int newx = exp_x + dx_[dir]; + int newy = exp_y + dy_[dir]; + + //make sure it is inside the map and has no obstacle + if (!withinMap(newx, newy)) continue; + + if (pbClosed[newx + width_ * newy] == 1) continue; + + //compute the cost + int mapcost = __max( getCost(Grid2D, newx, newy, downsample_), expcost); + +#if SBPL_2DGRIDSEARCH_NUMOF2DDIRS > 8 + if(dir > 7) { + //check two more cells through which the action goes + mapcost = __max(mapcost, getCost(Grid2D, exp_x + dx0intersects_[dir], exp_y + dy0intersects_[dir], downsample_)); + mapcost = __max(mapcost, getCost(Grid2D, exp_x + dx1intersects_[dir], exp_y + dy1intersects_[dir], downsample_)); + } +#endif + + if (mapcost >= obsthresh) //obstacle encountered + continue; + int cost = (mapcost + 1) * dxy_distance_mm_[dir]; + + //get the predecessor + searchPredState = &searchStates2D_[newx][newy]; + + //update predecessor if necessary + if (searchPredState->iterationaccessed != iteration_ || searchPredState->g > cost + searchExpState->g) { + searchPredState->iterationaccessed = iteration_; + searchPredState->g = __min(INFINITECOST, cost + searchExpState->g); + +#if DEBUG + SBPL_FPRINTF(f2Dsearch, "inserting state <%d %d> with g=%d\n", searchPredState->x, searchPredState->y, searchPredState->g); +#endif + + //put it into the list + OPEN2DBLIST_->insert(searchPredState, searchPredState->g); + } + } //over successors + }//while + + //set lower bounds for the remaining states + if (!OPEN2DBLIST_->empty()) + largestcomputedoptf_ = ((SBPL_2DGridSearchState*)OPEN2DBLIST_->getminelement())->g; + else + largestcomputedoptf_ = INFINITECOST; + + //delete[] pbClosed; + free(pbClosed); + + SBPL_PRINTF( "# of expands during 2dgridsearch=%d time=%d msecs 2Dsolcost_inmm=%d " + "largestoptfval=%d (start=%d %d goal=%d %d)\n", + numofExpands, (int)(((clock() - starttime) / (double)CLOCKS_PER_SEC) * 1000), + searchStates2D_[goalx_c][goaly_c].g, largestcomputedoptf_, startx_c, starty_c, goalx_c, goaly_c); + +#if DEBUG + SBPL_FCLOSE(f2Dsearch); +#endif + return true; +} + +//---------------------------------------------------------------------------------------------------------------------- + diff --git a/navigations/sbpl/src/utils/config.cpp b/navigations/sbpl/src/utils/config.cpp new file mode 100755 index 0000000..aa136e0 --- /dev/null +++ b/navigations/sbpl/src/utils/config.cpp @@ -0,0 +1,136 @@ +/* + * Copyright (c) 2008, Maxim Likhachev + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Carnegie Mellon University nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include +#include +#include + +#define SBPL_PRINTF_BUFFER_SIZE 1024 + +static int SBPL_DEFAULT_DEBUG_OUTPUT_LOGGER(int, const char*); +static int SBPL_DEFAULT_DEBUG_OUTPUT_FLUSH(FILE*); + +// set appropriate default logger +#if DEBUG && !defined(ROS) +static SBPL_PRINT_TEXT_FP sbpl_print_fp = SBPL_DEFAULT_DEBUG_OUTPUT_LOGGER; +static SBPL_FFLUSH_TEXT_FP sbpl_fflush_fp = SBPL_DEFAULT_DEBUG_OUTPUT_FLUSH; +#else +static SBPL_PRINT_TEXT_FP sbpl_print_fp = NULL; +static SBPL_FFLUSH_TEXT_FP sbpl_fflush_fp = NULL; +#endif + +void SET_SBPL_PRINT_TEXT_FP(SBPL_PRINT_TEXT_FP fptr) { sbpl_print_fp = fptr; } +void SET_SBPL_FFLUSH_TEXT_FP(SBPL_FFLUSH_TEXT_FP fptr) { sbpl_fflush_fp = fptr; } + +int SBPL_PRINTALL(int level, const char* format, ...) +{ + int retVal = 0; + if (sbpl_print_fp) { + // parse arguments and pass resultant string to configured logger + va_list args; + va_start(args, format); + char buffer[SBPL_PRINTF_BUFFER_SIZE] = {0}; + retVal = vsnprintf(buffer,SBPL_PRINTF_BUFFER_SIZE - 1, format, args); + if (retVal < 0) { + printf("SBPL_PRINTALL::ERROR, could not complete call to vsnprintf()"); + } + else { + if (retVal == SBPL_PRINTF_BUFFER_SIZE) { + printf("SBPL_PRINTALL::ERROR, SBPL_PRINTF_BUFFER_SIZE: %d not large enough", SBPL_PRINTF_BUFFER_SIZE); + } + if(buffer[retVal-1] == '\n') { // Remove newline + buffer[retVal-1] = '\0'; + } + sbpl_print_fp(level, &buffer[0]); + } + va_end(args); + } + return retVal; +} + +int SBPL_FPRINTALL(FILE* file, const char* format, ...) +{ + int retVal = 0; + va_list args; + va_start(args, format); + if ((file == stdout) && (sbpl_print_fp != NULL)) { + char buffer[SBPL_PRINTF_BUFFER_SIZE] = {0}; + retVal = vsnprintf(buffer,SBPL_PRINTF_BUFFER_SIZE-1,format, args); + if (retVal < 0) { + printf("SBPL_PRINTALL::ERROR, could not complete call to vsnprintf()"); + } + else { + if (retVal == SBPL_PRINTF_BUFFER_SIZE) { + printf("SBPL_PRINTALL::ERROR, SBPL_PRINTF_BUFFER_SIZE: %d not large enough", SBPL_PRINTF_BUFFER_SIZE); + } + if(buffer[retVal-1] == '\n') { // Remove newline + buffer[retVal-1] = '\0'; + } + sbpl_print_fp(SBPL_LEVEL_NONE, &buffer[0]); + } + } + else { + retVal = vfprintf(file, format, args); + } + va_end (args); + return retVal; +} + +int SBPL_FFLUSHALL(FILE* file) +{ + int retVal = 0; + if (sbpl_fflush_fp) { + retVal = sbpl_fflush_fp(file); + } + return retVal; +} + +int SBPL_DEFAULT_DEBUG_OUTPUT_LOGGER(int level, const char* msg) +{ + switch (level) + { + case SBPL_LEVEL_NONE: + case SBPL_LEVEL_DEBUG: + case SBPL_LEVEL_INFO: + case SBPL_LEVEL_WARN: + return printf("%s\n", msg); + case SBPL_LEVEL_ERROR: + case SBPL_LEVEL_FATAL: + return fprintf(stderr, "%s\n", msg); + default: + return -1; + } +} + +int SBPL_DEFAULT_DEBUG_OUTPUT_FLUSH(FILE* f) +{ + return fflush(f); +} + diff --git a/navigations/sbpl/src/utils/heap.cpp b/navigations/sbpl/src/utils/heap.cpp new file mode 100755 index 0000000..d064434 --- /dev/null +++ b/navigations/sbpl/src/utils/heap.cpp @@ -0,0 +1,514 @@ +/* + * Copyright (c) 2008, Maxim Likhachev + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Carnegie Mellon University nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include + +using namespace std; + +void heaperror(const char* ErrorString) +{ + //need to send a message from here somehow + throw SBPL_Exception(ErrorString); +} + +//returns an infinite key +CKey InfiniteKey() +{ + CKey key; + key.SetKeytoInfinity(); + return key; +} + +//---------------------------------normal (multi-priority) CHeap class-------------------------------------------------- + +//constructors and destructors +CHeap::CHeap() +{ + percolates = 0; + currentsize = 0; + allocated = HEAPSIZE_INIT; + + heap = new heapelement[allocated]; + +} + +CHeap::~CHeap() +{ + int i; + for (i = 1; i <= currentsize; ++i) + heap[i].heapstate->heapindex = 0; + + delete[] heap; +} + +void CHeap::percolatedown(int hole, heapelement tmp) +{ + int child; + + if (currentsize != 0) { + for (; 2 * hole <= currentsize; hole = child) { + child = 2 * hole; + + if (child != currentsize && heap[child + 1].key < heap[child].key) ++child; + if (heap[child].key < tmp.key) { + percolates += 1; + heap[hole] = heap[child]; + heap[hole].heapstate->heapindex = hole; + } + else + break; + } + heap[hole] = tmp; + heap[hole].heapstate->heapindex = hole; + } +} + +void CHeap::percolateup(int hole, heapelement tmp) +{ + if (currentsize != 0) { + for (; hole > 1 && tmp.key < heap[hole / 2].key; hole /= 2) { + percolates += 1; + heap[hole] = heap[hole / 2]; + heap[hole].heapstate->heapindex = hole; + } + heap[hole] = tmp; + heap[hole].heapstate->heapindex = hole; + } +} + +void CHeap::percolateupordown(int hole, heapelement tmp) +{ + if (currentsize != 0) { + if (hole > 1 && heap[hole / 2].key > tmp.key) + percolateup(hole, tmp); + else + percolatedown(hole, tmp); + } +} + +bool CHeap::emptyheap() +{ + return currentsize == 0; +} + +bool CHeap::fullheap() +{ + return currentsize == HEAPSIZE - 1; +} + +bool CHeap::inheap(AbstractSearchState *AbstractSearchState) +{ + return (AbstractSearchState->heapindex != 0); +} + +CKey CHeap::getkeyheap(AbstractSearchState *AbstractSearchState) +{ + if (AbstractSearchState->heapindex == 0) heaperror("GetKey: AbstractSearchState is not in heap"); + + return heap[AbstractSearchState->heapindex].key; +} + +void CHeap::makeemptyheap() +{ + int i; + + for (i = 1; i <= currentsize; ++i) + heap[i].heapstate->heapindex = 0; + currentsize = 0; +} + +void CHeap::makeheap() +{ + int i; + + for (i = currentsize / 2; i > 0; i--) { + percolatedown(i, heap[i]); + } +} + +void CHeap::growheap() +{ + heapelement* newheap; + int i; + + SBPL_PRINTF("growing heap size from %d ", allocated); + + allocated = 2 * allocated; + if (allocated > HEAPSIZE) allocated = HEAPSIZE; + + SBPL_PRINTF("to %d\n", allocated); + + newheap = new heapelement[allocated]; + + for (i = 0; i <= currentsize; ++i) + newheap[i] = heap[i]; + + delete[] heap; + + heap = newheap; +} + +void CHeap::sizecheck() +{ + if (fullheap()) + heaperror("insertheap: heap is full"); + else if (currentsize == allocated - 1) { + growheap(); + } +} + +void CHeap::insertheap(AbstractSearchState *AbstractSearchState, CKey key) +{ + heapelement tmp; + char strTemp[100]; + + sizecheck(); + + if (AbstractSearchState->heapindex != 0) { + sprintf(strTemp, "insertheap: AbstractSearchState is already in heap"); + heaperror(strTemp); + } + tmp.heapstate = AbstractSearchState; + tmp.key = key; + percolateup(++currentsize, tmp); +} + +void CHeap::deleteheap(AbstractSearchState *AbstractSearchState) +{ + if (AbstractSearchState->heapindex == 0) heaperror("deleteheap: AbstractSearchState is not in heap"); + percolateupordown(AbstractSearchState->heapindex, heap[currentsize--]); + AbstractSearchState->heapindex = 0; +} + +void CHeap::updateheap(AbstractSearchState *AbstractSearchState, CKey NewKey) +{ + if (AbstractSearchState->heapindex == 0) heaperror("Updateheap: AbstractSearchState is not in heap"); + if (heap[AbstractSearchState->heapindex].key != NewKey) { + heap[AbstractSearchState->heapindex].key = NewKey; + percolateupordown(AbstractSearchState->heapindex, heap[AbstractSearchState->heapindex]); + } +} + +void CHeap::insert_unsafe(AbstractSearchState* AbstractSearchState, CKey key) +{ + heapelement tmp; + char strTemp[100]; + + sizecheck(); + + if (AbstractSearchState->heapindex != 0) { + sprintf(strTemp, "insertheap: AbstractSearchState is already in heap"); + heaperror(strTemp); + } + tmp.heapstate = AbstractSearchState; + tmp.key = key; + + ++currentsize; + heap[currentsize] = tmp; + heap[currentsize].heapstate->heapindex = currentsize; +} + +void CHeap::deleteheap_unsafe(AbstractSearchState* AbstractSearchState) +{ + if (AbstractSearchState->heapindex == 0) { + heaperror("deleteheap: AbstractSearchState is not in heap"); + } + + heap[AbstractSearchState->heapindex] = heap[currentsize]; + --currentsize; + + heap[AbstractSearchState->heapindex].heapstate->heapindex = AbstractSearchState->heapindex; + AbstractSearchState->heapindex = 0; +} + +void CHeap::updateheap_unsafe(AbstractSearchState* AbstractSearchState, CKey NewKey) +{ + if (AbstractSearchState->heapindex == 0) { + heaperror("updateheap: AbstractSearchState is not in heap"); + } + if (heap[AbstractSearchState->heapindex].key != NewKey) { + heap[AbstractSearchState->heapindex].key = NewKey; + } +} + +AbstractSearchState* CHeap::getminheap() +{ + if (currentsize == 0) heaperror("GetMinheap: heap is empty"); + return heap[1].heapstate; +} + +AbstractSearchState* CHeap::getminheap(CKey& ReturnKey) +{ + if (currentsize == 0) { + heaperror("GetMinheap: heap is empty"); + ReturnKey = InfiniteKey(); + } + ReturnKey = heap[1].key; + return heap[1].heapstate; +} + +CKey CHeap::getminkeyheap() +{ + CKey ReturnKey; + if (currentsize == 0) return InfiniteKey(); + ReturnKey = heap[1].key; + return ReturnKey; +} + +AbstractSearchState* CHeap::deleteminheap() +{ + AbstractSearchState *AbstractSearchState; + + if (currentsize == 0) heaperror("DeleteMin: heap is empty"); + + AbstractSearchState = heap[1].heapstate; + AbstractSearchState->heapindex = 0; + percolatedown(1, heap[currentsize--]); + return AbstractSearchState; +} + +//---------------------------------end of normal (multi-priority) CHeap class------------------------------------------- + +//---------------------------------single-priority CIntHeap class--------------------------------------------------- + +//constructors and destructors +CIntHeap::CIntHeap() +{ + percolates = 0; + currentsize = 0; + allocated = HEAPSIZE_INIT; + + heap = new heapintelement[allocated]; +} + +CIntHeap::CIntHeap(int initial_size) +{ + percolates = 0; + currentsize = 0; + allocated = initial_size; + + heap = new heapintelement[allocated]; +} + +CIntHeap::~CIntHeap() +{ + int i; + for (i = 1; i <= currentsize; ++i) + heap[i].heapstate->heapindex = 0; + + delete[] heap; +} + +void CIntHeap::percolatedown(int hole, heapintelement tmp) +{ + int child; + + if (currentsize != 0) { + for (; 2 * hole <= currentsize; hole = child) { + child = 2 * hole; + + if (child != currentsize && heap[child + 1].key < heap[child].key) ++child; + if (heap[child].key < tmp.key) { + percolates += 1; + heap[hole] = heap[child]; + heap[hole].heapstate->heapindex = hole; + } + else + break; + } + heap[hole] = tmp; + heap[hole].heapstate->heapindex = hole; + } +} + +void CIntHeap::percolateup(int hole, heapintelement tmp) +{ + if (currentsize != 0) { + for (; hole > 1 && tmp.key < heap[hole / 2].key; hole /= 2) { + percolates += 1; + heap[hole] = heap[hole / 2]; + heap[hole].heapstate->heapindex = hole; + } + heap[hole] = tmp; + heap[hole].heapstate->heapindex = hole; + } +} + +void CIntHeap::percolateupordown(int hole, heapintelement tmp) +{ + if (currentsize != 0) { + if (hole > 1 && heap[hole / 2].key > tmp.key) + percolateup(hole, tmp); + else + percolatedown(hole, tmp); + } +} + +bool CIntHeap::emptyheap() +{ + return currentsize == 0; +} + +bool CIntHeap::fullheap() +{ + return currentsize == HEAPSIZE - 1; +} + +bool CIntHeap::inheap(AbstractSearchState *AbstractSearchState) +{ + return (AbstractSearchState->heapindex != 0); +} + +int CIntHeap::getkeyheap(AbstractSearchState *AbstractSearchState) +{ + if (AbstractSearchState->heapindex == 0) heaperror("GetKey: AbstractSearchState is not in heap"); + + return heap[AbstractSearchState->heapindex].key; +} + +void CIntHeap::makeemptyheap() +{ + int i; + + for (i = 1; i <= currentsize; ++i) + heap[i].heapstate->heapindex = 0; + currentsize = 0; +} + +void CIntHeap::makeheap() +{ + int i; + + for (i = currentsize / 2; i > 0; i--) { + percolatedown(i, heap[i]); + } +} + +void CIntHeap::growheap() +{ + heapintelement* newheap; + int i; + + SBPL_PRINTF("growing heap size from %d ", allocated); + + allocated = 2 * allocated; + if (allocated > HEAPSIZE) allocated = HEAPSIZE; + + SBPL_PRINTF("to %d\n", allocated); + + newheap = new heapintelement[allocated]; + + for (i = 0; i <= currentsize; ++i) + newheap[i] = heap[i]; + + delete[] heap; + + heap = newheap; +} + +void CIntHeap::sizecheck() +{ + if (fullheap()) + heaperror("insertheap: heap is full"); + else if (currentsize == allocated - 1) { + growheap(); + } +} + +void CIntHeap::insertheap(AbstractSearchState *AbstractSearchState, int key) +{ + heapintelement tmp; + char strTemp[100]; + + sizecheck(); + + if (AbstractSearchState->heapindex != 0) { + sprintf(strTemp, "insertheap: AbstractSearchState is already in heap"); + heaperror(strTemp); + } + tmp.heapstate = AbstractSearchState; + tmp.key = key; + percolateup(++currentsize, tmp); +} + +void CIntHeap::deleteheap(AbstractSearchState *AbstractSearchState) +{ + if (AbstractSearchState->heapindex == 0) heaperror("deleteheap: AbstractSearchState is not in heap"); + percolateupordown(AbstractSearchState->heapindex, heap[currentsize--]); + AbstractSearchState->heapindex = 0; +} + +void CIntHeap::updateheap(AbstractSearchState *AbstractSearchState, int NewKey) +{ + if (AbstractSearchState->heapindex == 0) heaperror("Updateheap: AbstractSearchState is not in heap"); + if (heap[AbstractSearchState->heapindex].key != NewKey) { + heap[AbstractSearchState->heapindex].key = NewKey; + percolateupordown(AbstractSearchState->heapindex, heap[AbstractSearchState->heapindex]); + } +} + +AbstractSearchState* CIntHeap::getminheap() +{ + if (currentsize == 0) heaperror("GetMinheap: heap is empty"); + return heap[1].heapstate; +} + +AbstractSearchState* CIntHeap::getminheap(int& ReturnKey) +{ + if (currentsize == 0) { + heaperror("GetMinheap: heap is empty"); + } + ReturnKey = heap[1].key; + return heap[1].heapstate; +} + +int CIntHeap::getminkeyheap() +{ + int ReturnKey; + if (currentsize == 0) return INFINITECOST; + ReturnKey = heap[1].key; + return ReturnKey; +} + +AbstractSearchState* CIntHeap::deleteminheap() +{ + AbstractSearchState *AbstractSearchState; + + if (currentsize == 0) heaperror("DeleteMin: heap is empty"); + + AbstractSearchState = heap[1].heapstate; + AbstractSearchState->heapindex = 0; + percolatedown(1, heap[currentsize--]); + return AbstractSearchState; +} + +//---------------------------------end of single-priority CIntHeap class------------------------------------------------ + + diff --git a/navigations/sbpl/src/utils/mdp.cpp b/navigations/sbpl/src/utils/mdp.cpp new file mode 100755 index 0000000..c6a2296 --- /dev/null +++ b/navigations/sbpl/src/utils/mdp.cpp @@ -0,0 +1,324 @@ +/* + * Copyright (c) 2008, Maxim Likhachev + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Carnegie Mellon University nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +//MDP.cpp - contains all the functions for MDP classes +#include +#include +#include + +using namespace std; + +//-------------------------MDPACTION class functions---------- + +bool CMDPACTION::Delete() +{ + SuccsID.clear(); + Costs.clear(); + SuccsProb.clear(); + return true; +} + +bool CMDPACTION::DeleteAllOutcomes() +{ + SuccsID.clear(); + Costs.clear(); + SuccsProb.clear(); + return true; +} + +bool CMDPACTION::IsValid() +{ + float Prob = 0; + for (int i = 0; i < (int)SuccsProb.size(); i++) { + Prob += SuccsProb[i]; + } + + return (fabs(Prob - 1.0) < EPS_ERROR); +} + +void CMDPACTION::AddOutcome(int OutcomeStateID, int OutcomeCost, float OutcomeProb) +{ +#if MEM_CHECK + DisableMemCheck(); +#endif + + SuccsID.push_back(OutcomeStateID); + Costs.push_back(OutcomeCost); + SuccsProb.push_back(OutcomeProb); + +#if MEM_CHECK + EnableMemCheck(); +#endif + +} + +void CMDPACTION::operator =(const CMDPACTION& rhsaction) +{ + this->ActionID = rhsaction.ActionID; +} + +int CMDPACTION::GetIndofMostLikelyOutcome() +{ + double HighestProb = 0; + int mlind = -1; + + for (int oind = 0; oind < (int)this->SuccsID.size(); oind++) { + if (this->SuccsProb[oind] >= HighestProb) { + mlind = oind; + HighestProb = this->SuccsProb[oind]; + } + } + + return mlind; +} + +int CMDPACTION::GetIndofOutcome(int OutcomeID) +{ + for (int oind = 0; oind < (int)this->SuccsID.size(); oind++) { + if (this->SuccsID[oind] == OutcomeID) { + return oind; + } + } + + return -1; +} + +//---------------------------------------------------------------------- + +//----------------------------MDPSTATE class functions--------------- + +bool CMDPSTATE::Delete() +{ + CMDPACTION* action; + + if (this->PlannerSpecificData != NULL) { + throw SBPL_Exception("ERROR deleting state: planner specific data is not deleted"); + } + + //delete predecessors array + PredsID.clear(); + + //delete actions array + while ((int)Actions.size() > 0) { + action = Actions[Actions.size() - 1]; + Actions.pop_back(); + + action->Delete(); + delete action; + } + + return true; +} + +CMDPACTION* CMDPSTATE::AddAction(int ID) +{ + CMDPACTION* action = new CMDPACTION(ID, this->StateID); + +#if MEM_CHECK + DisableMemCheck(); +#endif + + Actions.push_back(action); + +#if MEM_CHECK + EnableMemCheck(); +#endif + + return action; +} + +bool CMDPSTATE::AddPred(int stateID) +{ + //add the predecessor + if (!ContainsPred(stateID)) { +#if MEM_CHECK + DisableMemCheck(); +#endif + + PredsID.push_back(stateID); +#if MEM_CHECK + EnableMemCheck(); +#endif + } + + return true; +} + +bool CMDPSTATE::RemovePred(int stateID) +{ + for (int i = 0; i < (int)this->PredsID.size(); i++) { + if (this->PredsID.at(i) == stateID) { + this->PredsID.at(i) = this->PredsID.at(this->PredsID.size() - 1); + this->PredsID.pop_back(); + return true; + } + } + + //can happen when a state is twice a successor + //throw SBPL_Exception("ERROR in RemovePRed: no Pred is found"); + + return false; +} + +//requires the deletion of Preds elsewhere +bool CMDPSTATE::RemoveAllActions() +{ + CMDPACTION* action; + + //delete actions array + while ((int)Actions.size() > 0) { + action = Actions[Actions.size() - 1]; + Actions.pop_back(); + + action->Delete(); + delete action; + } + + return true; +} + +bool CMDPSTATE::ContainsPred(int stateID) +{ + for (int i = 0; i < (int)PredsID.size(); i++) { + if (PredsID[i] == stateID) return true; + } + return false; +} + +void CMDPSTATE::operator =(const CMDPSTATE& rhsstate) +{ + this->StateID = rhsstate.StateID; +} + +CMDPACTION* CMDPSTATE::GetAction(int actionID) +{ + for (int i = 0; i < (int)Actions.size(); i++) { + if (Actions[i]->ActionID == actionID) return Actions[i]; + } + + return NULL; +} + +//------------------------------------------------------------------------- + +//-------------MDP class functions-------------------------------- + +bool CMDP::empty() +{ + return ((int)StateArray.size() == 0); +} + +bool CMDP::full() +{ + return ((int)StateArray.size() >= MAXSTATESPACESIZE); +} + +//creates numofstates states. Their ids must be initialized elsewhere +bool CMDP::Create(int numofstates) +{ + CMDPSTATE* state; + + if (numofstates > MAXSTATESPACESIZE) { + throw SBPL_Exception("ERROR in Create: maximum MDP size is reached"); + } + + for (int i = 0; i < numofstates; i++) { + state = new CMDPSTATE(-1); + +#if MEM_CHECK + DisableMemCheck(); +#endif + StateArray.push_back(state); +#if MEM_CHECK + EnableMemCheck(); +#endif + + } + + return true; +} + +//Adds a new state The id must be initialized elsewhere +CMDPSTATE* CMDP::AddState(int StateID) +{ + CMDPSTATE* state; + + if ((int)StateArray.size() + 1 > MAXSTATESPACESIZE) { + throw SBPL_Exception("ERROR: maximum of states is reached in MDP"); + } + + state = new CMDPSTATE(StateID); + +#if MEM_CHECK + DisableMemCheck(); +#endif + StateArray.push_back(state); +#if MEM_CHECK + EnableMemCheck(); +#endif + + return state; +} + +bool CMDP::Delete() +{ + CMDPSTATE* state; + + while ((int)StateArray.size() > 0) { + state = StateArray[StateArray.size() - 1]; + StateArray.pop_back(); + + state->Delete(); + delete state; + } + + return true; +} + +void CMDP::Print(FILE* fOut) +{ + SBPL_FPRINTF(fOut, "MDP statespace size=%d\n", (unsigned int)StateArray.size()); + for (int i = 0; i < (int)StateArray.size(); i++) { + SBPL_FPRINTF(fOut, "%d: ", StateArray[i]->StateID); + for (int j = 0; j < (int)StateArray[i]->Actions.size(); j++) { + CMDPACTION* action = StateArray[i]->Actions[j]; + SBPL_FPRINTF(fOut, "[%d", action->ActionID); + for (int outind = 0; outind < (int)action->SuccsID.size(); outind++) { + SBPL_FPRINTF(fOut, " %d %d %f", action->SuccsID[outind], action->Costs[outind], + action->SuccsProb[outind]); + } + SBPL_FPRINTF(fOut, "] "); + } + SBPL_FPRINTF(fOut, "\n"); + } +} + +//-------------------------------------------------------- + +//----------------other functions------------------------- diff --git a/navigations/sbpl/src/utils/utils.cpp b/navigations/sbpl/src/utils/utils.cpp new file mode 100755 index 0000000..cfd4317 --- /dev/null +++ b/navigations/sbpl/src/utils/utils.cpp @@ -0,0 +1,929 @@ +/* + * Copyright (c) 2008, Maxim Likhachev + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Carnegie Mellon University nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include +#include + +#include +#include +#include +#include +#include + +using namespace std; + +#if MEM_CHECK == 1 +void DisableMemCheck() +{ + // Get the current state of the flag + // and store it in a temporary variable + int tmpFlag = _CrtSetDbgFlag( _CRTDBG_REPORT_FLAG ); + + // Turn On (OR) - All freed memory is re-initialized with xDD + tmpFlag |= _CRTDBG_DELAY_FREE_MEM_DF; + + // Turn Off (AND) - memory checking is disabled for future allocations + tmpFlag &= ~_CRTDBG_ALLOC_MEM_DF; + + // Set the new state for the flag + _CrtSetDbgFlag( tmpFlag ); +} + +void EnableMemCheck() +{ + // Get the current state of the flag + // and store it in a temporary variable + int tmpFlag = _CrtSetDbgFlag( _CRTDBG_REPORT_FLAG ); + + // Turn On (OR) - All freed memory is re-initialized with xDD + tmpFlag |= _CRTDBG_DELAY_FREE_MEM_DF; + + // Turn On (OR) - memory checking is enabled for future allocations + tmpFlag |= _CRTDBG_ALLOC_MEM_DF; + + // Set the new state for the flag + _CrtSetDbgFlag( tmpFlag ); +} +#endif + +void checkmdpstate(CMDPSTATE* state) +{ +#if DEBUG == 0 + throw SBPL_Exception("ERROR: checkMDPstate is too expensive for not in DEBUG mode"); +#endif + + for (int aind = 0; aind < (int)state->Actions.size(); aind++) { + for (int aind1 = 0; aind1 < (int)state->Actions.size(); aind1++) { + if (state->Actions[aind1]->ActionID == state->Actions[aind]->ActionID && aind1 != aind) { + throw SBPL_Exception("ERROR in CheckMDP: multiple actions with the same ID exist"); + } + } + for (int sind = 0; sind < (int)state->Actions[aind]->SuccsID.size(); sind++) { + for (int sind1 = 0; sind1 < (int)state->Actions[aind]->SuccsID.size(); sind1++) { + if (state->Actions[aind]->SuccsID[sind] == state->Actions[aind]->SuccsID[sind1] && sind != sind1) { + throw SBPL_Exception("ERROR in CheckMDP: multiple outcomes with the same ID exist"); + } + } + } + } +} + +void CheckMDP(CMDP* mdp) +{ + for (int i = 0; i < (int)mdp->StateArray.size(); i++) { + checkmdpstate(mdp->StateArray[i]); + } +} + +void PrintMatrix(int** matrix, int rows, int cols, FILE* fOut) +{ + for (int r = 0; r < rows; r++) { + for (int c = 0; c < cols; c++) { + SBPL_FPRINTF(fOut, "%d ", matrix[r][c]); + } + SBPL_FPRINTF(fOut, "\n"); + } +} + +//return true if there exists a path from sourcestate to targetstate and false otherwise +bool PathExists(CMDP* pMarkovChain, CMDPSTATE* sourcestate, CMDPSTATE* targetstate) +{ + CMDPSTATE* state; + vector WorkList; + int i; + bool *bProcessed = new bool[pMarkovChain->StateArray.size()]; + bool bFound = false; + + for (i = 0; i < (int)pMarkovChain->StateArray.size(); i++) + { + bProcessed[i] = false; + } + + + //insert the source state + WorkList.push_back(sourcestate); + while ((int)WorkList.size() > 0) { + //get the state and its info + state = WorkList[WorkList.size() - 1]; + WorkList.pop_back(); + + //Markov Chain should just contain a single policy + if ((int)state->Actions.size() > 1) { + throw SBPL_Exception("ERROR in PathExists: Markov Chain is a general MDP"); + } + + if (state == targetstate) { + //path found + bFound = true; + break; + } + + //otherwise just insert policy successors into the worklist unless it is a goal state + for (int sind = 0; (int)state->Actions.size() != 0 && sind < (int)state->Actions[0]->SuccsID.size(); sind++) { + //get a successor + for (i = 0; i < (int)pMarkovChain->StateArray.size(); i++) { + if (pMarkovChain->StateArray[i]->StateID == state->Actions[0]->SuccsID[sind]) break; + } + if (i == (int)pMarkovChain->StateArray.size()) { + throw SBPL_Exception("ERROR in PathExists: successor is not found"); + } + CMDPSTATE* SuccState = pMarkovChain->StateArray[i]; + + //insert at the end of list if not there or processed already + if (!bProcessed[i]) { + bProcessed[i] = true; + WorkList.push_back(SuccState); + } + } //for successors + }//while WorkList is non empty + + delete[] bProcessed; + + return bFound; +} + +int ComputeNumofStochasticActions(CMDP* pMDP) +{ + int i; + int nNumofStochActions = 0; + SBPL_PRINTF("ComputeNumofStochasticActions...\n"); + + for (i = 0; i < (int)pMDP->StateArray.size(); i++) { + for (int aind = 0; aind < (int)pMDP->StateArray[i]->Actions.size(); aind++) { + if ((int)pMDP->StateArray[i]->Actions[aind]->SuccsID.size() > 1) nNumofStochActions++; + } + } + SBPL_PRINTF("done\n"); + + return nNumofStochActions; +} + +void EvaluatePolicy(CMDP* PolicyMDP, int StartStateID, int GoalStateID, double* PolValue, bool *bFullPolicy, + double* Pcgoal, int *nMerges, bool* bCycles) +{ + int i, j, startind = -1; + double delta = INFINITECOST; + double mindelta = 0.1; + + *Pcgoal = 0; + *nMerges = 0; + + SBPL_PRINTF("Evaluating policy...\n"); + + //create and initialize values + double* vals = new double[PolicyMDP->StateArray.size()]; + double* Pcvals = new double[PolicyMDP->StateArray.size()]; + for (i = 0; i < (int)PolicyMDP->StateArray.size(); i++) { + vals[i] = 0; + Pcvals[i] = 0; + + //remember the start index + if (PolicyMDP->StateArray[i]->StateID == StartStateID) { + startind = i; + Pcvals[i] = 1; + } + } + + //initially assume full policy + *bFullPolicy = true; + bool bFirstIter = true; + while (delta > mindelta) { + delta = 0; + for (i = 0; i < (int)PolicyMDP->StateArray.size(); i++) { + //get the state + CMDPSTATE* state = PolicyMDP->StateArray[i]; + + //do the backup for values + if (state->StateID == GoalStateID) { + vals[i] = 0; + } + else if ((int)state->Actions.size() == 0) { + *bFullPolicy = false; + vals[i] = UNKNOWN_COST; + *PolValue = vals[startind]; + return; + } + else { + //normal backup + CMDPACTION* action = state->Actions[0]; + + //do backup + double Q = 0; + for (int oind = 0; oind < (int)action->SuccsID.size(); oind++) { + //get the state + for (j = 0; j < (int)PolicyMDP->StateArray.size(); j++) { + if (PolicyMDP->StateArray[j]->StateID == action->SuccsID[oind]) break; + } + if (j == (int)PolicyMDP->StateArray.size()) { + std::stringstream ss("ERROR in EvaluatePolicy: incorrect successor "); + ss << action->SuccsID[oind]; + throw SBPL_Exception(ss.str()); + } + Q += action->SuccsProb[oind] * (vals[j] + action->Costs[oind]); + } + + if (vals[i] > Q) { + throw SBPL_Exception("ERROR in EvaluatePolicy: val is decreasing"); + } + + //update delta + if (delta < Q - vals[i]) delta = Q - vals[i]; + + //set the value + vals[i] = Q; + } + + //iterate through all the predecessors and compute Pc + double Pc = 0; + //go over all predecessor states + int nMerge = 0; + for (j = 0; j < (int)PolicyMDP->StateArray.size(); j++) { + for (int oind = 0; (int)PolicyMDP->StateArray[j]->Actions.size() > 0 && + oind < (int)PolicyMDP->StateArray[j]->Actions[0]->SuccsID.size(); oind++) + { + if (PolicyMDP->StateArray[j]->Actions[0]->SuccsID[oind] == state->StateID) { + //process the predecessor + double PredPc = Pcvals[j]; + double OutProb = PolicyMDP->StateArray[j]->Actions[0]->SuccsProb[oind]; + + //accumulate into Pc + Pc = Pc + OutProb * PredPc; + nMerge++; + + //check for cycles + if (bFirstIter && !(*bCycles)) { + if (PathExists(PolicyMDP, state, PolicyMDP->StateArray[j])) *bCycles = true; + } + } + } + } + if (bFirstIter && state->StateID != GoalStateID && nMerge > 0) *nMerges += (nMerge - 1); + + //assign Pc + if (state->StateID != StartStateID) Pcvals[i] = Pc; + + if (state->StateID == GoalStateID) *Pcgoal = Pcvals[i]; + } //over states + bFirstIter = false; + } //until delta small + + *PolValue = vals[startind]; + + SBPL_PRINTF("done\n"); +} + +void get_bresenham_parameters(int p1x, int p1y, int p2x, int p2y, bresenham_param_t *params) +{ + params->UsingYIndex = 0; + + if (fabs((double)(p2y - p1y) / (double)(p2x - p1x)) > 1) (params->UsingYIndex)++; + + if (params->UsingYIndex) { + params->Y1 = p1x; + params->X1 = p1y; + params->Y2 = p2x; + params->X2 = p2y; + } + else { + params->X1 = p1x; + params->Y1 = p1y; + params->X2 = p2x; + params->Y2 = p2y; + } + + if ((p2x - p1x) * (p2y - p1y) < 0) { + params->Flipped = 1; + params->Y1 = -params->Y1; + params->Y2 = -params->Y2; + } + else + params->Flipped = 0; + + if (params->X2 > params->X1) + params->Increment = 1; + else + params->Increment = -1; + + params->DeltaX = params->X2 - params->X1; + params->DeltaY = params->Y2 - params->Y1; + + params->IncrE = 2 * params->DeltaY * params->Increment; + params->IncrNE = 2 * (params->DeltaY - params->DeltaX) * params->Increment; + params->DTerm = (2 * params->DeltaY - params->DeltaX) * params->Increment; + + params->XIndex = params->X1; + params->YIndex = params->Y1; +} + +void get_current_point(bresenham_param_t *params, int *x, int *y) +{ + if (params->UsingYIndex) { + *y = params->XIndex; + *x = params->YIndex; + if (params->Flipped) *x = -*x; + } + else { + *x = params->XIndex; + *y = params->YIndex; + if (params->Flipped) *y = -*y; + } +} + +int get_next_point(bresenham_param_t *params) +{ + if (params->XIndex == params->X2) { + return 0; + } + params->XIndex += params->Increment; + if (params->DTerm < 0 || (params->Increment < 0 && params->DTerm <= 0)) + params->DTerm += params->IncrE; + else { + params->DTerm += params->IncrNE; + params->YIndex += params->Increment; + } + return 1; +} + +//converts discretized version of angle into continuous (radians) +//maps 0->0, 1->delta, 2->2*delta, ... +double DiscTheta2Cont(int nTheta, int NUMOFANGLEVALS) +{ + double thetaBinSize = 2.0 * PI_CONST / NUMOFANGLEVALS; + return nTheta * thetaBinSize; +} + +//converts continuous (radians) version of angle into discrete +//maps 0->0, [delta/2, 3/2*delta)->1, [3/2*delta, 5/2*delta)->2,... +int ContTheta2Disc(double fTheta, int NUMOFANGLEVALS) +{ + double thetaBinSize = 2.0 * PI_CONST / NUMOFANGLEVALS; + return (int)(normalizeAngle(fTheta + thetaBinSize / 2.0) / (2.0 * PI_CONST) * (NUMOFANGLEVALS)); +} + +//input angle should be in radians +//counterclockwise is positive +//output is an angle in the range of from 0 to 2*PI +double normalizeAngle(double angle) +{ + double retangle = angle; + + //get to the range from -2PI, 2PI + if (fabs(retangle) > 2 * PI_CONST) retangle = retangle - ((int)(retangle / (2 * PI_CONST))) * 2 * PI_CONST; + + //get to the range 0, 2PI + if (retangle < 0) retangle += 2 * PI_CONST; + + if (retangle < 0 || retangle > 2 * PI_CONST) { + SBPL_ERROR("ERROR: after normalization of angle=%f we get angle=%f\n", angle, retangle); + } + + return retangle; +} + +/* + * point - the point to test + * + * Function derived from http://ozviz.wasp.uwa.edu.au/~pbourke/geometry/insidepoly/ + */ +bool IsInsideFootprint(sbpl_2Dpt_t pt, vector* bounding_polygon) +{ + int counter = 0; + int i; + double xinters; + sbpl_2Dpt_t p1; + sbpl_2Dpt_t p2; + int N = bounding_polygon->size(); + + p1 = bounding_polygon->at(0); + for (i = 1; i <= N; i++) { + p2 = bounding_polygon->at(i % N); + if (pt.y > __min(p1.y, p2.y)) { + if (pt.y <= __max(p1.y, p2.y)) { + if (pt.x <= __max(p1.x, p2.x)) { + if (p1.y != p2.y) { + xinters = (pt.y - p1.y) * (p2.x - p1.x) / (p2.y - p1.y) + p1.x; + if (p1.x == p2.x || pt.x <= xinters) counter++; + } + } + } + } + p1 = p2; + } + + if (counter % 2 == 0) + return false; + else + return true; +#if DEBUG + //SBPL_PRINTF("Returning from inside footprint: %d\n", c); +#endif + // return c; +} + +double computeMinUnsignedAngleDiff(double angle1, double angle2) +{ + //get the angles into 0-2*PI range + angle1 = normalizeAngle(angle1); + angle2 = normalizeAngle(angle2); + + double anglediff = fabs(angle1 - angle2); + + //see if we can take a shorter route + if (anglediff > PI_CONST) { + anglediff = fabs(anglediff - 2 * PI_CONST); + } + + return anglediff; +} + +//computes 8-connected distances to obstacles and non-free areas in two linear +//passes and returns them in disttoObs_incells +//and disttoNonfree_incells arrays. The distances are in terms of the number of cells but are floats. These distances +//can then be converted into the actual distances using the actual discretization values +//areas outside of the map are considered to be obstacles +void computeDistancestoNonfreeAreas(unsigned char** Grid2D, int width_x, int height_y, unsigned char obsthresh, + float** disttoObs_incells, float** disttoNonfree_incells) +{ + int x, y, nbrx, nbry; + float mindisttoObs, mindisttoNonfree; + float maxDist = (float)(__min(width_x, height_y)); + float disttoObs, disttoNonfree; + int dir; + const int NUMOF2DQUASIDIRS = 4; + + // for quasi-Euclidean distance transform + // going left-to-right, top-to-bottom + int dxdownlefttoright_[NUMOF2DQUASIDIRS]; + int dydownlefttoright_[NUMOF2DQUASIDIRS]; + int dxdownrighttoleft_[NUMOF2DQUASIDIRS]; + int dydownrighttoleft_[NUMOF2DQUASIDIRS]; + + // going right-to-left, bottom-to-top + int dxuprighttoleft_[NUMOF2DQUASIDIRS]; + int dyuprighttoleft_[NUMOF2DQUASIDIRS]; + int dxuplefttoright_[NUMOF2DQUASIDIRS]; + int dyuplefttoright_[NUMOF2DQUASIDIRS]; + + // distances to the above nbrs + float distdownlefttoright_[NUMOF2DQUASIDIRS]; + float distdownrighttoleft_[NUMOF2DQUASIDIRS]; + float distuprighttoleft_[NUMOF2DQUASIDIRS]; + float distuplefttoright_[NUMOF2DQUASIDIRS]; + + // and for distance transform: + // increasing x (outer) + // increasing y (inner) + // [2] + // [1][s] + // [0][3] + dxdownlefttoright_[0] = -1; + dydownlefttoright_[0] = -1; + dxdownlefttoright_[1] = -1; + dydownlefttoright_[1] = 0; + dxdownlefttoright_[2] = -1; + dydownlefttoright_[2] = 1; + dxdownlefttoright_[3] = 0; + dydownlefttoright_[3] = -1; + + // increasing x (outer) + // decreasing y (inner) + // [2][3] + // [1][s] + // [0] + dxdownrighttoleft_[0] = -1; + dydownrighttoleft_[0] = -1; + dxdownrighttoleft_[1] = -1; + dydownrighttoleft_[1] = 0; + dxdownrighttoleft_[2] = -1; + dydownrighttoleft_[2] = 1; + dxdownrighttoleft_[3] = 0; + dydownrighttoleft_[3] = 1; + + // decreasing x (outer) + // decreasing y (inner) + // [3][2] + // [s][1] + // [0] + dxuprighttoleft_[0] = 1; + dyuprighttoleft_[0] = -1; + dxuprighttoleft_[1] = 1; + dyuprighttoleft_[1] = 0; + dxuprighttoleft_[2] = 1; + dyuprighttoleft_[2] = 1; + dxuprighttoleft_[3] = 0; + dyuprighttoleft_[3] = 1; + + // decreasing x (outer) + // increasing y (inner) + // [2] + // [s][1] + // [3][0] + dxuplefttoright_[0] = 1; + dyuplefttoright_[0] = -1; + dxuplefttoright_[1] = 1; + dyuplefttoright_[1] = 0; + dxuplefttoright_[2] = 1; + dyuplefttoright_[2] = 1; + dxuplefttoright_[3] = 0; + dyuplefttoright_[3] = -1; + + // insert the corresponding distances + distdownlefttoright_[0] = (float)1.414; + distdownlefttoright_[1] = (float)1.0; + distdownlefttoright_[2] = (float)1.414; + distdownlefttoright_[3] = (float)1.0; + + distdownrighttoleft_[0] = (float)1.414; + distdownrighttoleft_[1] = (float)1.0; + distdownrighttoleft_[2] = (float)1.414; + distdownrighttoleft_[3] = (float)1.0; + + distuprighttoleft_[0] = (float)1.414; + distuprighttoleft_[1] = (float)1.0; + distuprighttoleft_[2] = (float)1.414; + distuprighttoleft_[3] = (float)1.0; + + distuplefttoright_[0] = (float)1.414; + distuplefttoright_[1] = (float)1.0; + distuplefttoright_[2] = (float)1.414; + distuplefttoright_[3] = (float)1.0; + + // step through the map from top to bottom, + // alternating left-to-right then right-to-left + // This order maintains the invariant that the min distance for each + // cell to all previously-visited obstacles is accurate + for (x = 0; x < width_x; x++) { + // move from left to right + if (x % 2 == 0) { + + for (y = 0; y < height_y; y++) { + + mindisttoObs = maxDist; // initialize to max distance + mindisttoNonfree = maxDist; + + // if cell is an obstacle, set disttoObs to 0 and continue + if (Grid2D[x][y] >= obsthresh) { + disttoObs_incells[x][y] = 0; + disttoNonfree_incells[x][y] = 0; + continue; + } + + if (Grid2D[x][y] > 0) { + mindisttoNonfree = 0; + } + + //iterate over predecessors + for (dir = 0; dir < NUMOF2DQUASIDIRS; dir++) { + nbrx = x + dxdownlefttoright_[dir]; + nbry = y + dydownlefttoright_[dir]; + + //make sure it is inside the map and has no obstacle + // compute min cost to an obstacle for each cell, using + // *just* the cells already computed this pass for checking distance + if (nbrx < 0 || nbrx >= width_x || nbry < 0 || nbry >= height_y) { + disttoObs = distdownlefttoright_[dir]; + disttoNonfree = disttoObs; + } + else { + disttoObs = distdownlefttoright_[dir] + disttoObs_incells[nbrx][nbry]; + disttoNonfree = distdownlefttoright_[dir] + disttoNonfree_incells[nbrx][nbry]; + } + + if (disttoObs < mindisttoObs) mindisttoObs = disttoObs; + if (disttoNonfree < mindisttoNonfree) mindisttoNonfree = disttoNonfree; + }//over preds + + disttoObs_incells[x][y] = mindisttoObs; + disttoNonfree_incells[x][y] = mindisttoNonfree; + } + + } + else { + + // move from right to left + for (y = height_y - 1; y >= 0; y--) { + + mindisttoObs = maxDist; // initialize to max distance + mindisttoNonfree = maxDist; + + // if cell is an obstacle, set disttoObs to 0 and continue + if (Grid2D[x][y] >= obsthresh) { + disttoObs_incells[x][y] = 0; + disttoNonfree_incells[x][y] = 0; + continue; + } + + if (Grid2D[x][y] > 0) { + mindisttoNonfree = 0; + } + + //iterate over predecessors + for (dir = 0; dir < NUMOF2DQUASIDIRS; dir++) { + nbrx = x + dxdownrighttoleft_[dir]; + nbry = y + dydownrighttoleft_[dir]; + + //make sure it is inside the map and has no obstacle + // compute min cost to an obstacle for each cell, using + // *just* the cells already computed this pass for checking distance + if (nbrx < 0 || nbrx >= width_x || nbry < 0 || nbry >= height_y) { + disttoObs = distdownrighttoleft_[dir]; + disttoNonfree = disttoObs; + } + else { + disttoObs = distdownrighttoleft_[dir] + disttoObs_incells[nbrx][nbry]; + disttoNonfree = distdownrighttoleft_[dir] + disttoNonfree_incells[nbrx][nbry]; + } + + if (disttoObs < mindisttoObs) mindisttoObs = disttoObs; + if (disttoNonfree < mindisttoNonfree) mindisttoNonfree = disttoNonfree; + } + + disttoObs_incells[x][y] = mindisttoObs; + disttoNonfree_incells[x][y] = mindisttoNonfree; + } + //SBPL_PRINTF("x=%d\n", x); + } + } + + // step through the map from bottom to top + for (x = width_x - 1; x >= 0; x--) { + // move from right to left + if (x % 2 == 0) { + for (y = height_y - 1; y >= 0; y--) { + // initialize to current distance + mindisttoObs = disttoObs_incells[x][y]; + mindisttoNonfree = disttoNonfree_incells[x][y]; + + //iterate over predecessors + for (dir = 0; dir < NUMOF2DQUASIDIRS; dir++) { + nbrx = x + dxuprighttoleft_[dir]; + nbry = y + dyuprighttoleft_[dir]; + + //make sure it is inside the map and has no obstacle + // compute min cost to an obstacle for each cell, using + // *just* the cells already computed this pass for checking distance + if (nbrx < 0 || nbrx >= width_x || nbry < 0 || nbry >= height_y) { + disttoObs = distuprighttoleft_[dir]; + disttoNonfree = disttoObs; + } + else { + disttoObs = distuprighttoleft_[dir] + disttoObs_incells[nbrx][nbry]; + disttoNonfree = distuprighttoleft_[dir] + disttoNonfree_incells[nbrx][nbry]; + } + + if (disttoObs < mindisttoObs) mindisttoObs = disttoObs; + if (disttoNonfree < mindisttoNonfree) mindisttoNonfree = disttoNonfree; + }//over preds + + disttoObs_incells[x][y] = mindisttoObs; + disttoNonfree_incells[x][y] = mindisttoNonfree; + }//for y + } + else { + // move from left to right + for (y = 0; y < height_y; y++) { + // initialize to current distance + mindisttoObs = disttoObs_incells[x][y]; + mindisttoNonfree = disttoNonfree_incells[x][y]; + + //iterate over predecessors + for (dir = 0; dir < NUMOF2DQUASIDIRS; dir++) { + nbrx = x + dxuplefttoright_[dir]; + nbry = y + dyuplefttoright_[dir]; + + //make sure it is inside the map and has no obstacle + // compute min cost to an obstacle for each cell, using + // *just* the cells already computed this pass for checking distance + if (nbrx < 0 || nbrx >= width_x || nbry < 0 || nbry >= height_y) { + disttoObs = distuplefttoright_[dir]; + disttoNonfree = disttoObs; + } + else { + disttoObs = distuplefttoright_[dir] + disttoObs_incells[nbrx][nbry]; + disttoNonfree = distuplefttoright_[dir] + disttoNonfree_incells[nbrx][nbry]; + } + + if (disttoObs < mindisttoObs) mindisttoObs = disttoObs; + if (disttoNonfree < mindisttoNonfree) mindisttoNonfree = disttoNonfree; + } + + disttoObs_incells[x][y] = mindisttoObs; + disttoNonfree_incells[x][y] = mindisttoNonfree; + }//over y + }//direction + }//over x +} + +void get_2d_motion_cells(vector polygon, vector poses, vector* cells, + double res) +{ + // can't find any motion cells if there are no poses + if (poses.empty()) { + return; + } + + //get first footprint set + set first_cell_set; + get_2d_footprint_cells(polygon, &first_cell_set, poses[0], res); + + //duplicate first footprint set into motion set + set cell_set = first_cell_set; + + //call get footprint on the rest of the points + for (unsigned int i = 1; i < poses.size(); i++) { + get_2d_footprint_cells(polygon, &cell_set, poses[i], res); + } + + //convert the motion set to a vector but don't include the cells in the first footprint set + cells->reserve(cell_set.size() - first_cell_set.size()); + for (set::iterator it = cell_set.begin(); it != cell_set.end(); it++) { + if (first_cell_set.find(*it) == first_cell_set.end()) { + cells->push_back(*it); + } + } +} + +//This function is inefficient and should be avoided if possible (you should +//use overloaded functions that uses a set for the cells)! +void get_2d_footprint_cells(vector polygon, vector* cells, sbpl_xy_theta_pt_t pose, + double res) +{ + set cell_set; + for (unsigned int i = 0; i < cells->size(); i++) + cell_set.insert(cells->at(i)); + get_2d_footprint_cells(polygon, &cell_set, pose, res); + cells->clear(); + cells->reserve(cell_set.size()); + //for(set::iterator it; it==cell_set.begin(); it++) + // cells->push_back(*it); + for (set::iterator it = cell_set.begin(); it != cell_set.end(); it++) { + cells->push_back(*it); + } +} + +void get_2d_footprint_cells(vector polygon, set* cells, sbpl_xy_theta_pt_t pose, double res) +{ + //special case for point robot + if (polygon.size() <= 1) { + sbpl_2Dcell_t cell; + cell.x = CONTXY2DISC(pose.x, res); + cell.y = CONTXY2DISC(pose.y, res); + + cells->insert(cell); + return; + } + + //run bressenham line algorithm around the polygon (add them to the cells set) + //while doing that find the min and max (x,y) and the average x and y + double cth = cos(pose.theta); + double sth = sin(pose.theta); + + vector > disc_polygon; + disc_polygon.reserve(polygon.size() + 1); + int minx = INFINITECOST; + int maxx = -INFINITECOST; + int miny = INFINITECOST; + int maxy = -INFINITECOST; + + //find the bounding box of the polygon + for (unsigned int i = 0; i < polygon.size(); i++) { + pair p; + // p.first = CONTXY2DISC(cth*polygon[i].x - sth*polygon[i].y + pose.x, res); + double cx = (cth * polygon[i].x - sth * polygon[i].y + pose.x); + double cy = (sth * polygon[i].x + cth * polygon[i].y + pose.y); + p.first = (int)(cx > 0 ? cx / res + 0.5 : cx / res - 0.5); //(int)(cx / res + 0.5 * sign(c); + // p.second = CONTXY2DISC(sth*polygon[i].x + cth*polygon[i].y + pose.y, res); + p.second = (int)(cy > 0 ? cy / res + 0.5 : cy / res - 0.5);//(int)(cy / res + 0.5); + disc_polygon.push_back(p); + if (p.first < minx) minx = p.first; + if (p.first > maxx) maxx = p.first; + if (p.second < miny) miny = p.second; + if (p.second > maxy) maxy = p.second; + } + disc_polygon.push_back(disc_polygon.front()); + + //make a grid big enough for the footprint + int sizex = (maxx - minx + 1) + 2; + int sizey = (maxy - miny + 1) + 2; + int** grid = new int*[sizex]; + for (int i = 0; i < sizex; i++) { + grid[i] = new int[sizey]; + for (int j = 0; j < sizey; j++) + grid[i][j] = 0; + } + + //plot line points on the grid + for (unsigned int i = 1; i < disc_polygon.size(); i++) { + int x0 = disc_polygon[i - 1].first - minx + 1; + int y0 = disc_polygon[i - 1].second - miny + 1; + int x1 = disc_polygon[i].first - minx + 1; + int y1 = disc_polygon[i].second - miny + 1; + + //bressenham (add the line cells to the set and to a vector) + bool steep = abs(y1 - y0) > abs(x1 - x0); + if (steep) { + int temp = x0; + x0 = y0; + y0 = temp; + temp = x1; + x1 = y1; + y1 = temp; + } + if (x0 > x1) { + int temp = x0; + x0 = x1; + x1 = temp; + temp = y0; + y0 = y1; + y1 = temp; + } + int deltax = x1 - x0; + int deltay = abs(y1 - y0); + int error = deltax / 2; + int ystep = (y0 < y1 ? 1 : -1); + int y = y0; + for (int x = x0; x <= x1; x++) { + if (steep) { + grid[y][x] = 1; + cells->insert(sbpl_2Dcell_t(y - 1 + minx, x - 1 + miny)); + } + else { + grid[x][y] = 1; + cells->insert(sbpl_2Dcell_t(x - 1 + minx, y - 1 + miny)); + } + int last_error = error; + error -= deltay; + if (error < 0 && x != x1) { + //make sure we can't have a diagonal line (the 8-connected bfs will leak through) + + int tempy = y; + int tempx = x; + if (last_error < -error) + tempy += ystep; + else + tempx += 1; + if (steep) { + grid[tempy][tempx] = 1; + cells->insert(sbpl_2Dcell_t(tempy - 1 + minx, tempx - 1 + miny)); + } + else { + grid[tempx][tempy] = 1; + cells->insert(sbpl_2Dcell_t(tempx - 1 + minx, tempy - 1 + miny)); + } + + y += ystep; + error += deltax; + } + } + } + + //run a 2d bfs from the average (x,y) + sbpl_bfs_2d bfs(sizex, sizey, 1); + bfs.compute_distance_from_point(grid, 0, 0); + + for (int i = 0; i < sizex; i++) + delete[] grid[i]; + delete[] grid; + + //add all cells expanded to the cells set + for (int i = 1; i < sizex - 1; i++) { + for (int j = 1; j < sizey - 1; j++) { + if (bfs.get_distance(i, j) < 0) cells->insert(sbpl_2Dcell_t(i - 1 + minx, j - 1 + miny)); + } + } +} + +void writePlannerStats(vector s, FILE* fout) +{ + fprintf(fout, "%%eps time expands cost\n"); + for (unsigned int i = 0; i < s.size(); i++) { + fprintf(fout, "%f %f %d %d\n", s[i].eps, s[i].time, s[i].expands, s[i].cost); + } +} diff --git a/navigations/sbpl/test/sbpl_main_tests.py b/navigations/sbpl/test/sbpl_main_tests.py new file mode 100755 index 0000000..98981e1 --- /dev/null +++ b/navigations/sbpl/test/sbpl_main_tests.py @@ -0,0 +1,359 @@ +#!/usr/bin/env python + +from sys import argv +from subprocess import call +from os import getcwd, chdir, pardir, devnull +from os.path import join, exists, abspath + +# This script should only be run from sbpl/test/ +sbpl_root = abspath(pardir) + +def generate_makefile(dir=''): + """ + Generates a Makefile for SBPL if one doesn't exist + + Looks in a directory relative to the current directory for a Makefile. A new one is generated + using CMake if one isn't already there. CMakeLists.txt must exist in that directory for this to + work. + + @return Whether or not a Makefile was generated + """ + # try to generate Makefile if one doesn't exist + cwd = join(getcwd(), dir) + print 'Looking for Makefile in', cwd + if not exists(join(cwd, 'Makefile')): + if not exists(join(cwd, 'CMakeLists.txt')): + return False + else: + print 'No Makefile found for SBPL, running cmake' + call(['cmake', '.']) + return exists(join(cwd, 'Makefile')) +#end generate_makefile + +def run_sbpl_test(env_type, planner_type, test_env, mprim, is_forward_search, navigating=False): + """ + @brief run the sbpl test executable + """ + sbpl_exe = join(sbpl_root, 'bin/test_sbpl') + + devnull_fd = open(devnull) # for surpressing output + + test_env_path = join(sbpl_root, test_env) + mprim_path = join(sbpl_root, mprim) + print + print 'Running', planner_type, 'planner on', env_type, 'environment' + print 'Navigating =', navigating + print 'Test environment =', test_env + print 'Motion primitives =', mprim + + forward_search_arg = '' + if is_forward_search: + forward_search_arg = 'forward' + else: + forward_search_arg = 'backward' + + args = [sbpl_exe, '--env=' + env_type, '--planner=' + planner_type, '--search-dir=' + forward_search_arg, test_env_path, mprim_path] + if mprim == '': args.pop() + if navigating: args.insert(1, '-s') + for arg in args: print arg, + print + + import time + start_time = time.time() + + sbpl_res = call(args, stdout=devnull_fd, stderr=devnull_fd) + + end_time = time.time() + print 'Planning took', end_time - start_time, 'seconds.' + + green_color = '\033[92;1m' + red_color = '\033[91;1m' + end_color = '\033[0m' + if sbpl_res == 0: + print green_color + 'Planning succeeded.' + end_color + else: + print red_color + 'Planner failed with exit code' + end_color, sbpl_res + print + + devnull_fd.close() + + return sbpl_res +#end run_sbpl_test + +if __name__ == '__main__': + print "SBPL is located at", sbpl_root + + chdir(sbpl_root) + + makefile_exists = generate_makefile() + + make_result = 0 + # build SBPL + if makefile_exists: + if 'rebuild' in argv: call(['make', 'clean']) + make_result = call(['make']) + else: + print 'No Makefile or CMakeLists.txt found. Attempting to run tests without building' + + if make_result != 0: + print 'Errors building SBPL. Checking for older version of SBPL...' + + + sbpl_exists = exists(join(sbpl_root, 'bin/test_sbpl')) and \ + exists(join(sbpl_root, 'lib/libsbpl.so')) + + if not sbpl_exists: + print 'Could not build SBPL and SBPL is not already pre-built. Aborting tests' + exit() + else: + print 'SBPL library and test executable built. Proceeding with tests.' + + num_2d_test_successes = 0 + + ### PLANNING FOR 2D ENVIRONMENTS ### + + # all planners on 2d environment (12 tests) env1 + if run_sbpl_test('2d', 'arastar', 'env_examples/nav2d/env1.cfg', 'matlab/mprim/pr2.mprim', True) == 0: + num_2d_test_successes = num_2d_test_successes + 1 + if run_sbpl_test('2d', 'adstar', 'env_examples/nav2d/env1.cfg', 'matlab/mprim/pr2.mprim', True) == 0: + num_2d_test_successes = num_2d_test_successes + 1 + if run_sbpl_test('2d', 'anastar', 'env_examples/nav2d/env1.cfg', 'matlab/mprim/pr2.mprim', True) == 0: + num_2d_test_successes = num_2d_test_successes + 1 + if run_sbpl_test('2d', 'rstar', 'env_examples/nav2d/env1.cfg', 'matlab/mprim/pr2.mprim', True) == 0: + num_2d_test_successes = num_2d_test_successes + 1 + + # all planners navigating on 2d env1 + if run_sbpl_test('2d', 'arastar', 'env_examples/nav2d/env1.cfg', 'matlab/mprim/pr2.mprim', True, True) == 0: + num_2d_test_successes = num_2d_test_successes + 1 + if run_sbpl_test('2d', 'adstar', 'env_examples/nav2d/env1.cfg', 'matlab/mprim/pr2.mprim', True, True) == 0: + num_2d_test_successes = num_2d_test_successes + 1 + if run_sbpl_test('2d', 'anastar', 'env_examples/nav2d/env1.cfg', 'matlab/mprim/pr2.mprim', True, True) == 0: + num_2d_test_successes = num_2d_test_successes + 1 + if run_sbpl_test('2d', 'rstar', 'env_examples/nav2d/env1.cfg', 'matlab/mprim/pr2.mprim', True, True) == 0: + num_2d_test_successes = num_2d_test_successes + 1 + + # all planners on 2d env2 + if run_sbpl_test('2d', 'arastar', 'env_examples/nav2d/env2.cfg', 'matlab/mprim/pr2.mprim', True) == 0: + num_2d_test_successes = num_2d_test_successes + 1 + if run_sbpl_test('2d', 'adstar', 'env_examples/nav2d/env2.cfg', 'matlab/mprim/pr2.mprim', True) == 0: + num_2d_test_successes = num_2d_test_successes + 1 + if run_sbpl_test('2d', 'anastar', 'env_examples/nav2d/env2.cfg', 'matlab/mprim/pr2.mprim', True) == 0: + num_2d_test_successes = num_2d_test_successes + 1 + if run_sbpl_test('2d', 'rstar', 'env_examples/nav2d/env2.cfg', 'matlab/mprim/pr2.mprim', True) == 0: + num_2d_test_successes = num_2d_test_successes + 1 + + # all planners navigating on 2d env2 (no thanks, I want my tests to finish) + #run_sbpl_test('2d', 'arastar', 'env_examples/nav2d/env2.cfg', 'matlab/mprim/pr2.mprim', True) + #run_sbpl_test('2d', 'adstar', 'env_examples/nav2d/env2.cfg', 'matlab/mprim/pr2.mprim', True) + #run_sbpl_test('2d', 'anastar', 'env_examples/nav2d/env2.cfg', 'matlab/mprim/pr2.mprim', True) + #run_sbpl_test('2d', 'rstar', 'env_examples/nav2d/env2.cfg', 'matlab/mprim/pr2.mprim', True) + + ### PLANNING FOR (X,Y,THETA) ENVIRONMENTS (9 tests) ### + + num_xytheta_test_successes = 0 + + # all planners on xytheta env1 + if run_sbpl_test('xytheta', 'arastar', 'env_examples/nav3d/env1.cfg', 'matlab/mprim/pr2.mprim', True) == 0: + num_xytheta_test_successes = num_xytheta_test_successes + 1 + if run_sbpl_test('xytheta', 'adstar', 'env_examples/nav3d/env1.cfg', 'matlab/mprim/pr2.mprim', True) == 0: + num_xytheta_test_successes = num_xytheta_test_successes + 1 + if run_sbpl_test('xytheta', 'anastar', 'env_examples/nav3d/env1.cfg', 'matlab/mprim/pr2.mprim', True) == 0: + num_xytheta_test_successes = num_xytheta_test_successes + 1 + + # all planners navigating on xytheta env1 + if run_sbpl_test('xytheta', 'arastar', 'env_examples/nav3d/env1.cfg', 'matlab/mprim/pr2.mprim', True, True) == 0: + num_xytheta_test_successes = num_xytheta_test_successes + 1 + if run_sbpl_test('xytheta', 'adstar', 'env_examples/nav3d/env1.cfg', 'matlab/mprim/pr2.mprim', True, True) == 0: + num_xytheta_test_successes = num_xytheta_test_successes + 1 + if run_sbpl_test('xytheta', 'anastar', 'env_examples/nav3d/env1.cfg', 'matlab/mprim/pr2.mprim', True, True) == 0: + num_xytheta_test_successes = num_xytheta_test_successes + 1 + + # all planners on xytheta env2 + if run_sbpl_test('xytheta', 'arastar', 'env_examples/nav3d/env2.cfg', 'matlab/mprim/pr2_10cm.mprim', True) == 0: + num_xytheta_test_successes = num_xytheta_test_successes + 1 + if run_sbpl_test('xytheta', 'adstar', 'env_examples/nav3d/env2.cfg', 'matlab/mprim/pr2_10cm.mprim', True) == 0: + num_xytheta_test_successes = num_xytheta_test_successes + 1 + if run_sbpl_test('xytheta', 'anastar', 'env_examples/nav3d/env2.cfg', 'matlab/mprim/pr2_10cm.mprim', True) == 0: + num_xytheta_test_successes = num_xytheta_test_successes + 1 + + # all planners navigating on xytheta env2 (no thanks, i want my tests to finish) + #run_sbpl_test('xytheta', 'arastar', 'env_examples/nav3d/env2.cfg', 'matlab/mprim/pr2_10cm.mprim', True) + #run_sbpl_test('xytheta', 'adstar', 'env_examples/nav3d/env2.cfg', 'matlab/mprim/pr2_10cm.mprim', True) + #run_sbpl_test('xytheta', 'anstar', 'env_examples/nav3d/env2.cfg', 'matlab/mprim/pr2_10cm.mprim', True) + + ### PLANNING FOR (X,Y,THETA,LEV) ENVIRONMENTS (6 tests) ### + + num_xythetamlev_test_successes = 0 + + # all planners on xythetamlev env1 + if run_sbpl_test('xythetamlev', 'arastar', 'env_examples/nav3d/env1.cfg', 'matlab/mprim/pr2.mprim', True) == 0: + num_xythetamlev_test_successes = num_xythetamlev_test_successes + 1 + if run_sbpl_test('xythetamlev', 'adstar', 'env_examples/nav3d/env1.cfg', 'matlab/mprim/pr2.mprim', True) == 0: + num_xythetamlev_test_successes = num_xythetamlev_test_successes + 1 + if run_sbpl_test('xythetamlev', 'anastar', 'env_examples/nav3d/env1.cfg', 'matlab/mprim/pr2.mprim', True) == 0: + num_xythetamlev_test_successes = num_xythetamlev_test_successes + 1 + + # all planners on xythetamlev env2 + if run_sbpl_test('xythetamlev', 'arastar', 'env_examples/nav3d/env2.cfg', 'matlab/mprim/pr2_10cm.mprim', True) == 0: + num_xythetamlev_test_successes = num_xythetamlev_test_successes + 1 + if run_sbpl_test('xythetamlev', 'adstar', 'env_examples/nav3d/env2.cfg', 'matlab/mprim/pr2_10cm.mprim', True) == 0: + num_xythetamlev_test_successes = num_xythetamlev_test_successes + 1 + if run_sbpl_test('xythetamlev', 'anastar', 'env_examples/nav3d/env2.cfg', 'matlab/mprim/pr2_10cm.mprim', True) == 0: + num_xythetamlev_test_successes = num_xythetamlev_test_successes + 1 + + ### PLANNING FOR ROBARM ENVIRONMENTS (12 tests) ### + + num_robarm_test_successes = 0 + + # all planners on robarm env1 + if run_sbpl_test('robarm', 'arastar', 'env_examples/robarm/env1_6d.cfg', '', True) == 0: + num_robarm_test_successes = num_robarm_test_successes + 1 + if run_sbpl_test('robarm', 'adstar', 'env_examples/robarm/env1_6d.cfg', '', True) == 0: + num_robarm_test_successes = num_robarm_test_successes + 1 + if run_sbpl_test('robarm', 'anastar', 'env_examples/robarm/env1_6d.cfg', '', True) == 0: + num_robarm_test_successes = num_robarm_test_successes + 1 + if run_sbpl_test('robarm', 'rstar', 'env_examples/robarm/env1_6d.cfg', '', True) == 0: + num_robarm_test_successes = num_robarm_test_successes + 1 + + # all planners on robarm env2 + if run_sbpl_test('robarm', 'arastar', 'env_examples/robarm/env2_6d.cfg', '', True) == 0: + num_robarm_test_successes = num_robarm_test_successes + 1 + if run_sbpl_test('robarm', 'adstar', 'env_examples/robarm/env2_6d.cfg', '', True) == 0: + num_robarm_test_successes = num_robarm_test_successes + 1 + if run_sbpl_test('robarm', 'anastar', 'env_examples/robarm/env2_6d.cfg', '', True) == 0: + num_robarm_test_successes = num_robarm_test_successes + 1 + if run_sbpl_test('robarm', 'rstar', 'env_examples/robarm/env2_6d.cfg', '', True) == 0: + num_robarm_test_successes = num_robarm_test_successes + 1 + + # all planners on robarm env3 + if run_sbpl_test('robarm', 'arastar', 'env_examples/robarm/env3_6d.cfg', '', True) == 0: + num_robarm_test_successes = num_robarm_test_successes + 1 + if run_sbpl_test('robarm', 'adstar', 'env_examples/robarm/env3_6d.cfg', '', True) == 0: + num_robarm_test_successes = num_robarm_test_successes + 1 + if run_sbpl_test('robarm', 'anastar', 'env_examples/robarm/env3_6d.cfg', '', True) == 0: + num_robarm_test_successes = num_robarm_test_successes + 1 + if run_sbpl_test('robarm', 'rstar', 'env_examples/robarm/env3_6d.cfg', '', True) == 0: + num_robarm_test_successes = num_robarm_test_successes + 1 + + + ###### RUN ALL TESTS WITH BACKWARD SEARCH NOW ###### + + ### PLANNING FOR 2D ENVIRONMENTS ### + + num_b_2d_test_successes = 0 + + # all planners on 2d environment (12 tests) env1 + if run_sbpl_test('2d', 'arastar', 'env_examples/nav2d/env1.cfg', 'matlab/mprim/pr2.mprim', False) == 0: + num_b_2d_test_successes = num_b_2d_test_successes + 1 + if run_sbpl_test('2d', 'adstar', 'env_examples/nav2d/env1.cfg', 'matlab/mprim/pr2.mprim', False) == 0: + num_b_2d_test_successes = num_b_2d_test_successes + 1 + if run_sbpl_test('2d', 'anastar', 'env_examples/nav2d/env1.cfg', 'matlab/mprim/pr2.mprim', False) == 0: + num_b_2d_test_successes = num_b_2d_test_successes + 1 + if run_sbpl_test('2d', 'rstar', 'env_examples/nav2d/env1.cfg', 'matlab/mprim/pr2.mprim', False) == 0: + num_b_2d_test_successes = num_b_2d_test_successes + 1 + + # all planners navigating on 2d env1 + if run_sbpl_test('2d', 'arastar', 'env_examples/nav2d/env1.cfg', 'matlab/mprim/pr2.mprim', False, True) == 0: + num_b_2d_test_successes = num_b_2d_test_successes + 1 + if run_sbpl_test('2d', 'adstar', 'env_examples/nav2d/env1.cfg', 'matlab/mprim/pr2.mprim', False, True) == 0: + num_b_2d_test_successes = num_b_2d_test_successes + 1 + if run_sbpl_test('2d', 'anastar', 'env_examples/nav2d/env1.cfg', 'matlab/mprim/pr2.mprim', False, True) == 0: + num_b_2d_test_successes = num_b_2d_test_successes + 1 + if run_sbpl_test('2d', 'rstar', 'env_examples/nav2d/env1.cfg', 'matlab/mprim/pr2.mprim', False, True) == 0: + num_b_2d_test_successes = num_b_2d_test_successes + 1 + + # all planners on 2d env2 + if run_sbpl_test('2d', 'arastar', 'env_examples/nav2d/env2.cfg', 'matlab/mprim/pr2.mprim', False) == 0: + num_b_2d_test_successes = num_b_2d_test_successes + 1 + if run_sbpl_test('2d', 'adstar', 'env_examples/nav2d/env2.cfg', 'matlab/mprim/pr2.mprim', False) == 0: + num_b_2d_test_successes = num_b_2d_test_successes + 1 + if run_sbpl_test('2d', 'anastar', 'env_examples/nav2d/env2.cfg', 'matlab/mprim/pr2.mprim', False) == 0: + num_b_2d_test_successes = num_b_2d_test_successes + 1 + if run_sbpl_test('2d', 'rstar', 'env_examples/nav2d/env2.cfg', 'matlab/mprim/pr2.mprim', False) == 0: + num_b_2d_test_successes = num_b_2d_test_successes + 1 + + # all planners navigating on 2d env2 (no thanks, I want my tests to finish) + #run_sbpl_test('2d', 'arastar', 'env_examples/nav2d/env2.cfg', 'matlab/mprim/pr2.mprim', False) + #run_sbpl_test('2d', 'adstar', 'env_examples/nav2d/env2.cfg', 'matlab/mprim/pr2.mprim', False) + #run_sbpl_test('2d', 'anastar', 'env_examples/nav2d/env2.cfg', 'matlab/mprim/pr2.mprim', False) + #run_sbpl_test('2d', 'rstar', 'env_examples/nav2d/env2.cfg', 'matlab/mprim/pr2.mprim', False) + + ### PLANNING FOR (X,Y,THETA) ENVIRONMENTS (9 tests) ### + + num_b_xytheta_test_successes = 0 + + # all planners on xytheta env1 + if run_sbpl_test('xytheta', 'arastar', 'env_examples/nav3d/env1.cfg', 'matlab/mprim/pr2.mprim', False) == 0: + num_b_xytheta_test_successes = num_b_xytheta_test_successes + 1 + if run_sbpl_test('xytheta', 'adstar', 'env_examples/nav3d/env1.cfg', 'matlab/mprim/pr2.mprim', False) == 0: + num_b_xytheta_test_successes = num_b_xytheta_test_successes + 1 + if run_sbpl_test('xytheta', 'anastar', 'env_examples/nav3d/env1.cfg', 'matlab/mprim/pr2.mprim', False) == 0: + num_b_xytheta_test_successes = num_b_xytheta_test_successes + 1 + + # all planners navigating on xytheta env1 + if run_sbpl_test('xytheta', 'arastar', 'env_examples/nav3d/env1.cfg', 'matlab/mprim/pr2.mprim', False, False) == 0: + num_b_xytheta_test_successes = num_b_xytheta_test_successes + 1 + if run_sbpl_test('xytheta', 'adstar', 'env_examples/nav3d/env1.cfg', 'matlab/mprim/pr2.mprim', False, False) == 0: + num_b_xytheta_test_successes = num_b_xytheta_test_successes + 1 + if run_sbpl_test('xytheta', 'anastar', 'env_examples/nav3d/env1.cfg', 'matlab/mprim/pr2.mprim', False, False) == 0: + num_b_xytheta_test_successes = num_b_xytheta_test_successes + 1 + + # all planners on xytheta env2 + if run_sbpl_test('xytheta', 'arastar', 'env_examples/nav3d/env2.cfg', 'matlab/mprim/pr2_10cm.mprim', False) == 0: + num_b_xytheta_test_successes = num_b_xytheta_test_successes + 1 + if run_sbpl_test('xytheta', 'adstar', 'env_examples/nav3d/env2.cfg', 'matlab/mprim/pr2_10cm.mprim', False) == 0: + num_b_xytheta_test_successes = num_b_xytheta_test_successes + 1 + if run_sbpl_test('xytheta', 'anastar', 'env_examples/nav3d/env2.cfg', 'matlab/mprim/pr2_10cm.mprim', False) == 0: + num_b_xytheta_test_successes = num_b_xytheta_test_successes + 1 + + # all planners navigating on xytheta env2 (no thanks, i want my tests to finish) + #run_sbpl_test('xytheta', 'arastar', 'env_examples/nav3d/env2.cfg', 'matlab/mprim/pr2_10cm.mprim', False) + #run_sbpl_test('xytheta', 'adstar', 'env_examples/nav3d/env2.cfg', 'matlab/mprim/pr2_10cm.mprim', False) + #run_sbpl_test('xytheta', 'anstar', 'env_examples/nav3d/env2.cfg', 'matlab/mprim/pr2_10cm.mprim', False) + + ### PLANNING FOR (X,Y,THETA,LEV) ENVIRONMENTS (6 tests) ### + + num_b_xythetamlev_test_successes = 0 + + # all planners on xythetamlev env1 + if run_sbpl_test('xythetamlev', 'arastar', 'env_examples/nav3d/env1.cfg', 'matlab/mprim/pr2.mprim', False) == 0: + num_b_xythetamlev_test_successes = num_b_xythetamlev_test_successes + 1 + if run_sbpl_test('xythetamlev', 'adstar', 'env_examples/nav3d/env1.cfg', 'matlab/mprim/pr2.mprim', False) == 0: + num_b_xythetamlev_test_successes = num_b_xythetamlev_test_successes + 1 + if run_sbpl_test('xythetamlev', 'anastar', 'env_examples/nav3d/env1.cfg', 'matlab/mprim/pr2.mprim', False) == 0: + num_b_xythetamlev_test_successes = num_b_xythetamlev_test_successes + 1 + + # all planners on xythetamlev env2 + if run_sbpl_test('xythetamlev', 'arastar', 'env_examples/nav3d/env2.cfg', 'matlab/mprim/pr2_10cm.mprim', False) == 0: + num_b_xythetamlev_test_successes = num_b_xythetamlev_test_successes + 1 + if run_sbpl_test('xythetamlev', 'adstar', 'env_examples/nav3d/env2.cfg', 'matlab/mprim/pr2_10cm.mprim', False) == 0: + num_b_xythetamlev_test_successes = num_b_xythetamlev_test_successes + 1 + if run_sbpl_test('xythetamlev', 'anastar', 'env_examples/nav3d/env2.cfg', 'matlab/mprim/pr2_10cm.mprim', False) == 0: + num_b_xythetamlev_test_successes = num_b_xythetamlev_test_successes + 1 + + print '\033[96;1m', 'Forward search results', '\033[0m' + print '\033[96;1m', '----------------------', '\033[0m' + print '\033[96;1m', num_2d_test_successes, 'out of', 12, '2d tests succeeded', '\033[0m' + print '\033[96;1m', num_xytheta_test_successes, 'out of', 9, 'xytheta tests succeeded.', '\033[0m' + print '\033[96;1m', num_xythetamlev_test_successes, 'out of', 6, 'xythetamlev tests succeeded.', '\033[0m' + print '\033[96;1m', num_robarm_test_successes, 'out of', 12, 'robarm tests succeeded.', '\033[0m' + + num_tests = 39 + print '\033[96;1m', num_2d_test_successes + num_xytheta_test_successes + num_xythetamlev_test_successes + \ + num_robarm_test_successes, 'out of', num_tests, 'tests succeeded.', '\033[0m' + + print + print '\033[96;1m', 'Backward search results', '\033[0m' + print '\033[96;1m', '-----------------------', '\033[0m' + print '\033[96;1m', num_b_2d_test_successes, 'out of', 12, '2d tests succeeded', '\033[0m' + print '\033[96;1m', num_b_xytheta_test_successes, 'out of', 9, 'xytheta tests succeeded.', '\033[0m' + print '\033[96;1m', num_b_xythetamlev_test_successes, 'out of', 6, 'xythetamlev tests succeeded.', '\033[0m' + + num_b_tests = 27 + print '\033[96;1m', num_b_2d_test_successes + num_b_xytheta_test_successes + num_b_xythetamlev_test_successes, \ + 'out of', num_b_tests, 'tests succeeded.', '\033[0m' +#end main + +# NOTES +# xytheta and xythetamlev environments do not support R* planning +# envrobarm does not support backward search diff --git a/navigations/sbpl_lattice_planner/CMakeLists.txt b/navigations/sbpl_lattice_planner/CMakeLists.txt new file mode 100755 index 0000000..47f70b4 --- /dev/null +++ b/navigations/sbpl_lattice_planner/CMakeLists.txt @@ -0,0 +1,82 @@ +cmake_minimum_required(VERSION 3.5.1) +cmake_policy(SET CMP0048 NEW) +project(sbpl_lattice_planner) + +############################################################################## +# Find dependencies +############################################################################## + +set(THIS_PACKAGE_ROS_DEPS roscpp costmap_2d nav_core pluginlib tf tf2 + geometry_msgs nav_msgs) +find_package(catkin REQUIRED COMPONENTS + ${THIS_PACKAGE_ROS_DEPS} message_generation) + +# Find SBPL +# find_package(SBPL REQUIRED) +find_package(PkgConfig REQUIRED) +pkg_check_modules(SBPL REQUIRED sbpl) +# include_directories(${SBPL_INCLUDE_DIRS}) +link_directories(${SBPL_LIBRARY_DIRS}) + +# include_directories(include ${catkin_INCLUDE_DIRS} ${SBPL_INCLUDE_DIRS}) + +############################################################################## +# Generate messages +############################################################################## + +add_message_files(FILES + SBPLLatticePlannerStats.msg + OccupancyGrid.msg) +generate_messages(DEPENDENCIES geometry_msgs nav_msgs) + +############################################################################## +# Define package +############################################################################## + +catkin_package( + INCLUDE_DIRS include + LIBRARIES ${PROJECT_NAME} + CATKIN_DEPENDS ${THIS_PACKAGE_ROS_DEPS} message_runtime + # DEPENDS SBPL +) + +############################################################################## +# Build +############################################################################## +include_directories( + include + ${catkin_INCLUDE_DIRS} + ${SBPL_INCLUDE_DIRS} +) +add_library(${PROJECT_NAME} src/sbpl_lattice_planner.cpp) +target_link_libraries(${PROJECT_NAME} ${SBPL_LIBRARIES}) +add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) +target_compile_options(${PROJECT_NAME} PUBLIC "-Wno-terminate") # suppress warning from included SBPL header + +############################################################################## +# Install +############################################################################## + +install(TARGETS ${PROJECT_NAME} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) + +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} + FILES_MATCHING PATTERN "*.h" + PATTERN ".svn" EXCLUDE +) + +install(FILES bgp_plugin.xml + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) + +install(DIRECTORY + launch + matlab + rviz + worlds + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) diff --git a/navigations/sbpl_lattice_planner/bgp_plugin.xml b/navigations/sbpl_lattice_planner/bgp_plugin.xml new file mode 100755 index 0000000..3aee5e8 --- /dev/null +++ b/navigations/sbpl_lattice_planner/bgp_plugin.xml @@ -0,0 +1,8 @@ + + + + An implementation of search-based planning using anytime A* and a lattice graph. + + + + diff --git a/navigations/sbpl_lattice_planner/include/sbpl_lattice_planner/sbpl_lattice_planner.h b/navigations/sbpl_lattice_planner/include/sbpl_lattice_planner/sbpl_lattice_planner.h new file mode 100755 index 0000000..0f8260f --- /dev/null +++ b/navigations/sbpl_lattice_planner/include/sbpl_lattice_planner/sbpl_lattice_planner.h @@ -0,0 +1,118 @@ +#ifndef SBPL_LATTICE_PLANNER_H +#define SBPL_LATTICE_PLANNER_H + +#include +#include + +using namespace std; + +// ROS +#include +#include +#include + +// Costmap used for the map representation +#include + +// sbpl headers +#include + +// global representation +#include + +namespace sbpl_lattice_planner{ + +class SBPLLatticePlanner : public nav_core::BaseGlobalPlanner{ +public: + + /** + * @brief Default constructor for the NavFnROS object + */ + SBPLLatticePlanner(); + + + /** + * @brief Constructor for the SBPLLatticePlanner object + * @param name The name of this planner + * @param costmap_ros A pointer to the ROS wrapper of the costmap to use + */ + SBPLLatticePlanner(std::string name, costmap_2d::Costmap2DROS* costmap_ros); + + + /** + * @brief Initialization function for the SBPLLatticePlanner object + * @param name The name of this planner + * @param costmap_ros A pointer to the ROS wrapper of the costmap to use + */ + virtual void initialize(std::string name, + costmap_2d::Costmap2DROS* costmap_ros); + + /** + * @brief Given a goal pose in the world, compute a plan + * @param start The start pose + * @param goal The goal pose + * @param plan The plan... filled by the planner + * @return True if a valid plan was found, false otherwise + */ + virtual bool makePlan(const geometry_msgs::PoseStamped& start, + const geometry_msgs::PoseStamped& goal, + std::vector& plan); + + virtual ~SBPLLatticePlanner(){}; + +private: + unsigned char costMapCostToSBPLCost(unsigned char newcost); + void publishStats(int solution_cost, int solution_size, + const geometry_msgs::PoseStamped& start, + const geometry_msgs::PoseStamped& goal); + + unsigned char computeCircumscribedCost(); + + static void transformFootprintToEdges(const geometry_msgs::Pose& robot_pose, + const std::vector& footprint, + std::vector& out_footprint); + + void getFootprintList(const std::vector& sbpl_path, const std::string& path_frame_id, + visualization_msgs::Marker& ma); + + bool initialized_; + + SBPLPlanner* planner_; + EnvironmentNAVXYTHETALAT* env_; + + std::string planner_type_; /**< sbpl method to use for planning. choices are ARAPlanner and ADPlanner */ + + double allocated_time_; /**< amount of time allowed for search */ + double initial_epsilon_; /**< initial epsilon for beginning the anytime search */ + + std::string environment_type_; /** what type of environment in which to plan. choices are 2D and XYThetaLattice. */ + std::string cost_map_topic_; /** what topic is being used for the costmap topic */ + + bool forward_search_; /** whether to use forward or backward search */ + std::string primitive_filename_; /** where to find the motion primitives for the current robot */ + int force_scratch_limit_; /** the number of cells that have to be changed in the costmap to force the planner to plan from scratch even if its an incremental planner */ + + unsigned char lethal_obstacle_; + unsigned char inscribed_inflated_obstacle_; + unsigned char circumscribed_cost_; + unsigned char sbpl_cost_multiplier_; + + bool publish_footprint_path_; + int visualizer_skip_poses_; + + bool allow_unknown_; + + std::string name_; + costmap_2d::Costmap2DROS* costmap_ros_; /**< manages the cost map for us */ + std::vector footprint_; + unsigned int current_env_width_; + unsigned int current_env_height_; + + ros::Publisher plan_pub_; + ros::Publisher stats_publisher_; + ros::Publisher sbpl_plan_footprint_pub_; +}; +}; + +#endif + diff --git a/navigations/sbpl_lattice_planner/launch/move_base/base_local_planner_params_close.yaml b/navigations/sbpl_lattice_planner/launch/move_base/base_local_planner_params_close.yaml new file mode 100755 index 0000000..8f7f62d --- /dev/null +++ b/navigations/sbpl_lattice_planner/launch/move_base/base_local_planner_params_close.yaml @@ -0,0 +1,28 @@ +TrajectoryPlannerROS: + #Independent settings for the local costmap + transform_tolerance: 0.3 + sim_time: 1.7 + sim_granularity: 0.025 + dwa: true + vx_samples: 3 + vtheta_samples: 20 + max_vel_x: 2.0 + min_vel_x: 0.1 + max_rotational_vel: 1.0 + min_in_place_vel_theta: 0.4 + xy_goal_tolerance: 0.1 + yaw_goal_tolerance: 0.1 + goal_distance_bias: 0.2 + path_distance_bias: .9 + occdist_scale: 0.01 + heading_lookahead: 0.325 + oscillation_reset_dist: 0.05 + holonomic_robot: true + acc_lim_theta: 3.2 + acc_lim_x: 2.5 + acc_lim_y: 2.5 + heading_scoring: false + heading_scoring_timestep: 0.8 + holonomic_robot: true + simple_attractor: false + meter_scoring: true diff --git a/navigations/sbpl_lattice_planner/launch/move_base/costmap_common_params.yaml b/navigations/sbpl_lattice_planner/launch/move_base/costmap_common_params.yaml new file mode 100755 index 0000000..ea87c54 --- /dev/null +++ b/navigations/sbpl_lattice_planner/launch/move_base/costmap_common_params.yaml @@ -0,0 +1,21 @@ +#START VOXEL STUFF +map_type: voxel +origin_z: 0.0 +z_resolution: 0.2 +z_voxels: 10 +unknown_threshold: 9 +mark_threshold: 0 +#END VOXEL STUFF +transform_tolerance: 0.3 +obstacle_range: 2.5 +max_obstacle_height: 2.0 +raytrace_range: 3.0 +footprint: [[-0.325, -0.325], [-0.325, 0.325], [0.325, 0.325], [0.46, 0.0], [0.325, -0.325]] +#robot_radius: 0.46 +footprint_padding: 0.01 +inflation_radius: 0.55 +cost_scaling_factor: 10.0 +lethal_cost_threshold: 100 +observation_sources: base_scan +base_scan: {data_type: LaserScan, expected_update_rate: 0.4, + observation_persistence: 0.0, marking: true, clearing: true, max_obstacle_height: 0.4, min_obstacle_height: 0.08} diff --git a/navigations/sbpl_lattice_planner/launch/move_base/global_costmap_params.yaml b/navigations/sbpl_lattice_planner/launch/move_base/global_costmap_params.yaml new file mode 100755 index 0000000..def99ec --- /dev/null +++ b/navigations/sbpl_lattice_planner/launch/move_base/global_costmap_params.yaml @@ -0,0 +1,12 @@ +#Independent settings for the planner's costmap +global_costmap: + global_frame: map + robot_base_frame: base_link + update_frequency: 5.0 + publish_frequency: 0.0 + static_map: true + rolling_window: false + static_layer: + track_unknown_space: true + obstacle_layer: + track_unknown_space: true diff --git a/navigations/sbpl_lattice_planner/launch/move_base/local_costmap_params_close.yaml b/navigations/sbpl_lattice_planner/launch/move_base/local_costmap_params_close.yaml new file mode 100755 index 0000000..8abecb1 --- /dev/null +++ b/navigations/sbpl_lattice_planner/launch/move_base/local_costmap_params_close.yaml @@ -0,0 +1,13 @@ +local_costmap: + publish_voxel_map: true + global_frame: map + robot_base_frame: base_link + update_frequency: 5.0 + publish_frequency: 2.0 + static_map: false + rolling_window: true + width: 2.0 + height: 2.0 + resolution: 0.025 + origin_x: 0.0 + origin_y: 0.0 diff --git a/navigations/sbpl_lattice_planner/launch/move_base/move_base.xml b/navigations/sbpl_lattice_planner/launch/move_base/move_base.xml new file mode 100755 index 0000000..0dc9752 --- /dev/null +++ b/navigations/sbpl_lattice_planner/launch/move_base/move_base.xml @@ -0,0 +1,44 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/navigations/sbpl_lattice_planner/launch/move_base/nav_view_sbpl.xml b/navigations/sbpl_lattice_planner/launch/move_base/nav_view_sbpl.xml new file mode 100755 index 0000000..c9c4952 --- /dev/null +++ b/navigations/sbpl_lattice_planner/launch/move_base/nav_view_sbpl.xml @@ -0,0 +1,10 @@ + + + + + + + + + + diff --git a/navigations/sbpl_lattice_planner/launch/move_base/sbpl_global_params.yaml b/navigations/sbpl_lattice_planner/launch/move_base/sbpl_global_params.yaml new file mode 100755 index 0000000..b9e348f --- /dev/null +++ b/navigations/sbpl_lattice_planner/launch/move_base/sbpl_global_params.yaml @@ -0,0 +1,18 @@ +# SBPLLatticePlanner: +# environment_type: XYThetaLattice +# planner_type: ARAPlanner +# allocated_time: 5.0 +# initial_epsilon: 3.0 +# forward_search: false +# allow_unknown: true + +base_global_planner: SBPLLatticePlanner +SBPLLatticePlanner: + environment_type: XYThetaLattice + planner_type: ARAPlanner + allocated_time: 10.0 + initial_epsilon: 15.0 + forward_search: false + nominalvel_mpersecs: 0.8 + timetoturn45degsinplace_secs: 1.31 # = 0.6 rad/s + allow_unknown: true \ No newline at end of file diff --git a/navigations/sbpl_lattice_planner/launch/move_base_sbpl_fake_localization_2.5cm.launch b/navigations/sbpl_lattice_planner/launch/move_base_sbpl_fake_localization_2.5cm.launch new file mode 100755 index 0000000..a95f539 --- /dev/null +++ b/navigations/sbpl_lattice_planner/launch/move_base_sbpl_fake_localization_2.5cm.launch @@ -0,0 +1,30 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/navigations/sbpl_lattice_planner/matlab/mprim/genmprim_unicycle_highcost_5cm.m b/navigations/sbpl_lattice_planner/matlab/mprim/genmprim_unicycle_highcost_5cm.m new file mode 100755 index 0000000..2810593 --- /dev/null +++ b/navigations/sbpl_lattice_planner/matlab/mprim/genmprim_unicycle_highcost_5cm.m @@ -0,0 +1,280 @@ +% /* +% * Copyright (c) 2008, Maxim Likhachev +% * All rights reserved. +% * +% * Redistribution and use in source and binary forms, with or without +% * modification, are permitted provided that the following conditions are met: +% * +% * * Redistributions of source code must retain the above copyright +% * notice, this list of conditions and the following disclaimer. +% * * Redistributions in binary form must reproduce the above copyright +% * notice, this list of conditions and the following disclaimer in the +% * documentation and/or other materials provided with the distribution. +% * * Neither the name of the Carnegie Mellon University nor the names of its +% * contributors may be used to endorse or promote products derived from +% * this software without specific prior written permission. +% * +% * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +% * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +% * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +% * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +% * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +% * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +% * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +% * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +% * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +% * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +% * POSSIBILITY OF SUCH DAMAGE. +% */ + +function[] = genmprim_unicycle_highcost_5cm(outfilename) + +% +%generates motion primitives and saves them into file +% +%written by Maxim Likhachev +%--------------------------------------------------- +% + +%defines + +UNICYCLE_MPRIM_16DEGS = 1; + + +if UNICYCLE_MPRIM_16DEGS == 1 + resolution = 0.05; + numberofangles = 16; %preferably a power of 2, definitely multiple of 8 + numberofprimsperangle = 7; + + %multipliers (multiplier is used as costmult*cost) + forwardcostmult = 1; + backwardcostmult = 40; + forwardandturncostmult = 2; + sidestepcostmult = 10; + turninplacecostmult = 20; + + %note, what is shown x,y,theta changes (not absolute numbers) + + %0 degreees + basemprimendpts0_c = zeros(numberofprimsperangle, 4); %x,y,theta,costmult + %x aligned with the heading of the robot, angles are positive + %counterclockwise + %0 theta change + basemprimendpts0_c(1,:) = [1 0 0 forwardcostmult]; + basemprimendpts0_c(2,:) = [8 0 0 forwardcostmult]; + basemprimendpts0_c(3,:) = [-1 0 0 backwardcostmult]; + %1/16 theta change + basemprimendpts0_c(4,:) = [8 1 1 forwardandturncostmult]; + basemprimendpts0_c(5,:) = [8 -1 -1 forwardandturncostmult]; + %turn in place + basemprimendpts0_c(6,:) = [0 0 1 turninplacecostmult]; + basemprimendpts0_c(7,:) = [0 0 -1 turninplacecostmult]; + + %45 degrees + basemprimendpts45_c = zeros(numberofprimsperangle, 4); %x,y,theta,costmult (multiplier is used as costmult*cost) + %x aligned with the heading of the robot, angles are positive + %counterclockwise + %0 theta change + basemprimendpts45_c(1,:) = [1 1 0 forwardcostmult]; + basemprimendpts45_c(2,:) = [6 6 0 forwardcostmult]; + basemprimendpts45_c(3,:) = [-1 -1 0 backwardcostmult]; + %1/16 theta change + basemprimendpts45_c(4,:) = [5 7 1 forwardandturncostmult]; + basemprimendpts45_c(5,:) = [7 5 -1 forwardandturncostmult]; + %turn in place + basemprimendpts45_c(6,:) = [0 0 1 turninplacecostmult]; + basemprimendpts45_c(7,:) = [0 0 -1 turninplacecostmult]; + + %22.5 degrees + basemprimendpts22p5_c = zeros(numberofprimsperangle, 4); %x,y,theta,costmult (multiplier is used as costmult*cost) + %x aligned with the heading of the robot, angles are positive + %counterclockwise + %0 theta change + basemprimendpts22p5_c(1,:) = [2 1 0 forwardcostmult]; + basemprimendpts22p5_c(2,:) = [6 3 0 forwardcostmult]; + basemprimendpts22p5_c(3,:) = [-2 -1 0 backwardcostmult]; + %1/16 theta change + basemprimendpts22p5_c(4,:) = [5 4 1 forwardandturncostmult]; + basemprimendpts22p5_c(5,:) = [7 2 -1 forwardandturncostmult]; + %turn in place + basemprimendpts22p5_c(6,:) = [0 0 1 turninplacecostmult]; + basemprimendpts22p5_c(7,:) = [0 0 -1 turninplacecostmult]; + +else + fprintf(1, 'ERROR: undefined mprims type\n'); + return; +end; + + +fout = fopen(outfilename, 'w'); + + +%write the header +fprintf(fout, 'resolution_m: %f\n', resolution); +fprintf(fout, 'numberofangles: %d\n', numberofangles); +fprintf(fout, 'totalnumberofprimitives: %d\n', numberofprimsperangle*numberofangles); + +%iterate over angles +for angleind = 1:numberofangles + + figure(1); + hold off; + + text(0, 0, int2str(angleind)); + + %iterate over primitives + for primind = 1:numberofprimsperangle + fprintf(fout, 'primID: %d\n', primind-1); + fprintf(fout, 'startangle_c: %d\n', angleind-1); + + %current angle + currentangle = (angleind-1)*2*pi/numberofangles; + currentangle_36000int = round((angleind-1)*36000/numberofangles); + + %compute which template to use + if (rem(currentangle_36000int, 9000) == 0) + basemprimendpts_c = basemprimendpts0_c(primind,:); + angle = currentangle; + elseif (rem(currentangle_36000int, 4500) == 0) + basemprimendpts_c = basemprimendpts45_c(primind,:); + angle = currentangle - 45*pi/180; + elseif (rem(currentangle_36000int-7875, 9000) == 0) + basemprimendpts_c = basemprimendpts33p75_c(primind,:); + basemprimendpts_c(1) = basemprimendpts33p75_c(primind, 2); %reverse x and y + basemprimendpts_c(2) = basemprimendpts33p75_c(primind, 1); + basemprimendpts_c(3) = -basemprimendpts33p75_c(primind, 3); %reverse the angle as well + angle = currentangle - 78.75*pi/180; + fprintf(1, '78p75\n'); + elseif (rem(currentangle_36000int-6750, 9000) == 0) + basemprimendpts_c = basemprimendpts22p5_c(primind,:); + basemprimendpts_c(1) = basemprimendpts22p5_c(primind, 2); %reverse x and y + basemprimendpts_c(2) = basemprimendpts22p5_c(primind, 1); + basemprimendpts_c(3) = -basemprimendpts22p5_c(primind, 3); %reverse the angle as well + %fprintf(1, '%d %d %d onto %d %d %d\n', basemprimendpts22p5_c(1), basemprimendpts22p5_c(2), basemprimendpts22p5_c(3), ... + % basemprimendpts_c(1), basemprimendpts_c(2), basemprimendpts_c(3)); + angle = currentangle - 67.5*pi/180; + fprintf(1, '67p5\n'); + elseif (rem(currentangle_36000int-5625, 9000) == 0) + basemprimendpts_c = basemprimendpts11p25_c(primind,:); + basemprimendpts_c(1) = basemprimendpts11p25_c(primind, 2); %reverse x and y + basemprimendpts_c(2) = basemprimendpts11p25_c(primind, 1); + basemprimendpts_c(3) = -basemprimendpts11p25_c(primind, 3); %reverse the angle as well + angle = currentangle - 56.25*pi/180; + fprintf(1, '56p25\n'); + elseif (rem(currentangle_36000int-3375, 9000) == 0) + basemprimendpts_c = basemprimendpts33p75_c(primind,:); + angle = currentangle - 33.75*pi/180; + fprintf(1, '33p75\n'); + elseif (rem(currentangle_36000int-2250, 9000) == 0) + basemprimendpts_c = basemprimendpts22p5_c(primind,:); + angle = currentangle - 22.5*pi/180; + fprintf(1, '22p5\n'); + elseif (rem(currentangle_36000int-1125, 9000) == 0) + basemprimendpts_c = basemprimendpts11p25_c(primind,:); + angle = currentangle - 11.25*pi/180; + fprintf(1, '11p25\n'); + else + fprintf(1, 'ERROR: invalid angular resolution. angle = %d\n', currentangle_36000int); + return; + end; + + %now figure out what action will be + baseendpose_c = basemprimendpts_c(1:3); + additionalactioncostmult = basemprimendpts_c(4); + endx_c = round(baseendpose_c(1)*cos(angle) - baseendpose_c(2)*sin(angle)); + endy_c = round(baseendpose_c(1)*sin(angle) + baseendpose_c(2)*cos(angle)); + endtheta_c = rem(angleind - 1 + baseendpose_c(3), numberofangles); + endpose_c = [endx_c endy_c endtheta_c]; + + fprintf(1, 'rotation angle=%f\n', angle*180/pi); + + if baseendpose_c(2) == 0 & baseendpose_c(3) == 0 + %fprintf(1, 'endpose=%d %d %d\n', endpose_c(1), endpose_c(2), endpose_c(3)); + end; + + %generate intermediate poses (remember they are w.r.t 0,0 (and not + %centers of the cells) + numofsamples = 10; + intermcells_m = zeros(numofsamples,3); + if UNICYCLE_MPRIM_16DEGS == 1 + startpt = [0 0 currentangle]; + endpt = [endpose_c(1)*resolution endpose_c(2)*resolution ... + rem(angleind - 1 + baseendpose_c(3), numberofangles)*2*pi/numberofangles]; + intermcells_m = zeros(numofsamples,3); + if ((endx_c == 0 & endy_c == 0) | baseendpose_c(3) == 0) %turn in place or move forward + for iind = 1:numofsamples + intermcells_m(iind,:) = [startpt(1) + (endpt(1) - startpt(1))*(iind-1)/(numofsamples-1) ... + startpt(2) + (endpt(2) - startpt(2))*(iind-1)/(numofsamples-1) ... + 0]; + rotation_angle = (baseendpose_c(3) ) * (2*pi/numberofangles); + intermcells_m(iind,3) = rem(startpt(3) + (rotation_angle)*(iind-1)/(numofsamples-1), 2*pi); + + end; + else %unicycle-based move forward or backward + R = [cos(startpt(3)) sin(endpt(3)) - sin(startpt(3)); + sin(startpt(3)) -(cos(endpt(3)) - cos(startpt(3)))]; + S = pinv(R)*[endpt(1) - startpt(1); endpt(2) - startpt(2)]; + l = S(1); + tvoverrv = S(2); + rv = (baseendpose_c(3)*2*pi/numberofangles + l/tvoverrv); + tv = tvoverrv*rv; + + if l < 0 + fprintf(1, 'WARNING: l = %d < 0 -> bad action start/end points\n', l); + l = 0; + end; + %compute rv + %rv = baseendpose_c(3)*2*pi/numberofangles; + %compute tv + %tvx = (endpt(1) - startpt(1))*rv/(sin(endpt(3)) - sin(startpt(3))) + %tvy = -(endpt(2) - startpt(2))*rv/(cos(endpt(3)) - cos(startpt(3))) + %tv = (tvx + tvy)/2.0; + %generate samples + for iind = 1:numofsamples + dt = (iind-1)/(numofsamples-1); + + %dtheta = rv*dt + startpt(3); + %intermcells_m(iind,:) = [startpt(1) + tv/rv*(sin(dtheta) - sin(startpt(3))) ... + % startpt(2) - tv/rv*(cos(dtheta) - cos(startpt(3))) ... + % dtheta]; + + if(dt*tv < l) + intermcells_m(iind,:) = [startpt(1) + dt*tv*cos(startpt(3)) ... + startpt(2) + dt*tv*sin(startpt(3)) ... + startpt(3)]; + else + dtheta = rv*(dt - l/tv) + startpt(3); + intermcells_m(iind,:) = [startpt(1) + l*cos(startpt(3)) + tvoverrv*(sin(dtheta) - sin(startpt(3))) ... + startpt(2) + l*sin(startpt(3)) - tvoverrv*(cos(dtheta) - cos(startpt(3))) ... + dtheta]; + end; + end; + %correct + errorxy = [endpt(1) - intermcells_m(numofsamples,1) ... + endpt(2) - intermcells_m(numofsamples,2)]; + fprintf(1, 'l=%f errx=%f erry=%f\n', l, errorxy(1), errorxy(2)); + interpfactor = [0:1/(numofsamples-1):1]; + intermcells_m(:,1) = intermcells_m(:,1) + errorxy(1)*interpfactor'; + intermcells_m(:,2) = intermcells_m(:,2) + errorxy(2)*interpfactor'; + end; + end; + + %write out + fprintf(fout, 'endpose_c: %d %d %d\n', endpose_c(1), endpose_c(2), endpose_c(3)); + fprintf(fout, 'additionalactioncostmult: %d\n', additionalactioncostmult); + fprintf(fout, 'intermediateposes: %d\n', size(intermcells_m,1)); + for interind = 1:size(intermcells_m, 1) + fprintf(fout, '%.4f %.4f %.4f\n', intermcells_m(interind,1), intermcells_m(interind,2), intermcells_m(interind,3)); + end; + + plot(intermcells_m(:,1), intermcells_m(:,2)); + axis([-0.3 0.3 -0.3 0.3]); + text(intermcells_m(numofsamples,1), intermcells_m(numofsamples,2), int2str(endpose_c(3))); + hold on; + + end; + grid; + pause; +end; + +fclose('all'); diff --git a/navigations/sbpl_lattice_planner/matlab/mprim/genmprim_unicycle_highcost_5cm.py b/navigations/sbpl_lattice_planner/matlab/mprim/genmprim_unicycle_highcost_5cm.py new file mode 100755 index 0000000..c8801c0 --- /dev/null +++ b/navigations/sbpl_lattice_planner/matlab/mprim/genmprim_unicycle_highcost_5cm.py @@ -0,0 +1,416 @@ +#!/usr/bin/env python3 +# +# Copyright (c) 2016, David Conner (Christopher Newport University) +# Based on genmprim_unicycle.m +# Copyright (c) 2008, Maxim Likhachev +# All rights reserved. +# converted by libermate utility (https://github.com/awesomebytes/libermate) +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# * Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in the +# documentation and/or other materials provided with the distribution. +# * Neither the name of the Carnegie Mellon University nor the names of its +# contributors may be used to endorse or promote products derived from +# this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. + +import numpy as np +import rospkg + +# if available import pylab (from matlibplot) +matplotlib_found = False +try: + import matplotlib.pylab as plt + + matplotlib_found = True +except ImportError: + pass + + +def matrix_size(mat, elem=None): + if not elem: + return mat.shape + else: + return mat.shape[int(elem) - 1] + + +def genmprim_unicycle(outfilename, visualize=False, separate_plots=False): + visualize = matplotlib_found and visualize # Plot the primitives + + # Local Variables: basemprimendpts22p5_c, endtheta_c, endx_c, + # baseendpose_c, additionalactioncostmult, fout, numofsamples, + # basemprimendpts45_c, primind, basemprimendpts0_c, rv, angle, outfilename, + # numberofangles, startpt, UNICYCLE_MPRIM_16DEGS, sidestepcostmult, + # rotation_angle, basemprimendpts_c, forwardandturncostmult, + # forwardcostmult, turninplacecostmult, endpose_c, backwardcostmult, + # interpfactor, S, R, tvoverrv, dtheta, intermcells_m, tv, dt, + # currentangle, numberofprimsperangle, resolution, currentangle_36000int, + # l, iind, errorxy, interind, endy_c, angleind, endpt + # Function calls: plot, cos, pi, grid, figure, genmprim_unicycle, text, + # int2str, pause, axis, sin, pinv, fprintf, fclose, rem, zeros, fopen, + # round, size + # % + # %generates motion primitives and saves them into file + # % + # %written by Maxim Likhachev + # %--------------------------------------------------- + # % + # %defines + UNICYCLE_MPRIM_16DEGS = 1.0 + if UNICYCLE_MPRIM_16DEGS == 1.0: + resolution = 0.05 + numberofangles = 16 + # %preferably a power of 2, definitely multiple of 8 + numberofprimsperangle = 7 + # %multipliers (multiplier is used as costmult*cost) + forwardcostmult = 1.0 + backwardcostmult = 40.0 + forwardandturncostmult = 2.0 + # sidestepcostmult = 10.0 + turninplacecostmult = 20.0 + # %note, what is shown x,y,theta changes (not absolute numbers) + # %0 degreees + basemprimendpts0_c = np.zeros((numberofprimsperangle, 4)) + # %x,y,theta,costmult + # %x aligned with the heading of the robot, angles are positive + # %counterclockwise + # %0 theta change + basemprimendpts0_c[0, :] = np.array(np.hstack((1.0, 0.0, 0.0, forwardcostmult))) + basemprimendpts0_c[1, :] = np.array(np.hstack((8.0, 0.0, 0.0, forwardcostmult))) + basemprimendpts0_c[2, :] = np.array(np.hstack((-1.0, 0.0, 0.0, backwardcostmult))) + # %1/16 theta change + basemprimendpts0_c[3, :] = np.array(np.hstack((8.0, 1.0, 1.0, forwardandturncostmult))) + basemprimendpts0_c[4, :] = np.array(np.hstack((8.0, -1.0, -1.0, forwardandturncostmult))) + # %turn in place + basemprimendpts0_c[5, :] = np.array(np.hstack((0.0, 0.0, 1.0, turninplacecostmult))) + basemprimendpts0_c[6, :] = np.array(np.hstack((0.0, 0.0, -1.0, turninplacecostmult))) + # %45 degrees + basemprimendpts45_c = np.zeros((numberofprimsperangle, 4)) + # %x,y,theta,costmult (multiplier is used as costmult*cost) + # %x aligned with the heading of the robot, angles are positive + # %counterclockwise + # %0 theta change + basemprimendpts45_c[0, :] = np.array(np.hstack((1.0, 1.0, 0.0, forwardcostmult))) + basemprimendpts45_c[1, :] = np.array(np.hstack((6.0, 6.0, 0.0, forwardcostmult))) + basemprimendpts45_c[2, :] = np.array(np.hstack((-1.0, -1.0, 0.0, backwardcostmult))) + # %1/16 theta change + basemprimendpts45_c[3, :] = np.array(np.hstack((5.0, 7.0, 1.0, forwardandturncostmult))) + basemprimendpts45_c[4, :] = np.array(np.hstack((7.0, 5.0, -1.0, forwardandturncostmult))) + # %turn in place + basemprimendpts45_c[5, :] = np.array(np.hstack((0.0, 0.0, 1.0, turninplacecostmult))) + basemprimendpts45_c[6, :] = np.array(np.hstack((0.0, 0.0, -1.0, turninplacecostmult))) + # %22.5 degrees + basemprimendpts22p5_c = np.zeros((numberofprimsperangle, 4)) + # %x,y,theta,costmult (multiplier is used as costmult*cost) + # %x aligned with the heading of the robot, angles are positive + # %counterclockwise + # %0 theta change + basemprimendpts22p5_c[0, :] = np.array(np.hstack((2.0, 1.0, 0.0, forwardcostmult))) + basemprimendpts22p5_c[1, :] = np.array(np.hstack((6.0, 3.0, 0.0, forwardcostmult))) + basemprimendpts22p5_c[2, :] = np.array(np.hstack((-2.0, -1.0, 0.0, backwardcostmult))) + # %1/16 theta change + basemprimendpts22p5_c[3, :] = np.array(np.hstack((5.0, 4.0, 1.0, forwardandturncostmult))) + basemprimendpts22p5_c[4, :] = np.array(np.hstack((7.0, 2.0, -1.0, forwardandturncostmult))) + # %turn in place + basemprimendpts22p5_c[5, :] = np.array(np.hstack((0.0, 0.0, 1.0, turninplacecostmult))) + basemprimendpts22p5_c[6, :] = np.array(np.hstack((0.0, 0.0, -1.0, turninplacecostmult))) + else: + print('ERROR: undefined mprims type\n') + return [] + + fout = open(outfilename, 'w') + # %write the header + fout.write('resolution_m: %f\n' % (resolution)) + fout.write('numberofangles: %d\n' % (numberofangles)) + fout.write('totalnumberofprimitives: %d\n' % (numberofprimsperangle * numberofangles)) + # %iterate over angles + for angleind in np.arange(1.0, (numberofangles) + 1): + currentangle = ((angleind - 1) * 2.0 * np.pi) / numberofangles + currentangle_36000int = np.round((angleind - 1) * 36000.0 / numberofangles) + if visualize: + if separate_plots: + fig = plt.figure(angleind) + plt.title('angle {:2.0f} (= {:3.1f} degrees)'.format(angleind - 1, currentangle_36000int / 100.0)) + else: + fig = plt.figure(1) + + plt.axis('equal') + plt.axis([-10 * resolution, 10 * resolution, -10 * resolution, 10 * resolution]) + ax = fig.add_subplot(1, 1, 1) + major_ticks = np.arange(-8 * resolution, 9 * resolution, 4 * resolution) + minor_ticks = np.arange(-8 * resolution, 9 * resolution, resolution) + ax.set_xticks(major_ticks) + ax.set_xticks(minor_ticks, minor=True) + ax.set_yticks(major_ticks) + ax.set_yticks(minor_ticks, minor=True) + ax.grid(which='minor', alpha=0.5) + ax.grid(which='major', alpha=0.9) + + # %iterate over primitives + for primind in np.arange(1.0, (numberofprimsperangle) + 1): + fout.write('primID: %d\n' % (primind - 1)) + fout.write('startangle_c: %d\n' % (angleind - 1)) + # %current angle + # %compute which template to use + if (currentangle_36000int % 9000) == 0: + basemprimendpts_c = basemprimendpts0_c[int(primind) - 1, :] + angle = currentangle + elif (currentangle_36000int % 4500) == 0: + basemprimendpts_c = basemprimendpts45_c[int(primind) - 1, :] + angle = currentangle - 45.0 * np.pi / 180.0 + + # commented out because basemprimendpts33p75_c is undefined + # elif ((currentangle_36000int - 7875) % 9000) == 0: + # basemprimendpts_c = ( + # 1 * basemprimendpts33p75_c[primind, :] + # ) # 1* to force deep copy to avoid reference update below + # basemprimendpts_c[0] = basemprimendpts33p75_c[primind, 1] + # # %reverse x and y + # basemprimendpts_c[1] = basemprimendpts33p75_c[primind, 0] + # basemprimendpts_c[2] = -basemprimendpts33p75_c[primind, 2] + # # %reverse the angle as well + # angle = currentangle - (78.75 * np.pi) / 180.0 + # print('78p75\n') + + elif ((currentangle_36000int - 6750) % 9000) == 0: + basemprimendpts_c = ( + 1 * basemprimendpts22p5_c[int(primind) - 1, :] + ) # 1* to force deep copy to avoid reference update below + basemprimendpts_c[0] = basemprimendpts22p5_c[int(primind) - 1, 1] + # %reverse x and y + basemprimendpts_c[1] = basemprimendpts22p5_c[int(primind) - 1, 0] + basemprimendpts_c[2] = -basemprimendpts22p5_c[int(primind) - 1, 2] + # %reverse the angle as well + # print( + # '%d : %d %d %d onto %d %d %d\n' + # % ( + # primind - 1, + # basemprimendpts22p5_c[int(primind) - 1, 0], + # basemprimendpts22p5_c[int(primind) - 1, 1], + # basemprimendpts22p5_c[int(primind) - 1, 2], + # basemprimendpts_c[0], + # basemprimendpts_c[1], + # basemprimendpts_c[2], + # ) + # ) + angle = currentangle - (67.5 * np.pi) / 180.0 + print('67p5\n') + + # commented out because basemprimendpts11p25_c is undefined + # elif ((currentangle_36000int - 5625) % 9000) == 0: + # basemprimendpts_c = ( + # 1 * basemprimendpts11p25_c[primind, :] + # ) # 1* to force deep copy to avoid reference update below + # basemprimendpts_c[0] = basemprimendpts11p25_c[primind, 1] + # # %reverse x and y + # basemprimendpts_c[1] = basemprimendpts11p25_c[primind, 0] + # basemprimendpts_c[2] = -basemprimendpts11p25_c[primind, 2] + # # %reverse the angle as well + # angle = currentangle - (56.25 * np.pi) / 180.0 + # print('56p25\n') + + # commented out because basemprimendpts33p75_c is undefined + # elif ((currentangle_36000int - 3375) % 9000) == 0: + # basemprimendpts_c = basemprimendpts33p75_c[int(primind), :] + # angle = currentangle - (33.75 * np.pi) / 180.0 + # print('33p75\n') + + elif ((currentangle_36000int - 2250) % 9000) == 0: + basemprimendpts_c = basemprimendpts22p5_c[int(primind) - 1, :] + angle = currentangle - (22.5 * np.pi) / 180.0 + print('22p5\n') + + # commented out because basemprimendpts11p25_c is undefined + # elif ((currentangle_36000int - 1125) % 9000) == 0: + # basemprimendpts_c = basemprimendpts11p25_c[int(primind), :] + # angle = currentangle - (11.25 * np.pi) / 180.0 + # print('11p25\n') + + else: + print('ERROR: invalid angular resolution. angle = %d\n' % currentangle_36000int) + return [] + + # %now figure out what action will be + baseendpose_c = basemprimendpts_c[0:3] + additionalactioncostmult = basemprimendpts_c[3] + endx_c = np.round((baseendpose_c[0] * np.cos(angle)) - (baseendpose_c[1] * np.sin(angle))) + endy_c = np.round((baseendpose_c[0] * np.sin(angle)) + (baseendpose_c[1] * np.cos(angle))) + endtheta_c = np.fmod(angleind - 1 + baseendpose_c[2], numberofangles) + endpose_c = np.array(np.hstack((endx_c, endy_c, endtheta_c))) + print("endpose_c=", endpose_c) + print(('rotation angle=%f\n' % (angle * 180.0 / np.pi))) + # if np.logical_and(baseendpose_c[1] == 0., baseendpose_c[2] == 0.): + # %fprintf(1, 'endpose=%d %d %d\n', endpose_c(1), endpose_c(2), endpose_c(3)); + + # %generate intermediate poses (remember they are w.r.t 0,0 (and not + # %centers of the cells) + numofsamples = 10 + intermcells_m = np.zeros((numofsamples, 3)) + if UNICYCLE_MPRIM_16DEGS == 1.0: + startpt = np.array(np.hstack((0.0, 0.0, currentangle))) + endpt = np.array( + np.hstack( + ( + (endpose_c[0] * resolution), + (endpose_c[1] * resolution), + ( + ((np.fmod(angleind - 1 + baseendpose_c[2], numberofangles)) * 2.0 * np.pi) + / numberofangles + ), + ) + ) + ) + + print("startpt =", startpt) + print("endpt =", endpt) + intermcells_m = np.zeros((numofsamples, 3)) + if np.logical_or(np.logical_and(endx_c == 0.0, endy_c == 0.0), baseendpose_c[2] == 0.0): + # %turn in place or move forward + for iind in np.arange(1.0, (numofsamples) + 1): + fraction = float(iind - 1) / (numofsamples - 1) + intermcells_m[int(iind) - 1, :] = np.array( + ( + startpt[0] + (endpt[0] - startpt[0]) * fraction, + startpt[1] + (endpt[1] - startpt[1]) * fraction, + 0, + ) + ) + rotation_angle = baseendpose_c[2] * (2.0 * np.pi / numberofangles) + intermcells_m[int(iind) - 1, 2] = np.fmod(startpt[2] + rotation_angle * fraction, (2.0 * np.pi)) + # print " ",iind," of ",numofsamples," fraction=",fraction," rotation=",rotation_angle + + else: + # %unicycle-based move forward or backward (http://sbpl.net/node/53) + R = np.array( + np.vstack( + ( + np.hstack((np.cos(startpt[2]), np.sin(endpt[2]) - np.sin(startpt[2]))), + np.hstack((np.sin(startpt[2]), -np.cos(endpt[2]) + np.cos(startpt[2]))), + ) + ) + ) + + S = np.dot(np.linalg.pinv(R), np.array(np.vstack((endpt[0] - startpt[0], endpt[1] - startpt[1])))) + l = S[0] + tvoverrv = S[1] + rv = (baseendpose_c[2] * 2.0 * np.pi / numberofangles) + l / tvoverrv + tv = tvoverrv * rv + + # print "R=\n",R + # print "Rpi=\n",np.linalg.pinv(R) + # print "S=\n",S + # print "l=",l + # print "tvoverrv=",tvoverrv + # print "rv=",rv + # print "tv=",tv + + if l < 0.0: + print(('WARNING: l = %f < 0 -> bad action start/end points\n' % (l))) + l = 0.0 + + # %compute rv + # %rv = baseendpose_c(3)*2*pi/numberofangles; + # %compute tv + # %tvx = (endpt(1) - startpt(1))*rv/(sin(endpt(3)) - sin(startpt(3))) + # %tvy = -(endpt(2) - startpt(2))*rv/(cos(endpt(3)) - cos(startpt(3))) + # %tv = (tvx + tvy)/2.0; + # %generate samples + for iind in np.arange(1, numofsamples + 1): + dt = (iind - 1) / (numofsamples - 1) + # %dtheta = rv*dt + startpt(3); + # %intermcells_m(iind,:) = [startpt(1) + tv/rv*(sin(dtheta) - sin(startpt(3))) ... + # % startpt(2) - tv/rv*(cos(dtheta) - cos(startpt(3))) ... + # % dtheta]; + if (dt * tv) < l: + intermcells_m[int(iind) - 1, :] = np.array( + np.hstack( + ( + startpt[0] + dt * tv * np.cos(startpt[2]), + startpt[1] + dt * tv * np.sin(startpt[2]), + startpt[2], + ) + ) + ) + else: + dtheta = rv * (dt - l / tv) + startpt[2] + intermcells_m[int(iind) - 1, :] = np.array( + np.hstack( + ( + startpt[0] + + l * np.cos(startpt[2]) + + tvoverrv * (np.sin(dtheta) - np.sin(startpt[2])), + startpt[1] + + l * np.sin(startpt[2]) + - tvoverrv * (np.cos(dtheta) - np.cos(startpt[2])), + dtheta, + ) + ) + ) + + # %correct + errorxy = np.array( + np.hstack( + ( + endpt[0] - intermcells_m[int(numofsamples) - 1, 0], + endpt[1] - intermcells_m[int(numofsamples) - 1, 1], + ) + ) + ) + # print('l=%f errx=%f erry=%f\n'%(l, errorxy[0], errorxy[1])) + interpfactor = np.array( + np.hstack((np.arange(0.0, 1.0 + (1.0 / (numofsamples)), 1.0 / (numofsamples - 1)))) + ) + + # print "intermcells_m=",intermcells_m + # print "interp'=",interpfactor.conj().T + + intermcells_m[:, 0] = intermcells_m[:, 0] + errorxy[0] * interpfactor.conj().T + intermcells_m[:, 1] = intermcells_m[:, 1] + errorxy[1] * interpfactor.conj().T + + # %write out + fout.write('endpose_c: %d %d %d\n' % (endpose_c[0], endpose_c[1], endpose_c[2])) + fout.write('additionalactioncostmult: %d\n' % (additionalactioncostmult)) + fout.write('intermediateposes: %d\n' % (matrix_size(intermcells_m, 1.0))) + for interind in np.arange(1.0, (matrix_size(intermcells_m, 1.0)) + 1): + fout.write( + '%.4f %.4f %.4f\n' + % ( + intermcells_m[int(interind) - 1, 0], + intermcells_m[int(interind) - 1, 1], + intermcells_m[int(interind) - 1, 2], + ) + ) + + if visualize: + plt.plot(intermcells_m[:, 0], intermcells_m[:, 1], linestyle="-", marker="o") + plt.text(endpt[0], endpt[1], '{:2.0f}'.format(endpose_c[2])) + # if (visualize): + # plt.waitforbuttonpress() # uncomment to plot each primitive set one at a time + + fout.close() + if visualize: + # plt.waitforbuttonpress() # hold until buttom pressed + plt.show() # Keep windows open until the program is terminated + return [] + + +if __name__ == "__main__": + rospack = rospkg.RosPack() + outfilename = rospack.get_path('mir_navigation') + '/mprim/unicycle_highcost_5cm.mprim' + genmprim_unicycle(outfilename, visualize=True) diff --git a/navigations/sbpl_lattice_planner/matlab/mprim/pr2.mprim b/navigations/sbpl_lattice_planner/matlab/mprim/pr2.mprim new file mode 100755 index 0000000..b34485f --- /dev/null +++ b/navigations/sbpl_lattice_planner/matlab/mprim/pr2.mprim @@ -0,0 +1,1683 @@ +resolution_m: 0.025000 +numberofangles: 16 +totalnumberofprimitives: 112 +primID: 0 +startangle_c: 0 +endpose_c: 1 0 0 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0028 0.0000 0.0000 +0.0056 0.0000 0.0000 +0.0083 0.0000 0.0000 +0.0111 0.0000 0.0000 +0.0139 0.0000 0.0000 +0.0167 0.0000 0.0000 +0.0194 0.0000 0.0000 +0.0222 0.0000 0.0000 +0.0250 0.0000 0.0000 +primID: 1 +startangle_c: 0 +endpose_c: 8 0 0 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0222 0.0000 0.0000 +0.0444 0.0000 0.0000 +0.0667 0.0000 0.0000 +0.0889 0.0000 0.0000 +0.1111 0.0000 0.0000 +0.1333 0.0000 0.0000 +0.1556 0.0000 0.0000 +0.1778 0.0000 0.0000 +0.2000 0.0000 0.0000 +primID: 2 +startangle_c: 0 +endpose_c: -1 0 0 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 0.0000 +-0.0028 0.0000 0.0000 +-0.0056 0.0000 0.0000 +-0.0083 0.0000 0.0000 +-0.0111 0.0000 0.0000 +-0.0139 0.0000 0.0000 +-0.0167 0.0000 0.0000 +-0.0194 0.0000 0.0000 +-0.0222 0.0000 0.0000 +-0.0250 0.0000 0.0000 +primID: 3 +startangle_c: 0 +endpose_c: 8 1 1 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0226 -0.0000 0.0000 +0.0452 -0.0000 0.0000 +0.0678 -0.0000 0.0000 +0.0903 0.0004 0.0488 +0.1128 0.0023 0.1176 +0.1352 0.0057 0.1864 +0.1572 0.0106 0.2551 +0.1789 0.0171 0.3239 +0.2000 0.0250 0.3927 +primID: 4 +startangle_c: 0 +endpose_c: 8 -1 -1 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0226 0.0000 0.0000 +0.0452 0.0000 0.0000 +0.0678 0.0000 0.0000 +0.0903 -0.0004 -0.0488 +0.1128 -0.0023 -0.1176 +0.1352 -0.0057 -0.1864 +0.1572 -0.0106 -0.2551 +0.1789 -0.0171 -0.3239 +0.2000 -0.0250 -0.3927 +primID: 5 +startangle_c: 0 +endpose_c: 0 0 1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0000 0.0000 0.0436 +0.0000 0.0000 0.0873 +0.0000 0.0000 0.1309 +0.0000 0.0000 0.1745 +0.0000 0.0000 0.2182 +0.0000 0.0000 0.2618 +0.0000 0.0000 0.3054 +0.0000 0.0000 0.3491 +0.0000 0.0000 0.3927 +primID: 6 +startangle_c: 0 +endpose_c: 0 0 -1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0000 0.0000 -0.0436 +0.0000 0.0000 -0.0873 +0.0000 0.0000 -0.1309 +0.0000 0.0000 -0.1745 +0.0000 0.0000 -0.2182 +0.0000 0.0000 -0.2618 +0.0000 0.0000 -0.3054 +0.0000 0.0000 -0.3491 +0.0000 0.0000 -0.3927 +primID: 0 +startangle_c: 1 +endpose_c: 2 1 1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0056 0.0028 0.3927 +0.0111 0.0056 0.3927 +0.0167 0.0083 0.3927 +0.0222 0.0111 0.3927 +0.0278 0.0139 0.3927 +0.0333 0.0167 0.3927 +0.0389 0.0194 0.3927 +0.0444 0.0222 0.3927 +0.0500 0.0250 0.3927 +primID: 1 +startangle_c: 1 +endpose_c: 6 3 1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0167 0.0083 0.3927 +0.0333 0.0167 0.3927 +0.0500 0.0250 0.3927 +0.0667 0.0333 0.3927 +0.0833 0.0417 0.3927 +0.1000 0.0500 0.3927 +0.1167 0.0583 0.3927 +0.1333 0.0667 0.3927 +0.1500 0.0750 0.3927 +primID: 2 +startangle_c: 1 +endpose_c: -2 -1 1 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 0.3927 +-0.0056 -0.0028 0.3927 +-0.0111 -0.0056 0.3927 +-0.0167 -0.0083 0.3927 +-0.0222 -0.0111 0.3927 +-0.0278 -0.0139 0.3927 +-0.0333 -0.0167 0.3927 +-0.0389 -0.0194 0.3927 +-0.0444 -0.0222 0.3927 +-0.0500 -0.0250 0.3927 +primID: 3 +startangle_c: 1 +endpose_c: 5 4 2 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0149 0.0092 0.4230 +0.0296 0.0189 0.4533 +0.0440 0.0291 0.4836 +0.0582 0.0398 0.5139 +0.0722 0.0509 0.5442 +0.0858 0.0625 0.5745 +0.0992 0.0746 0.6048 +0.1123 0.0871 0.6351 +0.1250 0.1000 0.6654 +primID: 4 +startangle_c: 1 +endpose_c: 7 2 0 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0188 0.0078 0.3927 +0.0377 0.0156 0.3927 +0.0565 0.0234 0.3927 +0.0754 0.0312 0.3736 +0.0946 0.0379 0.2989 +0.1143 0.0432 0.2242 +0.1344 0.0470 0.1494 +0.1546 0.0492 0.0747 +0.1750 0.0500 0.0000 +primID: 5 +startangle_c: 1 +endpose_c: 0 0 2 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0000 0.0000 0.4363 +0.0000 0.0000 0.4800 +0.0000 0.0000 0.5236 +0.0000 0.0000 0.5672 +0.0000 0.0000 0.6109 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.6981 +0.0000 0.0000 0.7418 +0.0000 0.0000 0.7854 +primID: 6 +startangle_c: 1 +endpose_c: 0 0 0 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0000 0.0000 0.3491 +0.0000 0.0000 0.3054 +0.0000 0.0000 0.2618 +0.0000 0.0000 0.2182 +0.0000 0.0000 0.1745 +0.0000 0.0000 0.1309 +0.0000 0.0000 0.0873 +0.0000 0.0000 0.0436 +0.0000 0.0000 0.0000 +primID: 0 +startangle_c: 2 +endpose_c: 1 1 2 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0028 0.0028 0.7854 +0.0056 0.0056 0.7854 +0.0083 0.0083 0.7854 +0.0111 0.0111 0.7854 +0.0139 0.0139 0.7854 +0.0167 0.0167 0.7854 +0.0194 0.0194 0.7854 +0.0222 0.0222 0.7854 +0.0250 0.0250 0.7854 +primID: 1 +startangle_c: 2 +endpose_c: 6 6 2 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0167 0.0167 0.7854 +0.0333 0.0333 0.7854 +0.0500 0.0500 0.7854 +0.0667 0.0667 0.7854 +0.0833 0.0833 0.7854 +0.1000 0.1000 0.7854 +0.1167 0.1167 0.7854 +0.1333 0.1333 0.7854 +0.1500 0.1500 0.7854 +primID: 2 +startangle_c: 2 +endpose_c: -1 -1 2 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 0.7854 +-0.0028 -0.0028 0.7854 +-0.0056 -0.0056 0.7854 +-0.0083 -0.0083 0.7854 +-0.0111 -0.0111 0.7854 +-0.0139 -0.0139 0.7854 +-0.0167 -0.0167 0.7854 +-0.0194 -0.0194 0.7854 +-0.0222 -0.0222 0.7854 +-0.0250 -0.0250 0.7854 +primID: 3 +startangle_c: 2 +endpose_c: 5 7 3 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0170 0.0170 0.7854 +0.0339 0.0342 0.8151 +0.0500 0.0522 0.8669 +0.0651 0.0709 0.9188 +0.0792 0.0904 0.9707 +0.0923 0.1107 1.0225 +0.1043 0.1315 1.0744 +0.1152 0.1530 1.1262 +0.1250 0.1750 1.1781 +primID: 4 +startangle_c: 2 +endpose_c: 7 5 1 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0170 0.0170 0.7854 +0.0342 0.0339 0.7557 +0.0522 0.0500 0.7039 +0.0709 0.0651 0.6520 +0.0904 0.0792 0.6001 +0.1107 0.0923 0.5483 +0.1315 0.1043 0.4964 +0.1530 0.1152 0.4446 +0.1750 0.1250 0.3927 +primID: 5 +startangle_c: 2 +endpose_c: 0 0 3 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0000 0.0000 0.8290 +0.0000 0.0000 0.8727 +0.0000 0.0000 0.9163 +0.0000 0.0000 0.9599 +0.0000 0.0000 1.0036 +0.0000 0.0000 1.0472 +0.0000 0.0000 1.0908 +0.0000 0.0000 1.1345 +0.0000 0.0000 1.1781 +primID: 6 +startangle_c: 2 +endpose_c: 0 0 1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0000 0.0000 0.7418 +0.0000 0.0000 0.6981 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.6109 +0.0000 0.0000 0.5672 +0.0000 0.0000 0.5236 +0.0000 0.0000 0.4800 +0.0000 0.0000 0.4363 +0.0000 0.0000 0.3927 +primID: 0 +startangle_c: 3 +endpose_c: 1 2 3 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0028 0.0056 1.1781 +0.0056 0.0111 1.1781 +0.0083 0.0167 1.1781 +0.0111 0.0222 1.1781 +0.0139 0.0278 1.1781 +0.0167 0.0333 1.1781 +0.0194 0.0389 1.1781 +0.0222 0.0444 1.1781 +0.0250 0.0500 1.1781 +primID: 1 +startangle_c: 3 +endpose_c: 3 6 3 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0083 0.0167 1.1781 +0.0167 0.0333 1.1781 +0.0250 0.0500 1.1781 +0.0333 0.0667 1.1781 +0.0417 0.0833 1.1781 +0.0500 0.1000 1.1781 +0.0583 0.1167 1.1781 +0.0667 0.1333 1.1781 +0.0750 0.1500 1.1781 +primID: 2 +startangle_c: 3 +endpose_c: -1 -2 3 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 1.1781 +-0.0028 -0.0056 1.1781 +-0.0056 -0.0111 1.1781 +-0.0083 -0.0167 1.1781 +-0.0111 -0.0222 1.1781 +-0.0139 -0.0278 1.1781 +-0.0167 -0.0333 1.1781 +-0.0194 -0.0389 1.1781 +-0.0222 -0.0444 1.1781 +-0.0250 -0.0500 1.1781 +primID: 3 +startangle_c: 3 +endpose_c: 4 5 2 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0092 0.0149 1.1478 +0.0189 0.0296 1.1175 +0.0291 0.0440 1.0872 +0.0398 0.0582 1.0569 +0.0509 0.0722 1.0266 +0.0625 0.0858 0.9963 +0.0746 0.0992 0.9660 +0.0871 0.1123 0.9357 +0.1000 0.1250 0.9054 +primID: 4 +startangle_c: 3 +endpose_c: 2 7 4 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0078 0.0188 1.1781 +0.0156 0.0377 1.1781 +0.0234 0.0565 1.1781 +0.0312 0.0754 1.1972 +0.0379 0.0946 1.2719 +0.0432 0.1143 1.3466 +0.0470 0.1344 1.4214 +0.0492 0.1546 1.4961 +0.0500 0.1750 1.5708 +primID: 5 +startangle_c: 3 +endpose_c: 0 0 2 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0000 0.0000 1.1345 +0.0000 0.0000 1.0908 +0.0000 0.0000 1.0472 +0.0000 0.0000 1.0036 +0.0000 0.0000 0.9599 +0.0000 0.0000 0.9163 +0.0000 0.0000 0.8727 +0.0000 0.0000 0.8290 +0.0000 0.0000 0.7854 +primID: 6 +startangle_c: 3 +endpose_c: 0 0 4 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0000 0.0000 1.2217 +0.0000 0.0000 1.2654 +0.0000 0.0000 1.3090 +0.0000 0.0000 1.3526 +0.0000 0.0000 1.3963 +0.0000 0.0000 1.4399 +0.0000 0.0000 1.4835 +0.0000 0.0000 1.5272 +0.0000 0.0000 1.5708 +primID: 0 +startangle_c: 4 +endpose_c: 0 1 4 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0028 1.5708 +0.0000 0.0056 1.5708 +0.0000 0.0083 1.5708 +0.0000 0.0111 1.5708 +0.0000 0.0139 1.5708 +0.0000 0.0167 1.5708 +0.0000 0.0194 1.5708 +0.0000 0.0222 1.5708 +0.0000 0.0250 1.5708 +primID: 1 +startangle_c: 4 +endpose_c: 0 8 4 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0222 1.5708 +0.0000 0.0444 1.5708 +0.0000 0.0667 1.5708 +0.0000 0.0889 1.5708 +0.0000 0.1111 1.5708 +0.0000 0.1333 1.5708 +0.0000 0.1556 1.5708 +0.0000 0.1778 1.5708 +0.0000 0.2000 1.5708 +primID: 2 +startangle_c: 4 +endpose_c: 0 -1 4 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 -0.0028 1.5708 +0.0000 -0.0056 1.5708 +0.0000 -0.0083 1.5708 +0.0000 -0.0111 1.5708 +0.0000 -0.0139 1.5708 +0.0000 -0.0167 1.5708 +0.0000 -0.0194 1.5708 +0.0000 -0.0222 1.5708 +0.0000 -0.0250 1.5708 +primID: 3 +startangle_c: 4 +endpose_c: -1 8 5 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0226 1.5708 +0.0000 0.0452 1.5708 +0.0000 0.0678 1.5708 +-0.0004 0.0903 1.6196 +-0.0023 0.1128 1.6884 +-0.0057 0.1352 1.7572 +-0.0106 0.1572 1.8259 +-0.0171 0.1789 1.8947 +-0.0250 0.2000 1.9635 +primID: 4 +startangle_c: 4 +endpose_c: 1 8 3 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 1.5708 +-0.0000 0.0226 1.5708 +-0.0000 0.0452 1.5708 +-0.0000 0.0678 1.5708 +0.0004 0.0903 1.5220 +0.0023 0.1128 1.4532 +0.0057 0.1352 1.3844 +0.0106 0.1572 1.3156 +0.0171 0.1789 1.2469 +0.0250 0.2000 1.1781 +primID: 5 +startangle_c: 4 +endpose_c: 0 0 5 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0000 1.6144 +0.0000 0.0000 1.6581 +0.0000 0.0000 1.7017 +0.0000 0.0000 1.7453 +0.0000 0.0000 1.7890 +0.0000 0.0000 1.8326 +0.0000 0.0000 1.8762 +0.0000 0.0000 1.9199 +0.0000 0.0000 1.9635 +primID: 6 +startangle_c: 4 +endpose_c: 0 0 3 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0000 1.5272 +0.0000 0.0000 1.4835 +0.0000 0.0000 1.4399 +0.0000 0.0000 1.3963 +0.0000 0.0000 1.3526 +0.0000 0.0000 1.3090 +0.0000 0.0000 1.2654 +0.0000 0.0000 1.2217 +0.0000 0.0000 1.1781 +primID: 0 +startangle_c: 5 +endpose_c: -1 2 5 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0028 0.0056 1.9635 +-0.0056 0.0111 1.9635 +-0.0083 0.0167 1.9635 +-0.0111 0.0222 1.9635 +-0.0139 0.0278 1.9635 +-0.0167 0.0333 1.9635 +-0.0194 0.0389 1.9635 +-0.0222 0.0444 1.9635 +-0.0250 0.0500 1.9635 +primID: 1 +startangle_c: 5 +endpose_c: -3 6 5 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0083 0.0167 1.9635 +-0.0167 0.0333 1.9635 +-0.0250 0.0500 1.9635 +-0.0333 0.0667 1.9635 +-0.0417 0.0833 1.9635 +-0.0500 0.1000 1.9635 +-0.0583 0.1167 1.9635 +-0.0667 0.1333 1.9635 +-0.0750 0.1500 1.9635 +primID: 2 +startangle_c: 5 +endpose_c: 1 -2 5 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0028 -0.0056 1.9635 +0.0056 -0.0111 1.9635 +0.0083 -0.0167 1.9635 +0.0111 -0.0222 1.9635 +0.0139 -0.0278 1.9635 +0.0167 -0.0333 1.9635 +0.0194 -0.0389 1.9635 +0.0222 -0.0444 1.9635 +0.0250 -0.0500 1.9635 +primID: 3 +startangle_c: 5 +endpose_c: -4 5 6 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0092 0.0149 1.9938 +-0.0189 0.0296 2.0241 +-0.0291 0.0440 2.0544 +-0.0398 0.0582 2.0847 +-0.0509 0.0722 2.1150 +-0.0625 0.0858 2.1453 +-0.0746 0.0992 2.1756 +-0.0871 0.1123 2.2059 +-0.1000 0.1250 2.2362 +primID: 4 +startangle_c: 5 +endpose_c: -2 7 4 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0078 0.0188 1.9635 +-0.0156 0.0377 1.9635 +-0.0234 0.0565 1.9635 +-0.0312 0.0754 1.9444 +-0.0379 0.0946 1.8697 +-0.0432 0.1143 1.7950 +-0.0470 0.1344 1.7202 +-0.0492 0.1546 1.6455 +-0.0500 0.1750 1.5708 +primID: 5 +startangle_c: 5 +endpose_c: 0 0 6 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0000 0.0000 2.0071 +0.0000 0.0000 2.0508 +0.0000 0.0000 2.0944 +0.0000 0.0000 2.1380 +0.0000 0.0000 2.1817 +0.0000 0.0000 2.2253 +0.0000 0.0000 2.2689 +0.0000 0.0000 2.3126 +0.0000 0.0000 2.3562 +primID: 6 +startangle_c: 5 +endpose_c: 0 0 4 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0000 0.0000 1.9199 +0.0000 0.0000 1.8762 +0.0000 0.0000 1.8326 +0.0000 0.0000 1.7890 +0.0000 0.0000 1.7453 +0.0000 0.0000 1.7017 +0.0000 0.0000 1.6581 +0.0000 0.0000 1.6144 +0.0000 0.0000 1.5708 +primID: 0 +startangle_c: 6 +endpose_c: -1 1 6 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0028 0.0028 2.3562 +-0.0056 0.0056 2.3562 +-0.0083 0.0083 2.3562 +-0.0111 0.0111 2.3562 +-0.0139 0.0139 2.3562 +-0.0167 0.0167 2.3562 +-0.0194 0.0194 2.3562 +-0.0222 0.0222 2.3562 +-0.0250 0.0250 2.3562 +primID: 1 +startangle_c: 6 +endpose_c: -6 6 6 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0167 0.0167 2.3562 +-0.0333 0.0333 2.3562 +-0.0500 0.0500 2.3562 +-0.0667 0.0667 2.3562 +-0.0833 0.0833 2.3562 +-0.1000 0.1000 2.3562 +-0.1167 0.1167 2.3562 +-0.1333 0.1333 2.3562 +-0.1500 0.1500 2.3562 +primID: 2 +startangle_c: 6 +endpose_c: 1 -1 6 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0028 -0.0028 2.3562 +0.0056 -0.0056 2.3562 +0.0083 -0.0083 2.3562 +0.0111 -0.0111 2.3562 +0.0139 -0.0139 2.3562 +0.0167 -0.0167 2.3562 +0.0194 -0.0194 2.3562 +0.0222 -0.0222 2.3562 +0.0250 -0.0250 2.3562 +primID: 3 +startangle_c: 6 +endpose_c: -7 5 7 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0170 0.0170 2.3562 +-0.0342 0.0339 2.3859 +-0.0522 0.0500 2.4377 +-0.0709 0.0651 2.4896 +-0.0904 0.0792 2.5415 +-0.1107 0.0923 2.5933 +-0.1315 0.1043 2.6452 +-0.1530 0.1152 2.6970 +-0.1750 0.1250 2.7489 +primID: 4 +startangle_c: 6 +endpose_c: -5 7 5 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0170 0.0170 2.3562 +-0.0339 0.0342 2.3265 +-0.0500 0.0522 2.2747 +-0.0651 0.0709 2.2228 +-0.0792 0.0904 2.1709 +-0.0923 0.1107 2.1191 +-0.1043 0.1315 2.0672 +-0.1152 0.1530 2.0154 +-0.1250 0.1750 1.9635 +primID: 5 +startangle_c: 6 +endpose_c: 0 0 7 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0000 0.0000 2.3998 +0.0000 0.0000 2.4435 +0.0000 0.0000 2.4871 +0.0000 0.0000 2.5307 +0.0000 0.0000 2.5744 +0.0000 0.0000 2.6180 +0.0000 0.0000 2.6616 +0.0000 0.0000 2.7053 +0.0000 0.0000 2.7489 +primID: 6 +startangle_c: 6 +endpose_c: 0 0 5 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0000 0.0000 2.3126 +0.0000 0.0000 2.2689 +0.0000 0.0000 2.2253 +0.0000 0.0000 2.1817 +0.0000 0.0000 2.1380 +0.0000 0.0000 2.0944 +0.0000 0.0000 2.0508 +0.0000 0.0000 2.0071 +0.0000 0.0000 1.9635 +primID: 0 +startangle_c: 7 +endpose_c: -2 1 7 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0056 0.0028 2.7489 +-0.0111 0.0056 2.7489 +-0.0167 0.0083 2.7489 +-0.0222 0.0111 2.7489 +-0.0278 0.0139 2.7489 +-0.0333 0.0167 2.7489 +-0.0389 0.0194 2.7489 +-0.0444 0.0222 2.7489 +-0.0500 0.0250 2.7489 +primID: 1 +startangle_c: 7 +endpose_c: -6 3 7 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0167 0.0083 2.7489 +-0.0333 0.0167 2.7489 +-0.0500 0.0250 2.7489 +-0.0667 0.0333 2.7489 +-0.0833 0.0417 2.7489 +-0.1000 0.0500 2.7489 +-0.1167 0.0583 2.7489 +-0.1333 0.0667 2.7489 +-0.1500 0.0750 2.7489 +primID: 2 +startangle_c: 7 +endpose_c: 2 -1 7 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0056 -0.0028 2.7489 +0.0111 -0.0056 2.7489 +0.0167 -0.0083 2.7489 +0.0222 -0.0111 2.7489 +0.0278 -0.0139 2.7489 +0.0333 -0.0167 2.7489 +0.0389 -0.0194 2.7489 +0.0444 -0.0222 2.7489 +0.0500 -0.0250 2.7489 +primID: 3 +startangle_c: 7 +endpose_c: -5 4 6 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0149 0.0092 2.7186 +-0.0296 0.0189 2.6883 +-0.0440 0.0291 2.6580 +-0.0582 0.0398 2.6277 +-0.0722 0.0509 2.5974 +-0.0858 0.0625 2.5671 +-0.0992 0.0746 2.5368 +-0.1123 0.0871 2.5065 +-0.1250 0.1000 2.4762 +primID: 4 +startangle_c: 7 +endpose_c: -7 2 8 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0188 0.0078 2.7489 +-0.0377 0.0156 2.7489 +-0.0565 0.0234 2.7489 +-0.0754 0.0312 2.7680 +-0.0946 0.0379 2.8427 +-0.1143 0.0432 2.9174 +-0.1344 0.0470 2.9921 +-0.1546 0.0492 3.0669 +-0.1750 0.0500 3.1416 +primID: 5 +startangle_c: 7 +endpose_c: 0 0 6 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0000 0.0000 2.7053 +0.0000 0.0000 2.6616 +0.0000 0.0000 2.6180 +0.0000 0.0000 2.5744 +0.0000 0.0000 2.5307 +0.0000 0.0000 2.4871 +0.0000 0.0000 2.4435 +0.0000 0.0000 2.3998 +0.0000 0.0000 2.3562 +primID: 6 +startangle_c: 7 +endpose_c: 0 0 8 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0000 0.0000 2.7925 +0.0000 0.0000 2.8362 +0.0000 0.0000 2.8798 +0.0000 0.0000 2.9234 +0.0000 0.0000 2.9671 +0.0000 0.0000 3.0107 +0.0000 0.0000 3.0543 +0.0000 0.0000 3.0980 +0.0000 0.0000 3.1416 +primID: 0 +startangle_c: 8 +endpose_c: -1 0 8 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0028 0.0000 3.1416 +-0.0056 0.0000 3.1416 +-0.0083 0.0000 3.1416 +-0.0111 0.0000 3.1416 +-0.0139 0.0000 3.1416 +-0.0167 0.0000 3.1416 +-0.0194 0.0000 3.1416 +-0.0222 0.0000 3.1416 +-0.0250 0.0000 3.1416 +primID: 1 +startangle_c: 8 +endpose_c: -8 0 8 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0222 0.0000 3.1416 +-0.0444 0.0000 3.1416 +-0.0667 0.0000 3.1416 +-0.0889 0.0000 3.1416 +-0.1111 0.0000 3.1416 +-0.1333 0.0000 3.1416 +-0.1556 0.0000 3.1416 +-0.1778 0.0000 3.1416 +-0.2000 0.0000 3.1416 +primID: 2 +startangle_c: 8 +endpose_c: 1 0 8 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0028 0.0000 3.1416 +0.0056 0.0000 3.1416 +0.0083 0.0000 3.1416 +0.0111 0.0000 3.1416 +0.0139 0.0000 3.1416 +0.0167 0.0000 3.1416 +0.0194 0.0000 3.1416 +0.0222 0.0000 3.1416 +0.0250 0.0000 3.1416 +primID: 3 +startangle_c: 8 +endpose_c: -8 -1 9 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0226 0.0000 3.1416 +-0.0452 0.0000 3.1416 +-0.0678 0.0000 3.1416 +-0.0903 -0.0004 3.1904 +-0.1128 -0.0023 3.2592 +-0.1352 -0.0057 3.3280 +-0.1572 -0.0106 3.3967 +-0.1789 -0.0171 3.4655 +-0.2000 -0.0250 3.5343 +primID: 4 +startangle_c: 8 +endpose_c: -8 1 7 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0226 0.0000 3.1416 +-0.0452 0.0000 3.1416 +-0.0678 0.0000 3.1416 +-0.0903 0.0004 3.0928 +-0.1128 0.0023 3.0240 +-0.1352 0.0057 2.9552 +-0.1572 0.0106 2.8864 +-0.1789 0.0171 2.8177 +-0.2000 0.0250 2.7489 +primID: 5 +startangle_c: 8 +endpose_c: 0 0 9 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0000 0.0000 3.1852 +0.0000 0.0000 3.2289 +0.0000 0.0000 3.2725 +0.0000 0.0000 3.3161 +0.0000 0.0000 3.3598 +0.0000 0.0000 3.4034 +0.0000 0.0000 3.4470 +0.0000 0.0000 3.4907 +0.0000 0.0000 3.5343 +primID: 6 +startangle_c: 8 +endpose_c: 0 0 7 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0000 0.0000 3.0980 +0.0000 0.0000 3.0543 +0.0000 0.0000 3.0107 +0.0000 0.0000 2.9671 +0.0000 0.0000 2.9234 +0.0000 0.0000 2.8798 +0.0000 0.0000 2.8362 +0.0000 0.0000 2.7925 +0.0000 0.0000 2.7489 +primID: 0 +startangle_c: 9 +endpose_c: -2 -1 9 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0056 -0.0028 3.5343 +-0.0111 -0.0056 3.5343 +-0.0167 -0.0083 3.5343 +-0.0222 -0.0111 3.5343 +-0.0278 -0.0139 3.5343 +-0.0333 -0.0167 3.5343 +-0.0389 -0.0194 3.5343 +-0.0444 -0.0222 3.5343 +-0.0500 -0.0250 3.5343 +primID: 1 +startangle_c: 9 +endpose_c: -6 -3 9 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0167 -0.0083 3.5343 +-0.0333 -0.0167 3.5343 +-0.0500 -0.0250 3.5343 +-0.0667 -0.0333 3.5343 +-0.0833 -0.0417 3.5343 +-0.1000 -0.0500 3.5343 +-0.1167 -0.0583 3.5343 +-0.1333 -0.0667 3.5343 +-0.1500 -0.0750 3.5343 +primID: 2 +startangle_c: 9 +endpose_c: 2 1 9 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0056 0.0028 3.5343 +0.0111 0.0056 3.5343 +0.0167 0.0083 3.5343 +0.0222 0.0111 3.5343 +0.0278 0.0139 3.5343 +0.0333 0.0167 3.5343 +0.0389 0.0194 3.5343 +0.0444 0.0222 3.5343 +0.0500 0.0250 3.5343 +primID: 3 +startangle_c: 9 +endpose_c: -5 -4 10 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0149 -0.0092 3.5646 +-0.0296 -0.0189 3.5949 +-0.0440 -0.0291 3.6252 +-0.0582 -0.0398 3.6555 +-0.0722 -0.0509 3.6858 +-0.0858 -0.0625 3.7161 +-0.0992 -0.0746 3.7464 +-0.1123 -0.0871 3.7767 +-0.1250 -0.1000 3.8070 +primID: 4 +startangle_c: 9 +endpose_c: -7 -2 8 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0188 -0.0078 3.5343 +-0.0377 -0.0156 3.5343 +-0.0565 -0.0234 3.5343 +-0.0754 -0.0312 3.5152 +-0.0946 -0.0379 3.4405 +-0.1143 -0.0432 3.3658 +-0.1344 -0.0470 3.2910 +-0.1546 -0.0492 3.2163 +-0.1750 -0.0500 3.1416 +primID: 5 +startangle_c: 9 +endpose_c: 0 0 10 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0000 0.0000 3.5779 +0.0000 0.0000 3.6216 +0.0000 0.0000 3.6652 +0.0000 0.0000 3.7088 +0.0000 0.0000 3.7525 +0.0000 0.0000 3.7961 +0.0000 0.0000 3.8397 +0.0000 0.0000 3.8834 +0.0000 0.0000 3.9270 +primID: 6 +startangle_c: 9 +endpose_c: 0 0 8 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0000 0.0000 3.4907 +0.0000 0.0000 3.4470 +0.0000 0.0000 3.4034 +0.0000 0.0000 3.3598 +0.0000 0.0000 3.3161 +0.0000 0.0000 3.2725 +0.0000 0.0000 3.2289 +0.0000 0.0000 3.1852 +0.0000 0.0000 3.1416 +primID: 0 +startangle_c: 10 +endpose_c: -1 -1 10 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0028 -0.0028 3.9270 +-0.0056 -0.0056 3.9270 +-0.0083 -0.0083 3.9270 +-0.0111 -0.0111 3.9270 +-0.0139 -0.0139 3.9270 +-0.0167 -0.0167 3.9270 +-0.0194 -0.0194 3.9270 +-0.0222 -0.0222 3.9270 +-0.0250 -0.0250 3.9270 +primID: 1 +startangle_c: 10 +endpose_c: -6 -6 10 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0167 -0.0167 3.9270 +-0.0333 -0.0333 3.9270 +-0.0500 -0.0500 3.9270 +-0.0667 -0.0667 3.9270 +-0.0833 -0.0833 3.9270 +-0.1000 -0.1000 3.9270 +-0.1167 -0.1167 3.9270 +-0.1333 -0.1333 3.9270 +-0.1500 -0.1500 3.9270 +primID: 2 +startangle_c: 10 +endpose_c: 1 1 10 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0028 0.0028 3.9270 +0.0056 0.0056 3.9270 +0.0083 0.0083 3.9270 +0.0111 0.0111 3.9270 +0.0139 0.0139 3.9270 +0.0167 0.0167 3.9270 +0.0194 0.0194 3.9270 +0.0222 0.0222 3.9270 +0.0250 0.0250 3.9270 +primID: 3 +startangle_c: 10 +endpose_c: -5 -7 11 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0170 -0.0170 3.9270 +-0.0339 -0.0342 3.9567 +-0.0500 -0.0522 4.0085 +-0.0651 -0.0709 4.0604 +-0.0792 -0.0904 4.1123 +-0.0923 -0.1107 4.1641 +-0.1043 -0.1315 4.2160 +-0.1152 -0.1530 4.2678 +-0.1250 -0.1750 4.3197 +primID: 4 +startangle_c: 10 +endpose_c: -7 -5 9 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0170 -0.0170 3.9270 +-0.0342 -0.0339 3.8973 +-0.0522 -0.0500 3.8455 +-0.0709 -0.0651 3.7936 +-0.0904 -0.0792 3.7417 +-0.1107 -0.0923 3.6899 +-0.1315 -0.1043 3.6380 +-0.1530 -0.1152 3.5862 +-0.1750 -0.1250 3.5343 +primID: 5 +startangle_c: 10 +endpose_c: 0 0 11 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.9706 +0.0000 0.0000 4.0143 +0.0000 0.0000 4.0579 +0.0000 0.0000 4.1015 +0.0000 0.0000 4.1452 +0.0000 0.0000 4.1888 +0.0000 0.0000 4.2324 +0.0000 0.0000 4.2761 +0.0000 0.0000 4.3197 +primID: 6 +startangle_c: 10 +endpose_c: 0 0 9 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.8834 +0.0000 0.0000 3.8397 +0.0000 0.0000 3.7961 +0.0000 0.0000 3.7525 +0.0000 0.0000 3.7088 +0.0000 0.0000 3.6652 +0.0000 0.0000 3.6216 +0.0000 0.0000 3.5779 +0.0000 0.0000 3.5343 +primID: 0 +startangle_c: 11 +endpose_c: -1 -2 11 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0028 -0.0056 4.3197 +-0.0056 -0.0111 4.3197 +-0.0083 -0.0167 4.3197 +-0.0111 -0.0222 4.3197 +-0.0139 -0.0278 4.3197 +-0.0167 -0.0333 4.3197 +-0.0194 -0.0389 4.3197 +-0.0222 -0.0444 4.3197 +-0.0250 -0.0500 4.3197 +primID: 1 +startangle_c: 11 +endpose_c: -3 -6 11 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0083 -0.0167 4.3197 +-0.0167 -0.0333 4.3197 +-0.0250 -0.0500 4.3197 +-0.0333 -0.0667 4.3197 +-0.0417 -0.0833 4.3197 +-0.0500 -0.1000 4.3197 +-0.0583 -0.1167 4.3197 +-0.0667 -0.1333 4.3197 +-0.0750 -0.1500 4.3197 +primID: 2 +startangle_c: 11 +endpose_c: 1 2 11 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0028 0.0056 4.3197 +0.0056 0.0111 4.3197 +0.0083 0.0167 4.3197 +0.0111 0.0222 4.3197 +0.0139 0.0278 4.3197 +0.0167 0.0333 4.3197 +0.0194 0.0389 4.3197 +0.0222 0.0444 4.3197 +0.0250 0.0500 4.3197 +primID: 3 +startangle_c: 11 +endpose_c: -4 -5 10 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0092 -0.0149 4.2894 +-0.0189 -0.0296 4.2591 +-0.0291 -0.0440 4.2288 +-0.0398 -0.0582 4.1985 +-0.0509 -0.0722 4.1682 +-0.0625 -0.0858 4.1379 +-0.0746 -0.0992 4.1076 +-0.0871 -0.1123 4.0773 +-0.1000 -0.1250 4.0470 +primID: 4 +startangle_c: 11 +endpose_c: -2 -7 12 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0078 -0.0188 4.3197 +-0.0156 -0.0377 4.3197 +-0.0234 -0.0565 4.3197 +-0.0312 -0.0754 4.3388 +-0.0379 -0.0946 4.4135 +-0.0432 -0.1143 4.4882 +-0.0470 -0.1344 4.5629 +-0.0492 -0.1546 4.6377 +-0.0500 -0.1750 4.7124 +primID: 5 +startangle_c: 11 +endpose_c: 0 0 10 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0000 0.0000 4.2761 +0.0000 0.0000 4.2324 +0.0000 0.0000 4.1888 +0.0000 0.0000 4.1452 +0.0000 0.0000 4.1015 +0.0000 0.0000 4.0579 +0.0000 0.0000 4.0143 +0.0000 0.0000 3.9706 +0.0000 0.0000 3.9270 +primID: 6 +startangle_c: 11 +endpose_c: 0 0 12 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0000 0.0000 4.3633 +0.0000 0.0000 4.4070 +0.0000 0.0000 4.4506 +0.0000 0.0000 4.4942 +0.0000 0.0000 4.5379 +0.0000 0.0000 4.5815 +0.0000 0.0000 4.6251 +0.0000 0.0000 4.6688 +0.0000 0.0000 4.7124 +primID: 0 +startangle_c: 12 +endpose_c: 0 -1 12 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0028 4.7124 +0.0000 -0.0056 4.7124 +0.0000 -0.0083 4.7124 +0.0000 -0.0111 4.7124 +0.0000 -0.0139 4.7124 +0.0000 -0.0167 4.7124 +0.0000 -0.0194 4.7124 +0.0000 -0.0222 4.7124 +0.0000 -0.0250 4.7124 +primID: 1 +startangle_c: 12 +endpose_c: 0 -8 12 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0222 4.7124 +0.0000 -0.0444 4.7124 +0.0000 -0.0667 4.7124 +0.0000 -0.0889 4.7124 +0.0000 -0.1111 4.7124 +0.0000 -0.1333 4.7124 +0.0000 -0.1556 4.7124 +0.0000 -0.1778 4.7124 +0.0000 -0.2000 4.7124 +primID: 2 +startangle_c: 12 +endpose_c: 0 1 12 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0028 4.7124 +0.0000 0.0056 4.7124 +0.0000 0.0083 4.7124 +0.0000 0.0111 4.7124 +0.0000 0.0139 4.7124 +0.0000 0.0167 4.7124 +0.0000 0.0194 4.7124 +0.0000 0.0222 4.7124 +0.0000 0.0250 4.7124 +primID: 3 +startangle_c: 12 +endpose_c: 1 -8 13 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 4.7124 +-0.0000 -0.0226 4.7124 +-0.0000 -0.0452 4.7124 +-0.0000 -0.0678 4.7124 +0.0004 -0.0903 4.7612 +0.0023 -0.1128 4.8300 +0.0057 -0.1352 4.8988 +0.0106 -0.1572 4.9675 +0.0171 -0.1789 5.0363 +0.0250 -0.2000 5.1051 +primID: 4 +startangle_c: 12 +endpose_c: -1 -8 11 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 4.7124 +-0.0000 -0.0226 4.7124 +-0.0000 -0.0452 4.7124 +-0.0000 -0.0678 4.7124 +-0.0004 -0.0903 4.6636 +-0.0023 -0.1128 4.5948 +-0.0057 -0.1352 4.5260 +-0.0106 -0.1572 4.4572 +-0.0171 -0.1789 4.3885 +-0.0250 -0.2000 4.3197 +primID: 5 +startangle_c: 12 +endpose_c: 0 0 13 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0000 4.7560 +0.0000 0.0000 4.7997 +0.0000 0.0000 4.8433 +0.0000 0.0000 4.8869 +0.0000 0.0000 4.9306 +0.0000 0.0000 4.9742 +0.0000 0.0000 5.0178 +0.0000 0.0000 5.0615 +0.0000 0.0000 5.1051 +primID: 6 +startangle_c: 12 +endpose_c: 0 0 11 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0000 4.6688 +0.0000 0.0000 4.6251 +0.0000 0.0000 4.5815 +0.0000 0.0000 4.5379 +0.0000 0.0000 4.4942 +0.0000 0.0000 4.4506 +0.0000 0.0000 4.4070 +0.0000 0.0000 4.3633 +0.0000 0.0000 4.3197 +primID: 0 +startangle_c: 13 +endpose_c: 1 -2 13 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0028 -0.0056 5.1051 +0.0056 -0.0111 5.1051 +0.0083 -0.0167 5.1051 +0.0111 -0.0222 5.1051 +0.0139 -0.0278 5.1051 +0.0167 -0.0333 5.1051 +0.0194 -0.0389 5.1051 +0.0222 -0.0444 5.1051 +0.0250 -0.0500 5.1051 +primID: 1 +startangle_c: 13 +endpose_c: 3 -6 13 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0083 -0.0167 5.1051 +0.0167 -0.0333 5.1051 +0.0250 -0.0500 5.1051 +0.0333 -0.0667 5.1051 +0.0417 -0.0833 5.1051 +0.0500 -0.1000 5.1051 +0.0583 -0.1167 5.1051 +0.0667 -0.1333 5.1051 +0.0750 -0.1500 5.1051 +primID: 2 +startangle_c: 13 +endpose_c: -1 2 13 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 5.1051 +-0.0028 0.0056 5.1051 +-0.0056 0.0111 5.1051 +-0.0083 0.0167 5.1051 +-0.0111 0.0222 5.1051 +-0.0139 0.0278 5.1051 +-0.0167 0.0333 5.1051 +-0.0194 0.0389 5.1051 +-0.0222 0.0444 5.1051 +-0.0250 0.0500 5.1051 +primID: 3 +startangle_c: 13 +endpose_c: 4 -5 14 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0092 -0.0149 5.1354 +0.0189 -0.0296 5.1657 +0.0291 -0.0440 5.1960 +0.0398 -0.0582 5.2263 +0.0509 -0.0722 5.2566 +0.0625 -0.0858 5.2869 +0.0746 -0.0992 5.3172 +0.0871 -0.1123 5.3475 +0.1000 -0.1250 5.3778 +primID: 4 +startangle_c: 13 +endpose_c: 2 -7 12 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0078 -0.0188 5.1051 +0.0156 -0.0377 5.1051 +0.0234 -0.0565 5.1051 +0.0312 -0.0754 5.0860 +0.0379 -0.0946 5.0113 +0.0432 -0.1143 4.9366 +0.0470 -0.1344 4.8618 +0.0492 -0.1546 4.7871 +0.0500 -0.1750 4.7124 +primID: 5 +startangle_c: 13 +endpose_c: 0 0 14 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0000 0.0000 5.1487 +0.0000 0.0000 5.1924 +0.0000 0.0000 5.2360 +0.0000 0.0000 5.2796 +0.0000 0.0000 5.3233 +0.0000 0.0000 5.3669 +0.0000 0.0000 5.4105 +0.0000 0.0000 5.4542 +0.0000 0.0000 5.4978 +primID: 6 +startangle_c: 13 +endpose_c: 0 0 12 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0000 0.0000 5.0615 +0.0000 0.0000 5.0178 +0.0000 0.0000 4.9742 +0.0000 0.0000 4.9306 +0.0000 0.0000 4.8869 +0.0000 0.0000 4.8433 +0.0000 0.0000 4.7997 +0.0000 0.0000 4.7560 +0.0000 0.0000 4.7124 +primID: 0 +startangle_c: 14 +endpose_c: 1 -1 14 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0028 -0.0028 5.4978 +0.0056 -0.0056 5.4978 +0.0083 -0.0083 5.4978 +0.0111 -0.0111 5.4978 +0.0139 -0.0139 5.4978 +0.0167 -0.0167 5.4978 +0.0194 -0.0194 5.4978 +0.0222 -0.0222 5.4978 +0.0250 -0.0250 5.4978 +primID: 1 +startangle_c: 14 +endpose_c: 6 -6 14 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0167 -0.0167 5.4978 +0.0333 -0.0333 5.4978 +0.0500 -0.0500 5.4978 +0.0667 -0.0667 5.4978 +0.0833 -0.0833 5.4978 +0.1000 -0.1000 5.4978 +0.1167 -0.1167 5.4978 +0.1333 -0.1333 5.4978 +0.1500 -0.1500 5.4978 +primID: 2 +startangle_c: 14 +endpose_c: -1 1 14 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 5.4978 +-0.0028 0.0028 5.4978 +-0.0056 0.0056 5.4978 +-0.0083 0.0083 5.4978 +-0.0111 0.0111 5.4978 +-0.0139 0.0139 5.4978 +-0.0167 0.0167 5.4978 +-0.0194 0.0194 5.4978 +-0.0222 0.0222 5.4978 +-0.0250 0.0250 5.4978 +primID: 3 +startangle_c: 14 +endpose_c: 7 -5 15 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0170 -0.0170 5.4978 +0.0342 -0.0339 5.5275 +0.0522 -0.0500 5.5793 +0.0709 -0.0651 5.6312 +0.0904 -0.0792 5.6830 +0.1107 -0.0923 5.7349 +0.1315 -0.1043 5.7868 +0.1530 -0.1152 5.8386 +0.1750 -0.1250 5.8905 +primID: 4 +startangle_c: 14 +endpose_c: 5 -7 13 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0170 -0.0170 5.4978 +0.0339 -0.0342 5.4681 +0.0500 -0.0522 5.4162 +0.0651 -0.0709 5.3644 +0.0792 -0.0904 5.3125 +0.0923 -0.1107 5.2607 +0.1043 -0.1315 5.2088 +0.1152 -0.1530 5.1569 +0.1250 -0.1750 5.1051 +primID: 5 +startangle_c: 14 +endpose_c: 0 0 15 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0000 0.0000 5.5414 +0.0000 0.0000 5.5851 +0.0000 0.0000 5.6287 +0.0000 0.0000 5.6723 +0.0000 0.0000 5.7160 +0.0000 0.0000 5.7596 +0.0000 0.0000 5.8032 +0.0000 0.0000 5.8469 +0.0000 0.0000 5.8905 +primID: 6 +startangle_c: 14 +endpose_c: 0 0 13 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0000 0.0000 5.4542 +0.0000 0.0000 5.4105 +0.0000 0.0000 5.3669 +0.0000 0.0000 5.3233 +0.0000 0.0000 5.2796 +0.0000 0.0000 5.2360 +0.0000 0.0000 5.1924 +0.0000 0.0000 5.1487 +0.0000 0.0000 5.1051 +primID: 0 +startangle_c: 15 +endpose_c: 2 -1 15 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0056 -0.0028 5.8905 +0.0111 -0.0056 5.8905 +0.0167 -0.0083 5.8905 +0.0222 -0.0111 5.8905 +0.0278 -0.0139 5.8905 +0.0333 -0.0167 5.8905 +0.0389 -0.0194 5.8905 +0.0444 -0.0222 5.8905 +0.0500 -0.0250 5.8905 +primID: 1 +startangle_c: 15 +endpose_c: 6 -3 15 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0167 -0.0083 5.8905 +0.0333 -0.0167 5.8905 +0.0500 -0.0250 5.8905 +0.0667 -0.0333 5.8905 +0.0833 -0.0417 5.8905 +0.1000 -0.0500 5.8905 +0.1167 -0.0583 5.8905 +0.1333 -0.0667 5.8905 +0.1500 -0.0750 5.8905 +primID: 2 +startangle_c: 15 +endpose_c: -2 1 15 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 5.8905 +-0.0056 0.0028 5.8905 +-0.0111 0.0056 5.8905 +-0.0167 0.0083 5.8905 +-0.0222 0.0111 5.8905 +-0.0278 0.0139 5.8905 +-0.0333 0.0167 5.8905 +-0.0389 0.0194 5.8905 +-0.0444 0.0222 5.8905 +-0.0500 0.0250 5.8905 +primID: 3 +startangle_c: 15 +endpose_c: 5 -4 14 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0149 -0.0092 5.8602 +0.0296 -0.0189 5.8299 +0.0440 -0.0291 5.7996 +0.0582 -0.0398 5.7693 +0.0722 -0.0509 5.7390 +0.0858 -0.0625 5.7087 +0.0992 -0.0746 5.6784 +0.1123 -0.0871 5.6481 +0.1250 -0.1000 5.6178 +primID: 4 +startangle_c: 15 +endpose_c: 7 -2 0 +additionalactioncostmult: 3 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0188 -0.0078 5.8905 +0.0377 -0.0156 5.8905 +0.0565 -0.0234 5.8905 +0.0754 -0.0312 5.9096 +0.0946 -0.0379 5.9843 +0.1143 -0.0432 6.0590 +0.1344 -0.0470 6.1337 +0.1546 -0.0492 6.2085 +0.1750 -0.0500 6.2832 +primID: 5 +startangle_c: 15 +endpose_c: 0 0 14 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0000 0.0000 5.8469 +0.0000 0.0000 5.8032 +0.0000 0.0000 5.7596 +0.0000 0.0000 5.7160 +0.0000 0.0000 5.6723 +0.0000 0.0000 5.6287 +0.0000 0.0000 5.5851 +0.0000 0.0000 5.5414 +0.0000 0.0000 5.4978 +primID: 6 +startangle_c: 15 +endpose_c: 0 0 0 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0000 0.0000 5.9341 +0.0000 0.0000 5.9778 +0.0000 0.0000 6.0214 +0.0000 0.0000 6.0650 +0.0000 0.0000 6.1087 +0.0000 0.0000 6.1523 +0.0000 0.0000 6.1959 +0.0000 0.0000 6.2396 +0.0000 0.0000 0.0000 diff --git a/navigations/sbpl_lattice_planner/matlab/mprim/unicycle_5cm.mprim b/navigations/sbpl_lattice_planner/matlab/mprim/unicycle_5cm.mprim new file mode 100755 index 0000000..cb56cd0 --- /dev/null +++ b/navigations/sbpl_lattice_planner/matlab/mprim/unicycle_5cm.mprim @@ -0,0 +1,1203 @@ +resolution_m: 0.050000 +numberofangles: 16 +totalnumberofprimitives: 80 +primID: 0 +startangle_c: 0 +endpose_c: 1 0 0 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0056 0.0000 0.0000 +0.0111 0.0000 0.0000 +0.0167 0.0000 0.0000 +0.0222 0.0000 0.0000 +0.0278 0.0000 0.0000 +0.0333 0.0000 0.0000 +0.0389 0.0000 0.0000 +0.0444 0.0000 0.0000 +0.0500 0.0000 0.0000 +primID: 1 +startangle_c: 0 +endpose_c: 8 0 0 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0444 0.0000 0.0000 +0.0889 0.0000 0.0000 +0.1333 0.0000 0.0000 +0.1778 0.0000 0.0000 +0.2222 0.0000 0.0000 +0.2667 0.0000 0.0000 +0.3111 0.0000 0.0000 +0.3556 0.0000 0.0000 +0.4000 0.0000 0.0000 +primID: 2 +startangle_c: 0 +endpose_c: -1 0 0 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 0.0000 +-0.0056 0.0000 0.0000 +-0.0111 0.0000 0.0000 +-0.0167 0.0000 0.0000 +-0.0222 0.0000 0.0000 +-0.0278 0.0000 0.0000 +-0.0333 0.0000 0.0000 +-0.0389 0.0000 0.0000 +-0.0444 0.0000 0.0000 +-0.0500 0.0000 0.0000 +primID: 3 +startangle_c: 0 +endpose_c: 8 1 1 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0452 -0.0000 0.0000 +0.0904 -0.0000 0.0000 +0.1355 -0.0000 0.0000 +0.1807 0.0008 0.0488 +0.2257 0.0045 0.1176 +0.2703 0.0114 0.1864 +0.3144 0.0213 0.2551 +0.3577 0.0342 0.3239 +0.4000 0.0500 0.3927 +primID: 4 +startangle_c: 0 +endpose_c: 8 -1 -1 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0452 0.0000 0.0000 +0.0904 0.0000 0.0000 +0.1355 0.0000 0.0000 +0.1807 -0.0008 -0.0488 +0.2257 -0.0045 -0.1176 +0.2703 -0.0114 -0.1864 +0.3144 -0.0213 -0.2551 +0.3577 -0.0342 -0.3239 +0.4000 -0.0500 -0.3927 +primID: 0 +startangle_c: 1 +endpose_c: 2 1 1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0111 0.0056 0.3927 +0.0222 0.0111 0.3927 +0.0333 0.0167 0.3927 +0.0444 0.0222 0.3927 +0.0556 0.0278 0.3927 +0.0667 0.0333 0.3927 +0.0778 0.0389 0.3927 +0.0889 0.0444 0.3927 +0.1000 0.0500 0.3927 +primID: 1 +startangle_c: 1 +endpose_c: 6 3 1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0333 0.0167 0.3927 +0.0667 0.0333 0.3927 +0.1000 0.0500 0.3927 +0.1333 0.0667 0.3927 +0.1667 0.0833 0.3927 +0.2000 0.1000 0.3927 +0.2333 0.1167 0.3927 +0.2667 0.1333 0.3927 +0.3000 0.1500 0.3927 +primID: 2 +startangle_c: 1 +endpose_c: -2 -1 1 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 0.3927 +-0.0111 -0.0056 0.3927 +-0.0222 -0.0111 0.3927 +-0.0333 -0.0167 0.3927 +-0.0444 -0.0222 0.3927 +-0.0556 -0.0278 0.3927 +-0.0667 -0.0333 0.3927 +-0.0778 -0.0389 0.3927 +-0.0889 -0.0444 0.3927 +-0.1000 -0.0500 0.3927 +primID: 3 +startangle_c: 1 +endpose_c: 5 4 2 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0298 0.0184 0.4230 +0.0592 0.0379 0.4533 +0.0881 0.0583 0.4836 +0.1165 0.0796 0.5139 +0.1444 0.1019 0.5442 +0.1717 0.1251 0.5745 +0.1984 0.1492 0.6048 +0.2245 0.1742 0.6351 +0.2500 0.2000 0.6654 +primID: 4 +startangle_c: 1 +endpose_c: 7 2 0 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0377 0.0156 0.3927 +0.0754 0.0312 0.3927 +0.1131 0.0468 0.3927 +0.1508 0.0623 0.3736 +0.1893 0.0758 0.2989 +0.2287 0.0863 0.2242 +0.2687 0.0939 0.1494 +0.3092 0.0985 0.0747 +0.3500 0.1000 0.0000 +primID: 0 +startangle_c: 2 +endpose_c: 1 1 2 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0056 0.0056 0.7854 +0.0111 0.0111 0.7854 +0.0167 0.0167 0.7854 +0.0222 0.0222 0.7854 +0.0278 0.0278 0.7854 +0.0333 0.0333 0.7854 +0.0389 0.0389 0.7854 +0.0444 0.0444 0.7854 +0.0500 0.0500 0.7854 +primID: 1 +startangle_c: 2 +endpose_c: 6 6 2 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0333 0.0333 0.7854 +0.0667 0.0667 0.7854 +0.1000 0.1000 0.7854 +0.1333 0.1333 0.7854 +0.1667 0.1667 0.7854 +0.2000 0.2000 0.7854 +0.2333 0.2333 0.7854 +0.2667 0.2667 0.7854 +0.3000 0.3000 0.7854 +primID: 2 +startangle_c: 2 +endpose_c: -1 -1 2 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 0.7854 +-0.0056 -0.0056 0.7854 +-0.0111 -0.0111 0.7854 +-0.0167 -0.0167 0.7854 +-0.0222 -0.0222 0.7854 +-0.0278 -0.0278 0.7854 +-0.0333 -0.0333 0.7854 +-0.0389 -0.0389 0.7854 +-0.0444 -0.0444 0.7854 +-0.0500 -0.0500 0.7854 +primID: 3 +startangle_c: 2 +endpose_c: 5 7 3 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0341 0.0341 0.7854 +0.0678 0.0684 0.8151 +0.1000 0.1043 0.8669 +0.1302 0.1418 0.9188 +0.1584 0.1809 0.9707 +0.1846 0.2213 1.0225 +0.2086 0.2631 1.0744 +0.2304 0.3060 1.1262 +0.2500 0.3500 1.1781 +primID: 4 +startangle_c: 2 +endpose_c: 7 5 1 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0341 0.0341 0.7854 +0.0684 0.0678 0.7557 +0.1043 0.1000 0.7039 +0.1418 0.1302 0.6520 +0.1809 0.1584 0.6001 +0.2213 0.1846 0.5483 +0.2631 0.2086 0.4964 +0.3060 0.2304 0.4446 +0.3500 0.2500 0.3927 +primID: 0 +startangle_c: 3 +endpose_c: 1 2 3 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0056 0.0111 1.1781 +0.0111 0.0222 1.1781 +0.0167 0.0333 1.1781 +0.0222 0.0444 1.1781 +0.0278 0.0556 1.1781 +0.0333 0.0667 1.1781 +0.0389 0.0778 1.1781 +0.0444 0.0889 1.1781 +0.0500 0.1000 1.1781 +primID: 1 +startangle_c: 3 +endpose_c: 3 6 3 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0167 0.0333 1.1781 +0.0333 0.0667 1.1781 +0.0500 0.1000 1.1781 +0.0667 0.1333 1.1781 +0.0833 0.1667 1.1781 +0.1000 0.2000 1.1781 +0.1167 0.2333 1.1781 +0.1333 0.2667 1.1781 +0.1500 0.3000 1.1781 +primID: 2 +startangle_c: 3 +endpose_c: -1 -2 3 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 1.1781 +-0.0056 -0.0111 1.1781 +-0.0111 -0.0222 1.1781 +-0.0167 -0.0333 1.1781 +-0.0222 -0.0444 1.1781 +-0.0278 -0.0556 1.1781 +-0.0333 -0.0667 1.1781 +-0.0389 -0.0778 1.1781 +-0.0444 -0.0889 1.1781 +-0.0500 -0.1000 1.1781 +primID: 3 +startangle_c: 3 +endpose_c: 4 5 2 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0184 0.0298 1.1478 +0.0379 0.0592 1.1175 +0.0583 0.0881 1.0872 +0.0796 0.1165 1.0569 +0.1019 0.1444 1.0266 +0.1251 0.1717 0.9963 +0.1492 0.1984 0.9660 +0.1742 0.2245 0.9357 +0.2000 0.2500 0.9054 +primID: 4 +startangle_c: 3 +endpose_c: 2 7 4 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0156 0.0377 1.1781 +0.0312 0.0754 1.1781 +0.0468 0.1131 1.1781 +0.0623 0.1508 1.1972 +0.0758 0.1893 1.2719 +0.0863 0.2287 1.3466 +0.0939 0.2687 1.4214 +0.0985 0.3092 1.4961 +0.1000 0.3500 1.5708 +primID: 0 +startangle_c: 4 +endpose_c: 0 1 4 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0056 1.5708 +0.0000 0.0111 1.5708 +0.0000 0.0167 1.5708 +0.0000 0.0222 1.5708 +0.0000 0.0278 1.5708 +0.0000 0.0333 1.5708 +0.0000 0.0389 1.5708 +0.0000 0.0444 1.5708 +0.0000 0.0500 1.5708 +primID: 1 +startangle_c: 4 +endpose_c: 0 8 4 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0444 1.5708 +0.0000 0.0889 1.5708 +0.0000 0.1333 1.5708 +0.0000 0.1778 1.5708 +0.0000 0.2222 1.5708 +0.0000 0.2667 1.5708 +0.0000 0.3111 1.5708 +0.0000 0.3556 1.5708 +0.0000 0.4000 1.5708 +primID: 2 +startangle_c: 4 +endpose_c: 0 -1 4 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 -0.0056 1.5708 +0.0000 -0.0111 1.5708 +0.0000 -0.0167 1.5708 +0.0000 -0.0222 1.5708 +0.0000 -0.0278 1.5708 +0.0000 -0.0333 1.5708 +0.0000 -0.0389 1.5708 +0.0000 -0.0444 1.5708 +0.0000 -0.0500 1.5708 +primID: 3 +startangle_c: 4 +endpose_c: -1 8 5 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0452 1.5708 +0.0000 0.0904 1.5708 +0.0000 0.1355 1.5708 +-0.0008 0.1807 1.6196 +-0.0045 0.2257 1.6884 +-0.0114 0.2703 1.7572 +-0.0213 0.3144 1.8259 +-0.0342 0.3577 1.8947 +-0.0500 0.4000 1.9635 +primID: 4 +startangle_c: 4 +endpose_c: 1 8 3 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.5708 +-0.0000 0.0452 1.5708 +-0.0000 0.0904 1.5708 +-0.0000 0.1355 1.5708 +0.0008 0.1807 1.5220 +0.0045 0.2257 1.4532 +0.0114 0.2703 1.3844 +0.0213 0.3144 1.3156 +0.0342 0.3577 1.2469 +0.0500 0.4000 1.1781 +primID: 0 +startangle_c: 5 +endpose_c: -1 2 5 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0056 0.0111 1.9635 +-0.0111 0.0222 1.9635 +-0.0167 0.0333 1.9635 +-0.0222 0.0444 1.9635 +-0.0278 0.0556 1.9635 +-0.0333 0.0667 1.9635 +-0.0389 0.0778 1.9635 +-0.0444 0.0889 1.9635 +-0.0500 0.1000 1.9635 +primID: 1 +startangle_c: 5 +endpose_c: -3 6 5 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0167 0.0333 1.9635 +-0.0333 0.0667 1.9635 +-0.0500 0.1000 1.9635 +-0.0667 0.1333 1.9635 +-0.0833 0.1667 1.9635 +-0.1000 0.2000 1.9635 +-0.1167 0.2333 1.9635 +-0.1333 0.2667 1.9635 +-0.1500 0.3000 1.9635 +primID: 2 +startangle_c: 5 +endpose_c: 1 -2 5 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0056 -0.0111 1.9635 +0.0111 -0.0222 1.9635 +0.0167 -0.0333 1.9635 +0.0222 -0.0444 1.9635 +0.0278 -0.0556 1.9635 +0.0333 -0.0667 1.9635 +0.0389 -0.0778 1.9635 +0.0444 -0.0889 1.9635 +0.0500 -0.1000 1.9635 +primID: 3 +startangle_c: 5 +endpose_c: -4 5 6 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0184 0.0298 1.9938 +-0.0379 0.0592 2.0241 +-0.0583 0.0881 2.0544 +-0.0796 0.1165 2.0847 +-0.1019 0.1444 2.1150 +-0.1251 0.1717 2.1453 +-0.1492 0.1984 2.1756 +-0.1742 0.2245 2.2059 +-0.2000 0.2500 2.2362 +primID: 4 +startangle_c: 5 +endpose_c: -2 7 4 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0156 0.0377 1.9635 +-0.0312 0.0754 1.9635 +-0.0468 0.1131 1.9635 +-0.0623 0.1508 1.9444 +-0.0758 0.1893 1.8697 +-0.0863 0.2287 1.7950 +-0.0939 0.2687 1.7202 +-0.0985 0.3092 1.6455 +-0.1000 0.3500 1.5708 +primID: 0 +startangle_c: 6 +endpose_c: -1 1 6 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0056 0.0056 2.3562 +-0.0111 0.0111 2.3562 +-0.0167 0.0167 2.3562 +-0.0222 0.0222 2.3562 +-0.0278 0.0278 2.3562 +-0.0333 0.0333 2.3562 +-0.0389 0.0389 2.3562 +-0.0444 0.0444 2.3562 +-0.0500 0.0500 2.3562 +primID: 1 +startangle_c: 6 +endpose_c: -6 6 6 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0333 0.0333 2.3562 +-0.0667 0.0667 2.3562 +-0.1000 0.1000 2.3562 +-0.1333 0.1333 2.3562 +-0.1667 0.1667 2.3562 +-0.2000 0.2000 2.3562 +-0.2333 0.2333 2.3562 +-0.2667 0.2667 2.3562 +-0.3000 0.3000 2.3562 +primID: 2 +startangle_c: 6 +endpose_c: 1 -1 6 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0056 -0.0056 2.3562 +0.0111 -0.0111 2.3562 +0.0167 -0.0167 2.3562 +0.0222 -0.0222 2.3562 +0.0278 -0.0278 2.3562 +0.0333 -0.0333 2.3562 +0.0389 -0.0389 2.3562 +0.0444 -0.0444 2.3562 +0.0500 -0.0500 2.3562 +primID: 3 +startangle_c: 6 +endpose_c: -7 5 7 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0341 0.0341 2.3562 +-0.0684 0.0678 2.3859 +-0.1043 0.1000 2.4377 +-0.1418 0.1302 2.4896 +-0.1809 0.1584 2.5415 +-0.2213 0.1846 2.5933 +-0.2631 0.2086 2.6452 +-0.3060 0.2304 2.6970 +-0.3500 0.2500 2.7489 +primID: 4 +startangle_c: 6 +endpose_c: -5 7 5 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0341 0.0341 2.3562 +-0.0678 0.0684 2.3265 +-0.1000 0.1043 2.2747 +-0.1302 0.1418 2.2228 +-0.1584 0.1809 2.1709 +-0.1846 0.2213 2.1191 +-0.2086 0.2631 2.0672 +-0.2304 0.3060 2.0154 +-0.2500 0.3500 1.9635 +primID: 0 +startangle_c: 7 +endpose_c: -2 1 7 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0111 0.0056 2.7489 +-0.0222 0.0111 2.7489 +-0.0333 0.0167 2.7489 +-0.0444 0.0222 2.7489 +-0.0556 0.0278 2.7489 +-0.0667 0.0333 2.7489 +-0.0778 0.0389 2.7489 +-0.0889 0.0444 2.7489 +-0.1000 0.0500 2.7489 +primID: 1 +startangle_c: 7 +endpose_c: -6 3 7 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0333 0.0167 2.7489 +-0.0667 0.0333 2.7489 +-0.1000 0.0500 2.7489 +-0.1333 0.0667 2.7489 +-0.1667 0.0833 2.7489 +-0.2000 0.1000 2.7489 +-0.2333 0.1167 2.7489 +-0.2667 0.1333 2.7489 +-0.3000 0.1500 2.7489 +primID: 2 +startangle_c: 7 +endpose_c: 2 -1 7 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0111 -0.0056 2.7489 +0.0222 -0.0111 2.7489 +0.0333 -0.0167 2.7489 +0.0444 -0.0222 2.7489 +0.0556 -0.0278 2.7489 +0.0667 -0.0333 2.7489 +0.0778 -0.0389 2.7489 +0.0889 -0.0444 2.7489 +0.1000 -0.0500 2.7489 +primID: 3 +startangle_c: 7 +endpose_c: -5 4 6 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0298 0.0184 2.7186 +-0.0592 0.0379 2.6883 +-0.0881 0.0583 2.6580 +-0.1165 0.0796 2.6277 +-0.1444 0.1019 2.5974 +-0.1717 0.1251 2.5671 +-0.1984 0.1492 2.5368 +-0.2245 0.1742 2.5065 +-0.2500 0.2000 2.4762 +primID: 4 +startangle_c: 7 +endpose_c: -7 2 8 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0377 0.0156 2.7489 +-0.0754 0.0312 2.7489 +-0.1131 0.0468 2.7489 +-0.1508 0.0623 2.7680 +-0.1893 0.0758 2.8427 +-0.2287 0.0863 2.9174 +-0.2687 0.0939 2.9921 +-0.3092 0.0985 3.0669 +-0.3500 0.1000 3.1416 +primID: 0 +startangle_c: 8 +endpose_c: -1 0 8 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0056 0.0000 3.1416 +-0.0111 0.0000 3.1416 +-0.0167 0.0000 3.1416 +-0.0222 0.0000 3.1416 +-0.0278 0.0000 3.1416 +-0.0333 0.0000 3.1416 +-0.0389 0.0000 3.1416 +-0.0444 0.0000 3.1416 +-0.0500 0.0000 3.1416 +primID: 1 +startangle_c: 8 +endpose_c: -8 0 8 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0444 0.0000 3.1416 +-0.0889 0.0000 3.1416 +-0.1333 0.0000 3.1416 +-0.1778 0.0000 3.1416 +-0.2222 0.0000 3.1416 +-0.2667 0.0000 3.1416 +-0.3111 0.0000 3.1416 +-0.3556 0.0000 3.1416 +-0.4000 0.0000 3.1416 +primID: 2 +startangle_c: 8 +endpose_c: 1 0 8 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0056 0.0000 3.1416 +0.0111 0.0000 3.1416 +0.0167 0.0000 3.1416 +0.0222 0.0000 3.1416 +0.0278 0.0000 3.1416 +0.0333 0.0000 3.1416 +0.0389 0.0000 3.1416 +0.0444 0.0000 3.1416 +0.0500 0.0000 3.1416 +primID: 3 +startangle_c: 8 +endpose_c: -8 -1 9 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0452 0.0000 3.1416 +-0.0904 0.0000 3.1416 +-0.1355 0.0000 3.1416 +-0.1807 -0.0008 3.1904 +-0.2257 -0.0045 3.2592 +-0.2703 -0.0114 3.3280 +-0.3144 -0.0213 3.3967 +-0.3577 -0.0342 3.4655 +-0.4000 -0.0500 3.5343 +primID: 4 +startangle_c: 8 +endpose_c: -8 1 7 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0452 0.0000 3.1416 +-0.0904 0.0000 3.1416 +-0.1355 0.0000 3.1416 +-0.1807 0.0008 3.0928 +-0.2257 0.0045 3.0240 +-0.2703 0.0114 2.9552 +-0.3144 0.0213 2.8864 +-0.3577 0.0342 2.8177 +-0.4000 0.0500 2.7489 +primID: 0 +startangle_c: 9 +endpose_c: -2 -1 9 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0111 -0.0056 3.5343 +-0.0222 -0.0111 3.5343 +-0.0333 -0.0167 3.5343 +-0.0444 -0.0222 3.5343 +-0.0556 -0.0278 3.5343 +-0.0667 -0.0333 3.5343 +-0.0778 -0.0389 3.5343 +-0.0889 -0.0444 3.5343 +-0.1000 -0.0500 3.5343 +primID: 1 +startangle_c: 9 +endpose_c: -6 -3 9 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0333 -0.0167 3.5343 +-0.0667 -0.0333 3.5343 +-0.1000 -0.0500 3.5343 +-0.1333 -0.0667 3.5343 +-0.1667 -0.0833 3.5343 +-0.2000 -0.1000 3.5343 +-0.2333 -0.1167 3.5343 +-0.2667 -0.1333 3.5343 +-0.3000 -0.1500 3.5343 +primID: 2 +startangle_c: 9 +endpose_c: 2 1 9 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0111 0.0056 3.5343 +0.0222 0.0111 3.5343 +0.0333 0.0167 3.5343 +0.0444 0.0222 3.5343 +0.0556 0.0278 3.5343 +0.0667 0.0333 3.5343 +0.0778 0.0389 3.5343 +0.0889 0.0444 3.5343 +0.1000 0.0500 3.5343 +primID: 3 +startangle_c: 9 +endpose_c: -5 -4 10 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0298 -0.0184 3.5646 +-0.0592 -0.0379 3.5949 +-0.0881 -0.0583 3.6252 +-0.1165 -0.0796 3.6555 +-0.1444 -0.1019 3.6858 +-0.1717 -0.1251 3.7161 +-0.1984 -0.1492 3.7464 +-0.2245 -0.1742 3.7767 +-0.2500 -0.2000 3.8070 +primID: 4 +startangle_c: 9 +endpose_c: -7 -2 8 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0377 -0.0156 3.5343 +-0.0754 -0.0312 3.5343 +-0.1131 -0.0468 3.5343 +-0.1508 -0.0623 3.5152 +-0.1893 -0.0758 3.4405 +-0.2287 -0.0863 3.3658 +-0.2687 -0.0939 3.2910 +-0.3092 -0.0985 3.2163 +-0.3500 -0.1000 3.1416 +primID: 0 +startangle_c: 10 +endpose_c: -1 -1 10 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0056 -0.0056 3.9270 +-0.0111 -0.0111 3.9270 +-0.0167 -0.0167 3.9270 +-0.0222 -0.0222 3.9270 +-0.0278 -0.0278 3.9270 +-0.0333 -0.0333 3.9270 +-0.0389 -0.0389 3.9270 +-0.0444 -0.0444 3.9270 +-0.0500 -0.0500 3.9270 +primID: 1 +startangle_c: 10 +endpose_c: -6 -6 10 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0333 -0.0333 3.9270 +-0.0667 -0.0667 3.9270 +-0.1000 -0.1000 3.9270 +-0.1333 -0.1333 3.9270 +-0.1667 -0.1667 3.9270 +-0.2000 -0.2000 3.9270 +-0.2333 -0.2333 3.9270 +-0.2667 -0.2667 3.9270 +-0.3000 -0.3000 3.9270 +primID: 2 +startangle_c: 10 +endpose_c: 1 1 10 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0056 0.0056 3.9270 +0.0111 0.0111 3.9270 +0.0167 0.0167 3.9270 +0.0222 0.0222 3.9270 +0.0278 0.0278 3.9270 +0.0333 0.0333 3.9270 +0.0389 0.0389 3.9270 +0.0444 0.0444 3.9270 +0.0500 0.0500 3.9270 +primID: 3 +startangle_c: 10 +endpose_c: -5 -7 11 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0341 -0.0341 3.9270 +-0.0678 -0.0684 3.9567 +-0.1000 -0.1043 4.0085 +-0.1302 -0.1418 4.0604 +-0.1584 -0.1809 4.1123 +-0.1846 -0.2213 4.1641 +-0.2086 -0.2631 4.2160 +-0.2304 -0.3060 4.2678 +-0.2500 -0.3500 4.3197 +primID: 4 +startangle_c: 10 +endpose_c: -7 -5 9 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0341 -0.0341 3.9270 +-0.0684 -0.0678 3.8973 +-0.1043 -0.1000 3.8455 +-0.1418 -0.1302 3.7936 +-0.1809 -0.1584 3.7417 +-0.2213 -0.1846 3.6899 +-0.2631 -0.2086 3.6380 +-0.3060 -0.2304 3.5862 +-0.3500 -0.2500 3.5343 +primID: 0 +startangle_c: 11 +endpose_c: -1 -2 11 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0056 -0.0111 4.3197 +-0.0111 -0.0222 4.3197 +-0.0167 -0.0333 4.3197 +-0.0222 -0.0444 4.3197 +-0.0278 -0.0556 4.3197 +-0.0333 -0.0667 4.3197 +-0.0389 -0.0778 4.3197 +-0.0444 -0.0889 4.3197 +-0.0500 -0.1000 4.3197 +primID: 1 +startangle_c: 11 +endpose_c: -3 -6 11 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0167 -0.0333 4.3197 +-0.0333 -0.0667 4.3197 +-0.0500 -0.1000 4.3197 +-0.0667 -0.1333 4.3197 +-0.0833 -0.1667 4.3197 +-0.1000 -0.2000 4.3197 +-0.1167 -0.2333 4.3197 +-0.1333 -0.2667 4.3197 +-0.1500 -0.3000 4.3197 +primID: 2 +startangle_c: 11 +endpose_c: 1 2 11 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0056 0.0111 4.3197 +0.0111 0.0222 4.3197 +0.0167 0.0333 4.3197 +0.0222 0.0444 4.3197 +0.0278 0.0556 4.3197 +0.0333 0.0667 4.3197 +0.0389 0.0778 4.3197 +0.0444 0.0889 4.3197 +0.0500 0.1000 4.3197 +primID: 3 +startangle_c: 11 +endpose_c: -4 -5 10 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0184 -0.0298 4.2894 +-0.0379 -0.0592 4.2591 +-0.0583 -0.0881 4.2288 +-0.0796 -0.1165 4.1985 +-0.1019 -0.1444 4.1682 +-0.1251 -0.1717 4.1379 +-0.1492 -0.1984 4.1076 +-0.1742 -0.2245 4.0773 +-0.2000 -0.2500 4.0470 +primID: 4 +startangle_c: 11 +endpose_c: -2 -7 12 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0156 -0.0377 4.3197 +-0.0312 -0.0754 4.3197 +-0.0468 -0.1131 4.3197 +-0.0623 -0.1508 4.3388 +-0.0758 -0.1893 4.4135 +-0.0863 -0.2287 4.4882 +-0.0939 -0.2687 4.5629 +-0.0985 -0.3092 4.6377 +-0.1000 -0.3500 4.7124 +primID: 0 +startangle_c: 12 +endpose_c: 0 -1 12 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0056 4.7124 +0.0000 -0.0111 4.7124 +0.0000 -0.0167 4.7124 +0.0000 -0.0222 4.7124 +0.0000 -0.0278 4.7124 +0.0000 -0.0333 4.7124 +0.0000 -0.0389 4.7124 +0.0000 -0.0444 4.7124 +0.0000 -0.0500 4.7124 +primID: 1 +startangle_c: 12 +endpose_c: 0 -8 12 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0444 4.7124 +0.0000 -0.0889 4.7124 +0.0000 -0.1333 4.7124 +0.0000 -0.1778 4.7124 +0.0000 -0.2222 4.7124 +0.0000 -0.2667 4.7124 +0.0000 -0.3111 4.7124 +0.0000 -0.3556 4.7124 +0.0000 -0.4000 4.7124 +primID: 2 +startangle_c: 12 +endpose_c: 0 1 12 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0056 4.7124 +0.0000 0.0111 4.7124 +0.0000 0.0167 4.7124 +0.0000 0.0222 4.7124 +0.0000 0.0278 4.7124 +0.0000 0.0333 4.7124 +0.0000 0.0389 4.7124 +0.0000 0.0444 4.7124 +0.0000 0.0500 4.7124 +primID: 3 +startangle_c: 12 +endpose_c: 1 -8 13 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 4.7124 +-0.0000 -0.0452 4.7124 +-0.0000 -0.0904 4.7124 +-0.0000 -0.1355 4.7124 +0.0008 -0.1807 4.7612 +0.0045 -0.2257 4.8300 +0.0114 -0.2703 4.8988 +0.0213 -0.3144 4.9675 +0.0342 -0.3577 5.0363 +0.0500 -0.4000 5.1051 +primID: 4 +startangle_c: 12 +endpose_c: -1 -8 11 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 4.7124 +-0.0000 -0.0452 4.7124 +-0.0000 -0.0904 4.7124 +-0.0000 -0.1355 4.7124 +-0.0008 -0.1807 4.6636 +-0.0045 -0.2257 4.5948 +-0.0114 -0.2703 4.5260 +-0.0213 -0.3144 4.4572 +-0.0342 -0.3577 4.3885 +-0.0500 -0.4000 4.3197 +primID: 0 +startangle_c: 13 +endpose_c: 1 -2 13 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0056 -0.0111 5.1051 +0.0111 -0.0222 5.1051 +0.0167 -0.0333 5.1051 +0.0222 -0.0444 5.1051 +0.0278 -0.0556 5.1051 +0.0333 -0.0667 5.1051 +0.0389 -0.0778 5.1051 +0.0444 -0.0889 5.1051 +0.0500 -0.1000 5.1051 +primID: 1 +startangle_c: 13 +endpose_c: 3 -6 13 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0167 -0.0333 5.1051 +0.0333 -0.0667 5.1051 +0.0500 -0.1000 5.1051 +0.0667 -0.1333 5.1051 +0.0833 -0.1667 5.1051 +0.1000 -0.2000 5.1051 +0.1167 -0.2333 5.1051 +0.1333 -0.2667 5.1051 +0.1500 -0.3000 5.1051 +primID: 2 +startangle_c: 13 +endpose_c: -1 2 13 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 5.1051 +-0.0056 0.0111 5.1051 +-0.0111 0.0222 5.1051 +-0.0167 0.0333 5.1051 +-0.0222 0.0444 5.1051 +-0.0278 0.0556 5.1051 +-0.0333 0.0667 5.1051 +-0.0389 0.0778 5.1051 +-0.0444 0.0889 5.1051 +-0.0500 0.1000 5.1051 +primID: 3 +startangle_c: 13 +endpose_c: 4 -5 14 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0184 -0.0298 5.1354 +0.0379 -0.0592 5.1657 +0.0583 -0.0881 5.1960 +0.0796 -0.1165 5.2263 +0.1019 -0.1444 5.2566 +0.1251 -0.1717 5.2869 +0.1492 -0.1984 5.3172 +0.1742 -0.2245 5.3475 +0.2000 -0.2500 5.3778 +primID: 4 +startangle_c: 13 +endpose_c: 2 -7 12 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0156 -0.0377 5.1051 +0.0312 -0.0754 5.1051 +0.0468 -0.1131 5.1051 +0.0623 -0.1508 5.0860 +0.0758 -0.1893 5.0113 +0.0863 -0.2287 4.9366 +0.0939 -0.2687 4.8618 +0.0985 -0.3092 4.7871 +0.1000 -0.3500 4.7124 +primID: 0 +startangle_c: 14 +endpose_c: 1 -1 14 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0056 -0.0056 5.4978 +0.0111 -0.0111 5.4978 +0.0167 -0.0167 5.4978 +0.0222 -0.0222 5.4978 +0.0278 -0.0278 5.4978 +0.0333 -0.0333 5.4978 +0.0389 -0.0389 5.4978 +0.0444 -0.0444 5.4978 +0.0500 -0.0500 5.4978 +primID: 1 +startangle_c: 14 +endpose_c: 6 -6 14 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0333 -0.0333 5.4978 +0.0667 -0.0667 5.4978 +0.1000 -0.1000 5.4978 +0.1333 -0.1333 5.4978 +0.1667 -0.1667 5.4978 +0.2000 -0.2000 5.4978 +0.2333 -0.2333 5.4978 +0.2667 -0.2667 5.4978 +0.3000 -0.3000 5.4978 +primID: 2 +startangle_c: 14 +endpose_c: -1 1 14 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 5.4978 +-0.0056 0.0056 5.4978 +-0.0111 0.0111 5.4978 +-0.0167 0.0167 5.4978 +-0.0222 0.0222 5.4978 +-0.0278 0.0278 5.4978 +-0.0333 0.0333 5.4978 +-0.0389 0.0389 5.4978 +-0.0444 0.0444 5.4978 +-0.0500 0.0500 5.4978 +primID: 3 +startangle_c: 14 +endpose_c: 7 -5 15 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0341 -0.0341 5.4978 +0.0684 -0.0678 5.5275 +0.1043 -0.1000 5.5793 +0.1418 -0.1302 5.6312 +0.1809 -0.1584 5.6830 +0.2213 -0.1846 5.7349 +0.2631 -0.2086 5.7868 +0.3060 -0.2304 5.8386 +0.3500 -0.2500 5.8905 +primID: 4 +startangle_c: 14 +endpose_c: 5 -7 13 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0341 -0.0341 5.4978 +0.0678 -0.0684 5.4681 +0.1000 -0.1043 5.4162 +0.1302 -0.1418 5.3644 +0.1584 -0.1809 5.3125 +0.1846 -0.2213 5.2607 +0.2086 -0.2631 5.2088 +0.2304 -0.3060 5.1569 +0.2500 -0.3500 5.1051 +primID: 0 +startangle_c: 15 +endpose_c: 2 -1 15 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0111 -0.0056 5.8905 +0.0222 -0.0111 5.8905 +0.0333 -0.0167 5.8905 +0.0444 -0.0222 5.8905 +0.0556 -0.0278 5.8905 +0.0667 -0.0333 5.8905 +0.0778 -0.0389 5.8905 +0.0889 -0.0444 5.8905 +0.1000 -0.0500 5.8905 +primID: 1 +startangle_c: 15 +endpose_c: 6 -3 15 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0333 -0.0167 5.8905 +0.0667 -0.0333 5.8905 +0.1000 -0.0500 5.8905 +0.1333 -0.0667 5.8905 +0.1667 -0.0833 5.8905 +0.2000 -0.1000 5.8905 +0.2333 -0.1167 5.8905 +0.2667 -0.1333 5.8905 +0.3000 -0.1500 5.8905 +primID: 2 +startangle_c: 15 +endpose_c: -2 1 15 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 5.8905 +-0.0111 0.0056 5.8905 +-0.0222 0.0111 5.8905 +-0.0333 0.0167 5.8905 +-0.0444 0.0222 5.8905 +-0.0556 0.0278 5.8905 +-0.0667 0.0333 5.8905 +-0.0778 0.0389 5.8905 +-0.0889 0.0444 5.8905 +-0.1000 0.0500 5.8905 +primID: 3 +startangle_c: 15 +endpose_c: 5 -4 14 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0298 -0.0184 5.8602 +0.0592 -0.0379 5.8299 +0.0881 -0.0583 5.7996 +0.1165 -0.0796 5.7693 +0.1444 -0.1019 5.7390 +0.1717 -0.1251 5.7087 +0.1984 -0.1492 5.6784 +0.2245 -0.1742 5.6481 +0.2500 -0.2000 5.6178 +primID: 4 +startangle_c: 15 +endpose_c: 7 -2 0 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0377 -0.0156 5.8905 +0.0754 -0.0312 5.8905 +0.1131 -0.0468 5.8905 +0.1508 -0.0623 5.9096 +0.1893 -0.0758 5.9843 +0.2287 -0.0863 6.0590 +0.2687 -0.0939 6.1337 +0.3092 -0.0985 6.2085 +0.3500 -0.1000 6.2832 diff --git a/navigations/sbpl_lattice_planner/matlab/mprim/unicycle_5cm_expensive_turn_in_place.mprim b/navigations/sbpl_lattice_planner/matlab/mprim/unicycle_5cm_expensive_turn_in_place.mprim new file mode 100755 index 0000000..f27907b --- /dev/null +++ b/navigations/sbpl_lattice_planner/matlab/mprim/unicycle_5cm_expensive_turn_in_place.mprim @@ -0,0 +1,1683 @@ +resolution_m: 0.050000 +numberofangles: 16 +totalnumberofprimitives: 112 +primID: 0 +startangle_c: 0 +endpose_c: 1 0 0 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0056 0.0000 0.0000 +0.0111 0.0000 0.0000 +0.0167 0.0000 0.0000 +0.0222 0.0000 0.0000 +0.0278 0.0000 0.0000 +0.0333 0.0000 0.0000 +0.0389 0.0000 0.0000 +0.0444 0.0000 0.0000 +0.0500 0.0000 0.0000 +primID: 1 +startangle_c: 0 +endpose_c: 8 0 0 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0444 0.0000 0.0000 +0.0889 0.0000 0.0000 +0.1333 0.0000 0.0000 +0.1778 0.0000 0.0000 +0.2222 0.0000 0.0000 +0.2667 0.0000 0.0000 +0.3111 0.0000 0.0000 +0.3556 0.0000 0.0000 +0.4000 0.0000 0.0000 +primID: 2 +startangle_c: 0 +endpose_c: -1 0 0 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 0.0000 +-0.0056 0.0000 0.0000 +-0.0111 0.0000 0.0000 +-0.0167 0.0000 0.0000 +-0.0222 0.0000 0.0000 +-0.0278 0.0000 0.0000 +-0.0333 0.0000 0.0000 +-0.0389 0.0000 0.0000 +-0.0444 0.0000 0.0000 +-0.0500 0.0000 0.0000 +primID: 3 +startangle_c: 0 +endpose_c: 8 1 1 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0452 -0.0000 0.0000 +0.0904 -0.0000 0.0000 +0.1355 -0.0000 0.0000 +0.1807 0.0008 0.0488 +0.2257 0.0045 0.1176 +0.2703 0.0114 0.1864 +0.3144 0.0213 0.2551 +0.3577 0.0342 0.3239 +0.4000 0.0500 0.3927 +primID: 4 +startangle_c: 0 +endpose_c: 8 -1 -1 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0452 0.0000 0.0000 +0.0904 0.0000 0.0000 +0.1355 0.0000 0.0000 +0.1807 -0.0008 -0.0488 +0.2257 -0.0045 -0.1176 +0.2703 -0.0114 -0.1864 +0.3144 -0.0213 -0.2551 +0.3577 -0.0342 -0.3239 +0.4000 -0.0500 -0.3927 +primID: 5 +startangle_c: 0 +endpose_c: 0 0 1 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0000 0.0000 0.0436 +0.0000 0.0000 0.0873 +0.0000 0.0000 0.1309 +0.0000 0.0000 0.1745 +0.0000 0.0000 0.2182 +0.0000 0.0000 0.2618 +0.0000 0.0000 0.3054 +0.0000 0.0000 0.3491 +0.0000 0.0000 0.3927 +primID: 6 +startangle_c: 0 +endpose_c: 0 0 -1 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0000 0.0000 -0.0436 +0.0000 0.0000 -0.0873 +0.0000 0.0000 -0.1309 +0.0000 0.0000 -0.1745 +0.0000 0.0000 -0.2182 +0.0000 0.0000 -0.2618 +0.0000 0.0000 -0.3054 +0.0000 0.0000 -0.3491 +0.0000 0.0000 -0.3927 +primID: 0 +startangle_c: 1 +endpose_c: 2 1 1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0111 0.0056 0.3927 +0.0222 0.0111 0.3927 +0.0333 0.0167 0.3927 +0.0444 0.0222 0.3927 +0.0556 0.0278 0.3927 +0.0667 0.0333 0.3927 +0.0778 0.0389 0.3927 +0.0889 0.0444 0.3927 +0.1000 0.0500 0.3927 +primID: 1 +startangle_c: 1 +endpose_c: 6 3 1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0333 0.0167 0.3927 +0.0667 0.0333 0.3927 +0.1000 0.0500 0.3927 +0.1333 0.0667 0.3927 +0.1667 0.0833 0.3927 +0.2000 0.1000 0.3927 +0.2333 0.1167 0.3927 +0.2667 0.1333 0.3927 +0.3000 0.1500 0.3927 +primID: 2 +startangle_c: 1 +endpose_c: -2 -1 1 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 0.3927 +-0.0111 -0.0056 0.3927 +-0.0222 -0.0111 0.3927 +-0.0333 -0.0167 0.3927 +-0.0444 -0.0222 0.3927 +-0.0556 -0.0278 0.3927 +-0.0667 -0.0333 0.3927 +-0.0778 -0.0389 0.3927 +-0.0889 -0.0444 0.3927 +-0.1000 -0.0500 0.3927 +primID: 3 +startangle_c: 1 +endpose_c: 5 4 2 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0298 0.0184 0.4230 +0.0592 0.0379 0.4533 +0.0881 0.0583 0.4836 +0.1165 0.0796 0.5139 +0.1444 0.1019 0.5442 +0.1717 0.1251 0.5745 +0.1984 0.1492 0.6048 +0.2245 0.1742 0.6351 +0.2500 0.2000 0.6654 +primID: 4 +startangle_c: 1 +endpose_c: 7 2 0 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0377 0.0156 0.3927 +0.0754 0.0312 0.3927 +0.1131 0.0468 0.3927 +0.1508 0.0623 0.3736 +0.1893 0.0758 0.2989 +0.2287 0.0863 0.2242 +0.2687 0.0939 0.1494 +0.3092 0.0985 0.0747 +0.3500 0.1000 -0.0000 +primID: 5 +startangle_c: 1 +endpose_c: 0 0 2 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0000 0.0000 0.4363 +0.0000 0.0000 0.4800 +0.0000 0.0000 0.5236 +0.0000 0.0000 0.5672 +0.0000 0.0000 0.6109 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.6981 +0.0000 0.0000 0.7418 +0.0000 0.0000 0.7854 +primID: 6 +startangle_c: 1 +endpose_c: 0 0 0 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0000 0.0000 0.3491 +0.0000 0.0000 0.3054 +0.0000 0.0000 0.2618 +0.0000 0.0000 0.2182 +0.0000 0.0000 0.1745 +0.0000 0.0000 0.1309 +0.0000 0.0000 0.0873 +0.0000 0.0000 0.0436 +0.0000 0.0000 0.0000 +primID: 0 +startangle_c: 2 +endpose_c: 1 1 2 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0056 0.0056 0.7854 +0.0111 0.0111 0.7854 +0.0167 0.0167 0.7854 +0.0222 0.0222 0.7854 +0.0278 0.0278 0.7854 +0.0333 0.0333 0.7854 +0.0389 0.0389 0.7854 +0.0444 0.0444 0.7854 +0.0500 0.0500 0.7854 +primID: 1 +startangle_c: 2 +endpose_c: 6 6 2 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0333 0.0333 0.7854 +0.0667 0.0667 0.7854 +0.1000 0.1000 0.7854 +0.1333 0.1333 0.7854 +0.1667 0.1667 0.7854 +0.2000 0.2000 0.7854 +0.2333 0.2333 0.7854 +0.2667 0.2667 0.7854 +0.3000 0.3000 0.7854 +primID: 2 +startangle_c: 2 +endpose_c: -1 -1 2 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 0.7854 +-0.0056 -0.0056 0.7854 +-0.0111 -0.0111 0.7854 +-0.0167 -0.0167 0.7854 +-0.0222 -0.0222 0.7854 +-0.0278 -0.0278 0.7854 +-0.0333 -0.0333 0.7854 +-0.0389 -0.0389 0.7854 +-0.0444 -0.0444 0.7854 +-0.0500 -0.0500 0.7854 +primID: 3 +startangle_c: 2 +endpose_c: 5 7 3 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0341 0.0341 0.7854 +0.0678 0.0684 0.8151 +0.1000 0.1043 0.8669 +0.1302 0.1418 0.9188 +0.1584 0.1809 0.9707 +0.1846 0.2213 1.0225 +0.2086 0.2631 1.0744 +0.2304 0.3060 1.1262 +0.2500 0.3500 1.1781 +primID: 4 +startangle_c: 2 +endpose_c: 7 5 1 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0341 0.0341 0.7854 +0.0684 0.0678 0.7557 +0.1043 0.1000 0.7039 +0.1418 0.1302 0.6520 +0.1809 0.1584 0.6001 +0.2213 0.1846 0.5483 +0.2631 0.2086 0.4964 +0.3060 0.2304 0.4446 +0.3500 0.2500 0.3927 +primID: 5 +startangle_c: 2 +endpose_c: 0 0 3 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0000 0.0000 0.8290 +0.0000 0.0000 0.8727 +0.0000 0.0000 0.9163 +0.0000 0.0000 0.9599 +0.0000 0.0000 1.0036 +0.0000 0.0000 1.0472 +0.0000 0.0000 1.0908 +0.0000 0.0000 1.1345 +0.0000 0.0000 1.1781 +primID: 6 +startangle_c: 2 +endpose_c: 0 0 1 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0000 0.0000 0.7418 +0.0000 0.0000 0.6981 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.6109 +0.0000 0.0000 0.5672 +0.0000 0.0000 0.5236 +0.0000 0.0000 0.4800 +0.0000 0.0000 0.4363 +0.0000 0.0000 0.3927 +primID: 0 +startangle_c: 3 +endpose_c: 1 2 3 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0056 0.0111 1.1781 +0.0111 0.0222 1.1781 +0.0167 0.0333 1.1781 +0.0222 0.0444 1.1781 +0.0278 0.0556 1.1781 +0.0333 0.0667 1.1781 +0.0389 0.0778 1.1781 +0.0444 0.0889 1.1781 +0.0500 0.1000 1.1781 +primID: 1 +startangle_c: 3 +endpose_c: 3 6 3 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0167 0.0333 1.1781 +0.0333 0.0667 1.1781 +0.0500 0.1000 1.1781 +0.0667 0.1333 1.1781 +0.0833 0.1667 1.1781 +0.1000 0.2000 1.1781 +0.1167 0.2333 1.1781 +0.1333 0.2667 1.1781 +0.1500 0.3000 1.1781 +primID: 2 +startangle_c: 3 +endpose_c: -1 -2 3 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 1.1781 +-0.0056 -0.0111 1.1781 +-0.0111 -0.0222 1.1781 +-0.0167 -0.0333 1.1781 +-0.0222 -0.0444 1.1781 +-0.0278 -0.0556 1.1781 +-0.0333 -0.0667 1.1781 +-0.0389 -0.0778 1.1781 +-0.0444 -0.0889 1.1781 +-0.0500 -0.1000 1.1781 +primID: 3 +startangle_c: 3 +endpose_c: 4 5 2 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0184 0.0298 1.1478 +0.0379 0.0592 1.1175 +0.0583 0.0881 1.0872 +0.0796 0.1165 1.0569 +0.1019 0.1444 1.0266 +0.1251 0.1717 0.9963 +0.1492 0.1984 0.9660 +0.1742 0.2245 0.9357 +0.2000 0.2500 0.9054 +primID: 4 +startangle_c: 3 +endpose_c: 2 7 4 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0156 0.0377 1.1781 +0.0312 0.0754 1.1781 +0.0468 0.1131 1.1781 +0.0623 0.1508 1.1972 +0.0758 0.1893 1.2719 +0.0863 0.2287 1.3466 +0.0939 0.2687 1.4214 +0.0985 0.3092 1.4961 +0.1000 0.3500 1.5708 +primID: 5 +startangle_c: 3 +endpose_c: 0 0 2 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0000 0.0000 1.1345 +0.0000 0.0000 1.0908 +0.0000 0.0000 1.0472 +0.0000 0.0000 1.0036 +0.0000 0.0000 0.9599 +0.0000 0.0000 0.9163 +0.0000 0.0000 0.8727 +0.0000 0.0000 0.8290 +0.0000 0.0000 0.7854 +primID: 6 +startangle_c: 3 +endpose_c: 0 0 4 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0000 0.0000 1.2217 +0.0000 0.0000 1.2654 +0.0000 0.0000 1.3090 +0.0000 0.0000 1.3526 +0.0000 0.0000 1.3963 +0.0000 0.0000 1.4399 +0.0000 0.0000 1.4835 +0.0000 0.0000 1.5272 +0.0000 0.0000 1.5708 +primID: 0 +startangle_c: 4 +endpose_c: 0 1 4 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0056 1.5708 +0.0000 0.0111 1.5708 +0.0000 0.0167 1.5708 +0.0000 0.0222 1.5708 +0.0000 0.0278 1.5708 +0.0000 0.0333 1.5708 +0.0000 0.0389 1.5708 +0.0000 0.0444 1.5708 +0.0000 0.0500 1.5708 +primID: 1 +startangle_c: 4 +endpose_c: 0 8 4 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0444 1.5708 +0.0000 0.0889 1.5708 +0.0000 0.1333 1.5708 +0.0000 0.1778 1.5708 +0.0000 0.2222 1.5708 +0.0000 0.2667 1.5708 +0.0000 0.3111 1.5708 +0.0000 0.3556 1.5708 +0.0000 0.4000 1.5708 +primID: 2 +startangle_c: 4 +endpose_c: 0 -1 4 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 -0.0056 1.5708 +0.0000 -0.0111 1.5708 +0.0000 -0.0167 1.5708 +0.0000 -0.0222 1.5708 +0.0000 -0.0278 1.5708 +0.0000 -0.0333 1.5708 +0.0000 -0.0389 1.5708 +0.0000 -0.0444 1.5708 +0.0000 -0.0500 1.5708 +primID: 3 +startangle_c: 4 +endpose_c: -1 8 5 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0452 1.5708 +0.0000 0.0904 1.5708 +0.0000 0.1355 1.5708 +-0.0008 0.1807 1.6196 +-0.0045 0.2257 1.6884 +-0.0114 0.2703 1.7572 +-0.0213 0.3144 1.8259 +-0.0342 0.3577 1.8947 +-0.0500 0.4000 1.9635 +primID: 4 +startangle_c: 4 +endpose_c: 1 8 3 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0452 1.5708 +0.0000 0.0904 1.5708 +0.0000 0.1355 1.5708 +0.0008 0.1807 1.5220 +0.0045 0.2257 1.4532 +0.0114 0.2703 1.3844 +0.0213 0.3144 1.3156 +0.0342 0.3577 1.2469 +0.0500 0.4000 1.1781 +primID: 5 +startangle_c: 4 +endpose_c: 0 0 5 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0000 1.6144 +0.0000 0.0000 1.6581 +0.0000 0.0000 1.7017 +0.0000 0.0000 1.7453 +0.0000 0.0000 1.7890 +0.0000 0.0000 1.8326 +0.0000 0.0000 1.8762 +0.0000 0.0000 1.9199 +0.0000 0.0000 1.9635 +primID: 6 +startangle_c: 4 +endpose_c: 0 0 3 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0000 1.5272 +0.0000 0.0000 1.4835 +0.0000 0.0000 1.4399 +0.0000 0.0000 1.3963 +0.0000 0.0000 1.3526 +0.0000 0.0000 1.3090 +0.0000 0.0000 1.2654 +0.0000 0.0000 1.2217 +0.0000 0.0000 1.1781 +primID: 0 +startangle_c: 5 +endpose_c: -1 2 5 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0056 0.0111 1.9635 +-0.0111 0.0222 1.9635 +-0.0167 0.0333 1.9635 +-0.0222 0.0444 1.9635 +-0.0278 0.0556 1.9635 +-0.0333 0.0667 1.9635 +-0.0389 0.0778 1.9635 +-0.0444 0.0889 1.9635 +-0.0500 0.1000 1.9635 +primID: 1 +startangle_c: 5 +endpose_c: -3 6 5 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0167 0.0333 1.9635 +-0.0333 0.0667 1.9635 +-0.0500 0.1000 1.9635 +-0.0667 0.1333 1.9635 +-0.0833 0.1667 1.9635 +-0.1000 0.2000 1.9635 +-0.1167 0.2333 1.9635 +-0.1333 0.2667 1.9635 +-0.1500 0.3000 1.9635 +primID: 2 +startangle_c: 5 +endpose_c: 1 -2 5 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0056 -0.0111 1.9635 +0.0111 -0.0222 1.9635 +0.0167 -0.0333 1.9635 +0.0222 -0.0444 1.9635 +0.0278 -0.0556 1.9635 +0.0333 -0.0667 1.9635 +0.0389 -0.0778 1.9635 +0.0444 -0.0889 1.9635 +0.0500 -0.1000 1.9635 +primID: 3 +startangle_c: 5 +endpose_c: -4 5 6 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0184 0.0298 1.9938 +-0.0379 0.0592 2.0241 +-0.0583 0.0881 2.0544 +-0.0796 0.1165 2.0847 +-0.1019 0.1444 2.1150 +-0.1251 0.1717 2.1453 +-0.1492 0.1984 2.1756 +-0.1742 0.2245 2.2059 +-0.2000 0.2500 2.2362 +primID: 4 +startangle_c: 5 +endpose_c: -2 7 4 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0156 0.0377 1.9635 +-0.0312 0.0754 1.9635 +-0.0468 0.1131 1.9635 +-0.0623 0.1508 1.9444 +-0.0758 0.1893 1.8697 +-0.0863 0.2287 1.7950 +-0.0939 0.2687 1.7202 +-0.0985 0.3092 1.6455 +-0.1000 0.3500 1.5708 +primID: 5 +startangle_c: 5 +endpose_c: 0 0 6 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0000 0.0000 2.0071 +0.0000 0.0000 2.0508 +0.0000 0.0000 2.0944 +0.0000 0.0000 2.1380 +0.0000 0.0000 2.1817 +0.0000 0.0000 2.2253 +0.0000 0.0000 2.2689 +0.0000 0.0000 2.3126 +0.0000 0.0000 2.3562 +primID: 6 +startangle_c: 5 +endpose_c: 0 0 4 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0000 0.0000 1.9199 +0.0000 0.0000 1.8762 +0.0000 0.0000 1.8326 +0.0000 0.0000 1.7890 +0.0000 0.0000 1.7453 +0.0000 0.0000 1.7017 +0.0000 0.0000 1.6581 +0.0000 0.0000 1.6144 +0.0000 0.0000 1.5708 +primID: 0 +startangle_c: 6 +endpose_c: -1 1 6 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0056 0.0056 2.3562 +-0.0111 0.0111 2.3562 +-0.0167 0.0167 2.3562 +-0.0222 0.0222 2.3562 +-0.0278 0.0278 2.3562 +-0.0333 0.0333 2.3562 +-0.0389 0.0389 2.3562 +-0.0444 0.0444 2.3562 +-0.0500 0.0500 2.3562 +primID: 1 +startangle_c: 6 +endpose_c: -6 6 6 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0333 0.0333 2.3562 +-0.0667 0.0667 2.3562 +-0.1000 0.1000 2.3562 +-0.1333 0.1333 2.3562 +-0.1667 0.1667 2.3562 +-0.2000 0.2000 2.3562 +-0.2333 0.2333 2.3562 +-0.2667 0.2667 2.3562 +-0.3000 0.3000 2.3562 +primID: 2 +startangle_c: 6 +endpose_c: 1 -1 6 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0056 -0.0056 2.3562 +0.0111 -0.0111 2.3562 +0.0167 -0.0167 2.3562 +0.0222 -0.0222 2.3562 +0.0278 -0.0278 2.3562 +0.0333 -0.0333 2.3562 +0.0389 -0.0389 2.3562 +0.0444 -0.0444 2.3562 +0.0500 -0.0500 2.3562 +primID: 3 +startangle_c: 6 +endpose_c: -7 5 7 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0341 0.0341 2.3562 +-0.0684 0.0678 2.3859 +-0.1043 0.1000 2.4377 +-0.1418 0.1302 2.4896 +-0.1809 0.1584 2.5415 +-0.2213 0.1846 2.5933 +-0.2631 0.2086 2.6452 +-0.3060 0.2304 2.6970 +-0.3500 0.2500 2.7489 +primID: 4 +startangle_c: 6 +endpose_c: -5 7 5 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0341 0.0341 2.3562 +-0.0678 0.0684 2.3265 +-0.1000 0.1043 2.2747 +-0.1302 0.1418 2.2228 +-0.1584 0.1809 2.1709 +-0.1846 0.2213 2.1191 +-0.2086 0.2631 2.0672 +-0.2304 0.3060 2.0154 +-0.2500 0.3500 1.9635 +primID: 5 +startangle_c: 6 +endpose_c: 0 0 7 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0000 0.0000 2.3998 +0.0000 0.0000 2.4435 +0.0000 0.0000 2.4871 +0.0000 0.0000 2.5307 +0.0000 0.0000 2.5744 +0.0000 0.0000 2.6180 +0.0000 0.0000 2.6616 +0.0000 0.0000 2.7053 +0.0000 0.0000 2.7489 +primID: 6 +startangle_c: 6 +endpose_c: 0 0 5 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0000 0.0000 2.3126 +0.0000 0.0000 2.2689 +0.0000 0.0000 2.2253 +0.0000 0.0000 2.1817 +0.0000 0.0000 2.1380 +0.0000 0.0000 2.0944 +0.0000 0.0000 2.0508 +0.0000 0.0000 2.0071 +0.0000 0.0000 1.9635 +primID: 0 +startangle_c: 7 +endpose_c: -2 1 7 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0111 0.0056 2.7489 +-0.0222 0.0111 2.7489 +-0.0333 0.0167 2.7489 +-0.0444 0.0222 2.7489 +-0.0556 0.0278 2.7489 +-0.0667 0.0333 2.7489 +-0.0778 0.0389 2.7489 +-0.0889 0.0444 2.7489 +-0.1000 0.0500 2.7489 +primID: 1 +startangle_c: 7 +endpose_c: -6 3 7 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0333 0.0167 2.7489 +-0.0667 0.0333 2.7489 +-0.1000 0.0500 2.7489 +-0.1333 0.0667 2.7489 +-0.1667 0.0833 2.7489 +-0.2000 0.1000 2.7489 +-0.2333 0.1167 2.7489 +-0.2667 0.1333 2.7489 +-0.3000 0.1500 2.7489 +primID: 2 +startangle_c: 7 +endpose_c: 2 -1 7 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0111 -0.0056 2.7489 +0.0222 -0.0111 2.7489 +0.0333 -0.0167 2.7489 +0.0444 -0.0222 2.7489 +0.0556 -0.0278 2.7489 +0.0667 -0.0333 2.7489 +0.0778 -0.0389 2.7489 +0.0889 -0.0444 2.7489 +0.1000 -0.0500 2.7489 +primID: 3 +startangle_c: 7 +endpose_c: -5 4 6 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0298 0.0184 2.7186 +-0.0592 0.0379 2.6883 +-0.0881 0.0583 2.6580 +-0.1165 0.0796 2.6277 +-0.1444 0.1019 2.5974 +-0.1717 0.1251 2.5671 +-0.1984 0.1492 2.5368 +-0.2245 0.1742 2.5065 +-0.2500 0.2000 2.4762 +primID: 4 +startangle_c: 7 +endpose_c: -7 2 8 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0377 0.0156 2.7489 +-0.0754 0.0312 2.7489 +-0.1131 0.0468 2.7489 +-0.1508 0.0623 2.7680 +-0.1893 0.0758 2.8427 +-0.2287 0.0863 2.9174 +-0.2687 0.0939 2.9921 +-0.3092 0.0985 3.0669 +-0.3500 0.1000 3.1416 +primID: 5 +startangle_c: 7 +endpose_c: 0 0 6 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0000 0.0000 2.7053 +0.0000 0.0000 2.6616 +0.0000 0.0000 2.6180 +0.0000 0.0000 2.5744 +0.0000 0.0000 2.5307 +0.0000 0.0000 2.4871 +0.0000 0.0000 2.4435 +0.0000 0.0000 2.3998 +0.0000 0.0000 2.3562 +primID: 6 +startangle_c: 7 +endpose_c: 0 0 8 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0000 0.0000 2.7925 +0.0000 0.0000 2.8362 +0.0000 0.0000 2.8798 +0.0000 0.0000 2.9234 +0.0000 0.0000 2.9671 +0.0000 0.0000 3.0107 +0.0000 0.0000 3.0543 +0.0000 0.0000 3.0980 +0.0000 0.0000 3.1416 +primID: 0 +startangle_c: 8 +endpose_c: -1 0 8 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0056 0.0000 3.1416 +-0.0111 0.0000 3.1416 +-0.0167 0.0000 3.1416 +-0.0222 0.0000 3.1416 +-0.0278 0.0000 3.1416 +-0.0333 0.0000 3.1416 +-0.0389 0.0000 3.1416 +-0.0444 0.0000 3.1416 +-0.0500 0.0000 3.1416 +primID: 1 +startangle_c: 8 +endpose_c: -8 0 8 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0444 0.0000 3.1416 +-0.0889 0.0000 3.1416 +-0.1333 0.0000 3.1416 +-0.1778 0.0000 3.1416 +-0.2222 0.0000 3.1416 +-0.2667 0.0000 3.1416 +-0.3111 0.0000 3.1416 +-0.3556 0.0000 3.1416 +-0.4000 0.0000 3.1416 +primID: 2 +startangle_c: 8 +endpose_c: 1 0 8 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0056 0.0000 3.1416 +0.0111 0.0000 3.1416 +0.0167 0.0000 3.1416 +0.0222 0.0000 3.1416 +0.0278 0.0000 3.1416 +0.0333 0.0000 3.1416 +0.0389 0.0000 3.1416 +0.0444 0.0000 3.1416 +0.0500 0.0000 3.1416 +primID: 3 +startangle_c: 8 +endpose_c: -8 -1 9 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0452 0.0000 3.1416 +-0.0904 0.0000 3.1416 +-0.1355 0.0000 3.1416 +-0.1807 -0.0008 3.1904 +-0.2257 -0.0045 3.2592 +-0.2703 -0.0114 3.3280 +-0.3144 -0.0213 3.3967 +-0.3577 -0.0342 3.4655 +-0.4000 -0.0500 3.5343 +primID: 4 +startangle_c: 8 +endpose_c: -8 1 7 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0452 0.0000 3.1416 +-0.0904 0.0000 3.1416 +-0.1355 0.0000 3.1416 +-0.1807 0.0008 3.0928 +-0.2257 0.0045 3.0240 +-0.2703 0.0114 2.9552 +-0.3144 0.0213 2.8864 +-0.3577 0.0342 2.8177 +-0.4000 0.0500 2.7489 +primID: 5 +startangle_c: 8 +endpose_c: 0 0 9 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0000 0.0000 3.1852 +0.0000 0.0000 3.2289 +0.0000 0.0000 3.2725 +0.0000 0.0000 3.3161 +0.0000 0.0000 3.3598 +0.0000 0.0000 3.4034 +0.0000 0.0000 3.4470 +0.0000 0.0000 3.4907 +0.0000 0.0000 3.5343 +primID: 6 +startangle_c: 8 +endpose_c: 0 0 7 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0000 0.0000 3.0980 +0.0000 0.0000 3.0543 +0.0000 0.0000 3.0107 +0.0000 0.0000 2.9671 +0.0000 0.0000 2.9234 +0.0000 0.0000 2.8798 +0.0000 0.0000 2.8362 +0.0000 0.0000 2.7925 +0.0000 0.0000 2.7489 +primID: 0 +startangle_c: 9 +endpose_c: -2 -1 9 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0111 -0.0056 3.5343 +-0.0222 -0.0111 3.5343 +-0.0333 -0.0167 3.5343 +-0.0444 -0.0222 3.5343 +-0.0556 -0.0278 3.5343 +-0.0667 -0.0333 3.5343 +-0.0778 -0.0389 3.5343 +-0.0889 -0.0444 3.5343 +-0.1000 -0.0500 3.5343 +primID: 1 +startangle_c: 9 +endpose_c: -6 -3 9 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0333 -0.0167 3.5343 +-0.0667 -0.0333 3.5343 +-0.1000 -0.0500 3.5343 +-0.1333 -0.0667 3.5343 +-0.1667 -0.0833 3.5343 +-0.2000 -0.1000 3.5343 +-0.2333 -0.1167 3.5343 +-0.2667 -0.1333 3.5343 +-0.3000 -0.1500 3.5343 +primID: 2 +startangle_c: 9 +endpose_c: 2 1 9 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0111 0.0056 3.5343 +0.0222 0.0111 3.5343 +0.0333 0.0167 3.5343 +0.0444 0.0222 3.5343 +0.0556 0.0278 3.5343 +0.0667 0.0333 3.5343 +0.0778 0.0389 3.5343 +0.0889 0.0444 3.5343 +0.1000 0.0500 3.5343 +primID: 3 +startangle_c: 9 +endpose_c: -5 -4 10 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0298 -0.0184 3.5646 +-0.0592 -0.0379 3.5949 +-0.0881 -0.0583 3.6252 +-0.1165 -0.0796 3.6555 +-0.1444 -0.1019 3.6858 +-0.1717 -0.1251 3.7161 +-0.1984 -0.1492 3.7464 +-0.2245 -0.1742 3.7767 +-0.2500 -0.2000 3.8070 +primID: 4 +startangle_c: 9 +endpose_c: -7 -2 8 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0377 -0.0156 3.5343 +-0.0754 -0.0312 3.5343 +-0.1131 -0.0468 3.5343 +-0.1508 -0.0623 3.5152 +-0.1893 -0.0758 3.4405 +-0.2287 -0.0863 3.3658 +-0.2687 -0.0939 3.2910 +-0.3092 -0.0985 3.2163 +-0.3500 -0.1000 3.1416 +primID: 5 +startangle_c: 9 +endpose_c: 0 0 10 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0000 0.0000 3.5779 +0.0000 0.0000 3.6216 +0.0000 0.0000 3.6652 +0.0000 0.0000 3.7088 +0.0000 0.0000 3.7525 +0.0000 0.0000 3.7961 +0.0000 0.0000 3.8397 +0.0000 0.0000 3.8834 +0.0000 0.0000 3.9270 +primID: 6 +startangle_c: 9 +endpose_c: 0 0 8 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0000 0.0000 3.4907 +0.0000 0.0000 3.4470 +0.0000 0.0000 3.4034 +0.0000 0.0000 3.3598 +0.0000 0.0000 3.3161 +0.0000 0.0000 3.2725 +0.0000 0.0000 3.2289 +0.0000 0.0000 3.1852 +0.0000 0.0000 3.1416 +primID: 0 +startangle_c: 10 +endpose_c: -1 -1 10 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0056 -0.0056 3.9270 +-0.0111 -0.0111 3.9270 +-0.0167 -0.0167 3.9270 +-0.0222 -0.0222 3.9270 +-0.0278 -0.0278 3.9270 +-0.0333 -0.0333 3.9270 +-0.0389 -0.0389 3.9270 +-0.0444 -0.0444 3.9270 +-0.0500 -0.0500 3.9270 +primID: 1 +startangle_c: 10 +endpose_c: -6 -6 10 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0333 -0.0333 3.9270 +-0.0667 -0.0667 3.9270 +-0.1000 -0.1000 3.9270 +-0.1333 -0.1333 3.9270 +-0.1667 -0.1667 3.9270 +-0.2000 -0.2000 3.9270 +-0.2333 -0.2333 3.9270 +-0.2667 -0.2667 3.9270 +-0.3000 -0.3000 3.9270 +primID: 2 +startangle_c: 10 +endpose_c: 1 1 10 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0056 0.0056 3.9270 +0.0111 0.0111 3.9270 +0.0167 0.0167 3.9270 +0.0222 0.0222 3.9270 +0.0278 0.0278 3.9270 +0.0333 0.0333 3.9270 +0.0389 0.0389 3.9270 +0.0444 0.0444 3.9270 +0.0500 0.0500 3.9270 +primID: 3 +startangle_c: 10 +endpose_c: -5 -7 11 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0341 -0.0341 3.9270 +-0.0678 -0.0684 3.9567 +-0.1000 -0.1043 4.0085 +-0.1302 -0.1418 4.0604 +-0.1584 -0.1809 4.1123 +-0.1846 -0.2213 4.1641 +-0.2086 -0.2631 4.2160 +-0.2304 -0.3060 4.2678 +-0.2500 -0.3500 4.3197 +primID: 4 +startangle_c: 10 +endpose_c: -7 -5 9 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0341 -0.0341 3.9270 +-0.0684 -0.0678 3.8973 +-0.1043 -0.1000 3.8455 +-0.1418 -0.1302 3.7936 +-0.1809 -0.1584 3.7417 +-0.2213 -0.1846 3.6899 +-0.2631 -0.2086 3.6380 +-0.3060 -0.2304 3.5862 +-0.3500 -0.2500 3.5343 +primID: 5 +startangle_c: 10 +endpose_c: 0 0 11 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.9706 +0.0000 0.0000 4.0143 +0.0000 0.0000 4.0579 +0.0000 0.0000 4.1015 +0.0000 0.0000 4.1452 +0.0000 0.0000 4.1888 +0.0000 0.0000 4.2324 +0.0000 0.0000 4.2761 +0.0000 0.0000 4.3197 +primID: 6 +startangle_c: 10 +endpose_c: 0 0 9 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.8834 +0.0000 0.0000 3.8397 +0.0000 0.0000 3.7961 +0.0000 0.0000 3.7525 +0.0000 0.0000 3.7088 +0.0000 0.0000 3.6652 +0.0000 0.0000 3.6216 +0.0000 0.0000 3.5779 +0.0000 0.0000 3.5343 +primID: 0 +startangle_c: 11 +endpose_c: -1 -2 11 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0056 -0.0111 4.3197 +-0.0111 -0.0222 4.3197 +-0.0167 -0.0333 4.3197 +-0.0222 -0.0444 4.3197 +-0.0278 -0.0556 4.3197 +-0.0333 -0.0667 4.3197 +-0.0389 -0.0778 4.3197 +-0.0444 -0.0889 4.3197 +-0.0500 -0.1000 4.3197 +primID: 1 +startangle_c: 11 +endpose_c: -3 -6 11 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0167 -0.0333 4.3197 +-0.0333 -0.0667 4.3197 +-0.0500 -0.1000 4.3197 +-0.0667 -0.1333 4.3197 +-0.0833 -0.1667 4.3197 +-0.1000 -0.2000 4.3197 +-0.1167 -0.2333 4.3197 +-0.1333 -0.2667 4.3197 +-0.1500 -0.3000 4.3197 +primID: 2 +startangle_c: 11 +endpose_c: 1 2 11 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0056 0.0111 4.3197 +0.0111 0.0222 4.3197 +0.0167 0.0333 4.3197 +0.0222 0.0444 4.3197 +0.0278 0.0556 4.3197 +0.0333 0.0667 4.3197 +0.0389 0.0778 4.3197 +0.0444 0.0889 4.3197 +0.0500 0.1000 4.3197 +primID: 3 +startangle_c: 11 +endpose_c: -4 -5 10 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0184 -0.0298 4.2894 +-0.0379 -0.0592 4.2591 +-0.0583 -0.0881 4.2288 +-0.0796 -0.1165 4.1985 +-0.1019 -0.1444 4.1682 +-0.1251 -0.1717 4.1379 +-0.1492 -0.1984 4.1076 +-0.1742 -0.2245 4.0773 +-0.2000 -0.2500 4.0470 +primID: 4 +startangle_c: 11 +endpose_c: -2 -7 12 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0156 -0.0377 4.3197 +-0.0312 -0.0754 4.3197 +-0.0468 -0.1131 4.3197 +-0.0623 -0.1508 4.3388 +-0.0758 -0.1893 4.4135 +-0.0863 -0.2287 4.4882 +-0.0939 -0.2687 4.5629 +-0.0985 -0.3092 4.6377 +-0.1000 -0.3500 4.7124 +primID: 5 +startangle_c: 11 +endpose_c: 0 0 10 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0000 0.0000 4.2761 +0.0000 0.0000 4.2324 +0.0000 0.0000 4.1888 +0.0000 0.0000 4.1452 +0.0000 0.0000 4.1015 +0.0000 0.0000 4.0579 +0.0000 0.0000 4.0143 +0.0000 0.0000 3.9706 +0.0000 0.0000 3.9270 +primID: 6 +startangle_c: 11 +endpose_c: 0 0 12 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0000 0.0000 4.3633 +0.0000 0.0000 4.4070 +0.0000 0.0000 4.4506 +0.0000 0.0000 4.4942 +0.0000 0.0000 4.5379 +0.0000 0.0000 4.5815 +0.0000 0.0000 4.6251 +0.0000 0.0000 4.6688 +0.0000 0.0000 4.7124 +primID: 0 +startangle_c: 12 +endpose_c: 0 -1 12 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0056 4.7124 +0.0000 -0.0111 4.7124 +0.0000 -0.0167 4.7124 +0.0000 -0.0222 4.7124 +0.0000 -0.0278 4.7124 +0.0000 -0.0333 4.7124 +0.0000 -0.0389 4.7124 +0.0000 -0.0444 4.7124 +0.0000 -0.0500 4.7124 +primID: 1 +startangle_c: 12 +endpose_c: 0 -8 12 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0444 4.7124 +0.0000 -0.0889 4.7124 +0.0000 -0.1333 4.7124 +0.0000 -0.1778 4.7124 +0.0000 -0.2222 4.7124 +0.0000 -0.2667 4.7124 +0.0000 -0.3111 4.7124 +0.0000 -0.3556 4.7124 +0.0000 -0.4000 4.7124 +primID: 2 +startangle_c: 12 +endpose_c: 0 1 12 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0056 4.7124 +0.0000 0.0111 4.7124 +0.0000 0.0167 4.7124 +0.0000 0.0222 4.7124 +0.0000 0.0278 4.7124 +0.0000 0.0333 4.7124 +0.0000 0.0389 4.7124 +0.0000 0.0444 4.7124 +0.0000 0.0500 4.7124 +primID: 3 +startangle_c: 12 +endpose_c: 1 -8 13 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0452 4.7124 +0.0000 -0.0904 4.7124 +0.0000 -0.1355 4.7124 +0.0008 -0.1807 4.7612 +0.0045 -0.2257 4.8300 +0.0114 -0.2703 4.8988 +0.0213 -0.3144 4.9675 +0.0342 -0.3577 5.0363 +0.0500 -0.4000 5.1051 +primID: 4 +startangle_c: 12 +endpose_c: -1 -8 11 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 4.7124 +-0.0000 -0.0452 4.7124 +-0.0000 -0.0904 4.7124 +-0.0000 -0.1355 4.7124 +-0.0008 -0.1807 4.6636 +-0.0045 -0.2257 4.5948 +-0.0114 -0.2703 4.5260 +-0.0213 -0.3144 4.4572 +-0.0342 -0.3577 4.3885 +-0.0500 -0.4000 4.3197 +primID: 5 +startangle_c: 12 +endpose_c: 0 0 13 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0000 4.7560 +0.0000 0.0000 4.7997 +0.0000 0.0000 4.8433 +0.0000 0.0000 4.8869 +0.0000 0.0000 4.9306 +0.0000 0.0000 4.9742 +0.0000 0.0000 5.0178 +0.0000 0.0000 5.0615 +0.0000 0.0000 5.1051 +primID: 6 +startangle_c: 12 +endpose_c: 0 0 11 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0000 4.6688 +0.0000 0.0000 4.6251 +0.0000 0.0000 4.5815 +0.0000 0.0000 4.5379 +0.0000 0.0000 4.4942 +0.0000 0.0000 4.4506 +0.0000 0.0000 4.4070 +0.0000 0.0000 4.3633 +0.0000 0.0000 4.3197 +primID: 0 +startangle_c: 13 +endpose_c: 1 -2 13 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0056 -0.0111 5.1051 +0.0111 -0.0222 5.1051 +0.0167 -0.0333 5.1051 +0.0222 -0.0444 5.1051 +0.0278 -0.0556 5.1051 +0.0333 -0.0667 5.1051 +0.0389 -0.0778 5.1051 +0.0444 -0.0889 5.1051 +0.0500 -0.1000 5.1051 +primID: 1 +startangle_c: 13 +endpose_c: 3 -6 13 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0167 -0.0333 5.1051 +0.0333 -0.0667 5.1051 +0.0500 -0.1000 5.1051 +0.0667 -0.1333 5.1051 +0.0833 -0.1667 5.1051 +0.1000 -0.2000 5.1051 +0.1167 -0.2333 5.1051 +0.1333 -0.2667 5.1051 +0.1500 -0.3000 5.1051 +primID: 2 +startangle_c: 13 +endpose_c: -1 2 13 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 5.1051 +-0.0056 0.0111 5.1051 +-0.0111 0.0222 5.1051 +-0.0167 0.0333 5.1051 +-0.0222 0.0444 5.1051 +-0.0278 0.0556 5.1051 +-0.0333 0.0667 5.1051 +-0.0389 0.0778 5.1051 +-0.0444 0.0889 5.1051 +-0.0500 0.1000 5.1051 +primID: 3 +startangle_c: 13 +endpose_c: 4 -5 14 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0184 -0.0298 5.1354 +0.0379 -0.0592 5.1657 +0.0583 -0.0881 5.1960 +0.0796 -0.1165 5.2263 +0.1019 -0.1444 5.2566 +0.1251 -0.1717 5.2869 +0.1492 -0.1984 5.3172 +0.1742 -0.2245 5.3475 +0.2000 -0.2500 5.3778 +primID: 4 +startangle_c: 13 +endpose_c: 2 -7 12 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0156 -0.0377 5.1051 +0.0312 -0.0754 5.1051 +0.0468 -0.1131 5.1051 +0.0623 -0.1508 5.0860 +0.0758 -0.1893 5.0113 +0.0863 -0.2287 4.9366 +0.0939 -0.2687 4.8618 +0.0985 -0.3092 4.7871 +0.1000 -0.3500 4.7124 +primID: 5 +startangle_c: 13 +endpose_c: 0 0 14 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0000 0.0000 5.1487 +0.0000 0.0000 5.1924 +0.0000 0.0000 5.2360 +0.0000 0.0000 5.2796 +0.0000 0.0000 5.3233 +0.0000 0.0000 5.3669 +0.0000 0.0000 5.4105 +0.0000 0.0000 5.4542 +0.0000 0.0000 5.4978 +primID: 6 +startangle_c: 13 +endpose_c: 0 0 12 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0000 0.0000 5.0615 +0.0000 0.0000 5.0178 +0.0000 0.0000 4.9742 +0.0000 0.0000 4.9306 +0.0000 0.0000 4.8869 +0.0000 0.0000 4.8433 +0.0000 0.0000 4.7997 +0.0000 0.0000 4.7560 +0.0000 0.0000 4.7124 +primID: 0 +startangle_c: 14 +endpose_c: 1 -1 14 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0056 -0.0056 5.4978 +0.0111 -0.0111 5.4978 +0.0167 -0.0167 5.4978 +0.0222 -0.0222 5.4978 +0.0278 -0.0278 5.4978 +0.0333 -0.0333 5.4978 +0.0389 -0.0389 5.4978 +0.0444 -0.0444 5.4978 +0.0500 -0.0500 5.4978 +primID: 1 +startangle_c: 14 +endpose_c: 6 -6 14 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0333 -0.0333 5.4978 +0.0667 -0.0667 5.4978 +0.1000 -0.1000 5.4978 +0.1333 -0.1333 5.4978 +0.1667 -0.1667 5.4978 +0.2000 -0.2000 5.4978 +0.2333 -0.2333 5.4978 +0.2667 -0.2667 5.4978 +0.3000 -0.3000 5.4978 +primID: 2 +startangle_c: 14 +endpose_c: -1 1 14 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 5.4978 +-0.0056 0.0056 5.4978 +-0.0111 0.0111 5.4978 +-0.0167 0.0167 5.4978 +-0.0222 0.0222 5.4978 +-0.0278 0.0278 5.4978 +-0.0333 0.0333 5.4978 +-0.0389 0.0389 5.4978 +-0.0444 0.0444 5.4978 +-0.0500 0.0500 5.4978 +primID: 3 +startangle_c: 14 +endpose_c: 7 -5 15 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0341 -0.0341 5.4978 +0.0684 -0.0678 5.5275 +0.1043 -0.1000 5.5793 +0.1418 -0.1302 5.6312 +0.1809 -0.1584 5.6830 +0.2213 -0.1846 5.7349 +0.2631 -0.2086 5.7868 +0.3060 -0.2304 5.8386 +0.3500 -0.2500 5.8905 +primID: 4 +startangle_c: 14 +endpose_c: 5 -7 13 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0341 -0.0341 5.4978 +0.0678 -0.0684 5.4681 +0.1000 -0.1043 5.4162 +0.1302 -0.1418 5.3644 +0.1584 -0.1809 5.3125 +0.1846 -0.2213 5.2607 +0.2086 -0.2631 5.2088 +0.2304 -0.3060 5.1569 +0.2500 -0.3500 5.1051 +primID: 5 +startangle_c: 14 +endpose_c: 0 0 15 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0000 0.0000 5.5414 +0.0000 0.0000 5.5851 +0.0000 0.0000 5.6287 +0.0000 0.0000 5.6723 +0.0000 0.0000 5.7160 +0.0000 0.0000 5.7596 +0.0000 0.0000 5.8032 +0.0000 0.0000 5.8469 +0.0000 0.0000 5.8905 +primID: 6 +startangle_c: 14 +endpose_c: 0 0 13 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0000 0.0000 5.4542 +0.0000 0.0000 5.4105 +0.0000 0.0000 5.3669 +0.0000 0.0000 5.3233 +0.0000 0.0000 5.2796 +0.0000 0.0000 5.2360 +0.0000 0.0000 5.1924 +0.0000 0.0000 5.1487 +0.0000 0.0000 5.1051 +primID: 0 +startangle_c: 15 +endpose_c: 2 -1 15 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0111 -0.0056 5.8905 +0.0222 -0.0111 5.8905 +0.0333 -0.0167 5.8905 +0.0444 -0.0222 5.8905 +0.0556 -0.0278 5.8905 +0.0667 -0.0333 5.8905 +0.0778 -0.0389 5.8905 +0.0889 -0.0444 5.8905 +0.1000 -0.0500 5.8905 +primID: 1 +startangle_c: 15 +endpose_c: 6 -3 15 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0333 -0.0167 5.8905 +0.0667 -0.0333 5.8905 +0.1000 -0.0500 5.8905 +0.1333 -0.0667 5.8905 +0.1667 -0.0833 5.8905 +0.2000 -0.1000 5.8905 +0.2333 -0.1167 5.8905 +0.2667 -0.1333 5.8905 +0.3000 -0.1500 5.8905 +primID: 2 +startangle_c: 15 +endpose_c: -2 1 15 +additionalactioncostmult: 5 +intermediateposes: 10 +0.0000 0.0000 5.8905 +-0.0111 0.0056 5.8905 +-0.0222 0.0111 5.8905 +-0.0333 0.0167 5.8905 +-0.0444 0.0222 5.8905 +-0.0556 0.0278 5.8905 +-0.0667 0.0333 5.8905 +-0.0778 0.0389 5.8905 +-0.0889 0.0444 5.8905 +-0.1000 0.0500 5.8905 +primID: 3 +startangle_c: 15 +endpose_c: 5 -4 14 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0298 -0.0184 5.8602 +0.0592 -0.0379 5.8299 +0.0881 -0.0583 5.7996 +0.1165 -0.0796 5.7693 +0.1444 -0.1019 5.7390 +0.1717 -0.1251 5.7087 +0.1984 -0.1492 5.6784 +0.2245 -0.1742 5.6481 +0.2500 -0.2000 5.6178 +primID: 4 +startangle_c: 15 +endpose_c: 7 -2 0 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0377 -0.0156 5.8905 +0.0754 -0.0312 5.8905 +0.1131 -0.0468 5.8905 +0.1508 -0.0623 5.9096 +0.1893 -0.0758 5.9843 +0.2287 -0.0863 6.0590 +0.2687 -0.0939 6.1337 +0.3092 -0.0985 6.2085 +0.3500 -0.1000 6.2832 +primID: 5 +startangle_c: 15 +endpose_c: 0 0 14 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0000 0.0000 5.8469 +0.0000 0.0000 5.8032 +0.0000 0.0000 5.7596 +0.0000 0.0000 5.7160 +0.0000 0.0000 5.6723 +0.0000 0.0000 5.6287 +0.0000 0.0000 5.5851 +0.0000 0.0000 5.5414 +0.0000 0.0000 5.4978 +primID: 6 +startangle_c: 15 +endpose_c: 0 0 0 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0000 0.0000 5.2360 +0.0000 0.0000 4.5815 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.2725 +0.0000 0.0000 2.6180 +0.0000 0.0000 1.9635 +0.0000 0.0000 1.3090 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.0000 diff --git a/navigations/sbpl_lattice_planner/matlab/mprim/unicycle_5cm_expensive_turn_in_place_highcost.mprim b/navigations/sbpl_lattice_planner/matlab/mprim/unicycle_5cm_expensive_turn_in_place_highcost.mprim new file mode 100755 index 0000000..0f11e5d --- /dev/null +++ b/navigations/sbpl_lattice_planner/matlab/mprim/unicycle_5cm_expensive_turn_in_place_highcost.mprim @@ -0,0 +1,1683 @@ +resolution_m: 0.050000 +numberofangles: 16 +totalnumberofprimitives: 112 +primID: 0 +startangle_c: 0 +endpose_c: 1 0 0 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0056 0.0000 0.0000 +0.0111 0.0000 0.0000 +0.0167 0.0000 0.0000 +0.0222 0.0000 0.0000 +0.0278 0.0000 0.0000 +0.0333 0.0000 0.0000 +0.0389 0.0000 0.0000 +0.0444 0.0000 0.0000 +0.0500 0.0000 0.0000 +primID: 1 +startangle_c: 0 +endpose_c: 8 0 0 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0444 0.0000 0.0000 +0.0889 0.0000 0.0000 +0.1333 0.0000 0.0000 +0.1778 0.0000 0.0000 +0.2222 0.0000 0.0000 +0.2667 0.0000 0.0000 +0.3111 0.0000 0.0000 +0.3556 0.0000 0.0000 +0.4000 0.0000 0.0000 +primID: 2 +startangle_c: 0 +endpose_c: -1 0 0 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.0000 +-0.0056 0.0000 0.0000 +-0.0111 0.0000 0.0000 +-0.0167 0.0000 0.0000 +-0.0222 0.0000 0.0000 +-0.0278 0.0000 0.0000 +-0.0333 0.0000 0.0000 +-0.0389 0.0000 0.0000 +-0.0444 0.0000 0.0000 +-0.0500 0.0000 0.0000 +primID: 3 +startangle_c: 0 +endpose_c: 8 1 1 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0452 -0.0000 0.0000 +0.0904 -0.0000 0.0000 +0.1355 -0.0000 0.0000 +0.1807 0.0008 0.0488 +0.2257 0.0045 0.1176 +0.2703 0.0114 0.1864 +0.3144 0.0213 0.2551 +0.3577 0.0342 0.3239 +0.4000 0.0500 0.3927 +primID: 4 +startangle_c: 0 +endpose_c: 8 -1 -1 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0452 0.0000 0.0000 +0.0904 0.0000 0.0000 +0.1355 0.0000 0.0000 +0.1807 -0.0008 -0.0488 +0.2257 -0.0045 -0.1176 +0.2703 -0.0114 -0.1864 +0.3144 -0.0213 -0.2551 +0.3577 -0.0342 -0.3239 +0.4000 -0.0500 -0.3927 +primID: 5 +startangle_c: 0 +endpose_c: 0 0 1 +additionalactioncostmult: 200 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0000 0.0000 0.0436 +0.0000 0.0000 0.0873 +0.0000 0.0000 0.1309 +0.0000 0.0000 0.1745 +0.0000 0.0000 0.2182 +0.0000 0.0000 0.2618 +0.0000 0.0000 0.3054 +0.0000 0.0000 0.3491 +0.0000 0.0000 0.3927 +primID: 6 +startangle_c: 0 +endpose_c: 0 0 -1 +additionalactioncostmult: 200 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0000 0.0000 -0.0436 +0.0000 0.0000 -0.0873 +0.0000 0.0000 -0.1309 +0.0000 0.0000 -0.1745 +0.0000 0.0000 -0.2182 +0.0000 0.0000 -0.2618 +0.0000 0.0000 -0.3054 +0.0000 0.0000 -0.3491 +0.0000 0.0000 -0.3927 +primID: 0 +startangle_c: 1 +endpose_c: 2 1 1 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0111 0.0056 0.3927 +0.0222 0.0111 0.3927 +0.0333 0.0167 0.3927 +0.0444 0.0222 0.3927 +0.0556 0.0278 0.3927 +0.0667 0.0333 0.3927 +0.0778 0.0389 0.3927 +0.0889 0.0444 0.3927 +0.1000 0.0500 0.3927 +primID: 1 +startangle_c: 1 +endpose_c: 6 3 1 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0333 0.0167 0.3927 +0.0667 0.0333 0.3927 +0.1000 0.0500 0.3927 +0.1333 0.0667 0.3927 +0.1667 0.0833 0.3927 +0.2000 0.1000 0.3927 +0.2333 0.1167 0.3927 +0.2667 0.1333 0.3927 +0.3000 0.1500 0.3927 +primID: 2 +startangle_c: 1 +endpose_c: -2 -1 1 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.3927 +-0.0111 -0.0056 0.3927 +-0.0222 -0.0111 0.3927 +-0.0333 -0.0167 0.3927 +-0.0444 -0.0222 0.3927 +-0.0556 -0.0278 0.3927 +-0.0667 -0.0333 0.3927 +-0.0778 -0.0389 0.3927 +-0.0889 -0.0444 0.3927 +-0.1000 -0.0500 0.3927 +primID: 3 +startangle_c: 1 +endpose_c: 5 4 2 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0298 0.0184 0.4230 +0.0592 0.0379 0.4533 +0.0881 0.0583 0.4836 +0.1165 0.0796 0.5139 +0.1444 0.1019 0.5442 +0.1717 0.1251 0.5745 +0.1984 0.1492 0.6048 +0.2245 0.1742 0.6351 +0.2500 0.2000 0.6654 +primID: 4 +startangle_c: 1 +endpose_c: 7 2 0 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0377 0.0156 0.3927 +0.0754 0.0312 0.3927 +0.1131 0.0468 0.3927 +0.1508 0.0623 0.3736 +0.1893 0.0758 0.2989 +0.2287 0.0863 0.2242 +0.2687 0.0939 0.1494 +0.3092 0.0985 0.0747 +0.3500 0.1000 -0.0000 +primID: 5 +startangle_c: 1 +endpose_c: 0 0 2 +additionalactioncostmult: 200 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0000 0.0000 0.4363 +0.0000 0.0000 0.4800 +0.0000 0.0000 0.5236 +0.0000 0.0000 0.5672 +0.0000 0.0000 0.6109 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.6981 +0.0000 0.0000 0.7418 +0.0000 0.0000 0.7854 +primID: 6 +startangle_c: 1 +endpose_c: 0 0 0 +additionalactioncostmult: 200 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0000 0.0000 0.3491 +0.0000 0.0000 0.3054 +0.0000 0.0000 0.2618 +0.0000 0.0000 0.2182 +0.0000 0.0000 0.1745 +0.0000 0.0000 0.1309 +0.0000 0.0000 0.0873 +0.0000 0.0000 0.0436 +0.0000 0.0000 0.0000 +primID: 0 +startangle_c: 2 +endpose_c: 1 1 2 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0056 0.0056 0.7854 +0.0111 0.0111 0.7854 +0.0167 0.0167 0.7854 +0.0222 0.0222 0.7854 +0.0278 0.0278 0.7854 +0.0333 0.0333 0.7854 +0.0389 0.0389 0.7854 +0.0444 0.0444 0.7854 +0.0500 0.0500 0.7854 +primID: 1 +startangle_c: 2 +endpose_c: 6 6 2 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0333 0.0333 0.7854 +0.0667 0.0667 0.7854 +0.1000 0.1000 0.7854 +0.1333 0.1333 0.7854 +0.1667 0.1667 0.7854 +0.2000 0.2000 0.7854 +0.2333 0.2333 0.7854 +0.2667 0.2667 0.7854 +0.3000 0.3000 0.7854 +primID: 2 +startangle_c: 2 +endpose_c: -1 -1 2 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.7854 +-0.0056 -0.0056 0.7854 +-0.0111 -0.0111 0.7854 +-0.0167 -0.0167 0.7854 +-0.0222 -0.0222 0.7854 +-0.0278 -0.0278 0.7854 +-0.0333 -0.0333 0.7854 +-0.0389 -0.0389 0.7854 +-0.0444 -0.0444 0.7854 +-0.0500 -0.0500 0.7854 +primID: 3 +startangle_c: 2 +endpose_c: 5 7 3 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0341 0.0341 0.7854 +0.0678 0.0684 0.8151 +0.1000 0.1043 0.8669 +0.1302 0.1418 0.9188 +0.1584 0.1809 0.9707 +0.1846 0.2213 1.0225 +0.2086 0.2631 1.0744 +0.2304 0.3060 1.1262 +0.2500 0.3500 1.1781 +primID: 4 +startangle_c: 2 +endpose_c: 7 5 1 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0341 0.0341 0.7854 +0.0684 0.0678 0.7557 +0.1043 0.1000 0.7039 +0.1418 0.1302 0.6520 +0.1809 0.1584 0.6001 +0.2213 0.1846 0.5483 +0.2631 0.2086 0.4964 +0.3060 0.2304 0.4446 +0.3500 0.2500 0.3927 +primID: 5 +startangle_c: 2 +endpose_c: 0 0 3 +additionalactioncostmult: 200 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0000 0.0000 0.8290 +0.0000 0.0000 0.8727 +0.0000 0.0000 0.9163 +0.0000 0.0000 0.9599 +0.0000 0.0000 1.0036 +0.0000 0.0000 1.0472 +0.0000 0.0000 1.0908 +0.0000 0.0000 1.1345 +0.0000 0.0000 1.1781 +primID: 6 +startangle_c: 2 +endpose_c: 0 0 1 +additionalactioncostmult: 200 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0000 0.0000 0.7418 +0.0000 0.0000 0.6981 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.6109 +0.0000 0.0000 0.5672 +0.0000 0.0000 0.5236 +0.0000 0.0000 0.4800 +0.0000 0.0000 0.4363 +0.0000 0.0000 0.3927 +primID: 0 +startangle_c: 3 +endpose_c: 1 2 3 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0056 0.0111 1.1781 +0.0111 0.0222 1.1781 +0.0167 0.0333 1.1781 +0.0222 0.0444 1.1781 +0.0278 0.0556 1.1781 +0.0333 0.0667 1.1781 +0.0389 0.0778 1.1781 +0.0444 0.0889 1.1781 +0.0500 0.1000 1.1781 +primID: 1 +startangle_c: 3 +endpose_c: 3 6 3 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0167 0.0333 1.1781 +0.0333 0.0667 1.1781 +0.0500 0.1000 1.1781 +0.0667 0.1333 1.1781 +0.0833 0.1667 1.1781 +0.1000 0.2000 1.1781 +0.1167 0.2333 1.1781 +0.1333 0.2667 1.1781 +0.1500 0.3000 1.1781 +primID: 2 +startangle_c: 3 +endpose_c: -1 -2 3 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.1781 +-0.0056 -0.0111 1.1781 +-0.0111 -0.0222 1.1781 +-0.0167 -0.0333 1.1781 +-0.0222 -0.0444 1.1781 +-0.0278 -0.0556 1.1781 +-0.0333 -0.0667 1.1781 +-0.0389 -0.0778 1.1781 +-0.0444 -0.0889 1.1781 +-0.0500 -0.1000 1.1781 +primID: 3 +startangle_c: 3 +endpose_c: 4 5 2 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0184 0.0298 1.1478 +0.0379 0.0592 1.1175 +0.0583 0.0881 1.0872 +0.0796 0.1165 1.0569 +0.1019 0.1444 1.0266 +0.1251 0.1717 0.9963 +0.1492 0.1984 0.9660 +0.1742 0.2245 0.9357 +0.2000 0.2500 0.9054 +primID: 4 +startangle_c: 3 +endpose_c: 2 7 4 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0156 0.0377 1.1781 +0.0312 0.0754 1.1781 +0.0468 0.1131 1.1781 +0.0623 0.1508 1.1972 +0.0758 0.1893 1.2719 +0.0863 0.2287 1.3466 +0.0939 0.2687 1.4214 +0.0985 0.3092 1.4961 +0.1000 0.3500 1.5708 +primID: 5 +startangle_c: 3 +endpose_c: 0 0 2 +additionalactioncostmult: 200 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0000 0.0000 1.1345 +0.0000 0.0000 1.0908 +0.0000 0.0000 1.0472 +0.0000 0.0000 1.0036 +0.0000 0.0000 0.9599 +0.0000 0.0000 0.9163 +0.0000 0.0000 0.8727 +0.0000 0.0000 0.8290 +0.0000 0.0000 0.7854 +primID: 6 +startangle_c: 3 +endpose_c: 0 0 4 +additionalactioncostmult: 200 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0000 0.0000 1.2217 +0.0000 0.0000 1.2654 +0.0000 0.0000 1.3090 +0.0000 0.0000 1.3526 +0.0000 0.0000 1.3963 +0.0000 0.0000 1.4399 +0.0000 0.0000 1.4835 +0.0000 0.0000 1.5272 +0.0000 0.0000 1.5708 +primID: 0 +startangle_c: 4 +endpose_c: 0 1 4 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0056 1.5708 +0.0000 0.0111 1.5708 +0.0000 0.0167 1.5708 +0.0000 0.0222 1.5708 +0.0000 0.0278 1.5708 +0.0000 0.0333 1.5708 +0.0000 0.0389 1.5708 +0.0000 0.0444 1.5708 +0.0000 0.0500 1.5708 +primID: 1 +startangle_c: 4 +endpose_c: 0 8 4 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0444 1.5708 +0.0000 0.0889 1.5708 +0.0000 0.1333 1.5708 +0.0000 0.1778 1.5708 +0.0000 0.2222 1.5708 +0.0000 0.2667 1.5708 +0.0000 0.3111 1.5708 +0.0000 0.3556 1.5708 +0.0000 0.4000 1.5708 +primID: 2 +startangle_c: 4 +endpose_c: 0 -1 4 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 -0.0056 1.5708 +0.0000 -0.0111 1.5708 +0.0000 -0.0167 1.5708 +0.0000 -0.0222 1.5708 +0.0000 -0.0278 1.5708 +0.0000 -0.0333 1.5708 +0.0000 -0.0389 1.5708 +0.0000 -0.0444 1.5708 +0.0000 -0.0500 1.5708 +primID: 3 +startangle_c: 4 +endpose_c: -1 8 5 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0452 1.5708 +0.0000 0.0904 1.5708 +0.0000 0.1355 1.5708 +-0.0008 0.1807 1.6196 +-0.0045 0.2257 1.6884 +-0.0114 0.2703 1.7572 +-0.0213 0.3144 1.8259 +-0.0342 0.3577 1.8947 +-0.0500 0.4000 1.9635 +primID: 4 +startangle_c: 4 +endpose_c: 1 8 3 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0452 1.5708 +0.0000 0.0904 1.5708 +0.0000 0.1355 1.5708 +0.0008 0.1807 1.5220 +0.0045 0.2257 1.4532 +0.0114 0.2703 1.3844 +0.0213 0.3144 1.3156 +0.0342 0.3577 1.2469 +0.0500 0.4000 1.1781 +primID: 5 +startangle_c: 4 +endpose_c: 0 0 5 +additionalactioncostmult: 200 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0000 1.6144 +0.0000 0.0000 1.6581 +0.0000 0.0000 1.7017 +0.0000 0.0000 1.7453 +0.0000 0.0000 1.7890 +0.0000 0.0000 1.8326 +0.0000 0.0000 1.8762 +0.0000 0.0000 1.9199 +0.0000 0.0000 1.9635 +primID: 6 +startangle_c: 4 +endpose_c: 0 0 3 +additionalactioncostmult: 200 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0000 1.5272 +0.0000 0.0000 1.4835 +0.0000 0.0000 1.4399 +0.0000 0.0000 1.3963 +0.0000 0.0000 1.3526 +0.0000 0.0000 1.3090 +0.0000 0.0000 1.2654 +0.0000 0.0000 1.2217 +0.0000 0.0000 1.1781 +primID: 0 +startangle_c: 5 +endpose_c: -1 2 5 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0056 0.0111 1.9635 +-0.0111 0.0222 1.9635 +-0.0167 0.0333 1.9635 +-0.0222 0.0444 1.9635 +-0.0278 0.0556 1.9635 +-0.0333 0.0667 1.9635 +-0.0389 0.0778 1.9635 +-0.0444 0.0889 1.9635 +-0.0500 0.1000 1.9635 +primID: 1 +startangle_c: 5 +endpose_c: -3 6 5 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0167 0.0333 1.9635 +-0.0333 0.0667 1.9635 +-0.0500 0.1000 1.9635 +-0.0667 0.1333 1.9635 +-0.0833 0.1667 1.9635 +-0.1000 0.2000 1.9635 +-0.1167 0.2333 1.9635 +-0.1333 0.2667 1.9635 +-0.1500 0.3000 1.9635 +primID: 2 +startangle_c: 5 +endpose_c: 1 -2 5 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0056 -0.0111 1.9635 +0.0111 -0.0222 1.9635 +0.0167 -0.0333 1.9635 +0.0222 -0.0444 1.9635 +0.0278 -0.0556 1.9635 +0.0333 -0.0667 1.9635 +0.0389 -0.0778 1.9635 +0.0444 -0.0889 1.9635 +0.0500 -0.1000 1.9635 +primID: 3 +startangle_c: 5 +endpose_c: -4 5 6 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0184 0.0298 1.9938 +-0.0379 0.0592 2.0241 +-0.0583 0.0881 2.0544 +-0.0796 0.1165 2.0847 +-0.1019 0.1444 2.1150 +-0.1251 0.1717 2.1453 +-0.1492 0.1984 2.1756 +-0.1742 0.2245 2.2059 +-0.2000 0.2500 2.2362 +primID: 4 +startangle_c: 5 +endpose_c: -2 7 4 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0156 0.0377 1.9635 +-0.0312 0.0754 1.9635 +-0.0468 0.1131 1.9635 +-0.0623 0.1508 1.9444 +-0.0758 0.1893 1.8697 +-0.0863 0.2287 1.7950 +-0.0939 0.2687 1.7202 +-0.0985 0.3092 1.6455 +-0.1000 0.3500 1.5708 +primID: 5 +startangle_c: 5 +endpose_c: 0 0 6 +additionalactioncostmult: 200 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0000 0.0000 2.0071 +0.0000 0.0000 2.0508 +0.0000 0.0000 2.0944 +0.0000 0.0000 2.1380 +0.0000 0.0000 2.1817 +0.0000 0.0000 2.2253 +0.0000 0.0000 2.2689 +0.0000 0.0000 2.3126 +0.0000 0.0000 2.3562 +primID: 6 +startangle_c: 5 +endpose_c: 0 0 4 +additionalactioncostmult: 200 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0000 0.0000 1.9199 +0.0000 0.0000 1.8762 +0.0000 0.0000 1.8326 +0.0000 0.0000 1.7890 +0.0000 0.0000 1.7453 +0.0000 0.0000 1.7017 +0.0000 0.0000 1.6581 +0.0000 0.0000 1.6144 +0.0000 0.0000 1.5708 +primID: 0 +startangle_c: 6 +endpose_c: -1 1 6 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0056 0.0056 2.3562 +-0.0111 0.0111 2.3562 +-0.0167 0.0167 2.3562 +-0.0222 0.0222 2.3562 +-0.0278 0.0278 2.3562 +-0.0333 0.0333 2.3562 +-0.0389 0.0389 2.3562 +-0.0444 0.0444 2.3562 +-0.0500 0.0500 2.3562 +primID: 1 +startangle_c: 6 +endpose_c: -6 6 6 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0333 0.0333 2.3562 +-0.0667 0.0667 2.3562 +-0.1000 0.1000 2.3562 +-0.1333 0.1333 2.3562 +-0.1667 0.1667 2.3562 +-0.2000 0.2000 2.3562 +-0.2333 0.2333 2.3562 +-0.2667 0.2667 2.3562 +-0.3000 0.3000 2.3562 +primID: 2 +startangle_c: 6 +endpose_c: 1 -1 6 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0056 -0.0056 2.3562 +0.0111 -0.0111 2.3562 +0.0167 -0.0167 2.3562 +0.0222 -0.0222 2.3562 +0.0278 -0.0278 2.3562 +0.0333 -0.0333 2.3562 +0.0389 -0.0389 2.3562 +0.0444 -0.0444 2.3562 +0.0500 -0.0500 2.3562 +primID: 3 +startangle_c: 6 +endpose_c: -7 5 7 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0341 0.0341 2.3562 +-0.0684 0.0678 2.3859 +-0.1043 0.1000 2.4377 +-0.1418 0.1302 2.4896 +-0.1809 0.1584 2.5415 +-0.2213 0.1846 2.5933 +-0.2631 0.2086 2.6452 +-0.3060 0.2304 2.6970 +-0.3500 0.2500 2.7489 +primID: 4 +startangle_c: 6 +endpose_c: -5 7 5 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0341 0.0341 2.3562 +-0.0678 0.0684 2.3265 +-0.1000 0.1043 2.2747 +-0.1302 0.1418 2.2228 +-0.1584 0.1809 2.1709 +-0.1846 0.2213 2.1191 +-0.2086 0.2631 2.0672 +-0.2304 0.3060 2.0154 +-0.2500 0.3500 1.9635 +primID: 5 +startangle_c: 6 +endpose_c: 0 0 7 +additionalactioncostmult: 200 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0000 0.0000 2.3998 +0.0000 0.0000 2.4435 +0.0000 0.0000 2.4871 +0.0000 0.0000 2.5307 +0.0000 0.0000 2.5744 +0.0000 0.0000 2.6180 +0.0000 0.0000 2.6616 +0.0000 0.0000 2.7053 +0.0000 0.0000 2.7489 +primID: 6 +startangle_c: 6 +endpose_c: 0 0 5 +additionalactioncostmult: 200 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0000 0.0000 2.3126 +0.0000 0.0000 2.2689 +0.0000 0.0000 2.2253 +0.0000 0.0000 2.1817 +0.0000 0.0000 2.1380 +0.0000 0.0000 2.0944 +0.0000 0.0000 2.0508 +0.0000 0.0000 2.0071 +0.0000 0.0000 1.9635 +primID: 0 +startangle_c: 7 +endpose_c: -2 1 7 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0111 0.0056 2.7489 +-0.0222 0.0111 2.7489 +-0.0333 0.0167 2.7489 +-0.0444 0.0222 2.7489 +-0.0556 0.0278 2.7489 +-0.0667 0.0333 2.7489 +-0.0778 0.0389 2.7489 +-0.0889 0.0444 2.7489 +-0.1000 0.0500 2.7489 +primID: 1 +startangle_c: 7 +endpose_c: -6 3 7 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0333 0.0167 2.7489 +-0.0667 0.0333 2.7489 +-0.1000 0.0500 2.7489 +-0.1333 0.0667 2.7489 +-0.1667 0.0833 2.7489 +-0.2000 0.1000 2.7489 +-0.2333 0.1167 2.7489 +-0.2667 0.1333 2.7489 +-0.3000 0.1500 2.7489 +primID: 2 +startangle_c: 7 +endpose_c: 2 -1 7 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0111 -0.0056 2.7489 +0.0222 -0.0111 2.7489 +0.0333 -0.0167 2.7489 +0.0444 -0.0222 2.7489 +0.0556 -0.0278 2.7489 +0.0667 -0.0333 2.7489 +0.0778 -0.0389 2.7489 +0.0889 -0.0444 2.7489 +0.1000 -0.0500 2.7489 +primID: 3 +startangle_c: 7 +endpose_c: -5 4 6 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0298 0.0184 2.7186 +-0.0592 0.0379 2.6883 +-0.0881 0.0583 2.6580 +-0.1165 0.0796 2.6277 +-0.1444 0.1019 2.5974 +-0.1717 0.1251 2.5671 +-0.1984 0.1492 2.5368 +-0.2245 0.1742 2.5065 +-0.2500 0.2000 2.4762 +primID: 4 +startangle_c: 7 +endpose_c: -7 2 8 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0377 0.0156 2.7489 +-0.0754 0.0312 2.7489 +-0.1131 0.0468 2.7489 +-0.1508 0.0623 2.7680 +-0.1893 0.0758 2.8427 +-0.2287 0.0863 2.9174 +-0.2687 0.0939 2.9921 +-0.3092 0.0985 3.0669 +-0.3500 0.1000 3.1416 +primID: 5 +startangle_c: 7 +endpose_c: 0 0 6 +additionalactioncostmult: 200 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0000 0.0000 2.7053 +0.0000 0.0000 2.6616 +0.0000 0.0000 2.6180 +0.0000 0.0000 2.5744 +0.0000 0.0000 2.5307 +0.0000 0.0000 2.4871 +0.0000 0.0000 2.4435 +0.0000 0.0000 2.3998 +0.0000 0.0000 2.3562 +primID: 6 +startangle_c: 7 +endpose_c: 0 0 8 +additionalactioncostmult: 200 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0000 0.0000 2.7925 +0.0000 0.0000 2.8362 +0.0000 0.0000 2.8798 +0.0000 0.0000 2.9234 +0.0000 0.0000 2.9671 +0.0000 0.0000 3.0107 +0.0000 0.0000 3.0543 +0.0000 0.0000 3.0980 +0.0000 0.0000 3.1416 +primID: 0 +startangle_c: 8 +endpose_c: -1 0 8 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0056 0.0000 3.1416 +-0.0111 0.0000 3.1416 +-0.0167 0.0000 3.1416 +-0.0222 0.0000 3.1416 +-0.0278 0.0000 3.1416 +-0.0333 0.0000 3.1416 +-0.0389 0.0000 3.1416 +-0.0444 0.0000 3.1416 +-0.0500 0.0000 3.1416 +primID: 1 +startangle_c: 8 +endpose_c: -8 0 8 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0444 0.0000 3.1416 +-0.0889 0.0000 3.1416 +-0.1333 0.0000 3.1416 +-0.1778 0.0000 3.1416 +-0.2222 0.0000 3.1416 +-0.2667 0.0000 3.1416 +-0.3111 0.0000 3.1416 +-0.3556 0.0000 3.1416 +-0.4000 0.0000 3.1416 +primID: 2 +startangle_c: 8 +endpose_c: 1 0 8 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0056 0.0000 3.1416 +0.0111 0.0000 3.1416 +0.0167 0.0000 3.1416 +0.0222 0.0000 3.1416 +0.0278 0.0000 3.1416 +0.0333 0.0000 3.1416 +0.0389 0.0000 3.1416 +0.0444 0.0000 3.1416 +0.0500 0.0000 3.1416 +primID: 3 +startangle_c: 8 +endpose_c: -8 -1 9 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0452 0.0000 3.1416 +-0.0904 0.0000 3.1416 +-0.1355 0.0000 3.1416 +-0.1807 -0.0008 3.1904 +-0.2257 -0.0045 3.2592 +-0.2703 -0.0114 3.3280 +-0.3144 -0.0213 3.3967 +-0.3577 -0.0342 3.4655 +-0.4000 -0.0500 3.5343 +primID: 4 +startangle_c: 8 +endpose_c: -8 1 7 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0452 0.0000 3.1416 +-0.0904 0.0000 3.1416 +-0.1355 0.0000 3.1416 +-0.1807 0.0008 3.0928 +-0.2257 0.0045 3.0240 +-0.2703 0.0114 2.9552 +-0.3144 0.0213 2.8864 +-0.3577 0.0342 2.8177 +-0.4000 0.0500 2.7489 +primID: 5 +startangle_c: 8 +endpose_c: 0 0 9 +additionalactioncostmult: 200 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0000 0.0000 3.1852 +0.0000 0.0000 3.2289 +0.0000 0.0000 3.2725 +0.0000 0.0000 3.3161 +0.0000 0.0000 3.3598 +0.0000 0.0000 3.4034 +0.0000 0.0000 3.4470 +0.0000 0.0000 3.4907 +0.0000 0.0000 3.5343 +primID: 6 +startangle_c: 8 +endpose_c: 0 0 7 +additionalactioncostmult: 200 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0000 0.0000 3.0980 +0.0000 0.0000 3.0543 +0.0000 0.0000 3.0107 +0.0000 0.0000 2.9671 +0.0000 0.0000 2.9234 +0.0000 0.0000 2.8798 +0.0000 0.0000 2.8362 +0.0000 0.0000 2.7925 +0.0000 0.0000 2.7489 +primID: 0 +startangle_c: 9 +endpose_c: -2 -1 9 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0111 -0.0056 3.5343 +-0.0222 -0.0111 3.5343 +-0.0333 -0.0167 3.5343 +-0.0444 -0.0222 3.5343 +-0.0556 -0.0278 3.5343 +-0.0667 -0.0333 3.5343 +-0.0778 -0.0389 3.5343 +-0.0889 -0.0444 3.5343 +-0.1000 -0.0500 3.5343 +primID: 1 +startangle_c: 9 +endpose_c: -6 -3 9 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0333 -0.0167 3.5343 +-0.0667 -0.0333 3.5343 +-0.1000 -0.0500 3.5343 +-0.1333 -0.0667 3.5343 +-0.1667 -0.0833 3.5343 +-0.2000 -0.1000 3.5343 +-0.2333 -0.1167 3.5343 +-0.2667 -0.1333 3.5343 +-0.3000 -0.1500 3.5343 +primID: 2 +startangle_c: 9 +endpose_c: 2 1 9 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0111 0.0056 3.5343 +0.0222 0.0111 3.5343 +0.0333 0.0167 3.5343 +0.0444 0.0222 3.5343 +0.0556 0.0278 3.5343 +0.0667 0.0333 3.5343 +0.0778 0.0389 3.5343 +0.0889 0.0444 3.5343 +0.1000 0.0500 3.5343 +primID: 3 +startangle_c: 9 +endpose_c: -5 -4 10 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0298 -0.0184 3.5646 +-0.0592 -0.0379 3.5949 +-0.0881 -0.0583 3.6252 +-0.1165 -0.0796 3.6555 +-0.1444 -0.1019 3.6858 +-0.1717 -0.1251 3.7161 +-0.1984 -0.1492 3.7464 +-0.2245 -0.1742 3.7767 +-0.2500 -0.2000 3.8070 +primID: 4 +startangle_c: 9 +endpose_c: -7 -2 8 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0377 -0.0156 3.5343 +-0.0754 -0.0312 3.5343 +-0.1131 -0.0468 3.5343 +-0.1508 -0.0623 3.5152 +-0.1893 -0.0758 3.4405 +-0.2287 -0.0863 3.3658 +-0.2687 -0.0939 3.2910 +-0.3092 -0.0985 3.2163 +-0.3500 -0.1000 3.1416 +primID: 5 +startangle_c: 9 +endpose_c: 0 0 10 +additionalactioncostmult: 200 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0000 0.0000 3.5779 +0.0000 0.0000 3.6216 +0.0000 0.0000 3.6652 +0.0000 0.0000 3.7088 +0.0000 0.0000 3.7525 +0.0000 0.0000 3.7961 +0.0000 0.0000 3.8397 +0.0000 0.0000 3.8834 +0.0000 0.0000 3.9270 +primID: 6 +startangle_c: 9 +endpose_c: 0 0 8 +additionalactioncostmult: 200 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0000 0.0000 3.4907 +0.0000 0.0000 3.4470 +0.0000 0.0000 3.4034 +0.0000 0.0000 3.3598 +0.0000 0.0000 3.3161 +0.0000 0.0000 3.2725 +0.0000 0.0000 3.2289 +0.0000 0.0000 3.1852 +0.0000 0.0000 3.1416 +primID: 0 +startangle_c: 10 +endpose_c: -1 -1 10 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0056 -0.0056 3.9270 +-0.0111 -0.0111 3.9270 +-0.0167 -0.0167 3.9270 +-0.0222 -0.0222 3.9270 +-0.0278 -0.0278 3.9270 +-0.0333 -0.0333 3.9270 +-0.0389 -0.0389 3.9270 +-0.0444 -0.0444 3.9270 +-0.0500 -0.0500 3.9270 +primID: 1 +startangle_c: 10 +endpose_c: -6 -6 10 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0333 -0.0333 3.9270 +-0.0667 -0.0667 3.9270 +-0.1000 -0.1000 3.9270 +-0.1333 -0.1333 3.9270 +-0.1667 -0.1667 3.9270 +-0.2000 -0.2000 3.9270 +-0.2333 -0.2333 3.9270 +-0.2667 -0.2667 3.9270 +-0.3000 -0.3000 3.9270 +primID: 2 +startangle_c: 10 +endpose_c: 1 1 10 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0056 0.0056 3.9270 +0.0111 0.0111 3.9270 +0.0167 0.0167 3.9270 +0.0222 0.0222 3.9270 +0.0278 0.0278 3.9270 +0.0333 0.0333 3.9270 +0.0389 0.0389 3.9270 +0.0444 0.0444 3.9270 +0.0500 0.0500 3.9270 +primID: 3 +startangle_c: 10 +endpose_c: -5 -7 11 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0341 -0.0341 3.9270 +-0.0678 -0.0684 3.9567 +-0.1000 -0.1043 4.0085 +-0.1302 -0.1418 4.0604 +-0.1584 -0.1809 4.1123 +-0.1846 -0.2213 4.1641 +-0.2086 -0.2631 4.2160 +-0.2304 -0.3060 4.2678 +-0.2500 -0.3500 4.3197 +primID: 4 +startangle_c: 10 +endpose_c: -7 -5 9 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0341 -0.0341 3.9270 +-0.0684 -0.0678 3.8973 +-0.1043 -0.1000 3.8455 +-0.1418 -0.1302 3.7936 +-0.1809 -0.1584 3.7417 +-0.2213 -0.1846 3.6899 +-0.2631 -0.2086 3.6380 +-0.3060 -0.2304 3.5862 +-0.3500 -0.2500 3.5343 +primID: 5 +startangle_c: 10 +endpose_c: 0 0 11 +additionalactioncostmult: 200 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.9706 +0.0000 0.0000 4.0143 +0.0000 0.0000 4.0579 +0.0000 0.0000 4.1015 +0.0000 0.0000 4.1452 +0.0000 0.0000 4.1888 +0.0000 0.0000 4.2324 +0.0000 0.0000 4.2761 +0.0000 0.0000 4.3197 +primID: 6 +startangle_c: 10 +endpose_c: 0 0 9 +additionalactioncostmult: 200 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.8834 +0.0000 0.0000 3.8397 +0.0000 0.0000 3.7961 +0.0000 0.0000 3.7525 +0.0000 0.0000 3.7088 +0.0000 0.0000 3.6652 +0.0000 0.0000 3.6216 +0.0000 0.0000 3.5779 +0.0000 0.0000 3.5343 +primID: 0 +startangle_c: 11 +endpose_c: -1 -2 11 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0056 -0.0111 4.3197 +-0.0111 -0.0222 4.3197 +-0.0167 -0.0333 4.3197 +-0.0222 -0.0444 4.3197 +-0.0278 -0.0556 4.3197 +-0.0333 -0.0667 4.3197 +-0.0389 -0.0778 4.3197 +-0.0444 -0.0889 4.3197 +-0.0500 -0.1000 4.3197 +primID: 1 +startangle_c: 11 +endpose_c: -3 -6 11 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0167 -0.0333 4.3197 +-0.0333 -0.0667 4.3197 +-0.0500 -0.1000 4.3197 +-0.0667 -0.1333 4.3197 +-0.0833 -0.1667 4.3197 +-0.1000 -0.2000 4.3197 +-0.1167 -0.2333 4.3197 +-0.1333 -0.2667 4.3197 +-0.1500 -0.3000 4.3197 +primID: 2 +startangle_c: 11 +endpose_c: 1 2 11 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0056 0.0111 4.3197 +0.0111 0.0222 4.3197 +0.0167 0.0333 4.3197 +0.0222 0.0444 4.3197 +0.0278 0.0556 4.3197 +0.0333 0.0667 4.3197 +0.0389 0.0778 4.3197 +0.0444 0.0889 4.3197 +0.0500 0.1000 4.3197 +primID: 3 +startangle_c: 11 +endpose_c: -4 -5 10 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0184 -0.0298 4.2894 +-0.0379 -0.0592 4.2591 +-0.0583 -0.0881 4.2288 +-0.0796 -0.1165 4.1985 +-0.1019 -0.1444 4.1682 +-0.1251 -0.1717 4.1379 +-0.1492 -0.1984 4.1076 +-0.1742 -0.2245 4.0773 +-0.2000 -0.2500 4.0470 +primID: 4 +startangle_c: 11 +endpose_c: -2 -7 12 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0156 -0.0377 4.3197 +-0.0312 -0.0754 4.3197 +-0.0468 -0.1131 4.3197 +-0.0623 -0.1508 4.3388 +-0.0758 -0.1893 4.4135 +-0.0863 -0.2287 4.4882 +-0.0939 -0.2687 4.5629 +-0.0985 -0.3092 4.6377 +-0.1000 -0.3500 4.7124 +primID: 5 +startangle_c: 11 +endpose_c: 0 0 10 +additionalactioncostmult: 200 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0000 0.0000 4.2761 +0.0000 0.0000 4.2324 +0.0000 0.0000 4.1888 +0.0000 0.0000 4.1452 +0.0000 0.0000 4.1015 +0.0000 0.0000 4.0579 +0.0000 0.0000 4.0143 +0.0000 0.0000 3.9706 +0.0000 0.0000 3.9270 +primID: 6 +startangle_c: 11 +endpose_c: 0 0 12 +additionalactioncostmult: 200 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0000 0.0000 4.3633 +0.0000 0.0000 4.4070 +0.0000 0.0000 4.4506 +0.0000 0.0000 4.4942 +0.0000 0.0000 4.5379 +0.0000 0.0000 4.5815 +0.0000 0.0000 4.6251 +0.0000 0.0000 4.6688 +0.0000 0.0000 4.7124 +primID: 0 +startangle_c: 12 +endpose_c: 0 -1 12 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0056 4.7124 +0.0000 -0.0111 4.7124 +0.0000 -0.0167 4.7124 +0.0000 -0.0222 4.7124 +0.0000 -0.0278 4.7124 +0.0000 -0.0333 4.7124 +0.0000 -0.0389 4.7124 +0.0000 -0.0444 4.7124 +0.0000 -0.0500 4.7124 +primID: 1 +startangle_c: 12 +endpose_c: 0 -8 12 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0444 4.7124 +0.0000 -0.0889 4.7124 +0.0000 -0.1333 4.7124 +0.0000 -0.1778 4.7124 +0.0000 -0.2222 4.7124 +0.0000 -0.2667 4.7124 +0.0000 -0.3111 4.7124 +0.0000 -0.3556 4.7124 +0.0000 -0.4000 4.7124 +primID: 2 +startangle_c: 12 +endpose_c: 0 1 12 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0056 4.7124 +0.0000 0.0111 4.7124 +0.0000 0.0167 4.7124 +0.0000 0.0222 4.7124 +0.0000 0.0278 4.7124 +0.0000 0.0333 4.7124 +0.0000 0.0389 4.7124 +0.0000 0.0444 4.7124 +0.0000 0.0500 4.7124 +primID: 3 +startangle_c: 12 +endpose_c: 1 -8 13 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0452 4.7124 +0.0000 -0.0904 4.7124 +0.0000 -0.1355 4.7124 +0.0008 -0.1807 4.7612 +0.0045 -0.2257 4.8300 +0.0114 -0.2703 4.8988 +0.0213 -0.3144 4.9675 +0.0342 -0.3577 5.0363 +0.0500 -0.4000 5.1051 +primID: 4 +startangle_c: 12 +endpose_c: -1 -8 11 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.7124 +-0.0000 -0.0452 4.7124 +-0.0000 -0.0904 4.7124 +-0.0000 -0.1355 4.7124 +-0.0008 -0.1807 4.6636 +-0.0045 -0.2257 4.5948 +-0.0114 -0.2703 4.5260 +-0.0213 -0.3144 4.4572 +-0.0342 -0.3577 4.3885 +-0.0500 -0.4000 4.3197 +primID: 5 +startangle_c: 12 +endpose_c: 0 0 13 +additionalactioncostmult: 200 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0000 4.7560 +0.0000 0.0000 4.7997 +0.0000 0.0000 4.8433 +0.0000 0.0000 4.8869 +0.0000 0.0000 4.9306 +0.0000 0.0000 4.9742 +0.0000 0.0000 5.0178 +0.0000 0.0000 5.0615 +0.0000 0.0000 5.1051 +primID: 6 +startangle_c: 12 +endpose_c: 0 0 11 +additionalactioncostmult: 200 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0000 4.6688 +0.0000 0.0000 4.6251 +0.0000 0.0000 4.5815 +0.0000 0.0000 4.5379 +0.0000 0.0000 4.4942 +0.0000 0.0000 4.4506 +0.0000 0.0000 4.4070 +0.0000 0.0000 4.3633 +0.0000 0.0000 4.3197 +primID: 0 +startangle_c: 13 +endpose_c: 1 -2 13 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0056 -0.0111 5.1051 +0.0111 -0.0222 5.1051 +0.0167 -0.0333 5.1051 +0.0222 -0.0444 5.1051 +0.0278 -0.0556 5.1051 +0.0333 -0.0667 5.1051 +0.0389 -0.0778 5.1051 +0.0444 -0.0889 5.1051 +0.0500 -0.1000 5.1051 +primID: 1 +startangle_c: 13 +endpose_c: 3 -6 13 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0167 -0.0333 5.1051 +0.0333 -0.0667 5.1051 +0.0500 -0.1000 5.1051 +0.0667 -0.1333 5.1051 +0.0833 -0.1667 5.1051 +0.1000 -0.2000 5.1051 +0.1167 -0.2333 5.1051 +0.1333 -0.2667 5.1051 +0.1500 -0.3000 5.1051 +primID: 2 +startangle_c: 13 +endpose_c: -1 2 13 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.1051 +-0.0056 0.0111 5.1051 +-0.0111 0.0222 5.1051 +-0.0167 0.0333 5.1051 +-0.0222 0.0444 5.1051 +-0.0278 0.0556 5.1051 +-0.0333 0.0667 5.1051 +-0.0389 0.0778 5.1051 +-0.0444 0.0889 5.1051 +-0.0500 0.1000 5.1051 +primID: 3 +startangle_c: 13 +endpose_c: 4 -5 14 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0184 -0.0298 5.1354 +0.0379 -0.0592 5.1657 +0.0583 -0.0881 5.1960 +0.0796 -0.1165 5.2263 +0.1019 -0.1444 5.2566 +0.1251 -0.1717 5.2869 +0.1492 -0.1984 5.3172 +0.1742 -0.2245 5.3475 +0.2000 -0.2500 5.3778 +primID: 4 +startangle_c: 13 +endpose_c: 2 -7 12 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0156 -0.0377 5.1051 +0.0312 -0.0754 5.1051 +0.0468 -0.1131 5.1051 +0.0623 -0.1508 5.0860 +0.0758 -0.1893 5.0113 +0.0863 -0.2287 4.9366 +0.0939 -0.2687 4.8618 +0.0985 -0.3092 4.7871 +0.1000 -0.3500 4.7124 +primID: 5 +startangle_c: 13 +endpose_c: 0 0 14 +additionalactioncostmult: 200 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0000 0.0000 5.1487 +0.0000 0.0000 5.1924 +0.0000 0.0000 5.2360 +0.0000 0.0000 5.2796 +0.0000 0.0000 5.3233 +0.0000 0.0000 5.3669 +0.0000 0.0000 5.4105 +0.0000 0.0000 5.4542 +0.0000 0.0000 5.4978 +primID: 6 +startangle_c: 13 +endpose_c: 0 0 12 +additionalactioncostmult: 200 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0000 0.0000 5.0615 +0.0000 0.0000 5.0178 +0.0000 0.0000 4.9742 +0.0000 0.0000 4.9306 +0.0000 0.0000 4.8869 +0.0000 0.0000 4.8433 +0.0000 0.0000 4.7997 +0.0000 0.0000 4.7560 +0.0000 0.0000 4.7124 +primID: 0 +startangle_c: 14 +endpose_c: 1 -1 14 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0056 -0.0056 5.4978 +0.0111 -0.0111 5.4978 +0.0167 -0.0167 5.4978 +0.0222 -0.0222 5.4978 +0.0278 -0.0278 5.4978 +0.0333 -0.0333 5.4978 +0.0389 -0.0389 5.4978 +0.0444 -0.0444 5.4978 +0.0500 -0.0500 5.4978 +primID: 1 +startangle_c: 14 +endpose_c: 6 -6 14 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0333 -0.0333 5.4978 +0.0667 -0.0667 5.4978 +0.1000 -0.1000 5.4978 +0.1333 -0.1333 5.4978 +0.1667 -0.1667 5.4978 +0.2000 -0.2000 5.4978 +0.2333 -0.2333 5.4978 +0.2667 -0.2667 5.4978 +0.3000 -0.3000 5.4978 +primID: 2 +startangle_c: 14 +endpose_c: -1 1 14 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.4978 +-0.0056 0.0056 5.4978 +-0.0111 0.0111 5.4978 +-0.0167 0.0167 5.4978 +-0.0222 0.0222 5.4978 +-0.0278 0.0278 5.4978 +-0.0333 0.0333 5.4978 +-0.0389 0.0389 5.4978 +-0.0444 0.0444 5.4978 +-0.0500 0.0500 5.4978 +primID: 3 +startangle_c: 14 +endpose_c: 7 -5 15 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0341 -0.0341 5.4978 +0.0684 -0.0678 5.5275 +0.1043 -0.1000 5.5793 +0.1418 -0.1302 5.6312 +0.1809 -0.1584 5.6830 +0.2213 -0.1846 5.7349 +0.2631 -0.2086 5.7868 +0.3060 -0.2304 5.8386 +0.3500 -0.2500 5.8905 +primID: 4 +startangle_c: 14 +endpose_c: 5 -7 13 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0341 -0.0341 5.4978 +0.0678 -0.0684 5.4681 +0.1000 -0.1043 5.4162 +0.1302 -0.1418 5.3644 +0.1584 -0.1809 5.3125 +0.1846 -0.2213 5.2607 +0.2086 -0.2631 5.2088 +0.2304 -0.3060 5.1569 +0.2500 -0.3500 5.1051 +primID: 5 +startangle_c: 14 +endpose_c: 0 0 15 +additionalactioncostmult: 200 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0000 0.0000 5.5414 +0.0000 0.0000 5.5851 +0.0000 0.0000 5.6287 +0.0000 0.0000 5.6723 +0.0000 0.0000 5.7160 +0.0000 0.0000 5.7596 +0.0000 0.0000 5.8032 +0.0000 0.0000 5.8469 +0.0000 0.0000 5.8905 +primID: 6 +startangle_c: 14 +endpose_c: 0 0 13 +additionalactioncostmult: 200 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0000 0.0000 5.4542 +0.0000 0.0000 5.4105 +0.0000 0.0000 5.3669 +0.0000 0.0000 5.3233 +0.0000 0.0000 5.2796 +0.0000 0.0000 5.2360 +0.0000 0.0000 5.1924 +0.0000 0.0000 5.1487 +0.0000 0.0000 5.1051 +primID: 0 +startangle_c: 15 +endpose_c: 2 -1 15 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0111 -0.0056 5.8905 +0.0222 -0.0111 5.8905 +0.0333 -0.0167 5.8905 +0.0444 -0.0222 5.8905 +0.0556 -0.0278 5.8905 +0.0667 -0.0333 5.8905 +0.0778 -0.0389 5.8905 +0.0889 -0.0444 5.8905 +0.1000 -0.0500 5.8905 +primID: 1 +startangle_c: 15 +endpose_c: 6 -3 15 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0333 -0.0167 5.8905 +0.0667 -0.0333 5.8905 +0.1000 -0.0500 5.8905 +0.1333 -0.0667 5.8905 +0.1667 -0.0833 5.8905 +0.2000 -0.1000 5.8905 +0.2333 -0.1167 5.8905 +0.2667 -0.1333 5.8905 +0.3000 -0.1500 5.8905 +primID: 2 +startangle_c: 15 +endpose_c: -2 1 15 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.8905 +-0.0111 0.0056 5.8905 +-0.0222 0.0111 5.8905 +-0.0333 0.0167 5.8905 +-0.0444 0.0222 5.8905 +-0.0556 0.0278 5.8905 +-0.0667 0.0333 5.8905 +-0.0778 0.0389 5.8905 +-0.0889 0.0444 5.8905 +-0.1000 0.0500 5.8905 +primID: 3 +startangle_c: 15 +endpose_c: 5 -4 14 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0298 -0.0184 5.8602 +0.0592 -0.0379 5.8299 +0.0881 -0.0583 5.7996 +0.1165 -0.0796 5.7693 +0.1444 -0.1019 5.7390 +0.1717 -0.1251 5.7087 +0.1984 -0.1492 5.6784 +0.2245 -0.1742 5.6481 +0.2500 -0.2000 5.6178 +primID: 4 +startangle_c: 15 +endpose_c: 7 -2 0 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0377 -0.0156 5.8905 +0.0754 -0.0312 5.8905 +0.1131 -0.0468 5.8905 +0.1508 -0.0623 5.9096 +0.1893 -0.0758 5.9843 +0.2287 -0.0863 6.0590 +0.2687 -0.0939 6.1337 +0.3092 -0.0985 6.2085 +0.3500 -0.1000 6.2832 +primID: 5 +startangle_c: 15 +endpose_c: 0 0 14 +additionalactioncostmult: 200 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0000 0.0000 5.8469 +0.0000 0.0000 5.8032 +0.0000 0.0000 5.7596 +0.0000 0.0000 5.7160 +0.0000 0.0000 5.6723 +0.0000 0.0000 5.6287 +0.0000 0.0000 5.5851 +0.0000 0.0000 5.5414 +0.0000 0.0000 5.4978 +primID: 6 +startangle_c: 15 +endpose_c: 0 0 0 +additionalactioncostmult: 200 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0000 0.0000 5.2360 +0.0000 0.0000 4.5815 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.2725 +0.0000 0.0000 2.6180 +0.0000 0.0000 1.9635 +0.0000 0.0000 1.3090 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.0000 diff --git a/navigations/sbpl_lattice_planner/matlab/mprim/unicycle_5cm_noreverse_trolley.mprim b/navigations/sbpl_lattice_planner/matlab/mprim/unicycle_5cm_noreverse_trolley.mprim new file mode 100755 index 0000000..596f5c5 --- /dev/null +++ b/navigations/sbpl_lattice_planner/matlab/mprim/unicycle_5cm_noreverse_trolley.mprim @@ -0,0 +1,2403 @@ +resolution_m: 0.050000 +numberofangles: 16 +totalnumberofprimitives: 160 +primID: 0 +startangle_c: 0 +endpose_c: 1 0 0 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0056 0.0000 0.0000 +0.0111 0.0000 0.0000 +0.0167 0.0000 0.0000 +0.0222 0.0000 0.0000 +0.0278 0.0000 0.0000 +0.0333 0.0000 0.0000 +0.0389 0.0000 0.0000 +0.0444 0.0000 0.0000 +0.0500 0.0000 0.0000 +primID: 1 +startangle_c: 0 +endpose_c: 8 0 0 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0444 0.0000 0.0000 +0.0889 0.0000 0.0000 +0.1333 0.0000 0.0000 +0.1778 0.0000 0.0000 +0.2222 0.0000 0.0000 +0.2667 0.0000 0.0000 +0.3111 0.0000 0.0000 +0.3556 0.0000 0.0000 +0.4000 0.0000 0.0000 +primID: 2 +startangle_c: 0 +endpose_c: 16 4 1 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0904 0.0095 0.0349 +0.1806 0.0222 0.0699 +0.2707 0.0381 0.1048 +0.3604 0.0572 0.1398 +0.4496 0.0795 0.1747 +0.5383 0.1050 0.2097 +0.6264 0.1335 0.2446 +0.7136 0.1652 0.2796 +0.8000 0.2000 0.3145 +primID: 3 +startangle_c: 0 +endpose_c: 16 -4 -1 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0904 -0.0095 -0.0349 +0.1806 -0.0222 -0.0699 +0.2707 -0.0381 -0.1048 +0.3604 -0.0572 -0.1398 +0.4496 -0.0795 -0.1747 +0.5383 -0.1050 -0.2097 +0.6264 -0.1335 -0.2446 +0.7136 -0.1652 -0.2796 +0.8000 -0.2000 -0.3145 +primID: 4 +startangle_c: 0 +endpose_c: 5 2 1 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0280 0.0085 0.0223 +0.0559 0.0177 0.0445 +0.0839 0.0275 0.0668 +0.1117 0.0380 0.0890 +0.1396 0.0491 0.1113 +0.1673 0.0609 0.1335 +0.1950 0.0733 0.1558 +0.2225 0.0863 0.1781 +0.2500 0.1000 0.2003 +primID: 5 +startangle_c: 0 +endpose_c: 5 -2 -1 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0280 -0.0085 -0.0223 +0.0559 -0.0177 -0.0445 +0.0839 -0.0275 -0.0668 +0.1117 -0.0380 -0.0890 +0.1396 -0.0491 -0.1113 +0.1673 -0.0609 -0.1335 +0.1950 -0.0733 -0.1558 +0.2225 -0.0863 -0.1781 +0.2500 -0.1000 -0.2003 +primID: 6 +startangle_c: 0 +endpose_c: 0 0 1 +additionalactioncostmult: 1000 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0000 0.0000 0.0436 +0.0000 0.0000 0.0873 +0.0000 0.0000 0.1309 +0.0000 0.0000 0.1745 +0.0000 0.0000 0.2182 +0.0000 0.0000 0.2618 +0.0000 0.0000 0.3054 +0.0000 0.0000 0.3491 +0.0000 0.0000 0.3927 +primID: 7 +startangle_c: 0 +endpose_c: 0 0 -1 +additionalactioncostmult: 1000 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0000 0.0000 -0.0436 +0.0000 0.0000 -0.0873 +0.0000 0.0000 -0.1309 +0.0000 0.0000 -0.1745 +0.0000 0.0000 -0.2182 +0.0000 0.0000 -0.2618 +0.0000 0.0000 -0.3054 +0.0000 0.0000 -0.3491 +0.0000 0.0000 -0.3927 +primID: 8 +startangle_c: 0 +endpose_c: 8 1 0 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0444 0.0056 0.0000 +0.0889 0.0111 0.0000 +0.1333 0.0167 0.0000 +0.1778 0.0222 0.0000 +0.2222 0.0278 0.0000 +0.2667 0.0333 0.0000 +0.3111 0.0389 0.0000 +0.3556 0.0444 0.0000 +0.4000 0.0500 0.0000 +primID: 9 +startangle_c: 0 +endpose_c: 8 -1 0 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0444 -0.0056 0.0000 +0.0889 -0.0111 0.0000 +0.1333 -0.0167 0.0000 +0.1778 -0.0222 0.0000 +0.2222 -0.0278 0.0000 +0.2667 -0.0333 0.0000 +0.3111 -0.0389 0.0000 +0.3556 -0.0444 0.0000 +0.4000 -0.0500 0.0000 +primID: 0 +startangle_c: 1 +endpose_c: 2 1 1 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0111 0.0056 0.3927 +0.0222 0.0111 0.3927 +0.0333 0.0167 0.3927 +0.0444 0.0222 0.3927 +0.0556 0.0278 0.3927 +0.0667 0.0333 0.3927 +0.0778 0.0389 0.3927 +0.0889 0.0444 0.3927 +0.1000 0.0500 0.3927 +primID: 1 +startangle_c: 1 +endpose_c: 6 3 1 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0333 0.0167 0.3927 +0.0667 0.0333 0.3927 +0.1000 0.0500 0.3927 +0.1333 0.0667 0.3927 +0.1667 0.0833 0.3927 +0.2000 0.1000 0.3927 +0.2333 0.1167 0.3927 +0.2667 0.1333 0.3927 +0.3000 0.1500 0.3927 +primID: 2 +startangle_c: 1 +endpose_c: 13 9 2 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0793 0.0378 0.4329 +0.1572 0.0787 0.4732 +0.2334 0.1229 0.5134 +0.3079 0.1701 0.5537 +0.3805 0.2204 0.5939 +0.4512 0.2736 0.6342 +0.5197 0.3296 0.6744 +0.5860 0.3885 0.7147 +0.6500 0.4500 0.7549 +primID: 3 +startangle_c: 1 +endpose_c: 14 3 0 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0741 0.0305 0.3774 +0.1493 0.0582 0.3302 +0.2256 0.0824 0.2830 +0.3031 0.1030 0.2359 +0.3814 0.1199 0.1887 +0.4604 0.1330 0.1415 +0.5400 0.1424 0.0943 +0.6199 0.1481 0.0472 +0.7000 0.1500 -0.0000 +primID: 4 +startangle_c: 1 +endpose_c: 5 4 2 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0298 0.0184 0.4230 +0.0592 0.0379 0.4533 +0.0881 0.0583 0.4836 +0.1165 0.0796 0.5139 +0.1444 0.1019 0.5442 +0.1717 0.1251 0.5745 +0.1984 0.1492 0.6048 +0.2245 0.1742 0.6351 +0.2500 0.2000 0.6654 +primID: 5 +startangle_c: 1 +endpose_c: 6 1 0 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0320 0.0105 0.3551 +0.0644 0.0197 0.3174 +0.0973 0.0278 0.2798 +0.1304 0.0346 0.2421 +0.1639 0.0402 0.2045 +0.1977 0.0446 0.1669 +0.2316 0.0476 0.1292 +0.2658 0.0495 0.0916 +0.3000 0.0500 0.0540 +primID: 6 +startangle_c: 1 +endpose_c: 0 0 2 +additionalactioncostmult: 1000 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0000 0.0000 0.4363 +0.0000 0.0000 0.4800 +0.0000 0.0000 0.5236 +0.0000 0.0000 0.5672 +0.0000 0.0000 0.6109 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.6981 +0.0000 0.0000 0.7418 +0.0000 0.0000 0.7854 +primID: 7 +startangle_c: 1 +endpose_c: 0 0 0 +additionalactioncostmult: 1000 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0000 0.0000 0.3491 +0.0000 0.0000 0.3054 +0.0000 0.0000 0.2618 +0.0000 0.0000 0.2182 +0.0000 0.0000 0.1745 +0.0000 0.0000 0.1309 +0.0000 0.0000 0.0873 +0.0000 0.0000 0.0436 +0.0000 0.0000 0.0000 +primID: 8 +startangle_c: 1 +endpose_c: 7 2 1 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0389 0.0111 0.3927 +0.0778 0.0222 0.3927 +0.1167 0.0333 0.3927 +0.1556 0.0444 0.3927 +0.1944 0.0556 0.3927 +0.2333 0.0667 0.3927 +0.2722 0.0778 0.3927 +0.3111 0.0889 0.3927 +0.3500 0.1000 0.3927 +primID: 9 +startangle_c: 1 +endpose_c: 5 4 1 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0278 0.0222 0.3927 +0.0556 0.0444 0.3927 +0.0833 0.0667 0.3927 +0.1111 0.0889 0.3927 +0.1389 0.1111 0.3927 +0.1667 0.1333 0.3927 +0.1944 0.1556 0.3927 +0.2222 0.1778 0.3927 +0.2500 0.2000 0.3927 +primID: 0 +startangle_c: 2 +endpose_c: 1 1 2 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0056 0.0056 0.7854 +0.0111 0.0111 0.7854 +0.0167 0.0167 0.7854 +0.0222 0.0222 0.7854 +0.0278 0.0278 0.7854 +0.0333 0.0333 0.7854 +0.0389 0.0389 0.7854 +0.0444 0.0444 0.7854 +0.0500 0.0500 0.7854 +primID: 1 +startangle_c: 2 +endpose_c: 6 6 2 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0333 0.0333 0.7854 +0.0667 0.0667 0.7854 +0.1000 0.1000 0.7854 +0.1333 0.1333 0.7854 +0.1667 0.1667 0.7854 +0.2000 0.2000 0.7854 +0.2333 0.2333 0.7854 +0.2667 0.2667 0.7854 +0.3000 0.3000 0.7854 +primID: 2 +startangle_c: 2 +endpose_c: 11 14 3 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0705 0.0705 0.7854 +0.1411 0.1411 0.7854 +0.2116 0.2116 0.7854 +0.2816 0.2828 0.8201 +0.3469 0.3581 0.8917 +0.4068 0.4379 0.9633 +0.4607 0.5218 1.0349 +0.5086 0.6093 1.1065 +0.5500 0.7000 1.1781 +primID: 3 +startangle_c: 2 +endpose_c: 14 11 1 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0705 0.0705 0.7854 +0.1411 0.1411 0.7854 +0.2116 0.2116 0.7854 +0.2828 0.2816 0.7507 +0.3581 0.3469 0.6791 +0.4379 0.4068 0.6075 +0.5218 0.4607 0.5359 +0.6093 0.5086 0.4643 +0.7000 0.5500 0.3927 +primID: 4 +startangle_c: 2 +endpose_c: 4 6 3 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0278 0.0292 0.8288 +0.0543 0.0595 0.8722 +0.0795 0.0910 0.9156 +0.1033 0.1235 0.9590 +0.1257 0.1571 1.0024 +0.1466 0.1916 1.0458 +0.1659 0.2269 1.0892 +0.1838 0.2631 1.1326 +0.2000 0.3000 1.1760 +primID: 5 +startangle_c: 2 +endpose_c: 6 4 1 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0292 0.0278 0.7420 +0.0595 0.0543 0.6986 +0.0910 0.0795 0.6552 +0.1235 0.1033 0.6118 +0.1571 0.1257 0.5684 +0.1916 0.1466 0.5250 +0.2269 0.1659 0.4816 +0.2631 0.1838 0.4382 +0.3000 0.2000 0.3948 +primID: 6 +startangle_c: 2 +endpose_c: 0 0 3 +additionalactioncostmult: 1000 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0000 0.0000 0.8290 +0.0000 0.0000 0.8727 +0.0000 0.0000 0.9163 +0.0000 0.0000 0.9599 +0.0000 0.0000 1.0036 +0.0000 0.0000 1.0472 +0.0000 0.0000 1.0908 +0.0000 0.0000 1.1345 +0.0000 0.0000 1.1781 +primID: 7 +startangle_c: 2 +endpose_c: 0 0 1 +additionalactioncostmult: 1000 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0000 0.0000 0.7418 +0.0000 0.0000 0.6981 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.6109 +0.0000 0.0000 0.5672 +0.0000 0.0000 0.5236 +0.0000 0.0000 0.4800 +0.0000 0.0000 0.4363 +0.0000 0.0000 0.3927 +primID: 8 +startangle_c: 2 +endpose_c: 6 7 2 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0333 0.0389 0.7854 +0.0667 0.0778 0.7854 +0.1000 0.1167 0.7854 +0.1333 0.1556 0.7854 +0.1667 0.1944 0.7854 +0.2000 0.2333 0.7854 +0.2333 0.2722 0.7854 +0.2667 0.3111 0.7854 +0.3000 0.3500 0.7854 +primID: 9 +startangle_c: 2 +endpose_c: 7 6 2 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0389 0.0333 0.7854 +0.0778 0.0667 0.7854 +0.1167 0.1000 0.7854 +0.1556 0.1333 0.7854 +0.1944 0.1667 0.7854 +0.2333 0.2000 0.7854 +0.2722 0.2333 0.7854 +0.3111 0.2667 0.7854 +0.3500 0.3000 0.7854 +primID: 0 +startangle_c: 3 +endpose_c: 1 2 3 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0056 0.0111 1.1781 +0.0111 0.0222 1.1781 +0.0167 0.0333 1.1781 +0.0222 0.0444 1.1781 +0.0278 0.0556 1.1781 +0.0333 0.0667 1.1781 +0.0389 0.0778 1.1781 +0.0444 0.0889 1.1781 +0.0500 0.1000 1.1781 +primID: 1 +startangle_c: 3 +endpose_c: 3 6 3 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0167 0.0333 1.1781 +0.0333 0.0667 1.1781 +0.0500 0.1000 1.1781 +0.0667 0.1333 1.1781 +0.0833 0.1667 1.1781 +0.1000 0.2000 1.1781 +0.1167 0.2333 1.1781 +0.1333 0.2667 1.1781 +0.1500 0.3000 1.1781 +primID: 2 +startangle_c: 3 +endpose_c: 9 13 2 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0378 0.0793 1.1378 +0.0787 0.1572 1.0976 +0.1229 0.2334 1.0574 +0.1701 0.3079 1.0171 +0.2204 0.3805 0.9769 +0.2736 0.4512 0.9366 +0.3296 0.5197 0.8964 +0.3885 0.5860 0.8561 +0.4500 0.6500 0.8159 +primID: 3 +startangle_c: 3 +endpose_c: 3 14 4 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0305 0.0741 1.1934 +0.0582 0.1493 1.2406 +0.0824 0.2256 1.2878 +0.1030 0.3031 1.3349 +0.1199 0.3814 1.3821 +0.1330 0.4604 1.4293 +0.1424 0.5400 1.4765 +0.1481 0.6199 1.5236 +0.1500 0.7000 1.5708 +primID: 4 +startangle_c: 3 +endpose_c: 4 5 2 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0184 0.0298 1.1478 +0.0379 0.0592 1.1175 +0.0583 0.0881 1.0872 +0.0796 0.1165 1.0569 +0.1019 0.1444 1.0266 +0.1251 0.1717 0.9963 +0.1492 0.1984 0.9660 +0.1742 0.2245 0.9357 +0.2000 0.2500 0.9054 +primID: 5 +startangle_c: 3 +endpose_c: 1 6 4 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0105 0.0320 1.2157 +0.0197 0.0644 1.2534 +0.0278 0.0973 1.2910 +0.0346 0.1304 1.3286 +0.0402 0.1639 1.3663 +0.0446 0.1977 1.4039 +0.0476 0.2316 1.4416 +0.0495 0.2658 1.4792 +0.0500 0.3000 1.5168 +primID: 6 +startangle_c: 3 +endpose_c: 0 0 2 +additionalactioncostmult: 1000 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0000 0.0000 1.1345 +0.0000 0.0000 1.0908 +0.0000 0.0000 1.0472 +0.0000 0.0000 1.0036 +0.0000 0.0000 0.9599 +0.0000 0.0000 0.9163 +0.0000 0.0000 0.8727 +0.0000 0.0000 0.8290 +0.0000 0.0000 0.7854 +primID: 7 +startangle_c: 3 +endpose_c: 0 0 4 +additionalactioncostmult: 1000 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0000 0.0000 1.2217 +0.0000 0.0000 1.2654 +0.0000 0.0000 1.3090 +0.0000 0.0000 1.3526 +0.0000 0.0000 1.3963 +0.0000 0.0000 1.4399 +0.0000 0.0000 1.4835 +0.0000 0.0000 1.5272 +0.0000 0.0000 1.5708 +primID: 8 +startangle_c: 3 +endpose_c: 2 7 3 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0111 0.0389 1.1781 +0.0222 0.0778 1.1781 +0.0333 0.1167 1.1781 +0.0444 0.1556 1.1781 +0.0556 0.1944 1.1781 +0.0667 0.2333 1.1781 +0.0778 0.2722 1.1781 +0.0889 0.3111 1.1781 +0.1000 0.3500 1.1781 +primID: 9 +startangle_c: 3 +endpose_c: 4 5 3 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0222 0.0278 1.1781 +0.0444 0.0556 1.1781 +0.0667 0.0833 1.1781 +0.0889 0.1111 1.1781 +0.1111 0.1389 1.1781 +0.1333 0.1667 1.1781 +0.1556 0.1944 1.1781 +0.1778 0.2222 1.1781 +0.2000 0.2500 1.1781 +primID: 0 +startangle_c: 4 +endpose_c: 0 1 4 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0056 1.5708 +0.0000 0.0111 1.5708 +0.0000 0.0167 1.5708 +0.0000 0.0222 1.5708 +0.0000 0.0278 1.5708 +0.0000 0.0333 1.5708 +0.0000 0.0389 1.5708 +0.0000 0.0444 1.5708 +0.0000 0.0500 1.5708 +primID: 1 +startangle_c: 4 +endpose_c: 0 8 4 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0444 1.5708 +0.0000 0.0889 1.5708 +0.0000 0.1333 1.5708 +0.0000 0.1778 1.5708 +0.0000 0.2222 1.5708 +0.0000 0.2667 1.5708 +0.0000 0.3111 1.5708 +0.0000 0.3556 1.5708 +0.0000 0.4000 1.5708 +primID: 2 +startangle_c: 4 +endpose_c: -4 16 5 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.5708 +-0.0095 0.0904 1.6057 +-0.0222 0.1806 1.6407 +-0.0381 0.2707 1.6756 +-0.0572 0.3604 1.7106 +-0.0795 0.4496 1.7455 +-0.1050 0.5383 1.7805 +-0.1335 0.6264 1.8154 +-0.1652 0.7136 1.8503 +-0.2000 0.8000 1.8853 +primID: 3 +startangle_c: 4 +endpose_c: 4 16 3 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0095 0.0904 1.5359 +0.0222 0.1806 1.5009 +0.0381 0.2707 1.4660 +0.0572 0.3604 1.4310 +0.0795 0.4496 1.3961 +0.1050 0.5383 1.3611 +0.1335 0.6264 1.3262 +0.1652 0.7136 1.2912 +0.2000 0.8000 1.2563 +primID: 4 +startangle_c: 4 +endpose_c: -2 5 5 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.5708 +-0.0085 0.0280 1.5931 +-0.0177 0.0559 1.6153 +-0.0275 0.0839 1.6376 +-0.0380 0.1117 1.6598 +-0.0491 0.1396 1.6821 +-0.0609 0.1673 1.7043 +-0.0733 0.1950 1.7266 +-0.0863 0.2225 1.7489 +-0.1000 0.2500 1.7711 +primID: 5 +startangle_c: 4 +endpose_c: 2 5 3 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0085 0.0280 1.5485 +0.0177 0.0559 1.5263 +0.0275 0.0839 1.5040 +0.0380 0.1117 1.4818 +0.0491 0.1396 1.4595 +0.0609 0.1673 1.4373 +0.0733 0.1950 1.4150 +0.0863 0.2225 1.3927 +0.1000 0.2500 1.3705 +primID: 6 +startangle_c: 4 +endpose_c: 0 0 5 +additionalactioncostmult: 1000 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0000 1.6144 +0.0000 0.0000 1.6581 +0.0000 0.0000 1.7017 +0.0000 0.0000 1.7453 +0.0000 0.0000 1.7890 +0.0000 0.0000 1.8326 +0.0000 0.0000 1.8762 +0.0000 0.0000 1.9199 +0.0000 0.0000 1.9635 +primID: 7 +startangle_c: 4 +endpose_c: 0 0 3 +additionalactioncostmult: 1000 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0000 1.5272 +0.0000 0.0000 1.4835 +0.0000 0.0000 1.4399 +0.0000 0.0000 1.3963 +0.0000 0.0000 1.3526 +0.0000 0.0000 1.3090 +0.0000 0.0000 1.2654 +0.0000 0.0000 1.2217 +0.0000 0.0000 1.1781 +primID: 8 +startangle_c: 4 +endpose_c: -1 8 4 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 1.5708 +-0.0056 0.0444 1.5708 +-0.0111 0.0889 1.5708 +-0.0167 0.1333 1.5708 +-0.0222 0.1778 1.5708 +-0.0278 0.2222 1.5708 +-0.0333 0.2667 1.5708 +-0.0389 0.3111 1.5708 +-0.0444 0.3556 1.5708 +-0.0500 0.4000 1.5708 +primID: 9 +startangle_c: 4 +endpose_c: 1 8 4 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0056 0.0444 1.5708 +0.0111 0.0889 1.5708 +0.0167 0.1333 1.5708 +0.0222 0.1778 1.5708 +0.0278 0.2222 1.5708 +0.0333 0.2667 1.5708 +0.0389 0.3111 1.5708 +0.0444 0.3556 1.5708 +0.0500 0.4000 1.5708 +primID: 0 +startangle_c: 5 +endpose_c: -1 2 5 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0056 0.0111 1.9635 +-0.0111 0.0222 1.9635 +-0.0167 0.0333 1.9635 +-0.0222 0.0444 1.9635 +-0.0278 0.0556 1.9635 +-0.0333 0.0667 1.9635 +-0.0389 0.0778 1.9635 +-0.0444 0.0889 1.9635 +-0.0500 0.1000 1.9635 +primID: 1 +startangle_c: 5 +endpose_c: -3 6 5 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0167 0.0333 1.9635 +-0.0333 0.0667 1.9635 +-0.0500 0.1000 1.9635 +-0.0667 0.1333 1.9635 +-0.0833 0.1667 1.9635 +-0.1000 0.2000 1.9635 +-0.1167 0.2333 1.9635 +-0.1333 0.2667 1.9635 +-0.1500 0.3000 1.9635 +primID: 2 +startangle_c: 5 +endpose_c: -9 13 6 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0378 0.0793 2.0037 +-0.0787 0.1572 2.0440 +-0.1229 0.2334 2.0842 +-0.1701 0.3079 2.1245 +-0.2204 0.3805 2.1647 +-0.2736 0.4512 2.2050 +-0.3296 0.5197 2.2452 +-0.3885 0.5860 2.2855 +-0.4500 0.6500 2.3257 +primID: 3 +startangle_c: 5 +endpose_c: -3 14 4 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0305 0.0741 1.9482 +-0.0582 0.1493 1.9010 +-0.0824 0.2256 1.8538 +-0.1030 0.3031 1.8067 +-0.1199 0.3814 1.7595 +-0.1330 0.4604 1.7123 +-0.1424 0.5400 1.6651 +-0.1481 0.6199 1.6180 +-0.1500 0.7000 1.5708 +primID: 4 +startangle_c: 5 +endpose_c: -4 5 6 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0184 0.0298 1.9938 +-0.0379 0.0592 2.0241 +-0.0583 0.0881 2.0544 +-0.0796 0.1165 2.0847 +-0.1019 0.1444 2.1150 +-0.1251 0.1717 2.1453 +-0.1492 0.1984 2.1756 +-0.1742 0.2245 2.2059 +-0.2000 0.2500 2.2362 +primID: 5 +startangle_c: 5 +endpose_c: -1 6 4 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0105 0.0320 1.9259 +-0.0197 0.0644 1.8882 +-0.0278 0.0973 1.8506 +-0.0346 0.1304 1.8129 +-0.0402 0.1639 1.7753 +-0.0446 0.1977 1.7377 +-0.0476 0.2316 1.7000 +-0.0495 0.2658 1.6624 +-0.0500 0.3000 1.6248 +primID: 6 +startangle_c: 5 +endpose_c: 0 0 6 +additionalactioncostmult: 1000 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0000 0.0000 2.0071 +0.0000 0.0000 2.0508 +0.0000 0.0000 2.0944 +0.0000 0.0000 2.1380 +0.0000 0.0000 2.1817 +0.0000 0.0000 2.2253 +0.0000 0.0000 2.2689 +0.0000 0.0000 2.3126 +0.0000 0.0000 2.3562 +primID: 7 +startangle_c: 5 +endpose_c: 0 0 4 +additionalactioncostmult: 1000 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0000 0.0000 1.9199 +0.0000 0.0000 1.8762 +0.0000 0.0000 1.8326 +0.0000 0.0000 1.7890 +0.0000 0.0000 1.7453 +0.0000 0.0000 1.7017 +0.0000 0.0000 1.6581 +0.0000 0.0000 1.6144 +0.0000 0.0000 1.5708 +primID: 8 +startangle_c: 5 +endpose_c: -2 7 5 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0111 0.0389 1.9635 +-0.0222 0.0778 1.9635 +-0.0333 0.1167 1.9635 +-0.0444 0.1556 1.9635 +-0.0556 0.1944 1.9635 +-0.0667 0.2333 1.9635 +-0.0778 0.2722 1.9635 +-0.0889 0.3111 1.9635 +-0.1000 0.3500 1.9635 +primID: 9 +startangle_c: 5 +endpose_c: -4 5 5 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0222 0.0278 1.9635 +-0.0444 0.0556 1.9635 +-0.0667 0.0833 1.9635 +-0.0889 0.1111 1.9635 +-0.1111 0.1389 1.9635 +-0.1333 0.1667 1.9635 +-0.1556 0.1944 1.9635 +-0.1778 0.2222 1.9635 +-0.2000 0.2500 1.9635 +primID: 0 +startangle_c: 6 +endpose_c: -1 1 6 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0056 0.0056 2.3562 +-0.0111 0.0111 2.3562 +-0.0167 0.0167 2.3562 +-0.0222 0.0222 2.3562 +-0.0278 0.0278 2.3562 +-0.0333 0.0333 2.3562 +-0.0389 0.0389 2.3562 +-0.0444 0.0444 2.3562 +-0.0500 0.0500 2.3562 +primID: 1 +startangle_c: 6 +endpose_c: -6 6 6 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0333 0.0333 2.3562 +-0.0667 0.0667 2.3562 +-0.1000 0.1000 2.3562 +-0.1333 0.1333 2.3562 +-0.1667 0.1667 2.3562 +-0.2000 0.2000 2.3562 +-0.2333 0.2333 2.3562 +-0.2667 0.2667 2.3562 +-0.3000 0.3000 2.3562 +primID: 2 +startangle_c: 6 +endpose_c: -14 11 7 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0705 0.0705 2.3562 +-0.1411 0.1411 2.3562 +-0.2116 0.2116 2.3562 +-0.2828 0.2816 2.3909 +-0.3581 0.3469 2.4625 +-0.4379 0.4068 2.5341 +-0.5218 0.4607 2.6057 +-0.6093 0.5086 2.6773 +-0.7000 0.5500 2.7489 +primID: 3 +startangle_c: 6 +endpose_c: -11 14 5 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0705 0.0705 2.3562 +-0.1411 0.1411 2.3562 +-0.2116 0.2116 2.3562 +-0.2816 0.2828 2.3215 +-0.3469 0.3581 2.2499 +-0.4068 0.4379 2.1783 +-0.4607 0.5218 2.1067 +-0.5086 0.6093 2.0351 +-0.5500 0.7000 1.9635 +primID: 4 +startangle_c: 6 +endpose_c: -6 4 7 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0292 0.0278 2.3996 +-0.0595 0.0543 2.4430 +-0.0910 0.0795 2.4864 +-0.1235 0.1033 2.5298 +-0.1571 0.1257 2.5732 +-0.1916 0.1466 2.6166 +-0.2269 0.1659 2.6600 +-0.2631 0.1838 2.7034 +-0.3000 0.2000 2.7468 +primID: 5 +startangle_c: 6 +endpose_c: -4 6 5 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0278 0.0292 2.3128 +-0.0543 0.0595 2.2694 +-0.0795 0.0910 2.2260 +-0.1033 0.1235 2.1826 +-0.1257 0.1571 2.1392 +-0.1466 0.1916 2.0958 +-0.1659 0.2269 2.0524 +-0.1838 0.2631 2.0090 +-0.2000 0.3000 1.9656 +primID: 6 +startangle_c: 6 +endpose_c: 0 0 7 +additionalactioncostmult: 1000 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0000 0.0000 2.3998 +0.0000 0.0000 2.4435 +0.0000 0.0000 2.4871 +0.0000 0.0000 2.5307 +0.0000 0.0000 2.5744 +0.0000 0.0000 2.6180 +0.0000 0.0000 2.6616 +0.0000 0.0000 2.7053 +0.0000 0.0000 2.7489 +primID: 7 +startangle_c: 6 +endpose_c: 0 0 5 +additionalactioncostmult: 1000 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0000 0.0000 2.3126 +0.0000 0.0000 2.2689 +0.0000 0.0000 2.2253 +0.0000 0.0000 2.1817 +0.0000 0.0000 2.1380 +0.0000 0.0000 2.0944 +0.0000 0.0000 2.0508 +0.0000 0.0000 2.0071 +0.0000 0.0000 1.9635 +primID: 8 +startangle_c: 6 +endpose_c: -7 6 6 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0389 0.0333 2.3562 +-0.0778 0.0667 2.3562 +-0.1167 0.1000 2.3562 +-0.1556 0.1333 2.3562 +-0.1944 0.1667 2.3562 +-0.2333 0.2000 2.3562 +-0.2722 0.2333 2.3562 +-0.3111 0.2667 2.3562 +-0.3500 0.3000 2.3562 +primID: 9 +startangle_c: 6 +endpose_c: -6 7 6 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0333 0.0389 2.3562 +-0.0667 0.0778 2.3562 +-0.1000 0.1167 2.3562 +-0.1333 0.1556 2.3562 +-0.1667 0.1944 2.3562 +-0.2000 0.2333 2.3562 +-0.2333 0.2722 2.3562 +-0.2667 0.3111 2.3562 +-0.3000 0.3500 2.3562 +primID: 0 +startangle_c: 7 +endpose_c: -2 1 7 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0111 0.0056 2.7489 +-0.0222 0.0111 2.7489 +-0.0333 0.0167 2.7489 +-0.0444 0.0222 2.7489 +-0.0556 0.0278 2.7489 +-0.0667 0.0333 2.7489 +-0.0778 0.0389 2.7489 +-0.0889 0.0444 2.7489 +-0.1000 0.0500 2.7489 +primID: 1 +startangle_c: 7 +endpose_c: -6 3 7 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0333 0.0167 2.7489 +-0.0667 0.0333 2.7489 +-0.1000 0.0500 2.7489 +-0.1333 0.0667 2.7489 +-0.1667 0.0833 2.7489 +-0.2000 0.1000 2.7489 +-0.2333 0.1167 2.7489 +-0.2667 0.1333 2.7489 +-0.3000 0.1500 2.7489 +primID: 2 +startangle_c: 7 +endpose_c: -13 9 6 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0793 0.0378 2.7086 +-0.1572 0.0787 2.6684 +-0.2334 0.1229 2.6281 +-0.3079 0.1701 2.5879 +-0.3805 0.2204 2.5477 +-0.4512 0.2736 2.5074 +-0.5197 0.3296 2.4672 +-0.5860 0.3885 2.4269 +-0.6500 0.4500 2.3867 +primID: 3 +startangle_c: 7 +endpose_c: -14 3 8 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0741 0.0305 2.7642 +-0.1493 0.0582 2.8114 +-0.2256 0.0824 2.8586 +-0.3031 0.1030 2.9057 +-0.3814 0.1199 2.9529 +-0.4604 0.1330 3.0001 +-0.5400 0.1424 3.0472 +-0.6199 0.1481 3.0944 +-0.7000 0.1500 3.1416 +primID: 4 +startangle_c: 7 +endpose_c: -5 4 6 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0298 0.0184 2.7186 +-0.0592 0.0379 2.6883 +-0.0881 0.0583 2.6580 +-0.1165 0.0796 2.6277 +-0.1444 0.1019 2.5974 +-0.1717 0.1251 2.5671 +-0.1984 0.1492 2.5368 +-0.2245 0.1742 2.5065 +-0.2500 0.2000 2.4762 +primID: 5 +startangle_c: 7 +endpose_c: -6 1 8 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0320 0.0105 2.7865 +-0.0644 0.0197 2.8242 +-0.0973 0.0278 2.8618 +-0.1304 0.0346 2.8994 +-0.1639 0.0402 2.9371 +-0.1977 0.0446 2.9747 +-0.2316 0.0476 3.0124 +-0.2658 0.0495 3.0500 +-0.3000 0.0500 3.0876 +primID: 6 +startangle_c: 7 +endpose_c: 0 0 6 +additionalactioncostmult: 1000 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0000 0.0000 2.7053 +0.0000 0.0000 2.6616 +0.0000 0.0000 2.6180 +0.0000 0.0000 2.5744 +0.0000 0.0000 2.5307 +0.0000 0.0000 2.4871 +0.0000 0.0000 2.4435 +0.0000 0.0000 2.3998 +0.0000 0.0000 2.3562 +primID: 7 +startangle_c: 7 +endpose_c: 0 0 8 +additionalactioncostmult: 1000 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0000 0.0000 2.7925 +0.0000 0.0000 2.8362 +0.0000 0.0000 2.8798 +0.0000 0.0000 2.9234 +0.0000 0.0000 2.9671 +0.0000 0.0000 3.0107 +0.0000 0.0000 3.0543 +0.0000 0.0000 3.0980 +0.0000 0.0000 3.1416 +primID: 8 +startangle_c: 7 +endpose_c: -7 2 7 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0389 0.0111 2.7489 +-0.0778 0.0222 2.7489 +-0.1167 0.0333 2.7489 +-0.1556 0.0444 2.7489 +-0.1944 0.0556 2.7489 +-0.2333 0.0667 2.7489 +-0.2722 0.0778 2.7489 +-0.3111 0.0889 2.7489 +-0.3500 0.1000 2.7489 +primID: 9 +startangle_c: 7 +endpose_c: -5 4 7 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0278 0.0222 2.7489 +-0.0556 0.0444 2.7489 +-0.0833 0.0667 2.7489 +-0.1111 0.0889 2.7489 +-0.1389 0.1111 2.7489 +-0.1667 0.1333 2.7489 +-0.1944 0.1556 2.7489 +-0.2222 0.1778 2.7489 +-0.2500 0.2000 2.7489 +primID: 0 +startangle_c: 8 +endpose_c: -1 0 8 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0056 0.0000 3.1416 +-0.0111 0.0000 3.1416 +-0.0167 0.0000 3.1416 +-0.0222 0.0000 3.1416 +-0.0278 0.0000 3.1416 +-0.0333 0.0000 3.1416 +-0.0389 0.0000 3.1416 +-0.0444 0.0000 3.1416 +-0.0500 0.0000 3.1416 +primID: 1 +startangle_c: 8 +endpose_c: -8 0 8 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0444 0.0000 3.1416 +-0.0889 0.0000 3.1416 +-0.1333 0.0000 3.1416 +-0.1778 0.0000 3.1416 +-0.2222 0.0000 3.1416 +-0.2667 0.0000 3.1416 +-0.3111 0.0000 3.1416 +-0.3556 0.0000 3.1416 +-0.4000 0.0000 3.1416 +primID: 2 +startangle_c: 8 +endpose_c: -16 -4 9 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0904 -0.0095 3.1765 +-0.1806 -0.0222 3.2115 +-0.2707 -0.0381 3.2464 +-0.3604 -0.0572 3.2814 +-0.4496 -0.0795 3.3163 +-0.5383 -0.1050 3.3513 +-0.6264 -0.1335 3.3862 +-0.7136 -0.1652 3.4211 +-0.8000 -0.2000 3.4561 +primID: 3 +startangle_c: 8 +endpose_c: -16 4 7 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0904 0.0095 3.1066 +-0.1806 0.0222 3.0717 +-0.2707 0.0381 3.0368 +-0.3604 0.0572 3.0018 +-0.4496 0.0795 2.9669 +-0.5383 0.1050 2.9319 +-0.6264 0.1335 2.8970 +-0.7136 0.1652 2.8620 +-0.8000 0.2000 2.8271 +primID: 4 +startangle_c: 8 +endpose_c: -5 -2 9 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0280 -0.0085 3.1639 +-0.0559 -0.0177 3.1861 +-0.0839 -0.0275 3.2084 +-0.1117 -0.0380 3.2306 +-0.1396 -0.0491 3.2529 +-0.1673 -0.0609 3.2751 +-0.1950 -0.0733 3.2974 +-0.2225 -0.0863 3.3197 +-0.2500 -0.1000 3.3419 +primID: 5 +startangle_c: 8 +endpose_c: -5 2 7 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0280 0.0085 3.1193 +-0.0559 0.0177 3.0971 +-0.0839 0.0275 3.0748 +-0.1117 0.0380 3.0526 +-0.1396 0.0491 3.0303 +-0.1673 0.0609 3.0080 +-0.1950 0.0733 2.9858 +-0.2225 0.0863 2.9635 +-0.2500 0.1000 2.9413 +primID: 6 +startangle_c: 8 +endpose_c: 0 0 9 +additionalactioncostmult: 1000 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0000 0.0000 3.1852 +0.0000 0.0000 3.2289 +0.0000 0.0000 3.2725 +0.0000 0.0000 3.3161 +0.0000 0.0000 3.3598 +0.0000 0.0000 3.4034 +0.0000 0.0000 3.4470 +0.0000 0.0000 3.4907 +0.0000 0.0000 3.5343 +primID: 7 +startangle_c: 8 +endpose_c: 0 0 7 +additionalactioncostmult: 1000 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0000 0.0000 3.0980 +0.0000 0.0000 3.0543 +0.0000 0.0000 3.0107 +0.0000 0.0000 2.9671 +0.0000 0.0000 2.9234 +0.0000 0.0000 2.8798 +0.0000 0.0000 2.8362 +0.0000 0.0000 2.7925 +0.0000 0.0000 2.7489 +primID: 8 +startangle_c: 8 +endpose_c: -8 -1 8 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0444 -0.0056 3.1416 +-0.0889 -0.0111 3.1416 +-0.1333 -0.0167 3.1416 +-0.1778 -0.0222 3.1416 +-0.2222 -0.0278 3.1416 +-0.2667 -0.0333 3.1416 +-0.3111 -0.0389 3.1416 +-0.3556 -0.0444 3.1416 +-0.4000 -0.0500 3.1416 +primID: 9 +startangle_c: 8 +endpose_c: -8 1 8 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0444 0.0056 3.1416 +-0.0889 0.0111 3.1416 +-0.1333 0.0167 3.1416 +-0.1778 0.0222 3.1416 +-0.2222 0.0278 3.1416 +-0.2667 0.0333 3.1416 +-0.3111 0.0389 3.1416 +-0.3556 0.0444 3.1416 +-0.4000 0.0500 3.1416 +primID: 0 +startangle_c: 9 +endpose_c: -2 -1 9 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0111 -0.0056 3.5343 +-0.0222 -0.0111 3.5343 +-0.0333 -0.0167 3.5343 +-0.0444 -0.0222 3.5343 +-0.0556 -0.0278 3.5343 +-0.0667 -0.0333 3.5343 +-0.0778 -0.0389 3.5343 +-0.0889 -0.0444 3.5343 +-0.1000 -0.0500 3.5343 +primID: 1 +startangle_c: 9 +endpose_c: -6 -3 9 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0333 -0.0167 3.5343 +-0.0667 -0.0333 3.5343 +-0.1000 -0.0500 3.5343 +-0.1333 -0.0667 3.5343 +-0.1667 -0.0833 3.5343 +-0.2000 -0.1000 3.5343 +-0.2333 -0.1167 3.5343 +-0.2667 -0.1333 3.5343 +-0.3000 -0.1500 3.5343 +primID: 2 +startangle_c: 9 +endpose_c: -13 -9 10 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0793 -0.0378 3.5745 +-0.1572 -0.0787 3.6148 +-0.2334 -0.1229 3.6550 +-0.3079 -0.1701 3.6953 +-0.3805 -0.2204 3.7355 +-0.4512 -0.2736 3.7758 +-0.5197 -0.3296 3.8160 +-0.5860 -0.3885 3.8563 +-0.6500 -0.4500 3.8965 +primID: 3 +startangle_c: 9 +endpose_c: -14 -3 8 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0741 -0.0305 3.5190 +-0.1493 -0.0582 3.4718 +-0.2256 -0.0824 3.4246 +-0.3031 -0.1030 3.3775 +-0.3814 -0.1199 3.3303 +-0.4604 -0.1330 3.2831 +-0.5400 -0.1424 3.2359 +-0.6199 -0.1481 3.1888 +-0.7000 -0.1500 3.1416 +primID: 4 +startangle_c: 9 +endpose_c: -5 -4 10 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0298 -0.0184 3.5646 +-0.0592 -0.0379 3.5949 +-0.0881 -0.0583 3.6252 +-0.1165 -0.0796 3.6555 +-0.1444 -0.1019 3.6858 +-0.1717 -0.1251 3.7161 +-0.1984 -0.1492 3.7464 +-0.2245 -0.1742 3.7767 +-0.2500 -0.2000 3.8070 +primID: 5 +startangle_c: 9 +endpose_c: -6 -1 8 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0320 -0.0105 3.4967 +-0.0644 -0.0197 3.4590 +-0.0973 -0.0278 3.4214 +-0.1304 -0.0346 3.3837 +-0.1639 -0.0402 3.3461 +-0.1977 -0.0446 3.3085 +-0.2316 -0.0476 3.2708 +-0.2658 -0.0495 3.2332 +-0.3000 -0.0500 3.1955 +primID: 6 +startangle_c: 9 +endpose_c: 0 0 10 +additionalactioncostmult: 1000 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0000 0.0000 3.5779 +0.0000 0.0000 3.6216 +0.0000 0.0000 3.6652 +0.0000 0.0000 3.7088 +0.0000 0.0000 3.7525 +0.0000 0.0000 3.7961 +0.0000 0.0000 3.8397 +0.0000 0.0000 3.8834 +0.0000 0.0000 3.9270 +primID: 7 +startangle_c: 9 +endpose_c: 0 0 8 +additionalactioncostmult: 1000 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0000 0.0000 3.4907 +0.0000 0.0000 3.4470 +0.0000 0.0000 3.4034 +0.0000 0.0000 3.3598 +0.0000 0.0000 3.3161 +0.0000 0.0000 3.2725 +0.0000 0.0000 3.2289 +0.0000 0.0000 3.1852 +0.0000 0.0000 3.1416 +primID: 8 +startangle_c: 9 +endpose_c: -7 -2 9 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0389 -0.0111 3.5343 +-0.0778 -0.0222 3.5343 +-0.1167 -0.0333 3.5343 +-0.1556 -0.0444 3.5343 +-0.1944 -0.0556 3.5343 +-0.2333 -0.0667 3.5343 +-0.2722 -0.0778 3.5343 +-0.3111 -0.0889 3.5343 +-0.3500 -0.1000 3.5343 +primID: 9 +startangle_c: 9 +endpose_c: -5 -4 9 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0278 -0.0222 3.5343 +-0.0556 -0.0444 3.5343 +-0.0833 -0.0667 3.5343 +-0.1111 -0.0889 3.5343 +-0.1389 -0.1111 3.5343 +-0.1667 -0.1333 3.5343 +-0.1944 -0.1556 3.5343 +-0.2222 -0.1778 3.5343 +-0.2500 -0.2000 3.5343 +primID: 0 +startangle_c: 10 +endpose_c: -1 -1 10 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0056 -0.0056 3.9270 +-0.0111 -0.0111 3.9270 +-0.0167 -0.0167 3.9270 +-0.0222 -0.0222 3.9270 +-0.0278 -0.0278 3.9270 +-0.0333 -0.0333 3.9270 +-0.0389 -0.0389 3.9270 +-0.0444 -0.0444 3.9270 +-0.0500 -0.0500 3.9270 +primID: 1 +startangle_c: 10 +endpose_c: -6 -6 10 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0333 -0.0333 3.9270 +-0.0667 -0.0667 3.9270 +-0.1000 -0.1000 3.9270 +-0.1333 -0.1333 3.9270 +-0.1667 -0.1667 3.9270 +-0.2000 -0.2000 3.9270 +-0.2333 -0.2333 3.9270 +-0.2667 -0.2667 3.9270 +-0.3000 -0.3000 3.9270 +primID: 2 +startangle_c: 10 +endpose_c: -11 -14 11 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0705 -0.0705 3.9270 +-0.1411 -0.1411 3.9270 +-0.2116 -0.2116 3.9270 +-0.2816 -0.2828 3.9617 +-0.3469 -0.3581 4.0333 +-0.4068 -0.4379 4.1049 +-0.4607 -0.5218 4.1765 +-0.5086 -0.6093 4.2481 +-0.5500 -0.7000 4.3197 +primID: 3 +startangle_c: 10 +endpose_c: -14 -11 9 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0705 -0.0705 3.9270 +-0.1411 -0.1411 3.9270 +-0.2116 -0.2116 3.9270 +-0.2828 -0.2816 3.8923 +-0.3581 -0.3469 3.8207 +-0.4379 -0.4068 3.7491 +-0.5218 -0.4607 3.6775 +-0.6093 -0.5086 3.6059 +-0.7000 -0.5500 3.5343 +primID: 4 +startangle_c: 10 +endpose_c: -4 -6 11 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0278 -0.0292 3.9704 +-0.0543 -0.0595 4.0138 +-0.0795 -0.0910 4.0572 +-0.1033 -0.1235 4.1006 +-0.1257 -0.1571 4.1440 +-0.1466 -0.1916 4.1874 +-0.1659 -0.2269 4.2308 +-0.1838 -0.2631 4.2742 +-0.2000 -0.3000 4.3176 +primID: 5 +startangle_c: 10 +endpose_c: -6 -4 9 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0292 -0.0278 3.8836 +-0.0595 -0.0543 3.8402 +-0.0910 -0.0795 3.7968 +-0.1235 -0.1033 3.7534 +-0.1571 -0.1257 3.7100 +-0.1916 -0.1466 3.6666 +-0.2269 -0.1659 3.6232 +-0.2631 -0.1838 3.5798 +-0.3000 -0.2000 3.5364 +primID: 6 +startangle_c: 10 +endpose_c: 0 0 11 +additionalactioncostmult: 1000 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.9706 +0.0000 0.0000 4.0143 +0.0000 0.0000 4.0579 +0.0000 0.0000 4.1015 +0.0000 0.0000 4.1452 +0.0000 0.0000 4.1888 +0.0000 0.0000 4.2324 +0.0000 0.0000 4.2761 +0.0000 0.0000 4.3197 +primID: 7 +startangle_c: 10 +endpose_c: 0 0 9 +additionalactioncostmult: 1000 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.8834 +0.0000 0.0000 3.8397 +0.0000 0.0000 3.7961 +0.0000 0.0000 3.7525 +0.0000 0.0000 3.7088 +0.0000 0.0000 3.6652 +0.0000 0.0000 3.6216 +0.0000 0.0000 3.5779 +0.0000 0.0000 3.5343 +primID: 8 +startangle_c: 10 +endpose_c: -6 -7 10 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0333 -0.0389 3.9270 +-0.0667 -0.0778 3.9270 +-0.1000 -0.1167 3.9270 +-0.1333 -0.1556 3.9270 +-0.1667 -0.1944 3.9270 +-0.2000 -0.2333 3.9270 +-0.2333 -0.2722 3.9270 +-0.2667 -0.3111 3.9270 +-0.3000 -0.3500 3.9270 +primID: 9 +startangle_c: 10 +endpose_c: -7 -6 10 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0389 -0.0333 3.9270 +-0.0778 -0.0667 3.9270 +-0.1167 -0.1000 3.9270 +-0.1556 -0.1333 3.9270 +-0.1944 -0.1667 3.9270 +-0.2333 -0.2000 3.9270 +-0.2722 -0.2333 3.9270 +-0.3111 -0.2667 3.9270 +-0.3500 -0.3000 3.9270 +primID: 0 +startangle_c: 11 +endpose_c: -1 -2 11 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0056 -0.0111 4.3197 +-0.0111 -0.0222 4.3197 +-0.0167 -0.0333 4.3197 +-0.0222 -0.0444 4.3197 +-0.0278 -0.0556 4.3197 +-0.0333 -0.0667 4.3197 +-0.0389 -0.0778 4.3197 +-0.0444 -0.0889 4.3197 +-0.0500 -0.1000 4.3197 +primID: 1 +startangle_c: 11 +endpose_c: -3 -6 11 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0167 -0.0333 4.3197 +-0.0333 -0.0667 4.3197 +-0.0500 -0.1000 4.3197 +-0.0667 -0.1333 4.3197 +-0.0833 -0.1667 4.3197 +-0.1000 -0.2000 4.3197 +-0.1167 -0.2333 4.3197 +-0.1333 -0.2667 4.3197 +-0.1500 -0.3000 4.3197 +primID: 2 +startangle_c: 11 +endpose_c: -9 -13 10 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0378 -0.0793 4.2794 +-0.0787 -0.1572 4.2392 +-0.1229 -0.2334 4.1989 +-0.1701 -0.3079 4.1587 +-0.2204 -0.3805 4.1185 +-0.2736 -0.4512 4.0782 +-0.3296 -0.5197 4.0380 +-0.3885 -0.5860 3.9977 +-0.4500 -0.6500 3.9575 +primID: 3 +startangle_c: 11 +endpose_c: -3 -14 12 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0305 -0.0741 4.3350 +-0.0582 -0.1493 4.3822 +-0.0824 -0.2256 4.4294 +-0.1030 -0.3031 4.4765 +-0.1199 -0.3814 4.5237 +-0.1330 -0.4604 4.5709 +-0.1424 -0.5400 4.6180 +-0.1481 -0.6199 4.6652 +-0.1500 -0.7000 4.7124 +primID: 4 +startangle_c: 11 +endpose_c: -4 -5 10 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0184 -0.0298 4.2894 +-0.0379 -0.0592 4.2591 +-0.0583 -0.0881 4.2288 +-0.0796 -0.1165 4.1985 +-0.1019 -0.1444 4.1682 +-0.1251 -0.1717 4.1379 +-0.1492 -0.1984 4.1076 +-0.1742 -0.2245 4.0773 +-0.2000 -0.2500 4.0470 +primID: 5 +startangle_c: 11 +endpose_c: -1 -6 12 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0105 -0.0320 4.3573 +-0.0197 -0.0644 4.3950 +-0.0278 -0.0973 4.4326 +-0.0346 -0.1304 4.4702 +-0.0402 -0.1639 4.5079 +-0.0446 -0.1977 4.5455 +-0.0476 -0.2316 4.5832 +-0.0495 -0.2658 4.6208 +-0.0500 -0.3000 4.6584 +primID: 6 +startangle_c: 11 +endpose_c: 0 0 10 +additionalactioncostmult: 1000 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0000 0.0000 4.2761 +0.0000 0.0000 4.2324 +0.0000 0.0000 4.1888 +0.0000 0.0000 4.1452 +0.0000 0.0000 4.1015 +0.0000 0.0000 4.0579 +0.0000 0.0000 4.0143 +0.0000 0.0000 3.9706 +0.0000 0.0000 3.9270 +primID: 7 +startangle_c: 11 +endpose_c: 0 0 12 +additionalactioncostmult: 1000 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0000 0.0000 4.3633 +0.0000 0.0000 4.4070 +0.0000 0.0000 4.4506 +0.0000 0.0000 4.4942 +0.0000 0.0000 4.5379 +0.0000 0.0000 4.5815 +0.0000 0.0000 4.6251 +0.0000 0.0000 4.6688 +0.0000 0.0000 4.7124 +primID: 8 +startangle_c: 11 +endpose_c: -2 -7 11 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0111 -0.0389 4.3197 +-0.0222 -0.0778 4.3197 +-0.0333 -0.1167 4.3197 +-0.0444 -0.1556 4.3197 +-0.0556 -0.1944 4.3197 +-0.0667 -0.2333 4.3197 +-0.0778 -0.2722 4.3197 +-0.0889 -0.3111 4.3197 +-0.1000 -0.3500 4.3197 +primID: 9 +startangle_c: 11 +endpose_c: -4 -5 11 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0222 -0.0278 4.3197 +-0.0444 -0.0556 4.3197 +-0.0667 -0.0833 4.3197 +-0.0889 -0.1111 4.3197 +-0.1111 -0.1389 4.3197 +-0.1333 -0.1667 4.3197 +-0.1556 -0.1944 4.3197 +-0.1778 -0.2222 4.3197 +-0.2000 -0.2500 4.3197 +primID: 0 +startangle_c: 12 +endpose_c: 0 -1 12 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0056 4.7124 +0.0000 -0.0111 4.7124 +0.0000 -0.0167 4.7124 +0.0000 -0.0222 4.7124 +0.0000 -0.0278 4.7124 +0.0000 -0.0333 4.7124 +0.0000 -0.0389 4.7124 +0.0000 -0.0444 4.7124 +0.0000 -0.0500 4.7124 +primID: 1 +startangle_c: 12 +endpose_c: 0 -8 12 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0444 4.7124 +0.0000 -0.0889 4.7124 +0.0000 -0.1333 4.7124 +0.0000 -0.1778 4.7124 +0.0000 -0.2222 4.7124 +0.0000 -0.2667 4.7124 +0.0000 -0.3111 4.7124 +0.0000 -0.3556 4.7124 +0.0000 -0.4000 4.7124 +primID: 2 +startangle_c: 12 +endpose_c: 4 -16 13 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0095 -0.0904 4.7473 +0.0222 -0.1806 4.7823 +0.0381 -0.2707 4.8172 +0.0572 -0.3604 4.8522 +0.0795 -0.4496 4.8871 +0.1050 -0.5383 4.9221 +0.1335 -0.6264 4.9570 +0.1652 -0.7136 4.9919 +0.2000 -0.8000 5.0269 +primID: 3 +startangle_c: 12 +endpose_c: -4 -16 11 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.7124 +-0.0095 -0.0904 4.6774 +-0.0222 -0.1806 4.6425 +-0.0381 -0.2707 4.6076 +-0.0572 -0.3604 4.5726 +-0.0795 -0.4496 4.5377 +-0.1050 -0.5383 4.5027 +-0.1335 -0.6264 4.4678 +-0.1652 -0.7136 4.4328 +-0.2000 -0.8000 4.3979 +primID: 4 +startangle_c: 12 +endpose_c: 2 -5 13 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0085 -0.0280 4.7346 +0.0177 -0.0559 4.7569 +0.0275 -0.0839 4.7792 +0.0380 -0.1117 4.8014 +0.0491 -0.1396 4.8237 +0.0609 -0.1673 4.8459 +0.0733 -0.1950 4.8682 +0.0863 -0.2225 4.8904 +0.1000 -0.2500 4.9127 +primID: 5 +startangle_c: 12 +endpose_c: -2 -5 11 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 4.7124 +-0.0085 -0.0280 4.6901 +-0.0177 -0.0559 4.6679 +-0.0275 -0.0839 4.6456 +-0.0380 -0.1117 4.6234 +-0.0491 -0.1396 4.6011 +-0.0609 -0.1673 4.5788 +-0.0733 -0.1950 4.5566 +-0.0863 -0.2225 4.5343 +-0.1000 -0.2500 4.5121 +primID: 6 +startangle_c: 12 +endpose_c: 0 0 13 +additionalactioncostmult: 1000 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0000 4.7560 +0.0000 0.0000 4.7997 +0.0000 0.0000 4.8433 +0.0000 0.0000 4.8869 +0.0000 0.0000 4.9306 +0.0000 0.0000 4.9742 +0.0000 0.0000 5.0178 +0.0000 0.0000 5.0615 +0.0000 0.0000 5.1051 +primID: 7 +startangle_c: 12 +endpose_c: 0 0 11 +additionalactioncostmult: 1000 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0000 4.6688 +0.0000 0.0000 4.6251 +0.0000 0.0000 4.5815 +0.0000 0.0000 4.5379 +0.0000 0.0000 4.4942 +0.0000 0.0000 4.4506 +0.0000 0.0000 4.4070 +0.0000 0.0000 4.3633 +0.0000 0.0000 4.3197 +primID: 8 +startangle_c: 12 +endpose_c: 1 -8 12 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0056 -0.0444 4.7124 +0.0111 -0.0889 4.7124 +0.0167 -0.1333 4.7124 +0.0222 -0.1778 4.7124 +0.0278 -0.2222 4.7124 +0.0333 -0.2667 4.7124 +0.0389 -0.3111 4.7124 +0.0444 -0.3556 4.7124 +0.0500 -0.4000 4.7124 +primID: 9 +startangle_c: 12 +endpose_c: -1 -8 12 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 4.7124 +-0.0056 -0.0444 4.7124 +-0.0111 -0.0889 4.7124 +-0.0167 -0.1333 4.7124 +-0.0222 -0.1778 4.7124 +-0.0278 -0.2222 4.7124 +-0.0333 -0.2667 4.7124 +-0.0389 -0.3111 4.7124 +-0.0444 -0.3556 4.7124 +-0.0500 -0.4000 4.7124 +primID: 0 +startangle_c: 13 +endpose_c: 1 -2 13 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0056 -0.0111 5.1051 +0.0111 -0.0222 5.1051 +0.0167 -0.0333 5.1051 +0.0222 -0.0444 5.1051 +0.0278 -0.0556 5.1051 +0.0333 -0.0667 5.1051 +0.0389 -0.0778 5.1051 +0.0444 -0.0889 5.1051 +0.0500 -0.1000 5.1051 +primID: 1 +startangle_c: 13 +endpose_c: 3 -6 13 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0167 -0.0333 5.1051 +0.0333 -0.0667 5.1051 +0.0500 -0.1000 5.1051 +0.0667 -0.1333 5.1051 +0.0833 -0.1667 5.1051 +0.1000 -0.2000 5.1051 +0.1167 -0.2333 5.1051 +0.1333 -0.2667 5.1051 +0.1500 -0.3000 5.1051 +primID: 2 +startangle_c: 13 +endpose_c: 9 -13 14 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0378 -0.0793 5.1453 +0.0787 -0.1572 5.1856 +0.1229 -0.2334 5.2258 +0.1701 -0.3079 5.2661 +0.2204 -0.3805 5.3063 +0.2736 -0.4512 5.3466 +0.3296 -0.5197 5.3868 +0.3885 -0.5860 5.4271 +0.4500 -0.6500 5.4673 +primID: 3 +startangle_c: 13 +endpose_c: 3 -14 12 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0305 -0.0741 5.0898 +0.0582 -0.1493 5.0426 +0.0824 -0.2256 4.9954 +0.1030 -0.3031 4.9482 +0.1199 -0.3814 4.9011 +0.1330 -0.4604 4.8539 +0.1424 -0.5400 4.8067 +0.1481 -0.6199 4.7596 +0.1500 -0.7000 4.7124 +primID: 4 +startangle_c: 13 +endpose_c: 4 -5 14 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0184 -0.0298 5.1354 +0.0379 -0.0592 5.1657 +0.0583 -0.0881 5.1960 +0.0796 -0.1165 5.2263 +0.1019 -0.1444 5.2566 +0.1251 -0.1717 5.2869 +0.1492 -0.1984 5.3172 +0.1742 -0.2245 5.3475 +0.2000 -0.2500 5.3778 +primID: 5 +startangle_c: 13 +endpose_c: 1 -6 12 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0105 -0.0320 5.0674 +0.0197 -0.0644 5.0298 +0.0278 -0.0973 4.9922 +0.0346 -0.1304 4.9545 +0.0402 -0.1639 4.9169 +0.0446 -0.1977 4.8793 +0.0476 -0.2316 4.8416 +0.0495 -0.2658 4.8040 +0.0500 -0.3000 4.7663 +primID: 6 +startangle_c: 13 +endpose_c: 0 0 14 +additionalactioncostmult: 1000 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0000 0.0000 5.1487 +0.0000 0.0000 5.1924 +0.0000 0.0000 5.2360 +0.0000 0.0000 5.2796 +0.0000 0.0000 5.3233 +0.0000 0.0000 5.3669 +0.0000 0.0000 5.4105 +0.0000 0.0000 5.4542 +0.0000 0.0000 5.4978 +primID: 7 +startangle_c: 13 +endpose_c: 0 0 12 +additionalactioncostmult: 1000 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0000 0.0000 5.0615 +0.0000 0.0000 5.0178 +0.0000 0.0000 4.9742 +0.0000 0.0000 4.9306 +0.0000 0.0000 4.8869 +0.0000 0.0000 4.8433 +0.0000 0.0000 4.7997 +0.0000 0.0000 4.7560 +0.0000 0.0000 4.7124 +primID: 8 +startangle_c: 13 +endpose_c: 2 -7 13 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0111 -0.0389 5.1051 +0.0222 -0.0778 5.1051 +0.0333 -0.1167 5.1051 +0.0444 -0.1556 5.1051 +0.0556 -0.1944 5.1051 +0.0667 -0.2333 5.1051 +0.0778 -0.2722 5.1051 +0.0889 -0.3111 5.1051 +0.1000 -0.3500 5.1051 +primID: 9 +startangle_c: 13 +endpose_c: 4 -5 13 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0222 -0.0278 5.1051 +0.0444 -0.0556 5.1051 +0.0667 -0.0833 5.1051 +0.0889 -0.1111 5.1051 +0.1111 -0.1389 5.1051 +0.1333 -0.1667 5.1051 +0.1556 -0.1944 5.1051 +0.1778 -0.2222 5.1051 +0.2000 -0.2500 5.1051 +primID: 0 +startangle_c: 14 +endpose_c: 1 -1 14 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0056 -0.0056 5.4978 +0.0111 -0.0111 5.4978 +0.0167 -0.0167 5.4978 +0.0222 -0.0222 5.4978 +0.0278 -0.0278 5.4978 +0.0333 -0.0333 5.4978 +0.0389 -0.0389 5.4978 +0.0444 -0.0444 5.4978 +0.0500 -0.0500 5.4978 +primID: 1 +startangle_c: 14 +endpose_c: 6 -6 14 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0333 -0.0333 5.4978 +0.0667 -0.0667 5.4978 +0.1000 -0.1000 5.4978 +0.1333 -0.1333 5.4978 +0.1667 -0.1667 5.4978 +0.2000 -0.2000 5.4978 +0.2333 -0.2333 5.4978 +0.2667 -0.2667 5.4978 +0.3000 -0.3000 5.4978 +primID: 2 +startangle_c: 14 +endpose_c: 14 -11 15 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0705 -0.0705 5.4978 +0.1411 -0.1411 5.4978 +0.2116 -0.2116 5.4978 +0.2828 -0.2816 5.5325 +0.3581 -0.3469 5.6041 +0.4379 -0.4068 5.6757 +0.5218 -0.4607 5.7473 +0.6093 -0.5086 5.8189 +0.7000 -0.5500 5.8905 +primID: 3 +startangle_c: 14 +endpose_c: 11 -14 13 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0705 -0.0705 5.4978 +0.1411 -0.1411 5.4978 +0.2116 -0.2116 5.4978 +0.2816 -0.2828 5.4631 +0.3469 -0.3581 5.3915 +0.4068 -0.4379 5.3199 +0.4607 -0.5218 5.2483 +0.5086 -0.6093 5.1767 +0.5500 -0.7000 5.1051 +primID: 4 +startangle_c: 14 +endpose_c: 6 -4 15 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0292 -0.0278 5.5412 +0.0595 -0.0543 5.5846 +0.0910 -0.0795 5.6280 +0.1235 -0.1033 5.6714 +0.1571 -0.1257 5.7148 +0.1916 -0.1466 5.7582 +0.2269 -0.1659 5.8016 +0.2631 -0.1838 5.8450 +0.3000 -0.2000 5.8884 +primID: 5 +startangle_c: 14 +endpose_c: 4 -6 13 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0278 -0.0292 5.4544 +0.0543 -0.0595 5.4110 +0.0795 -0.0910 5.3676 +0.1033 -0.1235 5.3242 +0.1257 -0.1571 5.2808 +0.1466 -0.1916 5.2374 +0.1659 -0.2269 5.1940 +0.1838 -0.2631 5.1506 +0.2000 -0.3000 5.1072 +primID: 6 +startangle_c: 14 +endpose_c: 0 0 15 +additionalactioncostmult: 1000 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0000 0.0000 5.5414 +0.0000 0.0000 5.5851 +0.0000 0.0000 5.6287 +0.0000 0.0000 5.6723 +0.0000 0.0000 5.7160 +0.0000 0.0000 5.7596 +0.0000 0.0000 5.8032 +0.0000 0.0000 5.8469 +0.0000 0.0000 5.8905 +primID: 7 +startangle_c: 14 +endpose_c: 0 0 13 +additionalactioncostmult: 1000 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0000 0.0000 5.4542 +0.0000 0.0000 5.4105 +0.0000 0.0000 5.3669 +0.0000 0.0000 5.3233 +0.0000 0.0000 5.2796 +0.0000 0.0000 5.2360 +0.0000 0.0000 5.1924 +0.0000 0.0000 5.1487 +0.0000 0.0000 5.1051 +primID: 8 +startangle_c: 14 +endpose_c: 7 -6 14 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0389 -0.0333 5.4978 +0.0778 -0.0667 5.4978 +0.1167 -0.1000 5.4978 +0.1556 -0.1333 5.4978 +0.1944 -0.1667 5.4978 +0.2333 -0.2000 5.4978 +0.2722 -0.2333 5.4978 +0.3111 -0.2667 5.4978 +0.3500 -0.3000 5.4978 +primID: 9 +startangle_c: 14 +endpose_c: 6 -7 14 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0333 -0.0389 5.4978 +0.0667 -0.0778 5.4978 +0.1000 -0.1167 5.4978 +0.1333 -0.1556 5.4978 +0.1667 -0.1944 5.4978 +0.2000 -0.2333 5.4978 +0.2333 -0.2722 5.4978 +0.2667 -0.3111 5.4978 +0.3000 -0.3500 5.4978 +primID: 0 +startangle_c: 15 +endpose_c: 2 -1 15 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0111 -0.0056 5.8905 +0.0222 -0.0111 5.8905 +0.0333 -0.0167 5.8905 +0.0444 -0.0222 5.8905 +0.0556 -0.0278 5.8905 +0.0667 -0.0333 5.8905 +0.0778 -0.0389 5.8905 +0.0889 -0.0444 5.8905 +0.1000 -0.0500 5.8905 +primID: 1 +startangle_c: 15 +endpose_c: 6 -3 15 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0333 -0.0167 5.8905 +0.0667 -0.0333 5.8905 +0.1000 -0.0500 5.8905 +0.1333 -0.0667 5.8905 +0.1667 -0.0833 5.8905 +0.2000 -0.1000 5.8905 +0.2333 -0.1167 5.8905 +0.2667 -0.1333 5.8905 +0.3000 -0.1500 5.8905 +primID: 2 +startangle_c: 15 +endpose_c: 13 -9 14 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0793 -0.0378 5.8502 +0.1572 -0.0787 5.8100 +0.2334 -0.1229 5.7697 +0.3079 -0.1701 5.7295 +0.3805 -0.2204 5.6892 +0.4512 -0.2736 5.6490 +0.5197 -0.3296 5.6088 +0.5860 -0.3885 5.5685 +0.6500 -0.4500 5.5283 +primID: 3 +startangle_c: 15 +endpose_c: 14 -3 0 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0741 -0.0305 5.9058 +0.1493 -0.0582 5.9530 +0.2256 -0.0824 6.0002 +0.3031 -0.1030 6.0473 +0.3814 -0.1199 6.0945 +0.4604 -0.1330 6.1417 +0.5400 -0.1424 6.1888 +0.6199 -0.1481 6.2360 +0.7000 -0.1500 6.2832 +primID: 4 +startangle_c: 15 +endpose_c: 5 -4 14 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0298 -0.0184 5.8602 +0.0592 -0.0379 5.8299 +0.0881 -0.0583 5.7996 +0.1165 -0.0796 5.7693 +0.1444 -0.1019 5.7390 +0.1717 -0.1251 5.7087 +0.1984 -0.1492 5.6784 +0.2245 -0.1742 5.6481 +0.2500 -0.2000 5.6178 +primID: 5 +startangle_c: 15 +endpose_c: 6 -1 0 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0320 -0.0105 5.9281 +0.0644 -0.0197 5.9658 +0.0973 -0.0278 6.0034 +0.1304 -0.0346 6.0410 +0.1639 -0.0402 6.0787 +0.1977 -0.0446 6.1163 +0.2316 -0.0476 6.1540 +0.2658 -0.0495 6.1916 +0.3000 -0.0500 6.2292 +primID: 6 +startangle_c: 15 +endpose_c: 0 0 14 +additionalactioncostmult: 1000 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0000 0.0000 5.8469 +0.0000 0.0000 5.8032 +0.0000 0.0000 5.7596 +0.0000 0.0000 5.7160 +0.0000 0.0000 5.6723 +0.0000 0.0000 5.6287 +0.0000 0.0000 5.5851 +0.0000 0.0000 5.5414 +0.0000 0.0000 5.4978 +primID: 7 +startangle_c: 15 +endpose_c: 0 0 0 +additionalactioncostmult: 1000 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0000 0.0000 5.2360 +0.0000 0.0000 4.5815 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.2725 +0.0000 0.0000 2.6180 +0.0000 0.0000 1.9635 +0.0000 0.0000 1.3090 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.0000 +primID: 8 +startangle_c: 15 +endpose_c: 7 -2 15 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0389 -0.0111 5.8905 +0.0778 -0.0222 5.8905 +0.1167 -0.0333 5.8905 +0.1556 -0.0444 5.8905 +0.1944 -0.0556 5.8905 +0.2333 -0.0667 5.8905 +0.2722 -0.0778 5.8905 +0.3111 -0.0889 5.8905 +0.3500 -0.1000 5.8905 +primID: 9 +startangle_c: 15 +endpose_c: 5 -4 15 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0278 -0.0222 5.8905 +0.0556 -0.0444 5.8905 +0.0833 -0.0667 5.8905 +0.1111 -0.0889 5.8905 +0.1389 -0.1111 5.8905 +0.1667 -0.1333 5.8905 +0.1944 -0.1556 5.8905 +0.2222 -0.1778 5.8905 +0.2500 -0.2000 5.8905 diff --git a/navigations/sbpl_lattice_planner/matlab/mprim/unicycle_highcost_10cm.mprim b/navigations/sbpl_lattice_planner/matlab/mprim/unicycle_highcost_10cm.mprim new file mode 100755 index 0000000..de16976 --- /dev/null +++ b/navigations/sbpl_lattice_planner/matlab/mprim/unicycle_highcost_10cm.mprim @@ -0,0 +1,1683 @@ +resolution_m: 0.100000 +numberofangles: 16 +totalnumberofprimitives: 112 +primID: 0 +startangle_c: 0 +endpose_c: 1 0 0 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0111 0.0000 0.0000 +0.0222 0.0000 0.0000 +0.0333 0.0000 0.0000 +0.0444 0.0000 0.0000 +0.0556 0.0000 0.0000 +0.0667 0.0000 0.0000 +0.0778 0.0000 0.0000 +0.0889 0.0000 0.0000 +0.1000 0.0000 0.0000 +primID: 1 +startangle_c: 0 +endpose_c: 4 0 0 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0444 0.0000 0.0000 +0.0889 0.0000 0.0000 +0.1333 0.0000 0.0000 +0.1778 0.0000 0.0000 +0.2222 0.0000 0.0000 +0.2667 0.0000 0.0000 +0.3111 0.0000 0.0000 +0.3556 0.0000 0.0000 +0.4000 0.0000 0.0000 +primID: 2 +startangle_c: 0 +endpose_c: -1 0 0 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.0000 +-0.0111 0.0000 0.0000 +-0.0222 0.0000 0.0000 +-0.0333 0.0000 0.0000 +-0.0444 0.0000 0.0000 +-0.0556 0.0000 0.0000 +-0.0667 0.0000 0.0000 +-0.0778 0.0000 0.0000 +-0.0889 0.0000 0.0000 +-0.1000 0.0000 0.0000 +primID: 3 +startangle_c: 0 +endpose_c: 4 1 1 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0452 0.0048 0.0349 +0.0903 0.0111 0.0699 +0.1353 0.0191 0.1048 +0.1802 0.0286 0.1398 +0.2248 0.0398 0.1747 +0.2692 0.0525 0.2097 +0.3132 0.0668 0.2446 +0.3568 0.0826 0.2796 +0.4000 0.1000 0.3145 +primID: 4 +startangle_c: 0 +endpose_c: 4 -1 -1 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0452 -0.0048 -0.0349 +0.0903 -0.0111 -0.0699 +0.1353 -0.0191 -0.1048 +0.1802 -0.0286 -0.1398 +0.2248 -0.0398 -0.1747 +0.2692 -0.0525 -0.2097 +0.3132 -0.0668 -0.2446 +0.3568 -0.0826 -0.2796 +0.4000 -0.1000 -0.3145 +primID: 5 +startangle_c: 0 +endpose_c: 0 0 1 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0000 0.0000 0.0436 +0.0000 0.0000 0.0873 +0.0000 0.0000 0.1309 +0.0000 0.0000 0.1745 +0.0000 0.0000 0.2182 +0.0000 0.0000 0.2618 +0.0000 0.0000 0.3054 +0.0000 0.0000 0.3491 +0.0000 0.0000 0.3927 +primID: 6 +startangle_c: 0 +endpose_c: 0 0 -1 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0000 0.0000 -0.0436 +0.0000 0.0000 -0.0873 +0.0000 0.0000 -0.1309 +0.0000 0.0000 -0.1745 +0.0000 0.0000 -0.2182 +0.0000 0.0000 -0.2618 +0.0000 0.0000 -0.3054 +0.0000 0.0000 -0.3491 +0.0000 0.0000 -0.3927 +primID: 0 +startangle_c: 1 +endpose_c: 2 1 1 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0222 0.0111 0.3927 +0.0444 0.0222 0.3927 +0.0667 0.0333 0.3927 +0.0889 0.0444 0.3927 +0.1111 0.0556 0.3927 +0.1333 0.0667 0.3927 +0.1556 0.0778 0.3927 +0.1778 0.0889 0.3927 +0.2000 0.1000 0.3927 +primID: 1 +startangle_c: 1 +endpose_c: 6 3 1 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0667 0.0333 0.3927 +0.1333 0.0667 0.3927 +0.2000 0.1000 0.3927 +0.2667 0.1333 0.3927 +0.3333 0.1667 0.3927 +0.4000 0.2000 0.3927 +0.4667 0.2333 0.3927 +0.5333 0.2667 0.3927 +0.6000 0.3000 0.3927 +primID: 2 +startangle_c: 1 +endpose_c: -2 -1 1 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.3927 +-0.0222 -0.0111 0.3927 +-0.0444 -0.0222 0.3927 +-0.0667 -0.0333 0.3927 +-0.0889 -0.0444 0.3927 +-0.1111 -0.0556 0.3927 +-0.1333 -0.0667 0.3927 +-0.1556 -0.0778 0.3927 +-0.1778 -0.0889 0.3927 +-0.2000 -0.1000 0.3927 +primID: 3 +startangle_c: 1 +endpose_c: 3 2 2 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0369 0.0162 0.4345 +0.0731 0.0339 0.4783 +0.1085 0.0533 0.5222 +0.1430 0.0741 0.5661 +0.1766 0.0965 0.6099 +0.2091 0.1203 0.6538 +0.2405 0.1455 0.6977 +0.2709 0.1721 0.7415 +0.3000 0.2000 0.7854 +primID: 4 +startangle_c: 1 +endpose_c: 4 1 0 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0427 0.0177 0.3927 +0.0854 0.0354 0.3927 +0.1283 0.0523 0.3477 +0.1722 0.0668 0.2898 +0.2168 0.0787 0.2318 +0.2621 0.0880 0.1739 +0.3078 0.0947 0.1159 +0.3538 0.0987 0.0580 +0.4000 0.1000 0.0000 +primID: 5 +startangle_c: 1 +endpose_c: 0 0 2 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0000 0.0000 0.4363 +0.0000 0.0000 0.4800 +0.0000 0.0000 0.5236 +0.0000 0.0000 0.5672 +0.0000 0.0000 0.6109 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.6981 +0.0000 0.0000 0.7418 +0.0000 0.0000 0.7854 +primID: 6 +startangle_c: 1 +endpose_c: 0 0 0 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0000 0.0000 0.3491 +0.0000 0.0000 0.3054 +0.0000 0.0000 0.2618 +0.0000 0.0000 0.2182 +0.0000 0.0000 0.1745 +0.0000 0.0000 0.1309 +0.0000 0.0000 0.0873 +0.0000 0.0000 0.0436 +0.0000 0.0000 0.0000 +primID: 0 +startangle_c: 2 +endpose_c: 1 1 2 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0111 0.0111 0.7854 +0.0222 0.0222 0.7854 +0.0333 0.0333 0.7854 +0.0444 0.0444 0.7854 +0.0556 0.0556 0.7854 +0.0667 0.0667 0.7854 +0.0778 0.0778 0.7854 +0.0889 0.0889 0.7854 +0.1000 0.1000 0.7854 +primID: 1 +startangle_c: 2 +endpose_c: 3 3 2 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0333 0.0333 0.7854 +0.0667 0.0667 0.7854 +0.1000 0.1000 0.7854 +0.1333 0.1333 0.7854 +0.1667 0.1667 0.7854 +0.2000 0.2000 0.7854 +0.2333 0.2333 0.7854 +0.2667 0.2667 0.7854 +0.3000 0.3000 0.7854 +primID: 2 +startangle_c: 2 +endpose_c: -1 -1 2 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.7854 +-0.0111 -0.0111 0.7854 +-0.0222 -0.0222 0.7854 +-0.0333 -0.0333 0.7854 +-0.0444 -0.0444 0.7854 +-0.0556 -0.0556 0.7854 +-0.0667 -0.0667 0.7854 +-0.0778 -0.0778 0.7854 +-0.0889 -0.0889 0.7854 +-0.1000 -0.1000 0.7854 +primID: 3 +startangle_c: 2 +endpose_c: 2 4 3 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0262 0.0411 0.8119 +0.0515 0.0831 0.8384 +0.0758 0.1260 0.8649 +0.0991 0.1697 0.8913 +0.1214 0.2142 0.9178 +0.1426 0.2595 0.9443 +0.1628 0.3056 0.9708 +0.1820 0.3525 0.9973 +0.2000 0.4000 1.0238 +primID: 4 +startangle_c: 2 +endpose_c: 4 2 1 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0411 0.0262 0.7589 +0.0831 0.0515 0.7324 +0.1260 0.0758 0.7059 +0.1697 0.0991 0.6795 +0.2142 0.1214 0.6530 +0.2595 0.1426 0.6265 +0.3056 0.1628 0.6000 +0.3525 0.1820 0.5735 +0.4000 0.2000 0.5470 +primID: 5 +startangle_c: 2 +endpose_c: 0 0 3 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0000 0.0000 0.8290 +0.0000 0.0000 0.8727 +0.0000 0.0000 0.9163 +0.0000 0.0000 0.9599 +0.0000 0.0000 1.0036 +0.0000 0.0000 1.0472 +0.0000 0.0000 1.0908 +0.0000 0.0000 1.1345 +0.0000 0.0000 1.1781 +primID: 6 +startangle_c: 2 +endpose_c: 0 0 1 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0000 0.0000 0.7418 +0.0000 0.0000 0.6981 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.6109 +0.0000 0.0000 0.5672 +0.0000 0.0000 0.5236 +0.0000 0.0000 0.4800 +0.0000 0.0000 0.4363 +0.0000 0.0000 0.3927 +primID: 0 +startangle_c: 3 +endpose_c: 1 2 3 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0111 0.0222 1.1781 +0.0222 0.0444 1.1781 +0.0333 0.0667 1.1781 +0.0444 0.0889 1.1781 +0.0556 0.1111 1.1781 +0.0667 0.1333 1.1781 +0.0778 0.1556 1.1781 +0.0889 0.1778 1.1781 +0.1000 0.2000 1.1781 +primID: 1 +startangle_c: 3 +endpose_c: 3 6 3 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0333 0.0667 1.1781 +0.0667 0.1333 1.1781 +0.1000 0.2000 1.1781 +0.1333 0.2667 1.1781 +0.1667 0.3333 1.1781 +0.2000 0.4000 1.1781 +0.2333 0.4667 1.1781 +0.2667 0.5333 1.1781 +0.3000 0.6000 1.1781 +primID: 2 +startangle_c: 3 +endpose_c: -1 -2 3 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.1781 +-0.0111 -0.0222 1.1781 +-0.0222 -0.0444 1.1781 +-0.0333 -0.0667 1.1781 +-0.0444 -0.0889 1.1781 +-0.0556 -0.1111 1.1781 +-0.0667 -0.1333 1.1781 +-0.0778 -0.1556 1.1781 +-0.0889 -0.1778 1.1781 +-0.1000 -0.2000 1.1781 +primID: 3 +startangle_c: 3 +endpose_c: 2 3 2 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0162 0.0369 1.1363 +0.0339 0.0731 1.0925 +0.0533 0.1085 1.0486 +0.0741 0.1430 1.0047 +0.0965 0.1766 0.9609 +0.1203 0.2091 0.9170 +0.1455 0.2405 0.8731 +0.1721 0.2709 0.8293 +0.2000 0.3000 0.7854 +primID: 4 +startangle_c: 3 +endpose_c: 1 4 4 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0177 0.0427 1.1781 +0.0354 0.0854 1.1781 +0.0523 0.1283 1.2231 +0.0668 0.1722 1.2810 +0.0787 0.2168 1.3390 +0.0880 0.2621 1.3969 +0.0947 0.3078 1.4549 +0.0987 0.3538 1.5128 +0.1000 0.4000 1.5708 +primID: 5 +startangle_c: 3 +endpose_c: 0 0 2 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0000 0.0000 1.1345 +0.0000 0.0000 1.0908 +0.0000 0.0000 1.0472 +0.0000 0.0000 1.0036 +0.0000 0.0000 0.9599 +0.0000 0.0000 0.9163 +0.0000 0.0000 0.8727 +0.0000 0.0000 0.8290 +0.0000 0.0000 0.7854 +primID: 6 +startangle_c: 3 +endpose_c: 0 0 4 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0000 0.0000 1.2217 +0.0000 0.0000 1.2654 +0.0000 0.0000 1.3090 +0.0000 0.0000 1.3526 +0.0000 0.0000 1.3963 +0.0000 0.0000 1.4399 +0.0000 0.0000 1.4835 +0.0000 0.0000 1.5272 +0.0000 0.0000 1.5708 +primID: 0 +startangle_c: 4 +endpose_c: 0 1 4 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0111 1.5708 +0.0000 0.0222 1.5708 +0.0000 0.0333 1.5708 +0.0000 0.0444 1.5708 +0.0000 0.0556 1.5708 +0.0000 0.0667 1.5708 +0.0000 0.0778 1.5708 +0.0000 0.0889 1.5708 +0.0000 0.1000 1.5708 +primID: 1 +startangle_c: 4 +endpose_c: 0 4 4 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0444 1.5708 +0.0000 0.0889 1.5708 +0.0000 0.1333 1.5708 +0.0000 0.1778 1.5708 +0.0000 0.2222 1.5708 +0.0000 0.2667 1.5708 +0.0000 0.3111 1.5708 +0.0000 0.3556 1.5708 +0.0000 0.4000 1.5708 +primID: 2 +startangle_c: 4 +endpose_c: 0 -1 4 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 -0.0111 1.5708 +0.0000 -0.0222 1.5708 +0.0000 -0.0333 1.5708 +0.0000 -0.0444 1.5708 +0.0000 -0.0556 1.5708 +0.0000 -0.0667 1.5708 +0.0000 -0.0778 1.5708 +0.0000 -0.0889 1.5708 +0.0000 -0.1000 1.5708 +primID: 3 +startangle_c: 4 +endpose_c: -1 4 5 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.5708 +-0.0048 0.0452 1.6057 +-0.0111 0.0903 1.6407 +-0.0191 0.1353 1.6756 +-0.0286 0.1802 1.7106 +-0.0398 0.2248 1.7455 +-0.0525 0.2692 1.7805 +-0.0668 0.3132 1.8154 +-0.0826 0.3568 1.8503 +-0.1000 0.4000 1.8853 +primID: 4 +startangle_c: 4 +endpose_c: 1 4 3 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0048 0.0452 1.5359 +0.0111 0.0903 1.5009 +0.0191 0.1353 1.4660 +0.0286 0.1802 1.4310 +0.0398 0.2248 1.3961 +0.0525 0.2692 1.3611 +0.0668 0.3132 1.3262 +0.0826 0.3568 1.2912 +0.1000 0.4000 1.2563 +primID: 5 +startangle_c: 4 +endpose_c: 0 0 5 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0000 1.6144 +0.0000 0.0000 1.6581 +0.0000 0.0000 1.7017 +0.0000 0.0000 1.7453 +0.0000 0.0000 1.7890 +0.0000 0.0000 1.8326 +0.0000 0.0000 1.8762 +0.0000 0.0000 1.9199 +0.0000 0.0000 1.9635 +primID: 6 +startangle_c: 4 +endpose_c: 0 0 3 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0000 1.5272 +0.0000 0.0000 1.4835 +0.0000 0.0000 1.4399 +0.0000 0.0000 1.3963 +0.0000 0.0000 1.3526 +0.0000 0.0000 1.3090 +0.0000 0.0000 1.2654 +0.0000 0.0000 1.2217 +0.0000 0.0000 1.1781 +primID: 0 +startangle_c: 5 +endpose_c: -1 2 5 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0111 0.0222 1.9635 +-0.0222 0.0444 1.9635 +-0.0333 0.0667 1.9635 +-0.0444 0.0889 1.9635 +-0.0556 0.1111 1.9635 +-0.0667 0.1333 1.9635 +-0.0778 0.1556 1.9635 +-0.0889 0.1778 1.9635 +-0.1000 0.2000 1.9635 +primID: 1 +startangle_c: 5 +endpose_c: -3 6 5 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0333 0.0667 1.9635 +-0.0667 0.1333 1.9635 +-0.1000 0.2000 1.9635 +-0.1333 0.2667 1.9635 +-0.1667 0.3333 1.9635 +-0.2000 0.4000 1.9635 +-0.2333 0.4667 1.9635 +-0.2667 0.5333 1.9635 +-0.3000 0.6000 1.9635 +primID: 2 +startangle_c: 5 +endpose_c: 1 -2 5 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0111 -0.0222 1.9635 +0.0222 -0.0444 1.9635 +0.0333 -0.0667 1.9635 +0.0444 -0.0889 1.9635 +0.0556 -0.1111 1.9635 +0.0667 -0.1333 1.9635 +0.0778 -0.1556 1.9635 +0.0889 -0.1778 1.9635 +0.1000 -0.2000 1.9635 +primID: 3 +startangle_c: 5 +endpose_c: -2 3 6 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0162 0.0369 2.0053 +-0.0339 0.0731 2.0491 +-0.0533 0.1085 2.0930 +-0.0741 0.1430 2.1369 +-0.0965 0.1766 2.1807 +-0.1203 0.2091 2.2246 +-0.1455 0.2405 2.2685 +-0.1721 0.2709 2.3123 +-0.2000 0.3000 2.3562 +primID: 4 +startangle_c: 5 +endpose_c: -1 4 4 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0177 0.0427 1.9635 +-0.0354 0.0854 1.9635 +-0.0523 0.1283 1.9185 +-0.0668 0.1722 1.8606 +-0.0787 0.2168 1.8026 +-0.0880 0.2621 1.7447 +-0.0947 0.3078 1.6867 +-0.0987 0.3538 1.6287 +-0.1000 0.4000 1.5708 +primID: 5 +startangle_c: 5 +endpose_c: 0 0 6 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0000 0.0000 2.0071 +0.0000 0.0000 2.0508 +0.0000 0.0000 2.0944 +0.0000 0.0000 2.1380 +0.0000 0.0000 2.1817 +0.0000 0.0000 2.2253 +0.0000 0.0000 2.2689 +0.0000 0.0000 2.3126 +0.0000 0.0000 2.3562 +primID: 6 +startangle_c: 5 +endpose_c: 0 0 4 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0000 0.0000 1.9199 +0.0000 0.0000 1.8762 +0.0000 0.0000 1.8326 +0.0000 0.0000 1.7890 +0.0000 0.0000 1.7453 +0.0000 0.0000 1.7017 +0.0000 0.0000 1.6581 +0.0000 0.0000 1.6144 +0.0000 0.0000 1.5708 +primID: 0 +startangle_c: 6 +endpose_c: -1 1 6 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0111 0.0111 2.3562 +-0.0222 0.0222 2.3562 +-0.0333 0.0333 2.3562 +-0.0444 0.0444 2.3562 +-0.0556 0.0556 2.3562 +-0.0667 0.0667 2.3562 +-0.0778 0.0778 2.3562 +-0.0889 0.0889 2.3562 +-0.1000 0.1000 2.3562 +primID: 1 +startangle_c: 6 +endpose_c: -3 3 6 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0333 0.0333 2.3562 +-0.0667 0.0667 2.3562 +-0.1000 0.1000 2.3562 +-0.1333 0.1333 2.3562 +-0.1667 0.1667 2.3562 +-0.2000 0.2000 2.3562 +-0.2333 0.2333 2.3562 +-0.2667 0.2667 2.3562 +-0.3000 0.3000 2.3562 +primID: 2 +startangle_c: 6 +endpose_c: 1 -1 6 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0111 -0.0111 2.3562 +0.0222 -0.0222 2.3562 +0.0333 -0.0333 2.3562 +0.0444 -0.0444 2.3562 +0.0556 -0.0556 2.3562 +0.0667 -0.0667 2.3562 +0.0778 -0.0778 2.3562 +0.0889 -0.0889 2.3562 +0.1000 -0.1000 2.3562 +primID: 3 +startangle_c: 6 +endpose_c: -4 2 7 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0411 0.0262 2.3827 +-0.0831 0.0515 2.4092 +-0.1260 0.0758 2.4357 +-0.1697 0.0991 2.4621 +-0.2142 0.1214 2.4886 +-0.2595 0.1426 2.5151 +-0.3056 0.1628 2.5416 +-0.3525 0.1820 2.5681 +-0.4000 0.2000 2.5946 +primID: 4 +startangle_c: 6 +endpose_c: -2 4 5 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0262 0.0411 2.3297 +-0.0515 0.0831 2.3032 +-0.0758 0.1260 2.2767 +-0.0991 0.1697 2.2502 +-0.1214 0.2142 2.2238 +-0.1426 0.2595 2.1973 +-0.1628 0.3056 2.1708 +-0.1820 0.3525 2.1443 +-0.2000 0.4000 2.1178 +primID: 5 +startangle_c: 6 +endpose_c: 0 0 7 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0000 0.0000 2.3998 +0.0000 0.0000 2.4435 +0.0000 0.0000 2.4871 +0.0000 0.0000 2.5307 +0.0000 0.0000 2.5744 +0.0000 0.0000 2.6180 +0.0000 0.0000 2.6616 +0.0000 0.0000 2.7053 +0.0000 0.0000 2.7489 +primID: 6 +startangle_c: 6 +endpose_c: 0 0 5 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0000 0.0000 2.3126 +0.0000 0.0000 2.2689 +0.0000 0.0000 2.2253 +0.0000 0.0000 2.1817 +0.0000 0.0000 2.1380 +0.0000 0.0000 2.0944 +0.0000 0.0000 2.0508 +0.0000 0.0000 2.0071 +0.0000 0.0000 1.9635 +primID: 0 +startangle_c: 7 +endpose_c: -2 1 7 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0222 0.0111 2.7489 +-0.0444 0.0222 2.7489 +-0.0667 0.0333 2.7489 +-0.0889 0.0444 2.7489 +-0.1111 0.0556 2.7489 +-0.1333 0.0667 2.7489 +-0.1556 0.0778 2.7489 +-0.1778 0.0889 2.7489 +-0.2000 0.1000 2.7489 +primID: 1 +startangle_c: 7 +endpose_c: -6 3 7 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0667 0.0333 2.7489 +-0.1333 0.0667 2.7489 +-0.2000 0.1000 2.7489 +-0.2667 0.1333 2.7489 +-0.3333 0.1667 2.7489 +-0.4000 0.2000 2.7489 +-0.4667 0.2333 2.7489 +-0.5333 0.2667 2.7489 +-0.6000 0.3000 2.7489 +primID: 2 +startangle_c: 7 +endpose_c: 2 -1 7 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0222 -0.0111 2.7489 +0.0444 -0.0222 2.7489 +0.0667 -0.0333 2.7489 +0.0889 -0.0444 2.7489 +0.1111 -0.0556 2.7489 +0.1333 -0.0667 2.7489 +0.1556 -0.0778 2.7489 +0.1778 -0.0889 2.7489 +0.2000 -0.1000 2.7489 +primID: 3 +startangle_c: 7 +endpose_c: -3 2 6 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0369 0.0162 2.7071 +-0.0731 0.0339 2.6633 +-0.1085 0.0533 2.6194 +-0.1430 0.0741 2.5755 +-0.1766 0.0965 2.5317 +-0.2091 0.1203 2.4878 +-0.2405 0.1455 2.4439 +-0.2709 0.1721 2.4001 +-0.3000 0.2000 2.3562 +primID: 4 +startangle_c: 7 +endpose_c: -4 1 8 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0427 0.0177 2.7489 +-0.0854 0.0354 2.7489 +-0.1283 0.0523 2.7939 +-0.1722 0.0668 2.8518 +-0.2168 0.0787 2.9098 +-0.2621 0.0880 2.9677 +-0.3078 0.0947 3.0257 +-0.3538 0.0987 3.0836 +-0.4000 0.1000 3.1416 +primID: 5 +startangle_c: 7 +endpose_c: 0 0 6 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0000 0.0000 2.7053 +0.0000 0.0000 2.6616 +0.0000 0.0000 2.6180 +0.0000 0.0000 2.5744 +0.0000 0.0000 2.5307 +0.0000 0.0000 2.4871 +0.0000 0.0000 2.4435 +0.0000 0.0000 2.3998 +0.0000 0.0000 2.3562 +primID: 6 +startangle_c: 7 +endpose_c: 0 0 8 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0000 0.0000 2.7925 +0.0000 0.0000 2.8362 +0.0000 0.0000 2.8798 +0.0000 0.0000 2.9234 +0.0000 0.0000 2.9671 +0.0000 0.0000 3.0107 +0.0000 0.0000 3.0543 +0.0000 0.0000 3.0980 +0.0000 0.0000 3.1416 +primID: 0 +startangle_c: 8 +endpose_c: -1 0 8 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0111 0.0000 3.1416 +-0.0222 0.0000 3.1416 +-0.0333 0.0000 3.1416 +-0.0444 0.0000 3.1416 +-0.0556 0.0000 3.1416 +-0.0667 0.0000 3.1416 +-0.0778 0.0000 3.1416 +-0.0889 0.0000 3.1416 +-0.1000 0.0000 3.1416 +primID: 1 +startangle_c: 8 +endpose_c: -4 0 8 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0444 0.0000 3.1416 +-0.0889 0.0000 3.1416 +-0.1333 0.0000 3.1416 +-0.1778 0.0000 3.1416 +-0.2222 0.0000 3.1416 +-0.2667 0.0000 3.1416 +-0.3111 0.0000 3.1416 +-0.3556 0.0000 3.1416 +-0.4000 0.0000 3.1416 +primID: 2 +startangle_c: 8 +endpose_c: 1 0 8 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0111 0.0000 3.1416 +0.0222 0.0000 3.1416 +0.0333 0.0000 3.1416 +0.0444 0.0000 3.1416 +0.0556 0.0000 3.1416 +0.0667 0.0000 3.1416 +0.0778 0.0000 3.1416 +0.0889 0.0000 3.1416 +0.1000 0.0000 3.1416 +primID: 3 +startangle_c: 8 +endpose_c: -4 -1 9 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0452 -0.0048 3.1765 +-0.0903 -0.0111 3.2115 +-0.1353 -0.0191 3.2464 +-0.1802 -0.0286 3.2814 +-0.2248 -0.0398 3.3163 +-0.2692 -0.0525 3.3513 +-0.3132 -0.0668 3.3862 +-0.3568 -0.0826 3.4211 +-0.4000 -0.1000 3.4561 +primID: 4 +startangle_c: 8 +endpose_c: -4 1 7 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0452 0.0048 3.1066 +-0.0903 0.0111 3.0717 +-0.1353 0.0191 3.0368 +-0.1802 0.0286 3.0018 +-0.2248 0.0398 2.9669 +-0.2692 0.0525 2.9319 +-0.3132 0.0668 2.8970 +-0.3568 0.0826 2.8620 +-0.4000 0.1000 2.8271 +primID: 5 +startangle_c: 8 +endpose_c: 0 0 9 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0000 0.0000 3.1852 +0.0000 0.0000 3.2289 +0.0000 0.0000 3.2725 +0.0000 0.0000 3.3161 +0.0000 0.0000 3.3598 +0.0000 0.0000 3.4034 +0.0000 0.0000 3.4470 +0.0000 0.0000 3.4907 +0.0000 0.0000 3.5343 +primID: 6 +startangle_c: 8 +endpose_c: 0 0 7 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0000 0.0000 3.0980 +0.0000 0.0000 3.0543 +0.0000 0.0000 3.0107 +0.0000 0.0000 2.9671 +0.0000 0.0000 2.9234 +0.0000 0.0000 2.8798 +0.0000 0.0000 2.8362 +0.0000 0.0000 2.7925 +0.0000 0.0000 2.7489 +primID: 0 +startangle_c: 9 +endpose_c: -2 -1 9 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0222 -0.0111 3.5343 +-0.0444 -0.0222 3.5343 +-0.0667 -0.0333 3.5343 +-0.0889 -0.0444 3.5343 +-0.1111 -0.0556 3.5343 +-0.1333 -0.0667 3.5343 +-0.1556 -0.0778 3.5343 +-0.1778 -0.0889 3.5343 +-0.2000 -0.1000 3.5343 +primID: 1 +startangle_c: 9 +endpose_c: -6 -3 9 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0667 -0.0333 3.5343 +-0.1333 -0.0667 3.5343 +-0.2000 -0.1000 3.5343 +-0.2667 -0.1333 3.5343 +-0.3333 -0.1667 3.5343 +-0.4000 -0.2000 3.5343 +-0.4667 -0.2333 3.5343 +-0.5333 -0.2667 3.5343 +-0.6000 -0.3000 3.5343 +primID: 2 +startangle_c: 9 +endpose_c: 2 1 9 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0222 0.0111 3.5343 +0.0444 0.0222 3.5343 +0.0667 0.0333 3.5343 +0.0889 0.0444 3.5343 +0.1111 0.0556 3.5343 +0.1333 0.0667 3.5343 +0.1556 0.0778 3.5343 +0.1778 0.0889 3.5343 +0.2000 0.1000 3.5343 +primID: 3 +startangle_c: 9 +endpose_c: -3 -2 10 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0369 -0.0162 3.5761 +-0.0731 -0.0339 3.6199 +-0.1085 -0.0533 3.6638 +-0.1430 -0.0741 3.7077 +-0.1766 -0.0965 3.7515 +-0.2091 -0.1203 3.7954 +-0.2405 -0.1455 3.8393 +-0.2709 -0.1721 3.8831 +-0.3000 -0.2000 3.9270 +primID: 4 +startangle_c: 9 +endpose_c: -4 -1 8 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0427 -0.0177 3.5343 +-0.0854 -0.0354 3.5343 +-0.1283 -0.0523 3.4893 +-0.1722 -0.0668 3.4313 +-0.2168 -0.0787 3.3734 +-0.2621 -0.0880 3.3154 +-0.3078 -0.0947 3.2575 +-0.3538 -0.0987 3.1995 +-0.4000 -0.1000 3.1416 +primID: 5 +startangle_c: 9 +endpose_c: 0 0 10 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0000 0.0000 3.5779 +0.0000 0.0000 3.6216 +0.0000 0.0000 3.6652 +0.0000 0.0000 3.7088 +0.0000 0.0000 3.7525 +0.0000 0.0000 3.7961 +0.0000 0.0000 3.8397 +0.0000 0.0000 3.8834 +0.0000 0.0000 3.9270 +primID: 6 +startangle_c: 9 +endpose_c: 0 0 8 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0000 0.0000 3.4907 +0.0000 0.0000 3.4470 +0.0000 0.0000 3.4034 +0.0000 0.0000 3.3598 +0.0000 0.0000 3.3161 +0.0000 0.0000 3.2725 +0.0000 0.0000 3.2289 +0.0000 0.0000 3.1852 +0.0000 0.0000 3.1416 +primID: 0 +startangle_c: 10 +endpose_c: -1 -1 10 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0111 -0.0111 3.9270 +-0.0222 -0.0222 3.9270 +-0.0333 -0.0333 3.9270 +-0.0444 -0.0444 3.9270 +-0.0556 -0.0556 3.9270 +-0.0667 -0.0667 3.9270 +-0.0778 -0.0778 3.9270 +-0.0889 -0.0889 3.9270 +-0.1000 -0.1000 3.9270 +primID: 1 +startangle_c: 10 +endpose_c: -3 -3 10 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0333 -0.0333 3.9270 +-0.0667 -0.0667 3.9270 +-0.1000 -0.1000 3.9270 +-0.1333 -0.1333 3.9270 +-0.1667 -0.1667 3.9270 +-0.2000 -0.2000 3.9270 +-0.2333 -0.2333 3.9270 +-0.2667 -0.2667 3.9270 +-0.3000 -0.3000 3.9270 +primID: 2 +startangle_c: 10 +endpose_c: 1 1 10 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0111 0.0111 3.9270 +0.0222 0.0222 3.9270 +0.0333 0.0333 3.9270 +0.0444 0.0444 3.9270 +0.0556 0.0556 3.9270 +0.0667 0.0667 3.9270 +0.0778 0.0778 3.9270 +0.0889 0.0889 3.9270 +0.1000 0.1000 3.9270 +primID: 3 +startangle_c: 10 +endpose_c: -2 -4 11 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0262 -0.0411 3.9535 +-0.0515 -0.0831 3.9800 +-0.0758 -0.1260 4.0064 +-0.0991 -0.1697 4.0329 +-0.1214 -0.2142 4.0594 +-0.1426 -0.2595 4.0859 +-0.1628 -0.3056 4.1124 +-0.1820 -0.3525 4.1389 +-0.2000 -0.4000 4.1654 +primID: 4 +startangle_c: 10 +endpose_c: -4 -2 9 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0411 -0.0262 3.9005 +-0.0831 -0.0515 3.8740 +-0.1260 -0.0758 3.8475 +-0.1697 -0.0991 3.8210 +-0.2142 -0.1214 3.7946 +-0.2595 -0.1426 3.7681 +-0.3056 -0.1628 3.7416 +-0.3525 -0.1820 3.7151 +-0.4000 -0.2000 3.6886 +primID: 5 +startangle_c: 10 +endpose_c: 0 0 11 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.9706 +0.0000 0.0000 4.0143 +0.0000 0.0000 4.0579 +0.0000 0.0000 4.1015 +0.0000 0.0000 4.1452 +0.0000 0.0000 4.1888 +0.0000 0.0000 4.2324 +0.0000 0.0000 4.2761 +0.0000 0.0000 4.3197 +primID: 6 +startangle_c: 10 +endpose_c: 0 0 9 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.8834 +0.0000 0.0000 3.8397 +0.0000 0.0000 3.7961 +0.0000 0.0000 3.7525 +0.0000 0.0000 3.7088 +0.0000 0.0000 3.6652 +0.0000 0.0000 3.6216 +0.0000 0.0000 3.5779 +0.0000 0.0000 3.5343 +primID: 0 +startangle_c: 11 +endpose_c: -1 -2 11 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0111 -0.0222 4.3197 +-0.0222 -0.0444 4.3197 +-0.0333 -0.0667 4.3197 +-0.0444 -0.0889 4.3197 +-0.0556 -0.1111 4.3197 +-0.0667 -0.1333 4.3197 +-0.0778 -0.1556 4.3197 +-0.0889 -0.1778 4.3197 +-0.1000 -0.2000 4.3197 +primID: 1 +startangle_c: 11 +endpose_c: -3 -6 11 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0333 -0.0667 4.3197 +-0.0667 -0.1333 4.3197 +-0.1000 -0.2000 4.3197 +-0.1333 -0.2667 4.3197 +-0.1667 -0.3333 4.3197 +-0.2000 -0.4000 4.3197 +-0.2333 -0.4667 4.3197 +-0.2667 -0.5333 4.3197 +-0.3000 -0.6000 4.3197 +primID: 2 +startangle_c: 11 +endpose_c: 1 2 11 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0111 0.0222 4.3197 +0.0222 0.0444 4.3197 +0.0333 0.0667 4.3197 +0.0444 0.0889 4.3197 +0.0556 0.1111 4.3197 +0.0667 0.1333 4.3197 +0.0778 0.1556 4.3197 +0.0889 0.1778 4.3197 +0.1000 0.2000 4.3197 +primID: 3 +startangle_c: 11 +endpose_c: -2 -3 10 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0162 -0.0369 4.2779 +-0.0339 -0.0731 4.2341 +-0.0533 -0.1085 4.1902 +-0.0741 -0.1430 4.1463 +-0.0965 -0.1766 4.1025 +-0.1203 -0.2091 4.0586 +-0.1455 -0.2405 4.0147 +-0.1721 -0.2709 3.9709 +-0.2000 -0.3000 3.9270 +primID: 4 +startangle_c: 11 +endpose_c: -1 -4 12 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0177 -0.0427 4.3197 +-0.0354 -0.0854 4.3197 +-0.0523 -0.1283 4.3647 +-0.0668 -0.1722 4.4226 +-0.0787 -0.2168 4.4806 +-0.0880 -0.2621 4.5385 +-0.0947 -0.3078 4.5965 +-0.0987 -0.3538 4.6544 +-0.1000 -0.4000 4.7124 +primID: 5 +startangle_c: 11 +endpose_c: 0 0 10 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0000 0.0000 4.2761 +0.0000 0.0000 4.2324 +0.0000 0.0000 4.1888 +0.0000 0.0000 4.1452 +0.0000 0.0000 4.1015 +0.0000 0.0000 4.0579 +0.0000 0.0000 4.0143 +0.0000 0.0000 3.9706 +0.0000 0.0000 3.9270 +primID: 6 +startangle_c: 11 +endpose_c: 0 0 12 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0000 0.0000 4.3633 +0.0000 0.0000 4.4070 +0.0000 0.0000 4.4506 +0.0000 0.0000 4.4942 +0.0000 0.0000 4.5379 +0.0000 0.0000 4.5815 +0.0000 0.0000 4.6251 +0.0000 0.0000 4.6688 +0.0000 0.0000 4.7124 +primID: 0 +startangle_c: 12 +endpose_c: 0 -1 12 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0111 4.7124 +0.0000 -0.0222 4.7124 +0.0000 -0.0333 4.7124 +0.0000 -0.0444 4.7124 +0.0000 -0.0556 4.7124 +0.0000 -0.0667 4.7124 +0.0000 -0.0778 4.7124 +0.0000 -0.0889 4.7124 +0.0000 -0.1000 4.7124 +primID: 1 +startangle_c: 12 +endpose_c: 0 -4 12 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0444 4.7124 +0.0000 -0.0889 4.7124 +0.0000 -0.1333 4.7124 +0.0000 -0.1778 4.7124 +0.0000 -0.2222 4.7124 +0.0000 -0.2667 4.7124 +0.0000 -0.3111 4.7124 +0.0000 -0.3556 4.7124 +0.0000 -0.4000 4.7124 +primID: 2 +startangle_c: 12 +endpose_c: 0 1 12 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0111 4.7124 +0.0000 0.0222 4.7124 +0.0000 0.0333 4.7124 +0.0000 0.0444 4.7124 +0.0000 0.0556 4.7124 +0.0000 0.0667 4.7124 +0.0000 0.0778 4.7124 +0.0000 0.0889 4.7124 +0.0000 0.1000 4.7124 +primID: 3 +startangle_c: 12 +endpose_c: 1 -4 13 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0048 -0.0452 4.7473 +0.0111 -0.0903 4.7823 +0.0191 -0.1353 4.8172 +0.0286 -0.1802 4.8522 +0.0398 -0.2248 4.8871 +0.0525 -0.2692 4.9221 +0.0668 -0.3132 4.9570 +0.0826 -0.3568 4.9919 +0.1000 -0.4000 5.0269 +primID: 4 +startangle_c: 12 +endpose_c: -1 -4 11 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.7124 +-0.0048 -0.0452 4.6774 +-0.0111 -0.0903 4.6425 +-0.0191 -0.1353 4.6076 +-0.0286 -0.1802 4.5726 +-0.0398 -0.2248 4.5377 +-0.0525 -0.2692 4.5027 +-0.0668 -0.3132 4.4678 +-0.0826 -0.3568 4.4328 +-0.1000 -0.4000 4.3979 +primID: 5 +startangle_c: 12 +endpose_c: 0 0 13 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0000 4.7560 +0.0000 0.0000 4.7997 +0.0000 0.0000 4.8433 +0.0000 0.0000 4.8869 +0.0000 0.0000 4.9306 +0.0000 0.0000 4.9742 +0.0000 0.0000 5.0178 +0.0000 0.0000 5.0615 +0.0000 0.0000 5.1051 +primID: 6 +startangle_c: 12 +endpose_c: 0 0 11 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0000 4.6688 +0.0000 0.0000 4.6251 +0.0000 0.0000 4.5815 +0.0000 0.0000 4.5379 +0.0000 0.0000 4.4942 +0.0000 0.0000 4.4506 +0.0000 0.0000 4.4070 +0.0000 0.0000 4.3633 +0.0000 0.0000 4.3197 +primID: 0 +startangle_c: 13 +endpose_c: 1 -2 13 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0111 -0.0222 5.1051 +0.0222 -0.0444 5.1051 +0.0333 -0.0667 5.1051 +0.0444 -0.0889 5.1051 +0.0556 -0.1111 5.1051 +0.0667 -0.1333 5.1051 +0.0778 -0.1556 5.1051 +0.0889 -0.1778 5.1051 +0.1000 -0.2000 5.1051 +primID: 1 +startangle_c: 13 +endpose_c: 3 -6 13 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0333 -0.0667 5.1051 +0.0667 -0.1333 5.1051 +0.1000 -0.2000 5.1051 +0.1333 -0.2667 5.1051 +0.1667 -0.3333 5.1051 +0.2000 -0.4000 5.1051 +0.2333 -0.4667 5.1051 +0.2667 -0.5333 5.1051 +0.3000 -0.6000 5.1051 +primID: 2 +startangle_c: 13 +endpose_c: -1 2 13 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.1051 +-0.0111 0.0222 5.1051 +-0.0222 0.0444 5.1051 +-0.0333 0.0667 5.1051 +-0.0444 0.0889 5.1051 +-0.0556 0.1111 5.1051 +-0.0667 0.1333 5.1051 +-0.0778 0.1556 5.1051 +-0.0889 0.1778 5.1051 +-0.1000 0.2000 5.1051 +primID: 3 +startangle_c: 13 +endpose_c: 2 -3 14 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0162 -0.0369 5.1469 +0.0339 -0.0731 5.1907 +0.0533 -0.1085 5.2346 +0.0741 -0.1430 5.2785 +0.0965 -0.1766 5.3223 +0.1203 -0.2091 5.3662 +0.1455 -0.2405 5.4101 +0.1721 -0.2709 5.4539 +0.2000 -0.3000 5.4978 +primID: 4 +startangle_c: 13 +endpose_c: 1 -4 12 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0177 -0.0427 5.1051 +0.0354 -0.0854 5.1051 +0.0523 -0.1283 5.0601 +0.0668 -0.1722 5.0021 +0.0787 -0.2168 4.9442 +0.0880 -0.2621 4.8862 +0.0947 -0.3078 4.8283 +0.0987 -0.3538 4.7703 +0.1000 -0.4000 4.7124 +primID: 5 +startangle_c: 13 +endpose_c: 0 0 14 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0000 0.0000 5.1487 +0.0000 0.0000 5.1924 +0.0000 0.0000 5.2360 +0.0000 0.0000 5.2796 +0.0000 0.0000 5.3233 +0.0000 0.0000 5.3669 +0.0000 0.0000 5.4105 +0.0000 0.0000 5.4542 +0.0000 0.0000 5.4978 +primID: 6 +startangle_c: 13 +endpose_c: 0 0 12 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0000 0.0000 5.0615 +0.0000 0.0000 5.0178 +0.0000 0.0000 4.9742 +0.0000 0.0000 4.9306 +0.0000 0.0000 4.8869 +0.0000 0.0000 4.8433 +0.0000 0.0000 4.7997 +0.0000 0.0000 4.7560 +0.0000 0.0000 4.7124 +primID: 0 +startangle_c: 14 +endpose_c: 1 -1 14 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0111 -0.0111 5.4978 +0.0222 -0.0222 5.4978 +0.0333 -0.0333 5.4978 +0.0444 -0.0444 5.4978 +0.0556 -0.0556 5.4978 +0.0667 -0.0667 5.4978 +0.0778 -0.0778 5.4978 +0.0889 -0.0889 5.4978 +0.1000 -0.1000 5.4978 +primID: 1 +startangle_c: 14 +endpose_c: 3 -3 14 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0333 -0.0333 5.4978 +0.0667 -0.0667 5.4978 +0.1000 -0.1000 5.4978 +0.1333 -0.1333 5.4978 +0.1667 -0.1667 5.4978 +0.2000 -0.2000 5.4978 +0.2333 -0.2333 5.4978 +0.2667 -0.2667 5.4978 +0.3000 -0.3000 5.4978 +primID: 2 +startangle_c: 14 +endpose_c: -1 1 14 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.4978 +-0.0111 0.0111 5.4978 +-0.0222 0.0222 5.4978 +-0.0333 0.0333 5.4978 +-0.0444 0.0444 5.4978 +-0.0556 0.0556 5.4978 +-0.0667 0.0667 5.4978 +-0.0778 0.0778 5.4978 +-0.0889 0.0889 5.4978 +-0.1000 0.1000 5.4978 +primID: 3 +startangle_c: 14 +endpose_c: 4 -2 15 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0411 -0.0262 5.5243 +0.0831 -0.0515 5.5508 +0.1260 -0.0758 5.5772 +0.1697 -0.0991 5.6037 +0.2142 -0.1214 5.6302 +0.2595 -0.1426 5.6567 +0.3056 -0.1628 5.6832 +0.3525 -0.1820 5.7097 +0.4000 -0.2000 5.7362 +primID: 4 +startangle_c: 14 +endpose_c: 2 -4 13 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0262 -0.0411 5.4713 +0.0515 -0.0831 5.4448 +0.0758 -0.1260 5.4183 +0.0991 -0.1697 5.3918 +0.1214 -0.2142 5.3654 +0.1426 -0.2595 5.3389 +0.1628 -0.3056 5.3124 +0.1820 -0.3525 5.2859 +0.2000 -0.4000 5.2594 +primID: 5 +startangle_c: 14 +endpose_c: 0 0 15 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0000 0.0000 5.5414 +0.0000 0.0000 5.5851 +0.0000 0.0000 5.6287 +0.0000 0.0000 5.6723 +0.0000 0.0000 5.7160 +0.0000 0.0000 5.7596 +0.0000 0.0000 5.8032 +0.0000 0.0000 5.8469 +0.0000 0.0000 5.8905 +primID: 6 +startangle_c: 14 +endpose_c: 0 0 13 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0000 0.0000 5.4542 +0.0000 0.0000 5.4105 +0.0000 0.0000 5.3669 +0.0000 0.0000 5.3233 +0.0000 0.0000 5.2796 +0.0000 0.0000 5.2360 +0.0000 0.0000 5.1924 +0.0000 0.0000 5.1487 +0.0000 0.0000 5.1051 +primID: 0 +startangle_c: 15 +endpose_c: 2 -1 15 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0222 -0.0111 5.8905 +0.0444 -0.0222 5.8905 +0.0667 -0.0333 5.8905 +0.0889 -0.0444 5.8905 +0.1111 -0.0556 5.8905 +0.1333 -0.0667 5.8905 +0.1556 -0.0778 5.8905 +0.1778 -0.0889 5.8905 +0.2000 -0.1000 5.8905 +primID: 1 +startangle_c: 15 +endpose_c: 6 -3 15 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0667 -0.0333 5.8905 +0.1333 -0.0667 5.8905 +0.2000 -0.1000 5.8905 +0.2667 -0.1333 5.8905 +0.3333 -0.1667 5.8905 +0.4000 -0.2000 5.8905 +0.4667 -0.2333 5.8905 +0.5333 -0.2667 5.8905 +0.6000 -0.3000 5.8905 +primID: 2 +startangle_c: 15 +endpose_c: -2 1 15 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.8905 +-0.0222 0.0111 5.8905 +-0.0444 0.0222 5.8905 +-0.0667 0.0333 5.8905 +-0.0889 0.0444 5.8905 +-0.1111 0.0556 5.8905 +-0.1333 0.0667 5.8905 +-0.1556 0.0778 5.8905 +-0.1778 0.0889 5.8905 +-0.2000 0.1000 5.8905 +primID: 3 +startangle_c: 15 +endpose_c: 3 -2 14 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0369 -0.0162 5.8487 +0.0731 -0.0339 5.8049 +0.1085 -0.0533 5.7610 +0.1430 -0.0741 5.7171 +0.1766 -0.0965 5.6733 +0.2091 -0.1203 5.6294 +0.2405 -0.1455 5.5855 +0.2709 -0.1721 5.5417 +0.3000 -0.2000 5.4978 +primID: 4 +startangle_c: 15 +endpose_c: 4 -1 0 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0427 -0.0177 5.8905 +0.0854 -0.0354 5.8905 +0.1283 -0.0523 5.9355 +0.1722 -0.0668 5.9934 +0.2168 -0.0787 6.0514 +0.2621 -0.0880 6.1093 +0.3078 -0.0947 6.1673 +0.3538 -0.0987 6.2252 +0.4000 -0.1000 6.2832 +primID: 5 +startangle_c: 15 +endpose_c: 0 0 14 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0000 0.0000 5.8469 +0.0000 0.0000 5.8032 +0.0000 0.0000 5.7596 +0.0000 0.0000 5.7160 +0.0000 0.0000 5.6723 +0.0000 0.0000 5.6287 +0.0000 0.0000 5.5851 +0.0000 0.0000 5.5414 +0.0000 0.0000 5.4978 +primID: 6 +startangle_c: 15 +endpose_c: 0 0 0 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0000 0.0000 5.2360 +0.0000 0.0000 4.5815 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.2725 +0.0000 0.0000 2.6180 +0.0000 0.0000 1.9635 +0.0000 0.0000 1.3090 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.0000 diff --git a/navigations/sbpl_lattice_planner/matlab/mprim/unicycle_highcost_1cm.mprim b/navigations/sbpl_lattice_planner/matlab/mprim/unicycle_highcost_1cm.mprim new file mode 100755 index 0000000..aa9670d --- /dev/null +++ b/navigations/sbpl_lattice_planner/matlab/mprim/unicycle_highcost_1cm.mprim @@ -0,0 +1,1683 @@ +resolution_m: 0.010000 +numberofangles: 16 +totalnumberofprimitives: 112 +primID: 0 +startangle_c: 0 +endpose_c: 1 0 0 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0011 0.0000 0.0000 +0.0022 0.0000 0.0000 +0.0033 0.0000 0.0000 +0.0044 0.0000 0.0000 +0.0056 0.0000 0.0000 +0.0067 0.0000 0.0000 +0.0078 0.0000 0.0000 +0.0089 0.0000 0.0000 +0.0100 0.0000 0.0000 +primID: 1 +startangle_c: 0 +endpose_c: 20 0 0 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0222 0.0000 0.0000 +0.0444 0.0000 0.0000 +0.0667 0.0000 0.0000 +0.0889 0.0000 0.0000 +0.1111 0.0000 0.0000 +0.1333 0.0000 0.0000 +0.1556 0.0000 0.0000 +0.1778 0.0000 0.0000 +0.2000 0.0000 0.0000 +primID: 2 +startangle_c: 0 +endpose_c: -1 0 0 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.0000 +-0.0011 0.0000 0.0000 +-0.0022 0.0000 0.0000 +-0.0033 0.0000 0.0000 +-0.0044 0.0000 0.0000 +-0.0056 0.0000 0.0000 +-0.0067 0.0000 0.0000 +-0.0078 0.0000 0.0000 +-0.0089 0.0000 0.0000 +-0.0100 0.0000 0.0000 +primID: 3 +startangle_c: 0 +endpose_c: 40 5 1 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0452 -0.0000 0.0000 +0.0904 -0.0000 0.0000 +0.1355 -0.0000 0.0000 +0.1807 0.0008 0.0488 +0.2257 0.0045 0.1176 +0.2703 0.0114 0.1864 +0.3144 0.0213 0.2551 +0.3577 0.0342 0.3239 +0.4000 0.0500 0.3927 +primID: 4 +startangle_c: 0 +endpose_c: 40 -5 -1 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0452 0.0000 0.0000 +0.0904 0.0000 0.0000 +0.1355 0.0000 0.0000 +0.1807 -0.0008 -0.0488 +0.2257 -0.0045 -0.1176 +0.2703 -0.0114 -0.1864 +0.3144 -0.0213 -0.2551 +0.3577 -0.0342 -0.3239 +0.4000 -0.0500 -0.3927 +primID: 5 +startangle_c: 0 +endpose_c: 0 0 1 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0000 0.0000 0.0436 +0.0000 0.0000 0.0873 +0.0000 0.0000 0.1309 +0.0000 0.0000 0.1745 +0.0000 0.0000 0.2182 +0.0000 0.0000 0.2618 +0.0000 0.0000 0.3054 +0.0000 0.0000 0.3491 +0.0000 0.0000 0.3927 +primID: 6 +startangle_c: 0 +endpose_c: 0 0 -1 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0000 0.0000 -0.0436 +0.0000 0.0000 -0.0873 +0.0000 0.0000 -0.1309 +0.0000 0.0000 -0.1745 +0.0000 0.0000 -0.2182 +0.0000 0.0000 -0.2618 +0.0000 0.0000 -0.3054 +0.0000 0.0000 -0.3491 +0.0000 0.0000 -0.3927 +primID: 0 +startangle_c: 1 +endpose_c: 2 1 1 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0022 0.0011 0.3927 +0.0044 0.0022 0.3927 +0.0067 0.0033 0.3927 +0.0089 0.0044 0.3927 +0.0111 0.0056 0.3927 +0.0133 0.0067 0.3927 +0.0156 0.0078 0.3927 +0.0178 0.0089 0.3927 +0.0200 0.0100 0.3927 +primID: 1 +startangle_c: 1 +endpose_c: 20 10 1 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0222 0.0111 0.3927 +0.0444 0.0222 0.3927 +0.0667 0.0333 0.3927 +0.0889 0.0444 0.3927 +0.1111 0.0556 0.3927 +0.1333 0.0667 0.3927 +0.1556 0.0778 0.3927 +0.1778 0.0889 0.3927 +0.2000 0.1000 0.3927 +primID: 2 +startangle_c: 1 +endpose_c: -2 -1 1 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.3927 +-0.0022 -0.0011 0.3927 +-0.0044 -0.0022 0.3927 +-0.0067 -0.0033 0.3927 +-0.0089 -0.0044 0.3927 +-0.0111 -0.0056 0.3927 +-0.0133 -0.0067 0.3927 +-0.0156 -0.0078 0.3927 +-0.0178 -0.0089 0.3927 +-0.0200 -0.0100 0.3927 +primID: 3 +startangle_c: 1 +endpose_c: 25 20 2 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0298 0.0184 0.4230 +0.0592 0.0379 0.4533 +0.0881 0.0583 0.4836 +0.1165 0.0796 0.5139 +0.1444 0.1019 0.5442 +0.1717 0.1251 0.5745 +0.1984 0.1492 0.6048 +0.2245 0.1742 0.6351 +0.2500 0.2000 0.6654 +primID: 4 +startangle_c: 1 +endpose_c: 35 10 0 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0377 0.0156 0.3927 +0.0754 0.0312 0.3927 +0.1131 0.0468 0.3927 +0.1508 0.0623 0.3736 +0.1893 0.0758 0.2989 +0.2287 0.0863 0.2242 +0.2687 0.0939 0.1494 +0.3092 0.0985 0.0747 +0.3500 0.1000 -0.0000 +primID: 5 +startangle_c: 1 +endpose_c: 0 0 2 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0000 0.0000 0.4363 +0.0000 0.0000 0.4800 +0.0000 0.0000 0.5236 +0.0000 0.0000 0.5672 +0.0000 0.0000 0.6109 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.6981 +0.0000 0.0000 0.7418 +0.0000 0.0000 0.7854 +primID: 6 +startangle_c: 1 +endpose_c: 0 0 0 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0000 0.0000 0.3491 +0.0000 0.0000 0.3054 +0.0000 0.0000 0.2618 +0.0000 0.0000 0.2182 +0.0000 0.0000 0.1745 +0.0000 0.0000 0.1309 +0.0000 0.0000 0.0873 +0.0000 0.0000 0.0436 +0.0000 0.0000 0.0000 +primID: 0 +startangle_c: 2 +endpose_c: 1 1 2 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0011 0.0011 0.7854 +0.0022 0.0022 0.7854 +0.0033 0.0033 0.7854 +0.0044 0.0044 0.7854 +0.0056 0.0056 0.7854 +0.0067 0.0067 0.7854 +0.0078 0.0078 0.7854 +0.0089 0.0089 0.7854 +0.0100 0.0100 0.7854 +primID: 1 +startangle_c: 2 +endpose_c: 10 10 2 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0111 0.0111 0.7854 +0.0222 0.0222 0.7854 +0.0333 0.0333 0.7854 +0.0444 0.0444 0.7854 +0.0556 0.0556 0.7854 +0.0667 0.0667 0.7854 +0.0778 0.0778 0.7854 +0.0889 0.0889 0.7854 +0.1000 0.1000 0.7854 +primID: 2 +startangle_c: 2 +endpose_c: -1 -1 2 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.7854 +-0.0011 -0.0011 0.7854 +-0.0022 -0.0022 0.7854 +-0.0033 -0.0033 0.7854 +-0.0044 -0.0044 0.7854 +-0.0056 -0.0056 0.7854 +-0.0067 -0.0067 0.7854 +-0.0078 -0.0078 0.7854 +-0.0089 -0.0089 0.7854 +-0.0100 -0.0100 0.7854 +primID: 3 +startangle_c: 2 +endpose_c: 25 35 3 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0341 0.0341 0.7854 +0.0678 0.0684 0.8151 +0.1000 0.1043 0.8669 +0.1302 0.1418 0.9188 +0.1584 0.1809 0.9707 +0.1846 0.2213 1.0225 +0.2086 0.2631 1.0744 +0.2304 0.3060 1.1262 +0.2500 0.3500 1.1781 +primID: 4 +startangle_c: 2 +endpose_c: 35 25 1 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0341 0.0341 0.7854 +0.0684 0.0678 0.7557 +0.1043 0.1000 0.7039 +0.1418 0.1302 0.6520 +0.1809 0.1584 0.6001 +0.2213 0.1846 0.5483 +0.2631 0.2086 0.4964 +0.3060 0.2304 0.4446 +0.3500 0.2500 0.3927 +primID: 5 +startangle_c: 2 +endpose_c: 0 0 3 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0000 0.0000 0.8290 +0.0000 0.0000 0.8727 +0.0000 0.0000 0.9163 +0.0000 0.0000 0.9599 +0.0000 0.0000 1.0036 +0.0000 0.0000 1.0472 +0.0000 0.0000 1.0908 +0.0000 0.0000 1.1345 +0.0000 0.0000 1.1781 +primID: 6 +startangle_c: 2 +endpose_c: 0 0 1 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0000 0.0000 0.7418 +0.0000 0.0000 0.6981 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.6109 +0.0000 0.0000 0.5672 +0.0000 0.0000 0.5236 +0.0000 0.0000 0.4800 +0.0000 0.0000 0.4363 +0.0000 0.0000 0.3927 +primID: 0 +startangle_c: 3 +endpose_c: 1 2 3 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0011 0.0022 1.1781 +0.0022 0.0044 1.1781 +0.0033 0.0067 1.1781 +0.0044 0.0089 1.1781 +0.0056 0.0111 1.1781 +0.0067 0.0133 1.1781 +0.0078 0.0156 1.1781 +0.0089 0.0178 1.1781 +0.0100 0.0200 1.1781 +primID: 1 +startangle_c: 3 +endpose_c: 10 20 3 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0111 0.0222 1.1781 +0.0222 0.0444 1.1781 +0.0333 0.0667 1.1781 +0.0444 0.0889 1.1781 +0.0556 0.1111 1.1781 +0.0667 0.1333 1.1781 +0.0778 0.1556 1.1781 +0.0889 0.1778 1.1781 +0.1000 0.2000 1.1781 +primID: 2 +startangle_c: 3 +endpose_c: -1 -2 3 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.1781 +-0.0011 -0.0022 1.1781 +-0.0022 -0.0044 1.1781 +-0.0033 -0.0067 1.1781 +-0.0044 -0.0089 1.1781 +-0.0056 -0.0111 1.1781 +-0.0067 -0.0133 1.1781 +-0.0078 -0.0156 1.1781 +-0.0089 -0.0178 1.1781 +-0.0100 -0.0200 1.1781 +primID: 3 +startangle_c: 3 +endpose_c: 20 25 2 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0184 0.0298 1.1478 +0.0379 0.0592 1.1175 +0.0583 0.0881 1.0872 +0.0796 0.1165 1.0569 +0.1019 0.1444 1.0266 +0.1251 0.1717 0.9963 +0.1492 0.1984 0.9660 +0.1742 0.2245 0.9357 +0.2000 0.2500 0.9054 +primID: 4 +startangle_c: 3 +endpose_c: 10 35 4 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0156 0.0377 1.1781 +0.0312 0.0754 1.1781 +0.0468 0.1131 1.1781 +0.0623 0.1508 1.1972 +0.0758 0.1893 1.2719 +0.0863 0.2287 1.3466 +0.0939 0.2687 1.4214 +0.0985 0.3092 1.4961 +0.1000 0.3500 1.5708 +primID: 5 +startangle_c: 3 +endpose_c: 0 0 2 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0000 0.0000 1.1345 +0.0000 0.0000 1.0908 +0.0000 0.0000 1.0472 +0.0000 0.0000 1.0036 +0.0000 0.0000 0.9599 +0.0000 0.0000 0.9163 +0.0000 0.0000 0.8727 +0.0000 0.0000 0.8290 +0.0000 0.0000 0.7854 +primID: 6 +startangle_c: 3 +endpose_c: 0 0 4 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0000 0.0000 1.2217 +0.0000 0.0000 1.2654 +0.0000 0.0000 1.3090 +0.0000 0.0000 1.3526 +0.0000 0.0000 1.3963 +0.0000 0.0000 1.4399 +0.0000 0.0000 1.4835 +0.0000 0.0000 1.5272 +0.0000 0.0000 1.5708 +primID: 0 +startangle_c: 4 +endpose_c: 0 1 4 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0011 1.5708 +0.0000 0.0022 1.5708 +0.0000 0.0033 1.5708 +0.0000 0.0044 1.5708 +0.0000 0.0056 1.5708 +0.0000 0.0067 1.5708 +0.0000 0.0078 1.5708 +0.0000 0.0089 1.5708 +0.0000 0.0100 1.5708 +primID: 1 +startangle_c: 4 +endpose_c: 0 20 4 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0222 1.5708 +0.0000 0.0444 1.5708 +0.0000 0.0667 1.5708 +0.0000 0.0889 1.5708 +0.0000 0.1111 1.5708 +0.0000 0.1333 1.5708 +0.0000 0.1556 1.5708 +0.0000 0.1778 1.5708 +0.0000 0.2000 1.5708 +primID: 2 +startangle_c: 4 +endpose_c: 0 -1 4 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 -0.0011 1.5708 +0.0000 -0.0022 1.5708 +0.0000 -0.0033 1.5708 +0.0000 -0.0044 1.5708 +0.0000 -0.0056 1.5708 +0.0000 -0.0067 1.5708 +0.0000 -0.0078 1.5708 +0.0000 -0.0089 1.5708 +0.0000 -0.0100 1.5708 +primID: 3 +startangle_c: 4 +endpose_c: -5 40 5 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0452 1.5708 +0.0000 0.0904 1.5708 +0.0000 0.1355 1.5708 +-0.0008 0.1807 1.6196 +-0.0045 0.2257 1.6884 +-0.0114 0.2703 1.7572 +-0.0213 0.3144 1.8259 +-0.0342 0.3577 1.8947 +-0.0500 0.4000 1.9635 +primID: 4 +startangle_c: 4 +endpose_c: 5 40 3 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0452 1.5708 +0.0000 0.0904 1.5708 +0.0000 0.1355 1.5708 +0.0008 0.1807 1.5220 +0.0045 0.2257 1.4532 +0.0114 0.2703 1.3844 +0.0213 0.3144 1.3156 +0.0342 0.3577 1.2469 +0.0500 0.4000 1.1781 +primID: 5 +startangle_c: 4 +endpose_c: 0 0 5 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0000 1.6144 +0.0000 0.0000 1.6581 +0.0000 0.0000 1.7017 +0.0000 0.0000 1.7453 +0.0000 0.0000 1.7890 +0.0000 0.0000 1.8326 +0.0000 0.0000 1.8762 +0.0000 0.0000 1.9199 +0.0000 0.0000 1.9635 +primID: 6 +startangle_c: 4 +endpose_c: 0 0 3 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0000 1.5272 +0.0000 0.0000 1.4835 +0.0000 0.0000 1.4399 +0.0000 0.0000 1.3963 +0.0000 0.0000 1.3526 +0.0000 0.0000 1.3090 +0.0000 0.0000 1.2654 +0.0000 0.0000 1.2217 +0.0000 0.0000 1.1781 +primID: 0 +startangle_c: 5 +endpose_c: -1 2 5 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0011 0.0022 1.9635 +-0.0022 0.0044 1.9635 +-0.0033 0.0067 1.9635 +-0.0044 0.0089 1.9635 +-0.0056 0.0111 1.9635 +-0.0067 0.0133 1.9635 +-0.0078 0.0156 1.9635 +-0.0089 0.0178 1.9635 +-0.0100 0.0200 1.9635 +primID: 1 +startangle_c: 5 +endpose_c: -10 20 5 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0111 0.0222 1.9635 +-0.0222 0.0444 1.9635 +-0.0333 0.0667 1.9635 +-0.0444 0.0889 1.9635 +-0.0556 0.1111 1.9635 +-0.0667 0.1333 1.9635 +-0.0778 0.1556 1.9635 +-0.0889 0.1778 1.9635 +-0.1000 0.2000 1.9635 +primID: 2 +startangle_c: 5 +endpose_c: 1 -2 5 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0011 -0.0022 1.9635 +0.0022 -0.0044 1.9635 +0.0033 -0.0067 1.9635 +0.0044 -0.0089 1.9635 +0.0056 -0.0111 1.9635 +0.0067 -0.0133 1.9635 +0.0078 -0.0156 1.9635 +0.0089 -0.0178 1.9635 +0.0100 -0.0200 1.9635 +primID: 3 +startangle_c: 5 +endpose_c: -20 25 6 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0184 0.0298 1.9938 +-0.0379 0.0592 2.0241 +-0.0583 0.0881 2.0544 +-0.0796 0.1165 2.0847 +-0.1019 0.1444 2.1150 +-0.1251 0.1717 2.1453 +-0.1492 0.1984 2.1756 +-0.1742 0.2245 2.2059 +-0.2000 0.2500 2.2362 +primID: 4 +startangle_c: 5 +endpose_c: -10 35 4 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0156 0.0377 1.9635 +-0.0312 0.0754 1.9635 +-0.0468 0.1131 1.9635 +-0.0623 0.1508 1.9444 +-0.0758 0.1893 1.8697 +-0.0863 0.2287 1.7950 +-0.0939 0.2687 1.7202 +-0.0985 0.3092 1.6455 +-0.1000 0.3500 1.5708 +primID: 5 +startangle_c: 5 +endpose_c: 0 0 6 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0000 0.0000 2.0071 +0.0000 0.0000 2.0508 +0.0000 0.0000 2.0944 +0.0000 0.0000 2.1380 +0.0000 0.0000 2.1817 +0.0000 0.0000 2.2253 +0.0000 0.0000 2.2689 +0.0000 0.0000 2.3126 +0.0000 0.0000 2.3562 +primID: 6 +startangle_c: 5 +endpose_c: 0 0 4 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0000 0.0000 1.9199 +0.0000 0.0000 1.8762 +0.0000 0.0000 1.8326 +0.0000 0.0000 1.7890 +0.0000 0.0000 1.7453 +0.0000 0.0000 1.7017 +0.0000 0.0000 1.6581 +0.0000 0.0000 1.6144 +0.0000 0.0000 1.5708 +primID: 0 +startangle_c: 6 +endpose_c: -1 1 6 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0011 0.0011 2.3562 +-0.0022 0.0022 2.3562 +-0.0033 0.0033 2.3562 +-0.0044 0.0044 2.3562 +-0.0056 0.0056 2.3562 +-0.0067 0.0067 2.3562 +-0.0078 0.0078 2.3562 +-0.0089 0.0089 2.3562 +-0.0100 0.0100 2.3562 +primID: 1 +startangle_c: 6 +endpose_c: -10 10 6 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0111 0.0111 2.3562 +-0.0222 0.0222 2.3562 +-0.0333 0.0333 2.3562 +-0.0444 0.0444 2.3562 +-0.0556 0.0556 2.3562 +-0.0667 0.0667 2.3562 +-0.0778 0.0778 2.3562 +-0.0889 0.0889 2.3562 +-0.1000 0.1000 2.3562 +primID: 2 +startangle_c: 6 +endpose_c: 1 -1 6 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0011 -0.0011 2.3562 +0.0022 -0.0022 2.3562 +0.0033 -0.0033 2.3562 +0.0044 -0.0044 2.3562 +0.0056 -0.0056 2.3562 +0.0067 -0.0067 2.3562 +0.0078 -0.0078 2.3562 +0.0089 -0.0089 2.3562 +0.0100 -0.0100 2.3562 +primID: 3 +startangle_c: 6 +endpose_c: -35 25 7 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0341 0.0341 2.3562 +-0.0684 0.0678 2.3859 +-0.1043 0.1000 2.4377 +-0.1418 0.1302 2.4896 +-0.1809 0.1584 2.5415 +-0.2213 0.1846 2.5933 +-0.2631 0.2086 2.6452 +-0.3060 0.2304 2.6970 +-0.3500 0.2500 2.7489 +primID: 4 +startangle_c: 6 +endpose_c: -25 35 5 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0341 0.0341 2.3562 +-0.0678 0.0684 2.3265 +-0.1000 0.1043 2.2747 +-0.1302 0.1418 2.2228 +-0.1584 0.1809 2.1709 +-0.1846 0.2213 2.1191 +-0.2086 0.2631 2.0672 +-0.2304 0.3060 2.0154 +-0.2500 0.3500 1.9635 +primID: 5 +startangle_c: 6 +endpose_c: 0 0 7 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0000 0.0000 2.3998 +0.0000 0.0000 2.4435 +0.0000 0.0000 2.4871 +0.0000 0.0000 2.5307 +0.0000 0.0000 2.5744 +0.0000 0.0000 2.6180 +0.0000 0.0000 2.6616 +0.0000 0.0000 2.7053 +0.0000 0.0000 2.7489 +primID: 6 +startangle_c: 6 +endpose_c: 0 0 5 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0000 0.0000 2.3126 +0.0000 0.0000 2.2689 +0.0000 0.0000 2.2253 +0.0000 0.0000 2.1817 +0.0000 0.0000 2.1380 +0.0000 0.0000 2.0944 +0.0000 0.0000 2.0508 +0.0000 0.0000 2.0071 +0.0000 0.0000 1.9635 +primID: 0 +startangle_c: 7 +endpose_c: -2 1 7 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0022 0.0011 2.7489 +-0.0044 0.0022 2.7489 +-0.0067 0.0033 2.7489 +-0.0089 0.0044 2.7489 +-0.0111 0.0056 2.7489 +-0.0133 0.0067 2.7489 +-0.0156 0.0078 2.7489 +-0.0178 0.0089 2.7489 +-0.0200 0.0100 2.7489 +primID: 1 +startangle_c: 7 +endpose_c: -20 10 7 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0222 0.0111 2.7489 +-0.0444 0.0222 2.7489 +-0.0667 0.0333 2.7489 +-0.0889 0.0444 2.7489 +-0.1111 0.0556 2.7489 +-0.1333 0.0667 2.7489 +-0.1556 0.0778 2.7489 +-0.1778 0.0889 2.7489 +-0.2000 0.1000 2.7489 +primID: 2 +startangle_c: 7 +endpose_c: 2 -1 7 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0022 -0.0011 2.7489 +0.0044 -0.0022 2.7489 +0.0067 -0.0033 2.7489 +0.0089 -0.0044 2.7489 +0.0111 -0.0056 2.7489 +0.0133 -0.0067 2.7489 +0.0156 -0.0078 2.7489 +0.0178 -0.0089 2.7489 +0.0200 -0.0100 2.7489 +primID: 3 +startangle_c: 7 +endpose_c: -25 20 6 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0298 0.0184 2.7186 +-0.0592 0.0379 2.6883 +-0.0881 0.0583 2.6580 +-0.1165 0.0796 2.6277 +-0.1444 0.1019 2.5974 +-0.1717 0.1251 2.5671 +-0.1984 0.1492 2.5368 +-0.2245 0.1742 2.5065 +-0.2500 0.2000 2.4762 +primID: 4 +startangle_c: 7 +endpose_c: -35 10 8 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0377 0.0156 2.7489 +-0.0754 0.0312 2.7489 +-0.1131 0.0468 2.7489 +-0.1508 0.0623 2.7680 +-0.1893 0.0758 2.8427 +-0.2287 0.0863 2.9174 +-0.2687 0.0939 2.9921 +-0.3092 0.0985 3.0669 +-0.3500 0.1000 3.1416 +primID: 5 +startangle_c: 7 +endpose_c: 0 0 6 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0000 0.0000 2.7053 +0.0000 0.0000 2.6616 +0.0000 0.0000 2.6180 +0.0000 0.0000 2.5744 +0.0000 0.0000 2.5307 +0.0000 0.0000 2.4871 +0.0000 0.0000 2.4435 +0.0000 0.0000 2.3998 +0.0000 0.0000 2.3562 +primID: 6 +startangle_c: 7 +endpose_c: 0 0 8 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0000 0.0000 2.7925 +0.0000 0.0000 2.8362 +0.0000 0.0000 2.8798 +0.0000 0.0000 2.9234 +0.0000 0.0000 2.9671 +0.0000 0.0000 3.0107 +0.0000 0.0000 3.0543 +0.0000 0.0000 3.0980 +0.0000 0.0000 3.1416 +primID: 0 +startangle_c: 8 +endpose_c: -1 0 8 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0011 0.0000 3.1416 +-0.0022 0.0000 3.1416 +-0.0033 0.0000 3.1416 +-0.0044 0.0000 3.1416 +-0.0056 0.0000 3.1416 +-0.0067 0.0000 3.1416 +-0.0078 0.0000 3.1416 +-0.0089 0.0000 3.1416 +-0.0100 0.0000 3.1416 +primID: 1 +startangle_c: 8 +endpose_c: -20 0 8 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0222 0.0000 3.1416 +-0.0444 0.0000 3.1416 +-0.0667 0.0000 3.1416 +-0.0889 0.0000 3.1416 +-0.1111 0.0000 3.1416 +-0.1333 0.0000 3.1416 +-0.1556 0.0000 3.1416 +-0.1778 0.0000 3.1416 +-0.2000 0.0000 3.1416 +primID: 2 +startangle_c: 8 +endpose_c: 1 0 8 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0011 0.0000 3.1416 +0.0022 0.0000 3.1416 +0.0033 0.0000 3.1416 +0.0044 0.0000 3.1416 +0.0056 0.0000 3.1416 +0.0067 0.0000 3.1416 +0.0078 0.0000 3.1416 +0.0089 0.0000 3.1416 +0.0100 0.0000 3.1416 +primID: 3 +startangle_c: 8 +endpose_c: -40 -5 9 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0452 0.0000 3.1416 +-0.0904 0.0000 3.1416 +-0.1355 0.0000 3.1416 +-0.1807 -0.0008 3.1904 +-0.2257 -0.0045 3.2592 +-0.2703 -0.0114 3.3280 +-0.3144 -0.0213 3.3967 +-0.3577 -0.0342 3.4655 +-0.4000 -0.0500 3.5343 +primID: 4 +startangle_c: 8 +endpose_c: -40 5 7 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0452 0.0000 3.1416 +-0.0904 0.0000 3.1416 +-0.1355 0.0000 3.1416 +-0.1807 0.0008 3.0928 +-0.2257 0.0045 3.0240 +-0.2703 0.0114 2.9552 +-0.3144 0.0213 2.8864 +-0.3577 0.0342 2.8177 +-0.4000 0.0500 2.7489 +primID: 5 +startangle_c: 8 +endpose_c: 0 0 9 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0000 0.0000 3.1852 +0.0000 0.0000 3.2289 +0.0000 0.0000 3.2725 +0.0000 0.0000 3.3161 +0.0000 0.0000 3.3598 +0.0000 0.0000 3.4034 +0.0000 0.0000 3.4470 +0.0000 0.0000 3.4907 +0.0000 0.0000 3.5343 +primID: 6 +startangle_c: 8 +endpose_c: 0 0 7 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0000 0.0000 3.0980 +0.0000 0.0000 3.0543 +0.0000 0.0000 3.0107 +0.0000 0.0000 2.9671 +0.0000 0.0000 2.9234 +0.0000 0.0000 2.8798 +0.0000 0.0000 2.8362 +0.0000 0.0000 2.7925 +0.0000 0.0000 2.7489 +primID: 0 +startangle_c: 9 +endpose_c: -2 -1 9 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0022 -0.0011 3.5343 +-0.0044 -0.0022 3.5343 +-0.0067 -0.0033 3.5343 +-0.0089 -0.0044 3.5343 +-0.0111 -0.0056 3.5343 +-0.0133 -0.0067 3.5343 +-0.0156 -0.0078 3.5343 +-0.0178 -0.0089 3.5343 +-0.0200 -0.0100 3.5343 +primID: 1 +startangle_c: 9 +endpose_c: -20 -10 9 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0222 -0.0111 3.5343 +-0.0444 -0.0222 3.5343 +-0.0667 -0.0333 3.5343 +-0.0889 -0.0444 3.5343 +-0.1111 -0.0556 3.5343 +-0.1333 -0.0667 3.5343 +-0.1556 -0.0778 3.5343 +-0.1778 -0.0889 3.5343 +-0.2000 -0.1000 3.5343 +primID: 2 +startangle_c: 9 +endpose_c: 2 1 9 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0022 0.0011 3.5343 +0.0044 0.0022 3.5343 +0.0067 0.0033 3.5343 +0.0089 0.0044 3.5343 +0.0111 0.0056 3.5343 +0.0133 0.0067 3.5343 +0.0156 0.0078 3.5343 +0.0178 0.0089 3.5343 +0.0200 0.0100 3.5343 +primID: 3 +startangle_c: 9 +endpose_c: -25 -20 10 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0298 -0.0184 3.5646 +-0.0592 -0.0379 3.5949 +-0.0881 -0.0583 3.6252 +-0.1165 -0.0796 3.6555 +-0.1444 -0.1019 3.6858 +-0.1717 -0.1251 3.7161 +-0.1984 -0.1492 3.7464 +-0.2245 -0.1742 3.7767 +-0.2500 -0.2000 3.8070 +primID: 4 +startangle_c: 9 +endpose_c: -35 -10 8 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0377 -0.0156 3.5343 +-0.0754 -0.0312 3.5343 +-0.1131 -0.0468 3.5343 +-0.1508 -0.0623 3.5152 +-0.1893 -0.0758 3.4405 +-0.2287 -0.0863 3.3658 +-0.2687 -0.0939 3.2910 +-0.3092 -0.0985 3.2163 +-0.3500 -0.1000 3.1416 +primID: 5 +startangle_c: 9 +endpose_c: 0 0 10 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0000 0.0000 3.5779 +0.0000 0.0000 3.6216 +0.0000 0.0000 3.6652 +0.0000 0.0000 3.7088 +0.0000 0.0000 3.7525 +0.0000 0.0000 3.7961 +0.0000 0.0000 3.8397 +0.0000 0.0000 3.8834 +0.0000 0.0000 3.9270 +primID: 6 +startangle_c: 9 +endpose_c: 0 0 8 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0000 0.0000 3.4907 +0.0000 0.0000 3.4470 +0.0000 0.0000 3.4034 +0.0000 0.0000 3.3598 +0.0000 0.0000 3.3161 +0.0000 0.0000 3.2725 +0.0000 0.0000 3.2289 +0.0000 0.0000 3.1852 +0.0000 0.0000 3.1416 +primID: 0 +startangle_c: 10 +endpose_c: -1 -1 10 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0011 -0.0011 3.9270 +-0.0022 -0.0022 3.9270 +-0.0033 -0.0033 3.9270 +-0.0044 -0.0044 3.9270 +-0.0056 -0.0056 3.9270 +-0.0067 -0.0067 3.9270 +-0.0078 -0.0078 3.9270 +-0.0089 -0.0089 3.9270 +-0.0100 -0.0100 3.9270 +primID: 1 +startangle_c: 10 +endpose_c: -10 -10 10 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0111 -0.0111 3.9270 +-0.0222 -0.0222 3.9270 +-0.0333 -0.0333 3.9270 +-0.0444 -0.0444 3.9270 +-0.0556 -0.0556 3.9270 +-0.0667 -0.0667 3.9270 +-0.0778 -0.0778 3.9270 +-0.0889 -0.0889 3.9270 +-0.1000 -0.1000 3.9270 +primID: 2 +startangle_c: 10 +endpose_c: 1 1 10 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0011 0.0011 3.9270 +0.0022 0.0022 3.9270 +0.0033 0.0033 3.9270 +0.0044 0.0044 3.9270 +0.0056 0.0056 3.9270 +0.0067 0.0067 3.9270 +0.0078 0.0078 3.9270 +0.0089 0.0089 3.9270 +0.0100 0.0100 3.9270 +primID: 3 +startangle_c: 10 +endpose_c: -25 -35 11 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0341 -0.0341 3.9270 +-0.0678 -0.0684 3.9567 +-0.1000 -0.1043 4.0085 +-0.1302 -0.1418 4.0604 +-0.1584 -0.1809 4.1123 +-0.1846 -0.2213 4.1641 +-0.2086 -0.2631 4.2160 +-0.2304 -0.3060 4.2678 +-0.2500 -0.3500 4.3197 +primID: 4 +startangle_c: 10 +endpose_c: -35 -25 9 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0341 -0.0341 3.9270 +-0.0684 -0.0678 3.8973 +-0.1043 -0.1000 3.8455 +-0.1418 -0.1302 3.7936 +-0.1809 -0.1584 3.7417 +-0.2213 -0.1846 3.6899 +-0.2631 -0.2086 3.6380 +-0.3060 -0.2304 3.5862 +-0.3500 -0.2500 3.5343 +primID: 5 +startangle_c: 10 +endpose_c: 0 0 11 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.9706 +0.0000 0.0000 4.0143 +0.0000 0.0000 4.0579 +0.0000 0.0000 4.1015 +0.0000 0.0000 4.1452 +0.0000 0.0000 4.1888 +0.0000 0.0000 4.2324 +0.0000 0.0000 4.2761 +0.0000 0.0000 4.3197 +primID: 6 +startangle_c: 10 +endpose_c: 0 0 9 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.8834 +0.0000 0.0000 3.8397 +0.0000 0.0000 3.7961 +0.0000 0.0000 3.7525 +0.0000 0.0000 3.7088 +0.0000 0.0000 3.6652 +0.0000 0.0000 3.6216 +0.0000 0.0000 3.5779 +0.0000 0.0000 3.5343 +primID: 0 +startangle_c: 11 +endpose_c: -1 -2 11 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0011 -0.0022 4.3197 +-0.0022 -0.0044 4.3197 +-0.0033 -0.0067 4.3197 +-0.0044 -0.0089 4.3197 +-0.0056 -0.0111 4.3197 +-0.0067 -0.0133 4.3197 +-0.0078 -0.0156 4.3197 +-0.0089 -0.0178 4.3197 +-0.0100 -0.0200 4.3197 +primID: 1 +startangle_c: 11 +endpose_c: -10 -20 11 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0111 -0.0222 4.3197 +-0.0222 -0.0444 4.3197 +-0.0333 -0.0667 4.3197 +-0.0444 -0.0889 4.3197 +-0.0556 -0.1111 4.3197 +-0.0667 -0.1333 4.3197 +-0.0778 -0.1556 4.3197 +-0.0889 -0.1778 4.3197 +-0.1000 -0.2000 4.3197 +primID: 2 +startangle_c: 11 +endpose_c: 1 2 11 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0011 0.0022 4.3197 +0.0022 0.0044 4.3197 +0.0033 0.0067 4.3197 +0.0044 0.0089 4.3197 +0.0056 0.0111 4.3197 +0.0067 0.0133 4.3197 +0.0078 0.0156 4.3197 +0.0089 0.0178 4.3197 +0.0100 0.0200 4.3197 +primID: 3 +startangle_c: 11 +endpose_c: -20 -25 10 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0184 -0.0298 4.2894 +-0.0379 -0.0592 4.2591 +-0.0583 -0.0881 4.2288 +-0.0796 -0.1165 4.1985 +-0.1019 -0.1444 4.1682 +-0.1251 -0.1717 4.1379 +-0.1492 -0.1984 4.1076 +-0.1742 -0.2245 4.0773 +-0.2000 -0.2500 4.0470 +primID: 4 +startangle_c: 11 +endpose_c: -10 -35 12 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0156 -0.0377 4.3197 +-0.0312 -0.0754 4.3197 +-0.0468 -0.1131 4.3197 +-0.0623 -0.1508 4.3388 +-0.0758 -0.1893 4.4135 +-0.0863 -0.2287 4.4882 +-0.0939 -0.2687 4.5629 +-0.0985 -0.3092 4.6377 +-0.1000 -0.3500 4.7124 +primID: 5 +startangle_c: 11 +endpose_c: 0 0 10 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0000 0.0000 4.2761 +0.0000 0.0000 4.2324 +0.0000 0.0000 4.1888 +0.0000 0.0000 4.1452 +0.0000 0.0000 4.1015 +0.0000 0.0000 4.0579 +0.0000 0.0000 4.0143 +0.0000 0.0000 3.9706 +0.0000 0.0000 3.9270 +primID: 6 +startangle_c: 11 +endpose_c: 0 0 12 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0000 0.0000 4.3633 +0.0000 0.0000 4.4070 +0.0000 0.0000 4.4506 +0.0000 0.0000 4.4942 +0.0000 0.0000 4.5379 +0.0000 0.0000 4.5815 +0.0000 0.0000 4.6251 +0.0000 0.0000 4.6688 +0.0000 0.0000 4.7124 +primID: 0 +startangle_c: 12 +endpose_c: 0 -1 12 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0011 4.7124 +0.0000 -0.0022 4.7124 +0.0000 -0.0033 4.7124 +0.0000 -0.0044 4.7124 +0.0000 -0.0056 4.7124 +0.0000 -0.0067 4.7124 +0.0000 -0.0078 4.7124 +0.0000 -0.0089 4.7124 +0.0000 -0.0100 4.7124 +primID: 1 +startangle_c: 12 +endpose_c: 0 -20 12 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0222 4.7124 +0.0000 -0.0444 4.7124 +0.0000 -0.0667 4.7124 +0.0000 -0.0889 4.7124 +0.0000 -0.1111 4.7124 +0.0000 -0.1333 4.7124 +0.0000 -0.1556 4.7124 +0.0000 -0.1778 4.7124 +0.0000 -0.2000 4.7124 +primID: 2 +startangle_c: 12 +endpose_c: 0 1 12 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0011 4.7124 +0.0000 0.0022 4.7124 +0.0000 0.0033 4.7124 +0.0000 0.0044 4.7124 +0.0000 0.0056 4.7124 +0.0000 0.0067 4.7124 +0.0000 0.0078 4.7124 +0.0000 0.0089 4.7124 +0.0000 0.0100 4.7124 +primID: 3 +startangle_c: 12 +endpose_c: 5 -40 13 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0452 4.7124 +0.0000 -0.0904 4.7124 +0.0000 -0.1355 4.7124 +0.0008 -0.1807 4.7612 +0.0045 -0.2257 4.8300 +0.0114 -0.2703 4.8988 +0.0213 -0.3144 4.9675 +0.0342 -0.3577 5.0363 +0.0500 -0.4000 5.1051 +primID: 4 +startangle_c: 12 +endpose_c: -5 -40 11 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.7124 +-0.0000 -0.0452 4.7124 +-0.0000 -0.0904 4.7124 +-0.0000 -0.1355 4.7124 +-0.0008 -0.1807 4.6636 +-0.0045 -0.2257 4.5948 +-0.0114 -0.2703 4.5260 +-0.0213 -0.3144 4.4572 +-0.0342 -0.3577 4.3885 +-0.0500 -0.4000 4.3197 +primID: 5 +startangle_c: 12 +endpose_c: 0 0 13 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0000 4.7560 +0.0000 0.0000 4.7997 +0.0000 0.0000 4.8433 +0.0000 0.0000 4.8869 +0.0000 0.0000 4.9306 +0.0000 0.0000 4.9742 +0.0000 0.0000 5.0178 +0.0000 0.0000 5.0615 +0.0000 0.0000 5.1051 +primID: 6 +startangle_c: 12 +endpose_c: 0 0 11 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0000 4.6688 +0.0000 0.0000 4.6251 +0.0000 0.0000 4.5815 +0.0000 0.0000 4.5379 +0.0000 0.0000 4.4942 +0.0000 0.0000 4.4506 +0.0000 0.0000 4.4070 +0.0000 0.0000 4.3633 +0.0000 0.0000 4.3197 +primID: 0 +startangle_c: 13 +endpose_c: 1 -2 13 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0011 -0.0022 5.1051 +0.0022 -0.0044 5.1051 +0.0033 -0.0067 5.1051 +0.0044 -0.0089 5.1051 +0.0056 -0.0111 5.1051 +0.0067 -0.0133 5.1051 +0.0078 -0.0156 5.1051 +0.0089 -0.0178 5.1051 +0.0100 -0.0200 5.1051 +primID: 1 +startangle_c: 13 +endpose_c: 10 -20 13 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0111 -0.0222 5.1051 +0.0222 -0.0444 5.1051 +0.0333 -0.0667 5.1051 +0.0444 -0.0889 5.1051 +0.0556 -0.1111 5.1051 +0.0667 -0.1333 5.1051 +0.0778 -0.1556 5.1051 +0.0889 -0.1778 5.1051 +0.1000 -0.2000 5.1051 +primID: 2 +startangle_c: 13 +endpose_c: -1 2 13 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.1051 +-0.0011 0.0022 5.1051 +-0.0022 0.0044 5.1051 +-0.0033 0.0067 5.1051 +-0.0044 0.0089 5.1051 +-0.0056 0.0111 5.1051 +-0.0067 0.0133 5.1051 +-0.0078 0.0156 5.1051 +-0.0089 0.0178 5.1051 +-0.0100 0.0200 5.1051 +primID: 3 +startangle_c: 13 +endpose_c: 20 -25 14 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0184 -0.0298 5.1354 +0.0379 -0.0592 5.1657 +0.0583 -0.0881 5.1960 +0.0796 -0.1165 5.2263 +0.1019 -0.1444 5.2566 +0.1251 -0.1717 5.2869 +0.1492 -0.1984 5.3172 +0.1742 -0.2245 5.3475 +0.2000 -0.2500 5.3778 +primID: 4 +startangle_c: 13 +endpose_c: 10 -35 12 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0156 -0.0377 5.1051 +0.0312 -0.0754 5.1051 +0.0468 -0.1131 5.1051 +0.0623 -0.1508 5.0860 +0.0758 -0.1893 5.0113 +0.0863 -0.2287 4.9366 +0.0939 -0.2687 4.8618 +0.0985 -0.3092 4.7871 +0.1000 -0.3500 4.7124 +primID: 5 +startangle_c: 13 +endpose_c: 0 0 14 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0000 0.0000 5.1487 +0.0000 0.0000 5.1924 +0.0000 0.0000 5.2360 +0.0000 0.0000 5.2796 +0.0000 0.0000 5.3233 +0.0000 0.0000 5.3669 +0.0000 0.0000 5.4105 +0.0000 0.0000 5.4542 +0.0000 0.0000 5.4978 +primID: 6 +startangle_c: 13 +endpose_c: 0 0 12 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0000 0.0000 5.0615 +0.0000 0.0000 5.0178 +0.0000 0.0000 4.9742 +0.0000 0.0000 4.9306 +0.0000 0.0000 4.8869 +0.0000 0.0000 4.8433 +0.0000 0.0000 4.7997 +0.0000 0.0000 4.7560 +0.0000 0.0000 4.7124 +primID: 0 +startangle_c: 14 +endpose_c: 1 -1 14 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0011 -0.0011 5.4978 +0.0022 -0.0022 5.4978 +0.0033 -0.0033 5.4978 +0.0044 -0.0044 5.4978 +0.0056 -0.0056 5.4978 +0.0067 -0.0067 5.4978 +0.0078 -0.0078 5.4978 +0.0089 -0.0089 5.4978 +0.0100 -0.0100 5.4978 +primID: 1 +startangle_c: 14 +endpose_c: 10 -10 14 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0111 -0.0111 5.4978 +0.0222 -0.0222 5.4978 +0.0333 -0.0333 5.4978 +0.0444 -0.0444 5.4978 +0.0556 -0.0556 5.4978 +0.0667 -0.0667 5.4978 +0.0778 -0.0778 5.4978 +0.0889 -0.0889 5.4978 +0.1000 -0.1000 5.4978 +primID: 2 +startangle_c: 14 +endpose_c: -1 1 14 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.4978 +-0.0011 0.0011 5.4978 +-0.0022 0.0022 5.4978 +-0.0033 0.0033 5.4978 +-0.0044 0.0044 5.4978 +-0.0056 0.0056 5.4978 +-0.0067 0.0067 5.4978 +-0.0078 0.0078 5.4978 +-0.0089 0.0089 5.4978 +-0.0100 0.0100 5.4978 +primID: 3 +startangle_c: 14 +endpose_c: 35 -25 15 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0341 -0.0341 5.4978 +0.0684 -0.0678 5.5275 +0.1043 -0.1000 5.5793 +0.1418 -0.1302 5.6312 +0.1809 -0.1584 5.6830 +0.2213 -0.1846 5.7349 +0.2631 -0.2086 5.7868 +0.3060 -0.2304 5.8386 +0.3500 -0.2500 5.8905 +primID: 4 +startangle_c: 14 +endpose_c: 25 -35 13 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0341 -0.0341 5.4978 +0.0678 -0.0684 5.4681 +0.1000 -0.1043 5.4162 +0.1302 -0.1418 5.3644 +0.1584 -0.1809 5.3125 +0.1846 -0.2213 5.2607 +0.2086 -0.2631 5.2088 +0.2304 -0.3060 5.1569 +0.2500 -0.3500 5.1051 +primID: 5 +startangle_c: 14 +endpose_c: 0 0 15 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0000 0.0000 5.5414 +0.0000 0.0000 5.5851 +0.0000 0.0000 5.6287 +0.0000 0.0000 5.6723 +0.0000 0.0000 5.7160 +0.0000 0.0000 5.7596 +0.0000 0.0000 5.8032 +0.0000 0.0000 5.8469 +0.0000 0.0000 5.8905 +primID: 6 +startangle_c: 14 +endpose_c: 0 0 13 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0000 0.0000 5.4542 +0.0000 0.0000 5.4105 +0.0000 0.0000 5.3669 +0.0000 0.0000 5.3233 +0.0000 0.0000 5.2796 +0.0000 0.0000 5.2360 +0.0000 0.0000 5.1924 +0.0000 0.0000 5.1487 +0.0000 0.0000 5.1051 +primID: 0 +startangle_c: 15 +endpose_c: 2 -1 15 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0022 -0.0011 5.8905 +0.0044 -0.0022 5.8905 +0.0067 -0.0033 5.8905 +0.0089 -0.0044 5.8905 +0.0111 -0.0056 5.8905 +0.0133 -0.0067 5.8905 +0.0156 -0.0078 5.8905 +0.0178 -0.0089 5.8905 +0.0200 -0.0100 5.8905 +primID: 1 +startangle_c: 15 +endpose_c: 20 -10 15 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0222 -0.0111 5.8905 +0.0444 -0.0222 5.8905 +0.0667 -0.0333 5.8905 +0.0889 -0.0444 5.8905 +0.1111 -0.0556 5.8905 +0.1333 -0.0667 5.8905 +0.1556 -0.0778 5.8905 +0.1778 -0.0889 5.8905 +0.2000 -0.1000 5.8905 +primID: 2 +startangle_c: 15 +endpose_c: -2 1 15 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.8905 +-0.0022 0.0011 5.8905 +-0.0044 0.0022 5.8905 +-0.0067 0.0033 5.8905 +-0.0089 0.0044 5.8905 +-0.0111 0.0056 5.8905 +-0.0133 0.0067 5.8905 +-0.0156 0.0078 5.8905 +-0.0178 0.0089 5.8905 +-0.0200 0.0100 5.8905 +primID: 3 +startangle_c: 15 +endpose_c: 25 -20 14 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0298 -0.0184 5.8602 +0.0592 -0.0379 5.8299 +0.0881 -0.0583 5.7996 +0.1165 -0.0796 5.7693 +0.1444 -0.1019 5.7390 +0.1717 -0.1251 5.7087 +0.1984 -0.1492 5.6784 +0.2245 -0.1742 5.6481 +0.2500 -0.2000 5.6178 +primID: 4 +startangle_c: 15 +endpose_c: 35 -10 0 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0377 -0.0156 5.8905 +0.0754 -0.0312 5.8905 +0.1131 -0.0468 5.8905 +0.1508 -0.0623 5.9096 +0.1893 -0.0758 5.9843 +0.2287 -0.0863 6.0590 +0.2687 -0.0939 6.1337 +0.3092 -0.0985 6.2085 +0.3500 -0.1000 6.2832 +primID: 5 +startangle_c: 15 +endpose_c: 0 0 14 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0000 0.0000 5.8469 +0.0000 0.0000 5.8032 +0.0000 0.0000 5.7596 +0.0000 0.0000 5.7160 +0.0000 0.0000 5.6723 +0.0000 0.0000 5.6287 +0.0000 0.0000 5.5851 +0.0000 0.0000 5.5414 +0.0000 0.0000 5.4978 +primID: 6 +startangle_c: 15 +endpose_c: 0 0 0 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0000 0.0000 5.2360 +0.0000 0.0000 4.5815 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.2725 +0.0000 0.0000 2.6180 +0.0000 0.0000 1.9635 +0.0000 0.0000 1.3090 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.0000 diff --git a/navigations/sbpl_lattice_planner/matlab/mprim/unicycle_highcost_2_5cm.mprim b/navigations/sbpl_lattice_planner/matlab/mprim/unicycle_highcost_2_5cm.mprim new file mode 100755 index 0000000..6bf962e --- /dev/null +++ b/navigations/sbpl_lattice_planner/matlab/mprim/unicycle_highcost_2_5cm.mprim @@ -0,0 +1,1683 @@ +resolution_m: 0.025000 +numberofangles: 16 +totalnumberofprimitives: 112 +primID: 0 +startangle_c: 0 +endpose_c: 1 0 0 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0028 0.0000 0.0000 +0.0056 0.0000 0.0000 +0.0083 0.0000 0.0000 +0.0111 0.0000 0.0000 +0.0139 0.0000 0.0000 +0.0167 0.0000 0.0000 +0.0194 0.0000 0.0000 +0.0222 0.0000 0.0000 +0.0250 0.0000 0.0000 +primID: 1 +startangle_c: 0 +endpose_c: 12 0 0 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0333 0.0000 0.0000 +0.0667 0.0000 0.0000 +0.1000 0.0000 0.0000 +0.1333 0.0000 0.0000 +0.1667 0.0000 0.0000 +0.2000 0.0000 0.0000 +0.2333 0.0000 0.0000 +0.2667 0.0000 0.0000 +0.3000 0.0000 0.0000 +primID: 2 +startangle_c: 0 +endpose_c: -1 0 0 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.0000 +-0.0028 0.0000 0.0000 +-0.0056 0.0000 0.0000 +-0.0083 0.0000 0.0000 +-0.0111 0.0000 0.0000 +-0.0139 0.0000 0.0000 +-0.0167 0.0000 0.0000 +-0.0194 0.0000 0.0000 +-0.0222 0.0000 0.0000 +-0.0250 0.0000 0.0000 +primID: 3 +startangle_c: 0 +endpose_c: 16 2 1 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0452 -0.0000 0.0000 +0.0904 -0.0000 0.0000 +0.1355 -0.0000 0.0000 +0.1807 0.0008 0.0488 +0.2257 0.0045 0.1176 +0.2703 0.0114 0.1864 +0.3144 0.0213 0.2551 +0.3577 0.0342 0.3239 +0.4000 0.0500 0.3927 +primID: 4 +startangle_c: 0 +endpose_c: 16 -2 -1 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0452 0.0000 0.0000 +0.0904 0.0000 0.0000 +0.1355 0.0000 0.0000 +0.1807 -0.0008 -0.0488 +0.2257 -0.0045 -0.1176 +0.2703 -0.0114 -0.1864 +0.3144 -0.0213 -0.2551 +0.3577 -0.0342 -0.3239 +0.4000 -0.0500 -0.3927 +primID: 5 +startangle_c: 0 +endpose_c: 0 0 1 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0000 0.0000 0.0436 +0.0000 0.0000 0.0873 +0.0000 0.0000 0.1309 +0.0000 0.0000 0.1745 +0.0000 0.0000 0.2182 +0.0000 0.0000 0.2618 +0.0000 0.0000 0.3054 +0.0000 0.0000 0.3491 +0.0000 0.0000 0.3927 +primID: 6 +startangle_c: 0 +endpose_c: 0 0 -1 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0000 0.0000 -0.0436 +0.0000 0.0000 -0.0873 +0.0000 0.0000 -0.1309 +0.0000 0.0000 -0.1745 +0.0000 0.0000 -0.2182 +0.0000 0.0000 -0.2618 +0.0000 0.0000 -0.3054 +0.0000 0.0000 -0.3491 +0.0000 0.0000 -0.3927 +primID: 0 +startangle_c: 1 +endpose_c: 2 1 1 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0056 0.0028 0.3927 +0.0111 0.0056 0.3927 +0.0167 0.0083 0.3927 +0.0222 0.0111 0.3927 +0.0278 0.0139 0.3927 +0.0333 0.0167 0.3927 +0.0389 0.0194 0.3927 +0.0444 0.0222 0.3927 +0.0500 0.0250 0.3927 +primID: 1 +startangle_c: 1 +endpose_c: 12 6 1 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0333 0.0167 0.3927 +0.0667 0.0333 0.3927 +0.1000 0.0500 0.3927 +0.1333 0.0667 0.3927 +0.1667 0.0833 0.3927 +0.2000 0.1000 0.3927 +0.2333 0.1167 0.3927 +0.2667 0.1333 0.3927 +0.3000 0.1500 0.3927 +primID: 2 +startangle_c: 1 +endpose_c: -2 -1 1 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.3927 +-0.0056 -0.0028 0.3927 +-0.0111 -0.0056 0.3927 +-0.0167 -0.0083 0.3927 +-0.0222 -0.0111 0.3927 +-0.0278 -0.0139 0.3927 +-0.0333 -0.0167 0.3927 +-0.0389 -0.0194 0.3927 +-0.0444 -0.0222 0.3927 +-0.0500 -0.0250 0.3927 +primID: 3 +startangle_c: 1 +endpose_c: 10 8 2 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0298 0.0184 0.4230 +0.0592 0.0379 0.4533 +0.0881 0.0583 0.4836 +0.1165 0.0796 0.5139 +0.1444 0.1019 0.5442 +0.1717 0.1251 0.5745 +0.1984 0.1492 0.6048 +0.2245 0.1742 0.6351 +0.2500 0.2000 0.6654 +primID: 4 +startangle_c: 1 +endpose_c: 14 4 0 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0377 0.0156 0.3927 +0.0754 0.0312 0.3927 +0.1131 0.0468 0.3927 +0.1508 0.0623 0.3736 +0.1893 0.0758 0.2989 +0.2287 0.0863 0.2242 +0.2687 0.0939 0.1494 +0.3092 0.0985 0.0747 +0.3500 0.1000 -0.0000 +primID: 5 +startangle_c: 1 +endpose_c: 0 0 2 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0000 0.0000 0.4363 +0.0000 0.0000 0.4800 +0.0000 0.0000 0.5236 +0.0000 0.0000 0.5672 +0.0000 0.0000 0.6109 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.6981 +0.0000 0.0000 0.7418 +0.0000 0.0000 0.7854 +primID: 6 +startangle_c: 1 +endpose_c: 0 0 0 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0000 0.0000 0.3491 +0.0000 0.0000 0.3054 +0.0000 0.0000 0.2618 +0.0000 0.0000 0.2182 +0.0000 0.0000 0.1745 +0.0000 0.0000 0.1309 +0.0000 0.0000 0.0873 +0.0000 0.0000 0.0436 +0.0000 0.0000 0.0000 +primID: 0 +startangle_c: 2 +endpose_c: 1 1 2 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0028 0.0028 0.7854 +0.0056 0.0056 0.7854 +0.0083 0.0083 0.7854 +0.0111 0.0111 0.7854 +0.0139 0.0139 0.7854 +0.0167 0.0167 0.7854 +0.0194 0.0194 0.7854 +0.0222 0.0222 0.7854 +0.0250 0.0250 0.7854 +primID: 1 +startangle_c: 2 +endpose_c: 12 12 2 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0333 0.0333 0.7854 +0.0667 0.0667 0.7854 +0.1000 0.1000 0.7854 +0.1333 0.1333 0.7854 +0.1667 0.1667 0.7854 +0.2000 0.2000 0.7854 +0.2333 0.2333 0.7854 +0.2667 0.2667 0.7854 +0.3000 0.3000 0.7854 +primID: 2 +startangle_c: 2 +endpose_c: -1 -1 2 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.7854 +-0.0028 -0.0028 0.7854 +-0.0056 -0.0056 0.7854 +-0.0083 -0.0083 0.7854 +-0.0111 -0.0111 0.7854 +-0.0139 -0.0139 0.7854 +-0.0167 -0.0167 0.7854 +-0.0194 -0.0194 0.7854 +-0.0222 -0.0222 0.7854 +-0.0250 -0.0250 0.7854 +primID: 3 +startangle_c: 2 +endpose_c: 10 14 3 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0341 0.0341 0.7854 +0.0678 0.0684 0.8151 +0.1000 0.1043 0.8669 +0.1302 0.1418 0.9188 +0.1584 0.1809 0.9707 +0.1846 0.2213 1.0225 +0.2086 0.2631 1.0744 +0.2304 0.3060 1.1262 +0.2500 0.3500 1.1781 +primID: 4 +startangle_c: 2 +endpose_c: 14 10 1 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0341 0.0341 0.7854 +0.0684 0.0678 0.7557 +0.1043 0.1000 0.7039 +0.1418 0.1302 0.6520 +0.1809 0.1584 0.6001 +0.2213 0.1846 0.5483 +0.2631 0.2086 0.4964 +0.3060 0.2304 0.4446 +0.3500 0.2500 0.3927 +primID: 5 +startangle_c: 2 +endpose_c: 0 0 3 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0000 0.0000 0.8290 +0.0000 0.0000 0.8727 +0.0000 0.0000 0.9163 +0.0000 0.0000 0.9599 +0.0000 0.0000 1.0036 +0.0000 0.0000 1.0472 +0.0000 0.0000 1.0908 +0.0000 0.0000 1.1345 +0.0000 0.0000 1.1781 +primID: 6 +startangle_c: 2 +endpose_c: 0 0 1 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0000 0.0000 0.7418 +0.0000 0.0000 0.6981 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.6109 +0.0000 0.0000 0.5672 +0.0000 0.0000 0.5236 +0.0000 0.0000 0.4800 +0.0000 0.0000 0.4363 +0.0000 0.0000 0.3927 +primID: 0 +startangle_c: 3 +endpose_c: 1 2 3 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0028 0.0056 1.1781 +0.0056 0.0111 1.1781 +0.0083 0.0167 1.1781 +0.0111 0.0222 1.1781 +0.0139 0.0278 1.1781 +0.0167 0.0333 1.1781 +0.0194 0.0389 1.1781 +0.0222 0.0444 1.1781 +0.0250 0.0500 1.1781 +primID: 1 +startangle_c: 3 +endpose_c: 6 12 3 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0167 0.0333 1.1781 +0.0333 0.0667 1.1781 +0.0500 0.1000 1.1781 +0.0667 0.1333 1.1781 +0.0833 0.1667 1.1781 +0.1000 0.2000 1.1781 +0.1167 0.2333 1.1781 +0.1333 0.2667 1.1781 +0.1500 0.3000 1.1781 +primID: 2 +startangle_c: 3 +endpose_c: -1 -2 3 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.1781 +-0.0028 -0.0056 1.1781 +-0.0056 -0.0111 1.1781 +-0.0083 -0.0167 1.1781 +-0.0111 -0.0222 1.1781 +-0.0139 -0.0278 1.1781 +-0.0167 -0.0333 1.1781 +-0.0194 -0.0389 1.1781 +-0.0222 -0.0444 1.1781 +-0.0250 -0.0500 1.1781 +primID: 3 +startangle_c: 3 +endpose_c: 8 10 2 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0184 0.0298 1.1478 +0.0379 0.0592 1.1175 +0.0583 0.0881 1.0872 +0.0796 0.1165 1.0569 +0.1019 0.1444 1.0266 +0.1251 0.1717 0.9963 +0.1492 0.1984 0.9660 +0.1742 0.2245 0.9357 +0.2000 0.2500 0.9054 +primID: 4 +startangle_c: 3 +endpose_c: 4 14 4 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0156 0.0377 1.1781 +0.0312 0.0754 1.1781 +0.0468 0.1131 1.1781 +0.0623 0.1508 1.1972 +0.0758 0.1893 1.2719 +0.0863 0.2287 1.3466 +0.0939 0.2687 1.4214 +0.0985 0.3092 1.4961 +0.1000 0.3500 1.5708 +primID: 5 +startangle_c: 3 +endpose_c: 0 0 2 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0000 0.0000 1.1345 +0.0000 0.0000 1.0908 +0.0000 0.0000 1.0472 +0.0000 0.0000 1.0036 +0.0000 0.0000 0.9599 +0.0000 0.0000 0.9163 +0.0000 0.0000 0.8727 +0.0000 0.0000 0.8290 +0.0000 0.0000 0.7854 +primID: 6 +startangle_c: 3 +endpose_c: 0 0 4 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0000 0.0000 1.2217 +0.0000 0.0000 1.2654 +0.0000 0.0000 1.3090 +0.0000 0.0000 1.3526 +0.0000 0.0000 1.3963 +0.0000 0.0000 1.4399 +0.0000 0.0000 1.4835 +0.0000 0.0000 1.5272 +0.0000 0.0000 1.5708 +primID: 0 +startangle_c: 4 +endpose_c: 0 1 4 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0028 1.5708 +0.0000 0.0056 1.5708 +0.0000 0.0083 1.5708 +0.0000 0.0111 1.5708 +0.0000 0.0139 1.5708 +0.0000 0.0167 1.5708 +0.0000 0.0194 1.5708 +0.0000 0.0222 1.5708 +0.0000 0.0250 1.5708 +primID: 1 +startangle_c: 4 +endpose_c: 0 12 4 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0333 1.5708 +0.0000 0.0667 1.5708 +0.0000 0.1000 1.5708 +0.0000 0.1333 1.5708 +0.0000 0.1667 1.5708 +0.0000 0.2000 1.5708 +0.0000 0.2333 1.5708 +0.0000 0.2667 1.5708 +0.0000 0.3000 1.5708 +primID: 2 +startangle_c: 4 +endpose_c: 0 -1 4 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 -0.0028 1.5708 +0.0000 -0.0056 1.5708 +0.0000 -0.0083 1.5708 +0.0000 -0.0111 1.5708 +0.0000 -0.0139 1.5708 +0.0000 -0.0167 1.5708 +0.0000 -0.0194 1.5708 +0.0000 -0.0222 1.5708 +0.0000 -0.0250 1.5708 +primID: 3 +startangle_c: 4 +endpose_c: -2 16 5 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0452 1.5708 +0.0000 0.0904 1.5708 +0.0000 0.1355 1.5708 +-0.0008 0.1807 1.6196 +-0.0045 0.2257 1.6884 +-0.0114 0.2703 1.7572 +-0.0213 0.3144 1.8259 +-0.0342 0.3577 1.8947 +-0.0500 0.4000 1.9635 +primID: 4 +startangle_c: 4 +endpose_c: 2 16 3 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0452 1.5708 +0.0000 0.0904 1.5708 +0.0000 0.1355 1.5708 +0.0008 0.1807 1.5220 +0.0045 0.2257 1.4532 +0.0114 0.2703 1.3844 +0.0213 0.3144 1.3156 +0.0342 0.3577 1.2469 +0.0500 0.4000 1.1781 +primID: 5 +startangle_c: 4 +endpose_c: 0 0 5 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0000 1.6144 +0.0000 0.0000 1.6581 +0.0000 0.0000 1.7017 +0.0000 0.0000 1.7453 +0.0000 0.0000 1.7890 +0.0000 0.0000 1.8326 +0.0000 0.0000 1.8762 +0.0000 0.0000 1.9199 +0.0000 0.0000 1.9635 +primID: 6 +startangle_c: 4 +endpose_c: 0 0 3 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0000 1.5272 +0.0000 0.0000 1.4835 +0.0000 0.0000 1.4399 +0.0000 0.0000 1.3963 +0.0000 0.0000 1.3526 +0.0000 0.0000 1.3090 +0.0000 0.0000 1.2654 +0.0000 0.0000 1.2217 +0.0000 0.0000 1.1781 +primID: 0 +startangle_c: 5 +endpose_c: -1 2 5 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0028 0.0056 1.9635 +-0.0056 0.0111 1.9635 +-0.0083 0.0167 1.9635 +-0.0111 0.0222 1.9635 +-0.0139 0.0278 1.9635 +-0.0167 0.0333 1.9635 +-0.0194 0.0389 1.9635 +-0.0222 0.0444 1.9635 +-0.0250 0.0500 1.9635 +primID: 1 +startangle_c: 5 +endpose_c: -6 12 5 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0167 0.0333 1.9635 +-0.0333 0.0667 1.9635 +-0.0500 0.1000 1.9635 +-0.0667 0.1333 1.9635 +-0.0833 0.1667 1.9635 +-0.1000 0.2000 1.9635 +-0.1167 0.2333 1.9635 +-0.1333 0.2667 1.9635 +-0.1500 0.3000 1.9635 +primID: 2 +startangle_c: 5 +endpose_c: 1 -2 5 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0028 -0.0056 1.9635 +0.0056 -0.0111 1.9635 +0.0083 -0.0167 1.9635 +0.0111 -0.0222 1.9635 +0.0139 -0.0278 1.9635 +0.0167 -0.0333 1.9635 +0.0194 -0.0389 1.9635 +0.0222 -0.0444 1.9635 +0.0250 -0.0500 1.9635 +primID: 3 +startangle_c: 5 +endpose_c: -8 10 6 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0184 0.0298 1.9938 +-0.0379 0.0592 2.0241 +-0.0583 0.0881 2.0544 +-0.0796 0.1165 2.0847 +-0.1019 0.1444 2.1150 +-0.1251 0.1717 2.1453 +-0.1492 0.1984 2.1756 +-0.1742 0.2245 2.2059 +-0.2000 0.2500 2.2362 +primID: 4 +startangle_c: 5 +endpose_c: -4 14 4 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0156 0.0377 1.9635 +-0.0312 0.0754 1.9635 +-0.0468 0.1131 1.9635 +-0.0623 0.1508 1.9444 +-0.0758 0.1893 1.8697 +-0.0863 0.2287 1.7950 +-0.0939 0.2687 1.7202 +-0.0985 0.3092 1.6455 +-0.1000 0.3500 1.5708 +primID: 5 +startangle_c: 5 +endpose_c: 0 0 6 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0000 0.0000 2.0071 +0.0000 0.0000 2.0508 +0.0000 0.0000 2.0944 +0.0000 0.0000 2.1380 +0.0000 0.0000 2.1817 +0.0000 0.0000 2.2253 +0.0000 0.0000 2.2689 +0.0000 0.0000 2.3126 +0.0000 0.0000 2.3562 +primID: 6 +startangle_c: 5 +endpose_c: 0 0 4 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0000 0.0000 1.9199 +0.0000 0.0000 1.8762 +0.0000 0.0000 1.8326 +0.0000 0.0000 1.7890 +0.0000 0.0000 1.7453 +0.0000 0.0000 1.7017 +0.0000 0.0000 1.6581 +0.0000 0.0000 1.6144 +0.0000 0.0000 1.5708 +primID: 0 +startangle_c: 6 +endpose_c: -1 1 6 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0028 0.0028 2.3562 +-0.0056 0.0056 2.3562 +-0.0083 0.0083 2.3562 +-0.0111 0.0111 2.3562 +-0.0139 0.0139 2.3562 +-0.0167 0.0167 2.3562 +-0.0194 0.0194 2.3562 +-0.0222 0.0222 2.3562 +-0.0250 0.0250 2.3562 +primID: 1 +startangle_c: 6 +endpose_c: -12 12 6 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0333 0.0333 2.3562 +-0.0667 0.0667 2.3562 +-0.1000 0.1000 2.3562 +-0.1333 0.1333 2.3562 +-0.1667 0.1667 2.3562 +-0.2000 0.2000 2.3562 +-0.2333 0.2333 2.3562 +-0.2667 0.2667 2.3562 +-0.3000 0.3000 2.3562 +primID: 2 +startangle_c: 6 +endpose_c: 1 -1 6 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0028 -0.0028 2.3562 +0.0056 -0.0056 2.3562 +0.0083 -0.0083 2.3562 +0.0111 -0.0111 2.3562 +0.0139 -0.0139 2.3562 +0.0167 -0.0167 2.3562 +0.0194 -0.0194 2.3562 +0.0222 -0.0222 2.3562 +0.0250 -0.0250 2.3562 +primID: 3 +startangle_c: 6 +endpose_c: -14 10 7 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0341 0.0341 2.3562 +-0.0684 0.0678 2.3859 +-0.1043 0.1000 2.4377 +-0.1418 0.1302 2.4896 +-0.1809 0.1584 2.5415 +-0.2213 0.1846 2.5933 +-0.2631 0.2086 2.6452 +-0.3060 0.2304 2.6970 +-0.3500 0.2500 2.7489 +primID: 4 +startangle_c: 6 +endpose_c: -10 14 5 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0341 0.0341 2.3562 +-0.0678 0.0684 2.3265 +-0.1000 0.1043 2.2747 +-0.1302 0.1418 2.2228 +-0.1584 0.1809 2.1709 +-0.1846 0.2213 2.1191 +-0.2086 0.2631 2.0672 +-0.2304 0.3060 2.0154 +-0.2500 0.3500 1.9635 +primID: 5 +startangle_c: 6 +endpose_c: 0 0 7 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0000 0.0000 2.3998 +0.0000 0.0000 2.4435 +0.0000 0.0000 2.4871 +0.0000 0.0000 2.5307 +0.0000 0.0000 2.5744 +0.0000 0.0000 2.6180 +0.0000 0.0000 2.6616 +0.0000 0.0000 2.7053 +0.0000 0.0000 2.7489 +primID: 6 +startangle_c: 6 +endpose_c: 0 0 5 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0000 0.0000 2.3126 +0.0000 0.0000 2.2689 +0.0000 0.0000 2.2253 +0.0000 0.0000 2.1817 +0.0000 0.0000 2.1380 +0.0000 0.0000 2.0944 +0.0000 0.0000 2.0508 +0.0000 0.0000 2.0071 +0.0000 0.0000 1.9635 +primID: 0 +startangle_c: 7 +endpose_c: -2 1 7 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0056 0.0028 2.7489 +-0.0111 0.0056 2.7489 +-0.0167 0.0083 2.7489 +-0.0222 0.0111 2.7489 +-0.0278 0.0139 2.7489 +-0.0333 0.0167 2.7489 +-0.0389 0.0194 2.7489 +-0.0444 0.0222 2.7489 +-0.0500 0.0250 2.7489 +primID: 1 +startangle_c: 7 +endpose_c: -12 6 7 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0333 0.0167 2.7489 +-0.0667 0.0333 2.7489 +-0.1000 0.0500 2.7489 +-0.1333 0.0667 2.7489 +-0.1667 0.0833 2.7489 +-0.2000 0.1000 2.7489 +-0.2333 0.1167 2.7489 +-0.2667 0.1333 2.7489 +-0.3000 0.1500 2.7489 +primID: 2 +startangle_c: 7 +endpose_c: 2 -1 7 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0056 -0.0028 2.7489 +0.0111 -0.0056 2.7489 +0.0167 -0.0083 2.7489 +0.0222 -0.0111 2.7489 +0.0278 -0.0139 2.7489 +0.0333 -0.0167 2.7489 +0.0389 -0.0194 2.7489 +0.0444 -0.0222 2.7489 +0.0500 -0.0250 2.7489 +primID: 3 +startangle_c: 7 +endpose_c: -10 8 6 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0298 0.0184 2.7186 +-0.0592 0.0379 2.6883 +-0.0881 0.0583 2.6580 +-0.1165 0.0796 2.6277 +-0.1444 0.1019 2.5974 +-0.1717 0.1251 2.5671 +-0.1984 0.1492 2.5368 +-0.2245 0.1742 2.5065 +-0.2500 0.2000 2.4762 +primID: 4 +startangle_c: 7 +endpose_c: -14 4 8 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0377 0.0156 2.7489 +-0.0754 0.0312 2.7489 +-0.1131 0.0468 2.7489 +-0.1508 0.0623 2.7680 +-0.1893 0.0758 2.8427 +-0.2287 0.0863 2.9174 +-0.2687 0.0939 2.9921 +-0.3092 0.0985 3.0669 +-0.3500 0.1000 3.1416 +primID: 5 +startangle_c: 7 +endpose_c: 0 0 6 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0000 0.0000 2.7053 +0.0000 0.0000 2.6616 +0.0000 0.0000 2.6180 +0.0000 0.0000 2.5744 +0.0000 0.0000 2.5307 +0.0000 0.0000 2.4871 +0.0000 0.0000 2.4435 +0.0000 0.0000 2.3998 +0.0000 0.0000 2.3562 +primID: 6 +startangle_c: 7 +endpose_c: 0 0 8 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0000 0.0000 2.7925 +0.0000 0.0000 2.8362 +0.0000 0.0000 2.8798 +0.0000 0.0000 2.9234 +0.0000 0.0000 2.9671 +0.0000 0.0000 3.0107 +0.0000 0.0000 3.0543 +0.0000 0.0000 3.0980 +0.0000 0.0000 3.1416 +primID: 0 +startangle_c: 8 +endpose_c: -1 0 8 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0028 0.0000 3.1416 +-0.0056 0.0000 3.1416 +-0.0083 0.0000 3.1416 +-0.0111 0.0000 3.1416 +-0.0139 0.0000 3.1416 +-0.0167 0.0000 3.1416 +-0.0194 0.0000 3.1416 +-0.0222 0.0000 3.1416 +-0.0250 0.0000 3.1416 +primID: 1 +startangle_c: 8 +endpose_c: -12 0 8 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0333 0.0000 3.1416 +-0.0667 0.0000 3.1416 +-0.1000 0.0000 3.1416 +-0.1333 0.0000 3.1416 +-0.1667 0.0000 3.1416 +-0.2000 0.0000 3.1416 +-0.2333 0.0000 3.1416 +-0.2667 0.0000 3.1416 +-0.3000 0.0000 3.1416 +primID: 2 +startangle_c: 8 +endpose_c: 1 0 8 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0028 0.0000 3.1416 +0.0056 0.0000 3.1416 +0.0083 0.0000 3.1416 +0.0111 0.0000 3.1416 +0.0139 0.0000 3.1416 +0.0167 0.0000 3.1416 +0.0194 0.0000 3.1416 +0.0222 0.0000 3.1416 +0.0250 0.0000 3.1416 +primID: 3 +startangle_c: 8 +endpose_c: -16 -2 9 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0452 0.0000 3.1416 +-0.0904 0.0000 3.1416 +-0.1355 0.0000 3.1416 +-0.1807 -0.0008 3.1904 +-0.2257 -0.0045 3.2592 +-0.2703 -0.0114 3.3280 +-0.3144 -0.0213 3.3967 +-0.3577 -0.0342 3.4655 +-0.4000 -0.0500 3.5343 +primID: 4 +startangle_c: 8 +endpose_c: -16 2 7 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0452 0.0000 3.1416 +-0.0904 0.0000 3.1416 +-0.1355 0.0000 3.1416 +-0.1807 0.0008 3.0928 +-0.2257 0.0045 3.0240 +-0.2703 0.0114 2.9552 +-0.3144 0.0213 2.8864 +-0.3577 0.0342 2.8177 +-0.4000 0.0500 2.7489 +primID: 5 +startangle_c: 8 +endpose_c: 0 0 9 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0000 0.0000 3.1852 +0.0000 0.0000 3.2289 +0.0000 0.0000 3.2725 +0.0000 0.0000 3.3161 +0.0000 0.0000 3.3598 +0.0000 0.0000 3.4034 +0.0000 0.0000 3.4470 +0.0000 0.0000 3.4907 +0.0000 0.0000 3.5343 +primID: 6 +startangle_c: 8 +endpose_c: 0 0 7 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0000 0.0000 3.0980 +0.0000 0.0000 3.0543 +0.0000 0.0000 3.0107 +0.0000 0.0000 2.9671 +0.0000 0.0000 2.9234 +0.0000 0.0000 2.8798 +0.0000 0.0000 2.8362 +0.0000 0.0000 2.7925 +0.0000 0.0000 2.7489 +primID: 0 +startangle_c: 9 +endpose_c: -2 -1 9 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0056 -0.0028 3.5343 +-0.0111 -0.0056 3.5343 +-0.0167 -0.0083 3.5343 +-0.0222 -0.0111 3.5343 +-0.0278 -0.0139 3.5343 +-0.0333 -0.0167 3.5343 +-0.0389 -0.0194 3.5343 +-0.0444 -0.0222 3.5343 +-0.0500 -0.0250 3.5343 +primID: 1 +startangle_c: 9 +endpose_c: -12 -6 9 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0333 -0.0167 3.5343 +-0.0667 -0.0333 3.5343 +-0.1000 -0.0500 3.5343 +-0.1333 -0.0667 3.5343 +-0.1667 -0.0833 3.5343 +-0.2000 -0.1000 3.5343 +-0.2333 -0.1167 3.5343 +-0.2667 -0.1333 3.5343 +-0.3000 -0.1500 3.5343 +primID: 2 +startangle_c: 9 +endpose_c: 2 1 9 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0056 0.0028 3.5343 +0.0111 0.0056 3.5343 +0.0167 0.0083 3.5343 +0.0222 0.0111 3.5343 +0.0278 0.0139 3.5343 +0.0333 0.0167 3.5343 +0.0389 0.0194 3.5343 +0.0444 0.0222 3.5343 +0.0500 0.0250 3.5343 +primID: 3 +startangle_c: 9 +endpose_c: -10 -8 10 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0298 -0.0184 3.5646 +-0.0592 -0.0379 3.5949 +-0.0881 -0.0583 3.6252 +-0.1165 -0.0796 3.6555 +-0.1444 -0.1019 3.6858 +-0.1717 -0.1251 3.7161 +-0.1984 -0.1492 3.7464 +-0.2245 -0.1742 3.7767 +-0.2500 -0.2000 3.8070 +primID: 4 +startangle_c: 9 +endpose_c: -14 -4 8 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0377 -0.0156 3.5343 +-0.0754 -0.0312 3.5343 +-0.1131 -0.0468 3.5343 +-0.1508 -0.0623 3.5152 +-0.1893 -0.0758 3.4405 +-0.2287 -0.0863 3.3658 +-0.2687 -0.0939 3.2910 +-0.3092 -0.0985 3.2163 +-0.3500 -0.1000 3.1416 +primID: 5 +startangle_c: 9 +endpose_c: 0 0 10 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0000 0.0000 3.5779 +0.0000 0.0000 3.6216 +0.0000 0.0000 3.6652 +0.0000 0.0000 3.7088 +0.0000 0.0000 3.7525 +0.0000 0.0000 3.7961 +0.0000 0.0000 3.8397 +0.0000 0.0000 3.8834 +0.0000 0.0000 3.9270 +primID: 6 +startangle_c: 9 +endpose_c: 0 0 8 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0000 0.0000 3.4907 +0.0000 0.0000 3.4470 +0.0000 0.0000 3.4034 +0.0000 0.0000 3.3598 +0.0000 0.0000 3.3161 +0.0000 0.0000 3.2725 +0.0000 0.0000 3.2289 +0.0000 0.0000 3.1852 +0.0000 0.0000 3.1416 +primID: 0 +startangle_c: 10 +endpose_c: -1 -1 10 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0028 -0.0028 3.9270 +-0.0056 -0.0056 3.9270 +-0.0083 -0.0083 3.9270 +-0.0111 -0.0111 3.9270 +-0.0139 -0.0139 3.9270 +-0.0167 -0.0167 3.9270 +-0.0194 -0.0194 3.9270 +-0.0222 -0.0222 3.9270 +-0.0250 -0.0250 3.9270 +primID: 1 +startangle_c: 10 +endpose_c: -12 -12 10 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0333 -0.0333 3.9270 +-0.0667 -0.0667 3.9270 +-0.1000 -0.1000 3.9270 +-0.1333 -0.1333 3.9270 +-0.1667 -0.1667 3.9270 +-0.2000 -0.2000 3.9270 +-0.2333 -0.2333 3.9270 +-0.2667 -0.2667 3.9270 +-0.3000 -0.3000 3.9270 +primID: 2 +startangle_c: 10 +endpose_c: 1 1 10 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0028 0.0028 3.9270 +0.0056 0.0056 3.9270 +0.0083 0.0083 3.9270 +0.0111 0.0111 3.9270 +0.0139 0.0139 3.9270 +0.0167 0.0167 3.9270 +0.0194 0.0194 3.9270 +0.0222 0.0222 3.9270 +0.0250 0.0250 3.9270 +primID: 3 +startangle_c: 10 +endpose_c: -10 -14 11 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0341 -0.0341 3.9270 +-0.0678 -0.0684 3.9567 +-0.1000 -0.1043 4.0085 +-0.1302 -0.1418 4.0604 +-0.1584 -0.1809 4.1123 +-0.1846 -0.2213 4.1641 +-0.2086 -0.2631 4.2160 +-0.2304 -0.3060 4.2678 +-0.2500 -0.3500 4.3197 +primID: 4 +startangle_c: 10 +endpose_c: -14 -10 9 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0341 -0.0341 3.9270 +-0.0684 -0.0678 3.8973 +-0.1043 -0.1000 3.8455 +-0.1418 -0.1302 3.7936 +-0.1809 -0.1584 3.7417 +-0.2213 -0.1846 3.6899 +-0.2631 -0.2086 3.6380 +-0.3060 -0.2304 3.5862 +-0.3500 -0.2500 3.5343 +primID: 5 +startangle_c: 10 +endpose_c: 0 0 11 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.9706 +0.0000 0.0000 4.0143 +0.0000 0.0000 4.0579 +0.0000 0.0000 4.1015 +0.0000 0.0000 4.1452 +0.0000 0.0000 4.1888 +0.0000 0.0000 4.2324 +0.0000 0.0000 4.2761 +0.0000 0.0000 4.3197 +primID: 6 +startangle_c: 10 +endpose_c: 0 0 9 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.8834 +0.0000 0.0000 3.8397 +0.0000 0.0000 3.7961 +0.0000 0.0000 3.7525 +0.0000 0.0000 3.7088 +0.0000 0.0000 3.6652 +0.0000 0.0000 3.6216 +0.0000 0.0000 3.5779 +0.0000 0.0000 3.5343 +primID: 0 +startangle_c: 11 +endpose_c: -1 -2 11 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0028 -0.0056 4.3197 +-0.0056 -0.0111 4.3197 +-0.0083 -0.0167 4.3197 +-0.0111 -0.0222 4.3197 +-0.0139 -0.0278 4.3197 +-0.0167 -0.0333 4.3197 +-0.0194 -0.0389 4.3197 +-0.0222 -0.0444 4.3197 +-0.0250 -0.0500 4.3197 +primID: 1 +startangle_c: 11 +endpose_c: -6 -12 11 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0167 -0.0333 4.3197 +-0.0333 -0.0667 4.3197 +-0.0500 -0.1000 4.3197 +-0.0667 -0.1333 4.3197 +-0.0833 -0.1667 4.3197 +-0.1000 -0.2000 4.3197 +-0.1167 -0.2333 4.3197 +-0.1333 -0.2667 4.3197 +-0.1500 -0.3000 4.3197 +primID: 2 +startangle_c: 11 +endpose_c: 1 2 11 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0028 0.0056 4.3197 +0.0056 0.0111 4.3197 +0.0083 0.0167 4.3197 +0.0111 0.0222 4.3197 +0.0139 0.0278 4.3197 +0.0167 0.0333 4.3197 +0.0194 0.0389 4.3197 +0.0222 0.0444 4.3197 +0.0250 0.0500 4.3197 +primID: 3 +startangle_c: 11 +endpose_c: -8 -10 10 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0184 -0.0298 4.2894 +-0.0379 -0.0592 4.2591 +-0.0583 -0.0881 4.2288 +-0.0796 -0.1165 4.1985 +-0.1019 -0.1444 4.1682 +-0.1251 -0.1717 4.1379 +-0.1492 -0.1984 4.1076 +-0.1742 -0.2245 4.0773 +-0.2000 -0.2500 4.0470 +primID: 4 +startangle_c: 11 +endpose_c: -4 -14 12 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0156 -0.0377 4.3197 +-0.0312 -0.0754 4.3197 +-0.0468 -0.1131 4.3197 +-0.0623 -0.1508 4.3388 +-0.0758 -0.1893 4.4135 +-0.0863 -0.2287 4.4882 +-0.0939 -0.2687 4.5629 +-0.0985 -0.3092 4.6377 +-0.1000 -0.3500 4.7124 +primID: 5 +startangle_c: 11 +endpose_c: 0 0 10 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0000 0.0000 4.2761 +0.0000 0.0000 4.2324 +0.0000 0.0000 4.1888 +0.0000 0.0000 4.1452 +0.0000 0.0000 4.1015 +0.0000 0.0000 4.0579 +0.0000 0.0000 4.0143 +0.0000 0.0000 3.9706 +0.0000 0.0000 3.9270 +primID: 6 +startangle_c: 11 +endpose_c: 0 0 12 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0000 0.0000 4.3633 +0.0000 0.0000 4.4070 +0.0000 0.0000 4.4506 +0.0000 0.0000 4.4942 +0.0000 0.0000 4.5379 +0.0000 0.0000 4.5815 +0.0000 0.0000 4.6251 +0.0000 0.0000 4.6688 +0.0000 0.0000 4.7124 +primID: 0 +startangle_c: 12 +endpose_c: 0 -1 12 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0028 4.7124 +0.0000 -0.0056 4.7124 +0.0000 -0.0083 4.7124 +0.0000 -0.0111 4.7124 +0.0000 -0.0139 4.7124 +0.0000 -0.0167 4.7124 +0.0000 -0.0194 4.7124 +0.0000 -0.0222 4.7124 +0.0000 -0.0250 4.7124 +primID: 1 +startangle_c: 12 +endpose_c: 0 -12 12 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0333 4.7124 +0.0000 -0.0667 4.7124 +0.0000 -0.1000 4.7124 +0.0000 -0.1333 4.7124 +0.0000 -0.1667 4.7124 +0.0000 -0.2000 4.7124 +0.0000 -0.2333 4.7124 +0.0000 -0.2667 4.7124 +0.0000 -0.3000 4.7124 +primID: 2 +startangle_c: 12 +endpose_c: 0 1 12 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0028 4.7124 +0.0000 0.0056 4.7124 +0.0000 0.0083 4.7124 +0.0000 0.0111 4.7124 +0.0000 0.0139 4.7124 +0.0000 0.0167 4.7124 +0.0000 0.0194 4.7124 +0.0000 0.0222 4.7124 +0.0000 0.0250 4.7124 +primID: 3 +startangle_c: 12 +endpose_c: 2 -16 13 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0452 4.7124 +0.0000 -0.0904 4.7124 +0.0000 -0.1355 4.7124 +0.0008 -0.1807 4.7612 +0.0045 -0.2257 4.8300 +0.0114 -0.2703 4.8988 +0.0213 -0.3144 4.9675 +0.0342 -0.3577 5.0363 +0.0500 -0.4000 5.1051 +primID: 4 +startangle_c: 12 +endpose_c: -2 -16 11 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.7124 +-0.0000 -0.0452 4.7124 +-0.0000 -0.0904 4.7124 +-0.0000 -0.1355 4.7124 +-0.0008 -0.1807 4.6636 +-0.0045 -0.2257 4.5948 +-0.0114 -0.2703 4.5260 +-0.0213 -0.3144 4.4572 +-0.0342 -0.3577 4.3885 +-0.0500 -0.4000 4.3197 +primID: 5 +startangle_c: 12 +endpose_c: 0 0 13 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0000 4.7560 +0.0000 0.0000 4.7997 +0.0000 0.0000 4.8433 +0.0000 0.0000 4.8869 +0.0000 0.0000 4.9306 +0.0000 0.0000 4.9742 +0.0000 0.0000 5.0178 +0.0000 0.0000 5.0615 +0.0000 0.0000 5.1051 +primID: 6 +startangle_c: 12 +endpose_c: 0 0 11 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0000 4.6688 +0.0000 0.0000 4.6251 +0.0000 0.0000 4.5815 +0.0000 0.0000 4.5379 +0.0000 0.0000 4.4942 +0.0000 0.0000 4.4506 +0.0000 0.0000 4.4070 +0.0000 0.0000 4.3633 +0.0000 0.0000 4.3197 +primID: 0 +startangle_c: 13 +endpose_c: 1 -2 13 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0028 -0.0056 5.1051 +0.0056 -0.0111 5.1051 +0.0083 -0.0167 5.1051 +0.0111 -0.0222 5.1051 +0.0139 -0.0278 5.1051 +0.0167 -0.0333 5.1051 +0.0194 -0.0389 5.1051 +0.0222 -0.0444 5.1051 +0.0250 -0.0500 5.1051 +primID: 1 +startangle_c: 13 +endpose_c: 6 -12 13 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0167 -0.0333 5.1051 +0.0333 -0.0667 5.1051 +0.0500 -0.1000 5.1051 +0.0667 -0.1333 5.1051 +0.0833 -0.1667 5.1051 +0.1000 -0.2000 5.1051 +0.1167 -0.2333 5.1051 +0.1333 -0.2667 5.1051 +0.1500 -0.3000 5.1051 +primID: 2 +startangle_c: 13 +endpose_c: -1 2 13 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.1051 +-0.0028 0.0056 5.1051 +-0.0056 0.0111 5.1051 +-0.0083 0.0167 5.1051 +-0.0111 0.0222 5.1051 +-0.0139 0.0278 5.1051 +-0.0167 0.0333 5.1051 +-0.0194 0.0389 5.1051 +-0.0222 0.0444 5.1051 +-0.0250 0.0500 5.1051 +primID: 3 +startangle_c: 13 +endpose_c: 8 -10 14 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0184 -0.0298 5.1354 +0.0379 -0.0592 5.1657 +0.0583 -0.0881 5.1960 +0.0796 -0.1165 5.2263 +0.1019 -0.1444 5.2566 +0.1251 -0.1717 5.2869 +0.1492 -0.1984 5.3172 +0.1742 -0.2245 5.3475 +0.2000 -0.2500 5.3778 +primID: 4 +startangle_c: 13 +endpose_c: 4 -14 12 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0156 -0.0377 5.1051 +0.0312 -0.0754 5.1051 +0.0468 -0.1131 5.1051 +0.0623 -0.1508 5.0860 +0.0758 -0.1893 5.0113 +0.0863 -0.2287 4.9366 +0.0939 -0.2687 4.8618 +0.0985 -0.3092 4.7871 +0.1000 -0.3500 4.7124 +primID: 5 +startangle_c: 13 +endpose_c: 0 0 14 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0000 0.0000 5.1487 +0.0000 0.0000 5.1924 +0.0000 0.0000 5.2360 +0.0000 0.0000 5.2796 +0.0000 0.0000 5.3233 +0.0000 0.0000 5.3669 +0.0000 0.0000 5.4105 +0.0000 0.0000 5.4542 +0.0000 0.0000 5.4978 +primID: 6 +startangle_c: 13 +endpose_c: 0 0 12 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0000 0.0000 5.0615 +0.0000 0.0000 5.0178 +0.0000 0.0000 4.9742 +0.0000 0.0000 4.9306 +0.0000 0.0000 4.8869 +0.0000 0.0000 4.8433 +0.0000 0.0000 4.7997 +0.0000 0.0000 4.7560 +0.0000 0.0000 4.7124 +primID: 0 +startangle_c: 14 +endpose_c: 1 -1 14 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0028 -0.0028 5.4978 +0.0056 -0.0056 5.4978 +0.0083 -0.0083 5.4978 +0.0111 -0.0111 5.4978 +0.0139 -0.0139 5.4978 +0.0167 -0.0167 5.4978 +0.0194 -0.0194 5.4978 +0.0222 -0.0222 5.4978 +0.0250 -0.0250 5.4978 +primID: 1 +startangle_c: 14 +endpose_c: 12 -12 14 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0333 -0.0333 5.4978 +0.0667 -0.0667 5.4978 +0.1000 -0.1000 5.4978 +0.1333 -0.1333 5.4978 +0.1667 -0.1667 5.4978 +0.2000 -0.2000 5.4978 +0.2333 -0.2333 5.4978 +0.2667 -0.2667 5.4978 +0.3000 -0.3000 5.4978 +primID: 2 +startangle_c: 14 +endpose_c: -1 1 14 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.4978 +-0.0028 0.0028 5.4978 +-0.0056 0.0056 5.4978 +-0.0083 0.0083 5.4978 +-0.0111 0.0111 5.4978 +-0.0139 0.0139 5.4978 +-0.0167 0.0167 5.4978 +-0.0194 0.0194 5.4978 +-0.0222 0.0222 5.4978 +-0.0250 0.0250 5.4978 +primID: 3 +startangle_c: 14 +endpose_c: 14 -10 15 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0341 -0.0341 5.4978 +0.0684 -0.0678 5.5275 +0.1043 -0.1000 5.5793 +0.1418 -0.1302 5.6312 +0.1809 -0.1584 5.6830 +0.2213 -0.1846 5.7349 +0.2631 -0.2086 5.7868 +0.3060 -0.2304 5.8386 +0.3500 -0.2500 5.8905 +primID: 4 +startangle_c: 14 +endpose_c: 10 -14 13 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0341 -0.0341 5.4978 +0.0678 -0.0684 5.4681 +0.1000 -0.1043 5.4162 +0.1302 -0.1418 5.3644 +0.1584 -0.1809 5.3125 +0.1846 -0.2213 5.2607 +0.2086 -0.2631 5.2088 +0.2304 -0.3060 5.1569 +0.2500 -0.3500 5.1051 +primID: 5 +startangle_c: 14 +endpose_c: 0 0 15 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0000 0.0000 5.5414 +0.0000 0.0000 5.5851 +0.0000 0.0000 5.6287 +0.0000 0.0000 5.6723 +0.0000 0.0000 5.7160 +0.0000 0.0000 5.7596 +0.0000 0.0000 5.8032 +0.0000 0.0000 5.8469 +0.0000 0.0000 5.8905 +primID: 6 +startangle_c: 14 +endpose_c: 0 0 13 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0000 0.0000 5.4542 +0.0000 0.0000 5.4105 +0.0000 0.0000 5.3669 +0.0000 0.0000 5.3233 +0.0000 0.0000 5.2796 +0.0000 0.0000 5.2360 +0.0000 0.0000 5.1924 +0.0000 0.0000 5.1487 +0.0000 0.0000 5.1051 +primID: 0 +startangle_c: 15 +endpose_c: 2 -1 15 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0056 -0.0028 5.8905 +0.0111 -0.0056 5.8905 +0.0167 -0.0083 5.8905 +0.0222 -0.0111 5.8905 +0.0278 -0.0139 5.8905 +0.0333 -0.0167 5.8905 +0.0389 -0.0194 5.8905 +0.0444 -0.0222 5.8905 +0.0500 -0.0250 5.8905 +primID: 1 +startangle_c: 15 +endpose_c: 12 -6 15 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0333 -0.0167 5.8905 +0.0667 -0.0333 5.8905 +0.1000 -0.0500 5.8905 +0.1333 -0.0667 5.8905 +0.1667 -0.0833 5.8905 +0.2000 -0.1000 5.8905 +0.2333 -0.1167 5.8905 +0.2667 -0.1333 5.8905 +0.3000 -0.1500 5.8905 +primID: 2 +startangle_c: 15 +endpose_c: -2 1 15 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.8905 +-0.0056 0.0028 5.8905 +-0.0111 0.0056 5.8905 +-0.0167 0.0083 5.8905 +-0.0222 0.0111 5.8905 +-0.0278 0.0139 5.8905 +-0.0333 0.0167 5.8905 +-0.0389 0.0194 5.8905 +-0.0444 0.0222 5.8905 +-0.0500 0.0250 5.8905 +primID: 3 +startangle_c: 15 +endpose_c: 10 -8 14 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0298 -0.0184 5.8602 +0.0592 -0.0379 5.8299 +0.0881 -0.0583 5.7996 +0.1165 -0.0796 5.7693 +0.1444 -0.1019 5.7390 +0.1717 -0.1251 5.7087 +0.1984 -0.1492 5.6784 +0.2245 -0.1742 5.6481 +0.2500 -0.2000 5.6178 +primID: 4 +startangle_c: 15 +endpose_c: 14 -4 0 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0377 -0.0156 5.8905 +0.0754 -0.0312 5.8905 +0.1131 -0.0468 5.8905 +0.1508 -0.0623 5.9096 +0.1893 -0.0758 5.9843 +0.2287 -0.0863 6.0590 +0.2687 -0.0939 6.1337 +0.3092 -0.0985 6.2085 +0.3500 -0.1000 6.2832 +primID: 5 +startangle_c: 15 +endpose_c: 0 0 14 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0000 0.0000 5.8469 +0.0000 0.0000 5.8032 +0.0000 0.0000 5.7596 +0.0000 0.0000 5.7160 +0.0000 0.0000 5.6723 +0.0000 0.0000 5.6287 +0.0000 0.0000 5.5851 +0.0000 0.0000 5.5414 +0.0000 0.0000 5.4978 +primID: 6 +startangle_c: 15 +endpose_c: 0 0 0 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0000 0.0000 5.2360 +0.0000 0.0000 4.5815 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.2725 +0.0000 0.0000 2.6180 +0.0000 0.0000 1.9635 +0.0000 0.0000 1.3090 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.0000 diff --git a/navigations/sbpl_lattice_planner/matlab/mprim/unicycle_highcost_2cm.mprim b/navigations/sbpl_lattice_planner/matlab/mprim/unicycle_highcost_2cm.mprim new file mode 100755 index 0000000..b87c310 --- /dev/null +++ b/navigations/sbpl_lattice_planner/matlab/mprim/unicycle_highcost_2cm.mprim @@ -0,0 +1,1683 @@ +resolution_m: 0.020000 +numberofangles: 16 +totalnumberofprimitives: 112 +primID: 0 +startangle_c: 0 +endpose_c: 1 0 0 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0022 0.0000 0.0000 +0.0044 0.0000 0.0000 +0.0067 0.0000 0.0000 +0.0089 0.0000 0.0000 +0.0111 0.0000 0.0000 +0.0133 0.0000 0.0000 +0.0156 0.0000 0.0000 +0.0178 0.0000 0.0000 +0.0200 0.0000 0.0000 +primID: 1 +startangle_c: 0 +endpose_c: 20 0 0 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0444 0.0000 0.0000 +0.0889 0.0000 0.0000 +0.1333 0.0000 0.0000 +0.1778 0.0000 0.0000 +0.2222 0.0000 0.0000 +0.2667 0.0000 0.0000 +0.3111 0.0000 0.0000 +0.3556 0.0000 0.0000 +0.4000 0.0000 0.0000 +primID: 2 +startangle_c: 0 +endpose_c: -1 0 0 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.0000 +-0.0022 0.0000 0.0000 +-0.0044 0.0000 0.0000 +-0.0067 0.0000 0.0000 +-0.0089 0.0000 0.0000 +-0.0111 0.0000 0.0000 +-0.0133 0.0000 0.0000 +-0.0156 0.0000 0.0000 +-0.0178 0.0000 0.0000 +-0.0200 0.0000 0.0000 +primID: 3 +startangle_c: 0 +endpose_c: 15 3 1 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0342 0.0008 0.0434 +0.0683 0.0031 0.0868 +0.1023 0.0069 0.1302 +0.1361 0.0121 0.1736 +0.1696 0.0188 0.2170 +0.2029 0.0270 0.2604 +0.2357 0.0366 0.3038 +0.2681 0.0476 0.3472 +0.3000 0.0600 0.3906 +primID: 4 +startangle_c: 0 +endpose_c: 15 -3 -1 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0342 -0.0008 -0.0434 +0.0683 -0.0031 -0.0868 +0.1023 -0.0069 -0.1302 +0.1361 -0.0121 -0.1736 +0.1696 -0.0188 -0.2170 +0.2029 -0.0270 -0.2604 +0.2357 -0.0366 -0.3038 +0.2681 -0.0476 -0.3472 +0.3000 -0.0600 -0.3906 +primID: 5 +startangle_c: 0 +endpose_c: 0 0 1 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0000 0.0000 0.0436 +0.0000 0.0000 0.0873 +0.0000 0.0000 0.1309 +0.0000 0.0000 0.1745 +0.0000 0.0000 0.2182 +0.0000 0.0000 0.2618 +0.0000 0.0000 0.3054 +0.0000 0.0000 0.3491 +0.0000 0.0000 0.3927 +primID: 6 +startangle_c: 0 +endpose_c: 0 0 -1 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0000 0.0000 -0.0436 +0.0000 0.0000 -0.0873 +0.0000 0.0000 -0.1309 +0.0000 0.0000 -0.1745 +0.0000 0.0000 -0.2182 +0.0000 0.0000 -0.2618 +0.0000 0.0000 -0.3054 +0.0000 0.0000 -0.3491 +0.0000 0.0000 -0.3927 +primID: 0 +startangle_c: 1 +endpose_c: 2 1 1 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0044 0.0022 0.3927 +0.0089 0.0044 0.3927 +0.0133 0.0067 0.3927 +0.0178 0.0089 0.3927 +0.0222 0.0111 0.3927 +0.0267 0.0133 0.3927 +0.0311 0.0156 0.3927 +0.0356 0.0178 0.3927 +0.0400 0.0200 0.3927 +primID: 1 +startangle_c: 1 +endpose_c: 15 8 1 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0333 0.0178 0.3927 +0.0667 0.0356 0.3927 +0.1000 0.0533 0.3927 +0.1333 0.0711 0.3927 +0.1667 0.0889 0.3927 +0.2000 0.1067 0.3927 +0.2333 0.1244 0.3927 +0.2667 0.1422 0.3927 +0.3000 0.1600 0.3927 +primID: 2 +startangle_c: 1 +endpose_c: -2 -1 1 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.3927 +-0.0044 -0.0022 0.3927 +-0.0089 -0.0044 0.3927 +-0.0133 -0.0067 0.3927 +-0.0178 -0.0089 0.3927 +-0.0222 -0.0111 0.3927 +-0.0267 -0.0133 0.3927 +-0.0311 -0.0156 0.3927 +-0.0356 -0.0178 0.3927 +-0.0400 -0.0200 0.3927 +primID: 3 +startangle_c: 1 +endpose_c: 12 10 2 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0285 0.0188 0.4210 +0.0566 0.0385 0.4492 +0.0842 0.0590 0.4775 +0.1115 0.0804 0.5057 +0.1382 0.1027 0.5340 +0.1645 0.1258 0.5623 +0.1902 0.1497 0.5905 +0.2154 0.1745 0.6188 +0.2400 0.2000 0.6470 +primID: 4 +startangle_c: 1 +endpose_c: 18 5 0 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0387 0.0160 0.3927 +0.0774 0.0320 0.3927 +0.1161 0.0481 0.3927 +0.1549 0.0636 0.3512 +0.1947 0.0766 0.2809 +0.2353 0.0868 0.2107 +0.2765 0.0941 0.1405 +0.3182 0.0985 0.0702 +0.3600 0.1000 0.0000 +primID: 5 +startangle_c: 1 +endpose_c: 0 0 2 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0000 0.0000 0.4363 +0.0000 0.0000 0.4800 +0.0000 0.0000 0.5236 +0.0000 0.0000 0.5672 +0.0000 0.0000 0.6109 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.6981 +0.0000 0.0000 0.7418 +0.0000 0.0000 0.7854 +primID: 6 +startangle_c: 1 +endpose_c: 0 0 0 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0000 0.0000 0.3491 +0.0000 0.0000 0.3054 +0.0000 0.0000 0.2618 +0.0000 0.0000 0.2182 +0.0000 0.0000 0.1745 +0.0000 0.0000 0.1309 +0.0000 0.0000 0.0873 +0.0000 0.0000 0.0436 +0.0000 0.0000 0.0000 +primID: 0 +startangle_c: 2 +endpose_c: 1 1 2 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0022 0.0022 0.7854 +0.0044 0.0044 0.7854 +0.0067 0.0067 0.7854 +0.0089 0.0089 0.7854 +0.0111 0.0111 0.7854 +0.0133 0.0133 0.7854 +0.0156 0.0156 0.7854 +0.0178 0.0178 0.7854 +0.0200 0.0200 0.7854 +primID: 1 +startangle_c: 2 +endpose_c: 15 15 2 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0333 0.0333 0.7854 +0.0667 0.0667 0.7854 +0.1000 0.1000 0.7854 +0.1333 0.1333 0.7854 +0.1667 0.1667 0.7854 +0.2000 0.2000 0.7854 +0.2333 0.2333 0.7854 +0.2667 0.2667 0.7854 +0.3000 0.3000 0.7854 +primID: 2 +startangle_c: 2 +endpose_c: -1 -1 2 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 0.7854 +-0.0022 -0.0022 0.7854 +-0.0044 -0.0044 0.7854 +-0.0067 -0.0067 0.7854 +-0.0089 -0.0089 0.7854 +-0.0111 -0.0111 0.7854 +-0.0133 -0.0133 0.7854 +-0.0156 -0.0156 0.7854 +-0.0178 -0.0178 0.7854 +-0.0200 -0.0200 0.7854 +primID: 3 +startangle_c: 2 +endpose_c: 12 18 3 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0334 0.0350 0.8288 +0.0652 0.0714 0.8722 +0.0954 0.1092 0.9156 +0.1240 0.1482 0.9590 +0.1508 0.1885 1.0024 +0.1759 0.2299 1.0458 +0.1991 0.2723 1.0892 +0.2205 0.3157 1.1326 +0.2400 0.3600 1.1760 +primID: 4 +startangle_c: 2 +endpose_c: 18 12 1 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0350 0.0334 0.7420 +0.0714 0.0652 0.6986 +0.1092 0.0954 0.6552 +0.1482 0.1240 0.6118 +0.1885 0.1508 0.5684 +0.2299 0.1759 0.5250 +0.2723 0.1991 0.4816 +0.3157 0.2205 0.4382 +0.3600 0.2400 0.3948 +primID: 5 +startangle_c: 2 +endpose_c: 0 0 3 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0000 0.0000 0.8290 +0.0000 0.0000 0.8727 +0.0000 0.0000 0.9163 +0.0000 0.0000 0.9599 +0.0000 0.0000 1.0036 +0.0000 0.0000 1.0472 +0.0000 0.0000 1.0908 +0.0000 0.0000 1.1345 +0.0000 0.0000 1.1781 +primID: 6 +startangle_c: 2 +endpose_c: 0 0 1 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0000 0.0000 0.7418 +0.0000 0.0000 0.6981 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.6109 +0.0000 0.0000 0.5672 +0.0000 0.0000 0.5236 +0.0000 0.0000 0.4800 +0.0000 0.0000 0.4363 +0.0000 0.0000 0.3927 +primID: 0 +startangle_c: 3 +endpose_c: 1 2 3 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0022 0.0044 1.1781 +0.0044 0.0089 1.1781 +0.0067 0.0133 1.1781 +0.0089 0.0178 1.1781 +0.0111 0.0222 1.1781 +0.0133 0.0267 1.1781 +0.0156 0.0311 1.1781 +0.0178 0.0356 1.1781 +0.0200 0.0400 1.1781 +primID: 1 +startangle_c: 3 +endpose_c: 8 15 3 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0178 0.0333 1.1781 +0.0356 0.0667 1.1781 +0.0533 0.1000 1.1781 +0.0711 0.1333 1.1781 +0.0889 0.1667 1.1781 +0.1067 0.2000 1.1781 +0.1244 0.2333 1.1781 +0.1422 0.2667 1.1781 +0.1600 0.3000 1.1781 +primID: 2 +startangle_c: 3 +endpose_c: -1 -2 3 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.1781 +-0.0022 -0.0044 1.1781 +-0.0044 -0.0089 1.1781 +-0.0067 -0.0133 1.1781 +-0.0089 -0.0178 1.1781 +-0.0111 -0.0222 1.1781 +-0.0133 -0.0267 1.1781 +-0.0156 -0.0311 1.1781 +-0.0178 -0.0356 1.1781 +-0.0200 -0.0400 1.1781 +primID: 3 +startangle_c: 3 +endpose_c: 10 12 2 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0188 0.0285 1.1498 +0.0385 0.0566 1.1216 +0.0590 0.0842 1.0933 +0.0804 0.1115 1.0651 +0.1027 0.1382 1.0368 +0.1258 0.1645 1.0085 +0.1497 0.1902 0.9803 +0.1745 0.2154 0.9520 +0.2000 0.2400 0.9238 +primID: 4 +startangle_c: 3 +endpose_c: 5 18 4 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0160 0.0387 1.1781 +0.0320 0.0774 1.1781 +0.0481 0.1161 1.1781 +0.0636 0.1549 1.2196 +0.0766 0.1947 1.2898 +0.0868 0.2353 1.3601 +0.0941 0.2765 1.4303 +0.0985 0.3182 1.5006 +0.1000 0.3600 1.5708 +primID: 5 +startangle_c: 3 +endpose_c: 0 0 2 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0000 0.0000 1.1345 +0.0000 0.0000 1.0908 +0.0000 0.0000 1.0472 +0.0000 0.0000 1.0036 +0.0000 0.0000 0.9599 +0.0000 0.0000 0.9163 +0.0000 0.0000 0.8727 +0.0000 0.0000 0.8290 +0.0000 0.0000 0.7854 +primID: 6 +startangle_c: 3 +endpose_c: 0 0 4 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0000 0.0000 1.2217 +0.0000 0.0000 1.2654 +0.0000 0.0000 1.3090 +0.0000 0.0000 1.3526 +0.0000 0.0000 1.3963 +0.0000 0.0000 1.4399 +0.0000 0.0000 1.4835 +0.0000 0.0000 1.5272 +0.0000 0.0000 1.5708 +primID: 0 +startangle_c: 4 +endpose_c: 0 1 4 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0022 1.5708 +0.0000 0.0044 1.5708 +0.0000 0.0067 1.5708 +0.0000 0.0089 1.5708 +0.0000 0.0111 1.5708 +0.0000 0.0133 1.5708 +0.0000 0.0156 1.5708 +0.0000 0.0178 1.5708 +0.0000 0.0200 1.5708 +primID: 1 +startangle_c: 4 +endpose_c: 0 20 4 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0444 1.5708 +0.0000 0.0889 1.5708 +0.0000 0.1333 1.5708 +0.0000 0.1778 1.5708 +0.0000 0.2222 1.5708 +0.0000 0.2667 1.5708 +0.0000 0.3111 1.5708 +0.0000 0.3556 1.5708 +0.0000 0.4000 1.5708 +primID: 2 +startangle_c: 4 +endpose_c: 0 -1 4 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 -0.0022 1.5708 +0.0000 -0.0044 1.5708 +0.0000 -0.0067 1.5708 +0.0000 -0.0089 1.5708 +0.0000 -0.0111 1.5708 +0.0000 -0.0133 1.5708 +0.0000 -0.0156 1.5708 +0.0000 -0.0178 1.5708 +0.0000 -0.0200 1.5708 +primID: 3 +startangle_c: 4 +endpose_c: -3 15 5 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.5708 +-0.0008 0.0342 1.6142 +-0.0031 0.0683 1.6576 +-0.0069 0.1023 1.7010 +-0.0121 0.1361 1.7444 +-0.0188 0.1696 1.7878 +-0.0270 0.2029 1.8312 +-0.0366 0.2357 1.8746 +-0.0476 0.2681 1.9180 +-0.0600 0.3000 1.9614 +primID: 4 +startangle_c: 4 +endpose_c: 3 15 3 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0008 0.0342 1.5274 +0.0031 0.0683 1.4840 +0.0069 0.1023 1.4406 +0.0121 0.1361 1.3972 +0.0188 0.1696 1.3538 +0.0270 0.2029 1.3104 +0.0366 0.2357 1.2670 +0.0476 0.2681 1.2236 +0.0600 0.3000 1.1802 +primID: 5 +startangle_c: 4 +endpose_c: 0 0 5 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0000 1.6144 +0.0000 0.0000 1.6581 +0.0000 0.0000 1.7017 +0.0000 0.0000 1.7453 +0.0000 0.0000 1.7890 +0.0000 0.0000 1.8326 +0.0000 0.0000 1.8762 +0.0000 0.0000 1.9199 +0.0000 0.0000 1.9635 +primID: 6 +startangle_c: 4 +endpose_c: 0 0 3 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0000 1.5272 +0.0000 0.0000 1.4835 +0.0000 0.0000 1.4399 +0.0000 0.0000 1.3963 +0.0000 0.0000 1.3526 +0.0000 0.0000 1.3090 +0.0000 0.0000 1.2654 +0.0000 0.0000 1.2217 +0.0000 0.0000 1.1781 +primID: 0 +startangle_c: 5 +endpose_c: -1 2 5 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0022 0.0044 1.9635 +-0.0044 0.0089 1.9635 +-0.0067 0.0133 1.9635 +-0.0089 0.0178 1.9635 +-0.0111 0.0222 1.9635 +-0.0133 0.0267 1.9635 +-0.0156 0.0311 1.9635 +-0.0178 0.0356 1.9635 +-0.0200 0.0400 1.9635 +primID: 1 +startangle_c: 5 +endpose_c: -8 15 5 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0178 0.0333 1.9635 +-0.0356 0.0667 1.9635 +-0.0533 0.1000 1.9635 +-0.0711 0.1333 1.9635 +-0.0889 0.1667 1.9635 +-0.1067 0.2000 1.9635 +-0.1244 0.2333 1.9635 +-0.1422 0.2667 1.9635 +-0.1600 0.3000 1.9635 +primID: 2 +startangle_c: 5 +endpose_c: 1 -2 5 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0022 -0.0044 1.9635 +0.0044 -0.0089 1.9635 +0.0067 -0.0133 1.9635 +0.0089 -0.0178 1.9635 +0.0111 -0.0222 1.9635 +0.0133 -0.0267 1.9635 +0.0156 -0.0311 1.9635 +0.0178 -0.0356 1.9635 +0.0200 -0.0400 1.9635 +primID: 3 +startangle_c: 5 +endpose_c: -10 12 6 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0188 0.0285 1.9918 +-0.0385 0.0566 2.0200 +-0.0590 0.0842 2.0483 +-0.0804 0.1115 2.0765 +-0.1027 0.1382 2.1048 +-0.1258 0.1645 2.1330 +-0.1497 0.1902 2.1613 +-0.1745 0.2154 2.1896 +-0.2000 0.2400 2.2178 +primID: 4 +startangle_c: 5 +endpose_c: -5 18 4 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0160 0.0387 1.9635 +-0.0320 0.0774 1.9635 +-0.0481 0.1161 1.9635 +-0.0636 0.1549 1.9220 +-0.0766 0.1947 1.8517 +-0.0868 0.2353 1.7815 +-0.0941 0.2765 1.7113 +-0.0985 0.3182 1.6410 +-0.1000 0.3600 1.5708 +primID: 5 +startangle_c: 5 +endpose_c: 0 0 6 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0000 0.0000 2.0071 +0.0000 0.0000 2.0508 +0.0000 0.0000 2.0944 +0.0000 0.0000 2.1380 +0.0000 0.0000 2.1817 +0.0000 0.0000 2.2253 +0.0000 0.0000 2.2689 +0.0000 0.0000 2.3126 +0.0000 0.0000 2.3562 +primID: 6 +startangle_c: 5 +endpose_c: 0 0 4 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0000 0.0000 1.9199 +0.0000 0.0000 1.8762 +0.0000 0.0000 1.8326 +0.0000 0.0000 1.7890 +0.0000 0.0000 1.7453 +0.0000 0.0000 1.7017 +0.0000 0.0000 1.6581 +0.0000 0.0000 1.6144 +0.0000 0.0000 1.5708 +primID: 0 +startangle_c: 6 +endpose_c: -1 1 6 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0022 0.0022 2.3562 +-0.0044 0.0044 2.3562 +-0.0067 0.0067 2.3562 +-0.0089 0.0089 2.3562 +-0.0111 0.0111 2.3562 +-0.0133 0.0133 2.3562 +-0.0156 0.0156 2.3562 +-0.0178 0.0178 2.3562 +-0.0200 0.0200 2.3562 +primID: 1 +startangle_c: 6 +endpose_c: -15 15 6 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0333 0.0333 2.3562 +-0.0667 0.0667 2.3562 +-0.1000 0.1000 2.3562 +-0.1333 0.1333 2.3562 +-0.1667 0.1667 2.3562 +-0.2000 0.2000 2.3562 +-0.2333 0.2333 2.3562 +-0.2667 0.2667 2.3562 +-0.3000 0.3000 2.3562 +primID: 2 +startangle_c: 6 +endpose_c: 1 -1 6 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0022 -0.0022 2.3562 +0.0044 -0.0044 2.3562 +0.0067 -0.0067 2.3562 +0.0089 -0.0089 2.3562 +0.0111 -0.0111 2.3562 +0.0133 -0.0133 2.3562 +0.0156 -0.0156 2.3562 +0.0178 -0.0178 2.3562 +0.0200 -0.0200 2.3562 +primID: 3 +startangle_c: 6 +endpose_c: -18 12 7 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0350 0.0334 2.3996 +-0.0714 0.0652 2.4430 +-0.1092 0.0954 2.4864 +-0.1482 0.1240 2.5298 +-0.1885 0.1508 2.5732 +-0.2299 0.1759 2.6166 +-0.2723 0.1991 2.6600 +-0.3157 0.2205 2.7034 +-0.3600 0.2400 2.7468 +primID: 4 +startangle_c: 6 +endpose_c: -12 18 5 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0334 0.0350 2.3128 +-0.0652 0.0714 2.2694 +-0.0954 0.1092 2.2260 +-0.1240 0.1482 2.1826 +-0.1508 0.1885 2.1392 +-0.1759 0.2299 2.0958 +-0.1991 0.2723 2.0524 +-0.2205 0.3157 2.0090 +-0.2400 0.3600 1.9656 +primID: 5 +startangle_c: 6 +endpose_c: 0 0 7 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0000 0.0000 2.3998 +0.0000 0.0000 2.4435 +0.0000 0.0000 2.4871 +0.0000 0.0000 2.5307 +0.0000 0.0000 2.5744 +0.0000 0.0000 2.6180 +0.0000 0.0000 2.6616 +0.0000 0.0000 2.7053 +0.0000 0.0000 2.7489 +primID: 6 +startangle_c: 6 +endpose_c: 0 0 5 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0000 0.0000 2.3126 +0.0000 0.0000 2.2689 +0.0000 0.0000 2.2253 +0.0000 0.0000 2.1817 +0.0000 0.0000 2.1380 +0.0000 0.0000 2.0944 +0.0000 0.0000 2.0508 +0.0000 0.0000 2.0071 +0.0000 0.0000 1.9635 +primID: 0 +startangle_c: 7 +endpose_c: -2 1 7 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0044 0.0022 2.7489 +-0.0089 0.0044 2.7489 +-0.0133 0.0067 2.7489 +-0.0178 0.0089 2.7489 +-0.0222 0.0111 2.7489 +-0.0267 0.0133 2.7489 +-0.0311 0.0156 2.7489 +-0.0356 0.0178 2.7489 +-0.0400 0.0200 2.7489 +primID: 1 +startangle_c: 7 +endpose_c: -15 8 7 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0333 0.0178 2.7489 +-0.0667 0.0356 2.7489 +-0.1000 0.0533 2.7489 +-0.1333 0.0711 2.7489 +-0.1667 0.0889 2.7489 +-0.2000 0.1067 2.7489 +-0.2333 0.1244 2.7489 +-0.2667 0.1422 2.7489 +-0.3000 0.1600 2.7489 +primID: 2 +startangle_c: 7 +endpose_c: 2 -1 7 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0044 -0.0022 2.7489 +0.0089 -0.0044 2.7489 +0.0133 -0.0067 2.7489 +0.0178 -0.0089 2.7489 +0.0222 -0.0111 2.7489 +0.0267 -0.0133 2.7489 +0.0311 -0.0156 2.7489 +0.0356 -0.0178 2.7489 +0.0400 -0.0200 2.7489 +primID: 3 +startangle_c: 7 +endpose_c: -12 10 6 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0285 0.0188 2.7206 +-0.0566 0.0385 2.6924 +-0.0842 0.0590 2.6641 +-0.1115 0.0804 2.6359 +-0.1382 0.1027 2.6076 +-0.1645 0.1258 2.5793 +-0.1902 0.1497 2.5511 +-0.2154 0.1745 2.5228 +-0.2400 0.2000 2.4946 +primID: 4 +startangle_c: 7 +endpose_c: -18 5 8 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0387 0.0160 2.7489 +-0.0774 0.0320 2.7489 +-0.1161 0.0481 2.7489 +-0.1549 0.0636 2.7904 +-0.1947 0.0766 2.8606 +-0.2353 0.0868 2.9309 +-0.2765 0.0941 3.0011 +-0.3182 0.0985 3.0714 +-0.3600 0.1000 3.1416 +primID: 5 +startangle_c: 7 +endpose_c: 0 0 6 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0000 0.0000 2.7053 +0.0000 0.0000 2.6616 +0.0000 0.0000 2.6180 +0.0000 0.0000 2.5744 +0.0000 0.0000 2.5307 +0.0000 0.0000 2.4871 +0.0000 0.0000 2.4435 +0.0000 0.0000 2.3998 +0.0000 0.0000 2.3562 +primID: 6 +startangle_c: 7 +endpose_c: 0 0 8 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0000 0.0000 2.7925 +0.0000 0.0000 2.8362 +0.0000 0.0000 2.8798 +0.0000 0.0000 2.9234 +0.0000 0.0000 2.9671 +0.0000 0.0000 3.0107 +0.0000 0.0000 3.0543 +0.0000 0.0000 3.0980 +0.0000 0.0000 3.1416 +primID: 0 +startangle_c: 8 +endpose_c: -1 0 8 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0022 0.0000 3.1416 +-0.0044 0.0000 3.1416 +-0.0067 0.0000 3.1416 +-0.0089 0.0000 3.1416 +-0.0111 0.0000 3.1416 +-0.0133 0.0000 3.1416 +-0.0156 0.0000 3.1416 +-0.0178 0.0000 3.1416 +-0.0200 0.0000 3.1416 +primID: 1 +startangle_c: 8 +endpose_c: -20 0 8 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0444 0.0000 3.1416 +-0.0889 0.0000 3.1416 +-0.1333 0.0000 3.1416 +-0.1778 0.0000 3.1416 +-0.2222 0.0000 3.1416 +-0.2667 0.0000 3.1416 +-0.3111 0.0000 3.1416 +-0.3556 0.0000 3.1416 +-0.4000 0.0000 3.1416 +primID: 2 +startangle_c: 8 +endpose_c: 1 0 8 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0022 0.0000 3.1416 +0.0044 0.0000 3.1416 +0.0067 0.0000 3.1416 +0.0089 0.0000 3.1416 +0.0111 0.0000 3.1416 +0.0133 0.0000 3.1416 +0.0156 0.0000 3.1416 +0.0178 0.0000 3.1416 +0.0200 0.0000 3.1416 +primID: 3 +startangle_c: 8 +endpose_c: -15 -3 9 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0342 -0.0008 3.1850 +-0.0683 -0.0031 3.2284 +-0.1023 -0.0069 3.2718 +-0.1361 -0.0121 3.3152 +-0.1696 -0.0188 3.3586 +-0.2029 -0.0270 3.4020 +-0.2357 -0.0366 3.4454 +-0.2681 -0.0476 3.4888 +-0.3000 -0.0600 3.5322 +primID: 4 +startangle_c: 8 +endpose_c: -15 3 7 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0342 0.0008 3.0982 +-0.0683 0.0031 3.0548 +-0.1023 0.0069 3.0114 +-0.1361 0.0121 2.9680 +-0.1696 0.0188 2.9246 +-0.2029 0.0270 2.8812 +-0.2357 0.0366 2.8378 +-0.2681 0.0476 2.7944 +-0.3000 0.0600 2.7510 +primID: 5 +startangle_c: 8 +endpose_c: 0 0 9 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0000 0.0000 3.1852 +0.0000 0.0000 3.2289 +0.0000 0.0000 3.2725 +0.0000 0.0000 3.3161 +0.0000 0.0000 3.3598 +0.0000 0.0000 3.4034 +0.0000 0.0000 3.4470 +0.0000 0.0000 3.4907 +0.0000 0.0000 3.5343 +primID: 6 +startangle_c: 8 +endpose_c: 0 0 7 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0000 0.0000 3.0980 +0.0000 0.0000 3.0543 +0.0000 0.0000 3.0107 +0.0000 0.0000 2.9671 +0.0000 0.0000 2.9234 +0.0000 0.0000 2.8798 +0.0000 0.0000 2.8362 +0.0000 0.0000 2.7925 +0.0000 0.0000 2.7489 +primID: 0 +startangle_c: 9 +endpose_c: -2 -1 9 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0044 -0.0022 3.5343 +-0.0089 -0.0044 3.5343 +-0.0133 -0.0067 3.5343 +-0.0178 -0.0089 3.5343 +-0.0222 -0.0111 3.5343 +-0.0267 -0.0133 3.5343 +-0.0311 -0.0156 3.5343 +-0.0356 -0.0178 3.5343 +-0.0400 -0.0200 3.5343 +primID: 1 +startangle_c: 9 +endpose_c: -15 -8 9 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0333 -0.0178 3.5343 +-0.0667 -0.0356 3.5343 +-0.1000 -0.0533 3.5343 +-0.1333 -0.0711 3.5343 +-0.1667 -0.0889 3.5343 +-0.2000 -0.1067 3.5343 +-0.2333 -0.1244 3.5343 +-0.2667 -0.1422 3.5343 +-0.3000 -0.1600 3.5343 +primID: 2 +startangle_c: 9 +endpose_c: 2 1 9 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0044 0.0022 3.5343 +0.0089 0.0044 3.5343 +0.0133 0.0067 3.5343 +0.0178 0.0089 3.5343 +0.0222 0.0111 3.5343 +0.0267 0.0133 3.5343 +0.0311 0.0156 3.5343 +0.0356 0.0178 3.5343 +0.0400 0.0200 3.5343 +primID: 3 +startangle_c: 9 +endpose_c: -12 -10 10 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0285 -0.0188 3.5626 +-0.0566 -0.0385 3.5908 +-0.0842 -0.0590 3.6191 +-0.1115 -0.0804 3.6473 +-0.1382 -0.1027 3.6756 +-0.1645 -0.1258 3.7038 +-0.1902 -0.1497 3.7321 +-0.2154 -0.1745 3.7604 +-0.2400 -0.2000 3.7886 +primID: 4 +startangle_c: 9 +endpose_c: -18 -5 8 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0387 -0.0160 3.5343 +-0.0774 -0.0320 3.5343 +-0.1161 -0.0481 3.5343 +-0.1549 -0.0636 3.4928 +-0.1947 -0.0766 3.4225 +-0.2353 -0.0868 3.3523 +-0.2765 -0.0941 3.2821 +-0.3182 -0.0985 3.2118 +-0.3600 -0.1000 3.1416 +primID: 5 +startangle_c: 9 +endpose_c: 0 0 10 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0000 0.0000 3.5779 +0.0000 0.0000 3.6216 +0.0000 0.0000 3.6652 +0.0000 0.0000 3.7088 +0.0000 0.0000 3.7525 +0.0000 0.0000 3.7961 +0.0000 0.0000 3.8397 +0.0000 0.0000 3.8834 +0.0000 0.0000 3.9270 +primID: 6 +startangle_c: 9 +endpose_c: 0 0 8 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0000 0.0000 3.4907 +0.0000 0.0000 3.4470 +0.0000 0.0000 3.4034 +0.0000 0.0000 3.3598 +0.0000 0.0000 3.3161 +0.0000 0.0000 3.2725 +0.0000 0.0000 3.2289 +0.0000 0.0000 3.1852 +0.0000 0.0000 3.1416 +primID: 0 +startangle_c: 10 +endpose_c: -1 -1 10 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0022 -0.0022 3.9270 +-0.0044 -0.0044 3.9270 +-0.0067 -0.0067 3.9270 +-0.0089 -0.0089 3.9270 +-0.0111 -0.0111 3.9270 +-0.0133 -0.0133 3.9270 +-0.0156 -0.0156 3.9270 +-0.0178 -0.0178 3.9270 +-0.0200 -0.0200 3.9270 +primID: 1 +startangle_c: 10 +endpose_c: -15 -15 10 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0333 -0.0333 3.9270 +-0.0667 -0.0667 3.9270 +-0.1000 -0.1000 3.9270 +-0.1333 -0.1333 3.9270 +-0.1667 -0.1667 3.9270 +-0.2000 -0.2000 3.9270 +-0.2333 -0.2333 3.9270 +-0.2667 -0.2667 3.9270 +-0.3000 -0.3000 3.9270 +primID: 2 +startangle_c: 10 +endpose_c: 1 1 10 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0022 0.0022 3.9270 +0.0044 0.0044 3.9270 +0.0067 0.0067 3.9270 +0.0089 0.0089 3.9270 +0.0111 0.0111 3.9270 +0.0133 0.0133 3.9270 +0.0156 0.0156 3.9270 +0.0178 0.0178 3.9270 +0.0200 0.0200 3.9270 +primID: 3 +startangle_c: 10 +endpose_c: -12 -18 11 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0334 -0.0350 3.9704 +-0.0652 -0.0714 4.0138 +-0.0954 -0.1092 4.0572 +-0.1240 -0.1482 4.1006 +-0.1508 -0.1885 4.1440 +-0.1759 -0.2299 4.1874 +-0.1991 -0.2723 4.2308 +-0.2205 -0.3157 4.2742 +-0.2400 -0.3600 4.3176 +primID: 4 +startangle_c: 10 +endpose_c: -18 -12 9 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0350 -0.0334 3.8836 +-0.0714 -0.0652 3.8402 +-0.1092 -0.0954 3.7968 +-0.1482 -0.1240 3.7534 +-0.1885 -0.1508 3.7100 +-0.2299 -0.1759 3.6666 +-0.2723 -0.1991 3.6232 +-0.3157 -0.2205 3.5798 +-0.3600 -0.2400 3.5364 +primID: 5 +startangle_c: 10 +endpose_c: 0 0 11 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.9706 +0.0000 0.0000 4.0143 +0.0000 0.0000 4.0579 +0.0000 0.0000 4.1015 +0.0000 0.0000 4.1452 +0.0000 0.0000 4.1888 +0.0000 0.0000 4.2324 +0.0000 0.0000 4.2761 +0.0000 0.0000 4.3197 +primID: 6 +startangle_c: 10 +endpose_c: 0 0 9 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.8834 +0.0000 0.0000 3.8397 +0.0000 0.0000 3.7961 +0.0000 0.0000 3.7525 +0.0000 0.0000 3.7088 +0.0000 0.0000 3.6652 +0.0000 0.0000 3.6216 +0.0000 0.0000 3.5779 +0.0000 0.0000 3.5343 +primID: 0 +startangle_c: 11 +endpose_c: -1 -2 11 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0022 -0.0044 4.3197 +-0.0044 -0.0089 4.3197 +-0.0067 -0.0133 4.3197 +-0.0089 -0.0178 4.3197 +-0.0111 -0.0222 4.3197 +-0.0133 -0.0267 4.3197 +-0.0156 -0.0311 4.3197 +-0.0178 -0.0356 4.3197 +-0.0200 -0.0400 4.3197 +primID: 1 +startangle_c: 11 +endpose_c: -8 -15 11 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0178 -0.0333 4.3197 +-0.0356 -0.0667 4.3197 +-0.0533 -0.1000 4.3197 +-0.0711 -0.1333 4.3197 +-0.0889 -0.1667 4.3197 +-0.1067 -0.2000 4.3197 +-0.1244 -0.2333 4.3197 +-0.1422 -0.2667 4.3197 +-0.1600 -0.3000 4.3197 +primID: 2 +startangle_c: 11 +endpose_c: 1 2 11 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0022 0.0044 4.3197 +0.0044 0.0089 4.3197 +0.0067 0.0133 4.3197 +0.0089 0.0178 4.3197 +0.0111 0.0222 4.3197 +0.0133 0.0267 4.3197 +0.0156 0.0311 4.3197 +0.0178 0.0356 4.3197 +0.0200 0.0400 4.3197 +primID: 3 +startangle_c: 11 +endpose_c: -10 -12 10 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0188 -0.0285 4.2914 +-0.0385 -0.0566 4.2632 +-0.0590 -0.0842 4.2349 +-0.0804 -0.1115 4.2067 +-0.1027 -0.1382 4.1784 +-0.1258 -0.1645 4.1501 +-0.1497 -0.1902 4.1219 +-0.1745 -0.2154 4.0936 +-0.2000 -0.2400 4.0654 +primID: 4 +startangle_c: 11 +endpose_c: -5 -18 12 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0160 -0.0387 4.3197 +-0.0320 -0.0774 4.3197 +-0.0481 -0.1161 4.3197 +-0.0636 -0.1549 4.3612 +-0.0766 -0.1947 4.4314 +-0.0868 -0.2353 4.5017 +-0.0941 -0.2765 4.5719 +-0.0985 -0.3182 4.6422 +-0.1000 -0.3600 4.7124 +primID: 5 +startangle_c: 11 +endpose_c: 0 0 10 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0000 0.0000 4.2761 +0.0000 0.0000 4.2324 +0.0000 0.0000 4.1888 +0.0000 0.0000 4.1452 +0.0000 0.0000 4.1015 +0.0000 0.0000 4.0579 +0.0000 0.0000 4.0143 +0.0000 0.0000 3.9706 +0.0000 0.0000 3.9270 +primID: 6 +startangle_c: 11 +endpose_c: 0 0 12 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0000 0.0000 4.3633 +0.0000 0.0000 4.4070 +0.0000 0.0000 4.4506 +0.0000 0.0000 4.4942 +0.0000 0.0000 4.5379 +0.0000 0.0000 4.5815 +0.0000 0.0000 4.6251 +0.0000 0.0000 4.6688 +0.0000 0.0000 4.7124 +primID: 0 +startangle_c: 12 +endpose_c: 0 -1 12 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0022 4.7124 +0.0000 -0.0044 4.7124 +0.0000 -0.0067 4.7124 +0.0000 -0.0089 4.7124 +0.0000 -0.0111 4.7124 +0.0000 -0.0133 4.7124 +0.0000 -0.0156 4.7124 +0.0000 -0.0178 4.7124 +0.0000 -0.0200 4.7124 +primID: 1 +startangle_c: 12 +endpose_c: 0 -20 12 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0444 4.7124 +0.0000 -0.0889 4.7124 +0.0000 -0.1333 4.7124 +0.0000 -0.1778 4.7124 +0.0000 -0.2222 4.7124 +0.0000 -0.2667 4.7124 +0.0000 -0.3111 4.7124 +0.0000 -0.3556 4.7124 +0.0000 -0.4000 4.7124 +primID: 2 +startangle_c: 12 +endpose_c: 0 1 12 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0022 4.7124 +0.0000 0.0044 4.7124 +0.0000 0.0067 4.7124 +0.0000 0.0089 4.7124 +0.0000 0.0111 4.7124 +0.0000 0.0133 4.7124 +0.0000 0.0156 4.7124 +0.0000 0.0178 4.7124 +0.0000 0.0200 4.7124 +primID: 3 +startangle_c: 12 +endpose_c: 3 -15 13 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0008 -0.0342 4.7558 +0.0031 -0.0683 4.7992 +0.0069 -0.1023 4.8426 +0.0121 -0.1361 4.8860 +0.0188 -0.1696 4.9294 +0.0270 -0.2029 4.9728 +0.0366 -0.2357 5.0162 +0.0476 -0.2681 5.0596 +0.0600 -0.3000 5.1030 +primID: 4 +startangle_c: 12 +endpose_c: -3 -15 11 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.7124 +-0.0008 -0.0342 4.6690 +-0.0031 -0.0683 4.6256 +-0.0069 -0.1023 4.5822 +-0.0121 -0.1361 4.5388 +-0.0188 -0.1696 4.4954 +-0.0270 -0.2029 4.4520 +-0.0366 -0.2357 4.4086 +-0.0476 -0.2681 4.3652 +-0.0600 -0.3000 4.3218 +primID: 5 +startangle_c: 12 +endpose_c: 0 0 13 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0000 4.7560 +0.0000 0.0000 4.7997 +0.0000 0.0000 4.8433 +0.0000 0.0000 4.8869 +0.0000 0.0000 4.9306 +0.0000 0.0000 4.9742 +0.0000 0.0000 5.0178 +0.0000 0.0000 5.0615 +0.0000 0.0000 5.1051 +primID: 6 +startangle_c: 12 +endpose_c: 0 0 11 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0000 4.6688 +0.0000 0.0000 4.6251 +0.0000 0.0000 4.5815 +0.0000 0.0000 4.5379 +0.0000 0.0000 4.4942 +0.0000 0.0000 4.4506 +0.0000 0.0000 4.4070 +0.0000 0.0000 4.3633 +0.0000 0.0000 4.3197 +primID: 0 +startangle_c: 13 +endpose_c: 1 -2 13 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0022 -0.0044 5.1051 +0.0044 -0.0089 5.1051 +0.0067 -0.0133 5.1051 +0.0089 -0.0178 5.1051 +0.0111 -0.0222 5.1051 +0.0133 -0.0267 5.1051 +0.0156 -0.0311 5.1051 +0.0178 -0.0356 5.1051 +0.0200 -0.0400 5.1051 +primID: 1 +startangle_c: 13 +endpose_c: 8 -15 13 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0178 -0.0333 5.1051 +0.0356 -0.0667 5.1051 +0.0533 -0.1000 5.1051 +0.0711 -0.1333 5.1051 +0.0889 -0.1667 5.1051 +0.1067 -0.2000 5.1051 +0.1244 -0.2333 5.1051 +0.1422 -0.2667 5.1051 +0.1600 -0.3000 5.1051 +primID: 2 +startangle_c: 13 +endpose_c: -1 2 13 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.1051 +-0.0022 0.0044 5.1051 +-0.0044 0.0089 5.1051 +-0.0067 0.0133 5.1051 +-0.0089 0.0178 5.1051 +-0.0111 0.0222 5.1051 +-0.0133 0.0267 5.1051 +-0.0156 0.0311 5.1051 +-0.0178 0.0356 5.1051 +-0.0200 0.0400 5.1051 +primID: 3 +startangle_c: 13 +endpose_c: 10 -12 14 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0188 -0.0285 5.1333 +0.0385 -0.0566 5.1616 +0.0590 -0.0842 5.1899 +0.0804 -0.1115 5.2181 +0.1027 -0.1382 5.2464 +0.1258 -0.1645 5.2746 +0.1497 -0.1902 5.3029 +0.1745 -0.2154 5.3312 +0.2000 -0.2400 5.3594 +primID: 4 +startangle_c: 13 +endpose_c: 5 -18 12 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0160 -0.0387 5.1051 +0.0320 -0.0774 5.1051 +0.0481 -0.1161 5.1051 +0.0636 -0.1549 5.0636 +0.0766 -0.1947 4.9933 +0.0868 -0.2353 4.9231 +0.0941 -0.2765 4.8529 +0.0985 -0.3182 4.7826 +0.1000 -0.3600 4.7124 +primID: 5 +startangle_c: 13 +endpose_c: 0 0 14 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0000 0.0000 5.1487 +0.0000 0.0000 5.1924 +0.0000 0.0000 5.2360 +0.0000 0.0000 5.2796 +0.0000 0.0000 5.3233 +0.0000 0.0000 5.3669 +0.0000 0.0000 5.4105 +0.0000 0.0000 5.4542 +0.0000 0.0000 5.4978 +primID: 6 +startangle_c: 13 +endpose_c: 0 0 12 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0000 0.0000 5.0615 +0.0000 0.0000 5.0178 +0.0000 0.0000 4.9742 +0.0000 0.0000 4.9306 +0.0000 0.0000 4.8869 +0.0000 0.0000 4.8433 +0.0000 0.0000 4.7997 +0.0000 0.0000 4.7560 +0.0000 0.0000 4.7124 +primID: 0 +startangle_c: 14 +endpose_c: 1 -1 14 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0022 -0.0022 5.4978 +0.0044 -0.0044 5.4978 +0.0067 -0.0067 5.4978 +0.0089 -0.0089 5.4978 +0.0111 -0.0111 5.4978 +0.0133 -0.0133 5.4978 +0.0156 -0.0156 5.4978 +0.0178 -0.0178 5.4978 +0.0200 -0.0200 5.4978 +primID: 1 +startangle_c: 14 +endpose_c: 15 -15 14 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0333 -0.0333 5.4978 +0.0667 -0.0667 5.4978 +0.1000 -0.1000 5.4978 +0.1333 -0.1333 5.4978 +0.1667 -0.1667 5.4978 +0.2000 -0.2000 5.4978 +0.2333 -0.2333 5.4978 +0.2667 -0.2667 5.4978 +0.3000 -0.3000 5.4978 +primID: 2 +startangle_c: 14 +endpose_c: -1 1 14 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.4978 +-0.0022 0.0022 5.4978 +-0.0044 0.0044 5.4978 +-0.0067 0.0067 5.4978 +-0.0089 0.0089 5.4978 +-0.0111 0.0111 5.4978 +-0.0133 0.0133 5.4978 +-0.0156 0.0156 5.4978 +-0.0178 0.0178 5.4978 +-0.0200 0.0200 5.4978 +primID: 3 +startangle_c: 14 +endpose_c: 18 -12 15 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0350 -0.0334 5.5412 +0.0714 -0.0652 5.5846 +0.1092 -0.0954 5.6280 +0.1482 -0.1240 5.6714 +0.1885 -0.1508 5.7148 +0.2299 -0.1759 5.7582 +0.2723 -0.1991 5.8016 +0.3157 -0.2205 5.8450 +0.3600 -0.2400 5.8884 +primID: 4 +startangle_c: 14 +endpose_c: 12 -18 13 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0334 -0.0350 5.4544 +0.0652 -0.0714 5.4110 +0.0954 -0.1092 5.3676 +0.1240 -0.1482 5.3242 +0.1508 -0.1885 5.2808 +0.1759 -0.2299 5.2374 +0.1991 -0.2723 5.1940 +0.2205 -0.3157 5.1506 +0.2400 -0.3600 5.1072 +primID: 5 +startangle_c: 14 +endpose_c: 0 0 15 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0000 0.0000 5.5414 +0.0000 0.0000 5.5851 +0.0000 0.0000 5.6287 +0.0000 0.0000 5.6723 +0.0000 0.0000 5.7160 +0.0000 0.0000 5.7596 +0.0000 0.0000 5.8032 +0.0000 0.0000 5.8469 +0.0000 0.0000 5.8905 +primID: 6 +startangle_c: 14 +endpose_c: 0 0 13 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0000 0.0000 5.4542 +0.0000 0.0000 5.4105 +0.0000 0.0000 5.3669 +0.0000 0.0000 5.3233 +0.0000 0.0000 5.2796 +0.0000 0.0000 5.2360 +0.0000 0.0000 5.1924 +0.0000 0.0000 5.1487 +0.0000 0.0000 5.1051 +primID: 0 +startangle_c: 15 +endpose_c: 2 -1 15 +additionalactioncostmult: 10 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0044 -0.0022 5.8905 +0.0089 -0.0044 5.8905 +0.0133 -0.0067 5.8905 +0.0178 -0.0089 5.8905 +0.0222 -0.0111 5.8905 +0.0267 -0.0133 5.8905 +0.0311 -0.0156 5.8905 +0.0356 -0.0178 5.8905 +0.0400 -0.0200 5.8905 +primID: 1 +startangle_c: 15 +endpose_c: 15 -8 15 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0333 -0.0178 5.8905 +0.0667 -0.0356 5.8905 +0.1000 -0.0533 5.8905 +0.1333 -0.0711 5.8905 +0.1667 -0.0889 5.8905 +0.2000 -0.1067 5.8905 +0.2333 -0.1244 5.8905 +0.2667 -0.1422 5.8905 +0.3000 -0.1600 5.8905 +primID: 2 +startangle_c: 15 +endpose_c: -2 1 15 +additionalactioncostmult: 50 +intermediateposes: 10 +0.0000 0.0000 5.8905 +-0.0044 0.0022 5.8905 +-0.0089 0.0044 5.8905 +-0.0133 0.0067 5.8905 +-0.0178 0.0089 5.8905 +-0.0222 0.0111 5.8905 +-0.0267 0.0133 5.8905 +-0.0311 0.0156 5.8905 +-0.0356 0.0178 5.8905 +-0.0400 0.0200 5.8905 +primID: 3 +startangle_c: 15 +endpose_c: 12 -10 14 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0285 -0.0188 5.8622 +0.0566 -0.0385 5.8340 +0.0842 -0.0590 5.8057 +0.1115 -0.0804 5.7775 +0.1382 -0.1027 5.7492 +0.1645 -0.1258 5.7209 +0.1902 -0.1497 5.6927 +0.2154 -0.1745 5.6644 +0.2400 -0.2000 5.6362 +primID: 4 +startangle_c: 15 +endpose_c: 18 -5 0 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0387 -0.0160 5.8905 +0.0774 -0.0320 5.8905 +0.1161 -0.0481 5.8905 +0.1549 -0.0636 5.9320 +0.1947 -0.0766 6.0022 +0.2353 -0.0868 6.0725 +0.2765 -0.0941 6.1427 +0.3182 -0.0985 6.2129 +0.3600 -0.1000 6.2832 +primID: 5 +startangle_c: 15 +endpose_c: 0 0 14 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0000 0.0000 5.8469 +0.0000 0.0000 5.8032 +0.0000 0.0000 5.7596 +0.0000 0.0000 5.7160 +0.0000 0.0000 5.6723 +0.0000 0.0000 5.6287 +0.0000 0.0000 5.5851 +0.0000 0.0000 5.5414 +0.0000 0.0000 5.4978 +primID: 6 +startangle_c: 15 +endpose_c: 0 0 0 +additionalactioncostmult: 100 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0000 0.0000 5.2360 +0.0000 0.0000 4.5815 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.2725 +0.0000 0.0000 2.6180 +0.0000 0.0000 1.9635 +0.0000 0.0000 1.3090 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.0000 diff --git a/navigations/sbpl_lattice_planner/matlab/mprim/unicycle_highcost_5cm.mprim b/navigations/sbpl_lattice_planner/matlab/mprim/unicycle_highcost_5cm.mprim new file mode 100755 index 0000000..bff2688 --- /dev/null +++ b/navigations/sbpl_lattice_planner/matlab/mprim/unicycle_highcost_5cm.mprim @@ -0,0 +1,1683 @@ +resolution_m: 0.050000 +numberofangles: 16 +totalnumberofprimitives: 112 +primID: 0 +startangle_c: 0 +endpose_c: 1 0 0 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0056 0.0000 0.0000 +0.0111 0.0000 0.0000 +0.0167 0.0000 0.0000 +0.0222 0.0000 0.0000 +0.0278 0.0000 0.0000 +0.0333 0.0000 0.0000 +0.0389 0.0000 0.0000 +0.0444 0.0000 0.0000 +0.0500 0.0000 0.0000 +primID: 1 +startangle_c: 0 +endpose_c: 8 0 0 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0444 0.0000 0.0000 +0.0889 0.0000 0.0000 +0.1333 0.0000 0.0000 +0.1778 0.0000 0.0000 +0.2222 0.0000 0.0000 +0.2667 0.0000 0.0000 +0.3111 0.0000 0.0000 +0.3556 0.0000 0.0000 +0.4000 0.0000 0.0000 +primID: 2 +startangle_c: 0 +endpose_c: -1 0 0 +additionalactioncostmult: 40 +intermediateposes: 10 +0.0000 0.0000 0.0000 +-0.0056 0.0000 0.0000 +-0.0111 0.0000 0.0000 +-0.0167 0.0000 0.0000 +-0.0222 0.0000 0.0000 +-0.0278 0.0000 0.0000 +-0.0333 0.0000 0.0000 +-0.0389 0.0000 0.0000 +-0.0444 0.0000 0.0000 +-0.0500 0.0000 0.0000 +primID: 3 +startangle_c: 0 +endpose_c: 8 1 1 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0452 -0.0000 0.0000 +0.0904 -0.0000 0.0000 +0.1355 -0.0000 0.0000 +0.1807 0.0008 0.0488 +0.2257 0.0045 0.1176 +0.2703 0.0114 0.1864 +0.3144 0.0213 0.2551 +0.3577 0.0342 0.3239 +0.4000 0.0500 0.3927 +primID: 4 +startangle_c: 0 +endpose_c: 8 -1 -1 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0452 0.0000 0.0000 +0.0904 0.0000 0.0000 +0.1355 0.0000 0.0000 +0.1807 -0.0008 -0.0488 +0.2257 -0.0045 -0.1176 +0.2703 -0.0114 -0.1864 +0.3144 -0.0213 -0.2551 +0.3577 -0.0342 -0.3239 +0.4000 -0.0500 -0.3927 +primID: 5 +startangle_c: 0 +endpose_c: 0 0 1 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0000 0.0000 0.0436 +0.0000 0.0000 0.0873 +0.0000 0.0000 0.1309 +0.0000 0.0000 0.1745 +0.0000 0.0000 0.2182 +0.0000 0.0000 0.2618 +0.0000 0.0000 0.3054 +0.0000 0.0000 0.3491 +0.0000 0.0000 0.3927 +primID: 6 +startangle_c: 0 +endpose_c: 0 0 -1 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.0000 +0.0000 0.0000 -0.0436 +0.0000 0.0000 -0.0873 +0.0000 0.0000 -0.1309 +0.0000 0.0000 -0.1745 +0.0000 0.0000 -0.2182 +0.0000 0.0000 -0.2618 +0.0000 0.0000 -0.3054 +0.0000 0.0000 -0.3491 +0.0000 0.0000 -0.3927 +primID: 0 +startangle_c: 1 +endpose_c: 2 1 1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0111 0.0056 0.3927 +0.0222 0.0111 0.3927 +0.0333 0.0167 0.3927 +0.0444 0.0222 0.3927 +0.0556 0.0278 0.3927 +0.0667 0.0333 0.3927 +0.0778 0.0389 0.3927 +0.0889 0.0444 0.3927 +0.1000 0.0500 0.3927 +primID: 1 +startangle_c: 1 +endpose_c: 6 3 1 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0333 0.0167 0.3927 +0.0667 0.0333 0.3927 +0.1000 0.0500 0.3927 +0.1333 0.0667 0.3927 +0.1667 0.0833 0.3927 +0.2000 0.1000 0.3927 +0.2333 0.1167 0.3927 +0.2667 0.1333 0.3927 +0.3000 0.1500 0.3927 +primID: 2 +startangle_c: 1 +endpose_c: -2 -1 1 +additionalactioncostmult: 40 +intermediateposes: 10 +0.0000 0.0000 0.3927 +-0.0111 -0.0056 0.3927 +-0.0222 -0.0111 0.3927 +-0.0333 -0.0167 0.3927 +-0.0444 -0.0222 0.3927 +-0.0556 -0.0278 0.3927 +-0.0667 -0.0333 0.3927 +-0.0778 -0.0389 0.3927 +-0.0889 -0.0444 0.3927 +-0.1000 -0.0500 0.3927 +primID: 3 +startangle_c: 1 +endpose_c: 5 4 2 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0298 0.0184 0.4230 +0.0592 0.0379 0.4533 +0.0881 0.0583 0.4836 +0.1165 0.0796 0.5139 +0.1444 0.1019 0.5442 +0.1717 0.1251 0.5745 +0.1984 0.1492 0.6048 +0.2245 0.1742 0.6351 +0.2500 0.2000 0.6654 +primID: 4 +startangle_c: 1 +endpose_c: 7 2 0 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0377 0.0156 0.3927 +0.0754 0.0312 0.3927 +0.1131 0.0468 0.3927 +0.1508 0.0623 0.3736 +0.1893 0.0758 0.2989 +0.2287 0.0863 0.2242 +0.2687 0.0939 0.1494 +0.3092 0.0985 0.0747 +0.3500 0.1000 -0.0000 +primID: 5 +startangle_c: 1 +endpose_c: 0 0 2 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0000 0.0000 0.4363 +0.0000 0.0000 0.4800 +0.0000 0.0000 0.5236 +0.0000 0.0000 0.5672 +0.0000 0.0000 0.6109 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.6981 +0.0000 0.0000 0.7418 +0.0000 0.0000 0.7854 +primID: 6 +startangle_c: 1 +endpose_c: 0 0 0 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.3927 +0.0000 0.0000 0.3491 +0.0000 0.0000 0.3054 +0.0000 0.0000 0.2618 +0.0000 0.0000 0.2182 +0.0000 0.0000 0.1745 +0.0000 0.0000 0.1309 +0.0000 0.0000 0.0873 +0.0000 0.0000 0.0436 +0.0000 0.0000 0.0000 +primID: 0 +startangle_c: 2 +endpose_c: 1 1 2 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0056 0.0056 0.7854 +0.0111 0.0111 0.7854 +0.0167 0.0167 0.7854 +0.0222 0.0222 0.7854 +0.0278 0.0278 0.7854 +0.0333 0.0333 0.7854 +0.0389 0.0389 0.7854 +0.0444 0.0444 0.7854 +0.0500 0.0500 0.7854 +primID: 1 +startangle_c: 2 +endpose_c: 6 6 2 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0333 0.0333 0.7854 +0.0667 0.0667 0.7854 +0.1000 0.1000 0.7854 +0.1333 0.1333 0.7854 +0.1667 0.1667 0.7854 +0.2000 0.2000 0.7854 +0.2333 0.2333 0.7854 +0.2667 0.2667 0.7854 +0.3000 0.3000 0.7854 +primID: 2 +startangle_c: 2 +endpose_c: -1 -1 2 +additionalactioncostmult: 40 +intermediateposes: 10 +0.0000 0.0000 0.7854 +-0.0056 -0.0056 0.7854 +-0.0111 -0.0111 0.7854 +-0.0167 -0.0167 0.7854 +-0.0222 -0.0222 0.7854 +-0.0278 -0.0278 0.7854 +-0.0333 -0.0333 0.7854 +-0.0389 -0.0389 0.7854 +-0.0444 -0.0444 0.7854 +-0.0500 -0.0500 0.7854 +primID: 3 +startangle_c: 2 +endpose_c: 5 7 3 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0341 0.0341 0.7854 +0.0678 0.0684 0.8151 +0.1000 0.1043 0.8669 +0.1302 0.1418 0.9188 +0.1584 0.1809 0.9707 +0.1846 0.2213 1.0225 +0.2086 0.2631 1.0744 +0.2304 0.3060 1.1262 +0.2500 0.3500 1.1781 +primID: 4 +startangle_c: 2 +endpose_c: 7 5 1 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0341 0.0341 0.7854 +0.0684 0.0678 0.7557 +0.1043 0.1000 0.7039 +0.1418 0.1302 0.6520 +0.1809 0.1584 0.6001 +0.2213 0.1846 0.5483 +0.2631 0.2086 0.4964 +0.3060 0.2304 0.4446 +0.3500 0.2500 0.3927 +primID: 5 +startangle_c: 2 +endpose_c: 0 0 3 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0000 0.0000 0.8290 +0.0000 0.0000 0.8727 +0.0000 0.0000 0.9163 +0.0000 0.0000 0.9599 +0.0000 0.0000 1.0036 +0.0000 0.0000 1.0472 +0.0000 0.0000 1.0908 +0.0000 0.0000 1.1345 +0.0000 0.0000 1.1781 +primID: 6 +startangle_c: 2 +endpose_c: 0 0 1 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 0.7854 +0.0000 0.0000 0.7418 +0.0000 0.0000 0.6981 +0.0000 0.0000 0.6545 +0.0000 0.0000 0.6109 +0.0000 0.0000 0.5672 +0.0000 0.0000 0.5236 +0.0000 0.0000 0.4800 +0.0000 0.0000 0.4363 +0.0000 0.0000 0.3927 +primID: 0 +startangle_c: 3 +endpose_c: 1 2 3 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0056 0.0111 1.1781 +0.0111 0.0222 1.1781 +0.0167 0.0333 1.1781 +0.0222 0.0444 1.1781 +0.0278 0.0556 1.1781 +0.0333 0.0667 1.1781 +0.0389 0.0778 1.1781 +0.0444 0.0889 1.1781 +0.0500 0.1000 1.1781 +primID: 1 +startangle_c: 3 +endpose_c: 3 6 3 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0167 0.0333 1.1781 +0.0333 0.0667 1.1781 +0.0500 0.1000 1.1781 +0.0667 0.1333 1.1781 +0.0833 0.1667 1.1781 +0.1000 0.2000 1.1781 +0.1167 0.2333 1.1781 +0.1333 0.2667 1.1781 +0.1500 0.3000 1.1781 +primID: 2 +startangle_c: 3 +endpose_c: -1 -2 3 +additionalactioncostmult: 40 +intermediateposes: 10 +0.0000 0.0000 1.1781 +-0.0056 -0.0111 1.1781 +-0.0111 -0.0222 1.1781 +-0.0167 -0.0333 1.1781 +-0.0222 -0.0444 1.1781 +-0.0278 -0.0556 1.1781 +-0.0333 -0.0667 1.1781 +-0.0389 -0.0778 1.1781 +-0.0444 -0.0889 1.1781 +-0.0500 -0.1000 1.1781 +primID: 3 +startangle_c: 3 +endpose_c: 4 5 2 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0184 0.0298 1.1478 +0.0379 0.0592 1.1175 +0.0583 0.0881 1.0872 +0.0796 0.1165 1.0569 +0.1019 0.1444 1.0266 +0.1251 0.1717 0.9963 +0.1492 0.1984 0.9660 +0.1742 0.2245 0.9357 +0.2000 0.2500 0.9054 +primID: 4 +startangle_c: 3 +endpose_c: 2 7 4 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0156 0.0377 1.1781 +0.0312 0.0754 1.1781 +0.0468 0.1131 1.1781 +0.0623 0.1508 1.1972 +0.0758 0.1893 1.2719 +0.0863 0.2287 1.3466 +0.0939 0.2687 1.4214 +0.0985 0.3092 1.4961 +0.1000 0.3500 1.5708 +primID: 5 +startangle_c: 3 +endpose_c: 0 0 2 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0000 0.0000 1.1345 +0.0000 0.0000 1.0908 +0.0000 0.0000 1.0472 +0.0000 0.0000 1.0036 +0.0000 0.0000 0.9599 +0.0000 0.0000 0.9163 +0.0000 0.0000 0.8727 +0.0000 0.0000 0.8290 +0.0000 0.0000 0.7854 +primID: 6 +startangle_c: 3 +endpose_c: 0 0 4 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.1781 +0.0000 0.0000 1.2217 +0.0000 0.0000 1.2654 +0.0000 0.0000 1.3090 +0.0000 0.0000 1.3526 +0.0000 0.0000 1.3963 +0.0000 0.0000 1.4399 +0.0000 0.0000 1.4835 +0.0000 0.0000 1.5272 +0.0000 0.0000 1.5708 +primID: 0 +startangle_c: 4 +endpose_c: 0 1 4 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0056 1.5708 +0.0000 0.0111 1.5708 +0.0000 0.0167 1.5708 +0.0000 0.0222 1.5708 +0.0000 0.0278 1.5708 +0.0000 0.0333 1.5708 +0.0000 0.0389 1.5708 +0.0000 0.0444 1.5708 +0.0000 0.0500 1.5708 +primID: 1 +startangle_c: 4 +endpose_c: 0 8 4 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0444 1.5708 +0.0000 0.0889 1.5708 +0.0000 0.1333 1.5708 +0.0000 0.1778 1.5708 +0.0000 0.2222 1.5708 +0.0000 0.2667 1.5708 +0.0000 0.3111 1.5708 +0.0000 0.3556 1.5708 +0.0000 0.4000 1.5708 +primID: 2 +startangle_c: 4 +endpose_c: 0 -1 4 +additionalactioncostmult: 40 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 -0.0056 1.5708 +0.0000 -0.0111 1.5708 +0.0000 -0.0167 1.5708 +0.0000 -0.0222 1.5708 +0.0000 -0.0278 1.5708 +0.0000 -0.0333 1.5708 +0.0000 -0.0389 1.5708 +0.0000 -0.0444 1.5708 +0.0000 -0.0500 1.5708 +primID: 3 +startangle_c: 4 +endpose_c: -1 8 5 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0452 1.5708 +0.0000 0.0904 1.5708 +0.0000 0.1355 1.5708 +-0.0008 0.1807 1.6196 +-0.0045 0.2257 1.6884 +-0.0114 0.2703 1.7572 +-0.0213 0.3144 1.8259 +-0.0342 0.3577 1.8947 +-0.0500 0.4000 1.9635 +primID: 4 +startangle_c: 4 +endpose_c: 1 8 3 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0452 1.5708 +0.0000 0.0904 1.5708 +0.0000 0.1355 1.5708 +0.0008 0.1807 1.5220 +0.0045 0.2257 1.4532 +0.0114 0.2703 1.3844 +0.0213 0.3144 1.3156 +0.0342 0.3577 1.2469 +0.0500 0.4000 1.1781 +primID: 5 +startangle_c: 4 +endpose_c: 0 0 5 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0000 1.6144 +0.0000 0.0000 1.6581 +0.0000 0.0000 1.7017 +0.0000 0.0000 1.7453 +0.0000 0.0000 1.7890 +0.0000 0.0000 1.8326 +0.0000 0.0000 1.8762 +0.0000 0.0000 1.9199 +0.0000 0.0000 1.9635 +primID: 6 +startangle_c: 4 +endpose_c: 0 0 3 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.5708 +0.0000 0.0000 1.5272 +0.0000 0.0000 1.4835 +0.0000 0.0000 1.4399 +0.0000 0.0000 1.3963 +0.0000 0.0000 1.3526 +0.0000 0.0000 1.3090 +0.0000 0.0000 1.2654 +0.0000 0.0000 1.2217 +0.0000 0.0000 1.1781 +primID: 0 +startangle_c: 5 +endpose_c: -1 2 5 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0056 0.0111 1.9635 +-0.0111 0.0222 1.9635 +-0.0167 0.0333 1.9635 +-0.0222 0.0444 1.9635 +-0.0278 0.0556 1.9635 +-0.0333 0.0667 1.9635 +-0.0389 0.0778 1.9635 +-0.0444 0.0889 1.9635 +-0.0500 0.1000 1.9635 +primID: 1 +startangle_c: 5 +endpose_c: -3 6 5 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0167 0.0333 1.9635 +-0.0333 0.0667 1.9635 +-0.0500 0.1000 1.9635 +-0.0667 0.1333 1.9635 +-0.0833 0.1667 1.9635 +-0.1000 0.2000 1.9635 +-0.1167 0.2333 1.9635 +-0.1333 0.2667 1.9635 +-0.1500 0.3000 1.9635 +primID: 2 +startangle_c: 5 +endpose_c: 1 -2 5 +additionalactioncostmult: 40 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0056 -0.0111 1.9635 +0.0111 -0.0222 1.9635 +0.0167 -0.0333 1.9635 +0.0222 -0.0444 1.9635 +0.0278 -0.0556 1.9635 +0.0333 -0.0667 1.9635 +0.0389 -0.0778 1.9635 +0.0444 -0.0889 1.9635 +0.0500 -0.1000 1.9635 +primID: 3 +startangle_c: 5 +endpose_c: -4 5 6 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0184 0.0298 1.9938 +-0.0379 0.0592 2.0241 +-0.0583 0.0881 2.0544 +-0.0796 0.1165 2.0847 +-0.1019 0.1444 2.1150 +-0.1251 0.1717 2.1453 +-0.1492 0.1984 2.1756 +-0.1742 0.2245 2.2059 +-0.2000 0.2500 2.2362 +primID: 4 +startangle_c: 5 +endpose_c: -2 7 4 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 1.9635 +-0.0156 0.0377 1.9635 +-0.0312 0.0754 1.9635 +-0.0468 0.1131 1.9635 +-0.0623 0.1508 1.9444 +-0.0758 0.1893 1.8697 +-0.0863 0.2287 1.7950 +-0.0939 0.2687 1.7202 +-0.0985 0.3092 1.6455 +-0.1000 0.3500 1.5708 +primID: 5 +startangle_c: 5 +endpose_c: 0 0 6 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0000 0.0000 2.0071 +0.0000 0.0000 2.0508 +0.0000 0.0000 2.0944 +0.0000 0.0000 2.1380 +0.0000 0.0000 2.1817 +0.0000 0.0000 2.2253 +0.0000 0.0000 2.2689 +0.0000 0.0000 2.3126 +0.0000 0.0000 2.3562 +primID: 6 +startangle_c: 5 +endpose_c: 0 0 4 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 1.9635 +0.0000 0.0000 1.9199 +0.0000 0.0000 1.8762 +0.0000 0.0000 1.8326 +0.0000 0.0000 1.7890 +0.0000 0.0000 1.7453 +0.0000 0.0000 1.7017 +0.0000 0.0000 1.6581 +0.0000 0.0000 1.6144 +0.0000 0.0000 1.5708 +primID: 0 +startangle_c: 6 +endpose_c: -1 1 6 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0056 0.0056 2.3562 +-0.0111 0.0111 2.3562 +-0.0167 0.0167 2.3562 +-0.0222 0.0222 2.3562 +-0.0278 0.0278 2.3562 +-0.0333 0.0333 2.3562 +-0.0389 0.0389 2.3562 +-0.0444 0.0444 2.3562 +-0.0500 0.0500 2.3562 +primID: 1 +startangle_c: 6 +endpose_c: -6 6 6 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0333 0.0333 2.3562 +-0.0667 0.0667 2.3562 +-0.1000 0.1000 2.3562 +-0.1333 0.1333 2.3562 +-0.1667 0.1667 2.3562 +-0.2000 0.2000 2.3562 +-0.2333 0.2333 2.3562 +-0.2667 0.2667 2.3562 +-0.3000 0.3000 2.3562 +primID: 2 +startangle_c: 6 +endpose_c: 1 -1 6 +additionalactioncostmult: 40 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0056 -0.0056 2.3562 +0.0111 -0.0111 2.3562 +0.0167 -0.0167 2.3562 +0.0222 -0.0222 2.3562 +0.0278 -0.0278 2.3562 +0.0333 -0.0333 2.3562 +0.0389 -0.0389 2.3562 +0.0444 -0.0444 2.3562 +0.0500 -0.0500 2.3562 +primID: 3 +startangle_c: 6 +endpose_c: -7 5 7 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0341 0.0341 2.3562 +-0.0684 0.0678 2.3859 +-0.1043 0.1000 2.4377 +-0.1418 0.1302 2.4896 +-0.1809 0.1584 2.5415 +-0.2213 0.1846 2.5933 +-0.2631 0.2086 2.6452 +-0.3060 0.2304 2.6970 +-0.3500 0.2500 2.7489 +primID: 4 +startangle_c: 6 +endpose_c: -5 7 5 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 2.3562 +-0.0341 0.0341 2.3562 +-0.0678 0.0684 2.3265 +-0.1000 0.1043 2.2747 +-0.1302 0.1418 2.2228 +-0.1584 0.1809 2.1709 +-0.1846 0.2213 2.1191 +-0.2086 0.2631 2.0672 +-0.2304 0.3060 2.0154 +-0.2500 0.3500 1.9635 +primID: 5 +startangle_c: 6 +endpose_c: 0 0 7 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0000 0.0000 2.3998 +0.0000 0.0000 2.4435 +0.0000 0.0000 2.4871 +0.0000 0.0000 2.5307 +0.0000 0.0000 2.5744 +0.0000 0.0000 2.6180 +0.0000 0.0000 2.6616 +0.0000 0.0000 2.7053 +0.0000 0.0000 2.7489 +primID: 6 +startangle_c: 6 +endpose_c: 0 0 5 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.3562 +0.0000 0.0000 2.3126 +0.0000 0.0000 2.2689 +0.0000 0.0000 2.2253 +0.0000 0.0000 2.1817 +0.0000 0.0000 2.1380 +0.0000 0.0000 2.0944 +0.0000 0.0000 2.0508 +0.0000 0.0000 2.0071 +0.0000 0.0000 1.9635 +primID: 0 +startangle_c: 7 +endpose_c: -2 1 7 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0111 0.0056 2.7489 +-0.0222 0.0111 2.7489 +-0.0333 0.0167 2.7489 +-0.0444 0.0222 2.7489 +-0.0556 0.0278 2.7489 +-0.0667 0.0333 2.7489 +-0.0778 0.0389 2.7489 +-0.0889 0.0444 2.7489 +-0.1000 0.0500 2.7489 +primID: 1 +startangle_c: 7 +endpose_c: -6 3 7 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0333 0.0167 2.7489 +-0.0667 0.0333 2.7489 +-0.1000 0.0500 2.7489 +-0.1333 0.0667 2.7489 +-0.1667 0.0833 2.7489 +-0.2000 0.1000 2.7489 +-0.2333 0.1167 2.7489 +-0.2667 0.1333 2.7489 +-0.3000 0.1500 2.7489 +primID: 2 +startangle_c: 7 +endpose_c: 2 -1 7 +additionalactioncostmult: 40 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0111 -0.0056 2.7489 +0.0222 -0.0111 2.7489 +0.0333 -0.0167 2.7489 +0.0444 -0.0222 2.7489 +0.0556 -0.0278 2.7489 +0.0667 -0.0333 2.7489 +0.0778 -0.0389 2.7489 +0.0889 -0.0444 2.7489 +0.1000 -0.0500 2.7489 +primID: 3 +startangle_c: 7 +endpose_c: -5 4 6 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0298 0.0184 2.7186 +-0.0592 0.0379 2.6883 +-0.0881 0.0583 2.6580 +-0.1165 0.0796 2.6277 +-0.1444 0.1019 2.5974 +-0.1717 0.1251 2.5671 +-0.1984 0.1492 2.5368 +-0.2245 0.1742 2.5065 +-0.2500 0.2000 2.4762 +primID: 4 +startangle_c: 7 +endpose_c: -7 2 8 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 2.7489 +-0.0377 0.0156 2.7489 +-0.0754 0.0312 2.7489 +-0.1131 0.0468 2.7489 +-0.1508 0.0623 2.7680 +-0.1893 0.0758 2.8427 +-0.2287 0.0863 2.9174 +-0.2687 0.0939 2.9921 +-0.3092 0.0985 3.0669 +-0.3500 0.1000 3.1416 +primID: 5 +startangle_c: 7 +endpose_c: 0 0 6 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0000 0.0000 2.7053 +0.0000 0.0000 2.6616 +0.0000 0.0000 2.6180 +0.0000 0.0000 2.5744 +0.0000 0.0000 2.5307 +0.0000 0.0000 2.4871 +0.0000 0.0000 2.4435 +0.0000 0.0000 2.3998 +0.0000 0.0000 2.3562 +primID: 6 +startangle_c: 7 +endpose_c: 0 0 8 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 2.7489 +0.0000 0.0000 2.7925 +0.0000 0.0000 2.8362 +0.0000 0.0000 2.8798 +0.0000 0.0000 2.9234 +0.0000 0.0000 2.9671 +0.0000 0.0000 3.0107 +0.0000 0.0000 3.0543 +0.0000 0.0000 3.0980 +0.0000 0.0000 3.1416 +primID: 0 +startangle_c: 8 +endpose_c: -1 0 8 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0056 0.0000 3.1416 +-0.0111 0.0000 3.1416 +-0.0167 0.0000 3.1416 +-0.0222 0.0000 3.1416 +-0.0278 0.0000 3.1416 +-0.0333 0.0000 3.1416 +-0.0389 0.0000 3.1416 +-0.0444 0.0000 3.1416 +-0.0500 0.0000 3.1416 +primID: 1 +startangle_c: 8 +endpose_c: -8 0 8 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0444 0.0000 3.1416 +-0.0889 0.0000 3.1416 +-0.1333 0.0000 3.1416 +-0.1778 0.0000 3.1416 +-0.2222 0.0000 3.1416 +-0.2667 0.0000 3.1416 +-0.3111 0.0000 3.1416 +-0.3556 0.0000 3.1416 +-0.4000 0.0000 3.1416 +primID: 2 +startangle_c: 8 +endpose_c: 1 0 8 +additionalactioncostmult: 40 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0056 0.0000 3.1416 +0.0111 0.0000 3.1416 +0.0167 0.0000 3.1416 +0.0222 0.0000 3.1416 +0.0278 0.0000 3.1416 +0.0333 0.0000 3.1416 +0.0389 0.0000 3.1416 +0.0444 0.0000 3.1416 +0.0500 0.0000 3.1416 +primID: 3 +startangle_c: 8 +endpose_c: -8 -1 9 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0452 0.0000 3.1416 +-0.0904 0.0000 3.1416 +-0.1355 0.0000 3.1416 +-0.1807 -0.0008 3.1904 +-0.2257 -0.0045 3.2592 +-0.2703 -0.0114 3.3280 +-0.3144 -0.0213 3.3967 +-0.3577 -0.0342 3.4655 +-0.4000 -0.0500 3.5343 +primID: 4 +startangle_c: 8 +endpose_c: -8 1 7 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.1416 +-0.0452 0.0000 3.1416 +-0.0904 0.0000 3.1416 +-0.1355 0.0000 3.1416 +-0.1807 0.0008 3.0928 +-0.2257 0.0045 3.0240 +-0.2703 0.0114 2.9552 +-0.3144 0.0213 2.8864 +-0.3577 0.0342 2.8177 +-0.4000 0.0500 2.7489 +primID: 5 +startangle_c: 8 +endpose_c: 0 0 9 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0000 0.0000 3.1852 +0.0000 0.0000 3.2289 +0.0000 0.0000 3.2725 +0.0000 0.0000 3.3161 +0.0000 0.0000 3.3598 +0.0000 0.0000 3.4034 +0.0000 0.0000 3.4470 +0.0000 0.0000 3.4907 +0.0000 0.0000 3.5343 +primID: 6 +startangle_c: 8 +endpose_c: 0 0 7 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.1416 +0.0000 0.0000 3.0980 +0.0000 0.0000 3.0543 +0.0000 0.0000 3.0107 +0.0000 0.0000 2.9671 +0.0000 0.0000 2.9234 +0.0000 0.0000 2.8798 +0.0000 0.0000 2.8362 +0.0000 0.0000 2.7925 +0.0000 0.0000 2.7489 +primID: 0 +startangle_c: 9 +endpose_c: -2 -1 9 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0111 -0.0056 3.5343 +-0.0222 -0.0111 3.5343 +-0.0333 -0.0167 3.5343 +-0.0444 -0.0222 3.5343 +-0.0556 -0.0278 3.5343 +-0.0667 -0.0333 3.5343 +-0.0778 -0.0389 3.5343 +-0.0889 -0.0444 3.5343 +-0.1000 -0.0500 3.5343 +primID: 1 +startangle_c: 9 +endpose_c: -6 -3 9 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0333 -0.0167 3.5343 +-0.0667 -0.0333 3.5343 +-0.1000 -0.0500 3.5343 +-0.1333 -0.0667 3.5343 +-0.1667 -0.0833 3.5343 +-0.2000 -0.1000 3.5343 +-0.2333 -0.1167 3.5343 +-0.2667 -0.1333 3.5343 +-0.3000 -0.1500 3.5343 +primID: 2 +startangle_c: 9 +endpose_c: 2 1 9 +additionalactioncostmult: 40 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0111 0.0056 3.5343 +0.0222 0.0111 3.5343 +0.0333 0.0167 3.5343 +0.0444 0.0222 3.5343 +0.0556 0.0278 3.5343 +0.0667 0.0333 3.5343 +0.0778 0.0389 3.5343 +0.0889 0.0444 3.5343 +0.1000 0.0500 3.5343 +primID: 3 +startangle_c: 9 +endpose_c: -5 -4 10 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0298 -0.0184 3.5646 +-0.0592 -0.0379 3.5949 +-0.0881 -0.0583 3.6252 +-0.1165 -0.0796 3.6555 +-0.1444 -0.1019 3.6858 +-0.1717 -0.1251 3.7161 +-0.1984 -0.1492 3.7464 +-0.2245 -0.1742 3.7767 +-0.2500 -0.2000 3.8070 +primID: 4 +startangle_c: 9 +endpose_c: -7 -2 8 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.5343 +-0.0377 -0.0156 3.5343 +-0.0754 -0.0312 3.5343 +-0.1131 -0.0468 3.5343 +-0.1508 -0.0623 3.5152 +-0.1893 -0.0758 3.4405 +-0.2287 -0.0863 3.3658 +-0.2687 -0.0939 3.2910 +-0.3092 -0.0985 3.2163 +-0.3500 -0.1000 3.1416 +primID: 5 +startangle_c: 9 +endpose_c: 0 0 10 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0000 0.0000 3.5779 +0.0000 0.0000 3.6216 +0.0000 0.0000 3.6652 +0.0000 0.0000 3.7088 +0.0000 0.0000 3.7525 +0.0000 0.0000 3.7961 +0.0000 0.0000 3.8397 +0.0000 0.0000 3.8834 +0.0000 0.0000 3.9270 +primID: 6 +startangle_c: 9 +endpose_c: 0 0 8 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.5343 +0.0000 0.0000 3.4907 +0.0000 0.0000 3.4470 +0.0000 0.0000 3.4034 +0.0000 0.0000 3.3598 +0.0000 0.0000 3.3161 +0.0000 0.0000 3.2725 +0.0000 0.0000 3.2289 +0.0000 0.0000 3.1852 +0.0000 0.0000 3.1416 +primID: 0 +startangle_c: 10 +endpose_c: -1 -1 10 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0056 -0.0056 3.9270 +-0.0111 -0.0111 3.9270 +-0.0167 -0.0167 3.9270 +-0.0222 -0.0222 3.9270 +-0.0278 -0.0278 3.9270 +-0.0333 -0.0333 3.9270 +-0.0389 -0.0389 3.9270 +-0.0444 -0.0444 3.9270 +-0.0500 -0.0500 3.9270 +primID: 1 +startangle_c: 10 +endpose_c: -6 -6 10 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0333 -0.0333 3.9270 +-0.0667 -0.0667 3.9270 +-0.1000 -0.1000 3.9270 +-0.1333 -0.1333 3.9270 +-0.1667 -0.1667 3.9270 +-0.2000 -0.2000 3.9270 +-0.2333 -0.2333 3.9270 +-0.2667 -0.2667 3.9270 +-0.3000 -0.3000 3.9270 +primID: 2 +startangle_c: 10 +endpose_c: 1 1 10 +additionalactioncostmult: 40 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0056 0.0056 3.9270 +0.0111 0.0111 3.9270 +0.0167 0.0167 3.9270 +0.0222 0.0222 3.9270 +0.0278 0.0278 3.9270 +0.0333 0.0333 3.9270 +0.0389 0.0389 3.9270 +0.0444 0.0444 3.9270 +0.0500 0.0500 3.9270 +primID: 3 +startangle_c: 10 +endpose_c: -5 -7 11 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0341 -0.0341 3.9270 +-0.0678 -0.0684 3.9567 +-0.1000 -0.1043 4.0085 +-0.1302 -0.1418 4.0604 +-0.1584 -0.1809 4.1123 +-0.1846 -0.2213 4.1641 +-0.2086 -0.2631 4.2160 +-0.2304 -0.3060 4.2678 +-0.2500 -0.3500 4.3197 +primID: 4 +startangle_c: 10 +endpose_c: -7 -5 9 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 3.9270 +-0.0341 -0.0341 3.9270 +-0.0684 -0.0678 3.8973 +-0.1043 -0.1000 3.8455 +-0.1418 -0.1302 3.7936 +-0.1809 -0.1584 3.7417 +-0.2213 -0.1846 3.6899 +-0.2631 -0.2086 3.6380 +-0.3060 -0.2304 3.5862 +-0.3500 -0.2500 3.5343 +primID: 5 +startangle_c: 10 +endpose_c: 0 0 11 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.9706 +0.0000 0.0000 4.0143 +0.0000 0.0000 4.0579 +0.0000 0.0000 4.1015 +0.0000 0.0000 4.1452 +0.0000 0.0000 4.1888 +0.0000 0.0000 4.2324 +0.0000 0.0000 4.2761 +0.0000 0.0000 4.3197 +primID: 6 +startangle_c: 10 +endpose_c: 0 0 9 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 3.9270 +0.0000 0.0000 3.8834 +0.0000 0.0000 3.8397 +0.0000 0.0000 3.7961 +0.0000 0.0000 3.7525 +0.0000 0.0000 3.7088 +0.0000 0.0000 3.6652 +0.0000 0.0000 3.6216 +0.0000 0.0000 3.5779 +0.0000 0.0000 3.5343 +primID: 0 +startangle_c: 11 +endpose_c: -1 -2 11 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0056 -0.0111 4.3197 +-0.0111 -0.0222 4.3197 +-0.0167 -0.0333 4.3197 +-0.0222 -0.0444 4.3197 +-0.0278 -0.0556 4.3197 +-0.0333 -0.0667 4.3197 +-0.0389 -0.0778 4.3197 +-0.0444 -0.0889 4.3197 +-0.0500 -0.1000 4.3197 +primID: 1 +startangle_c: 11 +endpose_c: -3 -6 11 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0167 -0.0333 4.3197 +-0.0333 -0.0667 4.3197 +-0.0500 -0.1000 4.3197 +-0.0667 -0.1333 4.3197 +-0.0833 -0.1667 4.3197 +-0.1000 -0.2000 4.3197 +-0.1167 -0.2333 4.3197 +-0.1333 -0.2667 4.3197 +-0.1500 -0.3000 4.3197 +primID: 2 +startangle_c: 11 +endpose_c: 1 2 11 +additionalactioncostmult: 40 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0056 0.0111 4.3197 +0.0111 0.0222 4.3197 +0.0167 0.0333 4.3197 +0.0222 0.0444 4.3197 +0.0278 0.0556 4.3197 +0.0333 0.0667 4.3197 +0.0389 0.0778 4.3197 +0.0444 0.0889 4.3197 +0.0500 0.1000 4.3197 +primID: 3 +startangle_c: 11 +endpose_c: -4 -5 10 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0184 -0.0298 4.2894 +-0.0379 -0.0592 4.2591 +-0.0583 -0.0881 4.2288 +-0.0796 -0.1165 4.1985 +-0.1019 -0.1444 4.1682 +-0.1251 -0.1717 4.1379 +-0.1492 -0.1984 4.1076 +-0.1742 -0.2245 4.0773 +-0.2000 -0.2500 4.0470 +primID: 4 +startangle_c: 11 +endpose_c: -2 -7 12 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 4.3197 +-0.0156 -0.0377 4.3197 +-0.0312 -0.0754 4.3197 +-0.0468 -0.1131 4.3197 +-0.0623 -0.1508 4.3388 +-0.0758 -0.1893 4.4135 +-0.0863 -0.2287 4.4882 +-0.0939 -0.2687 4.5629 +-0.0985 -0.3092 4.6377 +-0.1000 -0.3500 4.7124 +primID: 5 +startangle_c: 11 +endpose_c: 0 0 10 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0000 0.0000 4.2761 +0.0000 0.0000 4.2324 +0.0000 0.0000 4.1888 +0.0000 0.0000 4.1452 +0.0000 0.0000 4.1015 +0.0000 0.0000 4.0579 +0.0000 0.0000 4.0143 +0.0000 0.0000 3.9706 +0.0000 0.0000 3.9270 +primID: 6 +startangle_c: 11 +endpose_c: 0 0 12 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.3197 +0.0000 0.0000 4.3633 +0.0000 0.0000 4.4070 +0.0000 0.0000 4.4506 +0.0000 0.0000 4.4942 +0.0000 0.0000 4.5379 +0.0000 0.0000 4.5815 +0.0000 0.0000 4.6251 +0.0000 0.0000 4.6688 +0.0000 0.0000 4.7124 +primID: 0 +startangle_c: 12 +endpose_c: 0 -1 12 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0056 4.7124 +0.0000 -0.0111 4.7124 +0.0000 -0.0167 4.7124 +0.0000 -0.0222 4.7124 +0.0000 -0.0278 4.7124 +0.0000 -0.0333 4.7124 +0.0000 -0.0389 4.7124 +0.0000 -0.0444 4.7124 +0.0000 -0.0500 4.7124 +primID: 1 +startangle_c: 12 +endpose_c: 0 -8 12 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0444 4.7124 +0.0000 -0.0889 4.7124 +0.0000 -0.1333 4.7124 +0.0000 -0.1778 4.7124 +0.0000 -0.2222 4.7124 +0.0000 -0.2667 4.7124 +0.0000 -0.3111 4.7124 +0.0000 -0.3556 4.7124 +0.0000 -0.4000 4.7124 +primID: 2 +startangle_c: 12 +endpose_c: 0 1 12 +additionalactioncostmult: 40 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0056 4.7124 +0.0000 0.0111 4.7124 +0.0000 0.0167 4.7124 +0.0000 0.0222 4.7124 +0.0000 0.0278 4.7124 +0.0000 0.0333 4.7124 +0.0000 0.0389 4.7124 +0.0000 0.0444 4.7124 +0.0000 0.0500 4.7124 +primID: 3 +startangle_c: 12 +endpose_c: 1 -8 13 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 -0.0452 4.7124 +0.0000 -0.0904 4.7124 +0.0000 -0.1355 4.7124 +0.0008 -0.1807 4.7612 +0.0045 -0.2257 4.8300 +0.0114 -0.2703 4.8988 +0.0213 -0.3144 4.9675 +0.0342 -0.3577 5.0363 +0.0500 -0.4000 5.1051 +primID: 4 +startangle_c: 12 +endpose_c: -1 -8 11 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 4.7124 +-0.0000 -0.0452 4.7124 +-0.0000 -0.0904 4.7124 +-0.0000 -0.1355 4.7124 +-0.0008 -0.1807 4.6636 +-0.0045 -0.2257 4.5948 +-0.0114 -0.2703 4.5260 +-0.0213 -0.3144 4.4572 +-0.0342 -0.3577 4.3885 +-0.0500 -0.4000 4.3197 +primID: 5 +startangle_c: 12 +endpose_c: 0 0 13 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0000 4.7560 +0.0000 0.0000 4.7997 +0.0000 0.0000 4.8433 +0.0000 0.0000 4.8869 +0.0000 0.0000 4.9306 +0.0000 0.0000 4.9742 +0.0000 0.0000 5.0178 +0.0000 0.0000 5.0615 +0.0000 0.0000 5.1051 +primID: 6 +startangle_c: 12 +endpose_c: 0 0 11 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 4.7124 +0.0000 0.0000 4.6688 +0.0000 0.0000 4.6251 +0.0000 0.0000 4.5815 +0.0000 0.0000 4.5379 +0.0000 0.0000 4.4942 +0.0000 0.0000 4.4506 +0.0000 0.0000 4.4070 +0.0000 0.0000 4.3633 +0.0000 0.0000 4.3197 +primID: 0 +startangle_c: 13 +endpose_c: 1 -2 13 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0056 -0.0111 5.1051 +0.0111 -0.0222 5.1051 +0.0167 -0.0333 5.1051 +0.0222 -0.0444 5.1051 +0.0278 -0.0556 5.1051 +0.0333 -0.0667 5.1051 +0.0389 -0.0778 5.1051 +0.0444 -0.0889 5.1051 +0.0500 -0.1000 5.1051 +primID: 1 +startangle_c: 13 +endpose_c: 3 -6 13 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0167 -0.0333 5.1051 +0.0333 -0.0667 5.1051 +0.0500 -0.1000 5.1051 +0.0667 -0.1333 5.1051 +0.0833 -0.1667 5.1051 +0.1000 -0.2000 5.1051 +0.1167 -0.2333 5.1051 +0.1333 -0.2667 5.1051 +0.1500 -0.3000 5.1051 +primID: 2 +startangle_c: 13 +endpose_c: -1 2 13 +additionalactioncostmult: 40 +intermediateposes: 10 +0.0000 0.0000 5.1051 +-0.0056 0.0111 5.1051 +-0.0111 0.0222 5.1051 +-0.0167 0.0333 5.1051 +-0.0222 0.0444 5.1051 +-0.0278 0.0556 5.1051 +-0.0333 0.0667 5.1051 +-0.0389 0.0778 5.1051 +-0.0444 0.0889 5.1051 +-0.0500 0.1000 5.1051 +primID: 3 +startangle_c: 13 +endpose_c: 4 -5 14 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0184 -0.0298 5.1354 +0.0379 -0.0592 5.1657 +0.0583 -0.0881 5.1960 +0.0796 -0.1165 5.2263 +0.1019 -0.1444 5.2566 +0.1251 -0.1717 5.2869 +0.1492 -0.1984 5.3172 +0.1742 -0.2245 5.3475 +0.2000 -0.2500 5.3778 +primID: 4 +startangle_c: 13 +endpose_c: 2 -7 12 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0156 -0.0377 5.1051 +0.0312 -0.0754 5.1051 +0.0468 -0.1131 5.1051 +0.0623 -0.1508 5.0860 +0.0758 -0.1893 5.0113 +0.0863 -0.2287 4.9366 +0.0939 -0.2687 4.8618 +0.0985 -0.3092 4.7871 +0.1000 -0.3500 4.7124 +primID: 5 +startangle_c: 13 +endpose_c: 0 0 14 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0000 0.0000 5.1487 +0.0000 0.0000 5.1924 +0.0000 0.0000 5.2360 +0.0000 0.0000 5.2796 +0.0000 0.0000 5.3233 +0.0000 0.0000 5.3669 +0.0000 0.0000 5.4105 +0.0000 0.0000 5.4542 +0.0000 0.0000 5.4978 +primID: 6 +startangle_c: 13 +endpose_c: 0 0 12 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.1051 +0.0000 0.0000 5.0615 +0.0000 0.0000 5.0178 +0.0000 0.0000 4.9742 +0.0000 0.0000 4.9306 +0.0000 0.0000 4.8869 +0.0000 0.0000 4.8433 +0.0000 0.0000 4.7997 +0.0000 0.0000 4.7560 +0.0000 0.0000 4.7124 +primID: 0 +startangle_c: 14 +endpose_c: 1 -1 14 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0056 -0.0056 5.4978 +0.0111 -0.0111 5.4978 +0.0167 -0.0167 5.4978 +0.0222 -0.0222 5.4978 +0.0278 -0.0278 5.4978 +0.0333 -0.0333 5.4978 +0.0389 -0.0389 5.4978 +0.0444 -0.0444 5.4978 +0.0500 -0.0500 5.4978 +primID: 1 +startangle_c: 14 +endpose_c: 6 -6 14 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0333 -0.0333 5.4978 +0.0667 -0.0667 5.4978 +0.1000 -0.1000 5.4978 +0.1333 -0.1333 5.4978 +0.1667 -0.1667 5.4978 +0.2000 -0.2000 5.4978 +0.2333 -0.2333 5.4978 +0.2667 -0.2667 5.4978 +0.3000 -0.3000 5.4978 +primID: 2 +startangle_c: 14 +endpose_c: -1 1 14 +additionalactioncostmult: 40 +intermediateposes: 10 +0.0000 0.0000 5.4978 +-0.0056 0.0056 5.4978 +-0.0111 0.0111 5.4978 +-0.0167 0.0167 5.4978 +-0.0222 0.0222 5.4978 +-0.0278 0.0278 5.4978 +-0.0333 0.0333 5.4978 +-0.0389 0.0389 5.4978 +-0.0444 0.0444 5.4978 +-0.0500 0.0500 5.4978 +primID: 3 +startangle_c: 14 +endpose_c: 7 -5 15 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0341 -0.0341 5.4978 +0.0684 -0.0678 5.5275 +0.1043 -0.1000 5.5793 +0.1418 -0.1302 5.6312 +0.1809 -0.1584 5.6830 +0.2213 -0.1846 5.7349 +0.2631 -0.2086 5.7868 +0.3060 -0.2304 5.8386 +0.3500 -0.2500 5.8905 +primID: 4 +startangle_c: 14 +endpose_c: 5 -7 13 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0341 -0.0341 5.4978 +0.0678 -0.0684 5.4681 +0.1000 -0.1043 5.4162 +0.1302 -0.1418 5.3644 +0.1584 -0.1809 5.3125 +0.1846 -0.2213 5.2607 +0.2086 -0.2631 5.2088 +0.2304 -0.3060 5.1569 +0.2500 -0.3500 5.1051 +primID: 5 +startangle_c: 14 +endpose_c: 0 0 15 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0000 0.0000 5.5414 +0.0000 0.0000 5.5851 +0.0000 0.0000 5.6287 +0.0000 0.0000 5.6723 +0.0000 0.0000 5.7160 +0.0000 0.0000 5.7596 +0.0000 0.0000 5.8032 +0.0000 0.0000 5.8469 +0.0000 0.0000 5.8905 +primID: 6 +startangle_c: 14 +endpose_c: 0 0 13 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.4978 +0.0000 0.0000 5.4542 +0.0000 0.0000 5.4105 +0.0000 0.0000 5.3669 +0.0000 0.0000 5.3233 +0.0000 0.0000 5.2796 +0.0000 0.0000 5.2360 +0.0000 0.0000 5.1924 +0.0000 0.0000 5.1487 +0.0000 0.0000 5.1051 +primID: 0 +startangle_c: 15 +endpose_c: 2 -1 15 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0111 -0.0056 5.8905 +0.0222 -0.0111 5.8905 +0.0333 -0.0167 5.8905 +0.0444 -0.0222 5.8905 +0.0556 -0.0278 5.8905 +0.0667 -0.0333 5.8905 +0.0778 -0.0389 5.8905 +0.0889 -0.0444 5.8905 +0.1000 -0.0500 5.8905 +primID: 1 +startangle_c: 15 +endpose_c: 6 -3 15 +additionalactioncostmult: 1 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0333 -0.0167 5.8905 +0.0667 -0.0333 5.8905 +0.1000 -0.0500 5.8905 +0.1333 -0.0667 5.8905 +0.1667 -0.0833 5.8905 +0.2000 -0.1000 5.8905 +0.2333 -0.1167 5.8905 +0.2667 -0.1333 5.8905 +0.3000 -0.1500 5.8905 +primID: 2 +startangle_c: 15 +endpose_c: -2 1 15 +additionalactioncostmult: 40 +intermediateposes: 10 +0.0000 0.0000 5.8905 +-0.0111 0.0056 5.8905 +-0.0222 0.0111 5.8905 +-0.0333 0.0167 5.8905 +-0.0444 0.0222 5.8905 +-0.0556 0.0278 5.8905 +-0.0667 0.0333 5.8905 +-0.0778 0.0389 5.8905 +-0.0889 0.0444 5.8905 +-0.1000 0.0500 5.8905 +primID: 3 +startangle_c: 15 +endpose_c: 5 -4 14 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0298 -0.0184 5.8602 +0.0592 -0.0379 5.8299 +0.0881 -0.0583 5.7996 +0.1165 -0.0796 5.7693 +0.1444 -0.1019 5.7390 +0.1717 -0.1251 5.7087 +0.1984 -0.1492 5.6784 +0.2245 -0.1742 5.6481 +0.2500 -0.2000 5.6178 +primID: 4 +startangle_c: 15 +endpose_c: 7 -2 0 +additionalactioncostmult: 2 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0377 -0.0156 5.8905 +0.0754 -0.0312 5.8905 +0.1131 -0.0468 5.8905 +0.1508 -0.0623 5.9096 +0.1893 -0.0758 5.9843 +0.2287 -0.0863 6.0590 +0.2687 -0.0939 6.1337 +0.3092 -0.0985 6.2085 +0.3500 -0.1000 6.2832 +primID: 5 +startangle_c: 15 +endpose_c: 0 0 14 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0000 0.0000 5.8469 +0.0000 0.0000 5.8032 +0.0000 0.0000 5.7596 +0.0000 0.0000 5.7160 +0.0000 0.0000 5.6723 +0.0000 0.0000 5.6287 +0.0000 0.0000 5.5851 +0.0000 0.0000 5.5414 +0.0000 0.0000 5.4978 +primID: 6 +startangle_c: 15 +endpose_c: 0 0 0 +additionalactioncostmult: 20 +intermediateposes: 10 +0.0000 0.0000 5.8905 +0.0000 0.0000 5.9341 +0.0000 0.0000 5.9778 +0.0000 0.0000 6.0214 +0.0000 0.0000 6.0650 +0.0000 0.0000 6.1087 +0.0000 0.0000 6.1523 +0.0000 0.0000 6.1959 +0.0000 0.0000 6.2396 +0.0000 0.0000 0.0000 diff --git a/navigations/sbpl_lattice_planner/msg/OccupancyGrid.msg b/navigations/sbpl_lattice_planner/msg/OccupancyGrid.msg new file mode 100755 index 0000000..72d42f8 --- /dev/null +++ b/navigations/sbpl_lattice_planner/msg/OccupancyGrid.msg @@ -0,0 +1,10 @@ +# This represents a 2-D grid map, in which each cell represents the probability of +# occupancy. + +Header header + +#MetaData for the map +nav_msgs/MapMetaData info + +# The map data, in row-major order, starting with (0,0). Occupancy +int16[] data diff --git a/navigations/sbpl_lattice_planner/msg/SBPLLatticePlannerStats.msg b/navigations/sbpl_lattice_planner/msg/SBPLLatticePlannerStats.msg new file mode 100755 index 0000000..3eb99a9 --- /dev/null +++ b/navigations/sbpl_lattice_planner/msg/SBPLLatticePlannerStats.msg @@ -0,0 +1,15 @@ +#planner stats +float64 initial_epsilon +float64 final_epsilon +bool plan_to_first_solution +float64 allocated_time +float64 actual_time +float64 time_to_first_solution +float64 solution_cost +float64 path_size +int64 final_number_of_expands +int64 number_of_expands_initial_solution + +#problem stats +geometry_msgs/PoseStamped start +geometry_msgs/PoseStamped goal diff --git a/navigations/sbpl_lattice_planner/package.xml b/navigations/sbpl_lattice_planner/package.xml new file mode 100755 index 0000000..f1f4d0f --- /dev/null +++ b/navigations/sbpl_lattice_planner/package.xml @@ -0,0 +1,50 @@ + + + sbpl_lattice_planner + 0.4.1 + + The sbpl_lattice_planner is a global planner plugin for move_base and wraps + the SBPL search-based planning library. + + Martin Günther + Michael Phillips + BSD + http://wiki.ros.org/sbpl_lattice_planner + https://github.com/ros-planning/navigation_experimental.git + https://github.com/ros-planning/navigation_experimental/issues + + catkin + + costmap_2d + costmap_2d + + geometry_msgs + geometry_msgs + + nav_core + nav_core + + nav_msgs + nav_msgs + + pluginlib + pluginlib + + roscpp + + sbpl + sbpl + + tf + tf + + tf2 + tf2 + + message_generation + message_runtime + + + + + diff --git a/navigations/sbpl_lattice_planner/src/sbpl_lattice_planner.cpp b/navigations/sbpl_lattice_planner/src/sbpl_lattice_planner.cpp new file mode 100755 index 0000000..351604c --- /dev/null +++ b/navigations/sbpl_lattice_planner/src/sbpl_lattice_planner.cpp @@ -0,0 +1,602 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2008, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the Willow Garage nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: Mike Phillips + *********************************************************************/ + +#include +#include +#include +#include + +#include +#include +#include + +using namespace std; +using namespace ros; + +PLUGINLIB_EXPORT_CLASS(sbpl_lattice_planner::SBPLLatticePlanner, nav_core::BaseGlobalPlanner) + +namespace geometry_msgs +{ + bool operator==(const Point &p1, const Point &p2) + { + return p1.x == p2.x && p1.y == p2.y && p1.z == p2.z; + } +} + +namespace sbpl_lattice_planner +{ + + class LatticeSCQ : public StateChangeQuery + { + public: + LatticeSCQ(EnvironmentNAVXYTHETALAT *env, std::vector const &changedcellsV) + : env_(env), changedcellsV_(changedcellsV) + { + } + + // lazy init, because we do not always end up calling this method + virtual std::vector const *getPredecessors() const + { + if (predsOfChangedCells_.empty() && !changedcellsV_.empty()) + env_->GetPredsofChangedEdges(&changedcellsV_, &predsOfChangedCells_); + return &predsOfChangedCells_; + } + + // lazy init, because we do not always end up calling this method + virtual std::vector const *getSuccessors() const + { + if (succsOfChangedCells_.empty() && !changedcellsV_.empty()) + env_->GetSuccsofChangedEdges(&changedcellsV_, &succsOfChangedCells_); + return &succsOfChangedCells_; + } + + EnvironmentNAVXYTHETALAT *env_; + std::vector const &changedcellsV_; + mutable std::vector predsOfChangedCells_; + mutable std::vector succsOfChangedCells_; + }; + + SBPLLatticePlanner::SBPLLatticePlanner() + : initialized_(false), costmap_ros_(NULL) + { + } + + SBPLLatticePlanner::SBPLLatticePlanner(std::string name, costmap_2d::Costmap2DROS *costmap_ros) + : initialized_(false), costmap_ros_(NULL) + { + initialize(name, costmap_ros); + } + + void SBPLLatticePlanner::initialize(std::string name, costmap_2d::Costmap2DROS *costmap_ros) + { + if (!initialized_) + { + ros::NodeHandle private_nh("~/" + name); + + ROS_INFO("Name is %s", name.c_str()); + + private_nh.param("planner_type", planner_type_, string("ARAPlanner")); + private_nh.param("allocated_time", allocated_time_, 10.0); + private_nh.param("initial_epsilon", initial_epsilon_, 3.0); + private_nh.param("environment_type", environment_type_, string("XYThetaLattice")); + private_nh.param("forward_search", forward_search_, bool(false)); + private_nh.param("primitive_filename", primitive_filename_, string("")); + private_nh.param("force_scratch_limit", force_scratch_limit_, 500); + + double nominalvel_mpersecs, timetoturn45degsinplace_secs; + private_nh.param("nominalvel_mpersecs", nominalvel_mpersecs, 0.4); + private_nh.param("timetoturn45degsinplace_secs", timetoturn45degsinplace_secs, 0.6); + + int lethal_obstacle; + private_nh.param("lethal_obstacle", lethal_obstacle, 20); + lethal_obstacle_ = (unsigned char)lethal_obstacle; + inscribed_inflated_obstacle_ = lethal_obstacle_ - 1; + sbpl_cost_multiplier_ = (unsigned char)(costmap_2d::INSCRIBED_INFLATED_OBSTACLE / inscribed_inflated_obstacle_ + 1); + ROS_INFO("SBPL: lethal: %uz, inscribed inflated: %uz, multiplier: %uz", lethal_obstacle, inscribed_inflated_obstacle_, sbpl_cost_multiplier_); + + private_nh.param("publish_footprint_path", publish_footprint_path_, bool(true)); + private_nh.param("visualizer_skip_poses", visualizer_skip_poses_, 5); + + private_nh.param("allow_unknown", allow_unknown_, bool(true)); + + name_ = name; + costmap_ros_ = costmap_ros; + + footprint_ = costmap_ros_->getRobotFootprint(); + + if ("XYThetaLattice" == environment_type_) + { + ROS_DEBUG("Using a 3D costmap for theta lattice\n"); + env_ = new EnvironmentNAVXYTHETALAT(); + } + else + { + ROS_ERROR("XYThetaLattice is currently the only supported environment!\n"); + exit(1); + } + + circumscribed_cost_ = computeCircumscribedCost(); + + if (circumscribed_cost_ == 0) + { + // Unfortunately, the inflation_radius is not taken into account by + // inflation_layer->computeCost(). If inflation_radius is smaller than + // the circumscribed radius, SBPL will ignore some obstacles, but we + // cannot detect this problem. If the cost_scaling_factor is too large, + // SBPL won't run into obstacles, but will always perform an expensive + // footprint check, no matter how far the nearest obstacle is. + ROS_WARN("The costmap value at the robot's circumscribed radius (%f m) is 0.", costmap_ros_->getLayeredCostmap()->getCircumscribedRadius()); + ROS_WARN("SBPL performance will suffer."); + ROS_WARN("Please decrease the costmap's cost_scaling_factor."); + } + if (!env_->SetEnvParameter("cost_inscribed_thresh", costMapCostToSBPLCost(costmap_2d::INSCRIBED_INFLATED_OBSTACLE))) + { + ROS_ERROR("Failed to set cost_inscribed_thresh parameter"); + exit(1); + } + if (!env_->SetEnvParameter("cost_possibly_circumscribed_thresh", circumscribed_cost_)) + { + ROS_ERROR("Failed to set cost_possibly_circumscribed_thresh parameter"); + exit(1); + } + int obst_cost_thresh = costMapCostToSBPLCost(costmap_2d::LETHAL_OBSTACLE); + vector perimeterptsV; + perimeterptsV.reserve(footprint_.size()); + for (size_t ii(0); ii < footprint_.size(); ++ii) + { + sbpl_2Dpt_t pt; + pt.x = footprint_[ii].x; + pt.y = footprint_[ii].y; + perimeterptsV.push_back(pt); + } + + bool ret; + try + { + ret = env_->InitializeEnv(costmap_ros_->getCostmap()->getSizeInCellsX(), // width + costmap_ros_->getCostmap()->getSizeInCellsY(), // height + 0, // mapdata + 0, 0, 0, // start (x, y, theta, t) + 0, 0, 0, // goal (x, y, theta) + 0, 0, 0, // goal tolerance + perimeterptsV, costmap_ros_->getCostmap()->getResolution(), nominalvel_mpersecs, + timetoturn45degsinplace_secs, obst_cost_thresh, + primitive_filename_.c_str()); + current_env_width_ = costmap_ros_->getCostmap()->getSizeInCellsX(); + current_env_height_ = costmap_ros_->getCostmap()->getSizeInCellsY(); + } + catch (SBPL_Exception *e) + { + ROS_ERROR("SBPL encountered a fatal exception: %s", e->what()); + ret = false; + } + if (!ret) + { + ROS_ERROR("SBPL initialization failed!"); + exit(1); + } + for (ssize_t ix(0); ix < costmap_ros_->getCostmap()->getSizeInCellsX(); ++ix) + for (ssize_t iy(0); iy < costmap_ros_->getCostmap()->getSizeInCellsY(); ++iy) + env_->UpdateCost(ix, iy, costMapCostToSBPLCost(costmap_ros_->getCostmap()->getCost(ix, iy))); + + if ("ARAPlanner" == planner_type_) + { + ROS_INFO("Planning with ARA*"); + planner_ = new ARAPlanner(env_, forward_search_); + } + else if ("ADPlanner" == planner_type_) + { + ROS_INFO("Planning with AD*"); + planner_ = new ADPlanner(env_, forward_search_); + } + else + { + ROS_ERROR("ARAPlanner and ADPlanner are currently the only supported planners!\n"); + exit(1); + } + + ROS_INFO("[sbpl_lattice_planner] Initialized successfully"); + plan_pub_ = private_nh.advertise("plan", 1); + stats_publisher_ = private_nh.advertise("sbpl_lattice_planner_stats", 1); + sbpl_plan_footprint_pub_ = private_nh.advertise("footprint_markers", 1); + + initialized_ = true; + } + } + + // Taken from Sachin's sbpl_cart_planner + // This rescales the costmap according to a rosparam which sets the obstacle cost + unsigned char SBPLLatticePlanner::costMapCostToSBPLCost(unsigned char newcost) + { + if (newcost == costmap_2d::LETHAL_OBSTACLE || (!allow_unknown_ && newcost == costmap_2d::NO_INFORMATION)) + return lethal_obstacle_; + else if (newcost == costmap_2d::INSCRIBED_INFLATED_OBSTACLE) + return inscribed_inflated_obstacle_; + else if (newcost == 0) + return 0; + else if(newcost == costmap_2d::NO_INFORMATION) + return costmap_2d::FREE_SPACE/sbpl_cost_multiplier_; + else + { + unsigned char sbpl_cost = newcost / sbpl_cost_multiplier_; + if (sbpl_cost == 0) + sbpl_cost = 1; + return sbpl_cost; + } + } + + void SBPLLatticePlanner::publishStats(int solution_cost, int solution_size, + const geometry_msgs::PoseStamped &start, + const geometry_msgs::PoseStamped &goal) + { + // Fill up statistics and publish + sbpl_lattice_planner::SBPLLatticePlannerStats stats; + stats.initial_epsilon = initial_epsilon_; + stats.plan_to_first_solution = false; + stats.final_number_of_expands = planner_->get_n_expands(); + stats.allocated_time = allocated_time_; + + stats.time_to_first_solution = planner_->get_initial_eps_planning_time(); + stats.actual_time = planner_->get_final_eps_planning_time(); + stats.number_of_expands_initial_solution = planner_->get_n_expands_init_solution(); + stats.final_epsilon = planner_->get_final_epsilon(); + + stats.solution_cost = solution_cost; + stats.path_size = solution_size; + stats.start = start; + stats.goal = goal; + stats_publisher_.publish(stats); + } + + unsigned char SBPLLatticePlanner::computeCircumscribedCost() + { + unsigned char result = 0; + + if (!costmap_ros_) + { + ROS_ERROR("Costmap is not initialized"); + return 0; + } + + // check if the costmap has an inflation layer + for (std::vector>::const_iterator layer = costmap_ros_->getLayeredCostmap()->getPlugins()->begin(); + layer != costmap_ros_->getLayeredCostmap()->getPlugins()->end(); + ++layer) + { + boost::shared_ptr inflation_layer = boost::dynamic_pointer_cast(*layer); + if (!inflation_layer) + continue; + + result = costMapCostToSBPLCost(inflation_layer->computeCost(costmap_ros_->getLayeredCostmap()->getCircumscribedRadius() / costmap_ros_->getCostmap()->getResolution())); + } + return result; + } + + bool SBPLLatticePlanner::makePlan(const geometry_msgs::PoseStamped &start, + const geometry_msgs::PoseStamped &goal, + std::vector &plan) + { + if (!initialized_) + { + ROS_ERROR("Global planner is not initialized"); + return false; + } + + bool do_init = false; + if (current_env_width_ != costmap_ros_->getCostmap()->getSizeInCellsX() || + current_env_height_ != costmap_ros_->getCostmap()->getSizeInCellsY()) + { + ROS_INFO("Costmap dimensions have changed from (%d x %d) to (%d x %d), reinitializing sbpl_lattice_planner.", + current_env_width_, current_env_height_, + costmap_ros_->getCostmap()->getSizeInCellsX(), costmap_ros_->getCostmap()->getSizeInCellsY()); + do_init = true; + } + else if (footprint_ != costmap_ros_->getRobotFootprint()) + { + ROS_INFO("Robot footprint has changed, reinitializing sbpl_lattice_planner."); + do_init = true; + } + else if (circumscribed_cost_ != computeCircumscribedCost()) + { + ROS_INFO("Cost at circumscribed radius has changed, reinitializing sbpl_lattice_planner."); + do_init = true; + } + + if (do_init) + { + initialized_ = false; + delete planner_; + planner_ = NULL; + delete env_; + env_ = NULL; + initialize(name_, costmap_ros_); + } + + plan.clear(); + + ROS_INFO("[sbpl_lattice_planner] getting start point (%g,%g) goal point (%g,%g)", + start.pose.position.x, start.pose.position.y, goal.pose.position.x, goal.pose.position.y); + double theta_start = 2 * atan2(start.pose.orientation.z, start.pose.orientation.w); + double theta_goal = 2 * atan2(goal.pose.orientation.z, goal.pose.orientation.w); + + try + { + int ret = env_->SetStart(start.pose.position.x - costmap_ros_->getCostmap()->getOriginX(), start.pose.position.y - costmap_ros_->getCostmap()->getOriginY(), theta_start); + if (ret < 0 || planner_->set_start(ret) == 0) + { + ROS_ERROR("ERROR: failed to set start state\n"); + return false; + } + } + catch (SBPL_Exception *e) + { + ROS_ERROR("SBPL encountered a fatal exception while setting the start state"); + return false; + } + + try + { + int ret = env_->SetGoal(goal.pose.position.x - costmap_ros_->getCostmap()->getOriginX(), goal.pose.position.y - costmap_ros_->getCostmap()->getOriginY(), theta_goal); + if (ret < 0 || planner_->set_goal(ret) == 0) + { + ROS_ERROR("ERROR: failed to set goal state\n"); + return false; + } + } + catch (SBPL_Exception *e) + { + ROS_ERROR("SBPL encountered a fatal exception while setting the goal state"); + return false; + } + + int offOnCount = 0; + int onOffCount = 0; + int allCount = 0; + vector changedcellsV; + + for (unsigned int ix = 0; ix < costmap_ros_->getCostmap()->getSizeInCellsX(); ix++) + { + for (unsigned int iy = 0; iy < costmap_ros_->getCostmap()->getSizeInCellsY(); iy++) + { + + unsigned char oldCost = env_->GetMapCost(ix, iy); + unsigned char newCost = costMapCostToSBPLCost(costmap_ros_->getCostmap()->getCost(ix, iy)); + + if (oldCost == newCost) + continue; + + allCount++; + + // first case - off cell goes on + + if ((oldCost != costMapCostToSBPLCost(costmap_2d::LETHAL_OBSTACLE) && oldCost != costMapCostToSBPLCost(costmap_2d::INSCRIBED_INFLATED_OBSTACLE)) && + (newCost == costMapCostToSBPLCost(costmap_2d::LETHAL_OBSTACLE) || newCost == costMapCostToSBPLCost(costmap_2d::INSCRIBED_INFLATED_OBSTACLE))) + { + offOnCount++; + } + + if ((oldCost == costMapCostToSBPLCost(costmap_2d::LETHAL_OBSTACLE) || oldCost == costMapCostToSBPLCost(costmap_2d::INSCRIBED_INFLATED_OBSTACLE)) && + (newCost != costMapCostToSBPLCost(costmap_2d::LETHAL_OBSTACLE) && newCost != costMapCostToSBPLCost(costmap_2d::INSCRIBED_INFLATED_OBSTACLE))) + { + onOffCount++; + } + env_->UpdateCost(ix, iy, costMapCostToSBPLCost(costmap_ros_->getCostmap()->getCost(ix, iy))); + + nav2dcell_t nav2dcell; + nav2dcell.x = ix; + nav2dcell.y = iy; + changedcellsV.push_back(nav2dcell); + } + } + + try + { + if (!changedcellsV.empty()) + { + StateChangeQuery *scq = new LatticeSCQ(env_, changedcellsV); + planner_->costs_changed(*scq); + delete scq; + } + + if (allCount > force_scratch_limit_) + planner_->force_planning_from_scratch(); + } + catch (SBPL_Exception *e) + { + ROS_ERROR("SBPL failed to update the costmap"); + return false; + } + + // setting planner parameters + ROS_DEBUG("allocated:%f, init eps:%f\n", allocated_time_, initial_epsilon_); + planner_->set_initialsolution_eps(initial_epsilon_); + planner_->set_search_mode(false); + + ROS_DEBUG("[sbpl_lattice_planner] run planner"); + vector solution_stateIDs; + int solution_cost; + try + { + int ret = planner_->replan(allocated_time_, &solution_stateIDs, &solution_cost); + if (ret) + ROS_DEBUG("Solution is found\n"); + else + { + ROS_INFO("Solution not found\n"); + publishStats(solution_cost, 0, start, goal); + return false; + } + } + catch (SBPL_Exception *e) + { + ROS_ERROR("SBPL encountered a fatal exception while planning"); + return false; + } + + ROS_DEBUG("size of solution=%d", (int)solution_stateIDs.size()); + + vector sbpl_path; + try + { + env_->ConvertStateIDPathintoXYThetaPath(&solution_stateIDs, &sbpl_path); + } + catch (SBPL_Exception *e) + { + ROS_ERROR("SBPL encountered a fatal exception while reconstructing the path"); + return false; + } + // if the plan has zero points, add a single point to make move_base happy + if (sbpl_path.size() == 0) + { + EnvNAVXYTHETALAT3Dpt_t s( + start.pose.position.x - costmap_ros_->getCostmap()->getOriginX(), + start.pose.position.y - costmap_ros_->getCostmap()->getOriginY(), + theta_start); + sbpl_path.push_back(s); + } + + ROS_DEBUG("Plan has %d points.\n", (int)sbpl_path.size()); + if (sbpl_path.back().x != goal.pose.position.x - costmap_ros_->getCostmap()->getOriginX() || + sbpl_path.back().y != goal.pose.position.y - costmap_ros_->getCostmap()->getOriginY() || + sbpl_path.back().theta != theta_goal) + + { + EnvNAVXYTHETALAT3Dpt_t goal_stemp(goal.pose.position.x - costmap_ros_->getCostmap()->getOriginX(), + goal.pose.position.y - costmap_ros_->getCostmap()->getOriginY(), + theta_goal); + sbpl_path.push_back(goal_stemp); + } + + ros::Time plan_time = ros::Time::now(); + + if (publish_footprint_path_) + { + visualization_msgs::Marker sbpl_plan_footprint; + getFootprintList(sbpl_path, costmap_ros_->getGlobalFrameID(), sbpl_plan_footprint); + sbpl_plan_footprint_pub_.publish(sbpl_plan_footprint); + } + + // create a message for the plan + nav_msgs::Path gui_path; + gui_path.poses.resize(sbpl_path.size()); + gui_path.header.frame_id = costmap_ros_->getGlobalFrameID(); + gui_path.header.stamp = plan_time; + for (unsigned int i = 0; i < sbpl_path.size(); i++) + { + geometry_msgs::PoseStamped pose; + pose.header.stamp = plan_time; + pose.header.frame_id = costmap_ros_->getGlobalFrameID(); + + pose.pose.position.x = sbpl_path[i].x + costmap_ros_->getCostmap()->getOriginX(); + pose.pose.position.y = sbpl_path[i].y + costmap_ros_->getCostmap()->getOriginY(); + pose.pose.position.z = start.pose.position.z; + + tf2::Quaternion temp; + temp.setRPY(0, 0, sbpl_path[i].theta); + pose.pose.orientation.x = temp.getX(); + pose.pose.orientation.y = temp.getY(); + pose.pose.orientation.z = temp.getZ(); + pose.pose.orientation.w = temp.getW(); + + plan.push_back(pose); + + gui_path.poses[i] = plan[i]; + } + plan_pub_.publish(gui_path); + publishStats(solution_cost, sbpl_path.size(), start, goal); + + return true; + } + + void SBPLLatticePlanner::getFootprintList(const std::vector &sbpl_path, + const std::string &path_frame_id, visualization_msgs::Marker &ma) + { + ma.header.frame_id = path_frame_id; + ma.header.stamp = ros::Time(); + ma.ns = "sbpl_robot_footprint"; + ma.id = 0; + ma.type = visualization_msgs::Marker::LINE_LIST; + ma.action = visualization_msgs::Marker::ADD; + ma.scale.x = 0.05; + ma.color.a = 1.0; + ma.color.r = 0.0; + ma.color.g = 0.0; + ma.color.b = 1.0; + ma.pose.orientation.w = 1.0; + + for (unsigned int i = 0; i < sbpl_path.size(); i = i + visualizer_skip_poses_) + { + std::vector transformed_rfp; + geometry_msgs::Pose robot_pose; + robot_pose.position.x = sbpl_path[i].x + costmap_ros_->getCostmap()->getOriginX(); + ; + robot_pose.position.y = sbpl_path[i].y + costmap_ros_->getCostmap()->getOriginY(); + ; + robot_pose.position.z = 0.0; + tf::Quaternion quat; + quat.setRPY(0.0, 0.0, sbpl_path[i].theta); + tf::quaternionTFToMsg(quat, robot_pose.orientation); + transformFootprintToEdges(robot_pose, footprint_, transformed_rfp); + + for (auto &point : transformed_rfp) + ma.points.push_back(point); + } + } + + void SBPLLatticePlanner::transformFootprintToEdges(const geometry_msgs::Pose &robot_pose, + const std::vector &footprint, + std::vector &out_footprint) + { + out_footprint.resize(2 * footprint.size()); + double yaw = tf::getYaw(robot_pose.orientation); + for (unsigned int i = 0; i < footprint.size(); i++) + { + out_footprint[2 * i].x = robot_pose.position.x + cos(yaw) * footprint[i].x - sin(yaw) * footprint[i].y; + out_footprint[2 * i].y = robot_pose.position.y + sin(yaw) * footprint[i].x + cos(yaw) * footprint[i].y; + if (i == 0) + { + out_footprint.back().x = out_footprint[i].x; + out_footprint.back().y = out_footprint[i].y; + } + else + { + out_footprint[2 * i - 1].x = out_footprint[2 * i].x; + out_footprint[2 * i - 1].y = out_footprint[2 * i].y; + } + } + } +}; diff --git a/navigations/sbpl_lattice_planner/test.drawio b/navigations/sbpl_lattice_planner/test.drawio new file mode 100755 index 0000000..e69de29 diff --git a/navigations/sbpl_recovery/CHANGELOG.rst b/navigations/sbpl_recovery/CHANGELOG.rst new file mode 100755 index 0000000..7e72e78 --- /dev/null +++ b/navigations/sbpl_recovery/CHANGELOG.rst @@ -0,0 +1,40 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package sbpl_recovery +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +0.4.1 (2022-08-24) +------------------ + +0.4.0 (2022-03-07) +------------------ + +0.3.4 (2020-06-19) +------------------ +* Initial release into noetic * Set cmake_policy CMP0048 to fix warning +* Contributors: Martin Günther + +0.3.3 (2019-10-15) +------------------ +* Add READMEs +* Contributors: Martin Günther + +0.3.2 (2019-01-16) +------------------ +* Fix some includes +* Contributors: Martin Günther + +0.3.1 (2018-09-05) +------------------ +* sbpl_recovery: Ignore SBPL compile warning +* Contributors: Martin Günther + +0.3.0 (2018-09-04) +------------------ +* Convert to TF2 + new navigation API (for melodic) +* Use non deprecated pluginlib macro + headers +* Contributors: Martin Günther + +0.2.0 (2018-09-03) +------------------ +* Initial release into indigo, kinetic, lunar and melodic +* Contributors: Martin Günther, David V. Lu!!, Dave Hershberger, Jon Binney, Vincent Rabaud, Eitan Marder-Eppstein diff --git a/navigations/sbpl_recovery/CMakeLists.txt b/navigations/sbpl_recovery/CMakeLists.txt new file mode 100755 index 0000000..18846f2 --- /dev/null +++ b/navigations/sbpl_recovery/CMakeLists.txt @@ -0,0 +1,50 @@ +cmake_minimum_required(VERSION 3.5.1) +cmake_policy(SET CMP0048 NEW) +project(sbpl_recovery) + +############################################################################## +# Find dependencies +############################################################################## + +set(THIS_PACKAGE_ROS_DEPS roscpp nav_core sbpl_lattice_planner pose_follower + costmap_2d pluginlib base_local_planner tf2_ros) +find_package(catkin REQUIRED COMPONENTS ${THIS_PACKAGE_ROS_DEPS}) + +include_directories(include ${catkin_INCLUDE_DIRS}) + +############################################################################## +# Define package +############################################################################## + +catkin_package( + INCLUDE_DIRS include + LIBRARIES sbpl_recovery + CATKIN_DEPENDS ${THIS_PACKAGE_ROS_DEPS} +) + +############################################################################## +# Build +############################################################################## + +add_library(sbpl_recovery src/sbpl_recovery.cpp) +target_link_libraries(sbpl_recovery ${catkin_LIBRARIES}) +target_compile_options(sbpl_recovery PUBLIC "-Wno-terminate") # suppress warning from included SBPL header + +############################################################################## +# Install +############################################################################## + +install(TARGETS sbpl_recovery + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) + +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} + FILES_MATCHING PATTERN "*.h" +) + +install(FILES recovery_plugin.xml + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) diff --git a/navigations/sbpl_recovery/README.md b/navigations/sbpl_recovery/README.md new file mode 100755 index 0000000..0b67012 --- /dev/null +++ b/navigations/sbpl_recovery/README.md @@ -0,0 +1,5 @@ +sbpl_recovery +============= + +A recovery behavior that uses the SBPL lattice planner and the pose follower to +try to plan in full 3D to get the robot out of really tricky situations. diff --git a/navigations/sbpl_recovery/include/sbpl_recovery/sbpl_recovery.h b/navigations/sbpl_recovery/include/sbpl_recovery/sbpl_recovery.h new file mode 100755 index 0000000..9c0a810 --- /dev/null +++ b/navigations/sbpl_recovery/include/sbpl_recovery/sbpl_recovery.h @@ -0,0 +1,88 @@ +/********************************************************************* +* +* Software License Agreement (BSD License) +* +* Copyright (c) 2009, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of Willow Garage, Inc. nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* +* Author: Eitan Marder-Eppstein +*********************************************************************/ +#ifndef SBPL_RECOVERY_SBPL_RECOVERY_H_ +#define SBPL_RECOVERY_SBPL_RECOVERY_H_ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +namespace sbpl_recovery +{ + class SBPLRecovery : public nav_core::RecoveryBehavior + { + public: + SBPLRecovery(); + + // Initialize the parameters of the behavior + void initialize (std::string n, tf2_ros::Buffer* tf, + costmap_2d::Costmap2DROS* global_costmap, + costmap_2d::Costmap2DROS* local_costmap); + + // Run the behavior + void runBehavior(); + + private: + void planCB(const nav_msgs::Path::ConstPtr& plan); + double sqDistance(const geometry_msgs::PoseStamped& p1, + const geometry_msgs::PoseStamped& p2); + std::vector makePlan(); + + costmap_2d::Costmap2DROS* global_costmap_; + costmap_2d::Costmap2DROS* local_costmap_; + tf2_ros::Buffer* tf_; + sbpl_lattice_planner::SBPLLatticePlanner global_planner_; + pose_follower::PoseFollower local_planner_; + bool initialized_; + ros::Subscriber plan_sub_; + ros::Publisher vel_pub_; + boost::mutex plan_mutex_; + nav_msgs::Path plan_; + double control_frequency_, sq_planning_distance_, controller_patience_; + int planning_attempts_, attempts_per_run_; + bool use_local_frame_; + }; + +}; +#endif diff --git a/navigations/sbpl_recovery/package.xml b/navigations/sbpl_recovery/package.xml new file mode 100755 index 0000000..3d2bcb1 --- /dev/null +++ b/navigations/sbpl_recovery/package.xml @@ -0,0 +1,31 @@ + + + sbpl_recovery + 0.4.1 + + A recovery behavior that uses the sbpl lattice planner and the pose + follower to try to plan in full 3D to get the robot out of really tricky + situations. + + Martin Günther + Eitan Marder-Eppstein + BSD + http://wiki.ros.org/sbpl_recovery + https://github.com/ros-planning/navigation_experimental.git + https://github.com/ros-planning/navigation_experimental/issues + + catkin + + base_local_planner + costmap_2d + nav_core + pluginlib + pose_follower + roscpp + sbpl_lattice_planner + tf2_ros + + + + + diff --git a/navigations/sbpl_recovery/recovery_plugin.xml b/navigations/sbpl_recovery/recovery_plugin.xml new file mode 100755 index 0000000..d6901a2 --- /dev/null +++ b/navigations/sbpl_recovery/recovery_plugin.xml @@ -0,0 +1,7 @@ + + + + A recovery behavior that uses the sbpl lattice planner and the pose follower to try to plan in full 3D to get the robot out of really tricky situations. + + + diff --git a/navigations/sbpl_recovery/src/sbpl_recovery.cpp b/navigations/sbpl_recovery/src/sbpl_recovery.cpp new file mode 100755 index 0000000..8b33dac --- /dev/null +++ b/navigations/sbpl_recovery/src/sbpl_recovery.cpp @@ -0,0 +1,241 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2009, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: Eitan Marder-Eppstein + *********************************************************************/ + +#include +#include + +PLUGINLIB_EXPORT_CLASS(sbpl_recovery::SBPLRecovery, nav_core::RecoveryBehavior) + +namespace sbpl_recovery +{ + SBPLRecovery::SBPLRecovery(): + global_costmap_(NULL), + local_costmap_(NULL), + tf_(NULL), + initialized_(false) + { + } + + void SBPLRecovery::initialize (std::string n, tf2_ros::Buffer* tf, + costmap_2d::Costmap2DROS* global_costmap, + costmap_2d::Costmap2DROS* local_costmap) + { + ros::NodeHandle nh = ros::NodeHandle(); + ros::NodeHandle p_nh = ros::NodeHandle("~/" + n); + + std::string plan_topic; + p_nh.param("9", plan_topic, std::string("NavfnROS/plan")); + p_nh.param("control_frequency", control_frequency_, 10.0); + p_nh.param("controller_patience", controller_patience_, 5.0); + p_nh.param("planning_attempts", planning_attempts_, 3); + p_nh.param("attempts_per_run", attempts_per_run_, 3); + p_nh.param("use_local_frame", use_local_frame_, true); + + double planning_distance; + p_nh.param("planning_distance", planning_distance, 2.0); + sq_planning_distance_ = planning_distance * planning_distance; + + //we need to initialize our costmaps + global_costmap_ = global_costmap; + local_costmap_ = local_costmap; + tf_ = tf; + + //we need to initialize our local and global planners + if(use_local_frame_) + global_planner_.initialize(n , local_costmap_); + else + global_planner_.initialize(n , global_costmap_); + + local_planner_.initialize(n , tf, local_costmap_); + + //we'll need to subscribe to get the latest plan information + vel_pub_ = nh.advertise("cmd_vel", 1); + + ros::NodeHandle node_nh("~/"); + plan_sub_ = node_nh.subscribe(plan_topic, 1, boost::bind(&SBPLRecovery::planCB, this, _1)); + initialized_ = true; + } + + void SBPLRecovery::planCB(const nav_msgs::Path::ConstPtr& plan) + { + //just copy the plan data over + + geometry_msgs::PoseStamped global_pose; + local_costmap_->getRobotPose(global_pose); + + costmap_2d::Costmap2D costmap; + costmap = *(local_costmap_->getCostmap()); + + if(use_local_frame_) + { + std::vector transformed_plan; + if(base_local_planner::transformGlobalPlan(*tf_, plan->poses, global_pose, costmap, local_costmap_->getGlobalFrameID(), transformed_plan)) + { + boost::mutex::scoped_lock l(plan_mutex_); + if(!transformed_plan.empty()) + plan_.header = transformed_plan[0].header; + plan_.poses = transformed_plan; + } + else + ROS_WARN("Could not transform to frame of the local recovery"); + } + else + { + boost::mutex::scoped_lock l(plan_mutex_); + plan_ = *plan; + } + } + + double SBPLRecovery::sqDistance(const geometry_msgs::PoseStamped& p1, + const geometry_msgs::PoseStamped& p2) + { + return (p1.pose.position.x - p2.pose.position.x) * (p1.pose.position.x - p2.pose.position.x) + + (p1.pose.position.y - p2.pose.position.y) * (p1.pose.position.y - p2.pose.position.y); + } + + std::vector SBPLRecovery::makePlan() + { + boost::mutex::scoped_lock l(plan_mutex_); + std::vector sbpl_plan; + + geometry_msgs::PoseStamped start; + if(use_local_frame_) + { + if(!local_costmap_->getRobotPose(start)) + { + ROS_ERROR("SBPL recovery behavior could not get the current pose of the robot. Doing nothing."); + return sbpl_plan; + } + } + else + { + if(!global_costmap_->getRobotPose(start)) + { + ROS_ERROR("SBPL recovery behavior could not get the current pose of the robot. Doing nothing."); + return sbpl_plan; + } + } + + //first, we want to walk far enough along the path that we get to a point + //that is within the recovery distance from the robot. Otherwise, we might + //move backwards along the plan + unsigned int index = 0; + for(index=0; index < plan_.poses.size(); ++index) + { + if(sqDistance(start, plan_.poses[index]) < sq_planning_distance_) + break; + } + + //next, we want to find a goal point that is far enough away from the robot on the + //original plan and attempt to plan to it + int unsuccessful_attempts = 0; + for(unsigned int i = index; i < plan_.poses.size(); ++i) + { + ROS_DEBUG("SQ Distance: %.2f, spd: %.2f, start (%.2f, %.2f), goal (%.2f, %.2f)", + sqDistance(start, plan_.poses[i]), + sq_planning_distance_, + start.pose.position.x, start.pose.position.y, + plan_.poses[i].pose.position.x, + plan_.poses[i].pose.position.y); + if(sqDistance(start, plan_.poses[i]) >= sq_planning_distance_ || i == (plan_.poses.size() - 1)) + { + ROS_INFO("Calling sbpl planner with start (%.2f, %.2f), goal (%.2f, %.2f)", + start.pose.position.x, start.pose.position.y, + plan_.poses[i].pose.position.x, + plan_.poses[i].pose.position.y); + if(global_planner_.makePlan(start, plan_.poses[i], sbpl_plan) && !sbpl_plan.empty()) + { + ROS_INFO("Got a valid plan"); + return sbpl_plan; + } + sbpl_plan.clear(); + + //make sure that we don't spend forever planning + unsuccessful_attempts++; + if(unsuccessful_attempts >= attempts_per_run_) + return sbpl_plan; + } + } + + return sbpl_plan; + } + + void SBPLRecovery::runBehavior() + { + if(!initialized_) + { + ROS_ERROR("Please initialize this recovery behavior before attempting to run it."); + return; + } + + ROS_INFO("Starting the sbpl recovery behavior"); + + for(int i=0; i <= planning_attempts_; ++i) + { + std::vector sbpl_plan = makePlan(); + + if(sbpl_plan.empty()) + { + ROS_ERROR("Unable to find a valid pose to plan to on the global plan."); + return; + } + + //ok... now we've got a plan so we need to try to follow it + local_planner_.setPlan(sbpl_plan); + ros::Rate r(control_frequency_); + ros::Time last_valid_control = ros::Time::now(); + while(ros::ok() && + last_valid_control + ros::Duration(controller_patience_) >= ros::Time::now() && + !local_planner_.isGoalReached()) + { + geometry_msgs::Twist cmd_vel; + bool valid_control = local_planner_.computeVelocityCommands(cmd_vel); + + if(valid_control) + last_valid_control = ros::Time::now(); + + vel_pub_.publish(cmd_vel); + r.sleep(); + } + + if(local_planner_.isGoalReached()) + ROS_INFO("The sbpl recovery behavior made it to its desired goal"); + else + ROS_WARN("The sbpl recovery behavior failed to make it to its desired goal"); + } + } +}; diff --git a/navigations/teb_local_planner/CHANGELOG.rst b/navigations/teb_local_planner/CHANGELOG.rst new file mode 100755 index 0000000..11b4f73 --- /dev/null +++ b/navigations/teb_local_planner/CHANGELOG.rst @@ -0,0 +1,407 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package teb_local_planner +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +0.9.1 (2020-05-29) +------------------ +* Fixed RobotFootprintModel visualization bug (thanks to Anson Wang) +* Reserve the size of the relevant obstacles vector to avoid excessive memory allocations (thanks to João Monteiro) +* CMake: Removed system include to avoid compiling issues on some platforms +* Contributors: Anson Wang, Christoph Rösmann, João Carlos Espiúca Monteiro + +0.9.0 (2020-05-26) +------------------ +* Added pill resp. stadium-shaped obstacle +* Changed minimum CMake version to 3.1 +* Improved efficiency of 3d h-signature computation +* Changed default value for parameter penalty_epsilon to 0.05 +* Improved efficiency of findClosedTrajectoryPose() +* Removed obsolete method isHorizonReductionAppropriate() +* Contributors: Christoph Rösmann, XinyuKhan + +0.8.4 (2019-12-02) +------------------ +* Fixed TEB autoResize if last TimeDiff is small +* Add a rotational threshold for identifying a warm start goal +* Contributors: Rainer Kümmerle + +0.8.3 (2019-10-25) +------------------ +* Limiting the control look-ahead pose to the first that execeeds the expected look-ahead time (thanks to Marco Bassa) +* test_optim_node fix circular obstacles (thanks to dtaranta) +* Fix shadow variable warning (thanks to Victor Lopez) +* Use SYSTEM when including external dependencies headers (thanks to Victor Lopez) +* Robustify initTrajectoryToGoal if a plan is given (thanks to Rainer Kuemmerle) +* Adding the option to shift ahead the target pose used to extract the velocity command (thanks to Marco Bassa) +* Fixed segfault in optimal_planner.cpp when clearing graph with unallocated optimizer. + Fixes `#158 `_. +* On footprintCost, fail only if footprint is in collision, not outside the map or on unknown space (thanks to corot) +* Native MoveBaseFlex support added: Implements both nav_core::BaseLocalPlanner and mbf_costmap_core::CostmapController abstract interfaces (thanks to corot) +* added warning if parameter optimal_time is <= 0 +* Nonlinear obstacle cost from EdgeInflatedObstacle also added to EdgeObstacle. + See `#140 `_. +* Fixed proper initialization of parameter obstacle_cost_exponent in case it is not loaded from the parameter server +* Contributors: Christoph Rösmann, Marco Bassa, Rainer Kuemmerle, Victor Lopez, corot, dtaranta + +0.8.2 (2019-07-02) +------------------ +* Allow scripts to be executable and usable by rosrun after catkin_make install and through the catkin release process (thanks to Devon Ash) +* Add nonlinear part to obstacle cost to improve narrow gap behavior. + Parameter `obstacle_cost_exponent` defines the exponent of the nonlinear cost term. + The default linear behavior is achieved by setting this parameter to 1 (default). + A value of 4 performed well in some tests and experiments (thanks to Howard Cochran). +* Parameter `global_plan_prune_distance` added via ros parameter server. +* Fixed SIGSEGV in optimizeAllTEBs() if main thread is interrupted by boost (thanks to Howard Cochran) +* Fixed SIGSEGV crash in deleteTebDetours() (thanks to Howard Cochran) +* On footprint visualization, avoid overshadowing by obstacles (thanks to corot) +* Do not ignore robot model on the association stage. + Important mostly for polygon footprint model (thanks to corot). +* Adjustable color for footprint visualization +* Showing (detected) infeasible robot poses in a separate marker namespace and color +* Added edge for minimizing Euclidean path length (parameter: `weight_shortest_path`) +* Ackermann steering conversion (python script): fixed direction inversion in backwards mode when `cmd_angle_instead_rotvel` is true (thanks to Tobi Loew) +* Fixed wrong skipping condition in AddEdgesKinematicsCarlike() (thanks to ShiquLIU) +* Never discarding the previous best teb in renewAndAnalyzeOldTebs (thanks to Marco Bassa) +* Allowing for the fallback to a different trajectory when the costmap check fails. This prevents the switch to unfeasible trajectories (thanks to Marco Bassa). +* Skipping the generation of the homotopy exploration graph in case the maximum number of allowed classes is reached (thanks to Marco Bassa) +* Changed isTrajectoryFeasible function to allow for a more accurate linear and angular discretization (thanks to Marco Bassa) +* Function TebOptimalPlanner::computeError() considers now the actual optimizer weights. + As a result, the default value of `selection_obst_cost_scale` is reduced (thanks to Howard Cochran). +* update to use non deprecated pluginlib macro (thanks to Mikael Arguedas) +* Avoiding h signature interpolation between coincident poses (thanks to Marco Bassa) +* New strategy for the deletion of detours: Detours are now determined w.r.t. the least-cost alternative and not w.r.t. just the goal heading. + Deletion of additional alternatives applies if either an initial backward motion is detected, if the transition time is much bigger than the duration of the best teb + and if a teb cannot be optimized (thanks to Marco Bassa). + Optionally allowing the usage of the initial plan orientation when initializing new tebs. +* Contributors: Christoph Rösmann, Mikael Arguedas, Devon Ash, Howard Cochran, Marco Bassa, ShiquLIU, Tobi Loew, corot + +0.8.1 (2018-08-14) +------------------ +* bugfix in calculateHSignature. Fixes `#90 `_. +* fixed centroid computation in a special case of polygon-obstacles +* Contributors: Christoph Rösmann + +0.8.0 (2018-08-06) +------------------ +* First melodic release +* Updated to new g2o API +* Migration to tf2 +* Contributors: Christoph Rösmann + +0.7.3 (2018-07-05) +------------------ +* Parameter `switching_blocking_period` added to homotopy class planner parameter group. + Values greater than zero enforce the homotopy class planner to only switch to new equivalence classes as soon + as the given period is expired (this might reduce oscillations in some scenarios). The value is set to zero seconds + by default in order to not change the behavior of existing configurations. +* Fixed unconsistent naming of parameter `global_plan_viapoint_sep`. + The parameter retrieved at startup was `global_plan_via_point_sep` and via dynamic_reconfigure it was `global_plan_viapoint_sep`. + `global_plan_via_point_sep` has now been replaced by `global_plan_viapoint_sep` since this is more consistent with the variable name + in the code as well as `weight_viapoint` and the ros wiki description. + In order to not break things, the old parameter name can still be used. However, a deprecated warning is printed. +* transformGlobalPlan searches now for the closest point within the complete subset of the global plan in the local costmap: + In every sampling interval, the global plan is processed in order to find the closest pose to the robot (as reference start) + and the current end pose (either local at costmap boundary or max_global_plan_lookahead_dist). + Previously, the search algorithm stopped as soon as the distance to the robot increased once. + This caused troubles with more complex global plans, hence the new strategy checks the complete subset + of the global plan in the local costmap for the closest distance to the robot. +* via-points that are very close to the current robot pose or behind the robot are now skipped (in non-ordered mode) +* Edge creation: minor performance improvement for dynamic obstacle edges +* dynamic_reconfigure: parameter visualize_with_time_as_z_axis_scale moved to group trajectory +* Contributors: Christoph Rösmann + +0.7.2 (2018-06-08) +------------------ +* Adds the possibility to provide via-points via a topic. + Currently, the user needs to decide whether to receive via-points from topic or to obtain them from the global reference plan + (e.g., activate the latter by setting global_plan_viapoint_sep>0 as before). + A small test script publish_viapoints.py is provided to demonstrate the feature within test_optim_node. +* Contributors: Christoph Rösmann + +0.7.1 (2018-06-05) +------------------ +* Fixed a crucial bug (from 0.6.6): A cost function for prefering a clockwise resp. anti-clockwise turn was enabled by default. + This cost function was only intended to be active only for recovering from an oscillating robot. + This cost led to a penalty for one of the turning directions and hence the maximum turning rate for the penalized direction could not be reached. + Furthermore, which is more crucial: since the penalty applied only to a small (initial) subset of the trajectory, the overall control performance was poor + (huge gap between planned motion and closed-loop trajectories led to frequent corrections of the robot pose and hence many motion reversals). +* Adds support for circular obstacle types. This includes support for the radius field in costmap_converter::ObstacleMsg +* rqt reconfigure: parameters are now grouped in tabs (robot, trajectory, viapoints, ...) +* Update to use non deprecated pluginlib macro +* Python scripts updated to new obstacle message definition. +* Fixed issue when start and end are at the same location (PR #43) +* Normalize marker quaternions in *test_optim_node* +* Contributors: Christoph Rösmann, Alexander Reimann, Mikael Arguedas, wollip + +0.7.0 (2017-09-23) +------------------ +* This update introduces support for dynamic obstacles (thanks to Franz Albers, who implemented and tested the code). + Dynamic obstacle support requires parameter *include\_dynamic\_obstacles* to be activated. + Note, this feature is still experimental and subject to testing. + Motion prediction is performed using a constant velocity model. + Dynamic obstacles might be incorporated as follows: + * via a custom message provided on topic ~/obstacles (warning: we changed the message type from teb_local_planner/ObstacleMsg to costmap_converter/ObstacleArrayMsg). + * via the CostmapToDynamicObstacles plugin as part of the costmap\_converter package (still experimental). + A tutorial is going to be provided soon. +* FeedbackMsg includes a ObstacleMsg instead of a polygon +* ObstacleMsg removed from package since it is now part of the costmap\_converter package. +* Homotopy class planer code update: graph search methods and equivalence classes (h-signatures) are now + implemented as subclasses of more general interfaces. +* TEB trajectory initialization now uses a max\_vel\_x argument instead of the desired time difference in order to give the optimizer a better warm start. + Old methods are marked as deprecated. This change does not affect users settings. +* Inplace rotations removed from trajectory initialization to improve convergence speed of the optimizer +* teb\_local\_planner::ObstacleMsg removed in favor of costmap\_converter::ObstacleArrayMsg. This also requires custom obstacle publishers to update to the new format +* the "new" trajectory resizing method is only activated, if "include_dynamic_obstacles" is set to true. + We introduced the non-fast mode with the support of dynamic obstacles + (which leads to better results in terms of x-y-t homotopy planning). + However, we have not yet tested this mode intensively, so we keep + the previous mode as default until we finish our tests. +* added parameter and code to update costmap footprint if it is dynamic (#49) +* Contributors: Franz Albers, Christoph Rösmann, procopiostein + +0.6.6 (2016-12-23) +------------------ +* Strategy for recovering from oscillating local plans added (see new parameters) +* Horizon reduction for resolving infeasible trajectories is not activated anymore if the global goal is already selected + (to avoid oscillations due to changing final orientations) +* Global plan orientations are now taken for TEB initialization if lobal_plan_overwrite_orientation==true +* Parameter max_samples added +* Further fixes (thanks to Matthias Füller and Daniel Neumann for providing patches) + +0.6.5 (2016-11-15) +------------------ +* The trajectory is now initialized backwards for goals close to and behind the robot. + Parameter 'allow_init_with_backwards_motion' added. +* Updated the TEB selection in the HomotopyClassPlanner. + * A new parameter is introduced to prefer the equivalence class of the initial plan + * Fixed some bugs related to the deletion of candidates and for keeping the equivalence class of the initial plan. +* Weight adaptation added for obstacles edges. + Added parameter 'weight_adapt_factor'. + Obstacle weights are repeatedly scaled by this factor in each outer TEB iteration. + Increasing weights iteratively instead of setting a huge value a-priori leads to better numerical conditions. +* Added a warning if the optim footprint + min_obstacle_dist is smaller than the costmap footprint. + Validation is performed by only comparing the inscribed radii of the footprints. +* Revision/extension of the reduced-horizon backup mode which is triggered in case infeasible trajectories are detected. +* Changed HSignature to a generic equivalence class +* Minor changes + +0.6.4 (2016-10-23) +------------------ +* New default obstacle association strategy: + During optimization graph creation, for each pose of the trajectory a + relevance detection is performed before considering the obstacle + during optimization. New parameters are introduced. The + old strategy is kept as 'legacy' strategy (see parameters). +* Computation of velocities, acceleration and turning radii extended: + Added an option to compute the actual arc length + instead of using the Euclidean distance approximation (see parameter `exact_arc_length`. +* Added intermediate edge layer for unary, binary and multi edges in order to reduce code redundancy. +* Script for visualizing velocity profile updated to accept the feedback topic name via rosparam server +* Removed TebConfig dependency in TebVisualization +* PolygonObstacle can now be constructed using a vertices container +* HomotopyClassPlanner public interface extended +* Changed H-Signature computation to work 'again' with few obstacles such like 1 or 2 +* Removed inline flags in visualization.cpp +* Removed inline flags in timed_elastic_band.cpp. + Fixes `#15 `_. +* Increased bounds of many variables in dynamic_reconfigure. + Resolves `#14 `_. + The particular variables are maximum velocities, maximum accelerations, + minimum turning radius,... + Note: optimization weights and dt_ref as well as dt_hyst are not + tuned for velocities and accelerations beyond + the default values (e.g. >1 m/s). Just increasing the maximum velocity + bounds without adjusting the other parameters leads to an insufficient behavior. +* Default parameter value update: 'costmap_obstacles_behind_robot_dist' +* Additional minor fixes. + +0.6.3 (2016-08-17) +------------------ +* Changed the f0 function for calculating the H-Signature. + The new one seems to be more robust for a much larger number of obstacles + after some testing. +* HomotopyClassPlanner: vertex collision check removed since collisions will be determined in the edge collision check again +* Fixed distance calculation polygon-to-polygon-obstacle +* cmake config exports now *include directories* of external packages for dependent projects +* Enlarged upper bounds on goal position and orientation tolerances in *dynamic_reconfigure*. Fixes #13. + + +0.6.2 (2016-06-15) +------------------ +* Fixed bug causing the goal to disappear in case the robot arrives with non-zero orientation error. +* Inflation mode for obstacles added. +* The homotopy class of the global plan is now always forced to be initialized as trajectory. +* The initial velocity of the robot is now taken into account correctly for + all candidate trajectories. +* Removed a check in which the last remaining candidate trajectory was rejected if it was close to an obstacle. + This fix addresses issue `#7 `_ + +0.6.1 (2016-05-23) +------------------ +* Debian ARM64 library path added to SuiteSparse cmake find-script (resolves ARM compilation issue) + + +0.6.0 (2016-05-22) +------------------ +* Extended support to holonomic robots +* Wrong parameter namespace for *costmap_converter* plugins fixed +* Added the option to scale the length of the hcp sampling area +* Compiler warnings fixed. +* Workaround for compilation issues that are caused by a bug in boost 1.58 + concerning the graph library (missing move constructor/assignment operator + in boost source). +* Using *tf_listener* from *move_base* now. +* Via-point support improved. + Added the possibility to take the actual order of via-points into account. + Additionally, via-points beyond start and goal are now included. +* Obsolete include of the angles package header removed +* Update to package.xml version 2 +* Some other minor fixes. + + +0.4.0 (2016-04-19) +------------------ +* The teb_local_planner supports a path-following mode (w.r.t. the global plan) and via-points now. + This allows the user to adapt the tradeoff between time-optimality and path-following. + Check out the new tutorial: "Following the Global Plan (Via-Points)". +* All external configuration and launch files are removed, since they are part + of the new teb_local_planner_tutorials package. + + +0.3.1 (2016-04-14) +------------------ +* Fixed wrong coordinate transformation in 'line' and 'polygon' footprint models. +* Trajectory selection strategy in case of multiple topologies updated: + * The obstacle costs for selection can now be scaling separately. + * The cost regarding time optimality can now be replaced by the actual transition time. + * Added a hysteresis to cost comparison between a new and the previously selected trajectory. + * In the default parameter setting the strategy is similar to release 0.3.0. +* Warning message removed that occured if an odom message with only zeros was received. + + +0.3.0 (2016-04-08) +------------------ +* Different/custom robot footprints are now supported and subject to optimization (refer to the new tutorial!). +* The new robot footprint is also visualized using the common marker topic. +* The strategy of taking occupied costmap cells behind the robot into account has been improved. + These changes significantly improve navigation close to walls. +* Parameter 'max_global_plan_lookahead_dist' added. + Previously, the complete subset of the global plan contained in the local costmap + was taken into account for choosing the current intermediate goal point. With this parameter, the maximum + length of the reference global plan can be limited. The actual global plan subset + is now computed using the logical conjunction of both local costmap size and 'max_global_plan_lookahead_dist'. +* Bug fixes: + * Fixed a compilation issue on ARM architectures + * If custom obstacles are used, the container with old obstacles is now cleared properly. +* Parameter cleanup: + * "weight_X_obstacle" parameters combined to single parameter "weight_obstacle". + * "X_obstacle_poses_affected" parameters combined to single parameter "obstacle_poses_affected". + * Deprecated parameter 'costmap_emergency_stop_dist' removed. +* Code cleanup + + +0.2.3 (2016-02-01) +------------------ +* Marker lifetime changed +* In case the local planner detects an infeasible trajectory it does now try to + reduce the horizon to 50 percent of the length. The trajectory is only reduced + if some predefined cases are detected. + This mechanism constitutes a backup behavior. +* Improved carlike robot support. + Instead of commanding the robot using translational and rotational velocities, + the robot might also be commanded using the transl. velocity and steering angle. + Appropriate parameters are added to the config. +* Changed default parameter for 'h_signature_threshold' from 0.01 to 0.1 to better match the actual precision. +* Some python scripts for data conversion added +* Minor other changes + +0.2.2 (2016-01-11) +------------------ +* Carlike robots (ackermann steering) are supported from now on (at least experimentally) + by specifying a minimum bound on the turning radius. + Currently, the output of the planner in carlike mode is still (v,omega). + Since I don't have any real carlike robot, I would be really happy if someone could provide me with + some feedback to further improve/extend the support. +* Obstacle cost function modified to avoid undesired jerks in the trajectory. +* Added a feedback message that contains current trajectory information (poses, velocities and temporal information). + This is useful for analyzing and debugging the velocity profile e.g. at runtime. + The message will be published only if it's activated (rosparam). + A small python script is added to plot the velocity profile (while *test_optim_node* runs). +* Cost functions are now taking the direction/sign of the translational velocity into account: + Specifying a maximum backwards velocity other than forward velocity works now. + Additionally, the change in acceleration is now computed correctly if the robot switches directions. +* The global plan is now pruned such that already passed posses are cut off + (relevant for global planners with *planning_rate=0*). +* Fixed issue#1: If a global planner with *planning_rate=0* was used, + a TF timing/extrapolation issue appeared after some time. +* The planner resets now properly if the velocity command cannot be computed due to invalid optimization results. + + +0.2.1 (2015-12-30) +------------------ +* This is an important bugfix release. +* Fixed a major issue concerning the stability and performance of the optimization process. Each time the global planner was updating the global plan, the local planner was resetted completely even if + the updated global plan did not differ from the previous one. This led to stupid reinitializations and a slighly jerky behavior if the update rate of the global planner was high (each 0.5-2s). + From now on the local planner is able to utilize the global plan as a warm start and determine automatically whether to reinitialize or not. +* Support for polygon obstacles extended and improved (e.g. the homotopy class planner does now compute actual distances to the polygon rather than utilizing the distance to the centroid). + +0.2.0 (2015-12-23) +------------------ +* The teb_local_planner supports costmap_converter plugins (pluginlib) from now on. Those plugins convert occupied costmap2d cells into polygon shapes. + The costmap_converter is disabled by default, since the extension still needs to be tested (parameter choices, computation time advantages, etc.). + A tutorial will explain how to activate the converter using the ros-param server. + +0.1.11 (2015-12-12) +------------------- +* This is a bugfix release (it fixes a lot of issues which occured frequently when the robot was close to the goal) + +0.1.10 (2015-08-13) +------------------- +* The optimizer copies the global plan as initialization now instead of using a simple straight line approximation. +* Some bugfixes and improvements + +0.1.9 (2015-06-24) +------------------ +* Fixed a segmentation fault issue. This minor update is crucial for stability. + +0.1.8 (2015-06-08) +------------------ +* Custom obstacles can be included via publishing dedicated messages +* Goal-reached-condition also checks orientation error (desired yaw) now +* Numerical improvements of the h-signature calculation +* Minor bugfixes + +0.1.7 (2015-05-22) +------------------ +* Finally fixed saucy compilation issue by retaining compatiblity to newer distros + (my "new" 13.10 VM helps me to stop spamming new releases for testing). + +0.1.6 (2015-05-22) +------------------ +* Fixed compilation errors on ubuntu saucy caused by different FindEigen.cmake scripts. + I am not able to test releasing on saucy, forcing me to release again and again. Sorry. + +0.1.5 (2015-05-21) +------------------ +* Added possibility to dynamically change parameters of test_optim_node using dynamic reconfigure. +* Fixed a wrong default-min-max tuple in the dynamic reconfigure config. +* Useful config and launch files are now added to cmake install. +* Added install target for the test_optim_node executable. + +0.1.4 (2015-05-20) +------------------ +* Fixed compilation errors on ROS Jade + +0.1.3 (2015-05-20) +------------------ +* Fixed compilation errors on ubuntu saucy + +0.1.2 (2015-05-19) +------------------ +* Removed unused include that could break compilation. + +0.1.1 (2015-05-19) +------------------ +* All files added to the indigo-devel branch +* Initial commit +* Contributors: Christoph Rösmann diff --git a/navigations/teb_local_planner/CMakeLists.txt b/navigations/teb_local_planner/CMakeLists.txt new file mode 100755 index 0000000..165527d --- /dev/null +++ b/navigations/teb_local_planner/CMakeLists.txt @@ -0,0 +1,284 @@ +cmake_minimum_required(VERSION 3.1) +project(teb_local_planner) + +# Set to Release in order to speed up the program significantly +set(CMAKE_BUILD_TYPE Release) #None, Debug, Release, RelWithDebInfo, MinSizeRel + +## Find catkin macros and libraries +find_package(catkin REQUIRED COMPONENTS + base_local_planner + costmap_2d + costmap_converter + cmake_modules + dynamic_reconfigure + geometry_msgs + interactive_markers + message_generation + nav_core + nav_msgs + mbf_costmap_core + mbf_msgs + roscpp + std_msgs + pluginlib + tf2 + tf2_eigen + tf2_geometry_msgs + tf2_ros + visualization_msgs +) +message(STATUS "System: ${CMAKE_SYSTEM}") +## System dependencies are found with CMake's conventions +SET(CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH} ${PROJECT_SOURCE_DIR}/cmake_modules) +message(STATUS "${CMAKE_MODULE_PATH}") +find_package(Boost REQUIRED COMPONENTS system thread graph) +find_package(SUITESPARSE REQUIRED) +find_package(G2O REQUIRED) + +# Eigen3 FindScript Backward compatibility (ubuntu saucy) +# Since FindEigen.cmake is deprecated starting from jade. +if (EXISTS "FindEigen3.cmake") + find_package(Eigen3 REQUIRED) + set(Eigen_INCLUDE_DIRS ${Eigen3_INCLUDE_DIRS}) +elseif (EXISTS "FindEigen.cmake") + find_package(Eigen REQUIRED) +elseif (EXISTS "FindEigen.cmake") + message(WARNING "No findEigen cmake script found. You must provde one of them, + e.g. by adding it to ${PROJECT_SOURCE_DIR}/cmake_modules.") +endif (EXISTS "FindEigen3.cmake") + +set(EXTERNAL_INCLUDE_DIRS ${Eigen_INCLUDE_DIRS} ${SUITESPARSE_INCLUDE_DIRS} ${G2O_INCLUDE_DIR}) +set(EXTERNAL_LIBS ${SUITESPARSE_LIBRARIES} ${G2O_LIBRARIES}) + +## Uncomment this if the package has a setup.py. This macro ensures +## modules and global scripts declared therein get installed +## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html +# catkin_python_setup() + + +## C++11 support +## Unfortunately, the 3d-party dependency libg2o requires c++11 starting from ROS Jade. +## Even if the ROS Jade specifications do not want c++11-only packages, +## we cannot compile without c++11 enabled. Another option would be to downgrade +## libg2o third-party package. +## By now, if you do not want c++11, please refer to the ros indigo version. +IF(NOT MSVC) + include(CheckCXXCompilerFlag) + CHECK_CXX_COMPILER_FLAG("-std=c++11" COMPILER_SUPPORTS_CXX11) + CHECK_CXX_COMPILER_FLAG("-std=c++0x" COMPILER_SUPPORTS_CXX0X) +if(COMPILER_SUPPORTS_CXX11) + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11") +elseif(COMPILER_SUPPORTS_CXX0X) + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++0x") +else() + message(STATUS "The compiler ${CMAKE_CXX_COMPILER} has no C++11 support which is required + by linked third party packages starting from ROS Jade. Ignore this message for ROS Indigo.") +endif() +endif() + +################################################ +## Declare ROS messages, services and actions ## +################################################ + +## To declare and build messages, services or actions from within this +## package, follow these steps: +## * Let MSG_DEP_SET be the set of packages whose message types you use in +## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...). +## * In the file package.xml: +## * add a build_depend and a run_depend tag for each package in MSG_DEP_SET +## * If MSG_DEP_SET isn't empty the following dependencies might have been +## pulled in transitively but can be declared for certainty nonetheless: +## * add a build_depend tag for "message_generation" +## * add a run_depend tag for "message_runtime" +## * In this file (CMakeLists.txt): +## * add "message_generation" and every package in MSG_DEP_SET to +## find_package(catkin REQUIRED COMPONENTS ...) +## * add "message_runtime" and every package in MSG_DEP_SET to +## catkin_package(CATKIN_DEPENDS ...) +## * uncomment the add_*_files sections below as needed +## and list every .msg/.srv/.action file to be processed +## * uncomment the generate_messages entry below +## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...) + +## Generate messages in the 'msg' folder +add_message_files( + FILES + TrajectoryPointMsg.msg + TrajectoryMsg.msg + FeedbackMsg.msg +) + +## Generate services in the 'srv' folder +# add_service_files( +# FILES +# Service1.srv +# Service2.srv +# ) + +## Generate actions in the 'action' folder +# add_action_files( +# FILES +# Action1.action +# Action2.action +# ) + +## Generate added messages and services with any dependencies listed here +generate_messages( + DEPENDENCIES + geometry_msgs std_msgs costmap_converter +) + +#add dynamic reconfigure api +#find_package(catkin REQUIRED dynamic_reconfigure) +generate_dynamic_reconfigure_options( + cfg/TebLocalPlannerReconfigure.cfg +) + + +################################### +## catkin specific configuration ## +################################### +## The catkin_package macro generates cmake config files for your package +## Declare things to be passed to dependent projects +## INCLUDE_DIRS: uncomment this if you package contains header files +## LIBRARIES: libraries you create in this project that dependent projects also need +## CATKIN_DEPENDS: catkin_packages dependent projects also need +## DEPENDS: system dependencies of this project that dependent projects also need +catkin_package( + INCLUDE_DIRS include ${EXTERNAL_INCLUDE_DIRS} + LIBRARIES teb_local_planner ${EXTERNAL_LIBS} + CATKIN_DEPENDS + base_local_planner + costmap_2d + costmap_converter + dynamic_reconfigure + geometry_msgs + interactive_markers + message_runtime + nav_core + nav_msgs + pluginlib + roscpp + mbf_costmap_core + std_msgs + tf2 + tf2_ros + visualization_msgs + DEPENDS SUITESPARSE G2O +) + +########### +## Build ## +########### + +## Specify additional locations of header files +## Your package locations should be listed before other locations +include_directories(include) +include_directories( + ${EXTERNAL_INCLUDE_DIRS} + ${catkin_INCLUDE_DIRS} +) + +## Build the teb_local_planner library + +add_library(teb_local_planner + src/timed_elastic_band.cpp + src/optimal_planner.cpp + src/obstacles.cpp + src/visualization.cpp + src/recovery_behaviors.cpp + src/teb_config.cpp + src/homotopy_class_planner.cpp + src/teb_local_planner_ros.cpp + src/graph_search.cpp +) + +# Dynamic reconfigure: make sure configure headers are built before any node using them +add_dependencies(teb_local_planner ${PROJECT_NAME}_gencfg) +# Generate messages before compiling the lib +add_dependencies(teb_local_planner ${PROJECT_NAME}_generate_messages_cpp) + +target_link_libraries(teb_local_planner + ${EXTERNAL_LIBS} + ${catkin_LIBRARIES} +) + + + +## Build additional executables + +add_executable(test_optim_node src/test_optim_node.cpp) + +target_link_libraries(test_optim_node + teb_local_planner + ${EXTERNAL_LIBS} + ${catkin_LIBRARIES} +) + + +############# +## Install ## +############# + +# all install targets should use catkin DESTINATION variables +# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html + +## Mark executable scripts (Python etc.) for installation +## in contrast to setup.py, you can choose the destination +install(PROGRAMS + scripts/cmd_vel_to_ackermann_drive.py + scripts/export_to_mat.py + scripts/export_to_svg.py + scripts/publish_dynamic_obstacle.py + scripts/publish_test_obstacles.py + scripts/publish_viapoints.py + scripts/visualize_velocity_profile.py + DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) + +## Mark executables and/or libraries for installation +install(TARGETS teb_local_planner + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +) +install(TARGETS test_optim_node + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) + +## Mark cpp header files for installation +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} + #FILES_MATCHING PATTERN "*.h" + PATTERN ".svn" EXCLUDE +) + +## Mark other files for installation (e.g. launch and bag files, etc.) +install(FILES + teb_local_planner_plugin.xml + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) + +install(DIRECTORY + launch cfg scripts + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} + PATTERN ".svn" EXCLUDE +) + +############# +## Testing ## +############# + +if (CATKIN_ENABLE_TESTING) + catkin_add_gtest(test_teb_basics test/teb_basics.cpp) + if(TARGET test_teb_basics) + target_link_libraries(test_teb_basics teb_local_planner) + endif() +endif() + +## Add gtest based cpp test target and link libraries +# catkin_add_gtest(${PROJECT_NAME}-test test/test_teb_local_planner.cpp) +# if(TARGET ${PROJECT_NAME}-test) +# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME}) +# endif() + +## Add folders to be run by python nosetests +# catkin_add_nosetests(test) diff --git a/navigations/teb_local_planner/LICENSE b/navigations/teb_local_planner/LICENSE new file mode 100755 index 0000000..d4658cc --- /dev/null +++ b/navigations/teb_local_planner/LICENSE @@ -0,0 +1,28 @@ +Copyright (c) 2016, TU Dortmund - Lehrstuhl RST +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name of teb_local_planner nor the names of its + contributors may be used to endorse or promote products derived from + this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + diff --git a/navigations/teb_local_planner/README.md b/navigations/teb_local_planner/README.md new file mode 100755 index 0000000..0f01951 --- /dev/null +++ b/navigations/teb_local_planner/README.md @@ -0,0 +1,56 @@ +teb_local_planner ROS Package +============================= + +The teb_local_planner package implements a plugin to the base_local_planner of the 2D navigation stack. +The underlying method called Timed Elastic Band locally optimizes the robot's trajectory with respect to trajectory execution time, +separation from obstacles and compliance with kinodynamic constraints at runtime. + +Refer to http://wiki.ros.org/teb_local_planner for more information and tutorials. + +Build status of the *melodic-devel* branch: +- ROS Buildfarm (Melodic): [![Melodic Status](http://build.ros.org/buildStatus/icon?job=Mdev__teb_local_planner__ubuntu_bionic_amd64)](http://build.ros.org/job/Mdev__teb_local_planner__ubuntu_bionic_amd64/) + + +## Citing the Software + +*Since a lot of time and effort has gone into the development, please cite at least one of the following publications if you are using the planner for your own research:* + +- C. Rösmann, F. Hoffmann and T. Bertram: Integrated online trajectory planning and optimization in distinctive topologies, Robotics and Autonomous Systems, Vol. 88, 2017, pp. 142–153. +- C. Rösmann, W. Feiten, T. Wösch, F. Hoffmann and T. Bertram: Trajectory modification considering dynamic constraints of autonomous robots. Proc. 7th German Conference on Robotics, Germany, Munich, May 2012, pp 74–79. +- C. Rösmann, W. Feiten, T. Wösch, F. Hoffmann and T. Bertram: Efficient trajectory optimization using a sparse model. Proc. IEEE European Conference on Mobile Robots, Spain, Barcelona, Sept. 2013, pp. 138–143. +- C. Rösmann, F. Hoffmann and T. Bertram: Planning of Multiple Robot Trajectories in Distinctive Topologies, Proc. IEEE European Conference on Mobile Robots, UK, Lincoln, Sept. 2015. +- C. Rösmann, F. Hoffmann and T. Bertram: Kinodynamic Trajectory Optimization and Control for Car-Like Robots, IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), Vancouver, BC, Canada, Sept. 2017. + +Buy Me A Coffee + +## Videos + +The left of the following videos presents features of the package and shows examples from simulation and real robot situations. +Some spoken explanations are included in the audio track of the video. +The right one demonstrates features introduced in version 0.2 (supporting car-like robots and costmap conversion). Please watch the left one first. + + + + +## License + +The *teb_local_planner* package is licensed under the BSD license. +It depends on other ROS packages, which are listed in the package.xml. They are also BSD licensed. + +Some third-party dependencies are included that are licensed under different terms: + - *Eigen*, MPL2 license, http://eigen.tuxfamily.org + - *libg2o* / *g2o* itself is licensed under BSD, but the enabled *csparse_extension* is licensed under LGPL3+, + https://github.com/RainerKuemmerle/g2o. [*CSparse*](http://www.cise.ufl.edu/research/sparse/CSparse/) is included as part of the *SuiteSparse* collection, http://www.suitesparse.com. + - *Boost*, Boost Software License, http://www.boost.org + +All packages included are distributed in the hope that they will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the licenses for more details. + +## Requirements + +Install dependencies (listed in the *package.xml* and *CMakeLists.txt* file) using *rosdep*: + + rosdep install teb_local_planner + + diff --git a/navigations/teb_local_planner/cfg/TebLocalPlannerReconfigure.cfg b/navigations/teb_local_planner/cfg/TebLocalPlannerReconfigure.cfg new file mode 100755 index 0000000..2b04810 --- /dev/null +++ b/navigations/teb_local_planner/cfg/TebLocalPlannerReconfigure.cfg @@ -0,0 +1,447 @@ +#!/usr/bin/env python + +from dynamic_reconfigure.parameter_generator_catkin import * +#from local_planner_limits import add_generic_localplanner_params + +gen = ParameterGenerator() + +# This unusual line allows to reuse existing parameter definitions +# that concern all localplanners +#add_generic_localplanner_params(gen) + +# For integers and doubles: +# Name Type Reconfiguration level +# Description +# Default Min Max + + +grp_trajectory = gen.add_group("Trajectory", type="tab") + +# Trajectory +grp_trajectory.add("teb_autosize", bool_t, 0, + "Enable the automatic resizing of the trajectory during optimization (based on the temporal resolution of the trajectory, recommended)", + True) + +grp_trajectory.add("dt_ref", double_t, 0, + "Temporal resolution of the planned trajectory (usually it is set to the magnitude of the 1/control_rate)", + 0.3, 0.01, 1) + +grp_trajectory.add("dt_hysteresis", double_t, 0, + "Hysteresis that is utilized for automatic resizing depending on the current temporal resolution (dt): usually 10% of dt_ref", + 0.1, 0.002, 0.5) + +grp_trajectory.add("global_plan_overwrite_orientation", bool_t, 0, + "Some global planners are not considering the orientation at local subgoals between start and global goal, therefore determine it automatically", + True) + +grp_trajectory.add("allow_init_with_backwards_motion", bool_t, 0, + "If true, the underlying trajectories might be initialized with backwards motions in case the goal is behind the start within the local costmap (this is only recommended if the robot is equipped with rear sensors)", + False) + +grp_trajectory.add("max_global_plan_lookahead_dist", double_t, 0, + "Specify maximum length (cumulative Euclidean distances) of the subset of the global plan taken into account for optimization [if 0 or negative: disabled; the length is also bounded by the local costmap size]", + 3.0, 0, 50.0) + +grp_trajectory.add("force_reinit_new_goal_dist", double_t, 0, + "Force the planner to reinitialize the trajectory if a previous goal is updated with a seperation of more than the specified value in meters (skip hot-starting)", + 1.0, 0.0, 10.0) + +grp_trajectory.add("force_reinit_new_goal_angular", double_t, 0, + "Force the planner to reinitialize the trajectory if a previous goal is updated with a rotational difference of more than the specified value in radians (skip hot-starting)", + 0.78, 0.0, 4.0) + +grp_trajectory.add("feasibility_check_no_poses", int_t, 0, + "Specify up to which pose (under the feasibility_check_lookahead_distance) on the predicted plan the feasibility should be checked each sampling interval; if -1, all poses up to feasibility_check_lookahead_distance are checked.", + 5, -1, 50) + +grp_trajectory.add("feasibility_check_lookahead_distance", double_t, 0, + "Specify up to which distance (and with an index below feasibility_check_no_poses) from the robot the feasibility should be checked each sampling interval; if -1, all poses up to feasibility_check_no_poses are checked.", + -1, -1, 20) + +grp_trajectory.add("exact_arc_length", bool_t, 0, + "If true, the planner uses the exact arc length in velocity, acceleration and turning rate computations [-> increased cpu time], otherwise the euclidean approximation is used.", + False) + +grp_trajectory.add("publish_feedback", bool_t, 0, + "Publish planner feedback containing the full trajectory and a list of active obstacles (should be enabled only for evaluation or debugging purposes)", + False) + +grp_trajectory.add("control_look_ahead_poses", int_t, 0, + "Index of the pose used to extract the velocity command", + 1, 1, 100) + +grp_trajectory.add("prevent_look_ahead_poses_near_goal", int_t, 0, + "Prevents control_look_ahead_poses to look within this many poses of the goal in order to prevent overshoot & oscillation when xy_goal_tolerance is very small", + 0, 0, 20) + +grp_trajectory.add("visualize_with_time_as_z_axis_scale", double_t, 0, + "If this value is bigger than 0, the trajectory and obstacles are visualized in 3d using the time as the z-axis scaled by this value. Most useful for dynamic obstacles.", + 0, 0, 1) + +# ViaPoints +grp_viapoints = gen.add_group("ViaPoints", type="tab") + +grp_viapoints.add("global_plan_viapoint_sep", double_t, 0, + "Min. separation between each two consecutive via-points extracted from the global plan [if negative: disabled]", + -0.1, -0.1, 5.0) + +grp_viapoints.add("via_points_ordered", bool_t, 0, + "If true, the planner adheres to the order of via-points in the storage container", + False) + +# Robot +grp_robot = gen.add_group("Robot", type="tab") + +grp_robot.add("max_vel_x", double_t, 0, + "Maximum velocity in the x direction of the robot. May be overruled by the max_vel_trans parameter", + 0.4, 0.01, 100) + +grp_robot.add("max_vel_x_backwards", double_t, 0, + "Maximum translational velocity of the robot for driving backwards", + 0.2, 0.01, 100) + +grp_robot.add("max_vel_theta", double_t, 0, + "Maximum angular velocity of the robot", + 0.3, 0.01, 100) + +grp_robot.add("acc_lim_x", double_t, 0, + "Maximum translational acceleration of the robot", + 0.5, 0.01, 100) + +grp_robot.add("acc_lim_theta", double_t, 0, + "Maximum angular acceleration of the robot", + 0.5, 0.01, 100) + +grp_robot.add("is_footprint_dynamic", bool_t, 0, + "If true, updated the footprint before checking trajectory feasibility", + False) + +grp_robot.add("use_proportional_saturation", bool_t, 0, + "If true, reduce all twists components (linear x and y, and angular z) proportionally if any exceed its corresponding bounds, instead of saturating each one individually", + False) +grp_robot.add("transform_tolerance", double_t, 0, + "Tolerance when querying the TF Tree for a transformation (seconds)", + 0.5, 0.001, 20) + +# Robot/Carlike + +grp_robot_carlike = grp_robot.add_group("Carlike", type="hide") + +grp_robot_carlike.add("min_turning_radius", double_t, 0, + "Minimum turning radius of a carlike robot (diff-drive robot: zero)", + 0.0, 0.0, 50.0) + +grp_robot_carlike.add("wheelbase", double_t, 0, + "The distance between the drive shaft and steering axle (only required for a carlike robot with 'cmd_angle_instead_rotvel' enabled); The value might be negative for back-wheeled robots!", + 1.0, -10.0, 10.0) + +grp_robot_carlike.add("cmd_angle_instead_rotvel", bool_t, 0, + "Substitute the rotational velocity in the commanded velocity message by the corresponding steering angle (check 'axles_distance')", + False) + +# Robot/Omni + +grp_robot_omni = grp_robot.add_group("Omnidirectional", type="hide") + +grp_robot_omni.add("max_vel_y", double_t, 0, + "Maximum strafing velocity of the robot (should be zero for non-holonomic robots!). May be overruled by the max_vel_trans parameter", + 0.0, 0.0, 100) + +grp_robot_omni.add("max_vel_trans", double_t, 0, + "Maximum linear velocity of the robot. Will limit max_vel_x and max_vel_y when their linear combination exceeds its value. When set to default 0.0, it will be set equal to max_vel_x.", + 0.0, 0.0, 100) + +grp_robot_omni.add("acc_lim_y", double_t, 0, + "Maximum strafing acceleration of the robot", + 0.5, 0.01, 100) + +# GoalTolerance +grp_goal = gen.add_group("GoalTolerance", type="tab") + +grp_goal.add("xy_goal_tolerance", double_t, 0, + "Allowed final euclidean distance to the goal position", + 0.2, 0.001, 10) + +grp_goal.add("yaw_goal_tolerance", double_t, 0, + "Allowed final orientation error to the goal orientation", + 0.1, 0.001, 3.2) + +grp_goal.add("free_goal_vel", bool_t, 0, + "Allow the robot's velocity to be nonzero for planning purposes (the robot can arrive at the goal with max speed)", + False) + +grp_goal.add("trans_stopped_vel", double_t, 0, + "Below what maximum velocity we consider the robot to be stopped in translation", + 0.1, 0.0) + +grp_goal.add("theta_stopped_vel", double_t, 0, + "Below what maximum rotation velocity we consider the robot to be stopped in rotation", + 0.1, 0.0) + +# Obstacles +grp_obstacles = gen.add_group("Obstacles", type="tab") + +grp_obstacles.add("min_obstacle_dist", double_t, 0, + "Minimum desired separation from obstacles", + 0.5, 0, 10) + +grp_obstacles.add("inflation_dist", double_t, 0, + "Buffer zone around obstacles with non-zero penalty costs (should be larger than min_obstacle_dist in order to take effect)", + 0.6, 0, 15) + +grp_obstacles.add("dynamic_obstacle_inflation_dist", double_t, 0, + "Buffer zone around predicted locations of dynamic obstacles with non-zero penalty costs (should be larger than min_obstacle_dist in order to take effect)", + 0.6, 0, 15) + +grp_obstacles.add("include_dynamic_obstacles", bool_t, 0, + "Specify whether the movement of dynamic obstacles should be predicted by a constant velocity model (this also changes the homotopy class search). If false, all obstacles are considered to be static.", + False) + +grp_obstacles.add("include_costmap_obstacles", bool_t, 0, + "Specify whether the obstacles in the costmap should be taken into account directly (this is necessary if no seperate clustering and detection is implemented)", + True) + +grp_obstacles.add("legacy_obstacle_association", bool_t, 0, + "If true, the old association strategy is used (for each obstacle, find the nearest TEB pose), otherwise the new one (for each teb pose, find only 'relevant' obstacles).", + False) + +grp_obstacles.add("obstacle_association_force_inclusion_factor", double_t, 0, + "The non-legacy obstacle association technique tries to connect only relevant obstacles with the discretized trajectory during optimization, all obstacles within a specifed distance are forced to be included (as a multiple of min_obstacle_dist), e.g. choose 2.0 in order to consider obstacles within a radius of 2.0*min_obstacle_dist.", + 1.5, 0.0, 100.0) + +grp_obstacles.add("obstacle_association_cutoff_factor", double_t, 0, + "See obstacle_association_force_inclusion_factor, but beyond a multiple of [value]*min_obstacle_dist all obstacles are ignored during optimization. obstacle_association_force_inclusion_factor is processed first.", + 5.0, 1.0, 100.0) + +grp_obstacles.add("costmap_obstacles_behind_robot_dist", double_t, 0, + "Limit the occupied local costmap obstacles taken into account for planning behind the robot (specify distance in meters)", + 1.5, 0.0, 20.0) + +grp_obstacles.add("obstacle_poses_affected", int_t, 0, + "The obstacle position is attached to the closest pose on the trajectory to reduce computational effort, but take a number of neighbors into account as well", + 30, 0, 200) + +# Obstacle - Velocity ratio parameters +grp_obstacles_velocity_limit = grp_obstacles.add_group("Reduce velocity near obstacles") + +grp_obstacles_velocity_limit.add("obstacle_proximity_ratio_max_vel", double_t, 0, + "Ratio of the maximum velocities used as an upper bound when reducing the speed due to the proximity to static obstacles", + 1, 0, 1) + +grp_obstacles_velocity_limit.add("obstacle_proximity_lower_bound", double_t, 0, + "Distance to a static obstacle for which the velocity should be lower", + 0, 0, 10) + +grp_obstacles_velocity_limit.add("obstacle_proximity_upper_bound", double_t, 0, + "Distance to a static obstacle for which the velocity should be higher", + 0.5, 0, 10) + +# Optimization +grp_optimization = gen.add_group("Optimization", type="tab") + +grp_optimization.add("no_inner_iterations", int_t, 0, + "Number of solver iterations called in each outerloop iteration", + 5, 1, 100) + +grp_optimization.add("no_outer_iterations", int_t, 0, + "Each outerloop iteration automatically resizes the trajectory and invokes the internal optimizer with no_inner_iterations", + 4, 1, 100) + +grp_optimization.add("optimization_activate", bool_t, 0, + "Activate the optimization", + True) + +grp_optimization.add("optimization_verbose", bool_t, 0, + "Print verbose information", + False) + +grp_optimization.add("penalty_epsilon", double_t, 0, + "Add a small safty margin to penalty functions for hard-constraint approximations", + 0.05, 0, 1.0) + +grp_optimization.add("weight_max_vel_x", double_t, 0, + "Optimization weight for satisfying the maximum allowed translational velocity", + 2, 0, 1000) + +grp_optimization.add("weight_max_vel_y", double_t, 0, + "Optimization weight for satisfying the maximum allowed strafing velocity (in use only for holonomic robots)", + 2, 0, 1000) + +grp_optimization.add("weight_max_vel_theta", double_t, 0, + "Optimization weight for satisfying the maximum allowed angular velocity", + 1, 0, 1000) + +grp_optimization.add("weight_acc_lim_x", double_t, 0, + "Optimization weight for satisfying the maximum allowed translational acceleration", + 1, 0, 1000) + +grp_optimization.add("weight_acc_lim_y", double_t, 0, + "Optimization weight for satisfying the maximum allowed strafing acceleration (in use only for holonomic robots)", + 1, 0, 1000) + +grp_optimization.add("weight_acc_lim_theta", double_t, 0, + "Optimization weight for satisfying the maximum allowed angular acceleration", + 1, 0, 1000) + +grp_optimization.add("weight_kinematics_nh", double_t, 0, + "Optimization weight for satisfying the non-holonomic kinematics", + 1000 , 0, 10000) + +grp_optimization.add("weight_kinematics_forward_drive", double_t, 0, + "Optimization weight for forcing the robot to choose only forward directions (positive transl. velocities, only diffdrive robot)", + 1, 0, 10000) + +grp_optimization.add("weight_kinematics_turning_radius", double_t, 0, + "Optimization weight for enforcing a minimum turning radius (carlike robots)", + 1, 0, 1000) + +grp_optimization.add("weight_optimaltime", double_t, 0, + "Optimization weight for contracting the trajectory w.r.t. transition time", + 1, 0, 1000) + +grp_optimization.add("weight_shortest_path", double_t, 0, + "Optimization weight for contracting the trajectory w.r.t. path length", + 0, 0, 100) + +grp_optimization.add("weight_obstacle", double_t, 0, + "Optimization weight for satisfying a minimum seperation from obstacles", + 50, 0, 1000) + +grp_optimization.add("weight_inflation", double_t, 0, + "Optimization weight for the inflation penalty (should be small)", + 0.1, 0, 10) + +grp_optimization.add("weight_dynamic_obstacle", double_t, 0, + "Optimization weight for satisfying a minimum seperation from dynamic obstacles", + 50, 0, 1000) + +grp_optimization.add("weight_dynamic_obstacle_inflation", double_t, 0, + "Optimization weight for the inflation penalty of dynamic obstacles (should be small)", + 0.1, 0, 10) + +grp_optimization.add("weight_velocity_obstacle_ratio", double_t, 0, + "Optimization weight for satisfying a maximum allowed velocity with respect to the distance to a static obstacle", + 0, 0, 1000) + +grp_optimization.add("weight_viapoint", double_t, 0, + "Optimization weight for minimizing the distance to via-points", + 1, 0, 1000) + +grp_optimization.add("weight_adapt_factor", double_t, 0, + "Some special weights (currently 'weight_obstacle') are repeatedly scaled by this factor in each outer TEB iteration (weight_new: weight_old * factor); Increasing weights iteratively instead of setting a huge value a-priori leads to better numerical conditions of the underlying optimization problem.", + 2, 1, 100) + +grp_optimization.add("obstacle_cost_exponent", double_t, 0, + "Exponent for nonlinear obstacle cost (cost = linear_cost * obstacle_cost_exponent). Set to 1 to disable nonlinear cost (default)", + 1, 0.01, 100) + + +# Homotopy Class Planner +grp_hcp = gen.add_group("HCPlanning", type="tab") + +grp_hcp.add("enable_multithreading", bool_t, 0, + "Activate multiple threading for planning multiple trajectories in parallel", + True) + +grp_hcp.add("max_number_classes", int_t, 0, + "Specify the maximum number of allowed alternative homotopy classes (limits computational effort)", + 5, 1, 100) + +grp_hcp.add("max_number_plans_in_current_class", int_t, 0, + "Max number of trajectories to try that are in the same homotopy class as the current best trajectory (setting this to 2 or more helps avoid local minima). Must be <= max_number_classes", + 1, 1, 10) + +grp_hcp.add("selection_cost_hysteresis", double_t, 0, + "Specify how much trajectory cost must a new candidate have w.r.t. a previously selected trajectory in order to be selected (selection if new_cost < old_cost*factor)", + 1.0, 0, 2) + + +grp_hcp.add("selection_prefer_initial_plan", double_t, 0, + "Specify a cost reduction in the interval (0,1) for the trajectory in the equivalence class of the initial plan.)", + 0.95, 0, 1) + +grp_hcp.add("selection_obst_cost_scale", double_t, 0, + "Extra scaling of obstacle cost terms just for selecting the 'best' candidate (new_obst_cost: obst_cost*factor)", + 2.0, 0, 1000) + +grp_hcp.add("selection_viapoint_cost_scale", double_t, 0, + "Extra scaling of via-point cost terms just for selecting the 'best' candidate. (new_viapt_cost: viapt_cost*factor)", + 1.0, 0, 100) + +grp_hcp.add("selection_alternative_time_cost", bool_t, 0, + "If true, time cost is replaced by the total transition time.", + False) + +grp_hcp.add("selection_dropping_probability", double_t, 0, + "At each planning cycle, TEBs other than the current 'best' one will be randomly dropped with this probability. Prevents becoming 'fixated' on sub-optimal alternative homotopies.", + 0.0, 0.0, 1.0) + +grp_hcp.add("switching_blocking_period", double_t, 0, + "Specify a time duration in seconds that needs to be expired before a switch to new equivalence class is allowed", + 0.0, 0.0, 60) + +grp_hcp.add("roadmap_graph_no_samples", int_t, 0, + "Specify the number of samples generated for creating the roadmap graph, if simple_exploration is turend off", + 15, 1, 100) + +grp_hcp.add("roadmap_graph_area_width", double_t, 0, + "Specify the width of the area in which sampled will be generated between start and goal [m] (the height equals the start-goal distance)", + 5, 0.1, 20) + +grp_hcp.add("roadmap_graph_area_length_scale", double_t, 0, + "The length of the rectangular region is determined by the distance between start and goal. This parameter further scales the distance such that the geometric center remains equal!)", + 1.0, 0.5, 2) + +grp_hcp.add("h_signature_prescaler", double_t, 0, + "Scale number of obstacle value in order to allow huge number of obstacles. Do not choose it extremly low, otherwise obstacles cannot be distinguished from each other (0.2 + Value: true + - Alpha: 0.100000001 + Cell Size: 0.100000001 + Class: rviz/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.0299999993 + Value: Lines + Name: Fine Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 100 + Reference Frame: + Value: true + - Alpha: 1 + Buffer Length: 1 + Class: rviz/Path + Color: 25; 255; 0 + Enabled: true + Head Diameter: 0.300000012 + Head Length: 0.200000003 + Length: 0.300000012 + Line Style: Lines + Line Width: 0.0299999993 + Name: Path + Offset: + X: 0 + Y: 0 + Z: 0 + Pose Style: None + Radius: 0.0299999993 + Shaft Diameter: 0.100000001 + Shaft Length: 0.100000001 + Topic: /test_optim_node/local_plan + Unreliable: false + Value: true + - Alpha: 1 + Arrow Length: 0.300000012 + Axes Length: 0.300000012 + Axes Radius: 0.00999999978 + Class: rviz/PoseArray + Color: 255; 25; 0 + Enabled: true + Head Length: 0.0700000003 + Head Radius: 0.0299999993 + Name: PoseArray + Shaft Length: 0.230000004 + Shaft Radius: 0.00999999978 + Shape: Arrow (Flat) + Topic: /test_optim_node/teb_poses + Unreliable: false + Value: true + - Class: rviz/Marker + Enabled: true + Marker Topic: /test_optim_node/teb_markers + Name: Marker + Namespaces: + PointObstacles: true + Queue Size: 100 + Value: true + - Class: rviz/InteractiveMarkers + Enable Transparency: true + Enabled: true + Name: InteractiveMarkers + Show Axes: false + Show Descriptions: true + Show Visual Aids: false + Update Topic: /marker_obstacles/update + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Fixed Frame: odom + Frame Rate: 30 + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + - Class: rviz/FocusCamera + - Class: rviz/Measure + - Class: rviz/SetInitialPose + Topic: /initialpose + - Class: rviz/SetGoal + Topic: /move_base_simple/goal + - Class: rviz/PublishPoint + Single click: true + Topic: /clicked_point + Value: true + Views: + Current: + Class: rviz/Orbit + Distance: 7.77247 + Enable Stereo Rendering: + Stereo Eye Separation: 0.0599999987 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: 0 + Y: 0 + Z: 0 + Focal Shape Fixed Size: true + Focal Shape Size: 0.0500000007 + Name: Current View + Near Clip Distance: 0.00999999978 + Pitch: 1.56979632 + Target Frame: + Value: Orbit (rviz) + Yaw: 4.71043873 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 846 + Hide Left Dock: false + Hide Right Dock: true + QMainWindow State: 000000ff00000000fd00000004000000000000016a000002c4fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006400fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c0061007900730100000028000002c4000000dd00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002c4fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a005600690065007700730000000028000002c4000000b000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000054a0000003efc0100000002fb0000000800540069006d006501000000000000054a0000030000fffffffb0000000800540069006d00650100000000000004500000000000000000000003da000002c400000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: true + Width: 1354 + X: 137 + Y: 50 diff --git a/navigations/teb_local_planner/cmake_modules/FindG2O.cmake b/navigations/teb_local_planner/cmake_modules/FindG2O.cmake new file mode 100755 index 0000000..b2670d3 --- /dev/null +++ b/navigations/teb_local_planner/cmake_modules/FindG2O.cmake @@ -0,0 +1,97 @@ +# Locate the g2o libraries +# A general framework for graph optimization. +# +# This module defines +# G2O_FOUND, if false, do not try to link against g2o +# G2O_LIBRARIES, path to the libg2o +# G2O_INCLUDE_DIR, where to find the g2o header files +# +# Niko Suenderhauf +# Adapted by Felix Endres + +IF(UNIX) + + #IF(G2O_INCLUDE_DIR AND G2O_LIBRARIES) + # in cache already + # SET(G2O_FIND_QUIETLY TRUE) + #ENDIF(G2O_INCLUDE_DIR AND G2O_LIBRARIES) + + MESSAGE(STATUS "Searching for g2o ...") + FIND_PATH(G2O_INCLUDE_DIR + NAMES core math_groups types + PATHS /usr/local /usr + PATH_SUFFIXES include/g2o include) + + IF (G2O_INCLUDE_DIR) + MESSAGE(STATUS "Found g2o headers in: ${G2O_INCLUDE_DIR}") + ENDIF (G2O_INCLUDE_DIR) + + FIND_LIBRARY(G2O_CORE_LIB + NAMES g2o_core g2o_core_rd + PATHS /usr/local /usr ${CMAKE_PREFIX_PATH} + PATH_SUFFIXES lib) + FIND_LIBRARY(G2O_STUFF_LIB + NAMES g2o_stuff g2o_stuff_rd + PATHS /usr/local /usr ${CMAKE_PREFIX_PATH} + PATH_SUFFIXES lib) + FIND_LIBRARY(G2O_TYPES_SLAM2D_LIB + NAMES g2o_types_slam2d g2o_types_slam2d_rd + PATHS /usr/local /usr ${CMAKE_PREFIX_PATH} + PATH_SUFFIXES lib) + FIND_LIBRARY(G2O_TYPES_SLAM3D_LIB + NAMES g2o_types_slam3d g2o_types_slam3d_rd + PATHS /usr/local /usr ${CMAKE_PREFIX_PATH} + PATH_SUFFIXES lib) + FIND_LIBRARY(G2O_SOLVER_CHOLMOD_LIB + NAMES g2o_solver_cholmod g2o_solver_cholmod_rd + PATHS /usr/local /usr ${CMAKE_PREFIX_PATH} + PATH_SUFFIXES lib) + FIND_LIBRARY(G2O_SOLVER_PCG_LIB + NAMES g2o_solver_pcg g2o_solver_pcg_rd + PATHS /usr/local /usr ${CMAKE_PREFIX_PATH} + PATH_SUFFIXES lib) + FIND_LIBRARY(G2O_SOLVER_CSPARSE_LIB + NAMES g2o_solver_csparse g2o_solver_csparse_rd + PATHS /usr/local /usr + PATH_SUFFIXES lib) + FIND_LIBRARY(G2O_INCREMENTAL_LIB + NAMES g2o_incremental g2o_incremental_rd + PATHS /usr/local /usr ${CMAKE_PREFIX_PATH} + PATH_SUFFIXES lib) + FIND_LIBRARY(G2O_CSPARSE_EXTENSION_LIB + NAMES g2o_csparse_extension g2o_csparse_extension_rd + PATHS /usr/local /usr ${CMAKE_PREFIX_PATH} + PATH_SUFFIXES lib) + + SET(G2O_LIBRARIES ${G2O_CSPARSE_EXTENSION_LIB} + ${G2O_CORE_LIB} + ${G2O_STUFF_LIB} + ${G2O_TYPES_SLAM2D_LIB} + ${G2O_TYPES_SLAM3D_LIB} + ${G2O_SOLVER_CHOLMOD_LIB} + ${G2O_SOLVER_PCG_LIB} + ${G2O_SOLVER_CSPARSE_LIB} + ${G2O_INCREMENTAL_LIB} + ) + + IF(G2O_LIBRARIES AND G2O_INCLUDE_DIR) + SET(G2O_FOUND "YES") + IF(NOT G2O_FIND_QUIETLY) + MESSAGE(STATUS "Found libg2o: ${G2O_LIBRARIES}") + ENDIF(NOT G2O_FIND_QUIETLY) + ELSE(G2O_LIBRARIES AND G2O_INCLUDE_DIR) + IF(NOT G2O_LIBRARIES) + IF(G2O_FIND_REQUIRED) + message(FATAL_ERROR "Could not find libg2o!") + ENDIF(G2O_FIND_REQUIRED) + ENDIF(NOT G2O_LIBRARIES) + + IF(NOT G2O_INCLUDE_DIR) + IF(G2O_FIND_REQUIRED) + message(FATAL_ERROR "Could not find g2o include directory!") + ENDIF(G2O_FIND_REQUIRED) + ENDIF(NOT G2O_INCLUDE_DIR) + ENDIF(G2O_LIBRARIES AND G2O_INCLUDE_DIR) + +ENDIF(UNIX) + diff --git a/navigations/teb_local_planner/cmake_modules/FindSUITESPARSE.cmake b/navigations/teb_local_planner/cmake_modules/FindSUITESPARSE.cmake new file mode 100755 index 0000000..101b79b --- /dev/null +++ b/navigations/teb_local_planner/cmake_modules/FindSUITESPARSE.cmake @@ -0,0 +1,133 @@ +# - Try to find SUITESPARSE +# Once done this will define +# +# SUITESPARSE_FOUND - system has SUITESPARSE +# SUITESPARSE_INCLUDE_DIRS - the SUITESPARSE include directory +# SUITESPARSE_LIBRARIES - Link these to use SUITESPARSE +# SUITESPARSE_SPQR_LIBRARY - name of spqr library (necessary due to error in debian package) +# SUITESPARSE_SPQR_LIBRARY_DIR - name of spqr library (necessary due to error in debian package) +# SUITESPARSE_LIBRARY_DIR - Library main directory containing suitesparse libs +# SUITESPARSE_LIBRARY_DIRS - all Library directories containing suitesparse libs +# SUITESPARSE_SPQR_VALID - automatic identification whether or not spqr package is installed correctly + +IF (SUITESPARSE_INCLUDE_DIRS) + # Already in cache, be silent + SET(SUITESPARSE_FIND_QUIETLY TRUE) +ENDIF (SUITESPARSE_INCLUDE_DIRS) + +if( WIN32 ) + # Find cholmod part of the suitesparse library collection + + FIND_PATH( CHOLMOD_INCLUDE_DIR cholmod.h + PATHS "C:\\libs\\win32\\SuiteSparse\\Include" ) + + # Add cholmod include directory to collection include directories + IF ( CHOLMOD_INCLUDE_DIR ) + list ( APPEND SUITESPARSE_INCLUDE_DIRS ${CHOLMOD_INCLUDE_DIR} ) + ENDIF( CHOLMOD_INCLUDE_DIR ) + + + # find path suitesparse library + FIND_PATH( SUITESPARSE_LIBRARY_DIRS + amd.lib + PATHS "C:\\libs\\win32\\SuiteSparse\\libs" ) + + # if we found the library, add it to the defined libraries + IF ( SUITESPARSE_LIBRARY_DIRS ) + list ( APPEND SUITESPARSE_LIBRARIES optimized;amd;optimized;camd;optimized;ccolamd;optimized;cholmod;optimized;colamd;optimized;metis;optimized;spqr;optimized;umfpack;debug;amdd;debug;camdd;debug;ccolamdd;debug;cholmodd;debug;spqrd;debug;umfpackd;debug;colamdd;debug;metisd;optimized;blas;optimized;libf2c;optimized;lapack;debug;blasd;debug;libf2cd;debug;lapackd ) + ENDIF( SUITESPARSE_LIBRARY_DIRS ) + +else( WIN32 ) + IF(APPLE) + FIND_PATH( CHOLMOD_INCLUDE_DIR cholmod.h + PATHS /opt/local/include/ufsparse + /usr/local/include ) + + FIND_PATH( SUITESPARSE_LIBRARY_DIR + NAMES libcholmod.a + PATHS /opt/local/lib + /usr/local/lib ) + ELSE(APPLE) + FIND_PATH( CHOLMOD_INCLUDE_DIR cholmod.h + PATHS /usr/local/include + /usr/include + /usr/include/suitesparse/ + ${CMAKE_SOURCE_DIR}/MacOS/Libs/cholmod + PATH_SUFFIXES cholmod/ CHOLMOD/ ) + + FIND_PATH( SUITESPARSE_LIBRARY_DIR + NAMES libcholmod.so libcholmod.a + PATHS /usr/lib + /usr/lib64 + /usr/lib/x86_64-linux-gnu + /usr/lib/i386-linux-gnu + /usr/local/lib + /usr/lib/arm-linux-gnueabihf/ + /usr/lib/aarch64-linux-gnu/ + /usr/lib/arm-linux-gnueabi/ + /usr/lib/arm-linux-gnu) + ENDIF(APPLE) + + # Add cholmod include directory to collection include directories + IF ( CHOLMOD_INCLUDE_DIR ) + list ( APPEND SUITESPARSE_INCLUDE_DIRS ${CHOLMOD_INCLUDE_DIR} ) + ENDIF( CHOLMOD_INCLUDE_DIR ) + + # if we found the library, add it to the defined libraries + IF ( SUITESPARSE_LIBRARY_DIR ) + + list ( APPEND SUITESPARSE_LIBRARIES amd) + list ( APPEND SUITESPARSE_LIBRARIES btf) + list ( APPEND SUITESPARSE_LIBRARIES camd) + list ( APPEND SUITESPARSE_LIBRARIES ccolamd) + list ( APPEND SUITESPARSE_LIBRARIES cholmod) + list ( APPEND SUITESPARSE_LIBRARIES colamd) + # list ( APPEND SUITESPARSE_LIBRARIES csparse) + list ( APPEND SUITESPARSE_LIBRARIES cxsparse) + list ( APPEND SUITESPARSE_LIBRARIES klu) + # list ( APPEND SUITESPARSE_LIBRARIES spqr) + list ( APPEND SUITESPARSE_LIBRARIES umfpack) + + IF (APPLE) + list ( APPEND SUITESPARSE_LIBRARIES suitesparseconfig) + ENDIF (APPLE) + + # Metis and spqr are optional + FIND_LIBRARY( SUITESPARSE_METIS_LIBRARY + NAMES metis + PATHS ${SUITESPARSE_LIBRARY_DIR} ) + IF (SUITESPARSE_METIS_LIBRARY) + list ( APPEND SUITESPARSE_LIBRARIES metis) + ENDIF(SUITESPARSE_METIS_LIBRARY) + + if(EXISTS "${CHOLMOD_INCLUDE_DIR}/SuiteSparseQR.hpp") + SET(SUITESPARSE_SPQR_VALID TRUE CACHE BOOL "SuiteSparseSPQR valid") + else() + SET(SUITESPARSE_SPQR_VALID false CACHE BOOL "SuiteSparseSPQR valid") + endif() + + if(SUITESPARSE_SPQR_VALID) + FIND_LIBRARY( SUITESPARSE_SPQR_LIBRARY + NAMES spqr + PATHS ${SUITESPARSE_LIBRARY_DIR} ) + IF (SUITESPARSE_SPQR_LIBRARY) + list ( APPEND SUITESPARSE_LIBRARIES spqr) + ENDIF (SUITESPARSE_SPQR_LIBRARY) + endif() + + ENDIF( SUITESPARSE_LIBRARY_DIR ) + +endif( WIN32 ) + + +IF (SUITESPARSE_INCLUDE_DIRS AND SUITESPARSE_LIBRARIES) + IF(WIN32) + list (APPEND SUITESPARSE_INCLUDE_DIRS ${CHOLMOD_INCLUDE_DIR}/../../UFconfig ) + ENDIF(WIN32) + SET(SUITESPARSE_FOUND TRUE) + MESSAGE(STATUS "Found SuiteSparse") +ELSE (SUITESPARSE_INCLUDE_DIRS AND SUITESPARSE_LIBRARIES) + SET( SUITESPARSE_FOUND FALSE ) + MESSAGE(FATAL_ERROR "Unable to find SuiteSparse") +ENDIF (SUITESPARSE_INCLUDE_DIRS AND SUITESPARSE_LIBRARIES) + diff --git a/navigations/teb_local_planner/include/teb_local_planner/distance_calculations.h b/navigations/teb_local_planner/include/teb_local_planner/distance_calculations.h new file mode 100755 index 0000000..364dc5b --- /dev/null +++ b/navigations/teb_local_planner/include/teb_local_planner/distance_calculations.h @@ -0,0 +1,464 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2016, + * TU Dortmund - Institute of Control Theory and Systems Engineering. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the institute nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: Christoph Rösmann + *********************************************************************/ + +#ifndef DISTANCE_CALCULATIONS_H +#define DISTANCE_CALCULATIONS_H + +#include +#include + + +namespace teb_local_planner +{ + +//! Abbrev. for a container storing 2d points +typedef std::vector< Eigen::Vector2d, Eigen::aligned_allocator > Point2dContainer; + + +/** + * @brief Helper function to obtain the closest point on a line segment w.r.t. a reference point + * @param point 2D point + * @param line_start 2D point representing the start of the line segment + * @param line_end 2D point representing the end of the line segment + * @return Closest point on the line segment + */ +inline Eigen::Vector2d closest_point_on_line_segment_2d(const Eigen::Ref& point, const Eigen::Ref& line_start, const Eigen::Ref& line_end) +{ + Eigen::Vector2d diff = line_end - line_start; + double sq_norm = diff.squaredNorm(); + + if (sq_norm == 0) + return line_start; + + double u = ((point.x() - line_start.x()) * diff.x() + (point.y() - line_start.y())*diff.y()) / sq_norm; + + if (u <= 0) return line_start; + else if (u >= 1) return line_end; + + return line_start + u*diff; +} + +/** + * @brief Helper function to calculate the distance between a line segment and a point + * @param point 2D point + * @param line_start 2D point representing the start of the line segment + * @param line_end 2D point representing the end of the line segment + * @return minimum distance to a given line segment + */ +inline double distance_point_to_segment_2d(const Eigen::Ref& point, const Eigen::Ref& line_start, const Eigen::Ref& line_end) +{ + return (point - closest_point_on_line_segment_2d(point, line_start, line_end)).norm(); +} + +/** + * @brief Helper function to check whether two line segments intersects + * @param line1_start 2D point representing the start of the first line segment + * @param line1_end 2D point representing the end of the first line segment + * @param line2_start 2D point representing the start of the second line segment + * @param line2_end 2D point representing the end of the second line segment + * @param[out] intersection [optional] Write intersection point to destination (the value is only written, if both lines intersect, e.g. if the function returns \c true) + * @return \c true if both line segments intersect + */ +inline bool check_line_segments_intersection_2d(const Eigen::Ref& line1_start, const Eigen::Ref& line1_end, + const Eigen::Ref& line2_start, const Eigen::Ref& line2_end, Eigen::Vector2d* intersection = NULL) +{ + // http://stackoverflow.com/questions/563198/how-do-you-detect-where-two-line-segments-intersect + double s_numer, t_numer, denom, t; + Eigen::Vector2d line1 = line1_end - line1_start; + Eigen::Vector2d line2 = line2_end - line2_start; + + denom = line1.x() * line2.y() - line2.x() * line1.y(); + if (denom == 0) return false; // Collinear + bool denomPositive = denom > 0; + + Eigen::Vector2d aux = line1_start - line2_start; + + s_numer = line1.x() * aux.y() - line1.y() * aux.x(); + if ((s_numer < 0) == denomPositive) return false; // No collision + + t_numer = line2.x() * aux.y() - line2.y() * aux.x(); + if ((t_numer < 0) == denomPositive) return false; // No collision + + if (((s_numer > denom) == denomPositive) || ((t_numer > denom) == denomPositive)) return false; // No collision + + // Otherwise collision detected + t = t_numer / denom; + if (intersection) + { + *intersection = line1_start + t * line1; + } + + return true; +} + + +/** + * @brief Helper function to calculate the smallest distance between two line segments + * @param line1_start 2D point representing the start of the first line segment + * @param line1_end 2D point representing the end of the first line segment + * @param line2_start 2D point representing the start of the second line segment + * @param line2_end 2D point representing the end of the second line segment + * @return smallest distance between both segments +*/ +inline double distance_segment_to_segment_2d(const Eigen::Ref& line1_start, const Eigen::Ref& line1_end, + const Eigen::Ref& line2_start, const Eigen::Ref& line2_end) +{ + // TODO more efficient implementation + + // check if segments intersect + if (check_line_segments_intersection_2d(line1_start, line1_end, line2_start, line2_end)) + return 0; + + // check all 4 combinations + std::array distances; + + distances[0] = distance_point_to_segment_2d(line1_start, line2_start, line2_end); + distances[1] = distance_point_to_segment_2d(line1_end, line2_start, line2_end); + distances[2] = distance_point_to_segment_2d(line2_start, line1_start, line1_end); + distances[3] = distance_point_to_segment_2d(line2_end, line1_start, line1_end); + + return *std::min_element(distances.begin(), distances.end()); +} + + +/** + * @brief Helper function to calculate the smallest distance between a point and a closed polygon + * @param point 2D point + * @param vertices Vertices describing the closed polygon (the first vertex is not repeated at the end) + * @return smallest distance between point and polygon +*/ +inline double distance_point_to_polygon_2d(const Eigen::Vector2d& point, const Point2dContainer& vertices) +{ + double dist = HUGE_VAL; + + // the polygon is a point + if (vertices.size() == 1) + { + return (point - vertices.front()).norm(); + } + + // check each polygon edge + for (int i=0; i<(int)vertices.size()-1; ++i) + { + double new_dist = distance_point_to_segment_2d(point, vertices.at(i), vertices.at(i+1)); +// double new_dist = calc_distance_point_to_segment( position, vertices.at(i), vertices.at(i+1)); + if (new_dist < dist) + dist = new_dist; + } + + if (vertices.size()>2) // if not a line close polygon + { + double new_dist = distance_point_to_segment_2d(point, vertices.back(), vertices.front()); // check last edge + if (new_dist < dist) + return new_dist; + } + + return dist; +} + +/** + * @brief Helper function to calculate the smallest distance between a line segment and a closed polygon + * @param line_start 2D point representing the start of the line segment + * @param line_end 2D point representing the end of the line segment + * @param vertices Vertices describing the closed polygon (the first vertex is not repeated at the end) + * @return smallest distance between point and polygon +*/ +inline double distance_segment_to_polygon_2d(const Eigen::Vector2d& line_start, const Eigen::Vector2d& line_end, const Point2dContainer& vertices) +{ + double dist = HUGE_VAL; + + // the polygon is a point + if (vertices.size() == 1) + { + return distance_point_to_segment_2d(vertices.front(), line_start, line_end); + } + + // check each polygon edge + for (int i=0; i<(int)vertices.size()-1; ++i) + { + double new_dist = distance_segment_to_segment_2d(line_start, line_end, vertices.at(i), vertices.at(i+1)); +// double new_dist = calc_distance_point_to_segment( position, vertices.at(i), vertices.at(i+1)); + if (new_dist < dist) + dist = new_dist; + } + + if (vertices.size()>2) // if not a line close polygon + { + double new_dist = distance_segment_to_segment_2d(line_start, line_end, vertices.back(), vertices.front()); // check last edge + if (new_dist < dist) + return new_dist; + } + + return dist; +} + +/** + * @brief Helper function to calculate the smallest distance between two closed polygons + * @param vertices1 Vertices describing the first closed polygon (the first vertex is not repeated at the end) + * @param vertices2 Vertices describing the second closed polygon (the first vertex is not repeated at the end) + * @return smallest distance between point and polygon +*/ +inline double distance_polygon_to_polygon_2d(const Point2dContainer& vertices1, const Point2dContainer& vertices2) +{ + double dist = HUGE_VAL; + + // the polygon1 is a point + if (vertices1.size() == 1) + { + return distance_point_to_polygon_2d(vertices1.front(), vertices2); + } + + // check each edge of polygon1 + for (int i=0; i<(int)vertices1.size()-1; ++i) + { + double new_dist = distance_segment_to_polygon_2d(vertices1[i], vertices1[i+1], vertices2); + if (new_dist < dist) + dist = new_dist; + } + + if (vertices1.size()>2) // if not a line close polygon1 + { + double new_dist = distance_segment_to_polygon_2d(vertices1.back(), vertices1.front(), vertices2); // check last edge + if (new_dist < dist) + return new_dist; + } + + return dist; +} + + + + +// Further distance calculations: + + +// The Distance Calculations are mainly copied from http://geomalgorithms.com/a07-_distance.html +// Copyright 2001 softSurfer, 2012 Dan Sunday +// This code may be freely used and modified for any purpose +// providing that this copyright notice is included with it. +// SoftSurfer makes no warranty for this code, and cannot be held +// liable for any real or imagined damage resulting from its use. +// Users of this code must verify correctness for their application. + +inline double calc_distance_line_to_line_3d(const Eigen::Ref& x1, Eigen::Ref& u, + const Eigen::Ref& x2, Eigen::Ref& v) +{ + Eigen::Vector3d w = x2 - x1; + double a = u.squaredNorm(); // dot(u,u) always >= 0 + double b = u.dot(v); + double c = v.squaredNorm(); // dot(v,v) always >= 0 + double d = u.dot(w); + double e = v.dot(w); + double D = a*c - b*b; // always >= 0 + double sc, tc; + + // compute the line parameters of the two closest points + if (D < SMALL_NUM) { // the lines are almost parallel + sc = 0.0; + tc = (b>c ? d/b : e/c); // use the largest denominator + } + else { + sc = (b*e - c*d) / D; + tc = (a*e - b*d) / D; + } + + // get the difference of the two closest points + Eigen::Vector3d dP = w + (sc * u) - (tc * v); // = L1(sc) - L2(tc) + + return dP.norm(); // return the closest distance +} + + + + + +inline double calc_distance_segment_to_segment3D(const Eigen::Ref& line1_start, Eigen::Ref& line1_end, + const Eigen::Ref& line2_start, Eigen::Ref& line2_end) +{ + Eigen::Vector3d u = line1_end - line1_start; + Eigen::Vector3d v = line2_end - line2_start; + Eigen::Vector3d w = line2_start - line1_start; + double a = u.squaredNorm(); // dot(u,u) always >= 0 + double b = u.dot(v); + double c = v.squaredNorm(); // dot(v,v) always >= 0 + double d = u.dot(w); + double e = v.dot(w); + double D = a*c - b*b; // always >= 0 + double sc, sN, sD = D; // sc = sN / sD, default sD = D >= 0 + double tc, tN, tD = D; // tc = tN / tD, default tD = D >= 0 + + // compute the line parameters of the two closest points + if (D < SMALL_NUM) + { // the lines are almost parallel + sN = 0.0; // force using point P0 on segment S1 + sD = 1.0; // to prevent possible division by 0.0 later + tN = e; + tD = c; + } + else + { // get the closest points on the infinite lines + sN = (b*e - c*d); + tN = (a*e - b*d); + if (sN < 0.0) + { // sc < 0 => the s=0 edge is visible + sN = 0.0; + tN = e; + tD = c; + } + else if (sN > sD) + { // sc > 1 => the s=1 edge is visible + sN = sD; + tN = e + b; + tD = c; + } + } + + if (tN < 0.0) + { // tc < 0 => the t=0 edge is visible + tN = 0.0; + // recompute sc for this edge + if (-d < 0.0) + sN = 0.0; + else if (-d > a) + sN = sD; + else + { + sN = -d; + sD = a; + } + } + else if (tN > tD) + { // tc > 1 => the t=1 edge is visible + tN = tD; + // recompute sc for this edge + if ((-d + b) < 0.0) + sN = 0; + else if ((-d + b) > a) + sN = sD; + else + { + sN = (-d + b); + sD = a; + } + } + // finally do the division to get sc and tc + sc = (abs(sN) < SMALL_NUM ? 0.0 : sN / sD); + tc = (abs(tN) < SMALL_NUM ? 0.0 : tN / tD); + + // get the difference of the two closest points + Eigen::Vector3d dP = w + (sc * u) - (tc * v); // = S1(sc) - S2(tc) + + return dP.norm(); // return the closest distance +} + + + + +template +double calc_closest_point_to_approach_time(const VectorType& x1, const VectorType& vel1, const VectorType& x2, const VectorType& vel2) +{ + VectorType dv = vel1 - vel2; + + double dv2 = dv.squaredNorm(); // dot(v,v) + if (dv2 < SMALL_NUM) // the tracks are almost parallel + return 0.0; // any time is ok. Use time 0. + + VectorType w0 = x1 - x2; + double cpatime = -w0.dot(dv) / dv2; + + return cpatime; // time of CPA +} + +template +double calc_closest_point_to_approach_distance(const VectorType& x1, const VectorType& vel1, const VectorType& x2, const VectorType& vel2, double bound_cpa_time = 0) +{ + double ctime = calc_closest_point_to_approach_time(x1, vel1, x2, vel2); + if (bound_cpa_time!=0 && ctime > bound_cpa_time) ctime = bound_cpa_time; + VectorType P1 = x1 + (ctime * vel1); + VectorType P2 = x2 + (ctime * vel2); + + return (P2-P1).norm(); // distance at CPA +} + + + +// dist_Point_to_Line(): get the distance of a point to a line +// Input: a Point P and a Line L (in any dimension) +// Return: the shortest distance from P to L +template +double calc_distance_point_to_line( const VectorType& point, const VectorType& line_base, const VectorType& line_dir) +{ + VectorType w = point - line_base; + + double c1 = w.dot(line_dir); + double c2 = line_dir.dot(line_dir); + double b = c1 / c2; + + VectorType Pb = line_base + b * line_dir; + return (point-Pb).norm(); +} +//=================================================================== + + +// dist_Point_to_Segment(): get the distance of a point to a segment +// Input: a Point P and a Segment S (in any dimension) +// Return: the shortest distance from P to S +template +double calc_distance_point_to_segment( const VectorType& point, const VectorType& line_start, const VectorType& line_end) +{ + VectorType v = line_end - line_start; + VectorType w = point - line_start; + + double c1 = w.dot(v); + if ( c1 <= 0 ) + return w.norm(); + + double c2 = v.dot(v); + if ( c2 <= c1 ) + return (point-line_end).norm(); + + double b = c1 / c2; + VectorType Pb = line_start + b * v; + return (point-Pb).norm(); +} + + + +} // namespace teb_local_planner + +#endif /* DISTANCE_CALCULATIONS_H */ diff --git a/navigations/teb_local_planner/include/teb_local_planner/equivalence_relations.h b/navigations/teb_local_planner/include/teb_local_planner/equivalence_relations.h new file mode 100755 index 0000000..b39bb71 --- /dev/null +++ b/navigations/teb_local_planner/include/teb_local_planner/equivalence_relations.h @@ -0,0 +1,103 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2016, + * TU Dortmund - Institute of Control Theory and Systems Engineering. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the institute nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: Christoph Rösmann + *********************************************************************/ + +#ifndef EQUIVALENCE_RELATIONS_H_ +#define EQUIVALENCE_RELATIONS_H_ + +#include + +namespace teb_local_planner +{ + +/** + * @class EquivalenceClass + * @brief Abstract class that defines an interface for computing and comparing equivalence classes + * + * Equivalence relations are utilized in order to test if two trajectories are belonging to the same + * equivalence class w.r.t. the current obstacle configurations. A common equivalence relation is + * the concept of homotopy classes. All trajectories belonging to the same homotopy class + * can CONTINUOUSLY be deformed into each other without intersecting any obstacle. Hence they likely + * share the same local minimum after invoking (local) trajectory optimization. A weaker equivalence relation + * is defined by the concept of homology classes (e.g. refer to HSignature). + * + * Each EquivalenceClass object (or subclass) stores a candidate value which might be compared to another EquivalenceClass object. + * + * @remarks Currently, the computeEquivalenceClass method is not available in the generic interface EquivalenceClass. + * Call the "compute"-methods directly on the subclass. + */ +class EquivalenceClass +{ +public: + + /** + * @brief Default constructor + */ + EquivalenceClass() {} + + /** + * @brief virtual destructor + */ + virtual ~EquivalenceClass() {} + + /** + * @brief Check if two candidate classes are equivalent + * @param other The other equivalence class to test with + */ + virtual bool isEqual(const EquivalenceClass& other) const = 0; + + /** + * @brief Check if the equivalence value is detected correctly + * @return Returns false, if the equivalence class detection failed, e.g. if nan- or inf values occur. + */ + virtual bool isValid() const = 0; + + /** + * @brief Check if the trajectory is non-looping around an obstacle + * @return Returns false, if the trajectory loops around an obstacle + */ + virtual bool isReasonable() const = 0; + +}; + +using EquivalenceClassPtr = boost::shared_ptr; + + +} // namespace teb_local_planner + + +#endif /* EQUIVALENCE_RELATIONS_H_ */ diff --git a/navigations/teb_local_planner/include/teb_local_planner/g2o_types/base_teb_edges.h b/navigations/teb_local_planner/include/teb_local_planner/g2o_types/base_teb_edges.h new file mode 100755 index 0000000..0920c7b --- /dev/null +++ b/navigations/teb_local_planner/include/teb_local_planner/g2o_types/base_teb_edges.h @@ -0,0 +1,278 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2016, + * TU Dortmund - Institute of Control Theory and Systems Engineering. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the institute nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Notes: + * The following class is derived from a class defined by the + * g2o-framework. g2o is licensed under the terms of the BSD License. + * Refer to the base class source for detailed licensing information. + * + * Author: Christoph Rösmann + *********************************************************************/ + +#ifndef _BASE_TEB_EDGES_H_ +#define _BASE_TEB_EDGES_H_ + +#include + +#include +#include +#include + +namespace teb_local_planner +{ + + +/** + * @class BaseTebUnaryEdge + * @brief Base edge connecting a single vertex in the TEB optimization problem + * + * This edge defines a base edge type for the TEB optimization problem. + * It is derived from the corresponding g2o base classes augmented with additional information for the dedicated TEB problem (e.g. config). + * The destructor erases the edge in all attached vertices in order to allow keeping the vertices valid in subsequent g2o optimization calls. + * Memory of edges should be freed by calling the clearEdge method of the g2o optimizer class. + * @see BaseTebMultiEdge, BaseTebBinaryEdge, g2o::BaseBinaryEdge, g2o::BaseUnaryEdge, g2o::BaseMultiEdge + */ +template +class BaseTebUnaryEdge : public g2o::BaseUnaryEdge +{ +public: + + using typename g2o::BaseUnaryEdge::ErrorVector; + using g2o::BaseUnaryEdge::computeError; + + /** + * @brief Compute and return error / cost value. + * + * This method is called by TebOptimalPlanner::computeCurrentCost to obtain the current cost. + * @return 2D Cost / error vector [nh cost, backward drive dir cost]^T + */ + ErrorVector& getError() + { + computeError(); + return _error; + } + + /** + * @brief Read values from input stream + */ + virtual bool read(std::istream& is) + { + // TODO generic read + return true; + } + + /** + * @brief Write values to an output stream + */ + virtual bool write(std::ostream& os) const + { + // TODO generic write + return os.good(); + } + + /** + * @brief Assign the TebConfig class for parameters. + * @param cfg TebConfig class + */ + void setTebConfig(const TebConfig& cfg) + { + cfg_ = &cfg; + } + +protected: + + using g2o::BaseUnaryEdge::_error; + using g2o::BaseUnaryEdge::_vertices; + + const TebConfig* cfg_; //!< Store TebConfig class for parameters + +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +}; + +/** + * @class BaseTebBinaryEdge + * @brief Base edge connecting two vertices in the TEB optimization problem + * + * This edge defines a base edge type for the TEB optimization problem. + * It is derived from the corresponding g2o base classes augmented with additional information for the dedicated TEB problem (e.g. config). + * The destructor erases the edge in all attached vertices in order to allow keeping the vertices valid in subsequent g2o optimization calls. + * Memory of edges should be freed by calling the clearEdge method of the g2o optimizer class. + * @see BaseTebMultiEdge, BaseTebUnaryEdge, g2o::BaseBinaryEdge, g2o::BaseUnaryEdge, g2o::BaseMultiEdge + */ +template +class BaseTebBinaryEdge : public g2o::BaseBinaryEdge +{ +public: + + using typename g2o::BaseBinaryEdge::ErrorVector; + using g2o::BaseBinaryEdge::computeError; + + /** + * @brief Compute and return error / cost value. + * + * This method is called by TebOptimalPlanner::computeCurrentCost to obtain the current cost. + * @return 2D Cost / error vector [nh cost, backward drive dir cost]^T + */ + ErrorVector& getError() + { + computeError(); + return _error; + } + + /** + * @brief Read values from input stream + */ + virtual bool read(std::istream& is) + { + // TODO generic read + return true; + } + + /** + * @brief Write values to an output stream + */ + virtual bool write(std::ostream& os) const + { + // TODO generic write + return os.good(); + } + + /** + * @brief Assign the TebConfig class for parameters. + * @param cfg TebConfig class + */ + void setTebConfig(const TebConfig& cfg) + { + cfg_ = &cfg; + } + +protected: + + using g2o::BaseBinaryEdge::_error; + using g2o::BaseBinaryEdge::_vertices; + + const TebConfig* cfg_; //!< Store TebConfig class for parameters + +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +}; + + +/** + * @class BaseTebMultiEdge + * @brief Base edge connecting multiple vertices in the TEB optimization problem + * + * This edge defines a base edge type for the TEB optimization problem. + * It is derived from the corresponding g2o base classes augmented with additional information for the dedicated TEB problem (e.g. config). + * The destructor erases the edge in all attached vertices in order to allow keeping the vertices valid in subsequent g2o optimization calls. + * Memory of edges should be freed by calling the clearEdge method of the g2o optimizer class. + * @see BaseTebBinaryEdge, BaseTebUnaryEdge, g2o::BaseBinaryEdge, g2o::BaseUnaryEdge, g2o::BaseMultiEdge + */ +template +class BaseTebMultiEdge : public g2o::BaseMultiEdge +{ +public: + + using typename g2o::BaseMultiEdge::ErrorVector; + using g2o::BaseMultiEdge::computeError; + + // Overwrites resize() from the parent class + virtual void resize(size_t size) + { + g2o::BaseMultiEdge::resize(size); + + for(std::size_t i=0; i<_vertices.size(); ++i) + _vertices[i] = NULL; + } + + /** + * @brief Compute and return error / cost value. + * + * This method is called by TebOptimalPlanner::computeCurrentCost to obtain the current cost. + * @return 2D Cost / error vector [nh cost, backward drive dir cost]^T + */ + ErrorVector& getError() + { + computeError(); + return _error; + } + + /** + * @brief Read values from input stream + */ + virtual bool read(std::istream& is) + { + // TODO generic read + return true; + } + + /** + * @brief Write values to an output stream + */ + virtual bool write(std::ostream& os) const + { + // TODO generic write + return os.good(); + } + + /** + * @brief Assign the TebConfig class for parameters. + * @param cfg TebConfig class + */ + void setTebConfig(const TebConfig& cfg) + { + cfg_ = &cfg; + } + +protected: + + using g2o::BaseMultiEdge::_error; + using g2o::BaseMultiEdge::_vertices; + + const TebConfig* cfg_; //!< Store TebConfig class for parameters + +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +}; + + + + + + +} // end namespace + +#endif diff --git a/navigations/teb_local_planner/include/teb_local_planner/g2o_types/edge_acceleration.h b/navigations/teb_local_planner/include/teb_local_planner/g2o_types/edge_acceleration.h new file mode 100755 index 0000000..8eccf6d --- /dev/null +++ b/navigations/teb_local_planner/include/teb_local_planner/g2o_types/edge_acceleration.h @@ -0,0 +1,734 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2016, + * TU Dortmund - Institute of Control Theory and Systems Engineering. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the institute nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Notes: + * The following class is derived from a class defined by the + * g2o-framework. g2o is licensed under the terms of the BSD License. + * Refer to the base class source for detailed licensing information. + * + * Author: Christoph Rösmann + *********************************************************************/ + +#ifndef EDGE_ACCELERATION_H_ +#define EDGE_ACCELERATION_H_ + +#include +#include +#include +#include +#include + +#include + + + +namespace teb_local_planner +{ + +/** + * @class EdgeAcceleration + * @brief Edge defining the cost function for limiting the translational and rotational acceleration. + * + * The edge depends on five vertices \f$ \mathbf{s}_i, \mathbf{s}_{ip1}, \mathbf{s}_{ip2}, \Delta T_i, \Delta T_{ip1} \f$ and minimizes: + * \f$ \min \textrm{penaltyInterval}( [a, omegadot } ]^T ) \cdot weight \f$. \n + * \e a is calculated using the difference quotient (twice) and the position parts of all three poses \n + * \e omegadot is calculated using the difference quotient of the yaw angles followed by a normalization to [-pi, pi]. \n + * \e weight can be set using setInformation() \n + * \e penaltyInterval denotes the penalty function, see penaltyBoundToInterval() \n + * The dimension of the error / cost vector is 2: the first component represents the translational acceleration and + * the second one the rotational acceleration. + * @see TebOptimalPlanner::AddEdgesAcceleration + * @see EdgeAccelerationStart + * @see EdgeAccelerationGoal + * @remarks Do not forget to call setTebConfig() + * @remarks Refer to EdgeAccelerationStart() and EdgeAccelerationGoal() for defining boundary values! + */ +class EdgeAcceleration : public BaseTebMultiEdge<2, double> +{ +public: + + /** + * @brief Construct edge. + */ + EdgeAcceleration() + { + this->resize(5); + } + + /** + * @brief Actual cost function + */ + void computeError() + { + ROS_ASSERT_MSG(cfg_, "You must call setTebConfig on EdgeAcceleration()"); + const VertexPose* pose1 = static_cast(_vertices[0]); + const VertexPose* pose2 = static_cast(_vertices[1]); + const VertexPose* pose3 = static_cast(_vertices[2]); + const VertexTimeDiff* dt1 = static_cast(_vertices[3]); + const VertexTimeDiff* dt2 = static_cast(_vertices[4]); + + // VELOCITY & ACCELERATION + const Eigen::Vector2d diff1 = pose2->position() - pose1->position(); + const Eigen::Vector2d diff2 = pose3->position() - pose2->position(); + + double dist1 = diff1.norm(); + double dist2 = diff2.norm(); + const double angle_diff1 = g2o::normalize_theta(pose2->theta() - pose1->theta()); + const double angle_diff2 = g2o::normalize_theta(pose3->theta() - pose2->theta()); + + if (cfg_->trajectory.exact_arc_length) // use exact arc length instead of Euclidean approximation + { + if (angle_diff1 != 0) + { + const double radius = dist1/(2*sin(angle_diff1/2)); + dist1 = fabs( angle_diff1 * radius ); // actual arg length! + } + if (angle_diff2 != 0) + { + const double radius = dist2/(2*sin(angle_diff2/2)); + dist2 = fabs( angle_diff2 * radius ); // actual arg length! + } + } + + double vel1 = dist1 / dt1->dt(); + double vel2 = dist2 / dt2->dt(); + + + // consider directions +// vel1 *= g2o::sign(diff1[0]*cos(pose1->theta()) + diff1[1]*sin(pose1->theta())); +// vel2 *= g2o::sign(diff2[0]*cos(pose2->theta()) + diff2[1]*sin(pose2->theta())); + vel1 *= fast_sigmoid( 100*(diff1.x()*cos(pose1->theta()) + diff1.y()*sin(pose1->theta())) ); + vel2 *= fast_sigmoid( 100*(diff2.x()*cos(pose2->theta()) + diff2.y()*sin(pose2->theta())) ); + + const double acc_lin = (vel2 - vel1)*2 / ( dt1->dt() + dt2->dt() ); + + + _error[0] = penaltyBoundToInterval(acc_lin,cfg_->robot.acc_lim_x,cfg_->optim.penalty_epsilon); + + // ANGULAR ACCELERATION + const double omega1 = angle_diff1 / dt1->dt(); + const double omega2 = angle_diff2 / dt2->dt(); + const double acc_rot = (omega2 - omega1)*2 / ( dt1->dt() + dt2->dt() ); + + _error[1] = penaltyBoundToInterval(acc_rot,cfg_->robot.acc_lim_theta,cfg_->optim.penalty_epsilon); + + + ROS_ASSERT_MSG(std::isfinite(_error[0]), "EdgeAcceleration::computeError() translational: _error[0]=%f\n",_error[0]); + ROS_ASSERT_MSG(std::isfinite(_error[1]), "EdgeAcceleration::computeError() rotational: _error[1]=%f\n",_error[1]); + } + + + +#ifdef USE_ANALYTIC_JACOBI +#if 0 + /* + * @brief Jacobi matrix of the cost function specified in computeError(). + */ + void linearizeOplus() + { + ROS_ASSERT_MSG(cfg_, "You must call setTebConfig on EdgeAcceleration()"); + const VertexPointXY* conf1 = static_cast(_vertices[0]); + const VertexPointXY* conf2 = static_cast(_vertices[1]); + const VertexPointXY* conf3 = static_cast(_vertices[2]); + const VertexTimeDiff* deltaT1 = static_cast(_vertices[3]); + const VertexTimeDiff* deltaT2 = static_cast(_vertices[4]); + const VertexOrientation* angle1 = static_cast(_vertices[5]); + const VertexOrientation* angle2 = static_cast(_vertices[6]); + const VertexOrientation* angle3 = static_cast(_vertices[7]); + + Eigen::Vector2d deltaS1 = conf2->estimate() - conf1->estimate(); + Eigen::Vector2d deltaS2 = conf3->estimate() - conf2->estimate(); + double dist1 = deltaS1.norm(); + double dist2 = deltaS2.norm(); + + double sum_time = deltaT1->estimate() + deltaT2->estimate(); + double sum_time_inv = 1 / sum_time; + double dt1_inv = 1/deltaT1->estimate(); + double dt2_inv = 1/deltaT2->estimate(); + double aux0 = 2/sum_time_inv; + double aux1 = dist1 * deltaT1->estimate(); + double aux2 = dist2 * deltaT2->estimate(); + + double vel1 = dist1 * dt1_inv; + double vel2 = dist2 * dt2_inv; + double omega1 = g2o::normalize_theta( angle2->estimate() - angle1->estimate() ) * dt1_inv; + double omega2 = g2o::normalize_theta( angle3->estimate() - angle2->estimate() ) * dt2_inv; + double acc = (vel2 - vel1) * aux0; + double omegadot = (omega2 - omega1) * aux0; + double aux3 = -acc/2; + double aux4 = -omegadot/2; + + double dev_border_acc = penaltyBoundToIntervalDerivative(acc, tebConfig.robot_acceleration_max_trans,optimizationConfig.optimization_boundaries_epsilon,optimizationConfig.optimization_boundaries_scale,optimizationConfig.optimization_boundaries_order); + double dev_border_omegadot = penaltyBoundToIntervalDerivative(omegadot, tebConfig.robot_acceleration_max_rot,optimizationConfig.optimization_boundaries_epsilon,optimizationConfig.optimization_boundaries_scale,optimizationConfig.optimization_boundaries_order); + + _jacobianOplus[0].resize(2,2); // conf1 + _jacobianOplus[1].resize(2,2); // conf2 + _jacobianOplus[2].resize(2,2); // conf3 + _jacobianOplus[3].resize(2,1); // deltaT1 + _jacobianOplus[4].resize(2,1); // deltaT2 + _jacobianOplus[5].resize(2,1); // angle1 + _jacobianOplus[6].resize(2,1); // angle2 + _jacobianOplus[7].resize(2,1); // angle3 + + if (aux1==0) aux1=1e-20; + if (aux2==0) aux2=1e-20; + + if (dev_border_acc!=0) + { + // TODO: double aux = aux0 * dev_border_acc; + // double aux123 = aux / aux1; + _jacobianOplus[0](0,0) = aux0 * deltaS1[0] / aux1 * dev_border_acc; // acc x1 + _jacobianOplus[0](0,1) = aux0 * deltaS1[1] / aux1 * dev_border_acc; // acc y1 + _jacobianOplus[1](0,0) = -aux0 * ( deltaS1[0] / aux1 + deltaS2[0] / aux2 ) * dev_border_acc; // acc x2 + _jacobianOplus[1](0,1) = -aux0 * ( deltaS1[1] / aux1 + deltaS2[1] / aux2 ) * dev_border_acc; // acc y2 + _jacobianOplus[2](0,0) = aux0 * deltaS2[0] / aux2 * dev_border_acc; // acc x3 + _jacobianOplus[2](0,1) = aux0 * deltaS2[1] / aux2 * dev_border_acc; // acc y3 + _jacobianOplus[2](0,0) = 0; + _jacobianOplus[2](0,1) = 0; + _jacobianOplus[3](0,0) = aux0 * (aux3 + vel1 * dt1_inv) * dev_border_acc; // acc deltaT1 + _jacobianOplus[4](0,0) = aux0 * (aux3 - vel2 * dt2_inv) * dev_border_acc; // acc deltaT2 + } + else + { + _jacobianOplus[0](0,0) = 0; // acc x1 + _jacobianOplus[0](0,1) = 0; // acc y1 + _jacobianOplus[1](0,0) = 0; // acc x2 + _jacobianOplus[1](0,1) = 0; // acc y2 + _jacobianOplus[2](0,0) = 0; // acc x3 + _jacobianOplus[2](0,1) = 0; // acc y3 + _jacobianOplus[3](0,0) = 0; // acc deltaT1 + _jacobianOplus[4](0,0) = 0; // acc deltaT2 + } + + if (dev_border_omegadot!=0) + { + _jacobianOplus[3](1,0) = aux0 * ( aux4 + omega1 * dt1_inv ) * dev_border_omegadot; // omegadot deltaT1 + _jacobianOplus[4](1,0) = aux0 * ( aux4 - omega2 * dt2_inv ) * dev_border_omegadot; // omegadot deltaT2 + _jacobianOplus[5](1,0) = aux0 * dt1_inv * dev_border_omegadot; // omegadot angle1 + _jacobianOplus[6](1,0) = -aux0 * ( dt1_inv + dt2_inv ) * dev_border_omegadot; // omegadot angle2 + _jacobianOplus[7](1,0) = aux0 * dt2_inv * dev_border_omegadot; // omegadot angle3 + } + else + { + _jacobianOplus[3](1,0) = 0; // omegadot deltaT1 + _jacobianOplus[4](1,0) = 0; // omegadot deltaT2 + _jacobianOplus[5](1,0) = 0; // omegadot angle1 + _jacobianOplus[6](1,0) = 0; // omegadot angle2 + _jacobianOplus[7](1,0) = 0; // omegadot angle3 + } + + _jacobianOplus[0](1,0) = 0; // omegadot x1 + _jacobianOplus[0](1,1) = 0; // omegadot y1 + _jacobianOplus[1](1,0) = 0; // omegadot x2 + _jacobianOplus[1](1,1) = 0; // omegadot y2 + _jacobianOplus[2](1,0) = 0; // omegadot x3 + _jacobianOplus[2](1,1) = 0; // omegadot y3 + _jacobianOplus[5](0,0) = 0; // acc angle1 + _jacobianOplus[6](0,0) = 0; // acc angle2 + _jacobianOplus[7](0,0) = 0; // acc angle3 + } +#endif +#endif + + +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + +}; + + +/** + * @class EdgeAccelerationStart + * @brief Edge defining the cost function for limiting the translational and rotational acceleration at the beginning of the trajectory. + * + * The edge depends on three vertices \f$ \mathbf{s}_i, \mathbf{s}_{ip1}, \Delta T_i \f$, an initial velocity defined by setInitialVelocity() + * and minimizes: \n + * \f$ \min \textrm{penaltyInterval}( [a, omegadot ]^T ) \cdot weight \f$. \n + * \e a is calculated using the difference quotient (twice) and the position parts of the poses. \n + * \e omegadot is calculated using the difference quotient of the yaw angles followed by a normalization to [-pi, pi]. \n + * \e weight can be set using setInformation(). \n + * \e penaltyInterval denotes the penalty function, see penaltyBoundToInterval(). \n + * The dimension of the error / cost vector is 2: the first component represents the translational acceleration and + * the second one the rotational acceleration. + * @see TebOptimalPlanner::AddEdgesAcceleration + * @see EdgeAcceleration + * @see EdgeAccelerationGoal + * @remarks Do not forget to call setTebConfig() + * @remarks Refer to EdgeAccelerationGoal() for defining boundary values at the end of the trajectory! + */ +class EdgeAccelerationStart : public BaseTebMultiEdge<2, const geometry_msgs::Twist*> +{ +public: + + /** + * @brief Construct edge. + */ + EdgeAccelerationStart() + { + _measurement = NULL; + this->resize(3); + } + + + /** + * @brief Actual cost function + */ + void computeError() + { + ROS_ASSERT_MSG(cfg_ && _measurement, "You must call setTebConfig() and setStartVelocity() on EdgeAccelerationStart()"); + const VertexPose* pose1 = static_cast(_vertices[0]); + const VertexPose* pose2 = static_cast(_vertices[1]); + const VertexTimeDiff* dt = static_cast(_vertices[2]); + + // VELOCITY & ACCELERATION + const Eigen::Vector2d diff = pose2->position() - pose1->position(); + double dist = diff.norm(); + const double angle_diff = g2o::normalize_theta(pose2->theta() - pose1->theta()); + if (cfg_->trajectory.exact_arc_length && angle_diff != 0) + { + const double radius = dist/(2*sin(angle_diff/2)); + dist = fabs( angle_diff * radius ); // actual arg length! + } + + const double vel1 = _measurement->linear.x; + double vel2 = dist / dt->dt(); + + // consider directions + //vel2 *= g2o::sign(diff[0]*cos(pose1->theta()) + diff[1]*sin(pose1->theta())); + vel2 *= fast_sigmoid( 100*(diff.x()*cos(pose1->theta()) + diff.y()*sin(pose1->theta())) ); + + const double acc_lin = (vel2 - vel1) / dt->dt(); + + _error[0] = penaltyBoundToInterval(acc_lin,cfg_->robot.acc_lim_x,cfg_->optim.penalty_epsilon); + + // ANGULAR ACCELERATION + const double omega1 = _measurement->angular.z; + const double omega2 = angle_diff / dt->dt(); + const double acc_rot = (omega2 - omega1) / dt->dt(); + + _error[1] = penaltyBoundToInterval(acc_rot,cfg_->robot.acc_lim_theta,cfg_->optim.penalty_epsilon); + + ROS_ASSERT_MSG(std::isfinite(_error[0]), "EdgeAccelerationStart::computeError() translational: _error[0]=%f\n",_error[0]); + ROS_ASSERT_MSG(std::isfinite(_error[1]), "EdgeAccelerationStart::computeError() rotational: _error[1]=%f\n",_error[1]); + } + + /** + * @brief Set the initial velocity that is taken into account for calculating the acceleration + * @param vel_start twist message containing the translational and rotational velocity + */ + void setInitialVelocity(const geometry_msgs::Twist& vel_start) + { + _measurement = &vel_start; + } + +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +}; + + + + +/** + * @class EdgeAccelerationGoal + * @brief Edge defining the cost function for limiting the translational and rotational acceleration at the end of the trajectory. + * + * The edge depends on three vertices \f$ \mathbf{s}_i, \mathbf{s}_{ip1}, \Delta T_i \f$, an initial velocity defined by setGoalVelocity() + * and minimizes: \n + * \f$ \min \textrm{penaltyInterval}( [a, omegadot ]^T ) \cdot weight \f$. \n + * \e a is calculated using the difference quotient (twice) and the position parts of the poses \n + * \e omegadot is calculated using the difference quotient of the yaw angles followed by a normalization to [-pi, pi]. \n + * \e weight can be set using setInformation() \n + * \e penaltyInterval denotes the penalty function, see penaltyBoundToInterval() \n + * The dimension of the error / cost vector is 2: the first component represents the translational acceleration and + * the second one the rotational acceleration. + * @see TebOptimalPlanner::AddEdgesAcceleration + * @see EdgeAcceleration + * @see EdgeAccelerationStart + * @remarks Do not forget to call setTebConfig() + * @remarks Refer to EdgeAccelerationStart() for defining boundary (initial) values at the end of the trajectory + */ +class EdgeAccelerationGoal : public BaseTebMultiEdge<2, const geometry_msgs::Twist*> +{ +public: + + /** + * @brief Construct edge. + */ + EdgeAccelerationGoal() + { + _measurement = NULL; + this->resize(3); + } + + + /** + * @brief Actual cost function + */ + void computeError() + { + ROS_ASSERT_MSG(cfg_ && _measurement, "You must call setTebConfig() and setGoalVelocity() on EdgeAccelerationGoal()"); + const VertexPose* pose_pre_goal = static_cast(_vertices[0]); + const VertexPose* pose_goal = static_cast(_vertices[1]); + const VertexTimeDiff* dt = static_cast(_vertices[2]); + + // VELOCITY & ACCELERATION + + const Eigen::Vector2d diff = pose_goal->position() - pose_pre_goal->position(); + double dist = diff.norm(); + const double angle_diff = g2o::normalize_theta(pose_goal->theta() - pose_pre_goal->theta()); + if (cfg_->trajectory.exact_arc_length && angle_diff != 0) + { + double radius = dist/(2*sin(angle_diff/2)); + dist = fabs( angle_diff * radius ); // actual arg length! + } + + double vel1 = dist / dt->dt(); + const double vel2 = _measurement->linear.x; + + // consider directions + //vel1 *= g2o::sign(diff[0]*cos(pose_pre_goal->theta()) + diff[1]*sin(pose_pre_goal->theta())); + vel1 *= fast_sigmoid( 100*(diff.x()*cos(pose_pre_goal->theta()) + diff.y()*sin(pose_pre_goal->theta())) ); + + const double acc_lin = (vel2 - vel1) / dt->dt(); + + _error[0] = penaltyBoundToInterval(acc_lin,cfg_->robot.acc_lim_x,cfg_->optim.penalty_epsilon); + + // ANGULAR ACCELERATION + const double omega1 = angle_diff / dt->dt(); + const double omega2 = _measurement->angular.z; + const double acc_rot = (omega2 - omega1) / dt->dt(); + + _error[1] = penaltyBoundToInterval(acc_rot,cfg_->robot.acc_lim_theta,cfg_->optim.penalty_epsilon); + + ROS_ASSERT_MSG(std::isfinite(_error[0]), "EdgeAccelerationGoal::computeError() translational: _error[0]=%f\n",_error[0]); + ROS_ASSERT_MSG(std::isfinite(_error[1]), "EdgeAccelerationGoal::computeError() rotational: _error[1]=%f\n",_error[1]); + } + + /** + * @brief Set the goal / final velocity that is taken into account for calculating the acceleration + * @param vel_goal twist message containing the translational and rotational velocity + */ + void setGoalVelocity(const geometry_msgs::Twist& vel_goal) + { + _measurement = &vel_goal; + } + +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +}; + + + + +/** + * @class EdgeAccelerationHolonomic + * @brief Edge defining the cost function for limiting the translational and rotational acceleration. + * + * The edge depends on five vertices \f$ \mathbf{s}_i, \mathbf{s}_{ip1}, \mathbf{s}_{ip2}, \Delta T_i, \Delta T_{ip1} \f$ and minimizes: + * \f$ \min \textrm{penaltyInterval}( [ax, ay, omegadot } ]^T ) \cdot weight \f$. \n + * \e ax is calculated using the difference quotient (twice) and the x position parts of all three poses \n + * \e ay is calculated using the difference quotient (twice) and the y position parts of all three poses \n + * \e omegadot is calculated using the difference quotient of the yaw angles followed by a normalization to [-pi, pi]. \n + * \e weight can be set using setInformation() \n + * \e penaltyInterval denotes the penalty function, see penaltyBoundToInterval() \n + * The dimension of the error / cost vector is 3: the first component represents the translational acceleration (x-dir), + * the second one the strafing acceleration and the third one the rotational acceleration. + * @see TebOptimalPlanner::AddEdgesAcceleration + * @see EdgeAccelerationHolonomicStart + * @see EdgeAccelerationHolonomicGoal + * @remarks Do not forget to call setTebConfig() + * @remarks Refer to EdgeAccelerationHolonomicStart() and EdgeAccelerationHolonomicGoal() for defining boundary values! + */ +class EdgeAccelerationHolonomic : public BaseTebMultiEdge<3, double> +{ +public: + + /** + * @brief Construct edge. + */ + EdgeAccelerationHolonomic() + { + this->resize(5); + } + + /** + * @brief Actual cost function + */ + void computeError() + { + ROS_ASSERT_MSG(cfg_, "You must call setTebConfig on EdgeAcceleration()"); + const VertexPose* pose1 = static_cast(_vertices[0]); + const VertexPose* pose2 = static_cast(_vertices[1]); + const VertexPose* pose3 = static_cast(_vertices[2]); + const VertexTimeDiff* dt1 = static_cast(_vertices[3]); + const VertexTimeDiff* dt2 = static_cast(_vertices[4]); + + // VELOCITY & ACCELERATION + Eigen::Vector2d diff1 = pose2->position() - pose1->position(); + Eigen::Vector2d diff2 = pose3->position() - pose2->position(); + + double cos_theta1 = std::cos(pose1->theta()); + double sin_theta1 = std::sin(pose1->theta()); + double cos_theta2 = std::cos(pose2->theta()); + double sin_theta2 = std::sin(pose2->theta()); + + // transform pose2 into robot frame pose1 (inverse 2d rotation matrix) + double p1_dx = cos_theta1*diff1.x() + sin_theta1*diff1.y(); + double p1_dy = -sin_theta1*diff1.x() + cos_theta1*diff1.y(); + // transform pose3 into robot frame pose2 (inverse 2d rotation matrix) + double p2_dx = cos_theta2*diff2.x() + sin_theta2*diff2.y(); + double p2_dy = -sin_theta2*diff2.x() + cos_theta2*diff2.y(); + + double vel1_x = p1_dx / dt1->dt(); + double vel1_y = p1_dy / dt1->dt(); + double vel2_x = p2_dx / dt2->dt(); + double vel2_y = p2_dy / dt2->dt(); + + double dt12 = dt1->dt() + dt2->dt(); + + double acc_x = (vel2_x - vel1_x)*2 / dt12; + double acc_y = (vel2_y - vel1_y)*2 / dt12; + + _error[0] = penaltyBoundToInterval(acc_x,cfg_->robot.acc_lim_x,cfg_->optim.penalty_epsilon); + _error[1] = penaltyBoundToInterval(acc_y,cfg_->robot.acc_lim_y,cfg_->optim.penalty_epsilon); + + // ANGULAR ACCELERATION + double omega1 = g2o::normalize_theta(pose2->theta() - pose1->theta()) / dt1->dt(); + double omega2 = g2o::normalize_theta(pose3->theta() - pose2->theta()) / dt2->dt(); + double acc_rot = (omega2 - omega1)*2 / dt12; + + _error[2] = penaltyBoundToInterval(acc_rot,cfg_->robot.acc_lim_theta,cfg_->optim.penalty_epsilon); + + + ROS_ASSERT_MSG(std::isfinite(_error[0]), "EdgeAcceleration::computeError() translational: _error[0]=%f\n",_error[0]); + ROS_ASSERT_MSG(std::isfinite(_error[1]), "EdgeAcceleration::computeError() strafing: _error[1]=%f\n",_error[1]); + ROS_ASSERT_MSG(std::isfinite(_error[2]), "EdgeAcceleration::computeError() rotational: _error[2]=%f\n",_error[2]); + } + +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + +}; + + +/** + * @class EdgeAccelerationHolonomicStart + * @brief Edge defining the cost function for limiting the translational and rotational acceleration at the beginning of the trajectory. + * + * The edge depends on three vertices \f$ \mathbf{s}_i, \mathbf{s}_{ip1}, \Delta T_i \f$, an initial velocity defined by setInitialVelocity() + * and minimizes: \n + * \f$ \min \textrm{penaltyInterval}( [ax, ay, omegadot ]^T ) \cdot weight \f$. \n + * \e ax is calculated using the difference quotient (twice) and the x-position parts of the poses. \n + * \e ay is calculated using the difference quotient (twice) and the y-position parts of the poses. \n + * \e omegadot is calculated using the difference quotient of the yaw angles followed by a normalization to [-pi, pi]. \n + * \e weight can be set using setInformation(). \n + * \e penaltyInterval denotes the penalty function, see penaltyBoundToInterval(). \n + * The dimension of the error / cost vector is 3: the first component represents the translational acceleration, + * the second one the strafing acceleration and the third one the rotational acceleration. + * @see TebOptimalPlanner::AddEdgesAcceleration + * @see EdgeAccelerationHolonomic + * @see EdgeAccelerationHolonomicGoal + * @remarks Do not forget to call setTebConfig() + * @remarks Refer to EdgeAccelerationHolonomicGoal() for defining boundary values at the end of the trajectory! + */ +class EdgeAccelerationHolonomicStart : public BaseTebMultiEdge<3, const geometry_msgs::Twist*> +{ +public: + + /** + * @brief Construct edge. + */ + EdgeAccelerationHolonomicStart() + { + this->resize(3); + _measurement = NULL; + } + + /** + * @brief Actual cost function + */ + void computeError() + { + ROS_ASSERT_MSG(cfg_ && _measurement, "You must call setTebConfig() and setStartVelocity() on EdgeAccelerationStart()"); + const VertexPose* pose1 = static_cast(_vertices[0]); + const VertexPose* pose2 = static_cast(_vertices[1]); + const VertexTimeDiff* dt = static_cast(_vertices[2]); + + // VELOCITY & ACCELERATION + Eigen::Vector2d diff = pose2->position() - pose1->position(); + + double cos_theta1 = std::cos(pose1->theta()); + double sin_theta1 = std::sin(pose1->theta()); + + // transform pose2 into robot frame pose1 (inverse 2d rotation matrix) + double p1_dx = cos_theta1*diff.x() + sin_theta1*diff.y(); + double p1_dy = -sin_theta1*diff.x() + cos_theta1*diff.y(); + + double vel1_x = _measurement->linear.x; + double vel1_y = _measurement->linear.y; + double vel2_x = p1_dx / dt->dt(); + double vel2_y = p1_dy / dt->dt(); + + double acc_lin_x = (vel2_x - vel1_x) / dt->dt(); + double acc_lin_y = (vel2_y - vel1_y) / dt->dt(); + + _error[0] = penaltyBoundToInterval(acc_lin_x,cfg_->robot.acc_lim_x,cfg_->optim.penalty_epsilon); + _error[1] = penaltyBoundToInterval(acc_lin_y,cfg_->robot.acc_lim_y,cfg_->optim.penalty_epsilon); + + // ANGULAR ACCELERATION + double omega1 = _measurement->angular.z; + double omega2 = g2o::normalize_theta(pose2->theta() - pose1->theta()) / dt->dt(); + double acc_rot = (omega2 - omega1) / dt->dt(); + + _error[2] = penaltyBoundToInterval(acc_rot,cfg_->robot.acc_lim_theta,cfg_->optim.penalty_epsilon); + + ROS_ASSERT_MSG(std::isfinite(_error[0]), "EdgeAccelerationStart::computeError() translational: _error[0]=%f\n",_error[0]); + ROS_ASSERT_MSG(std::isfinite(_error[1]), "EdgeAccelerationStart::computeError() strafing: _error[1]=%f\n",_error[1]); + ROS_ASSERT_MSG(std::isfinite(_error[2]), "EdgeAccelerationStart::computeError() rotational: _error[2]=%f\n",_error[2]); + } + + /** + * @brief Set the initial velocity that is taken into account for calculating the acceleration + * @param vel_start twist message containing the translational and rotational velocity + */ + void setInitialVelocity(const geometry_msgs::Twist& vel_start) + { + _measurement = &vel_start; + } + +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +}; + + + +/** + * @class EdgeAccelerationHolonomicGoal + * @brief Edge defining the cost function for limiting the translational and rotational acceleration at the end of the trajectory. + * + * The edge depends on three vertices \f$ \mathbf{s}_i, \mathbf{s}_{ip1}, \Delta T_i \f$, an initial velocity defined by setGoalVelocity() + * and minimizes: \n + * \f$ \min \textrm{penaltyInterval}( [ax, ay, omegadot ]^T ) \cdot weight \f$. \n + * \e ax is calculated using the difference quotient (twice) and the x-position parts of the poses \n + * \e ay is calculated using the difference quotient (twice) and the y-position parts of the poses \n + * \e omegadot is calculated using the difference quotient of the yaw angles followed by a normalization to [-pi, pi]. \n + * \e weight can be set using setInformation() \n + * \e penaltyInterval denotes the penalty function, see penaltyBoundToInterval() \n + * The dimension of the error / cost vector is 3: the first component represents the translational acceleration, + * the second one is the strafing velocity and the third one the rotational acceleration. + * @see TebOptimalPlanner::AddEdgesAcceleration + * @see EdgeAccelerationHolonomic + * @see EdgeAccelerationHolonomicStart + * @remarks Do not forget to call setTebConfig() + * @remarks Refer to EdgeAccelerationHolonomicStart() for defining boundary (initial) values at the end of the trajectory + */ +class EdgeAccelerationHolonomicGoal : public BaseTebMultiEdge<3, const geometry_msgs::Twist*> +{ +public: + + /** + * @brief Construct edge. + */ + EdgeAccelerationHolonomicGoal() + { + _measurement = NULL; + this->resize(3); + } + + /** + * @brief Actual cost function + */ + void computeError() + { + ROS_ASSERT_MSG(cfg_ && _measurement, "You must call setTebConfig() and setGoalVelocity() on EdgeAccelerationGoal()"); + const VertexPose* pose_pre_goal = static_cast(_vertices[0]); + const VertexPose* pose_goal = static_cast(_vertices[1]); + const VertexTimeDiff* dt = static_cast(_vertices[2]); + + // VELOCITY & ACCELERATION + + Eigen::Vector2d diff = pose_goal->position() - pose_pre_goal->position(); + + double cos_theta1 = std::cos(pose_pre_goal->theta()); + double sin_theta1 = std::sin(pose_pre_goal->theta()); + + // transform pose2 into robot frame pose1 (inverse 2d rotation matrix) + double p1_dx = cos_theta1*diff.x() + sin_theta1*diff.y(); + double p1_dy = -sin_theta1*diff.x() + cos_theta1*diff.y(); + + double vel1_x = p1_dx / dt->dt(); + double vel1_y = p1_dy / dt->dt(); + double vel2_x = _measurement->linear.x; + double vel2_y = _measurement->linear.y; + + double acc_lin_x = (vel2_x - vel1_x) / dt->dt(); + double acc_lin_y = (vel2_y - vel1_y) / dt->dt(); + + _error[0] = penaltyBoundToInterval(acc_lin_x,cfg_->robot.acc_lim_x,cfg_->optim.penalty_epsilon); + _error[1] = penaltyBoundToInterval(acc_lin_y,cfg_->robot.acc_lim_y,cfg_->optim.penalty_epsilon); + + // ANGULAR ACCELERATION + double omega1 = g2o::normalize_theta(pose_goal->theta() - pose_pre_goal->theta()) / dt->dt(); + double omega2 = _measurement->angular.z; + double acc_rot = (omega2 - omega1) / dt->dt(); + + _error[2] = penaltyBoundToInterval(acc_rot,cfg_->robot.acc_lim_theta,cfg_->optim.penalty_epsilon); + + ROS_ASSERT_MSG(std::isfinite(_error[0]), "EdgeAccelerationGoal::computeError() translational: _error[0]=%f\n",_error[0]); + ROS_ASSERT_MSG(std::isfinite(_error[1]), "EdgeAccelerationGoal::computeError() strafing: _error[1]=%f\n",_error[1]); + ROS_ASSERT_MSG(std::isfinite(_error[2]), "EdgeAccelerationGoal::computeError() rotational: _error[2]=%f\n",_error[2]); + } + + + /** + * @brief Set the goal / final velocity that is taken into account for calculating the acceleration + * @param vel_goal twist message containing the translational and rotational velocity + */ + void setGoalVelocity(const geometry_msgs::Twist& vel_goal) + { + _measurement = &vel_goal; + } + + +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +}; + + + + +}; // end namespace + +#endif /* EDGE_ACCELERATION_H_ */ diff --git a/navigations/teb_local_planner/include/teb_local_planner/g2o_types/edge_dynamic_obstacle.h b/navigations/teb_local_planner/include/teb_local_planner/g2o_types/edge_dynamic_obstacle.h new file mode 100755 index 0000000..c5197d1 --- /dev/null +++ b/navigations/teb_local_planner/include/teb_local_planner/g2o_types/edge_dynamic_obstacle.h @@ -0,0 +1,153 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2016, + * TU Dortmund - Institute of Control Theory and Systems Engineering. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the institute nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Notes: + * The following class is derived from a class defined by the + * g2o-framework. g2o is licensed under the terms of the BSD License. + * Refer to the base class source for detailed licensing information. + * + * Author: Christoph Rösmann, Franz Albers + *********************************************************************/ + +#ifndef EDGE_DYNAMICOBSTACLE_H +#define EDGE_DYNAMICOBSTACLE_H + +#include +#include +#include +#include +#include +#include +#include + +namespace teb_local_planner +{ + +/** + * @class EdgeDynamicObstacle + * @brief Edge defining the cost function for keeping a distance from dynamic (moving) obstacles. + * + * The edge depends on two vertices \f$ \mathbf{s}_i, \Delta T_i \f$ and minimizes: \n + * \f$ \min \textrm{penaltyBelow}( dist2obstacle) \cdot weight \f$. \n + * \e dist2obstacle denotes the minimum distance to the obstacle trajectory (spatial and temporal). \n + * \e weight can be set using setInformation(). \n + * \e penaltyBelow denotes the penalty function, see penaltyBoundFromBelow(). \n + * @see TebOptimalPlanner::AddEdgesDynamicObstacles + * @remarks Do not forget to call setTebConfig(), setVertexIdx() and + * @warning Experimental + */ +class EdgeDynamicObstacle : public BaseTebUnaryEdge<2, const Obstacle*, VertexPose> +{ +public: + + /** + * @brief Construct edge. + */ + EdgeDynamicObstacle() : t_(0) + { + } + + /** + * @brief Construct edge and specify the time for its associated pose (neccessary for computeError). + * @param t_ Estimated time until current pose is reached + */ + EdgeDynamicObstacle(double t) : t_(t) + { + } + + /** + * @brief Actual cost function + */ + void computeError() + { + ROS_ASSERT_MSG(cfg_ && _measurement && robot_model_, "You must call setTebConfig(), setObstacle() and setRobotModel() on EdgeDynamicObstacle()"); + const VertexPose* bandpt = static_cast(_vertices[0]); + + double dist = robot_model_->estimateSpatioTemporalDistance(bandpt->pose(), _measurement, t_); + + _error[0] = penaltyBoundFromBelow(dist, cfg_->obstacles.min_obstacle_dist, cfg_->optim.penalty_epsilon); + _error[1] = penaltyBoundFromBelow(dist, cfg_->obstacles.dynamic_obstacle_inflation_dist, 0.0); + + ROS_ASSERT_MSG(std::isfinite(_error[0]), "EdgeDynamicObstacle::computeError() _error[0]=%f\n",_error[0]); + } + + + /** + * @brief Set Obstacle for the underlying cost function + * @param obstacle Const pointer to an Obstacle or derived Obstacle + */ + void setObstacle(const Obstacle* obstacle) + { + _measurement = obstacle; + } + + /** + * @brief Set pointer to the robot model + * @param robot_model Robot model required for distance calculation + */ + void setRobotModel(const BaseRobotFootprintModel* robot_model) + { + robot_model_ = robot_model; + } + + /** + * @brief Set all parameters at once + * @param cfg TebConfig class + * @param robot_model Robot model required for distance calculation + * @param obstacle 2D position vector containing the position of the obstacle + */ + void setParameters(const TebConfig& cfg, const BaseRobotFootprintModel* robot_model, const Obstacle* obstacle) + { + cfg_ = &cfg; + robot_model_ = robot_model; + _measurement = obstacle; + } + +protected: + + const BaseRobotFootprintModel* robot_model_; //!< Store pointer to robot_model + double t_; //!< Estimated time until current pose is reached + +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + +}; + + + + +} // end namespace + +#endif diff --git a/navigations/teb_local_planner/include/teb_local_planner/g2o_types/edge_kinematics.h b/navigations/teb_local_planner/include/teb_local_planner/g2o_types/edge_kinematics.h new file mode 100755 index 0000000..694e602 --- /dev/null +++ b/navigations/teb_local_planner/include/teb_local_planner/g2o_types/edge_kinematics.h @@ -0,0 +1,230 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2016, + * TU Dortmund - Institute of Control Theory and Systems Engineering. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the institute nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Notes: + * The following class is derived from a class defined by the + * g2o-framework. g2o is licensed under the terms of the BSD License. + * Refer to the base class source for detailed licensing information. + * + * Author: Christoph Rösmann + *********************************************************************/ + +#ifndef _EDGE_KINEMATICS_H +#define _EDGE_KINEMATICS_H + +#include +#include +#include +#include + +#include + +namespace teb_local_planner +{ + +/** + * @class EdgeKinematicsDiffDrive + * @brief Edge defining the cost function for satisfying the non-holonomic kinematics of a differential drive mobile robot. + * + * The edge depends on two vertices \f$ \mathbf{s}_i, \mathbf{s}_{ip1} \f$ and minimizes a geometric interpretation + * of the non-holonomic constraint: + * - C. Rösmann et al.: Trajectory modification considering dynamic constraints of autonomous robots, ROBOTIK, 2012. + * + * The \e weight can be set using setInformation(): Matrix element 1,1: (Choose a very high value: ~1000). \n + * A second equation is implemented to penalize backward motions (second element of the error /cost vector). \n + * The \e weight can be set using setInformation(): Matrix element 2,2: (A value ~1 allows backward driving, but penalizes it slighly). \n + * The dimension of the error / cost vector is 2: the first component represents the nonholonomic constraint cost, + * the second one backward-drive cost. + * @see TebOptimalPlanner::AddEdgesKinematics, EdgeKinematicsCarlike + * @remarks Do not forget to call setTebConfig() + */ +class EdgeKinematicsDiffDrive : public BaseTebBinaryEdge<2, double, VertexPose, VertexPose> +{ +public: + + /** + * @brief Construct edge. + */ + EdgeKinematicsDiffDrive() + { + this->setMeasurement(0.); + } + + /** + * @brief Actual cost function + */ + void computeError() + { + ROS_ASSERT_MSG(cfg_, "You must call setTebConfig on EdgeKinematicsDiffDrive()"); + const VertexPose* conf1 = static_cast(_vertices[0]); + const VertexPose* conf2 = static_cast(_vertices[1]); + + Eigen::Vector2d deltaS = conf2->position() - conf1->position(); + + // non holonomic constraint + _error[0] = fabs( ( cos(conf1->theta())+cos(conf2->theta()) ) * deltaS[1] - ( sin(conf1->theta())+sin(conf2->theta()) ) * deltaS[0] ); + + // positive-drive-direction constraint + Eigen::Vector2d angle_vec ( cos(conf1->theta()), sin(conf1->theta()) ); + _error[1] = penaltyBoundFromBelow(deltaS.dot(angle_vec), 0,0); + // epsilon=0, otherwise it pushes the first bandpoints away from start + + ROS_ASSERT_MSG(std::isfinite(_error[0]) && std::isfinite(_error[1]), "EdgeKinematicsDiffDrive::computeError() _error[0]=%f _error[1]=%f\n",_error[0],_error[1]); + } + +#ifdef USE_ANALYTIC_JACOBI +#if 1 + /** + * @brief Jacobi matrix of the cost function specified in computeError(). + */ + void linearizeOplus() + { + ROS_ASSERT_MSG(cfg_, "You must call setTebConfig on EdgeKinematicsDiffDrive()"); + const VertexPose* conf1 = static_cast(_vertices[0]); + const VertexPose* conf2 = static_cast(_vertices[1]); + + Eigen::Vector2d deltaS = conf2->position() - conf1->position(); + + double cos1 = cos(conf1->theta()); + double cos2 = cos(conf2->theta()); + double sin1 = sin(conf1->theta()); + double sin2 = sin(conf2->theta()); + double aux1 = sin1 + sin2; + double aux2 = cos1 + cos2; + + double dd_error_1 = deltaS[0]*cos1; + double dd_error_2 = deltaS[1]*sin1; + double dd_dev = penaltyBoundFromBelowDerivative(dd_error_1+dd_error_2, 0,0); + + double dev_nh_abs = g2o::sign( ( cos(conf1->theta())+cos(conf2->theta()) ) * deltaS[1] - + ( sin(conf1->theta())+sin(conf2->theta()) ) * deltaS[0] ); + + // conf1 + _jacobianOplusXi(0,0) = aux1 * dev_nh_abs; // nh x1 + _jacobianOplusXi(0,1) = -aux2 * dev_nh_abs; // nh y1 + _jacobianOplusXi(1,0) = -cos1 * dd_dev; // drive-dir x1 + _jacobianOplusXi(1,1) = -sin1 * dd_dev; // drive-dir y1 + _jacobianOplusXi(0,2) = (-dd_error_2 - dd_error_1) * dev_nh_abs; // nh angle + _jacobianOplusXi(1,2) = ( -sin1*deltaS[0] + cos1*deltaS[1] ) * dd_dev; // drive-dir angle1 + + // conf2 + _jacobianOplusXj(0,0) = -aux1 * dev_nh_abs; // nh x2 + _jacobianOplusXj(0,1) = aux2 * dev_nh_abs; // nh y2 + _jacobianOplusXj(1,0) = cos1 * dd_dev; // drive-dir x2 + _jacobianOplusXj(1,1) = sin1 * dd_dev; // drive-dir y2 + _jacobianOplusXj(0,2) = (-sin2*deltaS[1] - cos2*deltaS[0]) * dev_nh_abs; // nh angle + _jacobianOplusXj(1,2) = 0; // drive-dir angle1 + } +#endif +#endif + +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +}; + + + + +/** + * @class EdgeKinematicsCarlike + * @brief Edge defining the cost function for satisfying the non-holonomic kinematics of a carlike mobile robot. + * + * The edge depends on two vertices \f$ \mathbf{s}_i, \mathbf{s}_{ip1} \f$ and minimizes a geometric interpretation + * of the non-holonomic constraint: + * - C. Rösmann et al.: Trajectory modification considering dynamic constraints of autonomous robots, ROBOTIK, 2012. + * + * The definition is identically to the one of the differential drive robot. + * Additionally, this edge incorporates a minimum turning radius that is required by carlike robots. + * The turning radius is defined by \f$ r=v/omega \f$. + * + * The \e weight can be set using setInformation(): Matrix element 1,1: (Choose a very high value: ~1000). \n + * The second equation enforces a minimum turning radius. + * The \e weight can be set using setInformation(): Matrix element 2,2. \n + * The dimension of the error / cost vector is 3: the first component represents the nonholonomic constraint cost, + * the second one backward-drive cost and the third one the minimum turning radius + * @see TebOptimalPlanner::AddEdgesKinematics, EdgeKinematicsDiffDrive + * @remarks Bounding the turning radius from below is not affected by the penalty_epsilon parameter, + * the user might add an extra margin to the min_turning_radius param. + * @remarks Do not forget to call setTebConfig() + */ +class EdgeKinematicsCarlike : public BaseTebBinaryEdge<2, double, VertexPose, VertexPose> +{ +public: + + /** + * @brief Construct edge. + */ + EdgeKinematicsCarlike() + { + this->setMeasurement(0.); + } + + /** + * @brief Actual cost function + */ + void computeError() + { + ROS_ASSERT_MSG(cfg_, "You must call setTebConfig on EdgeKinematicsCarlike()"); + const VertexPose* conf1 = static_cast(_vertices[0]); + const VertexPose* conf2 = static_cast(_vertices[1]); + + Eigen::Vector2d deltaS = conf2->position() - conf1->position(); + + // non holonomic constraint + _error[0] = fabs( ( cos(conf1->theta())+cos(conf2->theta()) ) * deltaS[1] - ( sin(conf1->theta())+sin(conf2->theta()) ) * deltaS[0] ); + + // limit minimum turning radius + double angle_diff = g2o::normalize_theta( conf2->theta() - conf1->theta() ); + if (angle_diff == 0) + _error[1] = 0; // straight line motion + else if (cfg_->trajectory.exact_arc_length) // use exact computation of the radius + _error[1] = penaltyBoundFromBelow(fabs(deltaS.norm()/(2*sin(angle_diff/2))), cfg_->robot.min_turning_radius, 0.0); + else + _error[1] = penaltyBoundFromBelow(deltaS.norm() / fabs(angle_diff), cfg_->robot.min_turning_radius, 0.0); + // This edge is not affected by the epsilon parameter, the user might add an exra margin to the min_turning_radius parameter. + + ROS_ASSERT_MSG(std::isfinite(_error[0]) && std::isfinite(_error[1]), "EdgeKinematicsCarlike::computeError() _error[0]=%f _error[1]=%f\n",_error[0],_error[1]); + } + +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +}; + + + + +} // end namespace + +#endif diff --git a/navigations/teb_local_planner/include/teb_local_planner/g2o_types/edge_obstacle.h b/navigations/teb_local_planner/include/teb_local_planner/g2o_types/edge_obstacle.h new file mode 100755 index 0000000..976c494 --- /dev/null +++ b/navigations/teb_local_planner/include/teb_local_planner/g2o_types/edge_obstacle.h @@ -0,0 +1,295 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2016, + * TU Dortmund - Institute of Control Theory and Systems Engineering. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the institute nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Notes: + * The following class is derived from a class defined by the + * g2o-framework. g2o is licensed under the terms of the BSD License. + * Refer to the base class source for detailed licensing information. + * + * Author: Christoph Rösmann + *********************************************************************/ +#ifndef EDGE_OBSTACLE_H_ +#define EDGE_OBSTACLE_H_ + +#include +#include +#include +#include +#include +#include + + + +namespace teb_local_planner +{ + +/** + * @class EdgeObstacle + * @brief Edge defining the cost function for keeping a minimum distance from obstacles. + * + * The edge depends on a single vertex \f$ \mathbf{s}_i \f$ and minimizes: \n + * \f$ \min \textrm{penaltyBelow}( dist2point ) \cdot weight \f$. \n + * \e dist2point denotes the minimum distance to the point obstacle. \n + * \e weight can be set using setInformation(). \n + * \e penaltyBelow denotes the penalty function, see penaltyBoundFromBelow() \n + * @see TebOptimalPlanner::AddEdgesObstacles, TebOptimalPlanner::EdgeInflatedObstacle + * @remarks Do not forget to call setTebConfig() and setObstacle() + */ +class EdgeObstacle : public BaseTebUnaryEdge<1, const Obstacle*, VertexPose> +{ +public: + + /** + * @brief Construct edge. + */ + EdgeObstacle() + { + _measurement = NULL; + } + + /** + * @brief Actual cost function + */ + void computeError() + { + ROS_ASSERT_MSG(cfg_ && _measurement && robot_model_, "You must call setTebConfig(), setObstacle() and setRobotModel() on EdgeObstacle()"); + const VertexPose* bandpt = static_cast(_vertices[0]); + + double dist = robot_model_->calculateDistance(bandpt->pose(), _measurement); + + // Original obstacle cost. + _error[0] = penaltyBoundFromBelow(dist, cfg_->obstacles.min_obstacle_dist, cfg_->optim.penalty_epsilon); + + if (cfg_->optim.obstacle_cost_exponent != 1.0 && cfg_->obstacles.min_obstacle_dist > 0.0) + { + // Optional non-linear cost. Note the max cost (before weighting) is + // the same as the straight line version and that all other costs are + // below the straight line (for positive exponent), so it may be + // necessary to increase weight_obstacle and/or the inflation_weight + // when using larger exponents. + _error[0] = cfg_->obstacles.min_obstacle_dist * std::pow(_error[0] / cfg_->obstacles.min_obstacle_dist, cfg_->optim.obstacle_cost_exponent); + } + + ROS_ASSERT_MSG(std::isfinite(_error[0]), "EdgeObstacle::computeError() _error[0]=%f\n",_error[0]); + } + +#ifdef USE_ANALYTIC_JACOBI +#if 0 + + /** + * @brief Jacobi matrix of the cost function specified in computeError(). + */ + void linearizeOplus() + { + ROS_ASSERT_MSG(cfg_, "You must call setTebConfig on EdgePointObstacle()"); + const VertexPose* bandpt = static_cast(_vertices[0]); + + Eigen::Vector2d deltaS = *_measurement - bandpt->position(); + double angdiff = atan2(deltaS[1],deltaS[0])-bandpt->theta(); + + double dist_squared = deltaS.squaredNorm(); + double dist = sqrt(dist_squared); + + double aux0 = sin(angdiff); + double dev_left_border = penaltyBoundFromBelowDerivative(dist*fabs(aux0),cfg_->obstacles.min_obstacle_dist,cfg_->optim.penalty_epsilon); + + if (dev_left_border==0) + { + _jacobianOplusXi( 0 , 0 ) = 0; + _jacobianOplusXi( 0 , 1 ) = 0; + _jacobianOplusXi( 0 , 2 ) = 0; + return; + } + + double aux1 = -fabs(aux0) / dist; + double dev_norm_x = deltaS[0]*aux1; + double dev_norm_y = deltaS[1]*aux1; + + double aux2 = cos(angdiff) * g2o::sign(aux0); + double aux3 = aux2 / dist_squared; + double dev_proj_x = aux3 * deltaS[1] * dist; + double dev_proj_y = -aux3 * deltaS[0] * dist; + double dev_proj_angle = -aux2; + + _jacobianOplusXi( 0 , 0 ) = dev_left_border * ( dev_norm_x + dev_proj_x ); + _jacobianOplusXi( 0 , 1 ) = dev_left_border * ( dev_norm_y + dev_proj_y ); + _jacobianOplusXi( 0 , 2 ) = dev_left_border * dev_proj_angle; + } +#endif +#endif + + /** + * @brief Set pointer to associated obstacle for the underlying cost function + * @param obstacle 2D position vector containing the position of the obstacle + */ + void setObstacle(const Obstacle* obstacle) + { + _measurement = obstacle; + } + + /** + * @brief Set pointer to the robot model + * @param robot_model Robot model required for distance calculation + */ + void setRobotModel(const BaseRobotFootprintModel* robot_model) + { + robot_model_ = robot_model; + } + + /** + * @brief Set all parameters at once + * @param cfg TebConfig class + * @param robot_model Robot model required for distance calculation + * @param obstacle 2D position vector containing the position of the obstacle + */ + void setParameters(const TebConfig& cfg, const BaseRobotFootprintModel* robot_model, const Obstacle* obstacle) + { + cfg_ = &cfg; + robot_model_ = robot_model; + _measurement = obstacle; + } + +protected: + + const BaseRobotFootprintModel* robot_model_; //!< Store pointer to robot_model + +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + +}; + + + +/** + * @class EdgeInflatedObstacle + * @brief Edge defining the cost function for keeping a minimum distance from inflated obstacles. + * + * The edge depends on a single vertex \f$ \mathbf{s}_i \f$ and minimizes: \n + * \f$ \min \textrm{penaltyBelow}( dist2point, min_obstacle_dist ) \cdot weight_inflation \f$. \n + * Additional, a second penalty is provided with \n + * \f$ \min \textrm{penaltyBelow}( dist2point, inflation_dist ) \cdot weight_inflation \f$. + * It is assumed that inflation_dist > min_obstacle_dist and weight_inflation << weight_inflation. + * \e dist2point denotes the minimum distance to the point obstacle. \n + * \e penaltyBelow denotes the penalty function, see penaltyBoundFromBelow() \n + * @see TebOptimalPlanner::AddEdgesObstacles, TebOptimalPlanner::EdgeObstacle + * @remarks Do not forget to call setTebConfig() and setObstacle() + */ +class EdgeInflatedObstacle : public BaseTebUnaryEdge<2, const Obstacle*, VertexPose> +{ +public: + + /** + * @brief Construct edge. + */ + EdgeInflatedObstacle() + { + _measurement = NULL; + } + + /** + * @brief Actual cost function + */ + void computeError() + { + ROS_ASSERT_MSG(cfg_ && _measurement && robot_model_, "You must call setTebConfig(), setObstacle() and setRobotModel() on EdgeInflatedObstacle()"); + const VertexPose* bandpt = static_cast(_vertices[0]); + + double dist = robot_model_->calculateDistance(bandpt->pose(), _measurement); + + // Original "straight line" obstacle cost. The max possible value + // before weighting is min_obstacle_dist + _error[0] = penaltyBoundFromBelow(dist, cfg_->obstacles.min_obstacle_dist, cfg_->optim.penalty_epsilon); + + if (cfg_->optim.obstacle_cost_exponent != 1.0 && cfg_->obstacles.min_obstacle_dist > 0.0) + { + // Optional non-linear cost. Note the max cost (before weighting) is + // the same as the straight line version and that all other costs are + // below the straight line (for positive exponent), so it may be + // necessary to increase weight_obstacle and/or the inflation_weight + // when using larger exponents. + _error[0] = cfg_->obstacles.min_obstacle_dist * std::pow(_error[0] / cfg_->obstacles.min_obstacle_dist, cfg_->optim.obstacle_cost_exponent); + } + + // Additional linear inflation cost + _error[1] = penaltyBoundFromBelow(dist, cfg_->obstacles.inflation_dist, 0.0); + + + ROS_ASSERT_MSG(std::isfinite(_error[0]) && std::isfinite(_error[1]), "EdgeInflatedObstacle::computeError() _error[0]=%f, _error[1]=%f\n",_error[0], _error[1]); + } + + /** + * @brief Set pointer to associated obstacle for the underlying cost function + * @param obstacle 2D position vector containing the position of the obstacle + */ + void setObstacle(const Obstacle* obstacle) + { + _measurement = obstacle; + } + + /** + * @brief Set pointer to the robot model + * @param robot_model Robot model required for distance calculation + */ + void setRobotModel(const BaseRobotFootprintModel* robot_model) + { + robot_model_ = robot_model; + } + + /** + * @brief Set all parameters at once + * @param cfg TebConfig class + * @param robot_model Robot model required for distance calculation + * @param obstacle 2D position vector containing the position of the obstacle + */ + void setParameters(const TebConfig& cfg, const BaseRobotFootprintModel* robot_model, const Obstacle* obstacle) + { + cfg_ = &cfg; + robot_model_ = robot_model; + _measurement = obstacle; + } + +protected: + + const BaseRobotFootprintModel* robot_model_; //!< Store pointer to robot_model + +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + +}; + + +} // end namespace + +#endif diff --git a/navigations/teb_local_planner/include/teb_local_planner/g2o_types/edge_prefer_rotdir.h b/navigations/teb_local_planner/include/teb_local_planner/g2o_types/edge_prefer_rotdir.h new file mode 100755 index 0000000..f744ef4 --- /dev/null +++ b/navigations/teb_local_planner/include/teb_local_planner/g2o_types/edge_prefer_rotdir.h @@ -0,0 +1,115 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2016, + * TU Dortmund - Institute of Control Theory and Systems Engineering. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the institute nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Notes: + * The following class is derived from a class defined by the + * g2o-framework. g2o is licensed under the terms of the BSD License. + * Refer to the base class source for detailed licensing information. + * + * Author: Christoph Rösmann + *********************************************************************/ +#ifndef EDGE_PREFER_ROTDIR_H_ +#define EDGE_PREFER_ROTDIR_H_ + +#include +#include +#include +#include "g2o/core/base_unary_edge.h" + + +namespace teb_local_planner +{ + +/** + * @class EdgePreferRotDir + * @brief Edge defining the cost function for penalzing a specified turning direction, in particular left resp. right turns + * + * The edge depends on two consecutive vertices \f$ \mathbf{s}_i, \mathbf{s}_{i+1} \f$ and penalizes a given rotation direction + * based on the \e weight and \e dir (\f$ dir \in \{-1,1\} \f$) + * \e dir should be +1 to prefer left rotations and -1 to prefer right rotations \n + * \e weight can be set using setInformation(). \n + * @see TebOptimalPlanner::AddEdgePreferRotDir + */ +class EdgePreferRotDir : public BaseTebBinaryEdge<1, double, VertexPose, VertexPose> +{ +public: + + /** + * @brief Construct edge. + */ + EdgePreferRotDir() + { + _measurement = 1; + } + + /** + * @brief Actual cost function + */ + void computeError() + { + const VertexPose* conf1 = static_cast(_vertices[0]); + const VertexPose* conf2 = static_cast(_vertices[1]); + + _error[0] = penaltyBoundFromBelow( _measurement*g2o::normalize_theta(conf2->theta()-conf1->theta()) , 0, 0); + + ROS_ASSERT_MSG(std::isfinite(_error[0]), "EdgePreferRotDir::computeError() _error[0]=%f\n",_error[0]); + } + + /** + * @brief Specify the prefered direction of rotation + * @param dir +1 to prefer the left side, -1 to prefer the right side + */ + void setRotDir(double dir) + { + _measurement = dir; + } + + /** Prefer rotations to the right */ + void preferRight() {_measurement = -1;} + + /** Prefer rotations to the right */ + void preferLeft() {_measurement = 1;} + + +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + +}; + + + +} // end namespace + +#endif diff --git a/navigations/teb_local_planner/include/teb_local_planner/g2o_types/edge_shortest_path.h b/navigations/teb_local_planner/include/teb_local_planner/g2o_types/edge_shortest_path.h new file mode 100755 index 0000000..7a52c2f --- /dev/null +++ b/navigations/teb_local_planner/include/teb_local_planner/g2o_types/edge_shortest_path.h @@ -0,0 +1,89 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2016, + * TU Dortmund - Institute of Control Theory and Systems Engineering. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the institute nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Notes: + * The following class is derived from a class defined by the + * g2o-framework. g2o is licensed under the terms of the BSD License. + * Refer to the base class source for detailed licensing information. + * + * Author: Christoph Rösmann + *********************************************************************/ + +#ifndef EDGE_SHORTEST_PATH_H_ +#define EDGE_SHORTEST_PATH_H_ + +#include + +#include + +#include +#include + +#include + +namespace teb_local_planner { + +/** + * @class EdgeShortestPath + * @brief Edge defining the cost function for minimizing the Euclidean distance between two consectuive poses. + * + * @see TebOptimalPlanner::AddEdgesShortestPath + */ +class EdgeShortestPath : public BaseTebBinaryEdge<1, double, VertexPose, VertexPose> { +public: + /** + * @brief Construct edge. + */ + EdgeShortestPath() { this->setMeasurement(0.); } + + /** + * @brief Actual cost function + */ + void computeError() { + ROS_ASSERT_MSG(cfg_, "You must call setTebConfig on EdgeShortestPath()"); + const VertexPose *pose1 = static_cast(_vertices[0]); + const VertexPose *pose2 = static_cast(_vertices[1]); + _error[0] = (pose2->position() - pose1->position()).norm(); + + ROS_ASSERT_MSG(std::isfinite(_error[0]), "EdgeShortestPath::computeError() _error[0]=%f\n", _error[0]); + } + +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +}; + +} // end namespace + +#endif /* EDGE_SHORTEST_PATH_H_ */ diff --git a/navigations/teb_local_planner/include/teb_local_planner/g2o_types/edge_time_optimal.h b/navigations/teb_local_planner/include/teb_local_planner/g2o_types/edge_time_optimal.h new file mode 100755 index 0000000..43e1637 --- /dev/null +++ b/navigations/teb_local_planner/include/teb_local_planner/g2o_types/edge_time_optimal.h @@ -0,0 +1,116 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2016, + * TU Dortmund - Institute of Control Theory and Systems Engineering. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the institute nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Notes: + * The following class is derived from a class defined by the + * g2o-framework. g2o is licensed under the terms of the BSD License. + * Refer to the base class source for detailed licensing information. + * + * Author: Christoph Rösmann + *********************************************************************/ + +#ifndef EDGE_TIMEOPTIMAL_H_ +#define EDGE_TIMEOPTIMAL_H_ + +#include + +#include + +#include +#include +#include +#include + +#include + +namespace teb_local_planner +{ + + +/** + * @class EdgeTimeOptimal + * @brief Edge defining the cost function for minimizing transition time of the trajectory. + * + * The edge depends on a single vertex \f$ \Delta T_i \f$ and minimizes: \n + * \f$ \min \Delta T_i^2 \cdot scale \cdot weight \f$. \n + * \e scale is determined using the penaltyEquality() function, since we experiences good convergence speeds with it. \n + * \e weight can be set using setInformation() (something around 1.0 seems to be fine). \n + * @see TebOptimalPlanner::AddEdgesTimeOptimal + * @remarks Do not forget to call setTebConfig() + */ +class EdgeTimeOptimal : public BaseTebUnaryEdge<1, double, VertexTimeDiff> +{ +public: + + /** + * @brief Construct edge. + */ + EdgeTimeOptimal() + { + this->setMeasurement(0.); + } + + /** + * @brief Actual cost function + */ + void computeError() + { + ROS_ASSERT_MSG(cfg_, "You must call setTebConfig on EdgeTimeOptimal()"); + const VertexTimeDiff* timediff = static_cast(_vertices[0]); + + _error[0] = timediff->dt(); + + ROS_ASSERT_MSG(std::isfinite(_error[0]), "EdgeTimeOptimal::computeError() _error[0]=%f\n",_error[0]); + } + +#ifdef USE_ANALYTIC_JACOBI + /** + * @brief Jacobi matrix of the cost function specified in computeError(). + */ + void linearizeOplus() + { + ROS_ASSERT_MSG(cfg_, "You must call setTebConfig on EdgeTimeOptimal()"); + _jacobianOplusXi( 0 , 0 ) = 1; + } +#endif + + +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +}; + +}; // end namespace + +#endif /* EDGE_TIMEOPTIMAL_H_ */ diff --git a/navigations/teb_local_planner/include/teb_local_planner/g2o_types/edge_velocity.h b/navigations/teb_local_planner/include/teb_local_planner/g2o_types/edge_velocity.h new file mode 100755 index 0000000..d9f65ee --- /dev/null +++ b/navigations/teb_local_planner/include/teb_local_planner/g2o_types/edge_velocity.h @@ -0,0 +1,283 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2016, + * TU Dortmund - Institute of Control Theory and Systems Engineering. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the institute nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Notes: + * The following class is derived from a class defined by the + * g2o-framework. g2o is licensed under the terms of the BSD License. + * Refer to the base class source for detailed licensing information. + * + * Author: Christoph Rösmann + *********************************************************************/ + +#ifndef EDGE_VELOCITY_H +#define EDGE_VELOCITY_H + +#include +#include +#include +#include +#include + + +#include + +namespace teb_local_planner +{ + + +/** + * @class EdgeVelocity + * @brief Edge defining the cost function for limiting the translational and rotational velocity. + * + * The edge depends on three vertices \f$ \mathbf{s}_i, \mathbf{s}_{ip1}, \Delta T_i \f$ and minimizes: \n + * \f$ \min \textrm{penaltyInterval}( [v,omega]^T ) \cdot weight \f$. \n + * \e v is calculated using the difference quotient and the position parts of both poses. \n + * \e omega is calculated using the difference quotient of both yaw angles followed by a normalization to [-pi, pi]. \n + * \e weight can be set using setInformation(). \n + * \e penaltyInterval denotes the penalty function, see penaltyBoundToInterval(). \n + * The dimension of the error / cost vector is 2: the first component represents the translational velocity and + * the second one the rotational velocity. + * @see TebOptimalPlanner::AddEdgesVelocity + * @remarks Do not forget to call setTebConfig() + */ +class EdgeVelocity : public BaseTebMultiEdge<2, double> +{ +public: + + /** + * @brief Construct edge. + */ + EdgeVelocity() + { + this->resize(3); // Since we derive from a g2o::BaseMultiEdge, set the desired number of vertices + } + + /** + * @brief Actual cost function + */ + void computeError() + { + ROS_ASSERT_MSG(cfg_, "You must call setTebConfig on EdgeVelocity()"); + const VertexPose* conf1 = static_cast(_vertices[0]); + const VertexPose* conf2 = static_cast(_vertices[1]); + const VertexTimeDiff* deltaT = static_cast(_vertices[2]); + + const Eigen::Vector2d deltaS = conf2->estimate().position() - conf1->estimate().position(); + + double dist = deltaS.norm(); + const double angle_diff = g2o::normalize_theta(conf2->theta() - conf1->theta()); + if (cfg_->trajectory.exact_arc_length && angle_diff != 0) + { + double radius = dist/(2*sin(angle_diff/2)); + dist = fabs( angle_diff * radius ); // actual arg length! + } + double vel = dist / deltaT->estimate(); + +// vel *= g2o::sign(deltaS[0]*cos(conf1->theta()) + deltaS[1]*sin(conf1->theta())); // consider direction + vel *= fast_sigmoid( 100 * (deltaS.x()*cos(conf1->theta()) + deltaS.y()*sin(conf1->theta())) ); // consider direction + + const double omega = angle_diff / deltaT->estimate(); + + _error[0] = penaltyBoundToInterval(vel, -cfg_->robot.max_vel_x_backwards, cfg_->robot.max_vel_x,cfg_->optim.penalty_epsilon); + _error[1] = penaltyBoundToInterval(omega, cfg_->robot.max_vel_theta,cfg_->optim.penalty_epsilon); + + ROS_ASSERT_MSG(std::isfinite(_error[0]), "EdgeVelocity::computeError() _error[0]=%f _error[1]=%f\n",_error[0],_error[1]); + } + +#ifdef USE_ANALYTIC_JACOBI +#if 0 //TODO the hardcoded jacobian does not include the changing direction (just the absolute value) + // Change accordingly... + + /** + * @brief Jacobi matrix of the cost function specified in computeError(). + */ + void linearizeOplus() + { + ROS_ASSERT_MSG(cfg_, "You must call setTebConfig on EdgeVelocity()"); + const VertexPose* conf1 = static_cast(_vertices[0]); + const VertexPose* conf2 = static_cast(_vertices[1]); + const VertexTimeDiff* deltaT = static_cast(_vertices[2]); + + Eigen::Vector2d deltaS = conf2->position() - conf1->position(); + double dist = deltaS.norm(); + double aux1 = dist*deltaT->estimate(); + double aux2 = 1/deltaT->estimate(); + + double vel = dist * aux2; + double omega = g2o::normalize_theta(conf2->theta() - conf1->theta()) * aux2; + + double dev_border_vel = penaltyBoundToIntervalDerivative(vel, -cfg_->robot.max_vel_x_backwards, cfg_->robot.max_vel_x,cfg_->optim.penalty_epsilon); + double dev_border_omega = penaltyBoundToIntervalDerivative(omega, cfg_->robot.max_vel_theta,cfg_->optim.penalty_epsilon); + + _jacobianOplus[0].resize(2,3); // conf1 + _jacobianOplus[1].resize(2,3); // conf2 + _jacobianOplus[2].resize(2,1); // deltaT + +// if (aux1==0) aux1=1e-6; +// if (aux2==0) aux2=1e-6; + + if (dev_border_vel!=0) + { + double aux3 = dev_border_vel / aux1; + _jacobianOplus[0](0,0) = -deltaS[0] * aux3; // vel x1 + _jacobianOplus[0](0,1) = -deltaS[1] * aux3; // vel y1 + _jacobianOplus[1](0,0) = deltaS[0] * aux3; // vel x2 + _jacobianOplus[1](0,1) = deltaS[1] * aux3; // vel y2 + _jacobianOplus[2](0,0) = -vel * aux2 * dev_border_vel; // vel deltaT + } + else + { + _jacobianOplus[0](0,0) = 0; // vel x1 + _jacobianOplus[0](0,1) = 0; // vel y1 + _jacobianOplus[1](0,0) = 0; // vel x2 + _jacobianOplus[1](0,1) = 0; // vel y2 + _jacobianOplus[2](0,0) = 0; // vel deltaT + } + + if (dev_border_omega!=0) + { + double aux4 = aux2 * dev_border_omega; + _jacobianOplus[2](1,0) = -omega * aux4; // omega deltaT + _jacobianOplus[0](1,2) = -aux4; // omega angle1 + _jacobianOplus[1](1,2) = aux4; // omega angle2 + } + else + { + _jacobianOplus[2](1,0) = 0; // omega deltaT + _jacobianOplus[0](1,2) = 0; // omega angle1 + _jacobianOplus[1](1,2) = 0; // omega angle2 + } + + _jacobianOplus[0](1,0) = 0; // omega x1 + _jacobianOplus[0](1,1) = 0; // omega y1 + _jacobianOplus[1](1,0) = 0; // omega x2 + _jacobianOplus[1](1,1) = 0; // omega y2 + _jacobianOplus[0](0,2) = 0; // vel angle1 + _jacobianOplus[1](0,2) = 0; // vel angle2 + } +#endif +#endif + + +public: + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + +}; + + + + + + +/** + * @class EdgeVelocityHolonomic + * @brief Edge defining the cost function for limiting the translational and rotational velocity according to x,y and theta. + * + * The edge depends on three vertices \f$ \mathbf{s}_i, \mathbf{s}_{ip1}, \Delta T_i \f$ and minimizes: \n + * \f$ \min \textrm{penaltyInterval}( [vx,vy,omega]^T ) \cdot weight \f$. \n + * \e vx denotes the translational velocity w.r.t. x-axis (computed using finite differneces). \n + * \e vy denotes the translational velocity w.r.t. y-axis (computed using finite differneces). \n + * \e omega is calculated using the difference quotient of both yaw angles followed by a normalization to [-pi, pi]. \n + * \e weight can be set using setInformation(). \n + * \e penaltyInterval denotes the penalty function, see penaltyBoundToInterval(). \n + * The dimension of the error / cost vector is 3: the first component represents the translational velocity w.r.t. x-axis, + * the second one w.r.t. the y-axis and the third one the rotational velocity. + * @see TebOptimalPlanner::AddEdgesVelocity + * @remarks Do not forget to call setTebConfig() + */ +class EdgeVelocityHolonomic : public BaseTebMultiEdge<3, double> +{ +public: + + /** + * @brief Construct edge. + */ + EdgeVelocityHolonomic() + { + this->resize(3); // Since we derive from a g2o::BaseMultiEdge, set the desired number of vertices + } + + /** + * @brief Actual cost function + */ + void computeError() + { + ROS_ASSERT_MSG(cfg_, "You must call setTebConfig on EdgeVelocityHolonomic()"); + const VertexPose* conf1 = static_cast(_vertices[0]); + const VertexPose* conf2 = static_cast(_vertices[1]); + const VertexTimeDiff* deltaT = static_cast(_vertices[2]); + Eigen::Vector2d deltaS = conf2->position() - conf1->position(); + + double cos_theta1 = std::cos(conf1->theta()); + double sin_theta1 = std::sin(conf1->theta()); + + // transform conf2 into current robot frame conf1 (inverse 2d rotation matrix) + double r_dx = cos_theta1*deltaS.x() + sin_theta1*deltaS.y(); + double r_dy = -sin_theta1*deltaS.x() + cos_theta1*deltaS.y(); + + double vx = r_dx / deltaT->estimate(); + double vy = r_dy / deltaT->estimate(); + double omega = g2o::normalize_theta(conf2->theta() - conf1->theta()) / deltaT->estimate(); + + + double max_vel_trans_remaining_y; + double max_vel_trans_remaining_x; + max_vel_trans_remaining_y = std::sqrt(std::max(0.0, cfg_->robot.max_vel_trans * cfg_->robot.max_vel_trans - vx * vx)); + max_vel_trans_remaining_x = std::sqrt(std::max(0.0, cfg_->robot.max_vel_trans * cfg_->robot.max_vel_trans - vy * vy)); + + double max_vel_y = std::min(max_vel_trans_remaining_y, cfg_->robot.max_vel_y); + double max_vel_x = std::min(max_vel_trans_remaining_x, cfg_->robot.max_vel_x); + double max_vel_x_backwards = std::min(max_vel_trans_remaining_x, cfg_->robot.max_vel_x_backwards); + + _error[0] = penaltyBoundToInterval(vx, -max_vel_x_backwards, max_vel_x, cfg_->optim.penalty_epsilon); + _error[1] = penaltyBoundToInterval(vy, max_vel_y, 0.0); // we do not apply the penalty epsilon here, since the velocity could be close to zero + _error[2] = penaltyBoundToInterval(omega, cfg_->robot.max_vel_theta,cfg_->optim.penalty_epsilon); + + ROS_ASSERT_MSG(std::isfinite(_error[0]) && std::isfinite(_error[1]) && std::isfinite(_error[2]), + "EdgeVelocityHolonomic::computeError() _error[0]=%f _error[1]=%f _error[2]=%f\n",_error[0],_error[1],_error[2]); + } + + +public: + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + +}; + + +} // end namespace + +#endif diff --git a/navigations/teb_local_planner/include/teb_local_planner/g2o_types/edge_velocity_obstacle_ratio.h b/navigations/teb_local_planner/include/teb_local_planner/g2o_types/edge_velocity_obstacle_ratio.h new file mode 100755 index 0000000..ecac1aa --- /dev/null +++ b/navigations/teb_local_planner/include/teb_local_planner/g2o_types/edge_velocity_obstacle_ratio.h @@ -0,0 +1,166 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2016, + * TU Dortmund - Institute of Control Theory and Systems Engineering. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the institute nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Notes: + * The following class is derived from a class defined by the + * g2o-framework. g2o is licensed under the terms of the BSD License. + * Refer to the base class source for detailed licensing information. + * + *********************************************************************/ + +#pragma once + +#include +#include +#include +#include + +namespace teb_local_planner +{ + + +/** + * @class EdgeVelocityObstacleRatio + * @brief Edge defining the cost function for keeping a minimum distance from obstacles. + * + * The edge depends on a single vertex \f$ \mathbf{s}_i \f$ and minimizes: \n + * \f$ \min \textrm{penaltyBelow}( dist2point ) \cdot weight \f$. \n + * \e dist2point denotes the minimum distance to the point obstacle. \n + * \e weight can be set using setInformation(). \n + * \e penaltyBelow denotes the penalty function, see penaltyBoundFromBelow() \n + * @see TebOptimalPlanner::AddEdgesObstacles, TebOptimalPlanner::EdgeInflatedObstacle + * @remarks Do not forget to call setTebConfig() and setObstacle() + */ +class EdgeVelocityObstacleRatio : public BaseTebMultiEdge<2, const Obstacle*> +{ +public: + + /** + * @brief Construct edge. + */ + EdgeVelocityObstacleRatio() : + robot_model_(nullptr) + { + // The three vertices are two poses and one time difference + this->resize(3); // Since we derive from a g2o::BaseMultiEdge, set the desired number of vertices + } + + /** + * @brief Actual cost function + */ + void computeError() + { + ROS_ASSERT_MSG(cfg_ && _measurement && robot_model_, "You must call setTebConfig(), setObstacle() and setRobotModel() on EdgeVelocityObstacleRatio()"); + const VertexPose* conf1 = static_cast(_vertices[0]); + const VertexPose* conf2 = static_cast(_vertices[1]); + const VertexTimeDiff* deltaT = static_cast(_vertices[2]); + + const Eigen::Vector2d deltaS = conf2->estimate().position() - conf1->estimate().position(); + + double dist = deltaS.norm(); + const double angle_diff = g2o::normalize_theta(conf2->theta() - conf1->theta()); + if (cfg_->trajectory.exact_arc_length && angle_diff != 0) + { + double radius = dist/(2*sin(angle_diff/2)); + dist = fabs( angle_diff * radius ); // actual arg length! + } + double vel = dist / deltaT->estimate(); + + vel *= fast_sigmoid( 100 * (deltaS.x()*cos(conf1->theta()) + deltaS.y()*sin(conf1->theta())) ); // consider direction + + const double omega = angle_diff / deltaT->estimate(); + + double dist_to_obstacle = robot_model_->calculateDistance(conf1->pose(), _measurement); + + double ratio; + if (dist_to_obstacle < cfg_->obstacles.obstacle_proximity_lower_bound) + ratio = 0; + else if (dist_to_obstacle > cfg_->obstacles.obstacle_proximity_upper_bound) + ratio = 1; + else + ratio = (dist_to_obstacle - cfg_->obstacles.obstacle_proximity_lower_bound) / + (cfg_->obstacles.obstacle_proximity_upper_bound - cfg_->obstacles.obstacle_proximity_lower_bound); + ratio *= cfg_->obstacles.obstacle_proximity_ratio_max_vel; + + const double max_vel_fwd = ratio * cfg_->robot.max_vel_x; + const double max_omega = ratio * cfg_->robot.max_vel_theta; + _error[0] = penaltyBoundToInterval(vel, max_vel_fwd, 0); + _error[1] = penaltyBoundToInterval(omega, max_omega, 0); + + ROS_ASSERT_MSG(std::isfinite(_error[0]) || std::isfinite(_error[1]), "EdgeVelocityObstacleRatio::computeError() _error[0]=%f , _error[1]=%f\n",_error[0],_error[1]); + } + + /** + * @brief Set pointer to associated obstacle for the underlying cost function + * @param obstacle 2D position vector containing the position of the obstacle + */ + void setObstacle(const Obstacle* obstacle) + { + _measurement = obstacle; + } + + /** + * @brief Set pointer to the robot model + * @param robot_model Robot model required for distance calculation + */ + void setRobotModel(const BaseRobotFootprintModel* robot_model) + { + robot_model_ = robot_model; + } + + /** + * @brief Set all parameters at once + * @param cfg TebConfig class + * @param robot_model Robot model required for distance calculation + * @param obstacle 2D position vector containing the position of the obstacle + */ + void setParameters(const TebConfig& cfg, const BaseRobotFootprintModel* robot_model, const Obstacle* obstacle) + { + cfg_ = &cfg; + robot_model_ = robot_model; + _measurement = obstacle; + } + +protected: + + const BaseRobotFootprintModel* robot_model_; //!< Store pointer to robot_model + +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + +}; + + +} // end namespace diff --git a/navigations/teb_local_planner/include/teb_local_planner/g2o_types/edge_via_point.h b/navigations/teb_local_planner/include/teb_local_planner/g2o_types/edge_via_point.h new file mode 100755 index 0000000..9ddefcb --- /dev/null +++ b/navigations/teb_local_planner/include/teb_local_planner/g2o_types/edge_via_point.h @@ -0,0 +1,120 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2016, + * TU Dortmund - Institute of Control Theory and Systems Engineering. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the institute nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Notes: + * The following class is derived from a class defined by the + * g2o-framework. g2o is licensed under the terms of the BSD License. + * Refer to the base class source for detailed licensing information. + * + * Author: Christoph Rösmann + *********************************************************************/ +#ifndef EDGE_VIA_POINT_H_ +#define EDGE_VIA_POINT_H_ + +#include +#include + +#include "g2o/core/base_unary_edge.h" + + +namespace teb_local_planner +{ + +/** + * @class EdgeViaPoint + * @brief Edge defining the cost function for pushing a configuration towards a via point + * + * The edge depends on a single vertex \f$ \mathbf{s}_i \f$ and minimizes: \n + * \f$ \min dist2point \cdot weight \f$. \n + * \e dist2point denotes the distance to the via point. \n + * \e weight can be set using setInformation(). \n + * @see TebOptimalPlanner::AddEdgesViaPoints + * @remarks Do not forget to call setTebConfig() and setViaPoint() + */ +class EdgeViaPoint : public BaseTebUnaryEdge<1, const Eigen::Vector2d*, VertexPose> +{ +public: + + /** + * @brief Construct edge. + */ + EdgeViaPoint() + { + _measurement = NULL; + } + + /** + * @brief Actual cost function + */ + void computeError() + { + ROS_ASSERT_MSG(cfg_ && _measurement, "You must call setTebConfig(), setViaPoint() on EdgeViaPoint()"); + const VertexPose* bandpt = static_cast(_vertices[0]); + + _error[0] = (bandpt->position() - *_measurement).norm(); + + ROS_ASSERT_MSG(std::isfinite(_error[0]), "EdgeViaPoint::computeError() _error[0]=%f\n",_error[0]); + } + + /** + * @brief Set pointer to associated via point for the underlying cost function + * @param via_point 2D position vector containing the position of the via point + */ + void setViaPoint(const Eigen::Vector2d* via_point) + { + _measurement = via_point; + } + + /** + * @brief Set all parameters at once + * @param cfg TebConfig class + * @param via_point 2D position vector containing the position of the via point + */ + void setParameters(const TebConfig& cfg, const Eigen::Vector2d* via_point) + { + cfg_ = &cfg; + _measurement = via_point; + } + +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + +}; + + + +} // end namespace + +#endif diff --git a/navigations/teb_local_planner/include/teb_local_planner/g2o_types/penalties.h b/navigations/teb_local_planner/include/teb_local_planner/g2o_types/penalties.h new file mode 100755 index 0000000..6870558 --- /dev/null +++ b/navigations/teb_local_planner/include/teb_local_planner/g2o_types/penalties.h @@ -0,0 +1,193 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2016, + * TU Dortmund - Institute of Control Theory and Systems Engineering. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the institute nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: Christoph Rösmann + *********************************************************************/ + +#ifndef PENALTIES_H +#define PENALTIES_H + +#include +#include +#include + +namespace teb_local_planner +{ + +/** + * @brief Linear penalty function for bounding \c var to the interval \f$ -a < var < a \f$ + * @param var The scalar that should be bounded + * @param a lower and upper absolute bound + * @param epsilon safty margin (move bound to the interior of the interval) + * @see penaltyBoundToIntervalDerivative + * @return Penalty / cost value that is nonzero if the constraint is not satisfied + */ +inline double penaltyBoundToInterval(const double& var,const double& a,const double& epsilon) +{ + if (var < -a+epsilon) + { + return (-var - (a - epsilon)); + } + if (var <= a-epsilon) + { + return 0.; + } + else + { + return (var - (a - epsilon)); + } +} + +/** + * @brief Linear penalty function for bounding \c var to the interval \f$ a < var < b \f$ + * @param var The scalar that should be bounded + * @param a lower bound + * @param b upper bound + * @param epsilon safty margin (move bound to the interior of the interval) + * @see penaltyBoundToIntervalDerivative + * @return Penalty / cost value that is nonzero if the constraint is not satisfied + */ +inline double penaltyBoundToInterval(const double& var,const double& a, const double& b, const double& epsilon) +{ + if (var < a+epsilon) + { + return (-var + (a + epsilon)); + } + if (var <= b-epsilon) + { + return 0.; + } + else + { + return (var - (b - epsilon)); + } +} + + +/** + * @brief Linear penalty function for bounding \c var from below: \f$ a < var \f$ + * @param var The scalar that should be bounded + * @param a lower bound + * @param epsilon safty margin (move bound to the interior of the interval) + * @see penaltyBoundFromBelowDerivative + * @return Penalty / cost value that is nonzero if the constraint is not satisfied + */ +inline double penaltyBoundFromBelow(const double& var, const double& a,const double& epsilon) +{ + if (var >= a+epsilon) + { + return 0.; + } + else + { + return (-var + (a+epsilon)); + } +} + +/** + * @brief Derivative of the linear penalty function for bounding \c var to the interval \f$ -a < var < a \f$ + * @param var The scalar that should be bounded + * @param a lower and upper absolute bound + * @param epsilon safty margin (move bound to the interior of the interval) + * @see penaltyBoundToInterval + * @return Derivative of the penalty function w.r.t. \c var + */ +inline double penaltyBoundToIntervalDerivative(const double& var,const double& a, const double& epsilon) +{ + if (var < -a+epsilon) + { + return -1; + } + if (var <= a-epsilon) + { + return 0.; + } + else + { + return 1; + } +} + +/** + * @brief Derivative of the linear penalty function for bounding \c var to the interval \f$ a < var < b \f$ + * @param var The scalar that should be bounded + * @param a lower bound + * @param b upper bound + * @param epsilon safty margin (move bound to the interior of the interval) + * @see penaltyBoundToInterval + * @return Derivative of the penalty function w.r.t. \c var + */ +inline double penaltyBoundToIntervalDerivative(const double& var,const double& a, const double& b, const double& epsilon) +{ + if (var < a+epsilon) + { + return -1; + } + if (var <= b-epsilon) + { + return 0.; + } + else + { + return 1; + } +} + + +/** + * @brief Derivative of the linear penalty function for bounding \c var from below: \f$ a < var \f$ + * @param var The scalar that should be bounded + * @param a lower bound + * @param epsilon safty margin (move bound to the interior of the interval) + * @see penaltyBoundFromBelow + * @return Derivative of the penalty function w.r.t. \c var + */ +inline double penaltyBoundFromBelowDerivative(const double& var, const double& a,const double& epsilon) +{ + if (var >= a+epsilon) + { + return 0.; + } + else + { + return -1; + } +} + + +} // namespace teb_local_planner + + +#endif // PENALTIES_H diff --git a/navigations/teb_local_planner/include/teb_local_planner/g2o_types/vertex_pose.h b/navigations/teb_local_planner/include/teb_local_planner/g2o_types/vertex_pose.h new file mode 100755 index 0000000..eeab99a --- /dev/null +++ b/navigations/teb_local_planner/include/teb_local_planner/g2o_types/vertex_pose.h @@ -0,0 +1,229 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2016, + * TU Dortmund - Institute of Control Theory and Systems Engineering. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the institute nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Notes: + * The following class is derived from a class defined by the + * g2o-framework. g2o is licensed under the terms of the BSD License. + * Refer to the base class source for detailed licensing information. + * + * Author: Christoph Rösmann + *********************************************************************/ + +#ifndef VERTEX_POSE_H_ +#define VERTEX_POSE_H_ + +#include +#include +#include +#include + +#include + +namespace teb_local_planner +{ + +/** + * @class VertexPose + * @brief This class stores and wraps a SE2 pose (position and orientation) into a vertex that can be optimized via g2o + * @see PoseSE2 + * @see VertexTimeDiff + */ +class VertexPose : public g2o::BaseVertex<3, PoseSE2 > +{ +public: + + /** + * @brief Default constructor + * @param fixed if \c true, this vertex is considered fixed during optimization [default: \c false] + */ + VertexPose(bool fixed = false) + { + setToOriginImpl(); + setFixed(fixed); + } + + /** + * @brief Construct pose using a given PoseSE2 + * @param pose PoseSE2 defining the pose [x, y, angle_rad] + * @param fixed if \c true, this vertex is considered fixed during optimization [default: \c false] + */ + VertexPose(const PoseSE2& pose, bool fixed = false) + { + _estimate = pose; + setFixed(fixed); + } + + /** + * @brief Construct pose using a given 2D position vector and orientation + * @param position Eigen::Vector2d containing x and y coordinates + * @param theta yaw-angle + * @param fixed if \c true, this vertex is considered fixed during optimization [default: \c false] + */ + VertexPose(const Eigen::Ref& position, double theta, bool fixed = false) + { + _estimate.position() = position; + _estimate.theta() = theta; + setFixed(fixed); + } + + /** + * @brief Construct pose using single components x, y, and the yaw angle + * @param x x-coordinate + * @param y y-coordinate + * @param theta yaw angle in rad + * @param fixed if \c true, this vertex is considered fixed during optimization [default: \c false] + */ + VertexPose(double x, double y, double theta, bool fixed = false) + { + _estimate.x() = x; + _estimate.y() = y; + _estimate.theta() = theta; + setFixed(fixed); + } + + /** + * @brief Access the pose + * @see estimate + * @return reference to the PoseSE2 estimate + */ + inline PoseSE2& pose() {return _estimate;} + + /** + * @brief Access the pose (read-only) + * @see estimate + * @return const reference to the PoseSE2 estimate + */ + inline const PoseSE2& pose() const {return _estimate;} + + + /** + * @brief Access the 2D position part + * @see estimate + * @return reference to the 2D position part + */ + inline Eigen::Vector2d& position() {return _estimate.position();} + + /** + * @brief Access the 2D position part (read-only) + * @see estimate + * @return const reference to the 2D position part + */ + inline const Eigen::Vector2d& position() const {return _estimate.position();} + + /** + * @brief Access the x-coordinate the pose + * @return reference to the x-coordinate + */ + inline double& x() {return _estimate.x();} + + /** + * @brief Access the x-coordinate the pose (read-only) + * @return const reference to the x-coordinate + */ + inline const double& x() const {return _estimate.x();} + + /** + * @brief Access the y-coordinate the pose + * @return reference to the y-coordinate + */ + inline double& y() {return _estimate.y();} + + /** + * @brief Access the y-coordinate the pose (read-only) + * @return const reference to the y-coordinate + */ + inline const double& y() const {return _estimate.y();} + + /** + * @brief Access the orientation part (yaw angle) of the pose + * @return reference to the yaw angle + */ + inline double& theta() {return _estimate.theta();} + + /** + * @brief Access the orientation part (yaw angle) of the pose (read-only) + * @return const reference to the yaw angle + */ + inline const double& theta() const {return _estimate.theta();} + + /** + * @brief Set the underlying estimate (2D vector) to zero. + */ + virtual void setToOriginImpl() override + { + _estimate.setZero(); + } + + /** + * @brief Define the update increment \f$ \mathbf{x}_{k+1} = \mathbf{x}_k + \Delta \mathbf{x} \f$. + * A simple addition for the position. + * The angle is first added to the previous estimated angle and afterwards normalized to the interval \f$ [-\pi \pi] \f$ + * @param update increment that should be added to the previous esimate + */ + virtual void oplusImpl(const double* update) override + { + _estimate.plus(update); + } + + /** + * @brief Read an estimate from an input stream. + * First the x-coordinate followed by y and the yaw angle. + * @param is input stream + * @return always \c true + */ + virtual bool read(std::istream& is) override + { + is >> _estimate.x() >> _estimate.y() >> _estimate.theta(); + return true; + } + + /** + * @brief Write the estimate to an output stream + * First the x-coordinate followed by y and the yaw angle. + * @param os output stream + * @return \c true if the export was successful, otherwise \c false + */ + virtual bool write(std::ostream& os) const override + { + os << _estimate.x() << " " << _estimate.y() << " " << _estimate.theta(); + return os.good(); + } + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +}; + +} + +#endif // VERTEX_POSE_H_ diff --git a/navigations/teb_local_planner/include/teb_local_planner/g2o_types/vertex_timediff.h b/navigations/teb_local_planner/include/teb_local_planner/g2o_types/vertex_timediff.h new file mode 100755 index 0000000..4eead6c --- /dev/null +++ b/navigations/teb_local_planner/include/teb_local_planner/g2o_types/vertex_timediff.h @@ -0,0 +1,145 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2016, + * TU Dortmund - Institute of Control Theory and Systems Engineering. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the institute nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Notes: + * The following class is derived from a class defined by the + * g2o-framework. g2o is licensed under the terms of the BSD License. + * Refer to the base class source for detailed licensing information. + * + * Author: Christoph Rösmann + *********************************************************************/ + +#ifndef VERTEX_TIMEDIFF_H +#define VERTEX_TIMEDIFF_H + + +#include "g2o/config.h" +#include "g2o/core/base_vertex.h" +#include "g2o/core/hyper_graph_action.h" + +#include + +namespace teb_local_planner +{ + +/** + * @class VertexTimeDiff + * @brief This class stores and wraps a time difference \f$ \Delta T \f$ into a vertex that can be optimized via g2o + */ +class VertexTimeDiff : public g2o::BaseVertex<1, double> +{ +public: + + /** + * @brief Default constructor + * @param fixed if \c true, this vertex is considered fixed during optimization [default: \c false] + */ + VertexTimeDiff(bool fixed = false) + { + setToOriginImpl(); + setFixed(fixed); + } + + /** + * @brief Construct the TimeDiff vertex with a value + * @param dt time difference value of the vertex + * @param fixed if \c true, this vertex is considered fixed during optimization [default: \c false] + */ + VertexTimeDiff(double dt, bool fixed = false) + { + _estimate = dt; + setFixed(fixed); + } + + /** + * @brief Access the timediff value of the vertex + * @see estimate + * @return reference to dt + */ + inline double& dt() {return _estimate;} + + /** + * @brief Access the timediff value of the vertex (read-only) + * @see estimate + * @return const reference to dt + */ + inline const double& dt() const {return _estimate;} + + /** + * @brief Set the underlying TimeDiff estimate \f$ \Delta T \f$ to default. + */ + virtual void setToOriginImpl() override + { + _estimate = 0.1; + } + + /** + * @brief Define the update increment \f$ \Delta T_{k+1} = \Delta T_k + update \f$. + * A simple addition implements what we want. + * @param update increment that should be added to the previous esimate + */ + virtual void oplusImpl(const double* update) override + { + _estimate += *update; + } + + /** + * @brief Read an estimate of \f$ \Delta T \f$ from an input stream + * @param is input stream + * @return always \c true + */ + virtual bool read(std::istream& is) override + { + is >> _estimate; + return true; + } + + /** + * @brief Write the estimate \f$ \Delta T \f$ to an output stream + * @param os output stream + * @return \c true if the export was successful, otherwise \c false + */ + virtual bool write(std::ostream& os) const override + { + os << estimate(); + return os.good(); + } + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +}; + +} + +#endif diff --git a/navigations/teb_local_planner/include/teb_local_planner/graph_search.h b/navigations/teb_local_planner/include/teb_local_planner/graph_search.h new file mode 100755 index 0000000..b9dd4af --- /dev/null +++ b/navigations/teb_local_planner/include/teb_local_planner/graph_search.h @@ -0,0 +1,215 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, + * TU Dortmund - Institute of Control Theory and Systems Engineering. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the institute nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Authors: Christoph Rösmann, Franz Albers + *********************************************************************/ + +#ifndef GRAPH_SEARCH_INTERFACE_H +#define GRAPH_SEARCH_INTERFACE_H + +#ifdef BOOST_NO_CXX11_DEFAULTED_FUNCTIONS + #include +#else + // Workaround for a bug in boost graph library (concerning directed graphs), boost version 1.48: + // boost::add_vertex requires a move constructor/assignment operator in one of the underlying boost objects if C++11 is activated, + // but they are missing. The compiler fails due to an implicit deletion. We just deactivate C++11 default functions for now. + #define BOOST_NO_CXX11_DEFAULTED_FUNCTIONS + #include + #undef BOOST_NO_CXX11_DEFAULTED_FUNCTIONS +#endif + +#include +#include +#include +#include + +#include + +#include + +#include +#include +#include + +namespace teb_local_planner +{ + +class HomotopyClassPlanner; // Forward declaration + +//! Vertex in the graph that is used to find homotopy classes (only stores 2D positions) +struct HcGraphVertex +{ +public: + Eigen::Vector2d pos; // position of vertices in the map + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +}; + +//! Abbrev. for the homotopy class search-graph type @see HcGraphVertex +typedef boost::adjacency_list < boost::listS, boost::vecS, boost::directedS, HcGraphVertex, boost::no_property > HcGraph; +//! Abbrev. for vertex type descriptors in the homotopy class search-graph +typedef boost::graph_traits::vertex_descriptor HcGraphVertexType; +//! Abbrev. for edge type descriptors in the homotopy class search-graph +typedef boost::graph_traits::edge_descriptor HcGraphEdgeType; +//! Abbrev. for the vertices iterator of the homotopy class search-graph +typedef boost::graph_traits::vertex_iterator HcGraphVertexIterator; +//! Abbrev. for the edges iterator of the homotopy class search-graph +typedef boost::graph_traits::edge_iterator HcGraphEdgeIterator; +//! Abbrev. for the adjacency iterator that iterates vertices that are adjecent to the specified one +typedef boost::graph_traits::adjacency_iterator HcGraphAdjecencyIterator; + +//!< Inline function used for calculateHSignature() in combination with HCP graph vertex descriptors +inline std::complex getCplxFromHcGraph(HcGraphVertexType vert_descriptor, const HcGraph& graph) +{ + return std::complex(graph[vert_descriptor].pos.x(), graph[vert_descriptor].pos.y()); +} + +//!< Inline function used for initializing the TEB in combination with HCP graph vertex descriptors +inline const Eigen::Vector2d& getVector2dFromHcGraph(HcGraphVertexType vert_descriptor, const HcGraph& graph) +{ + return graph[vert_descriptor].pos; +} + +/** + * @brief Base class for graph based path planning / homotopy class sampling + */ +class GraphSearchInterface +{ +public: + + virtual void createGraph(const PoseSE2& start, const PoseSE2& goal, double dist_to_obst, double obstacle_heading_threshold, const geometry_msgs::Twist* start_velocity, bool free_goal_vel = false) = 0; + + /** + * @brief Clear any existing graph of the homotopy class search + */ + void clearGraph() {graph_.clear();} + + // HcGraph graph() const {return graph_;} + // Workaround. graph_ is public for now, beacuse otherwise the compilation fails with the same boost bug mentioned above. + HcGraph graph_; //!< Store the graph that is utilized to find alternative homotopy classes. + +protected: + /** + * @brief Protected constructor that should be called by subclasses + */ + GraphSearchInterface(const TebConfig& cfg, HomotopyClassPlanner* hcp) : cfg_(&cfg), hcp_(hcp){} + + /** + * @brief Depth First Search implementation to find all paths between the start and the specified goal vertex. + * + * Complete paths are stored to the internal path container. + * @sa http://www.technical-recipes.com/2011/a-recursive-algorithm-to-find-all-paths-between-two-given-nodes/ + * @param g Graph on which the depth first should be performed + * @param visited A container that stores visited vertices (pass an empty container, it will be filled inside during recursion). + * @param goal Desired goal vertex + * @param start_orientation Orientation of the first trajectory pose, required to initialize the trajectory/TEB + * @param goal_orientation Orientation of the goal trajectory pose, required to initialize the trajectory/TEB + * @param start_velocity start velocity (optional) + * @param free_goal_vel if \c true, a nonzero final velocity at the goal pose is allowed, otherwise the final velocity will be zero (default: false) + */ + void DepthFirst(HcGraph& g, std::vector& visited, const HcGraphVertexType& goal, double start_orientation, double goal_orientation, const geometry_msgs::Twist* start_velocity, bool free_goal_vel = false); + + +protected: + const TebConfig* cfg_; //!< Config class that stores and manages all related parameters + HomotopyClassPlanner* const hcp_; //!< Raw pointer to the HomotopyClassPlanner. The HomotopyClassPlanner itself is guaranteed to outlive the graph search class it is holding. + +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +}; + + + +class lrKeyPointGraph : public GraphSearchInterface +{ +public: + lrKeyPointGraph(const TebConfig& cfg, HomotopyClassPlanner* hcp) : GraphSearchInterface(cfg, hcp){} + + virtual ~lrKeyPointGraph(){} + + /** + * @brief Create a graph containing points in the global frame that can be used to explore new possible paths between start and goal. + * + * This version of the graph creation places a keypoint on the left and right side of each obstacle w.r.t to the goal heading. \n + * All feasible paths between start and goal point are extracted using a Depth First Search afterwards. \n + * This version works very well for small point obstacles. For more complex obstacles call the createProbRoadmapGraph() + * method that samples keypoints in a predefined area and hopefully finds all relevant alternative paths. + * + * @see createProbRoadmapGraph + * @param start Start pose from wich to start on (e.g. the current robot pose). + * @param goal Goal pose to find paths to (e.g. the robot's goal). + * @param dist_to_obst Allowed distance to obstacles: if not satisfying, the path will be rejected (note, this is not the distance used for optimization). + * @param obstacle_heading_threshold Value of the normalized scalar product between obstacle heading and goal heading in order to take them (obstacles) into account [0,1] + * @param start_velocity start velocity (optional) + * @param free_goal_vel if \c true, a nonzero final velocity at the goal pose is allowed, otherwise the final velocity will be zero (default: false) + */ + virtual void createGraph(const PoseSE2& start, const PoseSE2& goal, double dist_to_obst, double obstacle_heading_threshold, const geometry_msgs::Twist* start_velocity, bool free_goal_vel = false); +}; + + + + +class ProbRoadmapGraph : public GraphSearchInterface +{ +public: + ProbRoadmapGraph(const TebConfig& cfg, HomotopyClassPlanner* hcp) : GraphSearchInterface(cfg, hcp){} + + virtual ~ProbRoadmapGraph(){} + + + /** + * @brief Create a graph and sample points in the global frame that can be used to explore new possible paths between start and goal. + * + * This version of the graph samples keypoints in a predefined area (config) in the current frame between start and goal. \n + * Afterwards all feasible paths between start and goal point are extracted using a Depth First Search. \n + * Use the sampling method for complex, non-point or huge obstacles. \n + * You may call createGraph() instead. + * + * @see createGraph + * @param start Start pose from wich to start on (e.g. the current robot pose). + * @param goal Goal pose to find paths to (e.g. the robot's goal). + * @param dist_to_obst Allowed distance to obstacles: if not satisfying, the path will be rejected (note, this is not the distance used for optimization). + * @param no_samples number of random samples + * @param obstacle_heading_threshold Value of the normalized scalar product between obstacle heading and goal heading in order to take them (obstacles) into account [0,1] + * @param start_velocity start velocity (optional) + * @param free_goal_vel if \c true, a nonzero final velocity at the goal pose is allowed, otherwise the final velocity will be zero (default: false) + */ + virtual void createGraph(const PoseSE2& start, const PoseSE2& goal, double dist_to_obst, double obstacle_heading_threshold, const geometry_msgs::Twist* start_velocity, bool free_goal_vel = false); + +private: + boost::random::mt19937 rnd_generator_; //!< Random number generator used by createProbRoadmapGraph to sample graph keypoints. +}; +} // end namespace + +#endif // GRAPH_SEARCH_INTERFACE_H diff --git a/navigations/teb_local_planner/include/teb_local_planner/h_signature.h b/navigations/teb_local_planner/include/teb_local_planner/h_signature.h new file mode 100755 index 0000000..8837950 --- /dev/null +++ b/navigations/teb_local_planner/include/teb_local_planner/h_signature.h @@ -0,0 +1,428 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, + * TU Dortmund - Institute of Control Theory and Systems Engineering. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the institute nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Authors: Christoph Rösmann, Franz Albers + *********************************************************************/ + +#ifndef H_SIGNATURE_H_ +#define H_SIGNATURE_H_ + +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include + + +namespace teb_local_planner +{ + +/** + * @brief The H-signature defines an equivalence relation based on homology in terms of complex calculus. + * + * The H-Signature depends on the obstacle configuration and can be utilized + * to check whether two trajectores belong to the same homology class. + * Refer to: \n + * - S. Bhattacharya et al.: Search-based Path Planning with Homotopy Class Constraints, AAAI, 2010 + */ +class HSignature : public EquivalenceClass +{ + +public: + + /** + * @brief Constructor accepting a TebConfig + * @param cfg TebConfig storing some user configuration options + */ + HSignature(const TebConfig& cfg) : cfg_(&cfg) {} + + + /** + * @brief Calculate the H-Signature of a path + * + * The implemented function accepts generic path descriptions that are restricted to the following structure: \n + * The path is composed of points T and is represented by a std::vector< T > or similar type (std::list, std::deque, ...). \n + * Provide a unary function with the following signature std::complex< long double > (const T& point_type) + * that returns a complex value for the position (Re(*)=x, Im(*)=y). + * + * T could also be a pointer type, if the passed function also accepts a const T* point_Type. + * + * @param path_start Iterator to the first element in the path + * @param path_end Iterator to the last element in the path + * @param obstacles obstacle container + * @param fun_cplx_point function accepting the dereference iterator type and that returns the position as complex number. + * @tparam BidirIter Bidirectional iterator type + * @tparam Fun function of the form std::complex< long double > (const T& point_type) + */ + template + void calculateHSignature(BidirIter path_start, BidirIter path_end, Fun fun_cplx_point, const ObstContainer* obstacles) + { + if (obstacles->empty()) + { + hsignature_ = std::complex(0,0); + return; + } + + + ROS_ASSERT_MSG(cfg_->hcp.h_signature_prescaler>0.1 && cfg_->hcp.h_signature_prescaler<=1, "Only a prescaler on the interval (0.1,1] ist allowed."); + + // guess values for f0 + // paper proposes a+b=N-1 && |a-b|<=1, 1...N obstacles + int m = std::max( (int)obstacles->size()-1, 5 ); // for only a few obstacles we need a min threshold in order to get significantly high H-Signatures + + int a = (int) std::ceil(double(m)/2.0); + int b = m-a; + + std::advance(path_end, -1); // reduce path_end by 1 (since we check line segments between those path points + + typedef std::complex cplx; + // guess map size (only a really really coarse guess is required + // use distance from start to goal as distance to each direction + // TODO: one could move the map determination outside this function, since it remains constant for the whole planning interval + cplx start = fun_cplx_point(*path_start); + cplx end = fun_cplx_point(*path_end); // path_end points to the last point now after calling std::advance before + cplx delta = end-start; + cplx normal(-delta.imag(), delta.real()); + cplx map_bottom_left; + cplx map_top_right; + if (std::abs(delta) < 3.0) + { // set minimum bound on distance (we do not want to have numerical instabilities) and 3.0 performs fine... + map_bottom_left = start + cplx(0, -3); + map_top_right = start + cplx(3, 3); + } + else + { + map_bottom_left = start - normal; + map_top_right = start + delta + normal; + } + + hsignature_ = 0; // reset local signature + + std::vector imag_proposals(5); + + // iterate path + while(path_start != path_end) + { + cplx z1 = fun_cplx_point(*path_start); + cplx z2 = fun_cplx_point(*std::next(path_start)); + + for (std::size_t l=0; lsize(); ++l) // iterate all obstacles + { + cplx obst_l = obstacles->at(l)->getCentroidCplx(); + //cplx f0 = (long double) prescaler * std::pow(obst_l-map_bottom_left,a) * std::pow(obst_l-map_top_right,b); + cplx f0 = (long double) cfg_->hcp.h_signature_prescaler * (long double)a*(obst_l-map_bottom_left) * (long double)b*(obst_l-map_top_right); + + // denum contains product with all obstacles exepct j==l + cplx Al = f0; + for (std::size_t j=0; jsize(); ++j) + { + if (j==l) + continue; + cplx obst_j = obstacles->at(j)->getCentroidCplx(); + cplx diff = obst_l - obst_j; + //if (diff.real()!=0 || diff.imag()!=0) + if (std::abs(diff)<0.05) // skip really close obstacles + continue; + else + Al /= diff; + } + // compute log value + double diff2 = std::abs(z2-obst_l); + double diff1 = std::abs(z1-obst_l); + if (diff2 == 0 || diff1 == 0) + continue; + double log_real = std::log(diff2)-std::log(diff1); + // complex ln has more than one solution -> choose minimum abs angle -> paper + double arg_diff = std::arg(z2-obst_l)-std::arg(z1-obst_l); + imag_proposals.at(0) = arg_diff; + imag_proposals.at(1) = arg_diff+2*M_PI; + imag_proposals.at(2) = arg_diff-2*M_PI; + imag_proposals.at(3) = arg_diff+4*M_PI; + imag_proposals.at(4) = arg_diff-4*M_PI; + double log_imag = *std::min_element(imag_proposals.begin(),imag_proposals.end(),smaller_than_abs); + cplx log_value(log_real,log_imag); + //cplx log_value = std::log(z2-obst_l)-std::log(z1-obst_l); // the principal solution doesn't seem to work + hsignature_ += Al*log_value; + } + ++path_start; + } + } + + + /** + * @brief Check if two candidate classes are equivalent + * @param other The other equivalence class to test with + */ + virtual bool isEqual(const EquivalenceClass& other) const + { + const HSignature* hother = dynamic_cast(&other); // TODO: better architecture without dynamic_cast + if (hother) + { + double diff_real = std::abs(hother->hsignature_.real() - hsignature_.real()); + double diff_imag = std::abs(hother->hsignature_.imag() - hsignature_.imag()); + if (diff_real<=cfg_->hcp.h_signature_threshold && diff_imag<=cfg_->hcp.h_signature_threshold) + return true; // Found! Homotopy class already exists, therefore nothing added + } + else + ROS_ERROR("Cannot compare HSignature equivalence classes with types other than HSignature."); + + return false; + } + + /** + * @brief Check if the equivalence value is detected correctly + * @return Returns false, if the equivalence class detection failed, e.g. if nan- or inf values occur. + */ + virtual bool isValid() const + { + return std::isfinite(hsignature_.real()) && std::isfinite(hsignature_.imag()); + } + + /** + * @brief Check if the trajectory is non-looping around an obstacle. + * @return Returns always true, as this cannot be detected by this kind of H-Signature. + */ + virtual bool isReasonable() const + { + return true; + } + + /** + * @brief Get the current value of the h-signature (read-only) + * @return h-signature in complex-number format + */ + const std::complex& value() const {return hsignature_;} + + +private: + + const TebConfig* cfg_; + std::complex hsignature_; +}; + + + + + +/** + * @brief The H-signature in three dimensions (here: x-y-t) defines an equivalence relation based on homology using theorems from electro magnetism. + * + * The H-Signature depends on the obstacle configuration and can be utilized + * to check whether two trajectores belong to the same homology class. + * Refer to: \n + * - S. Bhattacharya et al.: Identification and Representation of Homotopy Classes of Trajectories for Search-based Path Planning in 3D, 2011 + */ +class HSignature3d : public EquivalenceClass +{ +public: + /** + * @brief Constructor accepting a TebConfig + * @param cfg TebConfig storing some user configuration options + */ + HSignature3d(const TebConfig& cfg) : cfg_(&cfg) {} + + + /** + * @brief Calculate the H-Signature of a path + * + * The implemented function accepts generic path descriptions that are restricted to the following structure: \n + * The path is composed of points T and is represented by a std::vector< T > or similar type (std::list, std::deque, ...). \n + * Provide a unary function with the following signature std::complex< long double > (const T& point_type) + * that returns a complex value for the position (Re(*)=x, Im(*)=y). + * + * T could also be a pointer type, if the passed function also accepts a const T* point_Type. + * + * @param path_start Iterator to the first element in the path + * @param path_end Iterator to the last element in the path + * @param obstacles obstacle container + * @param fun_cplx_point function accepting the dereference iterator type and that returns the position as complex number. + * @tparam BidirIter Bidirectional iterator type + * @tparam Fun function of the form std::complex< long double > (const T& point_type) + */ + template + void calculateHSignature(BidirIter path_start, BidirIter path_end, Fun fun_cplx_point, const ObstContainer* obstacles, + boost::optional timediff_start, boost::optional timediff_end) + { + hsignature3d_.resize(obstacles->size()); + + std::advance(path_end, -1); // reduce path_end by 1 (since we check line segments between those path points) + + constexpr int num_int_steps_per_segment = 10; + + for (std::size_t l = 0; l < obstacles->size(); ++l) // iterate all obstacles + { + double H = 0; + double transition_time = 0; + double next_transition_time = 0; + BidirIter path_iter; + TimeDiffSequence::iterator timediff_iter; + + Eigen::Vector3d s1 (obstacles->at(l)->getCentroid()(0), obstacles->at(l)->getCentroid()(1), 0); + double t = 120; // some large value for defining the end point of the obstacle/"conductor" model + Eigen::Vector3d s2; + obstacles->at(l)->predictCentroidConstantVelocity(t, s2.head(2)); + s2[2] = t; + Eigen::Vector3d ds = s2 - s1; + double ds_sq_norm = ds.squaredNorm(); // by definition not zero as t > 0 (3rd component) + + // iterate path + for (path_iter = path_start, timediff_iter = timediff_start.get(); path_iter != path_end; ++path_iter, ++timediff_iter) + { + std::complex z1 = fun_cplx_point(*path_iter); + std::complex z2 = fun_cplx_point(*std::next(path_iter)); + + transition_time = next_transition_time; + if (timediff_start == boost::none || timediff_end == boost::none) // if no time information is provided yet, approximate transition time + next_transition_time += std::abs(z2 - z1) / cfg_->robot.max_vel_x; // Approximate the time, if no time is known + else // otherwise use the time information from the teb trajectory + { + if (std::distance(path_iter, path_end) != std::distance(timediff_iter, timediff_end.get())) + ROS_ERROR("Size of poses and timediff vectors does not match. This is a bug."); + next_transition_time += (*timediff_iter)->dt(); + } + + Eigen::Vector3d direction_vec; + direction_vec[0] = z2.real() - z1.real(); + direction_vec[1] = z2.imag() - z1.imag(); + direction_vec[2] = next_transition_time - transition_time; + + if(direction_vec.norm() < 1e-15) // Coincident poses + continue; + + Eigen::Vector3d r(z1.real(), z1.imag(), transition_time); + Eigen::Vector3d dl = 1.0/static_cast(num_int_steps_per_segment) * direction_vec; // Integrate with multiple steps between each pose + Eigen::Vector3d p1, p2, d, phi; + for (int i = 0; i < num_int_steps_per_segment; ++i, r += dl) + { + p1 = s1 - r; + p2 = s2 - r; + d = (ds.cross(p1.cross(p2))) / ds_sq_norm; + phi = 1.0 / d.squaredNorm() * ((d.cross(p2) / p2.norm()) - (d.cross(p1) / p1.norm())); + H += phi.dot(dl); + } + } + + // normalize to 1 + hsignature3d_.at(l) = H/(4.0*M_PI); + } + } + + /** + * @brief Check if two candidate classes are equivalent + * + * If the absolute value of the H-Signature is equal or greater than 1, a loop (in x-y) around the obstacle is indicated. + * Positive H-Signature: Obstacle lies on the left hand side of the planned trajectory + * Negative H-Signature: Obstacle lies on the right hand side of the planned trajectory + * H-Signature equals zero: Obstacle lies in infinity, has no influence on trajectory + * + * @param other The other equivalence class to test with + */ + virtual bool isEqual(const EquivalenceClass& other) const + { + const HSignature3d* hother = dynamic_cast(&other); // TODO: better architecture without dynamic_cast + if (hother) + { + if (hsignature3d_.size() == hother->hsignature3d_.size()) + { + for(size_t i = 0; i < hsignature3d_.size(); ++i) + { + // If the H-Signature for one obstacle is below this threshold, that obstacle is far away from the planned trajectory, + // and therefore ignored in the homotopy class planning + if (std::abs(hother->hsignature3d_.at(i)) < cfg_->hcp.h_signature_threshold || std::abs(hsignature3d_.at(i)) < cfg_->hcp.h_signature_threshold) + continue; + + if (boost::math::sign(hother->hsignature3d_.at(i)) != boost::math::sign(hsignature3d_.at(i))) + return false; // Signatures are not equal, new homotopy class + } + return true; // Found! Homotopy class already exists, therefore nothing added + } + } + else + ROS_ERROR("Cannot compare HSignature3d equivalence classes with types other than HSignature3d."); + + return false; + } + + /** + * @brief Check if the equivalence value is detected correctly + * @return Returns false, if the equivalence class detection failed, e.g. if nan- or inf values occur. + */ + virtual bool isValid() const + { + for(const double& value : hsignature3d_) + { + if (!std::isfinite(value)) + return false; + } + return true; + } + + /** + * @brief Check if the trajectory is non-looping around any obstacle. Values greater than 1 indicate a looping trajectory. + * @return Returns false, if the trajectory loops around an obstacle + */ + virtual bool isReasonable() const + { + for(const double& value : hsignature3d_) + { + if (value > 1.0) + return false; + } + return true; + } + + /** + * @brief Get the current h-signature (read-only) + * @return h-signature in complex-number format + */ + const std::vector& values() const {return hsignature3d_;} + +private: + const TebConfig* cfg_; + std::vector hsignature3d_; +}; + + +} // namespace teb_local_planner + + +#endif /* H_SIGNATURE_H_ */ diff --git a/navigations/teb_local_planner/include/teb_local_planner/homotopy_class_planner.h b/navigations/teb_local_planner/include/teb_local_planner/homotopy_class_planner.h new file mode 100755 index 0000000..7b3a3bd --- /dev/null +++ b/navigations/teb_local_planner/include/teb_local_planner/homotopy_class_planner.h @@ -0,0 +1,593 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2016, + * TU Dortmund - Institute of Control Theory and Systems Engineering. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the institute nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: Christoph Rösmann + *********************************************************************/ + +#ifndef HOMOTOPY_CLASS_PLANNER_H_ +#define HOMOTOPY_CLASS_PLANNER_H_ + +#include +#include +#include +#include +#include +#include + +#include + +#include +#include +#include + +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include + + +namespace teb_local_planner +{ + +//!< Inline function used for calculateHSignature() in combination with VertexPose pointers +inline std::complex getCplxFromVertexPosePtr(const VertexPose* pose) +{ + return std::complex(pose->x(), pose->y()); +}; + + +//!< Inline function used for calculateHSignature() in combination with geometry_msgs::PoseStamped +inline std::complex getCplxFromMsgPoseStamped(const geometry_msgs::PoseStamped& pose) +{ + return std::complex(pose.pose.position.x, pose.pose.position.y); +}; + +/** + * @class HomotopyClassPlanner + * @brief Local planner that explores alternative homotopy classes, create a plan for each alternative + * and finally return the robot controls for the current best path (repeated in each sampling interval) + * + * Equivalence classes (e.g. homotopy) are explored using the help of a search-graph. \n + * A couple of possible candidates are sampled / generated and filtered afterwards such that only a single candidate + * per homotopy class remain. Filtering is applied using the H-Signature, a homotopy (resp. homology) invariant: \n + * - S. Bhattacharya et al.: Search-based Path Planning with Homotopy Class Constraints, AAAI, 2010 + * - C. Rösmann et al.: Planning of Multiple Robot Trajectories in Distinctive Topologies, ECMR, 2015. + * + * Followed by the homotopy class search, each candidate is used as an initialization for the underlying trajectory + * optimization (in this case utilizing the TebOptimalPlanner class with the TimedElasticBand). \n + * Depending on the config parameters, the optimization is performed in parallel. \n + * After the optimization is completed, the best optimized candidate is selected w.r.t. to trajectory cost, since the + * cost already contains important features like clearance from obstacles and transition time. \n + * + * Everyhting is performed by calling one of the overloaded plan() methods. \n + * Afterwards the velocity command to control the robot is obtained from the "best" candidate + * via getVelocityCommand(). \n + * + * All steps are repeated in the subsequent sampling interval with the exception, that already planned (optimized) trajectories + * are preferred against new path initilizations in order to improve the hot-starting capability. + */ +class HomotopyClassPlanner : public PlannerInterface +{ +public: + + using EquivalenceClassContainer = std::vector< std::pair >; + + /** + * @brief Default constructor + */ + HomotopyClassPlanner(); + + /** + * @brief Construct and initialize the HomotopyClassPlanner + * @param cfg Const reference to the TebConfig class for internal parameters + * @param obstacles Container storing all relevant obstacles (see Obstacle) + * @param robot_model Shared pointer to the robot shape model used for optimization (optional) + * @param visualization Shared pointer to the TebVisualization class (optional) + * @param via_points Container storing via-points (optional) + */ + HomotopyClassPlanner(const TebConfig& cfg, ObstContainer* obstacles = NULL, RobotFootprintModelPtr robot_model = boost::make_shared(), + TebVisualizationPtr visualization = TebVisualizationPtr(), const ViaPointContainer* via_points = NULL); + + /** + * @brief Destruct the HomotopyClassPlanner. + */ + virtual ~HomotopyClassPlanner(); + + /** + * @brief Initialize the HomotopyClassPlanner + * @param cfg Const reference to the TebConfig class for internal parameters + * @param obstacles Container storing all relevant obstacles (see Obstacle) + * @param robot_model Shared pointer to the robot shape model used for optimization (optional) + * @param visualization Shared pointer to the TebVisualization class (optional) + * @param via_points Container storing via-points (optional) + */ + void initialize(const TebConfig& cfg, ObstContainer* obstacles = NULL, RobotFootprintModelPtr robot_model = boost::make_shared(), + TebVisualizationPtr visualization = TebVisualizationPtr(), const ViaPointContainer* via_points = NULL); + + + void updateRobotModel(RobotFootprintModelPtr robot_model ); + + /** @name Plan a trajectory */ + //@{ + + /** + * @brief Plan a trajectory based on an initial reference plan. + * + * Provide this method to create and optimize a trajectory that is initialized + * according to an initial reference plan (given as a container of poses). + * @warning The current implementation extracts only the start and goal pose and calls the overloaded plan() + * @param initial_plan vector of geometry_msgs::PoseStamped (must be valid until clearPlanner() is called!) + * @param start_vel Current start velocity (e.g. the velocity of the robot, only linear.x, linear.y (holonomic) and angular.z are used) + * @param free_goal_vel if \c true, a nonzero final velocity at the goal pose is allowed, + * otherwise the final velocity will be zero (default: false) + * @return \c true if planning was successful, \c false otherwise + */ + virtual bool plan(const std::vector& initial_plan, const geometry_msgs::Twist* start_vel = NULL, bool free_goal_vel=false); + + /** + * @brief Plan a trajectory between a given start and goal pose (tf::Pose version). + * + * Provide this method to create and optimize a trajectory that is initialized between a given start and goal pose. + * @param start tf::Pose containing the start pose of the trajectory + * @param goal tf::Pose containing the goal pose of the trajectory + * @param start_vel Current start velocity (e.g. the velocity of the robot, only linear.x, linear.y (holonomic) and angular.z are used) + * @param free_goal_vel if \c true, a nonzero final velocity at the goal pose is allowed, + * otherwise the final velocity will be zero (default: false) + * @return \c true if planning was successful, \c false otherwise + */ + virtual bool plan(const tf::Pose& start, const tf::Pose& goal, const geometry_msgs::Twist* start_vel = NULL, bool free_goal_vel=false); + + /** + * @brief Plan a trajectory between a given start and goal pose. + * + * Provide this method to create and optimize a trajectory that is initialized between a given start and goal pose. + * @param start PoseSE2 containing the start pose of the trajectory + * @param goal PoseSE2 containing the goal pose of the trajectory + * @param start_vel Initial velocity at the start pose (twist message containing the translational and angular velocity). + * @param free_goal_vel if \c true, a nonzero final velocity at the goal pose is allowed, + * otherwise the final velocity will be zero (default: false) + * @return \c true if planning was successful, \c false otherwise + */ + virtual bool plan(const PoseSE2& start, const PoseSE2& goal, const geometry_msgs::Twist* start_vel = NULL, bool free_goal_vel=false); + + /** + * @brief Get the velocity command from a previously optimized plan to control the robot at the current sampling interval. + * @warning Call plan() first and check if the generated plan is feasible. + * @param[out] vx translational velocity [m/s] + * @param[out] vy strafing velocity which can be nonzero for holonomic robots [m/s] + * @param[out] omega rotational velocity [rad/s] + * @param[in] look_ahead_poses index of the final pose used to compute the velocity command. + * @return \c true if command is valid, \c false otherwise + */ + virtual bool getVelocityCommand(double& vx, double& vy, double& omega, int look_ahead_poses) const; + + /** + * @brief Access current best trajectory candidate (that relates to the "best" homotopy class). + * + * If no trajectory is available, the pointer will be empty. + * If only a single trajectory is available, return it. + * Otherwise return the best one, but call selectBestTeb() before to perform the actual selection (part of the plan() methods). + * @return Shared pointer to the best TebOptimalPlanner that contains the selected trajectory (TimedElasticBand). + */ + TebOptimalPlannerPtr bestTeb() const {return tebs_.empty() ? TebOptimalPlannerPtr() : tebs_.size()==1 ? tebs_.front() : best_teb_;} + + /** + * @brief Check whether the planned trajectory is feasible or not. + * + * This method currently checks only that the trajectory, or a part of the trajectory is collision free. + * Obstacles are here represented as costmap instead of the internal ObstacleContainer. + * @param costmap_model Pointer to the costmap model + * @param footprint_spec The specification of the footprint of the robot in world coordinates + * @param inscribed_radius The radius of the inscribed circle of the robot + * @param circumscribed_radius The radius of the circumscribed circle of the robot + * @param look_ahead_idx Number of poses along the trajectory that should be verified, if -1, the complete trajectory will be checked. + * @return \c true, if the robot footprint along the first part of the trajectory intersects with + * any obstacle in the costmap, \c false otherwise. + */ + virtual bool isTrajectoryFeasible(base_local_planner::CostmapModel* costmap_model, const std::vector& footprint_spec, + double inscribed_radius = 0.0, double circumscribed_radius=0.0, int look_ahead_idx=-1, double feasibility_check_lookahead_distance=-1.0); + + /** + * @brief In case of empty best teb, scores again the available plans to find the best one. + * The best_teb_ variable is updated consequently. + * @return Shared pointer to the best TebOptimalPlanner that contains the selected trajectory (TimedElasticBand). + * An empty pointer is returned if no plan is available. + */ + TebOptimalPlannerPtr findBestTeb(); + + /** + * @brief Removes the specified teb and the corresponding homotopy class from the list of available ones. + * @param pointer to the teb Band to be removed + * @return Iterator to the next valid teb if available, else to the end of the tebs container. + */ + TebOptPlannerContainer::iterator removeTeb(TebOptimalPlannerPtr& teb); + + //@} + + /** @name Visualization */ + //@{ + + /** + * @brief Register a TebVisualization class to enable visiualization routines (e.g. publish the local plan and pose sequence) + * @param visualization shared pointer to a TebVisualization instance + * @see visualizeTeb + */ + void setVisualization(TebVisualizationPtr visualization); + + /** + * @brief Publish the local plan, pose sequence and additional information via ros topics (e.g. subscribe with rviz). + * + * Make sure to register a TebVisualization instance before using setVisualization() or an overlaoded constructor. + * @see setVisualization + */ + virtual void visualize(); + + //@} + + /** @name Important steps that are called during planning */ + //@{ + + + /** + * @brief Explore paths in new equivalence classes (e.g. homotopy classes) and initialize TEBs from them. + * + * This "all-in-one" method creates a graph with position keypoints from which + * feasible paths (with clearance from obstacles) are extracted. \n + * All obtained paths are filted to only keep a single path for each equivalence class. \n + * Each time a new equivalence class is explored (by means of \b no previous trajectory/TEB remain in that equivalence class), + * a new trajectory/TEB will be initialized. \n + * + * Everything is prepared now for the optimization step: see optimizeAllTEBs(). + * @param start Current start pose (e.g. pose of the robot) + * @param goal Goal pose (e.g. robot's goal) + * @param dist_to_obst Allowed distance to obstacles: if not satisfying, the path will be rejected (note, this is not the distance used for optimization). + * @param @param start_velocity start velocity (optional) + * @param free_goal_vel if \c true, a nonzero final velocity at the goal pose is allowed, otherwise the final velocity will be zero (default: false) + */ + void exploreEquivalenceClassesAndInitTebs(const PoseSE2& start, const PoseSE2& goal, double dist_to_obst, const geometry_msgs::Twist* start_vel, bool free_goal_vel = false); + + /** + * @brief Add a new Teb to the internal trajectory container, if this teb constitutes a new equivalence class. Initialize it using a generic 2D reference path + * + * Refer to TimedElasticBand::initTEBtoGoal() for more details about the template parameters. + * @param path_start start iterator of a generic 2d path + * @param path_end end iterator of a generic 2d path + * @param fun_position unary function that returns the Eigen::Vector2d object + * @param start_orientation Orientation of the first pose of the trajectory (optional, otherwise use goal heading) + * @param goal_orientation Orientation of the last pose of the trajectory (optional, otherwise use goal heading) + * @param start_velocity start velocity (optional) + * @param free_goal_vel if \c true, a nonzero final velocity at the goal pose is allowed, otherwise the final velocity will be zero (default: false) + * @tparam BidirIter Bidirectional iterator type + * @tparam Fun unyary function that transforms the dereferenced iterator into an Eigen::Vector2d + * @return Shared pointer to the newly created teb optimal planner + */ + template + TebOptimalPlannerPtr addAndInitNewTeb(BidirIter path_start, BidirIter path_end, Fun fun_position, double start_orientation, double goal_orientation, const geometry_msgs::Twist* start_velocity, bool free_goal_vel = false); + + /** + * @brief Add a new Teb to the internal trajectory container, if this teb constitutes a new equivalence class. Initialize it with a simple straight line between a given start and goal + * @param start start pose + * @param goal goal pose + * @param start_velocity start velocity (optional) + * @param free_goal_vel if \c true, a nonzero final velocity at the goal pose is allowed, otherwise the final velocity will be zero (default: false) + * @return Shared pointer to the newly created teb optimal planner + */ + TebOptimalPlannerPtr addAndInitNewTeb(const PoseSE2& start, const PoseSE2& goal, const geometry_msgs::Twist* start_velocity, bool free_goal_vel = false); + + /** + * @brief Add a new Teb to the internal trajectory container , if this teb constitutes a new equivalence class. Initialize it using a PoseStamped container + * @param initial_plan container of poses (start and goal orientation should be valid!) + * @param start_velocity start velocity (optional) + * @param free_goal_vel if \c true, a nonzero final velocity at the goal pose is allowed, otherwise the final velocity will be zero (default: false) + * @return Shared pointer to the newly created teb optimal planner + */ + TebOptimalPlannerPtr addAndInitNewTeb(const std::vector& initial_plan, const geometry_msgs::Twist* start_velocity, bool free_goal_vel = false); + + /** + * @brief Update TEBs with new pose, goal and current velocity. + * @param start New start pose (optional) + * @param goal New goal pose (optional) + * @param start_velocity start velocity (optional) + */ + void updateAllTEBs(const PoseSE2* start, const PoseSE2* goal, const geometry_msgs::Twist* start_velocity); + + + /** + * @brief Optimize all available trajectories by invoking the optimizer on each one. + * + * Depending on the configuration parameters, the optimization is performed either single or multi threaded. + * @param iter_innerloop Number of inner iterations (see TebOptimalPlanner::optimizeTEB()) + * @param iter_outerloop Number of outer iterations (see TebOptimalPlanner::optimizeTEB()) + */ + void optimizeAllTEBs(int iter_innerloop, int iter_outerloop); + + /** + * @brief Returns a shared pointer to the TEB related to the initial plan + * @return A non-empty shared ptr is returned if a match was found; Otherwise the shared ptr is empty. + */ + TebOptimalPlannerPtr getInitialPlanTEB(); + + /** + * @brief In case of multiple, internally stored, alternative trajectories, select the best one according to their cost values. + * + * The trajectory cost includes features such as transition time and clearance from obstacles. \n + * The best trajectory can be accessed later by bestTeb() within the current sampling interval in order to avoid unessary recalculations. + * @return Shared pointer to the best TebOptimalPlanner that contains the selected trajectory (TimedElasticBand). + */ + TebOptimalPlannerPtr selectBestTeb(); + + //@} + + /** + * @brief Reset the planner. + * + * Clear all previously found H-signatures, paths, tebs and the hcgraph. + */ + virtual void clearPlanner() {clearGraph(); equivalence_classes_.clear(); tebs_.clear(); initial_plan_ = NULL;} + + + /** + * @brief Prefer a desired initial turning direction (by penalizing the opposing one) + * + * A desired (initial) turning direction might be specified in case the planned trajectory oscillates between two + * solutions (in the same equivalence class!) with similar cost. Check the parameters in order to adjust the weight of the penalty. + * Initial means that the penalty is applied only to the first few poses of the trajectory. + * @param dir This parameter might be RotType::left (prefer left), RotType::right (prefer right) or RotType::none (prefer none) + */ + virtual void setPreferredTurningDir(RotType dir); + + /** + * @brief Calculate the equivalence class of a path + * + * Currently, only the H-signature (refer to HSignature) is implemented. + * + * @param path_start Iterator to the first element in the path + * @param path_end Iterator to the last element in the path + * @param obstacles obstacle container + * @param fun_cplx_point function accepting the dereference iterator type and that returns the position as complex number. + * @tparam BidirIter Bidirectional iterator type + * @tparam Fun function of the form std::complex< long double > (const T& point_type) + * @return pointer to the equivalence class base type + */ + template + EquivalenceClassPtr calculateEquivalenceClass(BidirIter path_start, BidirIter path_end, Fun fun_cplx_point, const ObstContainer* obstacles = NULL, + boost::optional timediff_start = boost::none, boost::optional timediff_end = boost::none); + + /** + * @brief Read-only access to the internal trajectory container. + * @return read-only reference to the teb container. + */ + const TebOptPlannerContainer& getTrajectoryContainer() const {return tebs_;} + + bool hasDiverged() const override; + + /** + * Compute and return the cost of the current optimization graph (supports multiple trajectories) + * @param[out] cost current cost value for each trajectory + * [for a planner with just a single trajectory: size=1, vector will not be cleared] + * @param obst_cost_scale Specify extra scaling for obstacle costs + * @param viapoint_cost_scale Specify extra scaling for via points. + * @param alternative_time_cost Replace the cost for the time optimal objective by the actual (weighted) transition time + */ + virtual void computeCurrentCost(std::vector& cost, double obst_cost_scale=1.0, double viapoint_cost_scale=1.0, bool alternative_time_cost=false); + + /** + * @brief Check if two h-signatures are similar (w.r.t. a certain threshold) + * @param h1 first h-signature + * @param h2 second h-signature + * @return \c true if both h-signatures are similar, false otherwise. + */ + inline static bool isHSignatureSimilar(const std::complex& h1, const std::complex& h2, double threshold) + { + double diff_real = std::abs(h2.real() - h1.real()); + double diff_imag = std::abs(h2.imag() - h1.imag()); + if (diff_real<=threshold && diff_imag<=threshold) + return true; // Found! Homotopy class already exists, therefore nothing added + return false; + } + /** + * @brief Checks if the orientation of the computed trajectories differs from that of the best plan of more than the + * specified threshold and eventually deletes them. + * Also deletes detours with a duration much bigger than the duration of the best_teb (duration / best duration > max_ratio_detours_duration_best_duration). + * @param orient_threshold: Threshold paramter for allowed orientation changes in radians + * @param len_orientation_vector: length of the vector used to compute the start orientation + */ + void deletePlansDetouringBackwards(const double orient_threshold, const double len_orientation_vector); + /** + * @brief Given a plan, computes its start orientation using a vector of length >= len_orientation_vector + * starting from the initial pose. + * @param plan: Teb to be analyzed + * @param len_orientation_vector: min length of the vector used to compute the start orientation + * @param orientation: computed start orientation + * @return: Could the vector for the orientation check be computed? (False if the plan has no pose with a distance + * > len_orientation_vector from the start poseq) + */ + bool computeStartOrientation(const TebOptimalPlannerPtr plan, const double len_orientation_vector, double& orientation); + + + /** + * @brief Access config (read-only) + * @return const pointer to the config instance + */ + const TebConfig* config() const {return cfg_;} + + /** + * @brief Access current obstacle container (read-only) + * @return const pointer to the obstacle container instance + */ + const ObstContainer* obstacles() const {return obstacles_;} + + /** + * @brief Returns true if the planner is initialized + */ + bool isInitialized() const {return initialized_;} + + /** + * @brief Clear any existing graph of the homotopy class search + */ + void clearGraph() {if(graph_search_) graph_search_->clearGraph();} + + /** + * @brief find the index of the currently best TEB in the container + * @remarks bestTeb() should be preferred whenever possible + * @return index of the best TEB obtained with bestTEB(), if no TEB is avaiable, it returns -1. + */ + int bestTebIdx() const; + + + /** + * @brief Internal helper function that adds a new equivalence class to the list of known classes only if it is unique. + * @param eq_class equivalence class that should be tested + * @param lock if \c true, exclude the H-signature from deletion. + * @return \c true if the h-signature was added and no duplicate was found, \c false otherwise + */ + bool addEquivalenceClassIfNew(const EquivalenceClassPtr& eq_class, bool lock=false); + + /** + * @brief Return the current set of equivalence erelations (read-only) + * @return reference to the internal set of currently tracked equivalence relations + */ + const EquivalenceClassContainer& getEquivalenceClassRef() const {return equivalence_classes_;} + + bool isInBestTebClass(const EquivalenceClassPtr& eq_class) const; + + int numTebsInClass(const EquivalenceClassPtr& eq_class) const; + + int numTebsInBestTebClass() const; + + /** + * @brief Randomly drop non-optimal TEBs to so we can explore other alternatives + * + * The HCP has a tendency to become "fixated" once its tebs_ list becomes + * fully populated, repeatedly refining and evaluating paths from the same + * few homotopy classes until the robot moves far enough for a teb to become + * invalid. As a result, it can fail to discover a more optimal path. This + * function alleviates this problem by randomly dropping TEBs other than the + * current "best" one with a probability controlled by + * selection_dropping_probability parameter. + */ + void randomlyDropTebs(); + +protected: + + /** @name Explore new paths and keep only a single one for each homotopy class */ + //@{ + + /** + * @brief Check if a h-signature exists already. + * @param eq_class equivalence class that should be tested + * @return \c true if the h-signature is found, \c false otherwise + */ + bool hasEquivalenceClass(const EquivalenceClassPtr& eq_class) const; + + + /** + * @brief Renew all found h-signatures for the new planning step based on existing TEBs. Optionally detours can be discarded. + * + * Calling this method in each new planning interval is really important. + * First all old h-signatures are deleted, since they could be invalid for this planning step (obstacle position may changed). + * Afterwards the h-signatures are calculated for each existing TEB/trajectory and is inserted to the list of known h-signatures. + * Doing this is important to prefer already optimized trajectories in contrast to initialize newly explored coarse paths. + * @param delete_detours if this param is \c true, all existing TEBs are cleared from detour-candidates calling deletePlansGoingBackwards(). + */ + void renewAndAnalyzeOldTebs(bool delete_detours); + + /** + * @brief Associate trajectories with via-points + * + * If \c all_trajectories is true, all trajectory candidates are connected with the set of via_points, + * otherwise only the trajectory sharing the homotopy class of the initial/global plan (and all via-points from alternative trajectories are removed) + * @remarks Requires that the plan method is called with an initial plan provided and that via-points are enabled (config) + * @param all_trajectories see method description + */ + void updateReferenceTrajectoryViaPoints(bool all_trajectories); + + //@} + + + // external objects (store weak pointers) + const TebConfig* cfg_; //!< Config class that stores and manages all related parameters + ObstContainer* obstacles_; //!< Store obstacles that are relevant for planning + const ViaPointContainer* via_points_; //!< Store the current list of via-points + + // internal objects (memory management owned) + TebVisualizationPtr visualization_; //!< Instance of the visualization class (local/global plan, obstacles, ...) + TebOptimalPlannerPtr best_teb_; //!< Store the current best teb. + EquivalenceClassPtr best_teb_eq_class_; //!< Store the equivalence class of the current best teb + RobotFootprintModelPtr robot_model_; //!< Robot model shared instance + + const std::vector* initial_plan_; //!< Store the initial plan if available for a better trajectory initialization + EquivalenceClassPtr initial_plan_eq_class_; //!< Store the equivalence class of the initial plan + TebOptimalPlannerPtr initial_plan_teb_; //!< Store pointer to the TEB related to the initial plan (use method getInitialPlanTEB() since it checks if initial_plan_teb_ is still included in tebs_.) + + TebOptPlannerContainer tebs_; //!< Container that stores multiple local teb planners (for alternative equivalence classes) and their corresponding costs + + EquivalenceClassContainer equivalence_classes_; //!< Store all known quivalence classes (e.g. h-signatures) to allow checking for duplicates after finding and adding new ones. + // The second parameter denotes whether to exclude the class from detour deletion or not (true: force keeping). + + boost::shared_ptr graph_search_; + + ros::Time last_eq_class_switching_time_; //!< Store the time at which the equivalence class changed recently + + std::default_random_engine random_; + bool initialized_; //!< Keeps track about the correct initialization of this class + + TebOptimalPlannerPtr last_best_teb_; //!< Points to the plan used in the previous control cycle + + + +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + +}; + +//! Abbrev. for a shared pointer of a HomotopyClassPlanner instance. +typedef boost::shared_ptr HomotopyClassPlannerPtr; + + +} // namespace teb_local_planner + +// include template implementations / definitions +#include + +#endif /* HOMOTOPY_CLASS_PLANNER_H_ */ diff --git a/navigations/teb_local_planner/include/teb_local_planner/homotopy_class_planner.hpp b/navigations/teb_local_planner/include/teb_local_planner/homotopy_class_planner.hpp new file mode 100755 index 0000000..446dbc1 --- /dev/null +++ b/navigations/teb_local_planner/include/teb_local_planner/homotopy_class_planner.hpp @@ -0,0 +1,95 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, + * TU Dortmund - Institute of Control Theory and Systems Engineering. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the institute nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: Christoph Rösmann + *********************************************************************/ + +#include +#include + +namespace teb_local_planner +{ + + +template +EquivalenceClassPtr HomotopyClassPlanner::calculateEquivalenceClass(BidirIter path_start, BidirIter path_end, Fun fun_cplx_point, const ObstContainer* obstacles, + boost::optional timediff_start, boost::optional timediff_end) +{ + if(cfg_->obstacles.include_dynamic_obstacles) + { + HSignature3d* H = new HSignature3d(*cfg_); + H->calculateHSignature(path_start, path_end, fun_cplx_point, obstacles, timediff_start, timediff_end); + return EquivalenceClassPtr(H); + } + else + { + HSignature* H = new HSignature(*cfg_); + H->calculateHSignature(path_start, path_end, fun_cplx_point, obstacles); + return EquivalenceClassPtr(H); + } +} + + +template +TebOptimalPlannerPtr HomotopyClassPlanner::addAndInitNewTeb(BidirIter path_start, BidirIter path_end, Fun fun_position, double start_orientation, double goal_orientation, const geometry_msgs::Twist* start_velocity, bool free_goal_vel) +{ + TebOptimalPlannerPtr candidate = TebOptimalPlannerPtr( new TebOptimalPlanner(*cfg_, obstacles_, robot_model_)); + + candidate->teb().initTrajectoryToGoal(path_start, path_end, fun_position, cfg_->robot.max_vel_x, cfg_->robot.max_vel_theta, + cfg_->robot.acc_lim_x, cfg_->robot.acc_lim_theta, start_orientation, goal_orientation, cfg_->trajectory.min_samples, + cfg_->trajectory.allow_init_with_backwards_motion); + + if (start_velocity) + candidate->setVelocityStart(*start_velocity); + + EquivalenceClassPtr H = calculateEquivalenceClass(candidate->teb().poses().begin(), candidate->teb().poses().end(), getCplxFromVertexPosePtr, obstacles_, + candidate->teb().timediffs().begin(), candidate->teb().timediffs().end()); + + + if (free_goal_vel) + candidate->setVelocityGoalFree(); + + if(addEquivalenceClassIfNew(H)) + { + tebs_.push_back(candidate); + return tebs_.back(); + } + + // If the candidate constitutes no new equivalence class, return a null pointer + return TebOptimalPlannerPtr(); +} + +} // namespace teb_local_planner + diff --git a/navigations/teb_local_planner/include/teb_local_planner/misc.h b/navigations/teb_local_planner/include/teb_local_planner/misc.h new file mode 100755 index 0000000..09f055a --- /dev/null +++ b/navigations/teb_local_planner/include/teb_local_planner/misc.h @@ -0,0 +1,152 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2016, + * TU Dortmund - Institute of Control Theory and Systems Engineering. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the institute nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: Christoph Rösmann + *********************************************************************/ + +#ifndef MISC_H +#define MISC_H + +#include +#include +#include + + +namespace teb_local_planner +{ + +#define SMALL_NUM 0.00000001 + +//! Symbols for left/none/right rotations +enum class RotType { left, none, right }; + +/** + * @brief Check whether two variables (double) are close to each other + * @param a the first value to compare + * @param b the second value to compare + * @param epsilon precision threshold + * @return \c true if |a-b| < epsilon, false otherwise + */ +inline bool is_close(double a, double b, double epsilon = 1e-4) +{ + return std::fabs(a - b) < epsilon; +} + +/** + * @brief Return the average angle of an arbitrary number of given angles [rad] + * @param angles vector containing all angles + * @return average / mean angle, that is normalized to [-pi, pi] + */ +inline double average_angles(const std::vector& angles) +{ + double x=0, y=0; + for (std::vector::const_iterator it = angles.begin(); it!=angles.end(); ++it) + { + x += cos(*it); + y += sin(*it); + } + if(x == 0 && y == 0) + return 0; + else + return std::atan2(y, x); +} + +/** @brief Small helper function: check if |a|<|b| */ +inline bool smaller_than_abs(double i, double j) {return std::fabs(i) +inline double distance_points2d(const P1& point1, const P2& point2) +{ + return std::sqrt( std::pow(point2.x-point1.x,2) + std::pow(point2.y-point1.y,2) ); +} + + +/** + * @brief Calculate the 2d cross product (returns length of the resulting vector along the z-axis in 3d) + * @param v1 object containing public methods x() and y() + * @param v2 object containing fields x() and y() + * @return magnitude that would result in the 3D case (along the z-axis) +*/ +template +inline double cross2d(const V1& v1, const V2& v2) +{ + return v1.x()*v2.y() - v2.x()*v1.y(); +} + +/** + * @brief Helper function that returns the const reference to a value defined by either its raw pointer type or const reference. + * + * Return a constant reference for boths input variants (pointer or reference). + * @remarks Makes only sense in combination with the overload getConstReference(const T& val). + * @param ptr pointer of type T + * @tparam T arbitrary type + * @return If \c T is a pointer, return const *T (leading to const T&), otherwise const T& with out pointer-to-ref conversion + */ +template +inline const T& get_const_reference(const T* ptr) {return *ptr;} + +/** + * @brief Helper function that returns the const reference to a value defined by either its raw pointer type or const reference. + * + * Return a constant reference for boths input variants (pointer or reference). + * @remarks Makes only sense in combination with the overload getConstReference(const T* val). + * @param val + * @param dummy SFINAE helper variable + * @tparam T arbitrary type + * @return If \c T is a pointer, return const *T (leading to const T&), otherwise const T& with out pointer-to-ref conversion + */ +template +inline const T& get_const_reference(const T& val, typename boost::disable_if >::type* dummy = 0) {return val;} + +} // namespace teb_local_planner + +#endif /* MISC_H */ diff --git a/navigations/teb_local_planner/include/teb_local_planner/obstacles.h b/navigations/teb_local_planner/include/teb_local_planner/obstacles.h new file mode 100755 index 0000000..4a4e990 --- /dev/null +++ b/navigations/teb_local_planner/include/teb_local_planner/obstacles.h @@ -0,0 +1,1116 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2016, + * TU Dortmund - Institute of Control Theory and Systems Engineering. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the institute nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: Christoph Rösmann + *********************************************************************/ + + +#ifndef OBSTACLES_H +#define OBSTACLES_H + +#include +#include +#include + +#include + +#include +#include + +#include +#include +#include + +#include +#include + + +namespace teb_local_planner +{ + +/** + * @class Obstacle + * @brief Abstract class that defines the interface for modelling obstacles + */ +class Obstacle +{ +public: + + /** + * @brief Default constructor of the abstract obstacle class + */ + Obstacle() : dynamic_(false), centroid_velocity_(Eigen::Vector2d::Zero()) + { + } + + /** + * @brief Virtual destructor. + */ + virtual ~Obstacle() + { + } + + + /** @name Centroid coordinates (abstract, obstacle type depending) */ + //@{ + + /** + * @brief Get centroid coordinates of the obstacle + * @return Eigen::Vector2d containing the centroid + */ + virtual const Eigen::Vector2d& getCentroid() const = 0; + + /** + * @brief Get centroid coordinates of the obstacle as complex number + * @return std::complex containing the centroid coordinate + */ + virtual std::complex getCentroidCplx() const = 0; + + //@} + + + /** @name Collision checking and distance calculations (abstract, obstacle type depending) */ + //@{ + + /** + * @brief Check if a given point collides with the obstacle + * @param position 2D reference position that should be checked + * @param min_dist Minimum distance allowed to the obstacle to be collision free + * @return \c true if position is inside the region of the obstacle or if the minimum distance is lower than min_dist + */ + virtual bool checkCollision(const Eigen::Vector2d& position, double min_dist) const = 0; + + /** + * @brief Check if a given line segment between two points intersects with the obstacle (and additionally keeps a safty distance \c min_dist) + * @param line_start 2D point for the end of the reference line + * @param line_end 2D point for the end of the reference line + * @param min_dist Minimum distance allowed to the obstacle to be collision/intersection free + * @return \c true if given line intersects the region of the obstacle or if the minimum distance is lower than min_dist + */ + virtual bool checkLineIntersection(const Eigen::Vector2d& line_start, const Eigen::Vector2d& line_end, double min_dist=0) const = 0; + + /** + * @brief Get the minimum euclidean distance to the obstacle (point as reference) + * @param position 2d reference position + * @return The nearest possible distance to the obstacle + */ + virtual double getMinimumDistance(const Eigen::Vector2d& position) const = 0; + + /** + * @brief Get the minimum euclidean distance to the obstacle (line as reference) + * @param line_start 2d position of the begin of the reference line + * @param line_end 2d position of the end of the reference line + * @return The nearest possible distance to the obstacle + */ + virtual double getMinimumDistance(const Eigen::Vector2d& line_start, const Eigen::Vector2d& line_end) const = 0; + + /** + * @brief Get the minimum euclidean distance to the obstacle (polygon as reference) + * @param polygon Vertices (2D points) describing a closed polygon + * @return The nearest possible distance to the obstacle + */ + virtual double getMinimumDistance(const Point2dContainer& polygon) const = 0; + + /** + * @brief Get the closest point on the boundary of the obstacle w.r.t. a specified reference position + * @param position reference 2d position + * @return closest point on the obstacle boundary + */ + virtual Eigen::Vector2d getClosestPoint(const Eigen::Vector2d& position) const = 0; + + //@} + + + + /** @name Velocity related methods for non-static, moving obstacles */ + //@{ + + /** + * @brief Get the estimated minimum spatiotemporal distance to the moving obstacle using a constant velocity model (point as reference) + * @param position 2d reference position + * @param t time, for which the minimum distance to the obstacle is estimated + * @return The nearest possible distance to the obstacle at time t + */ + virtual double getMinimumSpatioTemporalDistance(const Eigen::Vector2d& position, double t) const = 0; + + /** + * @brief Get the estimated minimum spatiotemporal distance to the moving obstacle using a constant velocity model (line as reference) + * @param line_start 2d position of the begin of the reference line + * @param line_end 2d position of the end of the reference line + * @param t time, for which the minimum distance to the obstacle is estimated + * @return The nearest possible distance to the obstacle at time t + */ + virtual double getMinimumSpatioTemporalDistance(const Eigen::Vector2d& line_start, const Eigen::Vector2d& line_end, double t) const = 0; + + /** + * @brief Get the estimated minimum spatiotemporal distance to the moving obstacle using a constant velocity model (polygon as reference) + * @param polygon Vertices (2D points) describing a closed polygon + * @param t time, for which the minimum distance to the obstacle is estimated + * @return The nearest possible distance to the obstacle at time t + */ + virtual double getMinimumSpatioTemporalDistance(const Point2dContainer& polygon, double t) const = 0; + + /** + * @brief Predict position of the centroid assuming a constant velocity model + * @param[in] t time in seconds for the prediction (t>=0) + * @param[out] position predicted 2d position of the centroid + */ + virtual void predictCentroidConstantVelocity(double t, Eigen::Ref position) const + { + position = getCentroid() + t * getCentroidVelocity(); + } + + /** + * @brief Check if the obstacle is a moving with a (non-zero) velocity + * @return \c true if the obstacle is not marked as static, \c false otherwise + */ + bool isDynamic() const {return dynamic_;} + + /** + * @brief Set the 2d velocity (vx, vy) of the obstacle w.r.t to the centroid + * @remarks Setting the velocity using this function marks the obstacle as dynamic (@see isDynamic) + * @param vel 2D vector containing the velocities of the centroid in x and y directions + */ + void setCentroidVelocity(const Eigen::Ref& vel) {centroid_velocity_ = vel; dynamic_=true;} + + /** + * @brief Set the 2d velocity (vx, vy) of the obstacle w.r.t to the centroid + * @remarks Setting the velocity using this function marks the obstacle as dynamic (@see isDynamic) + * @param velocity geometry_msgs::TwistWithCovariance containing the velocity of the obstacle + * @param orientation geometry_msgs::QuaternionStamped containing the orientation of the obstacle + */ + void setCentroidVelocity(const geometry_msgs::TwistWithCovariance& velocity, + const geometry_msgs::Quaternion& orientation) + { + // Set velocity, if obstacle is moving + Eigen::Vector2d vel; + vel.coeffRef(0) = velocity.twist.linear.x; + vel.coeffRef(1) = velocity.twist.linear.y; + + // If norm of velocity is less than 0.001, consider obstacle as not dynamic + // TODO: Get rid of constant + if (vel.norm() < 0.001) + return; + + // currently velocity published by stage is already given in the map frame +// double yaw = tf::getYaw(orientation.quaternion); +// ROS_INFO("Yaw: %f", yaw); +// Eigen::Rotation2Dd rot(yaw); +// vel = rot * vel; + setCentroidVelocity(vel); + } + + void setCentroidVelocity(const geometry_msgs::TwistWithCovariance& velocity, + const geometry_msgs::QuaternionStamped& orientation) + { + setCentroidVelocity(velocity, orientation.quaternion); + } + + /** + * @brief Get the obstacle velocity (vx, vy) (w.r.t. to the centroid) + * @returns 2D vector containing the velocities of the centroid in x and y directions + */ + const Eigen::Vector2d& getCentroidVelocity() const {return centroid_velocity_;} + + //@} + + + + /** @name Helper Functions */ + //@{ + + /** + * @brief Convert the obstacle to a polygon message + * + * Convert the obstacle to a corresponding polygon msg. + * Point obstacles have one vertex, lines have two vertices + * and polygons might are implictly closed such that the start vertex must not be repeated. + * @param[out] polygon the polygon message + */ + virtual void toPolygonMsg(geometry_msgs::Polygon& polygon) = 0; + + virtual void toTwistWithCovarianceMsg(geometry_msgs::TwistWithCovariance& twistWithCovariance) + { + if (dynamic_) + { + twistWithCovariance.twist.linear.x = centroid_velocity_(0); + twistWithCovariance.twist.linear.y = centroid_velocity_(1); + } + else + { + twistWithCovariance.twist.linear.x = 0; + twistWithCovariance.twist.linear.y = 0; + } + + // TODO:Covariance + } + + //@} + +protected: + + bool dynamic_; //!< Store flag if obstacle is dynamic (resp. a moving obstacle) + Eigen::Vector2d centroid_velocity_; //!< Store the corresponding velocity (vx, vy) of the centroid (zero, if _dynamic is \c true) + +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +}; + + +//! Abbrev. for shared obstacle pointers +typedef boost::shared_ptr ObstaclePtr; +//! Abbrev. for shared obstacle const pointers +typedef boost::shared_ptr ObstacleConstPtr; +//! Abbrev. for containers storing multiple obstacles +typedef std::vector ObstContainer; + + + +/** + * @class PointObstacle + * @brief Implements a 2D point obstacle + */ +class PointObstacle : public Obstacle +{ +public: + + /** + * @brief Default constructor of the point obstacle class + */ + PointObstacle() : Obstacle(), pos_(Eigen::Vector2d::Zero()) + {} + + /** + * @brief Construct PointObstacle using a 2d position vector + * @param position 2d position that defines the current obstacle position + */ + PointObstacle(const Eigen::Ref< const Eigen::Vector2d>& position) : Obstacle(), pos_(position) + {} + + /** + * @brief Construct PointObstacle using x- and y-coordinates + * @param x x-coordinate + * @param y y-coordinate + */ + PointObstacle(double x, double y) : Obstacle(), pos_(Eigen::Vector2d(x,y)) + {} + + + // implements checkCollision() of the base class + virtual bool checkCollision(const Eigen::Vector2d& point, double min_dist) const + { + return getMinimumDistance(point) < min_dist; + } + + + // implements checkLineIntersection() of the base class + virtual bool checkLineIntersection(const Eigen::Vector2d& line_start, const Eigen::Vector2d& line_end, double min_dist=0) const + { + // Distance Line - Circle + // refer to http://www.spieleprogrammierer.de/wiki/2D-Kollisionserkennung#Kollision_Kreis-Strecke + Eigen::Vector2d a = line_end-line_start; // not normalized! a=y-x + Eigen::Vector2d b = pos_-line_start; // b=m-x + + // Now find nearest point to circle v=x+a*t with t=a*b/(a*a) and bound to 0<=t<=1 + double t = a.dot(b)/a.dot(a); + if (t<0) t=0; // bound t (since a is not normalized, t can be scaled between 0 and 1 to parametrize the line + else if (t>1) t=1; + Eigen::Vector2d nearest_point = line_start + a*t; + + // check collision + return checkCollision(nearest_point, min_dist); + } + + + // implements getMinimumDistance() of the base class + virtual double getMinimumDistance(const Eigen::Vector2d& position) const + { + return (position-pos_).norm(); + } + + // implements getMinimumDistance() of the base class + virtual double getMinimumDistance(const Eigen::Vector2d& line_start, const Eigen::Vector2d& line_end) const + { + return distance_point_to_segment_2d(pos_, line_start, line_end); + } + + // implements getMinimumDistance() of the base class + virtual double getMinimumDistance(const Point2dContainer& polygon) const + { + return distance_point_to_polygon_2d(pos_, polygon); + } + + // implements getMinimumDistanceVec() of the base class + virtual Eigen::Vector2d getClosestPoint(const Eigen::Vector2d& position) const + { + return pos_; + } + + // implements getMinimumSpatioTemporalDistance() of the base class + virtual double getMinimumSpatioTemporalDistance(const Eigen::Vector2d& position, double t) const + { + return (pos_ + t*centroid_velocity_ - position).norm(); + } + + // implements getMinimumSpatioTemporalDistance() of the base class + virtual double getMinimumSpatioTemporalDistance(const Eigen::Vector2d& line_start, const Eigen::Vector2d& line_end, double t) const + { + return distance_point_to_segment_2d(pos_ + t*centroid_velocity_, line_start, line_end); + } + + // implements getMinimumSpatioTemporalDistance() of the base class + virtual double getMinimumSpatioTemporalDistance(const Point2dContainer& polygon, double t) const + { + return distance_point_to_polygon_2d(pos_ + t*centroid_velocity_, polygon); + } + + // implements predictCentroidConstantVelocity() of the base class + virtual void predictCentroidConstantVelocity(double t, Eigen::Ref position) const + { + position = pos_ + t*centroid_velocity_; + } + + // implements getCentroid() of the base class + virtual const Eigen::Vector2d& getCentroid() const + { + return pos_; + } + + // implements getCentroidCplx() of the base class + virtual std::complex getCentroidCplx() const + { + return std::complex(pos_[0],pos_[1]); + } + + // Accessor methods + const Eigen::Vector2d& position() const {return pos_;} //!< Return the current position of the obstacle (read-only) + Eigen::Vector2d& position() {return pos_;} //!< Return the current position of the obstacle + double& x() {return pos_.coeffRef(0);} //!< Return the current x-coordinate of the obstacle + const double& x() const {return pos_.coeffRef(0);} //!< Return the current y-coordinate of the obstacle (read-only) + double& y() {return pos_.coeffRef(1);} //!< Return the current x-coordinate of the obstacle + const double& y() const {return pos_.coeffRef(1);} //!< Return the current y-coordinate of the obstacle (read-only) + + // implements toPolygonMsg() of the base class + virtual void toPolygonMsg(geometry_msgs::Polygon& polygon) + { + polygon.points.resize(1); + polygon.points.front().x = pos_.x(); + polygon.points.front().y = pos_.y(); + polygon.points.front().z = 0; + } + +protected: + + Eigen::Vector2d pos_; //!< Store the position of the PointObstacle + + +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +}; + +/** + * @class CircularObstacle + * @brief Implements a 2D circular obstacle (point obstacle plus radius) + */ +class CircularObstacle : public Obstacle +{ +public: + + /** + * @brief Default constructor of the circular obstacle class + */ + CircularObstacle() : Obstacle(), pos_(Eigen::Vector2d::Zero()) + {} + + /** + * @brief Construct CircularObstacle using a 2d center position vector and radius + * @param position 2d position that defines the current obstacle position + * @param radius radius of the obstacle + */ + CircularObstacle(const Eigen::Ref< const Eigen::Vector2d>& position, double radius) : Obstacle(), pos_(position), radius_(radius) + {} + + /** + * @brief Construct CircularObstacle using x- and y-center-coordinates and radius + * @param x x-coordinate + * @param y y-coordinate + * @param radius radius of the obstacle + */ + CircularObstacle(double x, double y, double radius) : Obstacle(), pos_(Eigen::Vector2d(x,y)), radius_(radius) + {} + + + // implements checkCollision() of the base class + virtual bool checkCollision(const Eigen::Vector2d& point, double min_dist) const + { + return getMinimumDistance(point) < min_dist; + } + + + // implements checkLineIntersection() of the base class + virtual bool checkLineIntersection(const Eigen::Vector2d& line_start, const Eigen::Vector2d& line_end, double min_dist=0) const + { + // Distance Line - Circle + // refer to http://www.spieleprogrammierer.de/wiki/2D-Kollisionserkennung#Kollision_Kreis-Strecke + Eigen::Vector2d a = line_end-line_start; // not normalized! a=y-x + Eigen::Vector2d b = pos_-line_start; // b=m-x + + // Now find nearest point to circle v=x+a*t with t=a*b/(a*a) and bound to 0<=t<=1 + double t = a.dot(b)/a.dot(a); + if (t<0) t=0; // bound t (since a is not normalized, t can be scaled between 0 and 1 to parametrize the line + else if (t>1) t=1; + Eigen::Vector2d nearest_point = line_start + a*t; + + // check collision + return checkCollision(nearest_point, min_dist); + } + + + // implements getMinimumDistance() of the base class + virtual double getMinimumDistance(const Eigen::Vector2d& position) const + { + return (position-pos_).norm() - radius_; + } + + // implements getMinimumDistance() of the base class + virtual double getMinimumDistance(const Eigen::Vector2d& line_start, const Eigen::Vector2d& line_end) const + { + return distance_point_to_segment_2d(pos_, line_start, line_end) - radius_; + } + + // implements getMinimumDistance() of the base class + virtual double getMinimumDistance(const Point2dContainer& polygon) const + { + return distance_point_to_polygon_2d(pos_, polygon) - radius_; + } + + // implements getMinimumDistanceVec() of the base class + virtual Eigen::Vector2d getClosestPoint(const Eigen::Vector2d& position) const + { + return pos_ + radius_*(position-pos_).normalized(); + } + + // implements getMinimumSpatioTemporalDistance() of the base class + virtual double getMinimumSpatioTemporalDistance(const Eigen::Vector2d& position, double t) const + { + return (pos_ + t*centroid_velocity_ - position).norm() - radius_; + } + + // implements getMinimumSpatioTemporalDistance() of the base class + virtual double getMinimumSpatioTemporalDistance(const Eigen::Vector2d& line_start, const Eigen::Vector2d& line_end, double t) const + { + return distance_point_to_segment_2d(pos_ + t*centroid_velocity_, line_start, line_end) - radius_; + } + + // implements getMinimumSpatioTemporalDistance() of the base class + virtual double getMinimumSpatioTemporalDistance(const Point2dContainer& polygon, double t) const + { + return distance_point_to_polygon_2d(pos_ + t*centroid_velocity_, polygon) - radius_; + } + + // implements predictCentroidConstantVelocity() of the base class + virtual void predictCentroidConstantVelocity(double t, Eigen::Ref position) const + { + position = pos_ + t*centroid_velocity_; + } + + // implements getCentroid() of the base class + virtual const Eigen::Vector2d& getCentroid() const + { + return pos_; + } + + // implements getCentroidCplx() of the base class + virtual std::complex getCentroidCplx() const + { + return std::complex(pos_[0],pos_[1]); + } + + // Accessor methods + const Eigen::Vector2d& position() const {return pos_;} //!< Return the current position of the obstacle (read-only) + Eigen::Vector2d& position() {return pos_;} //!< Return the current position of the obstacle + double& x() {return pos_.coeffRef(0);} //!< Return the current x-coordinate of the obstacle + const double& x() const {return pos_.coeffRef(0);} //!< Return the current y-coordinate of the obstacle (read-only) + double& y() {return pos_.coeffRef(1);} //!< Return the current x-coordinate of the obstacle + const double& y() const {return pos_.coeffRef(1);} //!< Return the current y-coordinate of the obstacle (read-only) + double& radius() {return radius_;} //!< Return the current radius of the obstacle + const double& radius() const {return radius_;} //!< Return the current radius of the obstacle + + // implements toPolygonMsg() of the base class + virtual void toPolygonMsg(geometry_msgs::Polygon& polygon) + { + // TODO(roesmann): the polygon message type cannot describe a "perfect" circle + // We could switch to ObstacleMsg if required somewhere... + polygon.points.resize(1); + polygon.points.front().x = pos_.x(); + polygon.points.front().y = pos_.y(); + polygon.points.front().z = 0; + } + +protected: + + Eigen::Vector2d pos_; //!< Store the center position of the CircularObstacle + double radius_ = 0.0; //!< Radius of the obstacle + + +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +}; + +/** +* @class LineObstacle +* @brief Implements a 2D line obstacle +*/ + +class LineObstacle : public Obstacle +{ +public: + //! Abbrev. for a container storing vertices (2d points defining the edge points of the polygon) + typedef std::vector > VertexContainer; + + /** + * @brief Default constructor of the point obstacle class + */ + LineObstacle() : Obstacle() + { + start_.setZero(); + end_.setZero(); + centroid_.setZero(); + } + + /** + * @brief Construct LineObstacle using 2d position vectors as start and end of the line + * @param line_start 2d position that defines the start of the line obstacle + * @param line_end 2d position that defines the end of the line obstacle + */ + LineObstacle(const Eigen::Ref< const Eigen::Vector2d>& line_start, const Eigen::Ref< const Eigen::Vector2d>& line_end) + : Obstacle(), start_(line_start), end_(line_end) + { + calcCentroid(); + } + + /** + * @brief Construct LineObstacle using start and end coordinates + * @param x1 x-coordinate of the start of the line + * @param y1 y-coordinate of the start of the line + * @param x2 x-coordinate of the end of the line + * @param y2 y-coordinate of the end of the line + */ + LineObstacle(double x1, double y1, double x2, double y2) : Obstacle() + { + start_.x() = x1; + start_.y() = y1; + end_.x() = x2; + end_.y() = y2; + calcCentroid(); + } + + // implements checkCollision() of the base class + virtual bool checkCollision(const Eigen::Vector2d& point, double min_dist) const + { + return getMinimumDistance(point) <= min_dist; + } + + // implements checkLineIntersection() of the base class + virtual bool checkLineIntersection(const Eigen::Vector2d& line_start, const Eigen::Vector2d& line_end, double min_dist=0) const + { + return check_line_segments_intersection_2d(line_start, line_end, start_, end_); + } + + // implements getMinimumDistance() of the base class + virtual double getMinimumDistance(const Eigen::Vector2d& position) const + { + return distance_point_to_segment_2d(position, start_, end_); + } + + // implements getMinimumDistance() of the base class + virtual double getMinimumDistance(const Eigen::Vector2d& line_start, const Eigen::Vector2d& line_end) const + { + return distance_segment_to_segment_2d(start_, end_, line_start, line_end); + } + + // implements getMinimumDistance() of the base class + virtual double getMinimumDistance(const Point2dContainer& polygon) const + { + return distance_segment_to_polygon_2d(start_, end_, polygon); + } + + // implements getMinimumDistanceVec() of the base class + virtual Eigen::Vector2d getClosestPoint(const Eigen::Vector2d& position) const + { + return closest_point_on_line_segment_2d(position, start_, end_); + } + + // implements getMinimumSpatioTemporalDistance() of the base class + virtual double getMinimumSpatioTemporalDistance(const Eigen::Vector2d& position, double t) const + { + Eigen::Vector2d offset = t*centroid_velocity_; + return distance_point_to_segment_2d(position, start_ + offset, end_ + offset); + } + + // implements getMinimumSpatioTemporalDistance() of the base class + virtual double getMinimumSpatioTemporalDistance(const Eigen::Vector2d& line_start, const Eigen::Vector2d& line_end, double t) const + { + Eigen::Vector2d offset = t*centroid_velocity_; + return distance_segment_to_segment_2d(start_ + offset, end_ + offset, line_start, line_end); + } + + // implements getMinimumSpatioTemporalDistance() of the base class + virtual double getMinimumSpatioTemporalDistance(const Point2dContainer& polygon, double t) const + { + Eigen::Vector2d offset = t*centroid_velocity_; + return distance_segment_to_polygon_2d(start_ + offset, end_ + offset, polygon); + } + + // implements getCentroid() of the base class + virtual const Eigen::Vector2d& getCentroid() const + { + return centroid_; + } + + // implements getCentroidCplx() of the base class + virtual std::complex getCentroidCplx() const + { + return std::complex(centroid_.x(), centroid_.y()); + } + + // Access or modify line + const Eigen::Vector2d& start() const {return start_;} + void setStart(const Eigen::Ref& start) {start_ = start; calcCentroid();} + const Eigen::Vector2d& end() const {return end_;} + void setEnd(const Eigen::Ref& end) {end_ = end; calcCentroid();} + + // implements toPolygonMsg() of the base class + virtual void toPolygonMsg(geometry_msgs::Polygon& polygon) + { + polygon.points.resize(2); + polygon.points.front().x = start_.x(); + polygon.points.front().y = start_.y(); + + polygon.points.back().x = end_.x(); + polygon.points.back().y = end_.y(); + polygon.points.back().z = polygon.points.front().z = 0; + } + +protected: + void calcCentroid() { centroid_ = 0.5*(start_ + end_); } + +private: + Eigen::Vector2d start_; + Eigen::Vector2d end_; + + Eigen::Vector2d centroid_; + +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +}; + + +/** +* @class PillObstacle +* @brief Implements a 2D pill/stadium/capsular-shaped obstacle (line + distance/radius) +*/ + +class PillObstacle : public Obstacle +{ +public: + + /** + * @brief Default constructor of the point obstacle class + */ + PillObstacle() : Obstacle() + { + start_.setZero(); + end_.setZero(); + centroid_.setZero(); + } + + /** + * @brief Construct LineObstacle using 2d position vectors as start and end of the line + * @param line_start 2d position that defines the start of the line obstacle + * @param line_end 2d position that defines the end of the line obstacle + */ + PillObstacle(const Eigen::Ref< const Eigen::Vector2d>& line_start, const Eigen::Ref< const Eigen::Vector2d>& line_end, double radius) + : Obstacle(), start_(line_start), end_(line_end), radius_(radius) + { + calcCentroid(); + } + + /** + * @brief Construct LineObstacle using start and end coordinates + * @param x1 x-coordinate of the start of the line + * @param y1 y-coordinate of the start of the line + * @param x2 x-coordinate of the end of the line + * @param y2 y-coordinate of the end of the line + */ + PillObstacle(double x1, double y1, double x2, double y2, double radius) : Obstacle(), radius_(radius) + { + start_.x() = x1; + start_.y() = y1; + end_.x() = x2; + end_.y() = y2; + calcCentroid(); + } + + // implements checkCollision() of the base class + virtual bool checkCollision(const Eigen::Vector2d& point, double min_dist) const + { + return getMinimumDistance(point) <= min_dist; + } + + // implements checkLineIntersection() of the base class + virtual bool checkLineIntersection(const Eigen::Vector2d& line_start, const Eigen::Vector2d& line_end, double min_dist=0) const + { + return check_line_segments_intersection_2d(line_start, line_end, start_, end_); + } + + // implements getMinimumDistance() of the base class + virtual double getMinimumDistance(const Eigen::Vector2d& position) const + { + return distance_point_to_segment_2d(position, start_, end_) - radius_; + } + + // implements getMinimumDistance() of the base class + virtual double getMinimumDistance(const Eigen::Vector2d& line_start, const Eigen::Vector2d& line_end) const + { + return distance_segment_to_segment_2d(start_, end_, line_start, line_end) - radius_; + } + + // implements getMinimumDistance() of the base class + virtual double getMinimumDistance(const Point2dContainer& polygon) const + { + return distance_segment_to_polygon_2d(start_, end_, polygon) - radius_; + } + + // implements getMinimumDistanceVec() of the base class + virtual Eigen::Vector2d getClosestPoint(const Eigen::Vector2d& position) const + { + Eigen::Vector2d closed_point_line = closest_point_on_line_segment_2d(position, start_, end_); + return closed_point_line + radius_*(position-closed_point_line).normalized(); + } + + // implements getMinimumSpatioTemporalDistance() of the base class + virtual double getMinimumSpatioTemporalDistance(const Eigen::Vector2d& position, double t) const + { + Eigen::Vector2d offset = t*centroid_velocity_; + return distance_point_to_segment_2d(position, start_ + offset, end_ + offset) - radius_; + } + + // implements getMinimumSpatioTemporalDistance() of the base class + virtual double getMinimumSpatioTemporalDistance(const Eigen::Vector2d& line_start, const Eigen::Vector2d& line_end, double t) const + { + Eigen::Vector2d offset = t*centroid_velocity_; + return distance_segment_to_segment_2d(start_ + offset, end_ + offset, line_start, line_end) - radius_; + } + + // implements getMinimumSpatioTemporalDistance() of the base class + virtual double getMinimumSpatioTemporalDistance(const Point2dContainer& polygon, double t) const + { + Eigen::Vector2d offset = t*centroid_velocity_; + return distance_segment_to_polygon_2d(start_ + offset, end_ + offset, polygon) - radius_; + } + + // implements getCentroid() of the base class + virtual const Eigen::Vector2d& getCentroid() const + { + return centroid_; + } + + // implements getCentroidCplx() of the base class + virtual std::complex getCentroidCplx() const + { + return std::complex(centroid_.x(), centroid_.y()); + } + + // Access or modify line + const Eigen::Vector2d& start() const {return start_;} + void setStart(const Eigen::Ref& start) {start_ = start; calcCentroid();} + const Eigen::Vector2d& end() const {return end_;} + void setEnd(const Eigen::Ref& end) {end_ = end; calcCentroid();} + + // implements toPolygonMsg() of the base class + virtual void toPolygonMsg(geometry_msgs::Polygon& polygon) + { + // Currently, we only export the line + // TODO(roesmann): export whole pill + polygon.points.resize(2); + polygon.points.front().x = start_.x(); + polygon.points.front().y = start_.y(); + + polygon.points.back().x = end_.x(); + polygon.points.back().y = end_.y(); + polygon.points.back().z = polygon.points.front().z = 0; + } + +protected: + void calcCentroid() { centroid_ = 0.5*(start_ + end_); } + +private: + Eigen::Vector2d start_; + Eigen::Vector2d end_; + double radius_ = 0.0; + + Eigen::Vector2d centroid_; + +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +}; + +/** + * @class PolygonObstacle + * @brief Implements a polygon obstacle with an arbitrary number of vertices + * @details If the polygon has only 2 vertices, than it is considered as a line, + * otherwise the polygon will always be closed (a connection between the first and the last vertex + * is included automatically). + */ +class PolygonObstacle : public Obstacle +{ +public: + + /** + * @brief Default constructor of the polygon obstacle class + */ + PolygonObstacle() : Obstacle(), finalized_(false) + { + centroid_.setConstant(NAN); + } + + /** + * @brief Construct polygon obstacle with a list of vertices + */ + PolygonObstacle(const Point2dContainer& vertices) : Obstacle(), vertices_(vertices) + { + finalizePolygon(); + } + + + /* FIXME Not working at the moment due to the aligned allocator version of std::vector + * And it is C++11 code that is disabled atm to ensure compliance with ROS indigo/jade + template + PolygonObstacle(const Vector2dType&... vertices) : _vertices({vertices...}) + { + calcCentroid(); + _finalized = true; + } + */ + + + // implements checkCollision() of the base class + virtual bool checkCollision(const Eigen::Vector2d& point, double min_dist) const + { + // line case + if (noVertices()==2) + return getMinimumDistance(point) <= min_dist; + + // check if point is in the interior of the polygon + // point in polygon test - raycasting (http://www.ecse.rpi.edu/Homepages/wrf/Research/Short_Notes/pnpoly.html) + // using the following algorithm we may obtain false negatives on edge-cases, but that's ok for our purposes + int i, j; + bool c = false; + for (i = 0, j = noVertices()-1; i < noVertices(); j = i++) + { + if ( ((vertices_.at(i).y()>point.y()) != (vertices_.at(j).y()>point.y())) && + (point.x() < (vertices_.at(j).x()-vertices_.at(i).x()) * (point.y()-vertices_.at(i).y()) / (vertices_.at(j).y()-vertices_.at(i).y()) + vertices_.at(i).x()) ) + c = !c; + } + if (c>0) return true; + + // If this statement is reached, the point lies outside the polygon or maybe on its edges + // Let us check the minium distance as well + return min_dist == 0 ? false : getMinimumDistance(point) < min_dist; + } + + + /** + * @brief Check if a given line segment between two points intersects with the obstacle (and additionally keeps a safty distance \c min_dist) + * @param line_start 2D point for the end of the reference line + * @param line_end 2D point for the end of the reference line + * @param min_dist Minimum distance allowed to the obstacle to be collision/intersection free + * @remarks we ignore \c min_dist here + * @return \c true if given line intersects the region of the obstacle or if the minimum distance is lower than min_dist + */ + virtual bool checkLineIntersection(const Eigen::Vector2d& line_start, const Eigen::Vector2d& line_end, double min_dist=0) const; + + + // implements getMinimumDistance() of the base class + virtual double getMinimumDistance(const Eigen::Vector2d& position) const + { + return distance_point_to_polygon_2d(position, vertices_); + } + + // implements getMinimumDistance() of the base class + virtual double getMinimumDistance(const Eigen::Vector2d& line_start, const Eigen::Vector2d& line_end) const + { + return distance_segment_to_polygon_2d(line_start, line_end, vertices_); + } + + // implements getMinimumDistance() of the base class + virtual double getMinimumDistance(const Point2dContainer& polygon) const + { + return distance_polygon_to_polygon_2d(polygon, vertices_); + } + + // implements getMinimumDistanceVec() of the base class + virtual Eigen::Vector2d getClosestPoint(const Eigen::Vector2d& position) const; + + // implements getMinimumSpatioTemporalDistance() of the base class + virtual double getMinimumSpatioTemporalDistance(const Eigen::Vector2d& position, double t) const + { + Point2dContainer pred_vertices; + predictVertices(t, pred_vertices); + return distance_point_to_polygon_2d(position, pred_vertices); + } + + // implements getMinimumSpatioTemporalDistance() of the base class + virtual double getMinimumSpatioTemporalDistance(const Eigen::Vector2d& line_start, const Eigen::Vector2d& line_end, double t) const + { + Point2dContainer pred_vertices; + predictVertices(t, pred_vertices); + return distance_segment_to_polygon_2d(line_start, line_end, pred_vertices); + } + + // implements getMinimumSpatioTemporalDistance() of the base class + virtual double getMinimumSpatioTemporalDistance(const Point2dContainer& polygon, double t) const + { + Point2dContainer pred_vertices; + predictVertices(t, pred_vertices); + return distance_polygon_to_polygon_2d(polygon, pred_vertices); + } + + virtual void predictVertices(double t, Point2dContainer& pred_vertices) const + { + // Predict obstacle (polygon) at time t + pred_vertices.resize(vertices_.size()); + Eigen::Vector2d offset = t*centroid_velocity_; + for (std::size_t i = 0; i < vertices_.size(); i++) + { + pred_vertices[i] = vertices_[i] + offset; + } + } + + // implements getCentroid() of the base class + virtual const Eigen::Vector2d& getCentroid() const + { + assert(finalized_ && "Finalize the polygon after all vertices are added."); + return centroid_; + } + + // implements getCentroidCplx() of the base class + virtual std::complex getCentroidCplx() const + { + assert(finalized_ && "Finalize the polygon after all vertices are added."); + return std::complex(centroid_.coeffRef(0), centroid_.coeffRef(1)); + } + + // implements toPolygonMsg() of the base class + virtual void toPolygonMsg(geometry_msgs::Polygon& polygon); + + + /** @name Define the polygon */ + ///@{ + + // Access or modify polygon + const Point2dContainer& vertices() const {return vertices_;} //!< Access vertices container (read-only) + Point2dContainer& vertices() {return vertices_;} //!< Access vertices container + + /** + * @brief Add a vertex to the polygon (edge-point) + * @remarks You do not need to close the polygon (do not repeat the first vertex) + * @warning Do not forget to call finalizePolygon() after adding all vertices + * @param vertex 2D point defining a new polygon edge + */ + void pushBackVertex(const Eigen::Ref& vertex) + { + vertices_.push_back(vertex); + finalized_ = false; + } + + /** + * @brief Add a vertex to the polygon (edge-point) + * @remarks You do not need to close the polygon (do not repeat the first vertex) + * @warning Do not forget to call finalizePolygon() after adding all vertices + * @param x x-coordinate of the new vertex + * @param y y-coordinate of the new vertex + */ + void pushBackVertex(double x, double y) + { + vertices_.push_back(Eigen::Vector2d(x,y)); + finalized_ = false; + } + + /** + * @brief Call finalizePolygon after the polygon is created with the help of pushBackVertex() methods + */ + void finalizePolygon() + { + fixPolygonClosure(); + calcCentroid(); + finalized_ = true; + } + + /** + * @brief Clear all vertices (Afterwards the polygon is not valid anymore) + */ + void clearVertices() {vertices_.clear(); finalized_ = false;} + + /** + * @brief Get the number of vertices defining the polygon (the first vertex is counted once) + */ + int noVertices() const {return (int)vertices_.size();} + + + ///@} + +protected: + + void fixPolygonClosure(); //!< Check if the current polygon contains the first vertex twice (as start and end) and in that case erase the last redundant one. + + void calcCentroid(); //!< Compute the centroid of the polygon (called inside finalizePolygon()) + + + Point2dContainer vertices_; //!< Store vertices defining the polygon (@see pushBackVertex) + Eigen::Vector2d centroid_; //!< Store the centroid coordinates of the polygon (@see calcCentroid) + + bool finalized_; //!< Flat that keeps track if the polygon was finalized after adding all vertices + + +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +}; + + +} // namespace teb_local_planner + +#endif /* OBSTACLES_H */ diff --git a/navigations/teb_local_planner/include/teb_local_planner/optimal_planner.h b/navigations/teb_local_planner/include/teb_local_planner/optimal_planner.h new file mode 100755 index 0000000..3f87b83 --- /dev/null +++ b/navigations/teb_local_planner/include/teb_local_planner/optimal_planner.h @@ -0,0 +1,714 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2016, + * TU Dortmund - Institute of Control Theory and Systems Engineering. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the institute nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: Christoph Rösmann + *********************************************************************/ + +#ifndef OPTIMAL_PLANNER_H_ +#define OPTIMAL_PLANNER_H_ + +#include + + +// teb stuff +#include +#include +#include +#include +#include +#include + +// g2o lib stuff +#include +#include +#include +#include +#include +#include +#include + +// messages +#include +#include +#include +#include + +#include +#include + +namespace teb_local_planner +{ + +//! Typedef for the block solver utilized for optimization +typedef g2o::BlockSolver< g2o::BlockSolverTraits<-1, -1> > TEBBlockSolver; + +//! Typedef for the linear solver utilized for optimization +typedef g2o::LinearSolverCSparse TEBLinearSolver; +//typedef g2o::LinearSolverCholmod TEBLinearSolver; + +//! Typedef for a container storing via-points +typedef std::vector< Eigen::Vector2d, Eigen::aligned_allocator > ViaPointContainer; + + +/** + * @class TebOptimalPlanner + * @brief This class optimizes an internal Timed Elastic Band trajectory using the g2o-framework. + * + * For an introduction and further details about the TEB optimization problem refer to: + * - C. Rösmann et al.: Trajectory modification considering dynamic constraints of autonomous robots, ROBOTIK, 2012. + * - C. Rösmann et al.: Efficient trajectory optimization using a sparse model, ECMR, 2013. + * - R. Kümmerle et al.: G2o: A general framework for graph optimization, ICRA, 2011. + * + * @todo: Call buildGraph() only if the teb structure has been modified to speed up hot-starting from previous solutions. + * @todo: We introduced the non-fast mode with the support of dynamic obstacles + * (which leads to better results in terms of x-y-t homotopy planning). + * However, we have not tested this mode intensively yet, so we keep + * the legacy fast mode as default until we finish our tests. + */ +class TebOptimalPlanner : public PlannerInterface +{ +public: + + /** + * @brief Default constructor + */ + TebOptimalPlanner(); + + /** + * @brief Construct and initialize the TEB optimal planner. + * @param cfg Const reference to the TebConfig class for internal parameters + * @param obstacles Container storing all relevant obstacles (see Obstacle) + * @param robot_model Shared pointer to the robot shape model used for optimization (optional) + * @param visual Shared pointer to the TebVisualization class (optional) + * @param via_points Container storing via-points (optional) + */ + TebOptimalPlanner(const TebConfig& cfg, ObstContainer* obstacles = NULL, RobotFootprintModelPtr robot_model = boost::make_shared(), + TebVisualizationPtr visual = TebVisualizationPtr(), const ViaPointContainer* via_points = NULL); + + /** + * @brief Destruct the optimal planner. + */ + virtual ~TebOptimalPlanner(); + + /** + * @brief Initializes the optimal planner + * @param cfg Const reference to the TebConfig class for internal parameters + * @param obstacles Container storing all relevant obstacles (see Obstacle) + * @param robot_model Shared pointer to the robot shape model used for optimization (optional) + * @param visual Shared pointer to the TebVisualization class (optional) + * @param via_points Container storing via-points (optional) + */ + void initialize(const TebConfig& cfg, ObstContainer* obstacles = NULL, RobotFootprintModelPtr robot_model = boost::make_shared(), + TebVisualizationPtr visual = TebVisualizationPtr(), const ViaPointContainer* via_points = NULL); + + /** + * @param robot_model Shared pointer to the robot shape model used for optimization (optional) + */ + void updateRobotModel(RobotFootprintModelPtr robot_model ); + + /** @name Plan a trajectory */ + //@{ + + /** + * @brief Plan a trajectory based on an initial reference plan. + * + * Call this method to create and optimize a trajectory that is initialized + * according to an initial reference plan (given as a container of poses). \n + * The method supports hot-starting from previous solutions, if avaiable: \n + * - If no trajectory exist yet, a new trajectory is initialized based on the initial plan, + * see TimedElasticBand::initTEBtoGoal + * - If a previous solution is avaiable, update the trajectory based on the initial plan, + * see bool TimedElasticBand::updateAndPruneTEB + * - Afterwards optimize the recently initialized or updated trajectory by calling optimizeTEB() and invoking g2o + * @param initial_plan vector of geometry_msgs::PoseStamped + * @param start_vel Current start velocity (e.g. the velocity of the robot, only linear.x, linear.y (holonomic) and angular.z are used) + * @param free_goal_vel if \c true, a nonzero final velocity at the goal pose is allowed, + * otherwise the final velocity will be zero (default: false) + * @return \c true if planning was successful, \c false otherwise + */ + virtual bool plan(const std::vector& initial_plan, const geometry_msgs::Twist* start_vel = NULL, bool free_goal_vel=false); + + /** + * @brief Plan a trajectory between a given start and goal pose (tf::Pose version) + * + * Call this method to create and optimize a trajectory that is initialized between a given start and goal pose. \n + * The method supports hot-starting from previous solutions, if avaiable: \n + * - If no trajectory exist yet, a new trajectory is initialized between start and goal poses, + * see TimedElasticBand::initTEBtoGoal + * - If a previous solution is avaiable, update the trajectory @see bool TimedElasticBand::updateAndPruneTEB + * - Afterwards optimize the recently initialized or updated trajectory by calling optimizeTEB() and invoking g2o + * @param start tf::Pose containing the start pose of the trajectory + * @param goal tf::Pose containing the goal pose of the trajectory + * @param start_vel Current start velocity (e.g. the velocity of the robot, only linear.x, linear.y (holonomic) and angular.z are used) + * @param free_goal_vel if \c true, a nonzero final velocity at the goal pose is allowed, + * otherwise the final velocity will be zero (default: false) + * @return \c true if planning was successful, \c false otherwise + */ + virtual bool plan(const tf::Pose& start, const tf::Pose& goal, const geometry_msgs::Twist* start_vel = NULL, bool free_goal_vel=false); + + /** + * @brief Plan a trajectory between a given start and goal pose + * + * Call this method to create and optimize a trajectory that is initialized between a given start and goal pose. \n + * The method supports hot-starting from previous solutions, if avaiable: \n + * - If no trajectory exist yet, a new trajectory is initialized between start and goal poses + * @see TimedElasticBand::initTEBtoGoal + * - If a previous solution is avaiable, update the trajectory @see bool TimedElasticBand::updateAndPruneTEB + * - Afterwards optimize the recently initialized or updated trajectory by calling optimizeTEB() and invoking g2o + * @param start PoseSE2 containing the start pose of the trajectory + * @param goal PoseSE2 containing the goal pose of the trajectory + * @param start_vel Initial velocity at the start pose (twist message containing the translational and angular velocity). + * @param free_goal_vel if \c true, a nonzero final velocity at the goal pose is allowed, + * otherwise the final velocity will be zero (default: false) + * @return \c true if planning was successful, \c false otherwise + */ + virtual bool plan(const PoseSE2& start, const PoseSE2& goal, const geometry_msgs::Twist* start_vel = NULL, bool free_goal_vel=false); + + + /** + * @brief Get the velocity command from a previously optimized plan to control the robot at the current sampling interval. + * @warning Call plan() first and check if the generated plan is feasible. + * @param[out] vx translational velocity [m/s] + * @param[out] vy strafing velocity which can be nonzero for holonomic robots[m/s] + * @param[out] omega rotational velocity [rad/s] + * @param[in] look_ahead_poses index of the final pose used to compute the velocity command. + * @return \c true if command is valid, \c false otherwise + */ + virtual bool getVelocityCommand(double& vx, double& vy, double& omega, int look_ahead_poses) const; + + + /** + * @brief Optimize a previously initialized trajectory (actual TEB optimization loop). + * + * optimizeTEB implements the main optimization loop. \n + * It consist of two nested loops: + * - The outer loop resizes the trajectory according to the temporal resolution by invoking TimedElasticBand::autoResize(). + * Afterwards the internal method optimizeGraph() is called that constitutes the innerloop. + * - The inner loop calls the solver (g2o framework, resp. sparse Levenberg-Marquardt) and iterates a specified + * number of optimization calls (\c iterations_innerloop). + * + * The outer loop is repeated \c iterations_outerloop times. \n + * The ratio of inner and outer loop iterations significantly defines the contraction behavior + * and convergence rate of the trajectory optimization. Based on our experiences, 2-6 innerloop iterations are sufficient. \n + * The number of outer loop iterations should be determined by considering the maximum CPU time required to match the control rate. \n + * Optionally, the cost vector can be calculated by specifying \c compute_cost_afterwards, see computeCurrentCost(). + * @remarks This method is usually called from a plan() method + * @param iterations_innerloop Number of iterations for the actual solver loop + * @param iterations_outerloop Specifies how often the trajectory should be resized followed by the inner solver loop. + * @param compute_cost_afterwards if \c true Calculate the cost vector according to computeCurrentCost(), + * the vector can be accessed afterwards using getCurrentCost(). + * @param obst_cost_scale Specify extra scaling for obstacle costs (only used if \c compute_cost_afterwards is true) + * @param viapoint_cost_scale Specify extra scaling for via-point costs (only used if \c compute_cost_afterwards is true) + * @param alternative_time_cost Replace the cost for the time optimal objective by the actual (weighted) transition time + * (only used if \c compute_cost_afterwards is true). + * @return \c true if the optimization terminates successfully, \c false otherwise + */ + bool optimizeTEB(int iterations_innerloop, int iterations_outerloop, bool compute_cost_afterwards = false, + double obst_cost_scale=1.0, double viapoint_cost_scale=1.0, bool alternative_time_cost=false); + + //@} + + + /** @name Desired initial and final velocity */ + //@{ + + + /** + * @brief Set the initial velocity at the trajectory's start pose (e.g. the robot's velocity) [twist overload]. + * @remarks Calling this function is not neccessary if the initial velocity is passed via the plan() method + * @param vel_start Current start velocity (e.g. the velocity of the robot, only linear.x and angular.z are used, + * for holonomic robots also linear.y) + */ + void setVelocityStart(const geometry_msgs::Twist& vel_start); + + /** + * @brief Set the desired final velocity at the trajectory's goal pose. + * @remarks Call this function only if a non-zero velocity is desired and if \c free_goal_vel is set to \c false in plan() + * @param vel_goal twist message containing the translational and angular final velocity + */ + void setVelocityGoal(const geometry_msgs::Twist& vel_goal); + + /** + * @brief Set the desired final velocity at the trajectory's goal pose to be the maximum velocity limit + * @remarks Calling this function is not neccessary if \c free_goal_vel is set to \c false in plan() + */ + void setVelocityGoalFree() {vel_goal_.first = false;} + + //@} + + + /** @name Take obstacles into account */ + //@{ + + + /** + * @brief Assign a new set of obstacles + * @param obst_vector pointer to an obstacle container (can also be a nullptr) + * @remarks This method overrids the obstacle container optinally assigned in the constructor. + */ + void setObstVector(ObstContainer* obst_vector) {obstacles_ = obst_vector;} + + /** + * @brief Access the internal obstacle container. + * @return Const reference to the obstacle container + */ + const ObstContainer& getObstVector() const {return *obstacles_;} + + //@} + + /** @name Take via-points into account */ + //@{ + + + /** + * @brief Assign a new set of via-points + * @param via_points pointer to a via_point container (can also be a nullptr) + * @details Any previously set container will be overwritten. + */ + void setViaPoints(const ViaPointContainer* via_points) {via_points_ = via_points;} + + /** + * @brief Access the internal via-point container. + * @return Const reference to the via-point container + */ + const ViaPointContainer& getViaPoints() const {return *via_points_;} + + //@} + + + /** @name Visualization */ + //@{ + + /** + * @brief Register a TebVisualization class to enable visiualization routines (e.g. publish the local plan and pose sequence) + * @param visualization shared pointer to a TebVisualization instance + * @see visualize + */ + void setVisualization(TebVisualizationPtr visualization); + + /** + * @brief Publish the local plan and pose sequence via ros topics (e.g. subscribe with rviz). + * + * Make sure to register a TebVisualization instance before using setVisualization() or an overlaoded constructor. + * @see setVisualization + */ + virtual void visualize(); + + //@} + + + /** @name Utility methods and more */ + //@{ + + /** + * @brief Reset the planner by clearing the internal graph and trajectory. + */ + virtual void clearPlanner() + { + clearGraph(); + teb_.clearTimedElasticBand(); + } + + /** + * @brief Prefer a desired initial turning direction (by penalizing the opposing one) + * + * A desired (initial) turning direction might be specified in case the planned trajectory oscillates between two + * solutions (in the same equivalence class!) with similar cost. Check the parameters in order to adjust the weight of the penalty. + * Initial means that the penalty is applied only to the first few poses of the trajectory. + * @param dir This parameter might be RotType::left (prefer left), RotType::right (prefer right) or RotType::none (prefer none) + */ + virtual void setPreferredTurningDir(RotType dir) {prefer_rotdir_=dir;} + + /** + * @brief Register the vertices and edges defined for the TEB to the g2o::Factory. + * + * This allows the user to export the internal graph to a text file for instance. + * Access the optimizer() for more details. + */ + static void registerG2OTypes(); + + /** + * @brief Access the internal TimedElasticBand trajectory. + * @warning In general, the underlying teb must not be modified directly. Use with care... + * @return reference to the teb + */ + TimedElasticBand& teb() {return teb_;}; + + /** + * @brief Access the internal TimedElasticBand trajectory (read-only). + * @return const reference to the teb + */ + const TimedElasticBand& teb() const {return teb_;}; + + /** + * @brief Access the internal g2o optimizer. + * @warning In general, the underlying optimizer must not be modified directly. Use with care... + * @return const shared pointer to the g2o sparse optimizer + */ + boost::shared_ptr optimizer() {return optimizer_;}; + + /** + * @brief Access the internal g2o optimizer (read-only). + * @return const shared pointer to the g2o sparse optimizer + */ + boost::shared_ptr optimizer() const {return optimizer_;}; + + /** + * @brief Check if last optimization was successful + * @return \c true if the last optimization returned without errors, + * otherwise \c false (also if no optimization has been called before). + */ + bool isOptimized() const {return optimized_;}; + + /** + * @brief Returns true if the planner has diverged. + */ + bool hasDiverged() const override; + + /** + * @brief Compute the cost vector of a given optimization problen (hyper-graph must exist). + * + * Use this method to obtain information about the current edge errors / costs (local cost functions). \n + * The vector of cost values is composed according to the different edge types (time_optimal, obstacles, ...). \n + * Refer to the method declaration for the detailed composition. \n + * The cost for the edges that minimize time differences (EdgeTimeOptimal) corresponds to the sum of all single + * squared time differneces: \f$ \sum_i \Delta T_i^2 \f$. Sometimes, the user may want to get a value that is proportional + * or identical to the actual trajectory transition time \f$ \sum_i \Delta T_i \f$. \n + * Set \c alternative_time_cost to true in order to get the cost calculated using the latter equation, but check the + * implemented definition, if the value is scaled to match the magnitude of other cost values. + * + * @todo Remove the scaling term for the alternative time cost. + * @todo Can we use the last error (chi2) calculated from g2o instead of calculating it by ourself? + * @see getCurrentCost + * @see optimizeTEB + * @param obst_cost_scale Specify extra scaling for obstacle costs. + * @param viapoint_cost_scale Specify extra scaling for via points. + * @param alternative_time_cost Replace the cost for the time optimal objective by the actual (weighted) transition time. + * @return TebCostVec containing the cost values + */ + void computeCurrentCost(double obst_cost_scale=1.0, double viapoint_cost_scale=1.0, bool alternative_time_cost=false); + + /** + * Compute and return the cost of the current optimization graph (supports multiple trajectories) + * @param[out] cost current cost value for each trajectory + * [for a planner with just a single trajectory: size=1, vector will not be cleared] + * @param obst_cost_scale Specify extra scaling for obstacle costs + * @param viapoint_cost_scale Specify extra scaling for via points. + * @param alternative_time_cost Replace the cost for the time optimal objective by the actual (weighted) transition time + */ + virtual void computeCurrentCost(std::vector& cost, double obst_cost_scale=1.0, double viapoint_cost_scale=1.0, bool alternative_time_cost=false) + { + computeCurrentCost(obst_cost_scale, viapoint_cost_scale, alternative_time_cost); + cost.push_back( getCurrentCost() ); + } + + /** + * @brief Access the cost vector. + * + * The accumulated cost value previously calculated using computeCurrentCost + * or by calling optimizeTEB with enabled cost flag. + * @return const reference to the TebCostVec. + */ + double getCurrentCost() const {return cost_;} + + + /** + * @brief Extract the velocity from consecutive poses and a time difference (including strafing velocity for holonomic robots) + * + * The velocity is extracted using finite differences. + * The direction of the translational velocity is also determined. + * @param pose1 pose at time k + * @param pose2 consecutive pose at time k+1 + * @param dt actual time difference between k and k+1 (must be >0 !!!) + * @param[out] vx translational velocity + * @param[out] vy strafing velocity which can be nonzero for holonomic robots + * @param[out] omega rotational velocity + */ + inline void extractVelocity(const PoseSE2& pose1, const PoseSE2& pose2, double dt, double& vx, double& vy, double& omega) const; + + /** + * @brief Compute the velocity profile of the trajectory + * + * This method computes the translational and rotational velocity for the complete + * planned trajectory. + * The first velocity is the one that is provided as initial velocity (fixed). + * Velocities at index k=2...end-1 are related to the transition from pose_{k-1} to pose_k. + * The last velocity is the final velocity (fixed). + * The number of Twist objects is therefore sizePoses()+1; + * In summary: + * v[0] = v_start, + * v[1,...end-1] = +-(pose_{k+1}-pose{k})/dt, + * v(end) = v_goal + * It can be used for evaluation and debugging purposes or + * for open-loop control. For computing the velocity required for controlling the robot + * to the next step refer to getVelocityCommand(). + * @param[out] velocity_profile velocity profile will be written to this vector (after clearing any existing content) with the size=no_poses+1 + */ + void getVelocityProfile(std::vector& velocity_profile) const; + + /** + * @brief Return the complete trajectory including poses, velocity profiles and temporal information + * + * It is useful for evaluation and debugging purposes or for open-loop control. + * Since the velocity obtained using difference quotients is the mean velocity between consecutive poses, + * the velocity at each pose at time stamp k is obtained by taking the average between both velocities. + * The velocity of the first pose is v_start (provided initial value) and the last one is v_goal (usually zero, if free_goal_vel is off). + * See getVelocityProfile() for the list of velocities between consecutive points. + * @todo The acceleration profile is not added at the moment. + * @param[out] trajectory the resulting trajectory + */ + void getFullTrajectory(std::vector& trajectory) const; + + /** + * @brief Check whether the planned trajectory is feasible or not. + * + * This method currently checks only that the trajectory, or a part of the trajectory is collision free. + * Obstacles are here represented as costmap instead of the internal ObstacleContainer. + * @param costmap_model Pointer to the costmap model + * @param footprint_spec The specification of the footprint of the robot in world coordinates + * @param inscribed_radius The radius of the inscribed circle of the robot + * @param circumscribed_radius The radius of the circumscribed circle of the robot + * @param look_ahead_idx Number of poses along the trajectory that should be verified, if -1, the complete trajectory will be checked. + * @return \c true, if the robot footprint along the first part of the trajectory intersects with + * any obstacle in the costmap, \c false otherwise. + */ + virtual bool isTrajectoryFeasible(base_local_planner::CostmapModel* costmap_model, const std::vector& footprint_spec, double inscribed_radius = 0.0, + double circumscribed_radius=0.0, int look_ahead_idx=-1, double feasibility_check_lookahead_distance=-1.0); + + //@} + +protected: + + /** @name Hyper-Graph creation and optimization */ + //@{ + + /** + * @brief Build the hyper-graph representing the TEB optimization problem. + * + * This method creates the optimization problem according to the hyper-graph formulation. \n + * For more details refer to the literature cited in the TebOptimalPlanner class description. + * @see optimizeGraph + * @see clearGraph + * @param weight_multiplier Specify a weight multipler for selected weights in optimizeGraph + * This might be used for weight adapation strategies. + * Currently, only obstacle collision weights are considered. + * @return \c true, if the graph was created successfully, \c false otherwise. + */ + bool buildGraph(double weight_multiplier=1.0); + + /** + * @brief Optimize the previously constructed hyper-graph to deform / optimize the TEB. + * + * This method invokes the g2o framework to solve the optimization problem considering dedicated sparsity patterns. \n + * The current implementation calls a non-constrained sparse Levenberg-Marquardt algorithm. Constraints are considered + * by utilizing penalty approximations. Refer to the literature cited in the TebOptimalPlanner class description. + * @see buildGraph + * @see clearGraph + * @param no_iterations Number of solver iterations + * @param clear_after Clear the graph after optimization. + * @return \c true, if optimization terminates successfully, \c false otherwise. + */ + bool optimizeGraph(int no_iterations, bool clear_after=true); + + /** + * @brief Clear an existing internal hyper-graph. + * @see buildGraph + * @see optimizeGraph + */ + void clearGraph(); + + /** + * @brief Add all relevant vertices to the hyper-graph as optimizable variables. + * + * Vertices (if unfixed) represent the variables that will be optimized. \n + * In case of the Timed-Elastic-Band poses and time differences form the vertices of the hyper-graph. \n + * The order of insertion of vertices (to the graph) is important for efficiency, + * since it affect the sparsity pattern of the underlying hessian computed for optimization. + * @see VertexPose + * @see VertexTimeDiff + * @see buildGraph + * @see optimizeGraph + */ + void AddTEBVertices(); + + /** + * @brief Add all edges (local cost functions) for limiting the translational and angular velocity. + * @see EdgeVelocity + * @see buildGraph + * @see optimizeGraph + */ + void AddEdgesVelocity(); + + /** + * @brief Add all edges (local cost functions) for limiting the translational and angular acceleration. + * @see EdgeAcceleration + * @see EdgeAccelerationStart + * @see EdgeAccelerationGoal + * @see buildGraph + * @see optimizeGraph + */ + void AddEdgesAcceleration(); + + /** + * @brief Add all edges (local cost functions) for minimizing the transition time (resp. minimize time differences) + * @see EdgeTimeOptimal + * @see buildGraph + * @see optimizeGraph + */ + void AddEdgesTimeOptimal(); + + /** + * @brief Add all edges (local cost functions) for minimizing the path length + * @see EdgeShortestPath + * @see buildGraph + * @see optimizeGraph + */ + void AddEdgesShortestPath(); + + /** + * @brief Add all edges (local cost functions) related to keeping a distance from static obstacles + * @warning do not combine with AddEdgesInflatedObstacles + * @see EdgeObstacle + * @see buildGraph + * @see optimizeGraph + * @param weight_multiplier Specify an additional weight multipler (in addition to the the config weight) + */ + void AddEdgesObstacles(double weight_multiplier=1.0); + + /** + * @brief Add all edges (local cost functions) related to keeping a distance from static obstacles (legacy association strategy) + * @see EdgeObstacle + * @see buildGraph + * @see optimizeGraph + * @param weight_multiplier Specify an additional weight multipler (in addition to the the config weight) + */ + void AddEdgesObstaclesLegacy(double weight_multiplier=1.0); + + /** + * @brief Add all edges (local cost functions) related to minimizing the distance to via-points + * @see EdgeViaPoint + * @see buildGraph + * @see optimizeGraph + */ + void AddEdgesViaPoints(); + + /** + * @brief Add all edges (local cost functions) related to keeping a distance from dynamic (moving) obstacles. + * @warning experimental + * @todo Should we also add neighbors to decrease jiggling/oscillations + * @see EdgeDynamicObstacle + * @see buildGraph + * @see optimizeGraph + * @param weight_multiplier Specify an additional weight multipler (in addition to the the config weight) + + */ + void AddEdgesDynamicObstacles(double weight_multiplier=1.0); + + /** + * @brief Add all edges (local cost functions) for satisfying kinematic constraints of a differential drive robot + * @warning do not combine with AddEdgesKinematicsCarlike() + * @see AddEdgesKinematicsCarlike + * @see buildGraph + * @see optimizeGraph + */ + void AddEdgesKinematicsDiffDrive(); + + /** + * @brief Add all edges (local cost functions) for satisfying kinematic constraints of a carlike robot + * @warning do not combine with AddEdgesKinematicsDiffDrive() + * @see AddEdgesKinematicsDiffDrive + * @see buildGraph + * @see optimizeGraph + */ + void AddEdgesKinematicsCarlike(); + + /** + * @brief Add all edges (local cost functions) for prefering a specifiy turning direction (by penalizing the other one) + * @see buildGraph + * @see optimizeGraph + */ + void AddEdgesPreferRotDir(); + + /** + * @brief Add all edges (local cost function) for reducing the velocity of a vertex due to its associated obstacles + * @see buildGraph + * @see optimizeGraph + */ + void AddEdgesVelocityObstacleRatio(); + + //@} + + + /** + * @brief Initialize and configure the g2o sparse optimizer. + * @return shared pointer to the g2o::SparseOptimizer instance + */ + boost::shared_ptr initOptimizer(); + + + // external objects (store weak pointers) + const TebConfig* cfg_; //!< Config class that stores and manages all related parameters + ObstContainer* obstacles_; //!< Store obstacles that are relevant for planning + const ViaPointContainer* via_points_; //!< Store via points for planning + std::vector obstacles_per_vertex_; //!< Store the obstacles associated with the n-1 initial vertices + + double cost_; //!< Store cost value of the current hyper-graph + RotType prefer_rotdir_; //!< Store whether to prefer a specific initial rotation in optimization (might be activated in case the robot oscillates) + + // internal objects (memory management owned) + TebVisualizationPtr visualization_; //!< Instance of the visualization class + TimedElasticBand teb_; //!< Actual trajectory object + RobotFootprintModelPtr robot_model_; //!< Robot model + boost::shared_ptr optimizer_; //!< g2o optimizer for trajectory optimization + std::pair vel_start_; //!< Store the initial velocity at the start pose + std::pair vel_goal_; //!< Store the final velocity at the goal pose + + bool initialized_; //!< Keeps track about the correct initialization of this class + bool optimized_; //!< This variable is \c true as long as the last optimization has been completed successful + +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +}; + +//! Abbrev. for shared instances of the TebOptimalPlanner +typedef boost::shared_ptr TebOptimalPlannerPtr; +//! Abbrev. for shared const TebOptimalPlanner pointers +typedef boost::shared_ptr TebOptimalPlannerConstPtr; +//! Abbrev. for containers storing multiple teb optimal planners +typedef std::vector< TebOptimalPlannerPtr > TebOptPlannerContainer; + +} // namespace teb_local_planner + +#endif /* OPTIMAL_PLANNER_H_ */ diff --git a/navigations/teb_local_planner/include/teb_local_planner/planner_interface.h b/navigations/teb_local_planner/include/teb_local_planner/planner_interface.h new file mode 100755 index 0000000..e1a1366 --- /dev/null +++ b/navigations/teb_local_planner/include/teb_local_planner/planner_interface.h @@ -0,0 +1,208 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2016, + * TU Dortmund - Institute of Control Theory and Systems Engineering. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the institute nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: Christoph Rösmann + *********************************************************************/ + +#ifndef PLANNER_INTERFACE_H_ +#define PLANNER_INTERFACE_H_ + +// boost +#include + +// ros +#include +#include + +// this package +#include +#include + +// messages +#include +#include +#include + + +namespace teb_local_planner +{ + + +/** + * @class PlannerInterface + * @brief This abstract class defines an interface for local planners + */ +class PlannerInterface +{ +public: + + /** + * @brief Default constructor + */ + PlannerInterface() + { + } + /** + * @brief Virtual destructor. + */ + virtual ~PlannerInterface() + { + } + + + /** @name Plan a trajectory */ + //@{ + + /** + * @brief Plan a trajectory based on an initial reference plan. + * + * Provide this method to create and optimize a trajectory that is initialized + * according to an initial reference plan (given as a container of poses). + * @param initial_plan vector of geometry_msgs::PoseStamped + * @param start_vel Current start velocity (e.g. the velocity of the robot, only linear.x and angular.z are used) + * @param free_goal_vel if \c true, a nonzero final velocity at the goal pose is allowed, + * otherwise the final velocity will be zero (default: false) + * @return \c true if planning was successful, \c false otherwise + */ + virtual bool plan(const std::vector& initial_plan, const geometry_msgs::Twist* start_vel = NULL, bool free_goal_vel=false) = 0; + + /** + * @brief Plan a trajectory between a given start and goal pose (tf::Pose version). + * + * Provide this method to create and optimize a trajectory that is initialized between a given start and goal pose. + * @param start tf::Pose containing the start pose of the trajectory + * @param goal tf::Pose containing the goal pose of the trajectory + * @param start_vel Current start velocity (e.g. the velocity of the robot, only linear.x and angular.z are used) + * @param free_goal_vel if \c true, a nonzero final velocity at the goal pose is allowed, + * otherwise the final velocity will be zero (default: false) + * @return \c true if planning was successful, \c false otherwise + */ + virtual bool plan(const tf::Pose& start, const tf::Pose& goal, const geometry_msgs::Twist* start_vel = NULL, bool free_goal_vel=false) = 0; + + /** + * @brief Plan a trajectory between a given start and goal pose. + * + * Provide this method to create and optimize a trajectory that is initialized between a given start and goal pose. + * @param start PoseSE2 containing the start pose of the trajectory + * @param goal PoseSE2 containing the goal pose of the trajectory + * @param start_vel Initial velocity at the start pose (twist msg containing the translational and angular velocity). + * @param free_goal_vel if \c true, a nonzero final velocity at the goal pose is allowed, + * otherwise the final velocity will be zero (default: false) + * @return \c true if planning was successful, \c false otherwise + */ + virtual bool plan(const PoseSE2& start, const PoseSE2& goal, const geometry_msgs::Twist* start_vel = NULL, bool free_goal_vel=false) = 0; + + /** + * @brief Get the velocity command from a previously optimized plan to control the robot at the current sampling interval. + * @warning Call plan() first and check if the generated plan is feasible. + * @param[out] vx translational velocity [m/s] + * @param[out] vy strafing velocity which can be nonzero for holonomic robots [m/s] + * @param[out] omega rotational velocity [rad/s] + * @param[in] look_ahead_poses index of the final pose used to compute the velocity command. + * @return \c true if command is valid, \c false otherwise + */ + virtual bool getVelocityCommand(double& vx, double& vy, double& omega, int look_ahead_poses) const = 0; + + //@} + + + /** + * @brief Reset the planner. + */ + virtual void clearPlanner() = 0; + + /** + * @brief Prefer a desired initial turning direction (by penalizing the opposing one) + * + * A desired (initial) turning direction might be specified in case the planned trajectory oscillates between two + * solutions (in the same equivalence class!) with similar cost. Check the parameters in order to adjust the weight of the penalty. + * Initial means that the penalty is applied only to the first few poses of the trajectory. + * @param dir This parameter might be RotType::left (prefer left), RotType::right (prefer right) or RotType::none (prefer none) + */ + virtual void setPreferredTurningDir(RotType dir) {ROS_WARN("setPreferredTurningDir() not implemented for this planner.");} + + /** + * @brief Visualize planner specific stuff. + * Overwrite this method to provide an interface to perform all planner related visualizations at once. + */ + virtual void visualize() + { + } + + virtual void updateRobotModel(RobotFootprintModelPtr robot_model) + { + } + + /** + * @brief Check whether the planned trajectory is feasible or not. + * + * This method currently checks only that the trajectory, or a part of the trajectory is collision free. + * Obstacles are here represented as costmap instead of the internal ObstacleContainer. + * @param costmap_model Pointer to the costmap model + * @param footprint_spec The specification of the footprint of the robot in world coordinates + * @param inscribed_radius The radius of the inscribed circle of the robot + * @param circumscribed_radius The radius of the circumscribed circle of the robot + * @param look_ahead_idx Number of poses along the trajectory that should be verified, if -1, the complete trajectory will be checked. + * @return \c true, if the robot footprint along the first part of the trajectory intersects with + * any obstacle in the costmap, \c false otherwise. + */ + virtual bool isTrajectoryFeasible(base_local_planner::CostmapModel* costmap_model, const std::vector& footprint_spec, + double inscribed_radius = 0.0, double circumscribed_radius=0.0, int look_ahead_idx=-1, double feasibility_check_lookahead_distance=-1.0) = 0; + + /** + * Compute and return the cost of the current optimization graph (supports multiple trajectories) + * @param[out] cost current cost value for each trajectory + * [for a planner with just a single trajectory: size=1, vector will not be cleared] + * @param obst_cost_scale Specify extra scaling for obstacle costs + * @param alternative_time_cost Replace the cost for the time optimal objective by the actual (weighted) transition time + */ + virtual void computeCurrentCost(std::vector& cost, double obst_cost_scale=1.0, bool alternative_time_cost=false) + { + } + + /** + * @brief Returns true if the planner has diverged. + */ + virtual bool hasDiverged() const = 0; + +}; + +//! Abbrev. for shared instances of PlannerInterface or it's subclasses +typedef boost::shared_ptr PlannerInterfacePtr; + + +} // namespace teb_local_planner + +#endif /* PLANNER_INTERFACE_H__ */ diff --git a/navigations/teb_local_planner/include/teb_local_planner/pose_se2.h b/navigations/teb_local_planner/include/teb_local_planner/pose_se2.h new file mode 100755 index 0000000..8b4272f --- /dev/null +++ b/navigations/teb_local_planner/include/teb_local_planner/pose_se2.h @@ -0,0 +1,406 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2016, + * TU Dortmund - Institute of Control Theory and Systems Engineering. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the institute nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: Christoph Rösmann + *********************************************************************/ + +#ifndef POSE_SE2_H_ +#define POSE_SE2_H_ + +#include + +#include +#include +#include +#include + +namespace teb_local_planner +{ + +/** + * @class PoseSE2 + * @brief This class implements a pose in the domain SE2: \f$ \mathbb{R}^2 \times S^1 \f$ + * The pose consist of the position x and y and an orientation given as angle theta [-pi, pi]. + */ +class PoseSE2 +{ +public: + + /** @name Construct PoseSE2 instances */ + ///@{ + + /** + * @brief Default constructor + */ + PoseSE2() + { + setZero(); + } + + /** + * @brief Construct pose given a position vector and an angle theta + * @param position 2D position vector + * @param theta angle given in rad + */ + PoseSE2(const Eigen::Ref& position, double theta) + { + _position = position; + _theta = theta; + } + + /** + * @brief Construct pose using single components x, y, and the yaw angle + * @param x x-coordinate + * @param y y-coordinate + * @param theta yaw angle in rad + */ + PoseSE2(double x, double y, double theta) + { + _position.coeffRef(0) = x; + _position.coeffRef(1) = y; + _theta = theta; + } + + /** + * @brief Construct pose using a geometry_msgs::Pose + * @param pose geometry_msgs::Pose object + */ + PoseSE2(const geometry_msgs::Pose& pose) + { + _position.coeffRef(0) = pose.position.x; + _position.coeffRef(1) = pose.position.y; + _theta = tf::getYaw( pose.orientation ); + } + + /** + * @brief Construct pose using a tf::Pose + * @param pose tf::Pose object + */ + PoseSE2(const tf::Pose& pose) + { + _position.coeffRef(0) = pose.getOrigin().getX(); + _position.coeffRef(1) = pose.getOrigin().getY(); + _theta = tf::getYaw( pose.getRotation() ); + } + + /** + * @brief Copy constructor + * @param pose PoseSE2 instance + */ + PoseSE2(const PoseSE2& pose) + { + _position = pose._position; + _theta = pose._theta; + } + + ///@} + + + /** + * @brief Destructs the PoseSE2 + */ + ~PoseSE2() {} + + + /** @name Access and modify values */ + ///@{ + + /** + * @brief Access the 2D position part + * @see estimate + * @return reference to the 2D position part + */ + Eigen::Vector2d& position() {return _position;} + + /** + * @brief Access the 2D position part (read-only) + * @see estimate + * @return const reference to the 2D position part + */ + const Eigen::Vector2d& position() const {return _position;} + + /** + * @brief Access the x-coordinate the pose + * @return reference to the x-coordinate + */ + double& x() {return _position.coeffRef(0);} + + /** + * @brief Access the x-coordinate the pose (read-only) + * @return const reference to the x-coordinate + */ + const double& x() const {return _position.coeffRef(0);} + + /** + * @brief Access the y-coordinate the pose + * @return reference to the y-coordinate + */ + double& y() {return _position.coeffRef(1);} + + /** + * @brief Access the y-coordinate the pose (read-only) + * @return const reference to the y-coordinate + */ + const double& y() const {return _position.coeffRef(1);} + + /** + * @brief Access the orientation part (yaw angle) of the pose + * @return reference to the yaw angle + */ + double& theta() {return _theta;} + + /** + * @brief Access the orientation part (yaw angle) of the pose (read-only) + * @return const reference to the yaw angle + */ + const double& theta() const {return _theta;} + + /** + * @brief Set pose to [0,0,0] + */ + void setZero() + { + _position.setZero(); + _theta = 0; + } + + /** + * @brief Convert PoseSE2 to a geometry_msgs::Pose + * @param[out] pose Pose message + */ + void toPoseMsg(geometry_msgs::Pose& pose) const + { + pose.position.x = _position.x(); + pose.position.y = _position.y(); + pose.position.z = 0; + pose.orientation = tf::createQuaternionMsgFromYaw(_theta); + } + + /** + * @brief Return the unit vector of the current orientation + * @returns [cos(theta), sin(theta))]^T + */ + Eigen::Vector2d orientationUnitVec() const {return Eigen::Vector2d(std::cos(_theta), std::sin(_theta));} + + ///@} + + + /** @name Arithmetic operations for which operators are not always reasonable */ + ///@{ + + /** + * @brief Scale all SE2 components (x,y,theta) and normalize theta afterwards to [-pi, pi] + * @param factor scale factor + */ + void scale(double factor) + { + _position *= factor; + _theta = g2o::normalize_theta( _theta*factor ); + } + + /** + * @brief Increment the pose by adding a double[3] array + * The angle is normalized afterwards + * @param pose_as_array 3D double array [x, y, theta] + */ + void plus(const double* pose_as_array) + { + _position.coeffRef(0) += pose_as_array[0]; + _position.coeffRef(1) += pose_as_array[1]; + _theta = g2o::normalize_theta( _theta + pose_as_array[2] ); + } + + /** + * @brief Get the mean / average of two poses and store it in the caller class + * For the position part: 0.5*(x1+x2) + * For the angle: take the angle of the mean direction vector + * @param pose1 first pose to consider + * @param pose2 second pose to consider + */ + void averageInPlace(const PoseSE2& pose1, const PoseSE2& pose2) + { + _position = (pose1._position + pose2._position)/2; + _theta = g2o::average_angle(pose1._theta, pose2._theta); + } + + /** + * @brief Get the mean / average of two poses and return the result (static) + * For the position part: 0.5*(x1+x2) + * For the angle: take the angle of the mean direction vector + * @param pose1 first pose to consider + * @param pose2 second pose to consider + * @return mean / average of \c pose1 and \c pose2 + */ + static PoseSE2 average(const PoseSE2& pose1, const PoseSE2& pose2) + { + return PoseSE2( (pose1._position + pose2._position)/2 , g2o::average_angle(pose1._theta, pose2._theta) ); + } + + /** + * @brief Rotate pose globally + * + * Compute [pose_x, pose_y] = Rot(\c angle) * [pose_x, pose_y]. + * if \c adjust_theta, pose_theta is also rotated by \c angle + * @param angle the angle defining the 2d rotation + * @param adjust_theta if \c true, the orientation theta is also rotated + */ + void rotateGlobal(double angle, bool adjust_theta=true) + { + double new_x = std::cos(angle)*_position.x() - std::sin(angle)*_position.y(); + double new_y = std::sin(angle)*_position.x() + std::cos(angle)*_position.y(); + _position.x() = new_x; + _position.y() = new_y; + if (adjust_theta) + _theta = g2o::normalize_theta(_theta+angle); + } + + ///@} + + + /** @name Operator overloads / Allow some arithmetic operations */ + ///@{ + + /** + * @brief Asignment operator + * @param rhs PoseSE2 instance + * @todo exception safe version of the assignment operator + */ + PoseSE2& operator=( const PoseSE2& rhs ) + { + if (&rhs != this) + { + _position = rhs._position; + _theta = rhs._theta; + } + return *this; + } + + /** + * @brief Compound assignment operator (addition) + * @param rhs addend + */ + PoseSE2& operator+=(const PoseSE2& rhs) + { + _position += rhs._position; + _theta = g2o::normalize_theta(_theta + rhs._theta); + return *this; + } + + /** + * @brief Arithmetic operator overload for additions + * @param lhs First addend + * @param rhs Second addend + */ + friend PoseSE2 operator+(PoseSE2 lhs, const PoseSE2& rhs) + { + return lhs += rhs; + } + + /** + * @brief Compound assignment operator (subtraction) + * @param rhs value to subtract + */ + PoseSE2& operator-=(const PoseSE2& rhs) + { + _position -= rhs._position; + _theta = g2o::normalize_theta(_theta - rhs._theta); + return *this; + } + + /** + * @brief Arithmetic operator overload for subtractions + * @param lhs First term + * @param rhs Second term + */ + friend PoseSE2 operator-(PoseSE2 lhs, const PoseSE2& rhs) + { + return lhs -= rhs; + } + + /** + * @brief Multiply pose with scalar and return copy without normalizing theta + * This operator is useful for calculating velocities ... + * @param pose pose to scale + * @param scalar factor to multiply with + * @warning theta is not normalized after multiplying + */ + friend PoseSE2 operator*(PoseSE2 pose, double scalar) + { + pose._position *= scalar; + pose._theta *= scalar; + return pose; + } + + /** + * @brief Multiply pose with scalar and return copy without normalizing theta + * This operator is useful for calculating velocities ... + * @param scalar factor to multiply with + * @param pose pose to scale + * @warning theta is not normalized after multiplying + */ + friend PoseSE2 operator*(double scalar, PoseSE2 pose) + { + pose._position *= scalar; + pose._theta *= scalar; + return pose; + } + + /** + * @brief Output stream operator + * @param stream output stream + * @param pose to be used + */ + friend std::ostream& operator<< (std::ostream& stream, const PoseSE2& pose) + { + stream << "x: " << pose._position[0] << " y: " << pose._position[1] << " theta: " << pose._theta; + return stream; + } + + ///@} + + +private: + + Eigen::Vector2d _position; + double _theta; + +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +}; + + +} // namespace teb_local_planner + +#endif // POSE_SE2_H_ diff --git a/navigations/teb_local_planner/include/teb_local_planner/recovery_behaviors.h b/navigations/teb_local_planner/include/teb_local_planner/recovery_behaviors.h new file mode 100755 index 0000000..c522db9 --- /dev/null +++ b/navigations/teb_local_planner/include/teb_local_planner/recovery_behaviors.h @@ -0,0 +1,134 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2016, + * TU Dortmund - Institute of Control Theory and Systems Engineering. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the institute nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: Christoph Rösmann + *********************************************************************/ + +#ifndef RECOVERY_BEHAVIORS_H__ +#define RECOVERY_BEHAVIORS_H__ + + +#include +#include +#include + +namespace teb_local_planner +{ + + +/** + * @class FailureDetector + * @brief This class implements methods in order to detect if the robot got stucked or is oscillating + * + * The StuckDetector analyzes the last N commanded velocities in order to detect whether the robot + * might got stucked or oscillates between left/right/forward/backwards motions. + */ +class FailureDetector +{ +public: + + /** + * @brief Default constructor + */ + FailureDetector() {} + + /** + * @brief destructor. + */ + ~FailureDetector() {} + + /** + * @brief Set buffer length (measurement history) + * @param length number of measurements to be kept + */ + void setBufferLength(int length) {buffer_.set_capacity(length);} + + /** + * @brief Add a new twist measurement to the internal buffer and compute a new decision + * @param twist geometry_msgs::Twist velocity information + * @param v_max maximum forward translational velocity + * @param v_backwards_max maximum backward translational velocity + * @param omega_max maximum angular velocity + * @param v_eps Threshold for the average normalized linear velocity in (0,1) that must not be exceded (e.g. 0.1) + * @param omega_eps Threshold for the average normalized angular velocity in (0,1) that must not be exceded (e.g. 0.1) + */ + void update(const geometry_msgs::Twist& twist, double v_max, double v_backwards_max, double omega_max, double v_eps, double omega_eps); + + /** + * @brief Check if the robot got stucked + * + * This call does not compute the actual decision, + * since it is computed within each update() invocation. + * @return true if the robot got stucked, false otherwise. + */ + bool isOscillating() const; + + /** + * @brief Clear the current internal state + * + * This call also resets the internal buffer + */ + void clear(); + +protected: + + /** Variables to be monitored */ + struct VelMeasurement + { + double v = 0; + double omega = 0; + }; + + /** + * @brief Detect if the robot got stucked based on the current buffer content + * + * Afterwards the status might be checked using gotStucked(); + * @param v_eps Threshold for the average normalized linear velocity in (0,1) that must not be exceded (e.g. 0.1) + * @param omega_eps Threshold for the average normalized angular velocity in (0,1) that must not be exceded (e.g. 0.1) + * @return true if the robot got stucked, false otherwise + */ + bool detect(double v_eps, double omega_eps); + +private: + + boost::circular_buffer buffer_; //!< Circular buffer to store the last measurements @see setBufferLength + bool oscillating_ = false; //!< Current state: true if robot is oscillating + +}; + + +} // namespace teb_local_planner + +#endif /* RECOVERY_BEHAVIORS_H__ */ diff --git a/navigations/teb_local_planner/include/teb_local_planner/robot_footprint_model.h b/navigations/teb_local_planner/include/teb_local_planner/robot_footprint_model.h new file mode 100755 index 0000000..c280756 --- /dev/null +++ b/navigations/teb_local_planner/include/teb_local_planner/robot_footprint_model.h @@ -0,0 +1,778 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2016, + * TU Dortmund - Institute of Control Theory and Systems Engineering. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the institute nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: Christoph Rösmann + *********************************************************************/ + + +#ifndef ROBOT_FOOTPRINT_MODEL_H +#define ROBOT_FOOTPRINT_MODEL_H + +#include +#include +#include + +namespace teb_local_planner +{ + +/** + * @class BaseRobotFootprintModel + * @brief Abstract class that defines the interface for robot footprint/contour models + * + * The robot model class is currently used in optimization only, since + * taking the navigation stack footprint into account might be + * inefficient. The footprint is only used for checking feasibility. + */ +class BaseRobotFootprintModel +{ +public: + + /** + * @brief Default constructor of the abstract obstacle class + */ + BaseRobotFootprintModel() + { + } + + /** + * @brief Virtual destructor. + */ + virtual ~BaseRobotFootprintModel() + { + } + + + /** + * @brief Calculate the distance between the robot and an obstacle + * @param current_pose Current robot pose + * @param obstacle Pointer to the obstacle + * @return Euclidean distance to the robot + */ + virtual double calculateDistance(const PoseSE2& current_pose, const Obstacle* obstacle) const = 0; + + /** + * @brief Estimate the distance between the robot and the predicted location of an obstacle at time t + * @param current_pose robot pose, from which the distance to the obstacle is estimated + * @param obstacle Pointer to the dynamic obstacle (constant velocity model is assumed) + * @param t time, for which the predicted distance to the obstacle is calculated + * @return Euclidean distance to the robot + */ + virtual double estimateSpatioTemporalDistance(const PoseSE2& current_pose, const Obstacle* obstacle, double t) const = 0; + + /** + * @brief Visualize the robot using a markers + * + * Fill a marker message with all necessary information (type, pose, scale and color). + * The header, namespace, id and marker lifetime will be overwritten. + * @param current_pose Current robot pose + * @param[out] markers container of marker messages describing the robot shape + * @param color Color of the footprint + */ + virtual void visualizeRobot(const PoseSE2& current_pose, std::vector& markers, const std_msgs::ColorRGBA& color) const {} + + + /** + * @brief Compute the inscribed radius of the footprint model + * @return inscribed radius + */ + virtual double getInscribedRadius() = 0; + + + +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +}; + + +//! Abbrev. for shared obstacle pointers +typedef boost::shared_ptr RobotFootprintModelPtr; +//! Abbrev. for shared obstacle const pointers +typedef boost::shared_ptr RobotFootprintModelConstPtr; + + + +/** + * @class PointRobotShape + * @brief Class that defines a point-robot + * + * Instead of using a CircularRobotFootprint this class might + * be utitilzed and the robot radius can be added to the mininum distance + * parameter. This avoids a subtraction of zero each time a distance is calculated. + */ +class PointRobotFootprint : public BaseRobotFootprintModel +{ +public: + + /** + * @brief Default constructor of the abstract obstacle class + */ + PointRobotFootprint() {} + + /** + * @brief Default constructor of the abstract obstacle class + * @param min_obstacle_dist Minimum obstacle distance + */ + PointRobotFootprint(const double min_obstacle_dist) : min_obstacle_dist_(min_obstacle_dist) {} + + /** + * @brief Virtual destructor. + */ + virtual ~PointRobotFootprint() {} + + /** + * @brief Calculate the distance between the robot and an obstacle + * @param current_pose Current robot pose + * @param obstacle Pointer to the obstacle + * @return Euclidean distance to the robot + */ + virtual double calculateDistance(const PoseSE2& current_pose, const Obstacle* obstacle) const + { + return obstacle->getMinimumDistance(current_pose.position()); + } + + /** + * @brief Estimate the distance between the robot and the predicted location of an obstacle at time t + * @param current_pose robot pose, from which the distance to the obstacle is estimated + * @param obstacle Pointer to the dynamic obstacle (constant velocity model is assumed) + * @param t time, for which the predicted distance to the obstacle is calculated + * @return Euclidean distance to the robot + */ + virtual double estimateSpatioTemporalDistance(const PoseSE2& current_pose, const Obstacle* obstacle, double t) const + { + return obstacle->getMinimumSpatioTemporalDistance(current_pose.position(), t); + } + + /** + * @brief Compute the inscribed radius of the footprint model + * @return inscribed radius + */ + virtual double getInscribedRadius() {return 0.0;} + + /** + * @brief Visualize the robot using a markers + * + * Fill a marker message with all necessary information (type, pose, scale and color). + * The header, namespace, id and marker lifetime will be overwritten. + * @param current_pose Current robot pose + * @param[out] markers container of marker messages describing the robot shape + * @param color Color of the footprint + */ + virtual void visualizeRobot(const PoseSE2& current_pose, std::vector& markers, const std_msgs::ColorRGBA& color) const + { + // point footprint + markers.push_back(visualization_msgs::Marker()); + visualization_msgs::Marker& marker = markers.back(); + marker.type = visualization_msgs::Marker::POINTS; + current_pose.toPoseMsg(marker.pose); // all points are transformed into the robot frame! + marker.points.push_back(geometry_msgs::Point()); + marker.scale.x = 0.025; + marker.color = color; + + if (min_obstacle_dist_ <= 0) + { + return; + } + + // footprint with min_obstacle_dist + markers.push_back(visualization_msgs::Marker()); + visualization_msgs::Marker& marker2 = markers.back(); + marker2.type = visualization_msgs::Marker::LINE_STRIP; + marker2.scale.x = 0.025; + marker2.color = color; + current_pose.toPoseMsg(marker2.pose); // all points are transformed into the robot frame! + + const double n = 9; + const double r = min_obstacle_dist_; + for (double theta = 0; theta <= 2 * M_PI; theta += M_PI / n) + { + geometry_msgs::Point pt; + pt.x = r * cos(theta); + pt.y = r * sin(theta); + marker2.points.push_back(pt); + } + } + +private: + const double min_obstacle_dist_ = 0.0; +}; + + +/** + * @class CircularRobotFootprint + * @brief Class that defines the a robot of circular shape + */ +class CircularRobotFootprint : public BaseRobotFootprintModel +{ +public: + + /** + * @brief Default constructor of the abstract obstacle class + * @param radius radius of the robot + */ + CircularRobotFootprint(double radius) : radius_(radius) { } + + /** + * @brief Virtual destructor. + */ + virtual ~CircularRobotFootprint() { } + + /** + * @brief Set radius of the circular robot + * @param radius radius of the robot + */ + void setRadius(double radius) {radius_ = radius;} + + /** + * @brief Calculate the distance between the robot and an obstacle + * @param current_pose Current robot pose + * @param obstacle Pointer to the obstacle + * @return Euclidean distance to the robot + */ + virtual double calculateDistance(const PoseSE2& current_pose, const Obstacle* obstacle) const + { + return obstacle->getMinimumDistance(current_pose.position()) - radius_; + } + + /** + * @brief Estimate the distance between the robot and the predicted location of an obstacle at time t + * @param current_pose robot pose, from which the distance to the obstacle is estimated + * @param obstacle Pointer to the dynamic obstacle (constant velocity model is assumed) + * @param t time, for which the predicted distance to the obstacle is calculated + * @return Euclidean distance to the robot + */ + virtual double estimateSpatioTemporalDistance(const PoseSE2& current_pose, const Obstacle* obstacle, double t) const + { + return obstacle->getMinimumSpatioTemporalDistance(current_pose.position(), t) - radius_; + } + + /** + * @brief Visualize the robot using a markers + * + * Fill a marker message with all necessary information (type, pose, scale and color). + * The header, namespace, id and marker lifetime will be overwritten. + * @param current_pose Current robot pose + * @param[out] markers container of marker messages describing the robot shape + * @param color Color of the footprint + */ + virtual void visualizeRobot(const PoseSE2& current_pose, std::vector& markers, const std_msgs::ColorRGBA& color) const + { + markers.resize(1); + visualization_msgs::Marker& marker = markers.back(); + marker.type = visualization_msgs::Marker::CYLINDER; + current_pose.toPoseMsg(marker.pose); + marker.scale.x = marker.scale.y = 2*radius_; // scale = diameter + marker.scale.z = 0.05; + marker.color = color; + } + + /** + * @brief Compute the inscribed radius of the footprint model + * @return inscribed radius + */ + virtual double getInscribedRadius() {return radius_;} + +private: + + double radius_; +}; + + +/** + * @class TwoCirclesRobotFootprint + * @brief Class that approximates the robot with two shifted circles + */ +class TwoCirclesRobotFootprint : public BaseRobotFootprintModel +{ +public: + + /** + * @brief Default constructor of the abstract obstacle class + * @param front_offset shift the center of the front circle along the robot orientation starting from the center at the rear axis (in meters) + * @param front_radius radius of the front circle + * @param rear_offset shift the center of the rear circle along the opposite robot orientation starting from the center at the rear axis (in meters) + * @param rear_radius radius of the front circle + */ + TwoCirclesRobotFootprint(double front_offset, double front_radius, double rear_offset, double rear_radius) + : front_offset_(front_offset), front_radius_(front_radius), rear_offset_(rear_offset), rear_radius_(rear_radius) { } + + /** + * @brief Virtual destructor. + */ + virtual ~TwoCirclesRobotFootprint() { } + + /** + * @brief Set parameters of the contour/footprint + * @param front_offset shift the center of the front circle along the robot orientation starting from the center at the rear axis (in meters) + * @param front_radius radius of the front circle + * @param rear_offset shift the center of the rear circle along the opposite robot orientation starting from the center at the rear axis (in meters) + * @param rear_radius radius of the front circle + */ + void setParameters(double front_offset, double front_radius, double rear_offset, double rear_radius) + {front_offset_=front_offset; front_radius_=front_radius; rear_offset_=rear_offset; rear_radius_=rear_radius;} + + /** + * @brief Calculate the distance between the robot and an obstacle + * @param current_pose Current robot pose + * @param obstacle Pointer to the obstacle + * @return Euclidean distance to the robot + */ + virtual double calculateDistance(const PoseSE2& current_pose, const Obstacle* obstacle) const + { + Eigen::Vector2d dir = current_pose.orientationUnitVec(); + double dist_front = obstacle->getMinimumDistance(current_pose.position() + front_offset_*dir) - front_radius_; + double dist_rear = obstacle->getMinimumDistance(current_pose.position() - rear_offset_*dir) - rear_radius_; + return std::min(dist_front, dist_rear); + } + + /** + * @brief Estimate the distance between the robot and the predicted location of an obstacle at time t + * @param current_pose robot pose, from which the distance to the obstacle is estimated + * @param obstacle Pointer to the dynamic obstacle (constant velocity model is assumed) + * @param t time, for which the predicted distance to the obstacle is calculated + * @return Euclidean distance to the robot + */ + virtual double estimateSpatioTemporalDistance(const PoseSE2& current_pose, const Obstacle* obstacle, double t) const + { + Eigen::Vector2d dir = current_pose.orientationUnitVec(); + double dist_front = obstacle->getMinimumSpatioTemporalDistance(current_pose.position() + front_offset_*dir, t) - front_radius_; + double dist_rear = obstacle->getMinimumSpatioTemporalDistance(current_pose.position() - rear_offset_*dir, t) - rear_radius_; + return std::min(dist_front, dist_rear); + } + + /** + * @brief Visualize the robot using a markers + * + * Fill a marker message with all necessary information (type, pose, scale and color). + * The header, namespace, id and marker lifetime will be overwritten. + * @param current_pose Current robot pose + * @param[out] markers container of marker messages describing the robot shape + * @param color Color of the footprint + */ + virtual void visualizeRobot(const PoseSE2& current_pose, std::vector& markers, const std_msgs::ColorRGBA& color) const + { + Eigen::Vector2d dir = current_pose.orientationUnitVec(); + if (front_radius_>0) + { + markers.push_back(visualization_msgs::Marker()); + visualization_msgs::Marker& marker1 = markers.back(); + marker1.type = visualization_msgs::Marker::CYLINDER; + current_pose.toPoseMsg(marker1.pose); + marker1.pose.position.x += front_offset_*dir.x(); + marker1.pose.position.y += front_offset_*dir.y(); + marker1.scale.x = marker1.scale.y = 2*front_radius_; // scale = diameter +// marker1.scale.z = 0.05; + marker1.color = color; + + } + if (rear_radius_>0) + { + markers.push_back(visualization_msgs::Marker()); + visualization_msgs::Marker& marker2 = markers.back(); + marker2.type = visualization_msgs::Marker::CYLINDER; + current_pose.toPoseMsg(marker2.pose); + marker2.pose.position.x -= rear_offset_*dir.x(); + marker2.pose.position.y -= rear_offset_*dir.y(); + marker2.scale.x = marker2.scale.y = 2*rear_radius_; // scale = diameter +// marker2.scale.z = 0.05; + marker2.color = color; + } + } + + /** + * @brief Compute the inscribed radius of the footprint model + * @return inscribed radius + */ + virtual double getInscribedRadius() + { + double min_longitudinal = std::min(rear_offset_ + rear_radius_, front_offset_ + front_radius_); + double min_lateral = std::min(rear_radius_, front_radius_); + return std::min(min_longitudinal, min_lateral); + } + +private: + + double front_offset_; + double front_radius_; + double rear_offset_; + double rear_radius_; + +}; + + + +/** + * @class LineRobotFootprint + * @brief Class that approximates the robot with line segment (zero-width) + */ +class LineRobotFootprint : public BaseRobotFootprintModel +{ +public: + + /** + * @brief Default constructor of the abstract obstacle class + * @param line_start start coordinates (only x and y) of the line (w.r.t. robot center at (0,0)) + * @param line_end end coordinates (only x and y) of the line (w.r.t. robot center at (0,0)) + */ + LineRobotFootprint(const geometry_msgs::Point& line_start, const geometry_msgs::Point& line_end) + { + setLine(line_start, line_end); + } + + /** + * @brief Default constructor of the abstract obstacle class (Eigen Version) + * @param line_start start coordinates (only x and y) of the line (w.r.t. robot center at (0,0)) + * @param line_end end coordinates (only x and y) of the line (w.r.t. robot center at (0,0)) + */ + LineRobotFootprint(const Eigen::Vector2d& line_start, const Eigen::Vector2d& line_end, const double min_obstacle_dist) : min_obstacle_dist_(min_obstacle_dist) + { + setLine(line_start, line_end); + } + + /** + * @brief Virtual destructor. + */ + virtual ~LineRobotFootprint() { } + + /** + * @brief Set vertices of the contour/footprint + * @param vertices footprint vertices (only x and y) around the robot center (0,0) (do not repeat the first and last vertex at the end) + */ + void setLine(const geometry_msgs::Point& line_start, const geometry_msgs::Point& line_end) + { + line_start_.x() = line_start.x; + line_start_.y() = line_start.y; + line_end_.x() = line_end.x; + line_end_.y() = line_end.y; + } + + /** + * @brief Set vertices of the contour/footprint (Eigen version) + * @param vertices footprint vertices (only x and y) around the robot center (0,0) (do not repeat the first and last vertex at the end) + */ + void setLine(const Eigen::Vector2d& line_start, const Eigen::Vector2d& line_end) + { + line_start_ = line_start; + line_end_ = line_end; + } + + /** + * @brief Calculate the distance between the robot and an obstacle + * @param current_pose Current robot pose + * @param obstacle Pointer to the obstacle + * @return Euclidean distance to the robot + */ + virtual double calculateDistance(const PoseSE2& current_pose, const Obstacle* obstacle) const + { + Eigen::Vector2d line_start_world; + Eigen::Vector2d line_end_world; + transformToWorld(current_pose, line_start_world, line_end_world); + return obstacle->getMinimumDistance(line_start_world, line_end_world); + } + + /** + * @brief Estimate the distance between the robot and the predicted location of an obstacle at time t + * @param current_pose robot pose, from which the distance to the obstacle is estimated + * @param obstacle Pointer to the dynamic obstacle (constant velocity model is assumed) + * @param t time, for which the predicted distance to the obstacle is calculated + * @return Euclidean distance to the robot + */ + virtual double estimateSpatioTemporalDistance(const PoseSE2& current_pose, const Obstacle* obstacle, double t) const + { + Eigen::Vector2d line_start_world; + Eigen::Vector2d line_end_world; + transformToWorld(current_pose, line_start_world, line_end_world); + return obstacle->getMinimumSpatioTemporalDistance(line_start_world, line_end_world, t); + } + + /** + * @brief Visualize the robot using a markers + * + * Fill a marker message with all necessary information (type, pose, scale and color). + * The header, namespace, id and marker lifetime will be overwritten. + * @param current_pose Current robot pose + * @param[out] markers container of marker messages describing the robot shape + * @param color Color of the footprint + */ + virtual void visualizeRobot(const PoseSE2& current_pose, std::vector& markers, const std_msgs::ColorRGBA& color) const + { + markers.push_back(visualization_msgs::Marker()); + visualization_msgs::Marker& marker = markers.back(); + marker.type = visualization_msgs::Marker::LINE_STRIP; + current_pose.toPoseMsg(marker.pose); // all points are transformed into the robot frame! + + // line + geometry_msgs::Point line_start_world; + line_start_world.x = line_start_.x(); + line_start_world.y = line_start_.y(); + line_start_world.z = 0; + marker.points.push_back(line_start_world); + + geometry_msgs::Point line_end_world; + line_end_world.x = line_end_.x(); + line_end_world.y = line_end_.y(); + line_end_world.z = 0; + marker.points.push_back(line_end_world); + + marker.scale.x = 0.025; + marker.color = color; + + if (min_obstacle_dist_ <= 0) + { + return; + } + + // footprint with min_obstacle_dist + markers.push_back(visualization_msgs::Marker()); + visualization_msgs::Marker& marker2 = markers.back(); + marker2.type = visualization_msgs::Marker::LINE_STRIP; + marker2.scale.x = 0.025; + marker2.color = color; + current_pose.toPoseMsg(marker2.pose); // all points are transformed into the robot frame! + + const double n = 9; + const double r = min_obstacle_dist_; + const double ori = atan2(line_end_.y() - line_start_.y(), line_end_.x() - line_start_.x()); + + // first half-circle + for (double theta = M_PI_2 + ori; theta <= 3 * M_PI_2 + ori; theta += M_PI / n) + { + geometry_msgs::Point pt; + pt.x = line_start_.x() + r * cos(theta); + pt.y = line_start_.y() + r * sin(theta); + marker2.points.push_back(pt); + } + + // second half-circle + for (double theta = -M_PI_2 + ori; theta <= M_PI_2 + ori; theta += M_PI / n) + { + geometry_msgs::Point pt; + pt.x = line_end_.x() + r * cos(theta); + pt.y = line_end_.y() + r * sin(theta); + marker2.points.push_back(pt); + } + + // duplicate 1st point to close shape + geometry_msgs::Point pt; + pt.x = line_start_.x() + r * cos(M_PI_2 + ori); + pt.y = line_start_.y() + r * sin(M_PI_2 + ori); + marker2.points.push_back(pt); + } + + /** + * @brief Compute the inscribed radius of the footprint model + * @return inscribed radius + */ + virtual double getInscribedRadius() + { + return 0.0; // lateral distance = 0.0 + } + +private: + + /** + * @brief Transforms a line to the world frame manually + * @param current_pose Current robot pose + * @param[out] line_start line_start_ in the world frame + * @param[out] line_end line_end_ in the world frame + */ + void transformToWorld(const PoseSE2& current_pose, Eigen::Vector2d& line_start_world, Eigen::Vector2d& line_end_world) const + { + double cos_th = std::cos(current_pose.theta()); + double sin_th = std::sin(current_pose.theta()); + line_start_world.x() = current_pose.x() + cos_th * line_start_.x() - sin_th * line_start_.y(); + line_start_world.y() = current_pose.y() + sin_th * line_start_.x() + cos_th * line_start_.y(); + line_end_world.x() = current_pose.x() + cos_th * line_end_.x() - sin_th * line_end_.y(); + line_end_world.y() = current_pose.y() + sin_th * line_end_.x() + cos_th * line_end_.y(); + } + + Eigen::Vector2d line_start_; + Eigen::Vector2d line_end_; + const double min_obstacle_dist_ = 0.0; + +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + +}; + + + +/** + * @class PolygonRobotFootprint + * @brief Class that approximates the robot with a closed polygon + */ +class PolygonRobotFootprint : public BaseRobotFootprintModel +{ +public: + + + + /** + * @brief Default constructor of the abstract obstacle class + * @param vertices footprint vertices (only x and y) around the robot center (0,0) (do not repeat the first and last vertex at the end) + */ + PolygonRobotFootprint(const Point2dContainer& vertices) : vertices_(vertices) { } + + /** + * @brief Virtual destructor. + */ + virtual ~PolygonRobotFootprint() { } + + /** + * @brief Set vertices of the contour/footprint + * @param vertices footprint vertices (only x and y) around the robot center (0,0) (do not repeat the first and last vertex at the end) + */ + void setVertices(const Point2dContainer& vertices) {vertices_ = vertices;} + + /** + * @brief Calculate the distance between the robot and an obstacle + * @param current_pose Current robot pose + * @param obstacle Pointer to the obstacle + * @return Euclidean distance to the robot + */ + virtual double calculateDistance(const PoseSE2& current_pose, const Obstacle* obstacle) const + { + Point2dContainer polygon_world(vertices_.size()); + transformToWorld(current_pose, polygon_world); + return obstacle->getMinimumDistance(polygon_world); + } + + /** + * @brief Estimate the distance between the robot and the predicted location of an obstacle at time t + * @param current_pose robot pose, from which the distance to the obstacle is estimated + * @param obstacle Pointer to the dynamic obstacle (constant velocity model is assumed) + * @param t time, for which the predicted distance to the obstacle is calculated + * @return Euclidean distance to the robot + */ + virtual double estimateSpatioTemporalDistance(const PoseSE2& current_pose, const Obstacle* obstacle, double t) const + { + Point2dContainer polygon_world(vertices_.size()); + transformToWorld(current_pose, polygon_world); + return obstacle->getMinimumSpatioTemporalDistance(polygon_world, t); + } + + /** + * @brief Visualize the robot using a markers + * + * Fill a marker message with all necessary information (type, pose, scale and color). + * The header, namespace, id and marker lifetime will be overwritten. + * @param current_pose Current robot pose + * @param[out] markers container of marker messages describing the robot shape + * @param color Color of the footprint + */ + virtual void visualizeRobot(const PoseSE2& current_pose, std::vector& markers, const std_msgs::ColorRGBA& color) const + { + if (vertices_.empty()) + return; + + markers.push_back(visualization_msgs::Marker()); + visualization_msgs::Marker& marker = markers.back(); + marker.type = visualization_msgs::Marker::LINE_STRIP; + current_pose.toPoseMsg(marker.pose); // all points are transformed into the robot frame! + + for (std::size_t i = 0; i < vertices_.size(); ++i) + { + geometry_msgs::Point point; + point.x = vertices_[i].x(); + point.y = vertices_[i].y(); + point.z = 0; + marker.points.push_back(point); + } + // add first point again in order to close the polygon + geometry_msgs::Point point; + point.x = vertices_.front().x(); + point.y = vertices_.front().y(); + point.z = 0; + marker.points.push_back(point); + + marker.scale.x = 0.025; + marker.color = color; + + } + + /** + * @brief Compute the inscribed radius of the footprint model + * @return inscribed radius + */ + virtual double getInscribedRadius() + { + double min_dist = std::numeric_limits::max(); + Eigen::Vector2d center(0.0, 0.0); + + if (vertices_.size() <= 2) + return 0.0; + + for (int i = 0; i < (int)vertices_.size() - 1; ++i) + { + // compute distance from the robot center point to the first vertex + double vertex_dist = vertices_[i].norm(); + double edge_dist = distance_point_to_segment_2d(center, vertices_[i], vertices_[i+1]); + min_dist = std::min(min_dist, std::min(vertex_dist, edge_dist)); + } + + // we also need to check the last vertex and the first vertex + double vertex_dist = vertices_.back().norm(); + double edge_dist = distance_point_to_segment_2d(center, vertices_.back(), vertices_.front()); + return std::min(min_dist, std::min(vertex_dist, edge_dist)); + } + +private: + + /** + * @brief Transforms a polygon to the world frame manually + * @param current_pose Current robot pose + * @param[out] polygon_world polygon in the world frame + */ + void transformToWorld(const PoseSE2& current_pose, Point2dContainer& polygon_world) const + { + double cos_th = std::cos(current_pose.theta()); + double sin_th = std::sin(current_pose.theta()); + for (std::size_t i=0; i +#include +#include +#include + +#include + + +// Definitions +#define USE_ANALYTIC_JACOBI // if available for a specific edge, use analytic jacobi + + +namespace teb_local_planner +{ + +/** + * @class TebConfig + * @brief Config class for the teb_local_planner and its components. + */ +class TebConfig +{ +public: + + std::string odom_topic; //!< Topic name of the odometry message, provided by the robot driver or simulator + std::string map_frame; //!< Global planning frame + + //! Trajectory related parameters + struct Trajectory + { + double teb_autosize; //!< Enable automatic resizing of the trajectory w.r.t to the temporal resolution (recommended) + double dt_ref; //!< Desired temporal resolution of the trajectory (should be in the magniture of the underlying control rate) + double dt_hysteresis; //!< Hysteresis for automatic resizing depending on the current temporal resolution (dt): usually 10% of dt_ref + int min_samples; //!< Minimum number of samples (should be always greater than 2) + int max_samples; //!< Maximum number of samples; Warning: if too small the discretization/resolution might not be sufficient for the given robot model or obstacle avoidance does not work anymore. + bool global_plan_overwrite_orientation; //!< Overwrite orientation of local subgoals provided by the global planner + bool allow_init_with_backwards_motion; //!< If true, the underlying trajectories might be initialized with backwards motions in case the goal is behind the start within the local costmap (this is only recommended if the robot is equipped with rear sensors) + double global_plan_viapoint_sep; //!< Min. separation between each two consecutive via-points extracted from the global plan (if negative: disabled) + bool via_points_ordered; //!< If true, the planner adheres to the order of via-points in the storage container + double max_global_plan_lookahead_dist; //!< Specify maximum length (cumulative Euclidean distances) of the subset of the global plan taken into account for optimization [if <=0: disabled; the length is also bounded by the local costmap size!] + double global_plan_prune_distance; //!< Distance between robot and via_points of global plan which is used for pruning + bool exact_arc_length; //!< If true, the planner uses the exact arc length in velocity, acceleration and turning rate computations [-> increased cpu time], otherwise the euclidean approximation is used. + double force_reinit_new_goal_dist; //!< Reinitialize the trajectory if a previous goal is updated with a seperation of more than the specified value in meters (skip hot-starting) + double force_reinit_new_goal_angular; //!< Reinitialize the trajectory if a previous goal is updated with an angular difference of more than the specified value in radians (skip hot-starting) + int feasibility_check_no_poses; //!< Specify up to which pose (under the feasibility_check_lookahead_distance) on the predicted plan the feasibility should be checked each sampling interval; if -1, all poses up to feasibility_check_lookahead_distance are checked. + double feasibility_check_lookahead_distance; //!< Specify up to which distance (and with an index below feasibility_check_no_poses) from the robot the feasibility should be checked each sampling interval; if -1, all poses up to feasibility_check_no_poses are checked. + bool publish_feedback; //!< Publish planner feedback containing the full trajectory and a list of active obstacles (should be enabled only for evaluation or debugging purposes) + double min_resolution_collision_check_angular; //! Min angular resolution used during the costmap collision check. If not respected, intermediate samples are added. [rad] + int control_look_ahead_poses; //! Index of the pose used to extract the velocity command + int prevent_look_ahead_poses_near_goal; //! Prevents control_look_ahead_poses to look within this many poses of the goal in order to prevent overshoot & oscillation when xy_goal_tolerance is very small + } trajectory; //!< Trajectory related parameters + + //! Robot related parameters + struct Robot + { + double max_vel_x; //!< Maximum translational velocity of the robot + double max_vel_x_backwards; //!< Maximum translational velocity of the robot for driving backwards + double max_vel_y; //!< Maximum strafing velocity of the robot (should be zero for non-holonomic robots!) + double max_vel_trans; //!< Maximum translational velocity of the robot for omni robots, which is different from max_vel_x + double max_vel_theta; //!< Maximum angular velocity of the robot + double acc_lim_x; //!< Maximum translational acceleration of the robot + double acc_lim_y; //!< Maximum strafing acceleration of the robot + double acc_lim_theta; //!< Maximum angular acceleration of the robot + double min_turning_radius; //!< Minimum turning radius of a carlike robot (diff-drive robot: zero); + double wheelbase; //!< The distance between the drive shaft and steering axle (only required for a carlike robot with 'cmd_angle_instead_rotvel' enabled); The value might be negative for back-wheeled robots! + bool cmd_angle_instead_rotvel; //!< Substitute the rotational velocity in the commanded velocity message by the corresponding steering angle (check 'axles_distance') + bool is_footprint_dynamic; // currently only activated if an oscillation is detected, see 'oscillation_recovery' + + double weight_adapt_factor; //!< Some special weights (currently 'weight_obstacle') are repeatedly scaled by this factor in each outer TEB iteration (weight_new = weight_old*factor); Increasing weights iteratively instead of setting a huge value a-priori leads to better numerical conditions of the underlying optimization problem. + double obstacle_cost_exponent; //!< Exponent for nonlinear obstacle cost (cost = linear_cost * obstacle_cost_exponent). Set to 1 to disable nonlinear cost (default) + } optim; //!< Optimization related parameters + + + struct HomotopyClasses + { + bool enable_homotopy_class_planning; //!< Activate homotopy class planning (Requires much more resources that simple planning, since multiple trajectories are optimized at once). + bool enable_multithreading; //!< Activate multiple threading for planning multiple trajectories in parallel. + bool simple_exploration; //!< If true, distinctive trajectories are explored using a simple left-right approach (pass each obstacle on the left or right side) for path generation, otherwise sample possible roadmaps randomly in a specified region between start and goal. + int max_number_classes; //!< Specify the maximum number of allowed alternative homotopy classes (limits computational effort) + int max_number_plans_in_current_class; //!< Specify the maximum number of trajectories to try that are in the same homotopy class as the current trajectory (helps avoid local minima) + double selection_cost_hysteresis; //!< Specify how much trajectory cost must a new candidate have w.r.t. a previously selected trajectory in order to be selected (selection if new_cost < old_cost*factor). + double selection_prefer_initial_plan; //!< Specify a cost reduction in the interval (0,1) for the trajectory in the equivalence class of the initial plan. + double selection_obst_cost_scale; //!< Extra scaling of obstacle cost terms just for selecting the 'best' candidate. + double selection_viapoint_cost_scale; //!< Extra scaling of via-point cost terms just for selecting the 'best' candidate. + bool selection_alternative_time_cost; //!< If true, time cost is replaced by the total transition time. + double selection_dropping_probability; //!< At each planning cycle, TEBs other than the current 'best' one will be randomly dropped with this probability. Prevents becoming 'fixated' on sub-optimal alternative homotopies. + double switching_blocking_period; //!< Specify a time duration in seconds that needs to be expired before a switch to new equivalence class is allowed + + int roadmap_graph_no_samples; //! < Specify the number of samples generated for creating the roadmap graph, if simple_exploration is turend off. + double roadmap_graph_area_width; //!< Random keypoints/waypoints are sampled in a rectangular region between start and goal. Specify the width of that region in meters. + double roadmap_graph_area_length_scale; //!< The length of the rectangular region is determined by the distance between start and goal. This parameter further scales the distance such that the geometric center remains equal! + double h_signature_prescaler; //!< Scale number of obstacle value in order to allow huge number of obstacles. Do not choose it extremly low, otherwise obstacles cannot be distinguished from each other (0.2 this + } hcp; + + //! Recovery/backup related parameters + struct Recovery + { + bool shrink_horizon_backup; //!< Allows the planner to shrink the horizon temporary (50%) in case of automatically detected issues. + double shrink_horizon_min_duration; //!< Specify minimum duration for the reduced horizon in case an infeasible trajectory is detected. + bool oscillation_recovery; //!< Try to detect and resolve oscillations between multiple solutions in the same equivalence class (robot frequently switches between left/right/forward/backwards) + double oscillation_v_eps; //!< Threshold for the average normalized linear velocity: if oscillation_v_eps and oscillation_omega_eps are not exceeded both, a possible oscillation is detected + double oscillation_omega_eps; //!< Threshold for the average normalized angular velocity: if oscillation_v_eps and oscillation_omega_eps are not exceeded both, a possible oscillation is detected + double oscillation_recovery_min_duration; //!< Minumum duration [sec] for which the recovery mode is activated after an oscillation is detected. + double oscillation_filter_duration; //!< Filter length/duration [sec] for the detection of oscillations + bool divergence_detection_enable; //!< True to enable divergence detection. + int divergence_detection_max_chi_squared; //!< Maximum acceptable Mahalanobis distance above which it is assumed that the optimization diverged. + } recovery; //!< Parameters related to recovery and backup strategies + + + /** + * @brief Construct the TebConfig using default values. + * @warning If the \b rosparam server or/and \b dynamic_reconfigure (rqt_reconfigure) node are used, + * the default variables will be overwritten: \n + * E.g. if \e base_local_planner is utilized as plugin for the navigation stack, the initialize() method will register a + * dynamic_reconfigure server. A subset (not all but most) of the parameters are considered for dynamic modifications. + * All parameters considered by the dynamic_reconfigure server (and their \b default values) are + * set in \e PROJECT_SRC/cfg/TebLocalPlannerReconfigure.cfg. \n + * In addition the rosparam server can be queried to get parameters e.g. defiend in a launch file. + * The plugin source (or a possible binary source) can call loadRosParamFromNodeHandle() to update the parameters. + * In \e summary, default parameters are loaded in the following order (the right one overrides the left ones): \n + * TebConfig Constructor defaults << dynamic_reconfigure defaults << rosparam server defaults + */ + TebConfig() + { + + odom_topic = "odom"; + map_frame = "odom"; + + // Trajectory + + trajectory.teb_autosize = true; + trajectory.dt_ref = 0.3; + trajectory.dt_hysteresis = 0.1; + trajectory.min_samples = 3; + trajectory.max_samples = 500; + trajectory.global_plan_overwrite_orientation = true; + trajectory.allow_init_with_backwards_motion = false; + trajectory.global_plan_viapoint_sep = -1; + trajectory.via_points_ordered = false; + trajectory.max_global_plan_lookahead_dist = 1; + trajectory.global_plan_prune_distance = 1; + trajectory.exact_arc_length = false; + trajectory.force_reinit_new_goal_dist = 1; + trajectory.force_reinit_new_goal_angular = 0.5 * M_PI; + trajectory.feasibility_check_no_poses = 5; + trajectory.feasibility_check_lookahead_distance = -1; + trajectory.publish_feedback = false; + trajectory.min_resolution_collision_check_angular = M_PI; + trajectory.control_look_ahead_poses = 1; + trajectory.prevent_look_ahead_poses_near_goal = 0; + + // Robot + + robot.max_vel_x = 0.4; + robot.max_vel_x_backwards = 0.2; + robot.max_vel_y = 0.0; + robot.max_vel_trans = 0.0; + robot.max_vel_theta = 0.3; + robot.acc_lim_x = 0.5; + robot.acc_lim_y = 0.5; + robot.acc_lim_theta = 0.5; + robot.min_turning_radius = 0; + robot.wheelbase = 1.0; + robot.cmd_angle_instead_rotvel = false; + robot.is_footprint_dynamic = false; + robot.use_proportional_saturation = false; + + // GoalTolerance + + goal_tolerance.xy_goal_tolerance = 0.2; + goal_tolerance.yaw_goal_tolerance = 0.2; + goal_tolerance.free_goal_vel = false; + goal_tolerance.trans_stopped_vel = 0.1; + goal_tolerance.theta_stopped_vel = 0.1; + goal_tolerance.complete_global_plan = true; + + // Obstacles + + obstacles.min_obstacle_dist = 0.5; + obstacles.inflation_dist = 0.6; + obstacles.dynamic_obstacle_inflation_dist = 0.6; + obstacles.include_dynamic_obstacles = true; + obstacles.include_costmap_obstacles = true; + obstacles.costmap_obstacles_behind_robot_dist = 1.5; + obstacles.obstacle_poses_affected = 25; + obstacles.legacy_obstacle_association = false; + obstacles.obstacle_association_force_inclusion_factor = 1.5; + obstacles.obstacle_association_cutoff_factor = 5; + obstacles.costmap_converter_plugin = ""; + obstacles.costmap_converter_spin_thread = true; + obstacles.costmap_converter_rate = 5; + obstacles.obstacle_proximity_ratio_max_vel = 1; + obstacles.obstacle_proximity_lower_bound = 0; + obstacles.obstacle_proximity_upper_bound = 0.5; + + // Optimization + + optim.no_inner_iterations = 5; + optim.no_outer_iterations = 4; + optim.optimization_activate = true; + optim.optimization_verbose = false; + optim.penalty_epsilon = 0.05; + optim.weight_max_vel_x = 2; //1 + optim.weight_max_vel_y = 2; + optim.weight_max_vel_theta = 1; + optim.weight_acc_lim_x = 1; + optim.weight_acc_lim_y = 1; + optim.weight_acc_lim_theta = 1; + optim.weight_kinematics_nh = 1000; + optim.weight_kinematics_forward_drive = 1; + optim.weight_kinematics_turning_radius = 1; + optim.weight_optimaltime = 1; + optim.weight_shortest_path = 0; + optim.weight_obstacle = 50; + optim.weight_inflation = 0.1; + optim.weight_dynamic_obstacle = 50; + optim.weight_dynamic_obstacle_inflation = 0.1; + optim.weight_velocity_obstacle_ratio = 0; + optim.weight_viapoint = 1; + optim.weight_prefer_rotdir = 50; + + optim.weight_adapt_factor = 2.0; + optim.obstacle_cost_exponent = 1.0; + + // Homotopy Class Planner + + hcp.enable_homotopy_class_planning = true; + hcp.enable_multithreading = true; + hcp.simple_exploration = false; + hcp.max_number_classes = 5; + hcp.selection_cost_hysteresis = 1.0; + hcp.selection_prefer_initial_plan = 0.95; + hcp.selection_obst_cost_scale = 100.0; + hcp.selection_viapoint_cost_scale = 1.0; + hcp.selection_alternative_time_cost = false; + hcp.selection_dropping_probability = 0.0; + + hcp.obstacle_keypoint_offset = 0.1; + hcp.obstacle_heading_threshold = 0.45; + hcp.roadmap_graph_no_samples = 15; + hcp.roadmap_graph_area_width = 6; // [m] + hcp.roadmap_graph_area_length_scale = 1.0; + hcp.h_signature_prescaler = 1; + hcp.h_signature_threshold = 0.1; + hcp.switching_blocking_period = 0.0; + + hcp.viapoints_all_candidates = true; + + hcp.visualize_hc_graph = false; + hcp.visualize_with_time_as_z_axis_scale = 0.0; + hcp.delete_detours_backwards = true; + hcp.detours_orientation_tolerance = M_PI / 2.0; + hcp.length_start_orientation_vector = 0.4; + hcp.max_ratio_detours_duration_best_duration = 3.0; + + // Recovery + + recovery.shrink_horizon_backup = true; + recovery.shrink_horizon_min_duration = 10; + recovery.oscillation_recovery = true; + recovery.oscillation_v_eps = 0.1; + recovery.oscillation_omega_eps = 0.1; + recovery.oscillation_recovery_min_duration = 10; + recovery.oscillation_filter_duration = 10; + + + } + + /** + * @brief Load parmeters from the ros param server. + * @param nh const reference to the local ros::NodeHandle + */ + void loadRosParamFromNodeHandle(const ros::NodeHandle& nh); + + /** + * @brief Reconfigure parameters from the dynamic_reconfigure config. + * Change parameters dynamically (e.g. with rosrun rqt_reconfigure rqt_reconfigure). + * A reconfigure server needs to be instantiated that calls this method in it's callback. + * In case of the plugin \e teb_local_planner default values are defined + * in \e PROJECT_SRC/cfg/TebLocalPlannerReconfigure.cfg. + * @param cfg Config class autogenerated by dynamic_reconfigure according to the cfg-file mentioned above. + */ + void reconfigure(TebLocalPlannerReconfigureConfig& cfg); + + /** + * @brief Check parameters and print warnings in case of discrepancies + * + * Call this method whenever parameters are changed using public interfaces to inform the user + * about some improper uses. + */ + void checkParameters() const; + + /** + * @brief Check if some deprecated parameters are found and print warnings + * @param nh const reference to the local ros::NodeHandle + */ + void checkDeprecated(const ros::NodeHandle& nh) const; + + /** + * @brief Return the internal config mutex + */ + boost::mutex& configMutex() {return config_mutex_;} + +private: + boost::mutex config_mutex_; //!< Mutex for config accesses and changes + +}; + + +} // namespace teb_local_planner + +#endif diff --git a/navigations/teb_local_planner/include/teb_local_planner/teb_local_planner_ros.h b/navigations/teb_local_planner/include/teb_local_planner/teb_local_planner_ros.h new file mode 100755 index 0000000..c4635eb --- /dev/null +++ b/navigations/teb_local_planner/include/teb_local_planner/teb_local_planner_ros.h @@ -0,0 +1,457 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2016, + * TU Dortmund - Institute of Control Theory and Systems Engineering. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the institute nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: Christoph Rösmann + *********************************************************************/ + +#ifndef TEB_LOCAL_PLANNER_ROS_H_ +#define TEB_LOCAL_PLANNER_ROS_H_ + +#include + +// base local planner base class and utilities +#include +#include +#include +#include +#include + + +// timed-elastic-band related classes +#include +#include +#include +#include + +// message types +#include +#include +#include +#include +#include +#include + +// transforms +#include +#include + +// costmap +#include +#include + + +// dynamic reconfigure +#include +#include + +// boost classes +#include +#include + + +namespace teb_local_planner +{ + +/** + * @class TebLocalPlannerROS + * @brief Implements both nav_core::BaseLocalPlanner and mbf_costmap_core::CostmapController abstract + * interfaces, so the teb_local_planner plugin can be used both in move_base and move_base_flex (MBF). + * @todo Escape behavior, more efficient obstacle handling + */ +class TebLocalPlannerROS : public nav_core::BaseLocalPlanner, public mbf_costmap_core::CostmapController +{ + +public: + /** + * @brief Default constructor of the teb plugin + */ + TebLocalPlannerROS(); + + /** + * @brief Destructor of the plugin + */ + ~TebLocalPlannerROS(); + + /** + * @brief Initializes the teb plugin + * @param name The name of the instance + * @param tf Pointer to a tf buffer + * @param costmap_ros Cost map representing occupied and free space + */ + void initialize(std::string name, tf2_ros::Buffer *tf, costmap_2d::Costmap2DROS* costmap_ros); + + /** + * @brief Set the plan that the teb local planner is following + * @param orig_global_plan The plan to pass to the local planner + * @return True if the plan was updated successfully, false otherwise + */ + bool setPlan(const std::vector& orig_global_plan); + + /** + * @brief Given the current position, orientation, and velocity of the robot, compute velocity commands to send to the base + * @param cmd_vel Will be filled with the velocity command to be passed to the robot base + * @return True if a valid trajectory was found, false otherwise + */ + bool computeVelocityCommands(geometry_msgs::Twist& cmd_vel); + + /** + * @brief Given the current position, orientation, and velocity of the robot, compute velocity commands to send to the base. + * @remark Extended version for MBF API + * @param pose the current pose of the robot. + * @param velocity the current velocity of the robot. + * @param cmd_vel Will be filled with the velocity command to be passed to the robot base. + * @param message Optional more detailed outcome as a string + * @return Result code as described on ExePath action result: + * SUCCESS = 0 + * 1..9 are reserved as plugin specific non-error results + * FAILURE = 100 Unspecified failure, only used for old, non-mfb_core based plugins + * CANCELED = 101 + * NO_VALID_CMD = 102 + * PAT_EXCEEDED = 103 + * COLLISION = 104 + * OSCILLATION = 105 + * ROBOT_STUCK = 106 + * MISSED_GOAL = 107 + * MISSED_PATH = 108 + * BLOCKED_PATH = 109 + * INVALID_PATH = 110 + * TF_ERROR = 111 + * NOT_INITIALIZED = 112 + * INVALID_PLUGIN = 113 + * INTERNAL_ERROR = 114 + * 121..149 are reserved as plugin specific errors + */ + uint32_t computeVelocityCommands(const geometry_msgs::PoseStamped& pose, const geometry_msgs::TwistStamped& velocity, + geometry_msgs::TwistStamped &cmd_vel, std::string &message); + + /** + * @brief Check if the goal pose has been achieved + * + * The actual check is performed in computeVelocityCommands(). + * Only the status flag is checked here. + * @return True if achieved, false otherwise + */ + bool isGoalReached(); + + /** + * @brief Dummy version to satisfy MBF API + */ + bool isGoalReached(double xy_tolerance, double yaw_tolerance) { return isGoalReached(); }; + + /** + * @brief Requests the planner to cancel, e.g. if it takes too much time + * @remark New on MBF API + * @return True if a cancel has been successfully requested, false if not implemented. + */ + bool cancel() { return false; }; + + + /** @name Public utility functions/methods */ + //@{ + + /** + * @brief Transform a tf::Pose type into a Eigen::Vector2d containing the translational and angular velocities. + * + * Translational velocities (x- and y-coordinates) are combined into a single translational velocity (first component). + * @param tf_vel tf::Pose message containing a 1D or 2D translational velocity (x,y) and an angular velocity (yaw-angle) + * @return Translational and angular velocity combined into an Eigen::Vector2d + */ + static Eigen::Vector2d tfPoseToEigenVector2dTransRot(const tf::Pose& tf_vel); + + /** + * @brief Get the current robot footprint/contour model + * @param nh const reference to the local ros::NodeHandle + * @param config const reference to the current configuration + * @return Robot footprint model used for optimization + */ + static RobotFootprintModelPtr getRobotFootprintFromParamServer(const ros::NodeHandle& nh, const TebConfig& config); + + /** + * @brief Set the footprint from the given XmlRpcValue. + * @remarks This method is copied from costmap_2d/footprint.h, since it is not declared public in all ros distros + * @remarks It is modified in order to return a container of Eigen::Vector2d instead of geometry_msgs::Point + * @param footprint_xmlrpc should be an array of arrays, where the top-level array should have 3 or more elements, and the + * sub-arrays should all have exactly 2 elements (x and y coordinates). + * @param full_param_name this is the full name of the rosparam from which the footprint_xmlrpc value came. + * It is used only for reporting errors. + * @return container of vertices describing the polygon + */ + static Point2dContainer makeFootprintFromXMLRPC(XmlRpc::XmlRpcValue& footprint_xmlrpc, const std::string& full_param_name); + + /** + * @brief Get a number from the given XmlRpcValue. + * @remarks This method is copied from costmap_2d/footprint.h, since it is not declared public in all ros distros + * @remarks It is modified in order to return a container of Eigen::Vector2d instead of geometry_msgs::Point + * @param value double value type + * @param full_param_name this is the full name of the rosparam from which the footprint_xmlrpc value came. + * It is used only for reporting errors. + * @returns double value + */ + static double getNumberFromXMLRPC(XmlRpc::XmlRpcValue& value, const std::string& full_param_name); + + //@} + +protected: + + /** + * @brief Update internal obstacle vector based on occupied costmap cells + * @remarks All occupied cells will be added as point obstacles. + * @remarks All previous obstacles are cleared. + * @sa updateObstacleContainerWithCostmapConverter + * @todo Include temporal coherence among obstacle msgs (id vector) + * @todo Include properties for dynamic obstacles (e.g. using constant velocity model) + */ + void updateObstacleContainerWithCostmap(); + + /** + * @brief Update internal obstacle vector based on polygons provided by a costmap_converter plugin + * @remarks Requires a loaded costmap_converter plugin. + * @remarks All previous obstacles are cleared. + * @sa updateObstacleContainerWithCostmap + */ + void updateObstacleContainerWithCostmapConverter(); + + /** + * @brief Update internal obstacle vector based on custom messages received via subscriber + * @remarks All previous obstacles are NOT cleared. Call this method after other update methods. + * @sa updateObstacleContainerWithCostmap, updateObstacleContainerWithCostmapConverter + */ + void updateObstacleContainerWithCustomObstacles(); + + + /** + * @brief Update internal via-point container based on the current reference plan + * @remarks All previous via-points will be cleared. + * @param transformed_plan (local) portion of the global plan (which is already transformed to the planning frame) + * @param min_separation minimum separation between two consecutive via-points + */ + void updateViaPointsContainer(const std::vector& transformed_plan, double min_separation); + + + /** + * @brief Callback for the dynamic_reconfigure node. + * + * This callback allows to modify parameters dynamically at runtime without restarting the node + * @param config Reference to the dynamic reconfigure config + * @param level Dynamic reconfigure level + */ + void reconfigureCB(TebLocalPlannerReconfigureConfig& config, uint32_t level); + + + /** + * @brief Callback for custom obstacles that are not obtained from the costmap + * @param obst_msg pointer to the message containing a list of polygon shaped obstacles + */ + void customObstacleCB(const costmap_converter::ObstacleArrayMsg::ConstPtr& obst_msg); + + /** + * @brief Callback for custom via-points + * @param via_points_msg pointer to the message containing a list of via-points + */ + void customViaPointsCB(const nav_msgs::Path::ConstPtr& via_points_msg); + + /** + * @brief Prune global plan such that already passed poses are cut off + * + * The pose of the robot is transformed into the frame of the global plan by taking the most recent tf transform. + * If no valid transformation can be found, the method returns \c false. + * The global plan is pruned until the distance to the robot is at least \c dist_behind_robot. + * If no pose within the specified treshold \c dist_behind_robot can be found, + * nothing will be pruned and the method returns \c false. + * @remarks Do not choose \c dist_behind_robot too small (not smaller the cellsize of the map), otherwise nothing will be pruned. + * @param tf A reference to a tf buffer + * @param global_pose The global pose of the robot + * @param[in,out] global_plan The plan to be transformed + * @param dist_behind_robot Distance behind the robot that should be kept [meters] + * @return \c true if the plan is pruned, \c false in case of a transform exception or if no pose cannot be found inside the threshold + */ + bool pruneGlobalPlan(const tf2_ros::Buffer& tf, const geometry_msgs::PoseStamped& global_pose, + std::vector& global_plan, double dist_behind_robot=1); + + /** + * @brief Transforms the global plan of the robot from the planner frame to the local frame (modified). + * + * The method replaces transformGlobalPlan as defined in base_local_planner/goal_functions.h + * such that the index of the current goal pose is returned as well as + * the transformation between the global plan and the planning frame. + * @param tf A reference to a tf buffer + * @param global_plan The plan to be transformed + * @param global_pose The global pose of the robot + * @param costmap A reference to the costmap being used so the window size for transforming can be computed + * @param global_frame The frame to transform the plan to + * @param max_plan_length Specify maximum length (cumulative Euclidean distances) of the transformed plan [if <=0: disabled; the length is also bounded by the local costmap size!] + * @param[out] transformed_plan Populated with the transformed plan + * @param[out] current_goal_idx Index of the current (local) goal pose in the global plan + * @param[out] tf_plan_to_global Transformation between the global plan and the global planning frame + * @return \c true if the global plan is transformed, \c false otherwise + */ + bool transformGlobalPlan(const tf2_ros::Buffer& tf, const std::vector& global_plan, + const geometry_msgs::PoseStamped& global_pose, const costmap_2d::Costmap2D& costmap, + const std::string& global_frame, double max_plan_length, std::vector& transformed_plan, + int* current_goal_idx = NULL, geometry_msgs::TransformStamped* tf_plan_to_global = NULL) const; + + /** + * @brief Estimate the orientation of a pose from the global_plan that is treated as a local goal for the local planner. + * + * If the current (local) goal point is not the final one (global) + * substitute the goal orientation by the angle of the direction vector between + * the local goal and the subsequent pose of the global plan. + * This is often helpful, if the global planner does not consider orientations. \n + * A moving average filter is utilized to smooth the orientation. + * @param global_plan The global plan + * @param local_goal Current local goal + * @param current_goal_idx Index of the current (local) goal pose in the global plan + * @param[out] tf_plan_to_global Transformation between the global plan and the global planning frame + * @param moving_average_length number of future poses of the global plan to be taken into account + * @return orientation (yaw-angle) estimate + */ + double estimateLocalGoalOrientation(const std::vector& global_plan, const geometry_msgs::PoseStamped& local_goal, + int current_goal_idx, const geometry_msgs::TransformStamped& tf_plan_to_global, int moving_average_length=3) const; + + + /** + * @brief Saturate the translational and angular velocity to given limits. + * + * The limit of the translational velocity for backwards driving can be changed independently. + * Do not choose max_vel_x_backwards <= 0. If no backward driving is desired, change the optimization weight for + * penalizing backwards driving instead. + * @param[in,out] vx The translational velocity that should be saturated. + * @param[in,out] vy Strafing velocity which can be nonzero for holonomic robots + * @param[in,out] omega The angular velocity that should be saturated. + * @param max_vel_x Maximum translational velocity for forward driving + * @param max_vel_y Maximum strafing velocity (for holonomic robots) + * @param max_vel_trans Maximum translational velocity for holonomic robots + * @param max_vel_theta Maximum (absolute) angular velocity + * @param max_vel_x_backwards Maximum translational velocity for backwards driving + */ + void saturateVelocity(double& vx, double& vy, double& omega, double max_vel_x, double max_vel_y, + double max_vel_trans, double max_vel_theta, double max_vel_x_backwards) const; + + + /** + * @brief Convert translational and rotational velocities to a steering angle of a carlike robot + * + * The conversion is based on the following equations: + * - The turning radius is defined by \f$ R = v/omega \f$ + * - For a car like robot withe a distance L between both axles, the relation is: \f$ tan(\phi) = L/R \f$ + * - phi denotes the steering angle. + * @remarks You might provide distances instead of velocities, since the temporal information is not required. + * @param v translational velocity [m/s] + * @param omega rotational velocity [rad/s] + * @param wheelbase distance between both axles (drive shaft and steering axle), the value might be negative for back_wheeled robots + * @param min_turning_radius Specify a lower bound on the turning radius + * @return Resulting steering angle in [rad] inbetween [-pi/2, pi/2] + */ + double convertTransRotVelToSteeringAngle(double v, double omega, double wheelbase, double min_turning_radius = 0) const; + + /** + * @brief Validate current parameter values of the footprint for optimization, obstacle distance and the costmap footprint + * + * This method prints warnings if validation fails. + * @remarks Currently, we only validate the inscribed radius of the footprints + * @param opt_inscribed_radius Inscribed radius of the RobotFootprintModel for optimization + * @param costmap_inscribed_radius Inscribed radius of the footprint model used for the costmap + * @param min_obst_dist desired distance to obstacles + */ + void validateFootprints(double opt_inscribed_radius, double costmap_inscribed_radius, double min_obst_dist); + + + void configureBackupModes(std::vector& transformed_plan, int& goal_idx); + + + +private: + // Definition of member variables + + // external objects (store weak pointers) + costmap_2d::Costmap2DROS* costmap_ros_; //!< Pointer to the costmap ros wrapper, received from the navigation stack + costmap_2d::Costmap2D* costmap_; //!< Pointer to the 2d costmap (obtained from the costmap ros wrapper) + tf2_ros::Buffer* tf_; //!< pointer to tf buffer + + // internal objects (memory management owned) + PlannerInterfacePtr planner_; //!< Instance of the underlying optimal planner class + ObstContainer obstacles_; //!< Obstacle vector that should be considered during local trajectory optimization + ViaPointContainer via_points_; //!< Container of via-points that should be considered during local trajectory optimization + TebVisualizationPtr visualization_; //!< Instance of the visualization class (local/global plan, obstacles, ...) + boost::shared_ptr costmap_model_; + TebConfig cfg_; //!< Config class that stores and manages all related parameters + FailureDetector failure_detector_; //!< Detect if the robot got stucked + + std::vector global_plan_; //!< Store the current global plan + + base_local_planner::OdometryHelperRos odom_helper_; //!< Provides an interface to receive the current velocity from the robot + + pluginlib::ClassLoader costmap_converter_loader_; //!< Load costmap converter plugins at runtime + boost::shared_ptr costmap_converter_; //!< Store the current costmap_converter + + boost::shared_ptr< dynamic_reconfigure::Server > dynamic_recfg_; //!< Dynamic reconfigure server to allow config modifications at runtime + ros::Subscriber custom_obst_sub_; //!< Subscriber for custom obstacles received via a ObstacleMsg. + boost::mutex custom_obst_mutex_; //!< Mutex that locks the obstacle array (multi-threaded) + costmap_converter::ObstacleArrayMsg custom_obstacle_msg_; //!< Copy of the most recent obstacle message + + ros::Subscriber via_points_sub_; //!< Subscriber for custom via-points received via a Path msg. + bool custom_via_points_active_; //!< Keep track whether valid via-points have been received from via_points_sub_ + boost::mutex via_point_mutex_; //!< Mutex that locks the via_points container (multi-threaded) + + PoseSE2 robot_pose_; //!< Store current robot pose + PoseSE2 robot_goal_; //!< Store current robot goal + geometry_msgs::Twist robot_vel_; //!< Store current robot translational and angular velocity (vx, vy, omega) + bool goal_reached_; //!< store whether the goal is reached or not + ros::Time time_last_infeasible_plan_; //!< Store at which time stamp the last infeasible plan was detected + int no_infeasible_plans_; //!< Store how many times in a row the planner failed to find a feasible plan. + ros::Time time_last_oscillation_; //!< Store at which time stamp the last oscillation was detected + RotType last_preferred_rotdir_; //!< Store recent preferred turning direction + geometry_msgs::Twist last_cmd_; //!< Store the last control command generated in computeVelocityCommands() + + std::vector footprint_spec_; //!< Store the footprint of the robot + double robot_inscribed_radius_; //!< The radius of the inscribed circle of the robot (collision possible) + double robot_circumscribed_radius; //!< The radius of the circumscribed circle of the robot + + std::string global_frame_; //!< The frame in which the controller will run + std::string robot_base_frame_; //!< Used as the base frame id of the robot + std::string name_; //!< For use with the ros nodehandle + + // flags + bool initialized_; //!< Keeps track about the correct initialization of this class + +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +}; + +}; // end namespace teb_local_planner + +#endif // TEB_LOCAL_PLANNER_ROS_H_ + + diff --git a/navigations/teb_local_planner/include/teb_local_planner/timed_elastic_band.h b/navigations/teb_local_planner/include/teb_local_planner/timed_elastic_band.h new file mode 100755 index 0000000..12c7d27 --- /dev/null +++ b/navigations/teb_local_planner/include/teb_local_planner/timed_elastic_band.h @@ -0,0 +1,659 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2016, + * TU Dortmund - Institute of Control Theory and Systems Engineering. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the institute nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: Christoph Rösmann + *********************************************************************/ + +#ifndef TIMED_ELASTIC_BAND_H_ +#define TIMED_ELASTIC_BAND_H_ + +#include +#include + +#include +#include +#include + +#include +#include + +#include + +// G2O Types +#include +#include + + +namespace teb_local_planner +{ + +//! Container of poses that represent the spatial part of the trajectory +typedef std::vector PoseSequence; +//! Container of time differences that define the temporal of the trajectory +typedef std::vector TimeDiffSequence; + + +/** + * @class TimedElasticBand + * @brief Class that defines a trajectory modeled as an elastic band with augmented tempoarl information. + * + * All trajectory related methods (initialization, modifying, ...) are implemented inside this class. \n + * Let \f$ Q = \lbrace \mathbf{s}_i \rbrace_{i=0...n},\ n \in \mathbb{N} \f$ be a sequence of poses, \n + * in which \f$ \mathbf{s}_i = [x_i, y_i, \beta_i]^T \in \mathbb{R}^2 \times S^1 \f$ denotes a single pose of the robot. \n + * The Timed Elastic Band (TEB) augments this sequence of poses by incorporating time intervals between + * two consecutive poses, resuting in a sequence of \c n-1 time intervals \f$ \Delta T_i \f$: \n + * \f$ \tau = \lbrace \Delta T_i \rbrace_{i=0...n-1} \f$. \n + * Each time interval (time diff) denotes the time that the robot requires to transit from the current configuration to the next configuration. + * The tuple of both sequences defines the underlying trajectory. + * + * Poses and time differences are wrapped into a g2o::Vertex class in order to enable the efficient optimization in TebOptimalPlanner. \n + * TebOptimalPlanner utilizes this Timed_Elastic_band class for representing an optimizable trajectory. + * + * @todo Move decision if the start or goal state should be marked as fixed or unfixed for the optimization to the TebOptimalPlanner class. + */ +class TimedElasticBand +{ +public: + + /** + * @brief Construct the class + */ + TimedElasticBand(); + + /** + * @brief Destruct the class + */ + virtual ~TimedElasticBand(); + + + + /** @name Access pose and timediff sequences */ + //@{ + + /** + * @brief Access the complete pose sequence + * @return reference to the pose sequence + */ + PoseSequence& poses() {return pose_vec_;}; + + /** + * @brief Access the complete pose sequence (read-only) + * @return const reference to the pose sequence + */ + const PoseSequence& poses() const {return pose_vec_;}; + + /** + * @brief Access the complete timediff sequence + * @return reference to the dimediff sequence + */ + TimeDiffSequence& timediffs() {return timediff_vec_;}; + + /** + * @brief Access the complete timediff sequence + * @return reference to the dimediff sequence + */ + const TimeDiffSequence& timediffs() const {return timediff_vec_;}; + + /** + * @brief Access the time difference at pos \c index of the time sequence + * @param index element position inside the internal TimeDiffSequence + * @return reference to the time difference at pos \c index + */ + double& TimeDiff(int index) + { + ROS_ASSERT(indexdt(); + } + + /** + * @brief Access the time difference at pos \c index of the time sequence (read-only) + * @param index element position inside the internal TimeDiffSequence + * @return const reference to the time difference at pos \c index + */ + const double& TimeDiff(int index) const + { + ROS_ASSERT(indexdt(); + } + + /** + * @brief Access the pose at pos \c index of the pose sequence + * @param index element position inside the internal PoseSequence + * @return reference to the pose at pos \c index + */ + PoseSE2& Pose(int index) + { + ROS_ASSERT(indexpose(); + } + + /** + * @brief Access the pose at pos \c index of the pose sequence (read-only) + * @param index element position inside the internal PoseSequence + * @return const reference to the pose at pos \c index + */ + const PoseSE2& Pose(int index) const + { + ROS_ASSERT(indexpose(); + } + + /** + * @brief Access the last PoseSE2 in the pose sequence + */ + PoseSE2& BackPose() {return pose_vec_.back()->pose(); } + + /** + * @brief Access the last PoseSE2 in the pose sequence (read-only) + */ + const PoseSE2& BackPose() const {return pose_vec_.back()->pose();} + + /** + * @brief Access the last TimeDiff in the time diff sequence + */ + double& BackTimeDiff() {return timediff_vec_.back()->dt(); } + + /** + * @brief Access the last TimeDiff in the time diff sequence (read-only) + */ + const double& BackTimeDiff() const {return timediff_vec_.back()->dt(); } + + /** + * @brief Access the vertex of a pose at pos \c index for optimization purposes + * @param index element position inside the internal PoseSequence + * @return Weak raw pointer to the pose vertex at pos \c index + */ + VertexPose* PoseVertex(int index) + { + ROS_ASSERT(index& position, double theta, bool fixed=false); + + /** + * @brief Append a new pose vertex to the back of the pose sequence + * @param x x-coordinate of the position part + * @param y y-coordinate of the position part + * @param theta yaw angle representing the orientation part + * @param fixed Mark the pose to be fixed or unfixed during trajectory optimization (important for the TebOptimalPlanner) + */ + void addPose(double x, double y, double theta, bool fixed=false); + + /** + * @brief Append a new time difference vertex to the back of the time diff sequence + * @param dt time difference value to push back on the internal TimeDiffSequence + * @param fixed Mark the pose to be fixed or unfixed during trajectory optimization (important for the TebOptimalPlanner) + */ + void addTimeDiff(double dt, bool fixed=false); + + /** + * @brief Append a (pose, timediff) vertex pair to the end of the current trajectory (pose and timediff sequences) + * @param pose PoseSE2 to push back on the internal PoseSequence + * @param dt time difference value to push back on the internal TimeDiffSequence + * @warning Since the timediff is defined to connect two consecutive poses, this call is only + * allowed if there exist already n poses and n-1 timediffs in the sequences (n=1,2,...): + * therefore add a single pose using addPose() first! + */ + void addPoseAndTimeDiff(const PoseSE2& pose, double dt); + + /** + * @brief Append a (pose, timediff) vertex pair to the end of the current trajectory (pose and timediff sequences) + * @param position 2D vector representing the position part + * @param theta yaw angle representing the orientation part + * @param dt time difference value to push back on the internal TimeDiffSequence + * @warning see addPoseAndTimeDiff(const PoseSE2& pose, double dt) + */ + void addPoseAndTimeDiff(const Eigen::Ref& position, double theta, double dt); + + /** + * @brief Append a (pose, timediff) vertex pair to the end of the current trajectory (pose and timediff sequences) + * @param x x-coordinate of the position part + * @param y y-coordinate of the position part + * @param theta yaw angle representing the orientation part + * @param dt time difference value to push back on the internal TimeDiffSequence + * @warning see addPoseAndTimeDiff(const PoseSE2& pose, double dt) + */ + void addPoseAndTimeDiff(double x, double y, double theta, double dt); + + //@} + + + /** @name Insert new elements and remove elements of the pose and timediff sequences */ + //@{ + + /** + * @brief Insert a new pose vertex at pos. \c index to the pose sequence + * @param index element position inside the internal PoseSequence + * @param pose PoseSE2 element to insert into the internal PoseSequence + */ + void insertPose(int index, const PoseSE2& pose); + + /** + * @brief Insert a new pose vertex at pos. \c index to the pose sequence + * @param index element position inside the internal PoseSequence + * @param position 2D vector representing the position part + * @param theta yaw-angle representing the orientation part + */ + void insertPose(int index, const Eigen::Ref& position, double theta); + + /** + * @brief Insert a new pose vertex at pos. \c index to the pose sequence + * @param index element position inside the internal PoseSequence + * @param x x-coordinate of the position part + * @param y y-coordinate of the position part + * @param theta yaw-angle representing the orientation part + */ + void insertPose(int index, double x, double y, double theta); + + /** + * @brief Insert a new timediff vertex at pos. \c index to the timediff sequence + * @param index element position inside the internal TimeDiffSequence + * @param dt timediff value + */ + void insertTimeDiff(int index, double dt); + + /** + * @brief Delete pose at pos. \c index in the pose sequence + * @param index element position inside the internal PoseSequence + */ + void deletePose(int index); + + /** + * @brief Delete multiple (\c number) poses starting at pos. \c index in the pose sequence + * @param index first element position inside the internal PoseSequence + * @param number number of elements that should be deleted + */ + void deletePoses(int index, int number); + + /** + * @brief Delete pose at pos. \c index in the timediff sequence + * @param index element position inside the internal TimeDiffSequence + */ + void deleteTimeDiff(int index); + + /** + * @brief Delete multiple (\c number) time differences starting at pos. \c index in the timediff sequence + * @param index first element position inside the internal TimeDiffSequence + * @param number number of elements that should be deleted + */ + void deleteTimeDiffs(int index, int number); + + //@} + + + /** @name Init the trajectory */ + //@{ + + /** + * @brief Initialize a trajectory between a given start and goal pose. + * + * The implemented algorithm subsamples the straight line between + * start and goal using a given discretiziation width. \n + * The discretization width can be defined in the euclidean space + * using the \c diststep parameter. Each time difference between two consecutive + * poses is initialized to \c timestep. \n + * If the \c diststep is chosen to be zero, + * the resulting trajectory contains the start and goal pose only. + * @param start PoseSE2 defining the start of the trajectory + * @param goal PoseSE2 defining the goal of the trajectory (final pose) + * @param diststep euclidean distance between two consecutive poses (if 0, no intermediate samples are inserted despite min_samples) + * @param max_vel_x maximum translational velocity used for determining time differences + * @param min_samples Minimum number of samples that should be initialized at least + * @param guess_backwards_motion Allow the initialization of backwards oriented trajectories if the goal heading is pointing behind the robot + * @return true if everything was fine, false otherwise + */ + bool initTrajectoryToGoal(const PoseSE2& start, const PoseSE2& goal, double diststep=0, double max_vel_x=0.5, int min_samples = 3, bool guess_backwards_motion = false); + + + /** + * @brief Initialize a trajectory from a generic 2D reference path. + * + * The temporal information is determined using a given maximum velocity + * (2D vector containing the translational and angular velocity). \n + * A constant velocity profile is implemented. \n + * A possible maximum acceleration is considered if \c max_acceleration param is provided. + * + * Since the orientation is not included in the reference path, it can be provided seperately + * (e.g. from the robot pose and robot goal). \n + * Otherwise the goal heading will be used as start and goal orientation. \n + * The orientation along the trajectory will be determined using the connection vector + * between two consecutive positions of the reference path. + * + * The reference path is provided using a start and end iterator to a container class. + * You must provide a unary function that accepts the dereferenced iterator and returns + * a copy or (const) reference to an Eigen::Vector2d type containing the 2d position. + * + * @param path_start start iterator of a generic 2d path + * @param path_end end iterator of a generic 2d path + * @param fun_position unary function that returns the Eigen::Vector2d object + * @param max_vel_x maximum translational velocity used for determining time differences + * @param max_vel_theta maximum angular velocity used for determining time differences + * @param max_acc_x specify to satisfy a maxmimum transl. acceleration and decceleration (optional) + * @param max_acc_theta specify to satisfy a maxmimum angular acceleration and decceleration (optional) + * @param start_orientation Orientation of the first pose of the trajectory (optional, otherwise use goal heading) + * @param goal_orientation Orientation of the last pose of the trajectory (optional, otherwise use goal heading) + * @param min_samples Minimum number of samples that should be initialized at least + * @param guess_backwards_motion Allow the initialization of backwards oriented trajectories if the goal heading is pointing behind the robot + * @tparam BidirIter Bidirectional iterator type + * @tparam Fun unyary function that transforms the dereferenced iterator into an Eigen::Vector2d + * @return true if everything was fine, false otherwise + * @remarks Use \c boost::none to skip optional arguments. + */ + template + bool initTrajectoryToGoal(BidirIter path_start, BidirIter path_end, Fun fun_position, double max_vel_x, double max_vel_theta, + boost::optional max_acc_x, boost::optional max_acc_theta, + boost::optional start_orientation, boost::optional goal_orientation, int min_samples = 3, bool guess_backwards_motion = false); + + /** + * @brief Initialize a trajectory from a reference pose sequence (positions and orientations). + * + * This method initializes the timed elastic band using a pose container + * (e.g. as local plan from the ros navigation stack). \n + * The initial time difference between two consecutive poses can be uniformly set + * via the argument \c dt. + * @param plan vector of geometry_msgs::PoseStamped + * @param max_vel_x maximum translational velocity used for determining time differences + * @param max_vel_theta maximum rotational velocity used for determining time differences + * @param estimate_orient if \c true, calculate orientation using the straight line distance vector between consecutive poses + * (only copy start and goal orientation; recommended if no orientation data is available). + * @param min_samples Minimum number of samples that should be initialized at least + * @param guess_backwards_motion Allow the initialization of backwards oriented trajectories if the goal heading is pointing behind the robot (this parameter is used only if \c estimate_orient is enabled. + * @return true if everything was fine, false otherwise + */ + bool initTrajectoryToGoal(const std::vector& plan, double max_vel_x, double max_vel_theta, bool estimate_orient=false, int min_samples = 3, bool guess_backwards_motion = false); + + + ROS_DEPRECATED bool initTEBtoGoal(const PoseSE2& start, const PoseSE2& goal, double diststep=0, double timestep=1, int min_samples = 3, bool guess_backwards_motion = false) + { + ROS_WARN_ONCE("initTEBtoGoal is deprecated and has been replaced by initTrajectoryToGoal. The signature has changed: timestep has been replaced by max_vel_x. \ + this deprecated method sets max_vel_x = 1. Please update your code."); + return initTrajectoryToGoal(start, goal, diststep, timestep, min_samples, guess_backwards_motion); + } + + template + ROS_DEPRECATED bool initTEBtoGoal(BidirIter path_start, BidirIter path_end, Fun fun_position, double max_vel_x, double max_vel_theta, + boost::optional max_acc_x, boost::optional max_acc_theta, + boost::optional start_orientation, boost::optional goal_orientation, int min_samples = 3, bool guess_backwards_motion = false) + { + return initTrajectoryToGoal(path_start, path_end, fun_position, max_vel_x, max_vel_theta, + max_acc_x, max_acc_theta, start_orientation, goal_orientation, min_samples, guess_backwards_motion); + } + + ROS_DEPRECATED bool initTEBtoGoal(const std::vector& plan, double dt, bool estimate_orient=false, int min_samples = 3, bool guess_backwards_motion = false) + { + ROS_WARN_ONCE("initTEBtoGoal is deprecated and has been replaced by initTrajectoryToGoal. The signature has changed: dt has been replaced by max_vel_x. \ + this deprecated method sets max_vel = 1. Please update your code."); + return initTrajectoryToGoal(plan, 1.0, 1.0, estimate_orient, min_samples, guess_backwards_motion); + } + + + //@} + + /** @name Update and modify the trajectory */ + //@{ + + + /** + * @brief Hot-Start from an existing trajectory with updated start and goal poses. + * + * This method updates a previously optimized trajectory with a new start and/or a new goal pose. \n + * The current simple implementation cuts of pieces of the trajectory that are already passed due to the new start. \n + * Afterwards the start and goal pose are replaced by the new ones. The resulting discontinuity will not be smoothed. + * The optimizer has to smooth the trajectory in TebOptimalPlanner. \n + * + * @todo Smooth the trajectory here and test the performance improvement of the optimization. + * @todo Implement a updateAndPruneTEB based on a new reference path / pose sequence. + * + * @param new_start New start pose (optional) + * @param new_goal New goal pose (optional) + * @param min_samples Specify the minimum number of samples that should at least remain in the trajectory + */ + void updateAndPruneTEB(boost::optional new_start, boost::optional new_goal, int min_samples = 3); + + + /** + * @brief Resize the trajectory by removing or inserting a (pose,dt) pair depending on a reference temporal resolution. + * + * Resizing the trajectory is helpful e.g. for the following scenarios: + * + * - Obstacles requires the teb to be extended in order to + * satisfy the given discritization width (plan resolution) + * and to avoid undesirable behavior due to a large/small discretization step widths \f$ \Delta T_i \f$ + * After clearance of obstacles, the teb should (re-) contract to its (time-)optimal version. + * - If the distance to the goal state is getting smaller, + * dt is decreasing as well. This leads to a heavily + * fine-grained discretization in combination with many + * discrete poses. Thus, the computation time will + * be/remain high and in addition numerical instabilities + * can appear (e.g. due to the division by a small \f$ \Delta T_i \f$). + * + * The implemented strategy checks all timediffs \f$ \Delta T_i \f$ and + * + * - inserts a new sample if \f$ \Delta T_i > \Delta T_{ref} + \Delta T_{hyst} \f$ + * - removes a sample if \f$ \Delta T_i < \Delta T_{ref} - \Delta T_{hyst} \f$ + * + * Each call only one new sample (pose-dt-pair) is inserted or removed. + * @param dt_ref reference temporal resolution + * @param dt_hysteresis hysteresis to avoid oscillations + * @param min_samples minimum number of samples that should be remain in the trajectory after resizing + * @param max_samples maximum number of samples that should not be exceeded during resizing + * @param fast_mode if true, the trajectory is iterated once to insert or erase points; if false the trajectory + * is repeatedly iterated until no poses are added or removed anymore + */ + void autoResize(double dt_ref, double dt_hysteresis, int min_samples = 3, int max_samples=1000, bool fast_mode=false); + + /** + * @brief Set a pose vertex at pos \c index of the pose sequence to be fixed or unfixed during optimization. + * @param index index to the pose vertex + * @param status if \c true, the vertex will be fixed, otherwise unfixed + */ + void setPoseVertexFixed(int index, bool status); + + /** + * @brief Set a timediff vertex at pos \c index of the timediff sequence to be fixed or unfixed during optimization. + * @param index index to the timediff vertex + * @param status if \c true, the vertex will be fixed, otherwise unfixed + */ + void setTimeDiffVertexFixed(int index, bool status); + + /** + * @brief clear all poses and timediffs from the trajectory. + * The pose and timediff sequences will be empty and isInit() will return \c false + */ + void clearTimedElasticBand(); + + //@} + + + /** @name Utility and status methods */ + //@{ + + /** + * @brief Find the closest point on the trajectory w.r.t. to a provided reference point. + * + * This function can be useful to find the part of a trajectory that is close to an obstacle. + * + * @todo implement a more efficient version that first performs a coarse search. + * @todo implement a fast approximation that assumes only one local minima w.r.t to the distance: + * Allows simple comparisons starting from the middle of the trajectory. + * + * @param ref_point reference point (2D position vector) + * @param[out] distance [optional] the resulting minimum distance + * @param begin_idx start search at this pose index + * @return Index to the closest pose in the pose sequence + */ + int findClosestTrajectoryPose(const Eigen::Ref& ref_point, double* distance = NULL, int begin_idx=0) const; + + /** + * @brief Find the closest point on the trajectory w.r.t. to a provided reference line. + * + * This function can be useful to find the part of a trajectory that is close to an (line) obstacle. + * + * @todo implement a more efficient version that first performs a coarse search. + * @todo implement a fast approximation that assumes only one local minima w.r.t to the distance: + * Allows simple comparisons starting from the middle of the trajectory. + * + * @param ref_line_start start of the reference line (2D position vector) + * @param ref_line_end end of the reference line (2D position vector) + * @param[out] distance [optional] the resulting minimum distance + * @return Index to the closest pose in the pose sequence + */ + int findClosestTrajectoryPose(const Eigen::Ref& ref_line_start, const Eigen::Ref& ref_line_end, double* distance = NULL) const; + + /** + * @brief Find the closest point on the trajectory w.r.t. to a provided reference polygon. + * + * This function can be useful to find the part of a trajectory that is close to an (polygon) obstacle. + * + * @todo implement a more efficient version that first performs a coarse search. + * @todo implement a fast approximation that assumes only one local minima w.r.t to the distance: + * Allows simple comparisons starting from the middle of the trajectory. + * + * @param vertices vertex container containing Eigen::Vector2d points (the last and first point are connected) + * @param[out] distance [optional] the resulting minimum distance + * @return Index to the closest pose in the pose sequence + */ + int findClosestTrajectoryPose(const Point2dContainer& vertices, double* distance = NULL) const; + + /** + * @brief Find the closest point on the trajectory w.r.t to a provided obstacle type + * + * This function can be useful to find the part of a trajectory that is close to an obstacle. + * The method is calculates appropriate distance metrics for point, line and polygon obstacles. + * For all unknown obstacles the centroid is used. + * + * @param obstacle Subclass of the Obstacle base class + * @param[out] distance [optional] the resulting minimum distance + * @return Index to the closest pose in the pose sequence + */ + int findClosestTrajectoryPose(const Obstacle& obstacle, double* distance = NULL) const; + + + /** + * @brief Get the length of the internal pose sequence + */ + int sizePoses() const {return (int)pose_vec_.size();}; + + /** + * @brief Get the length of the internal timediff sequence + */ + int sizeTimeDiffs() const {return (int)timediff_vec_.size();}; + + /** + * @brief Check whether the trajectory is initialized (nonzero pose and timediff sequences) + */ + bool isInit() const {return !timediff_vec_.empty() && !pose_vec_.empty();} + + /** + * @brief Calculate the total transition time (sum over all time intervals of the timediff sequence) + */ + double getSumOfAllTimeDiffs() const; + + /** + * @brief Calculate the estimated transition time up to the pose denoted by index + * @param index Index of the pose up to which the transition times are summed up + * @return Estimated transition time up to pose index + */ + double getSumOfTimeDiffsUpToIdx(int index) const; + + /** + * @brief Calculate the length (accumulated euclidean distance) of the trajectory + */ + double getAccumulatedDistance() const; + + /** + * @brief Check if all trajectory points are contained in a specific region + * + * The specific region is a circle around the current robot position (Pose(0)) with given radius \c radius. + * This method investigates a different radius for points behind the robot if \c max_dist_behind_robot >= 0. + * @param radius radius of the region with the robot position (Pose(0)) as center + * @param max_dist_behind_robot A separate radius for trajectory points behind the robot, activated if 0 or positive + * @param skip_poses If >0: the specified number of poses are skipped for the test, e.g. Pose(0), Pose(0+skip_poses+1), Pose(2*skip_poses+2), ... are tested. + * @return \c true, if all tested trajectory points are inside the specified region, \c false otherwise. + */ + bool isTrajectoryInsideRegion(double radius, double max_dist_behind_robot=-1, int skip_poses=0); + + + + //@} + +protected: + PoseSequence pose_vec_; //!< Internal container storing the sequence of optimzable pose vertices + TimeDiffSequence timediff_vec_; //!< Internal container storing the sequence of optimzable timediff vertices + +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +}; + +} // namespace teb_local_planner + + +// include template implementations / definitions +#include + + +#endif /* TIMED_ELASTIC_BAND_H_ */ diff --git a/navigations/teb_local_planner/include/teb_local_planner/timed_elastic_band.hpp b/navigations/teb_local_planner/include/teb_local_planner/timed_elastic_band.hpp new file mode 100755 index 0000000..66c92b8 --- /dev/null +++ b/navigations/teb_local_planner/include/teb_local_planner/timed_elastic_band.hpp @@ -0,0 +1,189 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2016, + * TU Dortmund - Institute of Control Theory and Systems Engineering. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the institute nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: Christoph Rösmann + *********************************************************************/ + +#include + +namespace teb_local_planner +{ + + + +template +bool TimedElasticBand::initTrajectoryToGoal(BidirIter path_start, BidirIter path_end, Fun fun_position, double max_vel_x, double max_vel_theta, + boost::optional max_acc_x, boost::optional max_acc_theta, + boost::optional start_orientation, boost::optional goal_orientation, int min_samples, bool guess_backwards_motion) +{ + Eigen::Vector2d start_position = fun_position( *path_start ); + Eigen::Vector2d goal_position = fun_position( *boost::prior(path_end) ); + + bool backwards = false; + + double start_orient, goal_orient; + if (start_orientation) + { + start_orient = *start_orientation; + + // check if the goal is behind the start pose (w.r.t. start orientation) + if (guess_backwards_motion && (goal_position-start_position).dot(Eigen::Vector2d(std::cos(start_orient), std::sin(start_orient))) < 0) + backwards = true; + } + else + { + Eigen::Vector2d start2goal = goal_position - start_position; + start_orient = atan2(start2goal[1],start2goal[0]); + } + + double timestep = 1; // TODO: time + + if (goal_orientation) + { + goal_orient = *goal_orientation; + } + else + { + goal_orient = start_orient; + } + + if (!isInit()) + { + addPose(start_position, start_orient, true); // add starting point and mark it as fixed for optimization + + // we insert middle points now (increase start by 1 and decrease goal by 1) + std::advance(path_start,1); + std::advance(path_end,-1); + int idx=0; + for (; path_start != path_end; ++path_start) // insert middle-points + { + //Eigen::Vector2d point_to_goal = path.back()-*it; + //double dir_to_goal = atan2(point_to_goal[1],point_to_goal[0]); // direction to goal + // Alternative: Direction from last path + Eigen::Vector2d curr_point = fun_position(*path_start); + Eigen::Vector2d diff_last = curr_point - Pose(idx).position(); // we do not use boost::prior(*path_start) for those cases, + // where fun_position() does not return a reference or is expensive. + double diff_norm = diff_last.norm(); + + double timestep_vel = diff_norm/max_vel_x; // constant velocity + double timestep_acc; + + if (max_acc_x) + { + timestep_acc = sqrt(2*diff_norm/(*max_acc_x)); // constant acceleration + if (timestep_vel < timestep_acc && max_acc_x) timestep = timestep_acc; + else timestep = timestep_vel; + } + else timestep = timestep_vel; + + if (timestep<=0) timestep=0.2; // TODO: this is an assumption + + double yaw = atan2(diff_last[1],diff_last[0]); + if (backwards) + yaw = g2o::normalize_theta(yaw + M_PI); + addPoseAndTimeDiff(curr_point, yaw ,timestep); + + /* + // TODO: the following code does not seem to hot-start the optimizer. Instead it recudes convergence time. + + Eigen::Vector2d diff_next = fun_position(*boost::next(path_start))-curr_point; // TODO maybe store the boost::next for the following iteration + double ang_diff = std::abs( g2o::normalize_theta( atan2(diff_next[1],diff_next[0]) + -atan2(diff_last[1],diff_last[0]) ) ); + + timestep_vel = ang_diff/max_vel_theta; // constant velocity + if (max_acc_theta) + { + timestep_acc = sqrt(2*ang_diff/(*max_acc_theta)); // constant acceleration + if (timestep_vel < timestep_acc) timestep = timestep_acc; + else timestep = timestep_vel; + } + else timestep = timestep_vel; + + if (timestep<=0) timestep=0.2; // TODO: this is an assumption + + yaw = atan2(diff_last[1],diff_last[0]); // TODO redundant right now, not yet finished + if (backwards) + yaw = g2o::normalize_theta(yaw + M_PI); + addPoseAndTimeDiff(curr_point, yaw ,timestep); + + */ + + ++idx; + } + Eigen::Vector2d diff = goal_position-Pose(idx).position(); + double diff_norm = diff.norm(); + double timestep_vel = diff_norm/max_vel_x; // constant velocity + if (max_acc_x) + { + double timestep_acc = sqrt(2*diff_norm/(*max_acc_x)); // constant acceleration + if (timestep_vel < timestep_acc) timestep = timestep_acc; + else timestep = timestep_vel; + } + else timestep = timestep_vel; + + + PoseSE2 goal(goal_position, goal_orient); + + // if number of samples is not larger than min_samples, insert manually + if ( sizePoses() < min_samples-1 ) + { + ROS_DEBUG("initTEBtoGoal(): number of generated samples is less than specified by min_samples. Forcing the insertion of more samples..."); + while (sizePoses() < min_samples-1) // subtract goal point that will be added later + { + // Each inserted point bisects the remaining distance. Thus the timestep is also bisected. + timestep /= 2; + // simple strategy: interpolate between the current pose and the goal + addPoseAndTimeDiff( PoseSE2::average(BackPose(), goal), timestep ); // let the optimier correct the timestep (TODO: better initialization + } + } + + // now add goal + addPoseAndTimeDiff(goal, timestep); // add goal point + setPoseVertexFixed(sizePoses()-1,true); // GoalConf is a fixed constraint during optimization + } + else // size!=0 + { + ROS_WARN("Cannot init TEB between given configuration and goal, because TEB vectors are not empty or TEB is already initialized (call this function before adding states yourself)!"); + ROS_WARN("Number of TEB configurations: %d, Number of TEB timediffs: %d", sizePoses(), sizeTimeDiffs()); + return false; + } + return true; +} + + +} // namespace teb_local_planner + + + diff --git a/navigations/teb_local_planner/include/teb_local_planner/visualization.h b/navigations/teb_local_planner/include/teb_local_planner/visualization.h new file mode 100755 index 0000000..d01a6fb --- /dev/null +++ b/navigations/teb_local_planner/include/teb_local_planner/visualization.h @@ -0,0 +1,287 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2016, + * TU Dortmund - Institute of Control Theory and Systems Engineering. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the institute nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: Christoph Rösmann + *********************************************************************/ + +#ifndef VISUALIZATION_H_ +#define VISUALIZATION_H_ + + + +// teb stuff +#include +#include +#include + +// ros stuff +#include +#include + +// boost +#include +#include + +// std +#include + +// messages +#include +#include +#include +#include +#include +#include +#include +#include + +namespace teb_local_planner +{ + +class TebOptimalPlanner; //!< Forward Declaration + + +/** + * @class TebVisualization + * @brief Visualize stuff from the teb_local_planner + */ +class TebVisualization +{ +public: + + /** + * @brief Default constructor + * @remarks do not forget to call initialize() + */ + TebVisualization(); + + /** + * @brief Constructor that initializes the class and registers topics + * @param nh local ros::NodeHandle + * @param cfg const reference to the TebConfig class for parameters + */ + TebVisualization(ros::NodeHandle& nh, const TebConfig& cfg); + + /** + * @brief Initializes the class and registers topics. + * + * Call this function if only the default constructor has been called before. + * @param nh local ros::NodeHandle + * @param cfg const reference to the TebConfig class for parameters + */ + void initialize(ros::NodeHandle& nh, const TebConfig& cfg); + + + /** @name Publish to topics */ + //@{ + + /** + * @brief Publish a given global plan to the ros topic \e ../../global_plan + * @param global_plan Pose array describing the global plan + */ + void publishGlobalPlan(const std::vector& global_plan) const; + + /** + * @brief Publish a given local plan to the ros topic \e ../../local_plan + * @param local_plan Pose array describing the local plan + */ + void publishLocalPlan(const std::vector& local_plan) const; + + /** + * @brief Publish Timed_Elastic_Band related stuff (local plan, pose sequence). + * + * Given a Timed_Elastic_Band instance, publish the local plan to \e ../../local_plan + * and the pose sequence to \e ../../teb_poses. + * @param teb const reference to a Timed_Elastic_Band + */ + void publishLocalPlanAndPoses(const TimedElasticBand& teb) const; + + /** + * @brief Publish the visualization of the robot model + * + * @param current_pose Current pose of the robot + * @param robot_model Subclass of BaseRobotFootprintModel + * @param ns Namespace for the marker objects + * @param color Color of the footprint + */ + void publishRobotFootprintModel(const PoseSE2& current_pose, const BaseRobotFootprintModel& robot_model, const std::string& ns = "RobotFootprintModel", + const std_msgs::ColorRGBA& color = toColorMsg(0.5, 0.0, 0.8, 0.0)); + + void publishRobotFootprint(const PoseSE2& current_pose, const std::vector& footprint, + const std::string& ns, const std_msgs::ColorRGBA &color); + + /** + * @brief Publish the robot footprint model and the actual robot footprint at an infeasible pose + * + * @param infeasible_pose Infeasible pose to visualize + * @param robot_model Subclass of BaseRobotFootprintModel + * @param footprint Actual robot footprint + */ + void publishInfeasibleRobotPose(const PoseSE2& infeasible_pose, const BaseRobotFootprintModel& robot_model, + const std::vector& footprint); + + /** + * @brief Publish obstacle positions to the ros topic \e ../../teb_markers + * @todo Move filling of the marker message to polygon class in order to avoid checking types. + * @param obstacles Obstacle container + * @param scale Size of the non-circular obstacles + */ + void publishObstacles(const ObstContainer& obstacles, double scale = 0.1) const; + + /** + * @brief Publish via-points to the ros topic \e ../../teb_markers + * @param via_points via-point container + */ + void publishViaPoints(const std::vector< Eigen::Vector2d, Eigen::aligned_allocator >& via_points, const std::string& ns = "ViaPoints") const; + + /** + * @brief Publish a boost::adjacency_list (boost's graph datatype) via markers. + * @remarks Make sure that vertices of the graph contain a member \c pos as \c Eigen::Vector2d type + * to query metric position values. + * @param graph Const reference to the boost::adjacency_list (graph) + * @param ns_prefix Namespace prefix for the marker objects (the strings "Edges" and "Vertices" will be appended) + * @tparam GraphType boost::graph object in which vertices has the field/member \c pos. + */ + template + void publishGraph(const GraphType& graph, const std::string& ns_prefix = "Graph"); + + /** + * @brief Publish multiple 2D paths (each path given as a point sequence) from a container class. + * + * Provide a std::vector< std::vector< T > > in which T.x() and T.y() exist + * and std::vector could be individually substituded by std::list / std::deque /... + * + * A common point-type for object T could be Eigen::Vector2d. + * + * T could be also a raw pointer std::vector< std::vector< T* > >. + * + * @code + * typedef std::vector > PathType; // could be a list or deque as well ... + * std::vector path_container(2); // init 2 empty paths; the container could be a list or deque as well ... + * // Fill path_container.at(0) with Eigen::Vector2d elements, we skip that here + * // Fill path_container.at(1) with Eigen::Vector2d elements, we skip that here + * publishPathContainer( path_container.begin(), path_container.end() ); + * @endcode + * + * @remarks Actually the underlying path does not necessarily need to be a Eigen::Vector2d sequence. + * Eigen::Vector2d can be replaced with any datatype that implement public x() and y() methods.\n + * @param first Bidirectional iterator pointing to the begin of the path + * @param last Bidirectional iterator pointing to the end of the path + * @param ns Namespace for the marker objects (the strings "Edges" and "Vertices" will be appended) + * @tparam BidirIter Bidirectional iterator to a 2D path (sequence of Eigen::Vector2d elements) in a container + */ + template + void publishPathContainer(BidirIter first, BidirIter last, const std::string& ns = "PathContainer"); + + /** + * @brief Publish multiple Tebs from a container class (publish as marker message). + * + * @param teb_planner Container of boost::shared_ptr< TebOptPlannerPtr > + * @param ns Namespace for the marker objects + */ + void publishTebContainer(const std::vector< boost::shared_ptr >& teb_planner, const std::string& ns = "TebContainer"); + + /** + * @brief Publish a feedback message (multiple trajectory version) + * + * The feedback message contains the all planned trajectory candidates (e.g. if planning in distinctive topologies is turned on). + * Each trajectory is composed of the sequence of poses, the velocity profile and temporal information. + * The feedback message also contains a list of active obstacles. + * @param teb_planners container with multiple tebs (resp. their planner instances) + * @param selected_trajectory_idx Idx of the currently selected trajectory in \c teb_planners + * @param obstacles Container of obstacles + */ + void publishFeedbackMessage(const std::vector< boost::shared_ptr >& teb_planners, unsigned int selected_trajectory_idx, const ObstContainer& obstacles); + + /** + * @brief Publish a feedback message (single trajectory overload) + * + * The feedback message contains the planned trajectory + * that is composed of the sequence of poses, the velocity profile and temporal information. + * The feedback message also contains a list of active obstacles. + * @param teb_planner the planning instance + * @param obstacles Container of obstacles + */ + void publishFeedbackMessage(const TebOptimalPlanner& teb_planner, const ObstContainer& obstacles); + + //@} + + /** + * @brief Helper function to generate a color message from single values + * @param a Alpha value + * @param r Red value + * @param g Green value + * @param b Blue value + * @return Color message + */ + static std_msgs::ColorRGBA toColorMsg(double a, double r, double g, double b); + +protected: + + /** + * @brief Small helper function that checks if initialize() has been called and prints an error message if not. + * @return \c true if not initialized, \c false if everything is ok + */ + bool printErrorWhenNotInitialized() const; + + ros::Publisher global_plan_pub_; //!< Publisher for the global plan + ros::Publisher local_plan_pub_; //!< Publisher for the local plan + ros::Publisher teb_poses_pub_; //!< Publisher for the trajectory pose sequence + ros::Publisher teb_marker_pub_; //!< Publisher for visualization markers + ros::Publisher feedback_pub_; //!< Publisher for the feedback message for analysis and debug purposes + + const TebConfig* cfg_; //!< Config class that stores and manages all related parameters + + bool initialized_; //!< Keeps track about the correct initialization of this class + + +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +}; + +//! Abbrev. for shared instances of the TebVisualization +typedef boost::shared_ptr TebVisualizationPtr; + +//! Abbrev. for shared instances of the TebVisualization (read-only) +typedef boost::shared_ptr TebVisualizationConstPtr; + + +} // namespace teb_local_planner + + +// Include template method implementations / definitions +#include + +#endif /* VISUALIZATION_H_ */ diff --git a/navigations/teb_local_planner/include/teb_local_planner/visualization.hpp b/navigations/teb_local_planner/include/teb_local_planner/visualization.hpp new file mode 100755 index 0000000..e619e52 --- /dev/null +++ b/navigations/teb_local_planner/include/teb_local_planner/visualization.hpp @@ -0,0 +1,225 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2016, + * TU Dortmund - Institute of Control Theory and Systems Engineering. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the institute nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: Christoph Rösmann + *********************************************************************/ + +#include +#include + + +namespace teb_local_planner +{ + + +template +void TebVisualization::publishGraph(const GraphType& graph, const std::string& ns_prefix) +{ + if ( printErrorWhenNotInitialized() ) + return; + + typedef typename boost::graph_traits::vertex_iterator GraphVertexIterator; + typedef typename boost::graph_traits::edge_iterator GraphEdgeIterator; + + // Visualize Edges + visualization_msgs::Marker marker; + marker.header.frame_id = cfg_->map_frame; + marker.header.stamp = ros::Time::now(); + marker.ns = ns_prefix + "Edges"; + marker.id = 0; +// #define TRIANGLE +#ifdef TRIANGLE + marker.type = visualization_msgs::Marker::TRIANGLE_LIST; +#else + marker.type = visualization_msgs::Marker::LINE_LIST; +#endif + marker.action = visualization_msgs::Marker::ADD; + + GraphEdgeIterator it_edge, end_edges; + for (boost::tie(it_edge,end_edges) = boost::edges(graph); it_edge!=end_edges; ++it_edge) + { +#ifdef TRIANGLE + geometry_msgs::Point point_start1; + point_start1.x = graph[boost::source(*it_edge,graph)].pos[0]+0.05; + point_start1.y = graph[boost::source(*it_edge,graph)].pos[1]-0.05; + point_start1.z = 0; + marker.points.push_back(point_start1); + geometry_msgs::Point point_start2; + point_start2.x = graph[boost::source(*it_edge,graph)].pos[0]-0.05; + point_start2.y = graph[boost::source(*it_edge,graph)].pos[1]+0.05; + point_start2.z = 0; + marker.points.push_back(point_start2); + +#else + geometry_msgs::Point point_start; + point_start.x = graph[boost::source(*it_edge,graph)].pos[0]; + point_start.y = graph[boost::source(*it_edge,graph)].pos[1]; + point_start.z = 0; + marker.points.push_back(point_start); +#endif + geometry_msgs::Point point_end; + point_end.x = graph[boost::target(*it_edge,graph)].pos[0]; + point_end.y = graph[boost::target(*it_edge,graph)].pos[1]; + point_end.z = 0; + marker.points.push_back(point_end); + + // add color + std_msgs::ColorRGBA color; + color.a = 1.0; + color.r = 0; + color.g = 0; + color.b = 1; + marker.colors.push_back(color); + marker.colors.push_back(color); +#ifdef TRIANGLE + marker.colors.push_back(color); +#endif + } + +#ifdef TRIANGLE + marker.scale.x = 1; + marker.scale.y = 1; + marker.scale.z = 1; +#else + marker.scale.x = 0.01; +#endif + marker.color.a = 1.0; + marker.color.r = 0.0; + marker.color.g = 1.0; + marker.color.b = 0.0; + + // Now publish edge markers + teb_marker_pub_.publish( marker ); + + // Visualize vertices + marker.header.frame_id = cfg_->map_frame; + marker.header.stamp = ros::Time::now(); + marker.ns = ns_prefix + "Vertices"; + marker.id = 0; + marker.type = visualization_msgs::Marker::POINTS; + marker.action = visualization_msgs::Marker::ADD; + + GraphVertexIterator it_vert, end_vert; + for (boost::tie(it_vert,end_vert) = boost::vertices(graph); it_vert!=end_vert; ++it_vert) + { + geometry_msgs::Point point; + point.x = graph[*it_vert].pos[0]; + point.y = graph[*it_vert].pos[1]; + point.z = 0; + marker.points.push_back(point); + // add color + + std_msgs::ColorRGBA color; + color.a = 1.0; + if (it_vert==end_vert-1) + { + color.r = 1; + color.g = 0; + color.b = 0; + } + else + { + color.r = 0; + color.g = 1; + color.b = 0; + } + marker.colors.push_back(color); + } + // set first color (start vertix) to blue + if (!marker.colors.empty()) + { + marker.colors.front().b = 1; + marker.colors.front().g = 0; + } + + marker.scale.x = 0.1; + marker.scale.y = 0.1; + marker.color.a = 1.0; + marker.color.r = 0.0; + marker.color.g = 1.0; + marker.color.b = 0.0; + + // Now publish vertex markers + teb_marker_pub_.publish( marker ); +} + +template +void TebVisualization::publishPathContainer(BidirIter first, BidirIter last, const std::string& ns) +{ + if ( printErrorWhenNotInitialized() ) + return; + + visualization_msgs::Marker marker; + marker.header.frame_id = cfg_->map_frame; + marker.header.stamp = ros::Time::now(); + marker.ns = ns; + marker.id = 0; + marker.type = visualization_msgs::Marker::LINE_LIST; + marker.action = visualization_msgs::Marker::ADD; + + typedef typename std::iterator_traits::value_type PathType; // Get type of the path (point container) + + // Iterate through path container + while(first != last) + { + // iterate single path points + typename PathType::const_iterator it_point, end_point; + for (it_point = first->begin(), end_point = boost::prior(first->end()); it_point != end_point; ++it_point) + { + geometry_msgs::Point point_start; + point_start.x = get_const_reference(*it_point).x(); + point_start.y = get_const_reference(*it_point).y(); + point_start.z = 0; + marker.points.push_back(point_start); + + geometry_msgs::Point point_end; + point_end.x = get_const_reference(*boost::next(it_point)).x(); + point_end.y = get_const_reference(*boost::next(it_point)).y(); + point_end.z = 0; + marker.points.push_back(point_end); + } + ++first; + } + marker.scale.x = 0.01; + marker.color.a = 1.0; + marker.color.r = 0.0; + marker.color.g = 1.0; + marker.color.b = 0.0; + + teb_marker_pub_.publish( marker ); +} + + +} // namespace teb_local_planner \ No newline at end of file diff --git a/navigations/teb_local_planner/launch/test_optim_node.launch b/navigations/teb_local_planner/launch/test_optim_node.launch new file mode 100755 index 0000000..9749d95 --- /dev/null +++ b/navigations/teb_local_planner/launch/test_optim_node.launch @@ -0,0 +1,10 @@ + + + + + + + + + + diff --git a/navigations/teb_local_planner/msg/FeedbackMsg.msg b/navigations/teb_local_planner/msg/FeedbackMsg.msg new file mode 100755 index 0000000..8b4977c --- /dev/null +++ b/navigations/teb_local_planner/msg/FeedbackMsg.msg @@ -0,0 +1,15 @@ +# Message that contains intermediate results +# and diagnostics of the (predictive) planner. + +std_msgs/Header header + +# The planned trajectory (or if multiple plans exist, all of them) +teb_local_planner/TrajectoryMsg[] trajectories + +# Index of the trajectory in 'trajectories' that is selected currently +uint16 selected_trajectory_idx + +# List of active obstacles +costmap_converter/ObstacleArrayMsg obstacles_msg + + diff --git a/navigations/teb_local_planner/msg/TrajectoryMsg.msg b/navigations/teb_local_planner/msg/TrajectoryMsg.msg new file mode 100755 index 0000000..2e90313 --- /dev/null +++ b/navigations/teb_local_planner/msg/TrajectoryMsg.msg @@ -0,0 +1,6 @@ +# Message that contains a trajectory for mobile robot navigation + +std_msgs/Header header +teb_local_planner/TrajectoryPointMsg[] trajectory + + diff --git a/navigations/teb_local_planner/msg/TrajectoryPointMsg.msg b/navigations/teb_local_planner/msg/TrajectoryPointMsg.msg new file mode 100755 index 0000000..eb1ef8b --- /dev/null +++ b/navigations/teb_local_planner/msg/TrajectoryPointMsg.msg @@ -0,0 +1,21 @@ +# Message that contains single point on a trajectory suited for mobile navigation. +# The trajectory is described by a sequence of poses, velocities, +# accelerations and temporal information. + +# Why this message type? +# nav_msgs/Path describes only a path without temporal information. +# trajectory_msgs package contains only messages for joint trajectories. + +# The pose of the robot +geometry_msgs/Pose pose + +# Corresponding velocity +geometry_msgs/Twist velocity + +# Corresponding acceleration +geometry_msgs/Twist acceleration + +duration time_from_start + + + diff --git a/navigations/teb_local_planner/package.xml b/navigations/teb_local_planner/package.xml new file mode 100755 index 0000000..baa6d8a --- /dev/null +++ b/navigations/teb_local_planner/package.xml @@ -0,0 +1,57 @@ + + + teb_local_planner + + 0.9.1 + + + The teb_local_planner package implements a plugin + to the base_local_planner of the 2D navigation stack. + The underlying method called Timed Elastic Band locally optimizes + the robot's trajectory with respect to trajectory execution time, + separation from obstacles and compliance with kinodynamic constraints at runtime. + + + + Christoph Rösmann + + BSD + + http://wiki.ros.org/teb_local_planner + + Christoph Rösmann + + catkin + + cmake_modules + message_generation + tf2_eigen + tf2_geometry_msgs + + message_runtime + message_runtime + + base_local_planner + costmap_2d + costmap_converter + + dynamic_reconfigure + geometry_msgs + interactive_markers + libg2o + nav_core + nav_msgs + mbf_costmap_core + mbf_msgs + pluginlib + roscpp + std_msgs + tf2 + tf2_ros + visualization_msgs + + + + + + diff --git a/navigations/teb_local_planner/scripts/cmd_vel_to_ackermann_drive.py b/navigations/teb_local_planner/scripts/cmd_vel_to_ackermann_drive.py new file mode 100755 index 0000000..ed2ed2a --- /dev/null +++ b/navigations/teb_local_planner/scripts/cmd_vel_to_ackermann_drive.py @@ -0,0 +1,65 @@ +#!/usr/bin/env python + +# Author: christoph.roesmann@tu-dortmund.de + +import rospy, math +from geometry_msgs.msg import Twist +from ackermann_msgs.msg import AckermannDriveStamped + + +def convert_trans_rot_vel_to_steering_angle(v, omega, wheelbase): + if omega == 0 or v == 0: + return 0 + + radius = v / omega + return math.atan(wheelbase / radius) + + +def cmd_callback(data): + global wheelbase + global ackermann_cmd_topic + global frame_id + global pub + global cmd_angle_instead_rotvel + + v = data.linear.x + # if cmd_angle_instead_rotvel is true, the rotational velocity is already converted in the C++ node + # in this case this script only needs to do the msg conversion from twist to Ackermann drive + if cmd_angle_instead_rotvel: + steering = data.angular.z + else: + steering = convert_trans_rot_vel_to_steering_angle(v, data.angular.z, wheelbase) + + msg = AckermannDriveStamped() + msg.header.stamp = rospy.Time.now() + msg.header.frame_id = frame_id + msg.drive.steering_angle = steering + msg.drive.speed = v + + pub.publish(msg) + + + + + +if __name__ == '__main__': + try: + + rospy.init_node('cmd_vel_to_ackermann_drive') + + twist_cmd_topic = rospy.get_param('~twist_cmd_topic', '/cmd_vel') + ackermann_cmd_topic = rospy.get_param('~ackermann_cmd_topic', '/ackermann_cmd') + wheelbase = rospy.get_param('~wheelbase', 1.0) + frame_id = rospy.get_param('~frame_id', 'odom') + cmd_angle_instead_rotvel = rospy.get_param('/move_base/TebLocalPlannerROS/cmd_angle_instead_rotvel', False) + + rospy.Subscriber(twist_cmd_topic, Twist, cmd_callback, queue_size=1) + pub = rospy.Publisher(ackermann_cmd_topic, AckermannDriveStamped, queue_size=1) + + rospy.loginfo("Node 'cmd_vel_to_ackermann_drive' started.\nListening to %s, publishing to %s. Frame id: %s, wheelbase: %f", "/cmd_vel", ackermann_cmd_topic, frame_id, wheelbase) + + rospy.spin() + + except rospy.ROSInterruptException: + pass + diff --git a/navigations/teb_local_planner/scripts/export_to_mat.py b/navigations/teb_local_planner/scripts/export_to_mat.py new file mode 100755 index 0000000..1cc3351 --- /dev/null +++ b/navigations/teb_local_planner/scripts/export_to_mat.py @@ -0,0 +1,112 @@ +#!/usr/bin/env python + +# This small script subscribes to the FeedbackMsg message of teb_local_planner +# and exports data to a mat file. +# publish_feedback must be turned on such that the planner publishes this information. +# Author: christoph.roesmann@tu-dortmund.de + +import rospy, math +from teb_local_planner.msg import FeedbackMsg, TrajectoryMsg, TrajectoryPointMsg +from geometry_msgs.msg import PolygonStamped, Point32, Quaternion +from tf.transformations import euler_from_quaternion +import numpy as np +import scipy.io as sio +import time + +def feedback_callback(data): + global got_data + + if not data.trajectories: # empty + trajectory = [] + return + + if got_data: + return + + got_data = True + + # copy trajectory + trajectories = [] + for traj in data.trajectories: + trajectory = [] +# # store as struct and cell array +# for point in traj.trajectory: +# (roll,pitch,yaw) = euler_from_quaternion([point.pose.orientation.x,point.pose.orientation.y,point.pose.orientation.z,point.pose.orientation.w]) +# pose = {'x': point.pose.position.x, 'y': point.pose.position.y, 'theta': yaw} +# velocity = {'v': point.velocity.linear.x, 'omega': point.velocity.angular.z} +# time_from_start = point.time_from_start.to_sec() +# trajectory.append({'pose': pose, 'velocity': velocity, 'time_from_start': time_from_start}) + + # store as all-in-one mat + arr = np.zeros([6, len(traj.trajectory)], dtype='double'); # x, y, theta, v, omega, t + for index, point in enumerate(traj.trajectory): + arr[0,index] = point.pose.position.x + arr[1,index] = point.pose.position.y + (roll,pitch,yaw) = euler_from_quaternion([point.pose.orientation.x,point.pose.orientation.y,point.pose.orientation.z,point.pose.orientation.w]) + arr[2,index] = yaw + arr[3,index] = point.velocity.linear.x + arr[4,index] = point.velocity.angular.z + arr[5,index] = point.time_from_start.to_sec() + +# trajectories.append({'raw': trajectory, 'mat': arr}) + trajectories.append({'data': arr, 'legend': ['x','y','theta','v','omega','t']}) + + # copy obstacles + obstacles = [] + for obst_id, obst in enumerate(data.obstacle_msg.obstacles): + #polygon = [] + #for point in obst.polygon.points: + # polygon.append({'x': point.x, 'y': point.y, 'z': point.z}) + obst_arr = np.zeros([4, len(obst.polygon.points)], dtype='double'); # x, y + for index, point in enumerate(obst.polygon.points): + obst_arr[0, index] = point.x + obst_arr[1, index] = point.y + obst_arr[2, index] = data.obstacle_msg.velocities[obst_id].twist.linear.x + obst_arr[3, index] = data.obstacle_msg.velocities[obst_id].twist.linear.y + + #obstacles.append(polygon) + obstacles.append({'data': obst_arr, 'legend': ['x','y', 'v_x', 'v_y']}) + + + # create main struct: + mat = {'selected_trajectory_idx': data.selected_trajectory_idx, 'trajectories': trajectories, 'obstacles': obstacles} + + timestr = time.strftime("%Y%m%d_%H%M%S") + filename = '/home/albers/MasterThesis/Matlab/Homotopie/test_optim_node/' + 'teb_data_' + timestr + '.mat' + + rospy.loginfo("Saving mat-file '%s'.", filename) + sio.savemat(filename, mat) + + + + + +def feedback_exporter(): + global got_data + + rospy.init_node("export_to_mat", anonymous=True) + + + topic_name = "/test_optim_node/teb_feedback" # define feedback topic here! + + rospy.Subscriber(topic_name, FeedbackMsg, feedback_callback, queue_size = 1) + + rospy.loginfo("Waiting for feedback message on topic %s.", topic_name) + + r = rospy.Rate(2) # define rate here + while not rospy.is_shutdown(): + + if got_data: + rospy.loginfo("Data export completed.") + return + + r.sleep() + +if __name__ == '__main__': + try: + global got_data + got_data = False + feedback_exporter() + except rospy.ROSInterruptException: + pass + diff --git a/navigations/teb_local_planner/scripts/export_to_svg.py b/navigations/teb_local_planner/scripts/export_to_svg.py new file mode 100755 index 0000000..8d5edf2 --- /dev/null +++ b/navigations/teb_local_planner/scripts/export_to_svg.py @@ -0,0 +1,244 @@ +#!/usr/bin/env python +# -*- coding: utf-8 -*- +""" +======================================================================================== +# This small script subscribes to the FeedbackMsg message of teb_local_planner +# and converts the current scene to a svg-image +# publish_feedback must be turned on such that the planner publishes this information. +# Author: christoph.roesmann@tu-dortmund.de + +It is recommendable to start this node after initialization of TEB is completed. + +Requirements: +svgwrite: A Python library to create SVG drawings. http://pypi.python.org/pypi/svgwrite +======================================================================================= +""" +import roslib; +import rospy +import svgwrite +import math +import sys +import time +import random +from svgwrite import cm, mm +from teb_local_planner.msg import FeedbackMsg, TrajectoryMsg, TrajectoryPointMsg +from geometry_msgs.msg import PolygonStamped, Point32, Quaternion + + +# ================= PARAMETERS ================== +# TODO: In case of a more general node, change parameter to ros-parameter +# Drawing parameters: +SCALE = 200 # Overall scaling: 100 pixel = 1 m +MIN_POSE_DISTANCE = 0.3 # Distance between two consecutive poses in SVG-image +SCALE_VELOCITY_VEC = 0.4 # Scaling of velocity vectors -> 1 cell = 1/SCALE_VELOCITY_VEC m/s +GRID_X_MIN = -2 # Define, how many cells your grid should contain in each direction. +GRID_X_MAX = 2 +GRID_Y_MIN = -2 +GRID_Y_MAX = 1 + +# TEB parameters: +OBSTACLE_DIST = 50 *SCALE/100 # cm + + +# ================= FUNCTIONS =================== + +def sign(number): + """ + Signum function: get sign of a number + + @param number: get sign of this number + @type number: numeric type (eg. integer) + @return: sign of number + @rtype: integer {1, -1, 0} + """ + return cmp(number,0) + +def arrowMarker(color='green', orientation='auto'): + """ + Create an arrow marker with svgwrite + + @return: arrow marker + @rtype: svg_write marker object + """ + arrow = svg.marker(insert=(1,5), size=(4,3), orient=orientation) + arrow.viewbox(width=10, height=10) + arrow.add(svg.polyline([(0,0),(10,5),(0,10),(1,5)], fill=color, opacity=1.0)) + svg.defs.add(arrow) + return arrow + +def quaternion2YawDegree(orientation): + """ + Get yaw angle [degree] from quaternion representation + + @param orientation: orientation in quaternions to read from + @type orientation: geometry_msgs/Quaternion + @return: yaw angle [degree] + @rtype: float + """ + yawRad = math.atan2(2*(orientation.x*orientation.y+orientation.z*orientation.w),1-2*(pow(orientation.y,2)+pow(orientation.z,2))) + return yawRad*180/math.pi + + +def feedback_callback(data): + """ + Callback for receiving TEB and obstacle information + + @param data: Received feedback message + @type data: visualization_msgs/Marker + + @globalparam tebList: Received TEB List + @globaltype tebList: teb_local_planner/FeedbackMsg + """ + # TODO: Remove global variables + global feedbackMsg + + if not feedbackMsg: + feedbackMsg = data + rospy.loginfo("TEB feedback message received...") + + +# ================ MAIN FUNCTION ================ + +if __name__ == '__main__': + rospy.init_node('export_to_svg', anonymous=True) + + topic_name = "/test_optim_node/teb_feedback" # define feedback topic here! + + rospy.Subscriber(topic_name, FeedbackMsg, feedback_callback, queue_size = 1) + + rospy.loginfo("Waiting for feedback message on topic %s.", topic_name) + + rate = rospy.Rate(10.0) + feedbackMsg = [] + + timestr = time.strftime("%Y%m%d_%H%M%S") + filename_string = "teb_svg_" + timestr + '.svg' + + rospy.loginfo("SVG will be written to '%s'.", filename_string) + + random.seed(0) + + svg=svgwrite.Drawing(filename=filename_string, debug=True) + + # Create viewbox -> this box defines the size of the visible drawing + svg.viewbox(GRID_X_MIN*SCALE-1*SCALE,GRID_Y_MIN*SCALE-1*SCALE,GRID_X_MAX*SCALE-GRID_X_MIN*SCALE+2*SCALE,GRID_Y_MAX*SCALE-GRID_Y_MIN*SCALE+2*SCALE) + + # Draw grid: + hLines = svg.add(svg.g(id='hLines', stroke='black')) + hLines.add(svg.line(start=(GRID_X_MIN*SCALE, 0), end=(GRID_X_MAX*SCALE, 0))) + for y in range(GRID_Y_MAX): + hLines.add(svg.line(start=(GRID_X_MIN*SCALE, SCALE+y*SCALE), end=(GRID_X_MAX*SCALE, SCALE+y*SCALE))) + for y in range(-GRID_Y_MIN): + hLines.add(svg.line(start=(GRID_X_MIN*SCALE, -SCALE-y*SCALE), end=(GRID_X_MAX*SCALE, -SCALE-y*SCALE))) + vLines = svg.add(svg.g(id='vline', stroke='black')) + vLines.add(svg.line(start=(0, GRID_Y_MIN*SCALE), end=(0, GRID_Y_MAX*SCALE))) + for x in range(GRID_X_MAX): + vLines.add(svg.line(start=(SCALE+x*SCALE, GRID_Y_MIN*SCALE), end=(SCALE+x*SCALE, GRID_Y_MAX*SCALE))) + for x in range(-GRID_X_MIN): + vLines.add(svg.line(start=(-SCALE-x*SCALE, GRID_Y_MIN*SCALE), end=(-SCALE-x*SCALE, GRID_Y_MAX*SCALE))) + + + # Draw legend: + legend = svg.g(id='legend', font_size=25) + stringGeometry = "Geometry: 1 Unit = 1.0m" + legendGeometry = svg.text(stringGeometry) + legend.add(legendGeometry) + legend.translate(tx=GRID_X_MIN*SCALE, ty=GRID_Y_MAX*SCALE + 30) # Move legend to buttom left corner + svg.add(legend) + + + #arrow = arrowMarker() # Init arrow marker + + rospy.loginfo("Initialization completed.\nWaiting for feedback message...") + + # -------------------- WAIT FOR CALLBACKS -------------------------- + while not rospy.is_shutdown(): + if feedbackMsg: + break # Leave loop after receiving all necessary TEB information (see callbacks) to finish drawing + rate.sleep() + # ------------------------------------------------------------------ + + if not feedbackMsg.trajectories: + rospy.loginfo("Received message does not contain trajectories. Shutting down...") + sys.exit() + + if len(feedbackMsg.trajectories[0].trajectory) < 2: + rospy.loginfo("Received message does not contain trajectories with at least two states (start and goal). Shutting down...") + sys.exit() + + # iterate trajectories + for index, traj in enumerate(feedbackMsg.trajectories): + + #color + traj_color = svgwrite.rgb(random.randint(0, 255), random.randint(0, 255), random.randint(0, 255), 'RGB') + + # Iterate through TEB positions -> Draw Paths + points = [] + for point in traj.trajectory: + points.append( (point.pose.position.x*SCALE,-point.pose.position.y*SCALE) ) # y is negative in image coordinates + # svgwrite rotates clockwise! + + + if index == feedbackMsg.selected_trajectory_idx: # highlight currently selected teb + line = svg.add( svg.polyline(points=points, fill='none', stroke=traj_color, stroke_width=10, stroke_linecap='round', \ + stroke_linejoin='round', opacity=1.0 ) ) + else: + line = svg.add( svg.polyline(points=points, fill='none', stroke=traj_color, stroke_width=10, stroke_linecap='butt', \ + stroke_linejoin='round', stroke_dasharray='10,3', opacity=1.0 ) ) + #marker_points = points[::7] + #markerline = svg.add( svg.polyline(points=marker_points, fill='none', stroke=traj_color, stroke_width=10, opacity=0.0 ) ) + #arrow = arrowMarker(traj_color) + #markerline.set_markers( (arrow, arrow, arrow) ) + #line.set_markers( (arrow, arrow, arrow) ) + #line['marker-start'] = arrow.get_funciri() + + + # Add Start and Goal Point + start_pose = feedbackMsg.trajectories[0].trajectory[0].pose + goal_pose = feedbackMsg.trajectories[0].trajectory[len(feedbackMsg.trajectories[0].trajectory)-1].pose + start_position = start_pose.position + goal_position = goal_pose.position + svg.add(svg.circle(center=(start_position.x*SCALE,-start_position.y*SCALE), r=10, stroke_width=1, stroke='blue', fill ='blue')) + svg.add(svg.text("Start", (start_position.x*SCALE-70, -start_position.y*SCALE+45), font_size=35)) # Add label + svg.add(svg.circle(center=(goal_position.x*SCALE,-goal_position.y*SCALE), r=10, stroke_width=1, stroke='red', fill ='red')) + svg.add(svg.text("Goal", (goal_position.x*SCALE-40, -goal_position.y*SCALE+45), font_size=35)) # Add label + + # draw start arrow + start_arrow = svg.polyline([(0,-1),(6,-1),(5,-5),(15,0),(5,5),(6,1),(0,1)], fill='blue', opacity=1.0) + start_arrow.translate(start_position.x*SCALE,-start_position.y*SCALE) + start_arrow.rotate( quaternion2YawDegree(start_pose.orientation) ) + start_arrow.scale(3) + svg.add(start_arrow) + + # draw goal arrow + goal_arrow = svg.polyline([(0,-1),(6,-1),(5,-5),(15,0),(5,5),(6,1),(0,1)], fill='red', opacity=1.0) + goal_arrow.translate(goal_position.x*SCALE,-goal_position.y*SCALE) + goal_arrow.rotate( quaternion2YawDegree(goal_pose.orientation) ) + goal_arrow.scale(3) + svg.add(goal_arrow) + + # Draw obstacles + for obstacle in feedbackMsg.obstacles: + if len(obstacle.polygon.points) == 1: # point obstacle + point = obstacle.polygon.points[0] + svg.add(svg.circle(center=(point.x*SCALE,-point.y*SCALE), r=OBSTACLE_DIST, stroke_width=1, stroke='grey', fill ='grey', opacity=0.3)) + svg.add(svg.circle(center=(point.x*SCALE,-point.y*SCALE), r=15, stroke_width=1, stroke='black', fill ='black')) + svg.add(svg.text("Obstacle", (point.x*SCALE-70, -point.y*SCALE+45), font_size=35)) # Add label + if len(obstacle.polygon.points) == 2: # line obstacle + line_start = obstacle.polygon.points[0] + line_end = obstacle.polygon.points[1] + svg.add(svg.line(start=(line_start.x*SCALE,-line_start.y*SCALE), end=(line_end.x*SCALE,-line_end.y*SCALE), stroke='black', fill='gray', stroke_width=1, opacity=1.0)) + svg.add(svg.text("Obstacle", (line_start.x*SCALE-70, -line_start.y*SCALE+45), font_size=35)) # Add label + if len(obstacle.polygon.points) > 2: # polygon obstacle + vertices = [] + for point in obstacle.polygon.points: + vertices.append((point.x*SCALE, -point.y*SCALE)) + svg.add(svg.polygon(points=vertices, stroke='black', fill='gray', stroke_width=1, opacity=1.0)) + svg.add(svg.text("Obstacle", (obstacle.polygon.points[0].x*SCALE-70, -obstacle.polygon.points.y*SCALE+45), font_size=35)) # Add label + + + + # Save svg to file (svg_output.svg) and exit node + svg.save() + + rospy.loginfo("Drawing completed.") diff --git a/navigations/teb_local_planner/scripts/publish_dynamic_obstacle.py b/navigations/teb_local_planner/scripts/publish_dynamic_obstacle.py new file mode 100755 index 0000000..0cc16d4 --- /dev/null +++ b/navigations/teb_local_planner/scripts/publish_dynamic_obstacle.py @@ -0,0 +1,67 @@ +#!/usr/bin/env python + +# Author: franz.albers@tu-dortmund.de + +import rospy, math, tf +from costmap_converter.msg import ObstacleArrayMsg, ObstacleMsg +from geometry_msgs.msg import PolygonStamped, Point32, QuaternionStamped, Quaternion, TwistWithCovariance +from tf.transformations import quaternion_from_euler + + +def publish_obstacle_msg(): + pub = rospy.Publisher('/test_optim_node/obstacles', ObstacleArrayMsg, queue_size=1) + #pub = rospy.Publisher('/p3dx/move_base/TebLocalPlannerROS/obstacles', ObstacleArrayMsg, queue_size=1) + rospy.init_node("test_obstacle_msg") + + y_0 = -3.0 + vel_x = 0.0 + vel_y = 0.3 + range_y = 6.0 + + obstacle_msg = ObstacleArrayMsg() + obstacle_msg.header.stamp = rospy.Time.now() + obstacle_msg.header.frame_id = "map" # CHANGE HERE: odom/map + + # Add point obstacle + obstacle_msg.obstacles.append(ObstacleMsg()) + obstacle_msg.obstacles[0].id = 99 + obstacle_msg.obstacles[0].polygon.points = [Point32()] + obstacle_msg.obstacles[0].polygon.points[0].x = -1.5 + obstacle_msg.obstacles[0].polygon.points[0].y = 0 + obstacle_msg.obstacles[0].polygon.points[0].z = 0 + + yaw = math.atan2(vel_y, vel_x) + q = tf.transformations.quaternion_from_euler(0,0,yaw) + obstacle_msg.obstacles[0].orientation = Quaternion(*q) + + obstacle_msg.obstacles[0].velocities.twist.linear.x = vel_x + obstacle_msg.obstacles[0].velocities.twist.linear.y = vel_y + obstacle_msg.obstacles[0].velocities.twist.linear.z = 0 + obstacle_msg.obstacles[0].velocities.twist.angular.x = 0 + obstacle_msg.obstacles[0].velocities.twist.angular.y = 0 + obstacle_msg.obstacles[0].velocities.twist.angular.z = 0 + + r = rospy.Rate(10) # 10hz + t = 0.0 + while not rospy.is_shutdown(): + + # Vary y component of the point obstacle + if (vel_y >= 0): + obstacle_msg.obstacles[0].polygon.points[0].y = y_0 + (vel_y*t)%range_y + else: + obstacle_msg.obstacles[0].polygon.points[0].y = y_0 + (vel_y*t)%range_y - range_y + + t = t + 0.1 + + pub.publish(obstacle_msg) + + r.sleep() + + + +if __name__ == '__main__': + try: + publish_obstacle_msg() + except rospy.ROSInterruptException: + pass + diff --git a/navigations/teb_local_planner/scripts/publish_test_obstacles.py b/navigations/teb_local_planner/scripts/publish_test_obstacles.py new file mode 100755 index 0000000..800803d --- /dev/null +++ b/navigations/teb_local_planner/scripts/publish_test_obstacles.py @@ -0,0 +1,76 @@ +#!/usr/bin/env python + +# Author: christoph.roesmann@tu-dortmund.de + +import rospy, math +from costmap_converter.msg import ObstacleArrayMsg, ObstacleMsg +from geometry_msgs.msg import PolygonStamped, Point32 + + +def publish_obstacle_msg(): + pub = rospy.Publisher('/test_optim_node/obstacles', ObstacleArrayMsg, queue_size=1) + #pub = rospy.Publisher('/p3dx/move_base/TebLocalPlannerROS/obstacles', ObstacleArrayMsg, queue_size=1) + rospy.init_node("test_obstacle_msg") + + + obstacle_msg = ObstacleArrayMsg() + obstacle_msg.header.stamp = rospy.Time.now() + obstacle_msg.header.frame_id = "odom" # CHANGE HERE: odom/map + + # Add point obstacle + obstacle_msg.obstacles.append(ObstacleMsg()) + obstacle_msg.obstacles[0].id = 0 + obstacle_msg.obstacles[0].polygon.points = [Point32()] + obstacle_msg.obstacles[0].polygon.points[0].x = 1.5 + obstacle_msg.obstacles[0].polygon.points[0].y = 0 + obstacle_msg.obstacles[0].polygon.points[0].z = 0 + + + # Add line obstacle + obstacle_msg.obstacles.append(ObstacleMsg()) + obstacle_msg.obstacles[1].id = 1 + line_start = Point32() + line_start.x = -2.5 + line_start.y = 0.5 + #line_start.y = -3 + line_end = Point32() + line_end.x = -2.5 + line_end.y = 2 + #line_end.y = -4 + obstacle_msg.obstacles[1].polygon.points = [line_start, line_end] + + # Add polygon obstacle + obstacle_msg.obstacles.append(ObstacleMsg()) + obstacle_msg.obstacles[1].id = 2 + v1 = Point32() + v1.x = -1 + v1.y = -1 + v2 = Point32() + v2.x = -0.5 + v2.y = -1.5 + v3 = Point32() + v3.x = 0 + v3.y = -1 + obstacle_msg.obstacles[2].polygon.points = [v1, v2, v3] + + + r = rospy.Rate(10) # 10hz + t = 0.0 + while not rospy.is_shutdown(): + + # Vary y component of the point obstacle + obstacle_msg.obstacles[0].polygon.points[0].y = 1*math.sin(t) + t = t + 0.1 + + pub.publish(obstacle_msg) + + r.sleep() + + + +if __name__ == '__main__': + try: + publish_obstacle_msg() + except rospy.ROSInterruptException: + pass + diff --git a/navigations/teb_local_planner/scripts/publish_viapoints.py b/navigations/teb_local_planner/scripts/publish_viapoints.py new file mode 100755 index 0000000..7bd0c7e --- /dev/null +++ b/navigations/teb_local_planner/scripts/publish_viapoints.py @@ -0,0 +1,46 @@ +#!/usr/bin/env python + +# Author: christoph.roesmann@tu-dortmund.de + +import rospy, math +from geometry_msgs.msg import PoseStamped +from nav_msgs.msg import Path + + +def publish_via_points_msg(): + pub = rospy.Publisher('/test_optim_node/via_points', Path, queue_size=1) + rospy.init_node("test_via_points_msg") + + + via_points_msg = Path() + via_points_msg.header.stamp = rospy.Time.now() + via_points_msg.header.frame_id = "odom" # CHANGE HERE: odom/map + + # Add via-points + point1 = PoseStamped() + point1.pose.position.x = 0.0; + point1.pose.position.y = 1.5; + + point2 = PoseStamped() + point2.pose.position.x = 2.0; + point2.pose.position.y = -0.5; + + + via_points_msg.poses = [point1, point2] + + r = rospy.Rate(5) # 10hz + t = 0.0 + while not rospy.is_shutdown(): + + pub.publish(via_points_msg) + + r.sleep() + + + +if __name__ == '__main__': + try: + publish_via_points_msg() + except rospy.ROSInterruptException: + pass + diff --git a/navigations/teb_local_planner/scripts/visualize_velocity_profile.py b/navigations/teb_local_planner/scripts/visualize_velocity_profile.py new file mode 100755 index 0000000..b9b6d78 --- /dev/null +++ b/navigations/teb_local_planner/scripts/visualize_velocity_profile.py @@ -0,0 +1,76 @@ +#!/usr/bin/env python + +# This small script subscribes to the FeedbackMsg message of teb_local_planner +# and plots the current velocity. +# publish_feedback must be turned on such that the planner publishes this information. +# Author: christoph.roesmann@tu-dortmund.de + +import rospy, math +from teb_local_planner.msg import FeedbackMsg, TrajectoryMsg, TrajectoryPointMsg +from geometry_msgs.msg import PolygonStamped, Point32 +import numpy as np +import matplotlib.pyplot as plotter + +def feedback_callback(data): + global trajectory + + if not data.trajectories: # empty + trajectory = [] + return + trajectory = data.trajectories[data.selected_trajectory_idx].trajectory + + +def plot_velocity_profile(fig, ax_v, ax_omega, t, v, omega): + ax_v.cla() + ax_v.grid() + ax_v.set_ylabel('Trans. velocity [m/s]') + ax_v.plot(t, v, '-bx') + ax_omega.cla() + ax_omega.grid() + ax_omega.set_ylabel('Rot. velocity [rad/s]') + ax_omega.set_xlabel('Time [s]') + ax_omega.plot(t, omega, '-bx') + fig.canvas.draw() + + + +def velocity_plotter(): + global trajectory + rospy.init_node("visualize_velocity_profile", anonymous=True) + + topic_name = "/test_optim_node/teb_feedback" + topic_name = rospy.get_param('~feedback_topic', topic_name) + rospy.Subscriber(topic_name, FeedbackMsg, feedback_callback, queue_size = 1) # define feedback topic here! + + rospy.loginfo("Visualizing velocity profile published on '%s'.",topic_name) + rospy.loginfo("Make sure to enable rosparam 'publish_feedback' in the teb_local_planner.") + + # two subplots sharing the same t axis + fig, (ax_v, ax_omega) = plotter.subplots(2, sharex=True) + plotter.ion() + plotter.show() + + + r = rospy.Rate(2) # define rate here + while not rospy.is_shutdown(): + + t = [] + v = [] + omega = [] + + for point in trajectory: + t.append(point.time_from_start.to_sec()) + v.append(point.velocity.linear.x) + omega.append(point.velocity.angular.z) + + plot_velocity_profile(fig, ax_v, ax_omega, np.asarray(t), np.asarray(v), np.asarray(omega)) + + r.sleep() + +if __name__ == '__main__': + try: + trajectory = [] + velocity_plotter() + except rospy.ROSInterruptException: + pass + diff --git a/navigations/teb_local_planner/src/graph_search.cpp b/navigations/teb_local_planner/src/graph_search.cpp new file mode 100755 index 0000000..1893589 --- /dev/null +++ b/navigations/teb_local_planner/src/graph_search.cpp @@ -0,0 +1,342 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2017, + * TU Dortmund - Institute of Control Theory and Systems Engineering. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the institute nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Authors: Christoph Rösmann, Franz Albers + *********************************************************************/ + +#include +#include + +namespace teb_local_planner +{ + +void GraphSearchInterface::DepthFirst(HcGraph& g, std::vector& visited, const HcGraphVertexType& goal, double start_orientation, + double goal_orientation, const geometry_msgs::Twist* start_velocity, bool free_goal_vel) +{ + // see http://www.technical-recipes.com/2011/a-recursive-algorithm-to-find-all-paths-between-two-given-nodes/ for details on finding all simple paths + + if ((int)hcp_->getTrajectoryContainer().size() >= cfg_->hcp.max_number_classes) + return; // We do not need to search for further possible alternative homotopy classes. + + HcGraphVertexType back = visited.back(); + + /// Examine adjacent nodes + HcGraphAdjecencyIterator it, end; + for ( boost::tie(it,end) = boost::adjacent_vertices(back,g); it!=end; ++it) + { + if ( std::find(visited.begin(), visited.end(), *it)!=visited.end() ) + continue; // already visited + + if ( *it == goal ) // goal reached + { + visited.push_back(*it); + + // Add new TEB, if this path belongs to a new homotopy class + hcp_->addAndInitNewTeb(visited.begin(), visited.end(), boost::bind(getVector2dFromHcGraph, _1, boost::cref(graph_)), + start_orientation, goal_orientation, start_velocity, free_goal_vel); + + visited.pop_back(); + break; + } + } + + /// Recursion for all adjacent vertices + for ( boost::tie(it,end) = boost::adjacent_vertices(back,g); it!=end; ++it) + { + if ( std::find(visited.begin(), visited.end(), *it)!=visited.end() || *it == goal) + continue; // already visited || goal reached + + + visited.push_back(*it); + + // recursion step + DepthFirst(g, visited, goal, start_orientation, goal_orientation, start_velocity, free_goal_vel); + + visited.pop_back(); + } +} + + + +void lrKeyPointGraph::createGraph(const PoseSE2& start, const PoseSE2& goal, double dist_to_obst, double obstacle_heading_threshold, const geometry_msgs::Twist* start_velocity, bool free_goal_vel) +{ + // Clear existing graph and paths + clearGraph(); + if((int)hcp_->getTrajectoryContainer().size() >= cfg_->hcp.max_number_classes) + return; + // Direction-vector between start and goal and normal-vector: + Eigen::Vector2d diff = goal.position()-start.position(); + + if (diff.norm()goal_tolerance.xy_goal_tolerance) + { + ROS_DEBUG("HomotopyClassPlanner::createProbRoadmapGraph(): xy-goal-tolerance already reached."); + if (hcp_->getTrajectoryContainer().empty()) + { + ROS_INFO("HomotopyClassPlanner::createProbRoadmapGraph(): Initializing a small straight line to just correct orientation errors."); + hcp_->addAndInitNewTeb(start, goal, start_velocity, free_goal_vel); + } + return; + } + + Eigen::Vector2d normal(-diff[1],diff[0]); // normal-vector + normal.normalize(); + normal = normal*dist_to_obst; // scale with obstacle_distance; + + // Insert Vertices + HcGraphVertexType start_vtx = boost::add_vertex(graph_); // start vertex + graph_[start_vtx].pos = start.position(); + diff.normalize(); + + // store nearest obstacle keypoints -> only used if limit_obstacle_heading is enabled + std::pair nearest_obstacle; // both vertices are stored + double min_dist = DBL_MAX; + + if (hcp_->obstacles()!=NULL) + { + for (ObstContainer::const_iterator it_obst = hcp_->obstacles()->begin(); it_obst != hcp_->obstacles()->end(); ++it_obst) + { + // check if obstacle is placed in front of start point + Eigen::Vector2d start2obst = (*it_obst)->getCentroid() - start.position(); + double dist = start2obst.norm(); + if (start2obst.dot(diff)/dist<0.1) + continue; + + // Add Keypoints + HcGraphVertexType u = boost::add_vertex(graph_); + graph_[u].pos = (*it_obst)->getCentroid() + normal; + HcGraphVertexType v = boost::add_vertex(graph_); + graph_[v].pos = (*it_obst)->getCentroid() - normal; + + // store nearest obstacle + if (obstacle_heading_threshold && distobstacles()!=NULL) + { + bool collision = false; + for (ObstContainer::const_iterator it_obst = hcp_->obstacles()->begin(); it_obst != hcp_->obstacles()->end(); ++it_obst) + { + if ( (*it_obst)->checkLineIntersection(graph_[*it_i].pos,graph_[*it_j].pos, 0.5*dist_to_obst) ) + { + collision = true; + break; + } + } + if (collision) + continue; + } + + // Create Edge + boost::add_edge(*it_i,*it_j,graph_); + } + } + + + // Find all paths between start and goal! + std::vector visited; + visited.push_back(start_vtx); + DepthFirst(graph_,visited,goal_vtx, start.theta(), goal.theta(), start_velocity, free_goal_vel); +} + + + +void ProbRoadmapGraph::createGraph(const PoseSE2& start, const PoseSE2& goal, double dist_to_obst, double obstacle_heading_threshold, const geometry_msgs::Twist* start_velocity, bool free_goal_vel) +{ + // Clear existing graph and paths + clearGraph(); + if((int)hcp_->getTrajectoryContainer().size() >= cfg_->hcp.max_number_classes) + return; + // Direction-vector between start and goal and normal-vector: + Eigen::Vector2d diff = goal.position()-start.position(); + double start_goal_dist = diff.norm(); + + if (start_goal_distgoal_tolerance.xy_goal_tolerance) + { + ROS_DEBUG("HomotopyClassPlanner::createProbRoadmapGraph(): xy-goal-tolerance already reached."); + if (hcp_->getTrajectoryContainer().empty()) + { + ROS_INFO("HomotopyClassPlanner::createProbRoadmapGraph(): Initializing a small straight line to just correct orientation errors."); + hcp_->addAndInitNewTeb(start, goal, start_velocity, free_goal_vel); + } + return; + } + Eigen::Vector2d normal(-diff.coeffRef(1),diff.coeffRef(0)); // normal-vector + normal.normalize(); + + // Now sample vertices between start, goal and a specified width between both sides + // Let's start with a square area between start and goal (maybe change it later to something like a circle or whatever) + + double area_width = cfg_->hcp.roadmap_graph_area_width; + + boost::random::uniform_real_distribution distribution_x(0, start_goal_dist * cfg_->hcp.roadmap_graph_area_length_scale); + boost::random::uniform_real_distribution distribution_y(0, area_width); + + double phi = atan2(diff.coeffRef(1),diff.coeffRef(0)); // rotate area by this angle + Eigen::Rotation2D rot_phi(phi); + + Eigen::Vector2d area_origin; + if (cfg_->hcp.roadmap_graph_area_length_scale != 1.0) + area_origin = start.position() + 0.5*(1.0-cfg_->hcp.roadmap_graph_area_length_scale)*start_goal_dist*diff.normalized() - 0.5*area_width*normal; // bottom left corner of the origin + else + area_origin = start.position() - 0.5*area_width*normal; // bottom left corner of the origin + + // Insert Vertices + HcGraphVertexType start_vtx = boost::add_vertex(graph_); // start vertex + graph_[start_vtx].pos = start.position(); + diff.normalize(); // normalize in place + + + // Start sampling + for (int i=0; i < cfg_->hcp.roadmap_graph_no_samples; ++i) + { + Eigen::Vector2d sample; +// bool coll_free; +// do // sample as long as a collision free sample is found +// { + // Sample coordinates + sample = area_origin + rot_phi*Eigen::Vector2d(distribution_x(rnd_generator_), distribution_y(rnd_generator_)); + + // Test for collision + // we do not care for collision checking here to improve efficiency, since we perform resampling repeatedly. + // occupied vertices are ignored in the edge insertion state since they always violate the edge-obstacle collision check. +// coll_free = true; +// for (ObstContainer::const_iterator it_obst = obstacles_->begin(); it_obst != obstacles_->end(); ++it_obst) +// { +// if ( (*it_obst)->checkCollision(sample, dist_to_obst)) // TODO really keep dist_to_obst here? +// { +// coll_free = false; +// break; +// } +// } +// +// } while (!coll_free && ros::ok()); + + // Add new vertex + HcGraphVertexType v = boost::add_vertex(graph_); + graph_[v].pos = sample; + } + + // Now add goal vertex + HcGraphVertexType goal_vtx = boost::add_vertex(graph_); // goal vertex + graph_[goal_vtx].pos = goal.position(); + + + // Insert Edges + HcGraphVertexIterator it_i, end_i, it_j, end_j; + for (boost::tie(it_i,end_i) = boost::vertices(graph_); it_i!=boost::prior(end_i); ++it_i) // ignore goal in this loop + { + for (boost::tie(it_j,end_j) = boost::vertices(graph_); it_j!=end_j; ++it_j) // check all forward connections + { + if (it_i==it_j) // same vertex found + continue; + + Eigen::Vector2d distij = graph_[*it_j].pos-graph_[*it_i].pos; + distij.normalize(); // normalize in place + + // Check if the direction is backwards: + if (distij.dot(diff)<=obstacle_heading_threshold) + continue; // diff is already normalized + + + // Collision Check + bool collision = false; + for (ObstContainer::const_iterator it_obst = hcp_->obstacles()->begin(); it_obst != hcp_->obstacles()->end(); ++it_obst) + { + if ( (*it_obst)->checkLineIntersection(graph_[*it_i].pos,graph_[*it_j].pos, dist_to_obst) ) + { + collision = true; + break; + } + } + if (collision) + continue; + + // Create Edge + boost::add_edge(*it_i,*it_j,graph_); + } + } + + /// Find all paths between start and goal! + std::vector visited; + visited.push_back(start_vtx); + DepthFirst(graph_,visited,goal_vtx, start.theta(), goal.theta(), start_velocity, free_goal_vel); +} + +} // end namespace diff --git a/navigations/teb_local_planner/src/homotopy_class_planner.cpp b/navigations/teb_local_planner/src/homotopy_class_planner.cpp new file mode 100755 index 0000000..05ceccd --- /dev/null +++ b/navigations/teb_local_planner/src/homotopy_class_planner.cpp @@ -0,0 +1,849 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2016, + * TU Dortmund - Institute of Control Theory and Systems Engineering. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the institute nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: Christoph Rösmann + *********************************************************************/ + +#include + +#include + +namespace teb_local_planner +{ + +HomotopyClassPlanner::HomotopyClassPlanner() : cfg_(NULL), obstacles_(NULL), via_points_(NULL), robot_model_(new PointRobotFootprint()), initial_plan_(NULL), initialized_(false) +{ +} + +HomotopyClassPlanner::HomotopyClassPlanner(const TebConfig& cfg, ObstContainer* obstacles, RobotFootprintModelPtr robot_model, + TebVisualizationPtr visual, const ViaPointContainer* via_points) : initial_plan_(NULL) +{ + initialize(cfg, obstacles, robot_model, visual, via_points); +} + +HomotopyClassPlanner::~HomotopyClassPlanner() +{ +} + +void HomotopyClassPlanner::initialize(const TebConfig& cfg, ObstContainer* obstacles, RobotFootprintModelPtr robot_model, + TebVisualizationPtr visual, const ViaPointContainer* via_points) +{ + cfg_ = &cfg; + obstacles_ = obstacles; + via_points_ = via_points; + robot_model_ = robot_model; + + if (cfg_->hcp.simple_exploration) + graph_search_ = boost::shared_ptr(new lrKeyPointGraph(*cfg_, this)); + else + graph_search_ = boost::shared_ptr(new ProbRoadmapGraph(*cfg_, this)); + + std::random_device rd; + random_.seed(rd()); + + initialized_ = true; + + setVisualization(visual); +} + +void HomotopyClassPlanner::updateRobotModel(RobotFootprintModelPtr robot_model ) +{ + robot_model_ = robot_model; +} + +void HomotopyClassPlanner::setVisualization(TebVisualizationPtr visualization) +{ + visualization_ = visualization; +} + + + +bool HomotopyClassPlanner::plan(const std::vector& initial_plan, const geometry_msgs::Twist* start_vel, bool free_goal_vel) +{ + ROS_ASSERT_MSG(initialized_, "Call initialize() first."); + + // store initial plan for further initializations (must be valid for the lifetime of this object or clearPlanner() is called!) + initial_plan_ = &initial_plan; + + PoseSE2 start(initial_plan.front().pose); + PoseSE2 goal(initial_plan.back().pose); + + return plan(start, goal, start_vel, free_goal_vel); +} + + +bool HomotopyClassPlanner::plan(const tf::Pose& start, const tf::Pose& goal, const geometry_msgs::Twist* start_vel, bool free_goal_vel) +{ + ROS_ASSERT_MSG(initialized_, "Call initialize() first."); + PoseSE2 start_pose(start); + PoseSE2 goal_pose(goal); + return plan(start_pose, goal_pose, start_vel, free_goal_vel); +} + +bool HomotopyClassPlanner::plan(const PoseSE2& start, const PoseSE2& goal, const geometry_msgs::Twist* start_vel, bool free_goal_vel) +{ + ROS_ASSERT_MSG(initialized_, "Call initialize() first."); + + // Update old TEBs with new start, goal and velocity + updateAllTEBs(&start, &goal, start_vel); + + // Init new TEBs based on newly explored homotopy classes + exploreEquivalenceClassesAndInitTebs(start, goal, cfg_->obstacles.min_obstacle_dist, start_vel, free_goal_vel); + // update via-points if activated + updateReferenceTrajectoryViaPoints(cfg_->hcp.viapoints_all_candidates); + // Optimize all trajectories in alternative homotopy classes + optimizeAllTEBs(cfg_->optim.no_inner_iterations, cfg_->optim.no_outer_iterations); + // Select which candidate (based on alternative homotopy classes) should be used + selectBestTeb(); + + initial_plan_ = nullptr; // clear pointer to any previous initial plan (any previous plan is useless regarding the h-signature); + return true; +} + +bool HomotopyClassPlanner::getVelocityCommand(double& vx, double& vy, double& omega, int look_ahead_poses) const +{ + TebOptimalPlannerConstPtr best_teb = bestTeb(); + if (!best_teb) + { + vx = 0; + vy = 0; + omega = 0; + return false; + } + + return best_teb->getVelocityCommand(vx, vy, omega, look_ahead_poses); +} + + + + +void HomotopyClassPlanner::visualize() +{ + if (visualization_) + { + // Visualize graph + if (cfg_->hcp.visualize_hc_graph && graph_search_) + visualization_->publishGraph(graph_search_->graph_); + + // Visualize active tebs as marker + visualization_->publishTebContainer(tebs_); + + // Visualize best teb and feedback message if desired + TebOptimalPlannerConstPtr best_teb = bestTeb(); + if (best_teb) + { + visualization_->publishLocalPlanAndPoses(best_teb->teb()); + + if (best_teb->teb().sizePoses() > 0) //TODO maybe store current pose (start) within plan method as class field. + visualization_->publishRobotFootprintModel(best_teb->teb().Pose(0), *robot_model_); + + // feedback message + if (cfg_->trajectory.publish_feedback) + { + int best_idx = bestTebIdx(); + if (best_idx>=0) + visualization_->publishFeedbackMessage(tebs_, (unsigned int) best_idx, *obstacles_); + } + } + } + else ROS_DEBUG("Ignoring HomotopyClassPlanner::visualize() call, since no visualization class was instantiated before."); +} + + + +bool HomotopyClassPlanner::hasEquivalenceClass(const EquivalenceClassPtr& eq_class) const +{ + // iterate existing h-signatures and check if there is an existing H-Signature similar the candidate + for (const std::pair& eqrel : equivalence_classes_) + { + if (eq_class->isEqual(*eqrel.first)) + return true; // Found! Homotopy class already exists, therefore nothing added + } + return false; +} + +bool HomotopyClassPlanner::addEquivalenceClassIfNew(const EquivalenceClassPtr& eq_class, bool lock) +{ + if (!eq_class) + return false; + + if (!eq_class->isValid()) + { + ROS_WARN("HomotopyClassPlanner: Ignoring invalid H-signature"); + return false; + } + + if (hasEquivalenceClass(eq_class)) + { + // Allow up to configured number of Tebs that are in the same homotopy + // class as the current (best) Teb to avoid being stuck in a local minimum + if (!isInBestTebClass(eq_class) || numTebsInBestTebClass() >= cfg_->hcp.max_number_plans_in_current_class) + return false; + } + + // Homotopy class not found -> Add to class-list, return that the h-signature is new + equivalence_classes_.push_back(std::make_pair(eq_class,lock)); + return true; +} + + +void HomotopyClassPlanner::renewAndAnalyzeOldTebs(bool delete_detours) +{ + // clear old h-signatures (since they could be changed due to new obstacle positions. + equivalence_classes_.clear(); + + // Adding the equivalence class of the latest best_teb_ first + TebOptPlannerContainer::iterator it_best_teb = best_teb_ ? std::find(tebs_.begin(), tebs_.end(), best_teb_) : tebs_.end(); + bool has_best_teb = it_best_teb != tebs_.end(); + if (has_best_teb) + { + std::iter_swap(tebs_.begin(), it_best_teb); // Putting the last best teb at the beginning of the container + best_teb_eq_class_ = calculateEquivalenceClass(best_teb_->teb().poses().begin(), + best_teb_->teb().poses().end(), getCplxFromVertexPosePtr , obstacles_, + best_teb_->teb().timediffs().begin(), best_teb_->teb().timediffs().end()); + addEquivalenceClassIfNew(best_teb_eq_class_); + } + // Collect h-signatures for all existing TEBs and store them together with the corresponding iterator / pointer: +// typedef std::list< std::pair > > TebCandidateType; +// TebCandidateType teb_candidates; + + // get new homotopy classes and delete multiple TEBs per homotopy class. Skips the best teb if available (added before). + TebOptPlannerContainer::iterator it_teb = has_best_teb ? std::next(tebs_.begin(), 1) : tebs_.begin(); + while(it_teb != tebs_.end()) + { + // calculate equivalence class for the current candidate + EquivalenceClassPtr equivalence_class = calculateEquivalenceClass(it_teb->get()->teb().poses().begin(), it_teb->get()->teb().poses().end(), getCplxFromVertexPosePtr , obstacles_, + it_teb->get()->teb().timediffs().begin(), it_teb->get()->teb().timediffs().end()); + +// teb_candidates.push_back(std::make_pair(it_teb,H)); + + // WORKAROUND until the commented code below works + // Here we do not compare cost values. Just first come first serve... + bool new_flag = addEquivalenceClassIfNew(equivalence_class); + if (!new_flag) + { + it_teb = tebs_.erase(it_teb); + continue; + } + + ++it_teb; + } + if(delete_detours) + deletePlansDetouringBackwards(cfg_->hcp.detours_orientation_tolerance, cfg_->hcp.length_start_orientation_vector); + + // Find multiple candidates and delete the one with higher cost + // TODO: this code needs to be adpated. Erasing tebs from the teb container_ could make iteratores stored in the candidate list invalid! +// TebCandidateType::reverse_iterator cand_i = teb_candidates.rbegin(); +// int test_idx = 0; +// while (cand_i != teb_candidates.rend()) +// { +// +// TebCandidateType::reverse_iterator cand_j = std::find_if(boost::next(cand_i),teb_candidates.rend(), boost::bind(compareH,_1,cand_i->second)); +// if (cand_j != teb_candidates.rend() && cand_j != cand_i) +// { +// TebOptimalPlannerPtr pt1 = *(cand_j->first); +// TebOptimalPlannerPtr pt2 = *(cand_i->first); +// assert(pt1); +// assert(pt2); +// if ( cand_j->first->get()->getCurrentCost().sum() > cand_i->first->get()->getCurrentCost().sum() ) +// { +// // found one that has higher cost, therefore erase cand_j +// tebs_.erase(cand_j->first); +// teb_candidates.erase(cand_j); +// } +// else // otherwise erase cand_i +// { +// tebs_.erase(cand_i->first); +// cand_i = teb_candidates.erase(cand_i); +// } +// } +// else +// { +// ROS_WARN_STREAM("increase cand_i"); +// ++cand_i; +// } +// } + + // now add the h-signatures to the internal lookup-table (but only if there is no existing duplicate) +// for (TebCandidateType::iterator cand=teb_candidates.begin(); cand!=teb_candidates.end(); ++cand) +// { +// bool new_flag = addNewHSignatureIfNew(cand->second, cfg_->hcp.h_signature_threshold); +// if (!new_flag) +// { +// // ROS_ERROR_STREAM("getAndFilterHomotopyClassesTEB() - This schould not be happen."); +// tebs_.erase(cand->first); +// } +// } + +} + +void HomotopyClassPlanner::updateReferenceTrajectoryViaPoints(bool all_trajectories) +{ + if ( (!all_trajectories && !initial_plan_) || !via_points_ || via_points_->empty() || cfg_->optim.weight_viapoint <= 0) + return; + + if(equivalence_classes_.size() < tebs_.size()) + { + ROS_ERROR("HomotopyClassPlanner::updateReferenceTrajectoryWithViaPoints(): Number of h-signatures does not match number of trajectories."); + return; + } + + if (all_trajectories) + { + // enable via-points for all tebs + for (std::size_t i=0; i < equivalence_classes_.size(); ++i) + { + tebs_[i]->setViaPoints(via_points_); + } + } + else + { + // enable via-points for teb in the same hommotopy class as the initial_plan and deactivate it for all other ones + for (std::size_t i=0; i < equivalence_classes_.size(); ++i) + { + if(initial_plan_eq_class_->isEqual(*equivalence_classes_[i].first)) + tebs_[i]->setViaPoints(via_points_); + else + tebs_[i]->setViaPoints(NULL); + } + } +} + + +void HomotopyClassPlanner::exploreEquivalenceClassesAndInitTebs(const PoseSE2& start, const PoseSE2& goal, double dist_to_obst, const geometry_msgs::Twist* start_vel, bool free_goal_vel) +{ + // first process old trajectories + renewAndAnalyzeOldTebs(cfg_->hcp.delete_detours_backwards); + randomlyDropTebs(); + + // inject initial plan if available and not yet captured + if (initial_plan_) + { + initial_plan_teb_ = addAndInitNewTeb(*initial_plan_, start_vel, free_goal_vel); + } + else + { + initial_plan_teb_.reset(); + initial_plan_teb_ = getInitialPlanTEB(); // this method searches for initial_plan_eq_class_ in the teb container (-> if !initial_plan_teb_) + } + + // now explore new homotopy classes and initialize tebs if new ones are found. The appropriate createGraph method is chosen via polymorphism. + graph_search_->createGraph(start,goal,dist_to_obst,cfg_->hcp.obstacle_heading_threshold, start_vel, free_goal_vel); +} + + +TebOptimalPlannerPtr HomotopyClassPlanner::addAndInitNewTeb(const PoseSE2& start, const PoseSE2& goal, const geometry_msgs::Twist* start_velocity, bool free_goal_vel) +{ + if(tebs_.size() >= cfg_->hcp.max_number_classes) + return TebOptimalPlannerPtr(); + TebOptimalPlannerPtr candidate = TebOptimalPlannerPtr( new TebOptimalPlanner(*cfg_, obstacles_, robot_model_, visualization_)); + + candidate->teb().initTrajectoryToGoal(start, goal, 0, cfg_->robot.max_vel_x, cfg_->trajectory.min_samples, cfg_->trajectory.allow_init_with_backwards_motion); + + if (start_velocity) + candidate->setVelocityStart(*start_velocity); + + EquivalenceClassPtr H = calculateEquivalenceClass(candidate->teb().poses().begin(), candidate->teb().poses().end(), getCplxFromVertexPosePtr, obstacles_, + candidate->teb().timediffs().begin(), candidate->teb().timediffs().end()); + + if (free_goal_vel) + candidate->setVelocityGoalFree(); + + if(addEquivalenceClassIfNew(H)) + { + tebs_.push_back(candidate); + return tebs_.back(); + } + + // If the candidate constitutes no new equivalence class, return a null pointer + return TebOptimalPlannerPtr(); +} + + +bool HomotopyClassPlanner::isInBestTebClass(const EquivalenceClassPtr& eq_class) const +{ + bool answer = false; + if (best_teb_eq_class_) + answer = best_teb_eq_class_->isEqual(*eq_class); + return answer; +} + +int HomotopyClassPlanner::numTebsInClass(const EquivalenceClassPtr& eq_class) const +{ + int count = 0; + for (const std::pair& eqrel : equivalence_classes_) + { + if (eq_class->isEqual(*eqrel.first)) + ++count; + } + return count; +} + +int HomotopyClassPlanner::numTebsInBestTebClass() const +{ + int count = 0; + if (best_teb_eq_class_) + count = numTebsInClass(best_teb_eq_class_); + return count; +} + +TebOptimalPlannerPtr HomotopyClassPlanner::addAndInitNewTeb(const std::vector& initial_plan, const geometry_msgs::Twist* start_velocity, bool free_goal_vel) +{ + if(tebs_.size() >= cfg_->hcp.max_number_classes) + return TebOptimalPlannerPtr(); + TebOptimalPlannerPtr candidate = TebOptimalPlannerPtr( new TebOptimalPlanner(*cfg_, obstacles_, robot_model_, visualization_)); + + candidate->teb().initTrajectoryToGoal(initial_plan, cfg_->robot.max_vel_x, cfg_->robot.max_vel_theta, + cfg_->trajectory.global_plan_overwrite_orientation, cfg_->trajectory.min_samples, cfg_->trajectory.allow_init_with_backwards_motion); + + if (start_velocity) + candidate->setVelocityStart(*start_velocity); + + if (free_goal_vel) + candidate->setVelocityGoalFree(); + + // store the h signature of the initial plan to enable searching a matching teb later. + initial_plan_eq_class_ = calculateEquivalenceClass(candidate->teb().poses().begin(), candidate->teb().poses().end(), getCplxFromVertexPosePtr, obstacles_, + candidate->teb().timediffs().begin(), candidate->teb().timediffs().end()); + + if(addEquivalenceClassIfNew(initial_plan_eq_class_, true)) // also prevent candidate from deletion + { + tebs_.push_back(candidate); + return tebs_.back(); + } + + // If the candidate constitutes no new equivalence class, return a null pointer + return TebOptimalPlannerPtr(); +} + +void HomotopyClassPlanner::updateAllTEBs(const PoseSE2* start, const PoseSE2* goal, const geometry_msgs::Twist* start_velocity) +{ + // If new goal is too far away, clear all existing trajectories to let them reinitialize later. + // Since all Tebs are sharing the same fixed goal pose, just take the first candidate: + if (!tebs_.empty() + && ((goal->position() - tebs_.front()->teb().BackPose().position()).norm() >= cfg_->trajectory.force_reinit_new_goal_dist + || fabs(g2o::normalize_theta(goal->theta() - tebs_.front()->teb().BackPose().theta())) >= cfg_->trajectory.force_reinit_new_goal_angular)) + { + ROS_DEBUG("New goal: distance to existing goal is higher than the specified threshold. Reinitalizing trajectories."); + tebs_.clear(); + equivalence_classes_.clear(); + } + + // hot-start from previous solutions + for (TebOptPlannerContainer::iterator it_teb = tebs_.begin(); it_teb != tebs_.end(); ++it_teb) + { + it_teb->get()->teb().updateAndPruneTEB(*start, *goal); + if (start_velocity) + it_teb->get()->setVelocityStart(*start_velocity); + } +} + + +void HomotopyClassPlanner::optimizeAllTEBs(int iter_innerloop, int iter_outerloop) +{ + // optimize TEBs in parallel since they are independend of each other + if (cfg_->hcp.enable_multithreading) + { + // Must prevent .join_all() from throwing exception if interruption was + // requested, as this can lead to multiple threads operating on the same + // TEB, which leads to SIGSEGV + boost::this_thread::disable_interruption di; + + boost::thread_group teb_threads; + for (TebOptPlannerContainer::iterator it_teb = tebs_.begin(); it_teb != tebs_.end(); ++it_teb) + { + teb_threads.create_thread( boost::bind(&TebOptimalPlanner::optimizeTEB, it_teb->get(), iter_innerloop, iter_outerloop, + true, cfg_->hcp.selection_obst_cost_scale, cfg_->hcp.selection_viapoint_cost_scale, + cfg_->hcp.selection_alternative_time_cost) ); + } + teb_threads.join_all(); + } + else + { + for (TebOptPlannerContainer::iterator it_teb = tebs_.begin(); it_teb != tebs_.end(); ++it_teb) + { + it_teb->get()->optimizeTEB(iter_innerloop,iter_outerloop, true, cfg_->hcp.selection_obst_cost_scale, + cfg_->hcp.selection_viapoint_cost_scale, cfg_->hcp.selection_alternative_time_cost); // compute cost as well inside optimizeTEB (last argument = true) + } + } +} + +TebOptimalPlannerPtr HomotopyClassPlanner::getInitialPlanTEB() +{ + // first check stored teb object + if (initial_plan_teb_) + { + // check if the teb is still part of the teb container + if ( std::find(tebs_.begin(), tebs_.end(), initial_plan_teb_ ) != tebs_.end() ) + return initial_plan_teb_; + else + { + initial_plan_teb_.reset(); // reset pointer for next call + ROS_DEBUG("initial teb not found, trying to find a match according to the cached equivalence class"); + } + } + + // reset the locked state for equivalence classes // TODO: this might be adapted if not only the plan containing the initial plan is locked! + for (int i=0; iisValid()) + { + if (equivalence_classes_.size() == tebs_.size()) + { + for (int i=0; iisEqual(*initial_plan_eq_class_)) + { + equivalence_classes_[i].second = true; + return tebs_[i]; + } + } + } + else + ROS_ERROR("HomotopyClassPlanner::getInitialPlanTEB(): number of equivalence classes (%lu) and number of trajectories (%lu) does not match.", equivalence_classes_.size(), tebs_.size()); + } + else + ROS_DEBUG("HomotopyClassPlanner::getInitialPlanTEB(): initial TEB not found in the set of available trajectories."); + + return TebOptimalPlannerPtr(); +} + +void HomotopyClassPlanner::randomlyDropTebs() +{ + if (cfg_->hcp.selection_dropping_probability == 0.0) + { + return; + } + // interate both vectors in parallel + auto it_eqrel = equivalence_classes_.begin(); + auto it_teb = tebs_.begin(); + while (it_teb != tebs_.end() && it_eqrel != equivalence_classes_.end()) + { + if (it_teb->get() != best_teb_.get() // Always preserve the "best" teb + && (random_() <= cfg_->hcp.selection_dropping_probability * random_.max())) + { + it_teb = tebs_.erase(it_teb); + it_eqrel = equivalence_classes_.erase(it_eqrel); + } + else + { + ++it_teb; + ++it_eqrel; + } + } +} + +TebOptimalPlannerPtr HomotopyClassPlanner::selectBestTeb() +{ + double min_cost = std::numeric_limits::max(); // maximum cost + double min_cost_last_best = std::numeric_limits::max(); + double min_cost_initial_plan_teb = std::numeric_limits::max(); + TebOptimalPlannerPtr initial_plan_teb = getInitialPlanTEB(); + + // check if last best_teb is still a valid candidate + if (best_teb_ && std::find(tebs_.begin(), tebs_.end(), best_teb_) != tebs_.end()) + { + // get cost of this candidate + min_cost_last_best = best_teb_->getCurrentCost() * cfg_->hcp.selection_cost_hysteresis; // small hysteresis + last_best_teb_ = best_teb_; + } + else + { + last_best_teb_.reset(); + } + + if (initial_plan_teb) // the validity was already checked in getInitialPlanTEB() + { + // get cost of this candidate + min_cost_initial_plan_teb = initial_plan_teb->getCurrentCost() * cfg_->hcp.selection_prefer_initial_plan; // small hysteresis + } + + + best_teb_.reset(); // reset pointer + + for (TebOptPlannerContainer::iterator it_teb = tebs_.begin(); it_teb != tebs_.end(); ++it_teb) + { + // check if the related TEB leaves the local costmap region +// if (tebs_.size()>1 && !(*it_teb)->teb().isTrajectoryInsideRegion(20, -1, 1)) +// { +// ROS_INFO("HomotopyClassPlanner::selectBestTeb(): skipping trajectories that are not inside the local costmap"); +// continue; +// } + + double teb_cost; + + if (*it_teb == last_best_teb_) + teb_cost = min_cost_last_best; // skip already known cost value of the last best_teb + else if (*it_teb == initial_plan_teb) + teb_cost = min_cost_initial_plan_teb; + else + teb_cost = it_teb->get()->getCurrentCost(); + + if (teb_cost < min_cost) + { + // check if this candidate is currently not selected + best_teb_ = *it_teb; + min_cost = teb_cost; + } + } + + + // in case we haven't found any teb due to some previous checks, investigate list again +// if (!best_teb_ && !tebs_.empty()) +// { +// ROS_DEBUG("all " << tebs_.size() << " tebs rejected previously"); +// if (tebs_.size()==1) +// best_teb_ = tebs_.front(); +// else // if multiple TEBs are available: +// { +// // try to use the one that relates to the initial plan +// TebOptimalPlannerPtr initial_plan_teb = getInitialPlanTEB(); +// if (initial_plan_teb) +// best_teb_ = initial_plan_teb; +// else +// { +// // now compute the cost for the rest (we haven't computed it before) +// for (TebOptPlannerContainer::iterator it_teb = tebs_.begin(); it_teb != tebs_.end(); ++it_teb) +// { +// double teb_cost = it_teb->get()->getCurrentCost(); +// if (teb_cost < min_cost) +// { +// // check if this candidate is currently not selected +// best_teb_ = *it_teb; +// min_cost = teb_cost; +// } +// } +// } +// } +// } + + // check if we are allowed to change + if (last_best_teb_ && best_teb_ != last_best_teb_) + { + ros::Time now = ros::Time::now(); + if ((now-last_eq_class_switching_time_).toSec() > cfg_->hcp.switching_blocking_period) + { + last_eq_class_switching_time_ = now; + } + else + { + ROS_DEBUG("HomotopyClassPlanner::selectBestTeb(): Switching equivalence classes blocked (check parameter switching_blocking_period."); + // block switching, so revert best_teb_ + best_teb_ = last_best_teb_; + } + + } + + + return best_teb_; +} + +int HomotopyClassPlanner::bestTebIdx() const +{ + if (tebs_.size() == 1) + return 0; + + if (!best_teb_) + return -1; + + int idx = 0; + for (TebOptPlannerContainer::const_iterator it_teb = tebs_.begin(); it_teb != tebs_.end(); ++it_teb, ++idx) + { + if (*it_teb == best_teb_) + return idx; + } + return -1; +} + +bool HomotopyClassPlanner::isTrajectoryFeasible(base_local_planner::CostmapModel* costmap_model, const std::vector& footprint_spec, + double inscribed_radius, double circumscribed_radius, int look_ahead_idx, double feasibility_check_lookahead_distance) +{ + bool feasible = false; + while(ros::ok() && !feasible && tebs_.size() > 0) + { + TebOptimalPlannerPtr best = findBestTeb(); + if (!best) + { + ROS_ERROR("Couldn't retrieve the best plan"); + return false; + } + feasible = best->isTrajectoryFeasible(costmap_model, footprint_spec, inscribed_radius, circumscribed_radius, look_ahead_idx, feasibility_check_lookahead_distance); + if(!feasible) + { + removeTeb(best); + if(last_best_teb_ && (last_best_teb_ == best)) // Same plan as before. + return feasible; // Not failing could result in oscillations between trajectories. + } + } + return feasible; +} + +TebOptimalPlannerPtr HomotopyClassPlanner::findBestTeb() +{ + if(tebs_.empty()) + return TebOptimalPlannerPtr(); + if (!best_teb_ || std::find(tebs_.begin(), tebs_.end(), best_teb_) == tebs_.end()) + best_teb_ = selectBestTeb(); + return best_teb_; +} + +TebOptPlannerContainer::iterator HomotopyClassPlanner::removeTeb(TebOptimalPlannerPtr& teb) +{ + TebOptPlannerContainer::iterator return_iterator = tebs_.end(); + if(equivalence_classes_.size() != tebs_.size()) + { + ROS_ERROR("removeTeb: size of eq classes != size of tebs"); + return return_iterator; + } + auto it_eq_classes = equivalence_classes_.begin(); + for(auto it = tebs_.begin(); it != tebs_.end(); ++it) + { + if(*it == teb) + { + return_iterator = tebs_.erase(it); + equivalence_classes_.erase(it_eq_classes); + break; + } + ++it_eq_classes; + } + return return_iterator; +} + +void HomotopyClassPlanner::setPreferredTurningDir(RotType dir) +{ + // set preferred turning dir for all TEBs + for (TebOptPlannerContainer::const_iterator it_teb = tebs_.begin(); it_teb != tebs_.end(); ++it_teb) + { + (*it_teb)->setPreferredTurningDir(dir); + } +} + +bool HomotopyClassPlanner::hasDiverged() const +{ + // Early return if there is no best trajectory initialized + if (!best_teb_) + return false; + + return best_teb_->hasDiverged(); +} + +void HomotopyClassPlanner::computeCurrentCost(std::vector& cost, double obst_cost_scale, double viapoint_cost_scale, bool alternative_time_cost) +{ + for (TebOptPlannerContainer::iterator it_teb = tebs_.begin(); it_teb != tebs_.end(); ++it_teb) + { + it_teb->get()->computeCurrentCost(cost, obst_cost_scale, viapoint_cost_scale, alternative_time_cost); + } +} + +void HomotopyClassPlanner::deletePlansDetouringBackwards(const double orient_threshold, + const double len_orientation_vector) +{ + if (tebs_.size() < 2 || !best_teb_ || std::find(tebs_.begin(), tebs_.end(), best_teb_) == tebs_.end() || + best_teb_->teb().sizePoses() < 2) + { + return; // A moving direction wasn't chosen yet + } + double current_movement_orientation; + double best_plan_duration = std::max(best_teb_->teb().getSumOfAllTimeDiffs(), 1.0); + if(!computeStartOrientation(best_teb_, len_orientation_vector, current_movement_orientation)) + return; // The plan is shorter than len_orientation_vector + for(auto it_teb = tebs_.begin(); it_teb != tebs_.end();) + { + if(*it_teb == best_teb_) // The current plan should not be considered a detour + { + ++it_teb; + continue; + } + if((*it_teb)->teb().sizePoses() < 2) + { + ROS_DEBUG("Discarding a plan with less than 2 poses"); + it_teb = removeTeb(*it_teb); + continue; + } + double plan_orientation; + if(!computeStartOrientation(*it_teb, len_orientation_vector, plan_orientation)) + { + ROS_DEBUG("Failed to compute the start orientation for one of the tebs, likely close to the target"); + it_teb = removeTeb(*it_teb); + continue; + } + if(fabs(g2o::normalize_theta(plan_orientation - current_movement_orientation)) > orient_threshold) + { + it_teb = removeTeb(*it_teb); // Plan detouring backwards + continue; + } + if(!it_teb->get()->isOptimized()) + { + ROS_DEBUG("Removing a teb because it's not optimized"); + it_teb = removeTeb(*it_teb); // Deletes tebs that cannot be optimized (last optim call failed) + continue; + } + if(it_teb->get()->teb().getSumOfAllTimeDiffs() / best_plan_duration > cfg_->hcp.max_ratio_detours_duration_best_duration) + { + ROS_DEBUG("Removing a teb because it's duration is much longer than that of the best teb"); + it_teb = removeTeb(*it_teb); + continue; + } + ++it_teb; + } +} + +bool HomotopyClassPlanner::computeStartOrientation(const TebOptimalPlannerPtr plan, const double len_orientation_vector, + double& orientation) +{ + VertexPose start_pose = plan->teb().Pose(0); + bool second_pose_found = false; + Eigen::Vector2d start_vector; + for(auto& pose : plan->teb().poses()) + { + start_vector = start_pose.position() - pose->position(); + if(start_vector.norm() > len_orientation_vector) + { + second_pose_found = true; + break; + } + } + if(!second_pose_found) // The current plan is too short to make assumptions on the start orientation + return false; + orientation = std::atan2(start_vector[1], start_vector[0]); + return true; +} + + +} // end namespace diff --git a/navigations/teb_local_planner/src/obstacles.cpp b/navigations/teb_local_planner/src/obstacles.cpp new file mode 100755 index 0000000..b969078 --- /dev/null +++ b/navigations/teb_local_planner/src/obstacles.cpp @@ -0,0 +1,214 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2016, + * TU Dortmund - Institute of Control Theory and Systems Engineering. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the institute nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: Christoph Rösmann + *********************************************************************/ + +#include +#include +#include +// #include + +namespace teb_local_planner +{ + + +void PolygonObstacle::fixPolygonClosure() +{ + if (vertices_.size()<2) + return; + + if (vertices_.front().isApprox(vertices_.back())) + vertices_.pop_back(); +} + +void PolygonObstacle::calcCentroid() +{ + if (vertices_.empty()) + { + centroid_.setConstant(NAN); + ROS_WARN("PolygonObstacle::calcCentroid(): number of vertices is empty. the resulting centroid is a vector of NANs."); + return; + } + + // if polygon is a point + if (noVertices()==1) + { + centroid_ = vertices_.front(); + return; + } + + // if polygon is a line: + if (noVertices()==2) + { + centroid_ = 0.5*(vertices_.front() + vertices_.back()); + return; + } + + // otherwise: + + centroid_.setZero(); + + // calculate centroid (see wikipedia http://de.wikipedia.org/wiki/Geometrischer_Schwerpunkt#Polygon) + double A = 0; // A = 0.5 * sum_0_n-1 (x_i * y_{i+1} - x_{i+1} * y_i) + for (int i=0; i < noVertices()-1; ++i) + { + A += vertices_.at(i).coeffRef(0) * vertices_.at(i+1).coeffRef(1) - vertices_.at(i+1).coeffRef(0) * vertices_.at(i).coeffRef(1); + } + A += vertices_.at(noVertices()-1).coeffRef(0) * vertices_.at(0).coeffRef(1) - vertices_.at(0).coeffRef(0) * vertices_.at(noVertices()-1).coeffRef(1); + A *= 0.5; + + if (A!=0) + { + for (int i=0; i < noVertices()-1; ++i) + { + double aux = (vertices_.at(i).coeffRef(0) * vertices_.at(i+1).coeffRef(1) - vertices_.at(i+1).coeffRef(0) * vertices_.at(i).coeffRef(1)); + centroid_ += ( vertices_.at(i) + vertices_.at(i+1) )*aux; + } + double aux = (vertices_.at(noVertices()-1).coeffRef(0) * vertices_.at(0).coeffRef(1) - vertices_.at(0).coeffRef(0) * vertices_.at(noVertices()-1).coeffRef(1)); + centroid_ += ( vertices_.at(noVertices()-1) + vertices_.at(0) )*aux; + centroid_ /= (6*A); + } + else // A == 0 -> all points are placed on a 'perfect' line + { + // seach for the two outer points of the line with the maximum distance inbetween + int i_cand = 0; + int j_cand = 0; + double max_dist = 0; + for (int i=0; i< noVertices(); ++i) + { + for (int j=i+1; j< noVertices(); ++j) // start with j=i+1 + { + double dist = (vertices_[j] - vertices_[i]).norm(); + if (dist > max_dist) + { + max_dist = dist; + i_cand = i; + j_cand = j; + } + } + } + // calc centroid of that line + centroid_ = 0.5*(vertices_[i_cand] + vertices_[j_cand]); + } +} + + + +Eigen::Vector2d PolygonObstacle::getClosestPoint(const Eigen::Vector2d& position) const +{ + // the polygon is a point + if (noVertices() == 1) + { + return vertices_.front(); + } + + if (noVertices() > 1) + { + + Eigen::Vector2d new_pt = closest_point_on_line_segment_2d(position, vertices_.at(0), vertices_.at(1)); + + if (noVertices() > 2) // real polygon and not a line + { + double dist = (new_pt-position).norm(); + Eigen::Vector2d closest_pt = new_pt; + + // check each polygon edge + for (int i=1; i + +// g2o custom edges and vertices for the TEB planner +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include + + +namespace teb_local_planner +{ + +// ============== Implementation =================== + +TebOptimalPlanner::TebOptimalPlanner() : cfg_(NULL), obstacles_(NULL), via_points_(NULL), cost_(HUGE_VAL), prefer_rotdir_(RotType::none), + robot_model_(new PointRobotFootprint()), initialized_(false), optimized_(false) +{ +} + +TebOptimalPlanner::TebOptimalPlanner(const TebConfig& cfg, ObstContainer* obstacles, RobotFootprintModelPtr robot_model, TebVisualizationPtr visual, const ViaPointContainer* via_points) +{ + initialize(cfg, obstacles, robot_model, visual, via_points); +} + +TebOptimalPlanner::~TebOptimalPlanner() +{ + clearGraph(); + // free dynamically allocated memory + //if (optimizer_) + // g2o::Factory::destroy(); + //g2o::OptimizationAlgorithmFactory::destroy(); + //g2o::HyperGraphActionLibrary::destroy(); +} + +void TebOptimalPlanner::updateRobotModel(RobotFootprintModelPtr robot_model) +{ + robot_model_ = robot_model; +} + +void TebOptimalPlanner::initialize(const TebConfig& cfg, ObstContainer* obstacles, RobotFootprintModelPtr robot_model, TebVisualizationPtr visual, const ViaPointContainer* via_points) +{ + // init optimizer (set solver and block ordering settings) + optimizer_ = initOptimizer(); + + cfg_ = &cfg; + obstacles_ = obstacles; + robot_model_ = robot_model; + via_points_ = via_points; + cost_ = HUGE_VAL; + prefer_rotdir_ = RotType::none; + setVisualization(visual); + + vel_start_.first = true; + vel_start_.second.linear.x = 0; + vel_start_.second.linear.y = 0; + vel_start_.second.angular.z = 0; + + vel_goal_.first = true; + vel_goal_.second.linear.x = 0; + vel_goal_.second.linear.y = 0; + vel_goal_.second.angular.z = 0; + initialized_ = true; +} + + +void TebOptimalPlanner::setVisualization(TebVisualizationPtr visualization) +{ + visualization_ = visualization; +} + +void TebOptimalPlanner::visualize() +{ + if (!visualization_) + return; + + visualization_->publishLocalPlanAndPoses(teb_); + + if (teb_.sizePoses() > 0) + visualization_->publishRobotFootprintModel(teb_.Pose(0), *robot_model_); + + if (cfg_->trajectory.publish_feedback) + visualization_->publishFeedbackMessage(*this, *obstacles_); + +} + + +/* + * registers custom vertices and edges in g2o framework + */ +void TebOptimalPlanner::registerG2OTypes() +{ + g2o::Factory* factory = g2o::Factory::instance(); + factory->registerType("VERTEX_POSE", new g2o::HyperGraphElementCreator); + factory->registerType("VERTEX_TIMEDIFF", new g2o::HyperGraphElementCreator); + + factory->registerType("EDGE_TIME_OPTIMAL", new g2o::HyperGraphElementCreator); + factory->registerType("EDGE_SHORTEST_PATH", new g2o::HyperGraphElementCreator); + factory->registerType("EDGE_VELOCITY", new g2o::HyperGraphElementCreator); + factory->registerType("EDGE_VELOCITY_HOLONOMIC", new g2o::HyperGraphElementCreator); + factory->registerType("EDGE_ACCELERATION", new g2o::HyperGraphElementCreator); + factory->registerType("EDGE_ACCELERATION_START", new g2o::HyperGraphElementCreator); + factory->registerType("EDGE_ACCELERATION_GOAL", new g2o::HyperGraphElementCreator); + factory->registerType("EDGE_ACCELERATION_HOLONOMIC", new g2o::HyperGraphElementCreator); + factory->registerType("EDGE_ACCELERATION_HOLONOMIC_START", new g2o::HyperGraphElementCreator); + factory->registerType("EDGE_ACCELERATION_HOLONOMIC_GOAL", new g2o::HyperGraphElementCreator); + factory->registerType("EDGE_KINEMATICS_DIFF_DRIVE", new g2o::HyperGraphElementCreator); + factory->registerType("EDGE_KINEMATICS_CARLIKE", new g2o::HyperGraphElementCreator); + factory->registerType("EDGE_OBSTACLE", new g2o::HyperGraphElementCreator); + factory->registerType("EDGE_INFLATED_OBSTACLE", new g2o::HyperGraphElementCreator); + factory->registerType("EDGE_DYNAMIC_OBSTACLE", new g2o::HyperGraphElementCreator); + factory->registerType("EDGE_VIA_POINT", new g2o::HyperGraphElementCreator); + factory->registerType("EDGE_PREFER_ROTDIR", new g2o::HyperGraphElementCreator); + return; +} + +/* + * initialize g2o optimizer. Set solver settings here. + * Return: pointer to new SparseOptimizer Object. + */ +boost::shared_ptr TebOptimalPlanner::initOptimizer() +{ + // Call register_g2o_types once, even for multiple TebOptimalPlanner instances (thread-safe) + static boost::once_flag flag = BOOST_ONCE_INIT; + boost::call_once(®isterG2OTypes, flag); + + // allocating the optimizer + boost::shared_ptr optimizer = boost::make_shared(); + std::unique_ptr linear_solver(new TEBLinearSolver()); // see typedef in optimization.h + linear_solver->setBlockOrdering(true); + std::unique_ptr block_solver(new TEBBlockSolver(std::move(linear_solver))); + g2o::OptimizationAlgorithmLevenberg* solver = new g2o::OptimizationAlgorithmLevenberg(std::move(block_solver)); + + optimizer->setAlgorithm(solver); + + optimizer->initMultiThreading(); // required for >Eigen 3.1 + + return optimizer; +} + + +bool TebOptimalPlanner::optimizeTEB(int iterations_innerloop, int iterations_outerloop, bool compute_cost_afterwards, + double obst_cost_scale, double viapoint_cost_scale, bool alternative_time_cost) +{ + if (cfg_->optim.optimization_activate==false) + return false; + + bool success = false; + optimized_ = false; + + double weight_multiplier = 1.0; + + // TODO(roesmann): we introduced the non-fast mode with the support of dynamic obstacles + // (which leads to better results in terms of x-y-t homotopy planning). + // however, we have not tested this mode intensively yet, so we keep + // the legacy fast mode as default until we finish our tests. + bool fast_mode = !cfg_->obstacles.include_dynamic_obstacles; + + for(int i=0; itrajectory.teb_autosize) + { + //teb_.autoResize(cfg_->trajectory.dt_ref, cfg_->trajectory.dt_hysteresis, cfg_->trajectory.min_samples, cfg_->trajectory.max_samples); + teb_.autoResize(cfg_->trajectory.dt_ref, cfg_->trajectory.dt_hysteresis, cfg_->trajectory.min_samples, cfg_->trajectory.max_samples, fast_mode); + + } + + success = buildGraph(weight_multiplier); + if (!success) + { + clearGraph(); + return false; + } + success = optimizeGraph(iterations_innerloop, false); + if (!success) + { + clearGraph(); + return false; + } + optimized_ = true; + + if (compute_cost_afterwards && i==iterations_outerloop-1) // compute cost vec only in the last iteration + computeCurrentCost(obst_cost_scale, viapoint_cost_scale, alternative_time_cost); + + clearGraph(); + + weight_multiplier *= cfg_->optim.weight_adapt_factor; + } + + return true; +} + +void TebOptimalPlanner::setVelocityStart(const geometry_msgs::Twist& vel_start) +{ + vel_start_.first = true; + vel_start_.second.linear.x = vel_start.linear.x; + vel_start_.second.linear.y = vel_start.linear.y; + vel_start_.second.angular.z = vel_start.angular.z; +} + +void TebOptimalPlanner::setVelocityGoal(const geometry_msgs::Twist& vel_goal) +{ + vel_goal_.first = true; + vel_goal_.second = vel_goal; +} + +bool TebOptimalPlanner::plan(const std::vector& initial_plan, const geometry_msgs::Twist* start_vel, bool free_goal_vel) +{ + ROS_ASSERT_MSG(initialized_, "Call initialize() first."); + if (!teb_.isInit()) + { + teb_.initTrajectoryToGoal(initial_plan, cfg_->robot.max_vel_x, cfg_->robot.max_vel_theta, cfg_->trajectory.global_plan_overwrite_orientation, + cfg_->trajectory.min_samples, cfg_->trajectory.allow_init_with_backwards_motion); + } + else // warm start + { + PoseSE2 start_(initial_plan.front().pose); + PoseSE2 goal_(initial_plan.back().pose); + if (teb_.sizePoses()>0 + && (goal_.position() - teb_.BackPose().position()).norm() < cfg_->trajectory.force_reinit_new_goal_dist + && fabs(g2o::normalize_theta(goal_.theta() - teb_.BackPose().theta())) < cfg_->trajectory.force_reinit_new_goal_angular) // actual warm start! + teb_.updateAndPruneTEB(start_, goal_, cfg_->trajectory.min_samples); // update TEB + else // goal too far away -> reinit + { + ROS_DEBUG("New goal: distance to existing goal is higher than the specified threshold. Reinitalizing trajectories."); + teb_.clearTimedElasticBand(); + teb_.initTrajectoryToGoal(initial_plan, cfg_->robot.max_vel_x, cfg_->robot.max_vel_theta, cfg_->trajectory.global_plan_overwrite_orientation, + cfg_->trajectory.min_samples, cfg_->trajectory.allow_init_with_backwards_motion); + } + } + if (start_vel) + setVelocityStart(*start_vel); + if (free_goal_vel) + setVelocityGoalFree(); + else + vel_goal_.first = true; // we just reactivate and use the previously set velocity (should be zero if nothing was modified) + + // now optimize + return optimizeTEB(cfg_->optim.no_inner_iterations, cfg_->optim.no_outer_iterations); +} + + +bool TebOptimalPlanner::plan(const tf::Pose& start, const tf::Pose& goal, const geometry_msgs::Twist* start_vel, bool free_goal_vel) +{ + PoseSE2 start_(start); + PoseSE2 goal_(goal); + return plan(start_, goal_, start_vel); +} + +bool TebOptimalPlanner::plan(const PoseSE2& start, const PoseSE2& goal, const geometry_msgs::Twist* start_vel, bool free_goal_vel) +{ + ROS_ASSERT_MSG(initialized_, "Call initialize() first."); + if (!teb_.isInit()) + { + // init trajectory + teb_.initTrajectoryToGoal(start, goal, 0, cfg_->robot.max_vel_x, cfg_->trajectory.min_samples, cfg_->trajectory.allow_init_with_backwards_motion); // 0 intermediate samples, but dt=1 -> autoResize will add more samples before calling first optimization + } + else // warm start + { + if (teb_.sizePoses() > 0 + && (goal.position() - teb_.BackPose().position()).norm() < cfg_->trajectory.force_reinit_new_goal_dist + && fabs(g2o::normalize_theta(goal.theta() - teb_.BackPose().theta())) < cfg_->trajectory.force_reinit_new_goal_angular) // actual warm start! + teb_.updateAndPruneTEB(start, goal, cfg_->trajectory.min_samples); + else // goal too far away -> reinit + { + ROS_DEBUG("New goal: distance to existing goal is higher than the specified threshold. Reinitalizing trajectories."); + teb_.clearTimedElasticBand(); + teb_.initTrajectoryToGoal(start, goal, 0, cfg_->robot.max_vel_x, cfg_->trajectory.min_samples, cfg_->trajectory.allow_init_with_backwards_motion); + } + } + if (start_vel) + setVelocityStart(*start_vel); + if (free_goal_vel) + setVelocityGoalFree(); + else + vel_goal_.first = true; // we just reactivate and use the previously set velocity (should be zero if nothing was modified) + + // now optimize + return optimizeTEB(cfg_->optim.no_inner_iterations, cfg_->optim.no_outer_iterations); +} + + +bool TebOptimalPlanner::buildGraph(double weight_multiplier) +{ + if (!optimizer_->edges().empty() || !optimizer_->vertices().empty()) + { + ROS_WARN("Cannot build graph, because it is not empty. Call graphClear()!"); + return false; + } + + optimizer_->setComputeBatchStatistics(cfg_->recovery.divergence_detection_enable); + + // add TEB vertices + AddTEBVertices(); + + // add Edges (local cost functions) + if (cfg_->obstacles.legacy_obstacle_association) + AddEdgesObstaclesLegacy(weight_multiplier); + else + AddEdgesObstacles(weight_multiplier); + + if (cfg_->obstacles.include_dynamic_obstacles) + AddEdgesDynamicObstacles(); + + AddEdgesViaPoints(); + + AddEdgesVelocity(); + + AddEdgesAcceleration(); + + AddEdgesTimeOptimal(); + + AddEdgesShortestPath(); + + if (cfg_->robot.min_turning_radius == 0 || cfg_->optim.weight_kinematics_turning_radius == 0) + AddEdgesKinematicsDiffDrive(); // we have a differential drive robot + else + AddEdgesKinematicsCarlike(); // we have a carlike robot since the turning radius is bounded from below. + + AddEdgesPreferRotDir(); + + if (cfg_->optim.weight_velocity_obstacle_ratio > 0) + AddEdgesVelocityObstacleRatio(); + + return true; +} + +bool TebOptimalPlanner::optimizeGraph(int no_iterations,bool clear_after) +{ + if (cfg_->robot.max_vel_x<0.01) + { + ROS_WARN("optimizeGraph(): Robot Max Velocity is smaller than 0.01m/s. Optimizing aborted..."); + if (clear_after) clearGraph(); + return false; + } + + if (!teb_.isInit() || teb_.sizePoses() < cfg_->trajectory.min_samples) + { + ROS_WARN("optimizeGraph(): TEB is empty or has too less elements. Skipping optimization."); + if (clear_after) clearGraph(); + return false; + } + + optimizer_->setVerbose(cfg_->optim.optimization_verbose); + optimizer_->initializeOptimization(); + + int iter = optimizer_->optimize(no_iterations); + + // Save Hessian for visualization + // g2o::OptimizationAlgorithmLevenberg* lm = dynamic_cast (optimizer_->solver()); + // lm->solver()->saveHessian("~/MasterThesis/Matlab/Hessian.txt"); + + if(!iter) + { + ROS_ERROR("optimizeGraph(): Optimization failed! iter=%i", iter); + return false; + } + + if (clear_after) clearGraph(); + + return true; +} + +void TebOptimalPlanner::clearGraph() +{ + // clear optimizer states + if (optimizer_) + { + // we will delete all edges but keep the vertices. + // before doing so, we will delete the link from the vertices to the edges. + auto& vertices = optimizer_->vertices(); + for(auto& v : vertices) + v.second->edges().clear(); + + optimizer_->vertices().clear(); // necessary, because optimizer->clear deletes pointer-targets (therefore it deletes TEB states!) + optimizer_->clear(); + } +} + + + +void TebOptimalPlanner::AddTEBVertices() +{ + // add vertices to graph + ROS_DEBUG_COND(cfg_->optim.optimization_verbose, "Adding TEB vertices ..."); + unsigned int id_counter = 0; // used for vertices ids + obstacles_per_vertex_.resize(teb_.sizePoses()); + auto iter_obstacle = obstacles_per_vertex_.begin(); + for (int i=0; isetId(id_counter++); + optimizer_->addVertex(teb_.PoseVertex(i)); + if (teb_.sizeTimeDiffs()!=0 && isetId(id_counter++); + optimizer_->addVertex(teb_.TimeDiffVertex(i)); + } + iter_obstacle->clear(); + (iter_obstacle++)->reserve(obstacles_->size()); + } +} + + +void TebOptimalPlanner::AddEdgesObstacles(double weight_multiplier) +{ + if (cfg_->optim.weight_obstacle==0 || weight_multiplier==0 || obstacles_==nullptr ) + return; // if weight equals zero skip adding edges! + + + bool inflated = cfg_->obstacles.inflation_dist > cfg_->obstacles.min_obstacle_dist; + + Eigen::Matrix information; + information.fill(cfg_->optim.weight_obstacle * weight_multiplier); + + Eigen::Matrix information_inflated; + information_inflated(0,0) = cfg_->optim.weight_obstacle * weight_multiplier; + information_inflated(1,1) = cfg_->optim.weight_inflation; + information_inflated(0,1) = information_inflated(1,0) = 0; + + auto iter_obstacle = obstacles_per_vertex_.begin(); + + auto create_edge = [inflated, &information, &information_inflated, this] (int index, const Obstacle* obstacle) { + if (inflated) + { + EdgeInflatedObstacle* dist_bandpt_obst = new EdgeInflatedObstacle; + dist_bandpt_obst->setVertex(0,teb_.PoseVertex(index)); + dist_bandpt_obst->setInformation(information_inflated); + dist_bandpt_obst->setParameters(*cfg_, robot_model_.get(), obstacle); + optimizer_->addEdge(dist_bandpt_obst); + } + else + { + EdgeObstacle* dist_bandpt_obst = new EdgeObstacle; + dist_bandpt_obst->setVertex(0,teb_.PoseVertex(index)); + dist_bandpt_obst->setInformation(information); + dist_bandpt_obst->setParameters(*cfg_, robot_model_.get(), obstacle); + optimizer_->addEdge(dist_bandpt_obst); + }; + }; + + // iterate all teb points, skipping the last and, if the EdgeVelocityObstacleRatio edges should not be created, the first one too + const int first_vertex = cfg_->optim.weight_velocity_obstacle_ratio == 0 ? 1 : 0; + for (int i = first_vertex; i < teb_.sizePoses() - 1; ++i) + { + double left_min_dist = std::numeric_limits::max(); + double right_min_dist = std::numeric_limits::max(); + ObstaclePtr left_obstacle; + ObstaclePtr right_obstacle; + + const Eigen::Vector2d pose_orient = teb_.Pose(i).orientationUnitVec(); + + // iterate obstacles + for (const ObstaclePtr& obst : *obstacles_) + { + // we handle dynamic obstacles differently below + if(cfg_->obstacles.include_dynamic_obstacles && obst->isDynamic()) + continue; + + // calculate distance to robot model + double dist = robot_model_->calculateDistance(teb_.Pose(i), obst.get()); + + // force considering obstacle if really close to the current pose + if (dist < cfg_->obstacles.min_obstacle_dist*cfg_->obstacles.obstacle_association_force_inclusion_factor) + { + iter_obstacle->push_back(obst); + continue; + } + // cut-off distance + if (dist > cfg_->obstacles.min_obstacle_dist*cfg_->obstacles.obstacle_association_cutoff_factor) + continue; + + // determine side (left or right) and assign obstacle if closer than the previous one + if (cross2d(pose_orient, obst->getCentroid()) > 0) // left + { + if (dist < left_min_dist) + { + left_min_dist = dist; + left_obstacle = obst; + } + } + else + { + if (dist < right_min_dist) + { + right_min_dist = dist; + right_obstacle = obst; + } + } + } + + if (left_obstacle) + iter_obstacle->push_back(left_obstacle); + if (right_obstacle) + iter_obstacle->push_back(right_obstacle); + + // continue here to ignore obstacles for the first pose, but use them later to create the EdgeVelocityObstacleRatio edges + if (i == 0) + { + ++iter_obstacle; + continue; + } + + // create obstacle edges + for (const ObstaclePtr obst : *iter_obstacle) + create_edge(i, obst.get()); + ++iter_obstacle; + } +} + + +void TebOptimalPlanner::AddEdgesObstaclesLegacy(double weight_multiplier) +{ + if (cfg_->optim.weight_obstacle==0 || weight_multiplier==0 || obstacles_==nullptr) + return; // if weight equals zero skip adding edges! + + Eigen::Matrix information; + information.fill(cfg_->optim.weight_obstacle * weight_multiplier); + + Eigen::Matrix information_inflated; + information_inflated(0,0) = cfg_->optim.weight_obstacle * weight_multiplier; + information_inflated(1,1) = cfg_->optim.weight_inflation; + information_inflated(0,1) = information_inflated(1,0) = 0; + + bool inflated = cfg_->obstacles.inflation_dist > cfg_->obstacles.min_obstacle_dist; + + for (ObstContainer::const_iterator obst = obstacles_->begin(); obst != obstacles_->end(); ++obst) + { + if (cfg_->obstacles.include_dynamic_obstacles && (*obst)->isDynamic()) // we handle dynamic obstacles differently below + continue; + + int index; + + if (cfg_->obstacles.obstacle_poses_affected >= teb_.sizePoses()) + index = teb_.sizePoses() / 2; + else + index = teb_.findClosestTrajectoryPose(*(obst->get())); + + + // check if obstacle is outside index-range between start and goal + if ( (index <= 1) || (index > teb_.sizePoses()-2) ) // start and goal are fixed and findNearestBandpoint finds first or last conf if intersection point is outside the range + continue; + + if (inflated) + { + EdgeInflatedObstacle* dist_bandpt_obst = new EdgeInflatedObstacle; + dist_bandpt_obst->setVertex(0,teb_.PoseVertex(index)); + dist_bandpt_obst->setInformation(information_inflated); + dist_bandpt_obst->setParameters(*cfg_, robot_model_.get(), obst->get()); + optimizer_->addEdge(dist_bandpt_obst); + } + else + { + EdgeObstacle* dist_bandpt_obst = new EdgeObstacle; + dist_bandpt_obst->setVertex(0,teb_.PoseVertex(index)); + dist_bandpt_obst->setInformation(information); + dist_bandpt_obst->setParameters(*cfg_, robot_model_.get(), obst->get()); + optimizer_->addEdge(dist_bandpt_obst); + } + + for (int neighbourIdx=0; neighbourIdx < floor(cfg_->obstacles.obstacle_poses_affected/2); neighbourIdx++) + { + if (index+neighbourIdx < teb_.sizePoses()) + { + if (inflated) + { + EdgeInflatedObstacle* dist_bandpt_obst_n_r = new EdgeInflatedObstacle; + dist_bandpt_obst_n_r->setVertex(0,teb_.PoseVertex(index+neighbourIdx)); + dist_bandpt_obst_n_r->setInformation(information_inflated); + dist_bandpt_obst_n_r->setParameters(*cfg_, robot_model_.get(), obst->get()); + optimizer_->addEdge(dist_bandpt_obst_n_r); + } + else + { + EdgeObstacle* dist_bandpt_obst_n_r = new EdgeObstacle; + dist_bandpt_obst_n_r->setVertex(0,teb_.PoseVertex(index+neighbourIdx)); + dist_bandpt_obst_n_r->setInformation(information); + dist_bandpt_obst_n_r->setParameters(*cfg_, robot_model_.get(), obst->get()); + optimizer_->addEdge(dist_bandpt_obst_n_r); + } + } + if ( index - neighbourIdx >= 0) // needs to be casted to int to allow negative values + { + if (inflated) + { + EdgeInflatedObstacle* dist_bandpt_obst_n_l = new EdgeInflatedObstacle; + dist_bandpt_obst_n_l->setVertex(0,teb_.PoseVertex(index-neighbourIdx)); + dist_bandpt_obst_n_l->setInformation(information_inflated); + dist_bandpt_obst_n_l->setParameters(*cfg_, robot_model_.get(), obst->get()); + optimizer_->addEdge(dist_bandpt_obst_n_l); + } + else + { + EdgeObstacle* dist_bandpt_obst_n_l = new EdgeObstacle; + dist_bandpt_obst_n_l->setVertex(0,teb_.PoseVertex(index-neighbourIdx)); + dist_bandpt_obst_n_l->setInformation(information); + dist_bandpt_obst_n_l->setParameters(*cfg_, robot_model_.get(), obst->get()); + optimizer_->addEdge(dist_bandpt_obst_n_l); + } + } + } + + } +} + + +void TebOptimalPlanner::AddEdgesDynamicObstacles(double weight_multiplier) +{ + if (cfg_->optim.weight_obstacle==0 || weight_multiplier==0 || obstacles_==NULL ) + return; // if weight equals zero skip adding edges! + + Eigen::Matrix information; + information(0,0) = cfg_->optim.weight_dynamic_obstacle * weight_multiplier; + information(1,1) = cfg_->optim.weight_dynamic_obstacle_inflation; + information(0,1) = information(1,0) = 0; + + for (ObstContainer::const_iterator obst = obstacles_->begin(); obst != obstacles_->end(); ++obst) + { + if (!(*obst)->isDynamic()) + continue; + + // Skip first and last pose, as they are fixed + double time = teb_.TimeDiff(0); + for (int i=1; i < teb_.sizePoses() - 1; ++i) + { + EdgeDynamicObstacle* dynobst_edge = new EdgeDynamicObstacle(time); + dynobst_edge->setVertex(0,teb_.PoseVertex(i)); + dynobst_edge->setInformation(information); + dynobst_edge->setParameters(*cfg_, robot_model_.get(), obst->get()); + optimizer_->addEdge(dynobst_edge); + time += teb_.TimeDiff(i); // we do not need to check the time diff bounds, since we iterate to "< sizePoses()-1". + } + } +} + +void TebOptimalPlanner::AddEdgesViaPoints() +{ + if (cfg_->optim.weight_viapoint==0 || via_points_==NULL || via_points_->empty() ) + return; // if weight equals zero skip adding edges! + + int start_pose_idx = 0; + + int n = teb_.sizePoses(); + if (n<3) // we do not have any degrees of freedom for reaching via-points + return; + + for (ViaPointContainer::const_iterator vp_it = via_points_->begin(); vp_it != via_points_->end(); ++vp_it) + { + + int index = teb_.findClosestTrajectoryPose(*vp_it, NULL, start_pose_idx); + if (cfg_->trajectory.via_points_ordered) + start_pose_idx = index+2; // skip a point to have a DOF inbetween for further via-points + + // check if point conicides with goal or is located behind it + if ( index > n-2 ) + index = n-2; // set to a pose before the goal, since we can move it away! + // check if point coincides with start or is located before it + if ( index < 1) + { + if (cfg_->trajectory.via_points_ordered) + { + index = 1; // try to connect the via point with the second (and non-fixed) pose. It is likely that autoresize adds new poses inbetween later. + } + else + { + ROS_DEBUG("TebOptimalPlanner::AddEdgesViaPoints(): skipping a via-point that is close or behind the current robot pose."); + continue; // skip via points really close or behind the current robot pose + } + } + Eigen::Matrix information; + information.fill(cfg_->optim.weight_viapoint); + + EdgeViaPoint* edge_viapoint = new EdgeViaPoint; + edge_viapoint->setVertex(0,teb_.PoseVertex(index)); + edge_viapoint->setInformation(information); + edge_viapoint->setParameters(*cfg_, &(*vp_it)); + optimizer_->addEdge(edge_viapoint); + } +} + +void TebOptimalPlanner::AddEdgesVelocity() +{ + if (cfg_->robot.max_vel_y == 0) // non-holonomic robot + { + if ( cfg_->optim.weight_max_vel_x==0 && cfg_->optim.weight_max_vel_theta==0) + return; // if weight equals zero skip adding edges! + + int n = teb_.sizePoses(); + Eigen::Matrix information; + information(0,0) = cfg_->optim.weight_max_vel_x; + information(1,1) = cfg_->optim.weight_max_vel_theta; + information(0,1) = 0.0; + information(1,0) = 0.0; + + for (int i=0; i < n - 1; ++i) + { + EdgeVelocity* velocity_edge = new EdgeVelocity; + velocity_edge->setVertex(0,teb_.PoseVertex(i)); + velocity_edge->setVertex(1,teb_.PoseVertex(i+1)); + velocity_edge->setVertex(2,teb_.TimeDiffVertex(i)); + velocity_edge->setInformation(information); + velocity_edge->setTebConfig(*cfg_); + optimizer_->addEdge(velocity_edge); + } + } + else // holonomic-robot + { + if ( cfg_->optim.weight_max_vel_x==0 && cfg_->optim.weight_max_vel_y==0 && cfg_->optim.weight_max_vel_theta==0) + return; // if weight equals zero skip adding edges! + + int n = teb_.sizePoses(); + Eigen::Matrix information; + information.fill(0); + information(0,0) = cfg_->optim.weight_max_vel_x; + information(1,1) = cfg_->optim.weight_max_vel_y; + information(2,2) = cfg_->optim.weight_max_vel_theta; + + for (int i=0; i < n - 1; ++i) + { + EdgeVelocityHolonomic* velocity_edge = new EdgeVelocityHolonomic; + velocity_edge->setVertex(0,teb_.PoseVertex(i)); + velocity_edge->setVertex(1,teb_.PoseVertex(i+1)); + velocity_edge->setVertex(2,teb_.TimeDiffVertex(i)); + velocity_edge->setInformation(information); + velocity_edge->setTebConfig(*cfg_); + optimizer_->addEdge(velocity_edge); + } + + } +} + +void TebOptimalPlanner::AddEdgesAcceleration() +{ + if (cfg_->optim.weight_acc_lim_x==0 && cfg_->optim.weight_acc_lim_theta==0) + return; // if weight equals zero skip adding edges! + + int n = teb_.sizePoses(); + + if (cfg_->robot.max_vel_y == 0 || cfg_->robot.acc_lim_y == 0) // non-holonomic robot + { + Eigen::Matrix information; + information.fill(0); + information(0,0) = cfg_->optim.weight_acc_lim_x; + information(1,1) = cfg_->optim.weight_acc_lim_theta; + + // check if an initial velocity should be taken into accound + if (vel_start_.first) + { + EdgeAccelerationStart* acceleration_edge = new EdgeAccelerationStart; + acceleration_edge->setVertex(0,teb_.PoseVertex(0)); + acceleration_edge->setVertex(1,teb_.PoseVertex(1)); + acceleration_edge->setVertex(2,teb_.TimeDiffVertex(0)); + acceleration_edge->setInitialVelocity(vel_start_.second); + acceleration_edge->setInformation(information); + acceleration_edge->setTebConfig(*cfg_); + optimizer_->addEdge(acceleration_edge); + } + + // now add the usual acceleration edge for each tuple of three teb poses + for (int i=0; i < n - 2; ++i) + { + EdgeAcceleration* acceleration_edge = new EdgeAcceleration; + acceleration_edge->setVertex(0,teb_.PoseVertex(i)); + acceleration_edge->setVertex(1,teb_.PoseVertex(i+1)); + acceleration_edge->setVertex(2,teb_.PoseVertex(i+2)); + acceleration_edge->setVertex(3,teb_.TimeDiffVertex(i)); + acceleration_edge->setVertex(4,teb_.TimeDiffVertex(i+1)); + acceleration_edge->setInformation(information); + acceleration_edge->setTebConfig(*cfg_); + optimizer_->addEdge(acceleration_edge); + } + + // check if a goal velocity should be taken into accound + if (vel_goal_.first) + { + EdgeAccelerationGoal* acceleration_edge = new EdgeAccelerationGoal; + acceleration_edge->setVertex(0,teb_.PoseVertex(n-2)); + acceleration_edge->setVertex(1,teb_.PoseVertex(n-1)); + acceleration_edge->setVertex(2,teb_.TimeDiffVertex( teb_.sizeTimeDiffs()-1 )); + acceleration_edge->setGoalVelocity(vel_goal_.second); + acceleration_edge->setInformation(information); + acceleration_edge->setTebConfig(*cfg_); + optimizer_->addEdge(acceleration_edge); + } + } + else // holonomic robot + { + Eigen::Matrix information; + information.fill(0); + information(0,0) = cfg_->optim.weight_acc_lim_x; + information(1,1) = cfg_->optim.weight_acc_lim_y; + information(2,2) = cfg_->optim.weight_acc_lim_theta; + + // check if an initial velocity should be taken into accound + if (vel_start_.first) + { + EdgeAccelerationHolonomicStart* acceleration_edge = new EdgeAccelerationHolonomicStart; + acceleration_edge->setVertex(0,teb_.PoseVertex(0)); + acceleration_edge->setVertex(1,teb_.PoseVertex(1)); + acceleration_edge->setVertex(2,teb_.TimeDiffVertex(0)); + acceleration_edge->setInitialVelocity(vel_start_.second); + acceleration_edge->setInformation(information); + acceleration_edge->setTebConfig(*cfg_); + optimizer_->addEdge(acceleration_edge); + } + + // now add the usual acceleration edge for each tuple of three teb poses + for (int i=0; i < n - 2; ++i) + { + EdgeAccelerationHolonomic* acceleration_edge = new EdgeAccelerationHolonomic; + acceleration_edge->setVertex(0,teb_.PoseVertex(i)); + acceleration_edge->setVertex(1,teb_.PoseVertex(i+1)); + acceleration_edge->setVertex(2,teb_.PoseVertex(i+2)); + acceleration_edge->setVertex(3,teb_.TimeDiffVertex(i)); + acceleration_edge->setVertex(4,teb_.TimeDiffVertex(i+1)); + acceleration_edge->setInformation(information); + acceleration_edge->setTebConfig(*cfg_); + optimizer_->addEdge(acceleration_edge); + } + + // check if a goal velocity should be taken into accound + if (vel_goal_.first) + { + EdgeAccelerationHolonomicGoal* acceleration_edge = new EdgeAccelerationHolonomicGoal; + acceleration_edge->setVertex(0,teb_.PoseVertex(n-2)); + acceleration_edge->setVertex(1,teb_.PoseVertex(n-1)); + acceleration_edge->setVertex(2,teb_.TimeDiffVertex( teb_.sizeTimeDiffs()-1 )); + acceleration_edge->setGoalVelocity(vel_goal_.second); + acceleration_edge->setInformation(information); + acceleration_edge->setTebConfig(*cfg_); + optimizer_->addEdge(acceleration_edge); + } + } +} + + + +void TebOptimalPlanner::AddEdgesTimeOptimal() +{ + if (cfg_->optim.weight_optimaltime==0) + return; // if weight equals zero skip adding edges! + + Eigen::Matrix information; + information.fill(cfg_->optim.weight_optimaltime); + + for (int i=0; i < teb_.sizeTimeDiffs(); ++i) + { + EdgeTimeOptimal* timeoptimal_edge = new EdgeTimeOptimal; + timeoptimal_edge->setVertex(0,teb_.TimeDiffVertex(i)); + timeoptimal_edge->setInformation(information); + timeoptimal_edge->setTebConfig(*cfg_); + optimizer_->addEdge(timeoptimal_edge); + } +} + +void TebOptimalPlanner::AddEdgesShortestPath() +{ + if (cfg_->optim.weight_shortest_path==0) + return; // if weight equals zero skip adding edges! + + Eigen::Matrix information; + information.fill(cfg_->optim.weight_shortest_path); + + for (int i=0; i < teb_.sizePoses()-1; ++i) + { + EdgeShortestPath* shortest_path_edge = new EdgeShortestPath; + shortest_path_edge->setVertex(0,teb_.PoseVertex(i)); + shortest_path_edge->setVertex(1,teb_.PoseVertex(i+1)); + shortest_path_edge->setInformation(information); + shortest_path_edge->setTebConfig(*cfg_); + optimizer_->addEdge(shortest_path_edge); + } +} + + + +void TebOptimalPlanner::AddEdgesKinematicsDiffDrive() +{ + if (cfg_->optim.weight_kinematics_nh==0 && cfg_->optim.weight_kinematics_forward_drive==0) + return; // if weight equals zero skip adding edges! + + // create edge for satisfiying kinematic constraints + Eigen::Matrix information_kinematics; + information_kinematics.fill(0.0); + information_kinematics(0, 0) = cfg_->optim.weight_kinematics_nh; + information_kinematics(1, 1) = cfg_->optim.weight_kinematics_forward_drive; + + for (int i=0; i < teb_.sizePoses()-1; i++) // ignore twiced start only + { + EdgeKinematicsDiffDrive* kinematics_edge = new EdgeKinematicsDiffDrive; + kinematics_edge->setVertex(0,teb_.PoseVertex(i)); + kinematics_edge->setVertex(1,teb_.PoseVertex(i+1)); + kinematics_edge->setInformation(information_kinematics); + kinematics_edge->setTebConfig(*cfg_); + optimizer_->addEdge(kinematics_edge); + } +} + +void TebOptimalPlanner::AddEdgesKinematicsCarlike() +{ + if (cfg_->optim.weight_kinematics_nh==0 && cfg_->optim.weight_kinematics_turning_radius==0) + return; // if weight equals zero skip adding edges! + + // create edge for satisfiying kinematic constraints + Eigen::Matrix information_kinematics; + information_kinematics.fill(0.0); + information_kinematics(0, 0) = cfg_->optim.weight_kinematics_nh; + information_kinematics(1, 1) = cfg_->optim.weight_kinematics_turning_radius; + + for (int i=0; i < teb_.sizePoses()-1; i++) // ignore twiced start only + { + EdgeKinematicsCarlike* kinematics_edge = new EdgeKinematicsCarlike; + kinematics_edge->setVertex(0,teb_.PoseVertex(i)); + kinematics_edge->setVertex(1,teb_.PoseVertex(i+1)); + kinematics_edge->setInformation(information_kinematics); + kinematics_edge->setTebConfig(*cfg_); + optimizer_->addEdge(kinematics_edge); + } +} + + +void TebOptimalPlanner::AddEdgesPreferRotDir() +{ + //TODO(roesmann): Note, these edges can result in odd predictions, in particular + // we can observe a substantional mismatch between open- and closed-loop planning + // leading to a poor control performance. + // At the moment, we keep these functionality for oscillation recovery: + // Activating the edge for a short time period might not be crucial and + // could move the robot to a new oscillation-free state. + // This needs to be analyzed in more detail! + if (prefer_rotdir_ == RotType::none || cfg_->optim.weight_prefer_rotdir==0) + return; // if weight equals zero skip adding edges! + + if (prefer_rotdir_ != RotType::right && prefer_rotdir_ != RotType::left) + { + ROS_WARN("TebOptimalPlanner::AddEdgesPreferRotDir(): unsupported RotType selected. Skipping edge creation."); + return; + } + + // create edge for satisfiying kinematic constraints + Eigen::Matrix information_rotdir; + information_rotdir.fill(cfg_->optim.weight_prefer_rotdir); + + for (int i=0; i < teb_.sizePoses()-1 && i < 3; ++i) // currently: apply to first 3 rotations + { + EdgePreferRotDir* rotdir_edge = new EdgePreferRotDir; + rotdir_edge->setVertex(0,teb_.PoseVertex(i)); + rotdir_edge->setVertex(1,teb_.PoseVertex(i+1)); + rotdir_edge->setInformation(information_rotdir); + + if (prefer_rotdir_ == RotType::left) + rotdir_edge->preferLeft(); + else if (prefer_rotdir_ == RotType::right) + rotdir_edge->preferRight(); + + optimizer_->addEdge(rotdir_edge); + } +} + +void TebOptimalPlanner::AddEdgesVelocityObstacleRatio() +{ + Eigen::Matrix information; + information(0,0) = cfg_->optim.weight_velocity_obstacle_ratio; + information(1,1) = cfg_->optim.weight_velocity_obstacle_ratio; + information(0,1) = information(1,0) = 0; + + auto iter_obstacle = obstacles_per_vertex_.begin(); + + for (int index = 0; index < teb_.sizePoses() - 1; ++index) + { + for (const ObstaclePtr obstacle : (*iter_obstacle++)) + { + EdgeVelocityObstacleRatio* edge = new EdgeVelocityObstacleRatio; + edge->setVertex(0,teb_.PoseVertex(index)); + edge->setVertex(1,teb_.PoseVertex(index + 1)); + edge->setVertex(2,teb_.TimeDiffVertex(index)); + edge->setInformation(information); + edge->setParameters(*cfg_, robot_model_.get(), obstacle.get()); + optimizer_->addEdge(edge); + } + } +} + +bool TebOptimalPlanner::hasDiverged() const +{ + // Early returns if divergence detection is not active + if (!cfg_->recovery.divergence_detection_enable) + return false; + + auto stats_vector = optimizer_->batchStatistics(); + + // No statistics yet + if (stats_vector.empty()) + return false; + + // Grab the statistics of the final iteration + const auto last_iter_stats = stats_vector.back(); + + return last_iter_stats.chi2 > cfg_->recovery.divergence_detection_max_chi_squared; +} + +void TebOptimalPlanner::computeCurrentCost(double obst_cost_scale, double viapoint_cost_scale, bool alternative_time_cost) +{ + // check if graph is empty/exist -> important if function is called between buildGraph and optimizeGraph/clearGraph + bool graph_exist_flag(false); + if (optimizer_->edges().empty() && optimizer_->vertices().empty()) + { + // here the graph is build again, for time efficiency make sure to call this function + // between buildGraph and Optimize (deleted), but it depends on the application + buildGraph(); + optimizer_->initializeOptimization(); + } + else + { + graph_exist_flag = true; + } + + optimizer_->computeInitialGuess(); + + cost_ = 0; + + if (alternative_time_cost) + { + cost_ += teb_.getSumOfAllTimeDiffs(); + // TEST we use SumOfAllTimeDiffs() here, because edge cost depends on number of samples, which is not always the same for similar TEBs, + // since we are using an AutoResize Function with hysteresis. + } + + // now we need pointers to all edges -> calculate error for each edge-type + // since we aren't storing edge pointers, we need to check every edge + for (std::vector::const_iterator it = optimizer_->activeEdges().begin(); it!= optimizer_->activeEdges().end(); it++) + { + double cur_cost = (*it)->chi2(); + + if (dynamic_cast(*it) != nullptr + || dynamic_cast(*it) != nullptr + || dynamic_cast(*it) != nullptr) + { + cur_cost *= obst_cost_scale; + } + else if (dynamic_cast(*it) != nullptr) + { + cur_cost *= viapoint_cost_scale; + } + else if (dynamic_cast(*it) != nullptr && alternative_time_cost) + { + continue; // skip these edges if alternative_time_cost is active + } + cost_ += cur_cost; + } + + // delete temporary created graph + if (!graph_exist_flag) + clearGraph(); +} + + +void TebOptimalPlanner::extractVelocity(const PoseSE2& pose1, const PoseSE2& pose2, double dt, double& vx, double& vy, double& omega) const +{ + if (dt == 0) + { + vx = 0; + vy = 0; + omega = 0; + return; + } + + Eigen::Vector2d deltaS = pose2.position() - pose1.position(); + + if (cfg_->robot.max_vel_y == 0) // nonholonomic robot + { + Eigen::Vector2d conf1dir( cos(pose1.theta()), sin(pose1.theta()) ); + // translational velocity + double dir = deltaS.dot(conf1dir); + vx = (double) g2o::sign(dir) * deltaS.norm()/dt; + vy = 0; + } + else // holonomic robot + { + // transform pose 2 into the current robot frame (pose1) + // for velocities only the rotation of the direction vector is necessary. + // (map->pose1-frame: inverse 2d rotation matrix) + double cos_theta1 = std::cos(pose1.theta()); + double sin_theta1 = std::sin(pose1.theta()); + double p1_dx = cos_theta1*deltaS.x() + sin_theta1*deltaS.y(); + double p1_dy = -sin_theta1*deltaS.x() + cos_theta1*deltaS.y(); + vx = p1_dx / dt; + vy = p1_dy / dt; + } + + // rotational velocity + double orientdiff = g2o::normalize_theta(pose2.theta() - pose1.theta()); + omega = orientdiff/dt; +} + +bool TebOptimalPlanner::getVelocityCommand(double& vx, double& vy, double& omega, int look_ahead_poses) const +{ + if (teb_.sizePoses()<2) + { + ROS_ERROR("TebOptimalPlanner::getVelocityCommand(): The trajectory contains less than 2 poses. Make sure to init and optimize/plan the trajectory fist."); + vx = 0; + vy = 0; + omega = 0; + return false; + } + look_ahead_poses = std::max(1, std::min(look_ahead_poses, teb_.sizePoses() - 1 - cfg_->trajectory.prevent_look_ahead_poses_near_goal)); + double dt = 0.0; + for(int counter = 0; counter < look_ahead_poses; ++counter) + { + dt += teb_.TimeDiff(counter); + if(dt >= cfg_->trajectory.dt_ref * look_ahead_poses) // TODO: change to look-ahead time? Refine trajectory? + { + look_ahead_poses = counter + 1; + break; + } + } + if (dt<=0) + { + ROS_ERROR("TebOptimalPlanner::getVelocityCommand() - timediff<=0 is invalid!"); + vx = 0; + vy = 0; + omega = 0; + return false; + } + + // Get velocity from the first two configurations + extractVelocity(teb_.Pose(0), teb_.Pose(look_ahead_poses), dt, vx, vy, omega); + return true; +} + +void TebOptimalPlanner::getVelocityProfile(std::vector& velocity_profile) const +{ + int n = teb_.sizePoses(); + velocity_profile.resize( n+1 ); + + // start velocity + velocity_profile.front().linear.z = 0; + velocity_profile.front().angular.x = velocity_profile.front().angular.y = 0; + velocity_profile.front().linear.x = vel_start_.second.linear.x; + velocity_profile.front().linear.y = vel_start_.second.linear.y; + velocity_profile.front().angular.z = vel_start_.second.angular.z; + + for (int i=1; i& trajectory) const +{ + int n = teb_.sizePoses(); + + trajectory.resize(n); + + if (n == 0) + return; + + double curr_time = 0; + + // start + TrajectoryPointMsg& start = trajectory.front(); + teb_.Pose(0).toPoseMsg(start.pose); + start.velocity.linear.z = 0; + start.velocity.angular.x = start.velocity.angular.y = 0; + start.velocity.linear.x = vel_start_.second.linear.x; + start.velocity.linear.y = vel_start_.second.linear.y; + start.velocity.angular.z = vel_start_.second.angular.z; + start.time_from_start.fromSec(curr_time); + + curr_time += teb_.TimeDiff(0); + + // intermediate points + for (int i=1; i < n-1; ++i) + { + TrajectoryPointMsg& point = trajectory[i]; + teb_.Pose(i).toPoseMsg(point.pose); + point.velocity.linear.z = 0; + point.velocity.angular.x = point.velocity.angular.y = 0; + double vel1_x, vel1_y, vel2_x, vel2_y, omega1, omega2; + extractVelocity(teb_.Pose(i-1), teb_.Pose(i), teb_.TimeDiff(i-1), vel1_x, vel1_y, omega1); + extractVelocity(teb_.Pose(i), teb_.Pose(i+1), teb_.TimeDiff(i), vel2_x, vel2_y, omega2); + point.velocity.linear.x = 0.5*(vel1_x+vel2_x); + point.velocity.linear.y = 0.5*(vel1_y+vel2_y); + point.velocity.angular.z = 0.5*(omega1+omega2); + point.time_from_start.fromSec(curr_time); + + curr_time += teb_.TimeDiff(i); + } + + // goal + TrajectoryPointMsg& goal = trajectory.back(); + teb_.BackPose().toPoseMsg(goal.pose); + goal.velocity.linear.z = 0; + goal.velocity.angular.x = goal.velocity.angular.y = 0; + goal.velocity.linear.x = vel_goal_.second.linear.x; + goal.velocity.linear.y = vel_goal_.second.linear.y; + goal.velocity.angular.z = vel_goal_.second.angular.z; + goal.time_from_start.fromSec(curr_time); +} + + +bool TebOptimalPlanner::isTrajectoryFeasible(base_local_planner::CostmapModel* costmap_model, const std::vector& footprint_spec, + double inscribed_radius, double circumscribed_radius, int look_ahead_idx, double feasibility_check_lookahead_distance) +{ + if (look_ahead_idx < 0 || look_ahead_idx >= teb().sizePoses()) + look_ahead_idx = teb().sizePoses() - 1; + + if (feasibility_check_lookahead_distance > 0){ + for (int i=1; i < teb().sizePoses(); ++i){ + double pose_distance=std::hypot(teb().Pose(i).x()-teb().Pose(0).x(), teb().Pose(i).y()-teb().Pose(0).y()); + if(pose_distance > feasibility_check_lookahead_distance){ + look_ahead_idx = i - 1; + break; + } + } + } + + for (int i=0; i <= look_ahead_idx; ++i) + { + if ( costmap_model->footprintCost(teb().Pose(i).x(), teb().Pose(i).y(), teb().Pose(i).theta(), footprint_spec, inscribed_radius, circumscribed_radius) == -1 ) + { + if (visualization_) + { + visualization_->publishInfeasibleRobotPose(teb().Pose(i), *robot_model_, footprint_spec); + } + return false; + } + // Checks if the distance between two poses is higher than the robot radius or the orientation diff is bigger than the specified threshold + // and interpolates in that case. + // (if obstacles are pushing two consecutive poses away, the center between two consecutive poses might coincide with the obstacle ;-)! + if (i cfg_->trajectory.min_resolution_collision_check_angular || delta_dist.norm() > inscribed_radius) + { + int n_additional_samples = std::max(std::ceil(fabs(delta_rot) / cfg_->trajectory.min_resolution_collision_check_angular), + std::ceil(delta_dist.norm() / inscribed_radius)) - 1; + PoseSE2 intermediate_pose = teb().Pose(i); + for(int step = 0; step < n_additional_samples; ++step) + { + intermediate_pose.position() = intermediate_pose.position() + delta_dist / (n_additional_samples + 1.0); + intermediate_pose.theta() = g2o::normalize_theta(intermediate_pose.theta() + + delta_rot / (n_additional_samples + 1.0)); + if ( costmap_model->footprintCost(intermediate_pose.x(), intermediate_pose.y(), intermediate_pose.theta(), + footprint_spec, inscribed_radius, circumscribed_radius) == -1 ) + { + if (visualization_) + { + visualization_->publishInfeasibleRobotPose(intermediate_pose, *robot_model_, footprint_spec); + } + return false; + } + } + } + } + } + return true; +} + +} // namespace teb_local_planner diff --git a/navigations/teb_local_planner/src/recovery_behaviors.cpp b/navigations/teb_local_planner/src/recovery_behaviors.cpp new file mode 100755 index 0000000..e16c11a --- /dev/null +++ b/navigations/teb_local_planner/src/recovery_behaviors.cpp @@ -0,0 +1,118 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2016, + * TU Dortmund - Institute of Control Theory and Systems Engineering. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the institute nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: Christoph Rösmann + *********************************************************************/ + +#include +#include +#include +#include +#include +#include + +namespace teb_local_planner +{ + +// ============== FailureDetector Implementation =================== + +void FailureDetector::update(const geometry_msgs::Twist& twist, double v_max, double v_backwards_max, double omega_max, double v_eps, double omega_eps) +{ + if (buffer_.capacity() == 0) + return; + + VelMeasurement measurement; + measurement.v = twist.linear.x; // just consider linear velocity in x-direction in the robot frame for now + measurement.omega = twist.angular.z; + + if (measurement.v > 0 && v_max>0) + measurement.v /= v_max; + else if (measurement.v < 0 && v_backwards_max > 0) + measurement.v /= v_backwards_max; + + if (omega_max > 0) + measurement.omega /= omega_max; + + buffer_.push_back(measurement); + + // immediately compute new state + detect(v_eps, omega_eps); +} + +void FailureDetector::clear() +{ + buffer_.clear(); + oscillating_ = false; +} + +bool FailureDetector::isOscillating() const +{ + return oscillating_; +} + +bool FailureDetector::detect(double v_eps, double omega_eps) +{ + oscillating_ = false; + + if (buffer_.size() < buffer_.capacity()/2) // we start detecting only as soon as we have the buffer filled at least half + return false; + + double n = (double)buffer_.size(); + + // compute mean for v and omega + double v_mean=0; + double omega_mean=0; + int omega_zero_crossings = 0; + for (int i=0; i < n; ++i) + { + v_mean += buffer_[i].v; + omega_mean += buffer_[i].omega; + if ( i>0 && g2o::sign(buffer_[i].omega) != g2o::sign(buffer_[i-1].omega) ) + ++omega_zero_crossings; + } + v_mean /= n; + omega_mean /= n; + + if (std::abs(v_mean) < v_eps && std::abs(omega_mean) < omega_eps && omega_zero_crossings>1 ) + { + oscillating_ = true; + } +// ROS_INFO_STREAM("v: " << std::abs(v_mean) << ", omega: " << std::abs(omega_mean) << ", zero crossings: " << omega_zero_crossings); + return oscillating_; +} + + + +} // namespace teb_local_planner diff --git a/navigations/teb_local_planner/src/teb_config.cpp b/navigations/teb_local_planner/src/teb_config.cpp new file mode 100755 index 0000000..a157d28 --- /dev/null +++ b/navigations/teb_local_planner/src/teb_config.cpp @@ -0,0 +1,397 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2016, + * TU Dortmund - Institute of Control Theory and Systems Engineering. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the institute nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: Christoph Rösmann + *********************************************************************/ + +#include + +namespace teb_local_planner +{ + +void TebConfig::loadRosParamFromNodeHandle(const ros::NodeHandle& nh) +{ + + nh.param("odom_topic", odom_topic, odom_topic); + nh.param("map_frame", map_frame, map_frame); + + // Trajectory + nh.param("teb_autosize", trajectory.teb_autosize, trajectory.teb_autosize); + nh.param("dt_ref", trajectory.dt_ref, trajectory.dt_ref); + nh.param("dt_hysteresis", trajectory.dt_hysteresis, trajectory.dt_hysteresis); + nh.param("min_samples", trajectory.min_samples, trajectory.min_samples); + nh.param("max_samples", trajectory.max_samples, trajectory.max_samples); + nh.param("global_plan_overwrite_orientation", trajectory.global_plan_overwrite_orientation, trajectory.global_plan_overwrite_orientation); + nh.param("allow_init_with_backwards_motion", trajectory.allow_init_with_backwards_motion, trajectory.allow_init_with_backwards_motion); + nh.getParam("global_plan_via_point_sep", trajectory.global_plan_viapoint_sep); // deprecated, see checkDeprecated() + if (!nh.param("global_plan_viapoint_sep", trajectory.global_plan_viapoint_sep, trajectory.global_plan_viapoint_sep)) + nh.setParam("global_plan_viapoint_sep", trajectory.global_plan_viapoint_sep); // write deprecated value to param server + nh.param("via_points_ordered", trajectory.via_points_ordered, trajectory.via_points_ordered); + nh.param("max_global_plan_lookahead_dist", trajectory.max_global_plan_lookahead_dist, trajectory.max_global_plan_lookahead_dist); + nh.param("global_plan_prune_distance", trajectory.global_plan_prune_distance, trajectory.global_plan_prune_distance); + nh.param("exact_arc_length", trajectory.exact_arc_length, trajectory.exact_arc_length); + nh.param("force_reinit_new_goal_dist", trajectory.force_reinit_new_goal_dist, trajectory.force_reinit_new_goal_dist); + nh.param("force_reinit_new_goal_angular", trajectory.force_reinit_new_goal_angular, trajectory.force_reinit_new_goal_angular); + nh.param("feasibility_check_no_poses", trajectory.feasibility_check_no_poses, trajectory.feasibility_check_no_poses); + nh.param("feasibility_check_lookahead_distance", trajectory.feasibility_check_lookahead_distance, trajectory.feasibility_check_lookahead_distance); + nh.param("publish_feedback", trajectory.publish_feedback, trajectory.publish_feedback); + nh.param("min_resolution_collision_check_angular", trajectory.min_resolution_collision_check_angular, trajectory.min_resolution_collision_check_angular); + nh.param("control_look_ahead_poses", trajectory.control_look_ahead_poses, trajectory.control_look_ahead_poses); + nh.param("prevent_look_ahead_poses_near_goal", trajectory.prevent_look_ahead_poses_near_goal, trajectory.prevent_look_ahead_poses_near_goal); + + // Robot + nh.param("max_vel_x", robot.max_vel_x, robot.max_vel_x); + nh.param("max_vel_x_backwards", robot.max_vel_x_backwards, robot.max_vel_x_backwards); + nh.param("max_vel_y", robot.max_vel_y, robot.max_vel_y); + nh.param("max_vel_trans", robot.max_vel_trans, robot.max_vel_trans); + nh.param("max_vel_theta", robot.max_vel_theta, robot.max_vel_theta); + nh.param("acc_lim_x", robot.acc_lim_x, robot.acc_lim_x); + nh.param("acc_lim_y", robot.acc_lim_y, robot.acc_lim_y); + nh.param("acc_lim_theta", robot.acc_lim_theta, robot.acc_lim_theta); + nh.param("min_turning_radius", robot.min_turning_radius, robot.min_turning_radius); + nh.param("wheelbase", robot.wheelbase, robot.wheelbase); + nh.param("cmd_angle_instead_rotvel", robot.cmd_angle_instead_rotvel, robot.cmd_angle_instead_rotvel); + nh.param("is_footprint_dynamic", robot.is_footprint_dynamic, robot.is_footprint_dynamic); + nh.param("use_proportional_saturation", robot.use_proportional_saturation, robot.use_proportional_saturation); + nh.param("transform_tolerance", robot.transform_tolerance, robot.transform_tolerance); + + // GoalTolerance + nh.param("xy_goal_tolerance", goal_tolerance.xy_goal_tolerance, goal_tolerance.xy_goal_tolerance); + nh.param("yaw_goal_tolerance", goal_tolerance.yaw_goal_tolerance, goal_tolerance.yaw_goal_tolerance); + nh.param("free_goal_vel", goal_tolerance.free_goal_vel, goal_tolerance.free_goal_vel); + nh.param("trans_stopped_vel", goal_tolerance.trans_stopped_vel, goal_tolerance.trans_stopped_vel); + nh.param("theta_stopped_vel", goal_tolerance.theta_stopped_vel, goal_tolerance.theta_stopped_vel); + nh.param("complete_global_plan", goal_tolerance.complete_global_plan, goal_tolerance.complete_global_plan); + + // Obstacles + nh.param("min_obstacle_dist", obstacles.min_obstacle_dist, obstacles.min_obstacle_dist); + nh.param("inflation_dist", obstacles.inflation_dist, obstacles.inflation_dist); + nh.param("dynamic_obstacle_inflation_dist", obstacles.dynamic_obstacle_inflation_dist, obstacles.dynamic_obstacle_inflation_dist); + nh.param("include_dynamic_obstacles", obstacles.include_dynamic_obstacles, obstacles.include_dynamic_obstacles); + nh.param("include_costmap_obstacles", obstacles.include_costmap_obstacles, obstacles.include_costmap_obstacles); + nh.param("costmap_obstacles_behind_robot_dist", obstacles.costmap_obstacles_behind_robot_dist, obstacles.costmap_obstacles_behind_robot_dist); + nh.param("obstacle_poses_affected", obstacles.obstacle_poses_affected, obstacles.obstacle_poses_affected); + nh.param("legacy_obstacle_association", obstacles.legacy_obstacle_association, obstacles.legacy_obstacle_association); + nh.param("obstacle_association_force_inclusion_factor", obstacles.obstacle_association_force_inclusion_factor, obstacles.obstacle_association_force_inclusion_factor); + nh.param("obstacle_association_cutoff_factor", obstacles.obstacle_association_cutoff_factor, obstacles.obstacle_association_cutoff_factor); + nh.param("costmap_converter_plugin", obstacles.costmap_converter_plugin, obstacles.costmap_converter_plugin); + nh.param("costmap_converter_spin_thread", obstacles.costmap_converter_spin_thread, obstacles.costmap_converter_spin_thread); + nh.param("obstacle_proximity_ratio_max_vel", obstacles.obstacle_proximity_ratio_max_vel, obstacles.obstacle_proximity_ratio_max_vel); + nh.param("obstacle_proximity_lower_bound", obstacles.obstacle_proximity_lower_bound, obstacles.obstacle_proximity_lower_bound); + nh.param("obstacle_proximity_upper_bound", obstacles.obstacle_proximity_upper_bound, obstacles.obstacle_proximity_upper_bound); + + // Optimization + nh.param("no_inner_iterations", optim.no_inner_iterations, optim.no_inner_iterations); + nh.param("no_outer_iterations", optim.no_outer_iterations, optim.no_outer_iterations); + nh.param("optimization_activate", optim.optimization_activate, optim.optimization_activate); + nh.param("optimization_verbose", optim.optimization_verbose, optim.optimization_verbose); + nh.param("penalty_epsilon", optim.penalty_epsilon, optim.penalty_epsilon); + nh.param("weight_max_vel_x", optim.weight_max_vel_x, optim.weight_max_vel_x); + nh.param("weight_max_vel_y", optim.weight_max_vel_y, optim.weight_max_vel_y); + nh.param("weight_max_vel_theta", optim.weight_max_vel_theta, optim.weight_max_vel_theta); + nh.param("weight_acc_lim_x", optim.weight_acc_lim_x, optim.weight_acc_lim_x); + nh.param("weight_acc_lim_y", optim.weight_acc_lim_y, optim.weight_acc_lim_y); + nh.param("weight_acc_lim_theta", optim.weight_acc_lim_theta, optim.weight_acc_lim_theta); + nh.param("weight_kinematics_nh", optim.weight_kinematics_nh, optim.weight_kinematics_nh); + nh.param("weight_kinematics_forward_drive", optim.weight_kinematics_forward_drive, optim.weight_kinematics_forward_drive); + nh.param("weight_kinematics_turning_radius", optim.weight_kinematics_turning_radius, optim.weight_kinematics_turning_radius); + nh.param("weight_optimaltime", optim.weight_optimaltime, optim.weight_optimaltime); + nh.param("weight_shortest_path", optim.weight_shortest_path, optim.weight_shortest_path); + nh.param("weight_obstacle", optim.weight_obstacle, optim.weight_obstacle); + nh.param("weight_inflation", optim.weight_inflation, optim.weight_inflation); + nh.param("weight_dynamic_obstacle", optim.weight_dynamic_obstacle, optim.weight_dynamic_obstacle); + nh.param("weight_dynamic_obstacle_inflation", optim.weight_dynamic_obstacle_inflation, optim.weight_dynamic_obstacle_inflation); + nh.param("weight_velocity_obstacle_ratio", optim.weight_velocity_obstacle_ratio, optim.weight_velocity_obstacle_ratio); + nh.param("weight_viapoint", optim.weight_viapoint, optim.weight_viapoint); + nh.param("weight_prefer_rotdir", optim.weight_prefer_rotdir, optim.weight_prefer_rotdir); + nh.param("weight_adapt_factor", optim.weight_adapt_factor, optim.weight_adapt_factor); + nh.param("obstacle_cost_exponent", optim.obstacle_cost_exponent, optim.obstacle_cost_exponent); + + // Homotopy Class Planner + nh.param("enable_homotopy_class_planning", hcp.enable_homotopy_class_planning, hcp.enable_homotopy_class_planning); + nh.param("enable_multithreading", hcp.enable_multithreading, hcp.enable_multithreading); + nh.param("simple_exploration", hcp.simple_exploration, hcp.simple_exploration); + nh.param("max_number_classes", hcp.max_number_classes, hcp.max_number_classes); + nh.param("max_number_plans_in_current_class", hcp.max_number_plans_in_current_class, hcp.max_number_plans_in_current_class); + nh.param("selection_obst_cost_scale", hcp.selection_obst_cost_scale, hcp.selection_obst_cost_scale); + nh.param("selection_prefer_initial_plan", hcp.selection_prefer_initial_plan, hcp.selection_prefer_initial_plan); + nh.param("selection_viapoint_cost_scale", hcp.selection_viapoint_cost_scale, hcp.selection_viapoint_cost_scale); + nh.param("selection_cost_hysteresis", hcp.selection_cost_hysteresis, hcp.selection_cost_hysteresis); + nh.param("selection_alternative_time_cost", hcp.selection_alternative_time_cost, hcp.selection_alternative_time_cost); + nh.param("selection_dropping_probability", hcp.selection_dropping_probability, hcp.selection_dropping_probability); + nh.param("switching_blocking_period", hcp.switching_blocking_period, hcp.switching_blocking_period); + nh.param("roadmap_graph_samples", hcp.roadmap_graph_no_samples, hcp.roadmap_graph_no_samples); + nh.param("roadmap_graph_area_width", hcp.roadmap_graph_area_width, hcp.roadmap_graph_area_width); + nh.param("roadmap_graph_area_length_scale", hcp.roadmap_graph_area_length_scale, hcp.roadmap_graph_area_length_scale); + nh.param("h_signature_prescaler", hcp.h_signature_prescaler, hcp.h_signature_prescaler); + nh.param("h_signature_threshold", hcp.h_signature_threshold, hcp.h_signature_threshold); + nh.param("obstacle_keypoint_offset", hcp.obstacle_keypoint_offset, hcp.obstacle_keypoint_offset); + nh.param("obstacle_heading_threshold", hcp.obstacle_heading_threshold, hcp.obstacle_heading_threshold); + nh.param("viapoints_all_candidates", hcp.viapoints_all_candidates, hcp.viapoints_all_candidates); + nh.param("visualize_hc_graph", hcp.visualize_hc_graph, hcp.visualize_hc_graph); + nh.param("visualize_with_time_as_z_axis_scale", hcp.visualize_with_time_as_z_axis_scale, hcp.visualize_with_time_as_z_axis_scale); + nh.param("delete_detours_backwards", hcp.delete_detours_backwards, hcp.delete_detours_backwards); + nh.param("detours_orientation_tolerance", hcp.detours_orientation_tolerance, hcp.detours_orientation_tolerance); + nh.param("length_start_orientation_vector", hcp.length_start_orientation_vector, hcp.length_start_orientation_vector); + nh.param("max_ratio_detours_duration_best_duration", hcp.max_ratio_detours_duration_best_duration, hcp.max_ratio_detours_duration_best_duration); + + // Recovery + nh.param("shrink_horizon_backup", recovery.shrink_horizon_backup, recovery.shrink_horizon_backup); + nh.param("shrink_horizon_min_duration", recovery.shrink_horizon_min_duration, recovery.shrink_horizon_min_duration); + nh.param("oscillation_recovery", recovery.oscillation_recovery, recovery.oscillation_recovery); + nh.param("oscillation_v_eps", recovery.oscillation_v_eps, recovery.oscillation_v_eps); + nh.param("oscillation_omega_eps", recovery.oscillation_omega_eps, recovery.oscillation_omega_eps); + nh.param("oscillation_recovery_min_duration", recovery.oscillation_recovery_min_duration, recovery.oscillation_recovery_min_duration); + nh.param("oscillation_filter_duration", recovery.oscillation_filter_duration, recovery.oscillation_filter_duration); + nh.param("divergence_detection", recovery.divergence_detection_enable, recovery.divergence_detection_enable); + nh.param("divergence_detection_max_chi_squared", recovery.divergence_detection_max_chi_squared, recovery.divergence_detection_max_chi_squared); + + checkParameters(); + checkDeprecated(nh); +} + +void TebConfig::reconfigure(TebLocalPlannerReconfigureConfig& cfg) +{ + boost::mutex::scoped_lock l(config_mutex_); + + // Trajectory + trajectory.teb_autosize = cfg.teb_autosize; + trajectory.dt_ref = cfg.dt_ref; + trajectory.dt_hysteresis = cfg.dt_hysteresis; + trajectory.global_plan_overwrite_orientation = cfg.global_plan_overwrite_orientation; + trajectory.allow_init_with_backwards_motion = cfg.allow_init_with_backwards_motion; + trajectory.global_plan_viapoint_sep = cfg.global_plan_viapoint_sep; + trajectory.via_points_ordered = cfg.via_points_ordered; + trajectory.max_global_plan_lookahead_dist = cfg.max_global_plan_lookahead_dist; + trajectory.exact_arc_length = cfg.exact_arc_length; + trajectory.force_reinit_new_goal_dist = cfg.force_reinit_new_goal_dist; + trajectory.force_reinit_new_goal_angular = cfg.force_reinit_new_goal_angular; + trajectory.feasibility_check_no_poses = cfg.feasibility_check_no_poses; + trajectory.feasibility_check_lookahead_distance = cfg.feasibility_check_lookahead_distance; + trajectory.publish_feedback = cfg.publish_feedback; + trajectory.control_look_ahead_poses = cfg.control_look_ahead_poses; + trajectory.prevent_look_ahead_poses_near_goal = cfg.prevent_look_ahead_poses_near_goal; + + // Robot + robot.max_vel_x = cfg.max_vel_x; + robot.max_vel_x_backwards = cfg.max_vel_x_backwards; + robot.max_vel_y = cfg.max_vel_y; + robot.max_vel_theta = cfg.max_vel_theta; + robot.acc_lim_x = cfg.acc_lim_x; + robot.acc_lim_y = cfg.acc_lim_y; + robot.acc_lim_theta = cfg.acc_lim_theta; + robot.min_turning_radius = cfg.min_turning_radius; + robot.wheelbase = cfg.wheelbase; + robot.cmd_angle_instead_rotvel = cfg.cmd_angle_instead_rotvel; + robot.use_proportional_saturation = cfg.use_proportional_saturation; + if (cfg.max_vel_trans == 0.0) + { + ROS_INFO_STREAM("max_vel_trans is not set, setting it equal to max_vel_x: " << robot.max_vel_x); + cfg.max_vel_trans = robot.max_vel_x; + } + robot.max_vel_trans = cfg.max_vel_trans; + + // GoalTolerance + goal_tolerance.xy_goal_tolerance = cfg.xy_goal_tolerance; + goal_tolerance.yaw_goal_tolerance = cfg.yaw_goal_tolerance; + goal_tolerance.free_goal_vel = cfg.free_goal_vel; + goal_tolerance.trans_stopped_vel = cfg.trans_stopped_vel; + goal_tolerance.theta_stopped_vel = cfg.theta_stopped_vel; + + // Obstacles + obstacles.min_obstacle_dist = cfg.min_obstacle_dist; + obstacles.inflation_dist = cfg.inflation_dist; + obstacles.dynamic_obstacle_inflation_dist = cfg.dynamic_obstacle_inflation_dist; + obstacles.include_dynamic_obstacles = cfg.include_dynamic_obstacles; + obstacles.include_costmap_obstacles = cfg.include_costmap_obstacles; + obstacles.legacy_obstacle_association = cfg.legacy_obstacle_association; + obstacles.obstacle_association_force_inclusion_factor = cfg.obstacle_association_force_inclusion_factor; + obstacles.obstacle_association_cutoff_factor = cfg.obstacle_association_cutoff_factor; + obstacles.costmap_obstacles_behind_robot_dist = cfg.costmap_obstacles_behind_robot_dist; + obstacles.obstacle_poses_affected = cfg.obstacle_poses_affected; + obstacles.obstacle_proximity_ratio_max_vel = cfg.obstacle_proximity_ratio_max_vel; + obstacles.obstacle_proximity_lower_bound = cfg.obstacle_proximity_lower_bound; + obstacles.obstacle_proximity_upper_bound = cfg.obstacle_proximity_upper_bound; + + // Optimization + optim.no_inner_iterations = cfg.no_inner_iterations; + optim.no_outer_iterations = cfg.no_outer_iterations; + optim.optimization_activate = cfg.optimization_activate; + optim.optimization_verbose = cfg.optimization_verbose; + optim.penalty_epsilon = cfg.penalty_epsilon; + optim.weight_max_vel_x = cfg.weight_max_vel_x; + optim.weight_max_vel_y = cfg.weight_max_vel_y; + optim.weight_max_vel_theta = cfg.weight_max_vel_theta; + optim.weight_acc_lim_x = cfg.weight_acc_lim_x; + optim.weight_acc_lim_y = cfg.weight_acc_lim_y; + optim.weight_acc_lim_theta = cfg.weight_acc_lim_theta; + optim.weight_kinematics_nh = cfg.weight_kinematics_nh; + optim.weight_kinematics_forward_drive = cfg.weight_kinematics_forward_drive; + optim.weight_kinematics_turning_radius = cfg.weight_kinematics_turning_radius; + optim.weight_optimaltime = cfg.weight_optimaltime; + optim.weight_shortest_path = cfg.weight_shortest_path; + optim.weight_obstacle = cfg.weight_obstacle; + optim.weight_inflation = cfg.weight_inflation; + optim.weight_dynamic_obstacle = cfg.weight_dynamic_obstacle; + optim.weight_dynamic_obstacle_inflation = cfg.weight_dynamic_obstacle_inflation; + optim.weight_velocity_obstacle_ratio = cfg.weight_velocity_obstacle_ratio; + optim.weight_viapoint = cfg.weight_viapoint; + optim.weight_adapt_factor = cfg.weight_adapt_factor; + optim.obstacle_cost_exponent = cfg.obstacle_cost_exponent; + + // Homotopy Class Planner + hcp.enable_multithreading = cfg.enable_multithreading; + hcp.max_number_classes = cfg.max_number_classes; + hcp.max_number_plans_in_current_class = cfg.max_number_plans_in_current_class; + hcp.selection_cost_hysteresis = cfg.selection_cost_hysteresis; + hcp.selection_prefer_initial_plan = cfg.selection_prefer_initial_plan; + hcp.selection_obst_cost_scale = cfg.selection_obst_cost_scale; + hcp.selection_viapoint_cost_scale = cfg.selection_viapoint_cost_scale; + hcp.selection_alternative_time_cost = cfg.selection_alternative_time_cost; + hcp.selection_dropping_probability = cfg.selection_dropping_probability; + hcp.switching_blocking_period = cfg.switching_blocking_period; + + hcp.obstacle_heading_threshold = cfg.obstacle_heading_threshold; + hcp.roadmap_graph_no_samples = cfg.roadmap_graph_no_samples; + hcp.roadmap_graph_area_width = cfg.roadmap_graph_area_width; + hcp.roadmap_graph_area_length_scale = cfg.roadmap_graph_area_length_scale; + hcp.h_signature_prescaler = cfg.h_signature_prescaler; + hcp.h_signature_threshold = cfg.h_signature_threshold; + hcp.viapoints_all_candidates = cfg.viapoints_all_candidates; + hcp.visualize_hc_graph = cfg.visualize_hc_graph; + hcp.visualize_with_time_as_z_axis_scale = cfg.visualize_with_time_as_z_axis_scale; + + // Recovery + recovery.shrink_horizon_backup = cfg.shrink_horizon_backup; + recovery.oscillation_recovery = cfg.oscillation_recovery; + recovery.divergence_detection_enable = cfg.divergence_detection_enable; + recovery.divergence_detection_max_chi_squared = cfg.divergence_detection_max_chi_squared; + + + checkParameters(); +} + + +void TebConfig::checkParameters() const +{ + // positive backward velocity? + if (robot.max_vel_x_backwards <= 0) + ROS_WARN("TebLocalPlannerROS() Param Warning: Do not choose max_vel_x_backwards to be <=0. Disable backwards driving by increasing the optimization weight for penalyzing backwards driving."); + + // bounds smaller than penalty epsilon + if (robot.max_vel_x <= optim.penalty_epsilon) + ROS_WARN("TebLocalPlannerROS() Param Warning: max_vel_x <= penalty_epsilon. The resulting bound is negative. Undefined behavior... Change at least one of them!"); + + if (robot.max_vel_x_backwards <= optim.penalty_epsilon) + ROS_WARN("TebLocalPlannerROS() Param Warning: max_vel_x_backwards <= penalty_epsilon. The resulting bound is negative. Undefined behavior... Change at least one of them!"); + + if (robot.max_vel_theta <= optim.penalty_epsilon) + ROS_WARN("TebLocalPlannerROS() Param Warning: max_vel_theta <= penalty_epsilon. The resulting bound is negative. Undefined behavior... Change at least one of them!"); + + if (robot.acc_lim_x <= optim.penalty_epsilon) + ROS_WARN("TebLocalPlannerROS() Param Warning: acc_lim_x <= penalty_epsilon. The resulting bound is negative. Undefined behavior... Change at least one of them!"); + + if (robot.acc_lim_theta <= optim.penalty_epsilon) + ROS_WARN("TebLocalPlannerROS() Param Warning: acc_lim_theta <= penalty_epsilon. The resulting bound is negative. Undefined behavior... Change at least one of them!"); + + // dt_ref and dt_hyst + if (trajectory.dt_ref <= trajectory.dt_hysteresis) + ROS_WARN("TebLocalPlannerROS() Param Warning: dt_ref <= dt_hysteresis. The hysteresis is not allowed to be greater or equal!. Undefined behavior... Change at least one of them!"); + + // min number of samples + if (trajectory.min_samples <3) + ROS_WARN("TebLocalPlannerROS() Param Warning: parameter min_samples is smaller than 3! Sorry, I haven't enough degrees of freedom to plan a trajectory for you. Please increase ..."); + + // costmap obstacle behind robot + if (obstacles.costmap_obstacles_behind_robot_dist < 0) + ROS_WARN("TebLocalPlannerROS() Param Warning: parameter 'costmap_obstacles_behind_robot_dist' should be positive or zero."); + + // hcp: obstacle heading threshold + if (hcp.obstacle_keypoint_offset>=1 || hcp.obstacle_keypoint_offset<=0) + ROS_WARN("TebLocalPlannerROS() Param Warning: parameter obstacle_heading_threshold must be in the interval ]0,1[. 0=0deg opening angle, 1=90deg opening angle."); + + // carlike + if (robot.cmd_angle_instead_rotvel && robot.wheelbase==0) + ROS_WARN("TebLocalPlannerROS() Param Warning: parameter cmd_angle_instead_rotvel is non-zero but wheelbase is set to zero: undesired behavior."); + + if (robot.cmd_angle_instead_rotvel && robot.min_turning_radius==0) + ROS_WARN("TebLocalPlannerROS() Param Warning: parameter cmd_angle_instead_rotvel is non-zero but min_turning_radius is set to zero: undesired behavior. You are mixing a carlike and a diffdrive robot"); + + // positive weight_adapt_factor + if (optim.weight_adapt_factor < 1.0) + ROS_WARN("TebLocalPlannerROS() Param Warning: parameter weight_adapt_factor shoud be >= 1.0"); + + if (recovery.oscillation_filter_duration < 0) + ROS_WARN("TebLocalPlannerROS() Param Warning: parameter oscillation_filter_duration must be >= 0"); + + // weights + if (optim.weight_optimaltime <= 0) + ROS_WARN("TebLocalPlannerROS() Param Warning: parameter weight_optimaltime shoud be > 0 (even if weight_shortest_path is in use)"); + + // holonomic check + if (robot.max_vel_y > 0) { + if (robot.max_vel_trans < std::min(robot.max_vel_x, robot.max_vel_trans)) { + ROS_WARN("TebLocalPlannerROS() Param Warning: max_vel_trans < min(max_vel_x, max_vel_y). Note that vel_trans = sqrt(Vx^2 + Vy^2), thus max_vel_trans will limit Vx and Vy in the optimization step."); + } + + if (robot.max_vel_trans > std::max(robot.max_vel_x, robot.max_vel_y)) { + ROS_WARN("TebLocalPlannerROS() Param Warning: max_vel_trans > max(max_vel_x, max_vel_y). Robot will rotate and move diagonally to achieve max resultant vel (possibly max vel on both axis), limited by the max_vel_trans."); + } + } + +} + +void TebConfig::checkDeprecated(const ros::NodeHandle& nh) const +{ + if (nh.hasParam("line_obstacle_poses_affected") || nh.hasParam("polygon_obstacle_poses_affected")) + ROS_WARN("TebLocalPlannerROS() Param Warning: 'line_obstacle_poses_affected' and 'polygon_obstacle_poses_affected' are deprecated. They share now the common parameter 'obstacle_poses_affected'."); + + if (nh.hasParam("weight_point_obstacle") || nh.hasParam("weight_line_obstacle") || nh.hasParam("weight_poly_obstacle")) + ROS_WARN("TebLocalPlannerROS() Param Warning: 'weight_point_obstacle', 'weight_line_obstacle' and 'weight_poly_obstacle' are deprecated. They are replaced by the single param 'weight_obstacle'."); + + if (nh.hasParam("costmap_obstacles_front_only")) + ROS_WARN("TebLocalPlannerROS() Param Warning: 'costmap_obstacles_front_only' is deprecated. It is replaced by 'costmap_obstacles_behind_robot_dist' to define the actual area taken into account."); + + if (nh.hasParam("costmap_emergency_stop_dist")) + ROS_WARN("TebLocalPlannerROS() Param Warning: 'costmap_emergency_stop_dist' is deprecated. You can safely remove it from your parameter config."); + + if (nh.hasParam("alternative_time_cost")) + ROS_WARN("TebLocalPlannerROS() Param Warning: 'alternative_time_cost' is deprecated. It has been replaced by 'selection_alternative_time_cost'."); + + if (nh.hasParam("global_plan_via_point_sep")) + ROS_WARN("TebLocalPlannerROS() Param Warning: 'global_plan_via_point_sep' is deprecated. It has been replaced by 'global_plan_viapoint_sep' due to consistency reasons."); +} + +} // namespace teb_local_planner diff --git a/navigations/teb_local_planner/src/teb_local_planner_ros.cpp b/navigations/teb_local_planner/src/teb_local_planner_ros.cpp new file mode 100755 index 0000000..7a58618 --- /dev/null +++ b/navigations/teb_local_planner/src/teb_local_planner_ros.cpp @@ -0,0 +1,1218 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2016, + * TU Dortmund - Institute of Control Theory and Systems Engineering. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the institute nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: Christoph Rösmann + *********************************************************************/ + +#include + +#include +#include + +#include + +// MBF return codes +#include + +// pluginlib macros +#include + +#include "g2o/core/sparse_optimizer.h" +#include "g2o/core/block_solver.h" +#include "g2o/core/factory.h" +#include "g2o/core/optimization_algorithm_gauss_newton.h" +#include "g2o/core/optimization_algorithm_levenberg.h" +#include "g2o/solvers/csparse/linear_solver_csparse.h" +#include "g2o/solvers/cholmod/linear_solver_cholmod.h" + + +// register this planner both as a BaseLocalPlanner and as a MBF's CostmapController plugin +PLUGINLIB_EXPORT_CLASS(teb_local_planner::TebLocalPlannerROS, nav_core::BaseLocalPlanner) +PLUGINLIB_EXPORT_CLASS(teb_local_planner::TebLocalPlannerROS, mbf_costmap_core::CostmapController) + +namespace teb_local_planner +{ + + +TebLocalPlannerROS::TebLocalPlannerROS() : costmap_ros_(NULL), tf_(NULL), costmap_model_(NULL), + costmap_converter_loader_("costmap_converter", "costmap_converter::BaseCostmapToPolygons"), + dynamic_recfg_(NULL), custom_via_points_active_(false), goal_reached_(false), no_infeasible_plans_(0), + last_preferred_rotdir_(RotType::none), initialized_(false) +{ +} + + +TebLocalPlannerROS::~TebLocalPlannerROS() +{ +} + +void TebLocalPlannerROS::reconfigureCB(TebLocalPlannerReconfigureConfig& config, uint32_t level) +{ + cfg_.reconfigure(config); + ros::NodeHandle nh("~/" + name_); + // create robot footprint/contour model for optimization + RobotFootprintModelPtr robot_model = getRobotFootprintFromParamServer(nh, cfg_); + planner_->updateRobotModel(robot_model); +} + +void TebLocalPlannerROS::initialize(std::string name, tf2_ros::Buffer* tf, costmap_2d::Costmap2DROS* costmap_ros) +{ + // check if the plugin is already initialized + if(!initialized_) + { + name_ = name; + // create Node Handle with name of plugin (as used in move_base for loading) + ros::NodeHandle nh("~/" + name); + + // get parameters of TebConfig via the nodehandle and override the default config + cfg_.loadRosParamFromNodeHandle(nh); + + // reserve some memory for obstacles + obstacles_.reserve(500); + + // create visualization instance + visualization_ = TebVisualizationPtr(new TebVisualization(nh, cfg_)); + + // create robot footprint/contour model for optimization + RobotFootprintModelPtr robot_model = getRobotFootprintFromParamServer(nh, cfg_); + + // create the planner instance + if (cfg_.hcp.enable_homotopy_class_planning) + { + planner_ = PlannerInterfacePtr(new HomotopyClassPlanner(cfg_, &obstacles_, robot_model, visualization_, &via_points_)); + ROS_INFO("Parallel planning in distinctive topologies enabled."); + } + else + { + planner_ = PlannerInterfacePtr(new TebOptimalPlanner(cfg_, &obstacles_, robot_model, visualization_, &via_points_)); + ROS_INFO("Parallel planning in distinctive topologies disabled."); + } + + // init other variables + tf_ = tf; + costmap_ros_ = costmap_ros; + costmap_ = costmap_ros_->getCostmap(); // locking should be done in MoveBase. + + costmap_model_ = boost::make_shared(*costmap_); + + global_frame_ = costmap_ros_->getGlobalFrameID(); + cfg_.map_frame = global_frame_; // TODO + robot_base_frame_ = costmap_ros_->getBaseFrameID(); + + //Initialize a costmap to polygon converter + if (!cfg_.obstacles.costmap_converter_plugin.empty()) + { + try + { + costmap_converter_ = costmap_converter_loader_.createInstance(cfg_.obstacles.costmap_converter_plugin); + std::string converter_name = costmap_converter_loader_.getName(cfg_.obstacles.costmap_converter_plugin); + // replace '::' by '/' to convert the c++ namespace to a NodeHandle namespace + boost::replace_all(converter_name, "::", "/"); + costmap_converter_->setOdomTopic(cfg_.odom_topic); + costmap_converter_->initialize(ros::NodeHandle(nh, "costmap_converter/" + converter_name)); + costmap_converter_->setCostmap2D(costmap_); + + costmap_converter_->startWorker(ros::Rate(cfg_.obstacles.costmap_converter_rate), costmap_, cfg_.obstacles.costmap_converter_spin_thread); + ROS_INFO_STREAM("Costmap conversion plugin " << cfg_.obstacles.costmap_converter_plugin << " loaded."); + } + catch(pluginlib::PluginlibException& ex) + { + ROS_WARN("The specified costmap converter plugin cannot be loaded. All occupied costmap cells are treaten as point obstacles. Error message: %s", ex.what()); + costmap_converter_.reset(); + } + } + else + ROS_INFO("No costmap conversion plugin specified. All occupied costmap cells are treaten as point obstacles."); + + + // Get footprint of the robot and minimum and maximum distance from the center of the robot to its footprint vertices. + footprint_spec_ = costmap_ros_->getRobotFootprint(); + costmap_2d::calculateMinAndMaxDistances(footprint_spec_, robot_inscribed_radius_, robot_circumscribed_radius); + + // init the odom helper to receive the robot's velocity from odom messages + odom_helper_.setOdomTopic(cfg_.odom_topic); + + // setup dynamic reconfigure + dynamic_recfg_ = boost::make_shared< dynamic_reconfigure::Server >(nh); + dynamic_reconfigure::Server::CallbackType cb = boost::bind(&TebLocalPlannerROS::reconfigureCB, this, _1, _2); + dynamic_recfg_->setCallback(cb); + + // validate optimization footprint and costmap footprint + validateFootprints(robot_model->getInscribedRadius(), robot_inscribed_radius_, cfg_.obstacles.min_obstacle_dist); + + // setup callback for custom obstacles + custom_obst_sub_ = nh.subscribe("obstacles", 1, &TebLocalPlannerROS::customObstacleCB, this); + + // setup callback for custom via-points + via_points_sub_ = nh.subscribe("via_points", 1, &TebLocalPlannerROS::customViaPointsCB, this); + + // initialize failure detector + ros::NodeHandle nh_move_base("~"); + double controller_frequency = 5; + nh_move_base.param("controller_frequency", controller_frequency, controller_frequency); + failure_detector_.setBufferLength(std::round(cfg_.recovery.oscillation_filter_duration*controller_frequency)); + + // set initialized flag + initialized_ = true; + + ROS_DEBUG("teb_local_planner plugin initialized."); + } + else + { + ROS_WARN("teb_local_planner has already been initialized, doing nothing."); + } +} + + + +bool TebLocalPlannerROS::setPlan(const std::vector& orig_global_plan) +{ + // check if plugin is initialized + if(!initialized_) + { + ROS_ERROR("teb_local_planner has not been initialized, please call initialize() before using this planner"); + return false; + } + + // store the global plan + global_plan_.clear(); + global_plan_ = orig_global_plan; + + // we do not clear the local planner here, since setPlan is called frequently whenever the global planner updates the plan. + // the local planner checks whether it is required to reinitialize the trajectory or not within each velocity computation step. + + // reset goal_reached_ flag + goal_reached_ = false; + + return true; +} + + +bool TebLocalPlannerROS::computeVelocityCommands(geometry_msgs::Twist& cmd_vel) +{ + std::string dummy_message; + geometry_msgs::PoseStamped dummy_pose; + geometry_msgs::TwistStamped dummy_velocity, cmd_vel_stamped; + uint32_t outcome = computeVelocityCommands(dummy_pose, dummy_velocity, cmd_vel_stamped, dummy_message); + cmd_vel = cmd_vel_stamped.twist; + return outcome == mbf_msgs::ExePathResult::SUCCESS; +} + +uint32_t TebLocalPlannerROS::computeVelocityCommands(const geometry_msgs::PoseStamped& pose, + const geometry_msgs::TwistStamped& velocity, + geometry_msgs::TwistStamped &cmd_vel, + std::string &message) +{ + // check if plugin initialized + if(!initialized_) + { + ROS_ERROR("teb_local_planner has not been initialized, please call initialize() before using this planner"); + message = "teb_local_planner has not been initialized"; + return mbf_msgs::ExePathResult::NOT_INITIALIZED; + } + + static uint32_t seq = 0; + cmd_vel.header.seq = seq++; + cmd_vel.header.stamp = ros::Time::now(); + cmd_vel.header.frame_id = robot_base_frame_; + cmd_vel.twist.linear.x = cmd_vel.twist.linear.y = cmd_vel.twist.angular.z = 0; + goal_reached_ = false; + + // Get robot pose + geometry_msgs::PoseStamped robot_pose; + costmap_ros_->getRobotPose(robot_pose); + robot_pose_ = PoseSE2(robot_pose.pose); + + // Get robot velocity + geometry_msgs::PoseStamped robot_vel_tf; + odom_helper_.getRobotVel(robot_vel_tf); + robot_vel_.linear.x = robot_vel_tf.pose.position.x; + robot_vel_.linear.y = robot_vel_tf.pose.position.y; + robot_vel_.angular.z = tf2::getYaw(robot_vel_tf.pose.orientation); + + // prune global plan to cut off parts of the past (spatially before the robot) + pruneGlobalPlan(*tf_, robot_pose, global_plan_, cfg_.trajectory.global_plan_prune_distance); + + // Transform global plan to the frame of interest (w.r.t. the local costmap) + std::vector transformed_plan; + int goal_idx; + geometry_msgs::TransformStamped tf_plan_to_global; + if (!transformGlobalPlan(*tf_, global_plan_, robot_pose, *costmap_, global_frame_, cfg_.trajectory.max_global_plan_lookahead_dist, + transformed_plan, &goal_idx, &tf_plan_to_global)) + { + ROS_WARN("Could not transform the global plan to the frame of the controller"); + message = "Could not transform the global plan to the frame of the controller"; + return mbf_msgs::ExePathResult::INTERNAL_ERROR; + } + + // update via-points container + if (!custom_via_points_active_) + updateViaPointsContainer(transformed_plan, cfg_.trajectory.global_plan_viapoint_sep); + + nav_msgs::Odometry base_odom; + odom_helper_.getOdom(base_odom); + + // check if global goal is reached + geometry_msgs::PoseStamped global_goal; + tf2::doTransform(global_plan_.back(), global_goal, tf_plan_to_global); + double dx = global_goal.pose.position.x - robot_pose_.x(); + double dy = global_goal.pose.position.y - robot_pose_.y(); + double delta_orient = g2o::normalize_theta( tf2::getYaw(global_goal.pose.orientation) - robot_pose_.theta() ); + if(fabs(std::sqrt(dx*dx+dy*dy)) < cfg_.goal_tolerance.xy_goal_tolerance + && fabs(delta_orient) < cfg_.goal_tolerance.yaw_goal_tolerance + && (!cfg_.goal_tolerance.complete_global_plan || via_points_.size() == 0) + && (base_local_planner::stopped(base_odom, cfg_.goal_tolerance.theta_stopped_vel, cfg_.goal_tolerance.trans_stopped_vel) + || cfg_.goal_tolerance.free_goal_vel)) + { + goal_reached_ = true; + return mbf_msgs::ExePathResult::SUCCESS; + } + + // check if we should enter any backup mode and apply settings + configureBackupModes(transformed_plan, goal_idx); + + + // Return false if the transformed global plan is empty + if (transformed_plan.empty()) + { + ROS_WARN("Transformed plan is empty. Cannot determine a local plan."); + message = "Transformed plan is empty"; + return mbf_msgs::ExePathResult::INVALID_PATH; + } + + // Get current goal point (last point of the transformed plan) + robot_goal_.x() = transformed_plan.back().pose.position.x; + robot_goal_.y() = transformed_plan.back().pose.position.y; + // Overwrite goal orientation if needed + if (cfg_.trajectory.global_plan_overwrite_orientation) + { + robot_goal_.theta() = estimateLocalGoalOrientation(global_plan_, transformed_plan.back(), goal_idx, tf_plan_to_global); + // overwrite/update goal orientation of the transformed plan with the actual goal (enable using the plan as initialization) + tf2::Quaternion q; + q.setRPY(0, 0, robot_goal_.theta()); + tf2::convert(q, transformed_plan.back().pose.orientation); + } + else + { + robot_goal_.theta() = tf2::getYaw(transformed_plan.back().pose.orientation); + } + + // overwrite/update start of the transformed plan with the actual robot position (allows using the plan as initial trajectory) + if (transformed_plan.size()==1) // plan only contains the goal + { + transformed_plan.insert(transformed_plan.begin(), geometry_msgs::PoseStamped()); // insert start (not yet initialized) + } + transformed_plan.front() = robot_pose; // update start + + // clear currently existing obstacles + obstacles_.clear(); + + // Update obstacle container with costmap information or polygons provided by a costmap_converter plugin + if (costmap_converter_) + updateObstacleContainerWithCostmapConverter(); + else + updateObstacleContainerWithCostmap(); + + // also consider custom obstacles (must be called after other updates, since the container is not cleared) + updateObstacleContainerWithCustomObstacles(); + + + // Do not allow config changes during the following optimization step + boost::mutex::scoped_lock cfg_lock(cfg_.configMutex()); + + // Now perform the actual planning +// bool success = planner_->plan(robot_pose_, robot_goal_, robot_vel_, cfg_.goal_tolerance.free_goal_vel); // straight line init + bool success = planner_->plan(transformed_plan, &robot_vel_, cfg_.goal_tolerance.free_goal_vel); + if (!success) + { + planner_->clearPlanner(); // force reinitialization for next time + ROS_WARN("teb_local_planner was not able to obtain a local plan for the current setting."); + + ++no_infeasible_plans_; // increase number of infeasible solutions in a row + time_last_infeasible_plan_ = ros::Time::now(); + last_cmd_ = cmd_vel.twist; + message = "teb_local_planner was not able to obtain a local plan"; + return mbf_msgs::ExePathResult::NO_VALID_CMD; + } + + // Check for divergence + if (planner_->hasDiverged()) + { + cmd_vel.twist.linear.x = cmd_vel.twist.linear.y = cmd_vel.twist.angular.z = 0; + + // Reset everything to start again with the initialization of new trajectories. + planner_->clearPlanner(); + ROS_WARN_THROTTLE(1.0, "TebLocalPlannerROS: the trajectory has diverged. Resetting planner..."); + + ++no_infeasible_plans_; // increase number of infeasible solutions in a row + time_last_infeasible_plan_ = ros::Time::now(); + last_cmd_ = cmd_vel.twist; + return mbf_msgs::ExePathResult::NO_VALID_CMD; + } + + // Check feasibility (but within the first few states only) + if(cfg_.robot.is_footprint_dynamic) + { + // Update footprint of the robot and minimum and maximum distance from the center of the robot to its footprint vertices. + footprint_spec_ = costmap_ros_->getRobotFootprint(); + costmap_2d::calculateMinAndMaxDistances(footprint_spec_, robot_inscribed_radius_, robot_circumscribed_radius); + } + + bool feasible = planner_->isTrajectoryFeasible(costmap_model_.get(), footprint_spec_, robot_inscribed_radius_, robot_circumscribed_radius, cfg_.trajectory.feasibility_check_no_poses, cfg_.trajectory.feasibility_check_lookahead_distance); + if (!feasible) + { + cmd_vel.twist.linear.x = cmd_vel.twist.linear.y = cmd_vel.twist.angular.z = 0; + + // now we reset everything to start again with the initialization of new trajectories. + planner_->clearPlanner(); + ROS_WARN("TebLocalPlannerROS: trajectory is not feasible. Resetting planner..."); + + ++no_infeasible_plans_; // increase number of infeasible solutions in a row + time_last_infeasible_plan_ = ros::Time::now(); + last_cmd_ = cmd_vel.twist; + message = "teb_local_planner trajectory is not feasible"; + return mbf_msgs::ExePathResult::NO_VALID_CMD; + } + + // Get the velocity command for this sampling interval + if (!planner_->getVelocityCommand(cmd_vel.twist.linear.x, cmd_vel.twist.linear.y, cmd_vel.twist.angular.z, cfg_.trajectory.control_look_ahead_poses)) + + { + planner_->clearPlanner(); + ROS_WARN("TebLocalPlannerROS: velocity command invalid. Resetting planner..."); + ++no_infeasible_plans_; // increase number of infeasible solutions in a row + time_last_infeasible_plan_ = ros::Time::now(); + last_cmd_ = cmd_vel.twist; + message = "teb_local_planner velocity command invalid"; + return mbf_msgs::ExePathResult::NO_VALID_CMD; + } + + // Saturate velocity, if the optimization results violates the constraints (could be possible due to soft constraints). + saturateVelocity(cmd_vel.twist.linear.x, cmd_vel.twist.linear.y, cmd_vel.twist.angular.z, + cfg_.robot.max_vel_x, cfg_.robot.max_vel_y, cfg_.robot.max_vel_trans, cfg_.robot.max_vel_theta, + cfg_.robot.max_vel_x_backwards); + + // convert rot-vel to steering angle if desired (carlike robot). + // The min_turning_radius is allowed to be slighly smaller since it is a soft-constraint + // and opposed to the other constraints not affected by penalty_epsilon. The user might add a safety margin to the parameter itself. + if (cfg_.robot.cmd_angle_instead_rotvel) + { + cmd_vel.twist.angular.z = convertTransRotVelToSteeringAngle(cmd_vel.twist.linear.x, cmd_vel.twist.angular.z, + cfg_.robot.wheelbase, 0.95*cfg_.robot.min_turning_radius); + if (!std::isfinite(cmd_vel.twist.angular.z)) + { + cmd_vel.twist.linear.x = cmd_vel.twist.linear.y = cmd_vel.twist.angular.z = 0; + last_cmd_ = cmd_vel.twist; + planner_->clearPlanner(); + ROS_WARN("TebLocalPlannerROS: Resulting steering angle is not finite. Resetting planner..."); + ++no_infeasible_plans_; // increase number of infeasible solutions in a row + time_last_infeasible_plan_ = ros::Time::now(); + message = "teb_local_planner steering angle is not finite"; + return mbf_msgs::ExePathResult::NO_VALID_CMD; + } + } + + // a feasible solution should be found, reset counter + no_infeasible_plans_ = 0; + + // store last command (for recovery analysis etc.) + last_cmd_ = cmd_vel.twist; + + // Now visualize everything + planner_->visualize(); + visualization_->publishObstacles(obstacles_, costmap_->getResolution()); + visualization_->publishViaPoints(via_points_); + visualization_->publishGlobalPlan(global_plan_); + return mbf_msgs::ExePathResult::SUCCESS; +} + + +bool TebLocalPlannerROS::isGoalReached() +{ + if (goal_reached_) + { + ROS_INFO("GOAL Reached!"); + planner_->clearPlanner(); + return true; + } + return false; +} + + + +void TebLocalPlannerROS::updateObstacleContainerWithCostmap() +{ + // Add costmap obstacles if desired + if (cfg_.obstacles.include_costmap_obstacles) + { + Eigen::Vector2d robot_orient = robot_pose_.orientationUnitVec(); + + for (unsigned int i=0; igetSizeInCellsX()-1; ++i) + { + for (unsigned int j=0; jgetSizeInCellsY()-1; ++j) + { + if (costmap_->getCost(i,j) == costmap_2d::LETHAL_OBSTACLE) + { + Eigen::Vector2d obs; + costmap_->mapToWorld(i,j,obs.coeffRef(0), obs.coeffRef(1)); + + // check if obstacle is interesting (e.g. not far behind the robot) + Eigen::Vector2d obs_dir = obs-robot_pose_.position(); + if ( obs_dir.dot(robot_orient) < 0 && obs_dir.norm() > cfg_.obstacles.costmap_obstacles_behind_robot_dist ) + continue; + + obstacles_.push_back(ObstaclePtr(new PointObstacle(obs))); + } + } + } + } +} + +void TebLocalPlannerROS::updateObstacleContainerWithCostmapConverter() +{ + if (!costmap_converter_) + return; + + //Get obstacles from costmap converter + costmap_converter::ObstacleArrayConstPtr obstacles = costmap_converter_->getObstacles(); + if (!obstacles) + return; + + for (std::size_t i=0; iobstacles.size(); ++i) + { + const costmap_converter::ObstacleMsg* obstacle = &obstacles->obstacles.at(i); + const geometry_msgs::Polygon* polygon = &obstacle->polygon; + + if (polygon->points.size()==1 && obstacle->radius > 0) // Circle + { + obstacles_.push_back(ObstaclePtr(new CircularObstacle(polygon->points[0].x, polygon->points[0].y, obstacle->radius))); + } + else if (polygon->points.size()==1) // Point + { + obstacles_.push_back(ObstaclePtr(new PointObstacle(polygon->points[0].x, polygon->points[0].y))); + } + else if (polygon->points.size()==2) // Line + { + obstacles_.push_back(ObstaclePtr(new LineObstacle(polygon->points[0].x, polygon->points[0].y, + polygon->points[1].x, polygon->points[1].y ))); + } + else if (polygon->points.size()>2) // Real polygon + { + PolygonObstacle* polyobst = new PolygonObstacle; + for (std::size_t j=0; jpoints.size(); ++j) + { + polyobst->pushBackVertex(polygon->points[j].x, polygon->points[j].y); + } + polyobst->finalizePolygon(); + obstacles_.push_back(ObstaclePtr(polyobst)); + } + + // Set velocity, if obstacle is moving + if(!obstacles_.empty()) + obstacles_.back()->setCentroidVelocity(obstacles->obstacles[i].velocities, obstacles->obstacles[i].orientation); + } +} + + +void TebLocalPlannerROS::updateObstacleContainerWithCustomObstacles() +{ + // Add custom obstacles obtained via message + boost::mutex::scoped_lock l(custom_obst_mutex_); + + if (!custom_obstacle_msg_.obstacles.empty()) + { + // We only use the global header to specify the obstacle coordinate system instead of individual ones + Eigen::Affine3d obstacle_to_map_eig; + try + { + geometry_msgs::TransformStamped obstacle_to_map = tf_->lookupTransform(global_frame_, ros::Time(0), + custom_obstacle_msg_.header.frame_id, ros::Time(0), + custom_obstacle_msg_.header.frame_id, ros::Duration(cfg_.robot.transform_tolerance)); + obstacle_to_map_eig = tf2::transformToEigen(obstacle_to_map); + } + catch (tf::TransformException ex) + { + ROS_ERROR("%s",ex.what()); + obstacle_to_map_eig.setIdentity(); + } + + for (size_t i=0; i 0 ) // circle + { + Eigen::Vector3d pos( custom_obstacle_msg_.obstacles.at(i).polygon.points.front().x, + custom_obstacle_msg_.obstacles.at(i).polygon.points.front().y, + custom_obstacle_msg_.obstacles.at(i).polygon.points.front().z ); + obstacles_.push_back(ObstaclePtr(new CircularObstacle( (obstacle_to_map_eig * pos).head(2), custom_obstacle_msg_.obstacles.at(i).radius))); + } + else if (custom_obstacle_msg_.obstacles.at(i).polygon.points.size() == 1 ) // point + { + Eigen::Vector3d pos( custom_obstacle_msg_.obstacles.at(i).polygon.points.front().x, + custom_obstacle_msg_.obstacles.at(i).polygon.points.front().y, + custom_obstacle_msg_.obstacles.at(i).polygon.points.front().z ); + obstacles_.push_back(ObstaclePtr(new PointObstacle( (obstacle_to_map_eig * pos).head(2) ))); + } + else if (custom_obstacle_msg_.obstacles.at(i).polygon.points.size() == 2 ) // line + { + Eigen::Vector3d line_start( custom_obstacle_msg_.obstacles.at(i).polygon.points.front().x, + custom_obstacle_msg_.obstacles.at(i).polygon.points.front().y, + custom_obstacle_msg_.obstacles.at(i).polygon.points.front().z ); + Eigen::Vector3d line_end( custom_obstacle_msg_.obstacles.at(i).polygon.points.back().x, + custom_obstacle_msg_.obstacles.at(i).polygon.points.back().y, + custom_obstacle_msg_.obstacles.at(i).polygon.points.back().z ); + obstacles_.push_back(ObstaclePtr(new LineObstacle( (obstacle_to_map_eig * line_start).head(2), + (obstacle_to_map_eig * line_end).head(2) ))); + } + else if (custom_obstacle_msg_.obstacles.at(i).polygon.points.empty()) + { + ROS_WARN("Invalid custom obstacle received. List of polygon vertices is empty. Skipping..."); + continue; + } + else // polygon + { + PolygonObstacle* polyobst = new PolygonObstacle; + for (size_t j=0; jpushBackVertex( (obstacle_to_map_eig * pos).head(2) ); + } + polyobst->finalizePolygon(); + obstacles_.push_back(ObstaclePtr(polyobst)); + } + + // Set velocity, if obstacle is moving + if(!obstacles_.empty()) + obstacles_.back()->setCentroidVelocity(custom_obstacle_msg_.obstacles[i].velocities, custom_obstacle_msg_.obstacles[i].orientation); + } + } +} + +void TebLocalPlannerROS::updateViaPointsContainer(const std::vector& transformed_plan, double min_separation) +{ + via_points_.clear(); + + if (min_separation<=0) + return; + + std::size_t prev_idx = 0; + for (std::size_t i=1; i < transformed_plan.size(); ++i) // skip first one, since we do not need any point before the first min_separation [m] + { + // check separation to the previous via-point inserted + if (distance_points2d( transformed_plan[prev_idx].pose.position, transformed_plan[i].pose.position ) < min_separation) + continue; + + // add via-point + via_points_.push_back( Eigen::Vector2d( transformed_plan[i].pose.position.x, transformed_plan[i].pose.position.y ) ); + prev_idx = i; + } + +} + +Eigen::Vector2d TebLocalPlannerROS::tfPoseToEigenVector2dTransRot(const tf::Pose& tf_vel) +{ + Eigen::Vector2d vel; + vel.coeffRef(0) = std::sqrt( tf_vel.getOrigin().getX() * tf_vel.getOrigin().getX() + tf_vel.getOrigin().getY() * tf_vel.getOrigin().getY() ); + vel.coeffRef(1) = tf::getYaw(tf_vel.getRotation()); + return vel; +} + + +bool TebLocalPlannerROS::pruneGlobalPlan(const tf2_ros::Buffer& tf, const geometry_msgs::PoseStamped& global_pose, std::vector& global_plan, double dist_behind_robot) +{ + if (global_plan.empty()) + return true; + + try + { + // transform robot pose into the plan frame (we do not wait here, since pruning not crucial, if missed a few times) + geometry_msgs::TransformStamped global_to_plan_transform = tf.lookupTransform(global_plan.front().header.frame_id, global_pose.header.frame_id, ros::Time(0)); + geometry_msgs::PoseStamped robot; + tf2::doTransform(global_pose, robot, global_to_plan_transform); + + double dist_thresh_sq = dist_behind_robot*dist_behind_robot; + + // iterate plan until a pose close the robot is found + std::vector::iterator it = global_plan.begin(); + std::vector::iterator erase_end = it; + while (it != global_plan.end()) + { + double dx = robot.pose.position.x - it->pose.position.x; + double dy = robot.pose.position.y - it->pose.position.y; + double dist_sq = dx * dx + dy * dy; + if (dist_sq < dist_thresh_sq) + { + erase_end = it; + break; + } + ++it; + } + if (erase_end == global_plan.end()) + return false; + + if (erase_end != global_plan.begin()) + global_plan.erase(global_plan.begin(), erase_end); + } + catch (const tf::TransformException& ex) + { + ROS_DEBUG("Cannot prune path since no transform is available: %s\n", ex.what()); + return false; + } + return true; +} + + +bool TebLocalPlannerROS::transformGlobalPlan(const tf2_ros::Buffer& tf, const std::vector& global_plan, + const geometry_msgs::PoseStamped& global_pose, const costmap_2d::Costmap2D& costmap, const std::string& global_frame, double max_plan_length, + std::vector& transformed_plan, int* current_goal_idx, geometry_msgs::TransformStamped* tf_plan_to_global) const +{ + // this method is a slightly modified version of base_local_planner/goal_functions.h + + const geometry_msgs::PoseStamped& plan_pose = global_plan[0]; + + transformed_plan.clear(); + + try + { + if (global_plan.empty()) + { + ROS_ERROR("Received plan with zero length"); + *current_goal_idx = 0; + return false; + } + + // get plan_to_global_transform from plan frame to global_frame + geometry_msgs::TransformStamped plan_to_global_transform = tf.lookupTransform(global_frame, ros::Time(), plan_pose.header.frame_id, plan_pose.header.stamp, + plan_pose.header.frame_id, ros::Duration(cfg_.robot.transform_tolerance)); + + //let's get the pose of the robot in the frame of the plan + geometry_msgs::PoseStamped robot_pose; + tf.transform(global_pose, robot_pose, plan_pose.header.frame_id); + + //we'll discard points on the plan that are outside the local costmap + double dist_threshold = std::max(costmap.getSizeInCellsX() * costmap.getResolution() / 2.0, + costmap.getSizeInCellsY() * costmap.getResolution() / 2.0); + dist_threshold *= 0.85; // just consider 85% of the costmap size to better incorporate point obstacle that are + // located on the border of the local costmap + + + int i = 0; + double sq_dist_threshold = dist_threshold * dist_threshold; + double sq_dist = 1e10; + + //we need to loop to a point on the plan that is within a certain distance of the robot + bool robot_reached = false; + for(int j=0; j < (int)global_plan.size(); ++j) + { + double x_diff = robot_pose.pose.position.x - global_plan[j].pose.position.x; + double y_diff = robot_pose.pose.position.y - global_plan[j].pose.position.y; + double new_sq_dist = x_diff * x_diff + y_diff * y_diff; + + if (robot_reached && new_sq_dist > sq_dist) + break; + + if (new_sq_dist < sq_dist) // find closest distance + { + sq_dist = new_sq_dist; + i = j; + if (sq_dist < 0.05) // 2.5 cm to the robot; take the immediate local minima; if it's not the global + robot_reached = true; // minima, probably means that there's a loop in the path, and so we prefer this + } + } + + geometry_msgs::PoseStamped newer_pose; + + double plan_length = 0; // check cumulative Euclidean distance along the plan + + //now we'll transform until points are outside of our distance threshold + while(i < (int)global_plan.size() && sq_dist <= sq_dist_threshold && (max_plan_length<=0 || plan_length <= max_plan_length)) + { + const geometry_msgs::PoseStamped& pose = global_plan[i]; + tf2::doTransform(pose, newer_pose, plan_to_global_transform); + + transformed_plan.push_back(newer_pose); + + double x_diff = robot_pose.pose.position.x - global_plan[i].pose.position.x; + double y_diff = robot_pose.pose.position.y - global_plan[i].pose.position.y; + sq_dist = x_diff * x_diff + y_diff * y_diff; + + // caclulate distance to previous pose + if (i>0 && max_plan_length>0) + plan_length += distance_points2d(global_plan[i-1].pose.position, global_plan[i].pose.position); + + ++i; + } + + // if we are really close to the goal (>0) + // the resulting transformed plan can be empty. In that case we explicitly inject the global goal. + if (transformed_plan.empty()) + { + tf2::doTransform(global_plan.back(), newer_pose, plan_to_global_transform); + + transformed_plan.push_back(newer_pose); + + // Return the index of the current goal point (inside the distance threshold) + if (current_goal_idx) *current_goal_idx = int(global_plan.size())-1; + } + else + { + // Return the index of the current goal point (inside the distance threshold) + if (current_goal_idx) *current_goal_idx = i-1; // subtract 1, since i was increased once before leaving the loop + } + + // Return the transformation from the global plan to the global planning frame if desired + if (tf_plan_to_global) *tf_plan_to_global = plan_to_global_transform; + } + catch(tf::LookupException& ex) + { + ROS_ERROR("No Transform available Error: %s\n", ex.what()); + return false; + } + catch(tf::ConnectivityException& ex) + { + ROS_ERROR("Connectivity Error: %s\n", ex.what()); + return false; + } + catch(tf::ExtrapolationException& ex) + { + ROS_ERROR("Extrapolation Error: %s\n", ex.what()); + if (global_plan.size() > 0) + ROS_ERROR("Global Frame: %s Plan Frame size %d: %s\n", global_frame.c_str(), (unsigned int)global_plan.size(), global_plan[0].header.frame_id.c_str()); + + return false; + } + + return true; +} + + + + +double TebLocalPlannerROS::estimateLocalGoalOrientation(const std::vector& global_plan, const geometry_msgs::PoseStamped& local_goal, + int current_goal_idx, const geometry_msgs::TransformStamped& tf_plan_to_global, int moving_average_length) const +{ + int n = (int)global_plan.size(); + + // check if we are near the global goal already + if (current_goal_idx > n-moving_average_length-2) + { + if (current_goal_idx >= n-1) // we've exactly reached the goal + { + return tf2::getYaw(local_goal.pose.orientation); + } + else + { + tf2::Quaternion global_orientation; + tf2::convert(global_plan.back().pose.orientation, global_orientation); + tf2::Quaternion rotation; + tf2::convert(tf_plan_to_global.transform.rotation, rotation); + // TODO(roesmann): avoid conversion to tf2::Quaternion + return tf2::getYaw(rotation * global_orientation); + } + } + + // reduce number of poses taken into account if the desired number of poses is not available + moving_average_length = std::min(moving_average_length, n-current_goal_idx-1 ); // maybe redundant, since we have checked the vicinity of the goal before + + std::vector candidates; + geometry_msgs::PoseStamped tf_pose_k = local_goal; + geometry_msgs::PoseStamped tf_pose_kp1; + + int range_end = current_goal_idx + moving_average_length; + for (int i = current_goal_idx; i < range_end; ++i) + { + // Transform pose of the global plan to the planning frame + tf2::doTransform(global_plan.at(i+1), tf_pose_kp1, tf_plan_to_global); + + // calculate yaw angle + candidates.push_back( std::atan2(tf_pose_kp1.pose.position.y - tf_pose_k.pose.position.y, + tf_pose_kp1.pose.position.x - tf_pose_k.pose.position.x ) ); + + if (i max_vel_x) + ratio_x = max_vel_x / vx; + + // limit strafing velocity + if (vy > max_vel_y || vy < -max_vel_y) + ratio_y = std::abs(max_vel_y / vy); + + // Limit angular velocity + if (omega > max_vel_theta || omega < -max_vel_theta) + ratio_omega = std::abs(max_vel_theta / omega); + + // Limit backwards velocity + if (max_vel_x_backwards<=0) + { + ROS_WARN_ONCE("TebLocalPlannerROS(): Do not choose max_vel_x_backwards to be <=0. Disable backwards driving by increasing the optimization weight for penalyzing backwards driving."); + } + else if (vx < -max_vel_x_backwards) + ratio_x = - max_vel_x_backwards / vx; + + if (cfg_.robot.use_proportional_saturation) + { + double ratio = std::min(std::min(ratio_x, ratio_y), ratio_omega); + vx *= ratio; + vy *= ratio; + omega *= ratio; + } + else + { + vx *= ratio_x; + vy *= ratio_y; + omega *= ratio_omega; + } + + double vel_linear = std::hypot(vx, vy); + if (vel_linear > max_vel_trans) + { + double max_vel_trans_ratio = max_vel_trans / vel_linear; + vx *= max_vel_trans_ratio; + vy *= max_vel_trans_ratio; + } +} + + +double TebLocalPlannerROS::convertTransRotVelToSteeringAngle(double v, double omega, double wheelbase, double min_turning_radius) const +{ + if (omega==0 || v==0) + return 0; + + double radius = v/omega; + + if (fabs(radius) < min_turning_radius) + radius = double(g2o::sign(radius)) * min_turning_radius; + + return std::atan(wheelbase / radius); +} + + +void TebLocalPlannerROS::validateFootprints(double opt_inscribed_radius, double costmap_inscribed_radius, double min_obst_dist) +{ + ROS_WARN_COND(opt_inscribed_radius + min_obst_dist < costmap_inscribed_radius, + "The inscribed radius of the footprint specified for TEB optimization (%f) + min_obstacle_dist (%f) are smaller " + "than the inscribed radius of the robot's footprint in the costmap parameters (%f, including 'footprint_padding'). " + "Infeasible optimziation results might occur frequently!", opt_inscribed_radius, min_obst_dist, costmap_inscribed_radius); +} + + + +void TebLocalPlannerROS::configureBackupModes(std::vector& transformed_plan, int& goal_idx) +{ + ros::Time current_time = ros::Time::now(); + + // reduced horizon backup mode + if (cfg_.recovery.shrink_horizon_backup && + goal_idx < (int)transformed_plan.size()-1 && // we do not reduce if the goal is already selected (because the orientation might change -> can introduce oscillations) + (no_infeasible_plans_>0 || (current_time - time_last_infeasible_plan_).toSec() < cfg_.recovery.shrink_horizon_min_duration )) // keep short horizon for at least a few seconds + { + ROS_INFO_COND(no_infeasible_plans_==1, "Activating reduced horizon backup mode for at least %.2f sec (infeasible trajectory detected).", cfg_.recovery.shrink_horizon_min_duration); + + + // Shorten horizon if requested + // reduce to 50 percent: + int horizon_reduction = goal_idx/2; + + if (no_infeasible_plans_ > 9) + { + ROS_INFO_COND(no_infeasible_plans_==10, "Infeasible trajectory detected 10 times in a row: further reducing horizon..."); + horizon_reduction /= 2; + } + + // we have a small overhead here, since we already transformed 50% more of the trajectory. + // But that's ok for now, since we do not need to make transformGlobalPlan more complex + // and a reduced horizon should occur just rarely. + int new_goal_idx_transformed_plan = int(transformed_plan.size()) - horizon_reduction - 1; + goal_idx -= horizon_reduction; + if (new_goal_idx_transformed_plan>0 && goal_idx >= 0) + transformed_plan.erase(transformed_plan.begin()+new_goal_idx_transformed_plan, transformed_plan.end()); + else + goal_idx += horizon_reduction; // this should not happen, but safety first ;-) + } + + + // detect and resolve oscillations + if (cfg_.recovery.oscillation_recovery) + { + double max_vel_theta; + double max_vel_current = last_cmd_.linear.x >= 0 ? cfg_.robot.max_vel_x : cfg_.robot.max_vel_x_backwards; + if (cfg_.robot.min_turning_radius!=0 && max_vel_current>0) + max_vel_theta = std::max( max_vel_current/std::abs(cfg_.robot.min_turning_radius), cfg_.robot.max_vel_theta ); + else + max_vel_theta = cfg_.robot.max_vel_theta; + + failure_detector_.update(last_cmd_, cfg_.robot.max_vel_x, cfg_.robot.max_vel_x_backwards, max_vel_theta, + cfg_.recovery.oscillation_v_eps, cfg_.recovery.oscillation_omega_eps); + + bool oscillating = failure_detector_.isOscillating(); + bool recently_oscillated = (ros::Time::now()-time_last_oscillation_).toSec() < cfg_.recovery.oscillation_recovery_min_duration; // check if we have already detected an oscillation recently + + if (oscillating) + { + if (!recently_oscillated) + { + // save current turning direction + if (robot_vel_.angular.z > 0) + last_preferred_rotdir_ = RotType::left; + else + last_preferred_rotdir_ = RotType::right; + ROS_WARN("TebLocalPlannerROS: possible oscillation (of the robot or its local plan) detected. Activating recovery strategy (prefer current turning direction during optimization)."); + } + time_last_oscillation_ = ros::Time::now(); + planner_->setPreferredTurningDir(last_preferred_rotdir_); + } + else if (!recently_oscillated && last_preferred_rotdir_ != RotType::none) // clear recovery behavior + { + last_preferred_rotdir_ = RotType::none; + planner_->setPreferredTurningDir(last_preferred_rotdir_); + ROS_INFO("TebLocalPlannerROS: oscillation recovery disabled/expired."); + } + } + +} + +void TebLocalPlannerROS::customObstacleCB(const costmap_converter::ObstacleArrayMsg::ConstPtr& obst_msg) +{ + boost::mutex::scoped_lock l(custom_obst_mutex_); + custom_obstacle_msg_ = *obst_msg; +} + +void TebLocalPlannerROS::customViaPointsCB(const nav_msgs::Path::ConstPtr& via_points_msg) +{ + ROS_INFO_ONCE("Via-points received. This message is printed once."); + if (cfg_.trajectory.global_plan_viapoint_sep > 0) + { + ROS_WARN("Via-points are already obtained from the global plan (global_plan_viapoint_sep>0)." + "Ignoring custom via-points."); + custom_via_points_active_ = false; + return; + } + + boost::mutex::scoped_lock l(via_point_mutex_); + via_points_.clear(); + for (const geometry_msgs::PoseStamped& pose : via_points_msg->poses) + { + via_points_.emplace_back(pose.pose.position.x, pose.pose.position.y); + } + custom_via_points_active_ = !via_points_.empty(); +} + +RobotFootprintModelPtr TebLocalPlannerROS::getRobotFootprintFromParamServer(const ros::NodeHandle& nh, const TebConfig& config) +{ + std::string model_name; + if (!nh.getParam("footprint_model/type", model_name)) + { + ROS_INFO("No robot footprint model specified for trajectory optimization. Using point-shaped model."); + return boost::make_shared(); + } + + // point + if (model_name.compare("point") == 0) + { + ROS_INFO("Footprint model 'point' loaded for trajectory optimization."); + return boost::make_shared(config.obstacles.min_obstacle_dist); + } + + // circular + if (model_name.compare("circular") == 0) + { + // get radius + double radius; + if (!nh.getParam("footprint_model/radius", radius)) + { + ROS_ERROR_STREAM("Footprint model 'circular' cannot be loaded for trajectory optimization, since param '" << nh.getNamespace() + << "/footprint_model/radius' does not exist. Using point-model instead."); + return boost::make_shared(); + } + ROS_INFO_STREAM("Footprint model 'circular' (radius: " << radius <<"m) loaded for trajectory optimization."); + return boost::make_shared(radius); + } + + // line + if (model_name.compare("line") == 0) + { + // check parameters + if (!nh.hasParam("footprint_model/line_start") || !nh.hasParam("footprint_model/line_end")) + { + ROS_ERROR_STREAM("Footprint model 'line' cannot be loaded for trajectory optimization, since param '" << nh.getNamespace() + << "/footprint_model/line_start' and/or '.../line_end' do not exist. Using point-model instead."); + return boost::make_shared(); + } + // get line coordinates + std::vector line_start, line_end; + nh.getParam("footprint_model/line_start", line_start); + nh.getParam("footprint_model/line_end", line_end); + if (line_start.size() != 2 || line_end.size() != 2) + { + ROS_ERROR_STREAM("Footprint model 'line' cannot be loaded for trajectory optimization, since param '" << nh.getNamespace() + << "/footprint_model/line_start' and/or '.../line_end' do not contain x and y coordinates (2D). Using point-model instead."); + return boost::make_shared(); + } + + ROS_INFO_STREAM("Footprint model 'line' (line_start: [" << line_start[0] << "," << line_start[1] <<"]m, line_end: [" + << line_end[0] << "," << line_end[1] << "]m) loaded for trajectory optimization."); + return boost::make_shared(Eigen::Map(line_start.data()), Eigen::Map(line_end.data()), config.obstacles.min_obstacle_dist); + } + + // two circles + if (model_name.compare("two_circles") == 0) + { + // check parameters + if (!nh.hasParam("footprint_model/front_offset") || !nh.hasParam("footprint_model/front_radius") + || !nh.hasParam("footprint_model/rear_offset") || !nh.hasParam("footprint_model/rear_radius")) + { + ROS_ERROR_STREAM("Footprint model 'two_circles' cannot be loaded for trajectory optimization, since params '" << nh.getNamespace() + << "/footprint_model/front_offset', '.../front_radius', '.../rear_offset' and '.../rear_radius' do not exist. Using point-model instead."); + return boost::make_shared(); + } + double front_offset, front_radius, rear_offset, rear_radius; + nh.getParam("footprint_model/front_offset", front_offset); + nh.getParam("footprint_model/front_radius", front_radius); + nh.getParam("footprint_model/rear_offset", rear_offset); + nh.getParam("footprint_model/rear_radius", rear_radius); + ROS_INFO_STREAM("Footprint model 'two_circles' (front_offset: " << front_offset <<"m, front_radius: " << front_radius + << "m, rear_offset: " << rear_offset << "m, rear_radius: " << rear_radius << "m) loaded for trajectory optimization."); + return boost::make_shared(front_offset, front_radius, rear_offset, rear_radius); + } + + // polygon + if (model_name.compare("polygon") == 0) + { + + // check parameters + XmlRpc::XmlRpcValue footprint_xmlrpc; + if (!nh.getParam("footprint_model/vertices", footprint_xmlrpc) ) + { + ROS_ERROR_STREAM("Footprint model 'polygon' cannot be loaded for trajectory optimization, since param '" << nh.getNamespace() + << "/footprint_model/vertices' does not exist. Using point-model instead."); + return boost::make_shared(); + } + // get vertices + if (footprint_xmlrpc.getType() == XmlRpc::XmlRpcValue::TypeArray) + { + try + { + Point2dContainer polygon = makeFootprintFromXMLRPC(footprint_xmlrpc, "/footprint_model/vertices"); + ROS_INFO_STREAM("Footprint model 'polygon' loaded for trajectory optimization."); + return boost::make_shared(polygon); + } + catch(const std::exception& ex) + { + ROS_ERROR_STREAM("Footprint model 'polygon' cannot be loaded for trajectory optimization: " << ex.what() << ". Using point-model instead."); + return boost::make_shared(); + } + } + else + { + ROS_ERROR_STREAM("Footprint model 'polygon' cannot be loaded for trajectory optimization, since param '" << nh.getNamespace() + << "/footprint_model/vertices' does not define an array of coordinates. Using point-model instead."); + return boost::make_shared(); + } + + } + + // otherwise + ROS_WARN_STREAM("Unknown robot footprint model specified with parameter '" << nh.getNamespace() << "/footprint_model/type'. Using point model instead."); + return boost::make_shared(); +} + + + + +Point2dContainer TebLocalPlannerROS::makeFootprintFromXMLRPC(XmlRpc::XmlRpcValue& footprint_xmlrpc, const std::string& full_param_name) +{ + // Make sure we have an array of at least 3 elements. + if (footprint_xmlrpc.getType() != XmlRpc::XmlRpcValue::TypeArray || + footprint_xmlrpc.size() < 3) + { + ROS_FATAL("The footprint must be specified as list of lists on the parameter server, %s was specified as %s", + full_param_name.c_str(), std::string(footprint_xmlrpc).c_str()); + throw std::runtime_error("The footprint must be specified as list of lists on the parameter server with at least " + "3 points eg: [[x1, y1], [x2, y2], ..., [xn, yn]]"); + } + + Point2dContainer footprint; + Eigen::Vector2d pt; + + for (int i = 0; i < footprint_xmlrpc.size(); ++i) + { + // Make sure each element of the list is an array of size 2. (x and y coordinates) + XmlRpc::XmlRpcValue point = footprint_xmlrpc[ i ]; + if (point.getType() != XmlRpc::XmlRpcValue::TypeArray || + point.size() != 2) + { + ROS_FATAL("The footprint (parameter %s) must be specified as list of lists on the parameter server eg: " + "[[x1, y1], [x2, y2], ..., [xn, yn]], but this spec is not of that form.", + full_param_name.c_str()); + throw std::runtime_error("The footprint must be specified as list of lists on the parameter server eg: " + "[[x1, y1], [x2, y2], ..., [xn, yn]], but this spec is not of that form"); + } + + pt.x() = getNumberFromXMLRPC(point[ 0 ], full_param_name); + pt.y() = getNumberFromXMLRPC(point[ 1 ], full_param_name); + + footprint.push_back(pt); + } + return footprint; +} + +double TebLocalPlannerROS::getNumberFromXMLRPC(XmlRpc::XmlRpcValue& value, const std::string& full_param_name) +{ + // Make sure that the value we're looking at is either a double or an int. + if (value.getType() != XmlRpc::XmlRpcValue::TypeInt && + value.getType() != XmlRpc::XmlRpcValue::TypeDouble) + { + std::string& value_string = value; + ROS_FATAL("Values in the footprint specification (param %s) must be numbers. Found value %s.", + full_param_name.c_str(), value_string.c_str()); + throw std::runtime_error("Values in the footprint specification must be numbers"); + } + return value.getType() == XmlRpc::XmlRpcValue::TypeInt ? (int)(value) : (double)(value); +} + +} // end namespace teb_local_planner + + diff --git a/navigations/teb_local_planner/src/test_optim_node.cpp b/navigations/teb_local_planner/src/test_optim_node.cpp new file mode 100755 index 0000000..9b60a9e --- /dev/null +++ b/navigations/teb_local_planner/src/test_optim_node.cpp @@ -0,0 +1,325 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2017. + * TU Dortmund - Institute of Control Theory and Systems Engineering. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the institute nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: Christoph Rösmann + *********************************************************************/ + +#include + +#include +#include + +#include +#include + + +using namespace teb_local_planner; // it is ok here to import everything for testing purposes + +// ============= Global Variables ================ +// Ok global variables are bad, but here we only have a simple testing node. +PlannerInterfacePtr planner; +TebVisualizationPtr visual; +std::vector obst_vector; +ViaPointContainer via_points; +TebConfig config; +boost::shared_ptr< dynamic_reconfigure::Server > dynamic_recfg; +ros::Subscriber custom_obst_sub; +ros::Subscriber via_points_sub; +ros::Subscriber clicked_points_sub; +std::vector obst_vel_subs; +unsigned int no_fixed_obstacles; + +// =========== Function declarations ============= +void CB_mainCycle(const ros::TimerEvent& e); +void CB_publishCycle(const ros::TimerEvent& e); +void CB_reconfigure(TebLocalPlannerReconfigureConfig& reconfig, uint32_t level); +void CB_customObstacle(const costmap_converter::ObstacleArrayMsg::ConstPtr& obst_msg); +void CreateInteractiveMarker(const double& init_x, const double& init_y, unsigned int id, std::string frame, interactive_markers::InteractiveMarkerServer* marker_server, interactive_markers::InteractiveMarkerServer::FeedbackCallback feedback_cb); +void CB_obstacle_marker(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback); +void CB_clicked_points(const geometry_msgs::PointStampedConstPtr& point_msg); +void CB_via_points(const nav_msgs::Path::ConstPtr& via_points_msg); +void CB_setObstacleVelocity(const geometry_msgs::TwistConstPtr& twist_msg, const unsigned int id); + + +// =============== Main function ================= +int main( int argc, char** argv ) +{ + ros::init(argc, argv, "test_optim_node"); + ros::NodeHandle n("~"); + + + // load ros parameters from node handle + config.loadRosParamFromNodeHandle(n); + + ros::Timer cycle_timer = n.createTimer(ros::Duration(0.025), CB_mainCycle); + ros::Timer publish_timer = n.createTimer(ros::Duration(0.1), CB_publishCycle); + + // setup dynamic reconfigure + dynamic_recfg = boost::make_shared< dynamic_reconfigure::Server >(n); + dynamic_reconfigure::Server::CallbackType cb = boost::bind(CB_reconfigure, _1, _2); + dynamic_recfg->setCallback(cb); + + // setup callback for custom obstacles + custom_obst_sub = n.subscribe("obstacles", 1, CB_customObstacle); + + // setup callback for clicked points (in rviz) that are considered as via-points + clicked_points_sub = n.subscribe("/clicked_point", 5, CB_clicked_points); + + // setup callback for via-points (callback overwrites previously set via-points) + via_points_sub = n.subscribe("via_points", 1, CB_via_points); + + // interactive marker server for simulated dynamic obstacles + interactive_markers::InteractiveMarkerServer marker_server("marker_obstacles"); + + obst_vector.push_back( boost::make_shared(-3,1) ); + obst_vector.push_back( boost::make_shared(6,2) ); + obst_vector.push_back( boost::make_shared(0,0.1) ); +// obst_vector.push_back( boost::make_shared(1,1.5,1,-1.5) ); //90 deg +// obst_vector.push_back( boost::make_shared(1,0,-1,0) ); //180 deg +// obst_vector.push_back( boost::make_shared(-1.5,-0.5) ); + + // Dynamic obstacles + Eigen::Vector2d vel (0.1, -0.3); + obst_vector.at(0)->setCentroidVelocity(vel); + vel = Eigen::Vector2d(-0.3, -0.2); + obst_vector.at(1)->setCentroidVelocity(vel); + + /* + PolygonObstacle* polyobst = new PolygonObstacle; + polyobst->pushBackVertex(1, -1); + polyobst->pushBackVertex(0, 1); + polyobst->pushBackVertex(1, 1); + polyobst->pushBackVertex(2, 1); + + polyobst->finalizePolygon(); + obst_vector.emplace_back(polyobst); + */ + + for (unsigned int i=0; i(topic, 1, boost::bind(&CB_setObstacleVelocity, _1, i))); + + //CreateInteractiveMarker(obst_vector.at(i)[0],obst_vector.at(i)[1],i,&marker_server, &CB_obstacle_marker); + // Add interactive markers for all point obstacles + boost::shared_ptr pobst = boost::dynamic_pointer_cast(obst_vector.at(i)); + if (pobst) + { + CreateInteractiveMarker(pobst->x(),pobst->y(),i, config.map_frame, &marker_server, &CB_obstacle_marker); + } + } + marker_server.applyChanges(); + + // Setup visualization + visual = TebVisualizationPtr(new TebVisualization(n, config)); + + // Setup robot shape model + RobotFootprintModelPtr robot_model = TebLocalPlannerROS::getRobotFootprintFromParamServer(n, config); + + // Setup planner (homotopy class planning or just the local teb planner) + if (config.hcp.enable_homotopy_class_planning) + planner = PlannerInterfacePtr(new HomotopyClassPlanner(config, &obst_vector, robot_model, visual, &via_points)); + else + planner = PlannerInterfacePtr(new TebOptimalPlanner(config, &obst_vector, robot_model, visual, &via_points)); + + + no_fixed_obstacles = obst_vector.size(); + ros::spin(); + + return 0; +} + +// Planning loop +void CB_mainCycle(const ros::TimerEvent& e) +{ + planner->plan(PoseSE2(-4,0,0), PoseSE2(4,0,0)); // hardcoded start and goal for testing purposes +} + +// Visualization loop +void CB_publishCycle(const ros::TimerEvent& e) +{ + planner->visualize(); + visual->publishObstacles(obst_vector); + visual->publishViaPoints(via_points); +} + +void CB_reconfigure(TebLocalPlannerReconfigureConfig& reconfig, uint32_t level) +{ + config.reconfigure(reconfig); +} + +void CreateInteractiveMarker(const double& init_x, const double& init_y, unsigned int id, std::string frame, interactive_markers::InteractiveMarkerServer* marker_server, interactive_markers::InteractiveMarkerServer::FeedbackCallback feedback_cb) +{ + // create an interactive marker for our server + visualization_msgs::InteractiveMarker i_marker; + i_marker.header.frame_id = frame; + i_marker.header.stamp = ros::Time::now(); + std::ostringstream oss; + //oss << "obstacle" << id; + oss << id; + i_marker.name = oss.str(); + i_marker.description = "Obstacle"; + i_marker.pose.position.x = init_x; + i_marker.pose.position.y = init_y; + i_marker.pose.orientation.w = 1.0f; // make quaternion normalized + + // create a grey box marker + visualization_msgs::Marker box_marker; + box_marker.type = visualization_msgs::Marker::CUBE; + box_marker.id = id; + box_marker.scale.x = 0.2; + box_marker.scale.y = 0.2; + box_marker.scale.z = 0.2; + box_marker.color.r = 0.5; + box_marker.color.g = 0.5; + box_marker.color.b = 0.5; + box_marker.color.a = 1.0; + box_marker.pose.orientation.w = 1.0f; // make quaternion normalized + + // create a non-interactive control which contains the box + visualization_msgs::InteractiveMarkerControl box_control; + box_control.always_visible = true; + box_control.markers.push_back( box_marker ); + + // add the control to the interactive marker + i_marker.controls.push_back( box_control ); + + // create a control which will move the box, rviz will insert 2 arrows + visualization_msgs::InteractiveMarkerControl move_control; + move_control.name = "move_x"; + move_control.orientation.w = 0.707107f; + move_control.orientation.x = 0; + move_control.orientation.y = 0.707107f; + move_control.orientation.z = 0; + move_control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_PLANE; + + + // add the control to the interactive marker + i_marker.controls.push_back(move_control); + + // add the interactive marker to our collection + marker_server->insert(i_marker); + marker_server->setCallback(i_marker.name,feedback_cb); +} + +void CB_obstacle_marker(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) +{ + std::stringstream ss(feedback->marker_name); + unsigned int index; + ss >> index; + + if (index>=no_fixed_obstacles) + return; + PointObstacle* pobst = static_cast(obst_vector.at(index).get()); + pobst->position() = Eigen::Vector2d(feedback->pose.position.x,feedback->pose.position.y); +} + +void CB_customObstacle(const costmap_converter::ObstacleArrayMsg::ConstPtr& obst_msg) +{ + // resize such that the vector contains only the fixed obstacles specified inside the main function + obst_vector.resize(no_fixed_obstacles); + + // Add custom obstacles obtained via message (assume that all obstacles coordiantes are specified in the default planning frame) + for (size_t i = 0; i < obst_msg->obstacles.size(); ++i) + { + if (obst_msg->obstacles.at(i).polygon.points.size() == 1 ) + { + if (obst_msg->obstacles.at(i).radius == 0) + { + obst_vector.push_back(ObstaclePtr(new PointObstacle( obst_msg->obstacles.at(i).polygon.points.front().x, + obst_msg->obstacles.at(i).polygon.points.front().y ))); + } + else + { + obst_vector.push_back(ObstaclePtr(new CircularObstacle( obst_msg->obstacles.at(i).polygon.points.front().x, + obst_msg->obstacles.at(i).polygon.points.front().y, + obst_msg->obstacles.at(i).radius ))); + } + } + else if (obst_msg->obstacles.at(i).polygon.points.empty()) + { + ROS_WARN("Invalid custom obstacle received. List of polygon vertices is empty. Skipping..."); + continue; + } + else + { + PolygonObstacle* polyobst = new PolygonObstacle; + for (size_t j=0; jobstacles.at(i).polygon.points.size(); ++j) + { + polyobst->pushBackVertex( obst_msg->obstacles.at(i).polygon.points[j].x, + obst_msg->obstacles.at(i).polygon.points[j].y ); + } + polyobst->finalizePolygon(); + obst_vector.push_back(ObstaclePtr(polyobst)); + } + + if(!obst_vector.empty()) + obst_vector.back()->setCentroidVelocity(obst_msg->obstacles.at(i).velocities, obst_msg->obstacles.at(i).orientation); + } +} + + +void CB_clicked_points(const geometry_msgs::PointStampedConstPtr& point_msg) +{ + // we assume for simplicity that the fixed frame is already the map/planning frame + // consider clicked points as via-points + via_points.push_back( Eigen::Vector2d(point_msg->point.x, point_msg->point.y) ); + ROS_INFO_STREAM("Via-point (" << point_msg->point.x << "," << point_msg->point.y << ") added."); + if (config.optim.weight_viapoint<=0) + ROS_WARN("Note, via-points are deactivated, since 'weight_via_point' <= 0"); +} + +void CB_via_points(const nav_msgs::Path::ConstPtr& via_points_msg) +{ + ROS_INFO_ONCE("Via-points received. This message is printed once."); + via_points.clear(); + for (const geometry_msgs::PoseStamped& pose : via_points_msg->poses) + { + via_points.emplace_back(pose.pose.position.x, pose.pose.position.y); + } +} + +void CB_setObstacleVelocity(const geometry_msgs::TwistConstPtr& twist_msg, const unsigned int id) +{ + if (id >= obst_vector.size()) + { + ROS_WARN("Cannot set velocity: unknown obstacle id."); + return; + } + + Eigen::Vector2d vel (twist_msg->linear.x, twist_msg->linear.y); + obst_vector.at(id)->setCentroidVelocity(vel); +} diff --git a/navigations/teb_local_planner/src/timed_elastic_band.cpp b/navigations/teb_local_planner/src/timed_elastic_band.cpp new file mode 100755 index 0000000..7a654c6 --- /dev/null +++ b/navigations/teb_local_planner/src/timed_elastic_band.cpp @@ -0,0 +1,634 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2016, + * TU Dortmund - Institute of Control Theory and Systems Engineering. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the institute nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: Christoph Rösmann + *********************************************************************/ + +#include + +#include + +namespace teb_local_planner +{ + +namespace +{ + /** + * estimate the time to move from start to end. + * Assumes constant velocity for the motion. + */ + double estimateDeltaT(const PoseSE2& start, const PoseSE2& end, + double max_vel_x, double max_vel_theta) + { + double dt_constant_motion = 0.1; + if (max_vel_x > 0) { + double trans_dist = (end.position() - start.position()).norm(); + dt_constant_motion = trans_dist / max_vel_x; + } + if (max_vel_theta > 0) { + double rot_dist = std::abs(g2o::normalize_theta(end.theta() - start.theta())); + dt_constant_motion = std::max(dt_constant_motion, rot_dist / max_vel_theta); + } + return dt_constant_motion; + } +} // namespace + + +TimedElasticBand::TimedElasticBand() +{ +} + +TimedElasticBand::~TimedElasticBand() +{ + ROS_DEBUG("Destructor Timed_Elastic_Band..."); + clearTimedElasticBand(); +} + + +void TimedElasticBand::addPose(const PoseSE2& pose, bool fixed) +{ + VertexPose* pose_vertex = new VertexPose(pose, fixed); + pose_vec_.push_back( pose_vertex ); + return; +} + +void TimedElasticBand::addPose(const Eigen::Ref& position, double theta, bool fixed) +{ + VertexPose* pose_vertex = new VertexPose(position, theta, fixed); + pose_vec_.push_back( pose_vertex ); + return; +} + + void TimedElasticBand::addPose(double x, double y, double theta, bool fixed) +{ + VertexPose* pose_vertex = new VertexPose(x, y, theta, fixed); + pose_vec_.push_back( pose_vertex ); + return; +} + +void TimedElasticBand::addTimeDiff(double dt, bool fixed) +{ + ROS_ASSERT_MSG(dt > 0., "Adding a timediff requires a positive dt"); + VertexTimeDiff* timediff_vertex = new VertexTimeDiff(dt, fixed); + timediff_vec_.push_back( timediff_vertex ); + return; +} + + +void TimedElasticBand::addPoseAndTimeDiff(double x, double y, double angle, double dt) +{ + if (sizePoses() != sizeTimeDiffs()) + { + addPose(x,y,angle,false); + addTimeDiff(dt,false); + } + else + ROS_ERROR("Method addPoseAndTimeDiff: Add one single Pose first. Timediff describes the time difference between last conf and given conf"); + return; +} + + + +void TimedElasticBand::addPoseAndTimeDiff(const PoseSE2& pose, double dt) +{ + if (sizePoses() != sizeTimeDiffs()) + { + addPose(pose,false); + addTimeDiff(dt,false); + } else + ROS_ERROR("Method addPoseAndTimeDiff: Add one single Pose first. Timediff describes the time difference between last conf and given conf"); + return; +} + +void TimedElasticBand::addPoseAndTimeDiff(const Eigen::Ref& position, double theta, double dt) +{ + if (sizePoses() != sizeTimeDiffs()) + { + addPose(position, theta,false); + addTimeDiff(dt,false); + } else + ROS_ERROR("Method addPoseAndTimeDiff: Add one single Pose first. Timediff describes the time difference between last conf and given conf"); + return; +} + + +void TimedElasticBand::deletePose(int index) +{ + ROS_ASSERT(index& position, double theta) +{ + VertexPose* pose_vertex = new VertexPose(position, theta); + pose_vec_.insert(pose_vec_.begin()+index, pose_vertex); +} + +void TimedElasticBand::insertPose(int index, double x, double y, double theta) +{ + VertexPose* pose_vertex = new VertexPose(x, y, theta); + pose_vec_.insert(pose_vec_.begin()+index, pose_vertex); +} + +void TimedElasticBand::insertTimeDiff(int index, double dt) +{ + VertexTimeDiff* timediff_vertex = new VertexTimeDiff(dt); + timediff_vec_.insert(timediff_vec_.begin()+index, timediff_vertex); +} + + +void TimedElasticBand::clearTimedElasticBand() +{ + for (PoseSequence::iterator pose_it = pose_vec_.begin(); pose_it != pose_vec_.end(); ++pose_it) + delete *pose_it; + pose_vec_.clear(); + + for (TimeDiffSequence::iterator dt_it = timediff_vec_.begin(); dt_it != timediff_vec_.end(); ++dt_it) + delete *dt_it; + timediff_vec_.clear(); +} + + +void TimedElasticBand::setPoseVertexFixed(int index, bool status) +{ + ROS_ASSERT(indexsetFixed(status); +} + +void TimedElasticBand::setTimeDiffVertexFixed(int index, bool status) +{ + ROS_ASSERT(indexsetFixed(status); +} + + +void TimedElasticBand::autoResize(double dt_ref, double dt_hysteresis, int min_samples, int max_samples, bool fast_mode) +{ + ROS_ASSERT(sizeTimeDiffs() == 0 || sizeTimeDiffs() + 1 == sizePoses()); + /// iterate through all TEB states and add/remove states! + bool modified = true; + + for (int rep = 0; rep < 100 && modified; ++rep) // actually it should be while(), but we want to make sure to not get stuck in some oscillation, hence max 100 repitions. + { + modified = false; + + for(int i=0; i < sizeTimeDiffs(); ++i) // TimeDiff connects Point(i) with Point(i+1) + { + if(TimeDiff(i) > dt_ref + dt_hysteresis && sizeTimeDiffs() 2*dt_ref) + { + double newtime = 0.5*TimeDiff(i); + + TimeDiff(i) = newtime; + insertPose(i+1, PoseSE2::average(Pose(i),Pose(i+1)) ); + insertTimeDiff(i+1,newtime); + + i--; // check the updated pose diff again + modified = true; + } + else + { + if (i < sizeTimeDiffs() - 1) + { + timediffs().at(i+1)->dt()+= timediffs().at(i)->dt() - dt_ref; + } + timediffs().at(i)->dt() = dt_ref; + } + } + else if(TimeDiff(i) < dt_ref - dt_hysteresis && sizeTimeDiffs()>min_samples) // only remove samples if size is larger than min_samples. + { + //ROS_DEBUG("teb_local_planner: autoResize() deleting bandpoint i=%u, #TimeDiffs=%lu",i,sizeTimeDiffs()); + + if(i < ((int)sizeTimeDiffs()-1)) + { + TimeDiff(i+1) = TimeDiff(i+1) + TimeDiff(i); + deleteTimeDiff(i); + deletePose(i+1); + i--; // check the updated pose diff again + } + else + { // last motion should be adjusted, shift time to the interval before + TimeDiff(i-1) += TimeDiff(i); + deleteTimeDiff(i); + deletePose(i); + } + + modified = true; + } + } + if (fast_mode) break; + } +} + + +double TimedElasticBand::getSumOfAllTimeDiffs() const +{ + double time = 0; + + for(TimeDiffSequence::const_iterator dt_it = timediff_vec_.begin(); dt_it != timediff_vec_.end(); ++dt_it) + { + time += (*dt_it)->dt(); + } + return time; +} + +double TimedElasticBand::getSumOfTimeDiffsUpToIdx(int index) const +{ + ROS_ASSERT(index<=timediff_vec_.size()); + + double time = 0; + + for(int i = 0; i < index; ++i) + { + time += timediff_vec_.at(i)->dt(); + } + + return time; +} + +double TimedElasticBand::getAccumulatedDistance() const +{ + double dist = 0; + + for(int i=1; i 0) timestep = diststep / max_vel_x; + + for (unsigned int i=1; i<=no_steps; i++) // start with 1! starting point had index 0 + { + if (i==no_steps && no_steps_d==(float) no_steps) + break; // if last conf (depending on stepsize) is equal to goal conf -> leave loop + addPoseAndTimeDiff(start.x()+i*dx,start.y()+i*dy,orient_init,timestep); + } + + } + + // if number of samples is not larger than min_samples, insert manually + if ( sizePoses() < min_samples-1 ) + { + ROS_DEBUG("initTEBtoGoal(): number of generated samples is less than specified by min_samples. Forcing the insertion of more samples..."); + while (sizePoses() < min_samples-1) // subtract goal point that will be added later + { + // simple strategy: interpolate between the current pose and the goal + PoseSE2 intermediate_pose = PoseSE2::average(BackPose(), goal); + if (max_vel_x > 0) timestep = (intermediate_pose.position()-BackPose().position()).norm()/max_vel_x; + addPoseAndTimeDiff( intermediate_pose, timestep ); // let the optimier correct the timestep (TODO: better initialization + } + } + + // add goal + if (max_vel_x > 0) timestep = (goal.position()-BackPose().position()).norm()/max_vel_x; + addPoseAndTimeDiff(goal,timestep); // add goal point + setPoseVertexFixed(sizePoses()-1,true); // GoalConf is a fixed constraint during optimization + } + else // size!=0 + { + ROS_WARN("Cannot init TEB between given configuration and goal, because TEB vectors are not empty or TEB is already initialized (call this function before adding states yourself)!"); + ROS_WARN("Number of TEB configurations: %d, Number of TEB timediffs: %d",(unsigned int) sizePoses(),(unsigned int) sizeTimeDiffs()); + return false; + } + return true; +} + + +bool TimedElasticBand::initTrajectoryToGoal(const std::vector& plan, double max_vel_x, double max_vel_theta, bool estimate_orient, int min_samples, bool guess_backwards_motion) +{ + + if (!isInit()) + { + PoseSE2 start(plan.front().pose); + PoseSE2 goal(plan.back().pose); + + addPose(start); // add starting point with given orientation + setPoseVertexFixed(0,true); // StartConf is a fixed constraint during optimization + + bool backwards = false; + if (guess_backwards_motion && (goal.position()-start.position()).dot(start.orientationUnitVec()) < 0) // check if the goal is behind the start pose (w.r.t. start orientation) + backwards = true; + // TODO: dt ~ max_vel_x_backwards for backwards motions + + for (int i=1; i<(int)plan.size()-1; ++i) + { + double yaw; + if (estimate_orient) + { + // get yaw from the orientation of the distance vector between pose_{i+1} and pose_{i} + double dx = plan[i+1].pose.position.x - plan[i].pose.position.x; + double dy = plan[i+1].pose.position.y - plan[i].pose.position.y; + yaw = std::atan2(dy,dx); + if (backwards) + yaw = g2o::normalize_theta(yaw+M_PI); + } + else + { + yaw = tf::getYaw(plan[i].pose.orientation); + } + PoseSE2 intermediate_pose(plan[i].pose.position.x, plan[i].pose.position.y, yaw); + double dt = estimateDeltaT(BackPose(), intermediate_pose, max_vel_x, max_vel_theta); + addPoseAndTimeDiff(intermediate_pose, dt); + } + + // if number of samples is not larger than min_samples, insert manually + if ( sizePoses() < min_samples-1 ) + { + ROS_DEBUG("initTEBtoGoal(): number of generated samples is less than specified by min_samples. Forcing the insertion of more samples..."); + while (sizePoses() < min_samples-1) // subtract goal point that will be added later + { + // simple strategy: interpolate between the current pose and the goal + PoseSE2 intermediate_pose = PoseSE2::average(BackPose(), goal); + double dt = estimateDeltaT(BackPose(), intermediate_pose, max_vel_x, max_vel_theta); + addPoseAndTimeDiff( intermediate_pose, dt ); // let the optimier correct the timestep (TODO: better initialization + } + } + + // Now add final state with given orientation + double dt = estimateDeltaT(BackPose(), goal, max_vel_x, max_vel_theta); + addPoseAndTimeDiff(goal, dt); + setPoseVertexFixed(sizePoses()-1,true); // GoalConf is a fixed constraint during optimization + } + else // size!=0 + { + ROS_WARN("Cannot init TEB between given configuration and goal, because TEB vectors are not empty or TEB is already initialized (call this function before adding states yourself)!"); + ROS_WARN("Number of TEB configurations: %d, Number of TEB timediffs: %d", sizePoses(), sizeTimeDiffs()); + return false; + } + + return true; +} + + +int TimedElasticBand::findClosestTrajectoryPose(const Eigen::Ref& ref_point, double* distance, int begin_idx) const +{ + int n = sizePoses(); + if (begin_idx < 0 || begin_idx >= n) + return -1; + + double min_dist_sq = std::numeric_limits::max(); + int min_idx = -1; + + for (int i = begin_idx; i < n; i++) + { + double dist_sq = (ref_point - Pose(i).position()).squaredNorm(); + if (dist_sq < min_dist_sq) + { + min_dist_sq = dist_sq; + min_idx = i; + } + } + + if (distance) + *distance = std::sqrt(min_dist_sq); + + return min_idx; +} + + +int TimedElasticBand::findClosestTrajectoryPose(const Eigen::Ref& ref_line_start, const Eigen::Ref& ref_line_end, double* distance) const +{ + double min_dist = std::numeric_limits::max(); + int min_idx = -1; + + for (int i = 0; i < sizePoses(); i++) + { + Eigen::Vector2d point = Pose(i).position(); + double dist = distance_point_to_segment_2d(point, ref_line_start, ref_line_end); + if (dist < min_dist) + { + min_dist = dist; + min_idx = i; + } + } + + if (distance) + *distance = min_dist; + return min_idx; +} + +int TimedElasticBand::findClosestTrajectoryPose(const Point2dContainer& vertices, double* distance) const +{ + if (vertices.empty()) + return 0; + else if (vertices.size() == 1) + return findClosestTrajectoryPose(vertices.front()); + else if (vertices.size() == 2) + return findClosestTrajectoryPose(vertices.front(), vertices.back()); + + double min_dist = std::numeric_limits::max(); + int min_idx = -1; + + for (int i = 0; i < sizePoses(); i++) + { + Eigen::Vector2d point = Pose(i).position(); + double dist_to_polygon = std::numeric_limits::max(); + for (int j = 0; j < (int) vertices.size()-1; ++j) + { + dist_to_polygon = std::min(dist_to_polygon, distance_point_to_segment_2d(point, vertices[j], vertices[j+1])); + } + dist_to_polygon = std::min(dist_to_polygon, distance_point_to_segment_2d(point, vertices.back(), vertices.front())); + if (dist_to_polygon < min_dist) + { + min_dist = dist_to_polygon; + min_idx = i; + } + } + + if (distance) + *distance = min_dist; + + return min_idx; +} + + +int TimedElasticBand::findClosestTrajectoryPose(const Obstacle& obstacle, double* distance) const +{ + const PointObstacle* pobst = dynamic_cast(&obstacle); + if (pobst) + return findClosestTrajectoryPose(pobst->position(), distance); + + const LineObstacle* lobst = dynamic_cast(&obstacle); + if (lobst) + return findClosestTrajectoryPose(lobst->start(), lobst->end(), distance); + + const PolygonObstacle* polyobst = dynamic_cast(&obstacle); + if (polyobst) + return findClosestTrajectoryPose(polyobst->vertices(), distance); + + return findClosestTrajectoryPose(obstacle.getCentroid(), distance); +} + + +void TimedElasticBand::updateAndPruneTEB(boost::optional new_start, boost::optional new_goal, int min_samples) +{ + // first and simple approach: change only start confs (and virtual start conf for inital velocity) + // TEST if optimizer can handle this "hard" placement + + if (new_start && sizePoses()>0) + { + // find nearest state (using l2-norm) in order to prune the trajectory + // (remove already passed states) + double dist_cache = (new_start->position()- Pose(0).position()).norm(); + double dist; + int lookahead = std::min( sizePoses()-min_samples, 10); // satisfy min_samples, otherwise max 10 samples + + int nearest_idx = 0; + for (int i = 1; i<=lookahead; ++i) + { + dist = (new_start->position()- Pose(i).position()).norm(); + if (dist0) + { + // nearest_idx is equal to the number of samples to be removed (since it counts from 0 ;-) ) + // WARNING delete starting at pose 1, and overwrite the original pose(0) with new_start, since Pose(0) is fixed during optimization! + deletePoses(1, nearest_idx); // delete first states such that the closest state is the new first one + deleteTimeDiffs(1, nearest_idx); // delete corresponding time differences + } + + // update start + Pose(0) = *new_start; + } + + if (new_goal && sizePoses()>0) + { + BackPose() = *new_goal; + } +}; + + +bool TimedElasticBand::isTrajectoryInsideRegion(double radius, double max_dist_behind_robot, int skip_poses) +{ + if (sizePoses()<=0) + return true; + + double radius_sq = radius*radius; + double max_dist_behind_robot_sq = max_dist_behind_robot*max_dist_behind_robot; + Eigen::Vector2d robot_orient = Pose(0).orientationUnitVec(); + + for (int i=1; i radius_sq) + { + ROS_INFO("outside robot"); + return false; + } + + // check behind the robot with a different distance, if specified (or >=0) + if (max_dist_behind_robot >= 0 && dist_vec.dot(robot_orient) < 0 && dist_sq > max_dist_behind_robot_sq) + { + ROS_INFO("outside robot behind"); + return false; + } + + } + return true; +} + + + + +} // namespace teb_local_planner diff --git a/navigations/teb_local_planner/src/visualization.cpp b/navigations/teb_local_planner/src/visualization.cpp new file mode 100755 index 0000000..63a7e97 --- /dev/null +++ b/navigations/teb_local_planner/src/visualization.cpp @@ -0,0 +1,540 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2016, + * TU Dortmund - Institute of Control Theory and Systems Engineering. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the institute nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * Author: Christoph Rösmann + *********************************************************************/ + +#include +#include +#include + +namespace teb_local_planner +{ + +TebVisualization::TebVisualization() : initialized_(false) +{ +} + +TebVisualization::TebVisualization(ros::NodeHandle& nh, const TebConfig& cfg) : initialized_(false) +{ + initialize(nh, cfg); +} + +void TebVisualization::initialize(ros::NodeHandle& nh, const TebConfig& cfg) +{ + if (initialized_) + ROS_WARN("TebVisualization already initialized. Reinitalizing..."); + + // set config + cfg_ = &cfg; + + // register topics + global_plan_pub_ = nh.advertise("global_plan", 1); + local_plan_pub_ = nh.advertise("local_plan",1); + teb_poses_pub_ = nh.advertise("teb_poses", 100); + teb_marker_pub_ = nh.advertise("teb_markers", 1000); + feedback_pub_ = nh.advertise("teb_feedback", 10); + + initialized_ = true; +} + + + +void TebVisualization::publishGlobalPlan(const std::vector& global_plan) const +{ + if ( printErrorWhenNotInitialized() ) return; + base_local_planner::publishPlan(global_plan, global_plan_pub_); +} + +void TebVisualization::publishLocalPlan(const std::vector& local_plan) const +{ + if ( printErrorWhenNotInitialized() ) + return; + base_local_planner::publishPlan(local_plan, local_plan_pub_); +} + +void TebVisualization::publishLocalPlanAndPoses(const TimedElasticBand& teb) const +{ + if ( printErrorWhenNotInitialized() ) + return; + + // create path msg + nav_msgs::Path teb_path; + teb_path.header.frame_id = cfg_->map_frame; + teb_path.header.stamp = ros::Time::now(); + + // create pose_array (along trajectory) + geometry_msgs::PoseArray teb_poses; + teb_poses.header.frame_id = teb_path.header.frame_id; + teb_poses.header.stamp = teb_path.header.stamp; + + // fill path msgs with teb configurations + for (int i=0; i < teb.sizePoses(); i++) + { + geometry_msgs::PoseStamped pose; + pose.header.frame_id = teb_path.header.frame_id; + pose.header.stamp = teb_path.header.stamp; + pose.pose.position.x = teb.Pose(i).x(); + pose.pose.position.y = teb.Pose(i).y(); + pose.pose.position.z = cfg_->hcp.visualize_with_time_as_z_axis_scale*teb.getSumOfTimeDiffsUpToIdx(i); + pose.pose.orientation = tf::createQuaternionMsgFromYaw(teb.Pose(i).theta()); + teb_path.poses.push_back(pose); + teb_poses.poses.push_back(pose.pose); + } + local_plan_pub_.publish(teb_path); + teb_poses_pub_.publish(teb_poses); +} + + + +void TebVisualization::publishRobotFootprintModel(const PoseSE2& current_pose, const BaseRobotFootprintModel& robot_model, + const std::string& ns, const std_msgs::ColorRGBA &color) +{ + if ( printErrorWhenNotInitialized() ) + return; + + std::vector markers; + robot_model.visualizeRobot(current_pose, markers, color); + if (markers.empty()) + return; + + int idx = 0; + for (std::vector::iterator marker_it = markers.begin(); marker_it != markers.end(); ++marker_it, ++idx) + { + marker_it->header.frame_id = cfg_->map_frame; + marker_it->header.stamp = ros::Time::now(); + marker_it->action = visualization_msgs::Marker::ADD; + marker_it->ns = ns; + marker_it->id = idx; + marker_it->lifetime = ros::Duration(2.0); + teb_marker_pub_.publish(*marker_it); + } + +} + +void TebVisualization::publishRobotFootprint(const PoseSE2& current_pose, const std::vector& footprint, + const std::string& ns, const std_msgs::ColorRGBA &color) +{ + if ( printErrorWhenNotInitialized() || footprint.empty() ) + return; + + visualization_msgs::Marker vertex_marker; + vertex_marker.header.frame_id = cfg_->map_frame; + vertex_marker.header.stamp = ros::Time::now(); + vertex_marker.ns = ns; + vertex_marker.type = visualization_msgs::Marker::LINE_STRIP; + vertex_marker.action = visualization_msgs::Marker::ADD; + vertex_marker.color = color; + vertex_marker.scale.x = 0.01; + vertex_marker.lifetime = ros::Duration(2.0); + vertex_marker.points = footprint; + vertex_marker.points.push_back(footprint.front()); // close the polygon + current_pose.toPoseMsg(vertex_marker.pose); + teb_marker_pub_.publish(vertex_marker); +} + +void TebVisualization::publishInfeasibleRobotPose(const PoseSE2& infeasible_pose, + const BaseRobotFootprintModel& robot_model, + const std::vector& footprint) +{ + publishRobotFootprintModel(infeasible_pose, robot_model, "InfeasibleRobotPose/model", toColorMsg(0.5, 0.8, 0.0, 0.0)); + publishRobotFootprint(infeasible_pose, footprint, "InfeasibleRobotPose/footprint", toColorMsg(0.5, 0.9, 0.7, 0.0)); +} + +void TebVisualization::publishObstacles(const ObstContainer& obstacles, double scale) const +{ + if ( obstacles.empty() || printErrorWhenNotInitialized() ) + return; + + // Visualize point obstacles + { + visualization_msgs::Marker marker; + marker.header.frame_id = cfg_->map_frame; + marker.header.stamp = ros::Time::now(); + marker.ns = "PointObstacles"; + marker.id = 0; + marker.type = visualization_msgs::Marker::POINTS; + marker.action = visualization_msgs::Marker::ADD; + marker.lifetime = ros::Duration(2.0); + + for (ObstContainer::const_iterator obst = obstacles.begin(); obst != obstacles.end(); ++obst) + { + boost::shared_ptr pobst = boost::dynamic_pointer_cast(*obst); + if (!pobst) + continue; + + if (cfg_->hcp.visualize_with_time_as_z_axis_scale < 0.001) + { + geometry_msgs::Point point; + point.x = pobst->x(); + point.y = pobst->y(); + point.z = 0; + marker.points.push_back(point); + } + else // Spatiotemporally point obstacles become a line + { + marker.type = visualization_msgs::Marker::LINE_LIST; + geometry_msgs::Point start; + start.x = pobst->x(); + start.y = pobst->y(); + start.z = 0; + marker.points.push_back(start); + + geometry_msgs::Point end; + double t = 20; + Eigen::Vector2d pred; + pobst->predictCentroidConstantVelocity(t, pred); + end.x = pred[0]; + end.y = pred[1]; + end.z = cfg_->hcp.visualize_with_time_as_z_axis_scale*t; + marker.points.push_back(end); + } + } + + marker.scale.x = scale; + marker.scale.y = scale; + marker.color.a = 1.0; + marker.color.r = 1.0; + marker.color.g = 0.0; + marker.color.b = 0.0; + + teb_marker_pub_.publish( marker ); + } + + // Visualize circular obstacles + { + std::size_t idx = 0; + for (ObstContainer::const_iterator obst = obstacles.begin(); obst != obstacles.end(); ++obst) + { + boost::shared_ptr pobst = boost::dynamic_pointer_cast(*obst); + if (!pobst) + continue; + + visualization_msgs::Marker marker; + marker.header.frame_id = cfg_->map_frame; + marker.header.stamp = ros::Time::now(); + marker.ns = "CircularObstacles"; + marker.id = idx++; + marker.type = visualization_msgs::Marker::SPHERE_LIST; + marker.action = visualization_msgs::Marker::ADD; + marker.lifetime = ros::Duration(2.0); + geometry_msgs::Point point; + point.x = pobst->x(); + point.y = pobst->y(); + point.z = 0; + marker.points.push_back(point); + + marker.scale.x = pobst->radius(); + marker.scale.y = pobst->radius(); + marker.color.a = 1.0; + marker.color.r = 0.0; + marker.color.g = 1.0; + marker.color.b = 0.0; + + teb_marker_pub_.publish( marker ); + } + } + + // Visualize line obstacles + { + std::size_t idx = 0; + for (ObstContainer::const_iterator obst = obstacles.begin(); obst != obstacles.end(); ++obst) + { + boost::shared_ptr pobst = boost::dynamic_pointer_cast(*obst); + if (!pobst) + continue; + + visualization_msgs::Marker marker; + marker.header.frame_id = cfg_->map_frame; + marker.header.stamp = ros::Time::now(); + marker.ns = "LineObstacles"; + marker.id = idx++; + marker.type = visualization_msgs::Marker::LINE_STRIP; + marker.action = visualization_msgs::Marker::ADD; + marker.lifetime = ros::Duration(2.0); + geometry_msgs::Point start; + start.x = pobst->start().x(); + start.y = pobst->start().y(); + start.z = 0; + marker.points.push_back(start); + geometry_msgs::Point end; + end.x = pobst->end().x(); + end.y = pobst->end().y(); + end.z = 0; + marker.points.push_back(end); + + marker.scale.x = scale; + marker.scale.y = scale; + marker.color.a = 1.0; + marker.color.r = 0.0; + marker.color.g = 1.0; + marker.color.b = 0.0; + + teb_marker_pub_.publish( marker ); + } + } + + + // Visualize polygon obstacles + { + std::size_t idx = 0; + for (ObstContainer::const_iterator obst = obstacles.begin(); obst != obstacles.end(); ++obst) + { + boost::shared_ptr pobst = boost::dynamic_pointer_cast(*obst); + if (!pobst) + continue; + + visualization_msgs::Marker marker; + marker.header.frame_id = cfg_->map_frame; + marker.header.stamp = ros::Time::now(); + marker.ns = "PolyObstacles"; + marker.id = idx++; + marker.type = visualization_msgs::Marker::LINE_STRIP; + marker.action = visualization_msgs::Marker::ADD; + marker.lifetime = ros::Duration(2.0); + + for (Point2dContainer::const_iterator vertex = pobst->vertices().begin(); vertex != pobst->vertices().end(); ++vertex) + { + geometry_msgs::Point point; + point.x = vertex->x(); + point.y = vertex->y(); + point.z = 0; + marker.points.push_back(point); + } + + // Also add last point to close the polygon + // but only if polygon has more than 2 points (it is not a line) + if (pobst->vertices().size() > 2) + { + geometry_msgs::Point point; + point.x = pobst->vertices().front().x(); + point.y = pobst->vertices().front().y(); + point.z = 0; + marker.points.push_back(point); + } + marker.scale.x = scale; + marker.scale.y = scale; + marker.color.a = 1.0; + marker.color.r = 1.0; + marker.color.g = 0.0; + marker.color.b = 0.0; + + teb_marker_pub_.publish( marker ); + } + } +} + + +void TebVisualization::publishViaPoints(const std::vector< Eigen::Vector2d, Eigen::aligned_allocator >& via_points, const std::string& ns) const +{ + if ( via_points.empty() || printErrorWhenNotInitialized() ) + return; + + visualization_msgs::Marker marker; + marker.header.frame_id = cfg_->map_frame; + marker.header.stamp = ros::Time::now(); + marker.ns = ns; + marker.id = 0; + marker.type = visualization_msgs::Marker::POINTS; + marker.action = visualization_msgs::Marker::ADD; + marker.lifetime = ros::Duration(2.0); + + for (std::size_t i=0; i < via_points.size(); ++i) + { + geometry_msgs::Point point; + point.x = via_points[i].x(); + point.y = via_points[i].y(); + point.z = 0; + marker.points.push_back(point); + } + + marker.scale.x = 0.1; + marker.scale.y = 0.1; + marker.color.a = 1.0; + marker.color.r = 0.0; + marker.color.g = 0.0; + marker.color.b = 1.0; + + teb_marker_pub_.publish( marker ); +} + +void TebVisualization::publishTebContainer(const TebOptPlannerContainer& teb_planner, const std::string& ns) +{ +if ( printErrorWhenNotInitialized() ) + return; + + visualization_msgs::Marker marker; + marker.header.frame_id = cfg_->map_frame; + marker.header.stamp = ros::Time::now(); + marker.ns = ns; + marker.id = 0; + marker.type = visualization_msgs::Marker::LINE_LIST; + marker.action = visualization_msgs::Marker::ADD; + + // Iterate through teb pose sequence + for( TebOptPlannerContainer::const_iterator it_teb = teb_planner.begin(); it_teb != teb_planner.end(); ++it_teb ) + { + // iterate single poses + PoseSequence::const_iterator it_pose = it_teb->get()->teb().poses().begin(); + TimeDiffSequence::const_iterator it_timediff = it_teb->get()->teb().timediffs().begin(); + PoseSequence::const_iterator it_pose_end = it_teb->get()->teb().poses().end(); + std::advance(it_pose_end, -1); // since we are interested in line segments, reduce end iterator by one. + double time = 0; + + while (it_pose != it_pose_end) + { + geometry_msgs::Point point_start; + point_start.x = (*it_pose)->x(); + point_start.y = (*it_pose)->y(); + point_start.z = cfg_->hcp.visualize_with_time_as_z_axis_scale*time; + marker.points.push_back(point_start); + + time += (*it_timediff)->dt(); + + geometry_msgs::Point point_end; + point_end.x = (*boost::next(it_pose))->x(); + point_end.y = (*boost::next(it_pose))->y(); + point_end.z = cfg_->hcp.visualize_with_time_as_z_axis_scale*time; + marker.points.push_back(point_end); + ++it_pose; + ++it_timediff; + } + } + marker.scale.x = 0.01; + marker.color.a = 1.0; + marker.color.r = 0.5; + marker.color.g = 1.0; + marker.color.b = 0.0; + + teb_marker_pub_.publish( marker ); +} + +void TebVisualization::publishFeedbackMessage(const std::vector< boost::shared_ptr >& teb_planners, + unsigned int selected_trajectory_idx, const ObstContainer& obstacles) +{ + FeedbackMsg msg; + msg.header.stamp = ros::Time::now(); + msg.header.frame_id = cfg_->map_frame; + msg.selected_trajectory_idx = selected_trajectory_idx; + + + msg.trajectories.resize(teb_planners.size()); + + // Iterate through teb pose sequence + std::size_t idx_traj = 0; + for( TebOptPlannerContainer::const_iterator it_teb = teb_planners.begin(); it_teb != teb_planners.end(); ++it_teb, ++idx_traj ) + { + msg.trajectories[idx_traj].header = msg.header; + it_teb->get()->getFullTrajectory(msg.trajectories[idx_traj].trajectory); + } + + // add obstacles + msg.obstacles_msg.obstacles.resize(obstacles.size()); + for (std::size_t i=0; itoPolygonMsg(msg.obstacles_msg.obstacles[i].polygon); + + // copy id + msg.obstacles_msg.obstacles[i].id = i; // TODO: we do not have any id stored yet + + // orientation + //msg.obstacles_msg.obstacles[i].orientation =; // TODO + + // copy velocities + obstacles[i]->toTwistWithCovarianceMsg(msg.obstacles_msg.obstacles[i].velocities); + } + + feedback_pub_.publish(msg); +} + +void TebVisualization::publishFeedbackMessage(const TebOptimalPlanner& teb_planner, const ObstContainer& obstacles) +{ + FeedbackMsg msg; + msg.header.stamp = ros::Time::now(); + msg.header.frame_id = cfg_->map_frame; + msg.selected_trajectory_idx = 0; + + msg.trajectories.resize(1); + msg.trajectories.front().header = msg.header; + teb_planner.getFullTrajectory(msg.trajectories.front().trajectory); + + // add obstacles + msg.obstacles_msg.obstacles.resize(obstacles.size()); + for (std::size_t i=0; itoPolygonMsg(msg.obstacles_msg.obstacles[i].polygon); + + // copy id + msg.obstacles_msg.obstacles[i].id = i; // TODO: we do not have any id stored yet + + // orientation + //msg.obstacles_msg.obstacles[i].orientation =; // TODO + + // copy velocities + obstacles[i]->toTwistWithCovarianceMsg(msg.obstacles_msg.obstacles[i].velocities); + } + + feedback_pub_.publish(msg); +} + +std_msgs::ColorRGBA TebVisualization::toColorMsg(double a, double r, double g, double b) +{ + std_msgs::ColorRGBA color; + color.a = a; + color.r = r; + color.g = g; + color.b = b; + return color; +} + +bool TebVisualization::printErrorWhenNotInitialized() const +{ + if (!initialized_) + { + ROS_ERROR("TebVisualization class not initialized. You must call initialize or an appropriate constructor"); + return true; + } + return false; +} + +} // namespace teb_local_planner diff --git a/navigations/teb_local_planner/teb_local_planner_plugin.xml b/navigations/teb_local_planner/teb_local_planner_plugin.xml new file mode 100755 index 0000000..eb0f4ce --- /dev/null +++ b/navigations/teb_local_planner/teb_local_planner_plugin.xml @@ -0,0 +1,14 @@ + + + + The teb_local_planner package implements a plugin + to the base_local_planner of the 2D navigation stack. + + + + + Same plugin implemented MBF CostmapController's extended interface. + + + + diff --git a/navigations/teb_local_planner/test/teb_basics.cpp b/navigations/teb_local_planner/test/teb_basics.cpp new file mode 100755 index 0000000..9a75909 --- /dev/null +++ b/navigations/teb_local_planner/test/teb_basics.cpp @@ -0,0 +1,73 @@ +#include + +#include + +TEST(TEBBasic, autoResizeLargeValueAtEnd) +{ + double dt = 0.1; + double dt_hysteresis = dt/3.; + teb_local_planner::TimedElasticBand teb; + + teb.addPose(teb_local_planner::PoseSE2(0., 0., 0.)); + for (int i = 1; i < 10; ++i) { + teb.addPoseAndTimeDiff(teb_local_planner::PoseSE2(i * 1., 0., 0.), dt); + } + // add a pose with a large timediff as the last one + teb.addPoseAndTimeDiff(teb_local_planner::PoseSE2(10., 0., 0.), dt + 2*dt_hysteresis); + + // auto resize + test of the result + teb.autoResize(dt, dt_hysteresis, 3, 100, false); + for (int i = 0; i < teb.sizeTimeDiffs(); ++i) { + ASSERT_LE(teb.TimeDiff(i), dt + dt_hysteresis + 1e-3) << "dt is greater than allowed: " << i; + ASSERT_LE(dt - dt_hysteresis - 1e-3, teb.TimeDiff(i)) << "dt is less than allowed: " << i; + } +} + +TEST(TEBBasic, autoResizeSmallValueAtEnd) +{ + double dt = 0.1; + double dt_hysteresis = dt/3.; + teb_local_planner::TimedElasticBand teb; + + teb.addPose(teb_local_planner::PoseSE2(0., 0., 0.)); + for (int i = 1; i < 10; ++i) { + teb.addPoseAndTimeDiff(teb_local_planner::PoseSE2(i * 1., 0., 0.), dt); + } + // add a pose with a small timediff as the last one + teb.addPoseAndTimeDiff(teb_local_planner::PoseSE2(10., 0., 0.), dt - 2*dt_hysteresis); + + // auto resize + test of the result + teb.autoResize(dt, dt_hysteresis, 3, 100, false); + for (int i = 0; i < teb.sizeTimeDiffs(); ++i) { + ASSERT_LE(teb.TimeDiff(i), dt + dt_hysteresis + 1e-3) << "dt is greater than allowed: " << i; + ASSERT_LE(dt - dt_hysteresis - 1e-3, teb.TimeDiff(i)) << "dt is less than allowed: " << i; + } +} + +TEST(TEBBasic, autoResize) +{ + double dt = 0.1; + double dt_hysteresis = dt/3.; + teb_local_planner::TimedElasticBand teb; + + teb.addPose(teb_local_planner::PoseSE2(0., 0., 0.)); + for (int i = 1; i < 10; ++i) { + teb.addPoseAndTimeDiff(teb_local_planner::PoseSE2(i * 1., 0., 0.), dt); + } + // modify the timediff in the middle and add a pose with a smaller timediff as the last one + teb.TimeDiff(5) = dt + 2*dt_hysteresis; + teb.addPoseAndTimeDiff(teb_local_planner::PoseSE2(10., 0., 0.), dt - 2*dt_hysteresis); + + // auto resize + teb.autoResize(dt, dt_hysteresis, 3, 100, false); + for (int i = 0; i < teb.sizeTimeDiffs(); ++i) { + ASSERT_LE(teb.TimeDiff(i), dt + dt_hysteresis + 1e-3) << "dt is greater than allowed: " << i; + ASSERT_LE(dt - dt_hysteresis - 1e-3, teb.TimeDiff(i)) << "dt is less than allowed: " << i; + } +} + +int main(int argc, char** argv) +{ + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} \ No newline at end of file diff --git a/navigations/twist_recovery/CHANGELOG.rst b/navigations/twist_recovery/CHANGELOG.rst new file mode 100755 index 0000000..0644897 --- /dev/null +++ b/navigations/twist_recovery/CHANGELOG.rst @@ -0,0 +1,39 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package twist_recovery +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +0.4.1 (2022-08-24) +------------------ + +0.4.0 (2022-03-07) +------------------ + +0.3.4 (2020-06-19) +------------------ +* Initial release into noetic * Set cmake_policy CMP0048 to fix warning +* Contributors: Martin Günther + +0.3.3 (2019-10-15) +------------------ +* Add READMEs +* Contributors: Martin Günther + +0.3.2 (2019-01-16) +------------------ + +0.3.1 (2018-09-05) +------------------ +* twist_recovery: Add missing dependency + Actually, this is a workaround for the following bug: https://github.com/ros/geometry2/issues/275 +* Contributors: Martin Günther + +0.3.0 (2018-09-04) +------------------ +* Convert to TF2 + new navigation API (for melodic) +* Use non deprecated pluginlib macro + headers +* Contributors: Martin Günther + +0.2.0 (2018-09-03) +------------------ +* Initial release into indigo, kinetic, lunar and melodic +* Contributors: Martin Günther, David V. Lu!!, Dave Hershberger, Jon Binney, Bhaskara Marti diff --git a/navigations/twist_recovery/CMakeLists.txt b/navigations/twist_recovery/CMakeLists.txt new file mode 100755 index 0000000..4b972c7 --- /dev/null +++ b/navigations/twist_recovery/CMakeLists.txt @@ -0,0 +1,37 @@ +cmake_minimum_required(VERSION 3.5.1) +cmake_policy(SET CMP0048 NEW) +project(twist_recovery) + +# Find ROS dependencies +set(THIS_PACKAGE_ROS_DEPS nav_core costmap_2d geometry_msgs pluginlib base_local_planner tf2_geometry_msgs tf2_ros) +find_package(catkin REQUIRED COMPONENTS ${THIS_PACKAGE_ROS_DEPS}) + +include_directories(include ${catkin_INCLUDE_DIRS}) + +catkin_package( + INCLUDE_DIRS include + LIBRARIES twist_recovery + CATKIN_DEPENDS ${THIS_PACKAGE_ROS_DEPS} +) + +add_library(twist_recovery src/twist_recovery.cpp) +target_link_libraries(twist_recovery ${catkin_LIBRARIES}) + +install(TARGETS twist_recovery + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) + +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} + FILES_MATCHING PATTERN "*.h" +) + +install(FILES twist_plugin.xml + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) + +install(DIRECTORY config + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) diff --git a/navigations/twist_recovery/README.md b/navigations/twist_recovery/README.md new file mode 100755 index 0000000..201e8d4 --- /dev/null +++ b/navigations/twist_recovery/README.md @@ -0,0 +1,4 @@ +twist_recovery +============== + +A recovery behavior that performs a particular used-defined twist. diff --git a/navigations/twist_recovery/config/backwards.yaml b/navigations/twist_recovery/config/backwards.yaml new file mode 100755 index 0000000..f7837d3 --- /dev/null +++ b/navigations/twist_recovery/config/backwards.yaml @@ -0,0 +1,5 @@ +# Configuration for version of this recovery where we back up slowly about half a meter +linear_x: -0.3 +linear_y: 0.0 +angular_z: 0.0 +duration: 1.5 \ No newline at end of file diff --git a/navigations/twist_recovery/config/diagonal_left.yaml b/navigations/twist_recovery/config/diagonal_left.yaml new file mode 100755 index 0000000..546b823 --- /dev/null +++ b/navigations/twist_recovery/config/diagonal_left.yaml @@ -0,0 +1,4 @@ +linear_x: 0.0 +linear_y: 0.2 +angular_z: 0.0 +duration: 1.0 \ No newline at end of file diff --git a/navigations/twist_recovery/config/diagonal_right.yaml b/navigations/twist_recovery/config/diagonal_right.yaml new file mode 100755 index 0000000..51be260 --- /dev/null +++ b/navigations/twist_recovery/config/diagonal_right.yaml @@ -0,0 +1,4 @@ +linear_x: 0.0 +linear_y: -0.2 +angular_z: 0.0 +duration: 1.0 \ No newline at end of file diff --git a/navigations/twist_recovery/include/twist_recovery/twist_recovery.h b/navigations/twist_recovery/include/twist_recovery/twist_recovery.h new file mode 100755 index 0000000..8897812 --- /dev/null +++ b/navigations/twist_recovery/include/twist_recovery/twist_recovery.h @@ -0,0 +1,107 @@ +/* + * Copyright (c) 2008, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +/** + * \file + * + * Recovery behavior based on executing a particular twist + * + * \author Bhaskara Marthi + */ + +#ifndef TWIST_RECOVERY_TWIST_RECOVERY_H +#define TWIST_RECOVERY_TWIST_RECOVERY_H + +#include +#include +#include +#include +#include +#include +#include + +namespace twist_recovery +{ + +/// Recovery behavior that takes a given twist and tries to execute it for up to +/// d seconds, or until reaching an obstacle. +class TwistRecovery : public nav_core::RecoveryBehavior +{ +public: + + /// Doesn't do anything: initialize is where the actual work happens + TwistRecovery(); + + ~TwistRecovery(); + + /// Initialize the parameters of the behavior + void initialize (std::string n, tf2_ros::Buffer* tf, + costmap_2d::Costmap2DROS* global_costmap, + costmap_2d::Costmap2DROS* local_costmap); + + /// Run the behavior + void runBehavior(); + +private: + + geometry_msgs::Pose2D getCurrentLocalPose () const; + geometry_msgs::Twist scaleGivenAccelerationLimits (const geometry_msgs::Twist& twist, const double time_remaining) const; + double nonincreasingCostInterval (const geometry_msgs::Pose2D& current, const geometry_msgs::Twist& twist) const; + double normalizedPoseCost (const geometry_msgs::Pose2D& pose) const; + geometry_msgs::Twist transformTwist (const geometry_msgs::Pose2D& pose) const; + + ros::NodeHandle nh_; + costmap_2d::Costmap2DROS* global_costmap_; + costmap_2d::Costmap2DROS* local_costmap_; + std::string name_; + tf2_ros::Buffer* tf_; + ros::Publisher pub_; + bool initialized_; + + // Memory owned by this object + // Mutable because footprintCost is not declared const + mutable base_local_planner::CostmapModel* world_model_; + + geometry_msgs::Twist base_frame_twist_; + + double duration_; + double linear_speed_limit_; + double angular_speed_limit_; + double linear_acceleration_limit_; + double angular_acceleration_limit_; + double controller_frequency_; + double simulation_inc_; + + +}; + +} // namespace twist_recovery + +#endif // include guard diff --git a/navigations/twist_recovery/package.xml b/navigations/twist_recovery/package.xml new file mode 100755 index 0000000..190f2a2 --- /dev/null +++ b/navigations/twist_recovery/package.xml @@ -0,0 +1,28 @@ + + + twist_recovery + 0.4.1 + + A recovery behavior that performs a particular used-defined twist. + + Martin Günther + Bhaskara Marthi + BSD + http://wiki.ros.org/twist_recovery + https://github.com/ros-planning/navigation_experimental.git + https://github.com/ros-planning/navigation_experimental/issues + + catkin + + base_local_planner + costmap_2d + geometry_msgs + nav_core + pluginlib + tf2_geometry_msgs + tf2_ros + + + + + diff --git a/navigations/twist_recovery/src/twist_recovery.cpp b/navigations/twist_recovery/src/twist_recovery.cpp new file mode 100755 index 0000000..c5ff9bc --- /dev/null +++ b/navigations/twist_recovery/src/twist_recovery.cpp @@ -0,0 +1,206 @@ +/* + * Copyright (c) 2008, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + */ + +/** + * \file + * + * \author Bhaskara Marthi + * + */ + +#include +#include +#include +#include + +// register as a RecoveryBehavior plugin +PLUGINLIB_EXPORT_CLASS(twist_recovery::TwistRecovery, nav_core::RecoveryBehavior) + +namespace gm=geometry_msgs; +namespace cmap=costmap_2d; +namespace blp=base_local_planner; +using std::vector; +using std::max; + +namespace twist_recovery +{ + +TwistRecovery::TwistRecovery () : + global_costmap_(NULL), local_costmap_(NULL), tf_(NULL), initialized_(false) +{} + +TwistRecovery::~TwistRecovery () +{ + delete world_model_; +} + +void TwistRecovery::initialize (std::string name, tf2_ros::Buffer* tf, + cmap::Costmap2DROS* global_cmap, cmap::Costmap2DROS* local_cmap) +{ + ROS_ASSERT(!initialized_); + name_ = name; + tf_ = tf; + local_costmap_ = local_cmap; + global_costmap_ = global_cmap; + world_model_ = new blp::CostmapModel(*local_costmap_->getCostmap()); + + pub_ = nh_.advertise("cmd_vel", 10); + ros::NodeHandle private_nh("~/" + name); + + { + bool found=true; + found = found && private_nh.getParam("linear_x", base_frame_twist_.linear.x); + found = found && private_nh.getParam("linear_y", base_frame_twist_.linear.y); + found = found && private_nh.getParam("angular_z", base_frame_twist_.angular.z); + if (!found) { + ROS_FATAL_STREAM ("Didn't find twist parameters in " << private_nh.getNamespace()); + ros::shutdown(); + } + } + + private_nh.param("duration", duration_, 1.0); + private_nh.param("linear_speed_limit", linear_speed_limit_, 0.3); + private_nh.param("angular_speed_limit", angular_speed_limit_, 1.0); + private_nh.param("linear_acceleration_limit", linear_acceleration_limit_, 4.0); + private_nh.param("angular_acceleration_limit", angular_acceleration_limit_, 3.2); + private_nh.param("controller_frequency", controller_frequency_, 20.0); + private_nh.param("simulation_inc", simulation_inc_, 1/controller_frequency_); + + ROS_INFO_STREAM_NAMED ("top", "Initialized twist recovery with twist " << + base_frame_twist_ << " and duration " << duration_); + + initialized_ = true; +} + +gm::Twist scaleTwist (const gm::Twist& twist, const double scale) +{ + gm::Twist t; + t.linear.x = twist.linear.x * scale; + t.linear.y = twist.linear.y * scale; + t.angular.z = twist.angular.z * scale; + return t; +} + +gm::Pose2D forwardSimulate (const gm::Pose2D& p, const gm::Twist& twist, const double t=1.0) +{ + gm::Pose2D p2; + p2.x = p.x + twist.linear.x*t; + p2.y = p.y + twist.linear.y*t; + p2.theta = p.theta + twist.angular.z*t; + return p2; +} + +/// Return the cost of a pose, modified so that -1 does not equal infinity; instead 1e9 does. +double TwistRecovery::normalizedPoseCost (const gm::Pose2D& pose) const +{ + const double c = world_model_->footprintCost(pose.x, pose.y, pose.theta, local_costmap_->getRobotFootprint(), 0.0, 0.0); + return c < 0 ? 1e9 : c; +} + + +/// Return the maximum d <= duration_ such that starting at the current pose, the cost is nonincreasing for +/// d seconds if we follow twist +/// It might also be good to have a threshold such that we're allowed to have lethal cost for at most +/// the first k of those d seconds, but this is not done +double TwistRecovery::nonincreasingCostInterval (const gm::Pose2D& current, const gm::Twist& twist) const +{ + double cost = normalizedPoseCost(current); + double t; // Will hold the first time that is invalid + for (t=simulation_inc_; t<=duration_; t+=simulation_inc_) { + const double next_cost = normalizedPoseCost(forwardSimulate(current, twist, t)); + if (next_cost > cost) { + ROS_DEBUG_STREAM_NAMED ("cost", "Cost at " << t << " and pose " << forwardSimulate(current, twist, t) + << " is " << next_cost << " which is greater than previous cost " << cost); + break; + } + cost = next_cost; + } + + return t-simulation_inc_; +} + +double linearSpeed (const gm::Twist& twist) +{ + return sqrt(twist.linear.x*twist.linear.x + twist.linear.y*twist.linear.y); +} + +double angularSpeed (const gm::Twist& twist) +{ + return fabs(twist.angular.z); +} + +// Scale twist so we can stop in the given time, and so it's within the max velocity +gm::Twist TwistRecovery::scaleGivenAccelerationLimits (const gm::Twist& twist, const double time_remaining) const +{ + const double linear_speed = linearSpeed(twist); + const double angular_speed = angularSpeed(twist); + const double linear_acc_scaling = linear_speed/(time_remaining*linear_acceleration_limit_); + const double angular_acc_scaling = angular_speed/(time_remaining*angular_acceleration_limit_); + const double acc_scaling = max(linear_acc_scaling, angular_acc_scaling); + const double linear_vel_scaling = linear_speed/linear_speed_limit_; + const double angular_vel_scaling = angular_speed/angular_speed_limit_; + const double vel_scaling = max(linear_vel_scaling, angular_vel_scaling); + return scaleTwist(twist, max(1.0, max(acc_scaling, vel_scaling))); +} + +// Get pose in local costmap frame +gm::Pose2D TwistRecovery::getCurrentLocalPose () const +{ + gm::PoseStamped p; + local_costmap_->getRobotPose(p); + gm::Pose2D pose; + pose.x = p.pose.position.x; + pose.y = p.pose.position.y; + pose.theta = tf2::getYaw(p.pose.orientation); + return pose; +} + +void TwistRecovery::runBehavior () +{ + ROS_ASSERT (initialized_); + + // Figure out how long we can safely run the behavior + const gm::Pose2D& current = getCurrentLocalPose(); + + const double d = nonincreasingCostInterval(current, base_frame_twist_); + ros::Rate r(controller_frequency_); + ROS_WARN_NAMED ("top", "Applying (%.2f, %.2f, %.2f) for %.2f seconds", base_frame_twist_.linear.x, + base_frame_twist_.linear.y, base_frame_twist_.angular.z, d); + + // We'll now apply this twist open-loop for d seconds (scaled so we can guarantee stopping at the end) + for (double t=0; t + + + A recovery behavior that performs a particular used-defined twist. + + + diff --git a/navigations/unique_identifier/README.rst b/navigations/unique_identifier/README.rst new file mode 100755 index 0000000..e287f6e --- /dev/null +++ b/navigations/unique_identifier/README.rst @@ -0,0 +1,13 @@ +unique_identifier +================= + +ROS messages and interfaces for Universally Unique Identifiers. + + * http://en.wikipedia.org/wiki/Uuid + * http://tools.ietf.org/html/rfc4122.html + +ROS documentation: + + * http://www.ros.org/wiki/unique_id + * http://www.ros.org/wiki/unique_identifier + * http://www.ros.org/wiki/uuid_msgs diff --git a/navigations/unique_identifier/unique_id/CHANGELOG.rst b/navigations/unique_identifier/unique_id/CHANGELOG.rst new file mode 100755 index 0000000..eb1d362 --- /dev/null +++ b/navigations/unique_identifier/unique_id/CHANGELOG.rst @@ -0,0 +1,52 @@ +Change history +============== + +1.0.6 (2017-04-04) +------------------ + + * Remove Python ``install_requires`` option. + * Fix minor catkin lint issues. + +1.0.5 (2015-04-17) +------------------ + + * Alter C++ unique_id functions to work in multiple cpp files (`#7`_). + +1.0.4 (2014-04-30) +------------------ + +1.0.3 (2013-07-24) +------------------ + + * Make unit tests conditional on ``CATKIN_ENABLE_TESTING``. + +1.0.2 (2013-07-18) +------------------- + +1.0.1 (2013-03-25) +------------------- + + * Fix catkin Python install problem (`#4`_). + +1.0.0 (2013-03-18) +------------------- + + * Hydro release. + * Convert to catkin (`#1`_). + +0.9.0 (2013-01-03) +------------------ + + * Initial release to Groovy. + * Add support for C++ interface using boost uuid package. + +0.8.0 (2012-07-19) +------------------ + + * Initial release to Fuerte. + * Supports Python interface based on standard uuid package, but no + C++ API yet. + +.. _`#1`: https://github.com/ros-geographic-info/unique_identifier/issues/1 +.. _`#4`: https://github.com/ros-geographic-info/unique_identifier/issues/4 +.. _`#7`: https://github.com/ros-geographic-info/unique_identifier/issues/7 diff --git a/navigations/unique_identifier/unique_id/CMakeLists.txt b/navigations/unique_identifier/unique_id/CMakeLists.txt new file mode 100755 index 0000000..4befe9f --- /dev/null +++ b/navigations/unique_identifier/unique_id/CMakeLists.txt @@ -0,0 +1,19 @@ +cmake_minimum_required(VERSION 2.8.3) +project(unique_id) + +find_package(catkin REQUIRED COMPONENTS roscpp rospy uuid_msgs) +find_package(Boost REQUIRED) +include_directories(include ${catkin_INCLUDE_DIRS}) + +catkin_python_setup() +catkin_package(INCLUDE_DIRS include + CATKIN_DEPENDS uuid_msgs + DEPENDS Boost) + +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}) + +# unit tests +if (CATKIN_ENABLE_TESTING) + add_subdirectory(tests) +endif() diff --git a/navigations/unique_identifier/unique_id/conf.py b/navigations/unique_identifier/unique_id/conf.py new file mode 100755 index 0000000..292c5f6 --- /dev/null +++ b/navigations/unique_identifier/unique_id/conf.py @@ -0,0 +1,246 @@ +# -*- coding: utf-8 -*- +# +# unique_id documentation build configuration file, created by +# sphinx-quickstart on Wed Apr 25 16:01:20 2012. +# +# This file is execfile()d with the current directory set to its containing dir. +# +# Note that not all possible configuration values are present in this +# autogenerated file. +# +# All configuration values have a default; values that are commented out +# serve to show the default. + +import sys, os + +# If extensions (or modules to document with autodoc) are in another directory, +# add these directories to sys.path here. If the directory is relative to the +# documentation root, use os.path.abspath to make it absolute, like shown here. +#sys.path.insert(0, os.path.abspath('.')) + +# -- General configuration ----------------------------------------------------- + +# If your documentation needs a minimal Sphinx version, state it here. +#needs_sphinx = '1.0' + +# Add any Sphinx extension module names here, as strings. They can be extensions +# coming with Sphinx (named 'sphinx.ext.*') or your custom ones. +extensions = ['sphinx.ext.autodoc', 'sphinx.ext.intersphinx', 'sphinx.ext.todo', 'sphinx.ext.viewcode'] + +# Add any paths that contain templates here, relative to this directory. +templates_path = ['_templates'] + +# The suffix of source filenames. +source_suffix = '.rst' + +# The encoding of source files. +#source_encoding = 'utf-8-sig' + +# The master toctree document. +master_doc = 'index' + +# General information about the project. +project = u'unique_id' +copyright = u'2012, Jack O\'Quin' + +# The version info for the project you're documenting, acts as replacement for +# |version| and |release|, also used in various other places throughout the +# built documents. +# +# The short X.Y version. +version = '0.9' +# The full version, including alpha/beta/rc tags. +release = '0.9.0' + +# The language for content autogenerated by Sphinx. Refer to documentation +# for a list of supported languages. +#language = None + +# There are two options for replacing |today|: either, you set today to some +# non-false value, then it is used: +#today = '' +# Else, today_fmt is used as the format for a strftime call. +#today_fmt = '%B %d, %Y' + +# List of patterns, relative to source directory, that match files and +# directories to ignore when looking for source files. +exclude_patterns = ['_build'] + +# The reST default role (used for this markup: `text`) to use for all documents. +#default_role = None + +# If true, '()' will be appended to :func: etc. cross-reference text. +#add_function_parentheses = True + +# If true, the current module name will be prepended to all description +# unit titles (such as .. function::). +#add_module_names = True + +# If true, sectionauthor and moduleauthor directives will be shown in the +# output. They are ignored by default. +#show_authors = False + +# The name of the Pygments (syntax highlighting) style to use. +pygments_style = 'sphinx' + +# A list of ignored prefixes for module index sorting. +#modindex_common_prefix = [] + + +# -- Options for HTML output --------------------------------------------------- + +# The theme to use for HTML and HTML Help pages. See the documentation for +# a list of builtin themes. +html_theme = 'default' + +# Theme options are theme-specific and customize the look and feel of a theme +# further. For a list of options available for each theme, see the +# documentation. +#html_theme_options = {} + +# Add any paths that contain custom themes here, relative to this directory. +#html_theme_path = [] + +# The name for this set of Sphinx documents. If None, it defaults to +# " v documentation". +#html_title = None + +# A shorter title for the navigation bar. Default is the same as html_title. +#html_short_title = None + +# The name of an image file (relative to this directory) to place at the top +# of the sidebar. +#html_logo = None + +# The name of an image file (within the static path) to use as favicon of the +# docs. This file should be a Windows icon file (.ico) being 16x16 or 32x32 +# pixels large. +#html_favicon = None + +# Add any paths that contain custom static files (such as style sheets) here, +# relative to this directory. They are copied after the builtin static files, +# so a file named "default.css" will overwrite the builtin "default.css". +html_static_path = [] + +# If not '', a 'Last updated on:' timestamp is inserted at every page bottom, +# using the given strftime format. +#html_last_updated_fmt = '%b %d, %Y' + +# If true, SmartyPants will be used to convert quotes and dashes to +# typographically correct entities. +#html_use_smartypants = True + +# Custom sidebar templates, maps document names to template names. +#html_sidebars = {} + +# Additional templates that should be rendered to pages, maps page names to +# template names. +#html_additional_pages = {} + +# If false, no module index is generated. +#html_domain_indices = True + +# If false, no index is generated. +#html_use_index = True + +# If true, the index is split into individual pages for each letter. +#html_split_index = False + +# If true, links to the reST sources are added to the pages. +#html_show_sourcelink = True + +# If true, "Created using Sphinx" is shown in the HTML footer. Default is True. +#html_show_sphinx = True + +# If true, "(C) Copyright ..." is shown in the HTML footer. Default is True. +#html_show_copyright = True + +# If true, an OpenSearch description file will be output, and all pages will +# contain a tag referring to it. The value of this option must be the +# base URL from which the finished HTML is served. +#html_use_opensearch = '' + +# This is the file name suffix for HTML files (e.g. ".xhtml"). +#html_file_suffix = None + +# Output file base name for HTML help builder. +htmlhelp_basename = 'unique_iddoc' + + +# -- Options for LaTeX output -------------------------------------------------- + +latex_elements = { +# The paper size ('letterpaper' or 'a4paper'). +#'papersize': 'letterpaper', + +# The font size ('10pt', '11pt' or '12pt'). +#'pointsize': '10pt', + +# Additional stuff for the LaTeX preamble. +#'preamble': '', +} + +# Grouping the document tree into LaTeX files. List of tuples +# (source start file, target name, title, author, documentclass [howto/manual]). +latex_documents = [ + ('index', 'unique_id.tex', u'ROS support for universally unique identifiers.', + u'Jack O\'Quin', 'manual'), +] + +# The name of an image file (relative to this directory) to place at the top of +# the title page. +#latex_logo = None + +# For "manual" documents, if this is true, then toplevel headings are parts, +# not chapters. +#latex_use_parts = False + +# If true, show page references after internal links. +#latex_show_pagerefs = False + +# If true, show URL addresses after external links. +#latex_show_urls = False + +# Documents to append as an appendix to all manuals. +#latex_appendices = [] + +# If false, no module index is generated. +#latex_domain_indices = True + + +# -- Options for manual page output -------------------------------------------- + +# One entry per manual page. List of tuples +# (source start file, name, description, authors, manual section). +man_pages = [ + ('index', 'unique_id', u'ROS support for universally unique identifiers.', + [u'Jack O\'Quin'], 1) +] + +# If true, show URL addresses after external links. +#man_show_urls = False + + +# -- Options for Texinfo output ------------------------------------------------ + +# Grouping the document tree into Texinfo files. List of tuples +# (source start file, target name, title, author, +# dir menu entry, description, category) +texinfo_documents = [ + ('index', 'unique_id', u'unique_id Documentation', + u'Jack O\'Quin', 'unique_id', 'ROS support for universally unique identifiers.', + 'Miscellaneous'), +] + +# Documents to append as an appendix to all manuals. +#texinfo_appendices = [] + +# If false, no module index is generated. +#texinfo_domain_indices = True + +# How to display URL addresses: 'footnote', 'no', or 'inline'. +#texinfo_show_urls = 'footnote' + + +# Example configuration for intersphinx: refer to the Python standard library. +intersphinx_mapping = {'http://docs.python.org/': None} diff --git a/navigations/unique_identifier/unique_id/include/unique_id/impl/unique_id.h b/navigations/unique_identifier/unique_id/include/unique_id/impl/unique_id.h new file mode 100755 index 0000000..7e9dd94 --- /dev/null +++ b/navigations/unique_identifier/unique_id/include/unique_id/impl/unique_id.h @@ -0,0 +1,115 @@ +/* -*- mode: C++ -*- */ +/********************************************************************* +* Software License Agreement (BSD License) +* +* Copyright (C) 2012 Jack O'Quin +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of the author nor other contributors may be +* used to endorse or promote products derived from this software +* without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +*********************************************************************/ + +#ifndef _IMPL_UNIQUE_ID_H_ +#define _IMPL_UNIQUE_ID_H_ 1 + +/** @file + + @brief Private implementation details for C++ unique_id interface. + + @author Jack O'Quin + */ + +#include + +#include + +namespace unique_id +{ + + /** @brief C++ namespace for private implementation details. */ + namespace impl + { + /* Instantiate boost string UUID generator. */ + static boost::uuids::string_generator genString; + + /* Instantiate boost random UUID generator. */ + static boost::uuids::random_generator genRandom; + + /* RFC 4122 namespace for URL identifiers. */ + static const std::string url_namespace = + "6ba7b811-9dad-11d1-80b4-00c04fd430c8"; + + /* RFC 4122 UUID for URL identifiers. */ + static const boost::uuids::uuid url_namespace_uuid = + genString(url_namespace); + + /* Instantiate boost URL name UUID generator. */ + static boost::uuids::name_generator genURL(url_namespace_uuid); + + /* Generate RFC4122 Version 1 Time-Based UUID */ + static boost::uuids::uuid genTime(ros::Time uuid_time, uint64_t hw_addr) + { + // Get no. of 100 nanosecond intervals since 00:00:00 October 15, 1582 + // The RFC4122 standard only requires the least significant 60 bits for timestamp + + // No. of 100 ns intervals between 00:00:00 Oct 15, 1582 and 00:00:00 Jan 1, 1970 + uint64_t offset = 122192928000000000; + + uint64_t num_hundred_epoch = static_cast(uuid_time.sec) / (1e-9 * 100) + + static_cast(uuid_time.nsec) / 100; + // Note: Adding offset in the same line as the above statement may yield incorrect + // values on some systems + uint64_t num_hundred_rfc = num_hundred_epoch + offset; + + uint32_t time_low = static_cast(num_hundred_rfc); + uint16_t time_mid = static_cast(num_hundred_rfc >> 32); + uint16_t version = 0x1000; + uint16_t time_hi_and_version = static_cast(num_hundred_rfc >> (32 + 16)) | version; + + // Generate Clock Sequence ID based on random number + uint16_t clock_seq_and_reserved = (rand() % (1 << 14)) | 0x8000; + + boost::uuids::uuid uu = { + static_cast(time_low >> 24), static_cast(time_low >> 16), + static_cast(time_low >> 8), static_cast(time_low), + static_cast(time_mid >> 8), static_cast(time_mid), + static_cast(time_hi_and_version >> 8), + static_cast(time_hi_and_version), + static_cast(clock_seq_and_reserved >> 8), + static_cast(clock_seq_and_reserved), + static_cast(hw_addr >> 40), static_cast(hw_addr >> 32), + static_cast(hw_addr >> 24), static_cast(hw_addr >> 16), + static_cast(hw_addr >> 8), static_cast(hw_addr) + }; + return uu; + } + + } // end namespace impl + +} // end namespace unique_id + +#endif // _IMPL_UNIQUE_ID_H_ diff --git a/navigations/unique_identifier/unique_id/include/unique_id/unique_id.h b/navigations/unique_identifier/unique_id/include/unique_id/unique_id.h new file mode 100755 index 0000000..ceeefbb --- /dev/null +++ b/navigations/unique_identifier/unique_id/include/unique_id/unique_id.h @@ -0,0 +1,209 @@ +/* -*- mode: C++ -*- */ +/********************************************************************* +* Software License Agreement (BSD License) +* +* Copyright (C) 2012 Jack O'Quin +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of the author nor other contributors may be +* used to endorse or promote products derived from this software +* without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +*********************************************************************/ + +#ifndef _UNIQUE_ID_H_ +#define _UNIQUE_ID_H_ 1 + +/** @file + + @brief Helper functions for universally unique identifiers and messages. + + @author Jack O'Quin + */ + +#include + +#include +#include + +#include +#include + +#include // private implementation details + +/** @brief C++ namespace for unique_id helper functions. + * + * Various ROS components use universally unique identifiers. This + * header provides functions for working with a common + * uuid_msgs/UniqueID message, and the boost uuid class. + * + * - http://en.wikipedia.org/wiki/Uuid + * - http://tools.ietf.org/html/rfc4122.html + * - http://www.boost.org/doc/libs/1_42_0/libs/uuid/uuid.html + * + * Programmers are free to create UUID objects using any approved RFC + * 4122 method. The boost uuid interface supports them all. + * + * Functions in this namespace provide simple APIs, not requiring + * detailed knowledge of RFC 4122 or the boost uuid interface. ROS + * applications are likely to need either a random or a name-based + * UUID. + * + * - fromRandom() generates a random UUID. + * - fromURL() generates a name-based UUID from a URL string. + */ +namespace unique_id +{ + +/** @brief Create UUID object from UniqueID message. + * + * @param msg uuid_msgs/UniqueID message. + * @returns boost::uuids::uuid object. + */ +static inline boost::uuids::uuid fromMsg(uuid_msgs::UniqueID const &msg) +{ + boost::uuids::uuid uu{}; + std::copy(msg.uuid.begin(), msg.uuid.end(), uu.begin()); + return uu; +} + +/** @brief Generate a random UUID object. + * + * @returns type 4 boost::uuids::uuid object. + * + * Different calls to this function at any time or place will almost + * certainly generate different UUIDs. The method used is RFC 4122 + * variant 4. + */ +static inline boost::uuids::uuid fromRandom(void) +{ + return impl::genRandom(); +} + +/** @brief Generate UUID from canonical hex string. + * + * @param str string containing canonical hex representation + * @returns corresponding boost::uuids::uuid object. + * + * @note This is not a general service for generating a UUID from an + * arbitrary character string. The fromURL() function will do that + * for any Uniform Resource Identifier. + * + * The canonical hex string is a human-readable representation of a + * correctly-formatted sixteen-byte UUID. In addition to the dashes, + * it should contain exactly 32 hexadecimal digits. The @a str can + * be any accepted by the boost uuid string generator, but that is + * not well-defined. The format produced by toHexString() works + * reliably: "01234567-89ab-cdef-0123-456789abcdef". + * + * @warning Strings not accepted by boost may produce undefined + * results: perhaps throwing a @c std::runtime_error exception, or + * silently ignoring parts of the string. + */ +static inline boost::uuids::uuid fromHexString(std::string const &str) +{ + return impl::genString(str); +} + +/** @brief Generate UUID from Uniform Resource Identifier. + * + * @param url URL for identifier creation. + * @returns type 5 boost::uuids::uuid object. + * + * Matching @a url strings must yield the same UUID. Different @a url + * strings will almost certainly generate different UUIDs. The method + * used is RFC 4122 variant 5, computing the SHA-1 hash of the @a + * url. + * + * For any given @a url, this function returns the same UUID as the + * corresponding Python @c unique_id.fromURL() function. + * + * For example, Open Street Map identifiers are encoded like this, + * with decimal representations of the integer OSM node, way, or + * relation identifiers appended to the URL: + * + * - fromURL("http://openstreetmap.org/node/123456789") + * - fromURL("http://openstreetmap.org/way/6543210") + * - fromURL("http://openstreetmap.org/relation/999999") + */ +static inline boost::uuids::uuid fromURL(std::string const &url) +{ + return impl::genURL(url); +} + +/** @brief Generate a Time Based UUID object. Users are recommended to seed the random + * number generator using srand from the calling application to generate the clock_id + * + * @param timestamp The ros::Time timestamp for UUID generation + * @param hw_addr A 48-bit (6 octets) network address assigned to the 48 LSBs + * @returns type 1 boost::uuids::uuid object. + * + * Different calls to this function at any time or place will almost + * certainly generate different UUIDs. The method used is RFC 4122 + * version 1. + */ +static inline boost::uuids::uuid fromTime(ros::Time timestamp, uint64_t hw_addr) +{ + return impl::genTime(timestamp, hw_addr); +} + +/** @brief Create a UniqueID message from a UUID object. + * + * @param uu boost::uuids::uuid object. + * @returns uuid_msgs/UniqueID message. + */ +static inline uuid_msgs::UniqueID toMsg(boost::uuids::uuid const &uu) +{ + uuid_msgs::UniqueID msg; + std::copy(uu.begin(), uu.end(), msg.uuid.begin()); + return msg; +} + +/** @brief Get the canonical string representation for a boost UUID. + * + * @param uu boost::uuids::uuid object. + * @returns canonical UUID hex string: "01234567-89ab-cdef-0123-456789abcdef". + * + * A @c boost::uuids::uuid object yields the same representation via + * its @c << operator or @c to_string() function. + */ +static inline std::string toHexString(boost::uuids::uuid const &uu) +{ + return boost::uuids::to_string(uu); +} + +/** @brief Get the canonical string representation for a UniqueID message. + * + * @param msg uuid_msgs/UniqueID message. + * @returns canonical UUID hex string: "01234567-89ab-cdef-0123-456789abcdef". + */ +static inline std::string toHexString(uuid_msgs::UniqueID const &msg) +{ + return boost::uuids::to_string(fromMsg(msg)); +} + +} // end namespace unique_id + +#endif // _UNIQUE_ID_H_ diff --git a/navigations/unique_identifier/unique_id/index.rst b/navigations/unique_identifier/unique_id/index.rst new file mode 100755 index 0000000..987e57c --- /dev/null +++ b/navigations/unique_identifier/unique_id/index.rst @@ -0,0 +1,16 @@ +unique_id: ROS universally unique identifier support +==================================================== + +Contents: + +.. toctree:: + :maxdepth: 2 + + unique_id + CHANGELOG + +Indices and tables +================== + +* :ref:`genindex` +* :ref:`modindex` diff --git a/navigations/unique_identifier/unique_id/mainpage.dox b/navigations/unique_identifier/unique_id/mainpage.dox new file mode 100755 index 0000000..9169c2d --- /dev/null +++ b/navigations/unique_identifier/unique_id/mainpage.dox @@ -0,0 +1,13 @@ +/** +\mainpage +\htmlinclude manifest.html + +This package provides Python and C++ interfaces for managing +universally unique identifiers. + +There are no ROS nodes or commands. + +Note: For Time-Based UUID generation using the C++ interface + seed the random number generator through srand() + +*/ diff --git a/navigations/unique_identifier/unique_id/package.xml b/navigations/unique_identifier/unique_id/package.xml new file mode 100755 index 0000000..5c6915d --- /dev/null +++ b/navigations/unique_identifier/unique_id/package.xml @@ -0,0 +1,29 @@ + + + + + unique_id + 1.0.6 + + ROS Python and C++ interfaces for universally unique identifiers. + + Jack O'Quin + Jack O'Quin + BSD + http://ros.org/wiki/unique_id + + catkin + python-setuptools + python3-setuptools + + roscpp + rospy + uuid_msgs + + rosunit + + + + + + diff --git a/navigations/unique_identifier/unique_id/rosdoc.yaml b/navigations/unique_identifier/unique_id/rosdoc.yaml new file mode 100755 index 0000000..3f6b24f --- /dev/null +++ b/navigations/unique_identifier/unique_id/rosdoc.yaml @@ -0,0 +1,8 @@ + - builder: doxygen + name: C++ API + output_dir: c++ + file_patterns: '*.c *.cpp *.h *.cc *.hh *.dox' + - builder: sphinx + name: Python API + output_dir: python + diff --git a/navigations/unique_identifier/unique_id/setup.py b/navigations/unique_identifier/unique_id/setup.py new file mode 100755 index 0000000..79ac0db --- /dev/null +++ b/navigations/unique_identifier/unique_id/setup.py @@ -0,0 +1,11 @@ +#!/usr/bin/env python + +from setuptools import setup +from catkin_pkg.python_setup import generate_distutils_setup + +d = generate_distutils_setup( + packages=['unique_id'], + package_dir={'': 'src'}, + ) + +setup(**d) diff --git a/navigations/unique_identifier/unique_id/src/unique_id/__init__.py b/navigations/unique_identifier/unique_id/src/unique_id/__init__.py new file mode 100755 index 0000000..86eafb4 --- /dev/null +++ b/navigations/unique_identifier/unique_id/src/unique_id/__init__.py @@ -0,0 +1,146 @@ +# Software License Agreement (BSD License) +# +# Copyright (C) 2012, Jack O'Quin +# All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# * Redistributions in binary form must reproduce the above +# copyright notice, this list of conditions and the following +# disclaimer in the documentation and/or other materials provided +# with the distribution. +# * Neither the name of the author nor of other contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. + +""" +Python module for unique_id helper functions. + +Various ROS components use universally unique identifiers +(UUID_). This module provides functions for working with a common +`uuid_msgs/UniqueID`_ message, and the standard Python +:class:`uuid.UUID` class. + +Programmers are free to create UUID objects using any approved `RFC +4122`_ method. The standard Python :py:mod:`uuid` module supports them +all. + +Functions in this module provide simple APIs, not requiring detailed +knowledge of `RFC 4122`_ or the :py:mod:`uuid` interface. ROS +applications are likely to need either a random or a name-based UUID. + + * :func:`fromRandom` generates a random UUID. + * :func:`fromURL` generates a name-based UUID from a URL string. + +.. _`uuid_msgs/UniqueID`: http://ros.org/doc/api/uuid_msgs/html/msg/UniqueID.html +.. _`RFC 4122`: http://tools.ietf.org/html/rfc4122.html +.. _UUID: http://en.wikipedia.org/wiki/Uuid + +""" + +# enable some python3 compatibility options: +from __future__ import absolute_import, print_function, unicode_literals + +from uuid_msgs.msg import UniqueID + +import uuid + +def fromMsg(msg): + """Create UUID object from UniqueID message. + + :param msg: `uuid_msgs/UniqueID`_ message. + :returns: :class:`uuid.UUID` object. + """ + return uuid.UUID(bytes = msg.uuid) + +def fromRandom(): + """Generate a random UUID object. + + :returns: type 4 :class:`uuid.UUID` object. + + Different calls to this function at any time or place will almost + certainly generate different UUIDs. The method used is `RFC 4122`_ + variant 4. + """ + return uuid.uuid4() + +def fromURL(url): + """Generate UUID from Uniform Resource Locator. + + :param url: URL for identifier creation. + :returns: type 5 :class:`uuid.UUID` object. + + Matching *url* strings must yield the same UUID. Different *url* + strings will almost certainly generate different UUIDs. The method + used is `RFC 4122`_ variant 5, computing the SHA-1 hash of the + *url*. + + For any given *url*, this function returns the same UUID as the + corresponding C++ `unique_id::fromURL()` function. + + For example, Open Street Map identifiers are encoded like this, + with decimal representations of the integer OSM node, way, or + relation identifiers appended to the URL:: + + fromURL('http://openstreetmap.org/node/' + str(node_id)) + fromURL('http://openstreetmap.org/way/' + str(way_id)) + fromURL('http://openstreetmap.org/relation/' + str(rel_id)) + + """ + return uuid.uuid5(uuid.NAMESPACE_URL, url) + +def fromTime(timestamp, hw_addr): + """Generate a Time Based UUID object. + + :param timestamp: The rospy.Time timestamp for UUID generation + :param hw_addr: A 48-bit long representing the network address + :returns: type 1 :class:`uuid.UUID` object + + Different calls to this function at any time or place will almost + certainly generate different UUIDs. The method used is RFC 4122 + version 1. + """ + uu = uuid.uuid1(hw_addr) + offset = 122192928000000000 + nano_epoch = long(timestamp.secs / (100 * 1e-9) + timestamp.nsecs / 100) + # return nano_epoch + nano_rfc = nano_epoch + offset + data = (nano_rfc & 0x0000000FFFFFFFF, (nano_rfc >> 32) & 0x000FFFF, (nano_rfc >> 48) | 0x1000, + uu.fields[3], uu.fields[4], uu.fields[5]) + return uuid.UUID(fields=data) + +def toMsg(uuid_obj): + """Create a UniqueID message from a UUID object. + + :param uuid_obj: standard Python :class:`uuid.UUID` object. + :returns: `uuid_msgs/UniqueID`_ message. + """ + return UniqueID(uuid = uuid_obj.bytes) + +def toHexString(msg): + """Get the canonical hexadecimal string representation for a UniqueID message. + + :param msg: `uuid_msgs/UniqueID`_ message. + :returns: UUID hex string: '01234567-89ab-cdef-0123-456789abcdef'. + + A :class:`uuid.UUID` object yields the same representation via the + :py:func:`str` function. + """ + return str(fromMsg(msg)) diff --git a/navigations/unique_identifier/unique_id/tests/CMakeLists.txt b/navigations/unique_identifier/unique_id/tests/CMakeLists.txt new file mode 100755 index 0000000..057b870 --- /dev/null +++ b/navigations/unique_identifier/unique_id/tests/CMakeLists.txt @@ -0,0 +1,15 @@ +### Unit tests +# +# Only configured when CATKIN_ENABLE_TESTING is true. + +# C++ gtests +catkin_add_gtest(test_${PROJECT_NAME} + test_${PROJECT_NAME}.cpp + second_test_${PROJECT_NAME}.cpp) +add_dependencies(test_${PROJECT_NAME} ${catkin_EXPORTED_TARGETS}) +target_link_libraries(test_${PROJECT_NAME} + ${Boost_LIBRARIES} + ${catkin_LIBRARIES}) + +# Python nose tests +catkin_add_nosetests(test_${PROJECT_NAME}.py) diff --git a/navigations/unique_identifier/unique_id/tests/second_test_unique_id.cpp b/navigations/unique_identifier/unique_id/tests/second_test_unique_id.cpp new file mode 100755 index 0000000..2f2a711 --- /dev/null +++ b/navigations/unique_identifier/unique_id/tests/second_test_unique_id.cpp @@ -0,0 +1,193 @@ +// +// A second C++ unit test for unique_id interface, which must be able +// to be included in more than one source file. +// + +#include + +#include + +using namespace unique_id; +typedef boost::uuids::uuid uuid; +typedef uuid_msgs::UniqueID UniqueID; + +/////////////////////////////////////////////////////////////// +// Test cases +/////////////////////////////////////////////////////////////// + +// Test random generator +TEST(BoostUUID2, fromRandom) +{ + static const int N = 1000; + uuid uu[N]; + for (int i = 0; i < N; ++i) + { + uu[i] = fromRandom(); + for (int j = i-1; j >= 0; --j) + { + EXPECT_NE(uu[i], uu[j]); + } + } +} + +TEST(BoostUUID2, emptyURL) +{ + std::string s; + uuid x = fromURL(s); + uuid y = fromURL(s); + EXPECT_EQ(x, y); + // MUST yield same result as Python fromURL() function: + EXPECT_EQ(toHexString(x), "1b4db7eb-4057-5ddf-91e0-36dec72071f5"); +} + +TEST(BoostUUID2, sameURL) +{ + std::string s("http://openstreetmap.org/node/1"); + uuid x = fromURL(s); + uuid y = fromURL(s); + EXPECT_EQ(x, y); + // MUST yield same result as Python fromURL() function: + EXPECT_EQ(toHexString(x), "ef362ac8-9659-5481-b954-88e9b741c8f9"); +} + +TEST(BoostUUID2, differentOsmNamespace) +{ + uuid x = fromURL("http://openstreetmap.org/node/1"); + uuid y = fromURL("http://openstreetmap.org/way/1"); + EXPECT_NE(x, y); + // MUST yield same result as Python fromURL() function: + EXPECT_EQ(toHexString(y), "b3180681-b125-5e41-bd04-3c8b046175b4"); +} + +TEST(BoostUUID2, actualOsmNode) +{ + uuid x = fromURL("http://openstreetmap.org/node/1"); + uuid y = fromURL("http://openstreetmap.org/node/152370223"); + EXPECT_NE(x, y); + // MUST yield same result as Python fromURL() function: + EXPECT_EQ(toHexString(y), "8e0b7d8a-c433-5c42-be2e-fbd97ddff9ac"); +} + +TEST(BoostUUID2, fromHexString) +{ + std::string s("da7c242f-2efe-5175-9961-49cc621b80b9"); + std::string r = toHexString(fromHexString(s)); + EXPECT_EQ(s, r); +} + +TEST(BoostUUID2, fromStringNoDashes) +{ + std::string s("da7c242f-2efe-5175-9961-49cc621b80b9"); + std::string s_hex("da7c242f2efe5175996149cc621b80b9"); + std::string r = toHexString(fromHexString(s_hex)); + EXPECT_EQ(s, r); +} + +TEST(BoostUUID2, fromBracesString) +{ + std::string s("da7c242f-2efe-5175-9961-49cc621b80b9"); + std::string s_braces = "{" + s + "}"; + std::string r = toHexString(fromHexString(s_braces)); + EXPECT_EQ(s, r); +} + +TEST(BoostUUID2, fromUrnString) +{ + // This documents boost 1.46.1 behavior, but is an undefined + // fromHexString() input, not really a valid test case. + std::string s("da7c242f-2efe-5175-9961-49cc621b80b9"); + std::string s_urn = "urn:uuid:" + s; + std::string r = toHexString(fromHexString(s_urn)); + EXPECT_NE(s, r); +} + +TEST(BoostUUID2, fromTooLongString) +{ + // This documents boost 1.46.1 behavior, but is an undefined + // fromHexString() input, not really a valid test case. + std::string s("da7c242f-2efe-5175-9961-49cc621b80b9"); + std::string s_too_long = s + "-0001"; + std::string r = toHexString(fromHexString(s_too_long)); + EXPECT_EQ(s, r); +} + +TEST(BoostUUID2, fromTooShortString) +{ + // This documents boost 1.46.1 behavior, but is an undefined + // fromHexString() input, not really a valid test case. + std::string s("da7c242f-2efe-5175-9961-49cc621b80"); + try + { + uuid x = fromHexString(s); + FAIL(); // expected exception not thrown + EXPECT_NE(toHexString(x), s); + } + catch (std::runtime_error &e) + { + EXPECT_EQ(e.what(), std::string("invalid uuid string")); + } + catch (...) + { + FAIL(); // unexpected exception + } +} + +TEST(BoostUUID2, fromBogusString) +{ + // This documents boost 1.46.1 behavior, but is an undefined + // fromHexString() input, not really a valid test case. + std::string s("Invalid UUID string"); + try + { + uuid x = fromHexString(s); + FAIL(); // expected exception not thrown + EXPECT_NE(toHexString(x), s); + } + catch (std::runtime_error &e) + { + EXPECT_EQ(e.what(), std::string("invalid uuid string")); + } + catch (...) + { + FAIL(); // unexpected exception + } +} + +TEST(UniqueID2, nilMessage) +{ + UniqueID x; + UniqueID y = toMsg(uuid()); + EXPECT_EQ(x.uuid, y.uuid); +} + +TEST(UniqueID2, randomMessage) +{ + UniqueID x; + UniqueID y = toMsg(fromRandom()); + EXPECT_NE(x.uuid, y.uuid); +} + +TEST(UniqueID2, equivalentMessages) +{ + std::string s("da7c242f-2efe-5175-9961-49cc621b80b9"); + UniqueID x = toMsg(fromHexString(s)); + UniqueID y = toMsg(fromHexString(s)); + EXPECT_EQ(x.uuid, y.uuid); + EXPECT_EQ(s, toHexString(y)); +} + +TEST(UniqueID2, toAndFromMessage) +{ + std::string s("da7c242f-2efe-5175-9961-49cc621b80b9"); + uuid x = uuid(fromHexString(s)); + uuid y = fromMsg(toMsg(x)); + EXPECT_EQ(x, y); +} + +TEST(UniqueID2, messageToString) +{ + std::string s("da7c242f-2efe-5175-9961-49cc621b80b9"); + UniqueID x = toMsg(fromHexString(s)); + std::string y = toHexString(x); + EXPECT_EQ(s, y); +} diff --git a/navigations/unique_identifier/unique_id/tests/test_unique_id.cpp b/navigations/unique_identifier/unique_id/tests/test_unique_id.cpp new file mode 100755 index 0000000..f32c305 --- /dev/null +++ b/navigations/unique_identifier/unique_id/tests/test_unique_id.cpp @@ -0,0 +1,327 @@ +// +// C++ unit tests for unique_id interface. +// +#include + +#include +#include + +using namespace unique_id; +typedef boost::uuids::uuid uuid; +typedef uuid_msgs::UniqueID UniqueID; + +/////////////////////////////////////////////////////////////// +// Test cases +/////////////////////////////////////////////////////////////// + +// Test random generator +TEST(BoostUUID, fromRandom) +{ + static const int N = 1000; + uuid uu[N]; + for (int i = 0; i < N; ++i) + { + uu[i] = fromRandom(); + for (int j = i-1; j >= 0; --j) + { + EXPECT_NE(uu[i], uu[j]); + } + } +} + +// Test Timebased UUID +TEST(BoostUUID, fromTime) +{ + ros::Time t(1515778146, 239216089); + uint64_t hw_addr = 0xAABBCCDDEEFF; + + // Generate UUID from time and hardware address + uuid uu = fromTime(t, hw_addr); + + // Obtain time since epoch back from the generated uuid + std::vector data(uu.size()); + std::copy(uu.begin(), uu.end(), data.begin()); + + uint64_t timestamp = (static_cast(data[0]) << 24) + (static_cast(data[1]) << 16) + + (static_cast(data[2]) << 8) + static_cast(data[3]) + + (static_cast(data[4]) << 40) + (static_cast(data[5]) << 32) + + (static_cast(data[6] & 0x0F) << 56) + (static_cast(data[7]) << 48); + uint64_t offset = 122192928000000000; // time offset in 100 ns intervals between RFC4122 Timestamp and Epoch Time + uint64_t ns_intervals = timestamp - offset; + uint64_t uu_hw_addr = 0; + for (int8_t i=0; i < 6; i++) + { + uu_hw_addr += static_cast(data[uu.size() - 1 - i]) << 8*i; + } + + ros::Time uu_time; + uu_time.sec = static_cast(ns_intervals / 1e9 * 100); + uu_time.nsec = static_cast((ns_intervals - static_cast(uu_time.sec) / (100 * 1e-9)) * 100); + + EXPECT_EQ(t.sec, uu_time.sec); + // The UUID stores the timestamp in 100ns intervals, + // so we lose precision for the 1's and 10's value of the nanoseconds in the time given + EXPECT_EQ(t.nsec - uu_time.nsec, 89); + EXPECT_EQ(hw_addr, uu_hw_addr); +} + +TEST(BoostUUID, timeWithinSameInterval) +{ + ros::Time t1(1515778146, 239216020); + ros::Time t2(1515778146, 239216080); + uint64_t hw_addr = 0xAABBCCDDEEFF; + + // Generate UUIDs from times and hardware address + uuid uu1 = fromTime(t1, hw_addr); + uuid uu2 = fromTime(t2, hw_addr); + + // Obtain times since epoch back from uu1 + std::vector data(uu1.size()); + std::copy(uu1.begin(), uu1.end(), data.begin()); + + uint64_t timestamp = (static_cast(data[0]) << 24) + (static_cast(data[1]) << 16) + + (static_cast(data[2]) << 8) + static_cast(data[3]) + + (static_cast(data[4]) << 40) + (static_cast(data[5]) << 32) + + (static_cast(data[6] & 0x0F) << 56) + (static_cast(data[7]) << 48); + uint64_t offset = 122192928000000000; // time offset in 100 ns intervals between RFC4122 Timestamp and Epoch Time + uint64_t ns_intervals = timestamp - offset; + + ros::Time uu1_time; + uu1_time.sec = static_cast(ns_intervals / 1e9 * 100); + uu1_time.nsec = static_cast((ns_intervals - static_cast(uu1_time.sec) / (100 * 1e-9)) * 100); + + // Obtain times since epoch back from uu2 + std::copy(uu2.begin(), uu2.end(), data.begin()); + + timestamp = (static_cast(data[0]) << 24) + (static_cast(data[1]) << 16) + + (static_cast(data[2]) << 8) + static_cast(data[3]) + + (static_cast(data[4]) << 40) + (static_cast(data[5]) << 32) + + (static_cast(data[6] & 0x0F) << 56) + (static_cast(data[7]) << 48); + ns_intervals = timestamp - offset; + + ros::Time uu2_time; + uu2_time.sec = static_cast(ns_intervals / 1e9 * 100); + uu2_time.nsec = static_cast((ns_intervals - static_cast(uu2_time.sec) / (100 * 1e-9)) * 100); + + // Compare + // Since both timestamps were in the same 100ns interval, should get same timestamp + EXPECT_EQ(uu1_time.sec, uu2_time.sec); + EXPECT_EQ(uu1_time.nsec, uu2_time.nsec); + + // While timestamps are the same, the clock_id is a randomly generated 14-bit value + // So, we should still expect the uuids generated to be different + EXPECT_NE(uu1, uu2); +} + +TEST(BoostUUID, timeWithinDifferentInterval) +{ + ros::Time t1(1515778146, 239216020); + ros::Time t2(1515778146, 239216120); + uint64_t hw_addr = 0xAABBCCDDEEFF; + + // Generate UUIDs from times and hardware address + uuid uu1 = fromTime(t1, hw_addr); + uuid uu2 = fromTime(t2, hw_addr); + + // Obtain times since epoch back from uu1 + std::vector data(uu1.size()); + std::copy(uu1.begin(), uu1.end(), data.begin()); + + uint64_t timestamp = (static_cast(data[0]) << 24) + (static_cast(data[1]) << 16) + + (static_cast(data[2]) << 8) + static_cast(data[3]) + + (static_cast(data[4]) << 40) + (static_cast(data[5]) << 32) + + (static_cast(data[6] & 0x0F) << 56) + (static_cast(data[7]) << 48); + uint64_t offset = 122192928000000000; // time offset in 100 ns intervals between RFC4122 Timestamp and Epoch Time + uint64_t ns_intervals = timestamp - offset; + + ros::Time uu1_time; + uu1_time.sec = static_cast(ns_intervals / 1e9 * 100); + uu1_time.nsec = static_cast((ns_intervals - static_cast(uu1_time.sec) / (100 * 1e-9)) * 100); + + // Obtain times since epoch back from uu2 + std::copy(uu2.begin(), uu2.end(), data.begin()); + + timestamp = (static_cast(data[0]) << 24) + (static_cast(data[1]) << 16) + + (static_cast(data[2]) << 8) + static_cast(data[3]) + + (static_cast(data[4]) << 40) + (static_cast(data[5]) << 32) + + (static_cast(data[6] & 0x0F) << 56) + (static_cast(data[7]) << 48); + ns_intervals = timestamp - offset; + + ros::Time uu2_time; + uu2_time.sec = static_cast(ns_intervals / 1e9 * 100); + uu2_time.nsec = static_cast((ns_intervals - static_cast(uu2_time.sec) / (100 * 1e-9)) * 100); + + // Compare + // Since both timestamps were in different 100ns intervals, should get different timestamps (at the ns level) + EXPECT_EQ(uu1_time.sec, uu2_time.sec); + EXPECT_NE(uu1_time.nsec, uu2_time.nsec); +} + +TEST(BoostUUID, emptyURL) +{ + std::string s; + uuid x = fromURL(s); + uuid y = fromURL(s); + EXPECT_EQ(x, y); + // MUST yield same result as Python fromURL() function: + EXPECT_EQ(toHexString(x), "1b4db7eb-4057-5ddf-91e0-36dec72071f5"); +} + +TEST(BoostUUID, sameURL) +{ + std::string s("http://openstreetmap.org/node/1"); + uuid x = fromURL(s); + uuid y = fromURL(s); + EXPECT_EQ(x, y); + // MUST yield same result as Python fromURL() function: + EXPECT_EQ(toHexString(x), "ef362ac8-9659-5481-b954-88e9b741c8f9"); +} + +TEST(BoostUUID, differentOsmNamespace) +{ + uuid x = fromURL("http://openstreetmap.org/node/1"); + uuid y = fromURL("http://openstreetmap.org/way/1"); + EXPECT_NE(x, y); + // MUST yield same result as Python fromURL() function: + EXPECT_EQ(toHexString(y), "b3180681-b125-5e41-bd04-3c8b046175b4"); +} + +TEST(BoostUUID, actualOsmNode) +{ + uuid x = fromURL("http://openstreetmap.org/node/1"); + uuid y = fromURL("http://openstreetmap.org/node/152370223"); + EXPECT_NE(x, y); + // MUST yield same result as Python fromURL() function: + EXPECT_EQ(toHexString(y), "8e0b7d8a-c433-5c42-be2e-fbd97ddff9ac"); +} + +TEST(BoostUUID, fromHexString) +{ + std::string s("da7c242f-2efe-5175-9961-49cc621b80b9"); + std::string r = toHexString(fromHexString(s)); + EXPECT_EQ(s, r); +} + +TEST(BoostUUID, fromStringNoDashes) +{ + std::string s("da7c242f-2efe-5175-9961-49cc621b80b9"); + std::string s_hex("da7c242f2efe5175996149cc621b80b9"); + std::string r = toHexString(fromHexString(s_hex)); + EXPECT_EQ(s, r); +} + +TEST(BoostUUID, fromBracesString) +{ + std::string s("da7c242f-2efe-5175-9961-49cc621b80b9"); + std::string s_braces = "{" + s + "}"; + std::string r = toHexString(fromHexString(s_braces)); + EXPECT_EQ(s, r); +} + +TEST(BoostUUID, fromUrnString) +{ + // This documents boost 1.46.1 behavior, but is an undefined + // fromHexString() input, not really a valid test case. + std::string s("da7c242f-2efe-5175-9961-49cc621b80b9"); + std::string s_urn = "urn:uuid:" + s; + std::string r = toHexString(fromHexString(s_urn)); + EXPECT_NE(s, r); +} + +TEST(BoostUUID, fromTooLongString) +{ + // This documents boost 1.46.1 behavior, but is an undefined + // fromHexString() input, not really a valid test case. + std::string s("da7c242f-2efe-5175-9961-49cc621b80b9"); + std::string s_too_long = s + "-0001"; + std::string r = toHexString(fromHexString(s_too_long)); + EXPECT_EQ(s, r); +} + +TEST(BoostUUID, fromTooShortString) +{ + // This documents boost 1.46.1 behavior, but is an undefined + // fromHexString() input, not really a valid test case. + std::string s("da7c242f-2efe-5175-9961-49cc621b80"); + try + { + uuid x = fromHexString(s); + FAIL(); // expected exception not thrown + EXPECT_NE(toHexString(x), s); + } + catch (std::runtime_error &e) + { + EXPECT_EQ(e.what(), std::string("invalid uuid string")); + } + catch (...) + { + FAIL(); // unexpected exception + } +} + +TEST(BoostUUID, fromBogusString) +{ + // This documents boost 1.46.1 behavior, but is an undefined + // fromHexString() input, not really a valid test case. + std::string s("Invalid UUID string"); + try + { + uuid x = fromHexString(s); + FAIL(); // expected exception not thrown + EXPECT_NE(toHexString(x), s); + } + catch (std::runtime_error &e) + { + EXPECT_EQ(e.what(), std::string("invalid uuid string")); + } + catch (...) + { + FAIL(); // unexpected exception + } +} + +TEST(UniqueID, nilMessage) +{ + UniqueID x; + UniqueID y = toMsg(uuid()); + EXPECT_EQ(x.uuid, y.uuid); +} + +TEST(UniqueID, randomMessage) +{ + UniqueID x; + UniqueID y = toMsg(fromRandom()); + EXPECT_NE(x.uuid, y.uuid); +} + +TEST(UniqueID, equivalentMessages) +{ + std::string s("da7c242f-2efe-5175-9961-49cc621b80b9"); + UniqueID x = toMsg(fromHexString(s)); + UniqueID y = toMsg(fromHexString(s)); + EXPECT_EQ(x.uuid, y.uuid); + EXPECT_EQ(s, toHexString(y)); +} + +TEST(UniqueID, toAndFromMessage) +{ + std::string s("da7c242f-2efe-5175-9961-49cc621b80b9"); + uuid x = uuid(fromHexString(s)); + uuid y = fromMsg(toMsg(x)); + EXPECT_EQ(x, y); +} + +TEST(UniqueID, messageToString) +{ + std::string s("da7c242f-2efe-5175-9961-49cc621b80b9"); + UniqueID x = toMsg(fromHexString(s)); + std::string y = toHexString(x); + EXPECT_EQ(s, y); +} + +// Run all the tests that were declared with TEST() +int main(int argc, char **argv) +{ + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/navigations/unique_identifier/unique_id/tests/test_unique_id.py b/navigations/unique_identifier/unique_id/tests/test_unique_id.py new file mode 100755 index 0000000..94171cf --- /dev/null +++ b/navigations/unique_identifier/unique_id/tests/test_unique_id.py @@ -0,0 +1,202 @@ +#!/usr/bin/env python + +# enable some python3 compatibility options: +# (unicode_literals not compatible with python2 uuid module) +from __future__ import absolute_import, print_function + +import sys +import unittest + +import uuid # standard Python module + +import rospy +from uuid_msgs.msg import UniqueID +from unique_id import * + +class TestPythonUUID(unittest.TestCase): + """Unit tests for Python UUID generation. + """ + + # random UUID generation tests + def test_random_uuids(self): + N = 1000 + uu = [] + for i in xrange(N): + uu.append(fromRandom()) + self.assertEqual(type(uu[i]), uuid.UUID) + for j in xrange(i-1, -1, -1): + self.assertNotEqual(uu[i], uu[j]) + + # UUID generation from URL tests + def test_empty_url(self): + x = fromURL('') + self.assertEqual(type(x), uuid.UUID) + y = fromURL('') + self.assertEqual(type(y), uuid.UUID) + self.assertEqual(x, y) + # MUST yield same result as C++ fromURL() function: + self.assertEqual(str(x), "1b4db7eb-4057-5ddf-91e0-36dec72071f5") + + def test_same_url(self): + x = fromURL('http://openstreetmap.org/node/1') + self.assertEqual(type(x), uuid.UUID) + y = fromURL('http://openstreetmap.org/node/1') + self.assertEqual(type(y), uuid.UUID) + self.assertEqual(x, y) + # MUST yield same result as C++ fromURL() function: + self.assertEqual(str(x), 'ef362ac8-9659-5481-b954-88e9b741c8f9') + + def test_same_id_different_osm_namespace(self): + x = fromURL('http://openstreetmap.org/node/1') + y = fromURL('http://openstreetmap.org/way/1') + self.assertNotEqual(x, y) + # MUST yield same result as C++ fromURL() function: + self.assertEqual(str(y), 'b3180681-b125-5e41-bd04-3c8b046175b4') + + def test_actual_osm_node_id(self): + x = fromURL('http://openstreetmap.org/node/1') + y = fromURL('http://openstreetmap.org/node/152370223') + self.assertNotEqual(x, y) + # MUST yield same result as C++ fromURL() function: + self.assertEqual(str(y), '8e0b7d8a-c433-5c42-be2e-fbd97ddff9ac') + + def test_route_segment(self): + start = 'da7c242f-2efe-5175-9961-49cc621b80b9' + end = '812f1c08-a34b-5a21-92b9-18b2b0cf4950' + x = fromURL('http://ros.org/wiki/road_network/' + start + '/' + end) + y = fromURL('http://ros.org/wiki/road_network/' + end + '/' + start) + self.assertNotEqual(x, y) + # MUST yield same result as C++ fromURL() function: + self.assertEqual(str(x), 'acaa906e-8411-5b45-a446-ccdc2fc39f29') + + # UniqueID message generation tests + def test_msg_creation(self): + msg = toMsg(fromURL('http://openstreetmap.org/node/152370223')) + self.assertEqual(toHexString(msg), + '8e0b7d8a-c433-5c42-be2e-fbd97ddff9ac') + + def test_msg_same_id_different_namespace(self): + x = toMsg(fromURL('http://openstreetmap.org/node/1')) + y = toMsg(fromURL('http://openstreetmap.org/way/1')) + self.assertNotEqual(x, y) + self.assertEqual(toHexString(y), + 'b3180681-b125-5e41-bd04-3c8b046175b4') + + def test_msg_route_segment(self): + start = 'da7c242f-2efe-5175-9961-49cc621b80b9' + end = '812f1c08-a34b-5a21-92b9-18b2b0cf4950' + x = toMsg(fromURL('http://ros.org/wiki/road_network/' + + start + '/' + end)) + y = toMsg(fromURL('http://ros.org/wiki/road_network/' + + end + '/' + start)) + self.assertNotEqual(x, y) + self.assertEqual(toHexString(x), + 'acaa906e-8411-5b45-a446-ccdc2fc39f29') + + def test_nil_msg(self): + x = UniqueID() + y = toMsg(uuid.UUID(hex='00000000-0000-0000-0000-000000000000')) + self.assertEqual(x, y) + + def test_random_msg(self): + x = UniqueID() + y = toMsg(fromRandom()) + self.assertNotEqual(x, y) + + def test_equivalent_msgs(self): + s = 'da7c242f-2efe-5175-9961-49cc621b80b9' + x = toMsg(uuid.UUID(s)) + y = toMsg(uuid.UUID(s)) + self.assertEqual(x, y) + self.assertEqual(s, toHexString(y)) + + def test_to_and_from_msg(self): + x = uuid.UUID('da7c242f-2efe-5175-9961-49cc621b80b9') + y = (fromMsg(toMsg(x))) + self.assertEqual(x, y) + self.assertEqual(type(y), uuid.UUID) + + def test_msg_to_string(self): + s = 'da7c242f-2efe-5175-9961-49cc621b80b9' + x = toMsg(uuid.UUID(s)) + y = toHexString(x) + self.assertEqual(s, y) + self.assertEqual(type(y), str) + + # UUID Time-Based Generation + def test_time(self): + hw_addr = 0xAABBCCDDEEFF + t = rospy.Time(1515778146, 239216089) + uu = fromTime(t, hw_addr) # generate UUID + offset = 122192928000000000 # in 100ns intervals between RFC4122 timestamp and epoch time + ns_intervals_rfc = uu.fields[0] + (uu.fields[1] << 32) + ((uu.fields[2] & 0x0FFF) << 48) + ns_intervals_epoch = ns_intervals_rfc - offset + uu_time = rospy.Time() + uu_time.secs = long(ns_intervals_epoch / 1e9 * 100) + uu_time.nsecs = long(ns_intervals_epoch - uu_time.secs / (100 * 1e-9)) * 100 + + self.assertEqual(t.secs, uu_time.secs) + # Expect 89ns to be shaved off due to timestamp being stored in 100ns intervals + self.assertEqual(t.nsecs - uu_time.nsecs, 89) + # Should be able to retrieve the hardware id + self.assertEqual(hw_addr, uu.fields[5]) + + def test_time_same_interval(self): + hw_addr = 0xAABBCCDDEEFF + t1 = rospy.Time(1515778146, 239216020) + t2 = rospy.Time(1515778146, 239216080) + uu1 = fromTime(t1, hw_addr) # generate UUID for t1 + uu2 = fromTime(t2, hw_addr) # generate UUID for t2 + offset = 122192928000000000 # in 100ns intervals between RFC4122 timestamp and epoch time + + # Get time associated with uuid uu1 + ns_intervals_rfc = uu1.fields[0] + (uu1.fields[1] << 32) + ((uu1.fields[2] & 0x0FFF) << 48) + ns_intervals_epoch = ns_intervals_rfc - offset + uu1_time = rospy.Time() + uu1_time.secs = long(ns_intervals_epoch / 1e9 * 100) + uu1_time.nsecs = long(ns_intervals_epoch - uu1_time.secs / (100 * 1e-9)) * 100 + + # Get time associated with uuid uu2 + ns_intervals_rfc = uu2.fields[0] + (uu2.fields[1] << 32) + ((uu2.fields[2] & 0x0FFF) << 48) + ns_intervals_epoch = ns_intervals_rfc - offset + uu2_time = rospy.Time() + uu2_time.secs = long(ns_intervals_epoch / 1e9 * 100) + uu2_time.nsecs = long(ns_intervals_epoch - uu2_time.secs / (100 * 1e-9)) * 100 + + self.assertEqual(uu1_time.secs, uu2_time.secs) + # Timestamps should be same as they were generated for timestamps in the same 100ns interval + self.assertEqual(uu1_time.nsecs, uu2_time.nsecs) + # UUIDs should be different due to different (hopefully) randomly generated 14-bit clock ids + self.assertNotEqual(uu1, uu2) + + def test_time_different_interval(self): + hw_addr = 0xAABBCCDDEEFF + t1 = rospy.Time(1515778146, 239216020) + t2 = rospy.Time(1515778146, 239216120) + uu1 = fromTime(t1, hw_addr) # generate UUID for t1 + uu2 = fromTime(t2, hw_addr) # generate UUID for t2 + offset = 122192928000000000 # in 100ns intervals between RFC4122 timestamp and epoch time + + # Get time associated with uuid uu1 + ns_intervals_rfc = uu1.fields[0] + (uu1.fields[1] << 32) + ((uu1.fields[2] & 0x0FFF) << 48) + ns_intervals_epoch = ns_intervals_rfc - offset + uu1_time = rospy.Time() + uu1_time.secs = long(ns_intervals_epoch / 1e9 * 100) + uu1_time.nsecs = long(ns_intervals_epoch - uu1_time.secs / (100 * 1e-9)) * 100 + + # Get time associated with uuid uu2 + ns_intervals_rfc = uu2.fields[0] + (uu2.fields[1] << 32) + ((uu2.fields[2] & 0x0FFF) << 48) + ns_intervals_epoch = ns_intervals_rfc - offset + uu2_time = rospy.Time() + uu2_time.secs = long(ns_intervals_epoch / 1e9 * 100) + uu2_time.nsecs = long(ns_intervals_epoch - uu2_time.secs / (100 * 1e-9)) * 100 + + # Timestamps were generated for the same second + self.assertEqual(uu1_time.secs, uu2_time.secs) + # Timestamps should be different as they were generated for times in different 100ns intervals + self.assertNotEqual(uu1_time.nsecs, uu2_time.nsecs) + + +if __name__ == '__main__': + import rosunit + rosunit.unitrun('unique_id', 'test_uuid_py', TestPythonUUID) diff --git a/navigations/unique_identifier/unique_id/unique_id.rst b/navigations/unique_identifier/unique_id/unique_id.rst new file mode 100755 index 0000000..d78213c --- /dev/null +++ b/navigations/unique_identifier/unique_id/unique_id.rst @@ -0,0 +1,5 @@ +unique_id +--------- + +.. automodule:: unique_id + :members: diff --git a/navigations/unique_identifier/unique_identifier/CHANGELOG.rst b/navigations/unique_identifier/unique_identifier/CHANGELOG.rst new file mode 100755 index 0000000..876c094 --- /dev/null +++ b/navigations/unique_identifier/unique_identifier/CHANGELOG.rst @@ -0,0 +1,49 @@ +Change history +============== + +1.0.6 (2017-04-04) +------------------ + +1.0.5 (2015-04-17) +------------------ + +1.0.4 (2014-04-30) +------------------ + + * add architecture independent tag + +1.0.3 (2013-07-24) +------------------ + +1.0.2 (2013-07-18) +------------------- + + * Add missing metapackage dependency on catkin (`#5`_). + +1.0.1 (2013-03-25) +------------------- + + * Hydro release update. + +1.0.0 (2013-03-18) +------------------- + + * Hydro release. + * Convert to catkin (`#1`_). + * Make **unique_identifier** into a metapackage, depending on the + **uuid_msgs** and **unique_id** packages. It should only be used + for dependencies in dry stacks. Wet packages will depend directly + on **uuid_msgs** and **unique_id**. + +0.9.0 (2013-01-03) +------------------ + + * Initial release to Groovy. + +0.8.0 (2012-07-19) +------------------ + + * Initial release to Fuerte. + +.. _`#1`: https://github.com/ros-geographic-info/unique_identifier/issues/1 +.. _`#5`: https://github.com/ros-geographic-info/unique_identifier/issues/5 diff --git a/navigations/unique_identifier/unique_identifier/CMakeLists.txt b/navigations/unique_identifier/unique_identifier/CMakeLists.txt new file mode 100755 index 0000000..135f2c8 --- /dev/null +++ b/navigations/unique_identifier/unique_identifier/CMakeLists.txt @@ -0,0 +1,4 @@ +cmake_minimum_required(VERSION 2.8.3) +project(unique_identifier) +find_package(catkin REQUIRED) +catkin_metapackage() diff --git a/navigations/unique_identifier/unique_identifier/package.xml b/navigations/unique_identifier/unique_identifier/package.xml new file mode 100755 index 0000000..962a70d --- /dev/null +++ b/navigations/unique_identifier/unique_identifier/package.xml @@ -0,0 +1,30 @@ + + + + + unique_identifier + 1.0.6 + + ROS messages and interfaces for universally unique identifiers. + + Not needed for wet packages, use only to resolve dry stack + dependencies. + + Jack O'Quin + Jack O'Quin + BSD + http://ros.org/wiki/unique_identifier + https://github.com/ros-geographic-info/unique_identifier + https://github.com/ros-geographic-info/unique_identifier/issues + + catkin + + unique_id + uuid_msgs + + + + + + + diff --git a/navigations/unique_identifier/uuid_msgs/CHANGELOG.rst b/navigations/unique_identifier/uuid_msgs/CHANGELOG.rst new file mode 100755 index 0000000..5763ace --- /dev/null +++ b/navigations/unique_identifier/uuid_msgs/CHANGELOG.rst @@ -0,0 +1,43 @@ +Change history +============== + +1.0.6 (2017-04-04) +------------------ + +1.0.5 (2015-04-17) +------------------ + +1.0.4 (2014-04-30) +------------------ + + * add architecture independent tag + +1.0.3 (2013-07-24) +------------------ + +1.0.2 (2013-07-18) +------------------- + +1.0.1 (2013-03-25) +------------------- + + * Hydro release update. + +1.0.0 (2013-03-18) +------------------- + + * Hydro release. + * Convert to catkin (`#1`_). + +0.9.0 (2013-01-03) +------------------ + + * Initial release to Groovy. + +0.8.0 (2012-07-19) +------------------ + + * Initial release to Fuerte. + * Provides uuid_msgs/UniqueID message. + +.. _`#1`: https://github.com/ros-geographic-info/unique_identifier/issues/1 diff --git a/navigations/unique_identifier/uuid_msgs/CMakeLists.txt b/navigations/unique_identifier/uuid_msgs/CMakeLists.txt new file mode 100755 index 0000000..6d3c5fe --- /dev/null +++ b/navigations/unique_identifier/uuid_msgs/CMakeLists.txt @@ -0,0 +1,13 @@ +cmake_minimum_required(VERSION 2.8.3) +project(uuid_msgs) + +find_package(catkin REQUIRED COMPONENTS message_generation std_msgs) +# We want boost/format.hpp, which isn't in its own component. +find_package(Boost REQUIRED) + +add_message_files(DIRECTORY msg FILES UniqueID.msg) +generate_messages(DEPENDENCIES std_msgs) + +catkin_package( + CATKIN_DEPENDS message_runtime std_msgs + DEPENDS Boost) diff --git a/navigations/unique_identifier/uuid_msgs/mainpage.dox b/navigations/unique_identifier/uuid_msgs/mainpage.dox new file mode 100755 index 0000000..3956384 --- /dev/null +++ b/navigations/unique_identifier/uuid_msgs/mainpage.dox @@ -0,0 +1,9 @@ +/** +\mainpage +\htmlinclude manifest.html + +This package contains ROS messages for universally unique identifiers (UUIDs). + +It does not provide any nodes, libraries or scripts. + +*/ diff --git a/navigations/unique_identifier/uuid_msgs/msg/UniqueID.msg b/navigations/unique_identifier/uuid_msgs/msg/UniqueID.msg new file mode 100755 index 0000000..c77b6a7 --- /dev/null +++ b/navigations/unique_identifier/uuid_msgs/msg/UniqueID.msg @@ -0,0 +1,6 @@ +# A universally unique identifier (UUID). +# +# http://en.wikipedia.org/wiki/Universally_unique_identifier +# http://tools.ietf.org/html/rfc4122.html + +uint8[16] uuid diff --git a/navigations/unique_identifier/uuid_msgs/package.xml b/navigations/unique_identifier/uuid_msgs/package.xml new file mode 100755 index 0000000..85138c0 --- /dev/null +++ b/navigations/unique_identifier/uuid_msgs/package.xml @@ -0,0 +1,27 @@ + + + + + uuid_msgs + 1.0.6 + + ROS messages for universally unique identifiers. + + Jack O'Quin + Jack O'Quin + BSD + http://ros.org/wiki/uuid_msgs + + catkin + + message_generation + + std_msgs + + message_runtime + + + + + + diff --git a/not_move_base.png b/not_move_base.png new file mode 100755 index 0000000..6d9abdf Binary files /dev/null and b/not_move_base.png differ diff --git a/simulators/aws-robomaker-small-warehouse-world_h/CMakeLists.txt b/simulators/aws-robomaker-small-warehouse-world_h/CMakeLists.txt new file mode 100755 index 0000000..10812b5 --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/CMakeLists.txt @@ -0,0 +1,13 @@ +cmake_minimum_required(VERSION 2.8.3) +project(aws_robomaker_small_warehouse_world) + +find_package(catkin REQUIRED COMPONENTS + gazebo_ros +) + +catkin_package() + +install(DIRECTORY launch models worlds maps rviz + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) + diff --git a/simulators/aws-robomaker-small-warehouse-world_h/CODE_OF_CONDUCT.md b/simulators/aws-robomaker-small-warehouse-world_h/CODE_OF_CONDUCT.md new file mode 100755 index 0000000..5b627cf --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/CODE_OF_CONDUCT.md @@ -0,0 +1,4 @@ +## Code of Conduct +This project has adopted the [Amazon Open Source Code of Conduct](https://aws.github.io/code-of-conduct). +For more information see the [Code of Conduct FAQ](https://aws.github.io/code-of-conduct-faq) or contact +opensource-codeofconduct@amazon.com with any additional questions or comments. diff --git a/simulators/aws-robomaker-small-warehouse-world_h/CONTRIBUTING.md b/simulators/aws-robomaker-small-warehouse-world_h/CONTRIBUTING.md new file mode 100755 index 0000000..914e074 --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/CONTRIBUTING.md @@ -0,0 +1,61 @@ +# Contributing Guidelines + +Thank you for your interest in contributing to our project. Whether it's a bug report, new feature, correction, or additional +documentation, we greatly value feedback and contributions from our community. + +Please read through this document before submitting any issues or pull requests to ensure we have all the necessary +information to effectively respond to your bug report or contribution. + + +## Reporting Bugs/Feature Requests + +We welcome you to use the GitHub issue tracker to report bugs or suggest features. + +When filing an issue, please check existing open, or recently closed, issues to make sure somebody else hasn't already +reported the issue. Please try to include as much information as you can. Details like these are incredibly useful: + +* A reproducible test case or series of steps +* The version of our code being used +* Any modifications you've made relevant to the bug +* Anything unusual about your environment or deployment + + +## Contributing via Pull Requests +Contributions via pull requests are much appreciated. Before sending us a pull request, please ensure that: + +1. You are working against the latest source on the *master* branch. +2. You check existing open, and recently merged, pull requests to make sure someone else hasn't addressed the problem already. +3. You open an issue to discuss any significant work - we would hate for your time to be wasted. + +To send us a pull request, please: + +1. Fork the repository. +2. Modify the source; please focus on the specific change you are contributing. If you also reformat all the code, it will be hard for us to focus on your change. +3. Ensure local tests pass. +4. Commit to your fork using clear commit messages. +5. Send us a pull request, answering any default questions in the pull request interface. +6. Pay attention to any automated CI failures reported in the pull request, and stay involved in the conversation. + +GitHub provides additional document on [forking a repository](https://help.github.com/articles/fork-a-repo/) and +[creating a pull request](https://help.github.com/articles/creating-a-pull-request/). + + +## Finding contributions to work on +Looking at the existing issues is a great way to find something to contribute on. As our projects, by default, use the default GitHub issue labels (enhancement/bug/duplicate/help wanted/invalid/question/wontfix), looking at any 'help wanted' issues is a great place to start. + + +## Code of Conduct +This project has adopted the [Amazon Open Source Code of Conduct](https://aws.github.io/code-of-conduct). +For more information see the [Code of Conduct FAQ](https://aws.github.io/code-of-conduct-faq) or contact +opensource-codeofconduct@amazon.com with any additional questions or comments. + + +## Security issue notifications +If you discover a potential security issue in this project we ask that you notify AWS/Amazon Security via our [vulnerability reporting page](http://aws.amazon.com/security/vulnerability-reporting/). Please do **not** create a public github issue. + + +## Licensing + +See the [LICENSE](LICENSE) file for our project's licensing. We will ask you to confirm the licensing of your contribution. + +We may ask you to sign a [Contributor License Agreement (CLA)](http://en.wikipedia.org/wiki/Contributor_License_Agreement) for larger changes. diff --git a/simulators/aws-robomaker-small-warehouse-world_h/LICENSE b/simulators/aws-robomaker-small-warehouse-world_h/LICENSE new file mode 100755 index 0000000..1bb4f21 --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/LICENSE @@ -0,0 +1,15 @@ +Copyright Amazon.com, Inc. or its affiliates. All Rights Reserved. + +Permission is hereby granted, free of charge, to any person obtaining a copy of +this software and associated documentation files (the "Software"), to deal in +the Software without restriction, including without limitation the rights to +use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of +the Software, and to permit persons to whom the Software is furnished to do so. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS +FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR +COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER +IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN +CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + diff --git a/simulators/aws-robomaker-small-warehouse-world_h/README.md b/simulators/aws-robomaker-small-warehouse-world_h/README.md new file mode 100755 index 0000000..067252d --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/README.md @@ -0,0 +1,118 @@ +# AWS RoboMaker Small Warehouse World + +![Gazebo01](docs/images/small_warehouse_gazebo.png) + +## AWS Robomaker Small Warehouse World on Gzweb + +![Gzweb01](docs/images/gzweb_aws_warehouse.png) + +This Gazebo world is well suited for organizations who are building and testing robot applications for warehouse and logistics use cases. + +## 3D Models included in this Gazebo World + +| Model (/models) | Picture | +| :------------- |:-------------:| +| **aws_robomaker_warehouse_Bucket_01** | ![Model: Buckets](docs/images/models_buckets.png) +| **aws_robomaker_warehouse_ClutteringA_01, aws_robomaker_warehouse_ClutteringC_01, aws_robomaker_warehouse_ClutteringD_01** | ![Model: Box Clusters](docs/images/models_boxes.png) | +| **aws_robomaker_warehouse_DeskC_01** | ![Model: Desk](docs/images/models_desk.png) +| **aws_robomaker_warehouse_GroundB_01** | ![Model: Ground Paint](docs/images/models_warehouse_ground_paint.png) +| **aws_robomaker_warehouse_TrashCanC_01** | ![Model: Humans](docs/images/models_trashcan.png) +| **aws_robomaker_warehouse_Lamp_01** | ![Model: Ceiling Lamp](docs/images/models_ceiling_lamp.png) +| **aws_robomaker_warehouse_PalletJackB_01** | ![Model: Pallet Jack](docs/images/models_lift.png) +| **aws_robomaker_warehouse_ShelfD_01, aws_robomaker_warehouse_ShelfE_01, aws_robomaker_warehouse_ShelfF_01** | ![Model: Pallet Jack](docs/images/models_shelves.png) + +## Building and Launching the Gazebo World with your ROS Applications + +* Create or update a **.rosinstall** file in the root directory of your ROS workspace. Add the following line to **.rosintall**: + ``` + - git: {local-name: src/aws-robomaker-small-warehouse-world, uri: 'https://github.com/aws-robotics/aws-robomaker-small-warehouse-world.git', version: master} + ``` +* Change the directory to your ROS workspace and run `rosws update` + +* Add the following include to the ROS launch file you are using: + ```xml + + + + ... + + ``` + +* Build your application using `colcon` + ```bash + rosws update + rosdep install --from-paths . --ignore-src -r -y + colcon build + ``` + +## Example: Running this world directly in Gazebo without a ROS application + +To open this world in Gazebo, change the directory to your ROS workspace root folder and run: + +```bash +cd aws-robomaker-small-warehouse-world +export GAZEBO_MODEL_PATH=`pwd`/models +gazebo worlds/small_warehouse.world +``` + +## Example: Running this world on Gazebo headless and running the UI on Gzweb +*Tested in ROS Kinetic/Melodic, Gazebo 7/9 with node version 8.11.3/10.22.1* + +To open this world in Gzweb, There are two steps, + +1) In a terminal, change to your ROS workspace root folder and run gzserver with the small warehouse world: + +```bash +cd aws-robomaker-small-warehouse-world +export GAZEBO_MODEL_PATH=`pwd`/models +gzserver worlds/small_warehouse.world +``` + +2) In another terminal, setup and run GzWeb +- Install GzWeb by following the [official documentation](http://gazebosim.org/gzweb#install-collapse-1): + + **Important**: + * The recommended NodeJS versions are 4 up to version 8. + * Watch out for [conflicting installations of Node/NodeJS](https://askubuntu.com/questions/695155/node-nodejs-have-different-version) + * See [Troubleshooting section](http://gazebosim.org/gzweb#install-collapse-3) for other issues + +- Deploy GzWeb + - Approach 1: Copy all the Gazebo models from small-warehouse world to gzweb/http/client/assets/, and run the deploy script + + ```bash + cp -r ~/aws-robomaker-small-warehouse-world/models/. ~/gzweb/http/client/assets + cd ~/gzweb + export GAZEBO_MASTER_URI="http://localhost:11345" # change localhost to IP address of the gzserver machine + npm run deploy + npm start + ``` + + - Approach 2: without copying the Gazebo models, export Gazebo model path and run the deploy script with `-m local` + + ```bash + cd aws-robomaker-small-warehouse-world + export GAZEBO_MODEL_PATH=`pwd`/models + cd ~/gzweb + export GAZEBO_MASTER_URI="http://localhost:11345" # change localhost to IP address of the gzserver machine + npm run deploy --- -m local + npm start + ``` + +## Example: Running this world directly using ROS without a simulated robot + +To launch this base Gazebo world without a robot, clone this repository and run the following commands. **Note: ROS and gazebo must already be installed on the host.** + +```bash +# build for ROS +rosdep install --from-paths . --ignore-src -r -y +colcon build + +# run in ROS +source install/setup.sh +roslaunch aws_robomaker_small_warehouse_world view_small_warehouse.launch +``` +**Visit the [AWS RoboMaker website](https://aws.amazon.com/robomaker/) to learn more about building intelligent robotic applications with Amazon Web Services.** + +## Notes +- Lighting might vary on different system(s) (e.g brighter on system without CPU and darker on system with GPU) +- Adjust lighting parameters in .world file as you need diff --git a/simulators/aws-robomaker-small-warehouse-world_h/docs/.DS_Store b/simulators/aws-robomaker-small-warehouse-world_h/docs/.DS_Store new file mode 100755 index 0000000..0d941ff Binary files /dev/null and b/simulators/aws-robomaker-small-warehouse-world_h/docs/.DS_Store differ diff --git a/simulators/aws-robomaker-small-warehouse-world_h/docs/images/.DS_Store b/simulators/aws-robomaker-small-warehouse-world_h/docs/images/.DS_Store new file mode 100755 index 0000000..5008ddf Binary files /dev/null and b/simulators/aws-robomaker-small-warehouse-world_h/docs/images/.DS_Store differ diff --git a/simulators/aws-robomaker-small-warehouse-world_h/docs/images/gzweb_aws_warehouse.png b/simulators/aws-robomaker-small-warehouse-world_h/docs/images/gzweb_aws_warehouse.png new file mode 100755 index 0000000..1145de3 Binary files /dev/null and b/simulators/aws-robomaker-small-warehouse-world_h/docs/images/gzweb_aws_warehouse.png differ diff --git a/simulators/aws-robomaker-small-warehouse-world_h/docs/images/models_boxes.png b/simulators/aws-robomaker-small-warehouse-world_h/docs/images/models_boxes.png new file mode 100755 index 0000000..21cd47b Binary files /dev/null and b/simulators/aws-robomaker-small-warehouse-world_h/docs/images/models_boxes.png differ diff --git a/simulators/aws-robomaker-small-warehouse-world_h/docs/images/models_buckets.png b/simulators/aws-robomaker-small-warehouse-world_h/docs/images/models_buckets.png new file mode 100755 index 0000000..086ec09 Binary files /dev/null and b/simulators/aws-robomaker-small-warehouse-world_h/docs/images/models_buckets.png differ diff --git a/simulators/aws-robomaker-small-warehouse-world_h/docs/images/models_ceiling_lamp.png b/simulators/aws-robomaker-small-warehouse-world_h/docs/images/models_ceiling_lamp.png new file mode 100755 index 0000000..8bc3681 Binary files /dev/null and b/simulators/aws-robomaker-small-warehouse-world_h/docs/images/models_ceiling_lamp.png differ diff --git a/simulators/aws-robomaker-small-warehouse-world_h/docs/images/models_desk.png b/simulators/aws-robomaker-small-warehouse-world_h/docs/images/models_desk.png new file mode 100755 index 0000000..bb37521 Binary files /dev/null and b/simulators/aws-robomaker-small-warehouse-world_h/docs/images/models_desk.png differ diff --git a/simulators/aws-robomaker-small-warehouse-world_h/docs/images/models_lift.png b/simulators/aws-robomaker-small-warehouse-world_h/docs/images/models_lift.png new file mode 100755 index 0000000..ea698d3 Binary files /dev/null and b/simulators/aws-robomaker-small-warehouse-world_h/docs/images/models_lift.png differ diff --git a/simulators/aws-robomaker-small-warehouse-world_h/docs/images/models_shelves.png b/simulators/aws-robomaker-small-warehouse-world_h/docs/images/models_shelves.png new file mode 100755 index 0000000..8d7542b Binary files /dev/null and b/simulators/aws-robomaker-small-warehouse-world_h/docs/images/models_shelves.png differ diff --git a/simulators/aws-robomaker-small-warehouse-world_h/docs/images/models_trashcan.png b/simulators/aws-robomaker-small-warehouse-world_h/docs/images/models_trashcan.png new file mode 100755 index 0000000..af707e5 Binary files /dev/null and b/simulators/aws-robomaker-small-warehouse-world_h/docs/images/models_trashcan.png differ diff --git a/simulators/aws-robomaker-small-warehouse-world_h/docs/images/models_warehouse_ground_paint.png b/simulators/aws-robomaker-small-warehouse-world_h/docs/images/models_warehouse_ground_paint.png new file mode 100755 index 0000000..0ca7a67 Binary files /dev/null and b/simulators/aws-robomaker-small-warehouse-world_h/docs/images/models_warehouse_ground_paint.png differ diff --git a/simulators/aws-robomaker-small-warehouse-world_h/docs/images/small_warehouse_gazebo.png b/simulators/aws-robomaker-small-warehouse-world_h/docs/images/small_warehouse_gazebo.png new file mode 100755 index 0000000..7778fd9 Binary files /dev/null and b/simulators/aws-robomaker-small-warehouse-world_h/docs/images/small_warehouse_gazebo.png differ diff --git a/simulators/aws-robomaker-small-warehouse-world_h/launch/no_roof_small_warehouse.launch b/simulators/aws-robomaker-small-warehouse-world_h/launch/no_roof_small_warehouse.launch new file mode 100755 index 0000000..82f5b21 --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/launch/no_roof_small_warehouse.launch @@ -0,0 +1,16 @@ + + + + + + + + + + + + + + diff --git a/simulators/aws-robomaker-small-warehouse-world_h/launch/small_warehouse.launch b/simulators/aws-robomaker-small-warehouse-world_h/launch/small_warehouse.launch new file mode 100755 index 0000000..796a280 --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/launch/small_warehouse.launch @@ -0,0 +1,16 @@ + + + + + + + + + + + + + + diff --git a/simulators/aws-robomaker-small-warehouse-world_h/launch/view_small_warehouse.launch b/simulators/aws-robomaker-small-warehouse-world_h/launch/view_small_warehouse.launch new file mode 100755 index 0000000..180df4b --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/launch/view_small_warehouse.launch @@ -0,0 +1,7 @@ + + + + + + + \ No newline at end of file diff --git a/simulators/aws-robomaker-small-warehouse-world_h/maps.zip b/simulators/aws-robomaker-small-warehouse-world_h/maps.zip new file mode 100755 index 0000000..833ca47 Binary files /dev/null and b/simulators/aws-robomaker-small-warehouse-world_h/maps.zip differ diff --git a/simulators/aws-robomaker-small-warehouse-world_h/maps/.DS_Store b/simulators/aws-robomaker-small-warehouse-world_h/maps/.DS_Store new file mode 100755 index 0000000..2f9ad61 Binary files /dev/null and b/simulators/aws-robomaker-small-warehouse-world_h/maps/.DS_Store differ diff --git a/simulators/aws-robomaker-small-warehouse-world_h/maps/002/map.pgm b/simulators/aws-robomaker-small-warehouse-world_h/maps/002/map.pgm new file mode 100755 index 0000000..37c3924 --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/maps/002/map.pgm @@ -0,0 +1,5 @@ +P5 +# CREATOR: map_saver.cpp 0.020 m/pix +1536 1504 +255 + \ No newline at end of file diff --git a/simulators/aws-robomaker-small-warehouse-world_h/maps/002/map.yaml b/simulators/aws-robomaker-small-warehouse-world_h/maps/002/map.yaml new file mode 100755 index 0000000..ed90b18 --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/maps/002/map.yaml @@ -0,0 +1,7 @@ +image: map.pgm +resolution: 0.020000 +origin: [-10.000000, -20.240000, 0.000000] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 + diff --git a/simulators/aws-robomaker-small-warehouse-world_h/maps/005/map.pgm b/simulators/aws-robomaker-small-warehouse-world_h/maps/005/map.pgm new file mode 100755 index 0000000..89e5384 --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/maps/005/map.pgm @@ -0,0 +1,5 @@ +P5 +# CREATOR: map_saver.cpp 0.050 m/pix +640 384 +255 + \ No newline at end of file diff --git a/simulators/aws-robomaker-small-warehouse-world_h/maps/005/map.yaml b/simulators/aws-robomaker-small-warehouse-world_h/maps/005/map.yaml new file mode 100755 index 0000000..fbaf3c8 --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/maps/005/map.yaml @@ -0,0 +1,8 @@ +image: map_rotated.png +resolution: 0.050000 +origin: [-7.000, -10.500000, 0.000000] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 + +# -3.071 3.583 diff --git a/simulators/aws-robomaker-small-warehouse-world_h/maps/005/map_rotated.pgm b/simulators/aws-robomaker-small-warehouse-world_h/maps/005/map_rotated.pgm new file mode 100755 index 0000000..c06a923 Binary files /dev/null and b/simulators/aws-robomaker-small-warehouse-world_h/maps/005/map_rotated.pgm differ diff --git a/simulators/aws-robomaker-small-warehouse-world_h/maps/005/map_rotated.png b/simulators/aws-robomaker-small-warehouse-world_h/maps/005/map_rotated.png new file mode 100755 index 0000000..e1fe0ea Binary files /dev/null and b/simulators/aws-robomaker-small-warehouse-world_h/maps/005/map_rotated.png differ diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/.DS_Store b/simulators/aws-robomaker-small-warehouse-world_h/models/.DS_Store new file mode 100755 index 0000000..480e6e1 Binary files /dev/null and b/simulators/aws-robomaker-small-warehouse-world_h/models/.DS_Store differ diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_Bucket_01/.DS_Store b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_Bucket_01/.DS_Store new file mode 100755 index 0000000..96f2a05 Binary files /dev/null and b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_Bucket_01/.DS_Store differ diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_Bucket_01/materials/.DS_Store b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_Bucket_01/materials/.DS_Store new file mode 100755 index 0000000..369de24 Binary files /dev/null and b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_Bucket_01/materials/.DS_Store differ diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_Bucket_01/materials/textures/aws_robomaker_warehouse_Bucket_01.png b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_Bucket_01/materials/textures/aws_robomaker_warehouse_Bucket_01.png new file mode 100755 index 0000000..2738ccc Binary files /dev/null and b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_Bucket_01/materials/textures/aws_robomaker_warehouse_Bucket_01.png differ diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_Bucket_01/meshes/aws_robomaker_warehouse_Bucket_01_collision.DAE b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_Bucket_01/meshes/aws_robomaker_warehouse_Bucket_01_collision.DAE new file mode 100755 index 0000000..c8146de --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_Bucket_01/meshes/aws_robomaker_warehouse_Bucket_01_collision.DAE @@ -0,0 +1,201 @@ + + + FBX COLLADA exporter2019-03-21T07:58:19Z2019-03-21T07:58:19ZZ_UP + + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + +-45.501598 -57.976257 0.490845 +44.339504 -57.976257 0.490845 +-45.501598 58.313538 0.490845 +44.339504 58.313538 0.490845 +-47.634106 -61.119202 140.905685 +46.472012 -61.119202 140.905685 +-47.634106 61.119202 140.905685 +46.472012 61.119202 140.905685 +46.472012 -61.119198 24.969147 +-47.634109 -61.119202 24.969151 +-47.634106 61.119198 24.969147 +46.472012 61.119198 24.969147 + + + + + + + + + + + +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -0.998076 -0.062006 +0.000000 -0.991858 -0.127352 +0.000000 -0.991858 -0.127352 +0.000000 -0.991858 -0.127352 +0.000000 -0.998076 -0.062006 +0.000000 -0.998076 -0.062006 +0.999126 0.000000 -0.041805 +0.996227 0.000000 -0.086790 +0.996227 0.000000 -0.086790 +0.996227 0.000000 -0.086790 +0.999126 0.000000 -0.041805 +0.999134 0.000000 -0.041602 +0.000000 0.998463 -0.055418 +0.000000 0.993495 -0.113873 +0.000000 0.998463 -0.055418 +0.000000 0.993495 -0.113873 +0.000000 0.998463 -0.055418 +0.000000 0.993495 -0.113873 +-0.999126 0.000000 -0.041805 +-0.996227 0.000000 -0.086790 +-0.999134 0.000000 -0.041602 +-0.996227 0.000000 -0.086790 +-0.999126 0.000000 -0.041805 +-0.996227 0.000000 -0.086790 +0.000000 -0.998076 -0.062006 +0.000000 -1.000000 -0.000000 +0.000000 -1.000000 -0.000000 +0.000000 -1.000000 -0.000000 +0.000000 -0.998076 -0.062006 +0.000000 -0.998076 -0.062006 +0.999134 0.000000 -0.041602 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.999134 0.000000 -0.041602 +0.999126 0.000000 -0.041805 +0.000000 1.000000 -0.000000 +0.000000 0.998463 -0.055418 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000000 +0.000000 0.998463 -0.055418 +0.000000 0.998463 -0.055418 +-0.999126 0.000000 -0.041805 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.999126 0.000000 -0.041805 +-0.999134 0.000000 -0.041602 + + + + + + + + + + + +1.000000 0.000000 +0.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +1.000000 0.174235 +0.000000 0.174235 +0.000000 0.174235 +1.000000 0.174235 +1.000000 0.174235 +0.000000 0.174235 +1.000000 0.174235 +0.000000 0.174235 + + + + + + + + + + + +

1 0 1 0 1 0 3 2 3 0 3 0 2 4 2 3 5 3 7 6 7 6 7 6 4 8 4 7 9 7 4 10 4 5 11 5 8 12 24 0 13 8 1 14 9 0 15 8 8 16 24 9 17 26 11 18 30 1 19 12 3 20 13 1 21 12 11 22 30 8 23 25 11 24 31 2 25 17 10 26 28 2 27 17 11 28 31 3 29 16 10 30 29 0 31 21 9 32 27 0 33 21 10 34 29 2 35 20 9 36 26 5 37 11 4 38 10 5 39 11 9 40 26 8 41 24 8 42 25 7 43 15 5 44 14 7 45 15 8 46 25 11 47 30 7 48 18 11 49 31 6 50 19 6 51 19 11 52 31 10 53 28 10 54 29 4 55 23 6 56 22 4 57 23 10 58 29 9 59 27

+
+
+
+ + + 1.000000 0.000000 0.000000 0.581024 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.0000001.000000 + 30.0000000.0000003.333333 + + + + + +
diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_Bucket_01/meshes/aws_robomaker_warehouse_Bucket_01_visual.DAE b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_Bucket_01/meshes/aws_robomaker_warehouse_Bucket_01_visual.DAE new file mode 100755 index 0000000..ea897f9 --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_Bucket_01/meshes/aws_robomaker_warehouse_Bucket_01_visual.DAE @@ -0,0 +1,786 @@ + + + FBX COLLADA exporter2019-03-21T07:57:48Z2019-03-21T07:57:48ZZ_UP + + + ../materials/textures/aws_robomaker_warehouse_Bucket_01.png + + + + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + +-47.053059 -59.404663 140.414841 +-3.469593 -59.404663 140.414841 +-47.053059 0.261108 140.414841 +-3.469593 0.261108 140.414841 +-47.053059 -59.404663 24.478302 +-3.469593 -59.404663 24.478302 +-47.053059 0.261108 24.478302 +-3.469593 0.261108 24.478302 +-44.920551 -56.664063 0.044712 +-5.602100 -56.664063 0.044712 +-44.920551 -2.479492 0.044712 +-5.602100 -2.479492 0.044712 +-45.551821 -1.313351 140.414841 +-45.551821 -57.830206 140.414841 +-4.970831 -57.830206 140.414841 +-4.970831 -1.313351 140.414841 +-43.497578 -4.180773 107.089249 +-43.497578 -55.149446 107.089249 +-7.025072 -55.149446 107.089249 +-7.025072 -4.180773 107.089249 +-43.109898 1.219604 119.170395 +0.473568 1.219604 119.170395 +-43.109898 60.885376 119.170395 +0.473568 60.885376 119.170395 +-43.109898 1.219604 24.433590 +0.473568 1.219604 24.433590 +-43.109898 60.885376 24.433590 +0.473568 60.885376 24.433590 +-40.977390 3.960205 0.000000 +-1.658939 3.960205 0.000000 +-40.977390 58.144775 0.000000 +-1.658939 58.144775 0.000000 +-41.608660 59.310913 119.170395 +-41.608660 2.794060 119.170395 +-1.027670 2.794060 119.170395 +-1.027670 59.310913 119.170395 +-39.554417 56.443497 85.865417 +-39.554417 5.474823 85.865417 +-3.081911 5.474823 85.865417 +-3.081911 56.443497 85.865417 +3.469601 1.219604 87.304581 +47.053070 1.219604 87.304581 +3.469601 60.885376 87.304581 +47.053070 60.885376 87.304581 +3.469601 1.219604 24.433590 +47.053070 1.219604 24.433590 +3.469601 60.885376 24.433590 +47.053070 60.885376 24.433590 +5.602108 3.960205 0.000000 +44.920563 3.960205 0.000000 +5.602108 58.144775 0.000000 +44.920563 58.144775 0.000000 +4.970839 59.310913 87.304581 +4.970839 2.794060 87.304581 +45.551826 2.794060 87.304581 +45.551826 59.310913 87.304581 +7.025082 56.443497 54.033794 +7.025082 5.474823 54.033794 +43.497589 5.474823 54.033794 +43.497589 56.443497 54.033794 +1.545681 -60.885498 129.792053 +45.129150 -60.885498 129.792053 +1.545681 -1.219727 129.792053 +45.129150 -1.219727 129.792053 +1.545681 -60.885498 24.478302 +45.129150 -60.885498 24.478302 +1.545681 -1.219727 24.478302 +45.129150 -1.219727 24.478302 +3.678188 -58.144897 0.044712 +42.996643 -58.144897 0.044712 +3.678188 -3.960327 0.044712 +42.996643 -3.960327 0.044712 +3.046919 -2.794186 129.792053 +3.046919 -59.311041 129.792053 +43.627907 -59.311041 129.792053 +43.627907 -2.794186 129.792053 +5.101162 -5.661608 96.496231 +5.101162 -56.630281 96.496231 +41.573669 -56.630281 96.496231 +41.573669 -5.661608 96.496231 + + + + + + + + + + + +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.996213 0.000000 -0.086947 +-0.996213 0.000000 -0.086947 +-0.996213 0.000000 -0.086947 +-0.996213 0.000000 -0.086947 +-0.996213 0.000000 -0.086947 +-0.996213 0.000000 -0.086947 +0.000000 0.993768 -0.111466 +0.000000 0.993768 -0.111466 +0.000000 0.993768 -0.111466 +0.000000 0.993768 -0.111466 +0.000000 0.993768 -0.111466 +0.000000 0.993768 -0.111466 +0.996213 0.000000 -0.086947 +0.996213 0.000000 -0.086947 +0.996213 0.000000 -0.086947 +0.996213 0.000000 -0.086947 +0.996213 0.000000 -0.086947 +0.996213 0.000000 -0.086947 +0.000000 -0.993768 -0.111466 +0.000000 -0.993768 -0.111466 +0.000000 -0.993768 -0.111466 +0.000000 -0.993768 -0.111466 +0.000000 -0.993768 -0.111466 +0.000000 -0.993768 -0.111466 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.998106 0.000000 0.061525 +0.998106 0.000000 0.061525 +0.998106 0.000000 0.061525 +0.998106 0.000000 0.061525 +0.998106 0.000000 0.061525 +0.998106 0.000000 0.061525 +0.000000 0.996780 0.080182 +0.000000 0.996780 0.080182 +0.000000 0.996780 0.080182 +0.000000 0.996780 0.080182 +0.000000 0.996780 0.080182 +0.000000 0.996780 0.080182 +-0.998106 0.000000 0.061525 +-0.998106 0.000000 0.061525 +-0.998106 0.000000 0.061525 +-0.998106 0.000000 0.061525 +-0.998106 0.000000 0.061525 +-0.998106 0.000000 0.061525 +0.000000 -0.996319 0.085726 +0.000000 -0.996319 0.085726 +0.000000 -0.996319 0.085726 +0.000000 -0.996319 0.085726 +0.000000 -0.996319 0.085726 +0.000000 -0.996319 0.085726 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.996213 0.000000 -0.086947 +-0.996213 0.000000 -0.086947 +-0.996213 0.000000 -0.086947 +-0.996213 0.000000 -0.086947 +-0.996213 0.000000 -0.086947 +-0.996213 0.000000 -0.086947 +0.000000 0.993768 -0.111466 +0.000000 0.993768 -0.111466 +0.000000 0.993768 -0.111466 +0.000000 0.993768 -0.111466 +0.000000 0.993768 -0.111466 +0.000000 0.993768 -0.111466 +0.996213 0.000000 -0.086947 +0.996213 0.000000 -0.086947 +0.996213 0.000000 -0.086947 +0.996213 0.000000 -0.086947 +0.996213 0.000000 -0.086947 +0.996213 0.000000 -0.086947 +0.000000 -0.993768 -0.111466 +0.000000 -0.993768 -0.111466 +0.000000 -0.993768 -0.111466 +0.000000 -0.993768 -0.111466 +0.000000 -0.993768 -0.111466 +0.000000 -0.993768 -0.111466 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.998103 0.000000 0.061563 +0.998103 0.000000 0.061563 +0.998103 0.000000 0.061563 +0.998103 0.000000 0.061563 +0.998103 0.000000 0.061563 +0.998103 0.000000 0.061563 +0.000000 0.996776 0.080232 +0.000000 0.996776 0.080232 +0.000000 0.996776 0.080232 +0.000000 0.996776 0.080232 +0.000000 0.996776 0.080232 +0.000000 0.996776 0.080232 +-0.998103 0.000000 0.061563 +-0.998103 0.000000 0.061563 +-0.998103 0.000000 0.061563 +-0.998103 0.000000 0.061563 +-0.998103 0.000000 0.061563 +-0.998103 0.000000 0.061563 +0.000000 -0.996314 0.085778 +0.000000 -0.996314 0.085778 +0.000000 -0.996314 0.085778 +0.000000 -0.996314 0.085778 +0.000000 -0.996314 0.085778 +0.000000 -0.996314 0.085778 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.996213 0.000000 -0.086947 +-0.996213 0.000000 -0.086947 +-0.996213 0.000000 -0.086947 +-0.996213 0.000000 -0.086947 +-0.996213 0.000000 -0.086947 +-0.996213 0.000000 -0.086947 +0.000000 0.993768 -0.111466 +0.000000 0.993768 -0.111466 +0.000000 0.993768 -0.111466 +0.000000 0.993768 -0.111466 +0.000000 0.993768 -0.111466 +0.000000 0.993768 -0.111466 +0.996213 0.000000 -0.086947 +0.996213 0.000000 -0.086947 +0.996213 0.000000 -0.086947 +0.996213 0.000000 -0.086947 +0.996213 0.000000 -0.086947 +0.996213 0.000000 -0.086947 +0.000000 -0.993768 -0.111466 +0.000000 -0.993768 -0.111466 +0.000000 -0.993768 -0.111466 +0.000000 -0.993768 -0.111466 +0.000000 -0.993768 -0.111466 +0.000000 -0.993768 -0.111466 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.998099 0.000000 0.061626 +0.998099 0.000000 0.061626 +0.998099 0.000000 0.061626 +0.998099 0.000000 0.061626 +0.998099 0.000000 0.061626 +0.998099 0.000000 0.061626 +0.000000 0.996770 0.080314 +0.000000 0.996770 0.080314 +0.000000 0.996770 0.080314 +0.000000 0.996770 0.080314 +0.000000 0.996770 0.080314 +0.000000 0.996770 0.080314 +-0.998099 0.000000 0.061626 +-0.998099 0.000000 0.061626 +-0.998099 0.000000 0.061626 +-0.998099 0.000000 0.061626 +-0.998099 0.000000 0.061626 +-0.998099 0.000000 0.061626 +0.000000 -0.996307 0.085866 +0.000000 -0.996307 0.085866 +0.000000 -0.996307 0.085866 +0.000000 -0.996307 0.085866 +0.000000 -0.996307 0.085866 +0.000000 -0.996307 0.085866 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.996213 0.000000 -0.086947 +-0.996213 0.000000 -0.086947 +-0.996213 0.000000 -0.086947 +-0.996213 0.000000 -0.086947 +-0.996213 0.000000 -0.086947 +-0.996213 0.000000 -0.086947 +0.000000 0.993768 -0.111466 +0.000000 0.993768 -0.111466 +0.000000 0.993768 -0.111466 +0.000000 0.993768 -0.111466 +0.000000 0.993768 -0.111466 +0.000000 0.993768 -0.111466 +0.996213 0.000000 -0.086947 +0.996213 0.000000 -0.086947 +0.996213 0.000000 -0.086947 +0.996213 0.000000 -0.086947 +0.996213 0.000000 -0.086947 +0.996213 0.000000 -0.086947 +0.000000 -0.993768 -0.111466 +0.000000 -0.993768 -0.111466 +0.000000 -0.993768 -0.111466 +0.000000 -0.993768 -0.111466 +0.000000 -0.993768 -0.111466 +0.000000 -0.993768 -0.111466 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.998102 0.000000 0.061580 +0.998102 0.000000 0.061580 +0.998102 0.000000 0.061580 +0.998102 0.000000 0.061580 +0.998102 0.000000 0.061580 +0.998102 0.000000 0.061580 +0.000000 0.996774 0.080254 +0.000000 0.996774 0.080254 +0.000000 0.996774 0.080254 +0.000000 0.996774 0.080254 +0.000000 0.996774 0.080254 +0.000000 0.996774 0.080254 +-0.998102 0.000000 0.061579 +-0.998102 0.000000 0.061579 +-0.998102 0.000000 0.061579 +-0.998102 0.000000 0.061579 +-0.998102 0.000000 0.061579 +-0.998102 0.000000 0.061579 +0.000000 -0.996312 0.085802 +0.000000 -0.996312 0.085802 +0.000000 -0.996312 0.085802 +0.000000 -0.996312 0.085802 +0.000000 -0.996312 0.085802 +0.000000 -0.996312 0.085802 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 + + + + + + + + + + + +0.503250 0.182172 +0.260475 0.182172 +0.266882 0.176062 +0.496844 0.176062 +0.202726 0.996046 +0.670755 0.996046 +0.004123 0.996046 +0.472024 0.996046 +0.003904 0.183168 +0.003904 0.004111 +0.250662 0.004111 +0.250662 0.183168 +0.677249 0.192456 +0.251604 0.192456 +0.429384 0.192456 +0.854111 0.192456 +0.765823 0.004091 +0.765823 0.182429 +0.516603 0.182429 +0.516603 0.004091 +0.670755 0.468044 +0.004123 0.468044 +0.670755 0.356586 +0.004123 0.356586 +0.202726 0.468044 +0.472024 0.468044 +0.202726 0.356586 +0.472024 0.356586 +0.260475 0.004834 +0.266882 0.010943 +0.503250 0.004834 +0.496844 0.010943 +0.004105 0.192456 +0.251604 0.345840 +0.004105 0.345840 +0.677249 0.345840 +0.429384 0.345840 +0.854111 0.345840 +0.941696 0.996046 +0.941696 0.468044 +0.941696 0.356586 +0.503250 0.182172 +0.260475 0.182172 +0.266882 0.176063 +0.496844 0.176063 +0.202726 0.899077 +0.670755 0.899077 +0.004123 0.899077 +0.472024 0.899077 +0.003904 0.183168 +0.003904 0.004111 +0.250662 0.004111 +0.250662 0.183168 +0.251893 0.192456 +0.677115 0.192456 +0.854111 0.192456 +0.429617 0.192456 +0.765823 0.004091 +0.765823 0.182429 +0.516603 0.182429 +0.516603 0.004091 +0.670755 0.468044 +0.004123 0.468044 +0.670755 0.356586 +0.004123 0.356586 +0.202726 0.468044 +0.472024 0.468044 +0.202726 0.356586 +0.472024 0.356586 +0.004105 0.192456 +0.004105 0.345840 +0.677115 0.345840 +0.260475 0.004834 +0.266882 0.010943 +0.503250 0.004834 +0.496844 0.010943 +0.429617 0.345840 +0.251893 0.345840 +0.854111 0.345840 +0.941696 0.899077 +0.941696 0.468044 +0.941696 0.356586 +0.503250 0.182172 +0.260475 0.182172 +0.266878 0.176066 +0.496844 0.176066 +0.670755 0.754753 +0.202726 0.754753 +0.472024 0.754753 +0.941696 0.754753 +0.003904 0.183168 +0.003904 0.004111 +0.250662 0.004111 +0.250662 0.183168 +0.251803 0.192456 +0.676793 0.192456 +0.854111 0.192456 +0.429464 0.192456 +0.765823 0.004091 +0.765823 0.182429 +0.516603 0.182429 +0.516603 0.004091 +0.202726 0.468044 +0.472024 0.468044 +0.202726 0.356586 +0.472024 0.356586 +0.670755 0.468044 +0.941696 0.468044 +0.670755 0.356586 +0.941696 0.356586 +0.004123 0.754753 +0.004123 0.468044 +0.004123 0.356586 +0.260475 0.004834 +0.266878 0.010943 +0.503250 0.004834 +0.496844 0.010943 +0.676793 0.345840 +0.429464 0.345840 +0.251803 0.345840 +0.854111 0.345840 +0.004105 0.192456 +0.004105 0.345840 +0.503250 0.182172 +0.260475 0.182172 +0.266884 0.176061 +0.496844 0.176061 +0.670755 0.949681 +0.202726 0.949681 +0.472024 0.949681 +0.941696 0.949681 +0.003904 0.183168 +0.003904 0.004111 +0.250662 0.004111 +0.250662 0.183168 +0.251692 0.192456 +0.677407 0.192456 +0.854111 0.192456 +0.429511 0.192456 +0.765823 0.004091 +0.765823 0.182429 +0.516603 0.182429 +0.516603 0.004091 +0.202726 0.468044 +0.472024 0.468044 +0.202726 0.356586 +0.472024 0.356586 +0.670755 0.468044 +0.941696 0.468044 +0.670755 0.356586 +0.941696 0.356586 +0.260475 0.004834 +0.266884 0.010943 +0.503250 0.004834 +0.496844 0.010943 +0.677407 0.345840 +0.429511 0.345840 +0.004105 0.192456 +0.251692 0.345840 +0.004105 0.345840 +0.854111 0.345840 +0.004123 0.949681 +0.004123 0.468044 +0.004123 0.356586 + + + + + + + + + + + +

2 0 4 6 1 24 0 2 7 0 3 7 6 4 24 4 5 25 3 6 6 7 7 21 2 8 4 2 9 4 7 10 21 6 11 24 1 12 5 5 13 20 3 14 38 3 15 38 5 16 20 7 17 39 0 18 7 4 19 25 1 20 5 1 21 5 4 22 25 5 23 20 10 24 26 4 25 25 6 26 24 4 27 25 10 28 26 8 29 27 7 30 21 11 31 23 6 32 24 6 33 24 11 34 23 10 35 26 7 36 39 5 37 20 9 38 22 7 39 39 9 40 22 11 41 40 4 42 25 8 43 27 5 44 20 5 45 20 8 46 27 9 47 22 8 48 11 11 49 9 9 50 10 11 51 9 8 52 11 10 53 8 0 54 1 12 55 3 2 56 0 12 57 3 0 58 1 13 59 2 0 60 1 1 61 28 14 62 29 0 63 1 14 64 29 13 65 2 1 66 28 3 67 30 15 68 31 1 69 28 15 70 31 14 71 29 12 72 3 3 73 30 2 74 0 3 75 30 12 76 3 15 77 31 13 78 13 16 79 34 12 80 32 16 81 34 13 82 13 17 83 33 14 84 14 17 85 33 13 86 13 17 87 33 14 88 14 18 89 36 15 90 12 19 91 35 14 92 14 14 93 14 19 94 35 18 95 36 12 96 15 16 97 37 15 98 12 15 99 12 16 100 37 19 101 35 16 102 19 18 103 17 19 104 18 18 105 17 16 106 19 17 107 16 22 108 45 26 109 65 20 110 48 20 111 48 26 112 65 24 113 66 23 114 47 27 115 62 22 116 45 22 117 45 27 118 62 26 119 65 21 120 46 25 121 61 23 122 79 23 123 79 25 124 61 27 125 80 20 126 48 24 127 66 21 128 46 21 129 46 24 130 66 25 131 61 24 132 66 26 133 65 30 134 67 24 135 66 30 136 67 28 137 68 27 138 62 31 139 64 26 140 65 26 141 65 31 142 64 30 143 67 29 144 63 27 145 80 25 146 61 27 147 80 29 148 63 31 149 81 24 150 66 28 151 68 25 152 61 25 153 61 28 154 68 29 155 63 28 156 52 31 157 50 29 158 51 31 159 50 28 160 52 30 161 49 20 162 42 32 163 44 22 164 41 32 165 44 20 166 42 33 167 43 20 168 42 21 169 72 34 170 73 20 171 42 34 172 73 33 173 43 21 174 72 23 175 74 35 176 75 21 177 72 35 178 75 34 179 73 23 180 74 22 181 41 32 182 44 23 183 74 32 184 44 35 185 75 33 186 54 36 187 76 32 188 56 36 189 76 33 190 54 37 191 71 34 192 55 37 193 71 33 194 54 37 195 71 34 196 55 38 197 78 35 198 53 39 199 77 34 200 69 34 201 69 39 202 77 38 203 70 32 204 56 36 205 76 35 206 53 35 207 53 36 208 76 39 209 77 36 210 60 38 211 58 39 212 59 38 213 58 36 214 60 37 215 57 46 216 106 40 217 89 42 218 86 40 219 89 46 220 106 44 221 107 43 222 88 47 223 103 42 224 86 42 225 86 47 226 103 46 227 106 45 228 102 43 229 88 41 230 87 43 231 88 45 232 102 47 233 103 40 234 110 44 235 111 41 236 87 41 237 87 44 238 111 45 239 102 44 240 107 46 241 106 50 242 108 44 243 107 50 244 108 48 245 109 47 246 103 51 247 105 46 248 106 46 249 106 51 250 105 50 251 108 49 252 104 47 253 103 45 254 102 47 255 103 49 256 104 51 257 105 44 258 111 48 259 112 45 260 102 45 261 102 48 262 112 49 263 104 48 264 93 51 265 91 49 266 92 51 267 91 48 268 93 50 269 90 40 270 83 52 271 85 42 272 82 52 273 85 40 274 83 53 275 84 40 276 83 41 277 113 54 278 114 40 279 83 54 280 114 53 281 84 41 282 113 43 283 115 55 284 116 41 285 113 55 286 116 54 287 114 42 288 82 55 289 116 43 290 115 55 291 116 42 292 82 52 293 85 53 294 95 56 295 118 52 296 97 56 297 118 53 298 95 57 299 117 54 300 96 57 301 117 53 302 95 57 303 117 54 304 96 58 305 120 55 306 94 59 307 119 54 308 121 54 309 121 59 310 119 58 311 122 52 312 97 56 313 118 55 314 94 55 315 94 56 316 118 59 317 119 56 318 101 58 319 99 59 320 100 58 321 99 56 322 101 57 323 98 62 324 127 66 325 147 60 326 130 60 327 130 66 328 147 64 329 148 63 330 129 67 331 144 62 332 127 62 333 127 67 334 144 66 335 147 61 336 128 65 337 143 63 338 129 63 339 129 65 340 143 67 341 144 60 342 161 64 343 162 61 344 128 61 345 128 64 346 162 65 347 143 70 348 149 64 349 148 66 350 147 64 351 148 70 352 149 68 353 150 67 354 144 71 355 146 66 356 147 66 357 147 71 358 146 70 359 149 67 360 144 65 361 143 69 362 145 67 363 144 69 364 145 71 365 146 64 366 162 68 367 163 65 368 143 65 369 143 68 370 163 69 371 145 68 372 134 71 373 132 69 374 133 71 375 132 68 376 134 70 377 131 60 378 124 72 379 126 62 380 123 72 381 126 60 382 124 73 383 125 60 384 124 61 385 151 74 386 152 60 387 124 74 388 152 73 389 125 61 390 151 63 391 153 75 392 154 61 393 151 75 394 154 74 395 152 62 396 123 75 397 154 63 398 153 75 399 154 62 400 123 72 401 126 73 402 136 76 403 156 72 404 138 76 405 156 73 406 136 77 407 155 74 408 137 77 409 155 73 410 136 77 411 155 74 412 137 78 413 160 75 414 135 79 415 158 74 416 157 74 417 157 79 418 158 78 419 159 72 420 138 76 421 156 75 422 135 75 423 135 76 424 156 79 425 158 76 426 142 78 427 140 79 428 141 78 429 140 76 430 142 77 431 139

+
+
+
+ + + 1.000000 0.000000 0.000000 -0.000031 0.000000 1.000000 0.000000 0.168701 0.000000 0.000000 1.000000 0.490845 0.000000 0.000000 0.000000 1.0000001.000000 + 30.0000000.0000003.333333 + + + + + +
diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_Bucket_01/model.config b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_Bucket_01/model.config new file mode 100755 index 0000000..cba5730 --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_Bucket_01/model.config @@ -0,0 +1,11 @@ + + + aws_robomaker_warehouse_Bucket_01 + 1.0 + model.sdf + + + + + + diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_Bucket_01/model.sdf b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_Bucket_01/model.sdf new file mode 100755 index 0000000..90b07d4 --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_Bucket_01/model.sdf @@ -0,0 +1,63 @@ + + + + + + 2 + 0 0 0 0 0 0 + + 0.570 + 0 + 0 + 0.474 + 0 + 0.391 + + + 0 0 0 0 -0 0 + 0 + 0 + 1 + + + + model://aws_robomaker_warehouse_Bucket_01/meshes/aws_robomaker_warehouse_Bucket_01_visual.DAE + + + 1 + + + 0 + 10 + 0 0 0 0 -0 0 + + + model://aws_robomaker_warehouse_Bucket_01/meshes/aws_robomaker_warehouse_Bucket_01_collision.DAE + 1 1 1 + + + + + + 0.4 + 0.4 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + true + + diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ClutteringA_01/.DS_Store b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ClutteringA_01/.DS_Store new file mode 100755 index 0000000..95f864b Binary files /dev/null and b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ClutteringA_01/.DS_Store differ diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ClutteringA_01/materials/.DS_Store b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ClutteringA_01/materials/.DS_Store new file mode 100755 index 0000000..369de24 Binary files /dev/null and b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ClutteringA_01/materials/.DS_Store differ diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ClutteringA_01/materials/textures/.DS_Store b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ClutteringA_01/materials/textures/.DS_Store new file mode 100755 index 0000000..5008ddf Binary files /dev/null and b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ClutteringA_01/materials/textures/.DS_Store differ diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ClutteringA_01/materials/textures/aws_robomaker_warehouse_ClutteringA_01.png b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ClutteringA_01/materials/textures/aws_robomaker_warehouse_ClutteringA_01.png new file mode 100755 index 0000000..b28b289 Binary files /dev/null and b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ClutteringA_01/materials/textures/aws_robomaker_warehouse_ClutteringA_01.png differ diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ClutteringA_01/materials/textures/aws_robomaker_warehouse_ClutteringA_02.png b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ClutteringA_01/materials/textures/aws_robomaker_warehouse_ClutteringA_02.png new file mode 100755 index 0000000..4b7e610 Binary files /dev/null and b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ClutteringA_01/materials/textures/aws_robomaker_warehouse_ClutteringA_02.png differ diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ClutteringA_01/materials/textures/aws_robomaker_warehouse_ClutteringA_03.png b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ClutteringA_01/materials/textures/aws_robomaker_warehouse_ClutteringA_03.png new file mode 100755 index 0000000..a8f1e1c Binary files /dev/null and b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ClutteringA_01/materials/textures/aws_robomaker_warehouse_ClutteringA_03.png differ diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_collision.DAE b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_collision.DAE new file mode 100755 index 0000000..553d82b --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_collision.DAE @@ -0,0 +1,327 @@ + + + FBX COLLADA exporter2019-03-18T11:45:58Z2019-03-18T11:45:58ZZ_UP + + + + + +-94.500908 -100.041384 3.000000 +62.468575 -100.041384 3.000000 +-94.500908 80.061399 3.000000 +62.468575 80.061399 3.000000 +-94.500908 -100.041384 111.551331 +62.468575 -100.041384 111.551331 +-94.500908 80.061399 111.551331 +62.468575 80.061399 111.551331 +29.526070 43.870054 3.000000 +96.793404 43.870054 3.000000 +29.526070 98.479551 3.000000 +96.793404 100.129454 3.000000 +29.526070 43.870054 73.674812 +96.793404 43.870054 73.674812 +29.526070 98.479551 73.674812 +96.793404 100.129454 73.674812 +56.843697 -49.131350 3.000000 +46.691963 22.638792 3.000000 +99.844673 23.109861 3.000000 +107.644112 -43.094973 3.000000 +56.843697 -49.131350 73.674812 +107.644112 -43.094973 73.674812 +99.844673 23.109861 73.674812 +46.691963 22.638792 73.674812 +-108.431084 -32.400026 3.000000 +-108.431084 18.446653 3.000000 +-88.055717 18.917723 3.000000 +-84.168144 -31.578005 3.000000 +-108.431084 -32.400026 73.674812 +-84.168144 -31.578005 73.674812 +-88.055717 18.917723 73.674812 +-108.431084 18.446653 73.674812 + + + + + + + + + + + +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.024520 0.999699 0.000000 +-0.024520 0.999699 0.000000 +-0.024520 0.999699 0.000000 +-0.024520 0.999699 0.000000 +-0.024520 0.999699 0.000000 +-0.024520 0.999699 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.117995 -0.993014 0.000000 +0.117995 -0.993014 0.000000 +0.117995 -0.993014 0.000000 +0.117995 -0.993014 0.000000 +0.117995 -0.993014 0.000000 +0.117995 -0.993014 0.000000 +0.993132 0.116999 0.000000 +0.993132 0.116999 0.000000 +0.993132 0.116999 0.000000 +0.993132 0.116999 0.000000 +0.993132 0.116999 0.000000 +0.993132 0.116999 0.000000 +-0.008862 0.999961 0.000000 +-0.008862 0.999961 0.000000 +-0.008862 0.999961 0.000000 +-0.008862 0.999961 0.000000 +-0.008862 0.999961 0.000000 +-0.008862 0.999961 0.000000 +-0.990144 -0.140054 0.000000 +-0.990144 -0.140054 0.000000 +-0.990144 -0.140054 0.000000 +-0.990144 -0.140054 0.000000 +-0.990144 -0.140054 0.000000 +-0.990144 -0.140054 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.033860 -0.999427 0.000000 +0.033860 -0.999427 0.000000 +0.033860 -0.999427 0.000000 +0.033860 -0.999427 0.000000 +0.033860 -0.999427 0.000000 +0.033860 -0.999427 0.000000 +0.997050 0.076761 0.000000 +0.997050 0.076761 0.000000 +0.997050 0.076761 0.000000 +0.997050 0.076761 0.000000 +0.997050 0.076761 0.000000 +0.997050 0.076761 0.000000 +-0.023113 0.999733 0.000000 +-0.023113 0.999733 0.000000 +-0.023113 0.999733 0.000000 +-0.023113 0.999733 0.000000 +-0.023113 0.999733 0.000000 +-0.023113 0.999733 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 + + + + + + + + + + + +1.000000 0.000000 +0.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +1.000000 0.000000 +0.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +1.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +0.000000 0.000000 +1.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +1.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +0.000000 0.000000 +1.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 + + + + + + + + + + + +

1 0 1 0 1 0 3 2 3 0 3 0 2 4 2 3 5 3 7 6 7 6 7 6 4 8 4 7 9 7 4 10 4 5 11 5 5 12 11 4 13 10 0 14 8 5 15 11 0 16 8 1 17 9 7 18 15 5 19 14 1 20 12 7 21 15 1 22 12 3 23 13 6 24 19 7 25 18 3 26 16 6 27 19 3 28 16 2 29 17 4 30 23 6 31 22 2 32 20 4 33 23 2 34 20 0 35 21 9 36 25 10 37 26 11 38 27 10 39 26 9 40 25 8 41 24 14 42 30 13 43 29 15 44 31 13 45 29 14 46 30 12 47 28 13 48 35 12 49 34 8 50 32 13 51 35 8 52 32 9 53 33 15 54 39 13 55 38 9 56 36 15 57 39 9 58 36 11 59 37 14 60 43 15 61 42 11 62 40 14 63 43 11 64 40 10 65 41 12 66 47 14 67 46 10 68 44 12 69 47 10 70 44 8 71 45 19 72 51 16 73 48 18 74 50 16 75 48 17 76 49 18 77 50 22 78 54 23 79 55 20 80 52 22 81 54 20 82 52 21 83 53 21 84 58 20 85 59 16 86 56 21 87 58 16 88 56 19 89 57 22 90 62 21 91 63 19 92 60 22 93 62 19 94 60 18 95 61 23 96 66 22 97 67 18 98 64 23 99 66 18 100 64 17 101 65 20 102 70 23 103 71 17 104 68 20 105 70 17 106 68 16 107 69 26 108 74 27 109 75 24 110 72 24 111 72 25 112 73 26 113 74 31 114 79 28 115 76 30 116 78 30 117 78 28 118 76 29 119 77 28 120 83 24 121 80 29 122 82 29 123 82 24 124 80 27 125 81 30 126 86 29 127 87 27 128 84 30 129 86 27 130 84 26 131 85 30 132 91 26 133 88 31 134 90 31 135 90 26 136 88 25 137 89 28 138 94 31 139 95 25 140 92 28 141 94 25 142 92 24 143 93

+
+
+
+ + + 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.0000001.000000 + 30.0000000.0000003.333333 + + + + + +
diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_visual.DAE b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_visual.DAE new file mode 100755 index 0000000..7b071bd --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_visual.DAE @@ -0,0 +1,1874 @@ + + + FBX COLLADA exporter2019-05-23T10:22:51Z2019-05-23T10:22:51ZZ_UP + + + ../materials/textures/aws_robomaker_warehouse_ClutteringA_01.png + + + ../materials/textures/aws_robomaker_warehouse_ClutteringA_02.png + + + ../materials/textures/aws_robomaker_warehouse_ClutteringA_03.png + + + + + + + + + + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + +0.762349 -0.606361 0.055429 +0.762349 -0.606361 0.494255 +0.673489 0.143674 0.494255 +0.673489 0.143674 0.055429 +1.358378 -0.535747 0.055429 +1.269518 0.214288 0.055429 +1.269519 0.214288 0.494255 +1.358378 -0.535747 0.494255 +0.686616 0.145229 0.494255 +0.727190 -0.442360 0.509501 +0.727190 0.276956 0.509501 +1.223694 0.276958 0.509501 +1.223696 -0.442358 0.509501 +0.654626 0.292200 0.055429 +0.654627 0.292200 0.494255 +0.670540 -0.462913 0.494255 +0.670540 -0.462913 0.055429 +0.054562 0.279554 0.055429 +0.070475 -0.475559 0.055429 +0.070476 -0.475559 0.494255 +0.067778 0.279833 0.494255 +0.054562 0.279554 0.494255 +0.049009 0.284453 0.055429 +0.049009 0.284453 0.494255 +0.064923 -0.470660 0.494255 +0.064923 -0.470661 0.055429 +-0.551056 0.271806 0.055429 +-0.535142 -0.483307 0.055429 +-0.535142 -0.483307 0.494255 +-0.537840 0.272085 0.494255 +-0.551055 0.271806 0.494255 +0.728582 -0.476027 0.055429 +0.728582 -0.476027 0.494255 +0.744496 -1.231140 0.494255 +0.744496 -1.231140 0.055429 +0.128518 -0.488673 0.055429 +0.144431 -1.243786 0.055429 +0.144431 -1.243786 0.494255 +0.141733 -0.488395 0.494255 +0.128518 -0.488673 0.494255 +0.113458 -0.487202 0.055429 +0.113459 -0.487202 0.494255 +0.129372 -1.242315 0.494255 +0.129372 -1.242316 0.055429 +-0.486606 -0.499848 0.055429 +-0.470693 -1.254962 0.055429 +-0.470692 -1.254962 0.494255 +-0.473390 -0.499570 0.494255 +-0.486606 -0.499848 0.494255 +-0.350717 -1.242098 0.502955 +-0.350717 -1.242099 0.941781 +-1.105990 -1.245517 0.941781 +-1.105990 -1.245517 0.502955 +-0.353434 -0.641907 0.502955 +-1.108707 -0.645325 0.502955 +-1.108707 -0.645325 0.941781 +-0.353374 -0.655125 0.941781 +-0.353434 -0.641907 0.941781 +-0.521947 -0.487202 0.055429 +-0.521946 -0.487202 0.494255 +-0.506033 -1.242315 0.494255 +-0.506033 -1.242316 0.055429 +-1.122011 -0.499848 0.055429 +-1.106098 -1.254962 0.055429 +-1.106098 -1.254962 0.494255 +-1.108795 -0.499570 0.494255 +-1.122011 -0.499848 0.494255 +0.414450 -1.246076 0.502955 +0.414450 -1.246077 0.941781 +-0.340823 -1.249495 0.941781 +-0.340823 -1.249495 0.502955 +0.411733 -0.645885 0.502955 +-0.343540 -0.649303 0.502955 +-0.343540 -0.649303 0.941781 +0.411793 -0.659103 0.941781 +0.411733 -0.645884 0.941781 +0.549717 -0.522866 0.457994 +0.549717 -0.522867 0.716063 +-0.436317 -0.570149 0.716063 +-0.436317 -0.570147 0.457994 +0.520747 0.081303 0.457994 +-0.465287 0.034019 0.457994 +0.520748 0.081303 0.716063 +-0.465287 0.034022 0.716063 +0.557365 -0.508447 0.724572 +0.557365 -0.508448 0.982641 +-0.426944 -0.583510 0.982641 +-0.426944 -0.583510 0.724572 +0.511375 0.094665 0.724573 +-0.472935 0.019601 0.724573 +0.511375 0.094664 0.982641 +-0.472935 0.019602 0.982641 +-1.130571 -0.501727 0.514184 +-1.130572 -0.501727 0.953010 +-1.133990 0.253546 0.953010 +-1.133990 0.253546 0.514184 +-0.530380 -0.499010 0.514184 +-0.533798 0.256263 0.514184 +-0.533798 0.256263 0.953010 +-0.543598 -0.499070 0.953010 +-0.530379 -0.499010 0.953010 +-0.590618 -0.387423 0.055429 +-0.590618 -0.387423 0.494255 +-1.345731 -0.403336 0.494255 +-1.345732 -0.403336 0.055429 +-0.603265 0.212642 0.055429 +-1.358378 0.196728 0.055429 +-1.358378 0.196728 0.494255 +-0.602986 0.199426 0.494255 +-0.603265 0.212642 0.494255 +-0.963410 0.251932 0.497822 +-0.963411 0.251932 0.936648 +-0.966830 1.007205 0.936648 +-0.966830 1.007206 0.497822 +-0.363219 0.254649 0.497822 +-0.366637 1.009923 0.497822 +-0.366638 1.009923 0.936648 +-0.376437 0.254589 0.936648 +-0.363219 0.254649 0.936648 +-0.423457 0.366237 0.055429 +-0.423457 0.366236 0.494255 +-1.178570 0.350323 0.494255 +-1.178571 0.350323 0.055429 +-0.436104 0.966301 0.055429 +-1.191217 0.950387 0.055429 +-1.191217 0.950387 0.494255 +-0.435825 0.953085 0.494255 +-0.436104 0.966301 0.494255 +-0.145074 0.178557 0.491724 +-0.145074 0.178557 0.930551 +-0.148493 0.933831 0.930551 +-0.148493 0.933831 0.491724 +0.455118 0.181274 0.491724 +0.451700 0.936548 0.491724 +0.451699 0.936548 0.930551 +0.441899 0.181214 0.930551 +0.455118 0.181274 0.930551 +0.394880 0.292862 0.055429 +0.394880 0.292861 0.494255 +-0.360234 0.276948 0.494255 +-0.360234 0.276948 0.055429 +0.382233 0.892926 0.055429 +-0.372880 0.877013 0.055429 +-0.372880 0.877013 0.494255 +0.382512 0.879710 0.494255 +0.382233 0.892926 0.494255 +0.464209 1.211223 0.487764 +0.464209 1.211223 0.926590 +1.219483 1.214642 0.926590 +1.219483 1.214642 0.487764 +0.466926 0.611031 0.487764 +1.222200 0.614450 0.487764 +1.222200 0.614450 0.926590 +0.466866 0.624250 0.926590 +0.466926 0.611031 0.926590 +1.164522 0.654896 0.055429 +1.164522 0.654896 0.494255 +0.409409 0.638982 0.494255 +0.409408 0.638982 0.055429 +1.151876 1.254961 0.055429 +0.396762 1.239047 0.055429 +0.396762 1.239047 0.494255 +1.152154 1.241745 0.494255 +1.151876 1.254961 0.494255 +-0.145074 0.178557 0.930911 +-0.145074 0.178557 1.369738 +-0.148493 0.933831 1.369738 +-0.148493 0.933831 0.930911 +0.455118 0.181274 0.930911 +0.451700 0.936548 0.930911 +0.451699 0.936548 1.369738 +0.441899 0.181214 1.369738 +0.455118 0.181274 1.369738 +0.557365 -0.508447 0.983359 +0.557365 -0.508448 1.241428 +-0.426944 -0.583510 1.241428 +-0.426944 -0.583510 0.983359 +0.511375 0.094665 0.983359 +-0.472935 0.019601 0.983359 +0.511375 0.094664 1.241428 +-0.472935 0.019602 1.241428 +-1.130571 -0.501727 0.955464 +-1.130572 -0.501727 1.394290 +-1.133990 0.253546 1.394290 +-1.133990 0.253547 0.955464 +-0.530380 -0.499010 0.955464 +-0.533798 0.256263 0.955464 +-0.533798 0.256263 1.394290 +-0.543598 -0.499070 1.394290 +-0.530379 -0.499010 1.394290 +0.727190 -0.442360 0.792406 +1.223696 -0.442358 0.792406 +1.223694 0.276958 0.792406 +0.727190 0.276956 0.792406 + + + + + + + + + + + +0.993055 0.117651 -0.000001 +0.993055 0.117651 -0.000001 +0.993055 0.117651 -0.000001 +0.993055 0.117651 -0.000001 +0.993055 0.117651 -0.000001 +0.993055 0.117651 -0.000001 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.117651 0.993055 0.000000 +0.117651 -0.993055 0.000000 +0.117651 -0.993055 0.000000 +0.117651 -0.993055 0.000000 +0.117651 -0.993055 0.000000 +0.117651 -0.993055 0.000000 +0.117651 -0.993055 0.000000 +-0.993055 -0.117651 0.000000 +-0.993055 -0.117651 0.000000 +-0.993055 -0.117651 0.000000 +-0.993055 -0.117651 0.000000 +-0.993055 -0.117651 0.000000 +-0.993055 -0.117651 0.000000 +-0.117651 0.993055 0.000000 +-0.117651 0.993055 0.000000 +-0.117651 0.993055 0.000000 +-0.117651 0.993055 0.000000 +-0.117651 0.993055 0.000000 +-0.117651 0.993055 0.000000 +0.999778 0.021070 -0.000001 +0.999778 0.021070 -0.000001 +0.999778 0.021070 -0.000001 +0.999778 0.021070 -0.000001 +0.999778 0.021070 -0.000001 +0.999778 0.021070 -0.000001 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.021070 0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.021070 0.999778 0.000000 +0.000000 0.000000 1.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.021070 0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.021070 0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +0.004527 -0.999990 -0.000001 +0.004527 -0.999990 -0.000001 +0.004527 -0.999990 -0.000001 +0.004527 -0.999990 -0.000001 +0.004527 -0.999990 -0.000001 +0.004527 -0.999990 -0.000001 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.999990 0.004527 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.004526 0.999990 0.000000 +-0.004526 0.999990 0.000000 +-0.004526 0.999990 0.000000 +-0.004526 0.999990 0.000000 +-0.004526 0.999990 0.000000 +-0.004526 0.999990 0.000000 +0.999990 0.004527 0.000000 +0.999990 0.004527 0.000000 +0.999990 0.004527 0.000000 +0.999990 0.004527 0.000000 +0.999990 0.004527 0.000000 +0.999990 0.004527 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.021070 0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.999990 0.004527 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.999990 0.004527 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.004526 0.999990 0.000000 +-0.004526 0.999990 0.000000 +-0.004526 0.999990 0.000000 +-0.004526 0.999990 0.000000 +-0.004526 0.999990 0.000000 +-0.004526 0.999990 0.000000 +0.999990 0.004527 0.000000 +0.999990 0.004527 0.000000 +0.999990 0.004527 0.000000 +0.999990 0.004527 0.000000 +0.999990 0.004527 0.000000 +0.999990 0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.004527 -0.999990 0.000000 +0.000000 0.000000 1.000000 +0.004527 -0.999990 0.000000 +0.000000 0.000000 1.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.999778 0.021070 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.004527 -0.999990 0.000000 +0.000000 0.000000 1.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.999778 0.021070 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.004527 -0.999990 0.000000 +0.000000 0.000000 1.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.999778 0.021070 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999990 -0.004527 0.000000 +0.999990 0.004527 0.000000 +0.999990 0.004527 0.000000 +0.999990 0.004527 0.000000 +0.999990 0.004527 0.000000 +0.999990 0.004527 0.000000 +0.999990 0.004527 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.999778 0.021070 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.004527 -0.999990 0.000000 +0.000000 0.000000 1.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +-0.999990 -0.004526 0.000000 +-0.999990 -0.004526 0.000000 +-0.999990 -0.004526 0.000000 +-0.999990 -0.004526 0.000000 +-0.999990 -0.004526 0.000000 +-0.999990 -0.004526 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.004527 -0.999990 0.000000 +0.000000 0.000000 1.000000 +0.004527 -0.999990 0.000000 +0.000000 0.000000 1.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.047896 -0.998852 -0.000005 +0.047896 -0.998852 -0.000005 +0.047896 -0.998852 -0.000005 +0.047896 -0.998852 -0.000005 +0.047896 -0.998852 -0.000005 +0.047896 -0.998852 -0.000005 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.998852 0.047894 -0.000002 +0.998852 0.047894 -0.000002 +0.998852 0.047894 -0.000002 +0.998852 0.047894 -0.000002 +0.998852 0.047894 -0.000002 +0.998852 0.047894 -0.000002 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.998852 -0.047894 0.000000 +-0.998852 -0.047894 0.000000 +-0.998852 -0.047894 0.000000 +-0.998852 -0.047894 0.000000 +-0.998852 -0.047894 0.000000 +-0.998852 -0.047894 0.000000 +-0.047897 0.998852 -0.000005 +-0.047897 0.998852 -0.000005 +-0.047897 0.998852 -0.000005 +-0.047897 0.998852 -0.000005 +-0.047897 0.998852 -0.000005 +-0.047897 0.998852 -0.000005 +0.076038 -0.997105 -0.000003 +0.076038 -0.997105 -0.000003 +0.076038 -0.997105 -0.000003 +0.076038 -0.997105 -0.000003 +0.076038 -0.997105 -0.000003 +0.076038 -0.997105 -0.000003 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.997105 0.076034 0.000000 +0.997105 0.076034 0.000000 +0.997105 0.076034 0.000000 +0.997105 0.076034 0.000000 +0.997105 0.076034 0.000000 +0.997105 0.076034 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.997105 -0.076035 0.000000 +-0.997105 -0.076035 0.000000 +-0.997105 -0.076035 0.000000 +-0.997105 -0.076035 0.000000 +-0.997105 -0.076035 0.000000 +-0.997105 -0.076035 0.000000 +-0.076039 0.997105 0.000000 +-0.076039 0.997105 0.000000 +-0.076039 0.997105 0.000000 +-0.076039 0.997105 0.000000 +-0.076039 0.997105 0.000000 +-0.076039 0.997105 0.000000 +0.076038 -0.997105 -0.000003 +0.076038 -0.997105 -0.000003 +0.076038 -0.997105 -0.000003 +0.076038 -0.997105 -0.000003 +0.076038 -0.997105 -0.000003 +0.076038 -0.997105 -0.000003 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.997105 0.076034 0.000000 +0.997105 0.076034 0.000000 +0.997105 0.076034 0.000000 +0.997105 0.076034 0.000000 +0.997105 0.076034 0.000000 +0.997105 0.076034 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.997105 -0.076035 0.000000 +-0.997105 -0.076035 0.000000 +-0.997105 -0.076035 0.000000 +-0.997105 -0.076035 0.000000 +-0.997105 -0.076035 0.000000 +-0.997105 -0.076035 0.000000 +-0.076039 0.997105 0.000000 +-0.076039 0.997105 0.000000 +-0.076039 0.997105 0.000000 +-0.076039 0.997105 0.000000 +-0.076039 0.997105 0.000000 +-0.076039 0.997105 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000004 -1.000000 0.000000 +0.000004 -1.000000 0.000000 +0.000004 -1.000000 0.000000 +0.000004 -1.000000 0.000000 +0.000004 -1.000000 0.000000 +0.000004 -1.000000 0.000000 +1.000000 0.000001 0.000000 +1.000000 0.000001 0.000000 +1.000000 0.000001 0.000000 +1.000000 0.000001 0.000000 +1.000000 0.000001 0.000000 +1.000000 0.000001 0.000000 +-0.000004 1.000000 0.000000 +-0.000004 1.000000 0.000000 +-0.000004 1.000000 0.000000 +-0.000004 1.000000 0.000000 +-0.000004 1.000000 0.000000 +-0.000004 1.000000 0.000000 +-1.000000 -0.000001 0.000000 +-1.000000 -0.000001 0.000000 +-1.000000 -0.000001 0.000000 +-1.000000 -0.000001 0.000000 +-1.000000 -0.000001 0.000000 +-1.000000 -0.000001 0.000000 + + + + + + + + + + + +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.505546 0.409621 +0.027038 0.424800 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.506996 0.036168 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.029544 0.035380 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.037422 0.971548 +0.039211 0.698717 +0.407335 0.698761 +0.409054 0.971742 +0.029544 0.043430 +0.570344 0.705031 +0.922325 0.705031 +0.570343 0.962377 +0.914572 0.962378 +0.238676 0.206126 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.691973 +0.217975 0.210005 +0.854670 0.918158 +0.150794 0.918158 +0.078207 0.207809 +0.288362 0.210005 +0.288362 0.695852 +0.854670 0.988546 +0.150794 0.988545 +0.010469 0.693656 +0.010469 0.207809 +0.171204 0.205139 +0.875080 0.205139 +0.875080 0.275526 +0.171204 0.275526 +0.147588 0.210005 +0.854670 0.847771 +0.150794 0.847770 +0.148885 0.207809 +0.854670 0.706996 +0.217975 0.695852 +0.078207 0.693656 +0.150794 0.706996 +0.875080 0.345913 +0.171204 0.345913 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.756345 0.522332 +0.756346 0.715841 +0.016244 0.715841 +0.016243 0.522332 +0.009526 0.514494 +0.009526 0.061000 +0.749636 0.060999 +0.749637 0.514493 +0.771396 0.480706 +0.969477 0.480355 +0.969577 0.938728 +0.771464 0.938319 +0.751630 0.039423 +0.751630 0.498972 +0.007192 0.498972 +0.007192 0.039423 +0.977311 0.498670 +0.779207 0.499082 +0.779286 0.040707 +0.977371 0.041060 +0.016243 0.718111 +0.756344 0.718111 +0.756344 0.911620 +0.016243 0.911620 +0.756345 0.522332 +0.756346 0.715841 +0.016244 0.715841 +0.016243 0.522332 +0.009526 0.514494 +0.009526 0.061000 +0.749636 0.060999 +0.749637 0.514493 +0.771396 0.480706 +0.969477 0.480355 +0.969577 0.938728 +0.771464 0.938319 +0.751630 0.039423 +0.751630 0.498972 +0.007192 0.498972 +0.007192 0.039423 +0.977311 0.498670 +0.779207 0.499082 +0.779286 0.040707 +0.977371 0.041060 +0.016243 0.718111 +0.756344 0.718111 +0.756344 0.911620 +0.016243 0.911620 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.756345 0.522332 +0.756346 0.715841 +0.016244 0.715841 +0.016243 0.522332 +0.009526 0.514494 +0.009526 0.061000 +0.749636 0.060999 +0.749637 0.514493 +0.771396 0.480706 +0.969477 0.480355 +0.969577 0.938728 +0.771464 0.938319 +0.751630 0.039423 +0.751630 0.498972 +0.007192 0.498972 +0.007192 0.039423 +0.977311 0.498670 +0.779207 0.499082 +0.779286 0.040707 +0.977371 0.041060 +0.016243 0.718111 +0.756344 0.718111 +0.756344 0.911620 +0.016243 0.911620 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.077201 0.210005 +0.854670 0.777384 +0.150794 0.777383 +0.219564 0.207809 +0.147588 0.695852 +0.148885 0.693656 +0.875080 0.416300 +0.171204 0.416300 +0.944549 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.240673 0.206126 +0.077201 0.695852 +0.219564 0.693656 +0.875080 0.486687 +0.171204 0.486687 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035379 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035381 +0.029544 0.035381 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035381 +0.006814 0.210005 +0.006814 0.695852 +0.287302 0.693656 +0.287302 0.207809 + + + + + + + + + + + +

6 0 6 7 1 7 5 2 5 7 3 7 4 4 4 5 5 5 0 6 8 5 7 10 4 8 11 5 9 10 0 10 8 3 11 9 6 12 15 8 13 20 7 14 14 8 15 20 1 16 13 7 17 14 1 18 13 8 19 20 2 20 12 2 21 12 8 22 20 3 23 566 7 24 19 1 25 16 4 26 18 1 27 16 0 28 17 4 29 18 1 30 1 2 31 2 0 32 0 2 33 2 3 34 3 0 35 0 6 36 23 5 37 21 8 38 24 8 39 24 5 40 21 3 41 22 14 42 54 15 43 55 13 44 53 15 45 55 16 46 56 13 47 53 18 48 60 17 49 57 16 50 59 16 51 59 17 52 57 13 53 58 14 54 63 20 55 64 15 56 62 20 57 64 19 58 61 15 59 62 19 60 61 20 61 64 21 62 65 21 63 65 20 64 64 17 65 567 15 66 67 19 67 68 16 68 66 19 69 68 18 70 69 16 71 66 19 72 72 21 73 73 18 74 71 21 75 73 17 76 70 18 77 71 14 78 75 13 79 76 20 80 74 20 81 74 13 82 76 17 83 77 23 84 79 24 85 80 22 86 78 24 87 80 25 88 81 22 89 78 27 90 85 26 91 82 25 92 84 25 93 84 26 94 82 22 95 83 23 96 88 29 97 89 24 98 87 29 99 89 28 100 86 24 101 87 28 102 86 29 103 89 30 104 90 29 105 89 26 106 568 30 107 90 24 108 92 28 109 93 25 110 91 28 111 93 27 112 94 25 113 91 30 114 98 26 115 95 28 116 97 28 117 97 26 118 95 27 119 96 23 120 100 22 121 101 29 122 99 29 123 99 22 124 101 26 125 102 32 126 104 33 127 105 31 128 103 33 129 105 34 130 106 31 131 103 36 132 110 35 133 107 34 134 109 34 135 109 35 136 107 31 137 108 32 138 113 38 139 114 33 140 112 38 141 114 37 142 111 33 143 112 37 144 111 38 145 114 39 146 115 39 147 115 38 148 114 35 149 569 33 150 117 37 151 118 34 152 116 37 153 118 36 154 119 34 155 116 35 156 120 37 157 122 39 158 123 37 159 122 35 160 120 36 161 121 32 162 125 31 163 126 38 164 124 38 165 124 31 166 126 35 167 127 41 168 129 42 169 130 40 170 128 42 171 130 43 172 131 40 173 128 45 174 135 44 175 132 43 176 134 43 177 134 44 178 132 40 179 133 41 180 138 47 181 139 42 182 137 47 183 139 46 184 136 42 185 137 46 186 136 47 187 139 48 188 140 48 189 140 47 190 139 44 191 570 42 192 142 46 193 143 43 194 141 46 195 143 45 196 144 43 197 141 48 198 148 44 199 145 46 200 147 46 201 147 44 202 145 45 203 146 41 204 150 40 205 151 47 206 149 47 207 149 40 208 151 44 209 152 50 210 154 51 211 155 49 212 153 51 213 155 52 214 156 49 215 153 52 216 159 53 217 157 49 218 158 53 219 157 52 220 159 54 221 160 55 222 161 56 223 164 53 224 571 56 225 164 55 226 161 51 227 162 56 228 164 51 229 162 50 230 163 51 231 167 55 232 168 52 233 166 55 234 168 54 235 169 52 236 166 57 237 173 53 238 170 55 239 172 55 240 172 53 241 170 54 242 171 50 243 175 49 244 176 56 245 174 56 246 174 49 247 176 53 248 177 59 249 179 60 250 180 58 251 178 60 252 180 61 253 181 58 254 178 63 255 185 62 256 182 61 257 184 61 258 184 62 259 182 58 260 183 59 261 188 65 262 189 60 263 187 65 264 189 64 265 186 60 266 187 64 267 186 65 268 189 66 269 190 66 270 190 65 271 189 62 272 572 60 273 192 64 274 193 61 275 191 64 276 193 63 277 194 61 278 191 66 279 198 62 280 195 64 281 197 64 282 197 62 283 195 63 284 196 59 285 200 58 286 201 65 287 199 65 288 199 58 289 201 62 290 202 68 291 204 69 292 205 67 293 203 69 294 205 70 295 206 67 296 203 67 297 208 70 298 209 71 299 207 70 300 209 72 301 210 71 302 207 73 303 211 71 304 573 75 305 215 73 306 211 74 307 214 71 308 573 74 309 214 73 310 211 69 311 212 74 312 214 69 313 212 68 314 213 69 315 217 73 316 218 70 317 216 73 318 218 72 319 219 70 320 216 71 321 220 73 322 222 75 323 223 73 324 222 71 325 220 72 326 221 68 327 225 67 328 226 74 329 224 74 330 224 67 331 226 71 332 227 93 333 277 94 334 278 92 335 276 94 336 278 95 337 279 92 338 276 92 339 281 95 340 282 96 341 280 96 342 280 95 343 282 97 344 283 98 345 284 94 346 285 99 347 287 94 348 285 93 349 286 99 350 287 100 351 288 98 352 284 96 353 574 99 354 287 96 355 574 98 356 284 94 357 290 98 358 291 95 359 289 98 360 291 97 361 292 95 362 289 100 363 296 96 364 293 98 365 295 98 366 295 96 367 293 97 368 294 93 369 298 92 370 299 99 371 297 99 372 297 92 373 299 96 374 300 102 375 302 103 376 303 101 377 301 103 378 303 104 379 304 101 380 301 101 381 306 104 382 307 105 383 305 104 384 307 106 385 308 105 386 305 107 387 309 108 388 312 105 389 575 108 390 312 107 391 309 103 392 310 108 393 312 103 394 310 102 395 311 103 396 315 107 397 316 106 398 317 103 399 315 106 400 317 104 401 314 109 402 321 105 403 318 107 404 320 107 405 320 105 406 318 106 407 319 102 408 323 101 409 324 108 410 322 108 411 322 101 412 324 105 413 325 111 414 327 112 415 328 110 416 326 112 417 328 113 418 329 110 419 326 110 420 331 113 421 332 114 422 330 114 423 330 113 424 332 115 425 333 116 426 334 112 427 335 117 428 337 112 429 335 111 430 336 117 431 337 117 432 337 114 433 576 116 434 334 112 435 340 116 436 341 113 437 339 116 438 341 115 439 342 113 440 339 118 441 346 114 442 343 116 443 345 116 444 345 114 445 343 115 446 344 111 447 348 110 448 349 117 449 347 117 450 347 110 451 349 114 452 350 120 453 352 121 454 353 119 455 351 121 456 353 122 457 354 119 458 351 122 459 357 123 460 355 119 461 356 123 462 355 122 463 357 124 464 358 125 465 359 126 466 362 123 467 577 126 468 362 125 469 359 121 470 360 126 471 362 121 472 360 120 473 361 121 474 365 125 475 366 124 476 367 121 477 365 124 478 367 122 479 364 127 480 371 123 481 368 125 482 370 125 483 370 123 484 368 124 485 369 120 486 373 119 487 374 126 488 372 126 489 372 119 490 374 123 491 375 129 492 377 130 493 378 128 494 376 130 495 378 131 496 379 128 497 376 128 498 381 131 499 382 132 500 380 132 501 380 131 502 382 133 503 383 134 504 384 130 505 385 135 506 387 130 507 385 129 508 386 135 509 387 135 510 387 132 511 578 134 512 384 130 513 390 134 514 391 131 515 389 134 516 391 133 517 392 131 518 389 132 519 393 134 520 395 136 521 396 134 522 395 132 523 393 133 524 394 129 525 398 128 526 399 135 527 397 135 528 397 128 529 399 132 530 400 138 531 402 139 532 403 137 533 401 139 534 403 140 535 404 137 536 401 140 537 407 141 538 405 137 539 406 141 540 405 140 541 407 142 542 408 143 543 409 144 544 412 141 545 579 144 546 412 143 547 409 139 548 410 144 549 412 139 550 410 138 551 411 139 552 415 143 553 416 142 554 417 139 555 415 142 556 417 140 557 414 145 558 421 141 559 418 143 560 420 143 561 420 141 562 418 142 563 419 138 564 423 137 565 424 144 566 422 144 567 422 137 568 424 141 569 425 147 570 427 148 571 428 146 572 426 148 573 428 149 574 429 146 575 426 151 576 433 150 577 430 149 578 432 150 579 430 146 580 431 149 581 432 153 582 437 148 583 435 147 584 436 148 585 435 153 586 437 152 587 434 152 588 434 153 589 437 154 590 438 154 591 438 153 592 437 150 593 580 148 594 440 152 595 441 149 596 439 152 597 441 151 598 442 149 599 439 150 600 443 152 601 445 154 602 446 152 603 445 150 604 443 151 605 444 147 606 448 146 607 449 153 608 447 153 609 447 146 610 449 150 611 450 156 612 452 157 613 453 155 614 451 157 615 453 158 616 454 155 617 451 155 618 456 160 619 458 159 620 455 160 621 458 155 622 456 158 623 457 161 624 459 162 625 462 159 626 581 162 627 462 161 628 459 157 629 460 162 630 462 157 631 460 156 632 461 157 633 465 161 634 466 160 635 467 157 636 465 160 637 467 158 638 464 163 639 471 159 640 468 161 641 470 161 642 470 159 643 468 160 644 469 156 645 473 155 646 474 162 647 472 162 648 472 155 649 474 159 650 475 165 651 477 166 652 478 164 653 476 166 654 478 167 655 479 164 656 476 164 657 481 167 658 482 168 659 480 168 660 480 167 661 482 169 662 483 170 663 484 166 664 485 171 665 487 166 666 485 165 667 486 171 668 487 171 669 487 168 670 582 170 671 484 166 672 490 170 673 491 167 674 489 170 675 491 169 676 492 167 677 489 168 678 493 170 679 495 172 680 496 170 681 495 168 682 493 169 683 494 165 684 498 164 685 499 171 686 497 171 687 497 164 688 499 168 689 500 182 690 526 183 691 527 181 692 525 183 693 527 184 694 528 181 695 525 181 696 530 186 697 532 185 698 529 186 699 532 181 700 530 184 701 531 187 702 533 183 703 534 188 704 536 183 705 534 182 706 535 188 707 536 189 708 537 187 709 533 185 710 583 188 711 536 185 712 583 187 713 533 183 714 539 187 715 540 184 716 538 187 717 540 186 718 541 184 719 538 189 720 545 185 721 542 187 722 544 187 723 544 185 724 542 186 725 543 182 726 547 181 727 548 188 728 546 188 729 546 181 730 548 185 731 549

+

79 732 231 76 733 228 78 734 230 77 735 229 78 736 230 76 737 228 76 738 233 79 739 234 81 740 235 76 741 233 81 742 235 80 743 232 82 744 237 77 745 238 76 746 239 82 747 237 76 748 239 80 749 236 83 750 240 77 751 242 82 752 243 77 753 242 83 754 240 78 755 241 81 756 247 78 757 245 83 758 246 78 759 245 81 760 247 79 761 244 83 762 250 82 763 251 80 764 248 83 765 250 80 766 248 81 767 249 87 768 255 84 769 252 86 770 254 85 771 253 86 772 254 84 773 252 84 774 257 87 775 258 89 776 259 84 777 257 89 778 259 88 779 256 90 780 261 85 781 262 84 782 263 90 783 261 84 784 263 88 785 260 91 786 264 85 787 266 90 788 267 85 789 266 91 790 264 86 791 265 86 792 269 91 793 270 89 794 271 86 795 269 89 796 271 87 797 268 88 798 272 89 799 273 90 800 275 91 801 274 90 802 275 89 803 273 176 804 504 173 805 501 175 806 503 174 807 502 175 808 503 173 809 501 173 810 506 176 811 507 178 812 508 173 813 506 178 814 508 177 815 505 179 816 510 174 817 511 173 818 512 179 819 510 173 820 512 177 821 509 180 822 513 174 823 515 179 824 516 174 825 515 180 826 513 175 827 514 175 828 518 180 829 519 178 830 520 175 831 518 178 832 520 176 833 517 177 834 521 178 835 522 179 836 524 180 837 523 179 838 524 178 839 522

+

9 840 25 10 841 26 12 842 28 12 843 28 10 844 26 11 845 27 192 846 560 193 847 561 191 848 559 193 849 561 190 850 558 191 851 559 191 852 585 190 853 584 9 854 33 191 855 585 9 856 33 12 857 34 192 858 50 191 859 47 12 860 35 192 861 50 12 862 35 11 863 36 193 864 587 192 865 586 11 866 37 193 867 587 11 868 37 10 869 38 190 870 564 193 871 565 10 872 39 190 873 564 10 874 39 9 875 40

+
+
+
+ + + + + + + + + 78.996956 0.000000 0.000000 0.000000 0.000000 78.996956 0.000000 0.000000 0.000000 0.000000 78.996956 0.000000 0.000000 0.000000 0.000000 1.0000001.000000 + 30.0000000.0000003.333333 + + + + + +
diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ClutteringA_01/model.config b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ClutteringA_01/model.config new file mode 100755 index 0000000..c3bf861 --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ClutteringA_01/model.config @@ -0,0 +1,11 @@ + + + aws_robomaker_warehouse_ClutteringA_01 + 1.0 + model.sdf + + + + + + diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ClutteringA_01/model.sdf b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ClutteringA_01/model.sdf new file mode 100755 index 0000000..629f0fc --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ClutteringA_01/model.sdf @@ -0,0 +1,55 @@ + + + + + + 2 + + 0.841 + 0 + 0 + 0.954 + 0 + 1.422 + + + + + + model://aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + model://aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_visual.DAE + + + 1 + + + 1 + + diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ClutteringC_01/materials/textures/aws_robomaker_warehouse_ClutteringC_01.png b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ClutteringC_01/materials/textures/aws_robomaker_warehouse_ClutteringC_01.png new file mode 100755 index 0000000..b28b289 Binary files /dev/null and b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ClutteringC_01/materials/textures/aws_robomaker_warehouse_ClutteringC_01.png differ diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ClutteringC_01/materials/textures/aws_robomaker_warehouse_ClutteringC_02.png b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ClutteringC_01/materials/textures/aws_robomaker_warehouse_ClutteringC_02.png new file mode 100755 index 0000000..4b7e610 Binary files /dev/null and b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ClutteringC_01/materials/textures/aws_robomaker_warehouse_ClutteringC_02.png differ diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_collision.DAE b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_collision.DAE new file mode 100755 index 0000000..4f4fd10 --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_collision.DAE @@ -0,0 +1,123 @@ + + + FBX COLLADA exporter2019-03-20T02:46:25Z2019-03-20T02:46:25ZZ_UP + + + + + +-88.666687 -102.994263 3.000000 +88.666687 -102.994263 3.000000 +-88.666687 102.994263 3.000000 +88.666687 102.994263 3.000000 +-88.666687 -102.994263 179.031189 +88.666687 -102.994263 179.031189 +-88.666687 102.994263 179.031189 +88.666687 102.994263 179.031189 + + + + + + + + + + + +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 + + + + + + + + + + + +1.000000 0.000000 +0.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 + + + + + + + + + + + +

1 0 1 0 1 0 3 2 3 0 3 0 2 4 2 3 5 3 7 6 7 6 7 6 4 8 4 7 9 7 4 10 4 5 11 5 5 12 11 4 13 10 0 14 8 5 15 11 0 16 8 1 17 9 7 18 15 5 19 14 1 20 12 7 21 15 1 22 12 3 23 13 6 24 19 7 25 18 3 26 16 6 27 19 3 28 16 2 29 17 4 30 23 6 31 22 2 32 20 4 33 23 2 34 20 0 35 21

+
+
+
+ + + 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.0000001.000000 + 30.0000000.0000003.333333 + + + + + +
diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_visual.DAE b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_visual.DAE new file mode 100755 index 0000000..3507fe5 --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_visual.DAE @@ -0,0 +1,2036 @@ + + + FBX COLLADA exporter2019-03-20T02:46:45Z2019-03-20T02:46:45ZZ_UP + + + ../materials/textures/aws_robomaker_warehouse_ClutteringC_01.png + + + + + + + + + + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + +1.067614 0.027155 0.952252 +1.067614 0.027155 1.391078 +1.083528 -0.727958 1.391078 +1.083528 -0.727958 0.952252 +0.467549 0.014509 0.952252 +0.483463 -0.740604 0.952252 +0.483463 -0.740604 1.391078 +0.480766 0.014787 1.391078 +0.467550 0.014509 1.391078 +-0.148068 -0.777457 0.043760 +-0.148068 -0.777457 0.482586 +-1.047329 -0.790820 0.482586 +-1.047329 -0.790820 0.043760 +-0.163129 -0.273580 0.043760 +-1.062389 -0.286942 0.043760 +-1.062389 -0.286943 0.482586 +-0.162797 -0.284678 0.482586 +-0.163129 -0.273580 0.482586 +-0.148068 -0.777457 0.496737 +-0.148068 -0.777457 0.935563 +-1.047329 -0.790820 0.935563 +-1.047329 -0.790820 0.496737 +-0.163129 -0.273580 0.496737 +-1.062389 -0.286942 0.496737 +-1.062389 -0.286943 0.935563 +-0.162797 -0.284678 0.935563 +-0.163129 -0.273580 0.935563 +-0.148068 -0.777457 0.952252 +-0.148068 -0.777457 1.391078 +-1.047329 -0.790820 1.391078 +-1.047329 -0.790820 0.952252 +-0.163129 -0.273580 0.952252 +-1.062389 -0.286942 0.952252 +-1.062389 -0.286943 1.391078 +-0.162797 -0.284678 1.391078 +-0.163129 -0.273580 1.391078 +-0.158738 -0.264175 0.043760 +-0.158738 -0.264175 0.482586 +-1.057999 -0.277538 0.482586 +-1.057999 -0.277538 0.043760 +-0.173799 0.239702 0.043760 +-1.073059 0.226339 0.043760 +-1.073059 0.226339 0.482586 +-0.173467 0.228604 0.482586 +-0.173799 0.239702 0.482586 +-0.158738 -0.264175 0.496737 +-0.158738 -0.264175 0.935563 +-1.057999 -0.277538 0.935563 +-1.057999 -0.277538 0.496737 +-0.173799 0.239702 0.496737 +-1.073059 0.226339 0.496737 +-1.073059 0.226339 0.935563 +-0.173467 0.228604 0.935563 +-0.173799 0.239702 0.935563 +-0.158738 -0.264175 0.952252 +-0.158738 -0.264175 1.391078 +-1.057999 -0.277538 1.391078 +-1.057999 -0.277538 0.952252 +-0.173799 0.239702 0.952252 +-1.073059 0.226339 0.952252 +-1.073059 0.226339 1.391078 +-0.173467 0.228604 1.391078 +-0.173799 0.239702 1.391078 +-0.154016 -0.491365 1.405229 +-0.154016 -0.491365 1.844055 +-1.053276 -0.504728 1.844055 +-1.053276 -0.504728 1.405229 +-0.169076 0.012512 1.405229 +-1.068336 -0.000851 1.405229 +-1.068336 -0.000851 1.844055 +-0.168745 0.001414 1.844055 +-0.169076 0.012512 1.844055 +1.067615 0.027155 0.043760 +1.067615 0.027155 0.482586 +1.083529 -0.727958 0.482586 +1.083529 -0.727958 0.043760 +0.467550 0.014509 0.043760 +0.483464 -0.740604 0.043760 +0.483464 -0.740604 0.482586 +0.480767 0.014787 0.482586 +0.467551 0.014509 0.482586 +1.067615 0.027155 0.496737 +1.067615 0.027155 0.935563 +1.083529 -0.727958 0.935563 +1.083529 -0.727958 0.496737 +0.467550 0.014509 0.496737 +0.483464 -0.740604 0.496737 +0.483464 -0.740604 0.935563 +0.480767 0.014787 0.935563 +0.467551 0.014509 0.935563 +0.456349 0.018195 0.043760 +0.456349 0.018195 0.482586 +0.472263 -0.736918 0.482586 +0.472263 -0.736918 0.043760 +-0.143716 0.005549 0.043760 +-0.127802 -0.749564 0.043760 +-0.127802 -0.749564 0.482586 +-0.130499 0.005827 0.482586 +-0.143715 0.005549 0.482586 +0.456349 0.018195 0.496737 +0.456349 0.018195 0.935563 +0.472263 -0.736918 0.935563 +0.472263 -0.736918 0.496737 +-0.143716 0.005549 0.496737 +-0.127802 -0.749564 0.496737 +-0.127802 -0.749564 0.935563 +-0.130499 0.005827 0.935563 +-0.143715 0.005549 0.935563 +0.456349 0.018195 0.952252 +0.456349 0.018195 1.391078 +0.472263 -0.736918 1.391078 +0.472263 -0.736918 0.952252 +-0.143716 0.005549 0.952252 +-0.127802 -0.749564 0.952252 +-0.127802 -0.749564 1.391078 +-0.130499 0.005827 1.391078 +-0.143715 0.005549 1.391078 +0.890204 -0.520833 1.405229 +0.890204 -0.520833 1.844055 +-0.009057 -0.534196 1.844055 +-0.009057 -0.534196 1.405229 +0.875143 -0.016957 1.405229 +-0.024117 -0.030319 1.405229 +-0.024117 -0.030320 1.844055 +0.875475 -0.028055 1.844055 +0.875143 -0.016957 1.844055 +1.051741 0.790819 0.043760 +1.051741 0.790819 0.482586 +1.067655 0.035707 0.482586 +1.067655 0.035707 0.043760 +0.451676 0.778173 0.043760 +0.467589 0.023060 0.043760 +0.467590 0.023060 0.482586 +0.464892 0.778451 0.482586 +0.451676 0.778173 0.482586 +1.051741 0.790819 0.496737 +1.051741 0.790819 0.935563 +1.067655 0.035707 0.935563 +1.067655 0.035707 0.496737 +0.451676 0.778173 0.496737 +0.467589 0.023060 0.496737 +0.467590 0.023060 0.935563 +0.464892 0.778451 0.935563 +0.451676 0.778173 0.935563 +1.051741 0.790819 0.952252 +1.051741 0.790819 1.391078 +1.067655 0.035707 1.391078 +1.067655 0.035707 0.952252 +0.451676 0.778173 0.952252 +0.467589 0.023060 0.952252 +0.467590 0.023060 1.391078 +0.464892 0.778451 1.391078 +0.451676 0.778173 1.391078 +0.440475 0.781860 0.043760 +0.440475 0.781860 0.482586 +0.456388 0.026747 0.482586 +0.456388 0.026747 0.043760 +-0.159590 0.769213 0.043760 +-0.143677 0.014100 0.043760 +-0.143676 0.014100 0.482586 +-0.146374 0.769491 0.482586 +-0.159590 0.769213 0.482586 +0.440475 0.781860 0.496737 +0.440475 0.781860 0.935563 +0.456388 0.026747 0.935563 +0.456388 0.026747 0.496737 +-0.159590 0.769213 0.496737 +-0.143677 0.014100 0.496737 +-0.143676 0.014100 0.935563 +-0.146374 0.769491 0.935563 +-0.159590 0.769213 0.935563 +0.440475 0.781860 0.952252 +0.440475 0.781860 1.391078 +0.456388 0.026747 1.391078 +0.456388 0.026747 0.952252 +-0.159590 0.769213 0.952252 +-0.143677 0.014100 0.952252 +-0.143676 0.014100 1.391078 +-0.146374 0.769491 1.391078 +-0.159590 0.769213 1.391078 +0.279776 0.779504 1.405229 +0.279776 0.779504 1.844055 +0.295690 0.024391 1.844055 +0.295690 0.024391 1.405229 +-0.320289 0.766858 1.405229 +-0.304376 0.011744 1.405229 +-0.304375 0.011744 1.844055 +-0.307073 0.767136 1.844055 +-0.320289 0.766858 1.844055 +-0.169208 0.239461 0.043760 +-0.169208 0.239461 0.482586 +-1.068468 0.226099 0.482586 +-1.068468 0.226099 0.043760 +-0.184268 0.743338 0.043760 +-1.083529 0.729976 0.043760 +-1.083529 0.729975 0.482586 +-0.183937 0.732240 0.482586 +-0.184268 0.743338 0.482586 +-0.169208 0.239461 0.496737 +-0.169208 0.239461 0.935563 +-1.068468 0.226099 0.935563 +-1.068468 0.226099 0.496737 +-0.184268 0.743338 0.496737 +-1.083529 0.729976 0.496737 +-1.083529 0.729975 0.935563 +-0.183937 0.732240 0.935563 +-0.184268 0.743338 0.935563 +-0.169208 0.239461 0.952252 +-0.169208 0.239461 1.391078 +-1.068468 0.226099 1.391078 +-1.068468 0.226099 0.952252 +-0.184268 0.743338 0.952252 +-1.083529 0.729976 0.952252 +-1.083529 0.729975 1.391078 +-0.183937 0.732240 1.391078 +-0.184268 0.743338 1.391078 + + + + + + + + + + + +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +0.999554 0.029877 -0.000000 +0.999554 0.029877 -0.000000 +0.999554 0.029877 -0.000000 +0.999554 0.029877 -0.000000 +0.999554 0.029877 -0.000000 +0.999554 0.029877 -0.000000 +0.999554 0.029877 -0.000000 +0.999554 0.029877 -0.000000 +0.999554 0.029877 -0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 + + + + + + + + + + + +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 + + + + + + + + + + + +

2 0 2 0 1 0 1 2 1 0 3 0 2 4 2 3 5 3 3 6 6 4 7 4 0 8 5 4 9 4 3 10 6 5 11 7 7 12 11 2 13 9 1 14 10 2 15 9 7 16 11 6 17 8 8 18 12 6 19 8 7 20 11 6 21 15 3 22 13 2 23 14 3 24 13 6 25 15 5 26 16 6 27 19 8 28 20 4 29 17 6 30 19 4 31 17 5 32 18 7 33 22 4 34 25 8 35 21 4 36 25 7 37 22 0 38 24 7 39 22 1 40 23 0 41 24 11 42 28 9 43 26 10 44 27 9 45 26 11 46 28 12 47 29 12 48 32 13 49 30 9 50 31 13 51 30 12 52 32 14 53 33 15 54 34 16 55 37 17 56 38 11 57 35 16 58 37 15 59 34 16 60 37 11 61 35 10 62 36 15 63 41 12 64 39 11 65 40 12 66 39 15 67 41 14 68 42 15 69 45 17 70 46 13 71 43 15 72 45 13 73 43 14 74 44 16 75 48 13 76 51 17 77 47 13 78 51 16 79 48 9 80 50 16 81 48 10 82 49 9 83 50 20 84 54 18 85 52 19 86 53 18 87 52 20 88 54 21 89 55 21 90 58 22 91 56 18 92 57 22 93 56 21 94 58 23 95 59 24 96 60 25 97 63 26 98 64 20 99 61 25 100 63 24 101 60 25 102 63 20 103 61 19 104 62 24 105 67 21 106 65 20 107 66 21 108 65 24 109 67 23 110 68 24 111 71 26 112 72 22 113 69 24 114 71 22 115 69 23 116 70 25 117 74 22 118 77 26 119 73 22 120 77 25 121 74 18 122 76 25 123 74 19 124 75 18 125 76 29 126 80 27 127 78 28 128 79 27 129 78 29 130 80 30 131 81 30 132 84 31 133 82 27 134 83 31 135 82 30 136 84 32 137 85 33 138 86 34 139 89 35 140 90 29 141 87 34 142 89 33 143 86 34 144 89 29 145 87 28 146 88 33 147 93 30 148 91 29 149 92 30 150 91 33 151 93 32 152 94 33 153 97 35 154 98 31 155 95 33 156 97 31 157 95 32 158 96 34 159 100 31 160 103 35 161 99 31 162 103 34 163 100 27 164 102 34 165 100 28 166 101 27 167 102 38 168 106 36 169 104 37 170 105 36 171 104 38 172 106 39 173 107 39 174 110 40 175 108 36 176 109 40 177 108 39 178 110 41 179 111 42 180 112 43 181 115 44 182 116 38 183 113 43 184 115 42 185 112 43 186 115 38 187 113 37 188 114 42 189 119 39 190 117 38 191 118 39 192 117 42 193 119 41 194 120 42 195 123 44 196 124 40 197 121 42 198 123 40 199 121 41 200 122 43 201 126 40 202 129 44 203 125 40 204 129 43 205 126 36 206 128 43 207 126 37 208 127 36 209 128 47 210 132 45 211 130 46 212 131 45 213 130 47 214 132 48 215 133 48 216 136 49 217 134 45 218 135 49 219 134 48 220 136 50 221 137 51 222 138 52 223 141 53 224 142 47 225 139 52 226 141 51 227 138 52 228 141 47 229 139 46 230 140 51 231 145 48 232 143 47 233 144 48 234 143 51 235 145 50 236 146 51 237 149 53 238 150 49 239 147 51 240 149 49 241 147 50 242 148 52 243 152 49 244 155 53 245 151 49 246 155 52 247 152 45 248 154 52 249 152 46 250 153 45 251 154 56 252 158 54 253 156 55 254 157 54 255 156 56 256 158 57 257 159 57 258 162 58 259 160 54 260 161 58 261 160 57 262 162 59 263 163 60 264 164 61 265 167 62 266 168 56 267 165 61 268 167 60 269 164 61 270 167 56 271 165 55 272 166 60 273 171 57 274 169 56 275 170 57 276 169 60 277 171 59 278 172 60 279 175 62 280 176 58 281 173 60 282 175 58 283 173 59 284 174 61 285 178 58 286 181 62 287 177 58 288 181 61 289 178 54 290 180 61 291 178 55 292 179 54 293 180 65 294 184 63 295 182 64 296 183 63 297 182 65 298 184 66 299 185 66 300 188 67 301 186 63 302 187 67 303 186 66 304 188 68 305 189 69 306 190 70 307 193 71 308 194 65 309 191 70 310 193 69 311 190 70 312 193 65 313 191 64 314 192 69 315 197 66 316 195 65 317 196 66 318 195 69 319 197 68 320 198 69 321 201 71 322 202 67 323 199 69 324 201 67 325 199 68 326 200 70 327 204 67 328 207 71 329 203 67 330 207 70 331 204 63 332 206 70 333 204 64 334 205 63 335 206 74 336 210 72 337 208 73 338 209 72 339 208 74 340 210 75 341 211 75 342 214 76 343 212 72 344 213 76 345 212 75 346 214 77 347 215 79 348 219 74 349 217 73 350 218 74 351 217 79 352 219 78 353 216 80 354 220 78 355 216 79 356 219 78 357 223 75 358 221 74 359 222 75 360 221 78 361 223 77 362 224 78 363 227 80 364 228 76 365 225 78 366 227 76 367 225 77 368 226 79 369 230 76 370 233 80 371 229 76 372 233 79 373 230 72 374 232 79 375 230 73 376 231 72 377 232 83 378 236 81 379 234 82 380 235 81 381 234 83 382 236 84 383 237 84 384 240 85 385 238 81 386 239 85 387 238 84 388 240 86 389 241 88 390 245 83 391 243 82 392 244 83 393 243 88 394 245 87 395 242 89 396 246 87 397 242 88 398 245 87 399 249 84 400 247 83 401 248 84 402 247 87 403 249 86 404 250 87 405 253 89 406 254 85 407 251 87 408 253 85 409 251 86 410 252 88 411 256 85 412 259 89 413 255 85 414 259 88 415 256 81 416 258 88 417 256 82 418 257 81 419 258 92 420 262 90 421 260 91 422 261 90 423 260 92 424 262 93 425 263 93 426 266 94 427 264 90 428 265 94 429 264 93 430 266 95 431 267 97 432 271 92 433 269 91 434 270 92 435 269 97 436 271 96 437 268 98 438 272 96 439 268 97 440 271 96 441 275 93 442 273 92 443 274 93 444 273 96 445 275 95 446 276 96 447 279 98 448 280 94 449 277 96 450 279 94 451 277 95 452 278 97 453 282 94 454 285 98 455 281 94 456 285 97 457 282 90 458 284 97 459 282 91 460 283 90 461 284 101 462 288 99 463 286 100 464 287 99 465 286 101 466 288 102 467 289 102 468 292 103 469 290 99 470 291 103 471 290 102 472 292 104 473 293 106 474 297 101 475 295 100 476 296 101 477 295 106 478 297 105 479 294 107 480 298 105 481 294 106 482 297 105 483 301 102 484 299 101 485 300 102 486 299 105 487 301 104 488 302 105 489 305 107 490 306 103 491 303 105 492 305 103 493 303 104 494 304 106 495 308 103 496 311 107 497 307 103 498 311 106 499 308 99 500 310 106 501 308 100 502 309 99 503 310 110 504 314 108 505 312 109 506 313 108 507 312 110 508 314 111 509 315 111 510 318 112 511 316 108 512 317 112 513 316 111 514 318 113 515 319 115 516 323 110 517 321 109 518 322 110 519 321 115 520 323 114 521 320 116 522 324 114 523 320 115 524 323 114 525 327 111 526 325 110 527 326 111 528 325 114 529 327 113 530 328 114 531 331 116 532 332 112 533 329 114 534 331 112 535 329 113 536 330 115 537 334 112 538 337 116 539 333 112 540 337 115 541 334 108 542 336 115 543 334 109 544 335 108 545 336 119 546 340 117 547 338 118 548 339 117 549 338 119 550 340 120 551 341 120 552 344 121 553 342 117 554 343 121 555 342 120 556 344 122 557 345 123 558 346 124 559 349 125 560 350 119 561 347 124 562 349 123 563 346 124 564 349 119 565 347 118 566 348 123 567 353 120 568 351 119 569 352 120 570 351 123 571 353 122 572 354 123 573 357 125 574 358 121 575 355 123 576 357 121 577 355 122 578 356 124 579 360 121 580 363 125 581 359 121 582 363 124 583 360 117 584 362 124 585 360 118 586 361 117 587 362 128 588 366 126 589 364 127 590 365 126 591 364 128 592 366 129 593 367 129 594 370 130 595 368 126 596 369 130 597 368 129 598 370 131 599 371 133 600 375 128 601 373 127 602 374 128 603 373 133 604 375 132 605 372 134 606 376 132 607 372 133 608 375 132 609 379 129 610 377 128 611 378 129 612 377 132 613 379 131 614 380 132 615 383 134 616 384 130 617 381 132 618 383 130 619 381 131 620 382 133 621 386 130 622 389 134 623 385 130 624 389 133 625 386 126 626 388 133 627 386 127 628 387 126 629 388 137 630 392 135 631 390 136 632 391 135 633 390 137 634 392 138 635 393 138 636 396 139 637 394 135 638 395 139 639 394 138 640 396 140 641 397 142 642 401 137 643 399 136 644 400 137 645 399 142 646 401 141 647 398 143 648 402 141 649 398 142 650 401 141 651 405 138 652 403 137 653 404 138 654 403 141 655 405 140 656 406 141 657 409 143 658 410 139 659 407 141 660 409 139 661 407 140 662 408 142 663 412 139 664 415 143 665 411 139 666 415 142 667 412 135 668 414 142 669 412 136 670 413 135 671 414 146 672 418 144 673 416 145 674 417 144 675 416 146 676 418 147 677 419 147 678 422 148 679 420 144 680 421 148 681 420 147 682 422 149 683 423 151 684 427 146 685 425 145 686 426 146 687 425 151 688 427 150 689 424 152 690 428 150 691 424 151 692 427 150 693 431 147 694 429 146 695 430 147 696 429 150 697 431 149 698 432 150 699 435 152 700 436 148 701 433 150 702 435 148 703 433 149 704 434 151 705 438 148 706 441 152 707 437 148 708 441 151 709 438 144 710 440 151 711 438 145 712 439 144 713 440 155 714 444 153 715 442 154 716 443 153 717 442 155 718 444 156 719 445 156 720 448 157 721 446 153 722 447 157 723 446 156 724 448 158 725 449 160 726 453 155 727 451 154 728 452 155 729 451 160 730 453 159 731 450 161 732 454 159 733 450 160 734 453 159 735 457 156 736 455 155 737 456 156 738 455 159 739 457 158 740 458 159 741 461 161 742 462 157 743 459 159 744 461 157 745 459 158 746 460 160 747 464 157 748 467 161 749 463 157 750 467 160 751 464 153 752 466 160 753 464 154 754 465 153 755 466 164 756 470 162 757 468 163 758 469 162 759 468 164 760 470 165 761 471 165 762 474 166 763 472 162 764 473 166 765 472 165 766 474 167 767 475 169 768 479 164 769 477 163 770 478 164 771 477 169 772 479 168 773 476 170 774 480 168 775 476 169 776 479 168 777 483 165 778 481 164 779 482 165 780 481 168 781 483 167 782 484 168 783 487 170 784 488 166 785 485 168 786 487 166 787 485 167 788 486 169 789 490 166 790 493 170 791 489 166 792 493 169 793 490 162 794 492 169 795 490 163 796 491 162 797 492 173 798 496 171 799 494 172 800 495 171 801 494 173 802 496 174 803 497 174 804 500 175 805 498 171 806 499 175 807 498 174 808 500 176 809 501 178 810 505 173 811 503 172 812 504 173 813 503 178 814 505 177 815 502 179 816 506 177 817 502 178 818 505 177 819 509 174 820 507 173 821 508 174 822 507 177 823 509 176 824 510 177 825 513 179 826 514 175 827 511 177 828 513 175 829 511 176 830 512 178 831 516 175 832 519 179 833 515 175 834 519 178 835 516 171 836 518 178 837 516 172 838 517 171 839 518 182 840 522 180 841 520 181 842 521 180 843 520 182 844 522 183 845 523 183 846 526 184 847 524 180 848 525 184 849 524 183 850 526 185 851 527 187 852 531 182 853 529 181 854 530 182 855 529 187 856 531 186 857 528 188 858 532 186 859 528 187 860 531 186 861 535 183 862 533 182 863 534 183 864 533 186 865 535 185 866 536 186 867 539 188 868 540 184 869 537 186 870 539 184 871 537 185 872 538 187 873 542 184 874 545 188 875 541 184 876 545 187 877 542 180 878 544 187 879 542 181 880 543 180 881 544 191 882 548 189 883 546 190 884 547 189 885 546 191 886 548 192 887 549 192 888 552 193 889 550 189 890 551 193 891 550 192 892 552 194 893 553 195 894 554 196 895 557 197 896 558 191 897 555 196 898 557 195 899 554 196 900 557 191 901 555 190 902 556 195 903 561 192 904 559 191 905 560 192 906 559 195 907 561 194 908 562 195 909 565 197 910 566 193 911 563 195 912 565 193 913 563 194 914 564 196 915 568 193 916 571 197 917 567 193 918 571 196 919 568 189 920 570 196 921 568 190 922 569 189 923 570 200 924 574 198 925 572 199 926 573 198 927 572 200 928 574 201 929 575 201 930 578 202 931 576 198 932 577 202 933 576 201 934 578 203 935 579 204 936 580 205 937 583 206 938 584 200 939 581 205 940 583 204 941 580 205 942 583 200 943 581 199 944 582 204 945 587 201 946 585 200 947 586 201 948 585 204 949 587 203 950 588 204 951 591 206 952 592 202 953 589 204 954 591 202 955 589 203 956 590 205 957 594 202 958 597 206 959 593 202 960 597 205 961 594 198 962 596 205 963 594 199 964 595 198 965 596 209 966 600 207 967 598 208 968 599 207 969 598 209 970 600 210 971 601 210 972 604 211 973 602 207 974 603 211 975 602 210 976 604 212 977 605 213 978 606 214 979 609 215 980 610 209 981 607 214 982 609 213 983 606 214 984 609 209 985 607 208 986 608 213 987 613 210 988 611 209 989 612 210 990 611 213 991 613 212 992 614 213 993 617 215 994 618 211 995 615 213 996 617 211 997 615 212 998 616 214 999 620 211 1000 623 215 1001 619 211 1002 623 214 1003 620 207 1004 622 214 1005 620 208 1006 621 207 1007 622

+

+

+
+
+
+ + + 1.672138 -114.084068 0.000000 0.000000 95.796867 1.991342 0.000000 0.000000 0.000000 0.000000 95.811455 0.000000 0.000000 0.000000 0.000000 1.0000001.000000 + 30.0000000.0000003.333333 + + + + + +
diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ClutteringC_01/model.config b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ClutteringC_01/model.config new file mode 100755 index 0000000..b842e6c --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ClutteringC_01/model.config @@ -0,0 +1,11 @@ + + + aws_robomaker_warehouse_ClutteringC_01 + 1.0 + model.sdf + + + + + + diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ClutteringC_01/model.sdf b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ClutteringC_01/model.sdf new file mode 100755 index 0000000..334a416 --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ClutteringC_01/model.sdf @@ -0,0 +1,55 @@ + + + + + + 1 + + 1.558 + 0 + 0 + 1.821 + 0 + 1.892 + + + + + + model://aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + model://aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_visual.DAE + + + 1 + + + 1 + + diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ClutteringD_01/materials/textures/aws_robomaker_warehouse_ClutteringD_01.png b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ClutteringD_01/materials/textures/aws_robomaker_warehouse_ClutteringD_01.png new file mode 100755 index 0000000..b28b289 Binary files /dev/null and b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ClutteringD_01/materials/textures/aws_robomaker_warehouse_ClutteringD_01.png differ diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ClutteringD_01/materials/textures/aws_robomaker_warehouse_ClutteringD_02.png b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ClutteringD_01/materials/textures/aws_robomaker_warehouse_ClutteringD_02.png new file mode 100755 index 0000000..4b7e610 Binary files /dev/null and b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ClutteringD_01/materials/textures/aws_robomaker_warehouse_ClutteringD_02.png differ diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ClutteringD_01/meshes/aws_robomaker_warehouse_ClutteringD_01_collision.DAE b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ClutteringD_01/meshes/aws_robomaker_warehouse_ClutteringD_01_collision.DAE new file mode 100755 index 0000000..08d4955 --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ClutteringD_01/meshes/aws_robomaker_warehouse_ClutteringD_01_collision.DAE @@ -0,0 +1,123 @@ + + + FBX COLLADA exporter2019-03-25T05:42:49Z2019-03-25T05:42:49ZZ_UP + + + + + +-50.844025 33.298004 -76.084843 +50.844025 33.298004 -76.084843 +-50.844025 182.463806 -76.084846 +50.844025 182.463806 -76.084846 +-50.844025 33.298012 76.084789 +50.844025 33.298012 76.084789 +-50.844025 182.463806 76.084789 +50.844025 182.463806 76.084789 + + + + + + + + + + + +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 + + + + + + + + + + + +1.000000 0.000000 +0.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 + + + + + + + + + + + +

1 0 1 0 1 0 3 2 3 0 3 0 2 4 2 3 5 3 7 6 7 6 7 6 4 8 4 7 9 7 4 10 4 5 11 5 5 12 11 4 13 10 0 14 8 5 15 11 0 16 8 1 17 9 5 18 14 3 19 13 7 20 15 3 21 13 5 22 14 1 23 12 6 24 19 7 25 18 3 26 16 6 27 19 3 28 16 2 29 17 4 30 23 6 31 22 2 32 20 4 33 23 2 34 20 0 35 21

+
+
+
+ + + 1.000000 0.000000 0.000000 0.000000 0.000000 -0.000000 -1.000000 0.000000 0.000000 1.000000 -0.000000 0.000000 0.000000 0.000000 0.000000 1.0000001.000000 + 30.0000000.0000003.333333 + + + + + +
diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ClutteringD_01/meshes/aws_robomaker_warehouse_ClutteringD_01_visual.DAE b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ClutteringD_01/meshes/aws_robomaker_warehouse_ClutteringD_01_visual.DAE new file mode 100755 index 0000000..5d51ad6 --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ClutteringD_01/meshes/aws_robomaker_warehouse_ClutteringD_01_visual.DAE @@ -0,0 +1,1420 @@ + + + FBX COLLADA exporter2019-03-25T05:43:02Z2019-03-25T05:43:02ZZ_UP + + + ../materials/textures/aws_robomaker_warehouse_ClutteringD_01.png + + + + + + + + + + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + +0.009253 -0.503716 0.419458 +0.009253 -0.503716 0.858284 +-0.890007 -0.517079 0.858284 +-0.890007 -0.517079 0.419458 +-0.005807 0.000161 0.419458 +-0.905068 -0.013201 0.419458 +-0.905068 -0.013202 0.858284 +-0.005476 -0.010937 0.858284 +-0.005807 0.000161 0.858284 +0.009254 -0.503716 0.865917 +0.009254 -0.503716 1.304744 +-0.890007 -0.517079 1.304744 +-0.890007 -0.517079 0.865917 +-0.005806 0.000160 0.865917 +-0.905068 -0.013202 0.865917 +-0.905068 -0.013202 1.304744 +-0.005475 -0.010937 1.304744 +-0.005806 0.000160 1.304744 +0.009255 -0.503716 1.310472 +0.009255 -0.503716 1.749298 +-0.890006 -0.517080 1.749298 +-0.890006 -0.517080 1.310472 +-0.005805 0.000160 1.310472 +-0.905068 -0.013202 1.310472 +-0.905067 -0.013203 1.749298 +-0.005474 -0.010937 1.749298 +-0.005805 0.000160 1.749298 +-0.001216 -0.000079 0.419458 +-0.001216 -0.000079 0.858284 +-0.900477 -0.013442 0.858284 +-0.900477 -0.013442 0.419458 +-0.016277 0.503797 0.419458 +-0.915537 0.490435 0.419458 +-0.915537 0.490434 0.858284 +-0.015945 0.492699 0.858284 +-0.016277 0.503797 0.858284 +-0.001215 -0.000080 0.865917 +-0.001215 -0.000080 1.304744 +-0.900476 -0.013443 1.304744 +-0.900476 -0.013443 0.865917 +-0.016275 0.503797 0.865917 +-0.915536 0.490434 0.865917 +-0.915536 0.490434 1.304744 +-0.015945 0.492699 1.304744 +-0.016275 0.503797 1.304744 +-0.001215 -0.000080 1.310472 +-0.001215 -0.000080 1.749298 +-0.900475 -0.013443 1.749298 +-0.900475 -0.013443 1.310472 +-0.016274 0.503797 1.310472 +-0.915535 0.490434 1.310472 +-0.915535 0.490433 1.749298 +-0.015944 0.492698 1.749298 +-0.016274 0.503797 1.749298 +0.915534 -0.490433 0.419458 +0.915534 -0.490433 0.858284 +0.016273 -0.503795 0.858284 +0.016273 -0.503795 0.419458 +0.900473 0.013444 0.419458 +0.001212 0.000082 0.419458 +0.001212 0.000081 0.858284 +0.900805 0.002347 0.858284 +0.900473 0.013444 0.858284 +0.915534 -0.490433 0.865917 +0.915534 -0.490433 1.304744 +0.016273 -0.503796 1.304744 +0.016273 -0.503796 0.865917 +0.900474 0.013444 0.865917 +0.001213 0.000081 0.865917 +0.001213 0.000081 1.304744 +0.900805 0.002346 1.304744 +0.900474 0.013444 1.304744 +0.915535 -0.490433 1.310472 +0.915535 -0.490433 1.749298 +0.016273 -0.503796 1.749298 +0.016273 -0.503796 1.310472 +0.900475 0.013444 1.310472 +0.001214 0.000081 1.310472 +0.001214 0.000081 1.749298 +0.900805 0.002346 1.749298 +0.900475 0.013444 1.749298 +0.905064 0.013204 0.419458 +0.905064 0.013204 0.858284 +0.005803 -0.000159 0.858284 +0.005803 -0.000159 0.419458 +0.890004 0.517081 0.419458 +-0.009257 0.503718 0.419458 +-0.009257 0.503717 0.858284 +0.890335 0.505983 0.858284 +0.890004 0.517081 0.858284 +0.905065 0.013204 0.865917 +0.905065 0.013204 1.304744 +0.005805 -0.000159 1.304744 +0.005805 -0.000159 0.865917 +0.890006 0.517080 0.865917 +-0.009256 0.503718 0.865917 +-0.009256 0.503717 1.304744 +0.890336 0.505982 1.304744 +0.890006 0.517080 1.304744 +0.905066 0.013204 1.310472 +0.905066 0.013204 1.749298 +0.005805 -0.000160 1.749298 +0.005805 -0.000160 1.310472 +0.890006 0.517080 1.310472 +-0.009255 0.503717 1.310472 +-0.009255 0.503716 1.749298 +0.890336 0.505982 1.749298 +0.890006 0.517080 1.749298 +0.009256 -0.503717 1.758337 +0.009256 -0.503717 2.197164 +-0.890004 -0.517080 2.197164 +-0.890004 -0.517080 1.758337 +-0.005803 0.000160 1.758337 +-0.905068 -0.013203 1.758337 +-0.905065 -0.013203 2.197164 +-0.005473 -0.010938 2.197164 +-0.005803 0.000160 2.197164 +-0.001214 -0.000080 1.758337 +-0.001214 -0.000080 2.197164 +-0.900473 -0.013444 2.197164 +-0.900473 -0.013444 1.758337 +-0.016271 0.503796 1.758337 +-0.915534 0.490433 1.758337 +-0.915534 0.490433 2.197164 +-0.015943 0.492697 2.197164 +-0.016271 0.503796 2.197164 +0.915537 -0.490433 1.758337 +0.915537 -0.490433 2.197164 +0.016273 -0.503797 2.197164 +0.016273 -0.503797 1.758337 +0.900476 0.013443 1.758337 +0.001215 0.000080 1.758337 +0.001215 0.000080 2.197164 +0.900805 0.002345 2.197164 +0.900476 0.013443 2.197164 +0.905067 0.013203 1.758337 +0.905067 0.013203 2.197164 +0.005807 -0.000160 2.197164 +0.005807 -0.000160 1.758337 +0.890007 0.517079 1.758337 +-0.009254 0.503716 1.758337 +-0.009254 0.503716 2.197164 +0.890337 0.505981 2.197164 +0.890007 0.517079 2.197164 + + + + + + + + + + + +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029878 -0.000000 +-0.999554 -0.029878 -0.000000 +-0.999554 -0.029878 -0.000000 +-0.999554 -0.029878 -0.000000 +-0.999554 -0.029878 -0.000000 +-0.999554 -0.029878 -0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029879 0.000001 +-0.999554 -0.029879 0.000001 +-0.999554 -0.029879 0.000001 +-0.999554 -0.029879 0.000001 +-0.999554 -0.029879 0.000001 +-0.999554 -0.029879 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.014859 -0.999890 0.000000 +0.014859 -0.999890 0.000000 +0.014859 -0.999890 0.000000 +0.014859 -0.999890 0.000000 +0.014859 -0.999890 0.000000 +0.014859 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029877 -0.000000 +-0.999554 -0.029877 -0.000000 +-0.999554 -0.029877 -0.000000 +-0.999554 -0.029877 -0.000000 +-0.999554 -0.029877 -0.000000 +-0.999554 -0.029877 -0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029875 -0.000000 +-0.999554 -0.029875 -0.000000 +-0.999554 -0.029875 -0.000000 +-0.999554 -0.029875 -0.000000 +-0.999554 -0.029875 -0.000000 +-0.999554 -0.029875 -0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +0.999554 0.029877 0.000001 +0.999554 0.029877 0.000001 +0.999554 0.029877 0.000001 +0.999554 0.029877 0.000001 +0.999554 0.029877 0.000001 +0.999554 0.029877 0.000001 +0.999554 0.029877 0.000001 +0.999554 0.029877 0.000001 +0.999554 0.029877 0.000001 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029875 -0.000000 +-0.999554 -0.029875 -0.000000 +-0.999554 -0.029875 -0.000000 +-0.999554 -0.029875 -0.000000 +-0.999554 -0.029875 -0.000000 +-0.999554 -0.029875 -0.000000 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029877 -0.000000 +-0.999554 -0.029877 -0.000000 +-0.999554 -0.029877 -0.000000 +-0.999554 -0.029877 -0.000000 +-0.999554 -0.029877 -0.000000 +-0.999554 -0.029877 -0.000000 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029877 -0.000000 +-0.999554 -0.029877 -0.000000 +-0.999554 -0.029877 -0.000000 +-0.999554 -0.029877 -0.000000 +-0.999554 -0.029877 -0.000000 +-0.999554 -0.029877 -0.000000 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +0.999554 0.029874 0.000002 +0.999554 0.029874 0.000002 +0.999554 0.029874 0.000002 +0.999554 0.029874 0.000002 +0.999554 0.029874 0.000002 +0.999554 0.029874 0.000002 +0.999554 0.029874 0.000002 +0.999554 0.029874 0.000002 +0.999554 0.029874 0.000002 +0.014859 -0.999890 0.000000 +0.014859 -0.999890 0.000000 +0.014859 -0.999890 0.000000 +0.014859 -0.999890 0.000000 +0.014859 -0.999890 0.000000 +0.014859 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029880 0.000003 +-0.999553 -0.029880 0.000003 +-0.999553 -0.029880 0.000003 +-0.999553 -0.029880 0.000003 +-0.999553 -0.029880 0.000003 +-0.999553 -0.029880 0.000003 +-0.014858 0.999890 -0.000000 +-0.014858 0.999890 -0.000000 +-0.014858 0.999890 -0.000000 +-0.014858 0.999890 -0.000000 +-0.014858 0.999890 -0.000000 +-0.014858 0.999890 -0.000000 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.014859 -0.999890 0.000000 +0.014859 -0.999890 0.000000 +0.014859 -0.999890 0.000000 +0.014859 -0.999890 0.000000 +0.014859 -0.999890 0.000000 +0.014859 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +0.999554 0.029870 0.000004 +0.999554 0.029870 0.000004 +0.999554 0.029870 0.000004 +0.999554 0.029870 0.000004 +0.999554 0.029870 0.000004 +0.999554 0.029870 0.000004 +0.999554 0.029870 0.000004 +0.999554 0.029870 0.000004 +0.999554 0.029870 0.000004 +0.014859 -0.999890 0.000000 +0.014859 -0.999890 0.000000 +0.014859 -0.999890 0.000000 +0.014859 -0.999890 0.000000 +0.014859 -0.999890 0.000000 +0.014859 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029872 -0.000000 +-0.999554 -0.029872 -0.000000 +-0.999554 -0.029872 -0.000000 +-0.999554 -0.029872 -0.000000 +-0.999554 -0.029872 -0.000000 +-0.999554 -0.029872 -0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +0.999554 0.029877 0.000003 +0.999554 0.029877 0.000003 +0.999554 0.029877 0.000003 +0.999554 0.029877 0.000003 +0.999554 0.029877 0.000003 +0.999554 0.029877 0.000003 +0.999554 0.029877 0.000003 +0.999554 0.029877 0.000003 +0.999554 0.029877 0.000003 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029877 -0.000000 +-0.999554 -0.029877 -0.000000 +-0.999554 -0.029877 -0.000000 +-0.999554 -0.029877 -0.000000 +-0.999554 -0.029877 -0.000000 +-0.999554 -0.029877 -0.000000 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +0.999554 0.029874 0.000002 +0.999554 0.029874 0.000002 +0.999554 0.029874 0.000002 +0.999554 0.029874 0.000002 +0.999554 0.029874 0.000002 +0.999554 0.029874 0.000002 +0.999554 0.029874 0.000002 +0.999554 0.029874 0.000002 +0.999554 0.029874 0.000002 + + + + + + + + + + + +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 + + + + + + + + + + + +

2 0 2 0 1 0 1 2 1 0 3 0 2 4 2 3 5 3 3 6 6 4 7 4 0 8 5 4 9 4 3 10 6 5 11 7 6 12 8 7 13 11 8 14 12 2 15 9 7 16 11 6 17 8 7 18 11 2 19 9 1 20 10 6 21 15 3 22 13 2 23 14 3 24 13 6 25 15 5 26 16 6 27 19 8 28 20 4 29 17 6 30 19 4 31 17 5 32 18 7 33 22 4 34 25 8 35 21 4 36 25 7 37 22 0 38 24 7 39 22 1 40 23 0 41 24 11 42 28 9 43 26 10 44 27 9 45 26 11 46 28 12 47 29 12 48 32 13 49 30 9 50 31 13 51 30 12 52 32 14 53 33 15 54 34 16 55 37 17 56 38 11 57 35 16 58 37 15 59 34 16 60 37 11 61 35 10 62 36 15 63 41 12 64 39 11 65 40 12 66 39 15 67 41 14 68 42 15 69 45 17 70 46 13 71 43 15 72 45 13 73 43 14 74 44 16 75 48 13 76 51 17 77 47 13 78 51 16 79 48 9 80 50 16 81 48 10 82 49 9 83 50 20 84 54 18 85 52 19 86 53 18 87 52 20 88 54 21 89 55 21 90 58 22 91 56 18 92 57 22 93 56 21 94 58 23 95 59 24 96 60 25 97 63 26 98 64 20 99 61 25 100 63 24 101 60 25 102 63 20 103 61 19 104 62 24 105 67 21 106 65 20 107 66 21 108 65 24 109 67 23 110 68 24 111 71 26 112 72 22 113 69 24 114 71 22 115 69 23 116 70 25 117 74 22 118 77 26 119 73 22 120 77 25 121 74 18 122 76 25 123 74 19 124 75 18 125 76 29 126 80 27 127 78 28 128 79 27 129 78 29 130 80 30 131 81 30 132 84 31 133 82 27 134 83 31 135 82 30 136 84 32 137 85 33 138 86 34 139 89 35 140 90 29 141 87 34 142 89 33 143 86 34 144 89 29 145 87 28 146 88 33 147 93 30 148 91 29 149 92 30 150 91 33 151 93 32 152 94 33 153 97 35 154 98 31 155 95 33 156 97 31 157 95 32 158 96 34 159 100 31 160 103 35 161 99 31 162 103 34 163 100 27 164 102 34 165 100 28 166 101 27 167 102 38 168 106 36 169 104 37 170 105 36 171 104 38 172 106 39 173 107 39 174 110 40 175 108 36 176 109 40 177 108 39 178 110 41 179 111 42 180 112 43 181 115 44 182 116 38 183 113 43 184 115 42 185 112 43 186 115 38 187 113 37 188 114 42 189 119 39 190 117 38 191 118 39 192 117 42 193 119 41 194 120 42 195 123 44 196 124 40 197 121 42 198 123 40 199 121 41 200 122 43 201 126 40 202 129 44 203 125 40 204 129 43 205 126 36 206 128 43 207 126 37 208 127 36 209 128 47 210 132 45 211 130 46 212 131 45 213 130 47 214 132 48 215 133 48 216 136 49 217 134 45 218 135 49 219 134 48 220 136 50 221 137 51 222 138 52 223 141 53 224 142 47 225 139 52 226 141 51 227 138 52 228 141 47 229 139 46 230 140 51 231 145 48 232 143 47 233 144 48 234 143 51 235 145 50 236 146 51 237 149 53 238 150 49 239 147 51 240 149 49 241 147 50 242 148 52 243 152 49 244 155 53 245 151 49 246 155 52 247 152 45 248 154 52 249 152 46 250 153 45 251 154 56 252 158 54 253 156 55 254 157 54 255 156 56 256 158 57 257 159 57 258 162 58 259 160 54 260 161 58 261 160 57 262 162 59 263 163 60 264 164 61 265 167 62 266 168 56 267 165 61 268 167 60 269 164 61 270 167 56 271 165 55 272 166 60 273 171 57 274 169 56 275 170 57 276 169 60 277 171 59 278 172 60 279 175 62 280 176 58 281 173 60 282 175 58 283 173 59 284 174 61 285 178 58 286 181 62 287 177 58 288 181 61 289 178 54 290 180 61 291 178 55 292 179 54 293 180 65 294 184 63 295 182 64 296 183 63 297 182 65 298 184 66 299 185 66 300 188 67 301 186 63 302 187 67 303 186 66 304 188 68 305 189 69 306 190 70 307 193 71 308 194 65 309 191 70 310 193 69 311 190 70 312 193 65 313 191 64 314 192 69 315 197 66 316 195 65 317 196 66 318 195 69 319 197 68 320 198 69 321 201 71 322 202 67 323 199 69 324 201 67 325 199 68 326 200 70 327 204 67 328 207 71 329 203 67 330 207 70 331 204 63 332 206 70 333 204 64 334 205 63 335 206 74 336 210 72 337 208 73 338 209 72 339 208 74 340 210 75 341 211 75 342 214 76 343 212 72 344 213 76 345 212 75 346 214 77 347 215 78 348 216 79 349 219 80 350 220 74 351 217 79 352 219 78 353 216 79 354 219 74 355 217 73 356 218 78 357 223 75 358 221 74 359 222 75 360 221 78 361 223 77 362 224 78 363 227 80 364 228 76 365 225 78 366 227 76 367 225 77 368 226 79 369 230 76 370 233 80 371 229 76 372 233 79 373 230 72 374 232 79 375 230 73 376 231 72 377 232 83 378 236 81 379 234 82 380 235 81 381 234 83 382 236 84 383 237 84 384 240 85 385 238 81 386 239 85 387 238 84 388 240 86 389 241 87 390 242 88 391 245 89 392 246 83 393 243 88 394 245 87 395 242 88 396 245 83 397 243 82 398 244 87 399 249 84 400 247 83 401 248 84 402 247 87 403 249 86 404 250 87 405 253 89 406 254 85 407 251 87 408 253 85 409 251 86 410 252 88 411 256 85 412 259 89 413 255 85 414 259 88 415 256 81 416 258 88 417 256 82 418 257 81 419 258 92 420 262 90 421 260 91 422 261 90 423 260 92 424 262 93 425 263 93 426 266 94 427 264 90 428 265 94 429 264 93 430 266 95 431 267 96 432 268 97 433 271 98 434 272 92 435 269 97 436 271 96 437 268 97 438 271 92 439 269 91 440 270 96 441 275 93 442 273 92 443 274 93 444 273 96 445 275 95 446 276 96 447 279 98 448 280 94 449 277 96 450 279 94 451 277 95 452 278 97 453 282 94 454 285 98 455 281 94 456 285 97 457 282 90 458 284 97 459 282 91 460 283 90 461 284 101 462 288 99 463 286 100 464 287 99 465 286 101 466 288 102 467 289 102 468 292 103 469 290 99 470 291 103 471 290 102 472 292 104 473 293 105 474 294 106 475 297 107 476 298 101 477 295 106 478 297 105 479 294 106 480 297 101 481 295 100 482 296 105 483 301 102 484 299 101 485 300 102 486 299 105 487 301 104 488 302 105 489 305 107 490 306 103 491 303 105 492 305 103 493 303 104 494 304 106 495 308 103 496 311 107 497 307 103 498 311 106 499 308 99 500 310 106 501 308 100 502 309 99 503 310 110 504 314 108 505 312 109 506 313 108 507 312 110 508 314 111 509 315 111 510 318 112 511 316 108 512 317 112 513 316 111 514 318 113 515 319 114 516 320 115 517 323 116 518 324 110 519 321 115 520 323 114 521 320 115 522 323 110 523 321 109 524 322 114 525 327 113 526 328 110 527 326 110 528 326 113 529 328 111 530 325 114 531 331 116 532 332 112 533 329 114 534 331 112 535 329 113 536 330 115 537 334 112 538 337 116 539 333 112 540 337 115 541 334 108 542 336 115 543 334 109 544 335 108 545 336 119 546 340 117 547 338 118 548 339 117 549 338 119 550 340 120 551 341 120 552 344 121 553 342 117 554 343 121 555 342 120 556 344 122 557 345 123 558 346 124 559 349 125 560 350 119 561 347 124 562 349 123 563 346 124 564 349 119 565 347 118 566 348 123 567 353 120 568 351 119 569 352 120 570 351 123 571 353 122 572 354 123 573 357 125 574 358 121 575 355 123 576 357 121 577 355 122 578 356 124 579 360 121 580 363 125 581 359 121 582 363 124 583 360 117 584 362 124 585 360 118 586 361 117 587 362 128 588 366 126 589 364 127 590 365 126 591 364 128 592 366 129 593 367 129 594 370 130 595 368 126 596 369 130 597 368 129 598 370 131 599 371 132 600 372 133 601 375 134 602 376 128 603 373 133 604 375 132 605 372 133 606 375 128 607 373 127 608 374 132 609 379 129 610 377 128 611 378 129 612 377 132 613 379 131 614 380 132 615 383 134 616 384 130 617 381 132 618 383 130 619 381 131 620 382 133 621 386 130 622 389 134 623 385 130 624 389 133 625 386 126 626 388 133 627 386 127 628 387 126 629 388 137 630 392 135 631 390 136 632 391 135 633 390 137 634 392 138 635 393 138 636 396 139 637 394 135 638 395 139 639 394 138 640 396 140 641 397 141 642 398 142 643 401 143 644 402 137 645 399 142 646 401 141 647 398 142 648 401 137 649 399 136 650 400 141 651 405 138 652 403 137 653 404 138 654 403 141 655 405 140 656 406 141 657 409 143 658 410 139 659 407 141 660 409 139 661 407 140 662 408 142 663 412 139 664 415 143 665 411 139 666 415 142 667 412 135 668 414 142 669 412 136 670 413 135 671 414

+

+

+
+
+
+ + + 1.447990 -98.791206 0.000000 0.000000 82.955384 1.724405 0.000000 0.000000 0.000000 0.000000 82.968018 0.000000 0.000000 0.000000 0.000000 1.0000001.000000 + 30.0000000.0000003.333333 + + + + + +
diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ClutteringD_01/model.config b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ClutteringD_01/model.config new file mode 100755 index 0000000..870fdd2 --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ClutteringD_01/model.config @@ -0,0 +1,11 @@ + + + aws_robomaker_warehouse_ClutteringD_01 + 1.0 + model.sdf + + + + + + diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ClutteringD_01/model.sdf b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ClutteringD_01/model.sdf new file mode 100755 index 0000000..51ac2cd --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ClutteringD_01/model.sdf @@ -0,0 +1,55 @@ + + + + + + 1 + + 1.558 + 0 + 0 + 1.821 + 0 + 1.892 + + + + + + model://aws_robomaker_warehouse_ClutteringD_01/meshes/aws_robomaker_warehouse_ClutteringD_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + model://aws_robomaker_warehouse_ClutteringD_01/meshes/aws_robomaker_warehouse_ClutteringD_01_visual.DAE + + + 1 + + +1 + + diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_DeskC_01/materials/.DS_Store b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_DeskC_01/materials/.DS_Store new file mode 100755 index 0000000..a4e009d Binary files /dev/null and b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_DeskC_01/materials/.DS_Store differ diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_DeskC_01/materials/textures/aws_robomaker_warehouse_DeskC_01.png b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_DeskC_01/materials/textures/aws_robomaker_warehouse_DeskC_01.png new file mode 100755 index 0000000..c4550df Binary files /dev/null and b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_DeskC_01/materials/textures/aws_robomaker_warehouse_DeskC_01.png differ diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_DeskC_01/materials/textures/aws_robomaker_warehouse_DeskC_02.png b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_DeskC_01/materials/textures/aws_robomaker_warehouse_DeskC_02.png new file mode 100755 index 0000000..b28b289 Binary files /dev/null and b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_DeskC_01/materials/textures/aws_robomaker_warehouse_DeskC_02.png differ diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_DeskC_01/materials/textures/aws_robomaker_warehouse_DeskC_03.png b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_DeskC_01/materials/textures/aws_robomaker_warehouse_DeskC_03.png new file mode 100755 index 0000000..4b7e610 Binary files /dev/null and b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_DeskC_01/materials/textures/aws_robomaker_warehouse_DeskC_03.png differ diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_DeskC_01/materials/textures/aws_robomaker_warehouse_DeskC_03.psd b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_DeskC_01/materials/textures/aws_robomaker_warehouse_DeskC_03.psd new file mode 100755 index 0000000..aa1d82a Binary files /dev/null and b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_DeskC_01/materials/textures/aws_robomaker_warehouse_DeskC_03.psd differ diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_DeskC_01/materials/textures/aws_robomaker_warehouse_DeskC_04.png b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_DeskC_01/materials/textures/aws_robomaker_warehouse_DeskC_04.png new file mode 100755 index 0000000..b9b6716 Binary files /dev/null and b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_DeskC_01/materials/textures/aws_robomaker_warehouse_DeskC_04.png differ diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_DeskC_01/meshes/aws_robomaker_warehouse_DeskC_01_collision.DAE b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_DeskC_01/meshes/aws_robomaker_warehouse_DeskC_01_collision.DAE new file mode 100755 index 0000000..1981666 --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_DeskC_01/meshes/aws_robomaker_warehouse_DeskC_01_collision.DAE @@ -0,0 +1,1224 @@ + + + FBX COLLADA exporter2019-05-15T10:12:35Z2019-05-15T10:12:35ZZ_UP + + file://C:\Users\Administrator\Desktop\Amazon1\aws_Desk_01\materials\textures\aws_Desk_01.png + + + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + +-44.096615 74.151184 89.855537 +-44.096645 -74.151169 89.855537 +40.481560 77.766258 89.855537 +40.481537 -77.766273 89.855537 +-44.096615 74.151184 94.565582 +-40.481571 -77.766258 94.565582 +40.481560 77.766258 94.565582 +44.096615 -74.151176 94.565582 +-40.481541 77.766273 89.855537 +-40.481571 -77.766258 89.855537 +44.096638 74.151161 89.855537 +44.096615 -74.151176 89.855537 +-40.481541 77.766273 94.565582 +-44.096645 -74.151169 94.565582 +44.096638 74.151161 94.565582 +40.481537 -77.766273 94.565582 +-43.694942 76.159561 89.855537 +-42.489918 77.364586 89.855537 +-42.489948 -77.364571 89.855537 +-43.694973 -76.159546 89.855537 +42.489937 77.364563 89.855537 +43.694962 76.159538 89.855537 +43.694939 -76.159554 89.855537 +42.489914 -77.364578 89.855537 +-42.489918 77.364586 94.565582 +-43.694942 76.159561 94.565582 +-43.694973 -76.159546 94.565582 +-42.489948 -77.364571 94.565582 +43.694962 76.159538 94.565582 +42.489937 77.364563 94.565582 +42.489914 -77.364578 94.565582 +43.694939 -76.159554 94.565582 +-44.096615 74.151184 95.154335 +-44.096645 -74.151169 95.154335 +-43.694973 -76.159546 95.154335 +-42.489948 -77.364571 95.154335 +-40.481571 -77.766258 95.154335 +40.481537 -77.766273 95.154335 +42.489914 -77.364578 95.154335 +43.694939 -76.159554 95.154335 +44.096615 -74.151176 95.154335 +44.096638 74.151161 95.154335 +43.694962 76.159538 95.154335 +42.489937 77.364563 95.154335 +40.481560 77.766258 95.154335 +-40.481541 77.766273 95.154335 +-42.489918 77.364586 95.154335 +-43.694942 76.159561 95.154335 +-44.096615 74.151184 94.565582 +-40.481571 -77.766258 94.565582 +40.481560 77.766258 94.565582 +44.096615 -74.151176 94.565582 +-40.481541 77.766273 94.565582 +-44.096645 -74.151169 94.565582 +44.096638 74.151161 94.565582 +40.481537 -77.766273 94.565582 +-42.489918 77.364586 94.565582 +-43.694942 76.159561 94.565582 +-43.694973 -76.159546 94.565582 +-42.489948 -77.364571 94.565582 +43.694962 76.159538 94.565582 +42.489937 77.364563 94.565582 +42.489914 -77.364578 94.565582 +43.694939 -76.159554 94.565582 +27.984621 -65.935883 0.000000 +36.987133 -65.935890 0.000000 +27.984623 65.935913 0.000000 +36.987137 65.935905 0.000000 +27.984621 -65.935883 90.633247 +36.987133 -65.935890 90.633247 +27.984623 65.935913 90.633247 +36.987137 65.935905 90.633247 +27.984623 -61.610500 0.000000 +27.984621 61.610512 0.000000 +36.987133 61.610512 0.000000 +36.987137 -61.610500 0.000000 +36.987137 -61.610500 90.633247 +36.987133 61.610512 90.633247 +27.984621 61.610512 90.633247 +27.984623 -61.610500 90.633247 +36.987133 -65.935890 18.550392 +27.984621 -65.935883 18.550392 +36.987137 65.935905 18.550392 +27.984623 65.935913 18.550392 +36.987133 61.610512 18.550392 +36.987137 -61.610500 18.550392 +27.984623 -61.610500 18.550392 +27.984621 61.610512 18.550392 +36.987133 -65.935890 14.262986 +36.987137 65.935905 14.262986 +27.984623 65.935913 14.262986 +36.987137 -61.610500 14.262986 +27.984621 61.610512 14.262986 +27.984621 -65.935883 14.262986 +36.987133 61.610512 14.262986 +27.984623 -61.610500 14.262986 +-37.371159 -65.935890 0.000000 +-28.368649 -65.935890 0.000000 +-37.371166 65.935905 0.000000 +-28.368656 65.935905 0.000000 +-37.371159 -65.935890 90.633247 +-28.368649 -65.935890 90.633247 +-37.371166 65.935905 90.633247 +-28.368656 65.935905 90.633247 +-37.371159 -61.610504 0.000000 +-37.371166 61.610512 0.000000 +-28.368656 61.610512 0.000000 +-28.368649 -61.610504 0.000000 +-28.368649 -61.610504 90.633247 +-28.368656 61.610512 90.633247 +-37.371166 61.610512 90.633247 +-37.371159 -61.610504 90.633247 +-28.368649 -65.935890 18.550392 +-37.371159 -65.935890 18.550392 +-28.368656 65.935905 18.550392 +-37.371166 65.935905 18.550392 +-28.368656 61.610512 18.550392 +-28.368649 -61.610504 18.550392 +-37.371159 -61.610504 18.550392 +-37.371166 61.610512 18.550392 +-28.368649 -65.935890 14.262986 +-28.368656 65.935905 14.262986 +-37.371166 65.935905 14.262986 +-28.368649 -61.610504 14.262986 +-37.371166 61.610512 14.262986 +-37.371159 -65.935890 14.262986 +-28.368656 61.610512 14.262986 +-37.371159 -61.610504 14.262986 +-13.446186 14.462212 95.483948 +36.117062 14.462212 95.483948 +-13.446186 75.304901 95.483948 +36.117062 75.304901 95.483948 +-13.446186 14.462212 144.011230 +36.117062 14.462212 144.011230 +-13.446186 75.304901 144.011230 +36.117062 75.304901 144.011230 +-13.446186 -65.250519 95.483948 +36.117062 -65.250519 95.483948 +-13.446186 3.149231 95.483948 +36.117062 3.149231 95.483948 +-13.446186 -65.250519 144.011230 +36.117062 -65.250519 144.011230 +-13.446186 3.149231 144.011230 +36.117062 3.149231 144.011230 + + + + + + + + + + + +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.995133 -0.098537 0.000000 +-0.995133 0.098537 0.000000 +-0.995133 0.098537 0.000000 +-0.995133 -0.098537 0.000000 +-0.995133 0.098537 0.000000 +-0.995133 -0.098537 0.000000 +0.098542 -0.995133 0.000000 +-0.098541 -0.995133 0.000000 +-0.098541 -0.995133 0.000000 +0.098542 -0.995133 0.000000 +-0.098541 -0.995133 0.000000 +0.098542 -0.995133 0.000000 +0.995133 0.098538 0.000000 +0.995133 -0.098538 0.000000 +0.995133 -0.098538 0.000000 +0.995133 0.098538 0.000000 +0.995133 -0.098538 0.000000 +0.995133 0.098538 0.000000 +-0.098540 0.995133 0.000000 +0.098542 0.995133 0.000000 +0.098542 0.995133 0.000000 +-0.098540 0.995133 0.000000 +0.098542 0.995133 0.000000 +-0.098540 0.995133 0.000000 +-0.995133 -0.098537 0.000000 +-0.995133 -0.098537 0.000000 +-0.980581 -0.196115 0.000000 +-0.980581 -0.196115 0.000000 +-0.995133 -0.098537 0.000000 +-0.980581 -0.196115 0.000000 +-0.980581 0.196115 0.000000 +-0.980581 0.196115 0.000000 +-0.995133 0.098537 0.000000 +-0.995133 0.098537 0.000000 +-0.980581 0.196115 0.000000 +-0.995133 0.098537 0.000000 +0.098542 -0.995133 0.000000 +0.098542 -0.995133 0.000000 +0.196125 -0.980579 0.000000 +0.196125 -0.980579 0.000000 +0.098542 -0.995133 0.000000 +0.196125 -0.980579 0.000000 +0.995133 0.098538 0.000000 +0.995133 0.098538 0.000000 +0.980581 0.196116 0.000000 +0.980581 0.196116 0.000000 +0.995133 0.098538 0.000000 +0.980581 0.196116 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.196122 -0.980579 0.000000 +-0.196122 -0.980579 0.000000 +-0.098541 -0.995133 0.000000 +-0.098541 -0.995133 0.000000 +-0.196122 -0.980579 0.000000 +-0.098541 -0.995133 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.098540 0.995133 0.000000 +-0.098540 0.995133 0.000000 +-0.196122 0.980579 0.000000 +-0.196122 0.980579 0.000000 +-0.098540 0.995133 0.000000 +-0.196122 0.980579 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.980581 -0.196117 0.000000 +0.980581 -0.196117 0.000000 +0.995133 -0.098538 0.000000 +0.995133 -0.098538 0.000000 +0.980581 -0.196117 0.000000 +0.995133 -0.098538 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.196125 0.980579 0.000000 +0.196125 0.980579 0.000000 +0.098542 0.995133 0.000000 +0.098542 0.995133 0.000000 +0.196125 0.980579 0.000000 +0.098542 0.995133 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.980581 -0.196115 0.000000 +-0.980581 -0.196115 0.000000 +-0.980581 -0.196115 0.000000 +-0.980581 -0.196115 0.000000 +-0.980581 -0.196115 0.000000 +-0.980581 -0.196115 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.196122 -0.980580 0.000000 +-0.196122 -0.980580 0.000000 +-0.196122 -0.980580 0.000000 +-0.196122 -0.980580 0.000000 +-0.196122 -0.980580 0.000000 +-0.196122 -0.980580 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +0.196125 -0.980579 0.000000 +0.196125 -0.980579 0.000000 +0.196125 -0.980579 0.000000 +0.196125 -0.980579 0.000000 +0.196125 -0.980579 0.000000 +0.196125 -0.980579 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.980581 -0.196117 0.000000 +0.980581 -0.196117 0.000000 +0.980581 -0.196117 0.000000 +0.980581 -0.196117 0.000000 +0.980581 -0.196117 0.000000 +0.980581 -0.196117 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +0.980581 0.196117 0.000000 +0.980581 0.196117 0.000000 +0.980581 0.196117 0.000000 +0.980581 0.196117 0.000000 +0.980581 0.196117 0.000000 +0.980581 0.196117 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.196125 0.980579 0.000000 +0.196125 0.980579 0.000000 +0.196125 0.980579 0.000000 +0.196125 0.980579 0.000000 +0.196125 0.980579 0.000000 +0.196125 0.980579 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.196122 0.980580 0.000000 +-0.196122 0.980580 0.000000 +-0.196122 0.980580 0.000000 +-0.196122 0.980580 0.000000 +-0.196122 0.980580 0.000000 +-0.196122 0.980580 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.980581 0.196115 0.000000 +-0.980581 0.196115 0.000000 +-0.980581 0.196115 0.000000 +-0.980581 0.196115 0.000000 +-0.980581 0.196115 0.000000 +-0.980581 0.196115 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000001 -1.000000 0.000000 +-0.000001 -1.000000 0.000000 +-0.000001 -1.000000 0.000000 +-0.000001 -1.000000 0.000000 +-0.000001 -1.000000 0.000000 +-0.000001 -1.000000 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.000001 -1.000000 0.000000 +-0.000001 -1.000000 0.000000 +-0.000001 -1.000000 0.000000 +-0.000001 -1.000000 0.000000 +-0.000001 -1.000000 0.000000 +-0.000001 -1.000000 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.000001 -1.000000 0.000000 +-0.000001 -1.000000 0.000000 +-0.000001 -1.000000 0.000000 +-0.000001 -1.000000 0.000000 +-0.000001 -1.000000 0.000000 +-0.000001 -1.000000 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 + + + + + + + + + + + +0.579139 0.446804 +0.576821 0.457549 +0.573698 0.053096 +0.575739 0.061897 +0.589360 0.048403 +0.592868 0.459541 +0.563212 0.045241 +0.028627 0.045211 +0.018884 0.026461 +0.571741 0.027248 +0.015722 0.063922 +0.019124 0.448828 +0.005502 0.462322 +0.001993 0.051185 +0.031650 0.465484 +0.566234 0.465515 +0.575977 0.484265 +0.023121 0.483477 +0.584626 0.039438 +0.588445 0.470220 +0.022647 0.048570 +0.011366 0.033315 +0.021163 0.457629 +0.010236 0.471286 +0.568987 0.048584 +0.579109 0.033070 +0.583495 0.477411 +0.572214 0.462156 +0.018040 0.053177 +0.006416 0.040506 +0.025874 0.462141 +0.015752 0.477654 +0.492728 0.609730 +0.493178 0.983298 +0.031504 0.983855 +0.031053 0.610287 +0.145240 0.568377 +0.436617 0.567900 +0.436667 0.572985 +0.145290 0.573462 +0.454310 0.567727 +0.454359 0.572813 +0.469033 0.567586 +0.469082 0.572673 +0.062037 0.594887 +0.467714 0.594043 +0.492339 0.593785 +0.492414 0.600863 +0.459939 0.558897 +0.459894 0.553811 +0.442248 0.559053 +0.442203 0.553968 +0.150867 0.559248 +0.150821 0.554163 +0.133177 0.559415 +0.133128 0.554329 +0.118456 0.559557 +0.118407 0.554471 +0.466655 0.585821 +0.060981 0.586666 +0.036348 0.586924 +0.036274 0.579844 +0.127549 0.568553 +0.127599 0.573638 +0.060907 0.579586 +0.062112 0.601967 +0.467789 0.601122 +0.466581 0.578742 +0.512822 0.944557 +0.511907 0.618459 +0.506170 0.975643 +0.037405 0.595148 +0.037480 0.602228 +0.499686 0.982019 +0.474658 0.558767 +0.474613 0.553682 +0.024999 0.982873 +0.018565 0.979944 +0.012324 0.975126 +0.011410 0.649029 +0.018062 0.617942 +0.491281 0.585561 +0.491207 0.578482 +0.024546 0.611567 +0.112829 0.568699 +0.112880 0.573784 +0.499232 0.610713 +0.505666 0.613641 +1.000000 0.000000 +0.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +1.000000 0.032800 +1.000000 0.967200 +0.967200 0.000000 +0.032800 0.000000 +0.000000 0.967200 +0.000000 0.032800 +0.967200 0.000000 +0.032800 0.000000 +1.000000 0.032800 +1.000000 0.967200 +0.032800 1.000000 +0.967200 1.000000 +0.000000 0.967200 +0.000000 0.032800 +0.032800 1.000000 +0.967200 1.000000 +1.000000 0.500000 +0.000000 0.500000 +0.000000 0.500000 +1.000000 0.500000 +1.000000 0.500000 +0.000000 0.500000 +1.000000 0.500000 +0.000000 0.500000 +0.967200 0.500000 +0.032800 0.500000 +0.967200 0.500000 +0.032800 0.500000 +1.000000 0.250000 +0.000000 0.250000 +1.000000 0.250000 +0.000000 0.250000 +1.000000 0.250000 +0.000000 0.250000 +0.032800 0.250000 +0.032800 0.250000 +0.000000 0.250000 +1.000000 0.250000 +0.967200 0.250000 +0.967200 0.250000 +1.000000 0.000000 +0.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +1.000000 0.032800 +1.000000 0.967200 +0.967200 0.000000 +0.032800 0.000000 +0.000000 0.967200 +0.000000 0.032800 +0.967200 0.000000 +0.032800 0.000000 +1.000000 0.032800 +1.000000 0.967200 +0.032800 1.000000 +0.967200 1.000000 +0.000000 0.967200 +0.000000 0.032800 +0.032800 1.000000 +0.967200 1.000000 +1.000000 0.500000 +0.000000 0.500000 +0.000000 0.500000 +1.000000 0.500000 +1.000000 0.500000 +0.000000 0.500000 +1.000000 0.500000 +0.000000 0.500000 +0.967200 0.500000 +0.032800 0.500000 +0.967200 0.500000 +0.032800 0.500000 +1.000000 0.250000 +0.000000 0.250000 +1.000000 0.250000 +0.000000 0.250000 +1.000000 0.250000 +0.000000 0.250000 +0.032800 0.250000 +0.032800 0.250000 +0.000000 0.250000 +1.000000 0.250000 +0.967200 0.250000 +0.967200 0.250000 +1.000000 0.000000 +0.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +1.000000 0.000000 +0.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 + + + + + + + + + + + +

19 0 2 0 1 0 16 2 1 0 3 0 19 4 2 1 5 3 13 6 4 4 7 5 0 8 0 13 9 4 0 10 0 1 11 3 15 12 8 5 13 9 9 14 6 15 15 8 9 16 6 3 17 7 14 18 12 7 19 13 11 20 10 14 21 12 11 22 10 10 23 11 12 24 16 6 25 17 2 26 14 12 27 16 2 28 14 8 29 15 13 30 4 1 31 3 26 32 18 26 33 18 1 34 3 19 35 2 25 36 19 16 37 1 4 38 5 4 39 5 16 40 1 0 41 0 15 42 8 3 43 7 30 44 21 30 45 21 3 46 7 23 47 20 14 48 12 10 49 11 28 50 23 28 51 23 10 52 11 21 53 22 26 54 18 19 55 2 27 56 25 27 57 25 19 58 2 18 59 24 27 60 25 18 61 24 5 62 9 5 63 9 18 64 24 9 65 6 24 66 26 17 67 27 25 68 19 25 69 19 17 70 27 16 71 1 12 72 16 8 73 15 24 74 26 24 75 26 8 76 15 17 77 27 30 78 21 23 79 20 31 80 29 31 81 29 23 82 20 22 83 28 31 84 29 22 85 28 7 86 13 7 87 13 22 88 28 11 89 10 28 90 23 21 91 22 29 92 31 29 93 31 21 94 22 20 95 30 29 96 31 20 97 30 6 98 17 6 99 17 20 100 30 2 101 14 45 102 32 36 103 33 44 104 35 44 105 35 36 106 33 37 107 34 33 108 38 32 109 39 48 110 36 33 111 38 48 112 36 53 113 37 34 114 41 33 115 38 53 116 37 34 117 41 53 118 37 58 119 40 35 120 43 34 121 41 58 122 40 35 123 43 58 124 40 59 125 42 36 126 65 35 127 72 59 128 71 36 129 65 59 130 71 49 131 44 37 132 66 36 133 65 49 134 44 37 135 66 49 136 44 55 137 45 38 138 47 37 139 66 55 140 45 38 141 47 55 142 45 62 143 46 39 144 49 38 145 75 62 146 74 39 147 49 62 148 74 63 149 48 40 150 51 39 151 49 63 152 48 40 153 51 63 154 48 51 155 50 41 156 53 40 157 51 51 158 50 41 159 53 51 160 50 54 161 52 42 162 55 41 163 53 54 164 52 42 165 55 54 166 52 60 167 54 43 168 57 42 169 55 60 170 54 43 171 57 60 172 54 61 173 56 44 174 67 43 175 82 61 176 81 44 177 67 61 178 81 50 179 58 45 180 64 44 181 67 50 182 58 45 183 64 50 184 58 52 185 59 46 186 61 45 187 64 52 188 59 46 189 61 52 190 59 56 191 60 47 192 63 46 193 85 56 194 84 47 195 63 56 196 84 57 197 62 32 198 39 47 199 63 57 200 62 32 201 39 57 202 62 48 203 36 44 204 35 38 205 76 43 206 83 38 207 76 44 208 35 37 209 34 43 210 83 39 211 77 42 212 80 43 213 83 38 214 76 39 215 77 40 216 78 42 217 80 39 218 77 42 219 80 40 220 78 41 221 79 36 222 33 45 223 32 46 224 86 46 225 86 35 226 73 36 227 33 35 228 73 46 229 86 47 230 87 35 231 73 47 232 87 34 233 70 32 234 69 34 235 70 47 236 87 34 237 70 32 238 69 33 239 68 23 240 20 2 241 14 20 242 30 2 243 14 23 244 20 3 245 7 22 246 28 20 247 30 21 248 22 20 249 30 22 250 28 23 251 20 21 252 22 11 253 10 22 254 28 11 255 10 21 256 22 10 257 11 9 258 6 2 259 14 3 260 7 2 261 14 9 262 6 8 263 15 9 264 6 17 265 27 8 266 15 17 267 27 9 268 6 18 269 24 18 270 24 16 271 1 17 272 27 16 273 1 18 274 24 19 275 2 93 276 148 65 277 97 88 278 140 65 279 97 93 280 148 64 281 96 89 282 143 66 283 105 90 284 144 66 285 105 89 286 143 67 287 104 74 288 116 73 289 113 66 290 90 74 291 116 66 292 90 67 293 91 72 294 112 65 295 89 64 296 88 65 297 89 72 298 112 75 299 117 70 300 94 77 301 121 71 302 95 77 303 121 70 304 94 78 305 124 79 306 125 69 307 93 76 308 120 69 309 93 79 310 125 68 311 92 94 312 150 67 313 101 89 314 142 67 315 101 94 316 150 74 317 118 85 318 137 76 319 122 69 320 102 69 321 102 80 322 129 85 323 137 95 324 151 64 325 109 93 326 149 64 327 109 95 328 151 72 329 114 87 330 139 78 331 126 70 332 110 70 333 110 83 334 135 87 335 139 68 336 98 81 337 130 69 338 99 69 339 99 81 340 130 80 341 128 82 342 133 70 343 107 71 344 106 70 345 107 82 346 133 83 347 134 77 348 123 84 349 136 71 350 103 71 351 103 84 352 136 82 353 132 85 354 137 80 355 129 88 356 141 85 357 137 88 358 141 91 359 146 79 360 127 86 361 138 68 362 111 68 363 111 86 364 138 81 365 131 87 366 139 83 367 135 90 368 145 87 369 139 90 370 145 92 371 147 80 372 128 81 373 130 93 374 148 80 375 128 93 376 148 88 377 140 83 378 134 82 379 133 89 380 143 83 381 134 89 382 143 90 383 144 84 384 136 94 385 150 82 386 132 82 387 132 94 388 150 89 389 142 86 390 138 95 391 151 81 392 131 81 393 131 95 394 151 93 395 149 88 396 141 65 397 100 91 398 146 91 399 146 65 400 100 75 401 119 90 402 145 66 403 108 92 404 147 92 405 147 66 406 108 73 407 115 86 408 110 87 409 111 92 410 116 86 411 110 92 412 116 95 413 119 84 414 108 85 415 109 91 416 115 84 417 108 91 418 115 94 419 118 87 420 111 86 421 110 84 422 108 84 423 108 86 424 110 85 425 109 95 426 119 94 427 118 91 428 115 94 429 118 95 430 119 92 431 116 73 432 115 94 433 150 92 434 116 94 435 150 73 436 115 74 437 116 75 438 119 95 439 151 91 440 115 95 441 151 75 442 119 72 443 112 78 444 124 87 445 139 77 446 123 77 447 123 87 448 139 84 449 108 76 450 120 85 451 137 79 452 127 79 453 127 85 454 137 86 455 110 125 456 212 97 457 161 120 458 204 97 459 161 125 460 212 96 461 160 121 462 207 98 463 169 122 464 208 98 465 169 121 466 207 99 467 168 106 468 180 105 469 177 98 470 154 106 471 180 98 472 154 99 473 155 97 474 153 96 475 152 104 476 176 97 477 153 104 478 176 107 479 181 103 480 159 102 481 158 110 482 188 103 483 159 110 484 188 109 485 185 108 486 184 111 487 189 100 488 156 108 489 184 100 490 156 101 491 157 126 492 214 99 493 165 121 494 206 99 495 165 126 496 214 106 497 182 117 498 201 108 499 186 101 500 166 101 501 166 112 502 193 117 503 201 127 504 215 96 505 173 125 506 213 96 507 173 127 508 215 104 509 178 119 510 203 110 511 190 102 512 174 102 513 174 115 514 199 119 515 203 100 516 162 113 517 194 101 518 163 101 519 163 113 520 194 112 521 192 103 522 170 114 523 197 102 524 171 102 525 171 114 526 197 115 527 198 109 528 187 116 529 200 103 530 167 103 531 167 116 532 200 114 533 196 117 534 201 112 535 193 120 536 205 117 537 201 120 538 205 123 539 210 111 540 191 118 541 202 100 542 175 100 543 175 118 544 202 113 545 195 119 546 203 115 547 199 122 548 209 119 549 203 122 550 209 124 551 211 125 552 212 112 553 192 113 554 194 112 555 192 125 556 212 120 557 204 115 558 198 114 559 197 121 560 207 115 561 198 121 562 207 122 563 208 116 564 200 126 565 214 114 566 196 114 567 196 126 568 214 121 569 206 127 570 215 113 571 195 118 572 202 113 573 195 127 574 215 125 575 213 120 576 205 97 577 164 123 578 210 123 579 210 97 580 164 107 581 183 122 582 209 98 583 172 124 584 211 124 585 211 98 586 172 105 587 179 118 588 174 119 589 175 124 590 180 118 591 174 124 592 180 127 593 183 116 594 172 117 595 173 123 596 179 116 597 172 123 598 179 126 599 182 119 600 175 118 601 174 116 602 172 116 603 172 118 604 174 117 605 173 127 606 183 126 607 182 123 608 179 126 609 182 127 610 183 124 611 180 105 612 179 126 613 214 124 614 180 126 615 214 105 616 179 106 617 180 123 618 179 107 619 183 127 620 215 127 621 215 107 622 183 104 623 176 110 624 188 119 625 203 109 626 187 109 627 187 119 628 203 116 629 172 108 630 184 117 631 201 111 632 191 111 633 191 117 634 201 118 635 174 129 636 217 128 637 216 131 638 219 128 639 216 130 640 218 131 641 219 135 642 223 134 643 222 132 644 220 135 645 223 132 646 220 133 647 221 133 648 227 132 649 226 128 650 224 133 651 227 128 652 224 129 653 225 135 654 231 133 655 230 129 656 228 135 657 231 129 658 228 131 659 229 134 660 235 135 661 234 131 662 232 134 663 235 131 664 232 130 665 233 132 666 239 134 667 238 130 668 236 132 669 239 130 670 236 128 671 237 137 672 241 136 673 240 139 674 243 136 675 240 138 676 242 139 677 243 143 678 247 142 679 246 140 680 244 143 681 247 140 682 244 141 683 245 141 684 251 140 685 250 136 686 248 141 687 251 136 688 248 137 689 249 143 690 255 141 691 254 137 692 252 143 693 255 137 694 252 139 695 253 142 696 259 143 697 258 139 698 256 142 699 259 139 700 256 138 701 257 140 702 263 142 703 262 138 704 260 140 705 263 138 706 260 136 707 261

+
+
+
+ + + 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.0000001.000000 + 30.0000000.0000003.333333 + + + + + +
diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_DeskC_01/meshes/aws_robomaker_warehouse_DeskC_01_visual.DAE b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_DeskC_01/meshes/aws_robomaker_warehouse_DeskC_01_visual.DAE new file mode 100755 index 0000000..398d91d --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_DeskC_01/meshes/aws_robomaker_warehouse_DeskC_01_visual.DAE @@ -0,0 +1,4729 @@ + + + FBX COLLADA exporter2019-05-24T05:15:49Z2019-05-24T05:15:49ZZ_UP + + + ../materials/textures/aws_robomaker_warehouse_DeskC_01.png + + + ../materials/textures/aws_robomaker_warehouse_DeskC_02.png + + + ../materials/textures/aws_robomaker_warehouse_DeskC_03.png + + + ../materials/textures/aws_robomaker_warehouse_DeskC_04.png + + + + + + + + + + + + + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + +-37.371174 -61.648491 -0.000007 +-37.371174 -65.510582 -0.000007 +-28.368664 -61.648491 -0.000007 +-28.793972 -65.935890 -0.000007 +-37.371174 -61.648491 90.633255 +-36.945866 -65.935890 90.633255 +-28.368664 -61.648491 90.633255 +-28.368664 -65.510582 90.633255 +-36.782421 -61.648491 -0.000007 +-36.782444 -65.004433 -0.000007 +-28.957417 -61.648491 -0.000007 +-29.382778 -65.429733 -0.000007 +-36.782421 -61.648491 90.633255 +-36.357136 -65.429733 90.633255 +-28.957417 -61.648491 90.633255 +-28.957462 -65.004433 90.633255 +-36.945866 -65.935890 -0.000007 +-28.368664 -65.510582 -0.000007 +-37.371174 -65.510582 90.633255 +-28.793972 -65.935890 90.633255 +-36.357136 -65.429733 -0.000007 +-28.957462 -65.004433 -0.000007 +-36.782444 -65.004433 90.633255 +-29.382778 -65.429733 90.633255 +-37.371159 61.648521 -0.000007 +-37.371159 65.510612 -0.000007 +-37.371159 65.510612 90.633255 +-37.371159 61.648521 90.633255 +-36.945850 65.935921 -0.000007 +-28.793957 65.935921 -0.000007 +-28.793957 65.935921 90.633255 +-36.945850 65.935921 90.633255 +-28.368649 65.510612 -0.000007 +-28.368649 61.648521 -0.000007 +-28.368649 61.648521 90.633255 +-28.368649 65.510612 90.633255 +-36.782429 65.004463 90.633255 +-36.782429 65.004463 -0.000007 +-36.782406 61.648521 -0.000007 +-36.782406 61.648521 90.633255 +-29.382763 65.429764 90.633255 +-29.382763 65.429764 -0.000007 +-36.357121 65.429764 -0.000007 +-36.357121 65.429764 90.633255 +-28.957401 61.648521 90.633255 +-28.957401 61.648521 -0.000007 +-28.957447 65.004463 -0.000007 +-28.957447 65.004463 90.633255 +36.987122 -61.648502 -0.000004 +36.987122 -65.510590 -0.000004 +36.987122 -65.510590 90.633263 +36.987122 -61.648502 90.633263 +36.561813 -65.935905 -0.000004 +28.409920 -65.935898 -0.000004 +28.409920 -65.935898 90.633263 +36.561813 -65.935905 90.633263 +27.984612 -65.510582 -0.000004 +27.984613 -61.648502 -0.000004 +27.984613 -61.648502 90.633263 +27.984612 -65.510582 90.633263 +36.398388 -65.004448 90.633263 +36.398388 -65.004448 -0.000004 +36.398376 -61.648502 -0.000004 +36.398376 -61.648502 90.633263 +28.998718 -65.429741 90.633263 +28.998718 -65.429741 -0.000004 +35.973080 -65.429749 -0.000004 +35.973080 -65.429749 90.633263 +28.573370 -61.648502 90.633263 +28.573370 -61.648502 -0.000004 +28.573410 -65.004440 -0.000004 +28.573410 -65.004440 90.633263 +36.987144 61.648502 -0.000004 +36.987144 61.648502 90.633263 +36.987144 65.510582 90.633263 +36.987144 65.510582 -0.000004 +36.561836 65.935890 -0.000004 +36.561836 65.935890 90.633263 +28.409943 65.935898 90.633263 +28.409943 65.935898 -0.000004 +27.984634 65.510590 -0.000004 +27.984634 65.510590 90.633263 +27.984632 61.648502 90.633263 +27.984632 61.648502 -0.000004 +36.398411 65.004448 90.633263 +36.398396 61.648502 90.633263 +36.398396 61.648502 -0.000004 +36.398411 65.004448 -0.000004 +28.998741 65.429756 90.633263 +35.973103 65.429749 90.633263 +35.973103 65.429749 -0.000004 +28.998741 65.429756 -0.000004 +28.573389 61.648502 90.633263 +28.573433 65.004456 90.633263 +28.573433 65.004456 -0.000004 +28.573389 61.648502 -0.000004 +-44.096615 74.151192 89.855537 +-44.096645 -74.151161 89.855537 +40.481560 77.766266 89.855537 +40.481537 -77.766266 89.855537 +-40.481541 77.766281 89.855537 +-40.481571 -77.766251 89.855537 +44.096638 74.151169 89.855537 +44.096615 -74.151169 89.855537 +-43.092430 76.762085 89.855537 +-43.092461 -76.762054 89.855537 +43.092449 76.762054 89.855537 +43.092426 -76.762054 89.855537 +-44.096615 74.151192 95.154335 +-44.096645 -74.151161 95.154335 +-43.092461 -76.762054 95.154335 +-40.481571 -77.766251 95.154335 +40.481537 -77.766266 95.154335 +43.092426 -76.762054 95.154335 +44.096615 -74.151169 95.154335 +44.096638 74.151169 95.154335 +43.092449 76.762054 95.154335 +40.481560 77.766266 95.154335 +-40.481541 77.766281 95.154335 +-43.092430 76.762085 95.154335 +-37.371159 65.163902 18.550394 +-37.371159 65.163902 14.688301 +-28.368649 65.163902 18.550394 +-28.793957 65.163902 14.262994 +-37.371174 -65.135574 18.550390 +-36.945866 -65.135574 14.262988 +-28.368664 -65.135574 18.550390 +-28.368664 -65.135574 14.688295 +-36.782406 65.163902 18.550394 +-36.782429 65.163902 15.194448 +-28.957401 65.163902 18.550394 +-29.382763 65.163902 14.769140 +-36.782421 -65.135574 18.550390 +-36.357136 -65.135574 14.769135 +-28.957417 -65.135574 18.550390 +-28.957462 -65.135574 15.194443 +-36.945850 65.163902 14.262994 +-28.368649 65.163902 14.688301 +-37.371174 -65.135574 14.688295 +-28.793972 -65.135574 14.262988 +-36.357121 65.163902 14.769140 +-28.957447 65.163902 15.194448 +-36.782444 -65.135574 15.194443 +-29.382778 -65.135574 14.769135 +36.987144 65.163887 18.550394 +36.987144 65.163887 14.688301 +36.987122 -65.135582 14.688295 +36.987122 -65.135582 18.550390 +36.561836 65.163887 14.262994 +28.409943 65.163895 14.262994 +28.409920 -65.135574 14.262988 +36.561813 -65.135582 14.262988 +27.984634 65.163895 14.688301 +27.984634 65.163895 18.550394 +27.984612 -65.135574 18.550390 +27.984612 -65.135574 14.688295 +36.398388 -65.135582 15.194441 +36.398411 65.163887 15.194448 +36.398399 65.163887 18.550394 +36.398376 -65.135582 18.550390 +28.998718 -65.135574 14.769133 +28.998741 65.163895 14.769140 +35.973103 65.163887 14.769140 +35.973080 -65.135582 14.769133 +28.573368 -65.135574 18.550390 +28.573391 65.163895 18.550394 +28.573433 65.163895 15.194448 +28.573410 -65.135574 15.194441 +-8.839386 -1.124335 120.142776 +-8.839371 -1.124274 143.656052 +31.564835 1.174650 143.656052 +31.564850 1.174649 120.142776 +-7.012421 -33.232262 120.142776 +33.391754 -30.933304 120.142776 +33.391754 -30.933304 143.656052 +-7.012421 -33.232262 143.656052 +-10.217209 0.013418 95.154068 +-10.217209 0.013487 120.323105 +33.032242 2.474308 120.323105 +33.032227 2.474310 95.154068 +-8.261658 -34.355511 95.154068 +34.987778 -31.894663 95.154068 +34.987778 -31.894663 120.323105 +-8.261658 -34.355511 120.323105 +33.170959 -61.850304 94.926239 +33.170959 -61.850349 106.544884 +-11.221756 -63.979034 106.544884 +-11.221756 -63.978981 94.926231 +31.866714 -34.649704 94.926239 +-12.525970 -36.778488 94.926239 +31.866760 -34.649704 106.544884 +-12.525970 -36.778381 106.544884 +33.515305 -61.201118 106.616203 +33.515335 -61.201187 118.234840 +-10.799744 -64.580566 118.234840 +-10.799744 -64.580566 106.616203 +31.444778 -34.048119 106.616203 +-12.870300 -37.427612 106.616203 +31.444778 -34.048187 118.234856 +-12.870300 -37.427559 118.234856 +33.515305 -61.201118 118.267174 +33.515335 -61.201187 129.885818 +-10.799744 -64.580566 129.885818 +-10.799744 -64.580566 118.267174 +31.444778 -34.048119 118.267174 +-12.870300 -37.427612 118.267174 +31.444778 -34.048187 129.885849 +-12.870300 -37.427559 129.885849 +9.794342 37.798069 119.188225 +3.209122 35.349949 98.549019 +3.852448 35.407131 98.492424 +4.444046 35.299751 96.616112 +5.399490 35.292645 95.483986 +5.622528 35.362576 96.034935 +3.935608 35.219280 96.259140 +17.493607 34.796902 95.325691 +17.494156 34.832615 95.657379 +6.781326 40.094135 109.247612 +6.490082 39.284817 108.072975 +6.291733 40.043987 109.247368 +5.982925 39.230625 108.075325 +6.049271 39.337070 106.686401 +5.520767 39.280712 106.691681 +5.627258 40.230923 105.617523 +5.081772 40.175091 105.624931 +10.942154 38.004017 120.243004 +10.193771 45.751507 120.243065 +10.177948 37.881214 119.711403 +9.418365 45.744717 119.711426 +9.024170 45.771511 119.188240 +6.081131 42.807156 109.417725 +5.642166 43.701550 108.350983 +6.329254 41.410091 109.760117 +2.021210 47.647732 98.549026 +4.871170 42.938259 105.795296 +5.180008 43.751621 106.967339 +4.833679 41.572155 105.282547 +3.276367 35.262211 97.473366 +2.066772 47.784870 97.473358 +2.701431 47.996349 96.259117 +4.149612 48.232090 95.483925 +15.958237 50.508831 95.325737 +19.289413 48.025524 95.305946 +17.425827 50.201374 95.317146 +18.597351 49.328053 95.310188 +20.283737 37.731731 95.306038 +19.958191 36.235332 95.309853 +18.861191 35.081440 95.317566 +19.957306 36.261181 95.594955 +18.861511 35.112644 95.625374 +17.432632 50.161282 95.624092 +15.966064 50.463970 95.657906 +4.383850 48.186581 96.034981 +3.217102 48.002018 96.616119 +2.692047 47.830471 97.593102 +2.666641 47.717113 98.491417 +9.312943 45.816120 119.056030 +6.147690 43.743908 108.349861 +9.641861 45.795330 119.476784 +10.359253 45.802021 119.963753 +19.294113 47.992107 95.580040 +20.282898 37.755699 95.579964 +6.569717 42.849995 109.418747 +6.811752 41.455944 109.761650 +8.399658 66.996185 138.911606 +8.491974 68.214172 137.726425 +8.395630 67.787796 138.502792 +14.055084 42.234097 120.488914 +14.542694 68.798599 103.251373 +13.243729 16.847363 138.911636 +14.866409 67.620819 102.066193 +14.718872 68.398560 102.474998 +19.710480 17.471996 102.066223 +19.618179 16.254036 103.251396 +19.714523 16.680370 102.475037 +13.567459 15.669559 137.726456 +13.391266 16.069614 138.502823 +3.899246 35.332874 97.593117 +10.083771 37.814251 119.056686 +10.406143 37.882626 119.476814 +11.113235 37.996014 119.963791 +18.602417 49.292431 95.596718 +5.385223 41.625027 105.274612 +5.415634 42.986820 105.788658 +7.937836 67.743698 138.421829 +7.942062 66.951996 138.830704 +12.786133 16.803127 138.830704 +12.933502 16.025257 138.421860 +14.085876 68.754532 103.170433 +14.261398 68.354462 102.393860 +8.034958 68.170090 137.645493 +19.161362 16.209816 103.170464 +19.257050 16.636074 102.393890 +13.110443 15.625324 137.645493 +25.414459 28.043316 95.179214 +25.418060 28.006012 95.191711 +25.389145 28.012619 95.191711 +25.377136 28.039730 95.191711 +22.731979 55.814083 95.179199 +22.694641 55.810474 95.191696 +36.761642 29.139393 95.179214 +36.765244 29.102077 95.191711 +22.728348 55.851398 95.191696 +22.691940 55.838467 95.201073 +36.798965 29.142998 95.191711 +36.792343 29.114094 95.191711 +34.075546 56.947475 95.191696 +34.079163 56.910137 95.179199 +34.116486 56.913746 95.191696 +34.103546 56.950184 95.201073 +14.409119 67.576645 101.985069 +19.253174 17.427784 101.985085 +22.694656 55.810482 95.466698 +22.691940 55.838467 95.457314 +22.682190 55.809261 95.429199 +22.691040 55.847797 95.429199 +22.682190 55.809261 95.229202 +22.691040 55.847797 95.229195 +25.364685 28.038525 95.429207 +25.377136 28.039730 95.466713 +25.390060 28.003307 95.457336 +25.380737 28.002392 95.429214 +25.364685 28.038525 95.229210 +25.380737 28.002392 95.229210 +34.112885 56.951077 95.229195 +34.128922 56.914928 95.229195 +34.128922 56.914928 95.429199 +34.112885 56.951077 95.429199 +34.103546 56.950184 95.457329 +34.116486 56.913746 95.466705 +36.798965 29.142998 95.466713 +36.811401 29.144199 95.429214 +36.811401 29.144199 95.229210 +36.802567 29.105679 95.229210 +36.802567 29.105679 95.429207 +36.801682 29.115009 95.457329 +25.414459 28.043316 95.479210 +25.418060 28.006012 95.466713 +36.765244 29.102077 95.466698 +36.761642 29.139393 95.479210 +22.731979 55.814083 95.479195 +22.728348 55.851398 95.466690 +34.079163 56.910137 95.479195 +34.075546 56.947475 95.466698 +34.074356 56.959904 95.429199 +22.727173 55.863857 95.429192 +34.074356 56.959904 95.229195 +22.727173 55.863857 95.229195 +25.419266 27.993565 95.429207 +25.419266 27.993565 95.229210 +36.766434 29.089626 95.429214 +36.766434 29.089626 95.229210 +8.875153 62.633190 130.125168 +12.347427 62.968586 110.341133 +16.347610 21.556057 110.341148 +12.875320 21.220657 130.125198 +5.706863 43.796139 106.963295 +33.308685 61.916687 95.506653 +31.478622 62.127151 96.195732 +31.523453 61.126381 95.942497 +24.229050 65.209167 95.209259 +22.995453 65.245811 95.508545 +24.239578 65.976151 95.865448 +23.196915 64.997963 95.351723 +22.472351 64.432724 95.414940 +23.190933 64.390694 95.194878 +25.852982 66.261078 96.083122 +25.923660 65.550308 95.186516 +28.548569 66.531967 96.164497 +28.618683 65.845886 95.192871 +30.931152 66.653091 95.941063 +31.052338 65.991043 95.195488 +32.716156 65.789085 95.279411 +32.894592 66.274818 95.492935 +33.526642 65.612503 95.414780 +32.975647 64.083923 95.162445 +33.857742 64.266319 95.414543 +31.305969 63.900269 95.003670 +28.854935 63.638275 94.980034 +26.152710 63.350006 94.989548 +33.863617 62.887047 95.414757 +33.082840 62.283501 95.303398 +31.504776 61.670441 95.259155 +29.162766 60.772652 96.164505 +29.101639 61.318420 95.265442 +26.405197 61.048401 95.256676 +26.465652 60.516106 96.083031 +24.739441 60.474792 95.837830 +24.700653 61.005707 95.276756 +24.403503 63.164505 95.021141 +22.546204 62.959801 95.414940 +23.302948 62.962952 95.166229 +23.578613 61.270309 95.309288 +23.000015 61.238602 95.430061 +23.550720 60.775475 95.516197 +33.125885 62.488159 95.720337 +33.013794 64.099106 95.809570 +29.052628 61.811325 96.436462 +26.344406 61.535881 96.350693 +24.622101 61.428223 96.106300 +28.857330 63.655716 96.590515 +26.140381 63.366035 96.480820 +24.377808 63.177887 96.199455 +23.494446 61.460281 95.724808 +23.255325 63.058197 95.815071 +23.151169 64.675156 95.724678 +24.245789 64.955109 96.106339 +25.952560 65.210144 96.350792 +28.659363 65.498062 96.436424 +31.098511 65.690918 96.195641 +31.323120 63.918724 96.299789 +32.783615 65.694832 95.720421 + + + + + + + + + + + +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 -0.000007 0.000000 +1.000000 -0.000007 0.000000 +1.000000 -0.000007 0.000000 +1.000000 -0.000007 0.000000 +1.000000 -0.000007 0.000000 +1.000000 -0.000007 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000014 0.000000 +-1.000000 0.000014 0.000000 +-1.000000 0.000014 0.000000 +-1.000000 0.000014 0.000000 +-1.000000 0.000014 0.000000 +-1.000000 0.000014 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.707100 0.707113 0.000000 +0.707100 0.707113 0.000000 +0.707100 0.707113 0.000000 +0.707100 0.707113 0.000000 +0.707100 0.707113 0.000000 +0.707100 0.707113 0.000000 +-0.707094 0.707119 0.000000 +-0.707094 0.707119 0.000000 +-0.707094 0.707119 0.000000 +-0.707094 0.707119 0.000000 +-0.707094 0.707119 0.000000 +-0.707094 0.707119 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000007 0.000000 +1.000000 0.000007 0.000000 +1.000000 0.000007 0.000000 +1.000000 0.000007 0.000000 +1.000000 0.000007 0.000000 +1.000000 0.000007 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-1.000000 -0.000014 0.000000 +-1.000000 -0.000014 0.000000 +-1.000000 -0.000014 0.000000 +-1.000000 -0.000014 0.000000 +-1.000000 -0.000014 0.000000 +-1.000000 -0.000014 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.707101 -0.707113 0.000000 +0.707101 -0.707113 0.000000 +0.707101 -0.707113 0.000000 +0.707101 -0.707113 0.000000 +0.707101 -0.707113 0.000000 +0.707101 -0.707113 0.000000 +-0.707094 -0.707119 0.000000 +-0.707094 -0.707119 0.000000 +-0.707094 -0.707119 0.000000 +-0.707094 -0.707119 0.000000 +-0.707094 -0.707119 0.000000 +-0.707094 -0.707119 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.000001 -1.000000 0.000000 +-0.000001 -1.000000 0.000000 +-0.000001 -1.000000 0.000000 +-0.000001 -1.000000 0.000000 +-0.000001 -1.000000 0.000000 +-0.000001 -1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 -0.000003 0.000000 +-1.000000 -0.000003 0.000000 +-1.000000 -0.000003 0.000000 +-1.000000 -0.000003 0.000000 +-1.000000 -0.000003 0.000000 +-1.000000 -0.000003 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +1.000000 0.000012 0.000000 +1.000000 0.000012 0.000000 +1.000000 0.000012 0.000000 +1.000000 0.000012 0.000000 +1.000000 0.000012 0.000000 +1.000000 0.000012 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.707113 -0.707100 0.000000 +0.707113 -0.707100 0.000000 +0.707113 -0.707100 0.000000 +0.707113 -0.707100 0.000000 +0.707113 -0.707100 0.000000 +0.707113 -0.707100 0.000000 +-0.707113 -0.707100 0.000000 +-0.707113 -0.707100 0.000000 +-0.707113 -0.707100 0.000000 +-0.707113 -0.707100 0.000000 +-0.707113 -0.707100 0.000000 +-0.707113 -0.707100 0.000000 +-0.707101 0.707113 0.000000 +-0.707101 0.707113 0.000000 +-0.707101 0.707113 0.000000 +-0.707101 0.707113 0.000000 +-0.707101 0.707113 0.000000 +-0.707101 0.707113 0.000000 +0.707101 0.707113 0.000000 +0.707101 0.707113 0.000000 +0.707101 0.707113 0.000000 +0.707101 0.707113 0.000000 +0.707101 0.707113 0.000000 +0.707101 0.707113 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000005 0.000000 +-1.000000 0.000005 0.000000 +-1.000000 0.000005 0.000000 +-1.000000 0.000005 0.000000 +-1.000000 0.000005 0.000000 +-1.000000 0.000005 0.000000 +-0.000001 -1.000000 0.000000 +-0.000001 -1.000000 0.000000 +-0.000001 -1.000000 0.000000 +-0.000001 -1.000000 0.000000 +-0.000001 -1.000000 0.000000 +-0.000001 -1.000000 0.000000 +1.000000 -0.000013 0.000000 +1.000000 -0.000013 0.000000 +1.000000 -0.000013 0.000000 +1.000000 -0.000013 0.000000 +1.000000 -0.000013 0.000000 +1.000000 -0.000013 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.707101 -0.707113 0.000000 +-0.707101 -0.707113 0.000000 +-0.707101 -0.707113 0.000000 +-0.707101 -0.707113 0.000000 +-0.707101 -0.707113 0.000000 +-0.707101 -0.707113 0.000000 +0.707101 -0.707113 0.000000 +0.707101 -0.707113 0.000000 +0.707101 -0.707113 0.000000 +0.707101 -0.707113 0.000000 +0.707101 -0.707113 0.000000 +0.707101 -0.707113 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.182561 0.983195 0.000000 +-0.182559 0.983195 0.000000 +0.182561 0.983195 0.000000 +-0.182559 0.983195 0.000000 +0.182561 0.983195 0.000000 +-0.182559 0.983195 0.000000 +-0.707108 0.707105 0.000000 +-0.983195 0.182557 0.000000 +-0.983195 0.182557 0.000000 +-0.983195 0.182557 0.000000 +-0.707108 0.707105 0.000000 +-0.707108 0.707105 0.000000 +-0.707108 -0.707105 0.000000 +-0.707108 -0.707105 0.000000 +-0.182559 -0.983195 0.000000 +-0.182559 -0.983195 0.000000 +-0.707108 -0.707105 0.000000 +-0.182559 -0.983195 0.000000 +0.707109 -0.707104 0.000000 +0.707109 -0.707104 0.000000 +0.983195 -0.182558 0.000000 +0.983195 -0.182558 0.000000 +0.707109 -0.707104 0.000000 +0.983195 -0.182558 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.983195 -0.182556 0.000000 +-0.983195 0.182557 0.000000 +-0.983195 0.182557 0.000000 +-0.983195 -0.182556 0.000000 +-0.983195 0.182557 0.000000 +-0.983195 -0.182556 0.000000 +-0.983195 -0.182556 0.000000 +-0.983195 -0.182556 0.000000 +-0.707108 -0.707105 0.000000 +-0.707108 -0.707105 0.000000 +-0.983195 -0.182556 0.000000 +-0.707108 -0.707105 0.000000 +-0.182559 -0.983195 0.000000 +0.182561 -0.983195 0.000000 +-0.182559 -0.983195 0.000000 +0.182561 -0.983195 0.000000 +-0.182559 -0.983195 0.000000 +0.182561 -0.983195 0.000000 +0.182561 -0.983195 0.000000 +0.182561 -0.983195 0.000000 +0.707109 -0.707104 0.000000 +0.707109 -0.707104 0.000000 +0.182561 -0.983195 0.000000 +0.707109 -0.707104 0.000000 +0.983195 -0.182558 0.000000 +0.983195 0.182558 0.000000 +0.983195 -0.182558 0.000000 +0.983195 0.182558 0.000000 +0.983195 -0.182558 0.000000 +0.983195 0.182558 0.000000 +0.983195 0.182558 0.000000 +0.983195 0.182558 0.000000 +0.707109 0.707104 0.000000 +0.707109 0.707104 0.000000 +0.983195 0.182558 0.000000 +0.707109 0.707104 0.000000 +0.707109 0.707104 0.000000 +0.707109 0.707104 0.000000 +0.182561 0.983195 0.000000 +0.182561 0.983195 0.000000 +0.707109 0.707104 0.000000 +0.182561 0.983195 0.000000 +-0.182559 0.983195 0.000000 +-0.182559 0.983195 0.000000 +-0.707108 0.707105 0.000000 +-0.707108 0.707105 0.000000 +-0.182559 0.983195 0.000000 +-0.707108 0.707105 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 -0.000007 +1.000000 -0.000000 -0.000007 +1.000000 -0.000000 -0.000007 +1.000000 -0.000000 -0.000007 +1.000000 -0.000000 -0.000007 +1.000000 -0.000000 -0.000007 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +-1.000000 0.000000 0.000014 +-1.000000 0.000000 0.000014 +-1.000000 0.000000 0.000014 +-1.000000 0.000000 0.000014 +-1.000000 0.000000 0.000014 +-1.000000 0.000000 0.000014 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +-0.707106 0.000000 -0.707108 +-0.707106 0.000000 -0.707108 +-0.707106 0.000000 -0.707108 +-0.707106 0.000000 -0.707108 +-0.707106 0.000000 -0.707108 +-0.707106 0.000000 -0.707108 +0.707106 -0.000000 -0.707108 +0.707106 -0.000000 -0.707108 +0.707106 -0.000000 -0.707108 +0.707106 -0.000000 -0.707108 +0.707106 -0.000000 -0.707108 +0.707106 -0.000000 -0.707108 +0.707106 -0.000000 0.707107 +0.707106 -0.000000 0.707107 +0.707106 -0.000000 0.707107 +0.707106 -0.000000 0.707107 +0.707106 -0.000000 0.707107 +0.707106 -0.000000 0.707107 +-0.707100 0.000000 0.707114 +-0.707100 0.000000 0.707114 +-0.707100 0.000000 0.707114 +-0.707100 0.000000 0.707114 +-0.707100 0.000000 0.707114 +-0.707100 0.000000 0.707114 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 -0.000003 +-1.000000 0.000000 -0.000003 +-1.000000 0.000000 -0.000003 +-1.000000 0.000000 -0.000003 +-1.000000 0.000000 -0.000003 +-1.000000 0.000000 -0.000003 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +1.000000 -0.000000 0.000013 +1.000000 -0.000000 0.000013 +1.000000 -0.000000 0.000013 +1.000000 -0.000000 0.000013 +1.000000 -0.000000 0.000013 +1.000000 -0.000000 0.000013 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.707106 -0.000000 -0.707108 +0.707106 -0.000000 -0.707108 +0.707106 -0.000000 -0.707108 +0.707106 -0.000000 -0.707108 +0.707106 -0.000000 -0.707108 +0.707106 -0.000000 -0.707108 +-0.707106 0.000000 -0.707108 +-0.707106 0.000000 -0.707108 +-0.707106 0.000000 -0.707108 +-0.707106 0.000000 -0.707108 +-0.707106 0.000000 -0.707108 +-0.707106 0.000000 -0.707108 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +0.707107 -0.000000 0.707107 +0.707107 -0.000000 0.707107 +0.707107 -0.000000 0.707107 +0.707107 -0.000000 0.707107 +0.707107 -0.000000 0.707107 +0.707107 -0.000000 0.707107 +-0.056807 0.998385 -0.000001 +-0.056807 0.998385 -0.000001 +-0.056807 0.998385 -0.000001 +-0.056807 0.998385 -0.000001 +-0.056807 0.998385 -0.000001 +-0.056807 0.998385 -0.000001 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.998385 0.056807 0.000000 +0.998385 0.056807 0.000000 +0.998385 0.056807 0.000000 +0.998385 0.056807 0.000000 +0.998385 0.056807 0.000000 +0.998385 0.056807 0.000000 +0.056807 -0.998385 0.000000 +0.056807 -0.998385 0.000000 +0.056807 -0.998385 0.000000 +0.056807 -0.998385 0.000000 +0.056807 -0.998385 0.000000 +0.056807 -0.998385 0.000000 +-0.998385 -0.056809 0.000000 +-0.998385 -0.056809 0.000000 +-0.998385 -0.056809 0.000000 +-0.998385 -0.056809 0.000000 +-0.998385 -0.056809 0.000000 +-0.998385 -0.056809 0.000000 +-0.056807 0.998385 -0.000001 +-0.056807 0.998385 -0.000001 +-0.056807 0.998385 -0.000001 +-0.056807 0.998385 -0.000001 +-0.056807 0.998385 -0.000001 +-0.056807 0.998385 -0.000001 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.998385 0.056807 -0.000000 +0.998385 0.056807 -0.000000 +0.998385 0.056807 -0.000000 +0.998385 0.056807 -0.000000 +0.998385 0.056807 -0.000000 +0.998385 0.056807 -0.000000 +0.056807 -0.998385 0.000000 +0.056807 -0.998385 0.000000 +0.056807 -0.998385 0.000000 +0.056807 -0.998385 0.000000 +0.056807 -0.998385 0.000000 +0.056807 -0.998385 0.000000 +-0.998385 -0.056807 0.000000 +-0.998385 -0.056807 0.000000 +-0.998385 -0.056807 0.000000 +-0.998385 -0.056807 0.000000 +-0.998385 -0.056807 0.000000 +-0.998385 -0.056807 0.000000 +0.047896 -0.998852 -0.000004 +0.047896 -0.998852 -0.000004 +0.047896 -0.998852 -0.000004 +0.047896 -0.998852 -0.000004 +0.047896 -0.998852 -0.000004 +0.047896 -0.998852 -0.000004 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.998852 0.047893 -0.000002 +0.998852 0.047893 -0.000002 +0.998852 0.047893 -0.000002 +0.998852 0.047893 -0.000002 +0.998852 0.047893 -0.000002 +0.998852 0.047893 -0.000002 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.998852 -0.047893 0.000000 +-0.998852 -0.047893 0.000000 +-0.998853 -0.047893 0.000000 +-0.998852 -0.047893 0.000000 +-0.998853 -0.047893 0.000000 +-0.998852 -0.047893 0.000000 +-0.047897 0.998852 -0.000004 +-0.047897 0.998852 -0.000004 +-0.047897 0.998852 -0.000004 +-0.047897 0.998852 -0.000004 +-0.047897 0.998852 -0.000004 +-0.047897 0.998852 -0.000004 +0.076038 -0.997105 -0.000003 +0.076038 -0.997105 -0.000003 +0.076038 -0.997105 -0.000003 +0.076038 -0.997105 -0.000003 +0.076038 -0.997105 -0.000003 +0.076038 -0.997105 -0.000003 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.997105 0.076034 -0.000001 +0.997105 0.076034 -0.000001 +0.997105 0.076034 -0.000001 +0.997105 0.076034 -0.000001 +0.997105 0.076034 -0.000001 +0.997105 0.076034 -0.000001 +0.000000 -0.000001 1.000000 +0.000000 -0.000001 1.000000 +0.000000 -0.000001 1.000000 +0.000000 -0.000001 1.000000 +0.000000 -0.000001 1.000000 +0.000000 -0.000001 1.000000 +-0.997105 -0.076034 0.000000 +-0.997105 -0.076034 0.000000 +-0.997105 -0.076034 0.000000 +-0.997105 -0.076034 0.000000 +-0.997105 -0.076034 0.000000 +-0.997105 -0.076034 0.000000 +-0.076038 0.997105 0.000001 +-0.076038 0.997105 0.000001 +-0.076038 0.997105 0.000001 +-0.076038 0.997105 0.000001 +-0.076038 0.997105 0.000001 +-0.076038 0.997105 0.000001 +0.076038 -0.997105 -0.000003 +0.076038 -0.997105 -0.000003 +0.076038 -0.997105 -0.000003 +0.076038 -0.997105 -0.000003 +0.076038 -0.997105 -0.000003 +0.076038 -0.997105 -0.000003 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.997105 0.076034 -0.000001 +0.997105 0.076034 -0.000001 +0.997105 0.076034 -0.000001 +0.997105 0.076034 -0.000001 +0.997105 0.076034 -0.000001 +0.997105 0.076034 -0.000001 +0.000000 -0.000001 1.000000 +0.000000 -0.000001 1.000000 +0.000000 -0.000001 1.000000 +0.000000 -0.000001 1.000000 +0.000000 -0.000001 1.000000 +0.000000 -0.000001 1.000000 +-0.997105 -0.076034 0.000000 +-0.997105 -0.076034 0.000000 +-0.997105 -0.076034 0.000000 +-0.997105 -0.076034 0.000000 +-0.997105 -0.076034 0.000000 +-0.997105 -0.076034 0.000000 +-0.076038 0.997105 0.000001 +-0.076038 0.997105 0.000001 +-0.076038 0.997105 0.000001 +-0.076038 0.997105 0.000001 +-0.076038 0.997105 0.000001 +-0.076038 0.997105 0.000001 +-0.894910 -0.308786 0.322160 +-0.884446 -0.102399 0.455270 +-0.914800 -0.245199 0.320964 +0.034962 -0.993747 0.106042 +0.095796 -0.991586 0.087064 +0.095794 -0.991587 0.087061 +0.022914 -0.993696 0.109741 +0.095796 -0.991586 0.087064 +0.034962 -0.993747 0.106042 +0.022914 -0.993696 0.109741 +0.082047 -0.989854 0.116006 +0.080800 -0.989940 0.116145 +0.082047 -0.989854 0.116006 +0.022914 -0.993696 0.109741 +0.034962 -0.993747 0.106042 +-0.059996 0.589474 -0.805557 +-0.100291 0.944861 -0.311736 +-0.067044 0.650716 -0.756356 +-0.100291 0.944861 -0.311736 +-0.103584 0.975661 -0.193277 +-0.067044 0.650716 -0.756356 +-0.100291 0.944861 -0.311736 +-0.095563 0.937572 0.334406 +-0.103584 0.975661 -0.193277 +-0.095563 0.937572 0.334406 +-0.089447 0.894973 0.437060 +-0.103584 0.975661 -0.193277 +-0.095563 0.937572 0.334406 +-0.044960 0.540904 0.839882 +-0.089447 0.894973 0.437060 +-0.044960 0.540904 0.839882 +-0.039044 0.490865 0.870360 +-0.089447 0.894973 0.437060 +-0.696848 -0.067315 0.714052 +-0.695053 -0.067142 0.715817 +-0.564298 -0.054514 0.823769 +-0.564298 -0.054514 0.823769 +-0.695053 -0.067142 0.715817 +-0.564298 -0.054514 0.823769 +-0.888900 -0.068381 0.452968 +-0.695053 -0.067142 0.715817 +-0.696848 -0.067315 0.714052 +-0.695053 -0.067142 0.715817 +-0.888900 -0.068381 0.452968 +-0.884446 -0.102399 0.455270 +-0.945513 -0.091326 0.312512 +-0.888900 -0.068381 0.452968 +-0.944512 0.048460 0.324881 +-0.888900 -0.068381 0.452968 +-0.945513 -0.091332 0.312512 +-0.884446 -0.102399 0.455270 +-0.945513 -0.091332 0.312512 +-0.888900 -0.068381 0.452968 +-0.945513 -0.091326 0.312512 +-0.945512 -0.091327 0.312517 +-0.984184 -0.028610 0.174824 +-0.945512 -0.091330 0.312515 +-0.944512 0.048460 0.324881 +-0.984184 -0.028610 0.174824 +-0.945512 -0.091327 0.312517 +-0.984184 -0.028610 0.174824 +-0.970173 -0.166491 0.176198 +-0.945513 -0.091333 0.312513 +-0.984184 -0.028610 0.174824 +-0.945513 -0.091333 0.312513 +-0.945512 -0.091330 0.312515 +-0.970173 -0.166491 0.176198 +-0.945514 -0.091326 0.312510 +-0.945513 -0.091331 0.312511 +-0.945513 -0.091333 0.312513 +-0.970173 -0.166491 0.176198 +-0.945513 -0.091331 0.312511 +-0.953813 -0.092132 -0.285924 +-0.955152 -0.092262 -0.281376 +-0.984184 -0.028610 0.174824 +-0.970173 -0.166491 0.176198 +-0.984184 -0.028610 0.174824 +-0.955152 -0.092262 -0.281376 +-0.953813 -0.092132 -0.285924 +-0.693562 -0.066995 -0.717275 +-0.955152 -0.092262 -0.281376 +-0.693562 -0.066995 -0.717275 +-0.953813 -0.092132 -0.285924 +-0.690150 -0.066666 -0.720589 +-0.693562 -0.066995 -0.717275 +-0.690150 -0.066666 -0.720589 +-0.233076 -0.022519 -0.972198 +-0.233076 -0.022519 -0.972198 +-0.690150 -0.066666 -0.720589 +-0.235194 -0.022722 -0.971683 +-0.011215 -0.000976 -0.999937 +-0.233076 -0.022519 -0.972198 +-0.235194 -0.022722 -0.971683 +-0.233076 -0.022519 -0.972198 +-0.011215 -0.000976 -0.999937 +-0.009327 -0.001069 -0.999956 +-0.009327 -0.001069 -0.999956 +-0.011215 -0.000976 -0.999937 +-0.010358 -0.000892 -0.999946 +-0.010358 -0.000892 -0.999946 +-0.011215 -0.000976 -0.999937 +-0.005818 0.000164 -0.999983 +-0.010358 -0.000892 -0.999946 +-0.005818 0.000164 -0.999983 +-0.005818 0.000164 -0.999983 +-0.006246 -0.000758 -0.999980 +-0.009327 -0.001069 -0.999956 +-0.010358 -0.000892 -0.999946 +-0.009327 -0.001069 -0.999956 +-0.006246 -0.000758 -0.999980 +-0.005661 -0.001311 -0.999983 +-0.009327 -0.001069 -0.999956 +-0.005661 -0.001311 -0.999983 +-0.005661 -0.001311 -0.999983 +0.489289 -0.867677 0.087938 +0.876674 -0.478765 0.047187 +0.887842 -0.457921 0.045217 +0.876674 -0.478765 0.047187 +0.489289 -0.867677 0.087938 +0.477266 -0.874267 0.088739 +0.008796 0.990106 0.140044 +0.400480 0.909619 0.110493 +0.007350 0.990104 0.140140 +0.400480 0.909619 0.110493 +0.008796 0.990106 0.140044 +0.415477 0.903028 0.109176 +0.007350 0.990104 0.140140 +-0.144185 0.979960 0.137438 +0.008796 0.990106 0.140044 +-0.144185 0.979960 0.137438 +0.007350 0.990104 0.140140 +-0.136214 0.981444 0.134956 +-0.095436 0.987911 0.122162 +-0.144185 0.979960 0.137438 +-0.136214 0.981444 0.134956 +-0.136214 0.981444 0.134956 +-0.095437 0.987911 0.122165 +-0.095436 0.987911 0.122162 +-0.095403 0.987927 0.122062 +-0.095437 0.987911 0.122165 +-0.095398 0.987929 0.122050 +-0.095437 0.987911 0.122165 +-0.095403 0.987927 0.122062 +-0.095436 0.987911 0.122162 +-0.095359 0.987946 0.121941 +-0.095403 0.987927 0.122062 +-0.095398 0.987929 0.122050 +-0.095403 0.987927 0.122062 +-0.095359 0.987946 0.121941 +-0.095359 0.987946 0.121941 +-0.937979 0.111219 0.328370 +-0.944512 0.048460 0.324881 +-0.888900 -0.068381 0.452968 +-0.944512 0.048460 0.324881 +-0.937979 0.111219 0.328370 +-0.984184 -0.028610 0.174824 +0.907183 0.126177 -0.401369 +0.943226 0.162213 -0.289847 +0.987753 0.104459 -0.115896 +-0.095542 0.987799 0.122986 +-0.094443 0.987858 0.123362 +-0.095542 0.987799 0.122986 +-0.095542 0.987799 0.122986 +-0.094443 0.987858 0.123362 +-0.094442 0.987857 0.123362 +-0.094443 0.987858 0.123362 +-0.093352 0.987915 0.123734 +-0.094442 0.987857 0.123362 +-0.094442 0.987857 0.123362 +-0.093352 0.987915 0.123734 +-0.093352 0.987915 0.123734 +0.961460 0.274410 0.017123 +0.998675 -0.050885 0.007691 +0.997688 -0.067341 0.009147 +0.961460 0.274410 0.017123 +0.997688 -0.067341 0.009147 +0.953010 0.302233 0.020686 +0.076094 -0.897797 -0.433786 +0.044065 -0.488238 -0.871597 +0.048511 -0.545170 -0.836921 +0.048511 -0.545170 -0.836921 +0.079604 -0.942633 -0.324201 +0.076094 -0.897797 -0.433786 +-0.005119 0.065282 -0.997854 +0.044065 -0.488238 -0.871597 +-0.004444 0.058336 -0.998287 +0.044065 -0.488238 -0.871597 +-0.005119 0.065282 -0.997854 +0.048511 -0.545170 -0.836921 +-0.067044 0.650716 -0.756356 +-0.005119 0.065282 -0.997854 +-0.059996 0.589474 -0.805557 +-0.059996 0.589474 -0.805557 +-0.005119 0.065282 -0.997854 +-0.004444 0.058336 -0.998287 +0.980245 0.094682 0.173653 +0.980556 0.091409 0.173647 +0.980245 0.094683 0.173652 +0.980245 0.094682 0.173653 +0.980245 0.094683 0.173652 +0.980245 0.094681 0.173655 +0.980556 0.091409 0.173647 +0.980246 0.094685 0.173647 +0.980245 0.094683 0.173652 +0.980244 0.094688 0.173652 +0.980556 0.091409 0.173647 +0.980245 0.094682 0.173653 +0.980246 0.094685 0.173647 +0.980556 0.091409 0.173647 +0.980246 0.094685 0.173647 +0.980246 0.094685 0.173647 +0.980246 0.094685 0.173647 +0.980246 0.094685 0.173647 +0.980556 0.091409 0.173647 +0.980246 0.094686 0.173647 +0.980246 0.094685 0.173647 +0.980556 0.091409 0.173647 +0.980854 0.088165 0.173644 +0.980246 0.094686 0.173647 +0.980246 0.094686 0.173647 +0.980854 0.088165 0.173644 +0.980245 0.094686 0.173647 +0.980556 0.091409 0.173647 +0.981791 0.077091 0.173621 +0.980854 0.088165 0.173644 +0.981791 0.077091 0.173621 +0.980556 0.091409 0.173647 +0.981032 0.086166 0.173645 +0.981032 0.086166 0.173645 +0.980556 0.091409 0.173647 +0.980244 0.094688 0.173652 +0.981032 0.086166 0.173645 +0.980244 0.094688 0.173652 +0.980244 0.094688 0.173653 +0.489289 -0.867677 0.087938 +0.082047 -0.989854 0.116006 +0.477266 -0.874267 0.088739 +0.082047 -0.989854 0.116006 +0.489289 -0.867677 0.087938 +0.080800 -0.989940 0.116145 +0.095796 -0.991586 0.087064 +0.095787 -0.991596 0.086962 +0.095794 -0.991587 0.087061 +0.095787 -0.991597 0.086952 +0.095794 -0.991587 0.087061 +0.095787 -0.991596 0.086962 +0.095787 -0.991604 0.086867 +0.095787 -0.991597 0.086952 +0.095787 -0.991596 0.086962 +0.095787 -0.991597 0.086952 +0.095787 -0.991604 0.086867 +0.095787 -0.991604 0.086867 +0.913813 0.045537 -0.403575 +0.989072 0.085694 -0.119970 +0.956566 0.012053 -0.291267 +0.957507 -0.021930 -0.287574 +0.989072 0.085694 -0.119970 +0.913813 0.045537 -0.403575 +0.095697 -0.991544 0.087648 +0.096726 -0.991399 0.088164 +0.096719 -0.991400 0.088160 +0.095697 -0.991544 0.087648 +0.096719 -0.991400 0.088160 +0.095697 -0.991544 0.087648 +0.097741 -0.991254 0.088672 +0.096726 -0.991399 0.088164 +0.097741 -0.991254 0.088672 +0.096726 -0.991399 0.088164 +0.097741 -0.991254 0.088672 +0.096719 -0.991400 0.088160 +0.747958 0.660113 0.069351 +0.415477 0.903028 0.109176 +0.765427 0.640081 0.066459 +0.415477 0.903028 0.109176 +0.747958 0.660113 0.069351 +0.400480 0.909619 0.110493 +0.953010 0.302233 0.020686 +0.765427 0.640081 0.066459 +0.961460 0.274410 0.017123 +0.765427 0.640081 0.066459 +0.953010 0.302233 0.020686 +0.747958 0.660113 0.069351 +0.876674 -0.478765 0.047187 +0.997688 -0.067341 0.009147 +0.887842 -0.457921 0.045217 +0.998675 -0.050885 0.007691 +0.887842 -0.457921 0.045217 +0.997688 -0.067341 0.009147 +-0.039044 0.490865 0.870360 +0.018733 -0.063991 0.997775 +0.018089 -0.057084 0.998205 +0.018733 -0.063991 0.997775 +-0.039044 0.490865 0.870360 +-0.044960 0.540904 0.839882 +0.018733 -0.063991 0.997775 +0.066135 -0.646321 0.760194 +0.062316 -0.590375 0.804720 +0.062316 -0.590375 0.804720 +0.018089 -0.057084 0.998205 +0.018733 -0.063991 0.997775 +-0.189901 0.692069 0.696403 +-0.189905 0.692018 0.696453 +-0.190541 0.222693 0.956087 +-0.189905 0.692018 0.696453 +-0.190541 0.222691 0.956087 +-0.190541 0.222693 0.956087 +-0.190541 0.222691 0.956087 +-0.144401 -0.255027 0.956091 +-0.190541 0.222693 0.956087 +-0.144401 -0.255027 0.956091 +-0.190541 0.222691 0.956087 +-0.144399 -0.255045 0.956086 +-0.053930 -0.715570 0.696456 +-0.144401 -0.255027 0.956091 +-0.144399 -0.255045 0.956086 +-0.144401 -0.255027 0.956091 +-0.053930 -0.715570 0.696456 +-0.053918 -0.715611 0.696415 +0.987753 0.104459 -0.115896 +0.949992 0.091486 -0.298573 +0.949992 0.091488 -0.298573 +0.949992 0.091484 -0.298572 +0.989072 0.085694 -0.119970 +0.949992 0.091488 -0.298573 +0.949992 0.091488 -0.298573 +0.989072 0.085694 -0.119970 +0.987753 0.104459 -0.115896 +0.956566 0.012053 -0.291267 +0.989072 0.085694 -0.119970 +0.949993 0.091481 -0.298571 +0.949993 0.091481 -0.298571 +0.989072 0.085694 -0.119970 +0.949992 0.091484 -0.298572 +0.913813 0.045537 -0.403575 +0.949992 0.091485 -0.298572 +0.907183 0.126177 -0.401369 +0.907183 0.126177 -0.401369 +0.949992 0.091485 -0.298572 +0.949992 0.091490 -0.298571 +0.943226 0.162213 -0.289847 +0.907183 0.126177 -0.401369 +0.949992 0.091490 -0.298571 +0.686032 0.066194 -0.724554 +0.907183 0.126177 -0.401369 +0.687764 0.066360 -0.722895 +0.907183 0.126177 -0.401369 +0.686032 0.066194 -0.724554 +0.913813 0.045537 -0.403575 +0.987753 0.104459 -0.115896 +0.989072 0.085694 -0.119970 +0.955110 0.092195 0.281541 +0.987753 0.104459 -0.115896 +0.955110 0.092195 0.281541 +0.953695 0.092060 0.286341 +0.678939 0.065580 0.731260 +0.953695 0.092060 0.286341 +0.955110 0.092195 0.281541 +0.953695 0.092060 0.286341 +0.678939 0.065580 0.731260 +0.675427 0.065240 0.734535 +0.229456 0.022162 0.973067 +0.231462 0.022354 0.972587 +0.675427 0.065240 0.734535 +0.675427 0.065240 0.734535 +0.678939 0.065580 0.731260 +0.229456 0.022162 0.973067 +0.229456 0.022162 0.973067 +0.029721 0.002419 0.999555 +0.231462 0.022354 0.972587 +0.029721 0.002419 0.999555 +0.027664 0.003301 0.999612 +0.028855 0.002329 0.999581 +0.027664 0.003301 0.999612 +0.029721 0.002419 0.999555 +0.229456 0.022162 0.973067 +0.022922 -0.000632 0.999737 +0.028855 0.002329 0.999581 +0.022922 -0.000632 0.999737 +0.029721 0.002419 0.999555 +0.028855 0.002329 0.999581 +0.022922 -0.000632 0.999737 +0.028855 0.002329 0.999581 +0.027664 0.003301 0.999612 +0.024653 0.002956 0.999692 +0.022343 0.005161 0.999737 +0.027664 0.003301 0.999612 +0.022343 0.005161 0.999737 +0.024653 0.002956 0.999692 +0.027664 0.003301 0.999612 +0.022343 0.005161 0.999737 +-0.051697 0.970308 -0.236282 +0.054470 0.715626 -0.696357 +-0.051685 0.970295 -0.236340 +0.054470 0.715626 -0.696357 +-0.051697 0.970308 -0.236282 +0.054458 0.715668 -0.696314 +-0.134620 0.962300 0.236341 +-0.051697 0.970308 -0.236282 +-0.134630 0.962281 0.236412 +-0.134630 0.962281 0.236412 +-0.051697 0.970308 -0.236282 +-0.051685 0.970295 -0.236340 +-0.189905 0.692018 0.696453 +-0.134620 0.962300 0.236341 +-0.134630 0.962281 0.236412 +-0.134620 0.962300 0.236341 +-0.189905 0.692018 0.696453 +-0.189901 0.692069 0.696403 +0.165839 -0.872948 -0.458759 +0.190477 -0.692014 -0.696301 +0.165839 -0.872948 -0.458759 +0.190477 -0.692014 -0.696301 +0.165839 -0.872948 -0.458759 +0.190480 -0.691974 -0.696340 +-0.923439 -0.345052 -0.167928 +-0.969930 -0.213588 -0.116691 +-0.971514 -0.195910 -0.133340 +0.004824 -0.888495 0.458861 +-0.053918 -0.715611 0.696415 +-0.053930 -0.715570 0.696456 +-0.053918 -0.715611 0.696415 +0.004824 -0.888495 0.458861 +0.004824 -0.888495 0.458861 +-0.190545 -0.231267 -0.954048 +-0.160408 -0.194804 -0.967637 +-0.068716 -0.279452 -0.957698 +-0.160408 -0.194804 -0.967637 +-0.190545 -0.231267 -0.954048 +-0.261074 -0.120885 -0.957720 +-0.227399 0.187367 -0.955606 +-0.160408 -0.194804 -0.967637 +-0.261074 -0.120885 -0.957720 +-0.261074 -0.120885 -0.957720 +-0.325911 0.126454 -0.936905 +-0.227399 0.187367 -0.955606 +0.120916 -0.261176 -0.957688 +-0.068716 -0.279452 -0.957698 +-0.160408 -0.194804 -0.967637 +0.120916 -0.261176 -0.957688 +-0.160408 -0.194804 -0.967637 +0.194761 -0.160497 -0.967631 +-0.227399 0.187367 -0.955606 +-0.325911 0.126454 -0.936905 +-0.329093 0.271054 -0.904559 +-0.227399 0.187367 -0.955606 +-0.329093 0.271054 -0.904559 +-0.174379 0.297418 -0.938688 +0.120916 -0.261176 -0.957688 +0.194761 -0.160497 -0.967631 +0.231283 -0.190598 -0.954034 +0.231283 -0.190598 -0.954034 +0.194761 -0.160497 -0.967631 +0.279412 -0.068717 -0.957709 +-0.227399 0.187367 -0.955606 +0.126459 0.325880 -0.936915 +0.187396 0.227419 -0.955596 +0.126459 0.325880 -0.936915 +-0.227399 0.187367 -0.955606 +-0.174379 0.297418 -0.938688 +0.279412 -0.068717 -0.957709 +0.187396 0.227419 -0.955596 +0.297459 0.174288 -0.938692 +0.187396 0.227419 -0.955596 +0.279412 -0.068717 -0.957709 +0.194761 -0.160497 -0.967631 +0.187396 0.227419 -0.955596 +0.271080 0.329024 -0.904576 +0.297459 0.174288 -0.938692 +0.271080 0.329024 -0.904576 +0.187396 0.227419 -0.955596 +0.126459 0.325880 -0.936915 +0.686032 0.066194 -0.724554 +0.560466 0.054132 -0.826407 +0.560466 0.054132 -0.826407 +0.560466 0.054132 -0.826407 +0.686032 0.066194 -0.724554 +0.687764 0.066360 -0.722895 +0.144974 0.255092 -0.955987 +0.054458 0.715668 -0.696314 +0.144973 0.255098 -0.955985 +0.054458 0.715668 -0.696314 +0.144974 0.255092 -0.955987 +0.054470 0.715626 -0.696357 +0.191142 -0.222642 -0.955979 +0.144974 0.255092 -0.955987 +0.191140 -0.222622 -0.955984 +0.191140 -0.222622 -0.955984 +0.144974 0.255092 -0.955987 +0.144973 0.255098 -0.955985 +0.190477 -0.692014 -0.696301 +0.190480 -0.691974 -0.696340 +0.191142 -0.222642 -0.955979 +0.190477 -0.692014 -0.696301 +0.191142 -0.222642 -0.955979 +0.191140 -0.222622 -0.955984 +-0.962306 0.002818 0.271955 +-0.969875 0.119390 0.212341 +-0.990299 0.038395 0.133544 +-0.969875 0.119390 0.212341 +-0.979309 0.178460 0.095428 +-0.990299 0.038395 0.133544 +-0.979309 0.178460 0.095428 +-0.990313 0.038435 -0.133430 +-0.990299 0.038395 0.133544 +-0.990313 0.038435 -0.133430 +-0.979309 0.178460 0.095428 +-0.979309 0.178506 -0.095337 +-0.920325 -0.234400 0.313142 +-0.990299 0.038395 0.133544 +-0.955865 -0.248949 0.156033 +-0.990299 0.038395 0.133544 +-0.920325 -0.234400 0.313142 +-0.962306 0.002818 0.271955 +-0.871378 -0.386948 0.301614 +-0.920325 -0.234400 0.313142 +-0.955865 -0.248949 0.156033 +-0.871378 -0.386948 0.301614 +-0.955865 -0.248949 0.156033 +-0.902531 -0.400868 0.157301 +-0.990299 0.038395 0.133544 +-0.955899 -0.248885 -0.155927 +-0.955865 -0.248949 0.156033 +-0.955899 -0.248885 -0.155927 +-0.990299 0.038395 0.133544 +-0.990313 0.038435 -0.133430 +-0.969911 0.119520 -0.212103 +-0.990313 0.038435 -0.133430 +-0.979309 0.178506 -0.095337 +-0.990313 0.038435 -0.133430 +-0.969911 0.119520 -0.212103 +-0.962365 0.002879 -0.271746 +-0.990313 0.038435 -0.133430 +-0.917476 -0.246380 -0.312305 +-0.955899 -0.248885 -0.155927 +-0.917476 -0.246380 -0.312305 +-0.990313 0.038435 -0.133430 +-0.962365 0.002879 -0.271746 +-0.955865 -0.248949 0.156033 +-0.904328 -0.401518 -0.144827 +-0.902531 -0.400868 0.157301 +-0.904328 -0.401518 -0.144827 +-0.955865 -0.248949 0.156033 +-0.955899 -0.248885 -0.155927 +-0.904328 -0.401518 -0.144827 +-0.955899 -0.248885 -0.155927 +-0.871572 -0.386711 -0.301359 +-0.955899 -0.248885 -0.155927 +-0.917476 -0.246380 -0.312305 +-0.871572 -0.386711 -0.301359 +0.902676 0.400575 -0.157211 +0.955941 0.248771 -0.155853 +0.871496 0.386838 -0.301415 +0.955941 0.248771 -0.155853 +0.920454 0.234411 -0.312756 +0.871496 0.386838 -0.301415 +0.955945 0.248771 0.155830 +0.955941 0.248771 -0.155853 +0.902683 0.400573 0.157176 +0.902683 0.400573 0.157176 +0.955941 0.248771 -0.155853 +0.902676 0.400575 -0.157211 +0.920469 0.234411 0.312710 +0.955945 0.248771 0.155830 +0.871517 0.386839 0.301352 +0.871517 0.386839 0.301352 +0.955945 0.248771 0.155830 +0.902683 0.400573 0.157176 +0.990346 -0.038268 0.133232 +0.920469 0.234411 0.312710 +0.962475 -0.002661 0.271356 +0.920469 0.234411 0.312710 +0.990346 -0.038268 0.133232 +0.955945 0.248771 0.155830 +0.985875 -0.061392 -0.155824 +0.920454 0.234411 -0.312756 +0.955941 0.248771 -0.155853 +0.920454 0.234411 -0.312756 +0.985875 -0.061392 -0.155824 +0.947723 -0.066399 -0.312111 +0.955945 0.248771 0.155830 +0.990346 -0.038268 0.133232 +0.985875 -0.061392 -0.155824 +0.955945 0.248771 0.155830 +0.985875 -0.061392 -0.155824 +0.955941 0.248771 -0.155853 +0.964427 -0.221148 -0.144822 +0.929417 -0.213069 -0.301305 +0.985875 -0.061392 -0.155824 +0.985875 -0.061392 -0.155824 +0.929417 -0.213069 -0.301305 +0.947723 -0.066399 -0.312111 +0.979389 -0.178190 0.095109 +0.985875 -0.061392 -0.155824 +0.990346 -0.038268 0.133232 +0.985875 -0.061392 -0.155824 +0.979389 -0.178190 0.095109 +0.964427 -0.221148 -0.144822 +0.962475 -0.002661 0.271356 +0.970051 -0.119135 0.211679 +0.990346 -0.038268 0.133232 +0.970051 -0.119135 0.211679 +0.979389 -0.178190 0.095109 +0.990346 -0.038268 0.133232 +-0.140195 -0.170276 0.975373 +-0.297521 -0.174300 0.938670 +-0.271180 -0.329135 0.904506 +-0.140195 -0.170276 0.975373 +-0.271180 -0.329135 0.904506 +-0.126523 -0.326098 0.936831 +-0.140195 -0.170276 0.975373 +0.174277 -0.297782 0.938591 +0.170129 -0.140343 0.975377 +-0.126523 -0.326098 0.936831 +0.174277 -0.297782 0.938591 +-0.140195 -0.170276 0.975373 +-0.297521 -0.174300 0.938670 +-0.170151 0.140221 0.975391 +-0.325974 0.126570 0.936868 +-0.170151 0.140221 0.975391 +-0.297521 -0.174300 0.938670 +-0.140195 -0.170276 0.975373 +-0.329147 0.271195 0.904498 +-0.170151 0.140221 0.975391 +-0.174413 0.297532 0.938645 +-0.170151 0.140221 0.975391 +-0.329147 0.271195 0.904498 +-0.325974 0.126570 0.936868 +0.140124 0.170152 0.975404 +-0.140195 -0.170276 0.975373 +0.170129 -0.140343 0.975377 +-0.140195 -0.170276 0.975373 +0.140124 0.170152 0.975404 +-0.170151 0.140221 0.975391 +0.170129 -0.140343 0.975377 +0.328983 -0.271448 0.904481 +0.325848 -0.126699 0.936894 +0.328983 -0.271448 0.904481 +0.170129 -0.140343 0.975377 +0.174277 -0.297782 0.938591 +0.140124 0.170152 0.975404 +0.325848 -0.126699 0.936894 +0.297323 0.174270 0.938738 +0.325848 -0.126699 0.936894 +0.140124 0.170152 0.975404 +0.170129 -0.140343 0.975377 +-0.170151 0.140221 0.975391 +0.126351 0.325905 0.936921 +-0.174413 0.297532 0.938645 +0.126351 0.325905 0.936921 +-0.170151 0.140221 0.975391 +0.140124 0.170152 0.975404 +0.270893 0.329001 0.904641 +0.126351 0.325905 0.936921 +0.140124 0.170152 0.975404 +0.140124 0.170152 0.975404 +0.297323 0.174270 0.938738 +0.270893 0.329001 0.904641 +0.002624 0.962448 0.271453 +0.119029 0.970064 0.211678 +0.038200 0.990343 0.133269 +0.119029 0.970064 0.211678 +0.178011 0.979420 0.095118 +0.038200 0.990343 0.133269 +-0.234600 0.920346 0.312930 +0.038200 0.990343 0.133269 +-0.249008 0.955867 0.155927 +0.038200 0.990343 0.133269 +-0.234600 0.920346 0.312930 +0.002624 0.962448 0.271453 +0.038207 0.990342 -0.133275 +0.038200 0.990343 0.133269 +0.178011 0.979420 0.095118 +0.178011 0.979420 0.095118 +0.178025 0.979417 -0.095126 +0.038207 0.990342 -0.133275 +0.178025 0.979417 -0.095126 +0.119056 0.970055 -0.211704 +0.038207 0.990342 -0.133275 +0.038207 0.990342 -0.133275 +0.119056 0.970055 -0.211704 +0.002627 0.962444 -0.271469 +0.038207 0.990342 -0.133275 +-0.234614 0.920348 -0.312914 +-0.249014 0.955865 -0.155928 +-0.234614 0.920348 -0.312914 +0.038207 0.990342 -0.133275 +0.002627 0.962444 -0.271469 +-0.249008 0.955867 0.155927 +0.038200 0.990343 0.133269 +0.038207 0.990342 -0.133275 +-0.249008 0.955867 0.155927 +0.038207 0.990342 -0.133275 +-0.249014 0.955865 -0.155928 +-0.387173 0.871286 0.301593 +-0.234600 0.920346 0.312930 +-0.249008 0.955867 0.155927 +-0.387173 0.871286 0.301593 +-0.249008 0.955867 0.155927 +-0.401062 0.902441 0.157319 +-0.401076 0.902441 -0.157282 +-0.401062 0.902441 0.157319 +-0.249008 0.955867 0.155927 +-0.249008 0.955867 0.155927 +-0.249014 0.955865 -0.155928 +-0.401076 0.902441 -0.157282 +-0.401076 0.902441 -0.157282 +-0.249014 0.955865 -0.155928 +-0.387200 0.871285 -0.301559 +-0.249014 0.955865 -0.155928 +-0.234614 0.920348 -0.312914 +-0.387200 0.871285 -0.301559 +-0.002701 -0.962351 0.271797 +-0.119150 -0.969929 0.212230 +-0.038222 -0.990318 0.133453 +-0.119150 -0.969929 0.212230 +-0.178051 -0.979385 0.095407 +-0.038222 -0.990318 0.133453 +-0.178051 -0.979385 0.095407 +-0.220854 -0.964484 -0.144895 +-0.038222 -0.990318 0.133453 +-0.038222 -0.990318 0.133453 +-0.220854 -0.964484 -0.144895 +-0.061242 -0.985866 -0.155938 +0.234477 -0.920351 0.313009 +-0.038222 -0.990318 0.133453 +0.248936 -0.955876 0.155985 +-0.038222 -0.990318 0.133453 +0.234477 -0.920351 0.313009 +-0.002701 -0.962351 0.271797 +-0.061242 -0.985866 -0.155938 +-0.220854 -0.964484 -0.144895 +-0.212703 -0.929458 -0.301439 +-0.061242 -0.985866 -0.155938 +-0.212703 -0.929458 -0.301439 +-0.066213 -0.947665 -0.312326 +0.386984 -0.871383 0.301554 +0.234477 -0.920351 0.313009 +0.248936 -0.955876 0.155985 +0.386984 -0.871383 0.301554 +0.248936 -0.955876 0.155985 +0.400884 -0.902527 0.157281 +-0.038222 -0.990318 0.133453 +0.248903 -0.955896 -0.155918 +0.248936 -0.955876 0.155985 +0.248903 -0.955896 -0.155918 +-0.038222 -0.990318 0.133453 +-0.061242 -0.985866 -0.155938 +-0.061242 -0.985866 -0.155938 +0.246499 -0.917451 -0.312285 +0.248903 -0.955896 -0.155918 +0.246499 -0.917451 -0.312285 +-0.061242 -0.985866 -0.155938 +-0.066213 -0.947665 -0.312326 +0.248936 -0.955876 0.155985 +0.248903 -0.955896 -0.155918 +0.400884 -0.902527 0.157281 +0.400884 -0.902527 0.157281 +0.248903 -0.955896 -0.155918 +0.401588 -0.904296 -0.144833 +0.401588 -0.904296 -0.144833 +0.248903 -0.955896 -0.155918 +0.386858 -0.871508 -0.301354 +0.248903 -0.955896 -0.155918 +0.246499 -0.917451 -0.312285 +0.386858 -0.871508 -0.301354 +-0.993106 0.004527 -0.117131 +-0.990734 -0.022558 -0.133927 +-0.995209 -0.052149 -0.082701 +-0.993106 0.004527 -0.117131 +-0.995209 -0.052149 -0.082701 +-0.994818 -0.020939 -0.099492 +-0.993106 0.004527 -0.117131 +-0.973661 0.006392 -0.227910 +-0.990734 -0.022558 -0.133927 +-0.990734 -0.022558 -0.133927 +-0.973661 0.006392 -0.227910 +-0.976999 -0.021232 -0.212186 +-0.976999 -0.021232 -0.212186 +-0.973661 0.006392 -0.227910 +-0.963587 -0.049105 -0.262846 +-0.963587 -0.049105 -0.262846 +-0.973661 0.006392 -0.227910 +-0.969115 -0.018474 -0.245915 +-0.976999 -0.021232 -0.212186 +-0.955171 -0.136237 -0.262844 +-0.962998 -0.166167 -0.212185 +-0.955171 -0.136237 -0.262844 +-0.976999 -0.021232 -0.212186 +-0.963587 -0.049105 -0.262846 +-0.962998 -0.166167 -0.212185 +-0.955171 -0.136237 -0.262844 +-0.945716 -0.249931 -0.207738 +-0.945716 -0.249931 -0.207738 +-0.955171 -0.136237 -0.262844 +-0.954734 -0.167362 -0.245911 +-0.945716 -0.249931 -0.207738 +-0.971514 -0.195910 -0.133340 +-0.962998 -0.166167 -0.212185 +-0.990734 -0.022558 -0.133927 +-0.962998 -0.166167 -0.212185 +-0.971514 -0.195910 -0.133340 +-0.962998 -0.166167 -0.212185 +-0.990734 -0.022558 -0.133927 +-0.976999 -0.021232 -0.212186 +-0.986792 -0.139296 -0.082698 +-0.971514 -0.195910 -0.133340 +-0.969930 -0.213588 -0.116691 +-0.986792 -0.139296 -0.082698 +-0.969930 -0.213588 -0.116691 +-0.980435 -0.169852 -0.099487 +-0.995209 -0.052149 -0.082701 +-0.971514 -0.195910 -0.133340 +-0.986792 -0.139296 -0.082698 +-0.971514 -0.195910 -0.133340 +-0.995209 -0.052149 -0.082701 +-0.990734 -0.022558 -0.133927 +0.085296 -0.975419 0.203181 +0.076094 -0.897797 -0.433786 +0.079604 -0.942633 -0.324201 +0.079604 -0.942633 -0.324201 +0.084197 -0.944550 0.317389 +0.085296 -0.975419 0.203181 +0.084197 -0.944550 0.317389 +0.066135 -0.646321 0.760194 +0.085296 -0.975419 0.203181 +0.066135 -0.646321 0.760194 +0.084197 -0.944550 0.317389 +0.062316 -0.590375 0.804720 +0.987753 0.104459 -0.115896 +0.943226 0.162213 -0.289847 +0.949992 0.091484 -0.298574 +0.987753 0.104459 -0.115896 +0.949992 0.091484 -0.298574 +0.949992 0.091486 -0.298573 +-0.945513 -0.091334 0.312512 +-0.884446 -0.102399 0.455270 +-0.945513 -0.091332 0.312512 +-0.914800 -0.245199 0.320964 +-0.884446 -0.102399 0.455270 +-0.945513 -0.091334 0.312512 +0.913813 0.045537 -0.403575 +0.956566 0.012053 -0.291267 +0.949992 0.091478 -0.298574 +0.913813 0.045537 -0.403575 +0.949992 0.091478 -0.298574 +0.949992 0.091485 -0.298572 +-0.970173 -0.166491 0.176198 +-0.914800 -0.245199 0.320964 +-0.945514 -0.091326 0.312510 +0.371463 -0.209993 0.904388 +0.213507 -0.142220 0.966534 +0.212033 -0.234455 0.948722 +0.213507 -0.142220 0.966534 +0.371463 -0.209993 0.904388 +0.365035 -0.121486 0.923034 +-0.123553 0.677464 -0.725104 +-0.112032 0.393384 -0.912523 +-0.241238 0.474412 -0.846603 +-0.112032 0.393384 -0.912523 +-0.231824 0.382446 -0.894423 +-0.241238 0.474412 -0.846603 +-0.112032 0.393384 -0.912523 +-0.198358 0.110712 -0.973857 +-0.231824 0.382446 -0.894423 +-0.284254 0.110859 -0.952318 +-0.231824 0.382446 -0.894423 +-0.198358 0.110712 -0.973857 +-0.284254 0.110859 -0.952318 +-0.241238 0.474412 -0.846603 +-0.231824 0.382446 -0.894423 +-0.123553 0.677464 -0.725104 +-0.084240 0.761176 -0.643051 +-0.057199 0.465279 -0.883314 +-0.123553 0.677464 -0.725104 +-0.057199 0.465279 -0.883314 +-0.112032 0.393384 -0.912523 +-0.072786 0.788610 -0.610570 +-0.057199 0.465279 -0.883314 +-0.084240 0.761176 -0.643051 +-0.057199 0.465279 -0.883314 +-0.072786 0.788610 -0.610570 +-0.043677 0.485072 -0.873383 +0.005246 0.439375 -0.898288 +-0.043677 0.485072 -0.873383 +-0.032879 0.728711 -0.684032 +-0.072786 0.788610 -0.610570 +-0.032879 0.728711 -0.684032 +-0.043677 0.485072 -0.873383 +0.005246 0.439375 -0.898288 +0.112016 0.515381 -0.849609 +0.126415 0.309935 -0.942316 +0.112016 0.515381 -0.849609 +0.005246 0.439375 -0.898288 +-0.032879 0.728711 -0.684032 +0.112016 0.515381 -0.849609 +0.223820 0.139402 -0.964610 +0.126415 0.309935 -0.942316 +0.154594 0.009858 -0.987929 +0.223820 0.139402 -0.964610 +0.225859 0.025780 -0.973819 +0.223820 0.139402 -0.964610 +0.154594 0.009858 -0.987929 +0.126415 0.309935 -0.942316 +0.154594 0.009858 -0.987929 +0.043735 -0.005893 -0.999026 +0.126415 0.309935 -0.942316 +0.043735 -0.005893 -0.999026 +0.005246 0.439375 -0.898288 +0.126415 0.309935 -0.942316 +-0.008727 -0.014005 -0.999864 +-0.057199 0.465279 -0.883314 +0.004361 -0.012264 -0.999915 +0.004361 -0.012264 -0.999915 +-0.057199 0.465279 -0.883314 +-0.043677 0.485072 -0.873383 +0.004361 -0.012264 -0.999915 +0.005246 0.439375 -0.898288 +0.043735 -0.005893 -0.999026 +0.005246 0.439375 -0.898288 +0.004361 -0.012264 -0.999915 +-0.043677 0.485072 -0.873383 +0.213749 -0.303465 -0.928558 +0.154594 0.009858 -0.987929 +0.249843 -0.076274 -0.965278 +0.249843 -0.076274 -0.965278 +0.154594 0.009858 -0.987929 +0.225859 0.025780 -0.973819 +0.106868 -0.468740 -0.876848 +0.043735 -0.005893 -0.999026 +0.213749 -0.303465 -0.928558 +0.213749 -0.303465 -0.928558 +0.043735 -0.005893 -0.999026 +0.154594 0.009858 -0.987929 +0.213749 -0.303465 -0.928558 +0.249843 -0.076274 -0.965278 +0.260453 -0.515416 -0.816401 +0.260453 -0.515416 -0.816401 +0.133636 -0.758805 -0.637461 +0.106868 -0.468740 -0.876848 +0.260453 -0.515416 -0.816401 +0.106868 -0.468740 -0.876848 +0.213749 -0.303465 -0.928558 +0.133636 -0.758805 -0.637461 +0.092492 -0.830128 -0.549848 +0.059843 -0.526592 -0.848009 +0.133636 -0.758805 -0.637461 +0.059843 -0.526592 -0.848009 +0.106868 -0.468740 -0.876848 +0.076377 -0.818674 -0.569157 +0.059843 -0.526592 -0.848009 +0.092492 -0.830128 -0.549848 +0.059843 -0.526592 -0.848009 +0.076377 -0.818674 -0.569157 +0.043261 -0.517814 -0.854399 +-0.017401 -0.447683 -0.894023 +0.043261 -0.517814 -0.854399 +0.016557 -0.719952 -0.693827 +0.076377 -0.818674 -0.569157 +0.016557 -0.719952 -0.693827 +0.043261 -0.517814 -0.854399 +0.043261 -0.517814 -0.854399 +0.004361 -0.012264 -0.999915 +0.059843 -0.526592 -0.848009 +0.004361 -0.012264 -0.999915 +0.043261 -0.517814 -0.854399 +-0.008727 -0.014005 -0.999864 +0.059843 -0.526592 -0.848009 +0.004361 -0.012264 -0.999915 +0.106868 -0.468740 -0.876848 +0.106868 -0.468740 -0.876848 +0.004361 -0.012264 -0.999915 +0.043735 -0.005893 -0.999026 +0.043261 -0.517814 -0.854399 +-0.017401 -0.447683 -0.894023 +-0.008727 -0.014005 -0.999864 +-0.017401 -0.447683 -0.894023 +-0.052106 -0.020482 -0.998432 +-0.008727 -0.014005 -0.999864 +-0.052106 -0.020482 -0.998432 +-0.112032 0.393384 -0.912523 +-0.008727 -0.014005 -0.999864 +-0.008727 -0.014005 -0.999864 +-0.112032 0.393384 -0.912523 +-0.057199 0.465279 -0.883314 +-0.198358 0.110712 -0.973857 +-0.186357 -0.046392 -0.981386 +-0.285232 -0.051054 -0.957098 +-0.285232 -0.051054 -0.957098 +-0.284254 0.110859 -0.952318 +-0.198358 0.110712 -0.973857 +-0.052106 -0.020482 -0.998432 +-0.198358 0.110712 -0.973857 +-0.112032 0.393384 -0.912523 +-0.052106 -0.020482 -0.998432 +-0.186357 -0.046392 -0.981386 +-0.198358 0.110712 -0.973857 +-0.052106 -0.020482 -0.998432 +-0.017401 -0.447683 -0.894023 +-0.140344 -0.286276 -0.947813 +-0.140344 -0.286276 -0.947813 +-0.186357 -0.046392 -0.981386 +-0.052106 -0.020482 -0.998432 +-0.235710 -0.188135 -0.953439 +-0.186357 -0.046392 -0.981386 +-0.140344 -0.286276 -0.947813 +-0.186357 -0.046392 -0.981386 +-0.235710 -0.188135 -0.953439 +-0.285232 -0.051054 -0.957098 +-0.088877 -0.527350 -0.844987 +-0.017401 -0.447683 -0.894023 +0.016557 -0.719952 -0.693827 +-0.017401 -0.447683 -0.894023 +-0.088877 -0.527350 -0.844987 +-0.140344 -0.286276 -0.947813 +-0.437132 -0.198064 0.877317 +-0.339633 -0.296734 0.892524 +-0.377945 -0.191019 0.905908 +0.341452 0.036601 0.939186 +0.420796 -0.049727 0.905791 +0.403106 0.048794 0.913852 +0.341452 0.036601 0.939186 +0.365035 -0.121486 0.923034 +0.420796 -0.049727 0.905791 +0.052390 -0.159169 0.985860 +0.212033 -0.234455 0.948722 +0.213507 -0.142220 0.966534 +0.212033 -0.234455 0.948722 +0.052390 -0.159169 0.985860 +0.060567 -0.246807 0.967170 +0.052390 -0.159169 0.985860 +-0.074773 -0.173604 0.981973 +-0.063017 -0.264344 0.962367 +0.052390 -0.159169 0.985860 +-0.063017 -0.264344 0.962367 +0.060567 -0.246807 0.967170 +-0.210094 -0.285228 0.935150 +-0.074773 -0.173604 0.981973 +-0.225022 -0.190033 0.955643 +-0.074773 -0.173604 0.981973 +-0.210094 -0.285228 0.935150 +-0.063017 -0.264344 0.962367 +0.035931 0.003849 0.999347 +-0.092507 -0.010054 0.995661 +-0.074773 -0.173604 0.981973 +0.035931 0.003849 0.999347 +-0.074773 -0.173604 0.981973 +0.052390 -0.159169 0.985860 +-0.092507 -0.010054 0.995661 +-0.238985 -0.025723 0.970682 +-0.225022 -0.190033 0.955643 +-0.092507 -0.010054 0.995661 +-0.225022 -0.190033 0.955643 +-0.074773 -0.173604 0.981973 +-0.225022 -0.190033 0.955643 +-0.377945 -0.191019 0.905908 +-0.339633 -0.296734 0.892524 +-0.225022 -0.190033 0.955643 +-0.339633 -0.296734 0.892524 +-0.210094 -0.285228 0.935150 +-0.464748 -0.058780 0.883490 +-0.437132 -0.198064 0.877317 +-0.377945 -0.191019 0.905908 +-0.464748 -0.058780 0.883490 +-0.377945 -0.191019 0.905908 +-0.396619 -0.046873 0.916786 +-0.396619 -0.046873 0.916786 +-0.377945 -0.191019 0.905908 +-0.238985 -0.025723 0.970682 +-0.377945 -0.191019 0.905908 +-0.225022 -0.190033 0.955643 +-0.238985 -0.025723 0.970682 +-0.396619 -0.046873 0.916786 +-0.405341 0.115799 0.906802 +-0.459857 0.055365 0.886265 +-0.459857 0.055365 0.886265 +-0.464748 -0.058780 0.883490 +-0.396619 -0.046873 0.916786 +-0.263020 0.133742 0.955475 +-0.405341 0.115799 0.906802 +-0.238985 -0.025723 0.970682 +-0.405341 0.115799 0.906802 +-0.396619 -0.046873 0.916786 +-0.238985 -0.025723 0.970682 +-0.409500 0.212869 0.887128 +-0.263020 0.133742 0.955475 +-0.255343 0.225120 0.940277 +-0.263020 0.133742 0.955475 +-0.409500 0.212869 0.887128 +-0.405341 0.115799 0.906802 +-0.263020 0.133742 0.955475 +-0.092507 -0.010054 0.995661 +-0.106685 0.149303 0.983019 +-0.092507 -0.010054 0.995661 +-0.263020 0.133742 0.955475 +-0.238985 -0.025723 0.970682 +-0.255343 0.225120 0.940277 +-0.106685 0.149303 0.983019 +-0.112195 0.236344 0.965170 +-0.106685 0.149303 0.983019 +-0.255343 0.225120 0.940277 +-0.263020 0.133742 0.955475 +-0.106685 0.149303 0.983019 +0.019033 0.167169 0.985745 +-0.112195 0.236344 0.965170 +0.009152 0.254961 0.966908 +-0.112195 0.236344 0.965170 +0.019033 0.167169 0.985745 +0.157858 0.279605 0.947049 +0.009152 0.254961 0.966908 +0.019033 0.167169 0.985745 +0.157858 0.279605 0.947049 +0.019033 0.167169 0.985745 +0.178680 0.187001 0.965973 +-0.092507 -0.010054 0.995661 +0.035931 0.003849 0.999347 +-0.106685 0.149303 0.983019 +0.019033 0.167169 0.985745 +-0.106685 0.149303 0.983019 +0.035931 0.003849 0.999347 +0.178680 0.187001 0.965973 +0.019033 0.167169 0.985745 +0.035931 0.003849 0.999347 +0.178680 0.187001 0.965973 +0.035931 0.003849 0.999347 +0.193154 0.020749 0.980949 +0.035931 0.003849 0.999347 +0.213507 -0.142220 0.966534 +0.193154 0.020749 0.980949 +0.213507 -0.142220 0.966534 +0.035931 0.003849 0.999347 +0.052390 -0.159169 0.985860 +0.193154 0.020749 0.980949 +0.365035 -0.121486 0.923034 +0.341452 0.036601 0.939186 +0.365035 -0.121486 0.923034 +0.193154 0.020749 0.980949 +0.213507 -0.142220 0.966534 +0.324062 0.194740 0.925775 +0.341452 0.036601 0.939186 +0.396753 0.150574 0.905491 +0.341452 0.036601 0.939186 +0.403106 0.048794 0.913852 +0.396753 0.150574 0.905491 +0.324062 0.194740 0.925775 +0.178680 0.187001 0.965973 +0.193154 0.020749 0.980949 +0.324062 0.194740 0.925775 +0.193154 0.020749 0.980949 +0.341452 0.036601 0.939186 +0.316330 0.286373 0.904393 +0.157858 0.279605 0.947049 +0.178680 0.187001 0.965973 +0.316330 0.286373 0.904393 +0.178680 0.187001 0.965973 +0.324062 0.194740 0.925775 +0.420796 -0.049727 0.905791 +0.365035 -0.121486 0.923034 +0.371463 -0.209993 0.904388 +0.316330 0.286373 0.904393 +0.324062 0.194740 0.925775 +0.396753 0.150574 0.905491 +-0.459857 0.055365 0.886265 +-0.405341 0.115799 0.906802 +-0.409500 0.212869 0.887128 +-0.235710 -0.188135 -0.953439 +-0.140344 -0.286276 -0.947813 +-0.088877 -0.527350 -0.844987 + + + + + + + + + + + +0.693248 0.853291 +0.684005 0.853291 +0.684005 0.636373 +0.693248 0.636373 +0.680219 0.853291 +0.660708 0.853291 +0.660708 0.636373 +0.680219 0.636373 +0.656922 0.853291 +0.647679 0.853291 +0.647679 0.636373 +0.656922 0.636373 +0.883212 0.635500 +0.883212 0.852230 +0.875187 0.852230 +0.875187 0.635500 +0.763108 0.852890 +0.763108 0.635068 +0.779869 0.635068 +0.779869 0.852890 +0.757962 0.637031 +0.757962 0.853724 +0.749938 0.853724 +0.749938 0.637031 +0.644769 0.636163 +0.644769 0.853081 +0.635526 0.853081 +0.635526 0.636163 +0.631741 0.636163 +0.631741 0.853081 +0.612230 0.853081 +0.612230 0.636163 +0.608445 0.636163 +0.608445 0.853081 +0.599202 0.853081 +0.599202 0.636163 +0.948280 0.633473 +0.956347 0.633473 +0.956347 0.851355 +0.948280 0.851355 +0.866868 0.852494 +0.850220 0.852494 +0.850220 0.636140 +0.866868 0.636140 +0.945403 0.851480 +0.937335 0.851480 +0.937335 0.633598 +0.945403 0.633598 +0.584316 0.893899 +0.584382 0.903166 +0.585411 0.904181 +0.605017 0.904031 +0.606032 0.903000 +0.605961 0.893707 +0.533227 0.854091 +0.533227 0.638586 +0.585787 0.901940 +0.585728 0.893888 +0.539592 0.853920 +0.539592 0.638416 +0.603591 0.902824 +0.586817 0.902954 +0.604544 0.893718 +0.604606 0.901793 +0.606061 0.877411 +0.605910 0.886685 +0.604871 0.887691 +0.585272 0.887371 +0.584265 0.886332 +0.584417 0.877045 +0.604647 0.877388 +0.604515 0.885446 +0.550922 0.853447 +0.550922 0.636530 +0.560165 0.636530 +0.560165 0.853447 +0.563951 0.853447 +0.563951 0.636530 +0.583461 0.636530 +0.583461 0.853447 +0.587246 0.853447 +0.587246 0.636530 +0.596489 0.636530 +0.596489 0.853447 +0.921292 0.851691 +0.913225 0.851691 +0.913225 0.633809 +0.921292 0.633809 +0.837242 0.852069 +0.820595 0.852069 +0.820595 0.635732 +0.837242 0.635732 +0.897638 0.851908 +0.889586 0.851908 +0.889586 0.634423 +0.897638 0.634423 +0.695335 0.636475 +0.704578 0.636475 +0.704578 0.853392 +0.695335 0.853392 +0.708364 0.636475 +0.727875 0.636475 +0.727875 0.853392 +0.708364 0.853392 +0.731661 0.636475 +0.740904 0.636475 +0.740904 0.853392 +0.731661 0.853392 +0.925747 0.851490 +0.925747 0.633608 +0.933814 0.633608 +0.933814 0.851490 +0.807635 0.636015 +0.807635 0.852323 +0.790990 0.852323 +0.790990 0.636015 +0.910015 0.633874 +0.910015 0.851756 +0.901947 0.851756 +0.901947 0.633874 +0.603476 0.886452 +0.586707 0.886177 +0.585701 0.885138 +0.585833 0.877068 +0.547769 0.887408 +0.547757 0.878114 +0.548779 0.877090 +0.568372 0.877062 +0.569395 0.878083 +0.569409 0.887362 +0.549186 0.887406 +0.549175 0.879330 +0.550196 0.878305 +0.566958 0.878281 +0.567982 0.879302 +0.567994 0.887365 +0.569545 0.905561 +0.569274 0.896264 +0.568221 0.895272 +0.548640 0.895835 +0.547648 0.896885 +0.547913 0.906158 +0.567892 0.897523 +0.568128 0.905602 +0.587382 0.426196 +0.585064 0.436941 +0.579587 0.030232 +0.583982 0.041290 +0.597603 0.027795 +0.601111 0.438933 +0.571455 0.024633 +0.036870 0.024603 +0.027127 0.005853 +0.579984 0.006640 +0.023965 0.043314 +0.027367 0.428220 +0.013745 0.441714 +0.010236 0.030577 +0.039893 0.444876 +0.574477 0.444907 +0.584220 0.463657 +0.031364 0.462869 +0.592869 0.018830 +0.596688 0.449612 +0.028587 0.030265 +0.019609 0.012707 +0.031762 0.439277 +0.018479 0.450678 +0.577231 0.027976 +0.587352 0.012462 +0.591739 0.456803 +0.582760 0.439245 +0.026283 0.032569 +0.014659 0.019898 +0.034117 0.441533 +0.023996 0.457046 +0.492728 0.609730 +0.493178 0.983298 +0.031504 0.983855 +0.031053 0.610287 +0.145240 0.568377 +0.436617 0.567900 +0.436667 0.572985 +0.145290 0.573462 +0.454310 0.567727 +0.454359 0.572813 +0.469033 0.567586 +0.469082 0.572673 +0.062037 0.594887 +0.467714 0.594043 +0.492339 0.593785 +0.492414 0.600863 +0.459939 0.558897 +0.459894 0.553811 +0.442248 0.559053 +0.442203 0.553968 +0.150867 0.559248 +0.150821 0.554163 +0.133177 0.559415 +0.133128 0.554329 +0.118456 0.559557 +0.118407 0.554471 +0.466655 0.585821 +0.060981 0.586666 +0.036348 0.586924 +0.036274 0.579844 +0.127549 0.568553 +0.127599 0.573638 +0.625503 0.163947 +0.625503 0.154708 +0.937183 0.154709 +0.937183 0.163947 +0.625573 0.149269 +0.625573 0.129770 +0.937253 0.129771 +0.937253 0.149270 +0.625643 0.124331 +0.625643 0.115092 +0.937323 0.115093 +0.937323 0.124332 +0.937925 0.396277 +0.624686 0.396277 +0.624686 0.388209 +0.937925 0.388209 +0.935891 0.260304 +0.625256 0.260304 +0.625256 0.243677 +0.935891 0.243677 +0.936592 0.329363 +0.623353 0.329363 +0.623353 0.321295 +0.936592 0.321295 +0.625186 0.171237 +0.936866 0.171237 +0.936866 0.180475 +0.625186 0.180476 +0.625231 0.185915 +0.936910 0.185915 +0.936910 0.205414 +0.625231 0.205415 +0.625275 0.210854 +0.936954 0.210854 +0.936954 0.220092 +0.625275 0.220093 +0.937137 0.374874 +0.937137 0.382942 +0.623898 0.382942 +0.623898 0.374874 +0.935865 0.289309 +0.935865 0.305936 +0.625230 0.305936 +0.625230 0.289309 +0.937964 0.349675 +0.937964 0.357743 +0.624725 0.357743 +0.624725 0.349675 +0.550089 0.897010 +0.566841 0.896529 +0.549327 0.906118 +0.549097 0.898060 +0.535831 0.853920 +0.535831 0.638416 +0.529466 0.638586 +0.529466 0.854091 +0.746156 0.637031 +0.746156 0.853724 +0.886994 0.852230 +0.886994 0.635500 +0.543550 0.638544 +0.543550 0.853983 +0.975845 0.851574 +0.975845 0.636134 +0.846444 0.852494 +0.547311 0.853983 +0.547311 0.638544 +0.846444 0.636140 +0.972085 0.851645 +0.870644 0.852494 +0.870644 0.636140 +0.972085 0.636206 +0.961968 0.635701 +0.961968 0.851205 +0.965197 0.636034 +0.965197 0.851539 +0.787214 0.636015 +0.787214 0.852323 +0.958207 0.635792 +0.958207 0.851297 +0.968957 0.851447 +0.968957 0.635942 +0.811411 0.852323 +0.811411 0.636015 +0.989138 0.851209 +0.989138 0.635771 +0.978851 0.636018 +0.978851 0.851457 +0.816818 0.852069 +0.985377 0.635842 +0.985377 0.851281 +0.816818 0.635732 +0.982612 0.635946 +0.841019 0.852069 +0.841019 0.635732 +0.982612 0.851386 +0.624749 0.342220 +0.934007 0.342220 +0.952041 0.871238 +0.642783 0.871238 +0.934077 0.336824 +0.624819 0.336824 +0.951971 0.876634 +0.642713 0.876634 +0.935909 0.311357 +0.625274 0.311358 +0.935821 0.283888 +0.625186 0.283888 +0.624174 0.364068 +0.933431 0.364068 +0.626933 0.406347 +0.936190 0.406347 +0.624218 0.369465 +0.933475 0.369465 +0.936146 0.400950 +0.626889 0.400950 +0.935960 0.238256 +0.625325 0.238257 +0.625186 0.265725 +0.935822 0.265725 +0.060907 0.579586 +0.062112 0.601967 +0.467789 0.601122 +0.466581 0.578742 +0.512822 0.944557 +0.511907 0.618459 +0.506170 0.975643 +0.037405 0.595148 +0.037480 0.602228 +0.502928 0.978831 +0.474658 0.558767 +0.474613 0.553682 +0.024999 0.982873 +0.021782 0.981408 +0.012324 0.975126 +0.011410 0.649029 +0.018062 0.617942 +0.491281 0.585561 +0.491207 0.578482 +0.021304 0.614754 +0.112829 0.568699 +0.112880 0.573784 +0.499232 0.610713 +0.502449 0.612177 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.756345 0.522332 +0.756346 0.715841 +0.016244 0.715841 +0.016243 0.522332 +0.009526 0.514494 +0.009526 0.061000 +0.749636 0.060999 +0.749637 0.514493 +0.771396 0.480706 +0.969477 0.480355 +0.969577 0.938728 +0.771464 0.938319 +0.751630 0.039423 +0.751630 0.498972 +0.007192 0.498972 +0.007192 0.039423 +0.977311 0.498670 +0.779207 0.499082 +0.779286 0.040707 +0.977371 0.041060 +0.016243 0.718111 +0.756344 0.718111 +0.756344 0.911620 +0.016243 0.911620 +0.756345 0.522332 +0.756346 0.715841 +0.016244 0.715841 +0.016243 0.522332 +0.009526 0.514494 +0.009526 0.061000 +0.749636 0.060999 +0.749637 0.514493 +0.771396 0.480706 +0.969477 0.480355 +0.969577 0.938728 +0.771464 0.938319 +0.751630 0.039423 +0.751630 0.498972 +0.007192 0.498972 +0.007192 0.039423 +0.977311 0.498670 +0.779207 0.499082 +0.779286 0.040707 +0.977371 0.041060 +0.016243 0.718111 +0.756344 0.718111 +0.756344 0.911620 +0.016243 0.911620 +0.756345 0.522332 +0.756346 0.715841 +0.016244 0.715841 +0.016243 0.522332 +0.009526 0.514494 +0.009526 0.061000 +0.749636 0.060999 +0.749637 0.514493 +0.771396 0.480706 +0.969477 0.480355 +0.969577 0.938728 +0.771464 0.938319 +0.751630 0.039423 +0.751630 0.498972 +0.007192 0.498972 +0.007192 0.039423 +0.977311 0.498670 +0.779207 0.499082 +0.779286 0.040707 +0.977371 0.041060 +0.016243 0.718111 +0.756344 0.718111 +0.756344 0.911620 +0.016243 0.911620 +0.076009 0.659668 +0.040405 0.870361 +0.040314 0.874227 +0.037069 0.899302 +0.035123 0.917445 +0.036067 0.912130 +0.036463 0.900950 +0.002443 0.979329 +0.003126 0.975510 +0.123881 0.764180 +0.113109 0.773072 +0.123881 0.761861 +0.113109 0.770671 +0.114161 0.788940 +0.114161 0.786408 +0.131775 0.801371 +0.131775 0.798767 +0.077800 0.652873 +0.231486 0.652832 +0.076904 0.655335 +0.232727 0.655335 +0.234009 0.659668 +0.181193 0.758565 +0.198812 0.770915 +0.151387 0.755615 +0.284180 0.870361 +0.189087 0.795491 +0.199870 0.786682 +0.161591 0.801666 +0.038559 0.883301 +0.286743 0.883301 +0.289673 0.900950 +0.291565 0.917450 +0.313884 0.979243 +0.258789 0.994857 +0.297567 0.989676 +0.276978 0.993504 +0.054739 0.994854 +0.036692 0.993475 +0.005191 0.984123 +0.037158 0.990271 +0.005814 0.980520 +0.309611 0.980416 +0.312988 0.975418 +0.290242 0.912130 +0.288818 0.899302 +0.286377 0.885000 +0.284180 0.874227 +0.234334 0.662598 +0.198598 0.773346 +0.233286 0.659139 +0.232178 0.656982 +0.258138 0.991714 +0.055206 0.991714 +0.181193 0.760885 +0.151387 0.757914 +0.917480 0.016724 +0.902832 0.002441 +0.912313 0.006999 +0.697998 0.324219 +0.488770 0.002930 +0.917740 0.630165 +0.474121 0.017578 +0.479248 0.008118 +0.474121 0.631592 +0.488770 0.646240 +0.479248 0.641174 +0.902832 0.645264 +0.912476 0.640259 +0.038763 0.885000 +0.075785 0.662598 +0.076523 0.659139 +0.077356 0.657031 +0.276327 0.990297 +0.161560 0.804352 +0.189067 0.798075 +0.924072 0.640015 +0.923889 0.629002 +0.929443 0.629639 +0.929443 0.640015 +0.924072 0.015625 +0.929443 0.015625 +0.929443 0.005127 +0.924072 0.005127 +0.952393 0.438477 +0.952393 0.448974 +0.946840 0.437825 +0.947021 0.448974 +0.952393 0.011719 +0.946839 0.012472 +0.947021 0.004150 +0.952393 0.004150 +0.939027 0.016277 +0.939209 0.005127 +0.944759 0.016285 +0.944580 0.005127 +0.939026 0.441731 +0.944580 0.442383 +0.939209 0.449951 +0.944580 0.449951 +0.465820 0.997532 +0.465820 0.998001 +0.465332 0.997883 +0.465332 0.997532 +0.465820 0.648438 +0.465332 0.648438 +0.608398 0.997532 +0.608398 0.998001 +0.465820 0.647949 +0.465332 0.648193 +0.608887 0.997532 +0.608398 0.997883 +0.608398 0.647949 +0.608398 0.648438 +0.608887 0.648438 +0.232056 0.656982 +0.937256 0.004150 +0.937435 0.012377 +0.931702 0.012345 +0.931885 0.004150 +0.937256 0.625733 +0.931702 0.625106 +0.931885 0.633423 +0.937256 0.633423 +0.461182 0.995430 +0.461182 0.995773 +0.460693 0.995430 +0.460693 0.995888 +0.458252 0.995430 +0.458252 0.995888 +0.460693 0.653076 +0.461182 0.653076 +0.461182 0.652588 +0.460693 0.652588 +0.458252 0.653076 +0.458008 0.995773 +0.457764 0.995430 +0.457764 0.653076 +0.458252 0.652588 +0.457764 0.652588 +0.610840 0.647949 +0.610840 0.648438 +0.610352 0.648438 +0.613281 0.648438 +0.613281 0.647949 +0.613770 0.647949 +0.613770 0.648438 +0.613770 0.990982 +0.613281 0.990982 +0.610840 0.990982 +0.610352 0.990982 +0.610840 0.991440 +0.610352 0.991325 +0.613281 0.991440 +0.613770 0.991325 +0.316162 0.653076 +0.316162 0.652588 +0.316406 0.653076 +0.316650 0.652588 +0.455566 0.652588 +0.455566 0.653076 +0.316406 0.993172 +0.316162 0.992989 +0.316162 0.993332 +0.316650 0.993446 +0.455566 0.993172 +0.456055 0.652588 +0.456055 0.653076 +0.456055 0.992989 +0.455566 0.993446 +0.455811 0.993446 +0.531250 0.946991 +0.531250 0.947327 +0.530762 0.946991 +0.530762 0.947449 +0.530762 0.807007 +0.531250 0.807007 +0.528320 0.946991 +0.528320 0.947449 +0.527832 0.947327 +0.527832 0.946991 +0.528320 0.807007 +0.527832 0.807007 +0.531250 0.806641 +0.530762 0.806641 +0.528320 0.806641 +0.527832 0.806641 +0.528809 0.795410 +0.528809 0.795776 +0.528320 0.795410 +0.528320 0.795898 +0.525879 0.795898 +0.525879 0.795410 +0.528320 0.655518 +0.528809 0.655518 +0.525391 0.795776 +0.525391 0.795410 +0.528809 0.655029 +0.528320 0.655029 +0.525879 0.655518 +0.525391 0.655518 +0.525879 0.655029 +0.525391 0.655273 +0.018436 0.003174 +0.003487 0.018066 +0.008855 0.008240 +0.109802 0.071777 +0.447021 0.003296 +0.355469 0.072266 +0.461975 0.018066 +0.456665 0.008362 +0.355469 0.580811 +0.461975 0.634949 +0.447021 0.649719 +0.456665 0.644592 +0.018436 0.649719 +0.109802 0.580811 +0.003487 0.635010 +0.008855 0.644653 +0.199524 0.789022 +0.618760 0.701971 +0.624622 0.731381 +0.608861 0.731117 +0.614305 0.840637 +0.610003 0.858801 +0.599464 0.839324 +0.614604 0.856184 +0.620981 0.868252 +0.623697 0.857468 +0.596263 0.814862 +0.613157 0.815466 +0.597480 0.774683 +0.614940 0.775894 +0.604189 0.739801 +0.618940 0.740750 +0.625086 0.716951 +0.617957 0.712688 +0.629454 0.705243 +0.650593 0.717277 +0.650070 0.703481 +0.649395 0.741799 +0.647553 0.777635 +0.645497 0.817152 +0.670360 0.706880 +0.676903 0.719972 +0.681881 0.744036 +0.683415 0.717249 +0.694686 0.744572 +0.697385 0.779918 +0.681930 0.779343 +0.679453 0.818845 +0.693916 0.819903 +0.687272 0.845013 +0.675959 0.843364 +0.644160 0.842771 +0.642836 0.870925 +0.644570 0.859215 +0.670041 0.859255 +0.669297 0.868050 +0.677765 0.861308 +0.628068 0.705014 +0.633099 0.692272 +0.652679 0.705217 +0.606112 0.767729 +0.622465 0.768417 +0.605143 0.809154 +0.621303 0.809512 +0.621605 0.835821 +0.606380 0.835927 +0.650477 0.769427 +0.649135 0.810427 +0.648179 0.837387 +0.612033 0.854684 +0.623029 0.853820 +0.619852 0.862722 +0.646699 0.867883 +0.647533 0.855362 +0.669449 0.867321 +0.672204 0.855579 +0.675058 0.837698 +0.681496 0.858341 +0.691075 0.837494 +0.677130 0.811469 +0.693651 0.812230 +0.678492 0.770371 +0.694854 0.770804 +0.694127 0.734052 +0.678733 0.733223 +0.651772 0.731958 +0.654349 0.690826 +0.675465 0.694380 +0.677231 0.706674 +0.686427 0.703459 +0.029544 0.035380 +0.029544 0.035380 +0.902832 0.645265 +0.447020 0.650719 +0.678335 0.857072 +0.680362 0.704784 +0.623673 0.703078 +0.618413 0.855377 +0.583154 0.465906 +0.030298 0.465118 +0.602564 0.440517 +0.598141 0.451196 +0.591476 0.013939 +0.594235 0.017123 +0.581249 0.004701 +0.588617 0.010523 +0.595624 0.455114 +0.593149 0.458710 +0.008783 0.028993 +0.013206 0.018314 +0.599319 0.029387 +0.602827 0.440525 +0.594572 0.017143 +0.599306 0.026108 +0.028193 0.003604 +0.581050 0.004391 +0.018391 0.010363 +0.025909 0.003509 +0.015724 0.014396 +0.018199 0.010800 +0.012029 0.440122 +0.008520 0.028985 +0.016776 0.452365 +0.012042 0.443401 +0.019872 0.455569 +0.017113 0.452385 +0.030099 0.464808 +0.022731 0.458985 +0.592957 0.459147 +0.585438 0.466001 + + + + + + + + + + +-37.371174 -61.648491 +-37.371174 -65.510582 +-28.368664 -61.648491 +-28.793972 -65.935890 +-37.371174 -61.648491 +-36.945866 -65.935890 +-28.368664 -61.648491 +-28.368664 -65.510582 +-36.782421 -61.648491 +-36.782444 -65.004433 +-28.957417 -61.648491 +-29.382778 -65.429733 +-36.782421 -61.648491 +-36.357136 -65.429733 +-28.957417 -61.648491 +-28.957462 -65.004433 +-36.945866 -65.935890 +-28.368664 -65.510582 +-37.371174 -65.510582 +-28.793972 -65.935890 +-36.357136 -65.429733 +-28.957462 -65.004433 +-36.782444 -65.004433 +-29.382778 -65.429733 +-37.371159 61.648521 +-37.371159 65.510612 +-37.371159 65.510612 +-37.371159 61.648521 +-36.945850 65.935921 +-28.793957 65.935921 +-28.793957 65.935921 +-36.945850 65.935921 +-28.368649 65.510612 +-28.368649 61.648521 +-28.368649 61.648521 +-28.368649 65.510612 +-36.782429 65.004463 +-36.782429 65.004463 +-36.782406 61.648521 +-36.782406 61.648521 +-29.382763 65.429764 +-29.382763 65.429764 +-36.357121 65.429764 +-36.357121 65.429764 +-28.957401 61.648521 +-28.957401 61.648521 +-28.957447 65.004463 +-28.957447 65.004463 +36.987122 -61.648502 +36.987122 -65.510590 +36.987122 -65.510590 +36.987122 -61.648502 +36.561813 -65.935905 +28.409920 -65.935898 +28.409920 -65.935898 +36.561813 -65.935905 +27.984612 -65.510582 +27.984613 -61.648502 +27.984613 -61.648502 +27.984612 -65.510582 +36.398388 -65.004448 +36.398388 -65.004448 +36.398376 -61.648502 +36.398376 -61.648502 +28.998718 -65.429741 +28.998718 -65.429741 +35.973080 -65.429749 +35.973080 -65.429749 +28.573370 -61.648502 +28.573370 -61.648502 +28.573410 -65.004440 +28.573410 -65.004440 +36.987144 61.648502 +36.987144 61.648502 +36.987144 65.510582 +36.987144 65.510582 +36.561836 65.935890 +36.561836 65.935890 +28.409943 65.935898 +28.409943 65.935898 +27.984634 65.510590 +27.984634 65.510590 +27.984632 61.648502 +27.984632 61.648502 +36.398411 65.004448 +36.398396 61.648502 +36.398396 61.648502 +36.398411 65.004448 +28.998741 65.429756 +35.973103 65.429749 +35.973103 65.429749 +28.998741 65.429756 +28.573389 61.648502 +28.573433 65.004456 +28.573433 65.004456 +28.573389 61.648502 +-44.096615 74.151192 +-44.096645 -74.151161 +40.481560 77.766266 +40.481537 -77.766266 +-44.096615 74.151192 +-40.481571 -77.766251 +40.481560 77.766266 +44.096615 -74.151169 +-40.481541 77.766281 +-40.481571 -77.766251 +44.096638 74.151169 +44.096615 -74.151169 +-40.481541 77.766281 +-44.096645 -74.151161 +44.096638 74.151169 +40.481537 -77.766266 +-43.694942 76.159569 +-43.092430 76.762085 +-42.489948 -77.364563 +-43.092461 -76.762054 +42.489937 77.364571 +43.092449 76.762054 +43.694939 -76.159546 +43.092426 -76.762054 +-42.489918 77.364594 +-43.694942 76.159569 +-43.694973 -76.159538 +-42.489948 -77.364563 +43.694962 76.159546 +42.489937 77.364571 +42.489914 -77.364571 +43.694939 -76.159546 +-44.096615 74.151192 +-44.096645 -74.151161 +-43.694973 -76.159538 +-43.092461 -76.762054 +-40.481571 -77.766251 +40.481537 -77.766266 +42.489914 -77.364571 +43.092426 -76.762054 +44.096615 -74.151169 +44.096638 74.151169 +43.694962 76.159546 +43.092449 76.762054 +40.481560 77.766266 +-40.481541 77.766281 +-42.489918 77.364594 +-43.092430 76.762085 +-44.096615 74.151192 +-40.481571 -77.766251 +40.481560 77.766266 +44.096615 -74.151169 +-40.481541 77.766281 +-44.096645 -74.151161 +44.096638 74.151169 +40.481537 -77.766266 +-42.489918 77.364594 +-43.694942 76.159569 +-43.694973 -76.159538 +-42.489948 -77.364563 +43.694962 76.159546 +42.489937 77.364571 +42.489914 -77.364571 +43.694939 -76.159546 +-37.371159 65.163902 +-37.371159 65.163902 +-28.368649 65.163902 +-28.793957 65.163902 +-37.371174 -65.135574 +-36.945866 -65.135574 +-28.368664 -65.135574 +-28.368664 -65.135574 +-36.782406 65.163902 +-36.782429 65.163902 +-28.957401 65.163902 +-29.382763 65.163902 +-36.782421 -65.135574 +-36.357136 -65.135574 +-28.957417 -65.135574 +-28.957462 -65.135574 +-36.945850 65.163902 +-28.368649 65.163902 +-37.371174 -65.135574 +-28.793972 -65.135574 +-36.357121 65.163902 +-28.957447 65.163902 +-36.782444 -65.135574 +-29.382778 -65.135574 +36.987144 65.163887 +36.987144 65.163887 +36.987122 -65.135582 +36.987122 -65.135582 +36.561836 65.163887 +28.409943 65.163895 +28.409920 -65.135574 +36.561813 -65.135582 +27.984634 65.163895 +27.984634 65.163895 +27.984612 -65.135574 +27.984612 -65.135574 +36.398388 -65.135582 +36.398411 65.163887 +36.398399 65.163887 +36.398376 -65.135582 +28.998718 -65.135574 +28.998741 65.163895 +35.973103 65.163887 +35.973080 -65.135582 +28.573368 -65.135574 +28.573391 65.163895 +28.573433 65.163895 +28.573410 -65.135574 +-2.646059 -0.570249 +-2.646059 -0.570248 +-2.137325 -0.509977 +-2.137324 -0.509977 +-2.598163 -0.974524 +-2.089428 -0.914252 +-2.089428 -0.914252 +-2.599217 -0.965620 +-2.598163 -0.974524 +-2.664405 -0.556926 +-2.664405 -0.556925 +-2.119845 -0.492409 +-2.119846 -0.492409 +-2.613136 -0.989670 +-2.068577 -0.925154 +-2.068577 -0.925154 +-2.614266 -0.980139 +-2.613136 -0.989670 +-2.101421 -1.567498 +-2.101421 -1.567499 +-2.663376 -1.594445 +-2.663376 -1.594445 +-2.117931 -1.223174 +-2.679886 -1.250121 +-2.117931 -1.223174 +-2.679886 -1.250120 +-2.097062 -1.559281 +-2.097062 -1.559281 +-2.658034 -1.602060 +-2.658034 -1.602060 +-2.123273 -1.215558 +-2.684245 -1.258339 +-2.123273 -1.215559 +-2.684245 -1.258338 +-2.097062 -1.559281 +-2.097062 -1.559281 +-2.658034 -1.602060 +-2.658034 -1.602060 +-2.123273 -1.215558 +-2.684245 -1.258339 +-2.123273 -1.215559 +-2.684245 -1.258338 +0.971672 0.040333 +0.749525 0.021780 +0.751040 0.021702 +0.609253 0.533447 +0.595052 0.527934 +0.599732 0.523987 +0.607585 0.539592 +0.555664 0.411133 +0.558838 0.409912 +0.194946 0.947632 +0.183960 0.947571 +0.194132 0.943232 +0.182902 0.943110 +0.167450 0.947090 +0.166321 0.942673 +0.154785 0.947174 +0.153524 0.942566 +0.988037 0.041504 +0.988037 0.120605 +0.978272 0.040894 +0.978272 0.121216 +0.971672 0.121776 +0.867676 0.094970 +0.853979 0.103853 +0.870728 0.079223 +0.749526 0.148140 +0.828125 0.099121 +0.837402 0.104980 +0.849102 0.106045 +0.821167 0.084595 +0.837768 0.059692 +0.824463 0.068847 +0.738770 0.020996 +0.738770 0.149170 +0.724609 0.150635 +0.724609 0.019776 +0.707763 0.019165 +0.707723 0.151886 +0.585063 0.163273 +0.584961 0.002441 +0.554009 0.134778 +0.564392 0.155098 +0.556553 0.144321 +0.554199 0.029297 +0.556641 0.019776 +0.575439 0.003663 +0.004866 0.930957 +0.003824 0.973534 +0.043595 0.967987 +0.554443 0.311035 +0.555989 0.304851 +0.557373 0.312012 +0.559326 0.305908 +0.594727 0.190796 +0.590108 0.187032 +0.604126 0.181152 +0.602132 0.175090 +0.616048 0.172607 +0.615488 0.179169 +0.624512 0.181396 +0.626953 0.175049 +0.186271 0.802606 +0.406738 0.828430 +0.291126 0.846878 +0.814209 0.295898 +0.820964 0.297974 +0.902614 0.332144 +0.816162 0.293213 +1.650879 0.612793 +0.822429 0.307942 +0.249030 0.973453 +0.061462 0.972870 +0.061116 0.968236 +0.249634 0.968236 +0.230550 0.943359 +0.249359 0.947718 +0.229980 0.947754 +0.250280 0.943214 +0.211899 0.947697 +0.211772 0.943321 +0.014585 0.397461 +0.002347 0.409668 +0.006571 0.401734 +0.272446 0.587891 +0.002677 0.766296 +0.529295 0.397202 +0.014954 0.778381 +0.006956 0.774140 +0.530029 0.778351 +0.542480 0.766296 +0.538208 0.774170 +0.541992 0.409668 +0.537720 0.401672 +0.552735 0.401693 +0.555664 0.400635 +0.621745 0.541707 +0.620696 0.535186 +0.629876 0.532342 +0.632324 0.538656 +0.186279 0.929260 +0.291407 0.891380 +0.406761 0.910774 +0.812988 0.409668 +0.816708 0.405450 +0.819621 0.407308 +0.815185 0.412354 +0.823608 0.398438 +0.820557 0.397217 +0.023979 0.789520 +0.266662 0.973373 +0.267171 0.968272 +0.290934 0.968302 +0.043915 0.973083 +0.317993 0.948219 +0.301452 0.947479 +0.317953 0.943161 +0.301697 0.942413 +0.283854 0.942510 +0.283020 0.947289 +0.535278 0.984306 +0.526328 0.984466 +0.526855 0.979805 +0.535278 0.979801 +0.012798 0.984308 +0.012802 0.979805 +0.004325 0.979801 +0.004322 0.984306 +0.265310 0.852164 +0.258896 0.866341 +0.274838 0.890630 +0.261964 0.881694 +0.307220 0.871521 +0.304199 0.856018 +0.411621 0.829010 +0.411682 0.910301 +0.177643 0.930115 +0.177552 0.801605 +0.166718 0.800385 +0.166748 0.930984 +0.153639 0.931585 +0.153652 0.799543 +0.033523 0.787598 +0.033340 0.948563 +0.002057 0.816138 +0.004814 0.806652 +0.001982 0.921590 +0.023769 0.947106 +0.916504 0.816589 +0.924927 0.816589 +0.916015 0.821242 +0.924927 0.821060 +0.559082 0.816589 +0.559571 0.821243 +0.552734 0.821106 +0.552734 0.816589 +0.562926 0.807692 +0.553589 0.807556 +0.562833 0.802946 +0.553589 0.803040 +0.918945 0.807693 +0.919433 0.803040 +0.925781 0.807556 +0.925781 0.803040 +0.837402 0.668213 +0.837891 0.668213 +0.837891 0.668457 +0.837402 0.668457 +0.551758 0.668213 +0.551758 0.668457 +0.837402 0.551514 +0.837891 0.551514 +0.551270 0.668213 +0.551270 0.668457 +0.837402 0.551025 +0.837891 0.551025 +0.551270 0.551514 +0.551758 0.551514 +0.551758 0.551025 +0.551270 0.551025 +0.420166 0.829682 +0.420166 0.909836 +0.003565 0.993280 +0.010391 0.993134 +0.010388 0.997935 +0.003565 0.997781 +0.523926 0.993282 +0.523458 0.997936 +0.530273 0.997781 +0.530273 0.993280 +0.836914 0.841309 +0.837402 0.841309 +0.836914 0.841675 +0.837402 0.841675 +0.836914 0.843750 +0.837402 0.843750 +0.551758 0.841675 +0.551758 0.841309 +0.551270 0.841309 +0.551270 0.841675 +0.551758 0.843750 +0.837402 0.843994 +0.836914 0.844116 +0.551758 0.844116 +0.551270 0.843750 +0.551270 0.844116 +0.551270 0.832275 +0.551758 0.832275 +0.551270 0.832642 +0.551758 0.832642 +0.551758 0.830200 +0.551270 0.830200 +0.551270 0.829956 +0.551758 0.829834 +0.837402 0.829834 +0.837402 0.830200 +0.837402 0.832275 +0.837402 0.832642 +0.837402 0.832764 +0.837402 0.829956 +0.551758 0.794312 +0.551270 0.794189 +0.551758 0.793945 +0.551270 0.793945 +0.551270 0.677490 +0.551758 0.677490 +0.836426 0.793945 +0.836426 0.794312 +0.836914 0.794312 +0.836914 0.793945 +0.836426 0.677490 +0.551270 0.677246 +0.551758 0.677246 +0.836426 0.677246 +0.836914 0.677490 +0.836914 0.677246 +0.800293 0.597168 +0.800781 0.597168 +0.800293 0.597412 +0.800781 0.597412 +0.683594 0.597412 +0.683594 0.597168 +0.800293 0.599609 +0.800781 0.599609 +0.800781 0.599854 +0.800293 0.599854 +0.683594 0.599609 +0.683594 0.599854 +0.683105 0.597168 +0.683105 0.597412 +0.683105 0.599609 +0.683105 0.599854 +0.679688 0.587891 +0.680176 0.587891 +0.679688 0.588135 +0.680176 0.588135 +0.680176 0.590332 +0.679688 0.590332 +0.563477 0.588135 +0.562988 0.587891 +0.680176 0.590576 +0.679688 0.590576 +0.562988 0.588135 +0.563477 0.590332 +0.563477 0.590576 +0.562988 0.590332 +0.562988 0.590576 +0.002961 0.374878 +0.015907 0.387695 +0.007790 0.383118 +0.060760 0.298340 +0.002951 0.015869 +0.060669 0.092285 +0.015818 0.002930 +0.007632 0.007568 +0.486816 0.092285 +0.531494 0.002930 +0.544434 0.015869 +0.540304 0.007670 +0.544434 0.375122 +0.486816 0.298340 +0.531494 0.387695 +0.539571 0.383321 +0.269819 0.947703 +0.270874 0.942775 +0.274611 0.846327 +0.854668 0.059385 +0.864013 0.064697 +0.300781 0.885864 +0.751042 0.148232 +0.971320 0.121952 +0.407160 0.910657 +0.797716 0.609565 +0.777710 0.614441 +0.777385 0.603495 +0.583117 0.608575 +0.570150 0.607340 +0.582764 0.598572 +0.572266 0.610107 +0.564453 0.615357 +0.571533 0.616455 +0.599854 0.594604 +0.600382 0.606160 +0.627930 0.592896 +0.628215 0.604940 +0.653320 0.595255 +0.653381 0.605184 +0.670166 0.608398 +0.672526 0.603475 +0.678223 0.610595 +0.671631 0.626262 +0.680827 0.625000 +0.654460 0.627055 +0.629150 0.628011 +0.601319 0.629150 +0.679850 0.639486 +0.671712 0.645019 +0.655070 0.650467 +0.673828 0.649007 +0.655395 0.659119 +0.630615 0.663208 +0.630127 0.652649 +0.602234 0.653442 +0.602539 0.663330 +0.584554 0.660319 +0.584717 0.652639 +0.583252 0.629802 +0.564056 0.636535 +0.571696 0.631144 +0.573567 0.649007 +0.567871 0.648926 +0.572754 0.654216 +0.795654 0.616211 +0.804633 0.619249 +0.795898 0.632813 +0.752442 0.602702 +0.752442 0.614014 +0.724366 0.602824 +0.724365 0.614075 +0.706543 0.614746 +0.706027 0.604262 +0.752442 0.632813 +0.724366 0.632813 +0.706055 0.632772 +0.693251 0.608426 +0.694336 0.616211 +0.687988 0.614014 +0.684886 0.626943 +0.693848 0.632813 +0.686035 0.647990 +0.694336 0.649536 +0.706543 0.651001 +0.692437 0.656128 +0.706990 0.662048 +0.724365 0.651611 +0.724366 0.663167 +0.752442 0.651550 +0.752442 0.662842 +0.777900 0.661682 +0.777710 0.651093 +0.777832 0.632813 +0.806125 0.633572 +0.804199 0.647990 +0.795654 0.649414 +0.798286 0.655802 +0.407135 0.828603 +0.541993 0.409668 +0.545270 0.015872 +0.693316 0.653875 +0.797108 0.651577 +0.796978 0.613054 +0.693048 0.612950 + + + + + + + + + + +-37.371174 -61.648491 +-37.371174 -65.510582 +-28.368664 -61.648491 +-28.793972 -65.935890 +-37.371174 -61.648491 +-36.945866 -65.935890 +-28.368664 -61.648491 +-28.368664 -65.510582 +-36.782421 -61.648491 +-36.782444 -65.004433 +-28.957417 -61.648491 +-29.382778 -65.429733 +-36.782421 -61.648491 +-36.357136 -65.429733 +-28.957417 -61.648491 +-28.957462 -65.004433 +-36.945866 -65.935890 +-28.368664 -65.510582 +-37.371174 -65.510582 +-28.793972 -65.935890 +-36.357136 -65.429733 +-28.957462 -65.004433 +-36.782444 -65.004433 +-29.382778 -65.429733 +-37.371159 61.648521 +-37.371159 65.510612 +-37.371159 65.510612 +-37.371159 61.648521 +-36.945850 65.935921 +-28.793957 65.935921 +-28.793957 65.935921 +-36.945850 65.935921 +-28.368649 65.510612 +-28.368649 61.648521 +-28.368649 61.648521 +-28.368649 65.510612 +-36.782429 65.004463 +-36.782429 65.004463 +-36.782406 61.648521 +-36.782406 61.648521 +-29.382763 65.429764 +-29.382763 65.429764 +-36.357121 65.429764 +-36.357121 65.429764 +-28.957401 61.648521 +-28.957401 61.648521 +-28.957447 65.004463 +-28.957447 65.004463 +36.987122 -61.648502 +36.987122 -65.510590 +36.987122 -65.510590 +36.987122 -61.648502 +36.561813 -65.935905 +28.409920 -65.935898 +28.409920 -65.935898 +36.561813 -65.935905 +27.984612 -65.510582 +27.984613 -61.648502 +27.984613 -61.648502 +27.984612 -65.510582 +36.398388 -65.004448 +36.398388 -65.004448 +36.398376 -61.648502 +36.398376 -61.648502 +28.998718 -65.429741 +28.998718 -65.429741 +35.973080 -65.429749 +35.973080 -65.429749 +28.573370 -61.648502 +28.573370 -61.648502 +28.573410 -65.004440 +28.573410 -65.004440 +36.987144 61.648502 +36.987144 61.648502 +36.987144 65.510582 +36.987144 65.510582 +36.561836 65.935890 +36.561836 65.935890 +28.409943 65.935898 +28.409943 65.935898 +27.984634 65.510590 +27.984634 65.510590 +27.984632 61.648502 +27.984632 61.648502 +36.398411 65.004448 +36.398396 61.648502 +36.398396 61.648502 +36.398411 65.004448 +28.998741 65.429756 +35.973103 65.429749 +35.973103 65.429749 +28.998741 65.429756 +28.573389 61.648502 +28.573433 65.004456 +28.573433 65.004456 +28.573389 61.648502 +-44.096615 74.151192 +-44.096645 -74.151161 +40.481560 77.766266 +40.481537 -77.766266 +-44.096615 74.151192 +-40.481571 -77.766251 +40.481560 77.766266 +44.096615 -74.151169 +-40.481541 77.766281 +-40.481571 -77.766251 +44.096638 74.151169 +44.096615 -74.151169 +-40.481541 77.766281 +-44.096645 -74.151161 +44.096638 74.151169 +40.481537 -77.766266 +-43.694942 76.159569 +-43.092430 76.762085 +-42.489948 -77.364563 +-43.092461 -76.762054 +42.489937 77.364571 +43.092449 76.762054 +43.694939 -76.159546 +43.092426 -76.762054 +-42.489918 77.364594 +-43.694942 76.159569 +-43.694973 -76.159538 +-42.489948 -77.364563 +43.694962 76.159546 +42.489937 77.364571 +42.489914 -77.364571 +43.694939 -76.159546 +-44.096615 74.151192 +-44.096645 -74.151161 +-43.694973 -76.159538 +-43.092461 -76.762054 +-40.481571 -77.766251 +40.481537 -77.766266 +42.489914 -77.364571 +43.092426 -76.762054 +44.096615 -74.151169 +44.096638 74.151169 +43.694962 76.159546 +43.092449 76.762054 +40.481560 77.766266 +-40.481541 77.766281 +-42.489918 77.364594 +-43.092430 76.762085 +-44.096615 74.151192 +-40.481571 -77.766251 +40.481560 77.766266 +44.096615 -74.151169 +-40.481541 77.766281 +-44.096645 -74.151161 +44.096638 74.151169 +40.481537 -77.766266 +-42.489918 77.364594 +-43.694942 76.159569 +-43.694973 -76.159538 +-42.489948 -77.364563 +43.694962 76.159546 +42.489937 77.364571 +42.489914 -77.364571 +43.694939 -76.159546 +-37.371159 65.163902 +-37.371159 65.163902 +-28.368649 65.163902 +-28.793957 65.163902 +-37.371174 -65.135574 +-36.945866 -65.135574 +-28.368664 -65.135574 +-28.368664 -65.135574 +-36.782406 65.163902 +-36.782429 65.163902 +-28.957401 65.163902 +-29.382763 65.163902 +-36.782421 -65.135574 +-36.357136 -65.135574 +-28.957417 -65.135574 +-28.957462 -65.135574 +-36.945850 65.163902 +-28.368649 65.163902 +-37.371174 -65.135574 +-28.793972 -65.135574 +-36.357121 65.163902 +-28.957447 65.163902 +-36.782444 -65.135574 +-29.382778 -65.135574 +36.987144 65.163887 +36.987144 65.163887 +36.987122 -65.135582 +36.987122 -65.135582 +36.561836 65.163887 +28.409943 65.163895 +28.409920 -65.135574 +36.561813 -65.135582 +27.984634 65.163895 +27.984634 65.163895 +27.984612 -65.135574 +27.984612 -65.135574 +36.398388 -65.135582 +36.398411 65.163887 +36.398399 65.163887 +36.398376 -65.135582 +28.998718 -65.135574 +28.998741 65.163895 +35.973103 65.163887 +35.973080 -65.135582 +28.573368 -65.135574 +28.573391 65.163895 +28.573433 65.163895 +28.573410 -65.135574 +-2.646059 -0.570249 +-2.646059 -0.570248 +-2.137325 -0.509977 +-2.137324 -0.509977 +-2.598163 -0.974524 +-2.089428 -0.914252 +-2.089428 -0.914252 +-2.599217 -0.965620 +-2.598163 -0.974524 +-2.664405 -0.556926 +-2.664405 -0.556925 +-2.119845 -0.492409 +-2.119846 -0.492409 +-2.613136 -0.989670 +-2.068577 -0.925154 +-2.068577 -0.925154 +-2.614266 -0.980139 +-2.613136 -0.989670 +-2.101421 -1.567498 +-2.101421 -1.567499 +-2.663376 -1.594445 +-2.663376 -1.594445 +-2.117931 -1.223174 +-2.679886 -1.250121 +-2.117931 -1.223174 +-2.679886 -1.250120 +-2.097062 -1.559281 +-2.097062 -1.559281 +-2.658034 -1.602060 +-2.658034 -1.602060 +-2.123273 -1.215558 +-2.684245 -1.258339 +-2.123273 -1.215559 +-2.684245 -1.258338 +-2.097062 -1.559281 +-2.097062 -1.559281 +-2.658034 -1.602060 +-2.658034 -1.602060 +-2.123273 -1.215558 +-2.684245 -1.258339 +-2.123273 -1.215559 +-2.684245 -1.258338 +0.283854 0.166504 +0.597005 0.187988 +0.594868 0.188081 +0.148030 0.191569 +0.121538 0.189925 +0.129252 0.190837 +0.145691 0.190674 +0.667033 0.191203 +0.759114 0.210775 +0.664279 0.190929 +0.753557 0.210937 +0.439453 0.137451 +0.452392 0.143799 +0.435872 0.137695 +0.448975 0.144125 +0.464355 0.145508 +0.472431 0.143534 +0.309671 0.240428 +0.291382 0.251546 +0.313354 0.240845 +0.295532 0.251709 +0.273743 0.165527 +0.273804 0.072876 +0.277506 0.166016 +0.277506 0.072062 +0.283854 0.071289 +0.430990 0.103190 +0.449386 0.092469 +0.426616 0.121134 +0.597005 0.041016 +0.485880 0.098389 +0.472779 0.091797 +0.495138 0.115031 +0.490763 0.132894 +0.616333 0.189087 +0.616374 0.039429 +0.642497 0.037679 +0.642456 0.190430 +0.667053 0.036601 +0.758789 0.023112 +0.782369 0.056138 +0.774713 0.032871 +0.780355 0.045626 +0.782227 0.179199 +0.780273 0.190186 +0.766113 0.209229 +0.014773 0.191569 +0.029053 0.171712 +0.010074 0.191325 +0.015646 0.356852 +0.031342 0.367188 +0.029213 0.364421 +0.036530 0.366699 +0.664280 0.037133 +0.753068 0.023473 +0.121543 0.353285 +0.148041 0.351196 +0.129252 0.352214 +0.151733 0.351563 +0.171326 0.350097 +0.250732 0.524740 +0.184814 0.348308 +0.190362 0.348632 +0.494792 0.316732 +0.332478 0.294083 +0.504883 0.316040 +0.499797 0.315959 +0.499048 0.316885 +0.508789 0.315155 +0.502930 0.315267 +0.012662 0.331868 +0.012657 0.203125 +0.008057 0.202637 +0.008052 0.332031 +0.452931 0.092897 +0.434693 0.103516 +0.430359 0.121094 +0.888184 0.402832 +0.874023 0.389160 +0.883240 0.393799 +0.676758 0.690582 +0.475220 0.390137 +0.888443 0.976762 +0.461243 0.403564 +0.466125 0.394715 +0.461243 0.978142 +0.475220 0.991763 +0.466125 0.987077 +0.874023 0.990971 +0.883240 0.986284 +0.031235 0.169434 +0.023969 0.171224 +0.036377 0.169922 +0.171326 0.192139 +0.168976 0.192505 +0.184814 0.193522 +0.190358 0.193360 +0.332931 0.239874 +0.494792 0.216146 +0.499797 0.216553 +0.504883 0.216553 +0.499044 0.215827 +0.505920 0.217285 +0.502930 0.217285 +0.014733 0.343343 +0.010035 0.343750 +0.287110 0.270426 +0.291260 0.270386 +0.300293 0.287598 +0.296224 0.287923 +0.976563 0.990919 +0.976563 0.986190 +0.978760 0.986187 +0.979004 0.990919 +0.978929 0.985302 +0.976563 0.708557 +0.978760 0.708130 +0.976563 0.985298 +0.979004 0.704071 +0.976563 0.703002 +0.355042 0.263957 +0.350749 0.282878 +0.978760 0.205566 +0.978760 0.211507 +0.976563 0.204915 +0.976563 0.209880 +0.978760 0.012451 +0.976563 0.012940 +0.976563 0.008627 +0.978760 0.009034 +0.976563 0.504517 +0.976563 0.498309 +0.978939 0.504805 +0.978814 0.499166 +0.976563 0.697103 +0.976563 0.504516 +0.978760 0.697753 +0.976563 0.697753 +0.978760 0.701934 +0.008255 0.460938 +0.007919 0.460938 +0.007813 0.460938 +0.008255 0.137695 +0.007813 0.137695 +0.143188 0.460938 +0.008255 0.137207 +0.007813 0.137207 +0.143677 0.460938 +0.143555 0.460938 +0.143188 0.137207 +0.143188 0.137695 +0.143677 0.137695 +0.143555 0.137207 +0.978939 0.216312 +0.976563 0.216053 +0.978760 0.494141 +0.976563 0.216064 +0.976563 0.494152 +0.916992 0.991760 +0.916992 0.992081 +0.916504 0.991760 +0.916504 0.992188 +0.914063 0.991760 +0.914063 0.992188 +0.916504 0.673584 +0.916992 0.673584 +0.916992 0.673096 +0.916504 0.673096 +0.914063 0.673584 +0.914063 0.992081 +0.914063 0.673096 +0.914063 0.673340 +0.945313 0.673096 +0.945313 0.673584 +0.947754 0.673584 +0.947754 0.673096 +0.948242 0.673096 +0.948242 0.673584 +0.948242 0.991760 +0.947754 0.991760 +0.945313 0.991760 +0.945313 0.992188 +0.945313 0.992081 +0.947754 0.992188 +0.948242 0.992081 +0.857422 0.236328 +0.857910 0.236328 +0.857422 0.236816 +0.857910 0.236816 +0.857910 0.367188 +0.857422 0.366699 +0.539063 0.236816 +0.539063 0.236328 +0.539063 0.366699 +0.857422 0.367188 +0.539063 0.367188 +0.932617 0.210938 +0.932129 0.210938 +0.932129 0.080566 +0.932617 0.080566 +0.929688 0.210938 +0.929688 0.080566 +0.932617 0.080078 +0.932129 0.080078 +0.929688 0.080078 +0.916992 0.648193 +0.916992 0.648438 +0.916504 0.648193 +0.916504 0.648438 +0.914063 0.648438 +0.914063 0.648193 +0.916504 0.518066 +0.916992 0.518066 +0.916992 0.517578 +0.916504 0.517578 +0.914063 0.518066 +0.914063 0.517578 +0.914063 0.517822 +0.023209 0.386719 +0.009203 0.400513 +0.014234 0.391480 +0.108765 0.451172 +0.424683 0.386719 +0.338867 0.451172 +0.438660 0.400635 +0.433655 0.391663 +0.338867 0.926941 +0.438660 0.977459 +0.424683 0.991255 +0.433655 0.986458 +0.023209 0.991302 +0.108765 0.926941 +0.009203 0.977516 +0.014234 0.986508 +0.324463 0.296387 +0.310928 0.294874 +0.312988 0.294434 +0.346016 0.246548 +0.594866 0.040900 +0.284349 0.071082 +0.942017 0.357829 +0.937378 0.336487 +0.949127 0.336060 +0.228021 0.056003 +0.229919 0.041829 +0.237610 0.056763 +0.226624 0.043457 +0.219849 0.034913 +0.218811 0.042724 +0.239197 0.075195 +0.230194 0.075195 +0.239136 0.106201 +0.230489 0.106201 +0.237488 0.134155 +0.229116 0.134399 +0.224304 0.153076 +0.229940 0.155599 +0.219604 0.162109 +0.201863 0.154134 +0.203084 0.163900 +0.201731 0.134847 +0.201558 0.106608 +0.201396 0.075277 +0.185547 0.162435 +0.178426 0.153157 +0.172559 0.134522 +0.173503 0.154948 +0.165664 0.133850 +0.164246 0.106689 +0.171188 0.106689 +0.171234 0.075562 +0.164429 0.075684 +0.166239 0.055990 +0.172938 0.055847 +0.201335 0.055176 +0.193878 0.033569 +0.200155 0.042155 +0.177816 0.043457 +0.178630 0.036946 +0.171672 0.042806 +0.935058 0.356201 +0.931396 0.365560 +0.916341 0.356934 +0.950440 0.308105 +0.938232 0.307861 +0.950440 0.276123 +0.938232 0.275879 +0.937622 0.255615 +0.948853 0.255900 +0.916504 0.307617 +0.916992 0.275635 +0.917074 0.254720 +0.944092 0.242188 +0.936035 0.242432 +0.937907 0.236165 +0.923798 0.232620 +0.916992 0.241536 +0.900268 0.233764 +0.898193 0.242188 +0.896240 0.255249 +0.891439 0.240845 +0.884277 0.256470 +0.895263 0.275635 +0.882935 0.275635 +0.895263 0.307617 +0.882935 0.307617 +0.884338 0.336121 +0.895630 0.336243 +0.916423 0.336833 +0.915283 0.367025 +0.899292 0.364746 +0.897461 0.355957 +0.890828 0.358053 +0.495351 0.316521 +0.874023 0.990972 +0.424683 0.992189 +0.893735 0.241533 +0.895237 0.357237 +0.938347 0.357325 +0.939355 0.241475 + + + + + + + + + + + +

4 0 3 4 4 0 1 0 0 0 18 2 2 18 18 18 3 2 18 18 0 4 0 0 0 1 5 1 1 1 5 6 7 5 5 16 7 4 16 16 19 8 6 19 19 19 9 6 19 19 16 10 4 16 16 3 11 5 3 3 7 12 11 7 7 17 13 8 17 17 6 14 10 6 6 6 15 10 6 6 17 16 8 17 17 2 17 9 2 2 22 18 12 22 22 8 19 14 8 8 12 20 15 12 12 8 21 14 8 8 22 22 12 22 22 9 23 13 9 9 23 24 16 23 23 20 25 18 20 20 13 26 19 13 13 20 27 18 20 20 23 28 16 23 23 11 29 17 11 11 14 30 20 14 14 21 31 22 21 21 15 32 23 15 15 21 33 22 21 21 14 34 20 14 14 10 35 21 10 10 1 36 49 1 1 0 37 48 0 0 9 38 56 9 9 9 39 56 9 9 0 40 48 0 0 8 41 57 8 8 0 42 260 0 0 4 43 261 4 4 12 44 59 12 12 12 45 59 12 12 8 46 58 8 8 0 47 260 0 0 11 48 60 11 11 16 49 50 16 16 20 50 61 20 20 3 51 51 3 3 16 52 50 16 16 11 53 60 11 11 2 54 53 2 2 17 55 52 17 17 21 56 63 21 21 2 57 53 2 2 21 58 63 21 21 10 59 62 10 10 6 60 55 6 6 10 61 263 10 10 14 62 262 14 14 10 63 263 10 10 6 64 55 6 6 2 65 54 2 2 18 66 2 18 18 1 67 1 1 1 5 68 7 5 5 5 69 7 5 5 1 70 1 1 1 16 71 4 16 16 19 72 6 19 19 3 73 5 3 3 7 74 11 7 7 7 75 11 7 7 3 76 5 3 3 17 77 8 17 17 13 78 267 13 13 20 79 266 20 20 22 80 12 22 22 22 81 12 22 22 20 82 266 20 20 9 83 13 9 9 15 84 23 15 15 21 85 22 21 21 23 86 264 23 23 23 87 264 23 23 21 88 22 21 21 11 89 265 11 11 16 90 50 16 16 9 91 56 9 9 20 92 61 20 20 9 93 56 9 9 16 94 50 16 16 1 95 49 1 1 21 96 63 21 21 17 97 52 17 17 3 98 51 3 3 21 99 63 21 21 3 100 51 3 3 11 101 60 11 11 24 102 24 24 24 27 103 25 27 27 26 104 26 26 26 26 105 26 26 26 25 106 27 25 25 24 107 24 24 24 28 108 28 28 28 31 109 29 31 31 30 110 30 30 30 30 111 30 30 30 29 112 31 29 29 28 113 28 28 28 32 114 32 32 32 35 115 33 35 35 34 116 34 34 34 34 117 34 34 34 33 118 35 33 33 32 119 32 32 32 39 120 37 39 39 38 121 38 38 38 36 122 36 36 36 36 123 36 36 36 38 124 38 38 38 37 125 39 37 37 43 126 41 43 43 42 127 42 42 42 40 128 40 40 40 40 129 40 40 40 42 130 42 42 42 41 131 43 41 41 47 132 45 47 47 46 133 46 46 46 44 134 44 44 44 44 135 44 44 44 46 136 46 46 46 45 137 47 45 45 37 138 71 37 37 38 139 70 38 38 24 140 64 24 24 24 141 64 24 24 25 142 65 25 25 37 143 71 37 37 27 144 269 27 27 24 145 268 24 24 39 146 273 39 39 39 147 273 39 39 24 148 268 24 24 38 149 274 38 38 28 150 66 28 28 29 151 67 29 29 41 152 121 41 41 28 153 66 28 28 41 154 121 41 41 42 155 120 42 42 45 156 123 45 45 46 157 122 46 46 33 158 69 33 33 33 159 69 33 33 46 160 122 46 46 32 161 68 32 32 44 162 276 44 44 45 163 279 45 45 34 164 270 34 34 34 165 270 34 34 45 166 279 45 45 33 167 271 33 33 25 168 27 25 25 26 169 26 26 26 31 170 29 31 31 31 171 29 31 31 28 172 28 28 28 25 173 27 25 25 29 174 31 29 29 30 175 30 30 30 35 176 33 35 35 35 177 33 35 35 32 178 32 32 32 29 179 31 29 29 36 180 272 36 36 42 181 42 42 42 43 182 41 43 43 42 183 42 42 42 36 184 272 36 36 37 185 275 37 37 40 186 40 40 40 46 187 278 46 46 47 188 277 47 47 46 189 278 46 46 40 190 40 40 40 41 191 43 41 41 37 192 71 37 37 28 193 66 28 28 42 194 120 42 42 28 195 66 28 28 37 196 71 37 37 25 197 65 25 25 32 198 68 32 32 46 199 122 46 46 29 200 67 29 29 29 201 67 29 29 46 202 122 46 46 41 203 121 41 41 48 204 72 48 48 51 205 73 51 51 50 206 74 50 50 50 207 74 50 50 49 208 75 49 49 48 209 72 48 48 52 210 76 52 52 55 211 77 55 55 54 212 78 54 54 54 213 78 54 54 53 214 79 53 53 52 215 76 52 52 56 216 80 56 56 59 217 81 59 59 58 218 82 58 58 58 219 82 58 58 57 220 83 57 57 56 221 80 56 56 63 222 85 63 63 62 223 86 62 62 60 224 84 60 60 60 225 84 60 60 62 226 86 62 62 61 227 87 61 61 67 228 89 67 67 66 229 90 66 66 64 230 88 64 64 64 231 88 64 64 66 232 90 66 66 65 233 91 65 65 71 234 93 71 71 70 235 94 70 70 68 236 92 68 68 68 237 92 68 68 70 238 94 70 70 69 239 95 69 69 48 240 124 48 48 49 241 125 49 49 61 242 131 61 61 48 243 124 48 48 61 244 131 61 61 62 245 130 62 62 51 246 293 51 51 48 247 292 48 48 63 248 297 63 63 63 249 297 63 63 48 250 292 48 48 62 251 298 62 62 52 252 126 52 52 53 253 127 53 53 65 254 133 65 65 52 255 126 52 52 65 256 133 65 65 66 257 132 66 66 56 258 128 56 56 57 259 129 57 57 70 260 134 70 70 70 261 134 70 70 57 262 129 57 57 69 263 135 69 69 68 264 300 68 68 69 265 303 69 69 58 266 294 58 58 58 267 294 58 58 69 268 303 69 69 57 269 295 57 57 49 270 75 49 49 50 271 74 50 50 55 272 77 55 55 55 273 77 55 55 52 274 76 52 52 49 275 75 49 49 53 276 79 53 53 54 277 78 54 54 59 278 81 59 59 59 279 81 59 59 56 280 80 56 56 53 281 79 53 53 60 282 296 60 60 66 283 90 66 66 67 284 89 67 67 66 285 90 66 66 60 286 296 60 60 61 287 299 61 61 64 288 88 64 64 70 289 302 70 70 71 290 301 71 71 70 291 302 70 70 64 292 88 64 64 65 293 91 65 65 61 294 131 61 61 49 295 125 49 49 52 296 126 52 52 61 297 131 61 61 52 298 126 52 52 66 299 132 66 66 65 300 133 65 65 53 301 127 53 53 70 302 134 70 70 70 303 134 70 70 53 304 127 53 53 56 305 128 56 56 73 306 99 73 73 72 307 96 72 72 74 308 98 74 74 74 309 98 74 74 72 310 96 72 72 75 311 97 75 75 77 312 103 77 77 76 313 100 76 76 78 314 102 78 78 78 315 102 78 78 76 316 100 76 76 79 317 101 79 79 81 318 107 81 81 80 319 104 80 80 82 320 106 82 82 82 321 106 82 82 80 322 104 80 80 83 323 105 83 83 84 324 108 84 84 86 325 110 86 86 85 326 111 85 85 86 327 110 86 86 84 328 108 84 84 87 329 109 87 87 88 330 112 88 88 90 331 114 90 90 89 332 115 89 89 90 333 114 90 90 88 334 112 88 88 91 335 113 91 91 92 336 116 92 92 94 337 118 94 94 93 338 119 93 93 94 339 118 94 94 92 340 116 92 92 95 341 117 95 95 86 342 143 86 86 87 343 142 87 87 72 344 136 72 72 75 345 137 75 75 72 346 136 72 72 87 347 142 87 87 72 348 280 72 72 73 349 281 73 73 85 350 287 85 85 85 351 287 85 85 86 352 286 86 86 72 353 280 72 72 76 354 138 76 76 91 355 256 91 91 79 356 139 79 79 91 357 256 91 91 76 358 138 76 76 90 359 257 90 90 83 360 141 83 83 94 361 259 94 94 95 362 258 95 95 83 363 141 83 83 80 364 140 80 80 94 365 259 94 94 82 366 283 82 82 95 367 289 95 95 92 368 288 92 92 95 369 289 95 95 82 370 283 82 82 83 371 282 83 83 74 372 98 74 74 75 373 97 75 75 77 374 103 77 77 77 375 103 77 77 75 376 97 75 75 76 377 100 76 76 78 378 102 78 78 79 379 101 79 79 81 380 107 81 81 81 381 107 81 81 79 382 101 79 79 80 383 104 80 80 89 384 115 89 89 90 385 114 90 90 84 386 284 84 84 84 387 284 84 84 90 388 114 90 90 87 389 285 87 87 93 390 291 93 93 94 391 290 94 94 88 392 112 88 88 88 393 112 88 88 94 394 290 94 94 91 395 113 91 91 87 396 142 87 87 76 397 138 76 76 75 398 137 75 75 76 399 138 76 76 87 400 142 87 87 90 401 257 90 90 79 402 139 79 79 91 403 256 91 91 94 404 259 94 94 79 405 139 79 79 94 406 259 94 94 80 407 140 80 80 105 408 146 115 115 96 409 144 96 96 104 410 171 113 113 96 411 144 96 96 105 412 146 115 115 97 413 147 97 97 98 414 158 98 98 100 415 159 104 104 117 416 778 140 140 118 417 777 141 141 117 418 778 140 140 100 419 159 104 104 119 420 780 143 143 96 421 144 96 96 108 422 779 128 128 96 423 144 96 96 119 424 780 143 143 104 425 171 113 113 110 426 784 131 131 105 427 146 115 115 111 428 783 132 132 111 429 783 132 132 105 430 146 115 115 101 431 150 105 105 113 432 788 135 135 107 433 164 119 119 114 434 787 136 136 114 435 787 136 136 107 436 164 119 119 103 437 154 107 107 118 438 176 141 141 111 439 177 132 132 117 440 179 140 140 117 441 179 140 140 111 442 177 132 132 112 443 178 133 133 109 444 789 129 129 108 445 790 128 128 96 446 144 96 96 109 447 789 129 129 96 448 144 96 96 97 449 147 97 97 109 450 792 129 129 97 451 147 97 97 110 452 791 131 131 110 453 791 131 131 97 454 147 97 97 105 455 146 115 115 101 456 150 105 105 99 457 151 99 99 111 458 794 132 132 112 459 793 133 133 111 460 794 132 132 99 461 151 99 99 112 462 796 133 133 99 463 151 99 99 113 464 795 135 135 113 465 795 135 135 99 466 151 99 99 107 467 164 119 119 103 468 154 107 107 102 469 155 106 106 114 470 800 136 136 115 471 799 137 137 114 472 800 136 136 102 473 155 106 106 115 474 802 137 137 102 475 155 106 106 116 476 801 139 139 116 477 801 139 139 102 478 155 106 106 106 479 166 117 117 116 480 806 139 139 106 481 166 117 117 117 482 805 140 140 117 483 805 140 140 106 484 166 117 117 98 485 158 98 98 118 486 808 141 141 100 487 159 104 104 119 488 807 143 143 119 489 807 143 143 100 490 159 104 104 104 491 171 113 113 117 492 179 140 140 113 493 341 135 135 116 494 347 139 139 113 495 341 135 135 117 496 179 140 140 112 497 178 133 133 116 498 347 139 139 113 499 341 135 135 114 500 342 136 136 116 501 347 139 139 114 502 342 136 136 115 503 343 137 137 111 504 177 132 132 118 505 176 141 141 119 506 351 143 143 119 507 351 143 143 110 508 337 131 131 111 509 177 132 132 110 510 337 131 131 119 511 351 143 143 108 512 333 128 128 110 513 337 131 131 108 514 333 128 128 109 515 332 129 129 99 516 151 99 99 98 517 158 98 98 107 518 164 119 119 107 519 164 119 119 98 520 158 98 98 106 521 166 117 117 106 522 166 117 117 103 523 154 107 107 107 524 164 119 119 103 525 154 107 107 106 526 166 117 117 102 527 155 106 106 98 528 158 98 98 99 529 151 99 99 101 530 150 105 105 101 531 150 105 105 100 532 159 104 104 98 533 158 98 98 104 534 171 113 113 101 535 150 105 105 105 536 146 115 115 100 537 159 104 104 101 538 150 105 105 104 539 171 113 113 124 540 211 164 164 120 541 208 160 160 121 542 209 161 161 124 543 211 164 164 121 544 209 161 161 138 545 210 178 178 125 546 215 165 165 136 547 212 176 176 139 548 214 179 179 139 549 214 179 179 136 550 212 176 176 123 551 213 163 163 127 552 219 167 167 137 553 216 177 177 126 554 218 166 166 122 555 217 162 162 126 556 218 166 166 137 557 216 177 177 142 558 220 182 182 129 559 221 169 169 132 560 223 172 172 128 561 222 168 168 132 562 223 172 172 129 563 221 169 169 143 564 224 183 183 131 565 225 171 171 140 566 226 180 180 140 567 226 180 180 133 568 227 173 173 143 569 224 183 183 134 570 228 174 174 130 571 229 170 170 141 572 230 181 181 134 573 228 174 174 141 574 230 181 181 135 575 231 175 175 120 576 316 160 160 132 577 321 172 172 128 578 320 168 168 132 579 321 172 172 120 580 316 160 160 124 581 317 164 164 126 582 319 166 166 122 583 318 162 162 130 584 323 170 170 130 585 323 170 170 134 586 322 174 174 126 587 319 166 166 138 588 210 178 178 121 589 209 161 161 125 590 215 165 165 125 591 215 165 165 121 592 209 161 161 136 593 212 176 176 139 594 214 179 179 123 595 213 163 163 127 596 219 167 167 127 597 219 167 167 123 598 213 163 163 137 599 216 177 177 133 600 227 173 173 140 601 226 180 180 129 602 325 169 169 129 603 325 169 169 142 604 324 182 182 133 605 227 173 173 135 606 327 175 175 141 607 326 181 181 131 608 225 171 171 131 609 225 171 171 143 610 224 183 183 135 611 327 175 175 146 612 234 186 186 145 613 235 185 185 147 614 233 187 187 144 615 232 184 184 147 616 233 187 187 145 617 235 185 185 148 618 236 188 188 151 619 237 191 191 150 620 238 190 190 150 621 238 190 190 149 622 239 189 189 148 623 236 188 188 154 624 242 194 194 153 625 243 193 193 152 626 240 192 192 154 627 242 194 194 152 628 240 192 192 155 629 241 195 195 159 630 245 199 199 158 631 246 198 198 157 632 247 197 197 159 633 245 199 199 157 634 247 197 197 156 635 244 196 196 161 636 251 201 201 160 637 248 200 200 162 638 250 202 202 162 639 250 202 202 160 640 248 200 200 163 641 249 203 203 164 642 252 204 204 166 643 254 206 206 165 644 255 205 205 166 645 254 206 206 164 646 252 204 204 167 647 253 207 207 147 648 305 187 187 144 649 304 184 184 158 650 309 198 198 158 651 309 198 198 159 652 308 199 199 147 653 305 187 187 164 654 310 204 204 165 655 311 205 205 153 656 307 193 193 153 657 307 193 193 154 658 306 194 194 164 659 310 204 204 151 660 237 191 191 148 661 236 188 188 146 662 234 186 186 146 663 234 186 186 148 664 236 188 188 145 665 235 185 185 155 666 241 195 195 152 667 240 192 192 150 668 238 190 190 150 669 238 190 190 152 670 240 192 192 149 671 239 189 189 156 672 312 196 196 157 673 313 197 197 162 674 250 202 202 162 675 250 202 202 163 676 249 203 203 156 677 312 196 196 160 678 248 200 200 161 679 251 201 201 166 680 315 206 206 166 681 315 206 206 167 682 314 207 207 160 683 248 200 200

+

210 864 478 252 252 208 865 476 250 250 220 866 488 535 264 212 867 480 254 254 211 868 479 253 253 214 869 482 256 256 213 870 481 255 255 211 871 479 253 253 212 872 480 254 254 213 873 481 255 259 215 874 483 257 258 216 875 484 258 260 215 876 483 257 258 213 877 481 255 259 212 878 480 254 257 217 879 485 259 261 218 880 486 260 262 219 881 487 261 263 218 882 486 260 262 220 883 488 262 264 219 884 487 261 263 218 885 486 260 262 221 886 489 263 265 220 887 488 262 264 221 888 489 263 265 222 889 490 264 266 220 890 488 262 264 221 891 489 263 267 223 892 491 265 268 222 893 490 264 269 223 894 491 265 268 224 895 492 266 270 222 896 490 264 269 228 897 496 270 274 227 898 495 269 273 226 899 494 268 272 226 900 494 268 272 227 901 495 269 273 225 902 493 267 271 229 903 497 271 275 227 904 495 269 273 228 905 496 270 274 227 906 495 269 273 229 907 497 271 275 208 908 476 250 250 230 909 498 272 276 229 910 497 271 275 231 911 499 273 277 229 912 497 271 275 232 913 500 274 278 208 914 476 250 250 232 915 500 274 278 229 916 497 271 275 230 917 498 272 276 235 918 503 277 281 233 919 501 275 279 234 920 502 276 280 231 921 499 278 277 233 922 501 275 279 235 923 503 277 281 233 924 501 275 279 209 925 477 251 251 236 926 504 279 282 233 927 501 275 279 236 928 504 279 282 234 929 502 276 280 209 930 477 251 251 222 931 490 280 266 224 932 492 281 283 236 933 504 279 282 209 934 477 251 251 224 935 492 281 283 238 936 506 283 285 237 937 505 282 284 233 938 501 275 279 209 939 477 251 251 233 940 501 275 279 237 941 505 282 284 238 942 506 283 285 214 943 482 285 287 237 944 505 282 284 214 945 482 285 287 238 946 506 283 285 239 947 507 284 286 214 948 482 285 287 239 949 507 284 286 212 950 480 286 257 212 951 480 286 257 239 952 507 284 286 240 953 508 287 288 241 954 509 288 289 212 955 480 286 257 240 956 508 287 288 212 957 480 286 257 241 958 509 288 289 215 959 483 289 258 215 960 483 289 258 241 961 509 288 289 242 962 510 290 290 242 963 510 290 290 241 964 509 288 289 243 965 511 291 291 242 966 510 290 290 243 967 511 291 291 244 968 512 292 292 245 969 513 293 293 215 970 483 289 258 242 971 510 290 290 215 972 483 289 258 245 973 513 293 293 246 974 514 294 294 215 975 483 289 258 246 976 514 294 294 247 977 515 295 295 249 978 517 297 297 246 979 514 298 298 248 980 516 296 296 246 981 514 298 298 249 982 517 297 297 247 983 515 295 295 251 984 519 302 302 243 985 511 299 299 241 986 509 300 300 243 987 511 299 299 251 988 519 302 302 250 989 518 301 301 241 990 509 300 289 252 991 520 303 303 251 992 519 302 304 252 993 520 303 303 241 994 509 300 289 240 995 508 304 288 253 996 521 305 306 252 997 520 303 307 240 998 508 304 305 240 999 508 304 305 239 1000 507 306 308 253 1001 521 305 306 254 1002 522 308 310 239 1003 507 306 308 238 1004 506 307 309 239 1005 507 306 308 254 1006 522 308 310 253 1007 521 305 306 233 1008 501 310 312 254 1009 522 308 310 238 1010 506 307 309 254 1011 522 308 310 233 1012 501 310 312 255 1013 523 309 311 255 1014 523 538 488 231 1015 499 278 277 229 1016 497 271 275 231 1017 499 278 277 255 1018 523 538 488 233 1019 501 275 279 256 1020 524 312 313 257 1021 525 313 314 255 1022 523 311 311 229 1023 497 317 317 228 1024 496 315 315 256 1025 524 314 313 256 1026 524 314 313 228 1027 496 315 315 258 1028 526 316 316 228 1029 496 315 315 226 1030 494 318 318 258 1031 526 316 316 258 1032 526 316 316 226 1033 494 318 318 259 1034 527 319 319 260 1035 528 320 320 261 1036 529 321 321 245 1037 513 322 322 260 1038 528 320 320 245 1039 513 322 322 242 1040 510 323 323 257 1041 525 325 324 262 1042 530 326 325 230 1043 498 324 276 230 1044 498 324 276 231 1045 499 327 277 257 1046 525 325 324 232 1047 500 329 278 262 1048 530 326 325 263 1049 531 328 326 262 1050 530 326 325 232 1051 500 329 278 230 1052 498 324 276 219 1053 487 261 263 232 1054 500 329 278 217 1055 485 259 261 217 1056 485 259 261 232 1057 500 329 278 263 1058 531 328 326 264 1059 532 330 327 267 1060 535 333 330 265 1061 533 331 328 264 1062 532 330 327 265 1063 533 331 328 266 1064 534 332 329 267 1065 535 333 330 268 1066 536 334 331 265 1067 533 331 328 269 1068 537 335 332 267 1069 535 333 330 264 1070 532 330 327 268 1071 536 334 331 267 1072 535 333 330 270 1073 538 336 333 268 1074 536 334 331 270 1075 538 336 333 271 1076 539 337 334 267 1077 535 333 330 272 1078 540 338 335 270 1079 538 336 333 267 1080 535 333 330 273 1081 541 339 336 272 1082 540 338 335 272 1083 540 338 335 273 1084 541 339 336 274 1085 542 340 337 267 1086 535 333 330 293 1087 771 615 564 273 1088 541 339 336 293 1089 771 615 564 267 1090 535 333 330 275 1091 543 341 338 275 1092 543 341 338 267 1093 535 333 330 269 1094 537 335 332 275 1095 543 341 338 269 1096 537 335 332 276 1097 544 342 339 249 1098 517 344 297 215 1099 483 257 340 247 1100 515 343 341 215 1101 483 257 340 249 1102 517 344 297 216 1103 484 258 342 211 1104 479 253 253 277 1105 545 346 344 214 1106 482 256 256 237 1107 505 345 343 214 1108 482 256 256 277 1109 545 346 344 210 1110 478 347 345 237 1111 505 345 343 277 1112 545 346 344 237 1113 505 345 343 210 1114 478 347 345 209 1115 477 348 346 278 1116 546 351 348 210 1117 478 349 345 218 1118 486 350 347 208 1119 476 540 351 210 1120 478 349 345 278 1121 546 351 348 278 1122 546 352 348 279 1123 547 353 349 227 1124 495 354 350 278 1125 546 352 348 227 1126 495 354 350 208 1127 476 355 351 225 1128 493 356 352 279 1129 547 353 349 280 1130 548 357 353 279 1131 547 353 349 225 1132 493 356 352 227 1133 495 354 350 244 1134 512 360 355 250 1135 518 358 301 281 1136 549 359 354 250 1137 518 358 301 244 1138 512 360 355 243 1139 511 361 299 242 1140 510 323 323 281 1141 549 359 354 260 1142 528 320 320 281 1143 549 359 354 242 1144 510 323 323 244 1145 512 360 355 246 1146 514 298 298 245 1147 513 322 322 248 1148 516 362 296 261 1149 529 321 321 248 1150 516 362 296 245 1151 513 322 322 224 1152 492 365 270 282 1153 550 364 356 236 1154 504 366 357 282 1155 550 364 356 224 1156 492 365 270 223 1157 491 363 268 282 1158 550 364 356 283 1159 551 368 359 234 1160 502 367 358 234 1161 502 367 358 236 1162 504 366 357 282 1163 550 364 356 266 1164 555 372 363 284 1165 552 369 360 264 1166 554 371 362 284 1167 552 369 360 285 1168 553 370 361 264 1169 554 371 362 285 1170 553 370 367 269 1171 557 374 366 264 1172 554 371 364 269 1173 557 374 366 285 1174 553 370 367 286 1175 556 373 365 287 1176 559 376 369 269 1177 557 374 366 286 1178 556 373 365 269 1179 557 374 366 287 1180 559 376 369 276 1181 558 375 368 255 1182 523 311 311 283 1183 551 377 359 282 1184 550 378 356 223 1185 491 380 268 210 1186 478 349 345 282 1187 550 378 356 282 1188 550 378 356 210 1189 478 349 345 255 1190 523 311 311 218 1191 486 350 347 210 1192 478 349 345 221 1193 489 379 267 221 1194 489 379 267 210 1195 478 349 345 223 1196 491 380 268 278 1197 546 351 348 263 1198 531 381 370 256 1199 524 312 313 256 1200 524 312 313 263 1201 531 381 370 262 1202 530 382 371 257 1203 525 313 314 256 1204 524 312 313 262 1205 530 382 371 279 1206 547 384 349 256 1207 524 312 313 258 1208 526 383 316 256 1209 524 312 313 279 1210 547 384 349 278 1211 546 351 348 255 1212 523 311 311 210 1213 478 349 345 277 1214 545 385 344 255 1215 523 311 311 277 1216 545 385 344 254 1217 522 386 310 211 1218 479 388 253 254 1219 522 386 310 277 1220 545 385 344 254 1221 522 386 310 211 1222 479 388 253 253 1223 521 387 306 213 1224 481 389 255 252 1225 520 390 307 253 1226 521 387 306 253 1227 521 387 306 211 1228 479 388 253 213 1229 481 389 255 213 1230 481 389 255 251 1231 519 391 302 252 1232 520 390 307 251 1233 519 391 302 216 1234 484 392 342 260 1235 528 393 320 216 1236 484 392 342 251 1237 519 391 302 213 1238 481 389 255 250 1239 518 358 301 260 1240 528 393 320 281 1241 549 394 354 251 1242 519 391 302 260 1243 528 393 320 250 1244 518 358 301 260 1245 528 393 320 216 1246 484 392 342 261 1247 529 395 321 248 1248 516 296 296 216 1249 484 392 342 249 1250 517 396 297 261 1251 529 395 321 216 1252 484 392 342 248 1253 516 296 296 268 1254 560 397 372 289 1255 563 400 375 288 1256 562 399 374 289 1257 563 400 375 268 1258 560 397 372 271 1259 561 398 373 265 1260 564 401 376 268 1261 560 397 372 290 1262 565 402 377 290 1263 565 402 377 268 1264 560 397 372 288 1265 562 399 374 284 1266 566 403 378 265 1267 564 401 376 290 1268 565 402 377 265 1269 564 401 376 284 1270 566 403 378 266 1271 567 404 379 291 1272 568 405 380 274 1273 571 408 383 273 1274 570 407 382 274 1275 571 408 383 291 1276 568 405 380 292 1277 569 406 381 273 1278 772 616 565 293 1279 691 528 480 355 1280 692 529 481 293 1281 572 409 387 276 1282 575 412 388 287 1283 574 411 369 276 1284 575 412 388 293 1285 572 409 387 275 1286 573 410 386 296 1287 578 415 390 294 1288 576 413 389 295 1289 577 414 389 294 1290 576 413 389 296 1291 578 415 390 297 1292 579 416 391 298 1293 580 417 392 294 1294 576 413 389 297 1295 579 416 391 297 1296 579 416 391 299 1297 581 418 393 298 1298 580 417 392 301 1299 583 420 394 295 1300 577 414 389 294 1301 576 413 389 301 1302 583 420 394 294 1303 576 413 389 300 1304 582 419 394 298 1305 580 417 392 299 1306 581 418 393 303 1307 585 422 396 298 1308 580 417 392 303 1309 585 422 396 302 1310 584 421 395 301 1311 583 420 394 300 1312 582 419 394 305 1313 587 424 398 305 1314 587 424 398 300 1315 582 419 394 304 1316 586 423 397 298 1317 580 417 392 306 1318 588 425 399 307 1319 589 426 400 306 1320 588 425 399 298 1321 580 417 392 302 1322 584 421 395 304 1323 586 423 397 307 1324 589 426 400 308 1325 590 427 401 307 1326 589 426 400 304 1327 586 423 397 300 1328 582 419 394 307 1329 589 426 400 309 1330 588 428 402 308 1331 590 427 401 309 1332 588 428 402 307 1333 589 426 400 306 1334 588 425 399 279 1335 547 384 349 259 1336 591 429 319 280 1337 548 430 353 259 1338 591 429 319 279 1339 547 384 349 258 1340 526 383 316 310 1341 594 433 404 271 1342 592 431 373 270 1343 593 432 403 271 1344 592 431 373 310 1345 594 433 404 289 1346 595 434 375 311 1347 597 436 407 310 1348 594 433 406 272 1349 596 435 405 272 1350 596 435 405 310 1351 594 433 406 270 1352 593 432 403 274 1353 599 438 383 292 1354 598 437 381 311 1355 597 436 407 274 1356 599 438 383 311 1357 597 436 407 272 1358 596 435 405 312 1359 600 439 408 313 1360 601 440 409 314 1361 602 441 410 313 1362 601 440 409 315 1363 603 442 411 314 1364 602 441 410 315 1365 603 442 411 316 1366 604 443 412 314 1367 602 441 410 316 1368 604 443 412 315 1369 603 442 411 317 1370 605 444 413 319 1371 607 446 415 314 1372 602 441 410 318 1373 606 445 414 314 1374 602 441 410 319 1375 607 446 415 312 1376 600 439 408 320 1377 608 447 416 319 1378 607 446 415 318 1379 606 445 414 320 1380 608 447 416 318 1381 606 445 414 321 1382 609 448 417 314 1383 602 441 410 322 1384 610 449 418 318 1385 606 445 414 322 1386 610 449 418 314 1387 602 441 410 316 1388 604 443 412 303 1389 611 450 419 316 1390 604 443 412 317 1391 605 444 413 316 1392 604 443 412 303 1393 611 450 419 299 1394 612 451 412 316 1395 604 443 412 297 1396 613 452 418 322 1397 610 449 418 297 1398 613 452 418 316 1399 604 443 412 299 1400 612 451 412 318 1401 606 445 414 323 1402 614 453 420 321 1403 609 448 417 323 1404 614 453 420 318 1405 606 445 414 322 1406 610 449 418 323 1407 614 453 420 322 1408 610 449 418 296 1409 615 454 421 322 1410 610 449 418 297 1411 613 452 418 296 1412 615 454 421 324 1413 616 455 422 325 1414 617 456 423 309 1415 616 457 422 325 1416 617 456 423 308 1417 618 458 423 309 1418 616 457 422 326 1419 619 459 424 325 1420 617 456 423 327 1421 620 460 425 327 1422 620 460 425 325 1423 617 456 423 324 1424 616 455 422 329 1425 622 462 427 326 1426 619 459 424 328 1427 621 461 426 328 1428 621 461 426 326 1429 619 459 424 327 1430 620 460 425 331 1431 624 464 429 329 1432 622 462 427 330 1433 623 463 428 329 1434 622 462 427 331 1435 624 464 429 326 1436 619 459 424 332 1437 625 465 430 308 1438 618 458 423 325 1439 617 456 423 308 1440 618 458 423 332 1441 625 465 430 304 1442 626 466 430 326 1443 619 459 424 331 1444 624 464 429 332 1445 625 465 430 326 1446 619 459 424 332 1447 625 465 430 325 1448 617 456 423 333 1449 627 465 431 305 1450 628 467 432 332 1451 625 465 430 332 1452 625 465 430 305 1453 628 467 432 304 1454 626 466 430 334 1455 629 464 433 332 1456 625 465 430 331 1457 624 464 429 332 1458 625 465 430 334 1459 629 464 433 333 1460 627 465 431 330 1461 623 463 428 335 1462 630 468 434 331 1463 624 464 429 335 1464 630 468 434 334 1465 629 464 433 331 1466 624 464 429 336 1467 633 471 437 319 1468 631 469 435 320 1469 632 470 436 336 1470 633 471 437 320 1471 632 470 436 337 1472 634 472 438 336 1473 633 471 437 338 1474 635 473 439 339 1475 636 474 440 337 1476 634 472 438 338 1477 635 473 439 336 1478 633 471 437 319 1479 631 469 435 340 1480 637 475 441 312 1481 638 476 442 340 1482 637 475 441 319 1483 631 469 435 336 1484 633 471 437 313 1485 639 477 442 340 1486 637 475 441 341 1487 640 478 441 340 1488 637 475 441 313 1489 639 477 442 312 1490 638 476 442 342 1491 641 479 443 336 1492 633 471 437 339 1493 636 474 440 336 1494 633 471 437 342 1495 641 479 443 340 1496 637 475 441 339 1497 636 474 440 335 1498 642 480 439 330 1499 643 481 444 335 1500 642 480 439 339 1501 636 474 440 338 1502 635 473 439 342 1503 641 479 443 330 1504 643 481 444 329 1505 644 482 445 330 1506 643 481 444 342 1507 641 479 443 339 1508 636 474 440 340 1509 637 475 441 343 1510 645 483 445 341 1511 640 478 441 343 1512 645 483 445 340 1513 637 475 441 342 1514 641 479 443 328 1515 646 484 445 343 1516 645 483 445 342 1517 641 479 443 342 1518 641 479 443 329 1519 644 482 445 328 1520 646 484 445 343 1521 647 485 446 328 1522 648 486 446 344 1523 649 487 447 328 1524 648 486 446 327 1525 650 488 447 344 1526 649 487 447 341 1527 652 490 449 344 1528 649 487 447 345 1529 651 489 448 344 1530 649 487 447 341 1531 652 490 449 343 1532 647 485 446 346 1533 653 491 450 344 1534 649 487 447 327 1535 650 488 447 327 1536 650 488 447 324 1537 654 492 450 346 1538 653 491 450 324 1539 654 492 450 309 1540 655 493 450 346 1541 653 491 450 346 1542 653 491 450 309 1543 655 493 450 306 1544 656 494 450 346 1545 653 491 450 302 1546 658 496 451 347 1547 657 495 451 302 1548 658 496 451 346 1549 653 491 450 306 1550 656 494 450 345 1551 651 489 448 344 1552 649 487 447 346 1553 653 491 450 345 1554 651 489 448 346 1555 653 491 450 347 1556 657 495 451 313 1557 659 497 452 341 1558 652 490 449 345 1559 651 489 448 313 1560 659 497 452 345 1561 651 489 448 315 1562 660 498 453 317 1563 661 499 454 315 1564 660 498 453 345 1565 651 489 448 345 1566 651 489 448 347 1567 657 495 451 317 1568 661 499 454 317 1569 661 499 454 347 1570 657 495 451 303 1571 662 500 454 347 1572 657 495 451 302 1573 658 496 451 303 1574 662 500 454 337 1575 663 501 455 320 1576 664 502 456 348 1577 665 503 457 320 1578 664 502 456 321 1579 666 504 458 348 1580 665 503 457 321 1581 666 504 458 323 1582 667 505 459 348 1583 665 503 457 348 1584 665 503 457 323 1585 667 505 459 349 1586 668 506 460 338 1587 670 508 462 348 1588 665 503 457 350 1589 669 507 461 348 1590 665 503 457 338 1591 670 508 462 337 1592 663 501 455 349 1593 668 506 460 323 1594 667 505 459 296 1595 671 509 459 349 1596 668 506 460 296 1597 671 509 459 295 1598 672 510 460 335 1599 673 508 463 338 1600 670 508 462 350 1601 669 507 461 335 1602 673 508 463 350 1603 669 507 461 334 1604 674 511 464 348 1605 665 503 457 351 1606 675 512 465 350 1607 669 507 461 351 1608 675 512 465 348 1609 665 503 457 349 1610 668 506 460 349 1611 668 506 460 301 1612 676 513 465 351 1613 675 512 465 301 1614 676 513 465 349 1615 668 506 460 295 1616 672 510 460 350 1617 669 507 461 351 1618 675 512 465 334 1619 674 511 464 334 1620 674 511 464 351 1621 675 512 465 333 1622 677 514 466 333 1623 677 514 466 351 1624 675 512 465 305 1625 678 515 467 351 1626 675 512 465 301 1627 676 513 465 305 1628 678 515 467 290 1629 679 516 468 352 1630 682 519 471 285 1631 680 517 469 290 1632 679 516 468 285 1633 680 517 469 284 1634 681 518 470 290 1635 679 516 468 288 1636 683 520 472 352 1637 682 519 471 352 1638 682 519 471 288 1639 683 520 472 353 1640 684 521 473 353 1641 684 521 473 288 1642 683 520 472 310 1643 685 522 474 310 1644 685 522 474 288 1645 683 520 472 289 1646 686 523 475 353 1647 684 521 473 311 1648 688 525 477 354 1649 687 524 476 311 1650 688 525 477 353 1651 684 521 473 310 1652 685 522 474 354 1653 687 524 476 311 1654 688 525 477 291 1655 689 526 478 291 1656 689 526 478 311 1657 688 525 477 292 1658 690 527 479 291 1659 689 526 478 355 1660 692 529 481 354 1661 687 524 476 352 1662 682 519 471 354 1663 687 524 476 355 1664 692 529 481 354 1665 687 524 476 352 1666 682 519 471 353 1667 684 521 473 286 1668 693 530 482 355 1669 692 529 481 293 1670 691 528 480 286 1671 693 530 482 293 1672 691 528 480 287 1673 694 531 483 285 1674 680 517 469 355 1675 692 529 481 286 1676 693 530 482 355 1677 692 529 481 285 1678 680 517 469 352 1679 682 519 471 356 1680 695 532 485 257 1681 525 325 314 231 1682 499 327 484 231 1683 499 327 484 235 1684 503 533 486 356 1685 695 532 485 235 1686 503 533 486 283 1687 551 368 359 356 1688 695 532 485 283 1689 551 368 359 235 1690 503 533 486 234 1691 502 367 358 255 1692 523 311 311 257 1693 525 313 314 356 1694 695 534 485 255 1695 523 311 311 356 1696 695 534 485 283 1697 551 377 359 219 1698 487 536 263 208 1699 476 250 250 232 1700 500 274 278 220 1701 488 535 264 208 1702 476 250 250 219 1703 487 536 263 278 1704 546 351 348 218 1705 486 350 347 217 1706 485 537 487 278 1707 546 351 348 217 1708 485 537 487 263 1709 531 381 370 209 1710 477 251 251 220 1711 488 535 264 222 1712 490 280 266 357 1713 696 541 490 358 1714 697 542 491 359 1715 698 543 492 358 1716 697 542 491 357 1717 696 541 490 395 1718 736 581 530 362 1719 701 546 495 360 1720 699 544 493 361 1721 700 545 494 360 1722 699 544 493 363 1723 702 547 496 361 1724 700 545 494 360 1725 699 544 493 365 1726 704 549 498 363 1727 702 547 496 364 1728 703 548 497 363 1729 702 547 496 365 1730 704 549 498 364 1731 753 598 547 361 1732 756 601 550 363 1733 773 617 566 362 1734 701 546 495 366 1735 705 550 499 367 1736 706 551 500 362 1737 701 546 495 367 1738 706 551 500 360 1739 699 544 493 368 1740 707 552 501 367 1741 706 551 500 366 1742 705 550 499 367 1743 706 551 500 368 1744 707 552 501 369 1745 708 553 502 371 1746 710 555 504 369 1747 708 553 502 370 1748 709 554 503 368 1749 707 552 501 370 1750 709 554 503 369 1751 708 553 502 371 1752 710 555 504 373 1753 712 557 506 372 1754 711 556 505 373 1755 712 557 506 371 1756 710 555 504 370 1757 709 554 503 373 1758 768 613 562 374 1759 766 611 560 372 1760 774 618 567 375 1761 714 559 508 374 1762 713 558 507 376 1763 715 560 509 374 1764 713 558 507 375 1765 714 559 508 372 1766 711 556 505 375 1767 714 559 508 377 1768 716 561 510 372 1769 711 556 505 377 1770 716 561 510 371 1771 710 555 504 372 1772 711 556 505 379 1773 718 563 512 367 1774 706 551 500 378 1775 717 562 511 378 1776 717 562 511 367 1777 706 551 500 369 1778 708 553 502 378 1779 717 562 511 371 1780 710 555 504 377 1781 716 561 510 371 1782 710 555 504 378 1783 717 562 511 369 1784 708 553 502 381 1785 720 565 514 375 1786 714 559 508 380 1787 719 564 513 380 1788 719 564 513 375 1789 714 559 508 376 1790 715 560 509 382 1791 721 566 515 377 1792 716 561 510 381 1793 720 565 514 381 1794 720 565 514 377 1795 716 561 510 375 1796 714 559 508 381 1797 775 619 568 380 1798 737 582 531 357 1799 696 541 490 357 1800 722 567 516 359 1801 723 568 517 382 1802 721 566 515 357 1803 722 567 516 382 1804 721 566 515 381 1805 720 565 514 359 1806 723 568 517 383 1807 724 569 518 384 1808 725 570 519 359 1809 723 568 517 384 1810 725 570 519 382 1811 721 566 515 386 1812 727 572 521 384 1813 725 570 519 383 1814 724 569 518 384 1815 725 570 519 386 1816 727 572 521 385 1817 726 571 520 388 1818 729 574 523 385 1819 726 571 520 387 1820 728 573 522 386 1821 727 572 521 387 1822 728 573 522 385 1823 726 571 520 385 1824 726 571 520 378 1825 717 562 511 384 1826 725 570 519 378 1827 717 562 511 385 1828 726 571 520 379 1829 718 563 512 384 1830 725 570 519 378 1831 717 562 511 382 1832 721 566 515 382 1833 721 566 515 378 1834 717 562 511 377 1835 716 561 510 385 1836 726 571 520 388 1837 729 574 523 379 1838 718 563 512 388 1839 729 574 523 389 1840 730 575 524 379 1841 718 563 512 389 1842 730 575 524 360 1843 699 544 493 379 1844 718 563 512 379 1845 718 563 512 360 1846 699 544 493 367 1847 706 551 500 365 1848 704 549 498 391 1849 732 577 526 390 1850 731 576 525 390 1851 731 576 525 364 1852 703 548 497 365 1853 704 549 498 389 1854 730 575 524 365 1855 704 549 498 360 1856 699 544 493 389 1857 730 575 524 391 1858 732 577 526 365 1859 704 549 498 389 1860 730 575 524 388 1861 729 574 523 392 1862 733 578 527 392 1863 733 578 527 391 1864 732 577 526 389 1865 730 575 524 393 1866 734 579 528 391 1867 732 577 526 392 1868 733 578 527 391 1869 732 577 526 393 1870 734 579 528 390 1871 731 576 525 394 1872 735 580 529 388 1873 729 574 523 387 1874 728 573 522 388 1875 729 574 523 394 1876 735 580 529 392 1877 733 578 527 393 1878 750 595 544 394 1879 748 593 542 403 1880 749 594 543 396 1881 738 583 532 380 1882 737 582 531 376 1883 765 610 559 396 1884 738 583 532 395 1885 736 581 530 380 1886 737 582 531 397 1887 740 585 534 359 1888 698 543 492 358 1889 697 542 491 359 1890 698 543 492 397 1891 740 585 534 383 1892 739 584 533 397 1893 740 585 534 398 1894 742 587 536 386 1895 741 586 535 397 1896 740 585 534 386 1897 741 586 535 383 1898 739 584 533 387 1899 744 589 538 398 1900 742 587 536 399 1901 743 588 537 398 1902 742 587 536 387 1903 744 589 538 386 1904 741 586 535 400 1905 745 590 539 401 1906 746 591 540 398 1907 742 587 536 400 1908 745 590 539 398 1909 742 587 536 397 1910 740 585 534 401 1911 746 591 540 402 1912 747 592 541 399 1913 743 588 537 401 1914 746 591 540 399 1915 743 588 537 398 1916 742 587 536 399 1917 743 588 537 403 1918 749 594 543 394 1919 748 593 542 399 1920 743 588 537 394 1921 748 593 542 387 1922 744 589 538 390 1923 751 596 545 393 1924 750 595 544 403 1925 749 594 543 390 1926 751 596 545 403 1927 749 594 543 404 1928 752 597 546 404 1929 752 597 546 403 1930 749 594 543 402 1931 747 592 541 403 1932 749 594 543 399 1933 743 588 537 402 1934 747 592 541 404 1935 752 597 546 405 1936 754 599 548 364 1937 753 598 547 364 1938 753 598 547 390 1939 751 596 545 404 1940 752 597 546 406 1941 755 600 549 405 1942 754 599 548 402 1943 747 592 541 405 1944 754 599 548 404 1945 752 597 546 402 1946 747 592 541 361 1947 756 601 550 406 1948 755 600 549 362 1949 757 602 551 406 1950 755 600 549 361 1951 756 601 550 405 1952 754 599 548 406 1953 755 600 549 401 1954 746 591 540 407 1955 758 603 552 401 1956 746 591 540 406 1957 755 600 549 402 1958 747 592 541 362 1959 757 602 551 407 1960 758 603 552 366 1961 759 604 553 407 1962 758 603 552 362 1963 757 602 551 406 1964 755 600 549 407 1965 758 603 552 408 1966 760 605 554 366 1967 759 604 553 368 1968 761 606 555 366 1969 759 604 553 408 1970 760 605 554 370 1971 762 607 556 368 1972 761 606 555 408 1973 760 605 554 370 1974 762 607 556 408 1975 760 605 554 409 1976 763 608 557 401 1977 746 591 540 400 1978 745 590 539 407 1979 758 603 552 408 1980 760 605 554 407 1981 758 603 552 400 1982 745 590 539 409 1983 763 608 557 408 1984 760 605 554 400 1985 745 590 539 409 1986 763 608 557 400 1987 745 590 539 410 1988 764 609 558 400 1989 745 590 539 358 1990 697 542 491 410 1991 764 609 558 358 1992 697 542 491 400 1993 745 590 539 397 1994 740 585 534 410 1995 764 609 558 395 1996 736 581 530 396 1997 738 583 532 395 1998 736 581 530 410 1999 764 609 558 358 2000 697 542 491 411 2001 767 612 561 396 2002 738 583 532 374 2003 766 611 560 396 2004 738 583 532 376 2005 765 610 559 374 2006 766 611 560 411 2007 767 612 561 409 2008 763 608 557 410 2009 764 609 558 411 2010 767 612 561 410 2011 764 609 558 396 2012 738 583 532 373 2013 768 613 562 370 2014 762 607 556 409 2015 763 608 557 373 2016 768 613 562 409 2017 763 608 557 411 2018 767 612 561 380 2019 737 582 531 395 2020 736 581 530 357 2021 696 541 490 373 2022 768 613 562 411 2023 767 612 561 374 2024 766 611 560 364 2025 753 598 547 405 2026 754 599 548 361 2027 756 601 550 393 2028 750 595 544 392 2029 776 620 569 394 2030 748 593 542

+

169 684 353 209 209 170 685 354 210 210 168 686 352 208 208 170 687 354 210 210 171 688 355 211 211 168 689 352 208 208 173 690 359 213 213 172 691 356 212 212 171 692 358 211 211 172 693 356 212 212 168 694 357 208 208 171 695 358 211 211 175 696 364 216 216 170 697 361 210 210 169 698 362 209 209 170 699 361 210 210 175 700 364 216 216 174 701 360 214 214 174 702 367 214 214 171 703 365 211 211 170 704 366 210 210 171 705 365 211 211 174 706 367 214 214 173 707 368 213 213 175 708 372 216 216 172 709 369 212 212 174 710 371 214 214 174 711 371 214 214 172 712 369 212 212 173 713 370 213 213 169 714 375 209 209 168 715 376 208 208 175 716 374 216 216 175 717 374 216 216 168 718 376 208 208 172 719 377 212 212 178 720 380 219 219 179 721 381 220 220 177 722 379 218 218 177 723 379 218 218 179 724 381 220 220 176 725 378 217 217 180 726 382 221 221 176 727 383 217 217 181 728 385 222 222 181 729 385 222 222 176 730 383 217 217 179 731 384 220 220 177 732 388 218 218 182 733 386 223 223 178 734 387 219 219 182 735 386 223 223 177 736 388 218 218 183 737 390 225 225 178 738 392 219 219 182 739 393 223 223 181 740 394 222 222 178 741 392 219 219 181 742 394 222 222 179 743 391 220 220 180 744 395 221 221 182 745 397 223 223 183 746 398 225 225 182 747 397 223 223 180 748 395 221 221 181 749 396 222 222 177 750 401 218 218 176 751 402 217 217 183 752 400 225 225 183 753 400 225 225 176 754 402 217 217 180 755 403 221 221

+

187 756 407 229 229 184 757 404 226 226 186 758 406 228 228 185 759 405 227 227 186 760 406 228 228 184 761 404 226 226 184 762 409 226 226 187 763 410 229 229 189 764 411 231 231 184 765 409 226 226 189 766 411 231 231 188 767 408 230 230 190 768 413 232 232 185 769 414 227 227 184 770 415 226 226 190 771 413 232 232 184 772 415 226 226 188 773 412 230 230 191 774 416 233 233 185 775 418 227 227 190 776 419 232 232 185 777 418 227 227 191 778 416 233 233 186 779 417 228 228 186 780 421 228 228 191 781 422 233 233 189 782 423 231 231 186 783 421 228 228 189 784 423 231 231 187 785 420 229 229 191 786 426 233 233 190 787 427 232 232 188 788 424 230 230 191 789 426 233 233 188 790 424 230 230 189 791 425 231 231 195 792 431 237 237 192 793 428 234 234 194 794 430 236 236 193 795 429 235 235 194 796 430 236 236 192 797 428 234 234 192 798 433 234 234 195 799 434 237 237 197 800 435 239 239 192 801 433 234 234 197 802 435 239 239 196 803 432 238 238 198 804 437 240 240 193 805 438 235 235 192 806 439 234 234 198 807 437 240 240 192 808 439 234 234 196 809 436 238 238 199 810 440 241 241 193 811 442 235 235 198 812 443 240 240 193 813 442 235 235 199 814 440 241 241 194 815 441 236 236 194 816 445 236 236 199 817 446 241 241 197 818 447 239 239 194 819 445 236 236 197 820 447 239 239 195 821 444 237 237 196 822 448 238 238 197 823 449 239 239 198 824 451 240 240 199 825 450 241 241 198 826 451 240 240 197 827 449 239 239 203 828 455 245 245 200 829 452 242 242 202 830 454 244 244 201 831 453 243 243 202 832 454 244 244 200 833 452 242 242 200 834 457 242 242 203 835 458 245 245 205 836 459 247 247 200 837 457 242 242 205 838 459 247 247 204 839 456 246 246 206 840 461 248 248 201 841 462 243 243 200 842 463 242 242 206 843 461 248 248 200 844 463 242 242 204 845 460 246 246 207 846 464 249 249 201 847 466 243 243 206 848 467 248 248 201 849 466 243 243 207 850 464 249 249 202 851 465 244 244 202 852 469 244 244 207 853 470 249 249 205 854 471 247 247 202 855 469 244 244 205 856 471 247 247 203 857 468 245 245 204 858 472 246 246 205 859 473 247 247 206 860 475 248 248 207 861 474 249 249 206 862 475 248 248 205 863 473 247 247

+
+
+
+ + + + + + + + + 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.0000001.000000 + 30.0000000.0000003.333333 + + + + + +
diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_DeskC_01/model.config b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_DeskC_01/model.config new file mode 100755 index 0000000..8e7c565 --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_DeskC_01/model.config @@ -0,0 +1,11 @@ + + + aws_robomaker_warehouse_DeskC_01 + 1.0 + model.sdf + + + + + + diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_DeskC_01/model.sdf b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_DeskC_01/model.sdf new file mode 100755 index 0000000..0ae3cee --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_DeskC_01/model.sdf @@ -0,0 +1,46 @@ + + + + + + 1 + + 0.608 + 0 + 0 + 0.476 + 0 + 0.542 + + + + + + model://aws_robomaker_warehouse_DeskC_01/meshes/aws_robomaker_warehouse_DeskC_01_collision.DAE + 1 1 1 + + + + + + 0.3 + 0.3 + 0 0 0 + 0 + 0 + + + + + + + + model://aws_robomaker_warehouse_DeskC_01/meshes/aws_robomaker_warehouse_DeskC_01_visual.DAE + + + 1 + + +1 + + diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_GroundB_01/materials/textures/aws_robomaker_warehouse_GroundB_01.png b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_GroundB_01/materials/textures/aws_robomaker_warehouse_GroundB_01.png new file mode 100755 index 0000000..7ee66a8 Binary files /dev/null and b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_GroundB_01/materials/textures/aws_robomaker_warehouse_GroundB_01.png differ diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_GroundB_01/materials/textures/aws_robomaker_warehouse_GroundB_02.png b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_GroundB_01/materials/textures/aws_robomaker_warehouse_GroundB_02.png new file mode 100755 index 0000000..3e9d59a Binary files /dev/null and b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_GroundB_01/materials/textures/aws_robomaker_warehouse_GroundB_02.png differ diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_GroundB_01/meshes/aws_robomaker_warehouse_GroundB_01_collision.DAE b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_GroundB_01/meshes/aws_robomaker_warehouse_GroundB_01_collision.DAE new file mode 100755 index 0000000..3d2c3d5 --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_GroundB_01/meshes/aws_robomaker_warehouse_GroundB_01_collision.DAE @@ -0,0 +1,123 @@ + + + FBX COLLADA exporter2019-05-15T08:16:04Z2019-05-15T08:16:04ZZ_UP + + + + + +-699.023499 -1045.333252 -0.000123 +699.023499 -1045.333252 -0.000124 +-699.023499 -1045.333252 12.431540 +699.023499 -1045.333252 12.431539 +-699.023499 1045.333252 0.000128 +699.023499 1045.333252 0.000129 +-699.023499 1045.333130 12.431791 +699.023499 1045.333130 12.431792 + + + + + + + + + + + +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.000000 1.000000 0.000010 +-0.000000 1.000000 0.000010 +-0.000000 1.000000 0.000010 +-0.000000 1.000000 0.000010 +-0.000000 1.000000 0.000010 +-0.000000 1.000000 0.000010 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 + + + + + + + + + + + +1.000000 0.000000 +0.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 + + + + + + + + + + + +

3 0 3 2 1 2 0 2 0 3 3 3 0 4 0 1 5 1 6 6 6 5 7 5 4 8 4 5 9 5 6 10 6 7 11 7 1 12 9 0 13 8 5 14 11 0 15 8 4 16 10 5 17 11 7 18 15 3 19 13 1 20 12 7 21 15 1 22 12 5 23 14 6 24 19 3 25 16 7 26 18 3 27 16 6 28 19 2 29 17 6 30 22 0 31 21 2 32 20 0 33 21 6 34 22 4 35 23

+
+
+
+ + + 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.0000001.000000 + 30.0000000.0000003.333333 + + + + + +
diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_GroundB_01/meshes/aws_robomaker_warehouse_GroundB_01_visual.DAE b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_GroundB_01/meshes/aws_robomaker_warehouse_GroundB_01_visual.DAE new file mode 100755 index 0000000..9037e95 --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_GroundB_01/meshes/aws_robomaker_warehouse_GroundB_01_visual.DAE @@ -0,0 +1,706 @@ + + + FBX COLLADA exporter2019-05-15T08:15:48Z2019-05-15T08:15:48ZZ_UP + + + ../materials/textures/aws_robomaker_warehouse_GroundB_01.png + + + ../materials/textures/aws_robomaker_warehouse_GroundB_02.png + + + + + + + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + +-699.023499 -1045.333252 -0.000123 +699.023499 -1045.333252 -0.000124 +-699.023499 -1045.333252 12.431540 +699.023499 -1045.333252 12.431539 +-699.023499 1045.333252 0.000128 +699.023499 1045.333252 0.000129 +-699.023499 1045.333130 12.431791 +699.023499 1045.333130 12.431792 +-255.414734 -237.748291 12.445392 +44.585266 -237.748291 12.445392 +-255.414734 62.251705 12.445440 +44.585266 62.251705 12.445440 +-248.186340 -230.519897 12.445393 +37.356873 -230.519897 12.445393 +37.356873 55.023312 12.445439 +-248.186340 55.023312 12.445439 +-255.414734 -882.155273 12.445316 +44.585266 -882.155273 12.445316 +-255.414734 -582.155273 12.445366 +44.585266 -582.155273 12.445366 +-248.186340 -874.926880 12.445318 +37.356873 -874.926880 12.445318 +37.356873 -589.383667 12.445364 +-248.186340 -589.383667 12.445364 +-255.414734 -559.951782 12.445369 +44.585266 -559.951782 12.445369 +-255.414734 -259.951782 12.445388 +44.585266 -259.951782 12.445388 +-248.186340 -552.723389 12.445371 +37.356873 -552.723389 12.445371 +37.356873 -267.180176 12.445387 +-248.186340 -267.180176 12.445387 +-255.414734 84.455200 12.445444 +44.585266 84.455200 12.445444 +-255.414734 384.455200 12.445462 +44.585266 384.455200 12.445462 +-248.186340 91.683594 12.445445 +37.356873 91.683594 12.445445 +37.356873 377.226807 12.445461 +-248.186340 377.226807 12.445461 +-255.414734 406.658691 12.445527 +44.585266 406.658691 12.445527 +-255.414734 706.658691 12.445576 +44.585266 706.658691 12.445576 +-248.186340 413.887085 12.445528 +37.356873 413.887085 12.445528 +37.356873 699.430298 12.445575 +-248.186340 699.430298 12.445575 +132.339752 -1043.718018 12.445252 +141.445953 -1043.718018 12.445252 +132.339752 1046.807373 12.445501 +141.445953 1046.807373 12.445501 +141.445953 -908.130371 12.445269 +132.339752 -908.130371 12.445269 +141.445953 -983.652710 12.445258 +132.339752 -983.652710 12.445258 +141.445953 -992.508667 12.445259 +132.339752 -992.508667 12.445259 +-423.674530 -983.652710 12.445258 +-423.674530 -992.508667 12.445259 +141.445953 -899.566162 12.445268 +132.339752 -899.566162 12.445268 +-337.738800 -908.130371 12.445269 +-337.738800 -899.566162 12.445268 +-329.554382 -908.130371 12.445269 +-329.554382 -899.566162 12.445268 +-337.738800 1046.807373 12.445501 +-329.554382 1046.807373 12.445501 +-415.294403 -983.652710 12.445258 +-415.294403 -992.508667 12.445259 +-423.674530 1046.807373 12.445501 +-415.294403 1046.807373 12.445501 +-423.674530 883.609009 12.445482 +-415.294403 883.609009 12.445482 +-415.294403 959.849304 12.445491 +-423.674530 959.849304 12.445491 +-423.674591 875.711548 12.445481 +-415.294403 875.711609 12.445481 +-686.119019 883.609009 12.445482 +-686.119019 875.711548 12.445481 +-415.294403 968.018066 12.445493 +-423.674530 968.018066 12.445493 +-689.973267 959.849304 12.445491 +-689.973267 968.018066 12.445493 +215.702194 -1044.132324 12.445252 +224.808395 -1044.132324 12.445252 +215.702194 177.500122 12.445397 +224.808395 177.500122 12.445397 +224.808395 168.217163 12.445396 +215.702194 168.217163 12.445396 +700.987549 177.500122 12.445397 +700.987549 168.217163 12.445396 +215.702194 258.095581 12.445407 +224.808395 258.095581 12.445407 +224.808395 1046.807373 12.445501 +215.702194 1046.807373 12.445501 +224.808395 266.876099 12.445409 +215.702194 266.876099 12.445409 +700.987549 258.095581 12.445407 +700.987549 266.876099 12.445409 + + + + + + + + + + + +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.000000 1.000000 0.000010 +-0.000000 1.000000 0.000010 +-0.000000 1.000000 0.000010 +-0.000000 1.000000 0.000010 +-0.000000 1.000000 0.000010 +-0.000000 1.000000 0.000010 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 + + + + + + + + + + + +4.846894 2.550678 +4.846894 4.846265 +4.826477 4.846265 +4.826477 2.550678 +4.783730 2.550678 +4.804147 2.550678 +4.804147 4.846265 +4.783730 4.846265 +1.222342 2.572054 +4.655206 2.572054 +4.655206 4.867640 +1.222342 4.867640 +1.222341 4.953428 +4.655206 4.953428 +4.655205 4.973845 +1.222341 4.973845 +1.179594 0.114090 +4.612459 0.114091 +4.612458 2.409678 +1.179594 2.409678 +1.414463 2.740246 +1.414463 -0.692619 +1.434875 -0.692619 +1.434875 2.740246 +-1.691137 1.355757 +-1.976730 0.985989 +-1.933884 0.943143 +-1.733945 1.312949 +-1.976730 -0.792248 +-1.933884 -0.749402 +-1.691137 -0.420905 +-1.733945 -0.378097 +-1.799502 -0.426135 +-1.798186 -0.952645 +-1.755340 -0.995491 +-1.842348 -0.468980 +-1.798186 -2.730882 +-1.755340 -2.688036 +-1.799502 -2.204372 +-1.842348 -2.161526 +-1.799502 1.365183 +-1.798186 0.838673 +-1.755340 0.795827 +-1.842348 1.322337 +-1.798186 -0.939565 +-1.755340 -0.896719 +-1.799502 -0.413054 +-1.842348 -0.370208 +-1.730909 -0.433973 +-1.875866 -0.575192 +-1.833020 -0.618038 +-1.773717 -0.476781 +-1.875866 -2.353429 +-1.833020 -2.310584 +-1.730909 -2.210634 +-1.773717 -2.167826 +-1.958919 2.451030 +-1.717841 -0.433973 +-1.675033 -0.476781 +-2.001765 2.408185 +-1.717841 -2.210634 +-1.675033 -2.167826 +-1.958919 0.672793 +-2.001765 0.715639 +0.521328 0.470354 +0.521328 0.474995 +0.410392 1.020932 +0.410392 1.016567 +0.415033 1.016567 +-1.461452 0.891229 +0.495226 0.474995 +-1.461452 0.864380 +0.495226 0.470354 +-1.461452 0.858776 +-1.461452 0.864380 +-1.461452 0.858776 +0.415033 1.020932 +-1.461452 0.896788 +-1.461452 0.896788 +-1.461452 0.891229 +-1.461452 0.891229 +-1.461452 0.896788 +-1.461452 0.896788 +-1.461452 0.896788 +-1.461452 0.864380 +-1.461452 0.858776 +-1.461452 0.864380 +-1.461452 0.864380 +-1.461452 0.864380 +-1.461452 0.864380 +-1.461452 0.864380 +-1.461452 0.864380 +-1.461452 0.864380 +-1.461452 0.864380 +-1.461452 0.864380 +-1.461452 0.864380 +-1.461452 0.864380 +-1.461452 0.864380 +-1.461452 0.864380 +-1.461452 0.864380 +0.436771 0.036056 +0.441413 0.036056 +0.422756 0.026574 +0.422756 0.021932 +0.418024 0.026574 +0.418024 0.021932 +0.422756 0.269288 +0.418024 0.269288 +-1.767357 1.965086 +-1.767357 0.186848 +0.425656 0.029564 +0.430298 0.029564 +0.430298 0.034040 +0.425656 0.034040 +0.430297 0.431580 +0.425656 0.431580 +0.444403 0.403750 +0.448879 0.403750 +-1.724511 0.229694 +-1.724511 1.922239 +-1.855502 0.428975 +-1.898310 0.471783 +-1.855502 2.205637 +-1.898310 2.162829 +-1.842433 0.376135 +-1.842433 -1.400526 +-1.799625 -1.357718 +-1.799626 0.333327 +-1.743367 -2.377502 +-1.786175 -2.334694 +-1.743367 -0.600840 +-1.786175 -0.643649 +-1.795829 2.663701 +-1.795829 0.885463 +-1.752983 0.928309 +-1.752983 2.620854 +-1.855502 -1.400526 +-1.898310 -1.357718 +-1.855502 0.376135 +-1.898310 0.333327 +-1.842434 2.165865 +-1.842433 0.389204 +-1.799626 0.432011 +-1.799626 2.123057 +-1.743367 -0.587772 +-1.786175 -0.544964 +-1.743367 1.188889 +-1.786175 1.146081 +-1.842434 3.955595 +-1.842434 2.178934 +-1.799626 2.221741 +-1.799626 3.912786 +-1.743367 1.201958 +-1.786175 1.244766 +-1.743367 2.978619 +-1.786175 2.935811 +0.410392 0.024476 +0.415033 0.024476 +0.490712 0.474995 +0.490712 0.470354 +0.441413 0.654006 +0.436771 0.654006 +0.444403 0.646464 +0.448879 0.646464 + + + + + + + + + + + +

3 0 2 2 1 3 0 2 0 3 3 2 0 4 0 1 5 1 6 6 5 5 7 7 4 8 4 5 9 7 6 10 5 7 11 6 1 12 11 0 13 8 5 14 10 0 15 8 4 16 9 5 17 10 7 18 14 3 19 15 1 20 12 7 21 14 1 22 12 5 23 13 6 24 18 3 25 16 7 26 17 3 27 16 6 28 18 2 29 19 6 30 21 0 31 23 2 32 20 0 33 23 6 34 21 4 35 22

+

8 36 108 9 37 109 13 38 118 8 39 108 13 40 118 12 41 119 9 42 25 11 43 28 14 44 29 9 45 25 14 46 29 13 47 26 11 48 120 10 49 122 15 50 123 11 51 120 15 52 123 14 53 121 10 54 30 8 55 24 12 56 27 10 57 30 12 58 27 15 59 31 16 60 124 17 61 125 21 62 126 16 63 124 21 64 126 20 65 127 17 66 33 19 67 36 22 68 37 17 69 33 22 70 37 21 71 34 19 72 128 18 73 130 23 74 131 19 75 128 23 76 131 22 77 129 18 78 38 16 79 32 20 80 35 18 81 38 20 82 35 23 83 39 24 84 132 25 85 133 29 86 134 24 87 132 29 88 134 28 89 135 25 90 41 27 91 44 30 92 45 25 93 41 30 94 45 29 95 42 27 96 136 26 97 138 31 98 139 27 99 136 31 100 139 30 101 137 26 102 46 24 103 40 28 104 43 26 105 46 28 106 43 31 107 47 32 108 140 33 109 141 37 110 142 32 111 140 37 112 142 36 113 143 33 114 49 35 115 52 38 116 53 33 117 49 38 118 53 37 119 50 35 120 144 34 121 146 39 122 147 35 123 144 39 124 147 38 125 145 34 126 54 32 127 48 36 128 51 34 129 54 36 130 51 39 131 55 40 132 148 41 133 149 45 134 150 40 135 148 45 136 150 44 137 151 41 138 57 43 139 60 46 140 61 41 141 57 46 142 61 45 143 58 43 144 152 42 145 154 47 146 155 43 147 152 47 148 155 46 149 153 42 150 62 40 151 56 44 152 59 42 153 62 44 154 59 47 155 63 57 156 72 49 157 65 56 158 70 49 159 65 57 160 72 48 161 64 61 162 68 53 163 76 60 164 67 60 165 67 53 166 76 52 167 66 55 168 159 57 169 72 54 170 158 54 171 158 57 172 72 56 173 70 69 174 85 55 175 71 68 176 84 55 177 71 69 178 85 57 179 73 50 180 157 61 181 68 51 182 156 51 183 156 61 184 68 60 185 67 61 186 77 65 187 81 64 188 80 61 189 77 64 190 80 53 191 69 65 192 81 63 193 78 64 194 80 63 195 78 62 196 79 64 197 80 66 198 83 63 199 78 67 200 82 67 201 82 63 202 78 65 203 81 68 204 84 58 205 74 69 206 85 58 207 74 59 208 75 69 209 85 76 210 92 68 211 84 77 212 93 68 213 84 76 214 92 58 215 74 81 216 97 75 217 91 80 218 96 80 219 96 75 220 91 74 221 90 72 222 88 77 223 93 73 224 89 77 225 93 72 226 88 76 227 92 78 228 94 76 229 92 72 230 88 76 231 92 78 232 94 79 233 95 81 234 97 71 235 86 70 236 87 71 237 86 81 238 97 80 239 96 83 240 98 75 241 91 81 242 97 75 243 91 83 244 98 82 245 99 89 246 161 84 247 100 88 248 160 88 249 160 84 250 100 85 251 101 86 252 105 89 253 103 87 254 104 87 255 104 89 256 103 88 257 102 88 258 102 91 259 106 87 260 104 90 261 107 87 262 104 91 263 106 97 264 113 93 265 111 96 266 112 93 267 111 97 268 113 92 269 110 95 270 115 97 271 113 94 272 114 94 273 114 97 274 113 96 275 112 93 276 162 98 277 116 96 278 163 99 279 117 96 280 163 98 281 116

+
+
+
+ + + 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.0000001.000000 + 30.0000000.0000003.333333 + + + + + +
diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_GroundB_01/model.config b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_GroundB_01/model.config new file mode 100755 index 0000000..ab216e8 --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_GroundB_01/model.config @@ -0,0 +1,11 @@ + + + aws_robomaker_warehouse_GroundB_01 + 1.0 + model.sdf + + + + + + diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_GroundB_01/model.sdf b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_GroundB_01/model.sdf new file mode 100755 index 0000000..9d78539 --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_GroundB_01/model.sdf @@ -0,0 +1,46 @@ + + + + + + 1000 + + 1200083.33 + 0 + 0 + 8333416.66 + 0 + 2033333.33 + + + + + + model://aws_robomaker_warehouse_GroundB_01/meshes/aws_robomaker_warehouse_GroundB_01_collision.DAE + 1 1 1 + + + + + + 100 + 50 + 0 0 0 + 0 + 0 + + + + + + + + model://aws_robomaker_warehouse_GroundB_01/meshes/aws_robomaker_warehouse_GroundB_01_visual.DAE + + + 1 + + +1 + + diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_Lamp_01/materials/textures/aws_robomaker_warehouse_Lamp_01.png b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_Lamp_01/materials/textures/aws_robomaker_warehouse_Lamp_01.png new file mode 100755 index 0000000..9e4dd9c Binary files /dev/null and b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_Lamp_01/materials/textures/aws_robomaker_warehouse_Lamp_01.png differ diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_Lamp_01/meshes/aws_robomaker_warehouse_Lamp_01_collision.DAE b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_Lamp_01/meshes/aws_robomaker_warehouse_Lamp_01_collision.DAE new file mode 100755 index 0000000..672719c --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_Lamp_01/meshes/aws_robomaker_warehouse_Lamp_01_collision.DAE @@ -0,0 +1,123 @@ + + + FBX COLLADA exporter2019-04-04T08:27:36Z2019-04-04T08:27:36ZZ_UP + + + + + +-51.220013 -75.723572 -50.385498 +51.220005 -75.723572 -50.385498 +-51.220013 75.723572 -50.385498 +51.220005 75.723572 -50.385498 +-51.220005 -75.723572 50.385498 +51.220013 -75.723572 50.385498 +-51.220005 75.723572 50.385498 +51.220013 75.723572 50.385498 + + + + + + + + + + + +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 + + + + + + + + + + + +1.000000 0.000000 +0.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 + + + + + + + + + + + +

1 0 1 0 1 0 3 2 3 0 3 0 2 4 2 3 5 3 7 6 7 6 7 6 4 8 4 7 9 7 4 10 4 5 11 5 4 12 10 1 13 9 5 14 11 1 15 9 4 16 10 0 17 8 7 18 15 5 19 14 1 20 12 7 21 15 1 22 12 3 23 13 6 24 19 7 25 18 3 26 16 6 27 19 3 28 16 2 29 17 4 30 23 6 31 22 2 32 20 4 33 23 2 34 20 0 35 21

+
+
+
+ + + -0.999000 -0.000000 -0.000000 0.087481 -0.000000 0.000000 0.998995 0.000494 0.000000 1.002288 -0.000000 1325.909302 0.000000 0.000000 0.000000 1.0000001.000000 + 30.0000000.0000003.333333 + + + + + +
diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_Lamp_01/meshes/aws_robomaker_warehouse_Lamp_01_visual.DAE b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_Lamp_01/meshes/aws_robomaker_warehouse_Lamp_01_visual.DAE new file mode 100755 index 0000000..cad638a --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_Lamp_01/meshes/aws_robomaker_warehouse_Lamp_01_visual.DAE @@ -0,0 +1,1056 @@ + + + FBX COLLADA exporter2019-05-27T02:45:50Z2019-05-27T02:45:50ZZ_UP + + + ../materials/textures/aws_robomaker_warehouse_Lamp_01.png + + + + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + +51.162598 0.000000 -75.723511 +48.077148 17.498535 -75.723511 +39.192871 32.886719 -75.723511 +25.581543 44.308594 -75.723511 +8.884521 50.385742 -75.723511 +-8.884277 50.385742 -75.723511 +-25.581055 44.308594 -75.723511 +-39.192383 32.886719 -75.723511 +-48.076904 17.498535 -75.723511 +-51.162354 0.000000 -75.723511 +-48.076904 -17.498047 -75.723511 +-39.192871 -32.886230 -75.723511 +-25.581055 -44.308105 -75.723511 +-8.884277 -50.385254 -75.723511 +8.884521 -50.385254 -75.723511 +25.581543 -44.308105 -75.723511 +39.192871 -32.886719 -75.723511 +48.077148 -17.498047 -75.723511 +26.794434 0.000000 0.394409 +25.178711 9.164063 0.394409 +20.525879 17.223145 0.394409 +13.397461 23.204590 0.394409 +4.652832 26.387695 0.394409 +-4.652832 26.387695 0.394409 +-13.396973 23.204590 0.394409 +-20.525391 17.223145 0.394409 +-25.178223 9.164063 0.394409 +-26.794434 0.000000 0.394409 +-25.178223 -9.164063 0.394409 +-20.525391 -17.222656 0.394409 +-13.396973 -23.204102 0.394409 +-4.652832 -26.387207 0.394409 +4.652832 -26.387207 0.394409 +13.397461 -23.204102 0.394409 +20.525879 -17.222656 0.394409 +25.178711 -9.164063 0.394409 +9.227295 0.000000 0.394409 +8.670898 3.155762 0.394409 +7.068359 5.931641 0.394409 +4.613770 7.991211 0.394409 +1.602539 9.086914 0.394409 +-1.602051 9.086914 0.394409 +-4.613281 7.991211 0.394409 +-7.068359 5.931641 0.394409 +-8.670410 3.155762 0.394409 +-9.227051 0.000000 0.394409 +-8.670410 -3.155273 0.394409 +-7.068359 -5.931152 0.394409 +-4.613281 -7.991211 0.394409 +-1.602051 -9.086914 0.394409 +1.602539 -9.086914 0.394409 +4.613770 -7.991211 0.394409 +7.068359 -5.931152 0.394409 +8.670898 -3.155273 0.394409 +9.227295 0.000000 75.723511 +8.670898 3.155762 75.723511 +7.068359 5.931641 75.723511 +4.613770 7.991211 75.723511 +1.602539 9.086914 75.723511 +-1.602051 9.086914 75.723511 +-4.613281 7.991211 75.723511 +-7.068359 5.931641 75.723511 +-8.670410 3.155762 75.723511 +-9.227051 0.000000 75.723511 +-8.670410 -3.155273 75.723511 +-7.068359 -5.931152 75.723511 +-4.613281 -7.991211 75.723511 +-1.602051 -9.086914 75.723511 +1.602539 -9.086914 75.723511 +4.613770 -7.991211 75.723511 +7.068359 -5.931152 75.723511 +8.670898 -3.155273 75.723511 +36.223633 13.184570 -75.723511 +38.548340 0.000000 -75.723511 +36.223633 -13.184082 -75.723511 +29.529785 -24.778320 -75.723511 +19.274170 -33.383789 -75.723511 +6.693848 -37.962891 -75.723511 +-6.693848 -37.961914 -75.723511 +-19.273926 -33.383789 -75.723511 +-29.529297 -24.778320 -75.723511 +-36.223145 -13.184082 -75.723511 +-38.547852 0.000000 -75.723511 +-36.223145 13.184570 -75.723511 +-29.529297 24.778320 -75.723511 +-19.273926 33.383789 -75.723511 +-6.693848 37.962891 -75.723511 +6.693848 37.962891 -75.723511 +19.274414 33.383789 -75.723511 +29.529785 24.778320 -75.723511 +36.223633 13.184570 -61.747925 +38.548340 0.000000 -61.747925 +36.223633 -13.184082 -61.747925 +29.529785 -24.778320 -61.747925 +19.274170 -33.383789 -61.747925 +6.693848 -37.962891 -61.747925 +-6.693848 -37.961914 -61.747925 +-19.273926 -33.383789 -61.747925 +-29.529297 -24.778320 -61.747925 +-36.223145 -13.184082 -61.747925 +-38.547852 0.000000 -61.747925 +-36.223145 13.184570 -61.747925 +-29.529297 24.778320 -61.747925 +-19.273926 33.383789 -61.747925 +-6.693848 37.962891 -61.747925 +6.693848 37.962891 -61.747925 +19.274414 33.383789 -61.747925 +29.529785 24.778320 -61.747925 +36.223145 13.184570 -73.245483 +38.547852 0.000488 -73.245483 +36.223145 -13.183594 -73.245483 +29.529297 -24.778320 -73.245483 +19.273926 -33.383301 -73.245483 +6.693359 -37.962402 -73.245483 +-6.694092 -37.961914 -73.245483 +-19.274414 -33.383301 -73.245483 +-29.529785 -24.778320 -73.245483 +-36.223633 -13.183594 -73.245483 +-38.548340 0.000488 -73.245483 +-36.223633 13.184570 -73.245483 +-29.529785 24.778809 -73.245483 +-19.274414 33.383789 -73.245483 +-6.694092 37.962891 -73.245483 +6.693359 37.962891 -73.245483 +19.273926 33.383789 -73.245483 +29.529297 24.778809 -73.245483 + + + + + + + + + + + +0.952386 -0.000003 0.304893 +0.894952 0.325733 0.304893 +0.894954 0.325725 0.304894 +0.894954 0.325725 0.304894 +0.952387 -0.000001 0.304892 +0.952386 -0.000003 0.304893 +0.894952 0.325733 0.304893 +0.729579 0.612172 0.304895 +0.729572 0.612180 0.304894 +0.729572 0.612180 0.304894 +0.894954 0.325725 0.304894 +0.894952 0.325733 0.304893 +0.729579 0.612172 0.304895 +0.476202 0.824784 0.304898 +0.476208 0.824781 0.304897 +0.476208 0.824781 0.304897 +0.729572 0.612180 0.304894 +0.729579 0.612172 0.304895 +0.476202 0.824784 0.304898 +0.165379 0.937917 0.304896 +0.165393 0.937914 0.304899 +0.165393 0.937914 0.304899 +0.476208 0.824781 0.304897 +0.476202 0.824784 0.304898 +0.165379 0.937917 0.304896 +-0.165382 0.937916 0.304897 +-0.165405 0.937913 0.304895 +-0.165405 0.937913 0.304895 +0.165393 0.937914 0.304899 +0.165379 0.937917 0.304896 +-0.165382 0.937916 0.304897 +-0.476202 0.824784 0.304898 +-0.476212 0.824780 0.304895 +-0.476212 0.824780 0.304895 +-0.165405 0.937913 0.304895 +-0.165382 0.937916 0.304897 +-0.476202 0.824784 0.304898 +-0.729576 0.612175 0.304894 +-0.729573 0.612178 0.304896 +-0.729573 0.612178 0.304896 +-0.476212 0.824780 0.304895 +-0.476202 0.824784 0.304898 +-0.729576 0.612175 0.304894 +-0.894949 0.325739 0.304894 +-0.894945 0.325749 0.304894 +-0.894945 0.325749 0.304894 +-0.729573 0.612178 0.304896 +-0.729576 0.612175 0.304894 +-0.894949 0.325739 0.304894 +-0.952387 -0.000003 0.304893 +-0.952386 -0.000003 0.304895 +-0.952386 -0.000003 0.304895 +-0.894945 0.325749 0.304894 +-0.894949 0.325739 0.304894 +-0.952387 -0.000003 0.304893 +-0.894952 -0.325730 0.304895 +-0.894943 -0.325759 0.304891 +-0.894943 -0.325759 0.304891 +-0.952386 -0.000003 0.304895 +-0.952387 -0.000003 0.304893 +-0.894952 -0.325730 0.304895 +-0.729577 -0.612172 0.304898 +-0.729565 -0.612188 0.304894 +-0.729565 -0.612188 0.304894 +-0.894943 -0.325759 0.304891 +-0.894952 -0.325730 0.304895 +-0.729577 -0.612172 0.304898 +-0.476198 -0.824787 0.304897 +-0.476214 -0.824777 0.304899 +-0.476214 -0.824777 0.304899 +-0.729565 -0.612188 0.304894 +-0.729577 -0.612172 0.304898 +-0.476198 -0.824787 0.304897 +-0.165381 -0.937917 0.304895 +-0.165401 -0.937912 0.304899 +-0.165401 -0.937912 0.304899 +-0.476214 -0.824777 0.304899 +-0.476198 -0.824787 0.304897 +-0.165381 -0.937917 0.304895 +0.165380 -0.937916 0.304897 +0.165396 -0.937914 0.304895 +0.165396 -0.937914 0.304895 +-0.165401 -0.937912 0.304899 +-0.165381 -0.937917 0.304895 +0.165380 -0.937916 0.304897 +0.476192 -0.824789 0.304899 +0.476205 -0.824783 0.304896 +0.476205 -0.824783 0.304896 +0.165396 -0.937914 0.304895 +0.165380 -0.937916 0.304897 +0.476192 -0.824789 0.304899 +0.729576 -0.612175 0.304895 +0.729564 -0.612188 0.304897 +0.729564 -0.612188 0.304897 +0.476205 -0.824783 0.304896 +0.476192 -0.824789 0.304899 +0.729576 -0.612175 0.304895 +0.894954 -0.325728 0.304892 +0.894951 -0.325735 0.304894 +0.894951 -0.325735 0.304894 +0.729564 -0.612188 0.304897 +0.729576 -0.612175 0.304895 +0.894954 -0.325728 0.304892 +0.952386 -0.000003 0.304893 +0.952387 -0.000001 0.304892 +0.952387 -0.000001 0.304892 +0.894951 -0.325735 0.304894 +0.894954 -0.325728 0.304892 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 -0.000013 0.000000 +0.939701 0.341998 0.000000 +0.939701 0.341998 0.000000 +0.939701 0.341998 0.000000 +1.000000 -0.000013 0.000000 +1.000000 -0.000013 0.000000 +0.939701 0.341998 0.000000 +0.766049 0.642783 0.000000 +0.766049 0.642783 0.000000 +0.766049 0.642783 0.000000 +0.939701 0.341998 0.000000 +0.939701 0.341998 0.000000 +0.766049 0.642783 0.000000 +0.499955 0.866052 0.000000 +0.499955 0.866052 0.000000 +0.499955 0.866052 0.000000 +0.766049 0.642783 0.000000 +0.766049 0.642783 0.000000 +0.499955 0.866052 0.000000 +0.173606 0.984815 0.000000 +0.173606 0.984815 0.000000 +0.173606 0.984815 0.000000 +0.499955 0.866052 0.000000 +0.499955 0.866052 0.000000 +0.173606 0.984815 0.000000 +-0.173606 0.984815 0.000000 +-0.173606 0.984815 0.000000 +-0.173606 0.984815 0.000000 +0.173606 0.984815 0.000000 +0.173606 0.984815 0.000000 +-0.173606 0.984815 0.000000 +-0.499912 0.866076 0.000000 +-0.499912 0.866076 0.000000 +-0.499912 0.866076 0.000000 +-0.173606 0.984815 0.000000 +-0.173606 0.984815 0.000000 +-0.499912 0.866076 0.000000 +-0.766060 0.642769 0.000000 +-0.766060 0.642770 0.000000 +-0.766060 0.642770 0.000000 +-0.499912 0.866076 0.000000 +-0.499912 0.866076 0.000000 +-0.766060 0.642769 0.000000 +-0.939710 0.341972 0.000000 +-0.939710 0.341972 0.000000 +-0.939710 0.341972 0.000000 +-0.766060 0.642770 0.000000 +-0.766060 0.642769 0.000000 +-0.939710 0.341972 0.000000 +-1.000000 -0.000013 0.000000 +-1.000000 -0.000013 0.000000 +-1.000000 -0.000013 0.000000 +-0.939710 0.341972 0.000000 +-0.939710 0.341972 0.000000 +-1.000000 -0.000013 0.000000 +-0.939706 -0.341984 0.000000 +-0.939706 -0.341984 0.000000 +-0.939706 -0.341984 0.000000 +-1.000000 -0.000013 0.000000 +-1.000000 -0.000013 0.000000 +-0.939706 -0.341984 0.000000 +-0.766097 -0.642725 0.000000 +-0.766097 -0.642725 0.000000 +-0.766097 -0.642725 0.000000 +-0.939706 -0.341984 0.000000 +-0.939706 -0.341984 0.000000 +-0.766097 -0.642725 0.000000 +-0.499963 -0.866047 0.000000 +-0.499963 -0.866047 0.000000 +-0.499963 -0.866047 0.000000 +-0.766097 -0.642725 0.000000 +-0.766097 -0.642725 0.000000 +-0.499963 -0.866047 0.000000 +-0.173606 -0.984815 0.000000 +-0.173606 -0.984815 0.000000 +-0.173606 -0.984815 0.000000 +-0.499963 -0.866047 0.000000 +-0.499963 -0.866047 0.000000 +-0.173606 -0.984815 0.000000 +0.173606 -0.984815 0.000000 +0.173606 -0.984815 0.000000 +0.173606 -0.984815 0.000000 +-0.173606 -0.984815 0.000000 +-0.173606 -0.984815 0.000000 +0.173606 -0.984815 0.000000 +0.500005 -0.866022 0.000000 +0.500005 -0.866022 0.000000 +0.500005 -0.866022 0.000000 +0.173606 -0.984815 0.000000 +0.173606 -0.984815 0.000000 +0.500005 -0.866022 0.000000 +0.766086 -0.642738 0.000000 +0.766086 -0.642738 0.000000 +0.766086 -0.642738 0.000000 +0.500005 -0.866022 0.000000 +0.500005 -0.866022 0.000000 +0.766086 -0.642738 0.000000 +0.939696 -0.342011 0.000000 +0.939696 -0.342011 0.000000 +0.939696 -0.342011 0.000000 +0.766086 -0.642738 0.000000 +0.766086 -0.642738 0.000000 +0.939696 -0.342011 0.000000 +1.000000 -0.000013 0.000000 +1.000000 -0.000013 0.000000 +1.000000 -0.000013 0.000000 +0.939696 -0.342011 0.000000 +0.939696 -0.342011 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.939692 -0.342023 0.000000 +-1.000000 0.000003 0.000000 +-1.000000 0.000003 0.000000 +-1.000000 0.000003 0.000000 +-0.939692 -0.342023 0.000000 +-0.939692 -0.342023 0.000000 +-1.000000 0.000003 0.000000 +-0.939694 0.342017 0.000000 +-0.939694 0.342017 0.000000 +-0.939694 0.342017 0.000000 +-1.000000 0.000003 0.000000 +-1.000000 0.000003 0.000000 +-0.939694 0.342017 0.000000 +-0.766046 0.642786 0.000000 +-0.766046 0.642786 0.000000 +-0.766046 0.642786 0.000000 +-0.939694 0.342017 0.000000 +-0.939694 0.342017 0.000000 +-0.766046 0.642786 0.000000 +-0.500007 0.866021 0.000000 +-0.500007 0.866021 0.000000 +-0.500007 0.866021 0.000000 +-0.766046 0.642786 0.000000 +-0.766046 0.642786 0.000000 +-0.500007 0.866021 0.000000 +-0.173621 0.984813 0.000000 +-0.173621 0.984813 0.000000 +-0.173621 0.984813 0.000000 +-0.500007 0.866021 0.000000 +-0.500007 0.866021 0.000000 +-0.173621 0.984813 0.000000 +0.173662 0.984805 0.000000 +0.173662 0.984805 0.000000 +0.173662 0.984805 0.000000 +-0.173621 0.984813 0.000000 +-0.173621 0.984813 0.000000 +0.173662 0.984805 0.000000 +0.499985 0.866034 0.000000 +0.499985 0.866034 0.000000 +0.499985 0.866034 0.000000 +0.173662 0.984805 0.000000 +0.173662 0.984805 0.000000 +0.499985 0.866034 0.000000 +0.766050 0.642781 0.000000 +0.766050 0.642781 0.000000 +0.766050 0.642781 0.000000 +0.499985 0.866034 0.000000 +0.499985 0.866034 0.000000 +0.766050 0.642781 0.000000 +0.939694 0.342017 0.000000 +0.939694 0.342017 0.000000 +0.939694 0.342017 0.000000 +0.766050 0.642781 0.000000 +0.766050 0.642781 0.000000 +0.939694 0.342017 0.000000 +1.000000 0.000003 0.000000 +1.000000 0.000003 0.000000 +1.000000 0.000003 0.000000 +0.939694 0.342017 0.000000 +0.939694 0.342017 0.000000 +1.000000 0.000003 0.000000 +0.939692 -0.342023 0.000000 +0.939692 -0.342023 0.000000 +0.939692 -0.342023 0.000000 +1.000000 0.000003 0.000000 +1.000000 0.000003 0.000000 +0.939692 -0.342023 0.000000 +0.766044 -0.642788 0.000000 +0.766044 -0.642788 0.000000 +0.766044 -0.642788 0.000000 +0.939692 -0.342023 0.000000 +0.939692 -0.342023 0.000000 +0.766044 -0.642788 0.000000 +0.500015 -0.866017 0.000000 +0.500015 -0.866017 0.000000 +0.500015 -0.866017 0.000000 +0.766044 -0.642788 0.000000 +0.766044 -0.642788 0.000000 +0.500015 -0.866017 0.000000 +0.173659 -0.984806 0.000000 +0.173659 -0.984806 0.000000 +0.173659 -0.984806 0.000000 +0.500015 -0.866017 0.000000 +0.500015 -0.866017 0.000000 +0.173659 -0.984806 0.000000 +-0.173653 -0.984807 0.000000 +-0.173653 -0.984807 0.000000 +-0.173653 -0.984807 0.000000 +0.173659 -0.984806 0.000000 +0.173659 -0.984806 0.000000 +-0.173653 -0.984807 0.000000 +-0.500009 -0.866020 0.000000 +-0.500009 -0.866020 0.000000 +-0.500009 -0.866020 0.000000 +-0.173653 -0.984807 0.000000 +-0.173653 -0.984807 0.000000 +-0.500009 -0.866020 0.000000 +-0.766044 -0.642788 0.000000 +-0.766044 -0.642788 0.000000 +-0.766044 -0.642788 0.000000 +-0.500009 -0.866020 0.000000 +-0.500009 -0.866020 0.000000 +-0.766044 -0.642788 0.000000 +-0.939692 -0.342023 0.000000 +-0.939692 -0.342023 0.000000 +-0.939692 -0.342023 0.000000 +-0.766044 -0.642788 0.000000 +-0.766044 -0.642788 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 + + + + + + + + + + + +0.537122 0.103646 +0.549949 0.103646 +0.546895 0.161264 +0.595048 0.283608 +0.582256 0.283608 +0.585302 0.226150 +0.203520 0.310616 +0.190728 0.310616 +0.193775 0.253158 +0.188995 0.115589 +0.201786 0.115589 +0.198740 0.173047 +0.593077 0.146331 +0.605869 0.146331 +0.602822 0.203789 +0.028301 0.243705 +0.028301 0.231088 +0.540177 0.161264 +0.562003 0.104966 +0.553207 0.161955 +0.571830 0.107445 +0.592001 0.226150 +0.570235 0.282293 +0.579007 0.225461 +0.200474 0.253158 +0.178708 0.309301 +0.187479 0.252469 +0.192041 0.173047 +0.213807 0.116905 +0.205035 0.173736 +0.596123 0.203789 +0.617890 0.147647 +0.609117 0.204478 +0.084975 0.234092 +0.084975 0.240700 +0.558353 0.163253 +0.560436 0.279821 +0.573875 0.224167 +0.447449 0.136913 +0.449640 0.124488 +0.458057 0.127551 +0.456407 0.136914 +0.455949 0.113561 +0.462810 0.119319 +0.465614 0.105451 +0.470093 0.113208 +0.477470 0.101136 +0.479026 0.109957 +0.490088 0.101136 +0.488532 0.109957 +0.501944 0.105451 +0.312863 0.222985 +0.317110 0.228047 +0.306307 0.234284 +0.304844 0.232541 +0.319371 0.234256 +0.307086 0.236423 +0.319371 0.240864 +0.307086 0.238698 +0.317110 0.247073 +0.306307 0.240836 +0.312863 0.252135 +0.304844 0.242579 +0.541438 0.104749 +0.541438 0.106996 +0.487784 0.106996 +0.839139 0.234210 +0.840890 0.234210 +0.840890 0.287958 +0.839139 0.287958 +0.541438 0.070394 +0.541438 0.072371 +0.487784 0.072371 +0.487784 0.070394 +0.541438 0.074619 +0.337134 0.120611 +0.338885 0.120611 +0.338885 0.174360 +0.337134 0.174360 +0.341033 0.120611 +0.487784 0.104749 +0.541438 0.108973 +0.487784 0.108973 +0.541438 0.100524 +0.843039 0.234210 +0.843039 0.287958 +0.845325 0.234210 +0.845325 0.287958 +0.487784 0.074619 +0.541438 0.076866 +0.487784 0.076866 +0.541438 0.078843 +0.487784 0.078843 +0.341033 0.174360 +0.343319 0.120611 +0.343319 0.174360 +0.345470 0.120611 +0.345470 0.174360 +0.541438 0.102501 +0.497466 0.113209 +0.511609 0.113561 +0.504747 0.119319 +0.517918 0.124488 +0.509500 0.127551 +0.520109 0.136914 +0.511151 0.136914 +0.517918 0.149339 +0.505360 0.303902 +0.513904 0.303902 +0.513904 0.314202 +0.505360 0.314202 +0.523621 0.303902 +0.874778 0.234210 +0.874778 0.241937 +0.864247 0.241937 +0.864247 0.234210 +0.874778 0.251415 +0.400917 0.273772 +0.410633 0.273772 +0.410633 0.284072 +0.485761 0.108057 +0.485761 0.115783 +0.475230 0.115783 +0.475230 0.108057 +0.485761 0.125263 +0.523621 0.314202 +0.533338 0.303902 +0.533338 0.314202 +0.541882 0.303902 +0.541882 0.314202 +0.864247 0.251415 +0.874778 0.261503 +0.864247 0.261503 +0.874778 0.270982 +0.864247 0.270982 +0.694674 0.497425 +0.693653 0.498282 +0.692400 0.498738 +0.691067 0.498738 +0.689815 0.498282 +0.688794 0.497425 +0.688127 0.496271 +0.687896 0.494958 +0.688127 0.493646 +0.688794 0.492491 +0.689815 0.491634 +0.691067 0.491179 +0.692400 0.491179 +0.693653 0.491634 +0.694674 0.492491 +0.695340 0.493646 +0.695572 0.494958 +0.695340 0.496271 +0.307140 0.255439 +0.302874 0.243717 +0.300633 0.256586 +0.300633 0.244112 +0.294125 0.255439 +0.298392 0.243717 +0.288403 0.252135 +0.296421 0.242579 +0.284156 0.247073 +0.294959 0.240836 +0.281896 0.240864 +0.294181 0.238698 +0.281896 0.234256 +0.294181 0.236422 +0.284156 0.228047 +0.294959 0.234284 +0.288403 0.222985 +0.296421 0.232541 +0.294126 0.219681 +0.298392 0.231403 +0.300633 0.218534 +0.300633 0.231008 +0.307141 0.219681 +0.302874 0.231403 +0.400917 0.284072 +0.420350 0.273772 +0.420350 0.284072 +0.428893 0.273772 +0.428893 0.284072 +0.392372 0.273772 +0.392372 0.284072 +0.847474 0.234210 +0.847474 0.287958 +0.849226 0.234210 +0.849226 0.287958 +0.475230 0.125263 +0.485761 0.135349 +0.475230 0.135349 +0.485761 0.144829 +0.475230 0.144829 +0.485761 0.152555 +0.475230 0.152555 +0.509500 0.146275 +0.511609 0.160266 +0.504747 0.154508 +0.501944 0.168376 +0.497465 0.160619 +0.490088 0.172692 +0.488532 0.163870 +0.477470 0.172692 +0.479025 0.163871 +0.465614 0.168376 +0.470093 0.160619 +0.455949 0.160266 +0.462810 0.154508 +0.449640 0.149339 +0.458057 0.146275 +0.487784 0.102501 +0.487784 0.100524 +0.347220 0.120611 +0.347220 0.174360 +0.874778 0.278709 +0.864247 0.278709 +0.515241 0.107445 +0.525068 0.104966 +0.533864 0.161955 +0.528718 0.163253 +0.168908 0.306828 +0.182347 0.251174 +0.223606 0.119377 +0.210167 0.175031 +0.627689 0.150119 +0.614250 0.205773 + + + + + + + + + + + +

0 0 0 1 1 1 19 2 2 19 3 2 18 4 17 0 5 0 1 6 1 2 7 18 20 8 19 20 9 19 19 10 2 1 11 1 2 12 18 3 13 20 21 14 35 21 15 35 20 16 19 2 17 18 3 18 3 4 19 4 22 20 5 22 21 5 21 22 21 3 23 3 4 24 4 5 25 22 23 26 23 23 27 23 22 28 5 4 29 4 5 30 22 6 31 36 24 32 37 24 33 37 23 34 23 5 35 22 6 36 6 7 37 7 25 38 8 25 39 8 24 40 24 6 41 6 7 42 7 8 43 25 26 44 26 26 45 26 25 46 8 7 47 7 8 48 25 9 49 220 27 50 221 27 51 221 26 52 26 8 53 25 9 54 9 10 55 10 28 56 11 28 57 11 27 58 27 9 59 9 10 60 10 11 61 28 29 62 29 29 63 29 28 64 11 10 65 10 11 66 28 12 67 222 30 68 223 30 69 223 29 70 29 11 71 28 12 72 12 13 73 13 31 74 14 31 75 14 30 76 30 12 77 12 13 78 13 14 79 31 32 80 32 32 81 32 31 82 14 13 83 13 14 84 31 15 85 224 33 86 225 33 87 225 32 88 32 14 89 31 15 90 15 16 91 16 34 92 33 34 93 33 33 94 34 15 95 15 16 96 216 17 97 217 35 98 218 35 99 218 34 100 219 16 101 216 17 102 217 0 103 0 18 104 17 18 105 17 35 106 218 17 107 217 18 108 51 19 109 52 37 110 53 37 111 53 36 112 54 18 113 51 19 114 52 20 115 55 38 116 56 38 117 56 37 118 53 19 119 52 20 120 55 21 121 57 39 122 58 39 123 58 38 124 56 20 125 55 21 126 57 22 127 59 40 128 60 40 129 60 39 130 58 21 131 57 22 132 59 23 133 61 41 134 62 41 135 62 40 136 60 22 137 59 23 138 61 24 139 153 42 140 154 42 141 154 41 142 62 23 143 61 24 144 153 25 145 155 43 146 156 43 147 156 42 148 154 24 149 153 25 150 155 26 151 157 44 152 158 44 153 158 43 154 156 25 155 155 26 156 157 27 157 159 45 158 160 45 159 160 44 160 158 26 161 157 27 162 159 28 163 161 46 164 162 46 165 162 45 166 160 27 167 159 28 168 161 29 169 163 47 170 164 47 171 164 46 172 162 28 173 161 29 174 163 30 175 165 48 176 166 48 177 166 47 178 164 29 179 163 30 180 165 31 181 167 49 182 168 49 183 168 48 184 166 30 185 165 31 186 167 32 187 169 50 188 170 50 189 170 49 190 168 31 191 167 32 192 169 33 193 171 51 194 172 51 195 172 50 196 170 32 197 169 33 198 171 34 199 173 52 200 174 52 201 174 51 202 172 33 203 171 34 204 173 35 205 175 53 206 176 53 207 176 52 208 174 34 209 173 35 210 175 18 211 51 36 212 54 36 213 54 53 214 176 35 215 175 36 216 63 37 217 64 55 218 65 55 219 65 54 220 80 36 221 63 37 222 64 38 223 81 56 224 82 56 225 82 55 226 65 37 227 64 38 228 66 39 229 67 57 230 68 57 231 68 56 232 69 38 233 66 39 234 67 40 235 84 58 236 85 58 237 85 57 238 68 39 239 67 40 240 84 41 241 86 59 242 87 59 243 87 58 244 85 40 245 84 41 246 86 42 247 184 60 248 185 60 249 185 59 250 87 41 251 86 42 252 184 43 253 186 61 254 187 61 255 187 60 256 185 42 257 184 43 258 70 44 259 71 62 260 72 62 261 72 61 262 73 43 263 70 44 264 71 45 265 74 63 266 88 63 267 88 62 268 72 44 269 71 45 270 74 46 271 89 64 272 90 64 273 90 63 274 88 45 275 74 46 276 89 47 277 91 65 278 92 65 279 92 64 280 90 46 281 89 47 282 75 48 283 76 66 284 77 66 285 77 65 286 78 47 287 75 48 288 76 49 289 79 67 290 93 67 291 93 66 292 77 48 293 76 49 294 79 50 295 94 68 296 95 68 297 95 67 298 93 49 299 79 50 300 94 51 301 96 69 302 97 69 303 97 68 304 95 50 305 94 51 306 96 52 307 212 70 308 213 70 309 213 69 310 97 51 311 96 52 312 83 53 313 98 71 314 210 71 315 210 70 316 211 52 317 83 53 318 98 36 319 63 54 320 80 54 321 80 71 322 210 53 323 98 1 324 38 0 325 39 73 326 40 73 327 40 72 328 41 1 329 38 0 330 39 17 331 42 74 332 43 74 333 43 73 334 40 0 335 39 17 336 42 16 337 44 75 338 45 75 339 45 74 340 43 17 341 42 16 342 44 15 343 46 76 344 47 76 345 47 75 346 45 16 347 44 15 348 46 14 349 48 77 350 49 77 351 49 76 352 47 15 353 46 14 354 48 13 355 50 78 356 99 78 357 99 77 358 49 14 359 48 13 360 50 12 361 100 79 362 101 79 363 101 78 364 99 13 365 50 12 366 100 11 367 102 80 368 103 80 369 103 79 370 101 12 371 100 11 372 102 10 373 104 81 374 105 81 375 105 80 376 103 11 377 102 10 378 104 9 379 106 82 380 195 82 381 195 81 382 105 10 383 104 9 384 106 8 385 196 83 386 197 83 387 197 82 388 195 9 389 106 8 390 196 7 391 198 84 392 199 84 393 199 83 394 197 8 395 196 7 396 198 6 397 200 85 398 201 85 399 201 84 400 199 7 401 198 6 402 200 5 403 202 86 404 203 86 405 203 85 406 201 6 407 200 5 408 202 4 409 204 87 410 205 87 411 205 86 412 203 5 413 202 4 414 204 3 415 206 88 416 207 88 417 207 87 418 205 4 419 204 3 420 206 2 421 208 89 422 209 89 423 209 88 424 207 3 425 206 2 426 208 1 427 38 72 428 41 72 429 41 89 430 209 2 431 208 72 432 117 73 433 118 91 434 119 91 435 119 90 436 177 72 437 117 73 438 118 74 439 178 92 440 179 92 441 179 91 442 119 73 443 118 74 444 178 75 445 180 93 446 181 93 447 181 92 448 179 74 449 178 75 450 120 76 451 121 94 452 122 94 453 122 93 454 123 75 455 120 76 456 121 77 457 124 95 458 188 95 459 188 94 460 122 76 461 121 77 462 124 78 463 189 96 464 190 96 465 190 95 466 188 77 467 124 78 468 189 79 469 191 97 470 192 97 471 192 96 472 190 78 473 189 79 474 191 80 475 193 98 476 194 98 477 194 97 478 192 79 479 191 80 480 107 81 481 108 99 482 109 99 483 109 98 484 110 80 485 107 81 486 108 82 487 111 100 488 125 100 489 125 99 490 109 81 491 108 82 492 111 83 493 126 101 494 127 101 495 127 100 496 125 82 497 111 83 498 126 84 499 128 102 500 129 102 501 129 101 502 127 83 503 126 84 504 112 85 505 113 103 506 114 103 507 114 102 508 115 84 509 112 85 510 113 86 511 116 104 512 130 104 513 130 103 514 114 85 515 113 86 516 116 87 517 131 105 518 132 105 519 132 104 520 130 86 521 116 87 522 131 88 523 133 106 524 134 106 525 134 105 526 132 87 527 131 88 528 133 89 529 214 107 530 215 107 531 215 106 532 134 88 533 133 89 534 182 72 535 117 90 536 177 90 537 177 107 538 183 89 539 182 111 540 136 112 541 137 113 542 138 113 543 138 114 544 139 115 545 140 115 546 140 116 547 141 117 548 142 113 549 138 115 550 140 117 551 142 117 552 142 118 553 143 119 554 144 119 555 144 120 556 145 121 557 146 117 558 142 119 559 144 121 560 146 121 561 146 122 562 147 123 563 148 123 564 148 124 565 149 125 566 150 121 567 146 123 568 148 125 569 150 117 570 142 121 571 146 125 572 150 113 573 138 117 574 142 125 575 150 125 576 150 108 577 151 109 578 152 113 579 138 125 580 150 109 581 152 111 582 136 113 583 138 109 584 152 110 585 135 111 586 136 109 587 152

+
+
+
+ + + + + + + + + 0.999000 0.000000 0.000000 0.029575 0.000000 0.998995 0.000000 0.000251 0.000000 0.000000 1.002288 1325.909302 0.000000 0.000000 0.000000 1.0000001.000000 + 30.0000000.0000003.333333 + + + + + +
diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_Lamp_01/model.config b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_Lamp_01/model.config new file mode 100755 index 0000000..8121b47 --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_Lamp_01/model.config @@ -0,0 +1,11 @@ + + + aws_robomaker_warehouse_Lamp_01 + 1.0 + model.sdf + + + + + + diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_Lamp_01/model.sdf b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_Lamp_01/model.sdf new file mode 100755 index 0000000..9ef1c09 --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_Lamp_01/model.sdf @@ -0,0 +1,46 @@ + + + + + + 30 + + 907.144 + 0 + 0 + 104.950 + 0 + 824.248 + + + + + + model://aws_robomaker_warehouse_Lamp_01/meshes/aws_robomaker_warehouse_Lamp_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + model://aws_robomaker_warehouse_Lamp_01/meshes/aws_robomaker_warehouse_Lamp_01_visual.DAE + + + 1 + + +1 + + diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_PalletJackB_01/.DS_Store b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_PalletJackB_01/.DS_Store new file mode 100755 index 0000000..90c2f9f Binary files /dev/null and b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_PalletJackB_01/.DS_Store differ diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_PalletJackB_01/materials/.DS_Store b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_PalletJackB_01/materials/.DS_Store new file mode 100755 index 0000000..616b3e2 Binary files /dev/null and b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_PalletJackB_01/materials/.DS_Store differ diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_PalletJackB_01/materials/textures/aws_robomaker_warehouse_PalletJackB_01.png b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_PalletJackB_01/materials/textures/aws_robomaker_warehouse_PalletJackB_01.png new file mode 100755 index 0000000..21c704c Binary files /dev/null and b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_PalletJackB_01/materials/textures/aws_robomaker_warehouse_PalletJackB_01.png differ diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_PalletJackB_01/materials/textures/aws_robomaker_warehouse_PalletJackB_02.png b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_PalletJackB_01/materials/textures/aws_robomaker_warehouse_PalletJackB_02.png new file mode 100755 index 0000000..9afb9b3 Binary files /dev/null and b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_PalletJackB_01/materials/textures/aws_robomaker_warehouse_PalletJackB_02.png differ diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_PalletJackB_01/meshes/aws_robomaker_warehouse_PalletJackB_01_collision.DAE b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_PalletJackB_01/meshes/aws_robomaker_warehouse_PalletJackB_01_collision.DAE new file mode 100755 index 0000000..dc0c1a2 --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_PalletJackB_01/meshes/aws_robomaker_warehouse_PalletJackB_01_collision.DAE @@ -0,0 +1,3373 @@ + + + FBX COLLADA exporter2019-03-28T09:56:39Z2019-03-28T09:56:39ZZ_UP + + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588235 0.588235 0.588235 1.000000 + + + 0.588235 0.588235 0.588235 1.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + +-43.491493 -9.846935 23.952991 +-39.490791 -9.846935 24.658491 +-39.490791 -4.445636 24.658491 +-43.491493 -4.445636 23.952991 +-47.009693 -9.846935 21.921791 +-47.009693 -4.445636 21.921791 +-49.620991 -9.846935 18.809792 +-49.620991 -4.445636 18.809792 +-51.010391 -9.846935 14.992290 +-51.010391 -4.445636 14.992290 +-51.010391 -9.846935 10.929891 +-51.010391 -4.445636 10.929891 +-49.620991 -9.846935 7.112391 +-49.620991 -4.445636 7.112391 +-47.009693 -9.846935 4.000391 +-47.009693 -4.445636 4.000391 +-43.491493 -9.846935 1.969191 +-43.491493 -4.445636 1.969191 +-39.490791 -9.846935 1.263691 +-39.490791 -4.445636 1.263691 +-35.489994 -9.846935 1.969191 +-35.489994 -4.445636 1.969191 +-31.971790 -9.846935 4.000391 +-31.971790 -4.445636 4.000391 +-29.360592 -9.846935 7.112391 +-29.360493 -4.445636 7.112391 +-27.971092 -9.846935 10.929891 +-27.971092 -4.445636 10.929891 +-27.971092 -9.846935 14.992290 +-27.971092 -4.445636 14.992290 +-29.360493 -9.846935 18.809792 +-29.360493 -4.445636 18.809792 +-31.971790 -9.846935 21.921791 +-31.971790 -4.445636 21.921791 +-35.489994 -9.846935 23.952991 +-35.489994 -4.445636 23.952991 +-43.491493 6.814264 23.952991 +-39.490791 6.814264 24.658491 +-39.490791 1.412965 24.658491 +-43.491493 1.412965 23.952991 +-47.009693 6.814264 21.921791 +-47.009693 1.412965 21.921791 +-49.620991 6.814264 18.809792 +-49.620991 1.412965 18.809792 +-51.010391 6.814264 14.992290 +-51.010391 1.412965 14.992290 +-51.010391 6.814264 10.929891 +-51.010391 1.412965 10.929891 +-49.620991 6.814264 7.112391 +-49.620991 1.412965 7.112391 +-47.009693 6.814264 4.000391 +-47.009693 1.412965 4.000391 +-43.491493 6.814264 1.969191 +-43.491493 1.412965 1.969191 +-39.490791 6.814264 1.263691 +-39.490791 1.412965 1.263691 +-35.489994 6.814264 1.969191 +-35.489994 1.412965 1.969191 +-31.971790 6.814264 4.000391 +-31.971790 1.412965 4.000391 +-29.360592 6.814264 7.112391 +-29.360493 1.412965 7.112391 +-27.971092 6.814264 10.929891 +-27.971092 1.412965 10.929891 +-27.971092 6.814264 14.992290 +-27.971092 1.412965 14.992290 +-29.360493 6.814264 18.809792 +-29.360493 1.412965 18.809792 +-31.971790 6.814264 21.921791 +-31.971790 1.412965 21.921791 +-35.489994 6.814264 23.952991 +-35.489994 1.412965 23.952991 +44.321407 15.830565 13.608291 +42.198505 15.830565 13.233991 +42.198505 19.891666 13.233991 +44.321407 19.891666 13.608291 +40.331608 15.830565 12.156091 +40.331608 19.891666 12.156091 +38.945908 15.830565 10.504791 +38.945908 19.891666 10.504791 +38.208611 15.830565 8.479091 +38.208611 19.891666 8.479091 +38.208611 15.830565 6.323390 +38.208611 19.891666 6.323390 +38.945908 15.830565 4.297691 +38.945908 19.891666 4.297691 +40.331608 15.830565 2.646291 +40.331608 19.891666 2.646291 +42.198505 15.830565 1.568491 +42.198505 19.891666 1.568491 +44.321407 15.830565 1.194091 +44.321407 19.891666 1.194091 +46.444408 15.830565 1.568491 +46.444408 19.891666 1.568491 +48.311310 15.830565 2.646291 +48.311310 19.891666 2.646291 +49.696907 15.830565 4.297691 +49.696907 19.891666 4.297691 +50.434208 15.830565 6.323390 +50.434208 19.891666 6.323390 +50.434208 15.830565 8.479091 +50.434208 19.891666 8.479091 +49.696907 15.830565 10.504791 +49.696907 19.891666 10.504791 +48.311310 15.830565 12.156091 +48.311310 19.891666 12.156091 +46.444408 15.830565 13.233991 +46.444408 19.891666 13.233991 +44.321407 -18.863235 13.608291 +42.198505 -18.863235 13.233991 +42.198505 -22.924335 13.233991 +44.321407 -22.924335 13.608291 +40.331608 -18.863235 12.156091 +40.331608 -22.924335 12.156091 +38.945908 -18.863235 10.504791 +38.945908 -22.924335 10.504791 +38.208611 -18.863235 8.479091 +38.208611 -22.924335 8.479091 +38.208611 -18.863235 6.323390 +38.208611 -22.924335 6.323390 +38.945908 -18.863235 4.297691 +38.945908 -22.924335 4.297691 +40.331608 -18.863235 2.646291 +40.331608 -22.924335 2.646291 +42.198505 -18.863235 1.568491 +42.198505 -22.924335 1.568491 +44.321407 -18.863235 1.194091 +44.321407 -22.924335 1.194091 +46.444408 -18.863235 1.568491 +46.444408 -22.924335 1.568491 +48.311310 -18.863235 2.646291 +48.311310 -22.924335 2.646291 +49.696907 -18.863235 4.297691 +49.696907 -22.924335 4.297691 +50.434208 -18.863235 6.323390 +50.434208 -22.924335 6.323390 +50.434208 -18.863235 8.479091 +50.434208 -22.924335 8.479091 +49.696907 -18.863235 10.504791 +49.696907 -22.924335 10.504791 +48.311310 -18.863235 12.156091 +48.311310 -22.924335 12.156091 +46.444408 -18.863235 13.233991 +46.444408 -22.924335 13.233991 +-26.551193 10.051767 8.147191 +65.077614 14.085981 8.147191 +-26.551193 25.475258 8.147191 +65.077614 21.550388 8.147191 +-26.551193 10.051767 14.167690 +65.077614 14.085981 14.167690 +-26.551193 25.475258 14.167690 +65.077614 21.550388 14.167690 +52.768509 25.475258 14.167690 +-11.961791 25.475258 8.147191 +-11.961791 10.051767 14.167690 +-11.961791 10.051767 8.147191 +-11.961791 25.475258 14.167690 +-25.527889 25.475258 8.147191 +-25.527889 10.051767 14.167690 +-25.527889 10.051767 8.147191 +-25.527889 25.475258 14.167690 +-11.961791 5.035481 53.648792 +-25.536491 5.035481 53.635590 +52.768509 10.051767 14.167690 +-11.961791 10.051767 13.330291 +-25.527889 10.051767 13.330291 +52.768509 25.475258 8.147191 +52.768509 10.051767 8.147191 +37.840710 20.088676 8.147191 +37.840710 15.625571 8.147191 +50.621807 20.088676 8.147191 +50.621807 15.625571 8.147191 +-11.326890 5.035481 53.648792 +-11.326890 5.035481 61.351391 +-11.326890 5.035481 53.635590 +-38.104794 5.035481 61.351391 +-25.536491 5.035481 53.635590 +-11.326890 -1.516335 53.648792 +-11.326890 -1.516335 61.351391 +-11.961791 -1.516335 13.330291 +-11.961791 -1.516335 14.167690 +-38.104794 5.035481 53.635590 +-38.104794 -1.516335 61.351391 +-25.527889 -1.516335 14.167690 +-37.267193 7.514789 30.846691 +-38.259289 7.514789 26.880592 +-25.532692 7.514789 27.432192 +-25.530293 7.514789 21.931791 +-25.532692 5.583035 27.432192 +-37.267193 5.583035 30.846691 +-38.259289 5.583035 26.880592 +-25.530293 5.583035 21.931791 +37.840710 20.088676 14.172491 +37.840710 15.625571 14.169190 +50.621807 20.088676 14.173890 +50.621807 15.625571 14.167791 +-26.551193 -13.084438 8.147191 +-26.551193 -28.507927 8.147191 +-25.527889 -28.507927 8.147191 +-25.527889 -13.084438 8.147191 +-26.551193 -13.084438 14.167690 +-25.527889 -13.084438 14.167690 +-25.527889 -28.507927 14.167690 +-26.551193 -28.507927 14.167690 +-25.527889 -13.084438 13.330291 +65.077614 -17.118652 8.147191 +65.077614 -24.583057 8.147191 +65.077614 -24.583057 14.167690 +65.077614 -17.118652 14.167690 +52.768509 -28.507927 8.147191 +52.768509 -28.507927 14.167690 +52.768509 -13.084438 8.147191 +52.768509 -13.084438 14.167690 +-11.961791 -28.507927 8.147191 +37.840710 -23.121346 8.147191 +37.840710 -18.658241 8.147191 +-11.961791 -13.084438 8.147191 +-11.961791 -13.084438 13.330291 +-11.961791 -28.507927 14.167690 +-25.536491 -8.068151 53.635590 +-11.961791 -8.068151 53.648792 +-11.961791 -13.084438 14.167690 +-11.961791 -1.516335 53.648792 +-25.527889 -1.516335 13.330291 +50.621807 -18.658241 8.147191 +50.621807 -23.121346 8.147191 +-11.326890 -8.068151 53.648792 +-11.326890 -8.068151 61.351391 +-38.104794 -8.068151 61.351391 +-11.326890 -8.068151 53.635590 +-25.536491 -8.068151 53.635590 +-38.104794 -8.068151 53.635590 +-38.104794 -1.516335 53.635590 +-25.536491 -1.516335 53.635590 +-25.532692 -10.547460 27.432192 +-25.530293 -10.547460 21.931791 +-38.259289 -10.547460 26.880592 +-37.267193 -10.547460 30.846691 +-25.530293 -8.615705 21.931791 +-38.259289 -8.615705 26.880592 +-25.532692 -8.615705 27.432192 +-37.267193 -8.615705 30.846691 +37.840710 -23.121346 14.172491 +37.840710 -18.658241 14.169190 +50.621807 -18.658241 14.167791 +50.621807 -23.121346 14.173890 +-33.549294 1.424371 10.896284 +-33.549297 -4.364129 10.896284 +-33.549294 1.424371 14.594985 +-33.549297 -4.364129 14.594985 +-41.235790 1.424372 10.896283 +-41.235794 -4.364128 10.896283 +-41.235790 1.424372 14.594984 +-41.235794 -4.364128 14.594984 +-32.404991 0.392671 11.022784 +-32.404991 -3.451929 11.022784 +-32.404995 0.392671 32.100487 +-32.404995 -3.451929 32.100487 +-35.993690 0.392671 11.022784 +-35.993690 -3.451929 11.022784 +-35.993694 0.392671 32.100483 +-35.993694 -3.451929 32.100483 +-46.667702 -1.516327 53.377083 +-46.667698 -6.459527 31.289381 +-29.835396 -6.459529 31.289385 +-46.667702 -6.459527 53.377083 +-29.835400 -6.459529 53.377083 +-46.667698 3.426873 31.289482 +-29.835396 3.426870 31.289486 +-29.835400 3.426870 53.377083 +-46.667702 3.426873 53.377083 +-46.667698 -1.516327 31.289381 +-29.835396 -1.516330 31.289385 +-29.835400 -1.516330 53.377083 +-41.219799 1.893072 51.678684 +-43.069313 0.400173 97.795525 +-43.069313 -3.432827 97.795525 +-41.219799 -4.925727 51.678684 +-45.298500 1.894173 51.675285 +-45.298500 -4.926826 51.675285 +-45.098412 -3.432527 97.794228 +-45.098412 0.399873 97.794228 +-43.148212 -1.516327 95.820427 +-44.992809 -6.806027 95.507317 +-43.147614 -6.806027 95.507317 +-43.148212 -1.516327 97.664223 +-43.147614 -6.931627 97.348320 +-44.992111 -1.516327 97.664223 +-44.992809 -6.931627 97.348228 +-44.992111 -1.516327 95.820427 +-44.993412 -10.413227 94.952721 +-43.146912 -10.413227 94.952827 +-43.147011 -10.842726 96.747032 +-44.993507 -10.842726 96.746925 +-43.147209 -13.182627 93.914925 +-44.993313 -13.889326 92.096825 +-43.146610 -13.889427 92.096825 +-43.147411 -14.555826 95.146126 +-43.146713 -15.683826 92.498726 +-44.991707 -14.555626 95.146019 +-44.993412 -15.683626 92.498726 +-44.991512 -13.182426 93.914833 +-44.994511 -14.089127 90.042931 +-43.145210 -14.089325 90.042931 +-43.145412 -15.932426 89.892036 +-44.994713 -15.932226 89.892036 +-44.997810 -13.581125 88.533119 +-43.141113 -13.581627 88.532829 +-43.141609 -15.092325 87.507927 +-44.998413 -15.091827 87.508232 +-44.992310 -12.060627 87.240929 +-43.148212 -12.060627 87.240929 +-43.148212 -13.112526 85.726219 +-44.992310 -13.112526 85.726219 +-44.992306 -1.810327 80.529320 +-43.148407 -1.810327 80.529320 +-43.148407 -2.820427 78.986824 +-44.992306 -2.820427 78.986824 +-44.993011 -12.282627 94.494026 +-43.146713 -12.282526 94.494026 +-43.146713 -13.229227 96.079124 +-44.993011 -13.229326 96.079124 +-43.147614 3.773273 95.507317 +-43.147614 3.898973 97.348320 +-44.992809 3.898973 97.348320 +-44.992809 3.773273 95.507317 +-44.993412 7.380474 94.952721 +-43.146912 7.380474 94.952827 +-43.147011 7.810073 96.747032 +-44.993507 7.810073 96.746925 +-44.991508 10.149773 93.914726 +-43.147205 10.149874 93.914925 +-43.147408 11.523172 95.146233 +-44.991703 11.522974 95.146019 +-44.993309 10.856672 92.096825 +-43.146606 10.856773 92.096825 +-43.146709 12.651073 92.498726 +-44.993408 12.650974 92.498726 +-44.997009 10.947073 89.486626 +-43.142105 10.947573 89.486412 +-43.142609 12.721174 89.037727 +-44.997509 12.720774 89.037819 +-43.143108 10.259373 88.135735 +-43.143505 11.576674 86.832527 +-44.996510 11.576374 86.832817 +-44.996109 10.259073 88.136024 +-43.148209 9.027973 87.240929 +-43.148209 10.079874 85.726219 +-44.992306 10.079773 85.726219 +-44.992306 9.027874 87.240929 +-43.148407 -1.222327 80.529320 +-43.148407 -0.212227 78.986824 +-44.992306 -0.212227 78.986824 +-44.992306 -1.222327 80.529320 +-43.146709 9.249874 94.494026 +-43.146709 10.196573 96.079124 +-44.993008 10.196672 96.079124 +-44.993008 9.249973 94.494026 +-43.772911 -11.534527 90.243629 +-44.279808 -11.534527 90.243629 +-44.383709 -8.683428 91.495613 +-44.508213 -3.241827 92.715614 +-43.669010 -8.683428 91.495613 +-43.544514 -3.241827 92.715614 +-43.774010 -11.239826 89.490929 +-43.662910 -8.450327 90.425819 +-43.541008 -3.217027 91.104225 +-44.511612 -3.217027 91.104225 +-44.389809 -8.450327 90.425819 +-44.278610 -11.239826 89.490929 +-25.536491 -1.516335 53.635590 + + + + + + + + + + + +-0.173664 0.000000 0.984805 +-0.173664 0.000000 0.984805 +-0.173664 0.000000 0.984805 +-0.173664 0.000000 0.984805 +-0.173664 0.000000 0.984805 +-0.173664 0.000000 0.984805 +-0.499994 0.000000 0.866029 +-0.499994 0.000000 0.866029 +-0.499994 0.000000 0.866029 +-0.499994 0.000000 0.866029 +-0.499994 0.000000 0.866029 +-0.499994 0.000000 0.866029 +-0.766042 0.000000 0.642790 +-0.766042 0.000000 0.642790 +-0.766042 0.000000 0.642790 +-0.766042 0.000000 0.642790 +-0.766042 0.000000 0.642790 +-0.766042 0.000000 0.642790 +-0.939697 0.000000 0.342008 +-0.939697 0.000000 0.342008 +-0.939697 0.000000 0.342008 +-0.939697 0.000000 0.342008 +-0.939697 0.000000 0.342008 +-0.939697 0.000000 0.342008 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.939697 0.000000 -0.342008 +-0.939697 0.000000 -0.342008 +-0.939697 0.000000 -0.342008 +-0.939697 0.000000 -0.342008 +-0.939697 0.000000 -0.342008 +-0.939697 0.000000 -0.342008 +-0.766042 0.000000 -0.642790 +-0.766042 0.000000 -0.642790 +-0.766042 0.000000 -0.642790 +-0.766042 0.000000 -0.642790 +-0.766042 0.000000 -0.642790 +-0.766042 0.000000 -0.642790 +-0.499994 0.000000 -0.866029 +-0.499994 0.000000 -0.866029 +-0.499994 0.000000 -0.866029 +-0.499994 0.000000 -0.866029 +-0.499994 0.000000 -0.866029 +-0.499994 0.000000 -0.866029 +-0.173664 0.000000 -0.984805 +-0.173664 0.000000 -0.984805 +-0.173664 0.000000 -0.984805 +-0.173664 0.000000 -0.984805 +-0.173664 0.000000 -0.984805 +-0.173664 0.000000 -0.984805 +0.173660 0.000000 -0.984806 +0.173660 0.000000 -0.984806 +0.173660 0.000000 -0.984806 +0.173660 0.000000 -0.984806 +0.173660 0.000000 -0.984806 +0.173660 0.000000 -0.984806 +0.499993 0.000000 -0.866029 +0.499993 0.000000 -0.866029 +0.499993 0.000000 -0.866029 +0.499993 0.000000 -0.866029 +0.499993 0.000000 -0.866029 +0.499993 0.000000 -0.866029 +0.766054 -0.000014 -0.642776 +0.766054 -0.000014 -0.642776 +0.766054 -0.000014 -0.642776 +0.766042 0.000000 -0.642790 +0.766042 0.000000 -0.642790 +0.766042 0.000000 -0.642790 +0.939697 -0.000017 -0.342008 +0.939697 -0.000017 -0.342008 +0.939697 -0.000017 -0.342008 +0.939689 0.000000 -0.342030 +0.939689 0.000000 -0.342030 +0.939689 0.000000 -0.342030 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.939697 0.000000 0.342008 +0.939697 0.000000 0.342008 +0.939697 0.000000 0.342008 +0.939697 0.000000 0.342008 +0.939697 0.000000 0.342008 +0.939697 0.000000 0.342008 +0.766042 0.000000 0.642790 +0.766042 0.000000 0.642790 +0.766042 0.000000 0.642790 +0.766042 0.000000 0.642790 +0.766042 0.000000 0.642790 +0.766042 0.000000 0.642790 +0.499993 0.000000 0.866029 +0.499993 0.000000 0.866029 +0.499993 0.000000 0.866029 +0.499993 0.000000 0.866029 +0.499993 0.000000 0.866029 +0.499993 0.000000 0.866029 +0.173660 0.000000 0.984806 +0.173660 0.000000 0.984806 +0.173660 0.000000 0.984806 +0.173660 0.000000 0.984806 +0.173660 0.000000 0.984806 +0.173660 0.000000 0.984806 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.173664 0.000000 0.984805 +-0.173664 0.000000 0.984805 +-0.173664 0.000000 0.984805 +-0.173664 0.000000 0.984805 +-0.173664 0.000000 0.984805 +-0.173664 0.000000 0.984805 +-0.499994 0.000000 0.866029 +-0.499994 0.000000 0.866029 +-0.499994 0.000000 0.866029 +-0.499994 0.000000 0.866029 +-0.499994 0.000000 0.866029 +-0.499994 0.000000 0.866029 +-0.766042 0.000000 0.642790 +-0.766042 0.000000 0.642790 +-0.766042 0.000000 0.642790 +-0.766042 0.000000 0.642790 +-0.766042 0.000000 0.642790 +-0.766042 0.000000 0.642790 +-0.939697 0.000000 0.342008 +-0.939697 0.000000 0.342008 +-0.939697 0.000000 0.342008 +-0.939697 0.000000 0.342008 +-0.939697 0.000000 0.342008 +-0.939697 0.000000 0.342008 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.939697 0.000000 -0.342008 +-0.939697 0.000000 -0.342008 +-0.939697 0.000000 -0.342008 +-0.939697 0.000000 -0.342008 +-0.939697 0.000000 -0.342008 +-0.939697 0.000000 -0.342008 +-0.766042 0.000000 -0.642790 +-0.766042 0.000000 -0.642790 +-0.766042 0.000000 -0.642790 +-0.766042 0.000000 -0.642790 +-0.766042 0.000000 -0.642790 +-0.766042 0.000000 -0.642790 +-0.499994 0.000000 -0.866029 +-0.499994 0.000000 -0.866029 +-0.499994 0.000000 -0.866029 +-0.499994 0.000000 -0.866029 +-0.499994 0.000000 -0.866029 +-0.499994 0.000000 -0.866029 +-0.173664 0.000000 -0.984805 +-0.173664 0.000000 -0.984805 +-0.173664 0.000000 -0.984805 +-0.173664 0.000000 -0.984805 +-0.173664 0.000000 -0.984805 +-0.173664 0.000000 -0.984805 +0.173660 0.000000 -0.984806 +0.173660 0.000000 -0.984806 +0.173660 0.000000 -0.984806 +0.173660 0.000000 -0.984806 +0.173660 0.000000 -0.984806 +0.173660 0.000000 -0.984806 +0.499993 0.000000 -0.866029 +0.499993 0.000000 -0.866029 +0.499993 0.000000 -0.866029 +0.499993 0.000000 -0.866029 +0.499993 0.000000 -0.866029 +0.499993 0.000000 -0.866029 +0.766054 0.000014 -0.642776 +0.766054 0.000014 -0.642776 +0.766054 0.000014 -0.642776 +0.766042 0.000000 -0.642790 +0.766042 0.000000 -0.642790 +0.766042 0.000000 -0.642790 +0.939689 0.000000 -0.342030 +0.939689 0.000000 -0.342030 +0.939689 0.000000 -0.342030 +0.939697 0.000017 -0.342008 +0.939697 0.000017 -0.342008 +0.939697 0.000017 -0.342008 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.939697 0.000000 0.342008 +0.939697 0.000000 0.342008 +0.939697 0.000000 0.342008 +0.939697 0.000000 0.342008 +0.939697 0.000000 0.342008 +0.939697 0.000000 0.342008 +0.766042 0.000000 0.642790 +0.766042 0.000000 0.642790 +0.766042 0.000000 0.642790 +0.766042 0.000000 0.642790 +0.766042 0.000000 0.642790 +0.766042 0.000000 0.642790 +0.499993 0.000000 0.866029 +0.499993 0.000000 0.866029 +0.499993 0.000000 0.866029 +0.499993 0.000000 0.866029 +0.499993 0.000000 0.866029 +0.499993 0.000000 0.866029 +0.173660 0.000000 0.984806 +0.173660 0.000000 0.984806 +0.173660 0.000000 0.984806 +0.173660 0.000000 0.984806 +0.173660 0.000000 0.984806 +0.173660 0.000000 0.984806 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.173637 0.000000 0.984810 +-0.173637 0.000000 0.984810 +-0.173637 0.000000 0.984810 +-0.173637 0.000000 0.984810 +-0.173637 0.000000 0.984810 +-0.173637 0.000000 0.984810 +-0.500016 0.000000 0.866016 +-0.500016 0.000000 0.866016 +-0.500016 0.000000 0.866016 +-0.500016 0.000000 0.866016 +-0.500016 0.000000 0.866016 +-0.500016 0.000000 0.866016 +-0.766023 0.000000 0.642814 +-0.766023 0.000000 0.642814 +-0.766023 0.000000 0.642814 +-0.766023 0.000000 0.642814 +-0.766023 0.000000 0.642814 +-0.766023 0.000000 0.642814 +-0.939692 0.000000 0.342021 +-0.939692 0.000000 0.342021 +-0.939692 0.000000 0.342021 +-0.939692 0.000000 0.342021 +-0.939692 0.000000 0.342021 +-0.939692 0.000000 0.342021 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.939692 0.000000 -0.342021 +-0.939692 0.000000 -0.342021 +-0.939692 0.000000 -0.342021 +-0.939692 0.000000 -0.342021 +-0.939692 0.000000 -0.342021 +-0.939692 0.000000 -0.342021 +-0.766042 0.000000 -0.642791 +-0.766042 0.000000 -0.642791 +-0.766042 0.000000 -0.642791 +-0.766042 0.000000 -0.642791 +-0.766042 0.000000 -0.642791 +-0.766042 0.000000 -0.642791 +-0.499981 0.000000 -0.866036 +-0.499981 0.000000 -0.866036 +-0.499981 0.000000 -0.866036 +-0.499981 0.000000 -0.866036 +-0.499981 0.000000 -0.866036 +-0.499981 0.000000 -0.866036 +-0.173682 0.000000 -0.984802 +-0.173682 0.000000 -0.984802 +-0.173682 0.000000 -0.984802 +-0.173682 0.000000 -0.984802 +-0.173682 0.000000 -0.984802 +-0.173682 0.000000 -0.984802 +0.173674 0.000000 -0.984803 +0.173674 0.000000 -0.984803 +0.173674 0.000000 -0.984803 +0.173674 0.000000 -0.984803 +0.173674 0.000000 -0.984803 +0.173674 0.000000 -0.984803 +0.499981 0.000000 -0.866037 +0.499980 0.000000 -0.866037 +0.499980 0.000000 -0.866037 +0.499981 0.000000 -0.866037 +0.499980 0.000000 -0.866037 +0.499980 0.000000 -0.866037 +0.766065 0.000000 -0.642763 +0.766065 0.000000 -0.642763 +0.766065 0.000000 -0.642763 +0.766065 0.000000 -0.642763 +0.766065 0.000000 -0.642763 +0.766065 0.000000 -0.642763 +0.939692 0.000000 -0.342023 +0.939692 0.000000 -0.342023 +0.939692 0.000000 -0.342023 +0.939692 0.000000 -0.342023 +0.939692 0.000000 -0.342023 +0.939692 0.000000 -0.342023 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.939692 0.000000 0.342023 +0.939692 0.000000 0.342023 +0.939692 0.000000 0.342023 +0.939692 0.000000 0.342023 +0.939692 0.000000 0.342023 +0.939692 0.000000 0.342023 +0.766046 0.000000 0.642786 +0.766046 0.000000 0.642786 +0.766046 0.000000 0.642785 +0.766046 0.000000 0.642785 +0.766046 0.000000 0.642786 +0.766046 0.000000 0.642786 +0.500015 0.000000 0.866017 +0.500015 0.000000 0.866017 +0.500015 0.000000 0.866017 +0.500015 0.000000 0.866017 +0.500015 0.000000 0.866017 +0.500015 0.000000 0.866017 +0.173629 0.000000 0.984811 +0.173629 0.000000 0.984811 +0.173629 0.000000 0.984811 +0.173629 0.000000 0.984811 +0.173629 0.000000 0.984811 +0.173629 0.000000 0.984811 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.173637 0.000000 0.984810 +-0.173637 0.000000 0.984810 +-0.173637 0.000000 0.984810 +-0.173637 0.000000 0.984810 +-0.173637 0.000000 0.984810 +-0.173637 0.000000 0.984810 +-0.500016 0.000000 0.866016 +-0.500016 0.000000 0.866016 +-0.500016 0.000000 0.866016 +-0.500016 0.000000 0.866016 +-0.500016 0.000000 0.866016 +-0.500016 0.000000 0.866016 +-0.766023 0.000000 0.642814 +-0.766023 0.000000 0.642814 +-0.766023 0.000000 0.642814 +-0.766023 0.000000 0.642814 +-0.766023 0.000000 0.642814 +-0.766023 0.000000 0.642814 +-0.939692 0.000000 0.342021 +-0.939692 0.000000 0.342021 +-0.939692 0.000000 0.342021 +-0.939692 0.000000 0.342021 +-0.939692 0.000000 0.342021 +-0.939692 0.000000 0.342021 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.939692 0.000000 -0.342021 +-0.939692 0.000000 -0.342021 +-0.939692 0.000000 -0.342021 +-0.939692 0.000000 -0.342021 +-0.939692 0.000000 -0.342021 +-0.939692 0.000000 -0.342021 +-0.766042 0.000000 -0.642791 +-0.766042 0.000000 -0.642791 +-0.766042 0.000000 -0.642791 +-0.766042 0.000000 -0.642791 +-0.766042 0.000000 -0.642791 +-0.766042 0.000000 -0.642791 +-0.499981 0.000000 -0.866036 +-0.499981 0.000000 -0.866036 +-0.499981 0.000000 -0.866036 +-0.499981 0.000000 -0.866036 +-0.499981 0.000000 -0.866036 +-0.499981 0.000000 -0.866036 +-0.173682 0.000000 -0.984802 +-0.173682 0.000000 -0.984802 +-0.173682 0.000000 -0.984802 +-0.173682 0.000000 -0.984802 +-0.173682 0.000000 -0.984802 +-0.173682 0.000000 -0.984802 +0.173674 0.000000 -0.984803 +0.173674 0.000000 -0.984803 +0.173674 0.000000 -0.984803 +0.173674 0.000000 -0.984803 +0.173674 0.000000 -0.984803 +0.173674 0.000000 -0.984803 +0.499981 0.000000 -0.866037 +0.499981 0.000000 -0.866037 +0.499980 0.000000 -0.866037 +0.499981 0.000000 -0.866037 +0.499980 0.000000 -0.866037 +0.499981 0.000000 -0.866037 +0.766065 0.000000 -0.642763 +0.766065 0.000000 -0.642763 +0.766065 0.000000 -0.642763 +0.766065 0.000000 -0.642763 +0.766065 0.000000 -0.642763 +0.766065 0.000000 -0.642763 +0.939692 0.000000 -0.342023 +0.939692 0.000000 -0.342023 +0.939692 0.000000 -0.342023 +0.939692 0.000000 -0.342023 +0.939692 0.000000 -0.342023 +0.939692 0.000000 -0.342023 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.939692 0.000000 0.342023 +0.939692 0.000000 0.342023 +0.939692 0.000000 0.342023 +0.939692 0.000000 0.342023 +0.939692 0.000000 0.342023 +0.939692 0.000000 0.342023 +0.766046 0.000000 0.642786 +0.766046 0.000000 0.642785 +0.766046 0.000000 0.642786 +0.766046 0.000000 0.642786 +0.766046 0.000000 0.642785 +0.766046 0.000000 0.642786 +0.500015 0.000000 0.866017 +0.500015 0.000000 0.866017 +0.500015 0.000000 0.866017 +0.500015 0.000000 0.866017 +0.500015 0.000000 0.866017 +0.500015 0.000000 0.866017 +0.173629 0.000000 0.984811 +0.173629 0.000000 0.984811 +0.173629 0.000000 0.984811 +0.173629 0.000000 0.984811 +0.173629 0.000000 0.984811 +0.173629 0.000000 0.984811 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.303790 0.952739 0.000000 +0.303790 0.952739 0.000000 +0.303790 0.952739 0.000000 +0.303790 0.952739 0.000000 +0.303790 0.952739 0.000000 +0.303790 0.952739 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.311442 -0.950265 0.000000 +0.311442 -0.950265 0.000000 +0.311442 -0.950265 0.000000 +0.311442 -0.950265 0.000000 +0.311442 -0.950265 0.000000 +0.311442 -0.950265 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.000447 0.888048 0.459751 +-0.000447 0.888048 0.459751 +-0.000447 0.888048 0.459751 +0.000000 0.887985 0.459873 +0.000000 0.887985 0.459873 +0.000000 0.887985 0.459873 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 -0.000218 +-1.000000 0.000000 -0.000218 +-1.000000 0.000000 -0.000218 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 -0.000218 +-1.000000 0.000000 -0.000218 +-1.000000 0.000000 -0.000218 +-1.000000 0.000000 -0.000218 +-1.000000 0.000000 -0.000218 +-1.000000 0.000000 -0.000218 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.362359 0.000000 -0.932038 +-0.362360 0.000000 -0.932038 +-0.362359 0.000000 -0.932038 +-0.362359 0.000000 -0.932038 +-0.362359 0.000000 -0.932038 +-0.362360 0.000000 -0.932038 +0.279392 0.000000 0.960177 +0.279392 0.000000 0.960177 +0.279392 0.000000 0.960177 +0.279392 0.000000 0.960177 +0.279392 0.000000 0.960177 +0.279392 0.000000 0.960177 +-0.970110 0.000000 0.242667 +-0.970110 0.000000 0.242667 +-0.970110 0.000000 0.242667 +-0.970110 0.000000 0.242667 +-0.970110 0.000000 0.242667 +-0.970110 0.000000 0.242667 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 0.000436 +1.000000 0.000000 0.000436 +1.000000 0.000000 0.000436 +1.000000 0.000000 0.000436 +1.000000 0.000000 0.000436 +1.000000 0.000000 0.000436 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -0.000269 1.000000 +0.000000 -0.000269 1.000000 +0.000000 -0.000269 1.000000 +0.000109 0.000024 1.000000 +0.000109 0.000024 1.000000 +0.000109 0.000024 1.000000 +0.000047 0.000000 1.000000 +0.000047 0.000000 1.000000 +0.000047 0.000000 1.000000 +0.006317 -0.001366 0.999979 +0.006317 -0.001366 0.999979 +0.006317 -0.001366 0.999979 +-0.000109 0.001195 0.999999 +-0.000109 0.001195 0.999999 +-0.000109 0.001195 0.999999 +0.000000 0.000891 1.000000 +0.000000 0.000891 1.000000 +0.000000 0.000891 1.000000 +-0.000176 -0.000740 1.000000 +-0.000176 -0.000740 1.000000 +-0.000176 -0.000740 1.000000 +-0.000030 0.000000 1.000000 +-0.000030 0.000000 1.000000 +-0.000030 0.000000 1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.303790 -0.952739 0.000000 +0.303790 -0.952739 0.000000 +0.303790 -0.952739 0.000000 +0.303790 -0.952739 0.000000 +0.303790 -0.952739 0.000000 +0.303790 -0.952739 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.311442 0.950265 0.000000 +0.311442 0.950265 0.000000 +0.311442 0.950265 0.000000 +0.311442 0.950265 0.000000 +0.311442 0.950265 0.000000 +0.311442 0.950265 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.000447 -0.888048 0.459751 +-0.000447 -0.888048 0.459751 +-0.000447 -0.888048 0.459751 +0.000000 -0.887985 0.459873 +0.000000 -0.887985 0.459873 +0.000000 -0.887985 0.459873 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 -0.000218 +-1.000000 0.000000 -0.000218 +-1.000000 0.000000 -0.000218 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 -0.000218 +-1.000000 0.000000 -0.000218 +-1.000000 0.000000 -0.000218 +-1.000000 0.000000 -0.000218 +-1.000000 0.000000 -0.000218 +-1.000000 0.000000 -0.000218 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.362360 0.000000 -0.932038 +-0.362359 0.000000 -0.932038 +-0.362359 0.000000 -0.932038 +-0.362360 0.000000 -0.932038 +-0.362359 0.000000 -0.932038 +-0.362359 0.000000 -0.932038 +0.279392 0.000000 0.960177 +0.279392 0.000000 0.960177 +0.279392 0.000000 0.960177 +0.279392 0.000000 0.960177 +0.279392 0.000000 0.960177 +0.279392 0.000000 0.960177 +-0.970110 0.000000 0.242667 +-0.970110 0.000000 0.242667 +-0.970110 0.000000 0.242667 +-0.970110 0.000000 0.242667 +-0.970110 0.000000 0.242667 +-0.970110 0.000000 0.242667 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +1.000000 0.000000 0.000436 +1.000000 0.000000 0.000436 +1.000000 0.000000 0.000436 +1.000000 0.000000 0.000436 +1.000000 0.000000 0.000436 +1.000000 0.000000 0.000436 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000269 1.000000 +0.000000 0.000269 1.000000 +0.000000 0.000269 1.000000 +0.000109 -0.000024 1.000000 +0.000109 -0.000024 1.000000 +0.000109 -0.000024 1.000000 +0.000047 0.000000 1.000000 +0.000047 0.000000 1.000000 +0.000047 0.000000 1.000000 +0.006317 0.001366 0.999979 +0.006317 0.001366 0.999979 +0.006317 0.001366 0.999979 +0.000000 -0.000891 1.000000 +0.000000 -0.000891 1.000000 +0.000000 -0.000891 1.000000 +-0.000109 -0.001195 0.999999 +-0.000109 -0.001195 0.999999 +-0.000109 -0.001195 0.999999 +-0.000030 0.000000 1.000000 +-0.000030 0.000000 1.000000 +-0.000030 0.000000 1.000000 +-0.000176 0.000740 1.000000 +-0.000176 0.000740 1.000000 +-0.000176 0.000740 1.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +-1.000000 0.000001 0.000000 +-1.000000 0.000001 0.000000 +-1.000000 0.000001 0.000000 +-1.000000 0.000001 0.000000 +-1.000000 0.000001 0.000000 +-1.000000 0.000001 0.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 0.000000 1.000000 +-0.000000 0.000000 1.000000 +-0.000000 0.000000 1.000000 +-0.000000 0.000000 1.000000 +-0.000000 0.000000 1.000000 +-0.000000 0.000000 1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 -0.000000 +-0.000001 0.000000 1.000000 +-0.000001 0.000000 1.000000 +-0.000001 0.000000 1.000000 +-0.000001 0.000000 1.000000 +-0.000001 0.000000 1.000000 +-0.000001 0.000000 1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 -0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000020 -1.000000 +0.000000 0.000020 -1.000000 +0.000000 0.000020 -1.000000 +0.000000 0.000020 -1.000000 +0.000000 0.000020 -1.000000 +0.000000 0.000020 -1.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +0.999197 0.000000 0.040073 +0.999197 0.000000 0.040073 +0.999197 0.000000 0.040073 +0.999197 0.000000 0.040073 +0.999197 0.000000 0.040073 +0.999197 0.000000 0.040073 +-0.999991 0.000000 0.004338 +-0.999991 0.000000 0.004338 +-0.999991 0.000000 0.004338 +-0.999991 0.000000 0.004338 +-0.999991 0.000000 0.004338 +-0.999991 0.000000 0.004338 +-0.000169 -0.999475 0.032385 +-0.000169 -0.999475 0.032385 +-0.000169 -0.999476 0.032385 +0.000242 -0.999476 0.032365 +0.000242 -0.999476 0.032365 +0.000242 -0.999476 0.032365 +-0.000639 0.000000 1.000000 +-0.000639 0.000000 1.000000 +-0.000639 0.000000 1.000000 +-0.000639 0.000000 1.000000 +-0.000639 0.000000 1.000000 +-0.000639 0.000000 1.000000 +-0.000168 0.999475 0.032385 +-0.000168 0.999476 0.032385 +-0.000168 0.999475 0.032385 +0.000243 0.999476 0.032365 +0.000243 0.999476 0.032365 +0.000243 0.999476 0.032365 +0.000000 0.059089 -0.998253 +0.000000 0.059089 -0.998253 +0.000000 0.059089 -0.998253 +0.000000 0.059089 -0.998253 +0.000000 0.059089 -0.998253 +0.000000 0.059089 -0.998253 +1.000000 0.000111 0.000000 +1.000000 0.000111 0.000000 +1.000000 0.000111 0.000000 +1.000000 0.000113 0.000008 +1.000000 0.000113 0.000008 +1.000000 0.000113 0.000008 +-0.000000 -0.058236 0.998303 +-0.000000 -0.058236 0.998303 +-0.000000 -0.058236 0.998303 +-0.000050 -0.058253 0.998302 +-0.000050 -0.058253 0.998302 +-0.000050 -0.058253 0.998302 +-1.000000 0.000129 0.000000 +-1.000000 0.000129 0.000000 +-1.000000 0.000129 0.000000 +-1.000000 0.000131 0.000009 +-1.000000 0.000131 0.000009 +-1.000000 0.000131 0.000009 +0.000000 0.151961 -0.988387 +0.000000 0.151961 -0.988386 +0.000000 0.151961 -0.988386 +0.000057 0.151933 -0.988391 +0.000057 0.151933 -0.988391 +0.000057 0.151933 -0.988391 +1.000000 0.000153 0.000010 +1.000000 0.000153 0.000010 +1.000000 0.000153 0.000010 +1.000000 0.000179 0.000098 +1.000000 0.000179 0.000098 +1.000000 0.000179 0.000098 +-0.000049 -0.151954 0.988388 +-0.000049 -0.151954 0.988388 +-0.000049 -0.151954 0.988388 +-0.000057 -0.151957 0.988387 +-0.000057 -0.151957 0.988387 +-0.000057 -0.151957 0.988387 +-1.000000 0.000169 -0.000013 +-1.000000 0.000169 -0.000013 +-1.000000 0.000169 -0.000013 +-1.000000 0.000177 0.000012 +-1.000000 0.000177 0.000012 +-1.000000 0.000177 0.000012 +0.000051 0.932023 -0.362400 +0.000051 0.932023 -0.362400 +0.000051 0.932023 -0.362400 +0.000119 0.932046 -0.362340 +0.000119 0.932046 -0.362340 +0.000119 0.932046 -0.362340 +1.000000 0.000065 0.000236 +1.000000 0.000065 0.000236 +1.000000 0.000065 0.000236 +1.000000 0.000015 0.000324 +1.000000 0.000015 0.000324 +1.000000 0.000015 0.000324 +-0.000123 -0.919973 0.391981 +-0.000123 -0.919973 0.391981 +-0.000123 -0.919973 0.391981 +-0.000100 -0.919968 0.391994 +-0.000100 -0.919968 0.391994 +-0.000100 -0.919968 0.391994 +-1.000000 0.000255 0.000891 +-1.000000 0.000255 0.000891 +-1.000000 0.000255 0.000891 +-1.000000 0.000520 0.000422 +-1.000000 0.000520 0.000422 +-1.000000 0.000520 0.000422 +0.000107 0.995297 -0.096868 +0.000107 0.995297 -0.096868 +0.000107 0.995297 -0.096868 +0.000054 0.995302 -0.096822 +0.000054 0.995302 -0.096822 +0.000054 0.995302 -0.096822 +1.000000 -0.000152 0.000513 +1.000000 -0.000152 0.000513 +1.000000 -0.000152 0.000513 +1.000000 0.000093 0.000673 +1.000000 0.000093 0.000673 +1.000000 0.000093 0.000673 +-0.000108 -0.995483 0.094939 +-0.000108 -0.995483 0.094939 +-0.000108 -0.995483 0.094939 +-0.000108 -0.995483 0.094939 +-0.000108 -0.995483 0.094939 +-0.000108 -0.995483 0.094939 +-1.000000 0.000182 0.000565 +-1.000000 0.000182 0.000565 +-1.000000 0.000182 0.000565 +-1.000000 0.000069 0.000492 +-1.000000 0.000069 0.000492 +-1.000000 0.000069 0.000492 +0.000306 0.947864 0.318674 +0.000306 0.947864 0.318674 +0.000306 0.947864 0.318674 +0.000102 0.947789 0.318899 +0.000102 0.947789 0.318899 +0.000102 0.947789 0.318899 +0.999999 -0.001138 0.001194 +0.999999 -0.001138 0.001194 +0.999999 -0.001138 0.001194 +0.999997 -0.000323 0.002604 +0.999997 -0.000323 0.002604 +0.999997 -0.000323 0.002604 +-0.000102 -0.943108 -0.332488 +-0.000102 -0.943107 -0.332488 +-0.000102 -0.943107 -0.332488 +-0.000308 -0.943158 -0.332346 +-0.000308 -0.943158 -0.332346 +-0.000308 -0.943157 -0.332346 +-0.999999 -0.000528 0.001366 +-0.999999 -0.000528 0.001366 +-0.999999 -0.000528 0.001366 +-0.999998 -0.000067 0.002163 +-0.999998 -0.000067 0.002163 +-0.999998 -0.000067 0.002163 +0.000000 0.647581 0.761997 +0.000000 0.647581 0.761997 +0.000000 0.647581 0.761997 +0.000294 0.647373 0.762173 +0.000294 0.647373 0.762173 +0.000294 0.647373 0.762173 +0.999996 0.001246 -0.002321 +0.999996 0.001246 -0.002321 +0.999997 0.001246 -0.002321 +0.999994 0.002936 -0.002039 +0.999994 0.002936 -0.002039 +0.999994 0.002936 -0.002039 +-0.000302 -0.668942 -0.743314 +-0.000302 -0.668942 -0.743314 +-0.000302 -0.668942 -0.743314 +0.000000 -0.669098 -0.743174 +0.000000 -0.669098 -0.743174 +0.000000 -0.669098 -0.743174 +-0.999996 0.002275 -0.001580 +-0.999996 0.002275 -0.001580 +-0.999996 0.002275 -0.001580 +-0.999997 0.001553 -0.001701 +-0.999997 0.001553 -0.001701 +-0.999997 0.001553 -0.001701 +0.000000 0.547792 0.836615 +0.000000 0.547792 0.836615 +0.000000 0.547792 0.836615 +0.000000 0.547792 0.836615 +0.000000 0.547792 0.836615 +0.000000 0.547792 0.836615 +1.000000 0.000013 -0.000009 +1.000000 0.000013 -0.000009 +1.000000 0.000013 -0.000009 +1.000000 0.000013 -0.000009 +1.000000 0.000013 -0.000009 +1.000000 0.000013 -0.000009 +0.000000 -0.547816 -0.836599 +0.000000 -0.547816 -0.836599 +0.000000 -0.547816 -0.836599 +-0.000000 -0.547816 -0.836599 +-0.000000 -0.547816 -0.836599 +-0.000000 -0.547816 -0.836599 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-0.000013 0.238366 -0.971175 +-0.000013 0.238366 -0.971176 +-0.000013 0.238366 -0.971175 +0.000056 0.238301 -0.971191 +0.000056 0.238301 -0.971191 +0.000056 0.238301 -0.971191 +1.000000 0.000087 0.000076 +1.000000 0.000087 0.000076 +1.000000 0.000087 0.000076 +1.000000 0.000107 0.000064 +1.000000 0.000107 0.000064 +1.000000 0.000107 0.000064 +-0.000056 -0.269463 0.963011 +-0.000056 -0.269463 0.963011 +-0.000056 -0.269463 0.963011 +0.000014 -0.269513 0.962997 +0.000014 -0.269513 0.962997 +0.000014 -0.269513 0.962997 +-1.000000 -0.000178 -0.000106 +-1.000000 -0.000178 -0.000106 +-1.000000 -0.000178 -0.000106 +-1.000000 -0.000190 -0.000099 +-1.000000 -0.000190 -0.000099 +-1.000000 -0.000190 -0.000099 +-0.000030 0.541254 -0.840859 +-0.000030 0.541254 -0.840859 +-0.000030 0.541254 -0.840859 +0.000101 0.541065 -0.840981 +0.000101 0.541065 -0.840981 +0.000101 0.541065 -0.840981 +1.000000 -0.000360 -0.000237 +1.000000 -0.000360 -0.000237 +1.000000 -0.000360 -0.000237 +1.000000 -0.000398 -0.000238 +1.000000 -0.000398 -0.000238 +1.000000 -0.000398 -0.000238 +0.000031 -0.575404 0.817869 +0.000031 -0.575404 0.817869 +0.000031 -0.575404 0.817869 +-0.000110 -0.575273 0.817961 +-0.000110 -0.575273 0.817961 +-0.000110 -0.575273 0.817961 +-1.000000 -0.000489 -0.000703 +-1.000000 -0.000489 -0.000703 +-1.000000 -0.000489 -0.000703 +-0.999999 -0.001203 -0.000719 +-0.999999 -0.001203 -0.000719 +-0.999999 -0.001203 -0.000719 +-0.000000 -0.059090 -0.998253 +-0.000000 -0.059090 -0.998253 +-0.000000 -0.059090 -0.998253 +-0.000000 -0.059090 -0.998253 +-0.000000 -0.059090 -0.998253 +-0.000000 -0.059090 -0.998253 +1.000000 -0.000113 0.000008 +1.000000 -0.000113 0.000008 +1.000000 -0.000113 0.000008 +1.000000 -0.000111 0.000000 +1.000000 -0.000111 0.000000 +1.000000 -0.000111 0.000000 +0.000000 0.058236 0.998303 +0.000000 0.058236 0.998303 +0.000000 0.058236 0.998303 +0.000000 0.058236 0.998303 +0.000000 0.058236 0.998303 +0.000000 0.058236 0.998303 +-1.000000 -0.000129 0.000000 +-1.000000 -0.000129 0.000000 +-1.000000 -0.000129 0.000000 +-1.000000 -0.000131 0.000009 +-1.000000 -0.000131 0.000009 +-1.000000 -0.000131 0.000009 +-0.000000 -0.151961 -0.988386 +-0.000000 -0.151961 -0.988386 +-0.000000 -0.151961 -0.988386 +0.000057 -0.151933 -0.988391 +0.000057 -0.151933 -0.988391 +0.000057 -0.151933 -0.988391 +1.000000 -0.000179 0.000098 +1.000000 -0.000179 0.000098 +1.000000 -0.000179 0.000098 +1.000000 -0.000153 0.000010 +1.000000 -0.000153 0.000010 +1.000000 -0.000153 0.000010 +-0.000057 0.151980 0.988384 +-0.000057 0.151980 0.988384 +-0.000057 0.151980 0.988384 +0.000000 0.151954 0.988388 +0.000000 0.151954 0.988388 +0.000000 0.151954 0.988388 +-1.000000 -0.000177 0.000012 +-1.000000 -0.000177 0.000012 +-1.000000 -0.000177 0.000012 +-1.000000 -0.000169 -0.000013 +-1.000000 -0.000169 -0.000013 +-1.000000 -0.000169 -0.000013 +0.000051 -0.932015 -0.362419 +0.000051 -0.932015 -0.362419 +0.000051 -0.932015 -0.362419 +0.000090 -0.932029 -0.362384 +0.000090 -0.932029 -0.362384 +0.000090 -0.932029 -0.362384 +1.000000 -0.000065 0.000236 +1.000000 -0.000065 0.000236 +1.000000 -0.000065 0.000236 +1.000000 -0.000015 0.000324 +1.000000 -0.000015 0.000324 +1.000000 -0.000015 0.000324 +-0.000049 0.919968 0.391994 +-0.000049 0.919968 0.391994 +-0.000049 0.919968 0.391994 +-0.000144 0.919991 0.391938 +-0.000144 0.919991 0.391938 +-0.000144 0.919991 0.391938 +-1.000000 -0.000520 0.000422 +-1.000000 -0.000520 0.000422 +-1.000000 -0.000520 0.000422 +-1.000000 -0.000255 0.000891 +-1.000000 -0.000255 0.000891 +-1.000000 -0.000255 0.000891 +0.000055 -0.999401 -0.034613 +0.000055 -0.999401 -0.034613 +0.000055 -0.999401 -0.034613 +0.000265 -0.999396 -0.034762 +0.000265 -0.999396 -0.034762 +0.000265 -0.999396 -0.034762 +0.999998 -0.000326 0.001713 +0.999999 -0.000326 0.001713 +0.999999 -0.000326 0.001713 +0.999999 0.000587 0.001197 +0.999999 0.000587 0.001197 +0.999999 0.000587 0.001197 +-0.000054 0.999797 0.020164 +-0.000054 0.999797 0.020164 +-0.000054 0.999797 0.020164 +-0.000215 0.999795 0.020250 +-0.000215 0.999795 0.020250 +-0.000215 0.999795 0.020250 +-0.999999 -0.000370 0.001405 +-0.999999 -0.000370 0.001405 +-0.999999 -0.000370 0.001405 +-0.999999 0.000018 0.001185 +-0.999999 0.000018 0.001185 +-0.999999 0.000018 0.001185 +0.000292 -0.891051 0.453904 +0.000292 -0.891051 0.453904 +0.000292 -0.891051 0.453904 +0.000215 -0.891008 0.453988 +0.000215 -0.891008 0.453988 +0.000215 -0.891008 0.453988 +1.000000 0.000085 -0.000786 +1.000000 0.000085 -0.000786 +1.000000 0.000085 -0.000786 +1.000000 -0.000067 -0.000372 +1.000000 -0.000067 -0.000372 +1.000000 -0.000067 -0.000372 +-0.000214 0.887579 -0.460655 +-0.000214 0.887579 -0.460655 +-0.000214 0.887579 -0.460655 +-0.000216 0.887580 -0.460654 +-0.000216 0.887580 -0.460654 +-0.000216 0.887580 -0.460654 +-1.000000 -0.000497 -0.000195 +-1.000000 -0.000497 -0.000195 +-1.000000 -0.000497 -0.000195 +-1.000000 -0.000399 -0.000463 +-1.000000 -0.000399 -0.000463 +-1.000000 -0.000399 -0.000463 +0.000032 -0.588033 0.808837 +0.000032 -0.588033 0.808837 +0.000032 -0.588033 0.808837 +0.000222 -0.587847 0.808972 +0.000222 -0.587847 0.808972 +0.000222 -0.587847 0.808972 +0.999997 -0.001670 -0.001992 +0.999997 -0.001670 -0.001992 +0.999997 -0.001670 -0.001992 +0.999994 -0.002753 -0.001912 +0.999994 -0.002753 -0.001912 +0.999994 -0.002753 -0.001912 +-0.000033 0.594535 -0.804070 +-0.000033 0.594535 -0.804070 +-0.000033 0.594535 -0.804070 +-0.000222 0.594384 -0.804181 +-0.000222 0.594384 -0.804181 +-0.000222 0.594384 -0.804181 +-0.999997 -0.001738 -0.001449 +-0.999997 -0.001738 -0.001449 +-0.999997 -0.001738 -0.001449 +-0.999997 -0.002053 -0.001426 +-0.999997 -0.002053 -0.001426 +-0.999997 -0.002053 -0.001426 +-0.000000 -0.547796 0.836612 +-0.000000 -0.547796 0.836612 +-0.000000 -0.547796 0.836612 +0.000029 -0.547792 0.836615 +0.000029 -0.547792 0.836615 +0.000029 -0.547792 0.836615 +1.000000 -0.000013 -0.000009 +1.000000 -0.000013 -0.000009 +1.000000 -0.000013 -0.000009 +1.000000 -0.000014 -0.000009 +1.000000 -0.000014 -0.000009 +1.000000 -0.000014 -0.000009 +0.000000 0.547819 -0.836597 +0.000000 0.547819 -0.836597 +0.000000 0.547819 -0.836597 +-0.000030 0.547816 -0.836599 +-0.000030 0.547816 -0.836599 +-0.000030 0.547816 -0.836599 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000056 -0.238289 -0.971194 +0.000056 -0.238289 -0.971194 +0.000056 -0.238289 -0.971194 +-0.000013 -0.238353 -0.971179 +-0.000013 -0.238353 -0.971179 +-0.000013 -0.238353 -0.971179 +1.000000 -0.000089 0.000077 +1.000000 -0.000089 0.000077 +1.000000 -0.000089 0.000077 +1.000000 -0.000108 0.000065 +1.000000 -0.000108 0.000065 +1.000000 -0.000108 0.000065 +-0.000056 0.269463 0.963011 +-0.000056 0.269463 0.963011 +-0.000056 0.269463 0.963011 +0.000014 0.269513 0.962997 +0.000014 0.269513 0.962997 +0.000014 0.269513 0.962997 +-1.000000 0.000179 -0.000107 +-1.000000 0.000179 -0.000107 +-1.000000 0.000179 -0.000107 +-1.000000 0.000192 -0.000099 +-1.000000 0.000192 -0.000099 +-1.000000 0.000192 -0.000099 +-0.000029 -0.541324 -0.840814 +-0.000029 -0.541324 -0.840814 +-0.000029 -0.541324 -0.840814 +0.000120 -0.541108 -0.840953 +0.000120 -0.541108 -0.840953 +0.000120 -0.541108 -0.840953 +1.000000 0.000398 -0.000238 +1.000000 0.000398 -0.000238 +1.000000 0.000398 -0.000238 +1.000000 0.000360 -0.000237 +1.000000 0.000360 -0.000237 +1.000000 0.000360 -0.000237 +0.000031 0.575404 0.817870 +0.000031 0.575404 0.817870 +0.000031 0.575404 0.817870 +-0.000157 0.575229 0.817992 +-0.000157 0.575229 0.817992 +-0.000157 0.575229 0.817992 +-1.000000 0.000489 -0.000703 +-1.000000 0.000489 -0.000703 +-1.000000 0.000489 -0.000703 +-0.999999 0.001203 -0.000719 +-0.999999 0.001203 -0.000719 +-0.999999 0.001203 -0.000719 +0.999282 -0.034750 -0.015064 +0.999282 -0.034750 -0.015064 +0.999282 -0.034750 -0.015064 +0.999367 -0.035523 -0.002042 +0.999367 -0.035523 -0.002042 +0.999367 -0.035523 -0.002042 +0.999727 -0.023366 0.000609 +0.999727 -0.023366 0.000609 +0.999727 -0.023366 0.000609 +0.999727 -0.023280 0.001817 +0.999727 -0.023280 0.001817 +0.999727 -0.023280 0.001817 +-0.999728 -0.023266 0.001751 +-0.999728 -0.023266 0.001751 +-0.999728 -0.023266 0.001751 +-0.999727 -0.023348 0.000613 +-0.999727 -0.023348 0.000613 +-0.999727 -0.023348 0.000613 +-0.999367 -0.035523 -0.002042 +-0.999367 -0.035523 -0.002042 +-0.999367 -0.035523 -0.002042 +-0.999281 -0.034743 -0.015193 +-0.999281 -0.034743 -0.015193 +-0.999281 -0.034743 -0.015193 +0.000000 0.999882 0.015389 +0.000000 0.999882 0.015389 +0.000000 0.999882 0.015389 +0.000000 0.999882 0.015389 +0.000000 0.999882 0.015389 +0.000000 0.999882 0.015389 +0.000000 0.128557 -0.991702 +0.000000 0.128557 -0.991702 +0.000000 0.128557 -0.991702 +0.000000 0.128557 -0.991702 +0.000000 0.128557 -0.991702 +0.000000 0.128557 -0.991702 +0.000000 0.317775 -0.948166 +0.000000 0.317775 -0.948166 +0.000000 0.317775 -0.948166 +0.000000 0.317775 -0.948166 +0.000000 0.317775 -0.948166 +0.000000 0.317775 -0.948166 +0.000000 -0.931173 -0.364577 +0.000000 -0.931173 -0.364577 +0.000000 -0.931173 -0.364577 +0.000000 -0.931173 -0.364577 +0.000000 -0.931173 -0.364577 +0.000000 -0.931173 -0.364577 +0.000000 -0.402066 0.915611 +0.000000 -0.402066 0.915611 +0.000000 -0.402066 0.915611 +0.000000 -0.402066 0.915611 +0.000000 -0.402066 0.915611 +0.000000 -0.402066 0.915611 +0.000000 -0.218768 0.975777 +0.000000 -0.218768 0.975777 +0.000000 -0.218768 0.975777 +-0.000000 -0.218768 0.975777 +-0.000000 -0.218768 0.975777 +-0.000000 -0.218768 0.975777 + + + + + + + + + + + +0.093513 0.445266 +0.093513 0.398749 +0.121630 0.398749 +0.121630 0.445266 +0.093513 0.491320 +0.121630 0.491320 +0.093513 0.536619 +0.121630 0.536619 +0.093513 0.580952 +0.121630 0.580952 +0.093513 0.624189 +0.121630 0.624189 +0.093513 0.666219 +0.121630 0.666219 +0.093513 0.706882 +0.121630 0.706882 +0.093513 0.745968 +0.121630 0.745968 +0.093513 0.783496 +0.121630 0.783496 +0.093513 0.043258 +0.093513 0.003616 +0.121630 0.003616 +0.121630 0.043258 +0.093513 0.084259 +0.121630 0.084259 +0.093513 0.126597 +0.121630 0.126597 +0.093513 0.170074 +0.121630 0.170074 +0.093513 0.214474 +0.121630 0.214474 +0.093513 0.259712 +0.121630 0.259712 +0.093513 0.305657 +0.121630 0.305657 +0.093513 0.352101 +0.121630 0.352101 +0.093513 0.445266 +0.093513 0.398749 +0.121630 0.398749 +0.121630 0.445266 +0.093513 0.491320 +0.121630 0.491320 +0.093513 0.536619 +0.121630 0.536619 +0.093513 0.580952 +0.121630 0.580952 +0.093513 0.624189 +0.121630 0.624189 +0.093513 0.666219 +0.121630 0.666219 +0.093513 0.706882 +0.121630 0.706882 +0.093513 0.745968 +0.121630 0.745968 +0.093513 0.783496 +0.121630 0.783496 +0.093513 0.043258 +0.093513 0.003616 +0.121630 0.003616 +0.121630 0.043258 +0.093513 0.084259 +0.121630 0.084259 +0.093513 0.126597 +0.121630 0.126597 +0.093513 0.170074 +0.121630 0.170074 +0.093513 0.214474 +0.121630 0.214474 +0.093513 0.259712 +0.121630 0.259712 +0.093513 0.305657 +0.121630 0.305657 +0.093513 0.352101 +0.121630 0.352101 +0.826497 0.683519 +0.826497 0.668769 +0.835791 0.668769 +0.835791 0.683519 +0.826497 0.654474 +0.835791 0.654474 +0.826497 0.640550 +0.835791 0.640550 +0.826497 0.626993 +0.835791 0.626993 +0.826497 0.613868 +0.835791 0.613868 +0.826497 0.600776 +0.835791 0.600776 +0.826497 0.587338 +0.835791 0.587338 +0.826497 0.573639 +0.835791 0.573639 +0.826497 0.559820 +0.835791 0.559820 +0.826497 0.807218 +0.826497 0.793395 +0.835791 0.793395 +0.835791 0.807218 +0.826497 0.779694 +0.835791 0.779694 +0.826497 0.766255 +0.835791 0.766255 +0.826497 0.753164 +0.835791 0.753164 +0.826497 0.740045 +0.835791 0.740045 +0.826497 0.726500 +0.835791 0.726500 +0.826497 0.712580 +0.835791 0.712580 +0.826497 0.698276 +0.835791 0.698276 +0.826497 0.683519 +0.826497 0.668769 +0.835791 0.668769 +0.835791 0.683519 +0.826497 0.654474 +0.835791 0.654474 +0.826497 0.640550 +0.835791 0.640550 +0.826497 0.626993 +0.835791 0.626993 +0.826497 0.613868 +0.835791 0.613868 +0.826497 0.600776 +0.835791 0.600776 +0.826497 0.587338 +0.835791 0.587338 +0.826497 0.573639 +0.835791 0.573639 +0.826497 0.559820 +0.835791 0.559820 +0.826497 0.807218 +0.826497 0.793395 +0.835791 0.793395 +0.835791 0.807218 +0.826497 0.779694 +0.835791 0.779694 +0.826497 0.766255 +0.835791 0.766255 +0.826497 0.753164 +0.835791 0.753164 +0.826497 0.740045 +0.835791 0.740045 +0.826497 0.726500 +0.835791 0.726500 +0.826497 0.712580 +0.835791 0.712580 +0.826497 0.698276 +0.835791 0.698276 +1.000000 0.000000 +0.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.500000 0.000000 +0.500000 0.000000 +0.500000 1.000000 +0.500000 1.000000 +0.750000 1.000000 +0.750000 0.000000 +0.250000 0.000000 +0.250000 1.000000 +0.750000 0.000000 +0.250000 0.000000 +0.250000 1.000000 +0.750000 1.000000 +0.875000 1.000000 +0.875000 0.000000 +0.125000 0.000000 +0.125000 1.000000 +0.875000 0.000000 +0.125000 0.000000 +0.125000 1.000000 +0.875000 1.000000 +0.875000 1.000000 +0.750000 1.000000 +0.250000 1.000000 +0.250000 0.000000 +0.125000 0.500000 +0.500000 0.500000 +0.250000 0.500000 +0.125000 0.500000 +0.593750 1.000000 +0.593750 0.000000 +0.500000 0.500000 +0.625000 0.708800 +0.625000 0.291200 +0.562500 0.708800 +0.562500 0.291200 +0.250000 1.000000 +0.250000 0.000000 +0.250000 1.000000 +0.250000 0.000000 +0.250000 1.000000 +0.250000 1.000000 +0.250000 1.000000 +0.500000 1.000000 +0.000000 1.000000 +0.625000 0.291200 +0.750000 0.000000 +0.250000 0.000000 +0.406250 0.000000 +0.250000 0.000000 +0.250000 0.500000 +0.250000 0.000000 +0.250000 1.000000 +0.125000 0.500000 +0.250000 0.000000 +0.250000 1.000000 +0.500000 0.750000 +0.500000 0.500000 +0.125000 0.500000 +0.250000 0.500000 +0.625000 0.500000 +0.203125 0.343750 +0.703125 1.000000 +0.125000 0.500000 +0.125000 0.127982 +0.125000 0.255963 +0.125000 0.250000 +0.125000 0.500000 +0.125000 0.255963 +0.125000 0.127982 +0.125000 0.250000 +0.171405 0.677520 +0.100895 0.959563 +0.090556 0.637775 +0.090556 0.637775 +0.129305 0.413608 +0.129305 0.358834 +0.129305 0.413608 +0.625000 0.708800 +0.625000 0.291200 +0.562500 0.291200 +0.562500 0.708800 +0.494699 0.741503 +0.438042 0.780345 +0.436228 0.250657 +0.496591 0.251554 +1.000000 0.000000 +1.000000 1.000000 +0.875000 1.000000 +0.875000 0.000000 +0.000000 0.000000 +0.125000 0.000000 +0.125000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +0.125000 0.000000 +0.125000 0.500000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +0.593750 0.000000 +0.500000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.593750 1.000000 +0.000000 1.000000 +0.000000 0.000000 +0.500000 0.500000 +0.500000 0.000000 +1.000000 0.000000 +1.000000 1.000000 +0.500000 1.000000 +0.500000 0.000000 +1.000000 0.000000 +1.000000 1.000000 +0.500000 0.500000 +0.750000 1.000000 +0.625000 0.708800 +0.625000 0.291200 +0.750000 0.000000 +0.250000 0.000000 +0.250000 0.500000 +0.750000 0.000000 +0.875000 0.000000 +0.875000 1.000000 +0.750000 1.000000 +1.000000 0.000000 +1.000000 1.000000 +0.875000 1.000000 +0.750000 1.000000 +0.250000 0.000000 +0.250000 1.000000 +0.250000 1.000000 +0.250000 0.000000 +0.125000 0.500000 +0.125000 1.000000 +0.250000 0.500000 +0.125000 0.500000 +0.250000 1.000000 +0.250000 1.000000 +0.562500 0.291200 +0.562500 0.708800 +0.250000 1.000000 +0.250000 0.000000 +0.250000 1.000000 +0.250000 0.000000 +0.250000 1.000000 +0.250000 0.000000 +0.250000 1.000000 +0.250000 1.000000 +0.250000 0.000000 +0.250000 0.000000 +0.250000 1.000000 +0.500000 0.750000 +0.500000 1.000000 +0.000000 1.000000 +0.500000 0.500000 +0.250000 0.500000 +0.625000 0.500000 +0.203125 0.343750 +0.703125 1.000000 +0.171405 0.677520 +0.100895 0.959563 +0.125000 0.500000 +0.125000 0.255963 +0.125000 0.127982 +0.125000 0.127982 +0.125000 0.255963 +0.125000 0.250000 +0.129305 0.413608 +0.129305 0.413608 +0.125000 0.250000 +0.090556 0.637775 +0.125000 0.500000 +0.125000 0.500000 +0.090556 0.637775 +0.129305 0.358834 +0.250000 0.000000 +0.406250 0.000000 +0.625000 0.291200 +0.750000 0.000000 +0.625000 0.708800 +0.625000 0.291200 +0.562500 0.291200 +0.562500 0.708800 +0.436228 0.250657 +0.496591 0.251554 +0.494699 0.741503 +0.438042 0.780345 +1.000000 0.000000 +0.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +1.000000 0.000000 +0.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.377324 0.003499 +0.361808 0.765063 +0.320989 0.765121 +0.303297 0.003605 +0.395489 0.003764 +0.469515 0.003799 +0.452554 0.765055 +0.411736 0.765036 +0.219929 0.004120 +0.209604 0.765772 +0.189226 0.766048 +0.176937 0.004702 +0.014284 0.902757 +0.055101 0.902876 +0.055042 0.923257 +0.014224 0.923138 +0.251390 0.766650 +0.241336 0.004994 +0.284328 0.005591 +0.271768 0.766933 +0.479330 0.459887 +0.487364 0.459887 +0.479330 0.526656 +0.487364 0.526656 +0.501809 0.459887 +0.501809 0.526656 +0.515050 0.459887 +0.515050 0.526656 +0.528874 0.459887 +0.528874 0.526656 +0.479330 0.572027 +0.487364 0.572027 +0.501809 0.572027 +0.515050 0.572027 +0.528874 0.572027 +0.479330 0.609095 +0.487364 0.609095 +0.479330 0.631422 +0.487364 0.631422 +0.501809 0.609095 +0.501809 0.631422 +0.515050 0.609095 +0.515050 0.631422 +0.528874 0.609095 +0.528874 0.631422 +0.479330 0.651815 +0.487364 0.651815 +0.501809 0.651815 +0.515050 0.651815 +0.528874 0.651815 +0.479330 0.668167 +0.487364 0.668167 +0.501809 0.668167 +0.515050 0.668167 +0.528874 0.668167 +0.479330 0.685906 +0.487364 0.685906 +0.501809 0.685906 +0.515050 0.685906 +0.528874 0.685906 +0.479330 0.777451 +0.487364 0.777451 +0.501809 0.777451 +0.515050 0.777451 +0.528874 0.777451 +0.479330 0.595957 +0.487364 0.595957 +0.501809 0.595957 +0.515050 0.595957 +0.528874 0.595957 +0.479330 0.391526 +0.487364 0.391526 +0.501809 0.391526 +0.515050 0.391526 +0.528874 0.391526 +0.479330 0.342195 +0.528874 0.342195 +0.487364 0.342195 +0.501809 0.342195 +0.515050 0.342195 +0.479330 0.297630 +0.479330 0.267134 +0.487364 0.297630 +0.501809 0.297630 +0.515050 0.297630 +0.528874 0.267134 +0.528874 0.297630 +0.487364 0.267134 +0.501809 0.267134 +0.515050 0.267134 +0.479330 0.227220 +0.528874 0.227220 +0.487364 0.227220 +0.501809 0.227220 +0.515050 0.227220 +0.479330 0.200766 +0.487364 0.200766 +0.501809 0.200766 +0.515050 0.200766 +0.528874 0.200766 +0.479330 0.177595 +0.487364 0.177595 +0.501809 0.177595 +0.515050 0.177595 +0.528874 0.177595 +0.479330 0.002954 +0.487364 0.002954 +0.501809 0.002954 +0.515050 0.002954 +0.528874 0.002954 +0.479330 0.314183 +0.487364 0.314183 +0.501809 0.314183 +0.515050 0.314183 +0.528874 0.314183 +0.182082 0.911611 +0.182594 0.927989 +0.152534 0.933244 +0.096470 0.943464 +0.151807 0.908221 +0.095169 0.901475 +0.181947 0.917439 +0.151927 0.916785 +0.096404 0.916062 +0.096807 0.928846 +0.152119 0.924684 +0.182103 0.922166 + + + + + + + + + + +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 + + + + + + + + + + + + + +

2 0 2 2 3 1 3 3 0 2 0 0 2 3 2 2 0 4 0 0 1 5 1 1 3 6 3 3 5 7 5 5 4 8 4 4 3 9 3 3 4 10 4 4 0 11 0 0 5 12 5 5 6 13 6 6 4 14 4 4 6 15 6 6 5 16 5 5 7 17 7 7 7 18 7 7 8 19 8 8 6 20 6 6 8 21 8 8 7 22 7 7 9 23 9 9 9 24 9 9 10 25 10 10 8 26 8 8 10 27 10 10 9 28 9 9 11 29 11 11 11 30 11 11 12 31 12 12 10 32 10 10 12 33 12 12 11 34 11 11 13 35 13 13 13 36 13 13 14 37 14 14 12 38 12 12 14 39 14 14 13 40 13 13 15 41 15 15 14 42 14 14 15 43 15 15 16 44 16 16 16 45 16 16 15 46 15 15 17 47 17 17 16 48 16 16 17 49 17 17 18 50 18 18 18 51 18 18 17 52 17 17 19 53 19 19 18 54 21 18 19 55 22 19 20 56 20 20 20 57 20 20 19 58 22 19 21 59 23 21 20 60 20 20 21 61 23 21 22 62 24 22 22 63 24 22 21 64 23 21 23 65 25 23 22 66 24 22 25 67 27 25 24 68 26 24 25 69 27 25 22 70 24 22 23 71 25 23 27 72 29 27 24 73 26 24 25 74 27 25 24 75 26 24 27 76 29 27 26 77 28 26 29 78 31 29 28 79 30 28 27 80 29 27 28 81 30 28 26 82 28 26 27 83 29 27 31 84 33 31 30 85 32 30 29 86 31 29 30 87 32 30 28 88 30 28 29 89 31 29 30 90 32 30 33 91 35 33 32 92 34 32 33 93 35 33 30 94 32 30 31 95 33 31 35 96 37 35 32 97 34 32 33 98 35 33 32 99 34 32 35 100 37 35 34 101 36 34 2 102 2 2 34 103 36 34 35 104 37 35 34 105 36 34 2 106 2 2 1 107 1 1 28 108 28 28 24 109 24 24 26 110 26 26 24 111 24 24 28 112 28 28 30 113 30 30 32 114 32 32 24 115 24 24 30 116 30 30 32 117 32 32 22 118 22 22 24 119 24 24 34 120 34 34 22 121 22 22 32 122 32 32 34 123 34 34 20 124 20 20 22 125 22 22 34 126 34 34 18 127 18 18 20 128 20 20 18 129 18 18 34 130 34 34 1 131 1 1 1 132 1 1 16 133 16 16 18 134 18 18 16 135 16 16 1 136 1 1 0 137 0 0 4 138 4 4 16 139 16 16 0 140 0 0 16 141 16 16 4 142 4 4 14 143 14 14 4 144 4 4 12 145 12 12 14 146 14 14 12 147 12 12 4 148 4 4 6 149 6 6 6 150 6 6 10 151 10 10 12 152 12 12 10 153 10 10 6 154 6 6 8 155 8 8 7 156 7 7 11 157 11 11 9 158 9 9 7 159 7 7 13 160 13 13 11 161 11 11 5 162 5 5 13 163 13 13 7 164 7 7 5 165 5 5 15 166 15 15 13 167 13 13 3 168 3 3 15 169 15 15 5 170 5 5 3 171 3 3 17 172 17 17 15 173 15 15 3 174 3 3 19 175 19 19 17 176 17 17 19 177 19 19 3 178 3 3 2 179 2 2 35 180 35 35 19 181 19 19 2 182 2 2 19 183 19 19 35 184 35 35 21 185 21 21 33 186 33 33 21 187 21 21 35 188 35 35 21 189 21 21 33 190 33 33 23 191 23 23 33 192 33 33 25 193 25 25 23 194 23 23 25 195 25 25 33 196 33 33 31 197 31 31 25 198 25 25 31 199 31 31 29 200 29 29 25 201 25 25 29 202 29 29 27 203 27 27 37 204 39 37 36 205 38 36 38 206 40 38 36 207 38 36 39 208 41 39 38 209 40 38 36 210 38 36 40 211 42 40 39 212 41 39 40 213 42 40 41 214 43 41 39 215 41 39 41 216 43 41 40 217 42 40 42 218 44 42 41 219 43 41 42 220 44 42 43 221 45 43 43 222 45 43 42 223 44 42 44 224 46 44 43 225 45 43 44 226 46 44 45 227 47 45 45 228 47 45 44 229 46 44 46 230 48 46 45 231 47 45 46 232 48 46 47 233 49 47 47 234 49 47 46 235 48 46 48 236 50 48 47 237 49 47 48 238 50 48 49 239 51 49 49 240 51 49 48 241 50 48 50 242 52 50 49 243 51 49 50 244 52 50 51 245 53 51 51 246 53 51 52 247 54 52 53 248 55 53 52 249 54 52 51 250 53 51 50 251 52 50 53 252 55 53 54 253 56 54 55 254 57 55 54 255 56 54 53 256 55 53 52 257 54 52 55 258 60 55 56 259 58 56 57 260 61 57 56 261 58 56 55 262 60 55 54 263 59 54 57 264 61 57 58 265 62 58 59 266 63 59 58 267 62 58 57 268 61 57 56 269 58 56 61 270 65 61 58 271 62 58 60 272 64 60 58 273 62 58 61 274 65 61 59 275 63 59 63 276 67 63 60 277 64 60 62 278 66 62 60 279 64 60 63 280 67 63 61 281 65 61 65 282 69 65 63 283 67 63 64 284 68 64 64 285 68 64 63 286 67 63 62 287 66 62 67 288 71 67 65 289 69 65 66 290 70 66 66 291 70 66 65 292 69 65 64 293 68 64 69 294 73 69 66 295 70 66 68 296 72 68 66 297 70 66 69 298 73 69 67 299 71 67 68 300 72 68 71 301 75 71 69 302 73 69 71 303 75 71 68 304 72 68 70 305 74 70 70 306 74 70 38 307 40 38 71 308 75 71 38 309 40 38 70 310 74 70 37 311 39 37 64 312 66 64 60 313 62 60 66 314 68 66 60 315 62 60 64 316 66 64 62 317 64 62 60 318 62 60 68 319 70 68 66 320 68 66 58 321 60 58 68 322 70 68 60 323 62 60 58 324 60 58 70 325 72 70 68 326 70 68 56 327 58 56 70 328 72 70 58 329 60 58 70 330 72 70 54 331 56 54 37 332 39 37 54 333 56 54 70 334 72 70 56 335 58 56 37 336 39 37 52 337 54 52 36 338 38 36 52 339 54 52 37 340 39 37 54 341 56 54 36 342 38 36 52 343 54 52 40 344 42 40 40 345 42 40 52 346 54 52 50 347 52 50 40 348 42 40 48 349 50 48 42 350 44 42 48 351 50 48 40 352 42 40 50 353 52 50 42 354 44 42 46 355 48 46 44 356 46 44 46 357 48 46 42 358 44 42 48 359 50 48 47 360 49 47 43 361 45 43 45 362 47 45 49 363 51 49 43 364 45 43 47 365 49 47 49 366 51 49 41 367 43 41 43 368 45 43 51 369 53 51 41 370 43 41 49 371 51 49 51 372 53 51 39 373 41 39 41 374 43 41 53 375 55 53 39 376 41 39 51 377 53 51 39 378 41 39 55 379 57 55 38 380 40 38 55 381 57 55 39 382 41 39 53 383 55 53 38 384 40 38 55 385 57 55 71 386 73 71 71 387 73 71 55 388 57 55 57 389 59 57 71 390 73 71 57 391 59 57 69 392 71 69 69 393 71 69 57 394 59 57 59 395 61 59 69 396 71 69 61 397 63 61 67 398 69 67 61 399 63 61 69 400 71 69 59 401 61 59 67 402 69 67 61 403 63 61 65 404 67 65 65 405 67 65 61 406 63 61 63 407 65 63 74 408 78 74 72 409 76 72 75 410 79 75 72 411 76 72 74 412 78 74 73 413 77 73 77 414 81 77 73 415 77 73 74 416 78 74 73 417 77 73 77 418 81 77 76 419 80 76 76 420 80 76 77 421 81 77 79 422 83 79 76 423 80 76 79 424 83 79 78 425 82 78 81 426 85 81 78 427 82 78 79 428 83 79 78 429 82 78 81 430 85 81 80 431 84 80 83 432 87 83 80 433 84 80 81 434 85 81 80 435 84 80 83 436 87 83 82 437 86 82 82 438 86 82 83 439 87 83 85 440 89 85 82 441 86 82 85 442 89 85 84 443 88 84 84 444 88 84 85 445 89 85 87 446 91 87 84 447 88 84 87 448 91 87 86 449 90 86 89 450 93 89 88 451 92 88 86 452 90 86 86 453 90 86 87 454 91 87 89 455 93 89 91 456 95 91 90 457 94 90 88 458 92 88 88 459 92 88 89 460 93 89 91 461 95 91 93 462 98 93 92 463 97 92 90 464 96 90 90 465 96 90 91 466 99 91 93 467 98 93 95 468 101 95 94 469 100 94 92 470 97 92 92 471 97 92 93 472 98 93 95 473 101 95 97 474 103 97 96 475 102 96 94 476 100 94 97 477 103 97 94 478 100 94 95 479 101 95 99 480 105 99 98 481 104 98 96 482 102 96 99 483 105 99 96 484 102 96 97 485 103 97 101 486 107 101 100 487 106 100 98 488 104 98 101 489 107 101 98 490 104 98 99 491 105 99 103 492 109 103 102 493 108 102 100 494 106 100 103 495 109 103 100 496 106 100 101 497 107 101 105 498 111 105 104 499 110 104 102 500 108 102 105 501 111 105 102 502 108 102 103 503 109 103 107 504 113 107 104 505 110 104 105 506 111 105 104 507 110 104 107 508 113 107 106 509 112 106 75 510 79 75 106 511 112 106 107 512 113 107 106 513 112 106 75 514 79 75 72 515 76 72 101 516 105 101 97 517 101 97 103 518 107 103 97 519 101 97 101 520 105 101 99 521 103 99 97 522 101 97 105 523 109 105 103 524 107 103 95 525 99 95 105 526 109 105 97 527 101 97 105 528 109 105 93 529 97 93 107 530 111 107 93 531 97 93 105 532 109 105 95 533 99 95 107 534 111 107 91 535 95 91 75 536 79 75 91 537 95 91 107 538 111 107 93 539 97 93 75 540 79 75 91 541 95 91 74 542 78 74 74 543 78 74 91 544 95 91 89 545 93 89 74 546 78 74 87 547 91 87 77 548 81 77 87 549 91 87 74 550 78 74 89 551 93 89 77 552 81 77 87 553 91 87 79 554 83 79 79 555 83 79 87 556 91 87 85 557 89 85 79 558 83 79 85 559 89 85 81 560 85 81 81 561 85 81 85 562 89 85 83 563 87 83 80 564 84 80 84 565 88 84 78 566 82 78 84 567 88 84 80 568 84 80 82 569 86 82 84 570 88 84 76 571 80 76 78 572 82 78 86 573 90 86 76 574 80 76 84 575 88 84 76 576 80 76 88 577 92 88 73 578 77 73 88 579 92 88 76 580 80 76 86 581 90 86 73 582 77 73 90 583 94 90 72 584 76 72 90 585 94 90 73 586 77 73 88 587 92 88 72 588 76 72 90 589 94 90 106 590 110 106 106 591 110 106 90 592 94 90 92 593 96 92 106 594 110 106 92 595 96 92 104 596 108 104 104 597 108 104 92 598 96 92 94 599 98 94 104 600 108 104 96 601 100 96 102 602 106 102 96 603 100 96 104 604 108 104 94 605 98 94 102 606 106 102 96 607 100 96 100 608 104 100 100 609 104 100 96 610 100 96 98 611 102 98 110 612 116 110 108 613 114 108 109 614 115 109 108 615 114 108 110 616 116 110 111 617 117 111 112 618 118 112 113 619 119 113 109 620 115 109 109 621 115 109 113 622 119 113 110 623 116 110 114 624 120 114 115 625 121 115 112 626 118 112 113 627 119 113 112 628 118 112 115 629 121 115 116 630 122 116 117 631 123 117 114 632 120 114 115 633 121 115 114 634 120 114 117 635 123 117 118 636 124 118 119 637 125 119 116 638 122 116 117 639 123 117 116 640 122 116 119 641 125 119 120 642 126 120 121 643 127 121 118 644 124 118 119 645 125 119 118 646 124 118 121 647 127 121 122 648 128 122 123 649 129 123 120 650 126 120 121 651 127 121 120 652 126 120 123 653 129 123 123 654 129 123 122 655 128 122 125 656 131 125 125 657 131 125 122 658 128 122 124 659 130 124 125 660 131 125 124 661 130 124 127 662 133 127 127 663 133 127 124 664 130 124 126 665 132 126 127 666 137 127 126 667 134 126 129 668 136 129 129 669 136 129 126 670 134 126 128 671 135 128 129 672 136 129 128 673 135 128 131 674 139 131 131 675 139 131 128 676 135 128 130 677 138 130 133 678 141 133 130 679 138 130 132 680 140 132 130 681 138 130 133 682 141 133 131 683 139 131 135 684 143 135 132 685 140 132 134 686 142 134 132 687 140 132 135 688 143 135 133 689 141 133 137 690 145 137 134 691 142 134 136 692 144 136 134 693 142 134 137 694 145 137 135 695 143 135 139 696 147 139 136 697 144 136 138 698 146 138 136 699 144 136 139 700 147 139 137 701 145 137 141 702 149 141 138 703 146 138 140 704 148 140 138 705 146 138 141 706 149 141 139 707 147 139 142 708 150 142 143 709 151 143 140 710 148 140 140 711 148 140 143 712 151 143 141 713 149 141 111 714 117 111 142 715 150 142 108 716 114 108 142 717 150 142 111 718 117 111 143 719 151 143 137 720 143 137 133 721 139 133 135 722 141 135 133 723 139 133 137 724 143 137 139 725 145 139 141 726 147 141 133 727 139 133 139 728 145 139 141 729 147 141 131 730 137 131 133 731 139 133 141 732 147 141 129 733 135 129 131 734 137 131 129 735 135 129 141 736 147 141 143 737 149 143 143 738 149 143 127 739 133 127 129 740 135 129 127 741 133 127 143 742 149 143 111 743 117 111 110 744 116 110 127 745 133 127 111 746 117 111 127 747 133 127 110 748 116 110 125 749 131 125 110 750 116 110 123 751 129 123 125 752 131 125 123 753 129 123 110 754 116 110 113 755 119 113 123 756 129 123 113 757 119 113 115 758 121 115 123 759 129 123 115 760 121 115 121 761 127 121 121 762 127 121 115 763 121 115 117 764 123 117 121 765 127 121 117 766 123 117 119 767 125 119 116 768 122 116 120 769 126 120 118 770 124 118 120 771 126 120 116 772 122 116 114 773 120 114 112 774 118 112 120 775 126 120 114 776 120 114 112 777 118 112 122 778 128 122 120 779 126 120 112 780 118 112 124 781 130 124 122 782 128 122 124 783 130 124 112 784 118 112 109 785 115 109 109 786 115 109 126 787 132 126 124 788 130 124 126 789 132 126 109 790 115 109 108 791 114 108 142 792 148 142 126 793 132 126 108 794 114 108 126 795 132 126 142 796 148 142 128 797 134 128 140 798 146 140 128 799 134 128 142 800 148 142 128 801 134 128 140 802 146 140 130 803 136 130 140 804 146 140 132 805 138 132 130 806 136 130 132 807 138 132 140 808 146 140 138 809 144 138 132 810 138 132 138 811 144 138 136 812 142 136 132 813 138 132 136 814 142 136 134 815 140 134 144 816 152 0 157 817 188 0 159 818 192 0 157 819 188 0 144 820 152 0 146 821 154 0 160 822 194 0 148 823 156 0 158 824 190 0 148 825 156 0 160 826 194 0 150 827 158 0 165 828 203 0 144 829 160 0 159 830 193 0 144 831 160 0 165 832 203 0 148 833 162 0 151 834 167 0 149 835 166 0 145 836 164 0 151 837 167 0 145 838 164 0 147 839 165 0 151 840 170 0 166 841 205 0 152 842 179 0 166 843 205 0 151 844 170 0 147 845 168 0 148 846 175 0 150 847 174 0 146 848 172 0 148 849 175 0 146 850 172 0 144 851 173 0 145 852 153 0 166 853 204 0 147 854 155 0 166 855 204 0 145 856 153 0 167 857 206 0 152 858 178 0 149 859 157 0 151 860 159 0 149 861 157 0 152 862 178 0 163 863 177 0 163 864 201 0 145 865 161 0 149 866 163 0 145 867 161 0 163 868 201 0 167 869 176 0 169 870 208 0 153 871 180 0 168 872 207 0 153 873 180 0 169 874 208 0 155 875 184 0 164 876 202 0 167 877 176 0 163 878 201 0 167 879 176 0 164 880 202 0 155 881 185 0 156 882 187 0 157 883 189 0 160 884 195 0 157 885 189 0 156 886 187 0 153 887 181 0 159 888 192 0 153 889 180 0 155 890 184 0 153 891 180 0 159 892 192 0 157 893 188 0 165 894 203 0 155 895 185 0 164 896 202 0 155 897 185 0 165 898 203 0 159 899 193 0 160 900 195 0 146 901 169 0 150 902 171 0 146 903 169 0 160 904 195 0 157 905 189 0 161 906 197 0 156 907 187 0 162 908 196 0 162 909 196 0 156 910 187 0 160 911 195 0 156 912 186 0 161 913 198 0 154 914 182 0 222 915 199 0 154 916 182 0 161 917 198 0 162 918 200 0 160 919 194 0 158 920 190 0 165 921 203 0 158 922 191 0 148 923 162 0 223 924 228 0 164 925 202 0 179 926 225 0 164 927 202 0 223 928 228 0 165 929 203 0 154 930 183 0 180 931 227 0 179 932 225 0 154 933 183 0 179 934 225 0 164 935 202 0 152 936 179 0 153 937 181 0 156 938 187 0 153 939 181 0 152 940 179 0 166 941 205 0 163 942 201 0 154 943 183 0 164 944 202 0 171 945 210 0 166 946 204 0 167 947 206 0 166 948 204 0 171 949 210 0 170 950 209 0 171 951 210 0 167 952 206 0 169 953 208 0 168 954 207 0 166 955 204 0 170 956 209 0 153 957 180 0 166 958 204 0 168 959 207 0 169 960 208 0 167 961 206 0 155 962 184 0 172 963 211 0 177 964 212 0 222 965 199 0 222 966 199 0 161 967 198 0 172 968 211 0 173 969 213 0 178 970 214 0 177 971 212 0 173 972 213 0 177 973 212 0 172 974 211 0 173 975 213 0 175 976 216 0 182 977 229 0 173 978 213 0 182 979 229 0 178 980 214 0 175 981 216 0 173 982 213 0 176 983 217 0 173 984 213 0 174 985 215 0 176 986 217 0 180 987 226 0 154 988 182 0 222 989 224 0 175 990 216 0 176 991 217 0 181 992 230 0 182 993 231 0 175 994 218 0 232 995 232 0 175 996 218 0 181 997 219 0 232 998 232 0 232 999 234 0 176 1000 198 0 370 1001 235 0 176 1002 198 0 232 1003 234 0 181 1004 219 0 165 1005 175 0 223 1006 237 0 158 1007 168 0 183 1008 236 0 158 1009 168 0 223 1010 237 0 162 1011 172 0 183 1012 247 0 233 1013 233 0 183 1014 247 0 162 1015 172 0 158 1016 246 0 187 1017 244 0 185 1018 239 0 186 1019 243 0 186 1020 243 0 185 1021 239 0 184 1022 240 0 191 1023 252 0 190 1024 250 0 185 1025 241 0 191 1026 252 0 185 1027 241 0 187 1028 245 0 189 1029 249 0 186 1030 242 0 184 1031 238 0 186 1032 242 0 189 1033 249 0 188 1034 248 0 190 1035 251 0 189 1036 249 0 184 1037 238 0 184 1038 238 0 185 1039 239 0 190 1040 251 0 190 1041 222 0 188 1042 220 0 189 1043 221 0 188 1044 220 0 190 1045 222 0 191 1046 223 0 187 1047 245 0 186 1048 243 0 188 1049 248 0 188 1050 248 0 191 1051 223 0 187 1052 245 0 193 1053 254 0 168 1054 207 0 192 1055 253 0 168 1056 207 0 193 1057 254 0 169 1058 208 0 195 1059 255 0 194 1060 256 0 170 1061 209 0 195 1062 255 0 170 1063 209 0 171 1064 210 0 195 1065 255 0 169 1066 208 0 193 1067 254 0 169 1068 208 0 195 1069 255 0 171 1070 210 0 192 1071 253 0 170 1072 209 0 194 1073 256 0 170 1074 209 0 192 1075 253 0 168 1076 207 0 154 1077 182 0 163 1078 177 0 193 1079 259 0 193 1080 259 0 163 1081 177 0 195 1082 260 0 163 1083 177 0 152 1084 178 0 195 1085 260 0 195 1086 260 0 152 1087 178 0 194 1088 257 0 152 1089 178 0 192 1090 258 0 194 1091 257 0 152 1092 178 0 156 1093 186 0 192 1094 258 0 156 1095 186 0 193 1096 259 0 192 1097 258 0 193 1098 259 0 156 1099 186 0 154 1100 182 0 197 1101 262 0 199 1102 264 0 198 1103 263 0 199 1104 264 0 197 1105 262 0 196 1106 261 0 200 1107 265 0 203 1108 268 0 201 1109 266 0 201 1110 266 0 203 1111 268 0 202 1112 267 0 204 1113 271 0 196 1114 269 0 200 1115 272 0 196 1116 269 0 204 1117 271 0 199 1118 270 0 207 1119 275 0 205 1120 273 0 208 1121 276 0 205 1122 273 0 207 1123 275 0 206 1124 274 0 207 1125 280 0 210 1126 279 0 209 1127 278 0 207 1128 280 0 209 1129 278 0 206 1130 277 0 200 1131 283 0 197 1132 281 0 203 1133 284 0 197 1134 281 0 200 1135 283 0 196 1136 282 0 209 1137 285 0 205 1138 287 0 206 1139 286 0 205 1140 287 0 209 1141 285 0 211 1142 288 0 208 1143 290 0 210 1144 292 0 207 1145 291 0 210 1146 292 0 208 1147 290 0 212 1148 289 0 212 1149 296 0 208 1150 295 0 205 1151 294 0 212 1152 296 0 205 1153 294 0 211 1154 293 0 213 1155 297 0 215 1156 299 0 214 1157 298 0 215 1158 299 0 213 1159 297 0 216 1160 300 0 217 1161 302 0 212 1162 296 0 211 1163 293 0 217 1164 302 0 211 1165 293 0 216 1166 301 0 218 1167 306 0 202 1168 305 0 198 1169 304 0 218 1170 306 0 198 1171 304 0 213 1172 303 0 213 1173 297 0 198 1174 263 0 199 1175 264 0 213 1176 297 0 199 1177 264 0 216 1178 300 0 204 1179 271 0 217 1180 302 0 216 1181 301 0 204 1182 271 0 216 1183 301 0 199 1184 270 0 203 1185 308 0 197 1186 307 0 202 1187 305 0 202 1188 305 0 197 1189 307 0 198 1190 304 0 219 1191 309 0 218 1192 306 0 220 1193 310 0 218 1194 306 0 219 1195 309 0 202 1196 305 0 220 1197 313 0 221 1198 311 0 222 1199 314 0 221 1200 311 0 220 1201 313 0 218 1202 312 0 219 1203 315 0 201 1204 266 0 202 1205 267 0 204 1206 271 0 200 1207 272 0 201 1208 316 0 217 1209 302 0 204 1210 271 0 223 1211 318 0 217 1212 302 0 223 1213 318 0 179 1214 317 0 221 1215 319 0 179 1216 317 0 180 1217 320 0 179 1218 317 0 221 1219 319 0 217 1220 302 0 210 1221 279 0 218 1222 306 0 213 1223 303 0 210 1224 279 0 213 1225 303 0 209 1226 278 0 212 1227 296 0 217 1228 302 0 221 1229 319 0 209 1230 285 0 224 1231 321 0 211 1232 288 0 224 1233 321 0 209 1234 285 0 225 1235 322 0 224 1236 321 0 215 1237 299 0 211 1238 288 0 214 1239 298 0 225 1240 322 0 209 1241 285 0 213 1242 297 0 214 1243 298 0 209 1244 285 0 215 1245 299 0 216 1246 300 0 211 1247 288 0 220 1248 313 0 222 1249 314 0 226 1250 323 0 226 1251 323 0 222 1252 314 0 177 1253 324 0 227 1254 325 0 177 1255 324 0 178 1256 326 0 177 1257 324 0 227 1258 325 0 226 1259 323 0 228 1260 327 0 227 1261 325 0 182 1262 328 0 178 1263 326 0 182 1264 328 0 227 1265 325 0 227 1266 325 0 228 1267 327 0 230 1268 330 0 227 1269 325 0 230 1270 330 0 229 1271 329 0 180 1272 331 0 222 1273 332 0 221 1274 311 0 228 1275 327 0 231 1276 333 0 230 1277 330 0 228 1278 335 0 182 1279 334 0 232 1280 337 0 228 1281 335 0 232 1282 337 0 231 1283 336 0 231 1284 336 0 370 1285 339 0 230 1286 313 0 370 1287 339 0 231 1288 336 0 232 1289 338 0 201 1290 277 0 183 1291 340 0 223 1292 341 0 201 1293 277 0 223 1294 341 0 204 1295 283 0 233 1296 344 0 183 1297 343 0 219 1298 281 0 219 1299 281 0 183 1300 343 0 201 1301 342 0 234 1302 345 0 237 1303 348 0 236 1304 347 0 234 1305 345 0 236 1306 347 0 235 1307 346 0 239 1308 351 0 238 1309 350 0 236 1310 352 0 235 1311 349 0 236 1312 352 0 238 1313 350 0 237 1314 355 0 234 1315 354 0 241 1316 356 0 240 1317 353 0 241 1318 356 0 234 1319 354 0 241 1320 356 0 239 1321 357 0 237 1322 355 0 237 1323 355 0 239 1324 357 0 236 1325 347 0 239 1326 358 0 240 1327 360 0 238 1328 359 0 240 1329 360 0 239 1330 358 0 241 1331 361 0 234 1332 345 0 235 1333 349 0 240 1334 353 0 240 1335 353 0 235 1336 349 0 238 1337 359 0 243 1338 363 0 214 1339 298 0 215 1340 299 0 214 1341 298 0 243 1342 363 0 242 1343 362 0 244 1344 364 0 225 1345 322 0 245 1346 365 0 225 1347 322 0 244 1348 364 0 224 1349 321 0 244 1350 364 0 215 1351 299 0 224 1352 321 0 215 1353 299 0 244 1354 364 0 243 1355 363 0 242 1356 362 0 225 1357 322 0 214 1358 298 0 225 1359 322 0 242 1360 362 0 245 1361 365 0 212 1362 289 0 221 1363 311 0 243 1364 366 0 212 1365 289 0 243 1366 366 0 244 1367 367 0 210 1368 292 0 212 1369 289 0 244 1370 367 0 210 1371 292 0 244 1372 367 0 245 1373 368 0 210 1374 292 0 242 1375 369 0 218 1376 312 0 242 1377 369 0 210 1378 292 0 245 1379 368 0 243 1380 366 0 221 1381 311 0 218 1382 312 0 243 1383 366 0 218 1384 312 0 242 1385 369 0 247 1386 371 145 248 1387 372 146 249 1388 373 147 248 1389 372 146 247 1390 371 145 246 1391 370 144 253 1392 377 151 252 1393 376 150 250 1394 374 148 253 1395 377 151 250 1396 374 148 251 1397 375 149 250 1398 380 148 247 1399 379 145 251 1400 381 149 247 1401 379 145 250 1402 380 148 246 1403 378 144 251 1404 384 149 249 1405 383 147 253 1406 385 151 249 1407 383 147 251 1408 384 149 247 1409 382 145 252 1410 389 150 253 1411 388 151 249 1412 386 147 252 1413 389 150 249 1414 386 147 248 1415 387 146 252 1416 392 150 248 1417 390 146 250 1418 393 148 250 1419 393 148 248 1420 390 146 246 1421 391 144 257 1422 397 155 255 1423 395 153 254 1424 394 152 254 1425 394 152 256 1426 396 154 257 1427 397 155 260 1428 400 158 259 1429 399 157 261 1430 401 159 259 1431 399 157 260 1432 400 158 258 1433 398 156 259 1434 405 157 258 1435 404 156 254 1436 402 152 259 1437 405 157 254 1438 402 152 255 1439 403 153 259 1440 408 157 257 1441 407 155 261 1442 409 159 257 1443 407 155 259 1444 408 157 255 1445 406 153 260 1446 413 158 261 1447 412 159 257 1448 410 155 260 1449 413 158 257 1450 410 155 256 1451 411 154 258 1452 417 156 260 1453 416 158 256 1454 414 154 258 1455 417 156 256 1456 414 154 254 1457 415 152 265 1458 420 163 264 1459 419 162 266 1460 421 164 264 1461 419 162 265 1462 420 163 263 1463 418 161 264 1464 425 162 263 1465 424 161 271 1466 422 169 271 1467 422 169 272 1468 423 170 264 1469 425 162 264 1470 428 162 273 1471 427 171 266 1472 429 164 273 1473 427 171 264 1474 428 162 272 1475 426 170 262 1476 431 160 266 1477 432 164 273 1478 430 171 266 1479 432 164 262 1480 431 160 265 1481 433 163 263 1482 437 161 265 1483 436 163 262 1484 434 160 262 1485 434 160 271 1486 435 169 263 1487 437 161 270 1488 441 168 268 1489 439 166 267 1490 438 165 268 1491 439 166 270 1492 441 168 269 1493 440 167 267 1494 445 165 272 1495 443 170 271 1496 442 169 272 1497 443 170 267 1498 445 165 268 1499 444 166 268 1500 449 166 273 1501 447 171 272 1502 446 170 273 1503 447 171 268 1504 449 166 269 1505 448 167 262 1506 451 160 273 1507 450 171 270 1508 452 168 270 1509 452 168 273 1510 450 171 269 1511 453 167 270 1512 457 168 267 1513 456 165 262 1514 454 160 262 1515 454 160 267 1516 456 165 271 1517 455 169 277 1518 461 175 275 1519 459 173 276 1520 460 174 275 1521 459 173 277 1522 461 175 274 1523 458 172 281 1524 465 179 278 1525 462 176 280 1526 464 178 278 1527 462 176 279 1528 463 177 280 1529 464 178 279 1530 469 177 276 1531 467 174 280 1532 468 178 276 1533 467 174 279 1534 469 177 277 1535 466 175 280 1536 473 178 275 1537 471 173 281 1538 472 179 275 1539 471 173 280 1540 473 178 276 1541 470 174 278 1542 476 176 281 1543 477 179 275 1544 474 173 278 1545 476 176 275 1546 474 173 274 1547 475 172 282 1548 479 180 284 1549 481 182 289 1550 478 187 283 1551 480 181 289 1552 478 187 284 1553 481 182 285 1554 482 183 286 1555 483 184 282 1556 479 180 284 1557 481 182 282 1558 479 180 286 1559 483 184 287 1560 484 185 286 1561 483 184 285 1562 482 183 286 1563 483 184 287 1564 484 185 288 1565 485 186 289 1566 486 187 288 1567 485 186 287 1568 484 185 288 1569 485 186 289 1570 486 187 283 1571 487 181 284 1572 481 182 290 1573 488 188 283 1574 480 181 290 1575 488 188 284 1576 481 182 291 1577 489 189 286 1578 483 184 292 1579 490 190 284 1580 481 182 284 1581 481 182 292 1582 490 190 291 1583 489 189 288 1584 485 186 292 1585 490 190 286 1586 483 184 292 1587 490 190 288 1588 485 186 293 1589 491 191 293 1590 491 191 283 1591 487 181 290 1592 492 188 283 1593 487 181 293 1594 491 191 288 1595 485 186 295 1596 495 193 301 1597 493 199 296 1598 496 194 301 1599 493 199 294 1600 494 192 296 1601 496 194 298 1602 498 196 294 1603 494 192 297 1604 497 195 294 1605 494 192 298 1606 498 196 296 1607 496 194 299 1608 499 197 298 1609 498 196 297 1610 497 195 298 1611 498 196 299 1612 499 197 300 1613 500 198 300 1614 500 198 301 1615 501 199 295 1616 502 193 301 1617 501 199 300 1618 500 198 299 1619 499 197 302 1620 503 200 296 1621 496 194 303 1622 504 201 296 1623 496 194 302 1624 503 200 295 1625 495 193 303 1626 504 201 298 1627 498 196 304 1628 505 202 298 1629 498 196 303 1630 504 201 296 1631 496 194 305 1632 506 203 298 1633 498 196 300 1634 500 198 298 1635 498 196 305 1636 506 203 304 1637 505 202 302 1638 507 200 300 1639 500 198 295 1640 502 193 300 1641 500 198 302 1642 507 200 305 1643 506 203 306 1644 508 204 303 1645 504 201 307 1646 509 205 303 1647 504 201 306 1648 508 204 302 1649 503 200 307 1650 509 205 304 1651 505 202 308 1652 510 206 304 1653 505 202 307 1654 509 205 303 1655 504 201 309 1656 511 207 304 1657 505 202 305 1658 506 203 304 1659 505 202 309 1660 511 207 308 1661 510 206 309 1662 511 207 305 1663 506 203 306 1664 512 204 305 1665 506 203 302 1666 507 200 306 1667 512 204 310 1668 513 208 306 1669 508 204 311 1670 514 209 306 1671 508 204 307 1672 509 205 311 1673 514 209 308 1674 510 206 312 1675 515 210 307 1676 509 205 307 1677 509 205 312 1678 515 210 311 1679 514 209 309 1680 511 207 312 1681 515 210 308 1682 510 206 312 1683 515 210 309 1684 511 207 313 1685 516 211 313 1686 516 211 306 1687 512 204 310 1688 517 208 306 1689 512 204 313 1690 516 211 309 1691 511 207 311 1692 514 209 315 1693 519 213 310 1694 513 208 314 1695 518 212 310 1696 513 208 315 1697 519 213 312 1698 515 210 316 1699 520 214 311 1700 514 209 311 1701 514 209 316 1702 520 214 315 1703 519 213 313 1704 516 211 316 1705 520 214 312 1706 515 210 316 1707 520 214 313 1708 516 211 317 1709 521 215 317 1710 521 215 310 1711 517 208 314 1712 522 212 310 1713 517 208 317 1714 521 215 313 1715 516 211 318 1716 523 216 291 1717 489 189 319 1718 524 217 291 1719 489 189 318 1720 523 216 290 1721 488 188 292 1722 490 190 319 1723 524 217 291 1724 489 189 319 1725 524 217 292 1726 490 190 320 1727 525 218 293 1728 491 191 321 1729 526 219 292 1730 490 190 321 1731 526 219 320 1732 525 218 292 1733 490 190 293 1734 491 191 318 1735 527 216 321 1736 526 219 318 1737 527 216 293 1738 491 191 290 1739 492 188 318 1740 523 216 319 1741 524 217 301 1742 493 199 301 1743 493 199 319 1744 524 217 294 1745 494 192 297 1746 497 195 294 1747 494 192 320 1748 525 218 319 1749 524 217 320 1750 525 218 294 1751 494 192 321 1752 526 219 299 1753 499 197 320 1754 525 218 299 1755 499 197 297 1756 497 195 320 1757 525 218 299 1758 499 197 321 1759 526 219 301 1760 501 199 301 1761 501 199 321 1762 526 219 318 1763 527 216 289 1764 478 187 325 1765 528 223 322 1766 529 220 289 1767 478 187 322 1768 529 220 282 1769 479 180 282 1770 479 180 322 1771 529 220 323 1772 530 221 282 1773 479 180 323 1774 530 221 285 1775 482 183 287 1776 484 185 323 1777 530 221 324 1778 531 222 323 1779 530 221 287 1780 484 185 285 1781 482 183 324 1782 531 222 289 1783 486 187 287 1784 484 185 289 1785 486 187 324 1786 531 222 325 1787 532 223 326 1788 533 224 322 1789 529 220 325 1790 528 223 322 1791 529 220 326 1792 533 224 327 1793 535 225 322 1794 529 220 327 1795 535 225 328 1796 536 226 322 1797 529 220 328 1798 536 226 323 1799 530 221 324 1800 531 222 328 1801 536 226 329 1802 537 227 328 1803 536 226 324 1804 531 222 323 1805 530 221 329 1806 537 227 325 1807 532 223 324 1808 531 222 325 1809 532 223 329 1810 537 227 326 1811 534 224 334 1812 539 232 335 1813 545 233 330 1814 538 228 330 1815 538 228 335 1816 545 233 331 1817 540 229 336 1818 546 234 332 1819 541 230 331 1820 540 229 336 1821 546 234 331 1822 540 229 335 1823 545 233 333 1824 542 231 336 1825 546 234 337 1826 547 235 336 1827 546 234 333 1828 542 231 332 1829 541 230 337 1830 547 235 330 1831 544 228 333 1832 542 231 330 1833 544 228 337 1834 547 235 334 1835 543 232 338 1836 548 236 335 1837 545 233 334 1838 539 232 335 1839 545 233 338 1840 548 236 339 1841 550 237 339 1842 550 237 336 1843 546 234 335 1844 545 233 336 1845 546 234 339 1846 550 237 340 1847 551 238 341 1848 552 239 337 1849 547 235 336 1850 546 234 341 1851 552 239 336 1852 546 234 340 1853 551 238 334 1854 543 232 337 1855 547 235 338 1856 549 236 337 1857 547 235 341 1858 552 239 338 1859 549 236 345 1860 553 243 339 1861 550 237 338 1862 548 236 339 1863 550 237 345 1864 553 243 342 1865 554 240 342 1866 554 240 340 1867 551 238 339 1868 550 237 340 1869 551 238 342 1870 554 240 343 1871 555 241 344 1872 556 242 341 1873 552 239 340 1874 551 238 344 1875 556 242 340 1876 551 238 343 1877 555 241 344 1878 556 242 345 1879 557 243 341 1880 552 239 341 1881 552 239 345 1882 557 243 338 1883 549 236 346 1884 559 244 345 1885 553 243 349 1886 558 247 345 1887 553 243 346 1888 559 244 342 1889 554 240 343 1890 555 241 342 1891 554 240 347 1892 560 245 342 1893 554 240 346 1894 559 244 347 1895 560 245 344 1896 556 242 347 1897 560 245 348 1898 561 246 347 1899 560 245 344 1900 556 242 343 1901 555 241 348 1902 561 246 345 1903 557 243 344 1904 556 242 345 1905 557 243 348 1906 561 246 349 1907 562 247 350 1908 564 248 349 1909 558 247 353 1910 563 251 349 1911 558 247 350 1912 564 248 346 1913 559 244 351 1914 565 249 347 1915 560 245 346 1916 559 244 346 1917 559 244 350 1918 564 248 351 1919 565 249 348 1920 561 246 351 1921 565 249 352 1922 566 250 351 1923 565 249 348 1924 561 246 347 1925 560 245 352 1926 566 250 349 1927 562 247 348 1928 561 246 349 1929 562 247 352 1930 566 250 353 1931 567 251 357 1932 568 255 327 1933 535 225 326 1934 533 224 327 1935 535 225 357 1936 568 255 354 1937 569 252 354 1938 569 252 328 1939 536 226 327 1940 535 225 328 1941 536 226 354 1942 569 252 355 1943 570 253 356 1944 571 254 329 1945 537 227 328 1946 536 226 356 1947 571 254 328 1948 536 226 355 1949 570 253 357 1950 572 255 329 1951 537 227 356 1952 571 254 329 1953 537 227 357 1954 572 255 326 1955 534 224 330 1956 538 228 354 1957 569 252 357 1958 568 255 354 1959 569 252 330 1960 538 228 331 1961 540 229 355 1962 570 253 354 1963 569 252 331 1964 540 229 355 1965 570 253 331 1966 540 229 332 1967 541 230 333 1968 542 231 356 1969 571 254 355 1970 570 253 333 1971 542 231 355 1972 570 253 332 1973 541 230 330 1974 544 228 356 1975 571 254 333 1976 542 231 356 1977 571 254 330 1978 544 228 357 1979 572 255 365 1980 580 263 358 1981 573 256 364 1982 579 262 358 1983 573 256 365 1984 580 263 362 1985 577 260 366 1986 581 264 362 1987 577 260 365 1988 580 263 362 1989 577 260 366 1990 581 264 363 1991 578 261 360 1992 575 258 361 1993 576 259 367 1994 582 265 360 1995 575 258 367 1996 582 265 368 1997 583 266 368 1998 583 266 359 1999 574 257 360 2000 575 258 359 2001 574 257 368 2002 583 266 369 2003 584 267 367 2004 582 265 361 2005 576 259 363 2006 578 261 367 2007 582 265 363 2008 578 261 366 2009 581 264 367 2010 582 265 365 2011 580 263 368 2012 583 266 365 2013 580 263 367 2014 582 265 366 2015 581 264 369 2016 584 267 368 2017 583 266 365 2018 580 263 369 2019 584 267 365 2020 580 263 364 2021 579 262 359 2022 574 257 369 2023 584 267 364 2024 579 262 359 2025 574 257 364 2026 579 262 358 2027 573 256 360 2028 575 258 359 2029 574 257 358 2030 573 256 360 2031 575 258 358 2032 573 256 362 2033 577 260 361 2034 576 259 360 2035 575 258 362 2036 577 260 361 2037 576 259 362 2038 577 260 363 2039 578 261

+
+
+
+ + + 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.0000001.000000 + 30.0000000.0000003.333333 + + + + + +
diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_PalletJackB_01/meshes/aws_robomaker_warehouse_PalletJackB_01_visual.DAE b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_PalletJackB_01/meshes/aws_robomaker_warehouse_PalletJackB_01_visual.DAE new file mode 100755 index 0000000..75f5487 --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_PalletJackB_01/meshes/aws_robomaker_warehouse_PalletJackB_01_visual.DAE @@ -0,0 +1,14389 @@ + + + FBX COLLADA exporter2019-05-27T02:24:52Z2019-05-27T02:24:52ZZ_UP + + + ../materials/textures/aws_robomaker_warehouse_PalletJackB_01.png + + + ../materials/textures/aws_robomaker_warehouse_PalletJackB_02.png + + + + + + + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + +0.643753 0.152121 0.138676 +0.643717 0.204227 0.138676 +0.643717 0.204227 0.106815 +0.643753 0.152121 0.106815 +0.635237 0.215456 0.138676 +0.634941 0.140295 0.138676 +0.634941 0.140295 0.106815 +0.635237 0.215456 0.106815 +0.618441 0.134194 0.138676 +0.618356 0.221812 0.138676 +0.618441 0.134194 0.106815 +0.618356 0.221812 0.106815 +0.583879 0.232880 0.138676 +0.582795 0.122474 0.138676 +0.582795 0.122474 0.106815 +0.583879 0.232880 0.106815 +0.528483 0.250665 0.138676 +0.526230 0.103876 0.138676 +0.526230 0.103876 0.084320 +0.528483 0.250665 0.084320 +0.510917 0.164164 0.138676 +0.505164 0.154273 0.138676 +0.335472 0.105908 0.084320 +0.335472 0.105908 0.138676 +-0.263088 0.247964 0.138676 +-0.263088 0.247964 0.084320 +0.336539 0.250010 0.084320 +0.336539 0.250010 0.138676 +-0.262971 0.112282 0.138676 +-0.262971 0.112282 0.084320 +0.374266 0.164164 0.084320 +0.374266 0.164164 0.138676 +0.371547 0.178185 0.138676 +0.371547 0.178185 0.084320 +0.374266 0.192207 0.138676 +0.374266 0.192207 0.084320 +0.380019 0.154273 0.084320 +0.380019 0.154273 0.138676 +0.380019 0.202097 0.138676 +0.380019 0.202097 0.084320 +0.497982 0.150142 0.084320 +0.497982 0.150142 0.138676 +0.387201 0.150142 0.138676 +0.387201 0.150142 0.084320 +0.505164 0.154273 0.084320 +0.510917 0.164164 0.084320 +0.505164 0.202097 0.084320 +0.505164 0.202097 0.138676 +0.510917 0.192207 0.138676 +0.510917 0.192207 0.084320 +0.513636 0.178185 0.084320 +0.513636 0.178185 0.138676 +0.497982 0.206228 0.138676 +0.387201 0.206228 0.138676 +0.497982 0.206228 0.084320 +0.387201 0.206228 0.084320 +-0.127360 0.244130 0.138858 +-0.248526 0.244130 0.138858 +-0.151246 0.023863 0.587088 +-0.224641 0.031921 0.587088 +-0.146783 0.048146 0.503330 +-0.229104 0.054287 0.503330 +-0.345318 0.040991 0.538917 +-0.345318 0.040991 0.612404 +-0.365603 0.021446 0.538917 +-0.379128 0.000397 0.538917 +-0.325032 0.048508 0.612404 +-0.365603 0.021446 0.612404 +-0.379128 0.000397 0.612404 +-0.325032 0.048508 0.538917 +-0.134185 0.028963 0.538917 +-0.134185 0.028963 0.606870 +-0.113900 0.000397 0.538917 +-0.167995 0.048508 0.611995 +-0.113900 0.000397 0.596112 +-0.167995 0.048508 0.538917 +-0.359436 0.031947 0.291840 +-0.354228 0.033659 0.287470 +-0.344224 0.033659 0.293246 +-0.345405 0.031947 0.299941 +-0.364977 0.031947 0.276615 +-0.358179 0.033659 0.276615 +-0.359436 0.031947 0.261391 +-0.354228 0.033659 0.265760 +-0.345405 0.031947 0.253290 +-0.344224 0.033659 0.259985 +-0.329449 0.031947 0.256103 +-0.332848 0.033659 0.261990 +-0.319035 0.031947 0.268514 +-0.325423 0.033659 0.270839 +-0.319035 0.031947 0.284716 +-0.325423 0.033659 0.282391 +-0.329449 0.031947 0.297127 +-0.332848 0.033659 0.291240 +-0.348386 0.070428 0.282568 +-0.342900 0.070428 0.285736 +-0.343781 0.070428 0.290734 +-0.352274 0.070428 0.285831 +-0.350553 0.070428 0.276615 +-0.355628 0.070428 0.276615 +-0.348386 0.070428 0.270662 +-0.352274 0.070428 0.267400 +-0.342900 0.070428 0.267495 +-0.343781 0.070428 0.262496 +-0.336661 0.070428 0.268595 +-0.334123 0.070428 0.264199 +-0.332589 0.070428 0.273448 +-0.327820 0.070428 0.271712 +-0.332589 0.070428 0.279783 +-0.327820 0.070428 0.281519 +-0.336661 0.070428 0.284636 +-0.334123 0.070428 0.289031 +-0.342900 0.074232 0.285736 +-0.348386 0.074232 0.282568 +-0.332589 0.074232 0.279783 +-0.336661 0.074232 0.284636 +-0.350553 0.074232 0.276615 +-0.348386 0.074232 0.270662 +-0.342900 0.074232 0.267495 +-0.336661 0.074232 0.268595 +-0.332589 0.074232 0.273448 +-0.374815 0.057187 0.267573 +-0.364105 0.057187 0.304235 +-0.227722 0.057187 0.264932 +-0.227722 0.057187 0.209872 +-0.374815 0.067899 0.267573 +-0.364105 0.067899 0.304235 +-0.376572 0.067899 0.274998 +-0.227722 0.067899 0.209872 +-0.227722 0.067899 0.264932 +-0.373342 0.057187 0.294117 +-0.375835 0.057187 0.288270 +-0.375835 0.067899 0.288270 +-0.373342 0.067899 0.294117 +-0.376572 0.057187 0.274998 +-0.146783 -0.015163 0.503330 +-0.229104 -0.015163 0.503330 +-0.151246 -0.015163 0.587088 +-0.224641 -0.015163 0.587088 +-0.113900 -0.015163 0.538917 +-0.140948 -0.015163 0.538917 +-0.379128 -0.015163 0.612404 +-0.140948 -0.015163 0.609441 +-0.352080 -0.015163 0.538917 +0.643753 -0.182447 0.138676 +0.643717 -0.234553 0.138676 +0.643753 -0.182447 0.106815 +0.643717 -0.234553 0.106815 +0.635237 -0.245782 0.138676 +0.634941 -0.170621 0.138676 +0.634941 -0.170621 0.106815 +0.635237 -0.245782 0.106815 +0.618356 -0.252138 0.138676 +0.618441 -0.164520 0.138676 +0.618441 -0.164520 0.106815 +0.618356 -0.252138 0.106815 +0.583879 -0.263206 0.138676 +0.582795 -0.152800 0.138676 +0.582795 -0.152800 0.106815 +0.583879 -0.263206 0.106815 +0.528483 -0.280991 0.138676 +0.526230 -0.134202 0.138676 +0.526230 -0.134202 0.084320 +0.528483 -0.280991 0.084320 +0.510917 -0.194490 0.138676 +0.505164 -0.184599 0.138676 +0.335472 -0.136234 0.138676 +0.335472 -0.136234 0.084320 +0.336539 -0.280336 0.138676 +0.336539 -0.280336 0.084320 +-0.263088 -0.278290 0.084320 +-0.263088 -0.278290 0.138676 +-0.262971 -0.142608 0.138676 +-0.262971 -0.142608 0.084320 +0.374266 -0.194490 0.084320 +0.371547 -0.208511 0.084320 +0.371547 -0.208511 0.138676 +0.374266 -0.194490 0.138676 +0.374266 -0.222533 0.084320 +0.374266 -0.222533 0.138676 +0.380019 -0.184599 0.138676 +0.380019 -0.184599 0.084320 +0.380019 -0.232423 0.084320 +0.380019 -0.232423 0.138676 +0.497982 -0.180468 0.084320 +0.387201 -0.180468 0.084320 +0.387201 -0.180468 0.138676 +0.497982 -0.180468 0.138676 +0.510917 -0.194490 0.084320 +0.505164 -0.184599 0.084320 +0.505164 -0.232423 0.084320 +0.510917 -0.222533 0.084320 +0.510917 -0.222533 0.138676 +0.505164 -0.232423 0.138676 +0.513636 -0.208511 0.084320 +0.513636 -0.208511 0.138676 +0.387201 -0.236554 0.138676 +0.497982 -0.236554 0.138676 +0.387201 -0.236554 0.084320 +0.497982 -0.236554 0.084320 +-0.127360 -0.274456 0.138858 +-0.146783 -0.078472 0.503330 +-0.127360 -0.015163 0.138858 +-0.248526 -0.274456 0.138858 +-0.229104 -0.084613 0.503330 +-0.151246 -0.054189 0.587088 +-0.224641 -0.062247 0.587088 +-0.134185 -0.059289 0.538917 +-0.113900 -0.030723 0.538917 +-0.127423 -0.015163 0.538917 +-0.325032 -0.078834 0.612404 +-0.167995 -0.078834 0.611995 +-0.167995 -0.078834 0.538917 +-0.325032 -0.078834 0.538917 +-0.345318 -0.071317 0.538917 +-0.345318 -0.071317 0.612404 +-0.365603 -0.051772 0.538917 +-0.379128 -0.030723 0.538917 +-0.379128 -0.030723 0.612404 +-0.365603 -0.051772 0.612404 +-0.167995 -0.015163 0.611995 +-0.113900 -0.030723 0.596112 +-0.134185 -0.059289 0.606870 +-0.167995 -0.015163 0.538917 +-0.325032 -0.015163 0.538917 +-0.379128 -0.015163 0.538917 +-0.345405 -0.062273 0.299941 +-0.344224 -0.063985 0.293246 +-0.354228 -0.063985 0.287470 +-0.359436 -0.062273 0.291840 +-0.358179 -0.063985 0.276615 +-0.364977 -0.062273 0.276615 +-0.354228 -0.063985 0.265760 +-0.359436 -0.062273 0.261391 +-0.344224 -0.063985 0.259985 +-0.345405 -0.062273 0.253290 +-0.332848 -0.063985 0.261990 +-0.329449 -0.062273 0.256103 +-0.325423 -0.063985 0.270839 +-0.319035 -0.062273 0.268514 +-0.325423 -0.063985 0.282391 +-0.319035 -0.062273 0.284716 +-0.332848 -0.063985 0.291240 +-0.329449 -0.062273 0.297127 +-0.348386 -0.100754 0.282568 +-0.352274 -0.100754 0.285831 +-0.343781 -0.100754 0.290734 +-0.342900 -0.100754 0.285736 +-0.350553 -0.100754 0.276615 +-0.355628 -0.100754 0.276615 +-0.348386 -0.100754 0.270662 +-0.352274 -0.100754 0.267400 +-0.342900 -0.100754 0.267495 +-0.343781 -0.100754 0.262496 +-0.336661 -0.100754 0.268595 +-0.334123 -0.100754 0.264199 +-0.332589 -0.100754 0.273448 +-0.327820 -0.100754 0.271712 +-0.332589 -0.100754 0.279783 +-0.327820 -0.100754 0.281519 +-0.336661 -0.100754 0.284636 +-0.334123 -0.100754 0.289031 +-0.336661 -0.104558 0.284636 +-0.332589 -0.104558 0.279783 +-0.348386 -0.104558 0.282568 +-0.342900 -0.104558 0.285736 +-0.350553 -0.104558 0.276615 +-0.348386 -0.104558 0.270662 +-0.342900 -0.104558 0.267495 +-0.336661 -0.104558 0.268595 +-0.332589 -0.104558 0.273448 +-0.374815 -0.087513 0.267573 +-0.227722 -0.087513 0.209872 +-0.227722 -0.087513 0.264932 +-0.364105 -0.087513 0.304235 +-0.376572 -0.098225 0.274998 +-0.364105 -0.098225 0.304235 +-0.374815 -0.098225 0.267573 +-0.227722 -0.098225 0.209872 +-0.227722 -0.098225 0.264932 +-0.373342 -0.098225 0.294117 +-0.375835 -0.098225 0.288270 +-0.375835 -0.087513 0.288270 +-0.373342 -0.087513 0.294117 +-0.376572 -0.087513 0.274998 +-0.248526 -0.015163 0.138858 +-0.325032 -0.015163 0.612404 +-0.365603 -0.015163 0.612404 +-0.113900 -0.015163 0.596112 +-0.394908 -0.098469 0.244618 +-0.434242 -0.098469 0.237682 +-0.468833 -0.098469 0.217711 +-0.494506 -0.098469 0.187114 +-0.508167 -0.098469 0.149582 +-0.508167 -0.098469 0.109640 +-0.494506 -0.098469 0.072108 +-0.468833 -0.098469 0.041511 +-0.434242 -0.098469 0.021540 +-0.394908 -0.098469 0.014605 +-0.355573 -0.098469 0.021540 +-0.320983 -0.098469 0.041511 +-0.295309 -0.098469 0.072108 +-0.281648 -0.098469 0.109640 +-0.281648 -0.098469 0.149582 +-0.295309 -0.098469 0.187114 +-0.320983 -0.098469 0.217711 +-0.355573 -0.098469 0.237682 +-0.394908 -0.073594 0.244618 +-0.434242 -0.073594 0.237682 +-0.468833 -0.073594 0.217711 +-0.494506 -0.073594 0.187114 +-0.508167 -0.073594 0.149582 +-0.508167 -0.073594 0.109640 +-0.494506 -0.073594 0.072108 +-0.468833 -0.073594 0.041511 +-0.434242 -0.073594 0.021540 +-0.394908 -0.073594 0.014605 +-0.355573 -0.073594 0.021540 +-0.320983 -0.073594 0.041511 +-0.295309 -0.073594 0.072108 +-0.281648 -0.073594 0.109640 +-0.281648 -0.073594 0.149582 +-0.295309 -0.073594 0.187114 +-0.320983 -0.073594 0.217711 +-0.355573 -0.073594 0.237682 +-0.430983 -0.073594 0.227496 +-0.394907 -0.073594 0.233853 +-0.358832 -0.073594 0.227496 +-0.327219 -0.073594 0.209257 +-0.303891 -0.073594 0.181479 +-0.291549 -0.073594 0.147597 +-0.291549 -0.073594 0.111625 +-0.303892 -0.073594 0.077743 +-0.327219 -0.073594 0.049965 +-0.358832 -0.073594 0.031726 +-0.394908 -0.073594 0.025369 +-0.430984 -0.073594 0.031726 +-0.462597 -0.073594 0.049965 +-0.485924 -0.073594 0.077743 +-0.498267 -0.073594 0.111625 +-0.498267 -0.073594 0.147596 +-0.485924 -0.073594 0.181479 +-0.462597 -0.073594 0.209257 +-0.394907 -0.045685 0.233853 +-0.430984 -0.045685 0.227496 +-0.462596 -0.045685 0.209258 +-0.485924 -0.045685 0.181479 +-0.498267 -0.045685 0.147597 +-0.498267 -0.045685 0.111625 +-0.485924 -0.045685 0.077743 +-0.462597 -0.045685 0.049965 +-0.430984 -0.045685 0.031726 +-0.394908 -0.045685 0.025369 +-0.358832 -0.045685 0.031726 +-0.327219 -0.045685 0.049965 +-0.303892 -0.045685 0.077743 +-0.291549 -0.045685 0.111625 +-0.291549 -0.045685 0.147597 +-0.303892 -0.045685 0.181479 +-0.327219 -0.045685 0.209258 +-0.358832 -0.045685 0.227496 +-0.434242 0.043268 0.237682 +-0.434242 0.068143 0.237682 +-0.394908 0.068143 0.244618 +-0.394908 0.043268 0.244618 +-0.468833 0.043268 0.217711 +-0.468833 0.068143 0.217711 +-0.494506 0.043268 0.187114 +-0.494506 0.068143 0.187114 +-0.508167 0.043268 0.149582 +-0.508167 0.068143 0.149582 +-0.508167 0.043268 0.109640 +-0.508167 0.068143 0.109640 +-0.494506 0.043268 0.072108 +-0.494506 0.068143 0.072108 +-0.468833 0.043268 0.041511 +-0.468833 0.068143 0.041511 +-0.434242 0.043268 0.021540 +-0.434242 0.068143 0.021540 +-0.394908 0.043268 0.014605 +-0.394908 0.068143 0.014605 +-0.355573 0.043268 0.021540 +-0.355573 0.068143 0.021540 +-0.320983 0.043268 0.041511 +-0.320983 0.068143 0.041511 +-0.295309 0.043268 0.072108 +-0.295309 0.068143 0.072108 +-0.281648 0.043268 0.109640 +-0.281648 0.068143 0.109640 +-0.281648 0.043268 0.149582 +-0.281648 0.068143 0.149582 +-0.295309 0.043268 0.187114 +-0.295309 0.068143 0.187114 +-0.320983 0.043268 0.217711 +-0.320983 0.068143 0.217711 +-0.355573 0.043268 0.237682 +-0.355573 0.068143 0.237682 +-0.394907 0.043268 0.233853 +-0.430983 0.043268 0.227496 +-0.358832 0.043268 0.227496 +-0.327219 0.043268 0.209257 +-0.303891 0.043268 0.181479 +-0.291549 0.043268 0.147597 +-0.291549 0.043268 0.111625 +-0.303892 0.043268 0.077743 +-0.327219 0.043268 0.049965 +-0.358832 0.043268 0.031726 +-0.394908 0.043268 0.025369 +-0.430984 0.043268 0.031726 +-0.462597 0.043268 0.049965 +-0.485924 0.043268 0.077743 +-0.498267 0.043268 0.111625 +-0.498267 0.043268 0.147596 +-0.485924 0.043268 0.181479 +-0.462597 0.043268 0.209257 +-0.430984 0.015359 0.227496 +-0.394907 0.015359 0.233853 +-0.462596 0.015359 0.209258 +-0.485924 0.015359 0.181479 +-0.498267 0.015359 0.147597 +-0.498267 0.015359 0.111625 +-0.485924 0.015359 0.077743 +-0.462597 0.015359 0.049965 +-0.430984 0.015359 0.031726 +-0.394908 0.015359 0.025369 +-0.358832 0.015359 0.031726 +-0.327219 0.015359 0.049965 +-0.303892 0.015359 0.077743 +-0.291549 0.015359 0.111625 +-0.291549 0.015359 0.147597 +-0.303892 0.015359 0.181479 +-0.327219 0.015359 0.209258 +-0.358832 0.015359 0.227496 +0.423930 0.168194 0.126336 +0.423930 0.188551 0.126336 +0.443215 0.188551 0.129734 +0.443215 0.168194 0.129734 +0.407032 0.168194 0.116587 +0.407032 0.188551 0.116587 +0.394562 0.168194 0.101738 +0.394562 0.188551 0.101738 +0.387964 0.168194 0.083626 +0.387964 0.188551 0.083626 +0.387964 0.168194 0.064398 +0.387964 0.188551 0.064398 +0.394562 0.168194 0.046287 +0.394562 0.188551 0.046287 +0.407032 0.168194 0.031438 +0.407032 0.188551 0.031438 +0.423930 0.168194 0.021688 +0.423930 0.188551 0.021688 +0.443214 0.168194 0.018290 +0.443214 0.188551 0.018290 +0.462499 0.168194 0.021688 +0.462499 0.188551 0.021688 +0.479397 0.168194 0.031438 +0.479397 0.188551 0.031438 +0.491867 0.168194 0.046287 +0.491867 0.188551 0.046287 +0.498464 0.168194 0.064398 +0.498464 0.188551 0.064398 +0.498465 0.168194 0.083626 +0.498464 0.188551 0.083626 +0.491867 0.168194 0.101738 +0.491867 0.188551 0.101738 +0.479397 0.168194 0.116587 +0.479397 0.188551 0.116587 +0.462498 0.168194 0.126336 +0.462499 0.188551 0.126336 +0.422188 0.188551 0.131781 +0.422188 0.197622 0.131781 +0.443214 0.197622 0.135488 +0.443214 0.188551 0.135489 +0.443214 0.168194 0.135489 +0.443214 0.159123 0.135489 +0.422188 0.159123 0.131781 +0.422188 0.168194 0.131781 +0.403698 0.188551 0.121106 +0.403698 0.197622 0.121106 +0.403698 0.159123 0.121106 +0.403698 0.168194 0.121106 +0.389974 0.188551 0.104750 +0.389974 0.197622 0.104750 +0.389974 0.159123 0.104750 +0.389974 0.168194 0.104750 +0.382672 0.188551 0.084688 +0.382672 0.197622 0.084688 +0.382672 0.159123 0.084688 +0.382672 0.168194 0.084688 +0.382672 0.188551 0.063337 +0.382672 0.197622 0.063337 +0.382672 0.159123 0.063337 +0.382672 0.168194 0.063337 +0.389974 0.188551 0.043274 +0.389974 0.197622 0.043274 +0.389974 0.159123 0.043274 +0.389974 0.168194 0.043274 +0.403698 0.188551 0.026919 +0.403698 0.197622 0.026919 +0.403698 0.159123 0.026919 +0.403698 0.168194 0.026919 +0.422188 0.188551 0.016244 +0.422188 0.197622 0.016244 +0.422188 0.159123 0.016244 +0.422188 0.168194 0.016244 +0.443214 0.188551 0.012536 +0.443214 0.197622 0.012536 +0.443214 0.159123 0.012536 +0.443214 0.168194 0.012536 +0.464240 0.188551 0.016244 +0.464240 0.197622 0.016244 +0.464241 0.159123 0.016244 +0.464240 0.168194 0.016244 +0.482730 0.188551 0.026919 +0.482730 0.197622 0.026919 +0.482731 0.159123 0.026919 +0.482730 0.168194 0.026919 +0.496454 0.188551 0.043274 +0.496454 0.197622 0.043274 +0.496454 0.159123 0.043274 +0.496454 0.168194 0.043274 +0.503757 0.188551 0.063337 +0.503757 0.197622 0.063337 +0.503757 0.159123 0.063337 +0.503757 0.168194 0.063337 +0.503757 0.188551 0.084688 +0.503757 0.197622 0.084688 +0.503757 0.159123 0.084688 +0.503757 0.168194 0.084688 +0.496454 0.188551 0.104750 +0.496454 0.197622 0.104750 +0.496454 0.159123 0.104750 +0.496454 0.168194 0.104750 +0.482730 0.188551 0.121106 +0.482730 0.197622 0.121106 +0.482731 0.159123 0.121106 +0.482730 0.168194 0.121106 +0.464240 0.188551 0.131781 +0.464240 0.197622 0.131781 +0.464241 0.159123 0.131781 +0.464240 0.168194 0.131781 +0.443215 -0.198520 0.129734 +0.443215 -0.218877 0.129734 +0.423930 -0.218877 0.126336 +0.423930 -0.198520 0.126336 +0.407032 -0.218877 0.116587 +0.407032 -0.198520 0.116587 +0.394562 -0.218877 0.101738 +0.394562 -0.198520 0.101738 +0.387964 -0.218877 0.083626 +0.387964 -0.198520 0.083626 +0.387964 -0.218877 0.064398 +0.387964 -0.198520 0.064398 +0.394562 -0.218877 0.046287 +0.394562 -0.198520 0.046287 +0.407032 -0.218877 0.031438 +0.407032 -0.198520 0.031438 +0.423930 -0.218877 0.021688 +0.423930 -0.198520 0.021688 +0.443214 -0.218877 0.018290 +0.443214 -0.198520 0.018290 +0.462499 -0.218877 0.021688 +0.462499 -0.198520 0.021688 +0.479397 -0.218877 0.031438 +0.479397 -0.198520 0.031438 +0.491867 -0.218877 0.046287 +0.491867 -0.198520 0.046287 +0.498464 -0.218877 0.064398 +0.498464 -0.198520 0.064398 +0.498464 -0.218877 0.083626 +0.498465 -0.198520 0.083626 +0.491867 -0.218877 0.101738 +0.491867 -0.198520 0.101738 +0.479397 -0.218877 0.116587 +0.479397 -0.198520 0.116587 +0.462499 -0.218877 0.126336 +0.462498 -0.198520 0.126336 +0.443214 -0.218877 0.135489 +0.443214 -0.227948 0.135488 +0.422188 -0.227948 0.131781 +0.422188 -0.218877 0.131781 +0.422188 -0.198520 0.131781 +0.422188 -0.189449 0.131781 +0.443214 -0.189449 0.135489 +0.443214 -0.198520 0.135489 +0.403698 -0.227948 0.121106 +0.403698 -0.218877 0.121106 +0.403698 -0.198520 0.121106 +0.403698 -0.189449 0.121106 +0.389974 -0.227948 0.104750 +0.389974 -0.218877 0.104750 +0.389974 -0.198520 0.104750 +0.389974 -0.189449 0.104750 +0.382672 -0.227948 0.084688 +0.382672 -0.218877 0.084688 +0.382672 -0.198520 0.084688 +0.382672 -0.189449 0.084688 +0.382672 -0.227948 0.063337 +0.382672 -0.218877 0.063337 +0.382672 -0.198520 0.063337 +0.382672 -0.189449 0.063337 +0.389974 -0.227948 0.043274 +0.389974 -0.218877 0.043274 +0.389974 -0.198520 0.043274 +0.389974 -0.189449 0.043274 +0.403698 -0.227948 0.026919 +0.403698 -0.218877 0.026919 +0.403698 -0.198520 0.026919 +0.403698 -0.189449 0.026919 +0.422188 -0.227948 0.016244 +0.422188 -0.218877 0.016244 +0.422188 -0.198520 0.016244 +0.422188 -0.189449 0.016244 +0.443214 -0.227948 0.012536 +0.443214 -0.218877 0.012536 +0.443214 -0.198520 0.012536 +0.443214 -0.189449 0.012536 +0.464240 -0.227948 0.016244 +0.464240 -0.218877 0.016244 +0.464240 -0.198520 0.016244 +0.464241 -0.189449 0.016244 +0.482730 -0.227948 0.026919 +0.482730 -0.218877 0.026919 +0.482730 -0.198520 0.026919 +0.482731 -0.189449 0.026919 +0.496454 -0.227948 0.043274 +0.496454 -0.218877 0.043274 +0.496454 -0.198520 0.043274 +0.496454 -0.189449 0.043274 +0.503757 -0.227948 0.063337 +0.503757 -0.218877 0.063337 +0.503757 -0.198520 0.063337 +0.503757 -0.189449 0.063337 +0.503757 -0.227948 0.084688 +0.503757 -0.218877 0.084688 +0.503757 -0.198520 0.084688 +0.503757 -0.189449 0.084688 +0.496454 -0.227948 0.104750 +0.496454 -0.218877 0.104750 +0.496454 -0.198520 0.104750 +0.496454 -0.189449 0.104750 +0.482730 -0.227948 0.121106 +0.482730 -0.218877 0.121106 +0.482730 -0.198520 0.121106 +0.482731 -0.189449 0.121106 +0.464240 -0.227948 0.131781 +0.464240 -0.218877 0.131781 +0.464240 -0.198520 0.131781 +0.464241 -0.189449 0.131781 +-0.347868 0.022133 0.330373 +-0.370303 0.009180 0.330373 +-0.379163 -0.015163 0.330373 +-0.370303 -0.039506 0.330373 +-0.347868 -0.052459 0.330373 +-0.322356 -0.047960 0.330373 +-0.305704 -0.028116 0.330373 +-0.305704 -0.002210 0.330373 +-0.322356 0.017634 0.330373 +-0.347868 0.022133 0.508813 +-0.370303 0.009180 0.508813 +-0.379163 -0.015163 0.508813 +-0.370303 -0.039506 0.508813 +-0.347868 -0.052459 0.508813 +-0.322356 -0.047960 0.508813 +-0.305704 -0.028116 0.508813 +-0.305704 -0.002210 0.508813 +-0.322356 0.017634 0.508813 +-0.345439 0.008356 0.508813 +-0.359586 0.000188 0.508813 +-0.365174 -0.015163 0.508813 +-0.359586 -0.030514 0.508813 +-0.345439 -0.038682 0.508813 +-0.329351 -0.035845 0.508813 +-0.318850 -0.023331 0.508813 +-0.318850 -0.006995 0.508813 +-0.329351 0.005519 0.508813 +-0.345439 0.008356 0.551350 +-0.359586 0.000188 0.551350 +-0.365174 -0.015163 0.551350 +-0.359586 -0.030514 0.551350 +-0.345439 -0.038682 0.551350 +-0.329351 -0.035845 0.551350 +-0.318850 -0.023331 0.551350 +-0.318850 -0.006995 0.551350 +-0.329351 0.005519 0.551350 +-0.344371 0.002302 0.330373 +-0.354877 -0.003763 0.330373 +-0.359026 -0.015163 0.330373 +-0.354877 -0.026563 0.330373 +-0.344371 -0.032628 0.330373 +-0.332424 -0.030522 0.330373 +-0.324627 -0.021229 0.330373 +-0.324627 -0.009097 0.330373 +-0.332424 0.000196 0.330373 +-0.344371 0.002302 0.113822 +-0.332424 0.000196 0.113822 +-0.324627 -0.009097 0.113822 +-0.324627 -0.021229 0.113822 +-0.332424 -0.030522 0.113822 +-0.344371 -0.032628 0.113822 +-0.354877 -0.026563 0.113822 +-0.359026 -0.015163 0.113822 +-0.354877 -0.003763 0.113822 +-0.413614 0.017520 0.516718 +-0.413614 -0.047846 0.516718 +-0.431833 0.002858 0.976774 +-0.431833 -0.033184 0.976774 +-0.451580 0.017520 0.516718 +-0.451580 -0.047846 0.516718 +-0.449829 0.002858 0.976774 +-0.449829 -0.033184 0.976774 +-0.442724 -0.068235 0.956731 +-0.435185 -0.068356 0.958751 +-0.433166 -0.068808 0.966291 +-0.438684 -0.015163 0.974951 +-0.438684 -0.069141 0.971810 +-0.444743 -0.069108 0.971269 +-0.448242 -0.068808 0.966291 +-0.447700 -0.068444 0.960230 +-0.447700 -0.015163 0.963374 +-0.442724 -0.097186 0.952555 +-0.435185 -0.097590 0.954535 +-0.433166 -0.099095 0.961925 +-0.438684 -0.100197 0.967335 +-0.444743 -0.100089 0.966804 +-0.448242 -0.099095 0.961925 +-0.447700 -0.097885 0.955984 +-0.435185 -0.134554 0.941584 +-0.433166 -0.140159 0.946633 +-0.438684 -0.144262 0.950330 +-0.446222 -0.142761 0.948977 +-0.448242 -0.137155 0.943927 +-0.442724 -0.133052 0.940230 +-0.442724 -0.139014 0.928059 +-0.435185 -0.140947 0.928670 +-0.433166 -0.148164 0.930949 +-0.438684 -0.153447 0.932618 +-0.446222 -0.151513 0.932007 +-0.448242 -0.144297 0.929728 +-0.442724 -0.141962 0.914640 +-0.435185 -0.143973 0.914897 +-0.433166 -0.151479 0.915860 +-0.438684 -0.156974 0.916565 +-0.446222 -0.154963 0.916307 +-0.448242 -0.147456 0.915344 +-0.442724 -0.142520 0.900295 +-0.435185 -0.144547 0.900129 +-0.433166 -0.152115 0.899510 +-0.438684 -0.157656 0.899057 +-0.446222 -0.155628 0.899222 +-0.448242 -0.148060 0.899842 +-0.442724 -0.140136 0.888675 +-0.435185 -0.142028 0.887846 +-0.433166 -0.149088 0.884753 +-0.438684 -0.154257 0.882489 +-0.446222 -0.152365 0.883317 +-0.448242 -0.145305 0.886410 +-0.442724 -0.134062 0.880228 +-0.435185 -0.135516 0.878789 +-0.433166 -0.140941 0.873423 +-0.438684 -0.144911 0.869493 +-0.446222 -0.143458 0.870932 +-0.448242 -0.138034 0.876299 +-0.442724 -0.121561 0.871032 +-0.435185 -0.122714 0.869373 +-0.433166 -0.127016 0.863180 +-0.438684 -0.130164 0.858645 +-0.446222 -0.129012 0.860305 +-0.448242 -0.124711 0.866498 +-0.442724 -0.019024 0.803887 +-0.435185 -0.020130 0.802197 +-0.433166 -0.024260 0.795891 +-0.438684 -0.027282 0.791275 +-0.446222 -0.026176 0.792964 +-0.448242 -0.022046 0.799270 +-0.435185 -0.015163 0.961895 +-0.442724 -0.015163 0.959875 +-0.444743 -0.115828 0.963804 +-0.438684 -0.115980 0.964327 +-0.433166 -0.114426 0.958997 +-0.435185 -0.112298 0.951708 +-0.442724 -0.111727 0.949754 +-0.447700 -0.112716 0.953139 +-0.448242 -0.114426 0.958997 +-0.446222 -0.130482 0.957545 +-0.438684 -0.131563 0.959262 +-0.433166 -0.128610 0.954571 +-0.435185 -0.124578 0.948160 +-0.442724 -0.123497 0.946441 +-0.448242 -0.126449 0.951136 +-0.435185 0.038029 0.958751 +-0.433166 -0.015163 0.969433 +-0.433166 0.038483 0.966291 +-0.438684 0.038814 0.971810 +-0.444743 -0.015163 0.974410 +-0.444743 0.038782 0.971269 +-0.448242 -0.015163 0.969433 +-0.448242 0.038483 0.966291 +-0.447700 0.038118 0.960230 +-0.442724 0.037909 0.956731 +-0.435185 0.067263 0.954535 +-0.433166 0.068769 0.961925 +-0.438684 0.069871 0.967335 +-0.444743 0.069763 0.966804 +-0.448242 0.068769 0.961925 +-0.447700 0.067559 0.955984 +-0.442724 0.066860 0.952555 +-0.435185 0.081972 0.951708 +-0.433166 0.084100 0.958997 +-0.438684 0.085654 0.964327 +-0.444743 0.085502 0.963804 +-0.448242 0.084100 0.958997 +-0.447700 0.082390 0.953139 +-0.442724 0.081400 0.949754 +-0.442724 0.102727 0.940230 +-0.435185 0.110621 0.928670 +-0.435185 0.104228 0.941584 +-0.433166 0.117839 0.930949 +-0.433166 0.109833 0.946633 +-0.438684 0.123122 0.932618 +-0.438684 0.113936 0.950330 +-0.444743 0.113534 0.949967 +-0.444743 0.122603 0.932455 +-0.448242 0.117839 0.930949 +-0.448242 0.109833 0.946633 +-0.447700 0.105327 0.942574 +-0.447700 0.112037 0.929117 +-0.442724 0.108688 0.928059 +-0.435185 0.113646 0.914897 +-0.433166 0.121153 0.915860 +-0.438684 0.126648 0.916565 +-0.444743 0.126109 0.916496 +-0.448242 0.121153 0.915860 +-0.447700 0.115119 0.915086 +-0.442724 0.111635 0.914640 +-0.435185 0.114221 0.900129 +-0.433166 0.121790 0.899510 +-0.438684 0.127329 0.899057 +-0.444743 0.126786 0.899101 +-0.448242 0.121790 0.899510 +-0.447700 0.115706 0.900008 +-0.442724 0.112193 0.900295 +-0.435185 0.111702 0.887846 +-0.433166 0.118762 0.884753 +-0.438684 0.123931 0.882489 +-0.444743 0.123424 0.882711 +-0.448242 0.118762 0.884753 +-0.447700 0.113087 0.887239 +-0.442724 0.109810 0.888675 +-0.435185 0.105190 0.878789 +-0.433166 0.110614 0.873423 +-0.438684 0.114586 0.869493 +-0.444743 0.114196 0.869879 +-0.448242 0.110614 0.873423 +-0.447700 0.106254 0.877737 +-0.442724 0.103735 0.880228 +-0.435185 0.092388 0.869373 +-0.433166 0.096689 0.863180 +-0.438684 0.099838 0.858645 +-0.444743 0.099529 0.859090 +-0.448242 0.096689 0.863180 +-0.447700 0.093232 0.868158 +-0.442724 0.091236 0.871032 +-0.435185 -0.010196 0.802197 +-0.433166 -0.006067 0.795891 +-0.438684 -0.003044 0.791275 +-0.444743 -0.003340 0.791727 +-0.447700 -0.004960 0.794201 +-0.448783 -0.007173 0.797580 +-0.447700 -0.009386 0.800960 +-0.442724 -0.011303 0.803887 +-0.435185 0.094252 0.948160 +-0.433166 0.098284 0.954571 +-0.438684 0.101236 0.959262 +-0.444743 0.100947 0.958802 +-0.448242 0.098284 0.954571 +-0.447700 0.095043 0.949418 +-0.442724 0.093171 0.946441 +-0.458525 -0.050293 0.479560 +-0.408804 -0.050293 0.508362 +-0.453385 -0.050293 0.533428 +-0.410645 -0.050293 0.533428 +-0.458525 -0.057032 0.479560 +-0.408804 -0.057032 0.508362 +-0.453385 -0.057032 0.533428 +-0.410645 -0.057032 0.533428 +-0.427501 -0.050293 0.455528 +-0.379586 -0.050293 0.484718 +-0.379586 -0.057032 0.484718 +-0.427501 -0.057032 0.455528 +-0.398920 -0.050293 0.455547 +-0.392822 -0.050293 0.457879 +-0.392822 -0.057032 0.457879 +-0.398920 -0.057032 0.455547 +-0.458525 0.019967 0.479560 +-0.453385 0.019967 0.533428 +-0.410645 0.019967 0.533428 +-0.408804 0.019967 0.508362 +-0.458525 0.026706 0.479560 +-0.408804 0.026706 0.508362 +-0.410645 0.026706 0.533428 +-0.453385 0.026706 0.533428 +-0.398920 0.019967 0.455547 +-0.392822 0.019967 0.457879 +-0.392822 0.026706 0.457879 +-0.398920 0.026706 0.455547 +-0.379586 0.019967 0.484718 +-0.427501 0.019967 0.455528 +-0.379586 0.026706 0.484718 +-0.427501 0.026706 0.455528 +-0.300337 -0.062632 0.314905 +-0.300337 0.025335 0.314905 +-0.464943 -0.062632 0.314905 +-0.464943 0.025335 0.314905 +-0.300337 -0.062632 0.340650 +-0.300337 0.025335 0.340650 +-0.464943 -0.062632 0.340650 +-0.464943 0.025335 0.340650 +-0.411579 -0.054043 0.509689 +-0.411579 0.020632 0.509689 +-0.452510 -0.054043 0.509689 +-0.452510 0.020632 0.509689 +-0.411579 -0.054043 0.519059 +-0.411579 0.020632 0.519059 +-0.452510 -0.054043 0.519059 +-0.452510 0.020632 0.519059 +-0.411579 -0.054043 0.490592 +-0.411579 0.020803 0.490592 +-0.452510 -0.054043 0.490592 +-0.452510 0.020803 0.490592 +-0.411579 -0.054043 0.499962 +-0.411579 0.020803 0.499962 +-0.452510 -0.054043 0.499962 +-0.452510 0.020803 0.499962 +-0.434868 -0.000483 0.334784 +-0.445664 -0.006716 0.334784 +-0.445664 -0.006716 0.497179 +-0.449927 -0.018430 0.334784 +-0.449927 -0.018430 0.497179 +-0.445664 -0.030145 0.334784 +-0.445664 -0.030145 0.497179 +-0.434868 -0.036378 0.334784 +-0.434868 -0.036378 0.497179 +-0.422591 -0.034213 0.334784 +-0.422591 -0.034213 0.497179 +-0.414578 -0.024663 0.334784 +-0.414578 -0.024663 0.497179 +-0.414578 -0.012197 0.334784 +-0.414578 -0.012197 0.497179 +-0.422591 -0.002648 0.334784 +-0.434868 -0.000483 0.497179 +-0.422591 -0.002648 0.497179 +-0.397435 0.039534 0.110252 +-0.385489 0.039534 0.112359 +-0.385489 -0.076395 0.112359 +-0.397435 -0.076395 0.110252 +-0.377691 0.039534 0.121652 +-0.377691 -0.076395 0.121652 +-0.377691 0.039534 0.133783 +-0.377691 -0.076395 0.133783 +-0.385489 0.039534 0.143076 +-0.385489 -0.076395 0.143076 +-0.397435 0.039534 0.145182 +-0.397435 -0.076395 0.145183 +-0.407941 0.039534 0.139117 +-0.407941 -0.076395 0.139117 +-0.412090 0.039534 0.127717 +-0.412090 -0.076395 0.127717 +-0.407941 0.039534 0.116318 +-0.407941 -0.076395 0.116318 +-0.335814 -0.013491 0.115999 +-0.335814 -0.021339 0.117383 +-0.393146 -0.021339 0.117383 +-0.393146 -0.013491 0.115999 +-0.335814 -0.026460 0.123487 +-0.393146 -0.026460 0.123487 +-0.335814 -0.026460 0.131455 +-0.393146 -0.026460 0.131455 +-0.335814 -0.021339 0.137559 +-0.393146 -0.021339 0.137559 +-0.335814 -0.013491 0.138943 +-0.393146 -0.013491 0.138943 +-0.335814 -0.006591 0.134959 +-0.393146 -0.006591 0.134959 +-0.335814 -0.003866 0.127471 +-0.393146 -0.003866 0.127471 +-0.335814 -0.006591 0.119983 +-0.393146 -0.006591 0.119983 +-0.436595 -0.033361 0.912128 +-0.443932 -0.033361 0.912128 +-0.442724 -0.075661 0.907796 +-0.437803 -0.075661 0.907796 +-0.438346 -0.093908 0.903420 +-0.442181 -0.093908 0.903420 +-0.437668 -0.033361 0.913747 +-0.442858 -0.033361 0.913747 +-0.438523 -0.075661 0.909415 +-0.442004 -0.075661 0.909415 +-0.438907 -0.093908 0.905040 +-0.441620 -0.093908 0.905040 +-0.438875 -0.111724 0.896412 +-0.441651 -0.111724 0.896412 +-0.439282 -0.112045 0.897264 +-0.441245 -0.112045 0.897264 +-0.438875 -0.113817 0.901842 +-0.438346 -0.095658 0.910665 +-0.437803 -0.077037 0.916535 +-0.436595 -0.033438 0.925877 +-0.437668 -0.033438 0.925877 +-0.438523 -0.077037 0.916535 +-0.438907 -0.095658 0.910665 +-0.439282 -0.113817 0.901842 +-0.441245 -0.113817 0.901842 +-0.441620 -0.095658 0.910665 +-0.442004 -0.077037 0.916535 +-0.442858 -0.033438 0.925877 +-0.443932 -0.033438 0.925877 +-0.442724 -0.077037 0.916535 +-0.442181 -0.095658 0.910665 +-0.441651 -0.113817 0.901842 + + + + + + + + + + + +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 0.000691 0.000000 +1.000000 0.000691 0.000000 +1.000000 0.000691 0.000000 +1.000000 0.000691 0.000000 +1.000000 0.000691 0.000000 +1.000000 0.000691 0.000000 +0.911684 -0.410892 0.000000 +0.602681 -0.797982 0.000000 +0.911684 -0.410893 0.000000 +0.911684 -0.410893 0.000000 +0.602681 -0.797982 0.000000 +0.602681 -0.797982 0.000000 +0.916173 0.400782 0.000000 +0.589034 0.808108 0.000000 +0.916173 0.400782 0.000000 +0.916173 0.400782 0.000000 +0.916173 0.400782 0.000000 +0.916173 0.400782 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.388846 -0.921303 0.000000 +0.302574 -0.953126 0.000000 +0.388846 -0.921303 0.000000 +0.388846 -0.921303 0.000000 +0.302574 -0.953126 0.000000 +0.302574 -0.953126 0.000000 +0.393221 0.919444 0.000000 +0.309391 0.950935 0.000000 +0.393221 0.919444 0.000000 +0.393221 0.919444 0.000000 +0.393221 0.919444 0.000000 +0.393221 0.919444 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.312340 -0.949970 0.000000 +0.312340 -0.949970 0.000000 +0.312340 -0.949970 0.000000 +0.312340 -0.949970 0.000000 +0.312340 -0.949970 0.000000 +0.312340 -0.949970 0.000000 +0.305661 0.952140 0.000000 +0.305661 0.952140 0.000000 +0.305661 0.952140 0.000000 +0.305661 0.952140 0.000000 +0.305661 0.952140 0.000000 +0.305661 0.952140 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.312341 -0.949970 0.000000 +0.312341 -0.949970 0.000000 +0.312341 -0.949970 0.000000 +0.312341 -0.949970 0.000000 +0.312341 -0.949970 0.000000 +0.312341 -0.949970 0.000000 +0.305684 0.952133 0.000000 +0.305684 0.952133 0.000000 +0.305684 0.952133 0.000000 +0.305684 0.952133 0.000000 +0.305684 0.952133 0.000000 +0.305684 0.952133 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.371145 -0.005697 -0.928557 +0.000000 0.000000 -1.000000 +0.371145 -0.005697 -0.928557 +-0.010652 -0.999943 0.000000 +-0.010652 -0.999943 0.000000 +-0.010652 -0.999943 0.000000 +-0.010652 -0.999943 0.000000 +-0.010652 -0.999943 0.000000 +-0.010652 -0.999943 0.000000 +-0.003412 0.999994 0.000000 +-0.003412 0.999994 0.000000 +-0.003412 0.999994 0.000000 +-0.003412 0.999994 0.000000 +-0.003412 0.999994 0.000000 +-0.003412 0.999994 0.000000 +-1.000000 -0.000862 0.000000 +-1.000000 -0.000862 0.000000 +-1.000000 -0.000862 0.000000 +-1.000000 -0.000862 0.000000 +-1.000000 -0.000862 0.000000 +-1.000000 -0.000862 0.000000 +0.981711 0.190376 0.000000 +0.981711 0.190376 0.000000 +0.981711 0.190376 0.000000 +0.981711 0.190376 0.000000 +0.981711 0.190376 0.000000 +0.981711 0.190376 0.000000 +0.981714 -0.190363 0.000000 +0.981714 -0.190363 0.000000 +0.981714 -0.190363 0.000000 +0.981714 -0.190363 0.000000 +0.981714 -0.190363 0.000000 +0.981714 -0.190363 0.000000 +0.864415 0.502779 0.000000 +0.864415 0.502779 0.000000 +0.864415 0.502779 0.000000 +0.864415 0.502779 0.000000 +0.864415 0.502779 0.000000 +0.864415 0.502779 0.000000 +0.864393 -0.502817 0.000000 +0.864393 -0.502817 0.000000 +0.864393 -0.502817 0.000000 +0.864393 -0.502817 0.000000 +0.864393 -0.502817 0.000000 +0.864393 -0.502817 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.864415 0.502779 0.000000 +-0.864415 0.502779 0.000000 +-0.864415 0.502779 0.000000 +-0.864415 0.502779 0.000000 +-0.864415 0.502779 0.000000 +-0.864415 0.502779 0.000000 +-0.864393 -0.502817 0.000000 +-0.864393 -0.502817 0.000000 +-0.864393 -0.502817 0.000000 +-0.864393 -0.502817 0.000000 +-0.864393 -0.502817 0.000000 +-0.864393 -0.502817 0.000000 +-0.981711 0.190378 0.000000 +-0.981711 0.190378 0.000000 +-0.981711 0.190378 0.000000 +-0.981711 0.190378 0.000000 +-0.981711 0.190378 0.000000 +-0.981711 0.190378 0.000000 +-0.981713 -0.190365 0.000000 +-0.981713 -0.190365 0.000000 +-0.981713 -0.190365 0.000000 +-0.981713 -0.190365 0.000000 +-0.981713 -0.190365 0.000000 +-0.981713 -0.190365 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.010650 -0.999943 0.000000 +-0.010650 -0.999943 0.000000 +-0.010650 -0.999943 0.000000 +-0.010650 -0.999943 0.000000 +-0.010650 -0.999943 0.000000 +-0.010650 -0.999943 0.000000 +-0.003413 0.999994 0.000000 +-0.003413 0.999994 0.000000 +-0.003413 0.999994 0.000000 +-0.003413 0.999994 0.000000 +-0.003413 0.999994 0.000000 +-0.003413 0.999994 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.498592 0.866837 0.000000 +0.498592 0.866836 0.000000 +0.498592 0.866837 0.000000 +0.498592 0.866837 0.000000 +0.498592 0.866836 0.000000 +0.498592 0.866837 0.000000 +0.498594 -0.866836 0.000000 +0.498594 -0.866836 0.000000 +0.498594 -0.866836 0.000000 +0.498594 -0.866836 0.000000 +0.498594 -0.866836 0.000000 +0.498594 -0.866836 0.000000 +-0.498594 0.866836 0.000000 +-0.498594 0.866836 0.000000 +-0.498594 0.866836 0.000000 +-0.498594 0.866836 0.000000 +-0.498594 0.866836 0.000000 +-0.498594 0.866836 0.000000 +-0.498595 -0.866835 0.000000 +-0.498595 -0.866835 0.000000 +-0.498595 -0.866835 0.000000 +-0.498595 -0.866835 0.000000 +-0.498595 -0.866835 0.000000 +-0.498595 -0.866835 0.000000 +0.998583 0.000000 0.053215 +0.998583 0.000000 0.053215 +0.998583 0.000000 0.053215 +0.998583 0.000000 0.053215 +0.998583 0.000000 0.053215 +0.998583 0.000000 0.053215 +0.065452 0.877396 0.475282 +0.000000 0.886900 0.461961 +0.065452 0.877396 0.475282 +0.000000 0.886900 0.461961 +0.065452 0.877396 0.475282 +0.065452 0.877396 0.475282 +0.998583 0.000000 0.053209 +0.998583 0.000000 0.053209 +0.998583 0.000000 0.053209 +0.998583 0.000000 0.053209 +0.998583 0.000000 0.053209 +0.998583 0.000000 0.053209 +0.105632 0.962130 0.251290 +0.105632 0.962130 0.251290 +0.105632 0.962131 0.251290 +0.105632 0.962130 0.251290 +0.071389 0.956976 0.281249 +0.105632 0.962131 0.251290 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.841303 0.540564 0.000000 +-0.841303 0.540564 0.000000 +-0.841303 0.540564 0.000000 +-0.841303 0.540564 0.000000 +-0.841303 0.540564 0.000000 +-0.841303 0.540564 0.000000 +-0.743494 0.668742 0.000000 +-0.743494 0.668742 0.000000 +-0.743494 0.668742 0.000000 +-0.743494 0.668742 0.000000 +-0.743494 0.668742 0.000000 +-0.743494 0.668742 0.000000 +-0.217041 0.976162 0.000000 +-0.217041 0.976163 0.000000 +-0.217041 0.976162 0.000000 +-0.217041 0.976162 0.000000 +-0.217041 0.976163 0.000000 +-0.217041 0.976162 0.000000 +0.217041 0.976163 0.000000 +0.554904 0.831914 0.000000 +0.217041 0.976163 0.000000 +0.554904 0.831914 0.000000 +0.217041 0.976163 0.000000 +0.554905 0.831914 0.000000 +0.153318 0.000000 0.988177 +0.033688 0.000000 0.999432 +0.033688 0.000000 0.999432 +0.033688 0.000000 0.999432 +0.153318 0.000000 0.988177 +0.033688 0.000000 0.999432 +0.841322 0.540535 0.000000 +0.841322 0.540535 0.000000 +0.841322 0.540535 0.000000 +0.841322 0.540535 0.000000 +0.841322 0.540535 0.000000 +0.841322 0.540535 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.129426 0.965918 0.224167 +-0.129426 0.965918 0.224167 +-0.129426 0.965918 0.224167 +-0.129426 0.965918 0.224167 +-0.129426 0.965918 0.224167 +-0.129427 0.965918 0.224167 +-0.243255 0.965913 0.088540 +-0.243241 0.965918 0.088526 +-0.243255 0.965913 0.088540 +-0.243255 0.965913 0.088540 +-0.243255 0.965913 0.088540 +-0.243255 0.965913 0.088540 +-0.243255 0.965913 -0.088537 +-0.243255 0.965913 -0.088537 +-0.243255 0.965913 -0.088537 +-0.243255 0.965913 -0.088537 +-0.243255 0.965913 -0.088537 +-0.243247 0.965915 -0.088537 +-0.129407 0.965920 -0.224171 +-0.129407 0.965920 -0.224171 +-0.129407 0.965920 -0.224171 +-0.129407 0.965920 -0.224171 +-0.129442 0.965910 -0.224195 +-0.129407 0.965920 -0.224171 +0.044935 0.965909 -0.254952 +0.044943 0.965916 -0.254926 +0.044943 0.965916 -0.254926 +0.044943 0.965916 -0.254926 +0.044935 0.965909 -0.254952 +0.044943 0.965916 -0.254926 +0.198311 0.965911 -0.166398 +0.198311 0.965911 -0.166398 +0.198305 0.965913 -0.166396 +0.198311 0.965911 -0.166398 +0.198311 0.965911 -0.166398 +0.198311 0.965911 -0.166398 +0.258867 0.965913 0.000000 +0.258867 0.965913 0.000000 +0.258867 0.965913 0.000000 +0.258867 0.965913 0.000000 +0.258867 0.965913 0.000000 +0.258867 0.965913 0.000000 +0.198306 0.965913 0.166394 +0.198308 0.965911 0.166400 +0.198306 0.965913 0.166394 +0.198308 0.965911 0.166400 +0.198306 0.965913 0.166394 +0.198306 0.965913 0.166394 +0.044955 0.965911 0.254941 +0.044955 0.965911 0.254941 +0.044959 0.965914 0.254928 +0.044955 0.965911 0.254941 +0.044955 0.965911 0.254941 +0.044955 0.965911 0.254941 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.500075 0.000000 0.865982 +-0.500075 0.000000 0.865982 +-0.500075 0.000000 0.865982 +-0.500075 0.000000 0.865982 +-0.500075 0.000000 0.865982 +-0.500075 0.000000 0.865982 +-0.939679 0.000000 0.342057 +-0.939679 0.000000 0.342057 +-0.939679 0.000000 0.342057 +-0.939679 0.000000 0.342057 +-0.939679 0.000000 0.342057 +-0.939679 0.000000 0.342057 +-0.939678 0.000000 -0.342059 +-0.939678 0.000000 -0.342059 +-0.939679 0.000000 -0.342059 +-0.939678 0.000000 -0.342059 +-0.939679 0.000000 -0.342059 +-0.939678 0.000000 -0.342059 +-0.499959 0.000000 -0.866049 +-0.499959 0.000000 -0.866049 +-0.499959 0.000000 -0.866049 +-0.499959 0.000000 -0.866049 +-0.499959 0.000000 -0.866049 +-0.499959 0.000000 -0.866049 +0.173633 0.000000 -0.984810 +0.173633 0.000000 -0.984810 +0.173633 0.000000 -0.984811 +0.173633 0.000000 -0.984810 +0.173633 0.000000 -0.984810 +0.173633 0.000000 -0.984811 +0.766056 0.000000 -0.642773 +0.766056 0.000000 -0.642773 +0.766056 0.000000 -0.642773 +0.766056 0.000000 -0.642773 +0.766056 0.000000 -0.642773 +0.766056 0.000000 -0.642773 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.766056 0.000000 0.642773 +0.766056 0.000000 0.642773 +0.766056 0.000000 0.642773 +0.766056 0.000000 0.642773 +0.766056 0.000000 0.642773 +0.766056 0.000000 0.642773 +0.173633 0.000000 0.984810 +0.173633 0.000000 0.984810 +0.173633 0.000000 0.984811 +0.173633 0.000000 0.984810 +0.173633 0.000000 0.984810 +0.173633 0.000000 0.984811 +-0.500010 0.000000 0.866020 +-0.500010 0.000000 0.866020 +-0.500010 0.000000 0.866020 +-0.500010 0.000000 0.866020 +-0.500010 0.000000 0.866020 +-0.500010 0.000000 0.866020 +-0.939701 0.000000 0.341997 +-0.939701 0.000000 0.341997 +-0.939701 0.000000 0.341997 +-0.939701 0.000000 0.341997 +-0.939701 0.000000 0.341997 +-0.939701 0.000000 0.341997 +-0.939694 0.000000 -0.342017 +-0.939694 0.000000 -0.342017 +-0.939694 0.000000 -0.342017 +-0.939694 0.000000 -0.342017 +-0.939694 0.000000 -0.342017 +-0.939694 0.000000 -0.342017 +-0.500009 0.000000 -0.866020 +-0.500009 0.000000 -0.866020 +-0.500009 0.000000 -0.866020 +-0.500009 0.000000 -0.866020 +-0.500009 0.000000 -0.866020 +-0.500009 0.000000 -0.866020 +0.173620 0.000000 -0.984813 +0.173620 0.000000 -0.984813 +0.173620 0.000000 -0.984813 +0.173620 0.000000 -0.984813 +0.173620 0.000000 -0.984813 +0.173620 0.000000 -0.984813 +0.766047 0.000000 -0.642785 +0.766047 0.000000 -0.642785 +0.766047 0.000000 -0.642785 +0.766047 0.000000 -0.642785 +0.766047 0.000000 -0.642785 +0.766047 0.000000 -0.642785 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.766046 0.000000 0.642785 +0.766046 0.000000 0.642785 +0.766046 0.000000 0.642785 +0.766046 0.000000 0.642785 +0.766046 0.000000 0.642785 +0.766046 0.000000 0.642785 +0.173680 0.000000 0.984802 +0.173680 0.000000 0.984802 +0.173680 0.000000 0.984802 +0.173680 0.000000 0.984802 +0.173680 0.000000 0.984802 +0.173680 0.000000 0.984802 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.498907 0.065052 0.864211 +-0.498907 0.065052 0.864211 +-0.498907 0.065052 0.864211 +-0.498907 0.065052 0.864211 +-0.498952 0.065037 0.864186 +-0.498907 0.065052 0.864211 +-0.937714 0.065058 0.341262 +-0.937700 0.065045 0.341304 +-0.937700 0.065045 0.341304 +-0.937700 0.065045 0.341304 +-0.937700 0.065045 0.341304 +-0.937700 0.065045 0.341304 +-0.937702 0.065057 -0.341295 +-0.937702 0.065057 -0.341295 +-0.937702 0.065057 -0.341295 +-0.937702 0.065057 -0.341295 +-0.937702 0.065057 -0.341295 +-0.937699 0.065055 -0.341305 +-0.498888 0.065059 -0.864221 +-0.498985 0.065027 -0.864168 +-0.498985 0.065027 -0.864168 +-0.498985 0.065027 -0.864168 +-0.498985 0.065027 -0.864168 +-0.498985 0.065027 -0.864168 +0.173205 0.065046 -0.982735 +0.173205 0.065046 -0.982735 +0.173205 0.065046 -0.982735 +0.173205 0.065046 -0.982735 +0.173205 0.065046 -0.982735 +0.173283 0.065024 -0.982723 +0.764432 0.065042 -0.641415 +0.764481 0.065065 -0.641355 +0.764481 0.065065 -0.641355 +0.764481 0.065065 -0.641355 +0.764481 0.065065 -0.641355 +0.764481 0.065065 -0.641355 +0.997882 0.065053 0.000000 +0.997882 0.065053 0.000000 +0.997882 0.065053 0.000000 +0.997882 0.065053 0.000000 +0.997882 0.065053 0.000000 +0.997882 0.065053 0.000000 +0.764431 0.065042 0.641416 +0.764431 0.065042 0.641416 +0.764431 0.065042 0.641416 +0.764431 0.065042 0.641416 +0.764431 0.065042 0.641416 +0.764439 0.065046 0.641406 +0.173283 0.065051 0.982722 +0.173289 0.065049 0.982720 +0.173289 0.065049 0.982721 +0.173289 0.065049 0.982721 +0.173289 0.065049 0.982720 +0.173289 0.065049 0.982721 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.365183 0.000000 -0.930936 +-0.365183 0.000000 -0.930936 +-0.365183 0.000000 -0.930936 +-0.365183 0.000000 -0.930936 +-0.365183 0.000000 -0.930936 +-0.365183 0.000000 -0.930936 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.276912 0.000000 0.960895 +0.276912 0.000000 0.960895 +0.276912 0.000000 0.960895 +0.276912 0.000000 0.960895 +0.276912 0.000000 0.960895 +0.276912 0.000000 0.960895 +-0.919875 0.000000 0.392213 +-0.919875 0.000000 0.392213 +-0.919875 0.000000 0.392213 +-0.919875 0.000000 0.392213 +-0.919875 0.000000 0.392213 +-0.919875 0.000000 0.392213 +-0.973126 0.000000 -0.230273 +-0.973126 0.000000 -0.230273 +-0.973126 0.000000 -0.230273 +-0.973126 0.000000 -0.230273 +-0.973126 0.000000 -0.230273 +-0.973126 0.000000 -0.230273 +-0.998788 0.000000 -0.049225 +-0.986019 0.000000 0.166631 +-0.998788 0.000000 -0.049225 +-0.986019 0.000000 0.166631 +-0.986019 0.000000 0.166631 +-0.998788 0.000000 -0.049225 +-0.669095 0.000000 0.743177 +-0.805887 0.000000 0.592069 +-0.805887 0.000000 0.592069 +-0.805887 0.000000 0.592069 +-0.669095 0.000000 0.743177 +-0.669094 0.000000 0.743177 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.998583 0.000000 0.053213 +-0.998583 0.000000 0.053213 +-0.998583 0.000000 0.053213 +-0.998583 0.000000 0.053213 +-0.998583 0.000000 0.053213 +-0.998583 0.000000 0.053213 +-0.998583 0.000000 0.053209 +-0.998583 0.000000 0.053209 +-0.998583 0.000000 0.053209 +-0.998583 0.000000 0.053209 +-0.998583 0.000000 0.053209 +-0.998583 0.000000 0.053209 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.517879 0.000000 0.855454 +0.355384 0.000000 0.934720 +0.517879 0.000000 0.855454 +0.002608 0.000000 0.999997 +0.002608 0.000000 0.999997 +0.002608 0.000000 0.999997 +0.002608 0.000000 0.999997 +0.002608 0.000000 0.999997 +0.002608 0.000000 0.999997 +1.000000 -0.000691 0.000000 +1.000000 -0.000691 0.000000 +1.000000 -0.000691 0.000000 +1.000000 -0.000691 0.000000 +1.000000 -0.000691 0.000000 +1.000000 -0.000691 0.000000 +0.602681 0.797982 0.000000 +0.911684 0.410893 0.000000 +0.602681 0.797982 0.000000 +0.911684 0.410893 0.000000 +0.602681 0.797982 0.000000 +0.911684 0.410892 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.589034 -0.808108 0.000000 +0.916173 -0.400782 0.000000 +0.916173 -0.400782 0.000000 +0.916173 -0.400782 0.000000 +0.589034 -0.808108 0.000000 +0.589034 -0.808108 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.302574 0.953126 0.000000 +0.388846 0.921303 0.000000 +0.302574 0.953126 0.000000 +0.388846 0.921303 0.000000 +0.302574 0.953126 0.000000 +0.388846 0.921303 0.000000 +0.393221 -0.919444 0.000000 +0.309391 -0.950935 0.000000 +0.393221 -0.919444 0.000000 +0.393221 -0.919444 0.000000 +0.309391 -0.950935 0.000000 +0.309391 -0.950935 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.312340 0.949970 0.000000 +0.312340 0.949970 0.000000 +0.312340 0.949970 0.000000 +0.312340 0.949970 0.000000 +0.312340 0.949970 0.000000 +0.312340 0.949970 0.000000 +0.305661 -0.952140 0.000000 +0.305661 -0.952140 0.000000 +0.305661 -0.952140 0.000000 +0.305661 -0.952140 0.000000 +0.305661 -0.952140 0.000000 +0.305661 -0.952140 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.312341 0.949970 0.000000 +0.312341 0.949970 0.000000 +0.312341 0.949970 0.000000 +0.312341 0.949970 0.000000 +0.312341 0.949970 0.000000 +0.312341 0.949970 0.000000 +0.305685 -0.952133 0.000000 +0.305684 -0.952133 0.000000 +0.305684 -0.952133 0.000000 +0.305684 -0.952133 0.000000 +0.305685 -0.952133 0.000000 +0.305684 -0.952133 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.375221 0.003684 -0.926928 +0.375221 0.003684 -0.926928 +0.375221 0.003684 -0.926928 +-0.010652 0.999943 0.000000 +-0.010652 0.999943 0.000000 +-0.010652 0.999943 0.000000 +-0.010652 0.999943 0.000000 +-0.010652 0.999943 0.000000 +-0.010652 0.999943 0.000000 +-0.003412 -0.999994 0.000000 +-0.003412 -0.999994 0.000000 +-0.003412 -0.999994 0.000000 +-0.003412 -0.999994 0.000000 +-0.003412 -0.999994 0.000000 +-0.003412 -0.999994 0.000000 +-1.000000 0.000862 0.000000 +-1.000000 0.000862 0.000000 +-1.000000 0.000862 0.000000 +-1.000000 0.000862 0.000000 +-1.000000 0.000862 0.000000 +-1.000000 0.000862 0.000000 +0.981711 -0.190376 0.000000 +0.981711 -0.190376 0.000000 +0.981711 -0.190376 0.000000 +0.981711 -0.190376 0.000000 +0.981711 -0.190376 0.000000 +0.981711 -0.190376 0.000000 +0.981714 0.190363 0.000000 +0.981714 0.190363 0.000000 +0.981714 0.190363 0.000000 +0.981714 0.190363 0.000000 +0.981714 0.190363 0.000000 +0.981714 0.190363 0.000000 +0.864415 -0.502779 0.000000 +0.864415 -0.502779 0.000000 +0.864415 -0.502779 0.000000 +0.864415 -0.502779 0.000000 +0.864415 -0.502779 0.000000 +0.864415 -0.502779 0.000000 +0.864393 0.502817 0.000000 +0.864393 0.502817 0.000000 +0.864393 0.502817 0.000000 +0.864393 0.502817 0.000000 +0.864393 0.502817 0.000000 +0.864393 0.502817 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.864415 -0.502779 0.000000 +-0.864415 -0.502779 0.000000 +-0.864415 -0.502779 0.000000 +-0.864415 -0.502779 0.000000 +-0.864415 -0.502779 0.000000 +-0.864415 -0.502779 0.000000 +-0.864393 0.502817 0.000000 +-0.864393 0.502817 0.000000 +-0.864393 0.502817 0.000000 +-0.864393 0.502817 0.000000 +-0.864393 0.502817 0.000000 +-0.864393 0.502817 0.000000 +-0.981711 -0.190378 0.000000 +-0.981711 -0.190378 0.000000 +-0.981711 -0.190378 0.000000 +-0.981711 -0.190378 0.000000 +-0.981711 -0.190378 0.000000 +-0.981711 -0.190378 0.000000 +-0.981713 0.190365 0.000000 +-0.981713 0.190365 0.000000 +-0.981713 0.190365 0.000000 +-0.981713 0.190365 0.000000 +-0.981713 0.190365 0.000000 +-0.981713 0.190365 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.010650 0.999943 0.000000 +-0.010650 0.999943 0.000000 +-0.010650 0.999943 0.000000 +-0.010650 0.999943 0.000000 +-0.010650 0.999943 0.000000 +-0.010650 0.999943 0.000000 +-0.003413 -0.999994 0.000000 +-0.003413 -0.999994 0.000000 +-0.003413 -0.999994 0.000000 +-0.003413 -0.999994 0.000000 +-0.003413 -0.999994 0.000000 +-0.003413 -0.999994 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.498592 -0.866836 0.000000 +0.498592 -0.866837 0.000000 +0.498592 -0.866837 0.000000 +0.498592 -0.866837 0.000000 +0.498592 -0.866837 0.000000 +0.498592 -0.866836 0.000000 +0.498594 0.866836 0.000000 +0.498594 0.866836 0.000000 +0.498594 0.866836 0.000000 +0.498594 0.866836 0.000000 +0.498594 0.866836 0.000000 +0.498594 0.866836 0.000000 +-0.498594 -0.866836 0.000000 +-0.498594 -0.866836 0.000000 +-0.498594 -0.866836 0.000000 +-0.498594 -0.866836 0.000000 +-0.498594 -0.866836 0.000000 +-0.498594 -0.866836 0.000000 +-0.498595 0.866835 0.000000 +-0.498595 0.866835 0.000000 +-0.498595 0.866835 0.000000 +-0.498595 0.866835 0.000000 +-0.498595 0.866835 0.000000 +-0.498595 0.866835 0.000000 +0.998583 0.000000 0.053215 +0.998583 0.000000 0.053215 +0.998583 0.000000 0.053215 +0.998583 0.000000 0.053215 +0.998583 0.000000 0.053215 +0.998583 0.000000 0.053215 +0.065452 -0.877396 0.475282 +0.000000 -0.886900 0.461961 +0.065452 -0.877396 0.475282 +0.000000 -0.886900 0.461961 +0.065452 -0.877396 0.475282 +0.065452 -0.877396 0.475282 +0.998583 0.000000 0.053209 +0.998583 0.000000 0.053209 +0.998583 0.000000 0.053209 +0.998583 0.000000 0.053209 +0.998583 0.000000 0.053209 +0.998583 0.000000 0.053209 +0.071389 -0.956976 0.281249 +0.071389 -0.956976 0.281249 +0.105632 -0.962130 0.251290 +0.071389 -0.956976 0.281249 +0.071389 -0.956976 0.281249 +0.071389 -0.956976 0.281249 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.841303 -0.540564 0.000000 +-0.841303 -0.540564 0.000000 +-0.841303 -0.540564 0.000000 +-0.841303 -0.540564 0.000000 +-0.841303 -0.540564 0.000000 +-0.841303 -0.540564 0.000000 +-0.743494 -0.668742 0.000000 +-0.743494 -0.668742 0.000000 +-0.743494 -0.668742 0.000000 +-0.743494 -0.668742 0.000000 +-0.743494 -0.668742 0.000000 +-0.743494 -0.668742 0.000000 +-0.217041 -0.976162 0.000000 +-0.217041 -0.976163 0.000000 +-0.217041 -0.976162 0.000000 +-0.217041 -0.976163 0.000000 +-0.217041 -0.976162 0.000000 +-0.217041 -0.976162 0.000000 +0.554905 -0.831914 0.000000 +0.217041 -0.976163 0.000000 +0.554904 -0.831914 0.000000 +0.554904 -0.831914 0.000000 +0.217041 -0.976163 0.000000 +0.217041 -0.976163 0.000000 +0.841322 -0.540535 0.000000 +0.841322 -0.540535 0.000000 +0.841322 -0.540535 0.000000 +0.841322 -0.540535 0.000000 +0.841322 -0.540535 0.000000 +0.841322 -0.540535 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.129426 -0.965918 0.224167 +-0.129426 -0.965918 0.224167 +-0.129426 -0.965918 0.224167 +-0.129426 -0.965918 0.224167 +-0.129426 -0.965918 0.224167 +-0.129427 -0.965918 0.224167 +-0.243241 -0.965918 0.088526 +-0.243241 -0.965918 0.088526 +-0.243241 -0.965918 0.088526 +-0.243241 -0.965918 0.088526 +-0.243241 -0.965918 0.088526 +-0.243255 -0.965913 0.088540 +-0.243255 -0.965913 -0.088537 +-0.243255 -0.965913 -0.088537 +-0.243255 -0.965913 -0.088537 +-0.243255 -0.965913 -0.088537 +-0.243247 -0.965915 -0.088537 +-0.243255 -0.965913 -0.088537 +-0.129442 -0.965910 -0.224195 +-0.129442 -0.965910 -0.224195 +-0.129407 -0.965920 -0.224171 +-0.129442 -0.965910 -0.224195 +-0.129442 -0.965910 -0.224195 +-0.129442 -0.965910 -0.224195 +0.044943 -0.965916 -0.254926 +0.044935 -0.965909 -0.254952 +0.044935 -0.965909 -0.254952 +0.044935 -0.965909 -0.254952 +0.044943 -0.965916 -0.254926 +0.044935 -0.965909 -0.254952 +0.198305 -0.965913 -0.166396 +0.198305 -0.965913 -0.166396 +0.198305 -0.965913 -0.166396 +0.198305 -0.965913 -0.166396 +0.198305 -0.965913 -0.166396 +0.198311 -0.965911 -0.166398 +0.258867 -0.965913 0.000000 +0.258867 -0.965913 0.000000 +0.258867 -0.965913 0.000000 +0.258867 -0.965913 0.000000 +0.258867 -0.965913 0.000000 +0.258867 -0.965913 0.000000 +0.198306 -0.965913 0.166394 +0.198308 -0.965911 0.166400 +0.198306 -0.965913 0.166394 +0.198308 -0.965911 0.166400 +0.198306 -0.965913 0.166394 +0.198306 -0.965913 0.166394 +0.044959 -0.965914 0.254928 +0.044959 -0.965914 0.254928 +0.044959 -0.965914 0.254928 +0.044959 -0.965914 0.254928 +0.044959 -0.965914 0.254928 +0.044955 -0.965911 0.254941 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.500075 0.000000 0.865982 +-0.500075 0.000000 0.865982 +-0.500075 0.000000 0.865982 +-0.500075 0.000000 0.865982 +-0.500075 0.000000 0.865982 +-0.500075 0.000000 0.865982 +-0.939679 0.000000 0.342057 +-0.939679 0.000000 0.342057 +-0.939679 0.000000 0.342057 +-0.939679 0.000000 0.342057 +-0.939679 0.000000 0.342057 +-0.939679 0.000000 0.342057 +-0.939678 0.000000 -0.342059 +-0.939678 0.000000 -0.342059 +-0.939679 0.000000 -0.342059 +-0.939678 0.000000 -0.342059 +-0.939678 0.000000 -0.342059 +-0.939679 0.000000 -0.342059 +-0.499959 0.000000 -0.866049 +-0.499959 0.000000 -0.866049 +-0.499959 0.000000 -0.866049 +-0.499959 0.000000 -0.866049 +-0.499959 0.000000 -0.866049 +-0.499959 0.000000 -0.866049 +0.173633 0.000000 -0.984810 +0.173633 0.000000 -0.984811 +0.173633 0.000000 -0.984810 +0.173633 0.000000 -0.984810 +0.173633 0.000000 -0.984811 +0.173633 0.000000 -0.984810 +0.766056 0.000000 -0.642773 +0.766056 0.000000 -0.642773 +0.766056 0.000000 -0.642773 +0.766056 0.000000 -0.642773 +0.766056 0.000000 -0.642773 +0.766056 0.000000 -0.642773 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.766056 0.000000 0.642773 +0.766056 0.000000 0.642773 +0.766056 0.000000 0.642773 +0.766056 0.000000 0.642773 +0.766056 0.000000 0.642773 +0.766056 0.000000 0.642773 +0.173633 0.000000 0.984810 +0.173633 0.000000 0.984810 +0.173633 0.000000 0.984811 +0.173633 0.000000 0.984810 +0.173633 0.000000 0.984811 +0.173633 0.000000 0.984810 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.498952 -0.065037 0.864186 +-0.498952 -0.065037 0.864186 +-0.498952 -0.065037 0.864186 +-0.498952 -0.065037 0.864186 +-0.498952 -0.065037 0.864186 +-0.498907 -0.065052 0.864211 +-0.937700 -0.065045 0.341304 +-0.937700 -0.065045 0.341304 +-0.937700 -0.065045 0.341304 +-0.937700 -0.065045 0.341304 +-0.937700 -0.065045 0.341304 +-0.937714 -0.065058 0.341262 +-0.937699 -0.065055 -0.341305 +-0.937699 -0.065055 -0.341305 +-0.937702 -0.065057 -0.341295 +-0.937699 -0.065055 -0.341305 +-0.937699 -0.065055 -0.341305 +-0.937699 -0.065055 -0.341305 +-0.498985 -0.065027 -0.864168 +-0.498985 -0.065027 -0.864168 +-0.498985 -0.065027 -0.864168 +-0.498985 -0.065027 -0.864168 +-0.498888 -0.065059 -0.864221 +-0.498985 -0.065027 -0.864168 +0.173283 -0.065024 -0.982723 +0.173283 -0.065024 -0.982723 +0.173283 -0.065024 -0.982723 +0.173283 -0.065024 -0.982723 +0.173283 -0.065024 -0.982723 +0.173205 -0.065046 -0.982735 +0.764432 -0.065042 -0.641415 +0.764481 -0.065065 -0.641355 +0.764432 -0.065042 -0.641415 +0.764432 -0.065042 -0.641415 +0.764432 -0.065042 -0.641415 +0.764432 -0.065042 -0.641415 +0.997882 -0.065053 0.000000 +0.997882 -0.065053 0.000000 +0.997882 -0.065053 0.000000 +0.997882 -0.065053 0.000000 +0.997882 -0.065053 0.000000 +0.997882 -0.065053 0.000000 +0.764439 -0.065046 0.641406 +0.764431 -0.065042 0.641416 +0.764431 -0.065042 0.641416 +0.764431 -0.065042 0.641416 +0.764431 -0.065042 0.641416 +0.764431 -0.065042 0.641416 +0.173289 -0.065049 0.982721 +0.173289 -0.065049 0.982721 +0.173289 -0.065049 0.982720 +0.173289 -0.065049 0.982720 +0.173283 -0.065051 0.982722 +0.173289 -0.065049 0.982721 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.365183 0.000000 -0.930936 +-0.365183 0.000000 -0.930936 +-0.365183 0.000000 -0.930936 +-0.365183 0.000000 -0.930936 +-0.365183 0.000000 -0.930936 +-0.365183 0.000000 -0.930936 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.276912 0.000000 0.960895 +0.276912 0.000000 0.960895 +0.276912 0.000000 0.960895 +0.276912 0.000000 0.960895 +0.276912 0.000000 0.960895 +0.276912 0.000000 0.960895 +-0.919875 0.000000 0.392213 +-0.919875 0.000000 0.392213 +-0.919875 0.000000 0.392213 +-0.919875 0.000000 0.392213 +-0.919875 0.000000 0.392213 +-0.919875 0.000000 0.392213 +-0.973126 0.000000 -0.230273 +-0.973126 0.000000 -0.230273 +-0.973126 0.000000 -0.230273 +-0.973126 0.000000 -0.230273 +-0.973126 0.000000 -0.230273 +-0.973126 0.000000 -0.230273 +-0.998788 0.000000 -0.049225 +-0.998788 0.000000 -0.049225 +-0.998788 0.000000 -0.049225 +-0.998788 0.000000 -0.049225 +-0.998788 0.000000 -0.049225 +-0.998788 0.000000 -0.049225 +-0.669095 0.000000 0.743177 +-0.669095 0.000000 0.743177 +-0.669094 0.000000 0.743177 +-0.669095 0.000000 0.743177 +-0.669095 0.000000 0.743177 +-0.805887 0.000000 0.592069 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.998583 0.000000 0.053213 +-0.998583 0.000000 0.053213 +-0.998583 0.000000 0.053213 +-0.998583 0.000000 0.053213 +-0.998583 0.000000 0.053213 +-0.998583 0.000000 0.053213 +-0.998583 0.000000 0.053209 +-0.998583 0.000000 0.053209 +-0.998583 0.000000 0.053209 +-0.998583 0.000000 0.053209 +-0.998583 0.000000 0.053209 +-0.998583 0.000000 0.053209 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.153318 0.000000 0.988177 +0.130071 -0.015485 0.991384 +0.153318 0.000000 0.988177 +0.153318 0.000000 0.988177 +0.153318 0.000000 0.988177 +0.355384 0.000000 0.934720 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.002608 0.000000 0.999997 +0.002608 0.000000 0.999997 +0.002608 0.000000 0.999997 +0.002608 0.000000 0.999997 +0.002608 0.000000 0.999997 +0.002608 0.000000 0.999997 +-0.173526 0.000000 0.984829 +-0.173526 0.000000 0.984829 +-0.173526 0.000000 0.984829 +-0.173526 0.000000 0.984829 +-0.173526 0.000000 0.984829 +-0.173526 0.000000 0.984829 +-0.499728 0.000000 0.866182 +-0.499728 0.000000 0.866182 +-0.499728 0.000000 0.866182 +-0.499728 0.000000 0.866182 +-0.499728 0.000000 0.866182 +-0.499728 0.000000 0.866182 +-0.765785 0.000000 0.643097 +-0.765785 0.000000 0.643097 +-0.765785 0.000000 0.643097 +-0.765785 0.000000 0.643097 +-0.765785 0.000000 0.643097 +-0.765785 0.000000 0.643097 +-0.939596 0.000000 0.342284 +-0.939596 0.000000 0.342284 +-0.939596 0.000000 0.342284 +-0.939596 0.000000 0.342284 +-0.939596 0.000000 0.342284 +-0.939596 0.000000 0.342284 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.939590 0.000000 -0.342301 +-0.939590 0.000000 -0.342301 +-0.939590 0.000000 -0.342301 +-0.939590 0.000000 -0.342301 +-0.939590 0.000000 -0.342301 +-0.939590 0.000000 -0.342301 +-0.765785 0.000000 -0.643097 +-0.765785 0.000000 -0.643097 +-0.765785 0.000000 -0.643097 +-0.765785 0.000000 -0.643097 +-0.765785 0.000000 -0.643097 +-0.765785 0.000000 -0.643097 +-0.499767 0.000000 -0.866160 +-0.499767 0.000000 -0.866160 +-0.499767 0.000000 -0.866160 +-0.499767 0.000000 -0.866160 +-0.499767 0.000000 -0.866160 +-0.499767 0.000000 -0.866160 +-0.173535 0.000000 -0.984828 +-0.173535 0.000000 -0.984828 +-0.173535 0.000000 -0.984828 +-0.173535 0.000000 -0.984828 +-0.173535 0.000000 -0.984828 +-0.173535 0.000000 -0.984828 +0.173526 0.000000 -0.984829 +0.173526 0.000000 -0.984829 +0.173526 0.000000 -0.984829 +0.173526 0.000000 -0.984829 +0.173526 0.000000 -0.984829 +0.173526 0.000000 -0.984829 +0.499767 0.000000 -0.866160 +0.499767 0.000000 -0.866160 +0.499767 0.000000 -0.866160 +0.499767 0.000000 -0.866160 +0.499767 0.000000 -0.866160 +0.499767 0.000000 -0.866160 +0.765785 0.000000 -0.643097 +0.765785 0.000000 -0.643097 +0.765785 0.000000 -0.643097 +0.765785 0.000000 -0.643097 +0.765785 0.000000 -0.643097 +0.765785 0.000000 -0.643097 +0.939607 0.000000 -0.342256 +0.939607 0.000000 -0.342256 +0.939607 0.000000 -0.342256 +0.939607 0.000000 -0.342256 +0.939607 0.000000 -0.342256 +0.939607 0.000000 -0.342256 +1.000000 0.000048 0.000000 +1.000000 0.000048 0.000000 +1.000000 0.000048 0.000000 +1.000000 0.000048 0.000000 +1.000000 0.000000 -0.000051 +1.000000 0.000048 0.000000 +0.939596 0.000000 0.342284 +0.939596 0.000000 0.342284 +0.939596 0.000000 0.342284 +0.939596 0.000000 0.342284 +0.939596 0.000000 0.342284 +0.939613 0.000045 0.342239 +0.765785 0.000000 0.643097 +0.765785 0.000000 0.643097 +0.765785 0.000000 0.643097 +0.765785 0.000000 0.643097 +0.765785 0.000000 0.643097 +0.765785 0.000000 0.643097 +0.499729 0.000000 0.866182 +0.499729 0.000000 0.866182 +0.499729 0.000000 0.866182 +0.499729 0.000000 0.866182 +0.499707 -0.000025 0.866195 +0.499729 0.000000 0.866182 +0.173535 -0.000009 0.984828 +0.173535 -0.000009 0.984828 +0.173535 -0.000009 0.984828 +0.173535 -0.000009 0.984828 +0.173544 0.000000 0.984826 +0.173535 -0.000009 0.984828 +-0.173673 0.000000 0.984803 +-0.173628 0.000109 0.984811 +-0.173628 0.000109 0.984811 +-0.173628 0.000109 0.984811 +-0.173628 0.000109 0.984811 +-0.173628 0.000109 0.984811 +-0.173673 0.000000 0.984803 +-0.173673 0.000000 0.984803 +-0.173673 0.000000 0.984803 +-0.173673 0.000000 0.984803 +-0.173673 0.000000 0.984803 +-0.173673 0.000000 0.984803 +-0.499992 0.000000 0.866030 +-0.499992 0.000000 0.866030 +-0.499992 0.000000 0.866030 +-0.499992 0.000000 0.866030 +-0.499992 0.000000 0.866030 +-0.499992 0.000000 0.866030 +-0.499992 0.000000 0.866030 +-0.499992 0.000000 0.866030 +-0.499992 0.000000 0.866030 +-0.499992 0.000000 0.866030 +-0.499992 0.000000 0.866030 +-0.499992 0.000000 0.866030 +-0.766052 0.000000 0.642779 +-0.766052 0.000000 0.642779 +-0.766052 0.000000 0.642779 +-0.766052 0.000000 0.642779 +-0.766052 0.000000 0.642779 +-0.766052 0.000000 0.642779 +-0.766052 0.000000 0.642779 +-0.766052 0.000000 0.642779 +-0.766052 0.000000 0.642779 +-0.766052 0.000000 0.642779 +-0.766052 0.000000 0.642779 +-0.766052 0.000000 0.642779 +-0.939692 0.000000 0.342021 +-0.939692 0.000000 0.342021 +-0.939692 0.000000 0.342021 +-0.939692 0.000000 0.342021 +-0.939692 0.000000 0.342021 +-0.939692 0.000000 0.342021 +-0.939692 0.000000 0.342021 +-0.939692 0.000000 0.342021 +-0.939692 0.000000 0.342021 +-0.939692 0.000000 0.342021 +-0.939692 0.000000 0.342021 +-0.939692 0.000000 0.342021 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.939698 0.000000 -0.342006 +-0.939698 0.000000 -0.342006 +-0.939698 0.000000 -0.342006 +-0.939698 0.000000 -0.342006 +-0.939698 0.000000 -0.342006 +-0.939698 0.000000 -0.342006 +-0.939698 0.000000 -0.342006 +-0.939698 0.000000 -0.342006 +-0.939698 0.000000 -0.342006 +-0.939698 0.000000 -0.342006 +-0.939698 0.000000 -0.342006 +-0.939698 0.000000 -0.342006 +-0.766032 0.000000 -0.642802 +-0.766032 0.000000 -0.642802 +-0.766032 0.000000 -0.642802 +-0.766032 0.000000 -0.642802 +-0.766032 0.000000 -0.642802 +-0.766032 0.000000 -0.642802 +-0.766032 0.000000 -0.642802 +-0.766032 0.000000 -0.642802 +-0.766032 0.000000 -0.642802 +-0.766032 0.000000 -0.642802 +-0.766032 0.000000 -0.642802 +-0.766032 0.000000 -0.642802 +-0.499992 0.000000 -0.866030 +-0.499992 0.000000 -0.866030 +-0.499992 0.000000 -0.866030 +-0.499992 0.000000 -0.866030 +-0.499992 0.000000 -0.866030 +-0.499992 0.000000 -0.866030 +-0.499992 0.000000 -0.866030 +-0.499992 0.000000 -0.866030 +-0.499992 0.000000 -0.866030 +-0.499992 0.000000 -0.866030 +-0.499992 0.000000 -0.866030 +-0.499992 0.000000 -0.866030 +-0.173673 0.000000 -0.984803 +-0.173673 0.000000 -0.984803 +-0.173673 0.000000 -0.984803 +-0.173673 0.000000 -0.984803 +-0.173673 0.000000 -0.984803 +-0.173673 0.000000 -0.984803 +-0.173673 0.000000 -0.984803 +-0.173673 0.000000 -0.984803 +-0.173673 0.000000 -0.984803 +-0.173673 0.000000 -0.984803 +-0.173673 0.000000 -0.984803 +-0.173673 0.000000 -0.984803 +0.173673 0.000000 -0.984803 +0.173673 0.000000 -0.984803 +0.173673 0.000000 -0.984803 +0.173673 0.000000 -0.984803 +0.173673 0.000000 -0.984803 +0.173673 0.000000 -0.984803 +0.173673 0.000000 -0.984803 +0.173665 0.000019 -0.984805 +0.173665 0.000019 -0.984805 +0.173665 0.000019 -0.984805 +0.173665 0.000019 -0.984805 +0.173665 0.000019 -0.984805 +0.499993 0.000000 -0.866029 +0.499993 0.000000 -0.866029 +0.499993 0.000000 -0.866029 +0.499993 0.000000 -0.866029 +0.499993 0.000000 -0.866029 +0.499993 0.000000 -0.866029 +0.499993 0.000054 -0.866029 +0.499992 0.000056 -0.866030 +0.499992 0.000056 -0.866030 +0.499992 0.000056 -0.866030 +0.499992 0.000056 -0.866030 +0.499992 0.000056 -0.866030 +0.766032 0.000000 -0.642802 +0.766032 0.000000 -0.642802 +0.766032 0.000000 -0.642802 +0.766032 0.000000 -0.642802 +0.766032 0.000000 -0.642802 +0.766032 0.000000 -0.642802 +0.766032 0.000000 -0.642802 +0.766032 0.000000 -0.642802 +0.766032 0.000000 -0.642802 +0.766032 0.000000 -0.642802 +0.766056 0.000086 -0.642774 +0.766032 0.000000 -0.642802 +0.939683 0.000000 -0.342048 +0.939683 0.000000 -0.342048 +0.939683 0.000000 -0.342048 +0.939683 0.000000 -0.342048 +0.939683 0.000000 -0.342048 +0.939683 0.000000 -0.342048 +0.939683 0.000000 -0.342048 +0.939683 0.000000 -0.342048 +0.939683 0.000000 -0.342048 +0.939683 0.000000 -0.342048 +0.939683 0.000000 -0.342048 +0.939683 0.000000 -0.342048 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.939677 0.000000 0.342063 +0.939677 0.000000 0.342063 +0.939677 0.000000 0.342063 +0.939677 0.000000 0.342063 +0.939677 0.000000 0.342063 +0.939677 0.000000 0.342063 +0.939677 0.000000 0.342063 +0.939677 0.000000 0.342063 +0.939677 0.000000 0.342063 +0.939677 0.000000 0.342063 +0.939677 0.000000 0.342063 +0.939677 0.000000 0.342063 +0.766052 0.000000 0.642779 +0.766052 0.000000 0.642779 +0.766052 0.000000 0.642779 +0.766052 0.000000 0.642779 +0.766052 0.000000 0.642779 +0.766052 0.000000 0.642779 +0.766075 0.000086 0.642751 +0.766075 0.000086 0.642751 +0.766075 0.000086 0.642751 +0.766075 0.000086 0.642751 +0.766075 0.000086 0.642751 +0.766052 0.000000 0.642779 +0.499993 0.000000 0.866030 +0.499993 0.000000 0.866029 +0.499993 0.000000 0.866030 +0.499993 0.000000 0.866030 +0.499993 0.000000 0.866030 +0.499993 0.000000 0.866029 +0.499993 0.000054 0.866029 +0.499993 0.000054 0.866029 +0.499993 0.000054 0.866029 +0.499993 0.000054 0.866029 +0.499993 0.000054 0.866029 +0.499992 0.000056 0.866030 +0.173673 0.000109 0.984803 +0.173628 0.000000 0.984811 +0.173628 0.000000 0.984811 +0.173628 0.000000 0.984811 +0.173628 0.000000 0.984811 +0.173628 0.000000 0.984811 +0.173673 0.000000 0.984803 +0.173673 0.000000 0.984803 +0.173673 0.000000 0.984803 +0.173673 0.000000 0.984803 +0.173673 0.000000 0.984803 +0.173665 0.000019 0.984805 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.173526 0.000000 0.984829 +-0.173526 0.000000 0.984829 +-0.173526 0.000000 0.984829 +-0.173526 0.000000 0.984829 +-0.173526 0.000000 0.984829 +-0.173526 0.000000 0.984829 +-0.499728 0.000000 0.866182 +-0.499728 0.000000 0.866182 +-0.499728 0.000000 0.866182 +-0.499728 0.000000 0.866182 +-0.499728 0.000000 0.866182 +-0.499728 0.000000 0.866182 +-0.765785 0.000000 0.643097 +-0.765785 0.000000 0.643097 +-0.765785 0.000000 0.643097 +-0.765785 0.000000 0.643097 +-0.765785 0.000000 0.643097 +-0.765785 0.000000 0.643097 +-0.939596 0.000000 0.342284 +-0.939596 0.000000 0.342284 +-0.939596 0.000000 0.342284 +-0.939596 0.000000 0.342284 +-0.939596 0.000000 0.342284 +-0.939596 0.000000 0.342284 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.939590 0.000000 -0.342301 +-0.939590 0.000000 -0.342301 +-0.939590 0.000000 -0.342301 +-0.939590 0.000000 -0.342301 +-0.939590 0.000000 -0.342301 +-0.939590 0.000000 -0.342301 +-0.765785 0.000000 -0.643097 +-0.765785 0.000000 -0.643097 +-0.765785 0.000000 -0.643097 +-0.765785 0.000000 -0.643097 +-0.765785 0.000000 -0.643097 +-0.765785 0.000000 -0.643097 +-0.499767 0.000000 -0.866160 +-0.499767 0.000000 -0.866160 +-0.499767 0.000000 -0.866160 +-0.499767 0.000000 -0.866160 +-0.499767 0.000000 -0.866160 +-0.499767 0.000000 -0.866160 +-0.173535 0.000000 -0.984828 +-0.173535 0.000000 -0.984828 +-0.173535 0.000000 -0.984828 +-0.173535 0.000000 -0.984828 +-0.173535 0.000000 -0.984828 +-0.173535 0.000000 -0.984828 +0.173526 0.000000 -0.984829 +0.173526 0.000000 -0.984829 +0.173526 0.000000 -0.984829 +0.173526 0.000000 -0.984829 +0.173526 0.000000 -0.984829 +0.173526 0.000000 -0.984829 +0.499767 0.000000 -0.866160 +0.499767 0.000000 -0.866160 +0.499767 0.000000 -0.866160 +0.499767 0.000000 -0.866160 +0.499767 0.000000 -0.866160 +0.499767 0.000000 -0.866160 +0.765785 0.000000 -0.643097 +0.765785 0.000000 -0.643097 +0.765785 0.000000 -0.643097 +0.765785 0.000000 -0.643097 +0.765785 0.000000 -0.643097 +0.765785 0.000000 -0.643097 +0.939607 0.000000 -0.342256 +0.939607 0.000000 -0.342256 +0.939607 0.000000 -0.342256 +0.939607 0.000000 -0.342256 +0.939607 0.000000 -0.342256 +0.939607 0.000000 -0.342256 +1.000000 0.000000 -0.000051 +1.000000 0.000000 -0.000051 +1.000000 -0.000048 0.000000 +1.000000 0.000000 -0.000051 +1.000000 0.000000 -0.000051 +1.000000 0.000000 -0.000051 +0.939596 0.000000 0.342284 +0.939596 0.000000 0.342284 +0.939596 0.000000 0.342284 +0.939596 0.000000 0.342284 +0.939613 -0.000045 0.342239 +0.939596 0.000000 0.342284 +0.765785 0.000000 0.643097 +0.765785 0.000000 0.643097 +0.765785 0.000000 0.643097 +0.765785 0.000000 0.643097 +0.765785 0.000000 0.643097 +0.765785 0.000000 0.643097 +0.499707 0.000025 0.866195 +0.499707 0.000025 0.866195 +0.499707 0.000025 0.866195 +0.499707 0.000025 0.866195 +0.499707 0.000025 0.866195 +0.499729 0.000000 0.866182 +0.173544 0.000000 0.984826 +0.173544 0.000000 0.984826 +0.173544 0.000000 0.984826 +0.173544 0.000000 0.984826 +0.173544 0.000000 0.984826 +0.173535 0.000009 0.984828 +-0.173673 0.000000 0.984803 +-0.173673 0.000000 0.984803 +-0.173673 0.000000 0.984803 +-0.173673 0.000000 0.984803 +-0.173673 0.000000 0.984803 +-0.173628 -0.000109 0.984811 +-0.173673 0.000000 0.984803 +-0.173673 0.000000 0.984803 +-0.173673 0.000000 0.984803 +-0.173673 0.000000 0.984803 +-0.173673 0.000000 0.984803 +-0.173673 0.000000 0.984803 +-0.499992 0.000000 0.866030 +-0.499992 0.000000 0.866030 +-0.499992 0.000000 0.866030 +-0.499992 0.000000 0.866030 +-0.499992 0.000000 0.866030 +-0.499992 0.000000 0.866030 +-0.499992 0.000000 0.866030 +-0.499992 0.000000 0.866030 +-0.499992 0.000000 0.866030 +-0.499992 0.000000 0.866030 +-0.499992 0.000000 0.866030 +-0.499992 0.000000 0.866030 +-0.766052 0.000000 0.642779 +-0.766052 0.000000 0.642779 +-0.766052 0.000000 0.642779 +-0.766052 0.000000 0.642779 +-0.766052 0.000000 0.642779 +-0.766052 0.000000 0.642779 +-0.766052 0.000000 0.642779 +-0.766052 0.000000 0.642779 +-0.766052 0.000000 0.642779 +-0.766052 0.000000 0.642779 +-0.766052 0.000000 0.642779 +-0.766052 0.000000 0.642779 +-0.939692 0.000000 0.342021 +-0.939692 0.000000 0.342021 +-0.939692 0.000000 0.342021 +-0.939692 0.000000 0.342021 +-0.939692 0.000000 0.342021 +-0.939692 0.000000 0.342021 +-0.939692 0.000000 0.342021 +-0.939692 0.000000 0.342021 +-0.939692 0.000000 0.342021 +-0.939692 0.000000 0.342021 +-0.939692 0.000000 0.342021 +-0.939692 0.000000 0.342021 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.939698 0.000000 -0.342006 +-0.939698 0.000000 -0.342006 +-0.939698 0.000000 -0.342006 +-0.939698 0.000000 -0.342006 +-0.939698 0.000000 -0.342006 +-0.939698 0.000000 -0.342006 +-0.939698 0.000000 -0.342006 +-0.939698 0.000000 -0.342006 +-0.939698 0.000000 -0.342006 +-0.939698 0.000000 -0.342006 +-0.939698 0.000000 -0.342006 +-0.939698 0.000000 -0.342006 +-0.766032 0.000000 -0.642802 +-0.766032 0.000000 -0.642802 +-0.766032 0.000000 -0.642802 +-0.766032 0.000000 -0.642802 +-0.766032 0.000000 -0.642802 +-0.766032 0.000000 -0.642802 +-0.766032 0.000000 -0.642802 +-0.766032 0.000000 -0.642802 +-0.766032 0.000000 -0.642802 +-0.766032 0.000000 -0.642802 +-0.766032 0.000000 -0.642802 +-0.766032 0.000000 -0.642802 +-0.499992 0.000000 -0.866030 +-0.499992 0.000000 -0.866030 +-0.499992 0.000000 -0.866030 +-0.499992 0.000000 -0.866030 +-0.499992 0.000000 -0.866030 +-0.499992 0.000000 -0.866030 +-0.499992 0.000000 -0.866030 +-0.499992 0.000000 -0.866030 +-0.499992 0.000000 -0.866030 +-0.499992 0.000000 -0.866030 +-0.499992 0.000000 -0.866030 +-0.499992 0.000000 -0.866030 +-0.173673 0.000000 -0.984803 +-0.173673 0.000000 -0.984803 +-0.173673 0.000000 -0.984803 +-0.173673 0.000000 -0.984803 +-0.173673 0.000000 -0.984803 +-0.173673 0.000000 -0.984803 +-0.173673 0.000000 -0.984803 +-0.173673 0.000000 -0.984803 +-0.173673 0.000000 -0.984803 +-0.173673 0.000000 -0.984803 +-0.173673 0.000000 -0.984803 +-0.173673 0.000000 -0.984803 +0.173673 0.000000 -0.984803 +0.173673 0.000000 -0.984803 +0.173673 0.000000 -0.984803 +0.173673 0.000000 -0.984803 +0.173673 0.000000 -0.984803 +0.173673 0.000000 -0.984803 +0.173673 0.000000 -0.984803 +0.173673 0.000000 -0.984803 +0.173673 0.000000 -0.984803 +0.173673 0.000000 -0.984803 +0.173673 0.000000 -0.984803 +0.173665 -0.000019 -0.984805 +0.499993 0.000000 -0.866029 +0.499993 0.000000 -0.866029 +0.499993 0.000000 -0.866029 +0.499993 0.000000 -0.866029 +0.499993 0.000000 -0.866029 +0.499993 0.000000 -0.866029 +0.499993 -0.000054 -0.866029 +0.499993 -0.000054 -0.866029 +0.499993 -0.000054 -0.866029 +0.499993 -0.000054 -0.866029 +0.499993 -0.000054 -0.866029 +0.499992 -0.000056 -0.866030 +0.766032 0.000000 -0.642802 +0.766032 0.000000 -0.642802 +0.766032 0.000000 -0.642802 +0.766032 0.000000 -0.642802 +0.766032 0.000000 -0.642802 +0.766032 0.000000 -0.642802 +0.766032 0.000000 -0.642802 +0.766056 -0.000086 -0.642774 +0.766056 -0.000086 -0.642774 +0.766056 -0.000086 -0.642774 +0.766056 -0.000086 -0.642774 +0.766056 -0.000086 -0.642774 +0.939683 0.000000 -0.342048 +0.939683 0.000000 -0.342048 +0.939683 0.000000 -0.342048 +0.939683 0.000000 -0.342048 +0.939683 0.000000 -0.342048 +0.939683 0.000000 -0.342048 +0.939683 0.000000 -0.342048 +0.939683 0.000000 -0.342048 +0.939683 0.000000 -0.342048 +0.939683 0.000000 -0.342048 +0.939683 0.000000 -0.342048 +0.939683 0.000000 -0.342048 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.939677 0.000000 0.342063 +0.939677 0.000000 0.342063 +0.939677 0.000000 0.342063 +0.939677 0.000000 0.342063 +0.939677 0.000000 0.342063 +0.939677 0.000000 0.342063 +0.939677 0.000000 0.342063 +0.939677 0.000000 0.342063 +0.939677 0.000000 0.342063 +0.939677 0.000000 0.342063 +0.939677 0.000000 0.342063 +0.939677 0.000000 0.342063 +0.766052 0.000000 0.642779 +0.766052 0.000000 0.642779 +0.766052 0.000000 0.642779 +0.766052 0.000000 0.642779 +0.766052 0.000000 0.642779 +0.766052 0.000000 0.642779 +0.766075 -0.000086 0.642751 +0.766075 -0.000086 0.642751 +0.766075 -0.000086 0.642751 +0.766075 -0.000086 0.642751 +0.766075 -0.000086 0.642751 +0.766052 0.000000 0.642779 +0.499993 0.000000 0.866030 +0.499993 0.000000 0.866030 +0.499993 0.000000 0.866029 +0.499993 0.000000 0.866030 +0.499993 0.000000 0.866029 +0.499993 0.000000 0.866030 +0.499993 -0.000054 0.866029 +0.499992 -0.000056 0.866030 +0.499992 -0.000056 0.866030 +0.499992 -0.000056 0.866030 +0.499992 -0.000056 0.866030 +0.499992 -0.000056 0.866030 +0.173673 -0.000109 0.984803 +0.173673 -0.000109 0.984803 +0.173673 -0.000109 0.984803 +0.173673 -0.000109 0.984803 +0.173673 -0.000109 0.984803 +0.173628 0.000000 0.984811 +0.173673 0.000000 0.984803 +0.173665 -0.000019 0.984805 +0.173665 -0.000019 0.984805 +0.173665 -0.000019 0.984805 +0.173665 -0.000019 0.984805 +0.173665 -0.000019 0.984805 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.442031 0.000000 0.897000 +0.355384 0.000000 0.934720 +0.442031 0.000000 0.897000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.442031 0.000000 0.897000 +0.442031 0.000000 0.897000 +0.517879 0.000000 0.855454 +0.449773 0.016898 0.892983 +0.449773 0.016898 0.892983 +0.449773 0.016898 0.892983 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.355106 -0.072741 -0.931992 +0.355106 -0.072741 -0.931992 +0.355106 -0.072741 -0.931992 +0.307115 -0.003015 -0.951668 +0.307115 -0.003015 -0.951668 +0.307115 -0.003015 -0.951668 +0.307115 0.003015 -0.951668 +0.307115 0.003015 -0.951668 +0.307115 0.003015 -0.951668 +0.355106 0.072741 -0.931992 +0.355106 0.072741 -0.931992 +0.355106 0.072741 -0.931992 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.173657 0.000000 0.984806 +-0.173657 0.000000 0.984806 +-0.173657 0.000000 0.984806 +-0.173657 0.000000 0.984806 +-0.173657 0.000000 0.984806 +-0.173657 0.000000 0.984806 +-0.499998 0.000000 0.866027 +-0.499998 0.000000 0.866027 +-0.499998 0.000000 0.866026 +-0.499998 0.000000 0.866026 +-0.499998 0.000000 0.866027 +-0.499998 0.000000 0.866027 +-0.766056 0.000000 0.642774 +-0.766056 0.000000 0.642774 +-0.766056 0.000000 0.642774 +-0.766056 0.000000 0.642774 +-0.766056 0.000000 0.642774 +-0.766056 0.000000 0.642774 +-0.939689 0.000000 0.342030 +-0.939689 0.000000 0.342030 +-0.939689 0.000000 0.342030 +-0.939689 0.000000 0.342030 +-0.939689 0.000000 0.342030 +-0.939689 0.000000 0.342030 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.939689 0.000000 -0.342030 +-0.939689 0.000000 -0.342030 +-0.939689 0.000000 -0.342030 +-0.939689 0.000000 -0.342030 +-0.939689 0.000000 -0.342030 +-0.939689 0.000000 -0.342030 +-0.766056 0.000000 -0.642774 +-0.766056 0.000000 -0.642774 +-0.766056 0.000000 -0.642774 +-0.766056 0.000000 -0.642774 +-0.766056 0.000000 -0.642774 +-0.766056 0.000000 -0.642774 +-0.499998 0.000000 -0.866027 +-0.499998 0.000000 -0.866027 +-0.499998 0.000000 -0.866027 +-0.499998 0.000000 -0.866027 +-0.499998 0.000000 -0.866027 +-0.499998 0.000000 -0.866027 +-0.173632 0.000000 -0.984810 +-0.173632 0.000000 -0.984811 +-0.173632 0.000000 -0.984811 +-0.173632 0.000000 -0.984810 +-0.173632 0.000000 -0.984811 +-0.173632 0.000000 -0.984811 +0.173628 0.000000 -0.984811 +0.173628 0.000000 -0.984811 +0.173628 0.000000 -0.984811 +0.173628 0.000000 -0.984811 +0.173628 0.000000 -0.984811 +0.173628 0.000000 -0.984811 +0.500008 0.000000 -0.866021 +0.500008 0.000000 -0.866021 +0.500008 0.000000 -0.866021 +0.500008 0.000000 -0.866021 +0.500008 0.000000 -0.866021 +0.500008 0.000000 -0.866021 +0.766043 0.000000 -0.642789 +0.766043 0.000000 -0.642789 +0.766043 0.000000 -0.642789 +0.766043 0.000000 -0.642789 +0.766043 0.000000 -0.642789 +0.766043 0.000000 -0.642789 +0.939689 0.000000 -0.342030 +0.939689 0.000000 -0.342030 +0.939689 0.000000 -0.342030 +0.939689 0.000000 -0.342030 +0.939689 0.000000 -0.342030 +0.939689 0.000000 -0.342030 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.939689 0.000000 0.342030 +0.939689 0.000000 0.342030 +0.939689 0.000000 0.342030 +0.939689 0.000000 0.342030 +0.939689 0.000000 0.342030 +0.939689 0.000000 0.342030 +0.766043 0.000000 0.642789 +0.766043 0.000000 0.642789 +0.766043 0.000000 0.642789 +0.766043 0.000000 0.642789 +0.766043 0.000000 0.642789 +0.766043 0.000000 0.642789 +0.500008 0.000000 0.866021 +0.500008 0.000000 0.866021 +0.500008 0.000000 0.866021 +0.500008 0.000000 0.866021 +0.500008 0.000000 0.866021 +0.500008 0.000000 0.866021 +0.173653 0.000000 0.984807 +0.173653 0.000000 0.984807 +0.173653 0.000000 0.984807 +0.173653 0.000000 0.984807 +0.173653 0.000000 0.984807 +0.173653 0.000000 0.984807 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.173533 -0.000006 0.984828 +-0.173533 -0.000006 0.984828 +-0.173533 -0.000006 0.984828 +-0.173533 -0.000006 0.984828 +-0.173533 -0.000006 0.984828 +-0.173538 0.000000 0.984827 +-0.499729 -0.000013 0.866182 +-0.499725 -0.000018 0.866184 +-0.499729 -0.000013 0.866182 +-0.499725 -0.000018 0.866184 +-0.499729 -0.000013 0.866182 +-0.499729 -0.000013 0.866182 +-0.765791 0.000005 0.643089 +-0.765794 0.000000 0.643086 +-0.765794 0.000000 0.643086 +-0.765794 0.000000 0.643086 +-0.765794 0.000000 0.643086 +-0.765794 0.000000 0.643086 +-0.939598 -0.000012 0.342279 +-0.939598 -0.000012 0.342279 +-0.939595 0.000000 0.342288 +-0.939598 -0.000012 0.342279 +-0.939598 -0.000012 0.342279 +-0.939598 -0.000012 0.342279 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.939595 0.000000 -0.342288 +-0.939595 0.000000 -0.342288 +-0.939595 0.000000 -0.342288 +-0.939595 0.000000 -0.342288 +-0.939595 0.000000 -0.342288 +-0.939595 0.000000 -0.342288 +-0.765794 0.000000 -0.643087 +-0.765794 0.000000 -0.643087 +-0.765794 0.000000 -0.643086 +-0.765794 0.000000 -0.643087 +-0.765794 0.000000 -0.643087 +-0.765794 0.000000 -0.643086 +-0.499737 0.000000 -0.866177 +-0.499737 0.000000 -0.866177 +-0.499737 0.000000 -0.866177 +-0.499737 0.000000 -0.866177 +-0.499737 0.000000 -0.866177 +-0.499737 0.000000 -0.866177 +-0.173538 0.000000 -0.984827 +-0.173538 0.000000 -0.984827 +-0.173538 0.000000 -0.984827 +-0.173538 0.000000 -0.984827 +-0.173538 0.000000 -0.984827 +-0.173538 0.000000 -0.984827 +0.173538 0.000000 -0.984827 +0.173538 0.000000 -0.984827 +0.173538 0.000000 -0.984827 +0.173538 0.000000 -0.984827 +0.173538 0.000000 -0.984827 +0.173538 0.000000 -0.984827 +0.499737 0.000000 -0.866177 +0.499737 0.000000 -0.866177 +0.499737 0.000000 -0.866177 +0.499737 0.000000 -0.866177 +0.499737 0.000000 -0.866177 +0.499737 0.000000 -0.866177 +0.765794 0.000000 -0.643086 +0.765794 0.000000 -0.643087 +0.765794 0.000000 -0.643087 +0.765794 0.000000 -0.643087 +0.765794 0.000000 -0.643087 +0.765794 0.000000 -0.643086 +0.939595 0.000000 -0.342288 +0.939595 0.000000 -0.342288 +0.939595 0.000000 -0.342288 +0.939595 0.000000 -0.342288 +0.939595 0.000000 -0.342288 +0.939595 0.000000 -0.342288 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.939595 0.000033 0.342288 +0.939595 0.000033 0.342288 +0.939595 0.000033 0.342288 +0.939595 0.000033 0.342288 +0.939604 0.000000 0.342264 +0.939595 0.000033 0.342288 +0.765805 -0.000023 0.643073 +0.765805 -0.000023 0.643073 +0.765805 -0.000023 0.643073 +0.765805 -0.000023 0.643073 +0.765780 0.000027 0.643102 +0.765805 -0.000023 0.643073 +0.499717 0.000000 0.866189 +0.499717 0.000000 0.866189 +0.499717 0.000000 0.866189 +0.499717 0.000000 0.866189 +0.499717 0.000000 0.866189 +0.499737 -0.000031 0.866177 +0.173542 0.000000 0.984827 +0.173542 0.000000 0.984826 +0.173542 0.000000 0.984826 +0.173542 0.000000 0.984826 +0.173542 0.000000 0.984827 +0.173542 0.000000 0.984826 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.173657 0.000000 0.984806 +-0.173657 0.000000 0.984806 +-0.173657 0.000000 0.984806 +-0.173657 0.000000 0.984806 +-0.173657 0.000000 0.984806 +-0.173657 0.000000 0.984806 +-0.499998 0.000000 0.866027 +-0.499998 0.000000 0.866026 +-0.499998 0.000000 0.866027 +-0.499998 0.000000 0.866026 +-0.499998 0.000000 0.866027 +-0.499998 0.000000 0.866027 +-0.766056 0.000000 0.642774 +-0.766056 0.000000 0.642774 +-0.766056 0.000000 0.642774 +-0.766056 0.000000 0.642774 +-0.766056 0.000000 0.642774 +-0.766056 0.000000 0.642774 +-0.939689 0.000000 0.342030 +-0.939689 0.000000 0.342030 +-0.939689 0.000000 0.342030 +-0.939689 0.000000 0.342030 +-0.939689 0.000000 0.342030 +-0.939689 0.000000 0.342030 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.939689 0.000000 -0.342030 +-0.939689 0.000000 -0.342030 +-0.939689 0.000000 -0.342030 +-0.939689 0.000000 -0.342030 +-0.939689 0.000000 -0.342030 +-0.939689 0.000000 -0.342030 +-0.766056 0.000000 -0.642774 +-0.766056 0.000000 -0.642774 +-0.766056 0.000000 -0.642774 +-0.766056 0.000000 -0.642774 +-0.766056 0.000000 -0.642774 +-0.766056 0.000000 -0.642774 +-0.499998 0.000000 -0.866027 +-0.499998 0.000000 -0.866027 +-0.499998 0.000000 -0.866027 +-0.499998 0.000000 -0.866027 +-0.499998 0.000000 -0.866027 +-0.499998 0.000000 -0.866027 +-0.173632 0.000000 -0.984811 +-0.173632 0.000000 -0.984810 +-0.173632 0.000000 -0.984811 +-0.173632 0.000000 -0.984810 +-0.173632 0.000000 -0.984811 +-0.173632 0.000000 -0.984811 +0.173628 0.000000 -0.984811 +0.173628 0.000000 -0.984811 +0.173628 0.000000 -0.984811 +0.173628 0.000000 -0.984811 +0.173628 0.000000 -0.984811 +0.173628 0.000000 -0.984811 +0.500008 0.000000 -0.866021 +0.500008 0.000000 -0.866021 +0.500008 0.000000 -0.866021 +0.500008 0.000000 -0.866021 +0.500008 0.000000 -0.866021 +0.500008 0.000000 -0.866021 +0.766043 0.000000 -0.642789 +0.766043 0.000000 -0.642789 +0.766043 0.000000 -0.642789 +0.766043 0.000000 -0.642789 +0.766043 0.000000 -0.642789 +0.766043 0.000000 -0.642789 +0.939689 0.000000 -0.342030 +0.939689 0.000000 -0.342030 +0.939689 0.000000 -0.342030 +0.939689 0.000000 -0.342030 +0.939689 0.000000 -0.342030 +0.939689 0.000000 -0.342030 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.939689 0.000000 0.342030 +0.939689 0.000000 0.342030 +0.939689 0.000000 0.342030 +0.939689 0.000000 0.342030 +0.939689 0.000000 0.342030 +0.939689 0.000000 0.342030 +0.766043 0.000000 0.642789 +0.766043 0.000000 0.642789 +0.766043 0.000000 0.642789 +0.766043 0.000000 0.642789 +0.766043 0.000000 0.642789 +0.766043 0.000000 0.642789 +0.500008 0.000000 0.866021 +0.500008 0.000000 0.866021 +0.500008 0.000000 0.866021 +0.500008 0.000000 0.866021 +0.500008 0.000000 0.866021 +0.500008 0.000000 0.866021 +0.173653 0.000000 0.984807 +0.173653 0.000000 0.984807 +0.173653 0.000000 0.984807 +0.173653 0.000000 0.984807 +0.173653 0.000000 0.984807 +0.173653 0.000000 0.984807 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.173538 0.000000 0.984827 +-0.173538 0.000000 0.984827 +-0.173538 0.000000 0.984827 +-0.173538 0.000000 0.984827 +-0.173533 0.000006 0.984828 +-0.173538 0.000000 0.984827 +-0.499725 0.000018 0.866184 +-0.499729 0.000013 0.866182 +-0.499725 0.000018 0.866184 +-0.499729 0.000013 0.866182 +-0.499725 0.000018 0.866184 +-0.499725 0.000018 0.866184 +-0.765791 -0.000005 0.643089 +-0.765791 -0.000005 0.643089 +-0.765791 -0.000005 0.643089 +-0.765791 -0.000005 0.643089 +-0.765794 0.000000 0.643086 +-0.765791 -0.000005 0.643089 +-0.939595 0.000000 0.342288 +-0.939595 0.000000 0.342288 +-0.939595 0.000000 0.342288 +-0.939595 0.000000 0.342288 +-0.939598 0.000012 0.342279 +-0.939595 0.000000 0.342288 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.939595 0.000000 -0.342288 +-0.939595 0.000000 -0.342288 +-0.939595 0.000000 -0.342288 +-0.939595 0.000000 -0.342288 +-0.939595 0.000000 -0.342288 +-0.939595 0.000000 -0.342288 +-0.765794 0.000000 -0.643086 +-0.765794 0.000000 -0.643087 +-0.765794 0.000000 -0.643087 +-0.765794 0.000000 -0.643087 +-0.765794 0.000000 -0.643086 +-0.765794 0.000000 -0.643087 +-0.499737 0.000000 -0.866177 +-0.499737 0.000000 -0.866177 +-0.499737 0.000000 -0.866177 +-0.499737 0.000000 -0.866177 +-0.499737 0.000000 -0.866177 +-0.499737 0.000000 -0.866177 +-0.173538 0.000000 -0.984827 +-0.173538 0.000000 -0.984827 +-0.173538 0.000000 -0.984827 +-0.173538 0.000000 -0.984827 +-0.173538 0.000000 -0.984827 +-0.173538 0.000000 -0.984827 +0.173538 0.000000 -0.984827 +0.173538 0.000000 -0.984827 +0.173538 0.000000 -0.984827 +0.173538 0.000000 -0.984827 +0.173538 0.000000 -0.984827 +0.173538 0.000000 -0.984827 +0.499737 0.000000 -0.866177 +0.499737 0.000000 -0.866177 +0.499737 0.000000 -0.866177 +0.499737 0.000000 -0.866177 +0.499737 0.000000 -0.866177 +0.499737 0.000000 -0.866177 +0.765794 0.000000 -0.643086 +0.765794 0.000000 -0.643087 +0.765794 0.000000 -0.643087 +0.765794 0.000000 -0.643087 +0.765794 0.000000 -0.643086 +0.765794 0.000000 -0.643087 +0.939595 0.000000 -0.342288 +0.939595 0.000000 -0.342288 +0.939595 0.000000 -0.342288 +0.939595 0.000000 -0.342288 +0.939595 0.000000 -0.342288 +0.939595 0.000000 -0.342288 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.939595 -0.000033 0.342288 +0.939595 -0.000033 0.342288 +0.939595 -0.000033 0.342288 +0.939595 -0.000033 0.342288 +0.939595 -0.000033 0.342288 +0.939604 0.000000 0.342264 +0.765805 0.000023 0.643073 +0.765805 0.000023 0.643073 +0.765805 0.000023 0.643073 +0.765805 0.000023 0.643073 +0.765805 0.000023 0.643073 +0.765780 -0.000027 0.643102 +0.499737 0.000031 0.866177 +0.499737 0.000031 0.866177 +0.499737 0.000031 0.866177 +0.499737 0.000031 0.866177 +0.499717 0.000000 0.866189 +0.499737 0.000031 0.866177 +0.173542 0.000000 0.984826 +0.173542 0.000000 0.984826 +0.173542 0.000000 0.984827 +0.173542 0.000000 0.984826 +0.173542 0.000000 0.984826 +0.173542 0.000000 0.984827 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.500005 0.866023 0.000000 +-0.500005 0.866023 0.000000 +-0.500005 0.866023 0.000000 +-0.500005 0.866023 0.000000 +-0.500005 0.866023 0.000000 +-0.500005 0.866023 0.000000 +-0.939694 0.342017 0.000000 +-0.939694 0.342017 0.000000 +-0.939694 0.342017 0.000000 +-0.939694 0.342017 0.000000 +-0.939694 0.342017 0.000000 +-0.939694 0.342017 0.000000 +-0.939694 -0.342017 0.000000 +-0.939694 -0.342017 0.000000 +-0.939694 -0.342017 0.000000 +-0.939694 -0.342017 0.000000 +-0.939694 -0.342017 0.000000 +-0.939694 -0.342017 0.000000 +-0.500005 -0.866023 0.000000 +-0.500005 -0.866023 0.000000 +-0.500005 -0.866023 0.000000 +-0.500005 -0.866023 0.000000 +-0.500005 -0.866023 0.000000 +-0.500005 -0.866023 0.000000 +0.173669 -0.984804 0.000000 +0.173669 -0.984804 0.000000 +0.173669 -0.984804 0.000000 +0.173669 -0.984804 0.000000 +0.173669 -0.984804 0.000000 +0.173669 -0.984804 0.000000 +0.766027 -0.642808 0.000000 +0.766027 -0.642808 0.000000 +0.766027 -0.642808 0.000000 +0.766027 -0.642808 0.000000 +0.766027 -0.642808 0.000000 +0.766027 -0.642808 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.766027 0.642808 0.000000 +0.766027 0.642808 0.000000 +0.766027 0.642808 0.000000 +0.766027 0.642808 0.000000 +0.766027 0.642808 0.000000 +0.766027 0.642808 0.000000 +0.173669 0.984804 0.000000 +0.173669 0.984804 0.000000 +0.173669 0.984804 0.000000 +0.173669 0.984804 0.000000 +0.173669 0.984804 0.000000 +0.173669 0.984804 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.500010 0.866020 0.000000 +-0.500010 0.866020 0.000000 +-0.500010 0.866020 0.000000 +-0.500010 0.866020 0.000000 +-0.500010 0.866020 0.000000 +-0.500010 0.866020 0.000000 +-0.939679 0.342057 0.000000 +-0.939679 0.342057 0.000000 +-0.939679 0.342057 0.000000 +-0.939679 0.342057 0.000000 +-0.939679 0.342057 0.000000 +-0.939679 0.342057 0.000000 +-0.939679 -0.342057 0.000000 +-0.939679 -0.342057 0.000000 +-0.939679 -0.342057 0.000000 +-0.939679 -0.342057 0.000000 +-0.939679 -0.342057 0.000000 +-0.939679 -0.342057 0.000000 +-0.500010 -0.866020 0.000000 +-0.500010 -0.866020 0.000000 +-0.500010 -0.866020 0.000000 +-0.500010 -0.866020 0.000000 +-0.500010 -0.866020 0.000000 +-0.500010 -0.866020 0.000000 +0.173663 -0.984805 0.000000 +0.173663 -0.984805 0.000000 +0.173663 -0.984805 0.000000 +0.173663 -0.984805 0.000000 +0.173663 -0.984805 0.000000 +0.173663 -0.984805 0.000000 +0.766029 -0.642806 0.000000 +0.766029 -0.642806 0.000000 +0.766029 -0.642806 0.000000 +0.766029 -0.642806 0.000000 +0.766029 -0.642806 0.000000 +0.766029 -0.642806 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.766029 0.642806 0.000000 +0.766029 0.642806 0.000000 +0.766029 0.642806 0.000000 +0.766029 0.642806 0.000000 +0.766029 0.642806 0.000000 +0.766029 0.642806 0.000000 +0.173663 0.984805 0.000000 +0.173663 0.984805 0.000000 +0.173663 0.984805 0.000000 +0.173663 0.984805 0.000000 +0.173663 0.984805 0.000000 +0.173663 0.984805 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.173602 0.984816 0.000000 +0.173602 0.984816 0.000000 +0.173602 0.984816 0.000000 +0.173602 0.984816 0.000000 +0.173602 0.984816 0.000000 +0.173602 0.984816 0.000000 +0.766075 0.642751 0.000000 +0.766075 0.642751 0.000000 +0.766075 0.642751 0.000000 +0.766075 0.642751 0.000000 +0.766075 0.642751 0.000000 +0.766075 0.642751 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.766075 -0.642751 0.000000 +0.766075 -0.642751 0.000000 +0.766075 -0.642751 0.000000 +0.766075 -0.642751 0.000000 +0.766075 -0.642751 0.000000 +0.766075 -0.642751 0.000000 +0.173602 -0.984816 0.000000 +0.173602 -0.984816 0.000000 +0.173602 -0.984816 0.000000 +0.173602 -0.984816 0.000000 +0.173602 -0.984816 0.000000 +0.173602 -0.984816 0.000000 +-0.499960 -0.866048 0.000000 +-0.499960 -0.866049 0.000000 +-0.499960 -0.866048 0.000000 +-0.499960 -0.866048 0.000000 +-0.499960 -0.866049 0.000000 +-0.499960 -0.866048 0.000000 +-0.939700 -0.342000 0.000000 +-0.939700 -0.342000 0.000000 +-0.939700 -0.342000 0.000000 +-0.939700 -0.342000 0.000000 +-0.939700 -0.342000 0.000000 +-0.939700 -0.342000 0.000000 +-0.939700 0.342000 0.000000 +-0.939700 0.342000 0.000000 +-0.939700 0.342000 0.000000 +-0.939700 0.342000 0.000000 +-0.939700 0.342000 0.000000 +-0.939700 0.342000 0.000000 +-0.499960 0.866048 0.000000 +-0.499960 0.866049 0.000000 +-0.499960 0.866048 0.000000 +-0.499960 0.866048 0.000000 +-0.499960 0.866049 0.000000 +-0.499960 0.866048 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.999217 0.000000 0.039571 +0.999217 0.000000 0.039571 +0.999217 0.000000 0.039571 +0.999217 0.000000 0.039571 +0.999217 0.000000 0.039571 +0.999217 0.000000 0.039571 +-0.999993 0.000000 0.003806 +-0.999993 0.000000 0.003806 +-0.999993 0.000000 0.003806 +-0.999993 0.000000 0.003806 +-0.999993 0.000000 0.003806 +-0.999993 0.000000 0.003806 +0.000000 -0.999493 0.031854 +0.000000 -0.999493 0.031854 +0.000000 -0.999493 0.031854 +0.000000 -0.999493 0.031854 +0.000000 -0.999492 0.031854 +0.000000 -0.999493 0.031854 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.999493 0.031854 +0.000000 0.999493 0.031854 +0.000000 0.999493 0.031854 +0.000000 0.999493 0.031854 +0.000000 0.999493 0.031854 +0.000000 0.999492 0.031854 +0.259379 0.057080 -0.964087 +0.259379 0.057080 -0.964087 +0.259379 0.057080 -0.964087 +0.259379 0.057080 -0.964087 +0.258521 0.057163 -0.964313 +0.259379 0.057080 -0.964087 +0.966091 0.015210 -0.257754 +0.965828 0.015188 -0.258739 +0.965828 0.015188 -0.258739 +0.965828 0.015188 -0.258739 +0.965828 0.015188 -0.258739 +0.965828 0.015188 -0.258739 +0.707866 -0.041207 0.705144 +0.706501 -0.041137 0.706515 +0.706501 -0.041137 0.706515 +0.706501 -0.041137 0.706515 +0.706501 -0.041137 0.706515 +0.706501 -0.041137 0.706515 +-0.258357 -0.056153 0.964416 +-0.258357 -0.056153 0.964416 +-0.258357 -0.056153 0.964416 +-0.258357 -0.056153 0.964416 +-0.258357 -0.056153 0.964416 +-0.259213 -0.056071 0.964191 +-0.706501 -0.041137 0.706515 +-0.706501 -0.041137 0.706515 +-0.706501 -0.041137 0.706515 +-0.706501 -0.041137 0.706515 +-0.706501 -0.041137 0.706515 +-0.707866 -0.041207 0.705144 +-0.965767 0.015202 -0.258965 +-0.965767 0.015202 -0.258965 +-0.965767 0.015202 -0.258965 +-0.965767 0.015202 -0.258965 +-0.965767 0.015202 -0.258965 +-0.966031 0.015223 -0.257979 +-0.707732 0.041755 -0.705246 +-0.706492 0.041691 -0.706492 +-0.706492 0.041691 -0.706492 +-0.706492 0.041691 -0.706492 +-0.707732 0.041755 -0.705246 +-0.706492 0.041691 -0.706492 +0.258716 0.137904 -0.956059 +0.258716 0.137904 -0.956059 +0.258716 0.137904 -0.956059 +0.258716 0.137904 -0.956059 +0.258539 0.137937 -0.956102 +0.258716 0.137904 -0.956059 +0.965884 0.036967 -0.256325 +0.965867 0.036967 -0.256386 +0.965867 0.036967 -0.256386 +0.965868 0.036967 -0.256386 +0.965867 0.036967 -0.256386 +0.965867 0.036967 -0.256386 +0.706715 -0.100936 0.700261 +0.706647 -0.100933 0.700331 +0.706647 -0.100933 0.700331 +0.706647 -0.100933 0.700331 +0.706647 -0.100933 0.700331 +0.706647 -0.100933 0.700331 +-0.258378 -0.137804 0.956165 +-0.258378 -0.137804 0.956165 +-0.258378 -0.137804 0.956165 +-0.258378 -0.137804 0.956165 +-0.258378 -0.137804 0.956165 +-0.258537 -0.137777 0.956126 +-0.706647 -0.100933 0.700331 +-0.706647 -0.100933 0.700331 +-0.706647 -0.100933 0.700331 +-0.706647 -0.100933 0.700331 +-0.706647 -0.100933 0.700331 +-0.706715 -0.100936 0.700261 +-0.965807 0.037000 -0.256609 +-0.965807 0.037000 -0.256609 +-0.965807 0.037000 -0.256609 +-0.965807 0.037000 -0.256609 +-0.965807 0.037000 -0.256609 +-0.965823 0.037000 -0.256549 +-0.706576 0.101026 -0.700389 +-0.706499 0.101022 -0.700466 +-0.706499 0.101022 -0.700466 +-0.706499 0.101022 -0.700466 +-0.706576 0.101026 -0.700389 +-0.706499 0.101022 -0.700466 +0.260078 0.182539 -0.948177 +0.260078 0.182539 -0.948177 +0.260078 0.182539 -0.948177 +0.260078 0.182539 -0.948177 +0.259102 0.182870 -0.948380 +0.260078 0.182539 -0.948177 +0.965987 0.048715 -0.253962 +0.965987 0.048715 -0.253962 +0.966128 0.048465 -0.253470 +0.965987 0.048715 -0.253962 +0.965987 0.048715 -0.253962 +0.965986 0.048715 -0.253962 +0.707281 -0.132502 0.694404 +0.707281 -0.132502 0.694404 +0.707650 -0.132297 0.694067 +0.707281 -0.132502 0.694404 +0.707281 -0.132502 0.694404 +0.707281 -0.132502 0.694404 +-0.258920 -0.180854 0.948816 +-0.259123 -0.180790 0.948773 +-0.259123 -0.180790 0.948773 +-0.259123 -0.180790 0.948773 +-0.259123 -0.180790 0.948773 +-0.259123 -0.180790 0.948773 +-0.707281 -0.132502 0.694404 +-0.707650 -0.132297 0.694067 +-0.707650 -0.132297 0.694067 +-0.707650 -0.132297 0.694067 +-0.707650 -0.132297 0.694067 +-0.707650 -0.132297 0.694067 +-0.966068 0.048507 -0.253691 +-0.966068 0.048507 -0.253691 +-0.966068 0.048507 -0.253691 +-0.966068 0.048507 -0.253691 +-0.965926 0.048757 -0.254184 +-0.966068 0.048507 -0.253691 +-0.708335 0.132976 -0.693238 +-0.708335 0.132976 -0.693238 +-0.708335 0.132976 -0.693238 +-0.708335 0.132976 -0.693238 +-0.708335 0.132976 -0.693238 +-0.707148 0.133667 -0.694316 +0.249793 0.869097 -0.426935 +0.249793 0.869097 -0.426935 +0.249793 0.869097 -0.426935 +0.249793 0.869097 -0.426935 +0.249793 0.869097 -0.426935 +0.257022 0.868415 -0.424023 +0.963654 0.238290 -0.120786 +0.963654 0.238290 -0.120786 +0.963654 0.238290 -0.120786 +0.963654 0.238290 -0.120786 +0.963654 0.238290 -0.120786 +0.965412 0.233331 -0.116344 +0.695676 -0.637891 0.330348 +0.695676 -0.637891 0.330348 +0.695676 -0.637891 0.330348 +0.695676 -0.637891 0.330348 +0.695676 -0.637891 0.330348 +0.703516 -0.632166 0.324702 +-0.251287 -0.858988 0.446088 +-0.251287 -0.858988 0.446088 +-0.251287 -0.858988 0.446088 +-0.251287 -0.858988 0.446088 +-0.256353 -0.858314 0.444500 +-0.251287 -0.858988 0.446088 +-0.965274 -0.233014 0.118112 +-0.963688 -0.237531 0.122004 +-0.965274 -0.233014 0.118112 +-0.965274 -0.233014 0.118112 +-0.965274 -0.233014 0.118112 +-0.965274 -0.233014 0.118112 +-0.704523 0.636975 -0.312907 +-0.694095 0.644238 -0.321231 +-0.704523 0.636975 -0.312907 +-0.704523 0.636975 -0.312907 +-0.704523 0.636975 -0.312907 +-0.704522 0.636975 -0.312907 +0.258717 0.943465 -0.207219 +0.258717 0.943465 -0.207219 +0.258717 0.943465 -0.207219 +0.258717 0.943465 -0.207219 +0.258717 0.943465 -0.207219 +0.258600 0.943487 -0.207262 +0.965955 0.252687 -0.055506 +0.965955 0.252687 -0.055506 +0.965955 0.252687 -0.055506 +0.965955 0.252687 -0.055506 +0.965955 0.252687 -0.055506 +0.965957 0.252680 -0.055503 +0.707121 -0.690624 0.151721 +0.707121 -0.690624 0.151720 +0.707121 -0.690624 0.151720 +0.707121 -0.690624 0.151720 +0.707121 -0.690624 0.151721 +0.707165 -0.690584 0.151695 +-0.258986 -0.943391 0.207219 +-0.258986 -0.943391 0.207219 +-0.258986 -0.943391 0.207219 +-0.258986 -0.943391 0.207219 +-0.258872 -0.943414 0.207255 +-0.258986 -0.943391 0.207219 +-0.965882 -0.252951 0.055564 +-0.965881 -0.252954 0.055565 +-0.965882 -0.252951 0.055564 +-0.965882 -0.252951 0.055564 +-0.965882 -0.252951 0.055564 +-0.965882 -0.252951 0.055564 +-0.707115 0.690634 -0.151702 +-0.707146 0.690606 -0.151682 +-0.707115 0.690634 -0.151702 +-0.707115 0.690634 -0.151702 +-0.707115 0.690634 -0.151702 +-0.707115 0.690634 -0.151702 +0.258607 0.965251 -0.037588 +0.258607 0.965251 -0.037588 +0.258607 0.965251 -0.037588 +0.258607 0.965251 -0.037588 +0.258607 0.965251 -0.037588 +0.258643 0.965242 -0.037577 +0.965956 0.258509 -0.010064 +0.965956 0.258509 -0.010064 +0.965956 0.258509 -0.010064 +0.965956 0.258509 -0.010064 +0.965957 0.258509 -0.010064 +0.965956 0.258509 -0.010064 +0.707162 -0.706517 0.027504 +0.707162 -0.706517 0.027504 +0.707162 -0.706517 0.027504 +0.707162 -0.706517 0.027504 +0.707144 -0.706534 0.027499 +0.707162 -0.706517 0.027504 +-0.258886 -0.965177 0.037574 +-0.258886 -0.965177 0.037574 +-0.258886 -0.965177 0.037574 +-0.258886 -0.965177 0.037574 +-0.258923 -0.965167 0.037565 +-0.258886 -0.965177 0.037574 +-0.965881 -0.258791 0.010075 +-0.965881 -0.258791 0.010075 +-0.965881 -0.258791 0.010075 +-0.965881 -0.258791 0.010075 +-0.965881 -0.258791 0.010075 +-0.965880 -0.258793 0.010075 +-0.707162 0.706516 -0.027513 +-0.707162 0.706516 -0.027513 +-0.707162 0.706516 -0.027513 +-0.707162 0.706516 -0.027513 +-0.707162 0.706516 -0.027513 +-0.707144 0.706535 -0.027506 +0.258645 0.946258 0.194164 +0.258645 0.946258 0.194164 +0.258645 0.946258 0.194164 +0.258645 0.946258 0.194164 +0.258822 0.946224 0.194090 +0.258645 0.946258 0.194164 +0.965956 0.253430 0.051980 +0.965937 0.253494 0.052016 +0.965956 0.253430 0.051980 +0.965956 0.253430 0.051980 +0.965956 0.253430 0.051980 +0.965956 0.253430 0.051980 +0.707141 -0.692651 -0.142078 +0.707132 -0.692659 -0.142083 +0.707141 -0.692651 -0.142078 +0.707141 -0.692651 -0.142078 +0.707141 -0.692651 -0.142078 +0.707141 -0.692651 -0.142078 +-0.258922 -0.946197 -0.194091 +-0.258922 -0.946197 -0.194091 +-0.258922 -0.946197 -0.194091 +-0.258922 -0.946197 -0.194091 +-0.258922 -0.946197 -0.194091 +-0.258893 -0.946203 -0.194100 +-0.965879 -0.253707 -0.052060 +-0.965879 -0.253707 -0.052060 +-0.965896 -0.253649 -0.052029 +-0.965879 -0.253707 -0.052060 +-0.965879 -0.253707 -0.052060 +-0.965879 -0.253707 -0.052060 +-0.707142 0.692650 0.142077 +-0.707142 0.692650 0.142077 +-0.707163 0.692632 0.142063 +-0.707142 0.692650 0.142077 +-0.707142 0.692650 0.142077 +-0.707142 0.692650 0.142077 +0.258801 0.784223 0.563929 +0.258801 0.784223 0.563929 +0.258801 0.784223 0.563929 +0.258801 0.784223 0.563929 +0.258832 0.784224 0.563914 +0.258801 0.784223 0.563929 +0.965944 0.210072 0.151067 +0.965936 0.210104 0.151077 +0.965936 0.210104 0.151077 +0.965936 0.210104 0.151077 +0.965936 0.210104 0.151077 +0.965936 0.210104 0.151077 +0.707137 -0.574045 -0.412830 +0.707110 -0.574073 -0.412838 +0.707110 -0.574073 -0.412838 +0.707110 -0.574073 -0.412838 +0.707110 -0.574073 -0.412838 +0.707110 -0.574073 -0.412838 +-0.258873 -0.784191 -0.563941 +-0.258873 -0.784191 -0.563941 +-0.258873 -0.784191 -0.563941 +-0.258873 -0.784191 -0.563941 +-0.258873 -0.784191 -0.563941 +-0.258891 -0.784190 -0.563934 +-0.965898 -0.210208 -0.151173 +-0.965898 -0.210208 -0.151173 +-0.965898 -0.210208 -0.151173 +-0.965898 -0.210208 -0.151173 +-0.965898 -0.210208 -0.151173 +-0.965883 -0.210264 -0.151192 +-0.707194 0.574009 0.412783 +-0.707194 0.574009 0.412783 +-0.707194 0.574009 0.412783 +-0.707194 0.574009 0.412783 +-0.707194 0.574009 0.412783 +-0.707151 0.574057 0.412789 +0.258631 0.572412 0.778110 +0.258631 0.572412 0.778110 +0.258631 0.572412 0.778110 +0.258631 0.572412 0.778110 +0.258631 0.572412 0.778110 +0.258848 0.572328 0.778099 +0.965945 0.153321 0.208427 +0.965945 0.153321 0.208427 +0.965945 0.153321 0.208427 +0.965945 0.153321 0.208427 +0.965945 0.153321 0.208427 +0.965945 0.153322 0.208428 +0.707113 -0.419004 -0.569585 +0.707113 -0.419004 -0.569585 +0.707113 -0.419004 -0.569585 +0.707113 -0.419004 -0.569585 +0.707113 -0.419004 -0.569585 +0.707158 -0.418966 -0.569558 +-0.258908 -0.572333 -0.778075 +-0.258908 -0.572333 -0.778076 +-0.258908 -0.572333 -0.778076 +-0.258908 -0.572333 -0.778076 +-0.258847 -0.572354 -0.778080 +-0.258908 -0.572333 -0.778075 +-0.965887 -0.153450 -0.208602 +-0.965884 -0.153460 -0.208610 +-0.965887 -0.153450 -0.208602 +-0.965887 -0.153450 -0.208602 +-0.965887 -0.153450 -0.208602 +-0.965887 -0.153450 -0.208602 +-0.707197 0.418923 0.569540 +-0.707197 0.418923 0.569540 +-0.707197 0.418923 0.569540 +-0.707197 0.418923 0.569540 +-0.707119 0.418993 0.569585 +-0.707197 0.418923 0.569540 +0.258706 0.529180 0.808108 +0.258706 0.529180 0.808108 +0.258706 0.529180 0.808109 +0.258706 0.529180 0.808109 +0.258706 0.529180 0.808108 +0.258635 0.529193 0.808123 +0.965959 0.141720 0.216422 +0.965959 0.141720 0.216422 +0.965959 0.141720 0.216422 +0.965959 0.141720 0.216422 +0.965959 0.141720 0.216422 +0.965945 0.141750 0.216463 +0.707116 -0.387371 -0.591549 +0.707116 -0.387371 -0.591549 +0.707116 -0.387371 -0.591549 +0.707116 -0.387371 -0.591549 +0.707116 -0.387371 -0.591549 +0.707116 -0.387371 -0.591549 +-0.258841 -0.529161 -0.808078 +-0.258841 -0.529161 -0.808078 +-0.258841 -0.529161 -0.808078 +-0.258841 -0.529161 -0.808078 +-0.258788 -0.529170 -0.808089 +-0.258841 -0.529161 -0.808078 +-0.965887 -0.141868 -0.216645 +-0.965887 -0.141868 -0.216645 +-0.965887 -0.141868 -0.216645 +-0.965887 -0.141868 -0.216645 +-0.965887 -0.141868 -0.216645 +-0.965883 -0.141878 -0.216660 +-0.707194 0.387325 0.591485 +-0.707195 0.387325 0.591485 +-0.707195 0.387325 0.591485 +-0.707195 0.387325 0.591485 +-0.707194 0.387325 0.591485 +-0.707122 0.387368 0.591544 +0.250230 0.264178 -0.931448 +0.250230 0.264178 -0.931448 +0.250230 0.264178 -0.931448 +0.250230 0.264178 -0.931448 +0.261145 0.259633 -0.929728 +0.250230 0.264178 -0.931448 +0.963926 0.078006 -0.254485 +0.963926 0.078006 -0.254485 +0.963926 0.078006 -0.254485 +0.963926 0.078006 -0.254485 +0.966420 0.072501 -0.246529 +0.963926 0.078006 -0.254485 +0.697611 -0.220750 0.681622 +0.697611 -0.220750 0.681622 +0.697611 -0.220750 0.681622 +0.697611 -0.220750 0.681622 +0.709164 -0.213105 0.672066 +0.697611 -0.220750 0.681622 +-0.260130 -0.297498 0.918601 +-0.260130 -0.297498 0.918601 +-0.260130 -0.297499 0.918601 +-0.260130 -0.297499 0.918601 +-0.260130 -0.297498 0.918601 +-0.252555 -0.300034 0.919889 +-0.709164 -0.213105 0.672066 +-0.964004 -0.080367 0.253453 +-0.709164 -0.213105 0.672066 +-0.709164 -0.213105 0.672066 +-0.709164 -0.213105 0.672066 +-0.709164 -0.213105 0.672066 +-0.966360 0.072564 -0.246745 +-0.966360 0.072564 -0.246745 +-0.966360 0.072564 -0.246745 +-0.695363 0.202761 -0.689463 +-0.695363 0.202761 -0.689463 +-0.695363 0.202761 -0.689463 +-0.695363 0.202761 -0.689463 +-0.695363 0.202761 -0.689463 +-0.709910 0.192173 -0.677567 +0.250892 0.528960 -0.810712 +0.250892 0.528960 -0.810713 +0.250892 0.528960 -0.810712 +0.250892 0.528960 -0.810713 +0.260084 0.524679 -0.810598 +0.250892 0.528960 -0.810712 +0.966238 0.142746 -0.214496 +0.966238 0.142746 -0.214496 +0.964081 0.149456 -0.219571 +0.966238 0.142746 -0.214496 +0.966238 0.142746 -0.214496 +0.966238 0.142746 -0.214496 +0.708345 -0.402275 0.580019 +0.708345 -0.402275 0.580019 +0.708345 -0.402275 0.580019 +0.708345 -0.402275 0.580019 +0.708345 -0.402275 0.580019 +0.698304 -0.411236 0.585880 +-0.259590 -0.554817 0.790437 +-0.259590 -0.554817 0.790437 +-0.259590 -0.554817 0.790437 +-0.259590 -0.554817 0.790437 +-0.259590 -0.554817 0.790437 +-0.253045 -0.557315 0.790802 +-0.964159 -0.151210 0.218021 +-0.964159 -0.151210 0.218021 +-0.964159 -0.151210 0.218021 +-0.964159 -0.151210 0.218021 +-0.964159 -0.151210 0.218021 +-0.966131 -0.145203 0.213323 +-0.696103 0.397757 -0.597687 +-0.696103 0.397757 -0.597687 +-0.696103 0.397757 -0.597687 +-0.696103 0.397757 -0.597687 +-0.696103 0.397757 -0.597687 +-0.708954 0.385378 -0.590651 +0.258521 -0.057163 -0.964313 +0.259379 -0.057080 -0.964087 +0.259379 -0.057080 -0.964087 +0.259379 -0.057080 -0.964087 +0.259379 -0.057080 -0.964087 +0.259379 -0.057080 -0.964087 +0.965828 -0.015188 -0.258739 +0.965828 -0.015188 -0.258739 +0.965828 -0.015188 -0.258739 +0.965828 -0.015188 -0.258739 +0.965828 -0.015188 -0.258739 +0.966091 -0.015210 -0.257754 +0.706501 0.041137 0.706515 +0.706501 0.041137 0.706515 +0.706501 0.041137 0.706515 +0.706501 0.041137 0.706515 +0.706501 0.041137 0.706515 +0.707866 0.041207 0.705144 +-0.259213 0.056071 0.964191 +-0.259213 0.056071 0.964191 +-0.259213 0.056071 0.964191 +-0.259213 0.056071 0.964191 +-0.258357 0.056153 0.964416 +-0.259213 0.056071 0.964191 +-0.707866 0.041207 0.705144 +-0.706501 0.041137 0.706515 +-0.706501 0.041137 0.706515 +-0.706501 0.041137 0.706515 +-0.706501 0.041137 0.706515 +-0.706501 0.041137 0.706515 +-0.966031 -0.015223 -0.257979 +-0.965767 -0.015202 -0.258965 +-0.965767 -0.015202 -0.258965 +-0.965767 -0.015202 -0.258965 +-0.965767 -0.015202 -0.258965 +-0.965767 -0.015202 -0.258965 +-0.706492 -0.041691 -0.706492 +-0.707732 -0.041755 -0.705246 +-0.706492 -0.041691 -0.706492 +-0.707732 -0.041755 -0.705246 +-0.706492 -0.041691 -0.706492 +-0.706492 -0.041691 -0.706492 +0.258539 -0.137937 -0.956102 +0.258715 -0.137904 -0.956059 +0.258715 -0.137904 -0.956059 +0.258715 -0.137904 -0.956059 +0.258715 -0.137904 -0.956059 +0.258715 -0.137904 -0.956059 +0.965867 -0.036967 -0.256386 +0.965867 -0.036967 -0.256386 +0.965867 -0.036967 -0.256386 +0.965867 -0.036967 -0.256386 +0.965867 -0.036967 -0.256386 +0.965884 -0.036967 -0.256325 +0.706647 0.100933 0.700331 +0.706647 0.100933 0.700331 +0.706647 0.100933 0.700331 +0.706647 0.100933 0.700331 +0.706647 0.100933 0.700331 +0.706715 0.100936 0.700261 +-0.258538 0.137777 0.956126 +-0.258538 0.137776 0.956125 +-0.258538 0.137776 0.956125 +-0.258538 0.137776 0.956125 +-0.258378 0.137804 0.956165 +-0.258538 0.137777 0.956126 +-0.706715 0.100936 0.700261 +-0.706647 0.100933 0.700331 +-0.706647 0.100933 0.700331 +-0.706647 0.100933 0.700331 +-0.706647 0.100933 0.700331 +-0.706647 0.100933 0.700331 +-0.965823 -0.037000 -0.256549 +-0.965807 -0.037000 -0.256610 +-0.965807 -0.037000 -0.256610 +-0.965807 -0.037000 -0.256610 +-0.965807 -0.037000 -0.256610 +-0.965807 -0.037000 -0.256610 +-0.706499 -0.101022 -0.700466 +-0.706576 -0.101026 -0.700389 +-0.706499 -0.101022 -0.700466 +-0.706576 -0.101026 -0.700389 +-0.706499 -0.101022 -0.700466 +-0.706499 -0.101022 -0.700466 +0.259101 -0.182870 -0.948380 +0.259101 -0.182870 -0.948380 +0.259101 -0.182870 -0.948380 +0.259101 -0.182870 -0.948380 +0.259101 -0.182870 -0.948380 +0.260079 -0.182539 -0.948177 +0.966129 -0.048465 -0.253470 +0.966129 -0.048465 -0.253470 +0.966129 -0.048465 -0.253470 +0.966129 -0.048465 -0.253470 +0.965986 -0.048715 -0.253962 +0.966129 -0.048465 -0.253470 +0.707650 0.132297 0.694067 +0.707650 0.132297 0.694067 +0.707650 0.132297 0.694067 +0.707650 0.132297 0.694067 +0.707281 0.132502 0.694404 +0.707650 0.132297 0.694067 +-0.259124 0.180790 0.948773 +-0.259124 0.180790 0.948773 +-0.259124 0.180790 0.948773 +-0.259124 0.180790 0.948773 +-0.258921 0.180854 0.948816 +-0.259124 0.180790 0.948773 +-0.707650 0.132297 0.694067 +-0.707650 0.132297 0.694067 +-0.707650 0.132297 0.694067 +-0.707650 0.132297 0.694067 +-0.707650 0.132297 0.694067 +-0.707281 0.132502 0.694404 +-0.966068 -0.048507 -0.253691 +-0.966068 -0.048507 -0.253691 +-0.966068 -0.048507 -0.253691 +-0.966068 -0.048507 -0.253691 +-0.966068 -0.048507 -0.253691 +-0.965926 -0.048757 -0.254184 +-0.708335 -0.132976 -0.693238 +-0.708335 -0.132976 -0.693238 +-0.707148 -0.133667 -0.694316 +-0.708335 -0.132976 -0.693238 +-0.708335 -0.132976 -0.693238 +-0.708335 -0.132976 -0.693238 +0.249792 -0.869098 -0.426934 +0.249792 -0.869098 -0.426934 +0.249792 -0.869098 -0.426934 +0.249792 -0.869098 -0.426934 +0.249792 -0.869098 -0.426934 +0.257016 -0.868415 -0.424025 +0.965412 -0.233331 -0.116344 +0.965412 -0.233331 -0.116344 +0.965412 -0.233331 -0.116344 +0.965412 -0.233331 -0.116344 +0.965412 -0.233331 -0.116344 +0.963654 -0.238290 -0.120786 +0.703517 0.632165 0.324702 +0.703517 0.632165 0.324702 +0.703517 0.632165 0.324702 +0.703517 0.632165 0.324702 +0.703517 0.632165 0.324702 +0.695676 0.637890 0.330349 +-0.251287 0.858988 0.446089 +-0.256356 0.858313 0.444500 +-0.256356 0.858313 0.444500 +-0.256356 0.858313 0.444500 +-0.256356 0.858313 0.444500 +-0.256356 0.858313 0.444500 +-0.695676 0.637890 0.330349 +-0.703517 0.632165 0.324702 +-0.703517 0.632165 0.324702 +-0.703517 0.632165 0.324702 +-0.703517 0.632165 0.324702 +-0.703517 0.632165 0.324702 +-0.963589 -0.238497 -0.120891 +-0.963589 -0.238497 -0.120891 +-0.963589 -0.238497 -0.120891 +-0.963589 -0.238497 -0.120891 +-0.963589 -0.238497 -0.120891 +-0.965351 -0.233535 -0.116446 +-0.694097 -0.644236 -0.321231 +-0.704525 -0.636973 -0.312906 +-0.704525 -0.636973 -0.312906 +-0.704525 -0.636973 -0.312906 +-0.704525 -0.636973 -0.312906 +-0.704525 -0.636973 -0.312906 +0.258711 -0.943466 -0.207221 +0.258711 -0.943466 -0.207221 +0.258711 -0.943466 -0.207221 +0.258711 -0.943466 -0.207221 +0.258711 -0.943466 -0.207221 +0.258600 -0.943488 -0.207261 +0.965954 -0.252688 -0.055507 +0.965954 -0.252688 -0.055507 +0.965957 -0.252679 -0.055502 +0.965954 -0.252688 -0.055507 +0.965954 -0.252688 -0.055507 +0.965954 -0.252688 -0.055507 +0.707122 0.690622 0.151720 +0.707122 0.690622 0.151720 +0.707165 0.690584 0.151696 +0.707122 0.690622 0.151720 +0.707122 0.690622 0.151720 +0.707122 0.690622 0.151720 +-0.258989 0.943390 0.207220 +-0.258878 0.943413 0.207255 +-0.258878 0.943413 0.207255 +-0.258878 0.943413 0.207255 +-0.258878 0.943413 0.207255 +-0.258878 0.943413 0.207255 +-0.707122 0.690622 0.151720 +-0.707165 0.690584 0.151696 +-0.707165 0.690584 0.151696 +-0.707165 0.690584 0.151696 +-0.707165 0.690584 0.151696 +-0.707165 0.690584 0.151696 +-0.965894 -0.252908 -0.055556 +-0.965897 -0.252899 -0.055551 +-0.965897 -0.252899 -0.055551 +-0.965897 -0.252899 -0.055551 +-0.965897 -0.252899 -0.055551 +-0.965897 -0.252899 -0.055551 +-0.707117 -0.690632 -0.151701 +-0.707145 -0.690607 -0.151684 +-0.707145 -0.690607 -0.151684 +-0.707145 -0.690607 -0.151684 +-0.707145 -0.690607 -0.151684 +-0.707145 -0.690607 -0.151684 +0.258607 -0.965251 -0.037588 +0.258607 -0.965251 -0.037588 +0.258607 -0.965251 -0.037588 +0.258607 -0.965251 -0.037588 +0.258607 -0.965251 -0.037588 +0.258871 -0.965183 -0.037506 +0.965957 -0.258508 -0.010064 +0.965957 -0.258508 -0.010064 +0.965957 -0.258507 -0.010064 +0.965957 -0.258508 -0.010064 +0.965957 -0.258508 -0.010064 +0.965957 -0.258508 -0.010064 +0.707146 0.706533 0.027498 +0.707146 0.706533 0.027498 +0.707162 0.706517 0.027503 +0.707146 0.706533 0.027498 +0.707146 0.706533 0.027498 +0.707146 0.706533 0.027498 +-0.258891 0.965178 0.037517 +-0.258701 0.965227 0.037566 +-0.258701 0.965227 0.037566 +-0.258701 0.965227 0.037566 +-0.258701 0.965227 0.037566 +-0.258701 0.965227 0.037566 +-0.707162 0.706517 0.027503 +-0.707162 0.706517 0.027503 +-0.707162 0.706517 0.027503 +-0.707162 0.706517 0.027503 +-0.707162 0.706517 0.027503 +-0.707146 0.706533 0.027498 +-0.965896 -0.258733 -0.010072 +-0.965896 -0.258733 -0.010072 +-0.965896 -0.258733 -0.010072 +-0.965896 -0.258733 -0.010072 +-0.965896 -0.258733 -0.010072 +-0.965896 -0.258734 -0.010072 +-0.707160 -0.706518 -0.027513 +-0.707140 -0.706538 -0.027506 +-0.707160 -0.706518 -0.027513 +-0.707140 -0.706538 -0.027506 +-0.707160 -0.706518 -0.027513 +-0.707160 -0.706518 -0.027513 +0.258869 -0.946215 0.194071 +0.258819 -0.946225 0.194092 +0.258819 -0.946225 0.194092 +0.258819 -0.946225 0.194092 +0.258819 -0.946225 0.194092 +0.258819 -0.946225 0.194092 +0.965956 -0.253429 0.051979 +0.965938 -0.253493 0.052015 +0.965938 -0.253493 0.052015 +0.965938 -0.253493 0.052015 +0.965938 -0.253493 0.052015 +0.965938 -0.253493 0.052015 +0.707142 0.692650 -0.142077 +0.707135 0.692656 -0.142081 +0.707135 0.692656 -0.142081 +0.707135 0.692656 -0.142081 +0.707135 0.692656 -0.142081 +0.707135 0.692656 -0.142081 +-0.258704 0.946254 -0.194101 +-0.258704 0.946254 -0.194101 +-0.258704 0.946254 -0.194101 +-0.258704 0.946254 -0.194101 +-0.258704 0.946254 -0.194101 +-0.258883 0.946216 -0.194046 +-0.707142 0.692650 -0.142077 +-0.707135 0.692656 -0.142081 +-0.707142 0.692650 -0.142077 +-0.707142 0.692650 -0.142077 +-0.707142 0.692650 -0.142077 +-0.707142 0.692650 -0.142077 +-0.965896 -0.253651 0.052025 +-0.965877 -0.253715 0.052061 +-0.965896 -0.253651 0.052025 +-0.965896 -0.253651 0.052025 +-0.965896 -0.253651 0.052025 +-0.965896 -0.253651 0.052025 +-0.707139 -0.692653 0.142078 +-0.707139 -0.692653 0.142078 +-0.707139 -0.692653 0.142078 +-0.707139 -0.692653 0.142078 +-0.707139 -0.692653 0.142078 +-0.707165 -0.692630 0.142061 +0.258798 -0.784223 0.563930 +0.258829 -0.784224 0.563915 +0.258829 -0.784224 0.563915 +0.258829 -0.784224 0.563915 +0.258829 -0.784224 0.563915 +0.258829 -0.784224 0.563915 +0.965936 -0.210104 0.151077 +0.965936 -0.210104 0.151077 +0.965936 -0.210104 0.151077 +0.965936 -0.210104 0.151077 +0.965936 -0.210104 0.151077 +0.965944 -0.210071 0.151067 +0.707113 0.574071 -0.412837 +0.707113 0.574071 -0.412837 +0.707113 0.574071 -0.412837 +0.707113 0.574071 -0.412837 +0.707113 0.574071 -0.412837 +0.707136 0.574047 -0.412831 +-0.258868 0.784191 -0.563943 +-0.258868 0.784191 -0.563943 +-0.258868 0.784191 -0.563943 +-0.258868 0.784191 -0.563943 +-0.258868 0.784191 -0.563943 +-0.258891 0.784190 -0.563934 +-0.707136 0.574047 -0.412831 +-0.707113 0.574071 -0.412837 +-0.707113 0.574071 -0.412837 +-0.707113 0.574071 -0.412837 +-0.707113 0.574071 -0.412837 +-0.707113 0.574071 -0.412837 +-0.965884 -0.210255 0.151199 +-0.965875 -0.210287 0.151209 +-0.965875 -0.210287 0.151209 +-0.965875 -0.210287 0.151209 +-0.965875 -0.210287 0.151209 +-0.965875 -0.210287 0.151209 +-0.707196 -0.574008 0.412782 +-0.707152 -0.574057 0.412789 +-0.707196 -0.574008 0.412782 +-0.707152 -0.574057 0.412789 +-0.707196 -0.574008 0.412782 +-0.707196 -0.574008 0.412782 +0.258847 -0.572329 0.778099 +0.258847 -0.572329 0.778099 +0.258847 -0.572329 0.778099 +0.258847 -0.572329 0.778099 +0.258847 -0.572329 0.778099 +0.258633 -0.572411 0.778110 +0.965945 -0.153322 0.208428 +0.965945 -0.153322 0.208428 +0.965945 -0.153322 0.208428 +0.965945 -0.153322 0.208428 +0.965945 -0.153322 0.208428 +0.965945 -0.153322 0.208427 +0.707157 0.418967 -0.569558 +0.707157 0.418967 -0.569558 +0.707157 0.418967 -0.569558 +0.707157 0.418967 -0.569558 +0.707157 0.418967 -0.569558 +0.707115 0.419003 -0.569583 +-0.258846 0.572355 -0.778080 +-0.258908 0.572334 -0.778075 +-0.258908 0.572334 -0.778075 +-0.258908 0.572334 -0.778075 +-0.258908 0.572334 -0.778075 +-0.258908 0.572334 -0.778075 +-0.707115 0.419003 -0.569583 +-0.707157 0.418967 -0.569558 +-0.707157 0.418967 -0.569558 +-0.707157 0.418967 -0.569558 +-0.707157 0.418967 -0.569558 +-0.707157 0.418967 -0.569558 +-0.965885 -0.153455 0.208609 +-0.965885 -0.153456 0.208610 +-0.965885 -0.153456 0.208610 +-0.965885 -0.153456 0.208610 +-0.965885 -0.153456 0.208610 +-0.965885 -0.153456 0.208610 +-0.707120 -0.418993 0.569585 +-0.707120 -0.418993 0.569585 +-0.707120 -0.418993 0.569585 +-0.707120 -0.418993 0.569585 +-0.707120 -0.418993 0.569585 +-0.707197 -0.418924 0.569540 +0.258636 -0.529193 0.808123 +0.258636 -0.529193 0.808123 +0.258636 -0.529193 0.808123 +0.258636 -0.529193 0.808123 +0.258636 -0.529193 0.808123 +0.258706 -0.529180 0.808109 +0.965945 -0.141750 0.216464 +0.965945 -0.141750 0.216464 +0.965945 -0.141750 0.216464 +0.965945 -0.141750 0.216464 +0.965945 -0.141750 0.216464 +0.965959 -0.141720 0.216422 +0.707118 0.387370 -0.591548 +0.707118 0.387370 -0.591548 +0.707118 0.387370 -0.591548 +0.707118 0.387370 -0.591548 +0.707118 0.387370 -0.591548 +0.707116 0.387371 -0.591549 +-0.258789 0.529170 -0.808089 +-0.258840 0.529161 -0.808078 +-0.258840 0.529161 -0.808078 +-0.258840 0.529161 -0.808078 +-0.258840 0.529161 -0.808078 +-0.258840 0.529161 -0.808078 +-0.707116 0.387371 -0.591549 +-0.707118 0.387370 -0.591548 +-0.707118 0.387370 -0.591548 +-0.707118 0.387370 -0.591548 +-0.707118 0.387370 -0.591548 +-0.707118 0.387370 -0.591548 +-0.965882 0.141878 -0.216660 +-0.965883 0.141879 -0.216660 +-0.965883 0.141879 -0.216660 +-0.965883 0.141879 -0.216660 +-0.965882 0.141878 -0.216660 +-0.965885 -0.141874 0.216653 +-0.965899 -0.141844 0.216611 +-0.965898 -0.141844 0.216611 +-0.965899 -0.141844 0.216611 +-0.707195 -0.387325 0.591485 +-0.707195 -0.387325 0.591485 +-0.707195 -0.387325 0.591485 +-0.707195 -0.387325 0.591485 +-0.707195 -0.387325 0.591485 +-0.707122 -0.387368 0.591544 +0.261147 -0.259632 -0.929728 +0.250230 -0.264178 -0.931448 +0.250230 -0.264178 -0.931448 +0.250230 -0.264178 -0.931448 +0.250230 -0.264178 -0.931448 +0.250230 -0.264178 -0.931448 +0.963926 -0.078006 -0.254484 +0.963926 -0.078006 -0.254484 +0.963926 -0.078006 -0.254484 +0.963926 -0.078006 -0.254484 +0.966420 -0.072500 -0.246529 +0.963926 -0.078006 -0.254484 +0.697612 0.220750 0.681621 +0.697612 0.220750 0.681621 +0.697612 0.220750 0.681621 +0.697612 0.220750 0.681621 +0.709164 0.213105 0.672066 +0.697612 0.220750 0.681621 +-0.252556 0.300034 0.919889 +-0.252556 0.300034 0.919889 +-0.252556 0.300034 0.919889 +-0.252556 0.300034 0.919889 +-0.260131 0.297498 0.918600 +-0.252556 0.300034 0.919889 +-0.697612 0.220750 0.681621 +-0.697612 0.220750 0.681621 +-0.697612 0.220750 0.681621 +-0.697612 0.220750 0.681621 +-0.709164 0.213105 0.672066 +-0.697612 0.220750 0.681621 +-0.963862 -0.078073 -0.254706 +-0.963862 -0.078073 -0.254706 +-0.963862 -0.078073 -0.254706 +-0.963862 -0.078073 -0.254706 +-0.966360 -0.072564 -0.246745 +-0.963862 -0.078073 -0.254706 +-0.695362 -0.202761 -0.689463 +-0.695362 -0.202761 -0.689463 +-0.709909 -0.192173 -0.677568 +-0.695362 -0.202761 -0.689463 +-0.695362 -0.202761 -0.689463 +-0.695362 -0.202761 -0.689463 +0.260084 -0.524679 -0.810597 +0.260084 -0.524679 -0.810597 +0.260084 -0.524679 -0.810597 +0.260084 -0.524679 -0.810597 +0.260084 -0.524679 -0.810597 +0.250892 -0.528961 -0.810712 +0.964081 -0.149456 -0.219571 +0.964081 -0.149456 -0.219571 +0.964080 -0.149456 -0.219571 +0.964081 -0.149456 -0.219571 +0.964080 -0.149456 -0.219571 +0.966238 -0.142745 -0.214495 +0.698304 0.411236 0.585880 +0.698304 0.411236 0.585880 +0.698304 0.411236 0.585880 +0.698304 0.411236 0.585880 +0.698304 0.411236 0.585880 +0.708346 0.402274 0.580018 +-0.253045 0.557316 0.790802 +-0.253045 0.557316 0.790802 +-0.253045 0.557316 0.790802 +-0.253045 0.557316 0.790802 +-0.259591 0.554817 0.790437 +-0.253045 0.557316 0.790802 +-0.708346 0.402274 0.580018 +-0.708346 0.402274 0.580018 +-0.708346 0.402274 0.580018 +-0.708346 0.402274 0.580018 +-0.708346 0.402274 0.580018 +-0.698304 0.411236 0.585880 +-0.966178 -0.142870 -0.214683 +-0.966178 -0.142870 -0.214683 +-0.966178 -0.142870 -0.214683 +-0.966178 -0.142870 -0.214683 +-0.966178 -0.142870 -0.214683 +-0.964017 -0.149586 -0.219763 +-0.708953 -0.385379 -0.590651 +-0.708953 -0.385379 -0.590651 +-0.708953 -0.385379 -0.590651 +-0.708953 -0.385379 -0.590651 +-0.696104 -0.397756 -0.597687 +-0.708953 -0.385379 -0.590651 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.357193 0.000000 -0.934031 +0.357193 0.000000 -0.934031 +0.357193 0.000000 -0.934031 +0.357193 0.000000 -0.934031 +0.357193 0.000000 -0.934031 +0.357193 0.000000 -0.934031 +0.997314 0.000000 0.073248 +0.997314 0.000000 0.073248 +0.997314 0.000000 0.073248 +0.997314 0.000000 0.073248 +0.997314 0.000000 0.073248 +0.997314 0.000000 0.073248 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.995479 0.000000 0.094987 +-0.995479 0.000000 0.094987 +-0.995479 0.000000 0.094987 +-0.995479 0.000000 0.094987 +-0.995479 0.000000 0.094987 +-0.995479 0.000000 0.094987 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.629059 0.000000 0.777358 +0.629059 0.000000 0.777358 +0.629059 0.000000 0.777358 +0.629059 0.000000 0.777358 +0.629059 0.000000 0.777358 +0.629059 0.000000 0.777358 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.612387 0.000000 -0.790558 +-0.612387 0.000000 -0.790558 +-0.612387 0.000000 -0.790558 +-0.612387 0.000000 -0.790558 +-0.612387 0.000000 -0.790558 +-0.612387 0.000000 -0.790558 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.896866 0.000000 -0.442302 +0.896866 0.000000 -0.442302 +0.896866 0.000000 -0.442302 +0.896866 0.000000 -0.442302 +0.896866 0.000000 -0.442302 +0.896866 0.000000 -0.442302 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000665 0.000000 -1.000000 +0.000665 0.000000 -1.000000 +0.000665 0.000000 -1.000000 +0.000665 0.000000 -1.000000 +0.000665 0.000000 -1.000000 +0.000665 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.357193 0.000000 -0.934031 +0.357193 0.000000 -0.934031 +0.357193 0.000000 -0.934031 +0.357193 0.000000 -0.934031 +0.357193 0.000000 -0.934031 +0.357193 0.000000 -0.934031 +0.997314 0.000000 0.073248 +0.997314 0.000000 0.073248 +0.997314 0.000000 0.073248 +0.997314 0.000000 0.073248 +0.997314 0.000000 0.073248 +0.997314 0.000000 0.073248 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.995479 0.000000 0.094987 +-0.995479 0.000000 0.094987 +-0.995479 0.000000 0.094987 +-0.995479 0.000000 0.094987 +-0.995479 0.000000 0.094987 +-0.995479 0.000000 0.094987 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.629059 0.000000 0.777358 +0.629059 0.000000 0.777358 +0.629059 0.000000 0.777358 +0.629059 0.000000 0.777358 +0.629059 0.000000 0.777358 +0.629059 0.000000 0.777358 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.612387 0.000000 -0.790558 +-0.612387 0.000000 -0.790558 +-0.612387 0.000000 -0.790558 +-0.612387 0.000000 -0.790558 +-0.612387 0.000000 -0.790558 +-0.612387 0.000000 -0.790558 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.896866 0.000000 -0.442302 +0.896866 0.000000 -0.442302 +0.896866 0.000000 -0.442302 +0.896866 0.000000 -0.442302 +0.896866 0.000000 -0.442302 +0.896866 0.000000 -0.442302 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000665 0.000000 -1.000000 +0.000665 0.000000 -1.000000 +0.000665 0.000000 -1.000000 +0.000665 0.000000 -1.000000 +0.000665 0.000000 -1.000000 +0.000665 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.499995 0.866028 0.000000 +-0.499995 0.866028 0.000000 +-0.499995 0.866028 0.000000 +-0.499995 0.866028 0.000000 +-0.499995 0.866028 0.000000 +-0.499995 0.866028 0.000000 +-0.939707 0.341980 0.000000 +-0.939707 0.341980 0.000000 +-0.939707 0.341980 0.000000 +-0.939707 0.341980 0.000000 +-0.939707 0.341980 0.000000 +-0.939707 0.341980 0.000000 +-0.939717 -0.341954 0.000000 +-0.939717 -0.341954 0.000000 +-0.939717 -0.341954 0.000000 +-0.939717 -0.341954 0.000000 +-0.939717 -0.341954 0.000000 +-0.939717 -0.341954 0.000000 +-0.499995 -0.866028 0.000000 +-0.499995 -0.866028 0.000000 +-0.499995 -0.866028 0.000000 +-0.499995 -0.866028 0.000000 +-0.499995 -0.866028 0.000000 +-0.499995 -0.866028 0.000000 +0.173667 -0.984805 0.000000 +0.173667 -0.984805 0.000000 +0.173667 -0.984805 0.000000 +0.173667 -0.984805 0.000000 +0.173667 -0.984805 0.000000 +0.173667 -0.984805 0.000000 +0.766060 -0.642769 0.000000 +0.766060 -0.642769 0.000000 +0.766060 -0.642769 0.000000 +0.766060 -0.642769 0.000000 +0.766060 -0.642769 0.000000 +0.766060 -0.642769 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.766027 0.642809 0.000000 +0.766027 0.642809 0.000000 +0.766027 0.642809 0.000000 +0.766027 0.642809 0.000000 +0.766027 0.642809 0.000000 +0.766027 0.642809 0.000000 +0.173667 0.984805 0.000000 +0.173667 0.984805 0.000000 +0.173667 0.984805 0.000000 +0.173667 0.984805 0.000000 +0.173667 0.984805 0.000000 +0.173667 0.984805 0.000000 +0.173696 0.000000 -0.984799 +0.173696 0.000000 -0.984799 +0.173696 0.000000 -0.984799 +0.173696 0.000000 -0.984799 +0.173696 0.000000 -0.984799 +0.173696 0.000000 -0.984799 +0.766035 0.000000 -0.642799 +0.766035 0.000000 -0.642799 +0.766035 0.000000 -0.642799 +0.766035 0.000000 -0.642799 +0.766035 0.000000 -0.642799 +0.766035 0.000000 -0.642799 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.766035 0.000000 0.642799 +0.766035 0.000000 0.642799 +0.766035 0.000000 0.642799 +0.766035 0.000000 0.642799 +0.766035 0.000000 0.642799 +0.766035 0.000000 0.642799 +0.173616 0.000008 0.984813 +0.173616 0.000008 0.984814 +0.173616 0.000008 0.984814 +0.173616 0.000008 0.984814 +0.173616 0.000008 0.984814 +0.173696 0.000000 0.984799 +-0.499960 0.000007 0.866049 +-0.499960 0.000007 0.866049 +-0.499960 0.000007 0.866048 +-0.499960 0.000007 0.866048 +-0.500022 0.000000 0.866013 +-0.499960 0.000007 0.866049 +-0.939700 0.000000 0.342000 +-0.939700 0.000000 0.342000 +-0.939700 0.000000 0.342000 +-0.939700 0.000000 0.342000 +-0.939700 0.000000 0.342000 +-0.939700 0.000000 0.342000 +-0.939690 0.000000 -0.342027 +-0.939690 0.000000 -0.342027 +-0.939690 0.000000 -0.342027 +-0.939690 0.000000 -0.342027 +-0.939690 0.000000 -0.342027 +-0.939690 0.000000 -0.342027 +-0.500022 0.000000 -0.866013 +-0.500022 0.000000 -0.866013 +-0.500022 0.000000 -0.866013 +-0.500022 0.000000 -0.866013 +-0.500022 0.000000 -0.866013 +-0.500022 0.000000 -0.866013 +0.000000 -0.173670 -0.984804 +0.000000 -0.173670 -0.984804 +0.000000 -0.173671 -0.984804 +0.000000 -0.173670 -0.984804 +0.000000 -0.173671 -0.984804 +0.000000 -0.173670 -0.984804 +0.000000 -0.766098 -0.642724 +0.000000 -0.766098 -0.642724 +0.000000 -0.766098 -0.642724 +0.000000 -0.766098 -0.642724 +0.000000 -0.766098 -0.642724 +0.000000 -0.766098 -0.642724 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -0.766098 0.642724 +0.000000 -0.766098 0.642724 +0.000000 -0.766098 0.642724 +0.000000 -0.766098 0.642724 +0.000000 -0.766098 0.642724 +0.000000 -0.766098 0.642724 +0.000000 -0.173671 0.984804 +0.000000 -0.173671 0.984804 +0.000000 -0.173671 0.984804 +0.000000 -0.173671 0.984804 +0.000000 -0.173671 0.984804 +0.000000 -0.173671 0.984804 +0.000000 0.500027 0.866010 +0.000000 0.500027 0.866010 +0.000000 0.500027 0.866010 +0.000000 0.500027 0.866010 +0.000000 0.500027 0.866010 +0.000000 0.500027 0.866010 +0.000000 0.939709 0.341975 +0.000000 0.939709 0.341975 +0.000000 0.939709 0.341975 +0.000000 0.939709 0.341975 +0.000000 0.939709 0.341975 +0.000000 0.939709 0.341975 +0.000000 0.939709 -0.341975 +0.000000 0.939709 -0.341975 +0.000000 0.939709 -0.341975 +0.000000 0.939709 -0.341975 +0.000000 0.939709 -0.341975 +0.000000 0.939709 -0.341975 +0.000000 0.500027 -0.866010 +0.000000 0.500027 -0.866010 +0.000000 0.500027 -0.866010 +0.000000 0.500027 -0.866010 +0.000000 0.500027 -0.866010 +0.000000 0.500027 -0.866010 +0.000000 -0.394046 0.919091 +0.000000 -0.394046 0.919091 +0.000000 -0.394046 0.919091 +0.000000 -0.394046 0.919091 +0.000000 -0.394046 0.919091 +0.000000 -0.394046 0.919091 +0.000000 -0.101879 0.994797 +0.000000 -0.101879 0.994797 +0.000000 -0.101879 0.994797 +0.000000 -0.101879 0.994797 +0.000000 -0.101879 0.994797 +0.000000 -0.101879 0.994797 +0.000000 -0.233160 0.972438 +0.000000 -0.233160 0.972438 +0.000000 -0.233160 0.972438 +0.000000 -0.233160 0.972438 +0.000000 -0.233160 0.972438 +0.000000 -0.233160 0.972438 +0.000000 -0.437022 0.899451 +0.000000 -0.437022 0.899451 +0.000000 -0.437022 0.899451 +0.000000 -0.437022 0.899451 +0.000000 -0.437022 0.899451 +0.000000 -0.437022 0.899451 +0.000000 -0.437022 0.899451 +0.000000 -0.437022 0.899451 +0.000000 -0.437022 0.899451 +0.000000 -0.437022 0.899451 +0.000000 -0.437022 0.899451 +0.000000 -0.437022 0.899451 +0.000000 -0.209514 0.977806 +0.000000 -0.209514 0.977806 +0.000000 -0.209514 0.977806 +0.000000 -0.209514 0.977806 +0.000000 -0.209514 0.977806 +0.000000 -0.209514 0.977805 +0.000000 -0.209514 0.977806 +0.000000 -0.209514 0.977806 +0.000000 -0.209514 0.977806 +0.000000 -0.209514 0.977806 +0.000000 -0.209514 0.977805 +0.000000 -0.209514 0.977806 +0.000000 -0.300650 0.953734 +0.000000 -0.300650 0.953734 +0.000000 -0.300650 0.953735 +0.000000 -0.300650 0.953735 +0.000000 -0.300650 0.953734 +0.000000 -0.300650 0.953734 +0.000000 -0.300650 0.953734 +0.000000 -0.300650 0.953734 +0.000000 -0.300650 0.953734 +0.000000 -0.300650 0.953734 +0.000000 -0.300650 0.953734 +0.000000 -0.300650 0.953734 +0.999619 -0.025773 -0.009934 +0.999641 -0.026062 -0.006295 +0.999641 -0.026062 -0.006295 +0.999641 -0.026062 -0.006295 +0.999641 -0.026062 -0.006295 +0.999640 -0.026062 -0.006295 +0.999582 -0.028117 -0.006792 +0.999605 -0.027771 -0.004373 +0.999605 -0.027771 -0.004373 +0.999605 -0.027771 -0.004373 +0.999605 -0.027771 -0.004373 +0.999605 -0.027771 -0.004373 +0.999596 -0.028094 -0.004423 +0.999617 -0.027663 -0.000155 +0.999617 -0.027663 -0.000155 +0.999617 -0.027663 -0.000155 +0.999617 -0.027663 -0.000155 +0.999617 -0.027663 -0.000155 +0.000000 0.999980 0.006348 +0.000000 0.999980 0.006348 +0.000000 0.999980 0.006348 +0.000000 0.999980 0.006348 +0.008450 0.999949 0.005600 +0.000000 0.999980 0.006348 +-0.999808 0.019581 0.000124 +-0.999808 0.019581 0.000124 +-0.999808 0.019581 0.000124 +-0.999808 0.019581 0.000124 +-0.999808 0.019581 0.000124 +-0.999796 0.019817 0.003830 +-0.999804 0.019433 0.003755 +-0.999804 0.019433 0.003755 +-0.999804 0.019433 0.003755 +-0.999804 0.019433 0.003755 +-0.999804 0.019433 0.003755 +-0.999790 0.019578 0.006091 +-0.999823 0.017938 0.005581 +-0.999823 0.017938 0.005581 +-0.999824 0.017938 0.005581 +-0.999823 0.017938 0.005581 +-0.999823 0.017938 0.005581 +-0.999819 0.017731 0.006863 +0.999819 0.017731 0.006863 +0.999823 0.017938 0.005581 +0.999824 0.017938 0.005581 +0.999824 0.017938 0.005581 +0.999823 0.017938 0.005581 +0.999824 0.017938 0.005581 +0.999790 0.019578 0.006091 +0.999804 0.019433 0.003755 +0.999804 0.019433 0.003755 +0.999804 0.019433 0.003755 +0.999804 0.019433 0.003755 +0.999804 0.019433 0.003755 +0.999797 0.019794 0.003825 +0.999809 0.019558 0.000124 +0.999809 0.019558 0.000124 +0.999809 0.019558 0.000124 +0.999809 0.019558 0.000124 +0.999809 0.019558 0.000124 +0.000000 0.999980 0.006348 +0.000000 0.999980 0.006348 +0.000000 0.999980 0.006348 +-0.008442 0.999949 0.005600 +0.000000 0.999980 0.006348 +0.000000 0.999980 0.006348 +-0.999617 -0.027663 -0.000155 +-0.999617 -0.027663 -0.000155 +-0.999617 -0.027663 -0.000155 +-0.999617 -0.027663 -0.000155 +-0.999617 -0.027663 -0.000155 +-0.999596 -0.028094 -0.004424 +-0.999605 -0.027771 -0.004373 +-0.999605 -0.027771 -0.004373 +-0.999605 -0.027771 -0.004373 +-0.999605 -0.027771 -0.004373 +-0.999605 -0.027771 -0.004373 +-0.999582 -0.028117 -0.006792 +-0.999639 -0.026112 -0.006307 +-0.999639 -0.026112 -0.006307 +-0.999639 -0.026112 -0.006307 +-0.999639 -0.026112 -0.006307 +-0.999639 -0.026112 -0.006307 +-0.999617 -0.025822 -0.009953 +0.000000 0.366056 -0.930593 +0.000000 0.366056 -0.930593 +0.000000 0.366056 -0.930593 +0.000000 0.366056 -0.930593 +0.000000 0.366056 -0.930593 +0.000000 0.366056 -0.930593 +0.000000 0.233211 -0.972426 +0.000000 0.233211 -0.972426 +0.000000 0.233211 -0.972426 +0.000000 0.233211 -0.972426 +0.000000 0.233211 -0.972426 +0.000000 0.233211 -0.972426 +0.000000 0.101876 -0.994797 +0.000000 0.101876 -0.994797 +0.000000 0.101876 -0.994797 +0.000000 0.101876 -0.994797 +0.000000 0.101876 -0.994797 +0.000000 0.101876 -0.994797 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -0.935795 -0.352543 +0.000000 -0.935795 -0.352544 +0.000000 -0.935795 -0.352544 +0.000000 -0.935795 -0.352544 +0.000000 -0.935795 -0.352543 +0.000000 -0.935795 -0.352543 +0.000000 -0.932577 -0.360972 +0.000000 -0.932577 -0.360972 +0.000000 -0.932577 -0.360972 +0.000000 -0.932577 -0.360972 +0.017064 -0.932949 -0.359603 +0.000000 -0.932577 -0.360972 +0.000000 -0.932577 -0.360972 +0.000000 -0.932577 -0.360972 +0.000000 -0.932577 -0.360972 +-0.017021 -0.932950 -0.359603 +0.000000 -0.932577 -0.360972 +0.000000 -0.932577 -0.360972 + + + + + + + + + + + +0.557290 0.646631 +0.551307 0.644150 +0.602577 0.644040 +0.596952 0.646380 +0.083823 0.998410 +0.083820 0.975838 +0.123281 0.975834 +0.123284 0.998406 +0.042331 0.667893 +0.017604 0.667811 +0.017628 0.661568 +0.042354 0.661650 +0.605460 0.640294 +0.548248 0.640408 +0.093631 0.661482 +0.118356 0.661512 +0.118348 0.667384 +0.093622 0.667354 +0.211487 0.647075 +0.262762 0.646947 +0.256791 0.649456 +0.217126 0.649390 +0.017646 0.656765 +0.042373 0.656847 +0.545559 0.634549 +0.608168 0.634268 +0.093637 0.656776 +0.118363 0.656807 +0.208585 0.643343 +0.265801 0.643191 +0.017671 0.650264 +0.042397 0.650346 +0.093646 0.650112 +0.118372 0.650142 +0.543528 0.628685 +0.610219 0.628246 +0.205844 0.637329 +0.268459 0.637318 +0.017694 0.643980 +0.042420 0.644061 +0.093655 0.643668 +0.118381 0.643699 +0.618485 0.603649 +0.534442 0.603355 +0.203761 0.631316 +0.270459 0.631445 +0.017797 0.616740 +0.042522 0.616821 +0.093692 0.617382 +0.118417 0.617412 +0.631766 0.564128 +0.520025 0.563158 +0.195364 0.606756 +0.279411 0.606071 +0.042683 0.573594 +0.000500 0.573457 +0.093751 0.575145 +0.135934 0.575196 +0.565843 0.551994 +0.558288 0.547940 +0.181844 0.564174 +0.293587 0.562727 +0.001014 0.434967 +0.043196 0.435104 +0.094551 0.000500 +0.136733 0.000551 +0.136128 0.435854 +0.093945 0.435802 +0.915021 0.588916 +0.872924 0.588922 +0.872909 0.490623 +0.915006 0.490618 +0.864341 0.382810 +0.864347 0.422101 +0.853311 0.422102 +0.853305 0.382812 +0.892182 0.363039 +0.851179 0.363038 +0.851179 0.352959 +0.892182 0.352960 +0.873182 0.382809 +0.873188 0.422099 +0.851179 0.344886 +0.892182 0.344886 +0.965184 0.382795 +0.965191 0.422086 +0.879590 0.422099 +0.879584 0.382808 +0.971593 0.422085 +0.971587 0.382794 +0.980428 0.382793 +0.980434 0.422083 +0.892182 0.255019 +0.851179 0.255019 +0.851179 0.246945 +0.892182 0.246945 +0.991464 0.382792 +0.991471 0.422082 +0.851179 0.236867 +0.892182 0.236867 +0.520689 0.427321 +0.522768 0.001171 +0.626045 0.000500 +0.630381 0.427457 +0.002614 0.000500 +0.044796 0.000636 +0.182565 0.427489 +0.184826 0.000500 +0.288109 0.000732 +0.292260 0.426887 +0.554598 0.463963 +0.555111 0.542844 +0.576528 0.553870 +0.587188 0.551873 +0.594690 0.547734 +0.575871 0.452695 +0.565211 0.454692 +0.557710 0.458831 +0.597801 0.542602 +0.597289 0.463720 +0.594112 0.458624 +0.586557 0.454570 +0.851179 0.260866 +0.892182 0.260866 +0.892182 0.339039 +0.851179 0.339039 +0.247869 0.454449 +0.237198 0.452497 +0.226522 0.454418 +0.255391 0.458556 +0.218987 0.458503 +0.258401 0.542562 +0.258528 0.463675 +0.247712 0.551758 +0.255247 0.547672 +0.218842 0.547621 +0.226364 0.551728 +0.237035 0.553679 +0.215834 0.463613 +0.215706 0.542502 +0.729383 0.005354 +0.635576 0.000500 +0.632752 0.300985 +0.696747 0.302203 +0.633392 0.364320 +0.690641 0.364909 +0.632752 0.377891 +0.196547 0.662159 +0.347338 0.924859 +0.778764 0.640494 +0.366022 0.985229 +0.795966 0.700842 +0.991236 0.187941 +0.897603 0.187941 +0.790917 0.976357 +0.780782 0.974249 +0.765362 0.780982 +0.755281 0.766191 +0.770411 0.786270 +0.426902 0.926822 +0.480263 0.926822 +0.775715 0.971087 +0.760514 0.957386 +0.738382 0.966251 +0.934409 0.962656 +0.918733 0.974249 +0.939830 0.957386 +0.696467 0.806938 +0.750022 0.914595 +0.696467 0.914595 +0.696467 0.791869 +0.696467 0.786296 +0.696467 0.772433 +0.785572 0.797915 +0.750322 0.806938 +0.750322 0.797441 +0.696467 0.949100 +0.696467 0.966251 +0.696467 0.942168 +0.750380 0.942631 +0.954074 0.766843 +0.750322 0.791869 +0.750321 0.772433 +0.951676 0.942631 +0.746265 0.942168 +0.749687 0.924092 +0.744381 0.949100 +0.913402 0.800443 +0.908593 0.976357 +0.795700 0.800057 +0.928626 0.795222 +0.933706 0.792076 +0.943882 0.781568 +0.696467 0.924092 +0.750321 0.755281 +0.696467 0.755281 +0.055147 0.926822 +0.046860 0.926822 +0.038404 0.926822 +0.029907 0.926822 +0.279028 0.926822 +0.270608 0.926822 +0.262215 0.926822 +0.253834 0.926822 +0.245559 0.926822 +0.046860 0.961117 +0.055147 0.961117 +0.055147 0.966040 +0.046860 0.966040 +0.038404 0.961117 +0.038404 0.966040 +0.029907 0.961117 +0.029907 0.966040 +0.279028 0.960971 +0.279028 0.965928 +0.270608 0.960971 +0.270608 0.965928 +0.262214 0.960971 +0.262214 0.965928 +0.253834 0.960971 +0.253834 0.965928 +0.245559 0.960971 +0.245559 0.965928 +0.046860 0.996637 +0.046860 0.993250 +0.055147 0.993250 +0.055147 0.996637 +0.038404 0.996637 +0.038404 0.993250 +0.029907 0.996637 +0.029907 0.993250 +0.279028 0.996661 +0.279028 0.993243 +0.270608 0.996661 +0.270608 0.993243 +0.262214 0.996661 +0.262214 0.993243 +0.253834 0.996661 +0.253834 0.993243 +0.245559 0.996661 +0.245559 0.993243 +0.055147 0.999483 +0.245559 0.999500 +0.253834 0.999500 +0.046860 0.999483 +0.038404 0.999483 +0.029907 0.999483 +0.279028 0.999500 +0.270608 0.999500 +0.262214 0.999500 +0.063399 0.926822 +0.063399 0.961117 +0.063399 0.966040 +0.063399 0.996637 +0.063399 0.993250 +0.836125 0.452884 +0.840614 0.451408 +0.845067 0.452977 +0.833700 0.456714 +0.834474 0.461106 +0.838085 0.464005 +0.842843 0.464055 +0.846522 0.461232 +0.847401 0.456857 +0.287406 0.926822 +0.287406 0.960971 +0.287406 0.965928 +0.287406 0.996661 +0.287406 0.993243 +0.287406 0.999500 +0.063399 0.999483 +0.249045 0.810003 +0.278280 0.808338 +0.285293 0.909943 +0.245559 0.923303 +0.835670 0.584352 +0.864882 0.586360 +0.860007 0.588735 +0.840533 0.587397 +0.019409 0.833743 +0.018725 0.949962 +0.010302 0.949919 +0.010986 0.833700 +0.467128 0.964594 +0.426902 0.964680 +0.426913 0.956315 +0.467138 0.956229 +0.412199 0.815518 +0.413082 0.711170 +0.421502 0.711233 +0.420617 0.815580 +0.500429 0.956233 +0.504936 0.956232 +0.504890 0.964349 +0.500382 0.964351 +0.514416 0.956231 +0.519826 0.956229 +0.519780 0.964347 +0.514370 0.964348 +0.509519 0.956232 +0.509473 0.964349 +0.495700 0.964351 +0.490618 0.964353 +0.490664 0.956236 +0.495746 0.956234 +0.253948 0.807016 +0.273438 0.805906 +0.833700 0.471013 +0.873255 0.484838 +0.855135 0.590027 +0.845397 0.589357 +0.258838 0.805112 +0.268583 0.804557 +0.850264 0.590234 +0.263717 0.804293 +0.991236 0.000500 +0.832179 0.377891 +0.897603 0.000500 +0.396048 0.662159 +0.396048 0.924859 +0.832179 0.640494 +0.396048 0.985229 +0.832179 0.700842 +0.790917 0.931724 +0.780783 0.931723 +0.755322 0.755281 +0.696467 0.976919 +0.765458 0.755314 +0.775595 0.755347 +0.426902 0.937392 +0.750380 0.931724 +0.480263 0.937392 +0.954115 0.755933 +0.770648 0.931724 +0.760514 0.931724 +0.738382 0.976919 +0.951676 0.931724 +0.928988 0.931724 +0.918733 0.931724 +0.939830 0.931724 +0.785731 0.755381 +0.908593 0.931724 +0.795867 0.755414 +0.913569 0.755800 +0.923705 0.755833 +0.933842 0.755867 +0.943978 0.755900 +0.444563 0.646631 +0.484225 0.646380 +0.489850 0.644040 +0.438580 0.644150 +0.490620 0.944497 +0.530081 0.944493 +0.530078 0.921921 +0.490618 0.921925 +0.086441 0.667893 +0.086465 0.661650 +0.061738 0.661568 +0.061715 0.667811 +0.492733 0.640294 +0.435521 0.640408 +0.137741 0.661482 +0.137733 0.667354 +0.162458 0.667384 +0.162467 0.661512 +0.324214 0.647075 +0.329853 0.649389 +0.369518 0.649456 +0.375489 0.646947 +0.086483 0.656847 +0.061757 0.656765 +0.495441 0.634268 +0.432832 0.634549 +0.137748 0.656776 +0.162473 0.656807 +0.321312 0.643342 +0.378528 0.643190 +0.086508 0.650346 +0.061781 0.650264 +0.137757 0.650112 +0.162482 0.650142 +0.497492 0.628246 +0.430801 0.628685 +0.381186 0.637318 +0.318571 0.637329 +0.086531 0.644061 +0.061805 0.643980 +0.137766 0.643668 +0.162491 0.643698 +0.505758 0.603650 +0.421715 0.603355 +0.383186 0.631445 +0.316488 0.631315 +0.086633 0.616821 +0.061907 0.616740 +0.137803 0.617382 +0.162528 0.617412 +0.519039 0.564128 +0.407298 0.563158 +0.308091 0.606755 +0.392138 0.606071 +0.086793 0.573594 +0.044611 0.573457 +0.137862 0.575145 +0.180044 0.575196 +0.453116 0.551994 +0.445561 0.547941 +0.294571 0.564174 +0.406314 0.562727 +0.087307 0.435104 +0.045124 0.434967 +0.138056 0.435802 +0.180238 0.435854 +0.180844 0.000551 +0.138661 0.000500 +0.959132 0.579114 +0.959117 0.480815 +0.917020 0.480821 +0.917035 0.579119 +0.864340 0.426921 +0.853305 0.426923 +0.853311 0.466213 +0.864347 0.466211 +0.848071 0.363039 +0.848071 0.352960 +0.807068 0.352959 +0.807068 0.363038 +0.873188 0.466210 +0.873182 0.426920 +0.848071 0.344886 +0.807068 0.344886 +0.965184 0.426906 +0.879584 0.426919 +0.879590 0.466209 +0.965191 0.466197 +0.971593 0.466195 +0.980434 0.466194 +0.980428 0.426904 +0.971587 0.426905 +0.848071 0.255019 +0.848071 0.246945 +0.807068 0.246945 +0.807068 0.255019 +0.991464 0.426902 +0.991470 0.466192 +0.848071 0.236867 +0.807068 0.236867 +0.517653 0.427457 +0.513318 0.000500 +0.410041 0.001171 +0.407962 0.427321 +0.088907 0.000636 +0.046725 0.000500 +0.404987 0.426887 +0.400836 0.000732 +0.297553 0.000500 +0.295292 0.427489 +0.442383 0.542844 +0.441871 0.463963 +0.463801 0.553870 +0.474461 0.551873 +0.481963 0.547734 +0.452484 0.454692 +0.463144 0.452695 +0.444982 0.458831 +0.484562 0.463720 +0.485074 0.542602 +0.473830 0.454570 +0.481385 0.458624 +0.807068 0.339039 +0.848071 0.339039 +0.848071 0.260866 +0.807068 0.260866 +0.360596 0.454448 +0.349925 0.452497 +0.339249 0.454417 +0.368118 0.458556 +0.331714 0.458503 +0.371255 0.463675 +0.371128 0.542562 +0.360439 0.551758 +0.367974 0.547672 +0.339091 0.551728 +0.331569 0.547621 +0.349762 0.553679 +0.328433 0.542502 +0.328561 0.463613 +0.000500 0.671961 +0.151291 0.934661 +0.200001 0.934661 +0.200001 0.671961 +0.733599 0.000500 +0.827407 0.005354 +0.794771 0.302203 +0.730775 0.300984 +0.169975 0.995031 +0.200001 0.995031 +0.788664 0.364909 +0.731416 0.364320 +0.770411 0.845083 +0.755281 0.825005 +0.755322 0.814095 +0.765458 0.814129 +0.775459 0.850371 +0.775595 0.814162 +0.892644 0.052157 +0.892344 0.159813 +0.838790 0.159813 +0.838790 0.052157 +0.838790 0.042660 +0.838790 0.037088 +0.892644 0.031515 +0.892644 0.037088 +0.838790 0.017652 +0.838789 0.000500 +0.892644 0.000500 +0.892644 0.017652 +0.785731 0.814195 +0.785572 0.856730 +0.890472 0.180455 +0.838790 0.180455 +0.838790 0.169311 +0.892010 0.169311 +0.923634 0.915435 +0.913494 0.917543 +0.913494 0.872910 +0.923634 0.872909 +0.880704 0.211470 +0.838789 0.211470 +0.838790 0.187387 +0.888587 0.187387 +0.795700 0.858871 +0.795867 0.814228 +0.913569 0.814614 +0.913402 0.859257 +0.923705 0.814647 +0.923546 0.857182 +0.933842 0.814681 +0.928626 0.854036 +0.943978 0.814714 +0.943882 0.840382 +0.954115 0.814748 +0.954074 0.825657 +0.986370 0.515110 +0.986370 0.520033 +0.978084 0.520033 +0.978084 0.515110 +0.969627 0.520033 +0.969627 0.515110 +0.961131 0.520033 +0.961131 0.515110 +0.757919 0.657098 +0.757919 0.662055 +0.749541 0.662055 +0.749541 0.657098 +0.741121 0.662055 +0.741121 0.657098 +0.732727 0.662055 +0.732727 0.657098 +0.724347 0.662055 +0.724347 0.657098 +0.716072 0.662055 +0.716072 0.657098 +0.994622 0.515110 +0.994622 0.520033 +0.978084 0.550630 +0.978084 0.547243 +0.986370 0.547243 +0.986370 0.550630 +0.969627 0.550630 +0.969627 0.547243 +0.961131 0.550630 +0.961131 0.547243 +0.749541 0.692788 +0.749541 0.689370 +0.757919 0.689370 +0.757919 0.692788 +0.741121 0.692788 +0.741121 0.689370 +0.732727 0.692788 +0.732727 0.689370 +0.724347 0.692788 +0.724347 0.689370 +0.716072 0.692788 +0.716072 0.689370 +0.994622 0.547243 +0.994622 0.550630 +0.497532 0.966032 +0.501985 0.967601 +0.490618 0.971337 +0.493043 0.967508 +0.986370 0.553476 +0.978084 0.553476 +0.969627 0.553476 +0.961131 0.553476 +0.757919 0.695627 +0.749541 0.695627 +0.741121 0.695627 +0.732727 0.695627 +0.724347 0.695627 +0.716072 0.695627 +0.994622 0.553476 +0.978084 0.480815 +0.986370 0.480815 +0.969627 0.480815 +0.961131 0.480815 +0.749541 0.622949 +0.757919 0.622949 +0.741121 0.622949 +0.732727 0.622949 +0.724347 0.622949 +0.716072 0.622949 +0.994622 0.480815 +0.504318 0.971480 +0.491392 0.975730 +0.503440 0.975855 +0.495002 0.978629 +0.499761 0.978678 +0.077504 0.863916 +0.074018 0.977215 +0.113751 0.963856 +0.106739 0.862251 +0.041641 0.920677 +0.061116 0.922015 +0.065991 0.919640 +0.036779 0.917632 +0.019409 0.716115 +0.010986 0.716072 +0.010302 0.832291 +0.018725 0.832334 +0.467128 0.974397 +0.467138 0.966032 +0.426913 0.966117 +0.426902 0.974482 +0.299472 0.972355 +0.307890 0.972418 +0.308774 0.868070 +0.300355 0.868008 +0.500382 0.954548 +0.504890 0.954547 +0.504936 0.946430 +0.500429 0.946431 +0.514370 0.954546 +0.519780 0.954544 +0.519826 0.946427 +0.514416 0.946428 +0.509472 0.954546 +0.509519 0.946429 +0.495746 0.946432 +0.490664 0.946433 +0.490618 0.954550 +0.495700 0.954549 +0.101896 0.859819 +0.082407 0.860929 +0.074363 0.818118 +0.034808 0.804293 +0.046506 0.922637 +0.056243 0.923307 +0.097042 0.858470 +0.087297 0.859025 +0.051373 0.923514 +0.092175 0.858206 +0.991048 0.191646 +0.991048 0.379087 +0.897415 0.379087 +0.897415 0.191646 +0.596923 0.919861 +0.543507 0.919861 +0.397495 0.657258 +0.596923 0.657258 +0.596923 0.980209 +0.560710 0.980209 +0.795818 0.872909 +0.795818 0.917543 +0.780617 0.912273 +0.785684 0.872909 +0.426902 0.952095 +0.426902 0.941526 +0.480263 0.941526 +0.480263 0.952095 +0.775550 0.909111 +0.775550 0.872909 +0.765415 0.872909 +0.765415 0.898572 +0.755281 0.883817 +0.755281 0.872909 +0.838789 0.222137 +0.880704 0.222138 +0.933889 0.872910 +0.933889 0.909111 +0.956577 0.872909 +0.956577 0.883817 +0.939310 0.903841 +0.944731 0.872909 +0.121630 0.445266 +0.093513 0.445266 +0.093513 0.398749 +0.121630 0.398749 +0.121630 0.491320 +0.093513 0.491320 +0.121630 0.536619 +0.093513 0.536619 +0.121630 0.580952 +0.093513 0.580952 +0.121630 0.624189 +0.093513 0.624189 +0.121630 0.666219 +0.093513 0.666219 +0.121630 0.706882 +0.093513 0.706882 +0.121630 0.745968 +0.093513 0.745968 +0.121630 0.783496 +0.093513 0.783496 +0.121630 0.043258 +0.093513 0.043258 +0.121630 0.084259 +0.093513 0.084259 +0.121630 0.126597 +0.093513 0.126597 +0.121630 0.170074 +0.093513 0.170074 +0.121630 0.214474 +0.093513 0.214474 +0.121630 0.259712 +0.093513 0.259712 +0.121630 0.305657 +0.093513 0.305657 +0.121630 0.352101 +0.093513 0.352101 +0.133073 0.398749 +0.133073 0.445266 +0.133073 0.352101 +0.133073 0.305657 +0.133073 0.259712 +0.133073 0.214474 +0.133073 0.170074 +0.133073 0.126597 +0.133073 0.084259 +0.133073 0.043258 +0.133073 0.003616 +0.133073 0.745968 +0.133073 0.706882 +0.133073 0.666219 +0.133073 0.624189 +0.133073 0.580952 +0.133073 0.536619 +0.133073 0.491320 +0.164606 0.445266 +0.164606 0.398749 +0.164606 0.491320 +0.164606 0.536619 +0.164606 0.580952 +0.164606 0.624189 +0.164606 0.666219 +0.164606 0.706882 +0.164606 0.745968 +0.164606 0.783496 +0.164606 0.043258 +0.164606 0.084259 +0.164606 0.126597 +0.164606 0.170074 +0.164606 0.214474 +0.164606 0.259712 +0.164606 0.305657 +0.164606 0.352101 +0.735709 0.113094 +0.736072 0.158310 +0.750833 0.070480 +0.779619 0.035610 +0.818596 0.012688 +0.863062 0.004478 +0.907653 0.011973 +0.946993 0.034266 +0.976336 0.068670 +0.121630 0.003616 +0.093513 0.003616 +0.992142 0.111035 +0.992505 0.156252 +0.977382 0.198865 +0.948595 0.233736 +0.909618 0.256659 +0.865152 0.264868 +0.820559 0.257374 +0.781219 0.235080 +0.751877 0.200675 +0.133073 0.783496 +0.788183 0.784364 +0.788032 0.825835 +0.774200 0.745484 +0.747926 0.713922 +0.712649 0.693377 +0.672570 0.686164 +0.632343 0.693123 +0.596716 0.713545 +0.570055 0.745111 +0.164606 0.003616 +0.555739 0.784032 +0.555588 0.825503 +0.569571 0.864383 +0.595844 0.895944 +0.631121 0.916490 +0.671201 0.923703 +0.711428 0.916744 +0.747056 0.896322 +0.773716 0.864755 +0.038368 0.445266 +0.010251 0.445266 +0.010251 0.398749 +0.038368 0.398749 +0.038368 0.491319 +0.010251 0.491319 +0.038368 0.536618 +0.010251 0.536618 +0.038368 0.580952 +0.010251 0.580952 +0.038368 0.624189 +0.010251 0.624189 +0.038368 0.666219 +0.010251 0.666219 +0.038368 0.706882 +0.010251 0.706882 +0.038368 0.745967 +0.010251 0.745967 +0.038368 0.783496 +0.010251 0.783496 +0.038368 0.043258 +0.010251 0.043258 +0.010251 0.003616 +0.038368 0.003616 +0.038368 0.084259 +0.010251 0.084259 +0.038368 0.126597 +0.010251 0.126597 +0.038368 0.170073 +0.010251 0.170073 +0.038368 0.214474 +0.010251 0.214474 +0.038368 0.259712 +0.010251 0.259712 +0.038368 0.305657 +0.010251 0.305657 +0.038368 0.352101 +0.010251 0.352101 +0.049811 0.398749 +0.049811 0.445266 +0.049811 0.352101 +0.049811 0.305657 +0.049811 0.259712 +0.049811 0.214474 +0.049811 0.170073 +0.049811 0.126597 +0.049811 0.084259 +0.049811 0.043258 +0.049811 0.003616 +0.049811 0.745967 +0.049811 0.783496 +0.049811 0.706882 +0.049811 0.666219 +0.049811 0.624189 +0.049811 0.580952 +0.049811 0.536618 +0.049811 0.491319 +0.081345 0.445266 +0.081345 0.398749 +0.081345 0.491319 +0.081345 0.536618 +0.081345 0.580952 +0.081345 0.624189 +0.081345 0.666219 +0.081345 0.706882 +0.081345 0.745967 +0.081345 0.783496 +0.081345 0.043258 +0.081345 0.003616 +0.081345 0.084259 +0.081345 0.126597 +0.081345 0.170073 +0.081345 0.214474 +0.081345 0.259712 +0.081345 0.305657 +0.081345 0.352101 +0.986570 0.606402 +1.000435 0.645324 +1.000158 0.686794 +0.985723 0.725672 +0.960392 0.574761 +0.958967 0.757157 +0.925177 0.554108 +0.923278 0.777470 +0.885120 0.546774 +0.883030 0.784307 +0.844872 0.553611 +0.842973 0.776973 +0.809182 0.573924 +0.807759 0.756320 +0.782426 0.605410 +0.781581 0.724679 +0.767992 0.644287 +0.767716 0.685757 +0.753612 0.473440 +0.737951 0.431021 +0.737742 0.385804 +0.753010 0.343242 +0.782838 0.507944 +0.781915 0.308470 +0.822102 0.530371 +0.820969 0.285680 +0.866669 0.538017 +0.865462 0.277622 +0.911163 0.529959 +0.910029 0.285267 +0.950217 0.507169 +0.949292 0.307694 +0.979122 0.472395 +0.978518 0.342198 +0.994390 0.429833 +0.994180 0.384616 +0.660137 0.844615 +0.681835 0.844615 +0.681835 0.858700 +0.660137 0.858700 +0.660137 0.830964 +0.681835 0.830964 +0.660137 0.817668 +0.681835 0.817668 +0.660137 0.804723 +0.681835 0.804723 +0.660137 0.792189 +0.681835 0.792189 +0.660137 0.779687 +0.681835 0.779687 +0.660137 0.766855 +0.681835 0.766855 +0.660137 0.753774 +0.681835 0.753774 +0.660137 0.740578 +0.681835 0.740578 +0.660137 0.963623 +0.681835 0.963623 +0.681835 0.976822 +0.660137 0.976822 +0.660137 0.950539 +0.681835 0.950539 +0.660137 0.937706 +0.681835 0.937706 +0.660137 0.925205 +0.681835 0.925205 +0.660137 0.912678 +0.681835 0.912678 +0.660137 0.899743 +0.681835 0.899743 +0.660137 0.886450 +0.681835 0.886450 +0.660137 0.872791 +0.681835 0.872791 +0.685647 0.844615 +0.694521 0.844615 +0.694521 0.858700 +0.685647 0.858700 +0.656326 0.858700 +0.647455 0.858700 +0.647455 0.844615 +0.656326 0.844615 +0.685647 0.830964 +0.694521 0.830964 +0.647455 0.830964 +0.656326 0.830964 +0.685647 0.817668 +0.694521 0.817668 +0.647455 0.817668 +0.656326 0.817668 +0.685647 0.804723 +0.694521 0.804723 +0.647455 0.804723 +0.656326 0.804723 +0.685647 0.792189 +0.694521 0.792189 +0.647455 0.792189 +0.656326 0.792189 +0.685647 0.779687 +0.694521 0.779687 +0.647455 0.779687 +0.656326 0.779687 +0.685647 0.766855 +0.694521 0.766855 +0.647455 0.766855 +0.656326 0.766855 +0.685647 0.753774 +0.694521 0.753774 +0.647455 0.753774 +0.656326 0.753774 +0.685647 0.740578 +0.694521 0.740578 +0.647455 0.740578 +0.656326 0.740578 +0.685647 0.963623 +0.694521 0.963623 +0.694521 0.976822 +0.685647 0.976822 +0.656326 0.976822 +0.647455 0.976822 +0.647455 0.963623 +0.656326 0.963623 +0.685647 0.950539 +0.694521 0.950539 +0.647455 0.950539 +0.656326 0.950539 +0.685647 0.937706 +0.694521 0.937706 +0.647455 0.937706 +0.656326 0.937706 +0.685647 0.925205 +0.694521 0.925205 +0.647455 0.925205 +0.656326 0.925205 +0.685647 0.912678 +0.694521 0.912678 +0.647455 0.912678 +0.656326 0.912678 +0.685647 0.899743 +0.694521 0.899743 +0.647455 0.899743 +0.656326 0.899743 +0.685647 0.886450 +0.694521 0.886450 +0.647455 0.886450 +0.656326 0.886450 +0.685647 0.872791 +0.694521 0.872791 +0.647455 0.872791 +0.656326 0.872791 +0.643318 0.607085 +0.637653 0.592359 +0.637714 0.576707 +0.643494 0.562020 +0.654025 0.619112 +0.654295 0.550067 +0.668485 0.626987 +0.668814 0.542291 +0.684951 0.629760 +0.685302 0.539629 +0.701438 0.627099 +0.701768 0.542403 +0.715958 0.619323 +0.716227 0.550278 +0.726759 0.607370 +0.726934 0.562304 +0.732538 0.592682 +0.732599 0.577031 +0.501246 0.855950 +0.507082 0.870618 +0.507203 0.886268 +0.501595 0.901014 +0.490399 0.844033 +0.490934 0.913076 +0.475850 0.836306 +0.476505 0.921000 +0.459352 0.833700 +0.460049 0.923829 +0.442896 0.836529 +0.443552 0.921223 +0.428468 0.844453 +0.429002 0.913495 +0.417807 0.856515 +0.418155 0.901579 +0.412199 0.871260 +0.412320 0.886911 +0.611126 0.858700 +0.632823 0.858700 +0.632823 0.844615 +0.611126 0.844615 +0.632823 0.830965 +0.611126 0.830965 +0.632823 0.817668 +0.611126 0.817668 +0.632823 0.804723 +0.611126 0.804723 +0.632823 0.792189 +0.611126 0.792189 +0.632823 0.779687 +0.611126 0.779687 +0.632823 0.766855 +0.611126 0.766855 +0.632823 0.753774 +0.611126 0.753774 +0.632823 0.740578 +0.611126 0.740578 +0.611126 0.976822 +0.632823 0.976822 +0.632823 0.963623 +0.611126 0.963623 +0.632823 0.950539 +0.611126 0.950539 +0.632823 0.937706 +0.611126 0.937706 +0.632823 0.925205 +0.611126 0.925205 +0.632823 0.912678 +0.611126 0.912678 +0.632823 0.899744 +0.611126 0.899744 +0.632823 0.886451 +0.611126 0.886451 +0.632823 0.872792 +0.611126 0.872792 +0.636635 0.858700 +0.645509 0.858700 +0.645509 0.844615 +0.636635 0.844615 +0.607314 0.844615 +0.598444 0.844615 +0.598444 0.858700 +0.607314 0.858700 +0.645509 0.830965 +0.636635 0.830965 +0.607314 0.830965 +0.598444 0.830965 +0.645509 0.817668 +0.636635 0.817668 +0.607314 0.817668 +0.598444 0.817668 +0.645509 0.804723 +0.636635 0.804723 +0.607314 0.804723 +0.598444 0.804723 +0.645509 0.792189 +0.636635 0.792189 +0.607314 0.792189 +0.598444 0.792189 +0.645509 0.779687 +0.636635 0.779687 +0.607314 0.779687 +0.598444 0.779687 +0.645509 0.766855 +0.636635 0.766855 +0.607314 0.766855 +0.598444 0.766855 +0.645509 0.753774 +0.636635 0.753774 +0.607314 0.753774 +0.598444 0.753774 +0.645509 0.740578 +0.636635 0.740578 +0.607314 0.740578 +0.598444 0.740578 +0.636635 0.976822 +0.645509 0.976822 +0.645509 0.963623 +0.636635 0.963623 +0.607314 0.963623 +0.598444 0.963623 +0.598444 0.976822 +0.607314 0.976822 +0.645509 0.950539 +0.636635 0.950539 +0.607314 0.950539 +0.598444 0.950539 +0.645509 0.937706 +0.636635 0.937706 +0.607314 0.937706 +0.598444 0.937706 +0.645509 0.925205 +0.636635 0.925205 +0.607314 0.925205 +0.598444 0.925205 +0.645509 0.912678 +0.636635 0.912678 +0.607314 0.912678 +0.598444 0.912678 +0.645509 0.899744 +0.636635 0.899744 +0.607314 0.899744 +0.598444 0.899744 +0.645509 0.886451 +0.636635 0.886451 +0.607314 0.886451 +0.598444 0.886451 +0.645509 0.872792 +0.636635 0.872792 +0.607314 0.872792 +0.598444 0.872792 +0.614087 0.650241 +0.608307 0.664929 +0.608246 0.680580 +0.613911 0.695307 +0.624888 0.638288 +0.624618 0.707333 +0.639407 0.630512 +0.639078 0.715208 +0.655895 0.627851 +0.655544 0.717982 +0.672361 0.630625 +0.672031 0.715320 +0.686820 0.638500 +0.686551 0.707544 +0.697527 0.650526 +0.697352 0.695591 +0.703192 0.665252 +0.703131 0.680903 +0.923096 0.670659 +0.928704 0.655913 +0.928583 0.640262 +0.922747 0.625594 +0.912435 0.682721 +0.911900 0.613678 +0.898006 0.690644 +0.897351 0.605951 +0.881551 0.693474 +0.880853 0.603345 +0.865054 0.690868 +0.864398 0.606174 +0.850504 0.683140 +0.849970 0.614098 +0.839657 0.671224 +0.839308 0.626160 +0.833821 0.656556 +0.833700 0.640905 +0.586734 0.208606 +0.586734 0.565608 +0.567089 0.208606 +0.606190 0.565608 +0.546909 0.208606 +0.625533 0.565608 +0.703055 0.208606 +0.395420 0.991461 +0.683476 0.208606 +0.387042 0.980082 +0.664111 0.208606 +0.387938 0.965979 +0.644821 0.208606 +0.397690 0.955753 +0.625533 0.208606 +0.411733 0.954187 +0.606190 0.208606 +0.567089 0.565608 +0.586734 0.068420 +0.567089 0.068420 +0.546909 0.068420 +0.723197 0.068420 +0.703055 0.068420 +0.683476 0.068420 +0.664111 0.068420 +0.644821 0.068420 +0.625533 0.068420 +0.606190 0.068420 +0.723197 0.208606 +0.586734 0.054419 +0.567089 0.054419 +0.546909 0.054419 +0.723197 0.054419 +0.703055 0.054419 +0.683476 0.054419 +0.664111 0.054419 +0.644821 0.054419 +0.625533 0.054419 +0.606190 0.054419 +0.586734 0.004051 +0.567089 0.004051 +0.546909 0.004051 +0.723197 0.004051 +0.703055 0.004051 +0.683476 0.004051 +0.664111 0.004051 +0.644821 0.004051 +0.625533 0.004051 +0.606190 0.004051 +0.586734 0.233166 +0.567089 0.233166 +0.546909 0.233166 +0.723197 0.233166 +0.703055 0.233166 +0.683476 0.233166 +0.664111 0.233166 +0.644821 0.233166 +0.625533 0.233166 +0.606190 0.233166 +0.427479 0.975573 +0.421813 0.988518 +0.409152 0.994793 +0.644821 0.565608 +0.664111 0.565608 +0.683476 0.565608 +0.703055 0.565608 +0.723197 0.565608 +0.546909 0.565608 +0.423498 0.962014 +0.241336 0.004994 +0.251390 0.766650 +0.209604 0.765772 +0.219929 0.004120 +0.284328 0.005591 +0.176937 0.004702 +0.189226 0.766048 +0.271768 0.766933 +0.377324 0.003499 +0.361808 0.765063 +0.320989 0.765121 +0.303297 0.003605 +0.395489 0.003764 +0.469515 0.003799 +0.452554 0.765055 +0.411736 0.765036 +0.055101 0.902876 +0.014284 0.902757 +0.014224 0.923138 +0.055042 0.923257 +0.508522 0.459887 +0.479330 0.526656 +0.484757 0.526656 +0.487364 0.526656 +0.494933 0.526656 +0.497286 0.526656 +0.504142 0.526656 +0.506332 0.459887 +0.506332 0.526656 +0.512860 0.526656 +0.517241 0.526656 +0.519489 0.526656 +0.526397 0.526656 +0.526397 0.459887 +0.531214 0.526656 +0.479330 0.563180 +0.484757 0.563180 +0.487364 0.563180 +0.494933 0.563180 +0.497286 0.563180 +0.504142 0.563180 +0.506332 0.563180 +0.512860 0.563180 +0.517241 0.563180 +0.519489 0.563180 +0.526397 0.563180 +0.531214 0.563180 +0.487364 0.609095 +0.489971 0.609095 +0.497286 0.609095 +0.499639 0.609095 +0.506332 0.609095 +0.508522 0.609095 +0.515051 0.609095 +0.517241 0.609095 +0.524067 0.609095 +0.526397 0.609095 +0.533681 0.609095 +0.479330 0.609095 +0.479330 0.624630 +0.484757 0.624630 +0.487364 0.624630 +0.494933 0.624630 +0.497286 0.624630 +0.504142 0.624630 +0.506332 0.624630 +0.512860 0.624630 +0.515051 0.624630 +0.521737 0.624630 +0.524067 0.624630 +0.531214 0.624630 +0.479330 0.638214 +0.484757 0.638214 +0.487364 0.638214 +0.494933 0.638214 +0.497286 0.638214 +0.504142 0.638214 +0.506332 0.638214 +0.512860 0.638214 +0.515051 0.638214 +0.521737 0.638214 +0.524067 0.638214 +0.531214 0.638214 +0.479330 0.651815 +0.484757 0.651815 +0.487364 0.651815 +0.494933 0.651815 +0.497286 0.651815 +0.504142 0.651815 +0.506332 0.651815 +0.512860 0.651815 +0.515051 0.651815 +0.521737 0.651815 +0.524067 0.651815 +0.531214 0.651815 +0.479330 0.663209 +0.484757 0.663209 +0.487364 0.663209 +0.494933 0.663209 +0.497286 0.663209 +0.504142 0.663209 +0.506332 0.663209 +0.512860 0.663209 +0.515051 0.663209 +0.521737 0.663209 +0.524067 0.663209 +0.531214 0.663209 +0.479330 0.673125 +0.484757 0.673125 +0.487364 0.673125 +0.494933 0.673125 +0.497286 0.673125 +0.504142 0.673125 +0.506332 0.673125 +0.512860 0.673125 +0.515051 0.673125 +0.521737 0.673125 +0.524067 0.673125 +0.531214 0.673125 +0.479330 0.685906 +0.484757 0.685906 +0.487364 0.685906 +0.494933 0.685906 +0.497286 0.685906 +0.504142 0.685906 +0.506332 0.685906 +0.512860 0.685906 +0.515051 0.685906 +0.521737 0.685906 +0.524067 0.685906 +0.531214 0.685906 +0.479330 0.777451 +0.484757 0.777451 +0.487364 0.777451 +0.494933 0.777451 +0.497286 0.777451 +0.504142 0.777451 +0.506332 0.777451 +0.512860 0.777451 +0.515051 0.777451 +0.521737 0.777451 +0.524067 0.777451 +0.531214 0.777451 +0.487365 0.459887 +0.499639 0.459887 +0.533681 0.459887 +0.517241 0.580873 +0.512860 0.580873 +0.506332 0.580873 +0.504142 0.580873 +0.497286 0.580873 +0.494933 0.580873 +0.487364 0.580873 +0.484757 0.580873 +0.479330 0.580873 +0.531214 0.580873 +0.526397 0.580873 +0.519489 0.580873 +0.521737 0.595957 +0.515051 0.595957 +0.512860 0.595957 +0.506332 0.595957 +0.504142 0.595957 +0.497286 0.595957 +0.494933 0.595957 +0.487364 0.595957 +0.484757 0.595957 +0.479330 0.595957 +0.531214 0.595957 +0.524067 0.595957 +0.479330 0.459887 +0.487365 0.391526 +0.479330 0.391526 +0.489972 0.459887 +0.489972 0.391526 +0.497286 0.459887 +0.497286 0.391526 +0.499639 0.391526 +0.506332 0.391526 +0.508522 0.391526 +0.512860 0.459887 +0.512860 0.391526 +0.519489 0.459887 +0.519489 0.391526 +0.521737 0.459887 +0.521737 0.391526 +0.526397 0.391526 +0.533681 0.391526 +0.487365 0.352210 +0.479330 0.352210 +0.489972 0.352210 +0.497286 0.352210 +0.499639 0.352210 +0.506332 0.352210 +0.508522 0.352210 +0.512860 0.352210 +0.519489 0.352210 +0.521737 0.352210 +0.526397 0.352210 +0.533681 0.352210 +0.487365 0.332180 +0.479330 0.332180 +0.489972 0.332180 +0.497286 0.332180 +0.499639 0.332180 +0.506332 0.332180 +0.508522 0.332180 +0.512860 0.332180 +0.519489 0.332180 +0.521737 0.332180 +0.526397 0.332180 +0.533681 0.332180 +0.479330 0.297630 +0.484757 0.297630 +0.487365 0.276860 +0.479330 0.276860 +0.487365 0.297630 +0.489972 0.276860 +0.494933 0.297630 +0.497286 0.276860 +0.497286 0.297630 +0.499639 0.276860 +0.504142 0.297630 +0.506332 0.276860 +0.506332 0.297630 +0.508522 0.276860 +0.512860 0.297630 +0.512860 0.276860 +0.517241 0.297630 +0.519489 0.276860 +0.519489 0.297630 +0.521737 0.276860 +0.526397 0.297630 +0.526397 0.276860 +0.531214 0.297630 +0.533681 0.276860 +0.487365 0.257408 +0.479330 0.257408 +0.489972 0.257408 +0.497286 0.257408 +0.499639 0.257408 +0.506332 0.257408 +0.508522 0.257408 +0.512860 0.257408 +0.519489 0.257408 +0.521737 0.257408 +0.526397 0.257408 +0.533681 0.257408 +0.487365 0.236545 +0.479330 0.236545 +0.489972 0.236545 +0.497286 0.236545 +0.499639 0.236545 +0.506332 0.236545 +0.508522 0.236545 +0.512860 0.236545 +0.519489 0.236545 +0.521737 0.236545 +0.526397 0.236545 +0.533681 0.236545 +0.487365 0.217895 +0.479330 0.217895 +0.489972 0.217895 +0.497286 0.217895 +0.499639 0.217895 +0.506332 0.217895 +0.508522 0.217895 +0.512860 0.217895 +0.519489 0.217895 +0.521737 0.217895 +0.526397 0.217895 +0.533681 0.217895 +0.487365 0.200766 +0.479330 0.200766 +0.489972 0.200766 +0.497286 0.200766 +0.499639 0.200766 +0.506332 0.200766 +0.508522 0.200766 +0.512860 0.200766 +0.519489 0.200766 +0.521737 0.200766 +0.526397 0.200766 +0.533681 0.200766 +0.487365 0.177595 +0.479330 0.177595 +0.489972 0.177595 +0.497286 0.177595 +0.499639 0.177595 +0.506332 0.177595 +0.508522 0.177595 +0.512860 0.177595 +0.519489 0.177595 +0.521737 0.177595 +0.526397 0.177595 +0.533681 0.177595 +0.487365 0.002954 +0.479330 0.002954 +0.489972 0.002954 +0.497286 0.002954 +0.499639 0.002954 +0.506332 0.002954 +0.508522 0.002954 +0.512860 0.002954 +0.517241 0.002954 +0.521737 0.002954 +0.526397 0.002954 +0.533681 0.002954 +0.487365 0.314183 +0.479330 0.314183 +0.489972 0.314183 +0.497286 0.314183 +0.499639 0.314183 +0.506332 0.314183 +0.508522 0.314183 +0.512860 0.314183 +0.519489 0.314183 +0.521737 0.314183 +0.526397 0.314183 +0.533681 0.314183 +0.533681 0.526656 +0.533681 0.563180 +0.536148 0.609095 +0.533681 0.624630 +0.533681 0.638214 +0.533681 0.651815 +0.533681 0.663209 +0.533681 0.673125 +0.533681 0.685906 +0.533681 0.777451 +0.533681 0.580873 +0.533681 0.595957 +0.536148 0.459887 +0.536148 0.391526 +0.536148 0.352210 +0.536148 0.332180 +0.533681 0.297630 +0.536148 0.276860 +0.536148 0.257408 +0.536148 0.236545 +0.536148 0.217895 +0.536148 0.200766 +0.536148 0.177595 +0.536148 0.002954 +0.536148 0.314183 +0.393687 0.928573 +0.403474 0.868076 +0.451773 0.871232 +0.452003 0.899695 +0.623960 0.995318 +0.641180 0.932563 +0.669164 0.927358 +0.681478 0.974168 +0.356871 0.933417 +0.349475 0.933380 +0.349513 0.925747 +0.356909 0.925784 +0.483277 0.928573 +0.426972 0.958022 +0.315623 0.925583 +0.588701 0.968263 +0.345479 0.938824 +0.284195 0.938798 +0.244574 0.932869 +0.273028 0.933007 +0.345476 0.946455 +0.273065 0.925378 +0.244611 0.925240 +0.284192 0.946429 +0.459274 0.960111 +0.466337 0.957926 +0.581284 0.929603 +0.580487 0.936954 +0.315586 0.933213 +0.389254 0.933579 +0.606866 0.907374 +0.389292 0.925945 +0.189432 0.918567 +0.237834 0.918281 +0.237788 0.910650 +0.189387 0.910936 +0.389921 0.938843 +0.389918 0.946474 +0.759447 0.987106 +0.698950 0.977320 +0.702106 0.929020 +0.730569 0.928790 +0.574012 0.933844 +0.517853 0.900968 +0.520068 0.872591 +0.568470 0.872812 +0.276845 0.912339 +0.284241 0.912366 +0.284214 0.919998 +0.276818 0.919973 +0.360688 0.912630 +0.389143 0.912727 +0.389117 0.920356 +0.360662 0.920259 +0.237491 0.933431 +0.189089 0.933717 +0.189045 0.926086 +0.237446 0.925800 +0.389711 0.958196 +0.328430 0.958707 +0.328366 0.951076 +0.389647 0.950564 +0.759447 0.897516 +0.788896 0.953821 +0.318104 0.920115 +0.318131 0.912484 +0.538754 0.960899 +0.484641 0.927595 +0.283989 0.959077 +0.283925 0.951447 +0.788800 0.914456 +0.790985 0.921520 +0.506386 0.960730 +0.499492 0.958058 +0.244435 0.919857 +0.244462 0.912223 +0.221834 0.895288 +0.035416 0.895288 +0.035416 0.795664 +0.221834 0.795664 +0.250991 0.895288 +0.250991 0.795664 +0.006259 0.795664 +0.006259 0.895288 +0.732613 0.574986 +0.732613 0.674609 +0.546195 0.674609 +0.546195 0.574986 +0.839833 0.809983 +0.839833 0.996401 +0.868990 0.809983 +0.868990 0.996401 +0.834025 0.996565 +0.834371 0.810147 +0.805214 0.810093 +0.804869 0.996511 +0.455998 0.857901 +0.409645 0.857901 +0.409645 0.773332 +0.455998 0.773332 +0.188349 0.950881 +0.272920 0.950881 +0.272920 0.997235 +0.188349 0.997235 +0.466610 0.857901 +0.466610 0.773332 +0.399033 0.773332 +0.399033 0.857901 +0.089025 0.940408 +0.089025 0.986762 +0.004263 0.986762 +0.004263 0.940408 +0.095861 0.951079 +0.180624 0.951079 +0.180624 0.997434 +0.095861 0.997434 +0.089025 0.929797 +0.004263 0.929797 +0.004263 0.997374 +0.089025 0.997374 +0.956615 0.997472 +0.943366 0.997431 +0.943615 0.801455 +0.956864 0.801496 +0.930116 0.997390 +0.930366 0.801413 +0.916868 0.997349 +0.917117 0.801372 +0.903619 0.997308 +0.903868 0.801331 +0.890370 0.997267 +0.890620 0.801290 +0.877121 0.997225 +0.877371 0.801248 +0.983112 0.997554 +0.983361 0.801578 +0.969863 0.997513 +0.970113 0.801537 +0.996361 0.997595 +0.996610 0.801619 +0.266964 0.775665 +0.280970 0.775665 +0.280970 0.904458 +0.266964 0.904458 +0.294975 0.775665 +0.294975 0.904458 +0.308980 0.775665 +0.308980 0.904458 +0.322985 0.775665 +0.322985 0.904458 +0.336990 0.775665 +0.336990 0.904458 +0.350994 0.775665 +0.350995 0.904458 +0.364999 0.775665 +0.365000 0.904458 +0.379004 0.775665 +0.379005 0.904458 +0.393009 0.775665 +0.393010 0.904458 +0.540293 0.782491 +0.540293 0.791412 +0.474616 0.791412 +0.474616 0.782491 +0.540293 0.800334 +0.474616 0.800334 +0.540293 0.809255 +0.474616 0.809255 +0.540293 0.818176 +0.474616 0.818176 +0.540293 0.827097 +0.474616 0.827097 +0.540293 0.836019 +0.474616 0.836019 +0.540293 0.844940 +0.474616 0.844940 +0.540293 0.853861 +0.474616 0.853861 +0.540293 0.862782 +0.474616 0.862782 +0.485622 0.976081 +0.506037 0.975331 +0.506027 0.980190 +0.485624 0.979393 +0.571276 0.973603 +0.571224 0.982616 +0.526249 0.980989 +0.526254 0.974755 +0.182082 0.911611 +0.161747 0.909280 +0.161898 0.908326 +0.182192 0.910924 +0.182594 0.927989 +0.182747 0.928670 +0.162604 0.932512 +0.162395 0.931568 +0.096910 0.945353 +0.096470 0.943464 +0.142672 0.934920 +0.142954 0.936166 +0.142071 0.905899 +0.141867 0.907161 +0.095169 0.901475 +0.095493 0.899560 +0.181947 0.917439 +0.162043 0.916969 +0.141811 0.916600 +0.096404 0.916062 +0.349862 0.986644 +0.142029 0.925506 +0.162210 0.923862 +0.182103 0.922166 +0.459255 0.974729 +0.455958 0.973619 +0.348308 0.975545 +0.348177 0.984724 +0.505883 0.969246 +0.485593 0.971211 +0.485583 0.984255 +0.505831 0.986273 +0.571999 0.995289 +0.525779 0.988612 +0.525866 0.967123 +0.572187 0.960930 +0.458296 0.979831 +0.457614 0.979601 +0.453635 0.978261 +0.454317 0.978491 +0.335408 0.984689 +0.335402 0.986601 +0.335675 0.973487 +0.335650 0.975382 +0.460242 0.974055 +0.350024 0.973670 +0.096807 0.928846 +0.455581 0.972485 +0.755363 0.803185 +0.954156 0.803839 +0.755281 0.862001 +0.956577 0.862001 +0.934066 0.872909 +0.933842 0.814680 +0.954115 0.814748 +0.046860 0.892527 +0.055147 0.892527 +0.038404 0.892527 +0.046860 0.892527 +0.029907 0.892527 +0.038404 0.892527 +0.279028 0.892673 +0.287406 0.892673 +0.270608 0.892673 +0.279028 0.892673 +0.262215 0.892673 +0.270608 0.892673 +0.253835 0.892673 +0.262216 0.892673 +0.245559 0.892673 +0.253834 0.892673 +0.055147 0.892527 +0.063399 0.892527 + + + + + + + + + + +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.000000 0.000000 +0.000000 0.000000 0.000000 0.000000 + + + + + + + + + + + + + +

4 0 12 12 0 1 0 0 1 2 3 3 0 3 0 0 4 4 12 12 5 5 13 15 1 6 4 4 0 7 7 7 3 8 6 6 1 9 4 4 3 10 6 6 2 11 5 5 5 12 23 27 6 13 22 26 0 14 8 8 0 15 8 8 6 16 22 26 3 17 9 9 7 18 27 33 4 19 26 32 1 20 17 19 1 21 17 19 2 22 16 18 7 23 27 33 4 24 12 31 8 25 34 50 5 26 13 28 8 27 34 50 4 28 12 31 9 29 35 51 7 30 28 36 3 31 20 22 6 32 29 37 3 33 20 22 7 34 28 36 2 35 21 23 8 36 39 59 10 37 38 58 5 38 23 40 5 39 23 40 10 40 38 58 6 41 22 41 11 42 41 61 9 43 40 60 4 44 26 47 4 45 26 47 7 46 27 46 11 47 41 61 10 48 45 70 7 49 28 53 6 50 29 52 7 51 28 53 10 52 45 70 11 53 44 69 12 54 42 64 8 55 34 66 9 56 35 65 8 57 34 66 12 58 42 64 13 59 43 67 8 60 39 72 13 61 47 75 14 62 46 74 8 63 39 72 14 64 46 74 10 65 38 73 12 66 48 76 9 67 40 79 11 68 41 78 12 69 48 76 11 70 41 78 15 71 49 77 13 72 43 82 51 73 112 165 17 74 51 83 14 75 53 85 15 76 52 84 10 77 45 86 10 78 45 86 15 79 52 84 11 80 44 87 17 81 54 88 14 82 46 90 13 83 47 89 14 84 46 90 17 85 54 88 18 86 55 91 16 87 56 92 12 88 48 95 15 89 49 94 16 90 56 92 15 91 49 94 19 92 57 93 17 93 51 97 21 94 59 98 41 95 111 164 17 96 51 97 20 97 58 96 21 98 59 98 18 99 61 100 50 100 137 143 14 101 53 101 23 102 63 106 18 103 55 104 17 104 54 103 18 105 55 104 23 106 63 106 22 107 62 105 27 108 67 110 25 109 65 108 24 110 64 107 25 111 65 108 27 112 67 110 26 113 66 109 28 114 68 111 24 115 71 114 25 116 70 113 28 117 68 111 25 118 70 113 29 119 69 112 31 120 73 116 30 121 72 115 32 122 74 117 32 123 74 117 30 124 72 115 33 125 75 118 32 126 77 120 33 127 76 119 34 128 78 121 34 129 78 121 33 130 76 119 35 131 79 122 37 132 81 126 36 133 80 125 31 134 73 123 31 135 73 123 36 136 80 125 30 137 72 124 34 138 78 128 35 139 79 127 38 140 82 129 38 141 82 129 35 142 79 127 39 143 83 130 40 144 84 131 42 145 86 133 41 146 85 132 42 147 86 133 40 148 84 131 43 149 87 134 20 150 91 138 45 151 90 137 21 152 88 135 21 153 88 135 45 154 90 137 44 155 89 136 47 156 93 140 46 157 92 139 48 158 94 141 48 159 94 141 46 160 92 139 49 161 95 142 51 162 97 144 50 163 96 143 20 164 91 145 20 165 91 145 50 166 96 143 45 167 90 146 48 168 94 148 49 169 95 147 51 170 98 149 51 171 98 149 49 172 95 147 50 173 99 150 27 174 103 154 24 175 102 153 28 176 101 152 27 177 103 154 28 178 101 152 23 179 100 151 23 180 63 106 28 181 105 156 29 182 104 155 23 183 63 106 29 184 104 155 22 185 62 105 19 186 57 157 27 187 67 110 16 188 56 158 27 189 67 110 19 190 57 157 26 191 66 109 25 192 107 160 26 193 106 159 29 194 108 161 22 195 109 162 29 196 108 161 26 197 106 159 17 198 51 97 42 199 110 163 23 200 100 151 42 201 110 163 17 202 51 97 41 203 111 164 17 204 51 97 51 205 112 165 20 206 58 96 48 207 113 169 16 208 50 167 47 209 114 170 51 210 112 168 16 211 50 167 48 212 113 169 32 213 115 171 23 214 100 151 31 215 116 172 34 216 121 177 27 217 103 154 32 218 115 171 27 219 103 154 23 220 100 151 32 221 115 171 16 222 50 167 27 223 103 154 53 224 119 175 16 225 50 167 53 226 119 175 52 227 118 174 27 228 103 154 38 229 120 176 53 230 119 175 53 231 125 32 54 232 123 178 52 233 122 35 54 234 123 178 53 235 125 32 55 236 124 48 22 237 109 180 30 238 126 115 36 239 129 125 22 240 109 180 26 241 106 179 33 242 127 118 33 243 127 118 26 244 106 179 35 245 128 122 35 246 128 127 26 247 106 183 39 248 130 130 18 249 61 184 22 250 109 185 43 251 132 134 18 252 61 184 43 253 132 134 40 254 131 131 45 255 133 137 18 256 61 186 44 257 134 136 19 258 60 187 46 259 135 139 54 260 139 195 49 261 136 147 19 262 60 190 50 263 137 150 19 264 60 49 55 265 138 48 26 266 106 191 55 267 138 48 19 268 60 49 54 269 139 178 16 270 50 167 52 271 118 174 47 272 114 170 37 273 117 173 23 274 100 151 42 275 110 163 40 276 131 131 44 277 134 192 18 278 61 184 36 279 129 125 43 280 132 193 22 281 109 182 36 282 80 196 37 283 81 197 42 284 86 133 42 285 86 133 43 286 87 134 36 287 80 196 38 288 82 198 55 289 124 48 53 290 125 32 55 291 124 48 38 292 82 198 39 293 83 199 40 294 84 200 41 295 85 201 21 296 88 135 21 297 88 135 44 298 89 136 40 299 84 200 46 300 92 202 47 301 93 203 52 302 122 35 52 303 122 35 54 304 123 178 46 305 92 202 135 306 319 304 202 307 318 303 60 308 148 208 202 309 318 303 56 310 147 204 60 311 148 208 60 312 142 208 57 313 140 205 61 314 143 209 57 315 140 205 60 316 142 208 56 317 141 204 137 318 321 306 135 319 319 304 58 320 150 206 135 321 319 304 60 322 148 208 58 323 150 206 59 324 145 207 58 325 144 206 61 326 143 209 58 327 144 206 60 328 142 208 61 329 143 209 209 330 502 311 139 331 501 310 208 332 500 542 140 333 328 312 72 334 157 225 209 335 327 311 72 336 157 225 140 337 328 312 70 338 158 221 140 339 328 312 223 340 342 323 70 341 158 221 75 342 169 229 69 343 167 219 73 344 168 226 66 345 174 216 73 346 168 226 69 347 167 219 67 348 182 217 64 349 172 214 68 350 194 218 68 351 194 218 64 352 172 214 65 353 195 215 63 354 181 213 62 355 170 210 67 356 182 217 67 357 182 217 62 358 170 210 64 359 172 214 66 360 174 216 69 361 167 219 63 362 181 213 63 363 181 213 69 364 167 219 62 365 170 210 71 366 184 223 75 367 169 229 73 368 168 226 75 369 169 229 71 370 184 223 70 371 178 221 71 372 164 223 220 373 341 322 142 374 337 318 220 375 341 322 71 376 164 223 73 377 188 226 74 378 163 228 70 379 178 221 71 380 184 223 70 381 178 221 74 382 163 228 72 383 177 225 223 384 342 323 224 385 343 324 69 386 187 219 223 387 342 323 69 388 187 219 75 389 189 229 143 390 345 326 64 391 192 214 224 392 343 324 76 393 205 235 79 394 206 238 77 395 208 236 77 396 208 236 79 397 206 238 78 398 207 237 80 399 209 239 76 400 205 235 77 401 208 236 80 402 209 239 77 403 208 236 81 404 210 240 82 405 211 241 80 406 209 239 81 407 210 240 82 408 211 241 81 409 210 240 83 410 212 242 83 411 266 242 85 412 214 244 84 413 213 243 84 414 213 243 82 415 265 241 83 416 266 242 87 417 216 246 84 418 213 243 85 419 214 244 84 420 213 243 87 421 216 246 86 422 215 245 86 423 215 245 89 424 218 248 88 425 217 247 89 426 218 248 86 427 215 245 87 428 216 246 90 429 219 249 88 430 217 247 91 431 220 250 91 432 220 250 88 433 217 247 89 434 218 248 91 435 220 250 92 436 221 251 90 437 219 249 92 438 221 251 91 439 220 250 93 440 222 252 92 441 251 251 78 442 207 237 79 443 206 238 78 444 207 237 92 445 251 251 93 446 252 252 97 447 224 256 95 448 226 254 94 449 223 253 95 450 226 254 97 451 224 256 96 452 225 255 99 453 228 258 94 454 223 253 98 455 227 257 94 456 223 253 99 457 228 258 97 458 224 256 98 459 227 257 101 460 230 260 99 461 228 258 101 462 230 260 98 463 227 257 100 464 229 259 102 465 231 261 101 466 268 260 100 467 267 259 101 468 268 260 102 469 231 261 103 470 232 262 104 471 233 263 103 472 232 262 102 473 231 261 103 474 232 262 104 475 233 263 105 476 234 264 104 477 233 263 107 478 236 266 105 479 234 264 107 480 236 266 104 481 233 263 106 482 235 265 108 483 237 267 109 484 238 268 106 485 235 265 109 486 238 268 107 487 236 266 106 488 235 265 111 489 240 270 108 490 237 267 110 491 239 269 108 492 237 267 111 493 240 270 109 494 238 268 110 495 253 269 96 496 225 255 111 497 254 270 96 498 225 255 110 499 253 269 95 500 226 254 113 501 258 272 115 502 256 274 114 503 257 273 115 504 256 274 113 505 258 272 112 506 255 271 112 507 241 271 113 508 244 272 95 509 226 254 113 510 244 272 94 511 223 253 95 512 226 254 94 513 223 253 113 514 244 272 116 515 245 275 94 516 223 253 116 517 245 275 98 518 227 257 98 519 227 257 116 520 245 275 117 521 246 276 98 522 227 257 117 523 246 276 100 524 229 259 102 525 231 261 100 526 267 259 118 527 247 277 100 528 267 259 117 529 269 276 118 530 247 277 104 531 233 263 102 532 231 261 119 533 248 278 102 534 231 261 118 535 247 277 119 536 248 278 106 537 235 265 104 538 233 263 120 539 249 279 120 540 249 279 104 541 233 263 119 542 248 278 108 543 237 267 106 544 235 265 114 545 243 273 114 546 243 273 106 547 235 265 120 548 249 279 110 549 239 269 108 550 237 267 115 551 242 274 115 552 242 274 108 553 237 267 114 554 243 273 115 555 270 274 112 556 241 271 110 557 253 269 112 558 241 271 95 559 226 254 110 560 253 269 76 561 205 235 229 562 1875 576 79 563 206 238 79 564 206 238 229 565 1875 576 226 566 1876 573 80 567 209 239 231 568 1877 578 76 569 205 235 229 570 1878 576 76 571 205 235 231 572 1877 578 82 573 211 241 233 574 1879 580 80 575 209 239 231 576 1880 578 80 577 209 239 233 578 1879 580 233 579 1882 580 82 580 265 241 235 581 1881 582 235 582 1881 582 82 583 265 241 84 584 213 243 235 585 1884 582 84 586 213 243 237 587 1883 584 237 588 1883 584 84 589 213 243 86 590 215 245 239 591 1885 586 86 592 215 245 88 593 217 247 86 594 215 245 239 595 1885 586 237 596 1886 584 241 597 1887 588 88 598 217 247 90 599 219 249 88 600 217 247 241 601 1887 588 239 602 1888 586 243 603 1889 590 90 604 219 249 92 605 221 251 90 606 219 249 243 607 1889 590 241 608 1890 588 79 609 206 238 226 610 1891 573 92 611 251 251 92 612 251 251 226 613 1891 573 243 614 1892 590 120 615 263 279 113 616 258 272 114 617 257 273 119 618 262 278 113 619 258 272 120 620 263 279 113 621 258 272 119 622 262 278 116 623 259 275 118 624 261 277 116 625 259 275 119 626 262 278 116 627 259 275 118 628 261 277 117 629 260 276 78 630 207 237 96 631 225 255 97 632 224 256 97 633 224 256 77 634 208 236 78 635 207 237 99 636 228 258 81 637 210 240 97 638 224 256 77 639 208 236 97 640 224 256 81 641 210 240 81 642 210 240 99 643 228 258 101 644 230 260 81 645 210 240 101 646 230 260 83 647 212 242 83 648 266 242 101 649 268 260 85 650 214 244 85 651 214 244 101 652 268 260 103 653 232 262 85 654 214 244 105 655 234 264 87 656 216 246 105 657 234 264 85 658 214 244 103 659 232 262 87 660 216 246 105 661 234 264 89 662 218 248 107 663 236 266 89 664 218 248 105 665 234 264 91 666 220 250 107 667 236 266 109 668 238 268 107 669 236 266 91 670 220 250 89 671 218 248 111 672 240 270 93 673 222 252 91 674 220 250 111 675 240 270 91 676 220 250 109 677 238 268 96 678 225 255 78 679 207 237 111 680 254 270 111 681 254 270 78 682 207 237 93 683 252 252 121 684 271 284 123 685 273 286 122 686 272 285 121 687 271 284 122 688 272 285 134 689 305 298 123 690 273 286 121 691 271 284 124 692 274 287 126 693 276 289 129 694 308 293 125 695 275 288 126 696 276 289 125 697 275 288 127 698 278 291 133 699 309 297 127 700 278 291 132 701 313 296 126 702 276 289 127 703 278 291 133 704 309 297 121 705 279 284 128 706 281 292 124 707 280 287 128 708 281 292 121 709 279 284 125 710 282 288 128 711 286 292 129 712 285 293 123 713 284 286 123 714 284 286 124 715 283 287 128 716 286 292 129 717 290 293 126 718 289 289 122 719 288 285 129 720 290 293 122 721 288 285 123 722 287 286 133 723 294 297 131 724 292 295 130 725 291 294 131 726 292 295 133 727 294 297 132 728 293 296 134 729 295 298 127 730 298 291 121 731 296 284 127 732 298 291 125 733 297 288 121 734 296 284 131 735 292 295 132 736 293 296 134 737 295 298 132 738 293 296 127 739 298 291 134 740 295 298 126 741 302 289 130 742 291 294 122 743 303 285 130 744 291 294 126 745 302 289 133 746 294 297 134 747 305 298 122 748 272 285 130 749 312 294 134 750 305 298 130 751 312 294 131 752 314 295 128 753 307 292 125 754 275 288 129 755 308 293 285 756 315 302 57 757 152 205 202 758 317 303 202 759 317 303 57 760 152 205 56 761 153 204 61 762 149 209 285 763 316 302 136 764 320 305 285 765 316 302 61 766 149 209 57 767 146 205 59 768 151 207 136 769 320 305 138 770 322 307 136 771 320 305 59 772 151 207 61 773 149 209 63 774 161 213 286 775 323 308 66 776 154 216 67 777 162 217 287 778 334 316 286 779 323 308 287 780 334 316 67 781 162 217 68 782 179 218 68 783 159 218 225 784 331 314 141 785 329 313 225 786 331 314 68 787 159 218 65 788 160 215 287 789 682 316 141 790 685 313 218 791 684 557 72 792 177 225 74 793 163 228 288 794 335 317 288 795 335 317 139 796 326 310 72 797 177 225 71 798 164 223 142 799 337 318 74 800 183 228 73 801 188 226 66 802 154 216 286 803 323 308 73 804 188 226 286 805 323 308 220 806 341 322 144 807 352 333 145 808 351 332 146 809 353 334 145 810 351 332 147 811 354 335 146 812 353 334 144 813 355 336 150 814 370 354 149 815 369 353 150 816 370 354 144 817 355 336 146 818 358 339 148 819 359 340 144 820 347 328 149 821 360 341 144 822 347 328 148 823 359 340 145 824 348 329 151 825 374 363 145 826 362 345 148 827 373 360 145 828 362 345 151 829 374 363 147 830 363 346 151 831 375 364 146 832 367 350 147 833 366 349 146 834 367 350 151 835 375 364 150 836 376 367 153 837 382 378 148 838 359 357 149 839 360 356 148 840 359 357 153 841 382 378 152 842 381 377 149 843 369 368 154 844 386 386 153 845 385 385 154 846 386 386 149 847 369 368 150 848 370 371 152 849 387 388 155 850 388 391 148 851 373 373 148 852 373 373 155 853 388 391 151 854 374 374 151 855 375 383 154 856 391 398 150 857 376 380 154 858 391 398 151 859 375 383 155 860 392 399 157 861 390 393 156 862 389 392 153 863 382 394 153 864 382 394 156 865 389 392 152 866 381 395 157 867 393 401 153 868 385 400 158 869 394 402 153 870 385 400 154 871 386 403 158 872 394 402 152 873 387 405 156 874 395 404 155 875 388 406 156 876 395 404 159 877 396 407 155 878 388 406 161 879 398 409 195 880 459 494 157 881 390 410 159 882 399 412 154 883 391 414 155 884 392 413 154 885 391 414 159 886 399 412 158 887 400 415 158 888 394 418 161 889 401 416 157 890 393 419 161 891 401 416 158 892 394 418 162 893 402 417 160 894 403 420 159 895 396 422 156 896 395 421 159 897 396 422 160 898 403 420 163 899 404 423 195 900 459 494 161 901 398 426 164 902 405 424 164 903 405 424 161 904 398 426 165 905 406 425 158 906 400 429 194 907 484 471 162 908 408 430 166 909 409 431 161 910 401 434 162 911 402 433 166 912 409 431 162 913 402 433 167 914 410 432 168 915 411 435 171 916 414 438 170 917 413 437 168 918 411 435 170 919 413 437 169 920 412 436 172 921 415 439 170 922 417 441 171 923 416 440 170 924 417 441 172 925 415 439 173 926 418 442 174 927 419 443 177 928 422 446 176 929 421 445 176 930 421 445 175 931 420 444 174 932 419 443 175 933 423 447 176 934 426 450 179 935 425 449 179 936 425 449 178 937 424 448 175 938 423 447 177 939 422 451 181 940 428 453 180 941 427 452 181 942 428 453 177 943 422 451 174 944 419 454 178 945 424 455 179 946 425 458 183 947 430 457 183 948 430 457 182 949 429 456 178 950 424 455 185 951 432 460 184 952 431 459 186 953 433 461 187 954 434 462 186 955 433 461 184 956 431 459 165 957 435 463 188 958 437 465 164 959 436 464 188 960 437 465 165 961 435 463 189 962 438 466 190 963 439 467 193 964 442 470 192 965 441 469 192 966 441 469 191 967 440 468 190 968 439 467 194 969 443 471 195 970 444 474 164 971 436 473 164 972 436 473 188 973 437 472 194 974 443 471 191 975 440 475 192 976 441 478 195 977 446 477 195 978 446 477 194 979 445 476 191 980 440 475 171 981 448 480 168 982 447 479 172 983 449 481 166 984 450 482 172 985 449 481 168 986 447 479 166 987 409 431 173 988 452 484 172 989 451 483 173 990 452 484 166 991 409 431 167 992 410 432 168 993 411 435 163 994 404 486 160 995 403 485 163 996 404 486 168 997 411 435 169 998 412 436 173 999 454 488 169 1000 456 490 170 1001 455 489 169 1002 456 490 173 1003 454 488 167 1004 453 487 161 1005 398 426 166 1006 450 482 186 1007 458 492 161 1008 398 426 186 1009 458 492 187 1010 457 491 160 1011 397 495 195 1012 459 497 192 1013 460 496 160 1014 397 495 192 1015 460 496 193 1016 461 498 177 1017 462 499 166 1018 450 482 176 1019 463 500 176 1020 463 500 168 1021 447 479 179 1022 467 504 166 1023 450 482 168 1024 447 479 176 1025 463 500 160 1026 397 495 196 1027 465 502 168 1028 447 479 196 1029 465 502 160 1030 397 495 197 1031 466 503 168 1032 447 479 183 1033 468 505 179 1034 467 504 196 1035 469 360 197 1036 472 361 199 1037 471 506 196 1038 469 360 199 1039 471 506 198 1040 470 376 175 1041 474 444 167 1042 453 507 174 1043 473 443 178 1044 475 448 169 1045 456 508 175 1046 474 444 169 1047 456 508 167 1048 453 507 175 1049 474 444 178 1050 475 455 182 1051 477 456 169 1052 456 511 162 1053 408 513 185 1054 478 460 167 1055 453 512 185 1056 478 460 162 1057 408 513 184 1058 479 459 188 1059 480 465 189 1060 481 466 162 1061 408 514 163 1062 407 515 191 1063 482 468 194 1064 484 476 162 1065 408 517 194 1066 484 471 188 1067 480 472 163 1068 407 379 169 1069 456 519 198 1070 486 376 163 1071 407 379 198 1072 486 376 199 1073 485 506 160 1074 397 495 193 1075 461 498 197 1076 466 503 180 1077 464 501 186 1078 458 492 166 1079 450 482 161 1080 398 426 187 1081 457 491 165 1082 406 425 181 1083 476 453 167 1084 453 510 185 1085 478 521 190 1086 483 467 163 1087 407 515 199 1088 485 523 180 1089 427 525 181 1090 428 524 186 1091 433 461 186 1092 433 461 181 1093 428 524 185 1094 432 460 196 1095 469 360 198 1096 470 376 183 1097 430 526 183 1098 430 526 198 1099 470 376 182 1100 429 527 187 1101 434 529 184 1102 431 528 165 1103 435 463 165 1104 435 463 184 1105 431 528 189 1106 438 466 193 1107 442 531 190 1108 439 530 197 1109 472 361 197 1110 472 361 190 1111 439 530 199 1112 471 506 202 1113 490 535 135 1114 489 534 201 1115 488 533 201 1116 488 533 200 1117 487 532 202 1118 490 535 201 1119 494 533 203 1120 492 536 200 1121 491 532 203 1122 492 536 201 1123 494 533 204 1124 493 537 205 1125 495 538 135 1126 489 534 137 1127 496 539 135 1128 489 534 205 1129 495 538 201 1130 488 533 204 1131 493 537 205 1132 498 538 206 1133 497 540 205 1134 498 538 204 1135 493 537 201 1136 494 533 140 1137 504 546 208 1138 500 542 207 1139 499 541 208 1140 500 542 140 1141 504 546 209 1142 502 544 211 1143 506 548 210 1144 505 547 213 1145 508 550 211 1146 506 548 213 1147 508 550 212 1148 507 549 216 1149 513 555 219 1150 516 558 218 1151 515 557 218 1152 515 557 217 1153 514 556 216 1154 513 555 214 1155 510 552 215 1156 512 554 219 1157 516 558 219 1158 516 558 216 1159 513 555 214 1160 510 552 215 1161 512 554 213 1162 508 550 210 1163 505 547 213 1164 508 550 215 1165 512 554 214 1166 510 552 211 1167 506 548 212 1168 507 549 222 1169 530 566 222 1170 530 566 212 1171 507 549 207 1172 529 541 222 1173 530 566 207 1174 529 541 221 1175 527 565 221 1176 527 565 207 1177 529 541 208 1178 528 542 213 1179 534 550 223 1180 532 567 212 1181 531 549 223 1182 532 567 213 1183 534 550 224 1184 533 568 224 1185 533 568 213 1186 534 550 214 1187 538 552 214 1188 538 552 216 1189 540 555 224 1190 533 568 216 1191 540 555 217 1192 542 556 143 1193 537 570 226 1194 543 573 229 1195 546 576 228 1196 545 575 226 1197 543 573 228 1198 545 575 227 1199 544 574 231 1200 548 578 228 1201 545 575 229 1202 546 576 228 1203 545 575 231 1204 548 578 230 1205 547 577 231 1206 548 578 233 1207 550 580 230 1208 547 577 233 1209 550 580 232 1210 549 579 230 1211 547 577 232 1212 552 579 235 1213 554 582 234 1214 553 581 235 1215 554 582 232 1216 552 579 233 1217 551 580 235 1218 554 582 236 1219 555 583 234 1220 553 581 236 1221 555 583 235 1222 554 582 237 1223 556 584 237 1224 556 584 239 1225 558 586 238 1226 557 585 237 1227 556 584 238 1228 557 585 236 1229 555 583 239 1230 558 586 241 1231 560 588 240 1232 559 587 239 1233 558 586 240 1234 559 587 238 1235 557 585 240 1236 559 587 243 1237 562 590 242 1238 561 589 243 1239 562 590 240 1240 559 587 241 1241 560 588 243 1242 563 590 226 1243 543 573 227 1244 544 574 243 1245 563 590 227 1246 544 574 242 1247 564 589 245 1248 566 592 247 1249 568 594 246 1250 567 593 247 1251 568 594 245 1252 566 592 244 1253 565 591 249 1254 570 596 244 1255 565 591 245 1256 566 592 244 1257 565 591 249 1258 570 596 248 1259 569 595 249 1260 570 596 251 1261 572 598 248 1262 569 595 251 1263 572 598 250 1264 571 597 248 1265 569 595 252 1266 573 599 251 1267 575 598 253 1268 574 600 251 1269 575 598 252 1270 573 599 250 1271 576 597 253 1272 574 600 254 1273 577 601 252 1274 573 599 254 1275 577 601 253 1276 574 600 255 1277 578 602 255 1278 578 602 257 1279 580 604 254 1280 577 601 257 1281 580 604 256 1282 579 603 254 1283 577 601 256 1284 579 603 259 1285 582 606 258 1286 581 605 257 1287 580 604 259 1288 582 606 256 1289 579 603 261 1290 584 608 258 1291 581 605 259 1292 582 606 258 1293 581 605 261 1294 584 608 260 1295 583 607 246 1296 567 593 260 1297 586 607 261 1298 585 608 260 1299 586 607 246 1300 567 593 247 1301 568 594 264 1302 589 611 263 1303 588 610 262 1304 587 609 264 1305 589 611 262 1306 587 609 265 1307 590 612 247 1308 568 594 244 1309 565 591 264 1310 592 611 247 1311 568 594 264 1312 592 611 265 1313 591 612 264 1314 592 611 244 1315 565 591 266 1316 593 613 244 1317 565 591 248 1318 569 595 266 1319 593 613 266 1320 593 613 248 1321 569 595 267 1322 594 614 248 1323 569 595 250 1324 571 597 267 1325 594 614 267 1326 595 614 250 1327 576 597 268 1328 596 615 268 1329 596 615 250 1330 576 597 252 1331 573 599 268 1332 596 615 252 1333 573 599 269 1334 597 616 269 1335 597 616 252 1336 573 599 254 1337 577 601 256 1338 579 603 270 1339 598 617 254 1340 577 601 270 1341 598 617 269 1342 597 616 254 1343 577 601 258 1344 581 605 263 1345 599 610 256 1346 579 603 263 1347 599 610 270 1348 598 617 256 1349 579 603 260 1350 583 607 262 1351 600 609 258 1352 581 605 262 1353 600 609 263 1354 599 610 258 1355 581 605 260 1356 586 607 247 1357 568 594 265 1358 591 612 260 1359 586 607 265 1360 591 612 262 1361 601 609 264 1362 589 611 270 1363 613 617 263 1364 588 610 269 1365 615 616 264 1366 589 611 266 1367 614 613 264 1368 589 611 269 1369 615 616 270 1370 613 617 266 1371 614 613 268 1372 617 615 269 1373 615 616 268 1374 617 615 266 1375 614 613 267 1376 616 614 228 1377 545 575 245 1378 566 592 227 1379 544 574 227 1380 544 574 245 1381 566 592 246 1382 567 593 245 1383 566 592 228 1384 545 575 230 1385 547 577 245 1386 566 592 230 1387 547 577 249 1388 570 596 230 1389 547 577 251 1390 572 598 249 1391 570 596 251 1392 572 598 230 1393 547 577 232 1394 549 579 234 1395 553 581 253 1396 574 600 251 1397 575 598 251 1398 575 598 232 1399 552 579 234 1400 553 581 253 1401 574 600 234 1402 553 581 255 1403 578 602 255 1404 578 602 234 1405 553 581 236 1406 555 583 238 1407 557 585 257 1408 580 604 255 1409 578 602 238 1410 557 585 255 1411 578 602 236 1412 555 583 257 1413 580 604 240 1414 559 587 259 1415 582 606 240 1416 559 587 257 1417 580 604 238 1418 557 585 259 1419 582 606 240 1420 559 587 261 1421 584 608 242 1422 561 589 261 1423 584 608 240 1424 559 587 261 1425 585 608 242 1426 564 589 227 1427 544 574 227 1428 544 574 246 1429 567 593 261 1430 585 608 272 1431 619 628 271 1432 618 627 273 1433 620 629 274 1434 621 630 271 1435 618 627 284 1436 653 641 273 1437 620 629 271 1438 618 627 274 1439 621 630 277 1440 625 634 279 1441 654 636 276 1442 624 633 277 1443 625 634 276 1444 624 633 275 1445 622 631 275 1446 622 631 276 1447 624 633 280 1448 657 637 275 1449 622 631 280 1450 657 637 281 1451 660 638 278 1452 628 635 277 1453 627 634 271 1454 626 627 278 1455 628 635 271 1456 626 627 272 1457 629 628 278 1458 631 635 273 1459 633 629 279 1460 632 636 273 1461 633 629 278 1462 631 635 272 1463 630 628 276 1464 636 633 279 1465 635 636 274 1466 637 630 273 1467 634 629 274 1468 637 630 279 1469 635 636 280 1470 638 637 283 1471 641 640 282 1472 640 639 280 1473 638 637 282 1474 640 639 281 1475 639 638 275 1476 642 631 284 1477 645 641 271 1478 644 627 275 1479 642 631 271 1480 644 627 277 1481 643 634 281 1482 639 638 282 1483 640 639 284 1484 645 641 281 1485 639 638 284 1486 645 641 275 1487 642 631 283 1488 641 640 276 1489 650 633 274 1490 649 630 276 1491 650 633 283 1492 641 640 280 1493 638 637 283 1494 658 640 284 1495 653 641 282 1496 661 639 274 1497 621 630 284 1498 653 641 283 1499 658 640 279 1500 654 636 277 1501 625 634 278 1502 655 635 202 1503 665 535 200 1504 664 532 203 1505 663 536 203 1506 663 536 285 1507 662 645 202 1508 665 535 136 1509 666 646 285 1510 669 645 204 1511 667 537 285 1512 669 645 203 1513 668 536 204 1514 667 537 138 1515 670 647 136 1516 666 646 206 1517 671 540 136 1518 666 646 204 1519 667 537 206 1520 671 540 141 1521 676 650 217 1522 678 556 218 1523 677 557 217 1524 678 556 141 1525 676 650 225 1526 679 572 286 1527 672 648 287 1528 682 652 219 1529 683 558 219 1530 683 558 287 1531 682 652 218 1532 684 557 221 1533 527 565 208 1534 528 542 288 1535 687 653 288 1536 687 653 208 1537 528 542 139 1538 686 543 220 1539 525 563 211 1540 524 548 222 1541 692 566 220 1542 525 563 222 1543 692 566 142 1544 688 654 212 1545 531 549 223 1546 532 567 207 1547 499 541 286 1548 672 648 211 1549 524 548 220 1550 525 563 211 1551 524 548 286 1552 672 648 210 1553 673 547 435 1554 920 802 434 1555 919 801 436 1556 921 803 434 1557 919 801 433 1558 918 800 436 1559 921 803 434 1560 919 801 438 1561 923 805 433 1562 918 800 438 1563 923 805 437 1564 922 804 433 1565 918 800 437 1566 922 804 438 1567 923 805 439 1568 924 806 438 1569 923 805 440 1570 925 807 439 1571 924 806 439 1572 924 806 440 1573 925 807 441 1574 926 808 440 1575 925 807 442 1576 927 809 441 1577 926 808 441 1578 926 808 442 1579 927 809 443 1580 928 810 442 1581 927 809 444 1582 929 811 443 1583 928 810 443 1584 928 810 444 1585 929 811 445 1586 930 812 444 1587 929 811 446 1588 931 813 445 1589 930 812 445 1590 930 812 446 1591 931 813 447 1592 932 814 446 1593 931 813 448 1594 933 815 447 1595 932 814 448 1596 933 815 449 1597 934 816 447 1598 932 814 449 1599 934 816 448 1600 933 815 450 1601 935 817 449 1602 934 816 450 1603 935 817 451 1604 936 818 451 1605 936 818 450 1606 935 817 452 1607 937 819 451 1608 941 818 452 1609 940 819 453 1610 938 820 453 1611 938 820 452 1612 940 819 454 1613 939 821 453 1614 938 820 454 1615 939 821 455 1616 942 822 455 1617 942 822 454 1618 939 821 456 1619 943 823 458 1620 945 825 457 1621 944 824 456 1622 943 823 457 1623 944 824 455 1624 942 822 456 1625 943 823 460 1626 947 827 459 1627 946 826 458 1628 945 825 459 1629 946 826 457 1630 944 824 458 1631 945 825 462 1632 949 829 461 1633 948 828 460 1634 947 827 461 1635 948 828 459 1636 946 826 460 1637 947 827 463 1638 950 830 461 1639 948 828 464 1640 951 831 464 1641 951 831 461 1642 948 828 462 1643 949 829 465 1644 952 832 463 1645 950 830 466 1646 953 833 466 1647 953 833 463 1648 950 830 464 1649 951 831 466 1650 953 833 468 1651 955 835 465 1652 952 832 468 1653 955 835 467 1654 954 834 465 1655 952 832 468 1656 955 835 435 1657 920 802 467 1658 954 834 435 1659 920 802 436 1660 921 803 467 1661 954 834 469 1662 956 836 472 1663 959 839 470 1664 957 837 471 1665 958 838 470 1666 957 837 472 1667 959 839 476 1668 963 843 474 1669 961 841 473 1670 960 840 474 1671 961 841 476 1672 963 843 475 1673 962 842 477 1674 964 844 469 1675 956 836 478 1676 965 845 470 1677 957 837 478 1678 965 845 469 1679 956 836 480 1680 967 847 475 1681 962 842 476 1682 963 843 475 1683 962 842 480 1684 967 847 479 1685 966 846 478 1686 965 845 482 1687 969 849 477 1688 964 844 477 1689 964 844 482 1690 969 849 481 1691 968 848 480 1692 967 847 484 1693 971 851 479 1694 966 846 479 1695 966 846 484 1696 971 851 483 1697 970 850 482 1698 969 849 486 1699 973 853 481 1700 968 848 481 1701 968 848 486 1702 973 853 485 1703 972 852 484 1704 971 851 488 1705 975 855 483 1706 970 850 483 1707 970 850 488 1708 975 855 487 1709 974 854 486 1710 973 853 490 1711 977 857 485 1712 972 852 485 1713 972 852 490 1714 977 857 489 1715 976 856 488 1716 975 855 492 1717 979 859 487 1718 974 854 487 1719 974 854 492 1720 979 859 491 1721 978 858 490 1722 977 857 494 1723 981 861 489 1724 976 856 489 1725 976 856 494 1726 981 861 493 1727 980 860 492 1728 979 859 496 1729 983 863 491 1730 978 858 491 1731 978 858 496 1732 983 863 495 1733 982 862 494 1734 981 861 498 1735 985 865 493 1736 980 860 493 1737 980 860 498 1738 985 865 497 1739 984 864 496 1740 983 863 500 1741 987 867 495 1742 982 862 495 1743 982 862 500 1744 987 867 499 1745 986 866 497 1746 984 864 502 1747 989 869 501 1748 988 868 502 1749 989 869 497 1750 984 864 498 1751 985 865 500 1752 987 867 504 1753 991 871 499 1754 986 866 503 1755 990 870 499 1756 986 866 504 1757 991 871 501 1758 988 868 506 1759 993 873 505 1760 992 872 506 1761 993 873 501 1762 988 868 502 1763 989 869 504 1764 991 871 508 1765 995 875 503 1766 990 870 507 1767 994 874 503 1768 990 870 508 1769 995 875 505 1770 999 872 510 1771 997 877 509 1772 996 876 510 1773 997 877 505 1774 999 872 506 1775 998 873 508 1776 1000 875 512 1777 1003 879 507 1778 1001 874 511 1779 1002 878 507 1780 1001 874 512 1781 1003 879 509 1782 996 876 514 1783 1005 881 513 1784 1004 880 514 1785 1005 881 509 1786 996 876 510 1787 997 877 512 1788 1003 879 516 1789 1007 883 511 1790 1002 878 515 1791 1006 882 511 1792 1002 878 516 1793 1007 883 517 1794 1008 884 513 1795 1004 880 518 1796 1009 885 518 1797 1009 885 513 1798 1004 880 514 1799 1005 881 516 1800 1007 883 520 1801 1011 887 519 1802 1010 886 519 1803 1010 886 515 1804 1006 882 516 1805 1007 883 521 1806 1012 888 517 1807 1008 884 522 1808 1013 889 522 1809 1013 889 517 1810 1008 884 518 1811 1009 885 523 1812 1014 890 519 1813 1010 886 524 1814 1015 891 524 1815 1015 891 519 1816 1010 886 520 1817 1011 887 525 1818 1016 892 521 1819 1012 888 526 1820 1017 893 526 1821 1017 893 521 1822 1012 888 522 1823 1013 889 527 1824 1018 894 523 1825 1014 890 528 1826 1019 895 528 1827 1019 895 523 1828 1014 890 524 1829 1015 891 529 1830 1020 896 525 1831 1016 892 530 1832 1021 897 530 1833 1021 897 525 1834 1016 892 526 1835 1017 893 531 1836 1022 898 527 1837 1018 894 532 1838 1023 899 532 1839 1023 899 527 1840 1018 894 528 1841 1019 895 533 1842 1024 900 529 1843 1020 896 534 1844 1025 901 534 1845 1025 901 529 1846 1020 896 530 1847 1021 897 535 1848 1026 902 531 1849 1022 898 536 1850 1027 903 536 1851 1027 903 531 1852 1022 898 532 1853 1023 899 537 1854 1028 904 533 1855 1024 900 538 1856 1029 905 534 1857 1025 901 538 1858 1029 905 533 1859 1024 900 536 1860 1027 903 540 1861 1031 907 539 1862 1030 906 536 1863 1027 903 539 1864 1030 906 535 1865 1026 902 472 1866 959 839 537 1867 1028 904 471 1868 958 838 538 1869 1029 905 471 1870 958 838 537 1871 1028 904 540 1872 1031 907 473 1873 960 840 474 1874 961 841 540 1875 1031 907 474 1876 961 841 539 1877 1030 906 469 1878 956 836 435 1879 920 802 472 1880 959 839 435 1881 920 802 469 1882 956 836 434 1883 919 801 537 1884 1028 904 472 1885 959 839 435 1886 920 802 537 1887 1028 904 435 1888 920 802 468 1889 955 835 468 1890 955 835 466 1891 953 833 533 1892 1024 900 533 1893 1024 900 537 1894 1028 904 468 1895 955 835 466 1896 953 833 464 1897 951 831 529 1898 1020 896 529 1899 1020 896 533 1900 1024 900 466 1901 953 833 464 1902 951 831 462 1903 949 829 525 1904 1016 892 464 1905 951 831 525 1906 1016 892 529 1907 1020 896 462 1908 949 829 521 1909 1012 888 525 1910 1016 892 521 1911 1012 888 462 1912 949 829 460 1913 947 827 521 1914 1012 888 458 1915 945 825 517 1916 1008 884 458 1917 945 825 521 1918 1012 888 460 1919 947 827 517 1920 1008 884 456 1921 943 823 513 1922 1004 880 456 1923 943 823 517 1924 1008 884 458 1925 945 825 509 1926 996 876 513 1927 1004 880 454 1928 939 821 454 1929 939 821 513 1930 1004 880 456 1931 943 823 509 1932 996 876 452 1933 940 819 505 1934 999 872 452 1935 940 819 509 1936 996 876 454 1937 939 821 452 1938 937 819 450 1939 935 817 501 1940 988 868 452 1941 937 819 501 1942 988 868 505 1943 992 872 497 1944 984 864 501 1945 988 868 450 1946 935 817 450 1947 935 817 448 1948 933 815 497 1949 984 864 493 1950 980 860 497 1951 984 864 448 1952 933 815 493 1953 980 860 448 1954 933 815 446 1955 931 813 489 1956 976 856 493 1957 980 860 446 1958 931 813 489 1959 976 856 446 1960 931 813 444 1961 929 811 485 1962 972 852 489 1963 976 856 442 1964 927 809 442 1965 927 809 489 1966 976 856 444 1967 929 811 485 1968 972 852 440 1969 925 807 481 1970 968 848 440 1971 925 807 485 1972 972 852 442 1973 927 809 477 1974 964 844 481 1975 968 848 438 1976 923 805 440 1977 925 807 438 1978 923 805 481 1979 968 848 438 1980 923 805 434 1981 919 801 477 1982 964 844 477 1983 964 844 434 1984 919 801 469 1985 956 836 476 1986 963 843 473 1987 960 840 436 1988 921 803 476 1989 963 843 436 1990 921 803 433 1991 918 800 433 1992 918 800 437 1993 922 804 480 1994 967 847 480 1995 967 847 476 1996 963 843 433 1997 918 800 437 1998 922 804 439 1999 924 806 484 2000 971 851 484 2001 971 851 480 2002 967 847 437 2003 922 804 439 2004 924 806 441 2005 926 808 488 2006 975 855 439 2007 924 806 488 2008 975 855 484 2009 971 851 441 2010 926 808 492 2011 979 859 488 2012 975 855 492 2013 979 859 441 2014 926 808 443 2015 928 810 492 2016 979 859 445 2017 930 812 496 2018 983 863 445 2019 930 812 492 2020 979 859 443 2021 928 810 496 2022 983 863 447 2023 932 814 500 2024 987 867 447 2025 932 814 496 2026 983 863 445 2027 930 812 504 2028 991 871 500 2029 987 867 449 2030 934 816 449 2031 934 816 500 2032 987 867 447 2033 932 814 504 2034 991 871 451 2035 936 818 508 2036 995 875 451 2037 936 818 504 2038 991 871 449 2039 934 816 451 2040 941 818 453 2041 938 820 512 2042 1003 879 451 2043 941 818 512 2044 1003 879 508 2045 1000 875 516 2046 1007 883 512 2047 1003 879 453 2048 938 820 453 2049 938 820 455 2050 942 822 516 2051 1007 883 520 2052 1011 887 516 2053 1007 883 455 2054 942 822 520 2055 1011 887 455 2056 942 822 457 2057 944 824 524 2058 1015 891 520 2059 1011 887 457 2060 944 824 524 2061 1015 891 457 2062 944 824 459 2063 946 826 528 2064 1019 895 524 2065 1015 891 461 2066 948 828 461 2067 948 828 524 2068 1015 891 459 2069 946 826 528 2070 1019 895 463 2071 950 830 532 2072 1023 899 463 2073 950 830 528 2074 1019 895 461 2075 948 828 536 2076 1027 903 532 2077 1023 899 465 2078 952 832 463 2079 950 830 465 2080 952 832 532 2081 1023 899 465 2082 952 832 467 2083 954 834 536 2084 1027 903 536 2085 1027 903 467 2086 954 834 540 2087 1031 907 540 2088 1031 907 436 2089 921 803 473 2090 960 840 436 2091 921 803 540 2092 1031 907 467 2093 954 834 534 2094 1032 901 471 2095 1034 838 538 2096 1033 905 471 2097 1034 838 534 2098 1032 901 470 2099 1035 837 530 2100 1036 897 470 2101 1035 837 534 2102 1032 901 470 2103 1035 837 530 2104 1036 897 478 2105 1037 845 482 2106 1039 849 530 2107 1036 897 526 2108 1038 893 530 2109 1036 897 482 2110 1039 849 478 2111 1037 845 522 2112 1040 889 482 2113 1039 849 526 2114 1038 893 482 2115 1039 849 522 2116 1040 889 486 2117 1041 853 518 2118 1042 885 486 2119 1041 853 522 2120 1040 889 486 2121 1041 853 518 2122 1042 885 490 2123 1043 857 514 2124 1044 881 490 2125 1043 857 518 2126 1042 885 490 2127 1043 857 514 2128 1044 881 494 2129 1045 861 498 2130 1047 865 514 2131 1044 881 510 2132 1046 877 494 2133 1045 861 514 2134 1044 881 498 2135 1047 865 510 2136 1046 877 502 2137 1049 869 498 2138 1047 865 502 2139 1049 869 510 2140 1046 877 506 2141 1048 873 511 2142 1050 878 503 2143 1052 870 507 2144 1051 874 503 2145 1052 870 511 2146 1050 878 499 2147 1053 866 495 2148 1055 862 511 2149 1050 878 515 2150 1054 882 511 2151 1050 878 495 2152 1055 862 499 2153 1053 866 495 2154 1055 862 515 2155 1054 882 491 2156 1057 858 491 2157 1057 858 515 2158 1054 882 519 2159 1056 886 519 2160 1056 886 487 2161 1059 854 491 2162 1057 858 519 2163 1056 886 483 2164 1061 850 487 2165 1059 854 483 2166 1061 850 519 2167 1056 886 523 2168 1058 890 483 2169 1061 850 523 2170 1058 890 527 2171 1060 894 527 2172 1060 894 479 2173 1063 846 483 2174 1061 850 479 2175 1063 846 527 2176 1060 894 531 2177 1062 898 531 2178 1062 898 475 2179 1065 842 479 2180 1063 846 475 2181 1065 842 531 2182 1062 898 535 2183 1064 902 539 2184 1066 906 475 2185 1065 842 535 2186 1064 902 475 2187 1065 842 539 2188 1066 906 474 2189 1067 841 541 2190 1068 908 544 2191 1071 911 543 2192 1070 910 541 2193 1068 908 543 2194 1070 910 542 2195 1069 909 544 2196 1071 911 546 2197 1073 913 545 2198 1072 912 544 2199 1071 911 545 2200 1072 912 543 2201 1070 910 548 2202 1075 915 545 2203 1072 912 546 2204 1073 913 545 2205 1072 912 548 2206 1075 915 547 2207 1074 914 550 2208 1077 917 547 2209 1074 914 548 2210 1075 915 547 2211 1074 914 550 2212 1077 917 549 2213 1076 916 552 2214 1079 919 549 2215 1076 916 550 2216 1077 917 549 2217 1076 916 552 2218 1079 919 551 2219 1078 918 552 2220 1079 919 554 2221 1081 921 551 2222 1078 918 551 2223 1078 918 554 2224 1081 921 553 2225 1080 920 556 2226 1083 923 553 2227 1080 920 554 2228 1081 921 553 2229 1080 920 556 2230 1083 923 555 2231 1082 922 557 2232 1084 924 555 2233 1082 922 558 2234 1085 925 555 2235 1082 922 556 2236 1083 923 558 2237 1085 925 559 2238 1086 926 557 2239 1084 924 560 2240 1087 927 557 2241 1084 924 558 2242 1085 925 560 2243 1087 927 561 2244 1090 928 559 2245 1089 926 562 2246 1091 929 559 2247 1089 926 560 2248 1088 927 562 2249 1091 929 563 2250 1092 930 561 2251 1090 928 564 2252 1093 931 561 2253 1090 928 562 2254 1091 929 564 2255 1093 931 565 2256 1094 932 563 2257 1092 930 566 2258 1095 933 566 2259 1095 933 563 2260 1092 930 564 2261 1093 931 567 2262 1096 934 565 2263 1094 932 568 2264 1097 935 568 2265 1097 935 565 2266 1094 932 566 2267 1095 933 567 2268 1096 934 570 2269 1099 937 569 2270 1098 936 570 2271 1099 937 567 2272 1096 934 568 2273 1097 935 572 2274 1101 939 571 2275 1100 938 570 2276 1099 937 571 2277 1100 938 569 2278 1098 936 570 2279 1099 937 574 2280 1103 941 573 2281 1102 940 572 2282 1101 939 573 2283 1102 940 571 2284 1100 938 572 2285 1101 939 574 2286 1103 941 576 2287 1105 943 575 2288 1104 942 574 2289 1103 941 575 2290 1104 942 573 2291 1102 940 576 2292 1105 943 541 2293 1068 908 542 2294 1069 909 576 2295 1105 943 542 2296 1069 909 575 2297 1104 942 577 2298 1106 944 580 2299 1109 947 579 2300 1108 946 577 2301 1106 944 579 2302 1108 946 578 2303 1107 945 581 2304 1110 948 583 2305 1112 950 582 2306 1111 949 583 2307 1112 950 581 2308 1110 948 584 2309 1113 951 580 2310 1109 947 586 2311 1115 953 585 2312 1114 952 580 2313 1109 947 585 2314 1114 952 579 2315 1108 946 582 2316 1111 949 588 2317 1117 955 587 2318 1116 954 582 2319 1111 949 587 2320 1116 954 581 2321 1110 948 586 2322 1115 953 589 2323 1118 956 585 2324 1114 952 589 2325 1118 956 586 2326 1115 953 590 2327 1119 957 591 2328 1120 958 587 2329 1116 954 588 2330 1117 955 588 2331 1117 955 592 2332 1121 959 591 2333 1120 958 590 2334 1119 957 593 2335 1122 960 589 2336 1118 956 593 2337 1122 960 590 2338 1119 957 594 2339 1123 961 595 2340 1124 962 591 2341 1120 958 592 2342 1121 959 592 2343 1121 959 596 2344 1125 963 595 2345 1124 962 594 2346 1123 961 597 2347 1126 964 593 2348 1122 960 597 2349 1126 964 594 2350 1123 961 598 2351 1127 965 599 2352 1128 966 595 2353 1124 962 596 2354 1125 963 596 2355 1125 963 600 2356 1129 967 599 2357 1128 966 598 2358 1127 965 601 2359 1130 968 597 2360 1126 964 601 2361 1130 968 598 2362 1127 965 602 2363 1131 969 603 2364 1132 970 599 2365 1128 966 600 2366 1129 967 600 2367 1129 967 604 2368 1133 971 603 2369 1132 970 602 2370 1131 969 605 2371 1134 972 601 2372 1130 968 605 2373 1134 972 602 2374 1131 969 606 2375 1135 973 607 2376 1136 974 603 2377 1132 970 604 2378 1133 971 604 2379 1133 971 608 2380 1137 975 607 2381 1136 974 609 2382 1138 976 605 2383 1134 972 606 2384 1135 973 609 2385 1138 976 606 2386 1135 973 610 2387 1139 977 611 2388 1140 978 607 2389 1136 974 608 2390 1137 975 611 2391 1140 978 608 2392 1137 975 612 2393 1141 979 613 2394 1142 980 609 2395 1138 976 610 2396 1139 977 613 2397 1142 980 610 2398 1139 977 614 2399 1143 981 612 2400 1141 979 615 2401 1144 982 611 2402 1140 978 615 2403 1144 982 612 2404 1141 979 616 2405 1145 983 614 2406 1146 981 617 2407 1148 984 613 2408 1147 980 617 2409 1148 984 614 2410 1146 981 618 2411 1149 985 619 2412 1150 986 615 2413 1153 982 616 2414 1152 983 619 2415 1150 986 616 2416 1152 983 620 2417 1151 987 621 2418 1154 988 617 2419 1148 984 618 2420 1149 985 621 2421 1154 988 618 2422 1149 985 622 2423 1155 989 623 2424 1156 990 619 2425 1150 986 620 2426 1151 987 623 2427 1156 990 620 2428 1151 987 624 2429 1157 991 622 2430 1155 989 626 2431 1159 993 625 2432 1158 992 625 2433 1158 992 621 2434 1154 988 622 2435 1155 989 627 2436 1160 994 623 2437 1156 990 628 2438 1161 995 628 2439 1161 995 623 2440 1156 990 624 2441 1157 991 626 2442 1159 993 630 2443 1163 997 629 2444 1162 996 629 2445 1162 996 625 2446 1158 992 626 2447 1159 993 631 2448 1164 998 628 2449 1161 995 632 2450 1165 999 628 2451 1161 995 631 2452 1164 998 627 2453 1160 994 630 2454 1163 997 634 2455 1167 1001 633 2456 1166 1000 633 2457 1166 1000 629 2458 1162 996 630 2459 1163 997 635 2460 1168 1002 632 2461 1165 999 636 2462 1169 1003 632 2463 1165 999 635 2464 1168 1002 631 2465 1164 998 634 2466 1167 1001 638 2467 1171 1005 637 2468 1170 1004 637 2469 1170 1004 633 2470 1166 1000 634 2471 1167 1001 639 2472 1172 1006 636 2473 1169 1003 640 2474 1173 1007 636 2475 1169 1003 639 2476 1172 1006 635 2477 1168 1002 638 2478 1171 1005 642 2479 1175 1009 641 2480 1174 1008 641 2481 1174 1008 637 2482 1170 1004 638 2483 1171 1005 643 2484 1176 1010 640 2485 1173 1007 644 2486 1177 1011 640 2487 1173 1007 643 2488 1176 1010 639 2489 1172 1006 642 2490 1175 1009 646 2491 1179 1013 645 2492 1178 1012 642 2493 1175 1009 645 2494 1178 1012 641 2495 1174 1008 647 2496 1180 1014 643 2497 1176 1010 648 2498 1181 1015 644 2499 1177 1011 648 2500 1181 1015 643 2501 1176 1010 578 2502 1107 945 646 2503 1179 1013 577 2504 1106 944 646 2505 1179 1013 578 2506 1107 945 645 2507 1178 1012 584 2508 1113 951 647 2509 1180 1014 583 2510 1112 950 648 2511 1181 1015 583 2512 1112 950 647 2513 1180 1014 580 2514 1109 947 577 2515 1106 944 542 2516 1069 909 580 2517 1109 947 542 2518 1069 909 543 2519 1070 910 575 2520 1104 942 542 2521 1069 909 646 2522 1179 1013 577 2523 1106 944 646 2524 1179 1013 542 2525 1069 909 575 2526 1104 942 642 2527 1175 1009 573 2528 1102 940 642 2529 1175 1009 575 2530 1104 942 646 2531 1179 1013 642 2532 1175 1009 638 2533 1171 1005 573 2534 1102 940 571 2535 1100 938 573 2536 1102 940 638 2537 1171 1005 638 2538 1171 1005 634 2539 1167 1001 571 2540 1100 938 571 2541 1100 938 634 2542 1167 1001 569 2543 1098 936 569 2544 1098 936 630 2545 1163 997 567 2546 1096 934 630 2547 1163 997 569 2548 1098 936 634 2549 1167 1001 630 2550 1163 997 626 2551 1159 993 565 2552 1094 932 630 2553 1163 997 565 2554 1094 932 567 2555 1096 934 626 2556 1159 993 622 2557 1155 989 563 2558 1092 930 626 2559 1159 993 563 2560 1092 930 565 2561 1094 932 622 2562 1155 989 618 2563 1149 985 561 2564 1090 928 561 2565 1090 928 563 2566 1092 930 622 2567 1155 989 618 2568 1149 985 559 2569 1089 926 561 2570 1090 928 559 2571 1089 926 618 2572 1149 985 614 2573 1146 981 614 2574 1143 981 610 2575 1139 977 559 2576 1086 926 559 2577 1086 926 610 2578 1139 977 557 2579 1084 924 610 2580 1139 977 606 2581 1135 973 557 2582 1084 924 557 2583 1084 924 606 2584 1135 973 555 2585 1082 922 553 2586 1080 920 555 2587 1082 922 602 2588 1131 969 606 2589 1135 973 602 2590 1131 969 555 2591 1082 922 551 2592 1078 918 553 2593 1080 920 598 2594 1127 965 602 2595 1131 969 598 2596 1127 965 553 2597 1080 920 598 2598 1127 965 594 2599 1123 961 549 2600 1076 916 549 2601 1076 916 551 2602 1078 918 598 2603 1127 965 594 2604 1123 961 547 2605 1074 914 549 2606 1076 916 547 2607 1074 914 594 2608 1123 961 590 2609 1119 957 590 2610 1119 957 545 2611 1072 912 547 2612 1074 914 545 2613 1072 912 590 2614 1119 957 586 2615 1115 953 586 2616 1115 953 543 2617 1070 910 545 2618 1072 912 543 2619 1070 910 586 2620 1115 953 580 2621 1109 947 544 2622 1071 911 541 2623 1068 908 581 2624 1110 948 584 2625 1113 951 581 2626 1110 948 541 2627 1068 908 544 2628 1071 911 587 2629 1116 954 546 2630 1073 913 587 2631 1116 954 544 2632 1071 911 581 2633 1110 948 587 2634 1116 954 591 2635 1120 958 546 2636 1073 913 548 2637 1075 915 546 2638 1073 913 591 2639 1120 958 591 2640 1120 958 595 2641 1124 962 548 2642 1075 915 548 2643 1075 915 595 2644 1124 962 550 2645 1077 917 550 2646 1077 917 599 2647 1128 966 552 2648 1079 919 599 2649 1128 966 550 2650 1077 917 595 2651 1124 962 599 2652 1128 966 603 2653 1132 970 554 2654 1081 921 599 2655 1128 966 554 2656 1081 921 552 2657 1079 919 603 2658 1132 970 607 2659 1136 974 556 2660 1083 923 603 2661 1132 970 556 2662 1083 923 554 2663 1081 921 607 2664 1136 974 611 2665 1140 978 558 2666 1085 925 558 2667 1085 925 556 2668 1083 923 607 2669 1136 974 611 2670 1140 978 560 2671 1087 927 558 2672 1085 925 560 2673 1087 927 611 2674 1140 978 615 2675 1144 982 615 2676 1153 982 619 2677 1150 986 560 2678 1088 927 560 2679 1088 927 619 2680 1150 986 562 2681 1091 929 619 2682 1150 986 623 2683 1156 990 562 2684 1091 929 562 2685 1091 929 623 2686 1156 990 564 2687 1093 931 566 2688 1095 933 564 2689 1093 931 627 2690 1160 994 623 2691 1156 990 627 2692 1160 994 564 2693 1093 931 568 2694 1097 935 566 2695 1095 933 631 2696 1164 998 627 2697 1160 994 631 2698 1164 998 566 2699 1095 933 631 2700 1164 998 635 2701 1168 1002 570 2702 1099 937 570 2703 1099 937 568 2704 1097 935 631 2705 1164 998 635 2706 1168 1002 572 2707 1101 939 570 2708 1099 937 572 2709 1101 939 635 2710 1168 1002 639 2711 1172 1006 639 2712 1172 1006 574 2713 1103 941 572 2714 1101 939 574 2715 1103 941 639 2716 1172 1006 643 2717 1176 1010 643 2718 1176 1010 576 2719 1105 943 574 2720 1103 941 576 2721 1105 943 643 2722 1176 1010 647 2723 1180 1014 647 2724 1180 1014 584 2725 1113 951 541 2726 1068 908 647 2727 1180 1014 541 2728 1068 908 576 2729 1105 943 641 2730 1185 1008 578 2731 1183 945 579 2732 1182 946 578 2733 1183 945 641 2734 1185 1008 645 2735 1184 1012 637 2736 1187 1004 579 2737 1182 946 585 2738 1186 952 579 2739 1182 946 637 2740 1187 1004 641 2741 1185 1008 589 2742 1188 956 637 2743 1187 1004 585 2744 1186 952 637 2745 1187 1004 589 2746 1188 956 633 2747 1189 1000 589 2748 1188 956 629 2749 1191 996 633 2750 1189 1000 629 2751 1191 996 589 2752 1188 956 593 2753 1190 960 597 2754 1192 964 625 2755 1193 992 593 2756 1190 960 629 2757 1191 996 593 2758 1190 960 625 2759 1193 992 597 2760 1192 964 621 2761 1195 988 625 2762 1193 992 621 2763 1195 988 597 2764 1192 964 601 2765 1194 968 621 2766 1195 988 601 2767 1194 968 605 2768 1196 972 621 2769 1195 988 605 2770 1196 972 617 2771 1197 984 609 2772 1198 976 617 2773 1197 984 605 2774 1196 972 617 2775 1197 984 609 2776 1198 976 613 2777 1199 980 620 2778 1203 987 612 2779 1201 979 608 2780 1200 975 612 2781 1201 979 620 2782 1203 987 616 2783 1202 983 620 2784 1203 987 604 2785 1204 971 624 2786 1205 991 604 2787 1204 971 620 2788 1203 987 608 2789 1200 975 628 2790 1207 995 600 2791 1206 967 596 2792 1208 963 624 2793 1205 991 600 2794 1206 967 628 2795 1207 995 600 2796 1206 967 624 2797 1205 991 604 2798 1204 971 628 2799 1207 995 592 2800 1210 959 632 2801 1209 999 592 2802 1210 959 628 2803 1207 995 596 2804 1208 963 632 2805 1209 999 592 2806 1210 959 636 2807 1211 1003 636 2808 1211 1003 592 2809 1210 959 588 2810 1212 955 636 2811 1211 1003 588 2812 1212 955 640 2813 1213 1007 640 2814 1213 1007 582 2815 1214 949 644 2816 1215 1011 582 2817 1214 949 640 2818 1213 1007 588 2819 1212 955 582 2820 1214 949 648 2821 1217 1015 644 2822 1215 1011 648 2823 1217 1015 582 2824 1214 949 583 2825 1216 950 142 2826 688 654 221 2827 691 565 288 2828 690 317 209 2829 502 311 72 2830 1868 225 139 2831 501 310 142 2832 1872 318 288 2833 690 317 74 2834 1871 228 142 2835 688 654 222 2836 692 566 221 2837 691 565 215 2838 674 554 210 2839 673 547 286 2840 672 648 286 2841 323 308 63 2842 161 213 67 2843 162 217 219 2844 683 558 215 2845 674 554 286 2846 672 648 287 2847 682 316 68 2848 1870 218 141 2849 685 313 62 2850 190 210 69 2851 187 219 224 2852 343 324 64 2853 192 214 62 2854 190 210 224 2855 343 324 216 2856 540 555 143 2857 537 570 224 2858 533 568 65 2859 180 215 64 2860 192 214 143 2861 345 326 225 2862 541 314 65 2863 1869 215 143 2864 537 570 143 2865 537 570 217 2866 542 556 225 2867 541 314 223 2868 342 323 75 2869 189 229 70 2870 158 221 223 2871 532 567 140 2872 504 546 207 2873 499 541 50 2874 137 143 19 2875 60 99 15 2876 52 102 50 2877 137 143 15 2878 52 102 14 2879 53 101 158 2880 400 429 159 2881 399 428 194 2882 484 471 159 2883 399 428 163 2884 407 427 194 2885 484 471 167 2886 453 507 181 2887 476 453 174 2888 473 443 182 2889 477 456 198 2890 486 376 169 2891 456 511 189 2892 481 466 184 2893 479 459 162 2894 408 514 163 2895 407 515 190 2896 483 467 191 2897 482 468 45 2898 133 137 50 2899 137 143 18 2900 61 186 19 2901 60 187 49 2902 136 142 46 2903 135 139 22 2904 109 180 33 2905 127 118 30 2906 126 115 26 2907 106 183 55 2908 138 48 39 2909 130 130 23 2910 100 151 37 2911 117 173 31 2912 116 172 27 2913 103 154 34 2914 121 177 38 2915 120 176 13 2916 43 82 12 2917 42 81 51 2918 112 165 12 2919 42 81 16 2920 50 80 51 2921 112 165 195 2922 459 494 160 2923 397 408 156 2924 389 411 195 2925 459 494 156 2926 389 411 157 2927 390 410 177 2928 462 499 180 2929 464 501 166 2930 450 482 168 2931 447 479 196 2932 465 502 183 2933 468 505

+

308 2934 694 675 290 2935 695 657 307 2936 697 674 307 2937 697 674 290 2938 695 657 289 2939 696 656 309 2940 698 676 291 2941 699 658 308 2942 694 675 308 2943 694 675 291 2944 699 658 290 2945 695 657 291 2946 699 658 309 2947 698 676 292 2948 701 659 309 2949 698 676 310 2950 700 677 292 2951 701 659 292 2952 701 659 310 2953 700 677 293 2954 703 660 310 2955 700 677 311 2956 702 678 293 2957 703 660 293 2958 703 660 311 2959 702 678 294 2960 705 661 311 2961 702 678 312 2962 704 679 294 2963 705 661 294 2964 705 661 312 2965 704 679 295 2966 707 662 312 2967 704 679 313 2968 706 680 295 2969 707 662 295 2970 707 662 313 2971 706 680 296 2972 709 663 313 2973 706 680 314 2974 708 681 296 2975 709 663 297 2976 711 664 296 2977 709 663 314 2978 708 681 297 2979 711 664 314 2980 708 681 315 2981 710 682 298 2982 713 665 297 2983 711 664 315 2984 710 682 298 2985 713 665 315 2986 710 682 316 2987 712 683 299 2988 715 666 298 2989 776 665 316 2990 775 683 299 2991 715 666 316 2992 775 683 317 2993 714 684 300 2994 717 667 299 2995 715 666 317 2996 714 684 300 2997 717 667 317 2998 714 684 318 2999 716 685 300 3000 717 667 319 3001 718 686 301 3002 719 668 319 3003 718 686 300 3004 717 667 318 3005 716 685 320 3006 720 687 302 3007 721 669 319 3008 718 686 302 3009 721 669 301 3010 719 668 319 3011 718 686 321 3012 722 688 303 3013 723 670 320 3014 720 687 303 3015 723 670 302 3016 721 669 320 3017 720 687 322 3018 724 689 304 3019 725 671 321 3020 722 688 304 3021 725 671 303 3022 723 670 321 3023 722 688 304 3024 725 671 323 3025 726 690 305 3026 727 672 323 3027 726 690 304 3028 725 671 322 3029 724 689 323 3030 726 690 324 3031 728 691 305 3032 727 672 324 3033 728 691 306 3034 729 673 305 3035 727 672 324 3036 728 691 307 3037 697 674 306 3038 729 673 307 3039 697 674 289 3040 696 656 306 3041 729 673 308 3042 694 675 307 3043 697 674 326 3044 730 693 308 3045 694 675 326 3046 730 693 325 3047 731 692 327 3048 732 694 326 3049 730 693 324 3050 728 691 307 3051 697 674 324 3052 728 691 326 3053 730 693 327 3054 732 694 323 3055 726 690 328 3056 733 695 323 3057 726 690 327 3058 732 694 324 3059 728 691 323 3060 726 690 322 3061 724 689 328 3062 733 695 329 3063 734 696 328 3064 733 695 322 3065 724 689 322 3066 724 689 321 3067 722 688 329 3068 734 696 329 3069 734 696 321 3070 722 688 330 3071 735 697 321 3072 722 688 320 3073 720 687 330 3074 735 697 330 3075 735 697 320 3076 720 687 331 3077 736 698 320 3078 720 687 319 3079 718 686 332 3080 737 699 320 3081 720 687 332 3082 737 699 331 3083 736 698 319 3084 718 686 318 3085 716 685 333 3086 738 700 319 3087 718 686 333 3088 738 700 332 3089 737 699 318 3090 716 685 317 3091 714 684 334 3092 739 701 334 3093 739 701 333 3094 738 700 318 3095 716 685 317 3096 714 684 335 3097 740 702 334 3098 739 701 335 3099 740 702 317 3100 714 684 316 3101 775 683 316 3102 712 683 315 3103 710 682 335 3104 786 702 335 3105 786 702 315 3106 710 682 336 3107 741 703 315 3108 710 682 314 3109 708 681 336 3110 741 703 336 3111 741 703 314 3112 708 681 337 3113 742 704 338 3114 743 705 337 3115 742 704 313 3116 706 680 314 3117 708 681 313 3118 706 680 337 3119 742 704 339 3120 744 706 338 3121 743 705 312 3122 704 679 313 3123 706 680 312 3124 704 679 338 3125 743 705 312 3126 704 679 311 3127 702 678 340 3128 745 707 340 3129 745 707 339 3130 744 706 312 3131 704 679 311 3132 702 678 341 3133 746 708 340 3134 745 707 341 3135 746 708 311 3136 702 678 310 3137 700 677 310 3138 700 677 342 3139 747 709 341 3140 746 708 342 3141 747 709 310 3142 700 677 309 3143 698 676 309 3144 698 676 325 3145 731 692 342 3146 747 709 325 3147 731 692 309 3148 698 676 308 3149 694 675 325 3150 731 692 343 3151 749 710 344 3152 748 711 343 3153 749 710 325 3154 731 692 326 3155 730 693 345 3156 750 712 325 3157 731 692 344 3158 748 711 325 3159 731 692 345 3160 750 712 342 3161 747 709 345 3162 750 712 346 3163 751 713 342 3164 747 709 342 3165 747 709 346 3166 751 713 341 3167 746 708 347 3168 752 714 341 3169 746 708 346 3170 751 713 341 3171 746 708 347 3172 752 714 340 3173 745 707 347 3174 752 714 348 3175 753 715 340 3176 745 707 340 3177 745 707 348 3178 753 715 339 3179 744 706 348 3180 753 715 349 3181 754 716 339 3182 744 706 339 3183 744 706 349 3184 754 716 338 3185 743 705 350 3186 755 717 338 3187 743 705 349 3188 754 716 338 3189 743 705 350 3190 755 717 337 3191 742 704 336 3192 741 703 337 3193 742 704 351 3194 756 718 337 3195 742 704 350 3196 755 717 351 3197 756 718 335 3198 786 702 336 3199 741 703 352 3200 757 719 336 3201 741 703 351 3202 756 718 352 3203 757 719 334 3204 739 701 335 3205 740 702 353 3206 758 720 335 3207 740 702 352 3208 796 719 353 3209 758 720 333 3210 738 700 334 3211 739 701 354 3212 759 721 334 3213 739 701 353 3214 758 720 354 3215 759 721 332 3216 737 699 333 3217 738 700 355 3218 760 722 355 3219 760 722 333 3220 738 700 354 3221 759 721 332 3222 737 699 356 3223 761 723 331 3224 736 698 356 3225 761 723 332 3226 737 699 355 3227 760 722 331 3228 736 698 357 3229 762 724 330 3230 735 697 357 3231 762 724 331 3232 736 698 356 3233 761 723 358 3234 763 725 329 3235 734 696 357 3236 762 724 329 3237 734 696 330 3238 735 697 357 3239 762 724 359 3240 764 726 328 3241 733 695 358 3242 763 725 328 3243 733 695 329 3244 734 696 358 3245 763 725 327 3246 732 694 359 3247 764 726 360 3248 765 727 359 3249 764 726 327 3250 732 694 328 3251 733 695 326 3252 730 693 360 3253 765 727 343 3254 749 710 360 3255 765 727 326 3256 730 693 327 3257 732 694 355 3258 800 722 352 3259 797 719 351 3260 795 718 352 3261 797 719 355 3262 800 722 354 3263 799 721 352 3264 797 719 354 3265 799 721 353 3266 798 720 356 3267 801 723 351 3268 795 718 350 3269 794 717 351 3270 795 718 356 3271 801 723 355 3272 800 722 357 3273 802 724 350 3274 794 717 349 3275 793 716 350 3276 794 717 357 3277 802 724 356 3278 801 723 358 3279 803 725 349 3280 793 716 348 3281 792 715 349 3282 793 716 358 3283 803 725 357 3284 802 724 359 3285 804 726 348 3286 792 715 347 3287 791 714 348 3288 792 715 359 3289 804 726 358 3290 803 725 347 3291 791 714 360 3292 805 727 359 3293 804 726 360 3294 805 727 347 3295 791 714 346 3296 790 713 346 3297 790 713 343 3298 788 710 360 3299 805 727 343 3300 788 710 346 3301 790 713 345 3302 789 712 343 3303 788 710 345 3304 789 712 344 3305 787 711 290 3306 766 657 306 3307 785 673 289 3308 767 656 291 3309 768 658 306 3310 785 673 290 3311 766 657 292 3312 769 659 306 3313 785 673 291 3314 768 658 306 3315 785 673 292 3316 769 659 305 3317 784 672 304 3318 783 671 292 3319 769 659 293 3320 770 660 292 3321 769 659 304 3322 783 671 305 3323 784 672 304 3324 783 671 293 3325 770 660 294 3326 771 661 294 3327 771 661 303 3328 782 670 304 3329 783 671 295 3330 772 662 303 3331 782 670 294 3332 771 661 303 3333 782 670 295 3334 772 662 302 3335 781 669 301 3336 780 668 295 3337 772 662 296 3338 773 663 302 3339 781 669 295 3340 772 662 301 3341 780 668 296 3342 773 663 300 3343 779 667 301 3344 780 668 300 3345 779 667 296 3346 773 663 297 3347 774 664 300 3348 779 667 297 3349 774 664 298 3350 777 665 300 3351 779 667 298 3352 777 665 299 3353 778 666 362 3354 807 729 361 3355 806 728 363 3356 808 730 363 3357 808 730 361 3358 806 728 364 3359 809 731 362 3360 807 729 366 3361 811 733 361 3362 806 728 366 3363 811 733 365 3364 810 732 361 3365 806 728 365 3366 810 732 366 3367 811 733 368 3368 813 735 365 3369 810 732 368 3370 813 735 367 3371 812 734 367 3372 812 734 368 3373 813 735 370 3374 815 737 367 3375 812 734 370 3376 815 737 369 3377 814 736 369 3378 814 736 370 3379 815 737 372 3380 817 739 369 3381 814 736 372 3382 817 739 371 3383 816 738 371 3384 816 738 372 3385 817 739 374 3386 819 741 371 3387 816 738 374 3388 819 741 373 3389 818 740 373 3390 818 740 374 3391 819 741 376 3392 821 743 373 3393 818 740 376 3394 821 743 375 3395 820 742 377 3396 822 744 375 3397 820 742 378 3398 823 745 375 3399 820 742 376 3400 821 743 378 3401 823 745 379 3402 824 746 377 3403 822 744 380 3404 825 747 377 3405 822 744 378 3406 823 745 380 3407 825 747 379 3408 829 746 380 3409 828 747 381 3410 826 748 381 3411 826 748 380 3412 828 747 382 3413 827 749 383 3414 830 750 381 3415 826 748 384 3416 831 751 381 3417 826 748 382 3418 827 749 384 3419 831 751 386 3420 833 753 385 3421 832 752 384 3422 831 751 385 3423 832 752 383 3424 830 750 384 3425 831 751 388 3426 835 755 387 3427 834 754 386 3428 833 753 387 3429 834 754 385 3430 832 752 386 3431 833 753 389 3432 836 756 387 3433 834 754 390 3434 837 757 390 3435 837 757 387 3436 834 754 388 3437 835 755 389 3438 836 756 392 3439 839 759 391 3440 838 758 392 3441 839 759 389 3442 836 756 390 3443 837 757 393 3444 840 760 391 3445 838 758 394 3446 841 761 394 3447 841 761 391 3448 838 758 392 3449 839 759 396 3450 843 763 395 3451 842 762 394 3452 841 761 394 3453 841 761 395 3454 842 762 393 3455 840 760 363 3456 808 730 364 3457 809 731 396 3458 843 763 396 3459 843 763 364 3460 809 731 395 3461 842 762 361 3462 806 728 397 3463 844 764 364 3464 809 731 397 3465 844 764 361 3466 806 728 398 3467 845 765 395 3468 842 762 364 3469 809 731 397 3470 844 764 395 3471 842 762 397 3472 844 764 399 3473 846 766 399 3474 846 766 400 3475 847 767 393 3476 840 760 393 3477 840 760 395 3478 842 762 399 3479 846 766 400 3480 847 767 401 3481 848 768 391 3482 838 758 391 3483 838 758 393 3484 840 760 400 3485 847 767 401 3486 848 768 402 3487 849 769 389 3488 836 756 401 3489 848 768 389 3490 836 756 391 3491 838 758 387 3492 834 754 389 3493 836 756 402 3494 849 769 402 3495 849 769 403 3496 850 770 387 3497 834 754 387 3498 834 754 404 3499 851 771 385 3500 832 752 404 3501 851 771 387 3502 834 754 403 3503 850 770 385 3504 832 752 405 3505 852 772 383 3506 830 750 405 3507 852 772 385 3508 832 752 404 3509 851 771 381 3510 826 748 383 3511 830 750 406 3512 853 773 406 3513 853 773 383 3514 830 750 405 3515 852 772 381 3516 826 748 407 3517 854 774 379 3518 829 746 407 3519 854 774 381 3520 826 748 406 3521 853 773 407 3522 856 774 408 3523 855 775 377 3524 822 744 407 3525 856 774 377 3526 822 744 379 3527 824 746 375 3528 820 742 377 3529 822 744 408 3530 855 775 408 3531 855 775 409 3532 857 776 375 3533 820 742 373 3534 818 740 375 3535 820 742 409 3536 857 776 373 3537 818 740 409 3538 857 776 410 3539 858 777 371 3540 816 738 373 3541 818 740 410 3542 858 777 371 3543 816 738 410 3544 858 777 411 3545 859 778 369 3546 814 736 371 3547 816 738 412 3548 860 779 412 3549 860 779 371 3550 816 738 411 3551 859 778 369 3552 814 736 413 3553 861 780 367 3554 812 734 413 3555 861 780 369 3556 814 736 412 3557 860 779 365 3558 810 732 367 3559 812 734 414 3560 862 781 413 3561 861 780 414 3562 862 781 367 3563 812 734 414 3564 862 781 398 3565 845 765 365 3566 810 732 365 3567 810 732 398 3568 845 765 361 3569 806 728 397 3570 844 764 398 3571 845 765 416 3572 864 783 398 3573 845 765 415 3574 863 782 416 3575 864 783 398 3576 845 765 417 3577 865 784 415 3578 863 782 417 3579 865 784 398 3580 845 765 414 3581 862 781 417 3582 865 784 414 3583 862 781 418 3584 866 785 414 3585 862 781 413 3586 861 780 418 3587 866 785 418 3588 866 785 413 3589 861 780 419 3590 867 786 413 3591 861 780 412 3592 860 779 419 3593 867 786 419 3594 867 786 412 3595 860 779 420 3596 868 787 412 3597 860 779 411 3598 859 778 420 3599 868 787 420 3600 868 787 411 3601 859 778 421 3602 869 788 411 3603 859 778 410 3604 858 777 421 3605 869 788 421 3606 869 788 410 3607 858 777 422 3608 870 789 410 3609 858 777 409 3610 857 776 422 3611 870 789 422 3612 870 789 409 3613 857 776 423 3614 871 790 423 3615 871 790 409 3616 857 776 408 3617 855 775 423 3618 871 790 408 3619 855 775 424 3620 872 791 424 3621 872 791 408 3622 855 775 407 3623 856 774 424 3624 874 791 407 3625 854 774 425 3626 873 792 425 3627 873 792 407 3628 854 774 406 3629 853 773 425 3630 873 792 406 3631 853 773 426 3632 875 793 426 3633 875 793 406 3634 853 773 405 3635 852 772 404 3636 851 771 427 3637 876 794 405 3638 852 772 427 3639 876 794 426 3640 875 793 405 3641 852 772 403 3642 850 770 428 3643 877 795 404 3644 851 771 428 3645 877 795 427 3646 876 794 404 3647 851 771 402 3648 849 769 429 3649 878 796 403 3650 850 770 429 3651 878 796 428 3652 877 795 403 3653 850 770 430 3654 879 797 429 3655 878 796 401 3656 848 768 401 3657 848 768 429 3658 878 796 402 3659 849 769 431 3660 880 798 430 3661 879 797 400 3662 847 767 400 3663 847 767 430 3664 879 797 401 3665 848 768 400 3666 847 767 399 3667 846 766 431 3668 880 798 399 3669 846 766 432 3670 881 799 431 3671 880 798 399 3672 846 766 397 3673 844 764 432 3674 881 799 397 3675 844 764 416 3676 864 783 432 3677 881 799 427 3678 886 794 424 3679 884 791 426 3680 882 793 424 3681 884 791 427 3682 886 794 423 3683 885 790 426 3684 882 793 424 3685 884 791 425 3686 883 792 423 3687 885 790 428 3688 888 795 422 3689 887 789 428 3690 888 795 423 3691 885 790 427 3692 886 794 429 3693 890 796 422 3694 887 789 428 3695 888 795 422 3696 887 789 429 3697 890 796 421 3698 889 788 421 3699 889 788 430 3700 892 797 420 3701 891 787 430 3702 892 797 421 3703 889 788 429 3704 890 796 420 3705 891 787 431 3706 894 798 419 3707 893 786 431 3708 894 798 420 3709 891 787 430 3710 892 797 419 3711 893 786 432 3712 896 799 418 3713 895 785 432 3714 896 799 419 3715 893 786 431 3716 894 798 418 3717 895 785 416 3718 898 783 417 3719 897 784 416 3720 898 783 418 3721 895 785 432 3722 896 799 417 3723 897 784 416 3724 898 783 415 3725 899 782 396 3726 900 763 366 3727 903 733 362 3728 902 729 396 3729 900 763 362 3730 902 729 363 3731 901 730 368 3732 905 735 396 3733 900 763 394 3734 904 761 396 3735 900 763 368 3736 905 735 366 3737 903 733 392 3738 906 759 368 3739 905 735 394 3740 904 761 368 3741 905 735 392 3742 906 759 370 3743 907 737 390 3744 908 757 372 3745 909 739 392 3746 906 759 370 3747 907 737 392 3748 906 759 372 3749 909 739 374 3750 911 741 390 3751 908 757 388 3752 910 755 390 3753 908 757 374 3754 911 741 372 3755 909 739 374 3756 911 741 388 3757 910 755 386 3758 912 753 374 3759 911 741 386 3760 912 753 376 3761 913 743 384 3762 914 751 376 3763 913 743 386 3764 912 753 376 3765 913 743 384 3766 914 751 378 3767 915 745 380 3768 917 747 384 3769 914 751 382 3770 916 749 378 3771 915 745 384 3772 914 751 380 3773 917 747 658 3774 1236 1025 649 3775 1218 1016 659 3776 1237 1026 659 3777 1237 1026 649 3778 1218 1016 650 3779 1220 1017 659 3780 1237 1026 650 3781 1220 1017 660 3782 1238 1027 660 3783 1238 1027 650 3784 1220 1017 651 3785 1222 1018 660 3786 1239 1027 651 3787 1246 1018 661 3788 1240 1028 661 3789 1240 1028 651 3790 1246 1018 652 3791 1224 1019 661 3792 1240 1028 652 3793 1224 1019 662 3794 1241 1029 662 3795 1241 1029 652 3796 1224 1019 653 3797 1226 1020 662 3798 1241 1029 653 3799 1226 1020 663 3800 1242 1030 663 3801 1242 1030 653 3802 1226 1020 654 3803 1228 1021 663 3804 1242 1030 654 3805 1228 1021 664 3806 1243 1031 664 3807 1243 1031 654 3808 1228 1021 655 3809 1230 1022 664 3810 1243 1031 655 3811 1230 1022 665 3812 1244 1032 665 3813 1244 1032 655 3814 1230 1022 656 3815 1232 1023 665 3816 1244 1032 656 3817 1232 1023 666 3818 1245 1033 666 3819 1245 1033 656 3820 1232 1023 657 3821 1234 1024 666 3822 1245 1033 657 3823 1234 1024 658 3824 1236 1025 658 3825 1236 1025 657 3826 1234 1024 649 3827 1218 1016 658 3828 1236 1025 659 3829 1237 1026 668 3830 1248 1035 658 3831 1236 1025 668 3832 1248 1035 667 3833 1247 1034 659 3834 1237 1026 669 3835 1249 1036 668 3836 1248 1035 669 3837 1249 1036 659 3838 1237 1026 660 3839 1238 1027 661 3840 1240 1028 669 3841 1250 1036 660 3842 1239 1027 669 3843 1250 1036 661 3844 1240 1028 670 3845 1251 1037 662 3846 1241 1029 671 3847 1252 1038 670 3848 1251 1037 662 3849 1241 1029 670 3850 1251 1037 661 3851 1240 1028 662 3852 1241 1029 672 3853 1253 1039 671 3854 1252 1038 672 3855 1253 1039 662 3856 1241 1029 663 3857 1242 1030 663 3858 1242 1030 673 3859 1254 1040 672 3860 1253 1039 673 3861 1254 1040 663 3862 1242 1030 664 3863 1243 1031 665 3864 1244 1032 674 3865 1255 1041 673 3866 1254 1040 665 3867 1244 1032 673 3868 1254 1040 664 3869 1243 1031 666 3870 1245 1033 674 3871 1255 1041 665 3872 1244 1032 674 3873 1255 1041 666 3874 1245 1033 675 3875 1256 1042 666 3876 1245 1033 658 3877 1236 1025 675 3878 1256 1042 658 3879 1236 1025 667 3880 1247 1034 675 3881 1256 1042 676 3882 1257 1043 667 3883 1247 1034 677 3884 1258 1044 677 3885 1258 1044 667 3886 1247 1034 668 3887 1248 1035 677 3888 1258 1044 668 3889 1248 1035 678 3890 1259 1045 678 3891 1259 1045 668 3892 1248 1035 669 3893 1249 1036 678 3894 1260 1045 669 3895 1250 1036 679 3896 1261 1046 679 3897 1261 1046 669 3898 1250 1036 670 3899 1251 1037 679 3900 1261 1046 670 3901 1251 1037 680 3902 1262 1047 680 3903 1262 1047 670 3904 1251 1037 671 3905 1252 1038 680 3906 1262 1047 671 3907 1252 1038 681 3908 1263 1048 681 3909 1263 1048 671 3910 1252 1038 672 3911 1253 1039 681 3912 1263 1048 672 3913 1253 1039 682 3914 1264 1049 682 3915 1264 1049 672 3916 1253 1039 673 3917 1254 1040 682 3918 1264 1049 673 3919 1254 1040 683 3920 1265 1050 683 3921 1265 1050 673 3922 1254 1040 674 3923 1255 1041 683 3924 1265 1050 674 3925 1255 1041 684 3926 1266 1051 684 3927 1266 1051 674 3928 1255 1041 675 3929 1256 1042 684 3930 1266 1051 675 3931 1256 1042 676 3932 1257 1043 676 3933 1257 1043 675 3934 1256 1042 667 3935 1247 1034 649 3936 1218 1016 686 3937 1268 1053 650 3938 1220 1017 686 3939 1268 1053 649 3940 1218 1016 685 3941 1267 1052 650 3942 1220 1017 687 3943 1269 1054 651 3944 1222 1018 687 3945 1269 1054 650 3946 1220 1017 686 3947 1268 1053 652 3948 1224 1019 687 3949 1270 1054 688 3950 1271 1055 687 3951 1270 1054 652 3952 1224 1019 651 3953 1246 1018 688 3954 1271 1055 653 3955 1226 1020 652 3956 1224 1019 653 3957 1226 1020 688 3958 1271 1055 689 3959 1272 1056 654 3960 1228 1021 653 3961 1226 1020 690 3962 1273 1057 653 3963 1226 1020 689 3964 1272 1056 690 3965 1273 1057 654 3966 1228 1021 691 3967 1274 1058 655 3968 1230 1022 691 3969 1274 1058 654 3970 1228 1021 690 3971 1273 1057 655 3972 1230 1022 691 3973 1274 1058 656 3974 1232 1023 691 3975 1274 1058 692 3976 1275 1059 656 3977 1232 1023 657 3978 1234 1024 692 3979 1275 1059 693 3980 1276 1060 692 3981 1275 1059 657 3982 1234 1024 656 3983 1232 1023 649 3984 1218 1016 657 3985 1234 1024 693 3986 1276 1060 649 3987 1218 1016 693 3988 1276 1060 685 3989 1267 1052 696 3990 1279 1063 694 3991 1277 1061 695 3992 1278 1062 694 3993 1277 1061 701 3994 1233 1068 702 3995 1286 1069 701 3996 1233 1068 694 3997 1277 1061 696 3998 1279 1063 693 3999 1276 1060 695 4000 1221 1062 685 4001 1267 1052 685 4002 1267 1052 695 4003 1221 1062 694 4004 1219 1061 692 4005 1275 1059 696 4006 1223 1063 693 4007 1276 1060 693 4008 1276 1060 696 4009 1223 1063 695 4010 1221 1062 691 4011 1274 1058 697 4012 1280 1064 692 4013 1275 1059 692 4014 1275 1059 697 4015 1280 1064 696 4016 1223 1063 690 4017 1273 1057 698 4018 1281 1065 691 4019 1274 1058 691 4020 1274 1058 698 4021 1281 1065 697 4022 1280 1064 689 4023 1272 1056 699 4024 1282 1066 690 4025 1273 1057 690 4026 1273 1057 699 4027 1282 1066 698 4028 1281 1065 688 4029 1271 1055 700 4030 1283 1067 689 4031 1272 1056 689 4032 1272 1056 700 4033 1283 1067 699 4034 1282 1066 700 4035 1283 1067 688 4036 1271 1055 687 4037 1270 1054 687 4038 1270 1054 701 4039 1284 1068 700 4040 1283 1067 686 4041 1268 1053 702 4042 1235 1069 687 4043 1269 1054 687 4044 1269 1054 702 4045 1235 1069 701 4046 1285 1068 685 4047 1267 1052 694 4048 1219 1061 686 4049 1268 1053 686 4050 1268 1053 694 4051 1219 1061 702 4052 1235 1069 699 4053 1229 1066 697 4054 1225 1064 698 4055 1227 1065 697 4056 1225 1064 699 4057 1229 1066 700 4058 1231 1067 697 4059 1225 1064 700 4060 1231 1067 701 4061 1233 1068 697 4062 1225 1064 701 4063 1233 1068 696 4064 1279 1063 703 4065 1295 1070 706 4066 1297 1073 704 4067 1298 1071 706 4068 1297 1073 703 4069 1295 1070 705 4070 1296 1072 709 4071 1302 1076 707 4072 1299 1074 710 4073 1301 1077 707 4074 1299 1074 708 4075 1300 1075 710 4076 1301 1077 710 4077 1293 1077 708 4078 1292 1075 706 4079 1289 1073 708 4080 1292 1075 704 4081 1290 1071 706 4082 1289 1073 709 4083 1306 1076 710 4084 1305 1077 705 4085 1303 1072 705 4086 1303 1072 710 4087 1305 1077 706 4088 1304 1073 705 4089 1288 1072 707 4090 1291 1074 709 4091 1294 1076 707 4092 1291 1074 705 4093 1288 1072 703 4094 1287 1070 775 4095 1430 1201 712 4096 1310 1081 711 4097 1308 1079 711 4098 1308 1079 776 4099 1457 1203 775 4100 1430 1201 712 4101 1310 1081 775 4102 1430 1201 713 4103 1312 1083 791 4104 1462 1233 713 4105 1312 1083 775 4106 1430 1201 713 4107 1312 1083 791 4108 1462 1233 715 4109 1315 1086 714 4110 1314 1085 715 4111 1315 1086 791 4112 1462 1233 794 4113 1467 1238 716 4114 1316 1087 714 4115 1314 1085 714 4116 1314 1085 716 4117 1316 1087 715 4118 1315 1086 716 4119 1316 1087 794 4120 1467 1238 796 4121 1469 1240 716 4122 1316 1087 796 4123 1469 1240 717 4124 1318 1089 717 4125 1318 1089 796 4126 1469 1240 719 4127 1320 1091 717 4128 1318 1089 719 4129 1320 1091 718 4130 1319 1090 711 4131 1607 1079 719 4132 1320 1091 776 4133 1432 1203 719 4134 1320 1091 711 4135 1607 1079 718 4136 1319 1090 712 4137 1310 1081 721 4138 1324 1095 720 4139 1322 1093 720 4140 1322 1093 711 4141 1308 1079 712 4142 1310 1081 721 4143 1324 1095 712 4144 1310 1081 722 4145 1326 1097 713 4146 1312 1083 722 4147 1326 1097 712 4148 1310 1081 722 4149 1326 1097 713 4150 1312 1083 723 4151 1328 1099 715 4152 1315 1086 723 4153 1328 1099 713 4154 1312 1083 716 4155 1316 1087 724 4156 1329 1100 715 4157 1315 1086 715 4158 1315 1086 724 4159 1329 1100 723 4160 1328 1099 724 4161 1329 1100 716 4162 1316 1087 717 4163 1318 1089 724 4164 1329 1100 717 4165 1318 1089 725 4166 1331 1102 725 4167 1331 1102 717 4168 1318 1089 718 4169 1319 1090 725 4170 1331 1102 718 4171 1319 1090 726 4172 1332 1103 720 4173 1608 1093 718 4174 1319 1090 711 4175 1607 1079 718 4176 1319 1090 720 4177 1608 1093 726 4178 1332 1103 721 4179 1324 1095 780 4180 1439 1210 781 4181 1441 1212 781 4182 1441 1212 720 4183 1322 1093 721 4184 1324 1095 780 4185 1439 1210 722 4186 1326 1097 779 4187 1437 1208 722 4188 1326 1097 780 4189 1439 1210 721 4190 1324 1095 779 4191 1437 1208 723 4192 1328 1099 778 4193 1435 1206 723 4194 1328 1099 779 4195 1437 1208 722 4196 1326 1097 724 4197 1329 1100 777 4198 1434 1205 723 4199 1328 1099 723 4200 1328 1099 777 4201 1434 1205 778 4202 1435 1206 725 4203 1331 1102 783 4204 1444 1215 724 4205 1329 1100 777 4206 1434 1205 724 4207 1329 1100 783 4208 1444 1215 783 4209 1444 1215 725 4210 1331 1102 782 4211 1443 1214 725 4212 1331 1102 726 4213 1332 1103 782 4214 1443 1214 782 4215 1443 1214 726 4216 1332 1103 781 4217 1617 1212 781 4218 1617 1212 726 4219 1332 1103 720 4220 1608 1093 732 4221 1345 1115 727 4222 1334 1105 734 4223 1348 1119 732 4224 1345 1115 734 4225 1348 1119 733 4226 1346 1117 735 4227 1350 1121 727 4228 1334 1105 728 4229 1336 1107 727 4230 1334 1105 735 4231 1350 1121 734 4232 1348 1119 736 4233 1352 1123 728 4234 1336 1107 729 4235 1338 1109 728 4236 1336 1107 736 4237 1352 1123 735 4238 1350 1121 736 4239 1352 1123 729 4240 1338 1109 730 4241 1340 1111 730 4242 1340 1111 737 4243 1354 1125 736 4244 1352 1123 737 4245 1354 1125 730 4246 1340 1111 731 4247 1342 1113 737 4248 1354 1125 731 4249 1342 1113 738 4250 1356 1127 738 4251 1356 1127 731 4252 1342 1113 732 4253 1344 1115 738 4254 1356 1127 732 4255 1344 1115 733 4256 1610 1117 734 4257 1348 1119 740 4258 1360 1131 733 4259 1346 1117 733 4260 1346 1117 740 4261 1360 1131 739 4262 1358 1129 741 4263 1362 1133 734 4264 1348 1119 735 4265 1350 1121 734 4266 1348 1119 741 4267 1362 1133 740 4268 1360 1131 742 4269 1364 1135 735 4270 1350 1121 736 4271 1352 1123 735 4272 1350 1121 742 4273 1364 1135 741 4274 1362 1133 742 4275 1364 1135 736 4276 1352 1123 737 4277 1354 1125 737 4278 1354 1125 743 4279 1366 1137 742 4280 1364 1135 738 4281 1356 1127 744 4282 1368 1139 743 4283 1366 1137 738 4284 1356 1127 743 4285 1366 1137 737 4286 1354 1125 733 4287 1610 1117 739 4288 1611 1129 744 4289 1368 1139 733 4290 1610 1117 744 4291 1368 1139 738 4292 1356 1127 740 4293 1360 1131 746 4294 1372 1143 739 4295 1358 1129 739 4296 1358 1129 746 4297 1372 1143 745 4298 1370 1141 746 4299 1372 1143 740 4300 1360 1131 741 4301 1362 1133 741 4302 1362 1133 747 4303 1374 1145 746 4304 1372 1143 747 4305 1374 1145 741 4306 1362 1133 742 4307 1364 1135 742 4308 1364 1135 748 4309 1376 1147 747 4310 1374 1145 748 4311 1376 1147 742 4312 1364 1135 743 4313 1366 1137 743 4314 1366 1137 749 4315 1378 1149 748 4316 1376 1147 744 4317 1368 1139 750 4318 1380 1151 743 4319 1366 1137 743 4320 1366 1137 750 4321 1380 1151 749 4322 1378 1149 739 4323 1611 1129 745 4324 1612 1141 744 4325 1368 1139 744 4326 1368 1139 745 4327 1612 1141 750 4328 1380 1151 745 4329 1370 1141 746 4330 1372 1143 751 4331 1382 1153 746 4332 1372 1143 752 4333 1384 1155 751 4334 1382 1153 747 4335 1374 1145 753 4336 1386 1157 752 4337 1384 1155 747 4338 1374 1145 752 4339 1384 1155 746 4340 1372 1143 748 4341 1376 1147 754 4342 1388 1159 753 4343 1386 1157 748 4344 1376 1147 753 4345 1386 1157 747 4346 1374 1145 749 4347 1378 1149 755 4348 1390 1161 748 4349 1376 1147 748 4350 1376 1147 755 4351 1390 1161 754 4352 1388 1159 749 4353 1378 1149 756 4354 1392 1163 755 4355 1390 1161 756 4356 1392 1163 749 4357 1378 1149 750 4358 1380 1151 750 4359 1380 1151 751 4360 1613 1153 756 4361 1392 1163 751 4362 1613 1153 750 4363 1380 1151 745 4364 1612 1141 751 4365 1382 1153 752 4366 1384 1155 757 4367 1394 1165 752 4368 1384 1155 758 4369 1396 1167 757 4370 1394 1165 758 4371 1396 1167 752 4372 1384 1155 759 4373 1398 1169 753 4374 1386 1157 759 4375 1398 1169 752 4376 1384 1155 759 4377 1398 1169 753 4378 1386 1157 760 4379 1400 1171 754 4380 1388 1159 760 4381 1400 1171 753 4382 1386 1157 754 4383 1388 1159 755 4384 1390 1161 761 4385 1402 1173 754 4386 1388 1159 761 4387 1402 1173 760 4388 1400 1171 761 4389 1402 1173 755 4390 1390 1161 756 4391 1392 1163 761 4392 1402 1173 756 4393 1392 1163 762 4394 1404 1175 762 4395 1404 1175 756 4396 1392 1163 751 4397 1613 1153 762 4398 1404 1175 751 4399 1613 1153 757 4400 1614 1165 764 4401 1408 1179 763 4402 1406 1177 757 4403 1394 1165 764 4404 1408 1179 757 4405 1394 1165 758 4406 1396 1167 758 4407 1396 1167 765 4408 1410 1181 764 4409 1408 1179 765 4410 1410 1181 758 4411 1396 1167 759 4412 1398 1169 765 4413 1410 1181 759 4414 1398 1169 766 4415 1412 1183 766 4416 1412 1183 759 4417 1398 1169 760 4418 1400 1171 766 4419 1412 1183 760 4420 1400 1171 761 4421 1402 1173 761 4422 1402 1173 767 4423 1414 1185 766 4424 1412 1183 767 4425 1414 1185 761 4426 1402 1173 762 4427 1404 1175 767 4428 1414 1185 762 4429 1404 1175 768 4430 1416 1187 757 4431 1614 1165 763 4432 1615 1177 768 4433 1416 1187 768 4434 1416 1187 762 4435 1404 1175 757 4436 1614 1165 769 4437 1418 1189 763 4438 1406 1177 770 4439 1420 1191 770 4440 1420 1191 763 4441 1406 1177 764 4442 1408 1179 770 4443 1420 1191 764 4444 1408 1179 771 4445 1422 1193 771 4446 1422 1193 764 4447 1408 1179 765 4448 1410 1181 771 4449 1422 1193 765 4450 1410 1181 772 4451 1424 1195 772 4452 1424 1195 765 4453 1410 1181 766 4454 1412 1183 772 4455 1424 1195 766 4456 1412 1183 767 4457 1414 1185 767 4458 1414 1185 773 4459 1426 1197 772 4460 1424 1195 768 4461 1416 1187 773 4462 1426 1197 767 4463 1414 1185 773 4464 1426 1197 768 4465 1416 1187 774 4466 1428 1199 763 4467 1615 1177 774 4468 1428 1199 768 4469 1416 1187 774 4470 1428 1199 763 4471 1615 1177 769 4472 1616 1189 787 4473 1452 1223 788 4474 1454 1225 780 4475 1439 1210 788 4476 1454 1225 781 4477 1441 1212 780 4478 1439 1210 779 4479 1437 1208 786 4480 1450 1221 787 4481 1452 1223 787 4482 1452 1223 780 4483 1439 1210 779 4484 1437 1208 778 4485 1435 1206 785 4486 1448 1219 786 4487 1450 1221 786 4488 1450 1221 779 4489 1437 1208 778 4490 1435 1206 777 4491 1434 1205 784 4492 1446 1217 778 4493 1435 1206 778 4494 1435 1206 784 4495 1446 1217 785 4496 1448 1219 783 4497 1444 1215 789 4498 1456 1227 784 4499 1446 1217 784 4500 1446 1217 777 4501 1434 1205 783 4502 1444 1215 789 4503 1456 1227 783 4504 1444 1215 782 4505 1443 1214 789 4506 1456 1227 782 4507 1443 1214 788 4508 1618 1225 788 4509 1618 1225 782 4510 1443 1214 781 4511 1617 1212 727 4512 1334 1105 732 4513 1345 1115 787 4514 1452 1223 732 4515 1345 1115 788 4516 1454 1225 787 4517 1452 1223 727 4518 1334 1105 786 4519 1450 1221 728 4520 1336 1107 786 4521 1450 1221 727 4522 1334 1105 787 4523 1452 1223 785 4524 1448 1219 728 4525 1336 1107 786 4526 1450 1221 728 4527 1336 1107 785 4528 1448 1219 729 4529 1338 1109 785 4530 1448 1219 784 4531 1446 1217 730 4532 1340 1111 785 4533 1448 1219 730 4534 1340 1111 729 4535 1338 1109 784 4536 1446 1217 731 4537 1342 1113 730 4538 1340 1111 731 4539 1342 1113 784 4540 1446 1217 789 4541 1456 1227 731 4542 1342 1113 789 4543 1456 1227 732 4544 1344 1115 732 4545 1344 1115 789 4546 1456 1227 788 4547 1618 1225 776 4548 1457 1203 799 4549 1459 1245 775 4550 1430 1201 775 4551 1430 1201 799 4552 1459 1245 790 4553 1458 1229 792 4554 1463 1234 791 4555 1462 1233 775 4556 1430 1201 792 4557 1463 1234 775 4558 1430 1201 790 4559 1458 1229 793 4560 1465 1236 714 4561 1314 1085 791 4562 1462 1233 793 4563 1465 1236 791 4564 1462 1233 792 4565 1463 1234 714 4566 1314 1085 793 4567 1465 1236 795 4568 1468 1239 795 4569 1468 1239 794 4570 1467 1238 714 4571 1314 1085 797 4572 1470 1241 796 4573 1469 1240 795 4574 1468 1239 794 4575 1467 1238 795 4576 1468 1239 796 4577 1469 1240 798 4578 1473 1244 719 4579 1320 1091 797 4580 1470 1241 796 4581 1469 1240 797 4582 1470 1241 719 4583 1320 1091 719 4584 1320 1091 799 4585 1474 1245 776 4586 1432 1203 799 4587 1474 1245 719 4588 1320 1091 798 4589 1473 1244 799 4590 1459 1245 806 4591 1476 1257 790 4592 1458 1229 790 4593 1458 1229 806 4594 1476 1257 800 4595 1475 1246 801 4596 1478 1249 792 4597 1463 1234 790 4598 1458 1229 801 4599 1478 1249 790 4600 1458 1229 800 4601 1475 1246 802 4602 1480 1251 793 4603 1465 1236 792 4604 1463 1234 802 4605 1480 1251 792 4606 1463 1234 801 4607 1478 1249 793 4608 1465 1236 802 4609 1480 1251 803 4610 1482 1253 803 4611 1482 1253 795 4612 1468 1239 793 4613 1465 1236 804 4614 1483 1254 797 4615 1470 1241 803 4616 1482 1253 795 4617 1468 1239 803 4618 1482 1253 797 4619 1470 1241 805 4620 1485 1256 798 4621 1473 1244 804 4622 1483 1254 797 4623 1470 1241 804 4624 1483 1254 798 4625 1473 1244 798 4626 1473 1244 806 4627 1486 1257 799 4628 1474 1245 806 4629 1486 1257 798 4630 1473 1244 805 4631 1485 1256 806 4632 1476 1257 813 4633 1488 1269 800 4634 1475 1246 800 4635 1475 1246 813 4636 1488 1269 807 4637 1487 1258 808 4638 1490 1261 801 4639 1478 1249 807 4640 1487 1258 801 4641 1478 1249 800 4642 1475 1246 807 4643 1487 1258 809 4644 1492 1263 802 4645 1480 1251 808 4646 1490 1261 802 4647 1480 1251 801 4648 1478 1249 808 4649 1490 1261 802 4650 1480 1251 809 4651 1492 1263 810 4652 1494 1265 810 4653 1494 1265 803 4654 1482 1253 802 4655 1480 1251 803 4656 1482 1253 810 4657 1494 1265 811 4658 1495 1266 803 4659 1482 1253 811 4660 1495 1266 804 4661 1483 1254 804 4662 1483 1254 811 4663 1495 1266 812 4664 1497 1268 804 4665 1483 1254 812 4666 1497 1268 805 4667 1485 1256 805 4668 1485 1256 813 4669 1498 1269 806 4670 1486 1257 813 4671 1498 1269 805 4672 1485 1256 812 4673 1497 1268 814 4674 1499 1270 815 4675 1501 1272 816 4676 1503 1274 815 4677 1501 1272 814 4678 1499 1270 827 4679 1502 1293 816 4680 1503 1274 815 4681 1501 1272 817 4682 1506 1277 816 4683 1503 1274 817 4684 1506 1277 818 4685 1507 1278 818 4686 1507 1278 817 4687 1506 1277 819 4688 1510 1281 818 4689 1507 1278 819 4690 1510 1281 820 4691 1511 1282 820 4692 1511 1282 819 4693 1510 1281 821 4694 1513 1284 821 4695 1513 1284 819 4696 1510 1281 822 4697 1514 1285 821 4698 1513 1284 822 4699 1514 1285 824 4700 1517 1288 824 4701 1517 1288 822 4702 1514 1285 823 4703 1516 1287 823 4704 1516 1287 825 4705 1519 1290 824 4706 1517 1288 825 4707 1519 1290 823 4708 1516 1287 826 4709 1520 1291 825 4710 1519 1290 826 4711 1520 1291 814 4712 1623 1270 814 4713 1623 1270 826 4714 1520 1291 827 4715 1522 1293 827 4716 1502 1293 828 4717 1523 1294 815 4718 1501 1272 828 4719 1523 1294 827 4720 1502 1293 834 4721 1524 1305 829 4722 1526 1297 815 4723 1501 1272 828 4724 1523 1294 815 4725 1501 1272 829 4726 1526 1297 817 4727 1506 1277 830 4728 1528 1299 817 4729 1506 1277 829 4730 1526 1297 817 4731 1506 1277 830 4732 1528 1299 819 4733 1510 1281 819 4734 1510 1281 830 4735 1528 1299 822 4736 1514 1285 822 4737 1514 1285 830 4738 1528 1299 831 4739 1530 1301 822 4740 1514 1285 831 4741 1530 1301 823 4742 1516 1287 823 4743 1516 1287 831 4744 1530 1301 832 4745 1531 1302 823 4746 1516 1287 832 4747 1531 1302 826 4748 1520 1291 826 4749 1520 1291 832 4750 1531 1302 833 4751 1533 1304 826 4752 1520 1291 833 4753 1533 1304 827 4754 1522 1293 827 4755 1522 1293 833 4756 1533 1304 834 4757 1534 1305 834 4758 1524 1305 835 4759 1535 1306 828 4760 1523 1294 835 4761 1535 1306 834 4762 1524 1305 841 4763 1536 1317 835 4764 1535 1306 829 4765 1526 1297 828 4766 1523 1294 829 4767 1526 1297 835 4768 1535 1306 836 4769 1538 1309 836 4770 1538 1309 830 4771 1528 1299 829 4772 1526 1297 830 4773 1528 1299 836 4774 1538 1309 837 4775 1540 1311 830 4776 1528 1299 837 4777 1540 1311 831 4778 1530 1301 831 4779 1530 1301 837 4780 1540 1311 838 4781 1542 1313 831 4782 1530 1301 839 4783 1543 1314 832 4784 1531 1302 839 4785 1543 1314 831 4786 1530 1301 838 4787 1542 1313 832 4788 1531 1302 840 4789 1545 1316 833 4790 1533 1304 840 4791 1545 1316 832 4792 1531 1302 839 4793 1543 1314 834 4794 1534 1305 840 4795 1545 1316 841 4796 1546 1317 840 4797 1545 1316 834 4798 1534 1305 833 4799 1533 1304 841 4800 1536 1317 848 4801 1548 1329 835 4802 1535 1306 835 4803 1535 1306 848 4804 1548 1329 842 4805 1547 1318 835 4806 1535 1306 842 4807 1547 1318 836 4808 1538 1309 843 4809 1550 1321 836 4810 1538 1309 842 4811 1547 1318 836 4812 1538 1309 843 4813 1550 1321 837 4814 1540 1311 844 4815 1552 1323 837 4816 1540 1311 843 4817 1550 1321 837 4818 1540 1311 845 4819 1554 1325 838 4820 1542 1313 845 4821 1554 1325 837 4822 1540 1311 844 4823 1552 1323 838 4824 1542 1313 845 4825 1554 1325 846 4826 1555 1326 838 4827 1542 1313 846 4828 1555 1326 839 4829 1543 1314 839 4830 1543 1314 846 4831 1555 1326 847 4832 1557 1328 839 4833 1543 1314 847 4834 1557 1328 840 4835 1545 1316 840 4836 1545 1316 848 4837 1558 1329 841 4838 1546 1317 848 4839 1558 1329 840 4840 1545 1316 847 4841 1557 1328 848 4842 1548 1329 855 4843 1560 1341 842 4844 1547 1318 842 4845 1547 1318 855 4846 1560 1341 849 4847 1559 1330 850 4848 1562 1333 843 4849 1550 1321 842 4850 1547 1318 850 4851 1562 1333 842 4852 1547 1318 849 4853 1559 1330 851 4854 1564 1335 844 4855 1552 1323 843 4856 1550 1321 851 4857 1564 1335 843 4858 1550 1321 850 4859 1562 1333 844 4860 1552 1323 852 4861 1566 1337 845 4862 1554 1325 852 4863 1566 1337 844 4864 1552 1323 851 4865 1564 1335 853 4866 1567 1338 846 4867 1555 1326 852 4868 1566 1337 845 4869 1554 1325 852 4870 1566 1337 846 4871 1555 1326 854 4872 1569 1340 847 4873 1557 1328 853 4874 1567 1338 846 4875 1555 1326 853 4876 1567 1338 847 4877 1557 1328 847 4878 1557 1328 855 4879 1570 1341 848 4880 1558 1329 855 4881 1570 1341 847 4882 1557 1328 854 4883 1569 1340 855 4884 1560 1341 856 4885 1571 1342 849 4886 1559 1330 856 4887 1571 1342 855 4888 1560 1341 862 4889 1572 1353 849 4890 1559 1330 857 4891 1574 1345 850 4892 1562 1333 857 4893 1574 1345 849 4894 1559 1330 856 4895 1571 1342 850 4896 1562 1333 858 4897 1576 1347 851 4898 1564 1335 858 4899 1576 1347 850 4900 1562 1333 857 4901 1574 1345 859 4902 1578 1349 852 4903 1566 1337 858 4904 1576 1347 858 4905 1576 1347 852 4906 1566 1337 851 4907 1564 1335 860 4908 1579 1350 853 4909 1567 1338 859 4910 1578 1349 859 4911 1578 1349 853 4912 1567 1338 852 4913 1566 1337 861 4914 1581 1352 854 4915 1569 1340 860 4916 1579 1350 860 4917 1579 1350 854 4918 1569 1340 853 4919 1567 1338 854 4920 1569 1340 861 4921 1581 1352 855 4922 1570 1341 855 4923 1570 1341 861 4924 1581 1352 862 4925 1582 1353 862 4926 1572 1353 863 4927 1583 1354 856 4928 1571 1342 863 4929 1583 1354 862 4930 1572 1353 870 4931 1584 1365 856 4932 1571 1342 864 4933 1586 1357 857 4934 1574 1345 864 4935 1586 1357 856 4936 1571 1342 863 4937 1583 1354 857 4938 1574 1345 865 4939 1588 1359 858 4940 1576 1347 865 4941 1588 1359 857 4942 1574 1345 864 4943 1586 1357 866 4944 1590 1361 859 4945 1578 1349 865 4946 1588 1359 865 4947 1588 1359 859 4948 1578 1349 858 4949 1576 1347 867 4950 1591 1362 860 4951 1579 1350 866 4952 1590 1361 866 4953 1590 1361 860 4954 1579 1350 859 4955 1578 1349 868 4956 1592 1363 860 4957 1579 1350 867 4958 1591 1362 860 4959 1579 1350 868 4960 1592 1363 861 4961 1581 1352 861 4962 1581 1352 868 4963 1592 1363 869 4964 1593 1364 861 4965 1581 1352 869 4966 1593 1364 862 4967 1582 1353 862 4968 1582 1353 869 4969 1593 1364 870 4970 1594 1365 813 4971 1488 1269 877 4972 1596 1377 807 4973 1487 1258 807 4974 1487 1258 877 4975 1596 1377 871 4976 1595 1366 872 4977 1598 1369 808 4978 1490 1261 871 4979 1595 1366 808 4980 1490 1261 807 4981 1487 1258 871 4982 1595 1366 873 4983 1600 1371 809 4984 1492 1263 872 4985 1598 1369 809 4986 1492 1263 808 4987 1490 1261 872 4988 1598 1369 809 4989 1492 1263 873 4990 1600 1371 874 4991 1602 1373 874 4992 1602 1373 810 4993 1494 1265 809 4994 1492 1263 810 4995 1494 1265 874 4996 1602 1373 875 4997 1603 1374 875 4998 1603 1374 811 4999 1495 1266 810 5000 1494 1265 811 5001 1495 1266 875 5002 1603 1374 876 5003 1605 1376 876 5004 1605 1376 812 5005 1497 1268 811 5006 1495 1266 812 5007 1497 1268 877 5008 1606 1377 813 5009 1498 1269 812 5010 1497 1268 876 5011 1605 1376 877 5012 1606 1377 871 5013 1595 1366 877 5014 1596 1377 814 5015 1499 1270 871 5016 1595 1366 814 5017 1499 1270 816 5018 1503 1274 816 5019 1503 1274 818 5020 1507 1278 872 5021 1598 1369 816 5022 1503 1274 872 5023 1598 1369 871 5024 1595 1366 820 5025 1511 1282 873 5026 1600 1371 818 5027 1507 1278 818 5028 1507 1278 873 5029 1600 1371 872 5030 1598 1369 873 5031 1600 1371 820 5032 1511 1282 821 5033 1513 1284 821 5034 1513 1284 874 5035 1602 1373 873 5036 1600 1371 874 5037 1602 1373 824 5038 1517 1288 875 5039 1603 1374 824 5040 1517 1288 874 5041 1602 1373 821 5042 1513 1284 875 5043 1603 1374 825 5044 1519 1290 876 5045 1605 1376 825 5046 1519 1290 875 5047 1603 1374 824 5048 1517 1288 877 5049 1606 1377 876 5050 1605 1376 814 5051 1623 1270 876 5052 1605 1376 825 5053 1519 1290 814 5054 1623 1270 878 5055 1632 1378 880 5056 1633 1380 879 5057 1635 1379 880 5058 1633 1380 881 5059 1634 1381 879 5060 1635 1379 884 5061 1639 1384 883 5062 1637 1383 885 5063 1638 1385 884 5064 1639 1384 882 5065 1636 1382 883 5066 1637 1383 889 5067 1647 1389 883 5068 1637 1383 882 5069 1636 1382 893 5070 1643 1393 890 5071 1640 1390 892 5072 1642 1392 892 5073 1642 1392 890 5074 1640 1390 891 5075 1641 1391 879 5076 1651 1379 881 5077 1650 1381 885 5078 1654 1385 885 5079 1654 1385 883 5080 1653 1383 879 5081 1651 1379 881 5082 1665 1381 880 5083 1664 1380 884 5084 1667 1384 881 5085 1665 1381 884 5086 1667 1384 885 5087 1666 1385 880 5088 1649 1380 878 5089 1648 1378 884 5090 1655 1384 884 5091 1655 1384 878 5092 1648 1378 882 5093 1652 1382 879 5094 1635 1379 890 5095 1656 1390 886 5096 1645 1386 890 5097 1656 1390 879 5098 1635 1379 887 5099 1644 1387 879 5100 1635 1379 886 5101 1645 1386 878 5102 1632 1378 879 5103 1651 1379 888 5104 1646 1388 887 5105 1660 1387 888 5106 1646 1388 879 5107 1651 1379 883 5108 1653 1383 883 5109 1637 1383 893 5110 1659 1393 888 5111 1662 1388 893 5112 1659 1393 883 5113 1637 1383 889 5114 1647 1389 882 5115 1652 1382 886 5116 1668 1386 889 5117 1669 1389 886 5118 1668 1386 882 5119 1652 1382 878 5120 1648 1378 890 5121 1656 1390 887 5122 1644 1387 891 5123 1657 1391 888 5124 1646 1388 892 5125 1642 1392 887 5126 1660 1387 887 5127 1660 1387 892 5128 1642 1392 891 5129 1641 1391 888 5130 1662 1388 893 5131 1659 1393 892 5132 1658 1392 893 5133 1643 1393 889 5134 1663 1389 886 5135 1661 1386 893 5136 1643 1393 886 5137 1661 1386 890 5138 1640 1390 895 5139 1671 1395 897 5140 1673 1397 896 5141 1672 1396 895 5142 1671 1395 894 5143 1670 1394 897 5144 1673 1397 907 5145 1695 1407 897 5146 1673 1397 894 5147 1670 1394 898 5148 1674 1398 901 5149 1677 1401 899 5150 1675 1399 901 5151 1677 1401 900 5152 1676 1400 899 5153 1675 1399 903 5154 1679 1403 902 5155 1678 1402 904 5156 1680 1404 902 5157 1678 1402 905 5158 1681 1405 904 5159 1680 1404 896 5160 1683 1396 897 5161 1682 1397 900 5162 1684 1400 900 5163 1684 1400 897 5164 1682 1397 899 5165 1685 1399 895 5166 1687 1395 896 5167 1686 1396 901 5168 1688 1401 900 5169 1689 1400 901 5170 1688 1401 896 5171 1686 1396 894 5172 1691 1394 895 5173 1690 1395 901 5174 1693 1401 901 5175 1693 1401 898 5176 1692 1398 894 5177 1691 1394 897 5178 1673 1397 902 5179 1703 1402 906 5180 1694 1406 902 5181 1703 1402 897 5182 1673 1397 907 5183 1695 1407 908 5184 1696 1408 899 5185 1685 1399 897 5186 1682 1397 908 5187 1696 1408 897 5188 1682 1397 906 5189 1697 1406 909 5190 1698 1409 898 5191 1674 1398 899 5192 1675 1399 899 5193 1675 1399 905 5194 1704 1405 909 5195 1698 1409 905 5196 1704 1405 899 5197 1675 1399 908 5198 1699 1408 898 5199 1692 1398 909 5200 1701 1409 894 5201 1691 1394 907 5202 1700 1407 894 5203 1691 1394 909 5204 1701 1409 906 5205 1694 1406 902 5206 1703 1402 903 5207 1702 1403 906 5208 1697 1406 904 5209 1680 1404 908 5210 1696 1408 904 5211 1680 1404 906 5212 1697 1406 903 5213 1679 1403 905 5214 1704 1405 908 5215 1699 1408 904 5216 1705 1404 909 5217 1706 1409 905 5218 1681 1405 907 5219 1707 1407 902 5220 1678 1402 907 5221 1707 1407 905 5222 1681 1405 910 5223 1708 1410 912 5224 1709 1412 913 5225 1710 1413 910 5226 1708 1410 913 5227 1710 1413 911 5228 1711 1411 916 5229 1719 1416 914 5230 1716 1414 917 5231 1718 1417 915 5232 1717 1415 917 5233 1718 1417 914 5234 1716 1414 915 5235 1713 1415 914 5236 1712 1414 910 5237 1708 1410 915 5238 1713 1415 910 5239 1708 1410 911 5240 1711 1411 917 5241 1727 1417 915 5242 1726 1415 911 5243 1725 1411 917 5244 1727 1417 911 5245 1725 1411 913 5246 1724 1413 916 5247 1715 1416 917 5248 1714 1417 913 5249 1710 1413 916 5250 1715 1416 913 5251 1710 1413 912 5252 1709 1412 912 5253 1721 1412 914 5254 1722 1414 916 5255 1723 1416 914 5256 1722 1414 912 5257 1721 1412 910 5258 1720 1410 920 5259 1729 1420 921 5260 1730 1421 918 5261 1728 1418 918 5262 1728 1418 921 5263 1730 1421 919 5264 1731 1419 922 5265 1732 1422 923 5266 1733 1423 925 5267 1734 1425 925 5268 1734 1425 924 5269 1735 1424 922 5270 1732 1422 923 5271 1737 1423 922 5272 1736 1422 918 5273 1728 1418 923 5274 1737 1423 918 5275 1728 1418 919 5276 1731 1419 924 5277 1739 1424 925 5278 1738 1425 921 5279 1730 1421 924 5280 1739 1424 921 5281 1730 1421 920 5282 1729 1420 928 5283 1741 1428 929 5284 1742 1429 926 5285 1740 1426 926 5286 1740 1426 929 5287 1742 1429 927 5288 1743 1427 930 5289 1744 1430 931 5290 1745 1431 933 5291 1746 1433 933 5292 1746 1433 932 5293 1747 1432 930 5294 1744 1430 926 5295 1740 1426 931 5296 1749 1431 930 5297 1748 1430 931 5298 1749 1431 926 5299 1740 1426 927 5300 1743 1427 929 5301 1742 1429 932 5302 1751 1432 933 5303 1750 1433 932 5304 1751 1432 929 5305 1742 1429 928 5306 1741 1428 950 5307 1755 1450 934 5308 1752 1434 936 5309 1754 1436 936 5310 1754 1436 934 5311 1752 1434 935 5312 1753 1435 936 5313 1754 1436 935 5314 1753 1435 938 5315 1757 1438 938 5316 1757 1438 935 5317 1753 1435 937 5318 1756 1437 938 5319 1757 1438 937 5320 1756 1437 940 5321 1759 1440 940 5322 1759 1440 937 5323 1756 1437 939 5324 1758 1439 940 5325 1759 1440 939 5326 1758 1439 942 5327 1761 1442 942 5328 1761 1442 939 5329 1758 1439 941 5330 1760 1441 942 5331 1761 1442 941 5332 1760 1441 944 5333 1763 1444 944 5334 1763 1444 941 5335 1760 1441 943 5336 1762 1443 944 5337 1763 1444 943 5338 1762 1443 946 5339 1765 1446 946 5340 1765 1446 943 5341 1762 1443 945 5342 1764 1445 946 5343 1771 1446 945 5344 1770 1445 948 5345 1767 1448 948 5346 1767 1448 945 5347 1770 1445 947 5348 1766 1447 948 5349 1767 1448 947 5350 1766 1447 951 5351 1769 1451 951 5352 1769 1451 947 5353 1766 1447 949 5354 1768 1449 951 5355 1769 1451 949 5356 1768 1449 950 5357 1755 1450 950 5358 1755 1450 949 5359 1768 1449 934 5360 1752 1434 955 5361 1775 1455 952 5362 1772 1452 954 5363 1774 1454 954 5364 1774 1454 952 5365 1772 1452 953 5366 1773 1453 954 5367 1774 1454 956 5368 1776 1456 957 5369 1777 1457 956 5370 1776 1456 954 5371 1774 1454 953 5372 1773 1453 958 5373 1778 1458 959 5374 1779 1459 957 5375 1777 1457 958 5376 1778 1458 957 5377 1777 1457 956 5378 1776 1456 960 5379 1780 1460 961 5380 1781 1461 959 5381 1779 1459 960 5382 1780 1460 959 5383 1779 1459 958 5384 1778 1458 962 5385 1782 1462 963 5386 1783 1463 960 5387 1780 1460 960 5388 1780 1460 963 5389 1783 1463 961 5390 1781 1461 963 5391 1783 1463 962 5392 1782 1462 964 5393 1784 1464 964 5394 1784 1464 965 5395 1785 1465 963 5396 1783 1463 964 5397 1784 1464 967 5398 1787 1467 965 5399 1785 1465 967 5400 1787 1467 964 5401 1784 1464 966 5402 1786 1466 966 5403 1786 1466 969 5404 1789 1469 967 5405 1787 1467 969 5406 1789 1469 966 5407 1786 1466 968 5408 1788 1468 969 5409 1789 1469 968 5410 1788 1468 955 5411 1791 1455 955 5412 1791 1455 968 5413 1788 1468 952 5414 1790 1452 973 5415 1795 1473 970 5416 1792 1470 972 5417 1794 1472 971 5418 1793 1471 972 5419 1794 1472 970 5420 1792 1470 972 5421 1794 1472 971 5422 1793 1471 975 5423 1797 1475 974 5424 1796 1474 975 5425 1797 1475 971 5426 1793 1471 975 5427 1797 1475 974 5428 1796 1474 977 5429 1799 1477 976 5430 1798 1476 977 5431 1799 1477 974 5432 1796 1474 977 5433 1799 1477 976 5434 1798 1476 979 5435 1801 1479 978 5436 1800 1478 979 5437 1801 1479 976 5438 1798 1476 979 5439 1801 1479 980 5440 1802 1480 981 5441 1803 1481 980 5442 1802 1480 979 5443 1801 1479 978 5444 1800 1478 982 5445 1804 1482 983 5446 1805 1483 981 5447 1803 1481 982 5448 1804 1482 981 5449 1803 1481 980 5450 1802 1480 982 5451 1804 1482 985 5452 1807 1485 983 5453 1805 1483 985 5454 1807 1485 982 5455 1804 1482 984 5456 1806 1484 985 5457 1807 1485 984 5458 1806 1484 986 5459 1808 1486 985 5460 1807 1485 986 5461 1808 1486 987 5462 1809 1487 987 5463 1809 1487 986 5464 1808 1486 973 5465 1811 1473 970 5466 1810 1470 973 5467 1811 1473 986 5468 1808 1486 999 5469 1814 1499 1003 5470 1815 1503 998 5471 1813 1498 998 5472 1813 1498 1003 5473 1815 1503 1002 5474 1812 1502 995 5475 1817 1495 996 5476 1819 1496 994 5477 1816 1494 996 5478 1819 1496 995 5479 1817 1495 997 5480 1818 1497 997 5481 1818 1497 998 5482 1813 1498 996 5483 1819 1496 998 5484 1813 1498 997 5485 1818 1497 999 5486 1814 1499 1004 5487 1820 1504 1005 5488 1821 1505 1010 5489 1822 1510 1010 5490 1822 1510 1011 5491 1823 1511 1004 5492 1820 1504 1018 5493 1827 1518 1019 5494 1824 1519 1013 5495 1826 1513 1019 5496 1824 1519 1012 5497 1825 1512 1013 5498 1826 1513 1016 5499 1829 1516 1017 5500 1830 1517 1015 5501 1828 1515 1015 5502 1828 1515 1017 5503 1830 1517 1014 5504 1831 1514 1006 5505 1833 1506 1007 5506 1834 1507 1008 5507 1835 1508 1008 5508 1835 1508 1009 5509 1832 1509 1006 5510 1833 1506 1017 5511 1830 1517 1018 5512 1827 1518 1014 5513 1831 1514 1014 5514 1831 1514 1018 5515 1827 1518 1013 5516 1826 1513 1005 5517 1821 1505 1006 5518 1833 1506 1009 5519 1832 1509 1009 5520 1832 1509 1010 5521 1822 1510 1005 5522 1821 1505 1000 5523 1836 1500 992 5524 1837 1492 1004 5525 1820 1504 1004 5526 1820 1504 992 5527 1837 1492 1005 5528 1821 1505 992 5529 1837 1492 991 5530 1838 1491 1005 5531 1821 1505 1006 5532 1833 1506 1005 5533 1821 1505 991 5534 1838 1491 991 5535 1838 1491 988 5536 1839 1488 1006 5537 1833 1506 1007 5538 1834 1507 1006 5539 1833 1506 988 5540 1839 1488 994 5541 1846 1494 1008 5542 1863 1508 1007 5543 1862 1507 1007 5544 1862 1507 988 5545 1865 1488 994 5546 1846 1494 1009 5547 1854 1509 1008 5548 1855 1508 994 5549 1816 1494 1009 5550 1854 1509 994 5551 1816 1494 996 5552 1819 1496 1010 5553 1848 1510 1009 5554 1854 1509 996 5555 1819 1496 1010 5556 1848 1510 996 5557 1819 1496 998 5558 1813 1498 998 5559 1813 1498 1011 5560 1849 1511 1010 5561 1848 1510 1011 5562 1849 1511 998 5563 1813 1498 1002 5564 1812 1502 1003 5565 1815 1503 999 5566 1814 1499 1012 5567 1850 1512 1012 5568 1850 1512 999 5569 1814 1499 1013 5570 1851 1513 999 5571 1814 1499 997 5572 1818 1497 1013 5573 1851 1513 1014 5574 1853 1514 1013 5575 1851 1513 997 5576 1818 1497 997 5577 1818 1497 995 5578 1817 1495 1014 5579 1853 1514 1015 5580 1852 1515 1014 5581 1853 1514 995 5582 1817 1495 1015 5583 1860 1515 995 5584 1847 1495 1016 5585 1861 1516 989 5586 1840 1489 1016 5587 1861 1516 995 5588 1847 1495 1017 5589 1830 1517 1016 5590 1829 1516 989 5591 1866 1489 1017 5592 1830 1517 989 5593 1866 1489 990 5594 1841 1490 1018 5595 1827 1518 1017 5596 1830 1517 990 5597 1841 1490 1018 5598 1827 1518 990 5599 1841 1490 993 5600 1842 1493 993 5601 1842 1493 1019 5602 1824 1519 1018 5603 1827 1518 1019 5604 1824 1519 993 5605 1842 1493 1001 5606 1843 1501 1001 5607 1843 1501 992 5608 1837 1492 1000 5609 1836 1500 992 5610 1837 1492 1001 5611 1843 1501 993 5612 1842 1493 993 5613 1842 1493 990 5614 1841 1490 992 5615 1837 1492 992 5616 1837 1492 990 5617 1841 1490 991 5618 1838 1491 990 5619 1841 1490 989 5620 1866 1489 991 5621 1838 1491 991 5622 1838 1491 989 5623 1866 1489 988 5624 1839 1488 988 5625 1865 1488 995 5626 1847 1495 994 5627 1846 1494 995 5628 1847 1495 988 5629 1865 1488 989 5630 1840 1489 1001 5631 1867 1501 1002 5632 1844 1502 1003 5633 1845 1503 1002 5634 1844 1502 1001 5635 1867 1501 1000 5636 1864 1500 1019 5637 1858 1519 1003 5638 1845 1503 1012 5639 1859 1512 1019 5640 1858 1519 1001 5641 1867 1501 1003 5642 1845 1503 1011 5643 1857 1511 1002 5644 1844 1502 1004 5645 1856 1504 1000 5646 1864 1500 1004 5647 1856 1504 1002 5648 1844 1502

+
+
+
+ + + + + + + + + 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 1.0000001.000000 + 30.0000000.0000003.333333 + + + + + +
diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_PalletJackB_01/model.config b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_PalletJackB_01/model.config new file mode 100755 index 0000000..5838110 --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_PalletJackB_01/model.config @@ -0,0 +1,11 @@ + + + aws_robomaker_warehouse_PalletJackB_01 + 1.0 + model.sdf + + + + + + diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_PalletJackB_01/model.sdf b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_PalletJackB_01/model.sdf new file mode 100755 index 0000000..72547b0 --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_PalletJackB_01/model.sdf @@ -0,0 +1,46 @@ + + + + + + 2 + + 0.277 + 0 + 0 + 0.452 + 0 + 0.268 + + + + + + model://aws_robomaker_warehouse_PalletJackB_01/meshes/aws_robomaker_warehouse_PalletJackB_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + model://aws_robomaker_warehouse_PalletJackB_01/meshes/aws_robomaker_warehouse_PalletJackB_01_visual.DAE + + + 1 + + +1 + + diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_RoofB_01/materials/textures/aws_robomaker_warehouse_RoofB_01.png b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_RoofB_01/materials/textures/aws_robomaker_warehouse_RoofB_01.png new file mode 100755 index 0000000..9e4dd9c Binary files /dev/null and b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_RoofB_01/materials/textures/aws_robomaker_warehouse_RoofB_01.png differ diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_RoofB_01/meshes/aws_robomaker_warehouse_RoofB_01_collision.DAE b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_RoofB_01/meshes/aws_robomaker_warehouse_RoofB_01_collision.DAE new file mode 100755 index 0000000..558a316 --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_RoofB_01/meshes/aws_robomaker_warehouse_RoofB_01_collision.DAE @@ -0,0 +1,123 @@ + + + FBX COLLADA exporter2019-06-03T07:07:22Z2019-06-03T07:07:22ZZ_UP + + + + + +-686.312866 -88.698654 -1045.333374 +711.734131 -88.698654 -1045.333374 +-686.312866 21.739517 -1045.333496 +711.734131 21.739517 -1045.333496 +-686.312866 -88.698593 1045.333008 +711.734131 -88.698593 1045.333008 +-686.312866 21.739578 1045.333008 +711.734131 21.739578 1045.333008 + + + + + + + + + + + +0.000000 -0.000001 -1.000000 +0.000000 -0.000001 -1.000000 +0.000000 -0.000001 -1.000000 +0.000000 -0.000001 -1.000000 +0.000000 -0.000001 -1.000000 +0.000000 -0.000001 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 + + + + + + + + + + + +1.000000 0.000000 +0.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 + + + + + + + + + + + +

2 0 2 3 1 3 0 2 0 1 3 1 0 4 0 3 5 3 7 6 7 6 7 6 4 8 4 7 9 7 4 10 4 5 11 5 5 12 11 4 13 10 0 14 8 5 15 11 0 16 8 1 17 9 5 18 14 1 19 12 7 20 15 7 21 15 1 22 12 3 23 13 6 24 19 7 25 18 3 26 16 6 27 19 3 28 16 2 29 17 6 30 22 0 31 21 4 32 23 0 33 21 6 34 22 2 35 20

+
+
+
+ + + 1.000000 0.000000 0.000000 -12.710449 0.000000 -0.000000 -1.000000 0.000000 0.000000 1.000000 -0.000000 990.684692 0.000000 0.000000 0.000000 1.0000001.000000 + 30.0000000.0000003.333333 + + + + + +
diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_RoofB_01/meshes/aws_robomaker_warehouse_RoofB_01_visual.DAE b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_RoofB_01/meshes/aws_robomaker_warehouse_RoofB_01_visual.DAE new file mode 100755 index 0000000..4cab933 --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_RoofB_01/meshes/aws_robomaker_warehouse_RoofB_01_visual.DAE @@ -0,0 +1,6734 @@ + + + FBX COLLADA exporter2019-06-03T07:06:51Z2019-06-03T07:06:51ZZ_UP + + + ../materials/textures/aws_robomaker_warehouse_RoofB_01.png + + + + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + +685.143066 1032.083740 901.985962 +699.023682 1045.333252 901.985962 +699.023682 1045.333252 957.578247 +685.143066 1032.083740 957.578247 +-699.023315 1045.333130 901.985962 +-699.023315 1045.333130 957.578247 +-686.135193 1032.083618 901.985962 +-686.135132 1032.083618 957.578247 +685.143066 -1032.083618 901.985962 +685.143066 -1032.083618 957.578247 +699.023682 -1045.333130 901.985962 +699.023682 -1045.333130 957.578247 +-686.135132 -1032.083618 957.578247 +-686.135132 -1032.083618 901.985962 +-699.023315 -1045.333130 957.578247 +-699.023315 -1045.333130 901.985962 +-0.496077 1032.083740 901.985962 +-0.496077 1045.333252 901.985962 +6.160819 1045.333252 995.633362 +-7.152973 1045.333130 995.633362 +-7.152973 1032.083618 995.633362 +6.160819 1032.083740 995.633362 +6.160905 -1045.333130 995.633362 +-7.152886 -1045.333130 995.633362 +-0.495991 -1045.333130 901.985962 +6.160905 -1032.083618 995.633362 +-7.152886 -1032.083618 995.633362 +-0.495991 -1032.083618 901.985962 +697.140503 321.945190 953.600037 +697.140503 321.945190 901.985962 +697.140503 335.194702 953.600037 +6.811340 321.945190 980.703552 +6.811329 321.945190 913.078613 +6.811329 335.194702 913.078613 +6.811340 335.194702 980.703552 +6.811340 335.194702 991.655212 +687.966919 321.945190 943.338684 +687.966919 321.945190 913.078613 +697.140503 335.194702 901.985962 +687.966919 335.194702 913.078613 +687.966919 335.194702 943.338684 +171.275497 321.945190 913.078613 +341.564392 321.945190 913.078613 +523.502747 321.945190 913.078613 +171.284241 335.194702 971.681396 +341.573151 335.194702 962.340149 +523.493958 335.194702 952.360901 +523.494019 321.945190 952.360840 +353.205109 321.945190 961.702087 +171.284271 321.945190 971.681335 +523.502747 335.194702 913.078613 +341.564392 335.194702 913.078613 +171.275497 335.194702 913.078613 +177.100189 335.194702 982.293396 +517.677979 321.945190 963.569702 +182.924942 321.945190 913.078613 +353.213867 321.945190 913.078613 +511.853302 321.945190 913.078613 +347.389130 335.194702 901.985962 +182.916199 335.194702 971.043335 +353.205109 335.194702 961.702087 +511.862000 335.194702 952.998962 +511.862061 321.945190 952.998901 +341.573151 321.945190 962.340149 +182.916229 321.945190 971.043274 +347.389130 321.945190 901.985962 +511.853302 335.194702 913.078613 +353.213867 335.194702 913.078613 +182.924942 335.194702 913.078613 +517.677979 335.194702 963.569702 +177.100189 321.945190 982.293396 +160.662079 321.945190 913.078613 +176.974945 335.194702 901.986023 +17.425293 335.194702 980.121338 +677.352905 321.945190 943.920898 +517.803345 321.945190 901.986023 +534.116150 335.194702 913.078613 +193.162476 321.945190 913.078613 +501.615784 321.945190 913.078613 +534.116150 321.945190 913.078613 +517.803345 335.194702 901.986023 +331.334473 335.194702 962.901794 +363.443787 335.194702 961.140442 +677.352905 335.194702 943.920898 +363.443787 321.945190 961.140442 +331.334473 321.945190 962.901794 +17.425323 321.945190 980.121338 +176.974945 321.945190 901.986023 +501.615784 335.194702 913.078613 +193.162476 335.194702 913.078613 +160.662079 335.194702 913.078613 +347.389099 335.194702 972.931580 +347.389099 321.945190 972.931580 +6.811340 321.945190 991.655212 +0.000061 335.194702 980.703552 +0.000061 321.945190 980.703552 +0.000061 335.194702 901.985962 +0.000061 321.945190 991.655212 +0.000061 335.194702 902.739136 +0.000061 321.945190 901.985962 +-697.140381 321.945190 901.985962 +-697.140381 321.945190 953.600037 +-687.966797 321.945190 943.338684 +-687.966797 321.945190 913.078613 +-697.140381 335.194702 901.985962 +-697.140381 335.194702 953.600037 +-687.966797 335.194702 913.078613 +-687.966797 335.194702 943.338684 +-6.811218 321.945190 980.703552 +0.000061 321.945190 913.078613 +-6.811207 321.945190 913.078613 +-6.811207 335.194702 913.078613 +0.000061 335.194702 913.078613 +-6.811218 335.194702 980.703552 +-6.811218 321.945190 991.655212 +-176.974823 321.945190 901.986023 +-347.389008 321.945190 901.985962 +-341.564270 321.945190 913.078613 +-193.162354 321.945190 913.078613 +-347.388977 335.194702 972.931580 +-331.334351 335.194702 962.901794 +-182.916077 335.194702 971.043335 +-177.100067 335.194702 982.293396 +-517.803223 321.945190 901.986023 +-347.389008 335.194702 901.985962 +-517.803223 335.194702 901.986023 +-347.388977 321.945190 972.931580 +-363.443665 321.945190 961.140442 +-511.861938 321.945190 952.998901 +-517.677856 321.945190 963.569702 +-353.213745 335.194702 913.078613 +-501.615662 335.194702 913.078613 +-534.116028 321.945190 913.078613 +-501.615662 321.945190 913.078613 +-353.213745 321.945190 913.078613 +-160.661957 321.945190 913.078613 +0.000061 321.945190 902.739136 +-677.352783 335.194702 943.920898 +-523.493835 335.194702 952.360901 +-517.677856 335.194702 963.569702 +-511.861877 335.194702 952.998962 +-363.443665 335.194702 961.140442 +-17.425171 335.194702 980.121338 +-6.811218 335.194702 991.655212 +-171.284119 335.194702 971.681396 +-176.974823 335.194702 901.986023 +-17.425201 321.945190 980.121338 +-171.284149 321.945190 971.681335 +-177.100067 321.945190 982.293396 +-182.916107 321.945190 971.043274 +-331.334351 321.945190 962.901794 +-677.352783 321.945190 943.920898 +-523.493896 321.945190 952.360840 +-160.661957 335.194702 913.078613 +-193.162354 335.194702 913.078613 +-341.564270 335.194702 913.078613 +-534.116028 335.194702 913.078613 +-523.502625 321.945190 913.078613 +-511.853180 321.945190 913.078613 +-182.924820 321.945190 913.078613 +-171.275375 321.945190 913.078613 +-353.204987 335.194702 961.702087 +-341.573029 335.194702 962.340149 +-353.204987 321.945190 961.702087 +-341.573029 321.945190 962.340149 +-182.924820 335.194702 913.078613 +-171.275375 335.194702 913.078613 +-523.502625 335.194702 913.078613 +-511.853180 335.194702 913.078613 +0.000061 335.194702 991.655212 +697.140503 -355.069092 953.600037 +697.140503 -355.069092 901.985962 +697.140503 -341.819580 953.600037 +6.811340 -355.069092 980.703552 +6.811329 -355.069092 913.078613 +6.811329 -341.819580 913.078613 +6.811340 -341.819580 980.703552 +6.811340 -341.819580 991.655212 +687.966919 -355.069092 943.338684 +687.966919 -355.069092 913.078613 +697.140503 -341.819580 901.985962 +687.966919 -341.819580 913.078613 +687.966919 -341.819580 943.338684 +171.275497 -355.069092 913.078613 +341.564392 -355.069092 913.078613 +523.502747 -355.069092 913.078613 +171.284241 -341.819580 971.681396 +341.573151 -341.819580 962.340149 +523.493958 -341.819580 952.360901 +523.494019 -355.069092 952.360840 +353.205109 -355.069092 961.702087 +171.284271 -355.069092 971.681335 +523.502747 -341.819580 913.078613 +341.564392 -341.819580 913.078613 +171.275497 -341.819580 913.078613 +177.100189 -341.819580 982.293396 +517.677979 -355.069092 963.569702 +182.924942 -355.069092 913.078613 +353.213867 -355.069092 913.078613 +511.853302 -355.069092 913.078613 +347.389130 -341.819580 901.985962 +182.916199 -341.819580 971.043335 +353.205109 -341.819580 961.702087 +511.862000 -341.819580 952.998962 +511.862061 -355.069092 952.998901 +341.573151 -355.069092 962.340149 +182.916229 -355.069092 971.043274 +347.389130 -355.069092 901.985962 +511.853302 -341.819580 913.078613 +353.213867 -341.819580 913.078613 +182.924942 -341.819580 913.078613 +517.677979 -341.819580 963.569702 +177.100189 -355.069092 982.293396 +160.662079 -355.069092 913.078613 +176.974945 -341.819580 901.986023 +17.425293 -341.819580 980.121338 +677.352905 -355.069092 943.920898 +517.803345 -355.069092 901.986023 +534.116150 -341.819580 913.078613 +193.162476 -355.069092 913.078613 +501.615784 -355.069092 913.078613 +534.116150 -355.069092 913.078613 +517.803345 -341.819580 901.986023 +331.334473 -341.819580 962.901794 +363.443787 -341.819580 961.140442 +677.352905 -341.819580 943.920898 +363.443787 -355.069092 961.140442 +331.334473 -355.069092 962.901794 +17.425323 -355.069092 980.121338 +176.974945 -355.069092 901.986023 +501.615784 -341.819580 913.078613 +193.162476 -341.819580 913.078613 +160.662079 -341.819580 913.078613 +347.389099 -341.819580 972.931580 +347.389099 -355.069092 972.931580 +6.811340 -355.069092 991.655212 +0.000061 -341.819580 980.703552 +0.000061 -355.069092 980.703552 +0.000061 -341.819580 901.985962 +0.000061 -355.069092 991.655212 +0.000061 -341.819580 902.739136 +0.000061 -355.069092 901.985962 +-697.140381 -355.069092 901.985962 +-697.140381 -355.069092 953.600037 +-687.966797 -355.069092 943.338684 +-687.966797 -355.069092 913.078613 +-697.140381 -341.819580 901.985962 +-697.140381 -341.819580 953.600037 +-687.966797 -341.819580 913.078613 +-687.966797 -341.819580 943.338684 +-6.811218 -355.069092 980.703552 +0.000061 -355.069092 913.078613 +-6.811207 -355.069092 913.078613 +-6.811207 -341.819580 913.078613 +0.000061 -341.819580 913.078613 +-6.811218 -341.819580 980.703552 +-6.811218 -355.069092 991.655212 +-176.974823 -355.069092 901.986023 +-347.389008 -355.069092 901.985962 +-341.564270 -355.069092 913.078613 +-193.162354 -355.069092 913.078613 +-347.388977 -341.819580 972.931580 +-331.334351 -341.819580 962.901794 +-182.916077 -341.819580 971.043335 +-177.100067 -341.819580 982.293396 +-517.803223 -355.069092 901.986023 +-347.389008 -341.819580 901.985962 +-517.803223 -341.819580 901.986023 +-347.388977 -355.069092 972.931580 +-363.443665 -355.069092 961.140442 +-511.861938 -355.069092 952.998901 +-517.677856 -355.069092 963.569702 +-353.213745 -341.819580 913.078613 +-501.615662 -341.819580 913.078613 +-534.116028 -355.069092 913.078613 +-501.615662 -355.069092 913.078613 +-353.213745 -355.069092 913.078613 +-160.661957 -355.069092 913.078613 +0.000061 -355.069092 902.739136 +-677.352783 -341.819580 943.920898 +-523.493835 -341.819580 952.360901 +-517.677856 -341.819580 963.569702 +-511.861877 -341.819580 952.998962 +-363.443665 -341.819580 961.140442 +-17.425171 -341.819580 980.121338 +-6.811218 -341.819580 991.655212 +-171.284119 -341.819580 971.681396 +-176.974823 -341.819580 901.986023 +-17.425201 -355.069092 980.121338 +-171.284149 -355.069092 971.681335 +-177.100067 -355.069092 982.293396 +-182.916107 -355.069092 971.043274 +-331.334351 -355.069092 962.901794 +-677.352783 -355.069092 943.920898 +-523.493896 -355.069092 952.360840 +-160.661957 -341.819580 913.078613 +-193.162354 -341.819580 913.078613 +-341.564270 -341.819580 913.078613 +-534.116028 -341.819580 913.078613 +-523.502625 -355.069092 913.078613 +-511.853180 -355.069092 913.078613 +-182.924820 -355.069092 913.078613 +-171.275375 -355.069092 913.078613 +-353.204987 -341.819580 961.702087 +-341.573029 -341.819580 962.340149 +-353.204987 -355.069092 961.702087 +-341.573029 -355.069092 962.340149 +-182.924820 -341.819580 913.078613 +-171.275375 -341.819580 913.078613 +-523.502625 -341.819580 913.078613 +-511.853180 -341.819580 913.078613 +0.000061 -341.819580 991.655212 +697.140503 -1032.083496 953.600037 +697.140503 -1032.083496 901.985962 +697.140503 -1018.833984 953.600037 +6.811340 -1032.083496 980.703552 +6.811329 -1032.083496 913.078613 +6.811329 -1018.833984 913.078613 +6.811340 -1018.833984 980.703552 +6.811340 -1018.833984 991.655212 +687.966919 -1032.083496 943.338684 +687.966919 -1032.083496 913.078613 +697.140503 -1018.833984 901.985962 +687.966919 -1018.833984 913.078613 +687.966919 -1018.833984 943.338684 +171.275497 -1032.083496 913.078613 +341.564392 -1032.083496 913.078613 +523.502747 -1032.083496 913.078613 +171.284241 -1018.833984 971.681396 +341.573151 -1018.833984 962.340149 +523.493958 -1018.833984 952.360901 +523.494019 -1032.083496 952.360840 +353.205109 -1032.083496 961.702087 +171.284271 -1032.083496 971.681335 +523.502747 -1018.833984 913.078613 +341.564392 -1018.833984 913.078613 +171.275497 -1018.833984 913.078613 +177.100189 -1018.833984 982.293396 +517.677979 -1032.083496 963.569702 +182.924942 -1032.083496 913.078613 +353.213867 -1032.083496 913.078613 +511.853302 -1032.083496 913.078613 +347.389130 -1018.833984 901.985962 +182.916199 -1018.833984 971.043335 +353.205109 -1018.833984 961.702087 +511.862000 -1018.833984 952.998962 +511.862061 -1032.083496 952.998901 +341.573151 -1032.083496 962.340149 +182.916229 -1032.083496 971.043274 +347.389130 -1032.083496 901.985962 +511.853302 -1018.833984 913.078613 +353.213867 -1018.833984 913.078613 +182.924942 -1018.833984 913.078613 +517.677979 -1018.833984 963.569702 +177.100189 -1032.083496 982.293396 +160.662079 -1032.083496 913.078613 +176.974945 -1018.833984 901.986023 +17.425293 -1018.833984 980.121338 +677.352905 -1032.083496 943.920898 +517.803345 -1032.083496 901.986023 +534.116150 -1018.833984 913.078613 +193.162476 -1032.083496 913.078613 +501.615784 -1032.083496 913.078613 +534.116150 -1032.083496 913.078613 +517.803345 -1018.833984 901.986023 +331.334473 -1018.833984 962.901794 +363.443787 -1018.833984 961.140442 +677.352905 -1018.833984 943.920898 +363.443787 -1032.083496 961.140442 +331.334473 -1032.083496 962.901794 +17.425323 -1032.083496 980.121338 +176.974945 -1032.083496 901.986023 +501.615784 -1018.833984 913.078613 +193.162476 -1018.833984 913.078613 +160.662079 -1018.833984 913.078613 +347.389099 -1018.833984 972.931580 +347.389099 -1032.083496 972.931580 +6.811340 -1032.083496 991.655212 +0.000061 -1018.833984 980.703552 +0.000061 -1032.083496 980.703552 +0.000061 -1018.833984 901.985962 +0.000061 -1032.083496 991.655212 +0.000061 -1018.833984 902.739136 +0.000061 -1032.083496 901.985962 +-697.140381 -1032.083496 901.985962 +-697.140381 -1032.083496 953.600037 +-687.966797 -1032.083496 943.338684 +-687.966797 -1032.083496 913.078613 +-697.140381 -1018.833984 901.985962 +-697.140381 -1018.833984 953.600037 +-687.966797 -1018.833984 913.078613 +-687.966797 -1018.833984 943.338684 +-6.811218 -1032.083496 980.703552 +0.000061 -1032.083496 913.078613 +-6.811207 -1032.083496 913.078613 +-6.811207 -1018.833984 913.078613 +0.000061 -1018.833984 913.078613 +-6.811218 -1018.833984 980.703552 +-6.811218 -1032.083496 991.655212 +-176.974823 -1032.083496 901.986023 +-347.389008 -1032.083496 901.985962 +-341.564270 -1032.083496 913.078613 +-193.162354 -1032.083496 913.078613 +-347.388977 -1018.833984 972.931580 +-331.334351 -1018.833984 962.901794 +-182.916077 -1018.833984 971.043335 +-177.100067 -1018.833984 982.293396 +-517.803223 -1032.083496 901.986023 +-347.389008 -1018.833984 901.985962 +-517.803223 -1018.833984 901.986023 +-347.388977 -1032.083496 972.931580 +-363.443665 -1032.083496 961.140442 +-511.861938 -1032.083496 952.998901 +-517.677856 -1032.083496 963.569702 +-353.213745 -1018.833984 913.078613 +-501.615662 -1018.833984 913.078613 +-534.116028 -1032.083496 913.078613 +-501.615662 -1032.083496 913.078613 +-353.213745 -1032.083496 913.078613 +-160.661957 -1032.083496 913.078613 +0.000061 -1032.083496 902.739136 +-677.352783 -1018.833984 943.920898 +-523.493835 -1018.833984 952.360901 +-517.677856 -1018.833984 963.569702 +-511.861877 -1018.833984 952.998962 +-363.443665 -1018.833984 961.140442 +-17.425171 -1018.833984 980.121338 +-6.811218 -1018.833984 991.655212 +-171.284119 -1018.833984 971.681396 +-176.974823 -1018.833984 901.986023 +-17.425201 -1032.083496 980.121338 +-171.284149 -1032.083496 971.681335 +-177.100067 -1032.083496 982.293396 +-182.916107 -1032.083496 971.043274 +-331.334351 -1032.083496 962.901794 +-677.352783 -1032.083496 943.920898 +-523.493896 -1032.083496 952.360840 +-160.661957 -1018.833984 913.078613 +-193.162354 -1018.833984 913.078613 +-341.564270 -1018.833984 913.078613 +-534.116028 -1018.833984 913.078613 +-523.502625 -1032.083496 913.078613 +-511.853180 -1032.083496 913.078613 +-182.924820 -1032.083496 913.078613 +-171.275375 -1032.083496 913.078613 +-353.204987 -1018.833984 961.702087 +-341.573029 -1018.833984 962.340149 +-353.204987 -1032.083496 961.702087 +-341.573029 -1032.083496 962.340149 +-182.924820 -1018.833984 913.078613 +-171.275375 -1018.833984 913.078613 +-523.502625 -1018.833984 913.078613 +-511.853180 -1018.833984 913.078613 +0.000061 -1018.833984 991.655212 +697.140503 1018.834229 953.600037 +697.140503 1018.834229 901.985962 +697.140503 1032.083740 953.600037 +6.811340 1018.834229 980.703552 +6.811329 1018.834229 913.078613 +6.811329 1032.083740 913.078613 +6.811340 1032.083740 980.703552 +6.811340 1032.083740 991.655212 +687.966919 1018.834229 943.338684 +687.966919 1018.834229 913.078613 +697.140503 1032.083740 901.985962 +687.966919 1032.083740 913.078613 +687.966919 1032.083740 943.338684 +171.275497 1018.834229 913.078613 +341.564392 1018.834229 913.078613 +523.502747 1018.834229 913.078613 +171.284241 1032.083740 971.681396 +341.573151 1032.083740 962.340149 +523.493958 1032.083740 952.360901 +523.494019 1018.834229 952.360840 +353.205109 1018.834229 961.702087 +171.284271 1018.834229 971.681335 +523.502747 1032.083740 913.078613 +341.564392 1032.083740 913.078613 +171.275497 1032.083740 913.078613 +177.100189 1032.083740 982.293396 +517.677979 1018.834229 963.569702 +182.924942 1018.834229 913.078613 +353.213867 1018.834229 913.078613 +511.853302 1018.834229 913.078613 +347.389130 1032.083740 901.985962 +182.916199 1032.083740 971.043335 +353.205109 1032.083740 961.702087 +511.862000 1032.083740 952.998962 +511.862061 1018.834229 952.998901 +341.573151 1018.834229 962.340149 +182.916229 1018.834229 971.043274 +347.389130 1018.834229 901.985962 +511.853302 1032.083740 913.078613 +353.213867 1032.083740 913.078613 +182.924942 1032.083740 913.078613 +517.677979 1032.083740 963.569702 +177.100189 1018.834229 982.293396 +160.662079 1018.834229 913.078613 +176.974945 1032.083740 901.986023 +17.425293 1032.083740 980.121338 +677.352905 1018.834229 943.920898 +517.803345 1018.834229 901.986023 +534.116150 1032.083740 913.078613 +193.162476 1018.834229 913.078613 +501.615784 1018.834229 913.078613 +534.116150 1018.834229 913.078613 +517.803345 1032.083740 901.986023 +331.334473 1032.083740 962.901794 +363.443787 1032.083740 961.140442 +677.352905 1032.083740 943.920898 +363.443787 1018.834229 961.140442 +331.334473 1018.834229 962.901794 +17.425323 1018.834229 980.121338 +176.974945 1018.834229 901.986023 +501.615784 1032.083740 913.078613 +193.162476 1032.083740 913.078613 +160.662079 1032.083740 913.078613 +347.389099 1032.083740 972.931580 +347.389099 1018.834229 972.931580 +6.811340 1018.834229 991.655212 +0.000061 1032.083740 980.703552 +0.000061 1018.834229 980.703552 +0.000061 1032.083740 901.985962 +0.000061 1018.834229 991.655212 +0.000061 1032.083740 902.739136 +0.000061 1018.834229 901.985962 +-697.140381 1018.834229 901.985962 +-697.140381 1018.834229 953.600037 +-687.966797 1018.834229 943.338684 +-687.966797 1018.834229 913.078613 +-697.140381 1032.083740 901.985962 +-697.140381 1032.083740 953.600037 +-687.966797 1032.083740 913.078613 +-687.966797 1032.083740 943.338684 +-6.811218 1018.834229 980.703552 +0.000061 1018.834229 913.078613 +-6.811207 1018.834229 913.078613 +-6.811207 1032.083740 913.078613 +0.000061 1032.083740 913.078613 +-6.811218 1032.083740 980.703552 +-6.811218 1018.834229 991.655212 +-176.974823 1018.834229 901.986023 +-347.389008 1018.834229 901.985962 +-341.564270 1018.834229 913.078613 +-193.162354 1018.834229 913.078613 +-347.388977 1032.083740 972.931580 +-331.334351 1032.083740 962.901794 +-182.916077 1032.083740 971.043335 +-177.100067 1032.083740 982.293396 +-517.803223 1018.834229 901.986023 +-347.389008 1032.083740 901.985962 +-517.803223 1032.083740 901.986023 +-347.388977 1018.834229 972.931580 +-363.443665 1018.834229 961.140442 +-511.861938 1018.834229 952.998901 +-517.677856 1018.834229 963.569702 +-353.213745 1032.083740 913.078613 +-501.615662 1032.083740 913.078613 +-534.116028 1018.834229 913.078613 +-501.615662 1018.834229 913.078613 +-353.213745 1018.834229 913.078613 +-160.661957 1018.834229 913.078613 +0.000061 1018.834229 902.739136 +-677.352783 1032.083740 943.920898 +-523.493835 1032.083740 952.360901 +-517.677856 1032.083740 963.569702 +-511.861877 1032.083740 952.998962 +-363.443665 1032.083740 961.140442 +-17.425171 1032.083740 980.121338 +-6.811218 1032.083740 991.655212 +-171.284119 1032.083740 971.681396 +-176.974823 1032.083740 901.986023 +-17.425201 1018.834229 980.121338 +-171.284149 1018.834229 971.681335 +-177.100067 1018.834229 982.293396 +-182.916107 1018.834229 971.043274 +-331.334351 1018.834229 962.901794 +-677.352783 1018.834229 943.920898 +-523.493896 1018.834229 952.360840 +-160.661957 1032.083740 913.078613 +-193.162354 1032.083740 913.078613 +-341.564270 1032.083740 913.078613 +-534.116028 1032.083740 913.078613 +-523.502625 1018.834229 913.078613 +-511.853180 1018.834229 913.078613 +-182.924820 1018.834229 913.078613 +-171.275375 1018.834229 913.078613 +-353.204987 1032.083740 961.702087 +-341.573029 1032.083740 962.340149 +-353.204987 1018.834229 961.702087 +-341.573029 1018.834229 962.340149 +-182.924820 1032.083740 913.078613 +-171.275375 1032.083740 913.078613 +-523.502625 1032.083740 913.078613 +-511.853180 1032.083740 913.078613 +0.000061 1032.083740 991.655212 +699.023682 -1045.333130 974.369080 +699.023682 1045.333130 974.369080 +-0.495991 1045.333130 1012.424255 +-0.495991 -1045.333130 1012.424255 +-699.023315 1045.333130 974.369080 +-699.023315 -1045.333130 974.369080 +699.023682 -1045.333130 953.385437 +699.023682 1045.333130 953.385437 +-0.495991 1045.333130 991.440613 +-0.495991 -1045.333130 991.440613 +-699.023315 1045.333130 953.385437 +-699.023315 -1045.333130 953.385437 +279.078979 518.069458 973.521423 +667.904297 518.069458 951.750305 +279.078979 561.112915 973.521423 +667.904297 561.112915 951.750305 +279.078979 518.069458 983.949829 +667.904297 518.069458 962.178711 +279.078979 561.112915 983.949829 +667.904297 561.112915 962.178711 +279.078979 539.591187 966.960938 +667.904297 539.591187 945.189819 +667.904297 539.591187 962.178711 +279.078979 539.591187 983.949829 +-279.078979 518.069458 973.521423 +-279.078979 539.591187 966.960938 +-667.904358 539.591187 945.189819 +-667.904358 518.069458 951.750305 +-667.904358 518.069458 962.178711 +-279.078979 518.069458 983.949829 +-667.904358 539.591187 962.178711 +-667.904358 561.112915 951.750305 +-279.078979 561.112915 973.521423 +-279.078979 561.112915 983.949829 +-667.904358 561.112915 962.178711 +-279.078979 539.591187 983.949829 +279.078979 -518.069458 973.521423 +279.078979 -539.591187 966.960938 +667.904297 -539.591187 945.189819 +667.904297 -518.069458 951.750305 +667.904297 -518.069458 962.178711 +279.078979 -518.069458 983.949829 +667.904297 -539.591187 962.178711 +667.904297 -561.112915 951.750305 +279.078979 -561.112915 973.521423 +279.078979 -561.112915 983.949829 +667.904297 -561.112915 962.178711 +279.078979 -539.591187 983.949829 +-279.078979 -518.069458 973.521423 +-667.904358 -518.069458 951.750305 +-667.904358 -539.591187 945.189819 +-279.078979 -539.591187 966.960938 +-279.078979 -518.069458 983.949829 +-667.904358 -518.069458 962.178711 +-667.904358 -539.591187 962.178711 +-667.904358 -561.112915 951.750305 +-667.904358 -561.112915 962.178711 +-279.078979 -561.112915 983.949829 +-279.078979 -561.112915 973.521423 +-279.078979 -539.591187 983.949829 +234.788025 1040.947998 975.133057 +261.869507 1040.947998 975.133057 +234.788025 1040.947632 982.615479 +261.869507 1040.947632 982.615479 +234.788025 -1039.386475 975.132690 +261.869507 -1039.386475 975.132690 +234.788025 -1039.387085 982.615112 +261.869507 -1039.387085 982.615112 +-234.788025 1040.947998 975.133057 +-234.788025 1040.947632 982.615479 +-261.869507 1040.947632 982.615479 +-261.869507 1040.947998 975.133057 +-234.788025 -1039.386475 975.132690 +-261.869507 -1039.386475 975.132690 +-261.869507 -1039.387085 982.615112 +-234.788025 -1039.387085 982.615112 + + + + + + + + + + + +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.000004 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.000004 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.000000 1.000000 0.000000 +-0.000005 1.000000 0.000001 +-0.000004 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -1.000000 -0.000000 +0.000004 -1.000000 -0.000000 +0.000005 -1.000000 -0.000001 +1.000000 0.000000 -0.000001 +1.000000 0.000000 -0.000001 +1.000000 0.000000 -0.000001 +1.000000 0.000000 -0.000001 +1.000000 0.000000 -0.000001 +1.000000 0.000000 -0.000001 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000005 1.000000 0.000001 +-0.000000 1.000000 0.000001 +-0.000000 1.000000 0.000001 +-0.000000 1.000000 0.000001 +-0.000005 1.000000 0.000001 +-0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000004 -1.000000 -0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000004 -1.000000 -0.000000 +0.000000 -1.000000 -0.000000 +0.000000 -1.000000 -0.000001 +0.000005 -1.000000 -0.000001 +0.000000 -1.000000 -0.000001 +0.000005 -1.000000 -0.000001 +0.000000 -1.000000 -0.000001 +0.000000 -1.000000 -0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 -0.000001 0.000149 +-1.000000 -0.000001 0.000149 +-1.000000 -0.000001 0.000149 +-1.000000 -0.000001 0.000149 +-1.000000 -0.000001 0.000149 +-1.000000 -0.000001 0.000149 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-1.000000 0.000000 0.000178 +-1.000000 0.000000 0.000178 +-1.000000 0.000000 0.000178 +-1.000000 0.000000 0.000178 +-1.000000 0.000000 0.000178 +-1.000000 0.000000 0.000178 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +1.000000 0.000001 0.000151 +1.000000 0.000001 0.000151 +1.000000 0.000001 0.000151 +1.000000 0.000001 0.000151 +1.000000 0.000001 0.000151 +1.000000 0.000001 0.000151 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 -0.000002 0.000219 +-1.000000 -0.000002 0.000219 +-1.000000 -0.000002 0.000219 +-1.000000 -0.000002 0.000219 +-1.000000 -0.000002 0.000219 +-1.000000 -0.000002 0.000219 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +1.000000 0.000000 0.000180 +1.000000 0.000000 0.000180 +1.000000 0.000000 0.000180 +1.000000 0.000000 0.000180 +1.000000 0.000000 0.000180 +1.000000 0.000000 0.000180 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 0.000002 0.000223 +1.000000 0.000002 0.000223 +1.000000 0.000002 0.000223 +1.000000 0.000002 0.000223 +1.000000 0.000002 0.000223 +1.000000 0.000002 0.000223 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.399484 0.000000 0.916740 +0.399484 0.000000 0.916740 +0.399484 0.000000 0.916740 +0.399484 0.000000 0.916740 +0.399484 0.000000 0.916740 +0.399484 0.000000 0.916740 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.402393 0.000000 -0.915467 +-0.402393 0.000000 -0.915467 +-0.402393 0.000000 -0.915467 +-0.402393 0.000000 -0.915467 +-0.402393 0.000000 -0.915467 +-0.402393 0.000000 -0.915467 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.315026 0.000000 -0.949083 +0.315026 0.000000 -0.949083 +0.315026 0.000000 -0.949083 +0.315026 0.000000 -0.949083 +0.315026 0.000000 -0.949083 +0.315026 0.000000 -0.949083 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.318258 0.000000 0.948004 +-0.318258 0.000000 0.948004 +-0.318258 0.000000 0.948004 +-0.318258 0.000000 0.948004 +-0.318258 0.000000 0.948004 +-0.318258 0.000000 0.948004 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.308093 0.000000 0.951356 +0.308093 0.000000 0.951356 +0.308093 0.000000 0.951356 +0.308093 0.000000 0.951356 +0.308093 0.000000 0.951356 +0.308093 0.000000 0.951356 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.311344 0.000000 -0.950297 +-0.311344 0.000000 -0.950297 +-0.311344 0.000000 -0.950297 +-0.311344 0.000000 -0.950297 +-0.311344 0.000000 -0.950297 +-0.311344 0.000000 -0.950297 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.196559 0.000000 0.980492 +-0.196559 0.000000 0.980492 +-0.196559 0.000000 0.980492 +-0.196559 0.000000 0.980492 +-0.196559 0.000000 0.980492 +-0.196559 0.000000 0.980492 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.192987 0.000000 -0.981201 +0.192987 0.000000 -0.981201 +0.192987 0.000000 -0.981201 +0.192987 0.000000 -0.981201 +0.192987 0.000000 -0.981201 +0.192987 0.000000 -0.981201 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 -0.000001 0.000149 +1.000000 -0.000001 0.000149 +1.000000 -0.000001 0.000149 +1.000000 -0.000001 0.000149 +1.000000 -0.000001 0.000149 +1.000000 -0.000001 0.000149 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +1.000000 0.000000 0.000178 +1.000000 0.000000 0.000178 +1.000000 0.000000 0.000178 +1.000000 0.000000 0.000178 +1.000000 0.000000 0.000178 +1.000000 0.000000 0.000178 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +-1.000000 0.000001 0.000151 +-1.000000 0.000001 0.000151 +-1.000000 0.000001 0.000151 +-1.000000 0.000001 0.000151 +-1.000000 0.000001 0.000151 +-1.000000 0.000001 0.000151 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 -0.000002 0.000219 +1.000000 -0.000002 0.000219 +1.000000 -0.000002 0.000219 +1.000000 -0.000002 0.000219 +1.000000 -0.000002 0.000219 +1.000000 -0.000002 0.000219 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +-1.000000 0.000000 0.000180 +-1.000000 0.000000 0.000180 +-1.000000 0.000000 0.000180 +-1.000000 0.000000 0.000180 +-1.000000 0.000000 0.000180 +-1.000000 0.000000 0.000180 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000002 0.000223 +-1.000000 0.000002 0.000223 +-1.000000 0.000002 0.000223 +-1.000000 0.000002 0.000223 +-1.000000 0.000002 0.000223 +-1.000000 0.000002 0.000223 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.399484 0.000000 0.916740 +-0.399484 0.000000 0.916740 +-0.399484 0.000000 0.916740 +-0.399484 0.000000 0.916740 +-0.399484 0.000000 0.916740 +-0.399484 0.000000 0.916740 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.402393 0.000000 -0.915467 +0.402393 0.000000 -0.915467 +0.402393 0.000000 -0.915467 +0.402393 0.000000 -0.915467 +0.402393 0.000000 -0.915467 +0.402393 0.000000 -0.915467 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.315026 0.000000 -0.949083 +-0.315026 0.000000 -0.949083 +-0.315026 0.000000 -0.949083 +-0.315026 0.000000 -0.949083 +-0.315026 0.000000 -0.949083 +-0.315026 0.000000 -0.949083 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.318258 0.000000 0.948004 +0.318258 0.000000 0.948004 +0.318258 0.000000 0.948004 +0.318258 0.000000 0.948004 +0.318258 0.000000 0.948004 +0.318258 0.000000 0.948004 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.308093 0.000000 0.951356 +-0.308093 0.000000 0.951356 +-0.308093 0.000000 0.951356 +-0.308093 0.000000 0.951356 +-0.308093 0.000000 0.951356 +-0.308093 0.000000 0.951356 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.311344 0.000000 -0.950297 +0.311344 0.000000 -0.950297 +0.311344 0.000000 -0.950297 +0.311344 0.000000 -0.950297 +0.311344 0.000000 -0.950297 +0.311344 0.000000 -0.950297 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.196559 0.000000 0.980492 +0.196559 0.000000 0.980492 +0.196559 0.000000 0.980492 +0.196559 0.000000 0.980492 +0.196559 0.000000 0.980492 +0.196559 0.000000 0.980492 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.192987 0.000000 -0.981201 +-0.192987 0.000000 -0.981201 +-0.192987 0.000000 -0.981201 +-0.192987 0.000000 -0.981201 +-0.192987 0.000000 -0.981201 +-0.192987 0.000000 -0.981201 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 -0.000001 0.000149 +-1.000000 -0.000001 0.000149 +-1.000000 -0.000001 0.000149 +-1.000000 -0.000001 0.000149 +-1.000000 -0.000001 0.000149 +-1.000000 -0.000001 0.000149 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-1.000000 0.000000 0.000178 +-1.000000 0.000000 0.000178 +-1.000000 0.000000 0.000178 +-1.000000 0.000000 0.000178 +-1.000000 0.000000 0.000178 +-1.000000 0.000000 0.000178 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +1.000000 0.000001 0.000151 +1.000000 0.000001 0.000151 +1.000000 0.000001 0.000151 +1.000000 0.000001 0.000151 +1.000000 0.000001 0.000151 +1.000000 0.000001 0.000151 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 -0.000002 0.000219 +-1.000000 -0.000002 0.000219 +-1.000000 -0.000002 0.000219 +-1.000000 -0.000002 0.000219 +-1.000000 -0.000002 0.000219 +-1.000000 -0.000002 0.000219 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +1.000000 0.000000 0.000180 +1.000000 0.000000 0.000180 +1.000000 0.000000 0.000180 +1.000000 0.000000 0.000180 +1.000000 0.000000 0.000180 +1.000000 0.000000 0.000180 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 0.000002 0.000223 +1.000000 0.000002 0.000223 +1.000000 0.000002 0.000223 +1.000000 0.000002 0.000223 +1.000000 0.000002 0.000223 +1.000000 0.000002 0.000223 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.399484 0.000000 0.916740 +0.399484 0.000000 0.916740 +0.399484 0.000000 0.916740 +0.399484 0.000000 0.916740 +0.399484 0.000000 0.916740 +0.399484 0.000000 0.916740 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.402393 0.000000 -0.915467 +-0.402393 0.000000 -0.915467 +-0.402393 0.000000 -0.915467 +-0.402393 0.000000 -0.915467 +-0.402393 0.000000 -0.915467 +-0.402393 0.000000 -0.915467 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.315026 0.000000 -0.949083 +0.315026 0.000000 -0.949083 +0.315026 0.000000 -0.949083 +0.315026 0.000000 -0.949083 +0.315026 0.000000 -0.949083 +0.315026 0.000000 -0.949083 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.318258 0.000000 0.948004 +-0.318258 0.000000 0.948004 +-0.318258 0.000000 0.948004 +-0.318258 0.000000 0.948004 +-0.318258 0.000000 0.948004 +-0.318258 0.000000 0.948004 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.308093 0.000000 0.951356 +0.308093 0.000000 0.951356 +0.308093 0.000000 0.951356 +0.308093 0.000000 0.951356 +0.308093 0.000000 0.951356 +0.308093 0.000000 0.951356 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.311344 0.000000 -0.950297 +-0.311344 0.000000 -0.950297 +-0.311344 0.000000 -0.950297 +-0.311344 0.000000 -0.950297 +-0.311344 0.000000 -0.950297 +-0.311344 0.000000 -0.950297 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.196559 0.000000 0.980492 +-0.196559 0.000000 0.980492 +-0.196559 0.000000 0.980492 +-0.196559 0.000000 0.980492 +-0.196559 0.000000 0.980492 +-0.196559 0.000000 0.980492 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.192987 0.000000 -0.981201 +0.192987 0.000000 -0.981201 +0.192987 0.000000 -0.981201 +0.192987 0.000000 -0.981201 +0.192987 0.000000 -0.981201 +0.192987 0.000000 -0.981201 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 -0.000001 0.000149 +1.000000 -0.000001 0.000149 +1.000000 -0.000001 0.000149 +1.000000 -0.000001 0.000149 +1.000000 -0.000001 0.000149 +1.000000 -0.000001 0.000149 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +1.000000 0.000000 0.000178 +1.000000 0.000000 0.000178 +1.000000 0.000000 0.000178 +1.000000 0.000000 0.000178 +1.000000 0.000000 0.000178 +1.000000 0.000000 0.000178 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +-1.000000 0.000001 0.000151 +-1.000000 0.000001 0.000151 +-1.000000 0.000001 0.000151 +-1.000000 0.000001 0.000151 +-1.000000 0.000001 0.000151 +-1.000000 0.000001 0.000151 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 -0.000002 0.000219 +1.000000 -0.000002 0.000219 +1.000000 -0.000002 0.000219 +1.000000 -0.000002 0.000219 +1.000000 -0.000002 0.000219 +1.000000 -0.000002 0.000219 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +-1.000000 0.000000 0.000180 +-1.000000 0.000000 0.000180 +-1.000000 0.000000 0.000180 +-1.000000 0.000000 0.000180 +-1.000000 0.000000 0.000180 +-1.000000 0.000000 0.000180 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000002 0.000223 +-1.000000 0.000002 0.000223 +-1.000000 0.000002 0.000223 +-1.000000 0.000002 0.000223 +-1.000000 0.000002 0.000223 +-1.000000 0.000002 0.000223 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.399484 0.000000 0.916740 +-0.399484 0.000000 0.916740 +-0.399484 0.000000 0.916740 +-0.399484 0.000000 0.916740 +-0.399484 0.000000 0.916740 +-0.399484 0.000000 0.916740 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.402393 0.000000 -0.915467 +0.402393 0.000000 -0.915467 +0.402393 0.000000 -0.915467 +0.402393 0.000000 -0.915467 +0.402393 0.000000 -0.915467 +0.402393 0.000000 -0.915467 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.315026 0.000000 -0.949083 +-0.315026 0.000000 -0.949083 +-0.315026 0.000000 -0.949083 +-0.315026 0.000000 -0.949083 +-0.315026 0.000000 -0.949083 +-0.315026 0.000000 -0.949083 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.318258 0.000000 0.948004 +0.318258 0.000000 0.948004 +0.318258 0.000000 0.948004 +0.318258 0.000000 0.948004 +0.318258 0.000000 0.948004 +0.318258 0.000000 0.948004 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.308093 0.000000 0.951356 +-0.308093 0.000000 0.951356 +-0.308093 0.000000 0.951356 +-0.308093 0.000000 0.951356 +-0.308093 0.000000 0.951356 +-0.308093 0.000000 0.951356 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.311344 0.000000 -0.950297 +0.311344 0.000000 -0.950297 +0.311344 0.000000 -0.950297 +0.311344 0.000000 -0.950297 +0.311344 0.000000 -0.950297 +0.311344 0.000000 -0.950297 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.196559 0.000000 0.980492 +0.196559 0.000000 0.980492 +0.196559 0.000000 0.980492 +0.196559 0.000000 0.980492 +0.196559 0.000000 0.980492 +0.196559 0.000000 0.980492 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.192987 0.000000 -0.981201 +-0.192987 0.000000 -0.981201 +-0.192987 0.000000 -0.981201 +-0.192987 0.000000 -0.981201 +-0.192987 0.000000 -0.981201 +-0.192987 0.000000 -0.981201 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 -0.000001 0.000149 +-1.000000 -0.000001 0.000149 +-1.000000 -0.000001 0.000149 +-1.000000 -0.000001 0.000149 +-1.000000 -0.000001 0.000149 +-1.000000 -0.000001 0.000149 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-1.000000 0.000000 0.000178 +-1.000000 0.000000 0.000178 +-1.000000 0.000000 0.000178 +-1.000000 0.000000 0.000178 +-1.000000 0.000000 0.000178 +-1.000000 0.000000 0.000178 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +1.000000 0.000001 0.000151 +1.000000 0.000001 0.000151 +1.000000 0.000001 0.000151 +1.000000 0.000001 0.000151 +1.000000 0.000001 0.000151 +1.000000 0.000001 0.000151 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 -0.000002 0.000219 +-1.000000 -0.000002 0.000219 +-1.000000 -0.000002 0.000219 +-1.000000 -0.000002 0.000219 +-1.000000 -0.000002 0.000219 +-1.000000 -0.000002 0.000219 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +1.000000 0.000000 0.000180 +1.000000 0.000000 0.000180 +1.000000 0.000000 0.000180 +1.000000 0.000000 0.000180 +1.000000 0.000000 0.000180 +1.000000 0.000000 0.000180 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 0.000002 0.000223 +1.000000 0.000002 0.000223 +1.000000 0.000002 0.000223 +1.000000 0.000002 0.000223 +1.000000 0.000002 0.000223 +1.000000 0.000002 0.000223 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.399484 0.000000 0.916740 +0.399484 0.000000 0.916740 +0.399484 0.000000 0.916740 +0.399484 0.000000 0.916740 +0.399484 0.000000 0.916740 +0.399484 0.000000 0.916740 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.402393 0.000000 -0.915467 +-0.402393 0.000000 -0.915467 +-0.402393 0.000000 -0.915467 +-0.402393 0.000000 -0.915467 +-0.402393 0.000000 -0.915467 +-0.402393 0.000000 -0.915467 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.315026 0.000000 -0.949083 +0.315026 0.000000 -0.949083 +0.315026 0.000000 -0.949083 +0.315026 0.000000 -0.949083 +0.315026 0.000000 -0.949083 +0.315026 0.000000 -0.949083 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.318258 0.000000 0.948004 +-0.318258 0.000000 0.948004 +-0.318258 0.000000 0.948004 +-0.318258 0.000000 0.948004 +-0.318258 0.000000 0.948004 +-0.318258 0.000000 0.948004 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.308093 0.000000 0.951356 +0.308093 0.000000 0.951356 +0.308093 0.000000 0.951356 +0.308093 0.000000 0.951356 +0.308093 0.000000 0.951356 +0.308093 0.000000 0.951356 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.311344 0.000000 -0.950297 +-0.311344 0.000000 -0.950297 +-0.311344 0.000000 -0.950297 +-0.311344 0.000000 -0.950297 +-0.311344 0.000000 -0.950297 +-0.311344 0.000000 -0.950297 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.196559 0.000000 0.980492 +-0.196559 0.000000 0.980492 +-0.196559 0.000000 0.980492 +-0.196559 0.000000 0.980492 +-0.196559 0.000000 0.980492 +-0.196559 0.000000 0.980492 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.192987 0.000000 -0.981201 +0.192987 0.000000 -0.981201 +0.192987 0.000000 -0.981201 +0.192987 0.000000 -0.981201 +0.192987 0.000000 -0.981201 +0.192987 0.000000 -0.981201 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 -0.000001 0.000149 +1.000000 -0.000001 0.000149 +1.000000 -0.000001 0.000149 +1.000000 -0.000001 0.000149 +1.000000 -0.000001 0.000149 +1.000000 -0.000001 0.000149 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +1.000000 0.000000 0.000178 +1.000000 0.000000 0.000178 +1.000000 0.000000 0.000178 +1.000000 0.000000 0.000178 +1.000000 0.000000 0.000178 +1.000000 0.000000 0.000178 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +-1.000000 0.000001 0.000151 +-1.000000 0.000001 0.000151 +-1.000000 0.000001 0.000151 +-1.000000 0.000001 0.000151 +-1.000000 0.000001 0.000151 +-1.000000 0.000001 0.000151 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 -0.000002 0.000219 +1.000000 -0.000002 0.000219 +1.000000 -0.000002 0.000219 +1.000000 -0.000002 0.000219 +1.000000 -0.000002 0.000219 +1.000000 -0.000002 0.000219 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +-1.000000 0.000000 0.000180 +-1.000000 0.000000 0.000180 +-1.000000 0.000000 0.000180 +-1.000000 0.000000 0.000180 +-1.000000 0.000000 0.000180 +-1.000000 0.000000 0.000180 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000002 0.000223 +-1.000000 0.000002 0.000223 +-1.000000 0.000002 0.000223 +-1.000000 0.000002 0.000223 +-1.000000 0.000002 0.000223 +-1.000000 0.000002 0.000223 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.399484 0.000000 0.916740 +-0.399484 0.000000 0.916740 +-0.399484 0.000000 0.916740 +-0.399484 0.000000 0.916740 +-0.399484 0.000000 0.916740 +-0.399484 0.000000 0.916740 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.402393 0.000000 -0.915467 +0.402393 0.000000 -0.915467 +0.402393 0.000000 -0.915467 +0.402393 0.000000 -0.915467 +0.402393 0.000000 -0.915467 +0.402393 0.000000 -0.915467 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.315026 0.000000 -0.949083 +-0.315026 0.000000 -0.949083 +-0.315026 0.000000 -0.949083 +-0.315026 0.000000 -0.949083 +-0.315026 0.000000 -0.949083 +-0.315026 0.000000 -0.949083 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.318258 0.000000 0.948004 +0.318258 0.000000 0.948004 +0.318258 0.000000 0.948004 +0.318258 0.000000 0.948004 +0.318258 0.000000 0.948004 +0.318258 0.000000 0.948004 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.308093 0.000000 0.951356 +-0.308093 0.000000 0.951356 +-0.308093 0.000000 0.951356 +-0.308093 0.000000 0.951356 +-0.308093 0.000000 0.951356 +-0.308093 0.000000 0.951356 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.311344 0.000000 -0.950297 +0.311344 0.000000 -0.950297 +0.311344 0.000000 -0.950297 +0.311344 0.000000 -0.950297 +0.311344 0.000000 -0.950297 +0.311344 0.000000 -0.950297 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.196559 0.000000 0.980492 +0.196559 0.000000 0.980492 +0.196559 0.000000 0.980492 +0.196559 0.000000 0.980492 +0.196559 0.000000 0.980492 +0.196559 0.000000 0.980492 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.192987 0.000000 -0.981201 +-0.192987 0.000000 -0.981201 +-0.192987 0.000000 -0.981201 +-0.192987 0.000000 -0.981201 +-0.192987 0.000000 -0.981201 +-0.192987 0.000000 -0.981201 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 -0.000001 0.000149 +-1.000000 -0.000001 0.000149 +-1.000000 -0.000001 0.000149 +-1.000000 -0.000001 0.000149 +-1.000000 -0.000001 0.000149 +-1.000000 -0.000001 0.000149 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-1.000000 0.000000 0.000178 +-1.000000 0.000000 0.000178 +-1.000000 0.000000 0.000178 +-1.000000 0.000000 0.000178 +-1.000000 0.000000 0.000178 +-1.000000 0.000000 0.000178 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +1.000000 0.000001 0.000151 +1.000000 0.000001 0.000151 +1.000000 0.000001 0.000151 +1.000000 0.000001 0.000151 +1.000000 0.000001 0.000151 +1.000000 0.000001 0.000151 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 -0.000002 0.000219 +-1.000000 -0.000002 0.000219 +-1.000000 -0.000002 0.000219 +-1.000000 -0.000002 0.000219 +-1.000000 -0.000002 0.000219 +-1.000000 -0.000002 0.000219 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +1.000000 0.000000 0.000180 +1.000000 0.000000 0.000180 +1.000000 0.000000 0.000180 +1.000000 0.000000 0.000180 +1.000000 0.000000 0.000180 +1.000000 0.000000 0.000180 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 0.000002 0.000223 +1.000000 0.000002 0.000223 +1.000000 0.000002 0.000223 +1.000000 0.000002 0.000223 +1.000000 0.000002 0.000223 +1.000000 0.000002 0.000223 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.399484 0.000000 0.916740 +0.399484 0.000000 0.916740 +0.399484 0.000000 0.916740 +0.399484 0.000000 0.916740 +0.399484 0.000000 0.916740 +0.399484 0.000000 0.916740 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.402393 0.000000 -0.915467 +-0.402393 0.000000 -0.915467 +-0.402393 0.000000 -0.915467 +-0.402393 0.000000 -0.915467 +-0.402393 0.000000 -0.915467 +-0.402393 0.000000 -0.915467 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.315026 0.000000 -0.949083 +0.315026 0.000000 -0.949083 +0.315026 0.000000 -0.949083 +0.315026 0.000000 -0.949083 +0.315026 0.000000 -0.949083 +0.315026 0.000000 -0.949083 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.318258 0.000000 0.948004 +-0.318258 0.000000 0.948004 +-0.318258 0.000000 0.948004 +-0.318258 0.000000 0.948004 +-0.318258 0.000000 0.948004 +-0.318258 0.000000 0.948004 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.308093 0.000000 0.951356 +0.308093 0.000000 0.951356 +0.308093 0.000000 0.951356 +0.308093 0.000000 0.951356 +0.308093 0.000000 0.951356 +0.308093 0.000000 0.951356 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.311344 0.000000 -0.950297 +-0.311344 0.000000 -0.950297 +-0.311344 0.000000 -0.950297 +-0.311344 0.000000 -0.950297 +-0.311344 0.000000 -0.950297 +-0.311344 0.000000 -0.950297 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.196559 0.000000 0.980492 +-0.196559 0.000000 0.980492 +-0.196559 0.000000 0.980492 +-0.196559 0.000000 0.980492 +-0.196559 0.000000 0.980492 +-0.196559 0.000000 0.980492 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.192987 0.000000 -0.981201 +0.192987 0.000000 -0.981201 +0.192987 0.000000 -0.981201 +0.192987 0.000000 -0.981201 +0.192987 0.000000 -0.981201 +0.192987 0.000000 -0.981201 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 -0.000001 0.000149 +1.000000 -0.000001 0.000149 +1.000000 -0.000001 0.000149 +1.000000 -0.000001 0.000149 +1.000000 -0.000001 0.000149 +1.000000 -0.000001 0.000149 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +1.000000 0.000000 0.000178 +1.000000 0.000000 0.000178 +1.000000 0.000000 0.000178 +1.000000 0.000000 0.000178 +1.000000 0.000000 0.000178 +1.000000 0.000000 0.000178 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +-1.000000 0.000001 0.000151 +-1.000000 0.000001 0.000151 +-1.000000 0.000001 0.000151 +-1.000000 0.000001 0.000151 +-1.000000 0.000001 0.000151 +-1.000000 0.000001 0.000151 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 -0.000002 0.000219 +1.000000 -0.000002 0.000219 +1.000000 -0.000002 0.000219 +1.000000 -0.000002 0.000219 +1.000000 -0.000002 0.000219 +1.000000 -0.000002 0.000219 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +-1.000000 0.000000 0.000180 +-1.000000 0.000000 0.000180 +-1.000000 0.000000 0.000180 +-1.000000 0.000000 0.000180 +-1.000000 0.000000 0.000180 +-1.000000 0.000000 0.000180 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000002 0.000223 +-1.000000 0.000002 0.000223 +-1.000000 0.000002 0.000223 +-1.000000 0.000002 0.000223 +-1.000000 0.000002 0.000223 +-1.000000 0.000002 0.000223 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.399484 0.000000 0.916740 +-0.399484 0.000000 0.916740 +-0.399484 0.000000 0.916740 +-0.399484 0.000000 0.916740 +-0.399484 0.000000 0.916740 +-0.399484 0.000000 0.916740 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.402393 0.000000 -0.915467 +0.402393 0.000000 -0.915467 +0.402393 0.000000 -0.915467 +0.402393 0.000000 -0.915467 +0.402393 0.000000 -0.915467 +0.402393 0.000000 -0.915467 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.315026 0.000000 -0.949083 +-0.315026 0.000000 -0.949083 +-0.315026 0.000000 -0.949083 +-0.315026 0.000000 -0.949083 +-0.315026 0.000000 -0.949083 +-0.315026 0.000000 -0.949083 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.318258 0.000000 0.948004 +0.318258 0.000000 0.948004 +0.318258 0.000000 0.948004 +0.318258 0.000000 0.948004 +0.318258 0.000000 0.948004 +0.318258 0.000000 0.948004 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.308093 0.000000 0.951356 +-0.308093 0.000000 0.951356 +-0.308093 0.000000 0.951356 +-0.308093 0.000000 0.951356 +-0.308093 0.000000 0.951356 +-0.308093 0.000000 0.951356 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.311344 0.000000 -0.950297 +0.311344 0.000000 -0.950297 +0.311344 0.000000 -0.950297 +0.311344 0.000000 -0.950297 +0.311344 0.000000 -0.950297 +0.311344 0.000000 -0.950297 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.196559 0.000000 0.980492 +0.196559 0.000000 0.980492 +0.196559 0.000000 0.980492 +0.196559 0.000000 0.980492 +0.196559 0.000000 0.980492 +0.196559 0.000000 0.980492 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.192987 0.000000 -0.981201 +-0.192987 0.000000 -0.981201 +-0.192987 0.000000 -0.981201 +-0.192987 0.000000 -0.981201 +-0.192987 0.000000 -0.981201 +-0.192987 0.000000 -0.981201 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.000039 0.000000 1.000000 +-0.000039 0.000000 1.000000 +0.054322 0.000000 0.998523 +0.054322 0.000000 0.998523 +-0.000039 0.000000 1.000000 +0.054322 0.000000 0.998523 +-0.054398 0.000000 0.998519 +-0.054398 0.000000 0.998519 +-0.000039 0.000000 1.000000 +-0.000039 0.000000 1.000000 +-0.054398 0.000000 0.998519 +-0.000039 0.000000 1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000039 0.000000 -1.000000 +0.000039 0.000000 -1.000000 +-0.054322 0.000000 -0.998523 +-0.054322 0.000000 -0.998523 +0.000039 0.000000 -1.000000 +-0.054322 0.000000 -0.998523 +0.000039 0.000000 -1.000000 +0.000039 0.000000 -1.000000 +0.054398 0.000000 -0.998519 +0.054398 0.000000 -0.998519 +0.054398 0.000000 -0.998519 +0.000039 0.000000 -1.000000 +-0.053482 -0.291167 -0.955176 +-0.053482 -0.291167 -0.955176 +-0.055904 0.000000 -0.998436 +-0.053482 -0.291167 -0.955176 +-0.055904 0.000000 -0.998436 +-0.055904 0.000000 -0.998436 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.055904 0.000000 -0.998436 +-0.055904 0.000000 -0.998436 +-0.053482 0.291167 -0.955176 +-0.055904 0.000000 -0.998436 +-0.053482 0.291167 -0.955176 +-0.053482 0.291167 -0.955176 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.055904 -0.000000 -0.998436 +0.055904 -0.000000 -0.998436 +0.053482 -0.291167 -0.955176 +0.053482 -0.291167 -0.955176 +0.053482 -0.291167 -0.955176 +0.055904 -0.000000 -0.998436 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.053482 0.291167 -0.955176 +0.053482 0.291167 -0.955176 +0.055904 -0.000000 -0.998436 +0.055904 -0.000000 -0.998436 +0.055904 -0.000000 -0.998436 +0.053482 0.291167 -0.955176 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.055904 0.000000 -0.998436 +-0.053482 0.291167 -0.955176 +-0.055904 0.000000 -0.998436 +-0.053482 0.291167 -0.955176 +-0.055904 0.000000 -0.998436 +-0.053482 0.291167 -0.955176 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.053482 -0.291167 -0.955176 +-0.055904 0.000000 -0.998436 +-0.053482 -0.291167 -0.955176 +-0.055904 0.000000 -0.998436 +-0.053482 -0.291167 -0.955176 +-0.055904 0.000000 -0.998436 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.055904 0.000000 -0.998436 +0.055904 0.000000 -0.998436 +0.053482 0.291167 -0.955176 +0.055904 0.000000 -0.998436 +0.053482 0.291167 -0.955176 +0.053482 0.291167 -0.955176 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.053482 -0.291167 -0.955176 +0.053482 -0.291167 -0.955176 +0.055904 0.000000 -0.998436 +0.053482 -0.291167 -0.955176 +0.055904 0.000000 -0.998436 +0.055904 0.000000 -0.998436 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000049 +0.000000 1.000000 0.000049 +0.000000 1.000000 0.000049 +0.000000 1.000000 0.000049 +0.000000 1.000000 0.000049 +0.000000 1.000000 0.000049 +0.000000 -1.000000 -0.000082 +0.000000 -1.000000 -0.000082 +0.000000 -1.000000 -0.000082 +0.000000 -1.000000 -0.000082 +0.000000 -1.000000 -0.000082 +0.000000 -1.000000 -0.000082 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 1.000000 0.000049 +0.000000 1.000000 0.000049 +0.000000 1.000000 0.000049 +0.000000 1.000000 0.000049 +0.000000 1.000000 0.000049 +0.000000 1.000000 0.000049 +0.000000 -1.000000 -0.000082 +0.000000 -1.000000 -0.000082 +0.000000 -1.000000 -0.000082 +0.000000 -1.000000 -0.000082 +0.000000 -1.000000 -0.000082 +0.000000 -1.000000 -0.000082 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 + + + + + + + + + + + +0.307256 0.287678 +0.309725 0.285091 +0.696866 0.012381 +0.696866 0.022741 +0.685172 0.070052 +0.554812 0.070052 +0.696866 0.303200 +0.307256 0.303200 +0.694397 0.285091 +0.696866 0.287678 +0.307256 0.314271 +0.307256 0.303911 +0.691928 0.303911 +0.691928 0.314271 +0.424636 0.052416 +0.424636 0.042056 +0.694397 0.157317 +0.307256 0.022741 +0.307256 0.012381 +0.694397 0.029544 +0.557398 0.105323 +0.556158 0.087872 +0.558639 0.087872 +0.429625 0.105323 +0.307256 0.292840 +0.696866 0.292840 +0.553756 0.034964 +0.554997 0.052416 +0.696866 0.027142 +0.557398 0.087687 +0.556158 0.070236 +0.558639 0.070236 +0.429625 0.087687 +0.696866 0.157317 +0.556052 0.052600 +0.685172 0.059692 +0.691928 0.314981 +0.691928 0.325341 +0.307256 0.325341 +0.307256 0.314981 +0.307256 0.157317 +0.429625 0.077327 +0.307256 0.027142 +0.553571 0.052600 +0.424636 0.070052 +0.424636 0.059692 +0.685172 0.077327 +0.685172 0.087687 +0.556237 0.034964 +0.685172 0.042056 +0.309725 0.029544 +0.685172 0.052416 +0.429625 0.094963 +0.685172 0.094963 +0.685172 0.105323 +0.309725 0.157317 +0.028294 0.161426 +0.845851 0.072634 +0.028294 0.126921 +0.965740 0.103010 +0.307570 0.173685 +0.412003 0.173685 +0.412003 0.182543 +0.307570 0.182543 +0.965740 0.137515 +0.731259 0.073629 +0.289884 0.082486 +0.731927 0.072634 +0.959607 0.130099 +0.187033 0.082486 +0.731259 0.082486 +0.725300 0.173685 +0.427377 0.203242 +0.114079 0.192395 +0.831314 0.173685 +0.422159 0.193390 +0.119991 0.253147 +0.119991 0.226887 +0.640183 0.192395 +0.870491 0.173685 +0.114079 0.183537 +0.526586 0.203242 +0.725300 0.182543 +0.959607 0.109870 +0.034427 0.133781 +0.631023 0.193390 +0.240187 0.213094 +0.213293 0.203242 +0.731927 0.063777 +0.504246 0.130099 +0.321229 0.110195 +0.640183 0.183537 +0.535750 0.192395 +0.535750 0.183537 +0.422159 0.202247 +0.282479 0.110195 +0.845851 0.063777 +0.034427 0.154011 +0.213293 0.212099 +0.272692 0.213094 +0.631023 0.202247 +0.499693 0.130099 +0.489788 0.108802 +0.204719 0.182543 +0.618003 0.072634 +0.499693 0.084891 +0.622449 0.182543 +0.216930 0.183537 +0.499693 0.072634 +0.494341 0.108802 +0.628408 0.082486 +0.322944 0.202247 +0.739397 0.183537 +0.628408 0.073629 +0.499693 0.063777 +0.504246 0.084891 +0.531809 0.202247 +0.114079 0.212099 +0.216930 0.192395 +0.114079 0.203242 +0.531809 0.193390 +0.622449 0.173685 +0.618003 0.063777 +0.494341 0.154011 +0.739397 0.192395 +0.322944 0.193390 +0.204719 0.173685 +0.731927 0.090087 +0.489788 0.154011 +0.489788 0.101481 +0.494341 0.101481 +0.721194 0.096792 +0.376031 0.161426 +0.965740 0.063777 +0.621974 0.091349 +0.618086 0.083828 +0.845851 0.137515 +0.262107 0.161426 +0.266001 0.154011 +0.731927 0.137515 +0.965740 0.072634 +0.365210 0.154011 +0.262107 0.113998 +0.251375 0.121881 +0.295406 0.073629 +0.237159 0.114136 +0.735821 0.130099 +0.835029 0.130099 +0.237159 0.105279 +0.398258 0.073629 +0.413584 0.173685 +0.152155 0.127323 +0.148267 0.120257 +0.100286 0.173685 +0.203138 0.173685 +0.952512 0.109481 +0.849655 0.103838 +0.516435 0.173685 +0.148183 0.161426 +0.137278 0.154011 +0.159005 0.154011 +0.258213 0.154011 +0.235680 0.213094 +0.114079 0.193390 +0.845767 0.096345 +0.427377 0.193390 +0.530537 0.183537 +0.841879 0.103412 +0.153534 0.072634 +0.153534 0.063777 +0.267459 0.063777 +0.267459 0.072634 +0.386937 0.154011 +0.636242 0.193390 +0.061315 0.073629 +0.494341 0.160923 +0.742659 0.097969 +0.511342 0.085280 +0.277625 0.221951 +0.218512 0.193390 +0.494341 0.161426 +0.398258 0.082486 +0.317726 0.193390 +0.277625 0.213094 +0.516435 0.182543 +0.482692 0.109192 +0.379836 0.114834 +0.829732 0.182543 +0.341323 0.213094 +0.504246 0.077570 +0.061315 0.082486 +0.735456 0.193390 +0.518016 0.173685 +0.614198 0.090922 +0.239987 0.249849 +0.381383 0.072634 +0.381383 0.063777 +0.033645 0.072634 +0.033645 0.063777 +0.065368 0.073629 +0.110576 0.073629 +0.620867 0.173685 +0.137131 0.249849 +0.375948 0.107740 +0.530537 0.192395 +0.526591 0.193390 +0.726881 0.182543 +0.341323 0.221951 +0.618003 0.137515 +0.499693 0.137515 +0.499693 0.137011 +0.413584 0.182543 +0.213294 0.193390 +0.235680 0.221951 +0.295406 0.082486 +0.726881 0.173685 +0.735456 0.202247 +0.526591 0.202247 +0.620867 0.182543 +0.317726 0.202247 +0.213294 0.202247 +0.218512 0.202247 +0.114079 0.202247 +0.427377 0.202247 +0.518016 0.182543 +0.829732 0.173685 +0.636242 0.202247 +0.607097 0.130099 +0.872693 0.173685 +0.905625 0.173685 +0.905625 0.182543 +0.872693 0.182543 +0.628824 0.130099 +0.728033 0.130099 +0.856756 0.130099 +0.735815 0.097594 +0.728039 0.097167 +0.621980 0.130099 +0.614192 0.130099 +0.849661 0.130099 +0.841873 0.130099 +0.499693 0.077570 +0.033645 0.103010 +0.039778 0.109870 +0.039778 0.130099 +0.033645 0.137515 +0.495139 0.130099 +0.495139 0.084891 +0.267459 0.090087 +0.381299 0.083828 +0.377411 0.091349 +0.278191 0.096792 +0.153534 0.137515 +0.164356 0.130099 +0.263565 0.130099 +0.267459 0.137515 +0.153618 0.096345 +0.149730 0.103838 +0.046874 0.109481 +0.256726 0.097969 +0.157506 0.103412 +0.488044 0.085280 +0.385187 0.090922 +0.495139 0.077570 +0.381383 0.137515 +0.392288 0.130099 +0.271352 0.130099 +0.370561 0.130099 +0.142629 0.130099 +0.271347 0.097167 +0.263570 0.097594 +0.377405 0.130099 +0.385193 0.130099 +0.157512 0.130099 +0.149724 0.130099 +0.372060 0.115260 +0.272840 0.120703 +0.041522 0.133392 +0.144379 0.127750 +0.144373 0.154011 +0.152161 0.154011 +0.372054 0.154011 +0.379842 0.154011 +0.258219 0.121505 +0.265995 0.121079 +0.960389 0.161426 +0.954256 0.154011 +0.954256 0.133781 +0.960389 0.126922 +0.498895 0.108802 +0.498895 0.154011 +0.498895 0.101481 +0.612651 0.161426 +0.623473 0.154011 +0.722682 0.154011 +0.726575 0.161426 +0.726575 0.113998 +0.840416 0.120257 +0.836528 0.127323 +0.737308 0.121881 +0.840499 0.161426 +0.851405 0.154011 +0.730469 0.154011 +0.829678 0.154011 +0.601746 0.154011 +0.612735 0.107740 +0.608847 0.114834 +0.505990 0.109192 +0.715843 0.120703 +0.616623 0.115261 +0.947160 0.133392 +0.844304 0.127750 +0.836522 0.154011 +0.844310 0.154011 +0.616629 0.154011 +0.608841 0.154011 +0.730464 0.121505 +0.722687 0.121079 +0.526586 0.212099 +0.427377 0.212099 +0.110576 0.082486 +0.065368 0.082486 +0.061315 0.092338 +0.034628 0.092338 +0.034628 0.083481 +0.061315 0.083481 +0.317721 0.203242 +0.317721 0.212099 +0.218512 0.212099 +0.218512 0.203242 +0.222453 0.183537 +0.321672 0.183537 +0.321672 0.192395 +0.222453 0.192395 +0.282479 0.101338 +0.321229 0.101338 +0.756875 0.086427 +0.736646 0.086427 +0.736646 0.077570 +0.756875 0.077570 +0.631018 0.203242 +0.631018 0.212099 +0.531809 0.212099 +0.531809 0.203242 +0.634970 0.183537 +0.634970 0.192395 +0.272692 0.221951 +0.240187 0.221951 +0.065368 0.092338 +0.065368 0.083481 +0.110576 0.083481 +0.110576 0.092338 +0.322944 0.203242 +0.422153 0.203242 +0.422153 0.212099 +0.322944 0.212099 +0.862883 0.077570 +0.965740 0.077570 +0.965740 0.086427 +0.862883 0.086427 +0.128848 0.226887 +0.128848 0.253147 +0.118996 0.255785 +0.110139 0.255785 +0.110139 0.217035 +0.118996 0.217035 +0.309151 0.182543 +0.309151 0.173685 +0.326885 0.183537 +0.426105 0.183537 +0.426105 0.192395 +0.326885 0.192395 +0.100286 0.217035 +0.109144 0.217035 +0.109144 0.256211 +0.100286 0.256211 +0.310130 0.213094 +0.310130 0.221951 +0.187033 0.073629 +0.289884 0.073629 +0.861307 0.077570 +0.861307 0.086427 +0.758451 0.086427 +0.758451 0.077570 +0.202749 0.221951 +0.202749 0.213094 +0.315063 0.221951 +0.315063 0.213094 +0.203138 0.182543 +0.100286 0.182543 +0.241563 0.243938 +0.241563 0.235081 +0.344420 0.235081 +0.344420 0.243938 +0.034628 0.082486 +0.034628 0.073629 +0.870491 0.182543 +0.831314 0.182543 +0.116098 0.092338 +0.116098 0.083481 +0.218949 0.083481 +0.218949 0.092338 +0.137131 0.240992 +0.239987 0.240992 +0.257388 0.105279 +0.257388 0.114136 +0.431318 0.192395 +0.431318 0.183537 +0.028294 0.161426 +0.845851 0.072634 +0.028294 0.126921 +0.965740 0.103010 +0.307570 0.173685 +0.412003 0.173685 +0.412003 0.182543 +0.307570 0.182543 +0.965740 0.137515 +0.731259 0.073629 +0.289884 0.082486 +0.731927 0.072634 +0.959607 0.130099 +0.187033 0.082486 +0.731259 0.082486 +0.725300 0.173685 +0.427377 0.203242 +0.114079 0.192395 +0.831314 0.173685 +0.422159 0.193390 +0.119991 0.253147 +0.119991 0.226887 +0.640183 0.192395 +0.870491 0.173685 +0.114079 0.183537 +0.526586 0.203242 +0.725300 0.182543 +0.959607 0.109870 +0.034427 0.133781 +0.631023 0.193390 +0.240187 0.213094 +0.213293 0.203242 +0.731927 0.063777 +0.504246 0.130099 +0.321229 0.110195 +0.640183 0.183537 +0.535750 0.192395 +0.535750 0.183537 +0.422159 0.202247 +0.282479 0.110195 +0.845851 0.063777 +0.034427 0.154011 +0.213293 0.212099 +0.272692 0.213094 +0.631023 0.202247 +0.499693 0.130099 +0.489788 0.108802 +0.204719 0.182543 +0.618003 0.072634 +0.499693 0.084891 +0.622449 0.182543 +0.216930 0.183537 +0.499693 0.072634 +0.494341 0.108802 +0.628408 0.082486 +0.322944 0.202247 +0.739397 0.183537 +0.628408 0.073629 +0.499693 0.063777 +0.504246 0.084891 +0.531809 0.202247 +0.114079 0.212099 +0.216930 0.192395 +0.114079 0.203242 +0.531809 0.193390 +0.622449 0.173685 +0.618003 0.063777 +0.494341 0.154011 +0.739397 0.192395 +0.322944 0.193390 +0.204719 0.173685 +0.731927 0.090087 +0.489788 0.154011 +0.489788 0.101481 +0.494341 0.101481 +0.721194 0.096792 +0.376031 0.161426 +0.965740 0.063777 +0.621974 0.091349 +0.618086 0.083828 +0.845851 0.137515 +0.262107 0.161426 +0.266001 0.154011 +0.731927 0.137515 +0.965740 0.072634 +0.365210 0.154011 +0.262107 0.113998 +0.251375 0.121881 +0.295406 0.073629 +0.237159 0.114136 +0.735821 0.130099 +0.835029 0.130099 +0.237159 0.105279 +0.398258 0.073629 +0.413584 0.173685 +0.152155 0.127323 +0.148267 0.120257 +0.100286 0.173685 +0.203138 0.173685 +0.952512 0.109481 +0.849655 0.103838 +0.516435 0.173685 +0.148183 0.161426 +0.137278 0.154011 +0.159005 0.154011 +0.258213 0.154011 +0.235680 0.213094 +0.114079 0.193390 +0.845767 0.096345 +0.427377 0.193390 +0.530537 0.183537 +0.841879 0.103412 +0.153534 0.072634 +0.153534 0.063777 +0.267459 0.063777 +0.267459 0.072634 +0.386937 0.154011 +0.636242 0.193390 +0.061315 0.073629 +0.494341 0.160923 +0.742659 0.097969 +0.511342 0.085280 +0.277625 0.221951 +0.218512 0.193390 +0.494341 0.161426 +0.398258 0.082486 +0.317726 0.193390 +0.277625 0.213094 +0.516435 0.182543 +0.482692 0.109192 +0.379836 0.114834 +0.829732 0.182543 +0.341323 0.213094 +0.504246 0.077570 +0.061315 0.082486 +0.735456 0.193390 +0.518016 0.173685 +0.614198 0.090922 +0.239987 0.249849 +0.381383 0.072634 +0.381383 0.063777 +0.033645 0.072634 +0.033645 0.063777 +0.065368 0.073629 +0.110576 0.073629 +0.620867 0.173685 +0.137131 0.249849 +0.375948 0.107740 +0.530537 0.192395 +0.526591 0.193390 +0.726881 0.182543 +0.341323 0.221951 +0.618003 0.137515 +0.499693 0.137515 +0.499693 0.137011 +0.413584 0.182543 +0.213294 0.193390 +0.235680 0.221951 +0.295406 0.082486 +0.726881 0.173685 +0.735456 0.202247 +0.526591 0.202247 +0.620867 0.182543 +0.317726 0.202247 +0.213294 0.202247 +0.218512 0.202247 +0.114079 0.202247 +0.427377 0.202247 +0.518016 0.182543 +0.829732 0.173685 +0.636242 0.202247 +0.607097 0.130099 +0.872693 0.173685 +0.905625 0.173685 +0.905625 0.182543 +0.872693 0.182543 +0.628824 0.130099 +0.728033 0.130099 +0.856756 0.130099 +0.735815 0.097594 +0.728039 0.097167 +0.621980 0.130099 +0.614192 0.130099 +0.849661 0.130099 +0.841873 0.130099 +0.499693 0.077570 +0.033645 0.103010 +0.039778 0.109870 +0.039778 0.130099 +0.033645 0.137515 +0.495139 0.130099 +0.495139 0.084891 +0.267459 0.090087 +0.381299 0.083828 +0.377411 0.091349 +0.278191 0.096792 +0.153534 0.137515 +0.164356 0.130099 +0.263565 0.130099 +0.267459 0.137515 +0.153618 0.096345 +0.149730 0.103838 +0.046874 0.109481 +0.256726 0.097969 +0.157506 0.103412 +0.488044 0.085280 +0.385187 0.090922 +0.495139 0.077570 +0.381383 0.137515 +0.392288 0.130099 +0.271352 0.130099 +0.370561 0.130099 +0.142629 0.130099 +0.271347 0.097167 +0.263570 0.097594 +0.377405 0.130099 +0.385193 0.130099 +0.157512 0.130099 +0.149724 0.130099 +0.372060 0.115260 +0.272840 0.120703 +0.041522 0.133392 +0.144379 0.127750 +0.144373 0.154011 +0.152161 0.154011 +0.372054 0.154011 +0.379842 0.154011 +0.258219 0.121505 +0.265995 0.121079 +0.960389 0.161426 +0.954256 0.154011 +0.954256 0.133781 +0.960389 0.126922 +0.498895 0.108802 +0.498895 0.154011 +0.498895 0.101481 +0.612651 0.161426 +0.623473 0.154011 +0.722682 0.154011 +0.726575 0.161426 +0.726575 0.113998 +0.840416 0.120257 +0.836528 0.127323 +0.737308 0.121881 +0.840499 0.161426 +0.851405 0.154011 +0.730469 0.154011 +0.829678 0.154011 +0.601746 0.154011 +0.612735 0.107740 +0.608847 0.114834 +0.505990 0.109192 +0.715843 0.120703 +0.616623 0.115261 +0.947160 0.133392 +0.844304 0.127750 +0.836522 0.154011 +0.844310 0.154011 +0.616629 0.154011 +0.608841 0.154011 +0.730464 0.121505 +0.722687 0.121079 +0.526586 0.212099 +0.427377 0.212099 +0.110576 0.082486 +0.065368 0.082486 +0.061315 0.092338 +0.034628 0.092338 +0.034628 0.083481 +0.061315 0.083481 +0.317721 0.203242 +0.317721 0.212099 +0.218512 0.212099 +0.218512 0.203242 +0.222453 0.183537 +0.321672 0.183537 +0.321672 0.192395 +0.222453 0.192395 +0.282479 0.101338 +0.321229 0.101338 +0.756875 0.086427 +0.736646 0.086427 +0.736646 0.077570 +0.756875 0.077570 +0.631018 0.203242 +0.631018 0.212099 +0.531809 0.212099 +0.531809 0.203242 +0.634970 0.183537 +0.634970 0.192395 +0.272692 0.221951 +0.240187 0.221951 +0.065368 0.092338 +0.065368 0.083481 +0.110576 0.083481 +0.110576 0.092338 +0.322944 0.203242 +0.422153 0.203242 +0.422153 0.212099 +0.322944 0.212099 +0.862883 0.077570 +0.965740 0.077570 +0.965740 0.086427 +0.862883 0.086427 +0.128848 0.226887 +0.128848 0.253147 +0.118996 0.255785 +0.110139 0.255785 +0.110139 0.217035 +0.118996 0.217035 +0.309151 0.182543 +0.309151 0.173685 +0.326885 0.183537 +0.426105 0.183537 +0.426105 0.192395 +0.326885 0.192395 +0.100286 0.217035 +0.109144 0.217035 +0.109144 0.256211 +0.100286 0.256211 +0.310130 0.213094 +0.310130 0.221951 +0.187033 0.073629 +0.289884 0.073629 +0.861307 0.077570 +0.861307 0.086427 +0.758451 0.086427 +0.758451 0.077570 +0.202749 0.221951 +0.202749 0.213094 +0.315063 0.221951 +0.315063 0.213094 +0.203138 0.182543 +0.100286 0.182543 +0.241563 0.243938 +0.241563 0.235081 +0.344420 0.235081 +0.344420 0.243938 +0.034628 0.082486 +0.034628 0.073629 +0.870491 0.182543 +0.831314 0.182543 +0.116098 0.092338 +0.116098 0.083481 +0.218949 0.083481 +0.218949 0.092338 +0.137131 0.240992 +0.239987 0.240992 +0.257388 0.105279 +0.257388 0.114136 +0.431318 0.192395 +0.431318 0.183537 +0.028294 0.161426 +0.845851 0.072634 +0.028294 0.126921 +0.965740 0.103010 +0.307570 0.173685 +0.412003 0.173685 +0.412003 0.182543 +0.307570 0.182543 +0.965740 0.137515 +0.731259 0.073629 +0.289884 0.082486 +0.731927 0.072634 +0.959607 0.130099 +0.187033 0.082486 +0.731259 0.082486 +0.725300 0.173685 +0.427377 0.203242 +0.114079 0.192395 +0.831314 0.173685 +0.422159 0.193390 +0.119991 0.253147 +0.119991 0.226887 +0.640183 0.192395 +0.870491 0.173685 +0.114079 0.183537 +0.526586 0.203242 +0.725300 0.182543 +0.959607 0.109870 +0.034427 0.133781 +0.631023 0.193390 +0.240187 0.213094 +0.213293 0.203242 +0.731927 0.063777 +0.504246 0.130099 +0.321229 0.110195 +0.640183 0.183537 +0.535750 0.192395 +0.535750 0.183537 +0.422159 0.202247 +0.282479 0.110195 +0.845851 0.063777 +0.034427 0.154011 +0.213293 0.212099 +0.272692 0.213094 +0.631023 0.202247 +0.499693 0.130099 +0.489788 0.108802 +0.204719 0.182543 +0.618003 0.072634 +0.499693 0.084891 +0.622449 0.182543 +0.216930 0.183537 +0.499693 0.072634 +0.494341 0.108802 +0.628408 0.082486 +0.322944 0.202247 +0.739397 0.183537 +0.628408 0.073629 +0.499693 0.063777 +0.504246 0.084891 +0.531809 0.202247 +0.114079 0.212099 +0.216930 0.192395 +0.114079 0.203242 +0.531809 0.193390 +0.622449 0.173685 +0.618003 0.063777 +0.494341 0.154011 +0.739397 0.192395 +0.322944 0.193390 +0.204719 0.173685 +0.731927 0.090087 +0.489788 0.154011 +0.489788 0.101481 +0.494341 0.101481 +0.721194 0.096792 +0.376031 0.161426 +0.965740 0.063777 +0.621974 0.091349 +0.618086 0.083828 +0.845851 0.137515 +0.262107 0.161426 +0.266001 0.154011 +0.731927 0.137515 +0.965740 0.072634 +0.365210 0.154011 +0.262107 0.113998 +0.251375 0.121881 +0.295406 0.073629 +0.237159 0.114136 +0.735821 0.130099 +0.835029 0.130099 +0.237159 0.105279 +0.398258 0.073629 +0.413584 0.173685 +0.152155 0.127323 +0.148267 0.120257 +0.100286 0.173685 +0.203138 0.173685 +0.952512 0.109481 +0.849655 0.103838 +0.516435 0.173685 +0.148183 0.161426 +0.137278 0.154011 +0.159005 0.154011 +0.258213 0.154011 +0.235680 0.213094 +0.114079 0.193390 +0.845767 0.096345 +0.427377 0.193390 +0.530537 0.183537 +0.841879 0.103412 +0.153534 0.072634 +0.153534 0.063777 +0.267459 0.063777 +0.267459 0.072634 +0.386937 0.154011 +0.636242 0.193390 +0.061315 0.073629 +0.494341 0.160923 +0.742659 0.097969 +0.511342 0.085280 +0.277625 0.221951 +0.218512 0.193390 +0.494341 0.161426 +0.398258 0.082486 +0.317726 0.193390 +0.277625 0.213094 +0.516435 0.182543 +0.482692 0.109192 +0.379836 0.114834 +0.829732 0.182543 +0.341323 0.213094 +0.504246 0.077570 +0.061315 0.082486 +0.735456 0.193390 +0.518016 0.173685 +0.614198 0.090922 +0.239987 0.249849 +0.381383 0.072634 +0.381383 0.063777 +0.033645 0.072634 +0.033645 0.063777 +0.065368 0.073629 +0.110576 0.073629 +0.620867 0.173685 +0.137131 0.249849 +0.375948 0.107740 +0.530537 0.192395 +0.526591 0.193390 +0.726881 0.182543 +0.341323 0.221951 +0.618003 0.137515 +0.499693 0.137515 +0.499693 0.137011 +0.413584 0.182543 +0.213294 0.193390 +0.235680 0.221951 +0.295406 0.082486 +0.726881 0.173685 +0.735456 0.202247 +0.526591 0.202247 +0.620867 0.182543 +0.317726 0.202247 +0.213294 0.202247 +0.218512 0.202247 +0.114079 0.202247 +0.427377 0.202247 +0.518016 0.182543 +0.829732 0.173685 +0.636242 0.202247 +0.607097 0.130099 +0.872693 0.173685 +0.905625 0.173685 +0.905625 0.182543 +0.872693 0.182543 +0.628824 0.130099 +0.728033 0.130099 +0.856756 0.130099 +0.735815 0.097594 +0.728039 0.097167 +0.621980 0.130099 +0.614192 0.130099 +0.849661 0.130099 +0.841873 0.130099 +0.499693 0.077570 +0.033645 0.103010 +0.039778 0.109870 +0.039778 0.130099 +0.033645 0.137515 +0.495139 0.130099 +0.495139 0.084891 +0.267459 0.090087 +0.381299 0.083828 +0.377411 0.091349 +0.278191 0.096792 +0.153534 0.137515 +0.164356 0.130099 +0.263565 0.130099 +0.267459 0.137515 +0.153618 0.096345 +0.149730 0.103838 +0.046874 0.109481 +0.256726 0.097969 +0.157506 0.103412 +0.488044 0.085280 +0.385187 0.090922 +0.495139 0.077570 +0.381383 0.137515 +0.392288 0.130099 +0.271352 0.130099 +0.370561 0.130099 +0.142629 0.130099 +0.271347 0.097167 +0.263570 0.097594 +0.377405 0.130099 +0.385193 0.130099 +0.157512 0.130099 +0.149724 0.130099 +0.372060 0.115260 +0.272840 0.120703 +0.041522 0.133392 +0.144379 0.127750 +0.144373 0.154011 +0.152161 0.154011 +0.372054 0.154011 +0.379842 0.154011 +0.258219 0.121505 +0.265995 0.121079 +0.960389 0.161426 +0.954256 0.154011 +0.954256 0.133781 +0.960389 0.126922 +0.498895 0.108802 +0.498895 0.154011 +0.498895 0.101481 +0.612651 0.161426 +0.623473 0.154011 +0.722682 0.154011 +0.726575 0.161426 +0.726575 0.113998 +0.840416 0.120257 +0.836528 0.127323 +0.737308 0.121881 +0.840499 0.161426 +0.851405 0.154011 +0.730469 0.154011 +0.829678 0.154011 +0.601746 0.154011 +0.612735 0.107740 +0.608847 0.114834 +0.505990 0.109192 +0.715843 0.120703 +0.616623 0.115261 +0.947160 0.133392 +0.844304 0.127750 +0.836522 0.154011 +0.844310 0.154011 +0.616629 0.154011 +0.608841 0.154011 +0.730464 0.121505 +0.722687 0.121079 +0.526586 0.212099 +0.427377 0.212099 +0.110576 0.082486 +0.065368 0.082486 +0.061315 0.092338 +0.034628 0.092338 +0.034628 0.083481 +0.061315 0.083481 +0.317721 0.203242 +0.317721 0.212099 +0.218512 0.212099 +0.218512 0.203242 +0.222453 0.183537 +0.321672 0.183537 +0.321672 0.192395 +0.222453 0.192395 +0.282479 0.101338 +0.321229 0.101338 +0.756875 0.086427 +0.736646 0.086427 +0.736646 0.077570 +0.756875 0.077570 +0.631018 0.203242 +0.631018 0.212099 +0.531809 0.212099 +0.531809 0.203242 +0.634970 0.183537 +0.634970 0.192395 +0.272692 0.221951 +0.240187 0.221951 +0.065368 0.092338 +0.065368 0.083481 +0.110576 0.083481 +0.110576 0.092338 +0.322944 0.203242 +0.422153 0.203242 +0.422153 0.212099 +0.322944 0.212099 +0.862883 0.077570 +0.965740 0.077570 +0.965740 0.086427 +0.862883 0.086427 +0.128848 0.226887 +0.128848 0.253147 +0.118996 0.255785 +0.110139 0.255785 +0.110139 0.217035 +0.118996 0.217035 +0.309151 0.182543 +0.309151 0.173685 +0.326885 0.183537 +0.426105 0.183537 +0.426105 0.192395 +0.326885 0.192395 +0.100286 0.217035 +0.109144 0.217035 +0.109144 0.256211 +0.100286 0.256211 +0.310130 0.213094 +0.310130 0.221951 +0.187033 0.073629 +0.289884 0.073629 +0.861307 0.077570 +0.861307 0.086427 +0.758451 0.086427 +0.758451 0.077570 +0.202749 0.221951 +0.202749 0.213094 +0.315063 0.221951 +0.315063 0.213094 +0.203138 0.182543 +0.100286 0.182543 +0.241563 0.243938 +0.241563 0.235081 +0.344420 0.235081 +0.344420 0.243938 +0.034628 0.082486 +0.034628 0.073629 +0.870491 0.182543 +0.831314 0.182543 +0.116098 0.092338 +0.116098 0.083481 +0.218949 0.083481 +0.218949 0.092338 +0.137131 0.240992 +0.239987 0.240992 +0.257388 0.105279 +0.257388 0.114136 +0.431318 0.192395 +0.431318 0.183537 +0.028294 0.161426 +0.845851 0.072634 +0.028294 0.126921 +0.965740 0.103010 +0.307570 0.173685 +0.412003 0.173685 +0.412003 0.182543 +0.307570 0.182543 +0.965740 0.137515 +0.731259 0.073629 +0.289884 0.082486 +0.731927 0.072634 +0.959607 0.130099 +0.187033 0.082486 +0.731259 0.082486 +0.725300 0.173685 +0.427377 0.203242 +0.114079 0.192395 +0.831314 0.173685 +0.422159 0.193390 +0.119991 0.253147 +0.119991 0.226887 +0.640183 0.192395 +0.870491 0.173685 +0.114079 0.183537 +0.526586 0.203242 +0.725300 0.182543 +0.959607 0.109870 +0.034427 0.133781 +0.631023 0.193390 +0.240187 0.213094 +0.213293 0.203242 +0.731927 0.063777 +0.504246 0.130099 +0.321229 0.110195 +0.640183 0.183537 +0.535750 0.192395 +0.535750 0.183537 +0.422159 0.202247 +0.282479 0.110195 +0.845851 0.063777 +0.034427 0.154011 +0.213293 0.212099 +0.272692 0.213094 +0.631023 0.202247 +0.499693 0.130099 +0.489788 0.108802 +0.204719 0.182543 +0.618003 0.072634 +0.499693 0.084891 +0.622449 0.182543 +0.216930 0.183537 +0.499693 0.072634 +0.494341 0.108802 +0.628408 0.082486 +0.322944 0.202247 +0.739397 0.183537 +0.628408 0.073629 +0.499693 0.063777 +0.504246 0.084891 +0.531809 0.202247 +0.114079 0.212099 +0.216930 0.192395 +0.114079 0.203242 +0.531809 0.193390 +0.622449 0.173685 +0.618003 0.063777 +0.494341 0.154011 +0.739397 0.192395 +0.322944 0.193390 +0.204719 0.173685 +0.731927 0.090087 +0.489788 0.154011 +0.489788 0.101481 +0.494341 0.101481 +0.721194 0.096792 +0.376031 0.161426 +0.965740 0.063777 +0.621974 0.091349 +0.618086 0.083828 +0.845851 0.137515 +0.262107 0.161426 +0.266001 0.154011 +0.731927 0.137515 +0.965740 0.072634 +0.365210 0.154011 +0.262107 0.113998 +0.251375 0.121881 +0.295406 0.073629 +0.237159 0.114136 +0.735821 0.130099 +0.835029 0.130099 +0.237159 0.105279 +0.398258 0.073629 +0.413584 0.173685 +0.152155 0.127323 +0.148267 0.120257 +0.100286 0.173685 +0.203138 0.173685 +0.952512 0.109481 +0.849655 0.103838 +0.516435 0.173685 +0.148183 0.161426 +0.137278 0.154011 +0.159005 0.154011 +0.258213 0.154011 +0.235680 0.213094 +0.114079 0.193390 +0.845767 0.096345 +0.427377 0.193390 +0.530537 0.183537 +0.841879 0.103412 +0.153534 0.072634 +0.153534 0.063777 +0.267459 0.063777 +0.267459 0.072634 +0.386937 0.154011 +0.636242 0.193390 +0.061315 0.073629 +0.494341 0.160923 +0.742659 0.097969 +0.511342 0.085280 +0.277625 0.221951 +0.218512 0.193390 +0.494341 0.161426 +0.398258 0.082486 +0.317726 0.193390 +0.277625 0.213094 +0.516435 0.182543 +0.482692 0.109192 +0.379836 0.114834 +0.829732 0.182543 +0.341323 0.213094 +0.504246 0.077570 +0.061315 0.082486 +0.735456 0.193390 +0.518016 0.173685 +0.614198 0.090922 +0.239987 0.249849 +0.381383 0.072634 +0.381383 0.063777 +0.033645 0.072634 +0.033645 0.063777 +0.065368 0.073629 +0.110576 0.073629 +0.620867 0.173685 +0.137131 0.249849 +0.375948 0.107740 +0.530537 0.192395 +0.526591 0.193390 +0.726881 0.182543 +0.341323 0.221951 +0.618003 0.137515 +0.499693 0.137515 +0.499693 0.137011 +0.413584 0.182543 +0.213294 0.193390 +0.235680 0.221951 +0.295406 0.082486 +0.726881 0.173685 +0.735456 0.202247 +0.526591 0.202247 +0.620867 0.182543 +0.317726 0.202247 +0.213294 0.202247 +0.218512 0.202247 +0.114079 0.202247 +0.427377 0.202247 +0.518016 0.182543 +0.829732 0.173685 +0.636242 0.202247 +0.607097 0.130099 +0.872693 0.173685 +0.905625 0.173685 +0.905625 0.182543 +0.872693 0.182543 +0.628824 0.130099 +0.728033 0.130099 +0.856756 0.130099 +0.735815 0.097594 +0.728039 0.097167 +0.621980 0.130099 +0.614192 0.130099 +0.849661 0.130099 +0.841873 0.130099 +0.499693 0.077570 +0.033645 0.103010 +0.039778 0.109870 +0.039778 0.130099 +0.033645 0.137515 +0.495139 0.130099 +0.495139 0.084891 +0.267459 0.090087 +0.381299 0.083828 +0.377411 0.091349 +0.278191 0.096792 +0.153534 0.137515 +0.164356 0.130099 +0.263565 0.130099 +0.267459 0.137515 +0.153618 0.096345 +0.149730 0.103838 +0.046874 0.109481 +0.256726 0.097969 +0.157506 0.103412 +0.488044 0.085280 +0.385187 0.090922 +0.495139 0.077570 +0.381383 0.137515 +0.392288 0.130099 +0.271352 0.130099 +0.370561 0.130099 +0.142629 0.130099 +0.271347 0.097167 +0.263570 0.097594 +0.377405 0.130099 +0.385193 0.130099 +0.157512 0.130099 +0.149724 0.130099 +0.372060 0.115260 +0.272840 0.120703 +0.041522 0.133392 +0.144379 0.127750 +0.144373 0.154011 +0.152161 0.154011 +0.372054 0.154011 +0.379842 0.154011 +0.258219 0.121505 +0.265995 0.121079 +0.960389 0.161426 +0.954256 0.154011 +0.954256 0.133781 +0.960389 0.126922 +0.498895 0.108802 +0.498895 0.154011 +0.498895 0.101481 +0.612651 0.161426 +0.623473 0.154011 +0.722682 0.154011 +0.726575 0.161426 +0.726575 0.113998 +0.840416 0.120257 +0.836528 0.127323 +0.737308 0.121881 +0.840499 0.161426 +0.851405 0.154011 +0.730469 0.154011 +0.829678 0.154011 +0.601746 0.154011 +0.612735 0.107740 +0.608847 0.114834 +0.505990 0.109192 +0.715843 0.120703 +0.616623 0.115261 +0.947160 0.133392 +0.844304 0.127750 +0.836522 0.154011 +0.844310 0.154011 +0.616629 0.154011 +0.608841 0.154011 +0.730464 0.121505 +0.722687 0.121079 +0.526586 0.212099 +0.427377 0.212099 +0.110576 0.082486 +0.065368 0.082486 +0.061315 0.092338 +0.034628 0.092338 +0.034628 0.083481 +0.061315 0.083481 +0.317721 0.203242 +0.317721 0.212099 +0.218512 0.212099 +0.218512 0.203242 +0.222453 0.183537 +0.321672 0.183537 +0.321672 0.192395 +0.222453 0.192395 +0.282479 0.101338 +0.321229 0.101338 +0.756875 0.086427 +0.736646 0.086427 +0.736646 0.077570 +0.756875 0.077570 +0.631018 0.203242 +0.631018 0.212099 +0.531809 0.212099 +0.531809 0.203242 +0.634970 0.183537 +0.634970 0.192395 +0.272692 0.221951 +0.240187 0.221951 +0.065368 0.092338 +0.065368 0.083481 +0.110576 0.083481 +0.110576 0.092338 +0.322944 0.203242 +0.422153 0.203242 +0.422153 0.212099 +0.322944 0.212099 +0.862883 0.077570 +0.965740 0.077570 +0.965740 0.086427 +0.862883 0.086427 +0.128848 0.226887 +0.128848 0.253147 +0.118996 0.255785 +0.110139 0.255785 +0.110139 0.217035 +0.118996 0.217035 +0.309151 0.182543 +0.309151 0.173685 +0.326885 0.183537 +0.426105 0.183537 +0.426105 0.192395 +0.326885 0.192395 +0.100286 0.217035 +0.109144 0.217035 +0.109144 0.256211 +0.100286 0.256211 +0.310130 0.213094 +0.310130 0.221951 +0.187033 0.073629 +0.289884 0.073629 +0.861307 0.077570 +0.861307 0.086427 +0.758451 0.086427 +0.758451 0.077570 +0.202749 0.221951 +0.202749 0.213094 +0.315063 0.221951 +0.315063 0.213094 +0.203138 0.182543 +0.100286 0.182543 +0.241563 0.243938 +0.241563 0.235081 +0.344420 0.235081 +0.344420 0.243938 +0.034628 0.082486 +0.034628 0.073629 +0.870491 0.182543 +0.831314 0.182543 +0.116098 0.092338 +0.116098 0.083481 +0.218949 0.083481 +0.218949 0.092338 +0.137131 0.240992 +0.239987 0.240992 +0.257388 0.105279 +0.257388 0.114136 +0.431318 0.192395 +0.431318 0.183537 +0.274782 0.709736 +0.361876 0.709736 +0.361876 0.970034 +0.274782 0.970034 +0.187812 0.709736 +0.187812 0.970034 +0.099276 0.706657 +0.186369 0.706657 +0.186369 0.966955 +0.099276 0.966955 +0.012306 0.706657 +0.012306 0.966955 +0.096980 0.974069 +0.096980 0.971456 +0.357278 0.971456 +0.357278 0.974069 +0.013845 0.706190 +0.013845 0.703578 +0.274143 0.703578 +0.274143 0.706190 +0.183194 0.982352 +0.270164 0.977614 +0.270164 0.980227 +0.183194 0.984965 +0.357257 0.982352 +0.357257 0.984965 +0.183194 0.979273 +0.270287 0.974535 +0.270287 0.977148 +0.183194 0.981886 +0.357257 0.979273 +0.357257 0.981886 +0.361876 0.796502 +0.361876 0.883268 +0.183746 0.974069 +0.270512 0.974069 +0.274782 0.796502 +0.274782 0.883268 +0.187812 0.883268 +0.187812 0.796502 +0.100611 0.706190 +0.187377 0.706190 +0.183746 0.971456 +0.270512 0.971456 +0.186369 0.880189 +0.186369 0.793423 +0.100611 0.703578 +0.187377 0.703578 +0.012306 0.793423 +0.012306 0.880189 +0.099276 0.880189 +0.099276 0.793423 +0.947894 0.460818 +0.947894 0.510889 +0.043280 0.510889 +0.043280 0.460818 +0.040852 0.522376 +0.946795 0.534951 +0.945103 0.559154 +0.039160 0.546579 +0.176994 0.590459 +0.126923 0.605722 +0.126923 0.566197 +0.176994 0.566197 +0.043636 0.459622 +0.948250 0.510273 +0.948250 0.534535 +0.043636 0.483883 +0.200504 0.575951 +0.250574 0.560688 +0.250574 0.600213 +0.200504 0.600213 +0.947894 0.560960 +0.300645 0.575951 +0.043280 0.560960 +0.076852 0.590459 +0.076852 0.566197 +0.300645 0.600213 +0.947894 0.460818 +0.947894 0.510889 +0.043280 0.510889 +0.043280 0.460818 +0.040852 0.522376 +0.946795 0.534951 +0.945103 0.559154 +0.039160 0.546579 +0.176994 0.590459 +0.126923 0.605722 +0.126923 0.566197 +0.176994 0.566197 +0.043636 0.459622 +0.948250 0.510273 +0.948250 0.534535 +0.043636 0.483883 +0.200504 0.575951 +0.250574 0.560688 +0.250574 0.600213 +0.200504 0.600213 +0.947894 0.560960 +0.043280 0.560960 +0.076852 0.590459 +0.076852 0.566197 +0.300645 0.575951 +0.300645 0.600213 +0.947894 0.460818 +0.947894 0.510889 +0.043280 0.510889 +0.043280 0.460818 +0.040852 0.522376 +0.946795 0.534951 +0.945103 0.559154 +0.039160 0.546579 +0.176994 0.590459 +0.126923 0.605722 +0.126923 0.566197 +0.176994 0.566197 +0.043636 0.459622 +0.948250 0.510273 +0.948250 0.534535 +0.043636 0.483883 +0.200504 0.575951 +0.250574 0.560688 +0.250574 0.600213 +0.200504 0.600213 +0.947894 0.560960 +0.043280 0.560960 +0.076852 0.590459 +0.076852 0.566197 +0.300645 0.575951 +0.300645 0.600213 +0.947894 0.460818 +0.043280 0.460818 +0.043280 0.510889 +0.947894 0.510889 +0.040852 0.522376 +0.039160 0.546579 +0.945103 0.559154 +0.946795 0.534951 +0.176994 0.590459 +0.176994 0.566197 +0.126923 0.566197 +0.126923 0.605722 +0.043636 0.459622 +0.043636 0.483883 +0.948250 0.534535 +0.948250 0.510273 +0.200504 0.575951 +0.200504 0.600213 +0.250574 0.600213 +0.250574 0.560688 +0.043280 0.560960 +0.947894 0.560960 +0.076852 0.566197 +0.076852 0.590459 +0.300645 0.600213 +0.300645 0.575951 +0.056753 0.146942 +0.056753 0.150229 +0.044853 0.150229 +0.044853 0.146942 +0.044853 0.151136 +0.056753 0.151136 +0.056753 0.154424 +0.044853 0.154424 +0.044853 0.167008 +0.044853 0.155109 +0.958938 0.155109 +0.958938 0.167008 +0.958938 0.183016 +0.958938 0.186304 +0.044853 0.186304 +0.044853 0.183016 +0.958938 0.169371 +0.958938 0.181270 +0.044853 0.181270 +0.044853 0.169371 +0.044853 0.191338 +0.044853 0.188050 +0.958938 0.188050 +0.958938 0.191338 +0.056753 0.146942 +0.056753 0.150229 +0.044853 0.150229 +0.044853 0.146942 +0.044853 0.151136 +0.056753 0.151136 +0.056753 0.154424 +0.044853 0.154424 +0.044853 0.167008 +0.044853 0.155109 +0.958938 0.155109 +0.958938 0.167008 +0.958938 0.183016 +0.958938 0.186304 +0.044853 0.186304 +0.044853 0.183016 +0.958938 0.169371 +0.958938 0.181270 +0.044853 0.181270 +0.044853 0.169371 +0.044853 0.191338 +0.044853 0.188050 +0.958938 0.188050 +0.958938 0.191338 + + + + + + + + + + + +

0 0 8 10 1 0 8 2 1 1 3 9 10 4 0 0 5 8 2 6 3 11 7 17 10 8 18 2 9 3 10 10 18 1 11 2 18 12 34 1 13 4 17 14 5 1 15 4 18 16 34 2 17 35 17 18 5 19 19 43 18 20 34 9 21 13 3 22 10 0 23 11 9 24 13 0 25 11 8 26 12 22 27 26 10 28 14 11 29 15 10 30 14 22 31 26 24 32 27 22 33 26 23 34 48 24 35 27 27 36 20 26 37 21 25 38 22 4 39 24 15 40 25 5 41 7 14 42 6 5 43 7 15 44 25 16 45 29 21 46 30 20 47 31 12 48 38 6 49 36 7 50 37 6 51 36 12 52 38 13 53 39 4 54 28 17 55 33 6 56 19 16 57 16 6 58 19 17 59 33 19 60 43 4 61 44 5 62 45 4 63 44 19 64 43 17 65 5 15 66 51 23 67 48 14 68 49 23 69 48 15 70 51 24 71 27 13 72 50 24 73 40 15 74 42 24 75 40 13 76 50 27 77 55 26 78 21 13 79 23 12 80 52 13 81 23 26 82 21 27 83 20 8 84 54 25 85 22 9 86 53 25 87 22 8 88 54 27 89 20 21 90 30 0 91 32 3 92 41 0 93 32 21 94 30 16 95 29 6 96 47 20 97 31 7 98 46 20 99 31 6 100 47 16 101 29 27 102 55 8 103 1 24 104 40 10 105 0 24 106 40 8 107 1 17 108 33 0 109 8 16 110 16 0 111 8 17 112 33 1 113 9 15 114 42 4 115 28 6 116 19 15 117 42 6 118 19 13 119 50 37 120 97 28 121 58 36 122 84 29 123 56 28 124 58 37 125 97 30 126 59 38 127 64 39 128 68 30 129 59 39 130 68 40 131 83 32 132 128 31 133 102 95 134 109 95 135 109 109 136 123 32 137 128 94 138 105 33 139 89 112 140 101 33 141 89 94 142 105 34 143 115 93 144 129 97 145 130 31 146 102 97 147 130 95 148 109 31 149 102 77 150 141 65 151 137 42 152 138 87 153 132 65 154 137 77 155 141 81 156 131 53 157 135 91 158 127 53 159 135 81 160 131 59 161 134 58 162 88 80 163 96 65 164 67 75 165 57 65 166 67 80 167 96 84 168 143 54 169 152 92 170 142 54 171 152 84 172 143 62 173 151 88 174 147 58 175 139 67 176 146 80 177 136 58 178 139 88 179 147 79 180 159 29 181 56 37 182 97 75 183 158 29 184 56 79 185 159 65 186 137 78 187 160 56 188 161 78 189 160 65 190 137 75 191 158 32 192 128 99 193 180 71 194 172 71 195 172 99 196 180 87 197 132 99 198 180 32 199 128 136 200 175 83 201 155 69 202 164 30 203 59 69 204 164 83 205 155 46 206 156 82 207 176 69 208 164 61 209 167 91 210 127 69 211 164 82 212 176 35 213 189 53 214 135 73 215 177 73 216 177 53 217 135 44 218 193 96 219 114 72 220 122 99 221 108 87 222 104 99 223 108 72 224 122 72 225 122 58 226 88 87 227 104 65 228 67 87 229 104 58 230 88 75 231 57 38 232 133 29 233 140 38 234 133 75 235 57 80 236 96 86 237 185 70 238 203 93 239 129 70 240 203 86 241 185 49 242 186 85 243 276 70 244 203 64 245 275 92 246 142 70 247 203 85 248 276 28 249 58 54 250 152 74 251 277 74 252 277 54 253 152 47 254 278 33 255 89 96 256 209 98 257 210 90 258 227 96 259 209 33 260 89 72 261 208 96 262 209 90 263 227 58 264 139 89 265 232 51 266 233 89 267 232 58 268 139 72 269 208 38 270 64 76 271 234 39 272 68 76 273 234 38 274 64 80 275 136 75 276 158 43 277 279 57 278 280 65 279 137 56 280 161 42 281 138 55 282 281 41 283 282 87 284 132 69 285 164 46 286 156 61 287 167 91 288 127 60 289 235 45 290 236 59 291 134 44 292 193 53 293 135 49 294 186 41 295 282 64 296 275 64 297 275 41 298 282 55 299 281 63 300 284 42 301 138 48 302 283 48 303 283 42 304 138 56 305 161 62 306 151 57 307 280 47 308 278 47 309 278 57 310 280 43 311 279 59 312 134 52 313 238 44 314 193 52 315 238 59 316 134 68 317 237 60 318 235 51 319 233 45 320 236 51 321 233 60 322 235 67 323 146 46 324 156 66 325 240 61 326 167 66 327 240 46 328 156 50 329 239 70 330 203 49 331 186 64 332 275 92 333 142 63 334 284 48 335 283 62 336 151 47 337 278 54 338 152 72 339 208 52 340 238 68 341 237 58 342 139 51 343 233 67 344 146 66 345 240 50 346 239 80 347 136 33 348 320 34 349 321 31 350 199 31 351 199 32 352 200 33 353 320 90 354 62 33 355 366 32 356 367 90 357 62 32 358 367 71 359 61 49 360 79 52 361 397 41 362 74 52 363 397 49 364 79 44 365 396 86 366 390 44 367 392 49 368 393 44 369 392 86 370 390 73 371 391 45 372 230 42 373 228 63 374 229 42 375 228 45 376 230 51 377 231 64 378 331 81 379 333 85 380 330 81 381 333 64 382 331 59 383 332 68 384 334 59 385 335 64 386 90 64 387 90 55 388 95 68 389 334 51 390 318 89 391 319 77 392 72 51 393 318 77 394 72 42 395 81 62 396 323 66 397 325 57 398 322 66 399 325 62 400 323 61 401 324 84 402 92 61 403 344 62 404 345 61 405 344 84 406 92 82 407 93 67 408 346 60 409 347 48 410 86 48 411 86 56 412 99 67 413 346 56 414 329 88 415 327 67 416 328 88 417 327 56 418 329 78 419 326 50 420 360 46 421 361 47 422 76 47 423 76 43 424 77 50 425 360 39 426 378 76 427 379 79 428 66 39 429 378 79 430 66 37 431 69 40 432 338 37 433 336 36 434 337 37 435 336 40 436 338 39 437 339 47 438 357 83 439 359 74 440 356 83 441 359 47 442 357 46 443 358 77 444 141 55 445 281 87 446 132 91 447 127 45 448 236 81 449 131 92 450 142 48 451 283 84 452 143 88 453 147 66 454 240 80 455 136 79 456 159 43 457 279 75 458 158 75 459 158 57 460 280 78 461 160 87 462 132 41 463 282 71 464 172 30 465 59 40 466 83 83 467 155 82 468 176 60 469 235 91 470 127 73 471 177 34 472 115 35 473 189 93 474 129 31 475 102 86 476 185 85 477 276 63 478 284 92 479 142 74 480 277 36 481 84 28 482 58 90 483 227 52 484 238 72 485 208 72 486 208 68 487 237 89 488 232 80 489 136 50 490 239 76 491 234 41 492 282 86 493 185 71 494 172 31 495 102 71 496 172 86 497 185 52 498 82 86 499 121 41 500 71 86 501 121 52 502 82 73 503 106 73 504 177 52 505 238 90 506 227 90 507 227 34 508 115 73 509 177 31 510 103 90 511 60 71 512 63 90 513 60 31 514 103 34 515 126 45 516 236 89 517 232 81 518 131 68 519 237 81 520 131 89 521 232 77 522 111 45 523 75 63 524 94 45 525 75 77 526 111 89 527 125 85 528 276 77 529 141 63 530 284 85 531 276 55 532 281 77 533 141 68 534 116 85 535 85 81 536 100 85 537 85 68 538 116 55 539 120 57 540 280 84 541 143 78 542 160 48 543 283 78 544 160 84 545 143 82 546 117 57 547 87 66 548 98 57 549 87 82 550 117 84 551 119 82 552 176 66 553 240 88 554 147 88 555 147 60 556 235 82 557 176 48 558 112 88 559 78 78 560 91 88 561 78 48 562 112 60 563 124 50 564 239 83 565 155 76 566 234 40 567 83 76 568 234 83 569 155 43 570 80 74 571 107 50 572 73 83 573 118 50 574 73 74 575 107 74 576 277 43 577 279 79 578 159 79 579 159 36 580 84 74 581 277 76 582 70 40 583 110 79 584 65 36 585 113 79 586 65 40 587 110 136 588 175 32 589 128 109 590 123 169 591 241 35 592 189 94 593 105 35 594 189 34 595 115 94 596 105 112 597 101 33 598 89 98 599 210 101 600 288 103 601 286 102 602 287 101 603 288 100 604 285 103 605 286 106 606 244 105 607 242 107 608 243 104 609 245 105 610 242 106 611 244 108 612 289 110 613 290 95 614 109 95 615 109 110 616 290 109 617 123 94 618 105 111 619 246 113 620 247 111 621 246 94 622 105 112 623 101 97 624 130 114 625 291 108 626 289 97 627 130 108 628 289 95 629 109 116 630 295 115 631 292 118 632 293 118 633 293 117 634 294 116 635 295 122 636 249 120 637 251 119 638 248 120 639 251 122 640 249 121 641 250 116 642 171 123 643 168 125 644 169 116 645 171 125 646 169 124 647 170 129 648 297 127 649 299 126 650 296 127 651 299 129 652 297 128 653 298 124 654 255 125 655 252 131 656 253 131 657 253 130 658 254 124 659 255 100 660 285 123 661 300 132 662 301 132 663 301 103 664 286 100 665 285 116 666 295 133 667 303 123 668 300 133 669 303 116 670 295 134 671 302 110 672 290 99 673 180 136 674 175 99 675 180 135 676 304 115 677 292 135 678 304 99 679 180 110 680 290 139 681 256 137 682 258 105 683 242 137 684 258 139 685 256 138 686 257 139 687 256 119 688 248 141 689 259 139 690 256 141 691 259 140 692 260 122 693 249 143 694 263 142 695 261 122 696 249 142 697 261 144 698 262 99 699 108 115 700 195 145 701 196 99 702 108 145 703 196 96 704 114 115 705 195 116 706 171 124 707 170 115 708 195 124 709 170 145 710 196 123 711 168 100 712 197 104 713 198 123 714 168 104 715 198 125 716 169 148 717 305 146 718 307 114 719 291 146 720 307 148 721 305 147 722 306 148 723 305 126 724 296 150 725 308 148 726 305 150 727 308 149 728 309 129 729 297 101 730 288 151 731 310 129 732 297 151 733 310 152 734 311 96 735 209 145 736 264 153 737 265 96 738 209 153 739 265 111 740 246 96 741 209 111 742 246 98 743 210 124 744 255 154 745 267 145 746 264 154 747 267 124 748 255 155 749 266 104 750 245 156 751 268 125 752 252 156 753 268 104 754 245 106 755 244 123 756 300 158 757 312 157 758 313 116 759 295 117 760 294 134 761 302 159 762 314 115 763 292 160 764 315 139 765 256 140 766 260 138 767 257 119 768 248 162 769 269 161 770 270 121 771 250 122 772 249 144 773 262 160 774 315 147 775 306 149 776 309 149 777 309 159 778 314 160 779 315 117 780 294 164 781 317 163 782 316 163 783 316 134 784 302 117 785 294 152 786 311 158 787 312 128 788 298 158 789 312 152 790 311 157 791 313 121 792 250 166 793 272 165 794 271 166 795 272 121 796 250 144 797 262 161 798 270 155 799 266 130 800 254 155 801 266 161 802 270 162 803 269 138 804 257 168 805 273 167 806 274 168 807 273 138 808 257 140 809 260 148 810 305 149 811 309 147 812 306 126 813 296 163 814 316 164 815 317 128 816 298 129 817 297 152 818 311 145 819 264 165 820 271 166 821 272 124 822 255 130 823 254 155 824 266 168 825 273 125 826 252 167 827 274 113 828 349 111 829 350 108 830 348 108 831 348 111 832 350 110 833 351 153 834 389 110 835 154 111 836 388 110 837 154 153 838 389 135 839 153 147 840 375 166 841 373 144 842 374 166 843 373 147 844 375 160 845 372 144 846 402 146 847 194 147 848 202 146 849 194 144 850 402 142 851 403 164 852 385 117 853 162 162 854 384 162 855 384 117 856 162 155 857 213 120 858 204 149 859 407 150 860 166 149 861 407 120 862 204 121 863 406 121 864 363 165 865 364 149 866 362 149 867 362 165 868 364 159 869 365 155 870 342 118 871 340 154 872 341 118 873 340 155 874 342 117 875 343 128 876 395 168 877 190 140 878 394 168 879 190 128 880 395 158 881 174 140 882 370 127 883 368 128 884 369 127 885 368 140 886 370 141 887 371 161 888 183 130 889 376 163 890 178 163 891 178 130 892 376 134 893 377 131 894 355 134 895 353 130 896 354 134 897 353 131 898 355 133 899 352 138 900 207 167 901 386 152 902 188 152 903 188 167 904 386 157 905 387 106 906 400 132 907 398 156 908 399 132 909 398 106 910 400 103 911 401 102 912 405 103 913 145 107 914 404 107 915 404 103 916 145 106 917 148 137 918 381 152 919 383 151 920 380 152 921 383 137 922 381 138 923 382 118 924 293 115 925 292 159 926 314 119 927 248 120 928 251 162 929 269 126 930 296 127 931 299 163 932 316 131 933 253 125 934 252 168 935 273 132 936 301 123 937 300 157 938 313 123 939 300 133 940 303 158 941 312 115 942 292 135 943 304 160 944 315 105 945 242 137 946 258 107 947 243 141 948 259 119 949 248 161 950 270 142 951 261 143 952 263 113 953 247 114 954 291 146 955 307 108 956 289 150 957 308 126 958 296 164 959 317 151 960 310 101 961 288 102 962 287 153 963 265 145 964 264 166 965 272 145 966 264 154 967 267 165 968 271 125 969 252 156 970 268 167 971 274 146 972 307 160 973 315 135 974 304 135 975 304 108 976 289 146 977 307 166 978 224 146 979 201 142 980 218 146 981 201 166 982 224 160 983 192 113 984 247 153 985 265 142 986 261 166 987 272 142 988 261 153 989 265 108 990 184 135 991 211 153 992 150 108 993 184 153 994 150 113 995 157 120 996 251 165 997 271 154 998 267 154 999 267 162 1000 269 120 1001 251 118 1002 220 164 1003 222 162 1004 163 118 1005 220 162 1006 163 154 1007 212 159 1008 314 150 1009 308 118 1010 293 164 1011 317 118 1012 293 150 1013 308 165 1014 217 120 1015 223 150 1016 165 165 1017 217 150 1018 165 159 1019 205 127 1020 299 158 1021 312 133 1022 303 133 1023 303 163 1024 316 127 1025 299 141 1026 216 168 1027 226 158 1028 173 141 1029 216 158 1030 173 127 1031 191 168 1032 273 141 1033 259 131 1034 253 161 1035 270 131 1036 253 141 1037 259 163 1038 219 133 1039 221 131 1040 179 163 1041 219 131 1042 179 161 1043 182 137 1044 258 167 1045 274 156 1046 268 156 1047 268 107 1048 243 137 1049 258 167 1050 187 137 1051 206 151 1052 215 167 1053 187 151 1054 215 157 1055 225 157 1056 313 151 1057 310 132 1058 301 102 1059 287 132 1060 301 151 1061 310 132 1062 144 102 1063 149 107 1064 181 132 1065 144 107 1066 181 156 1067 214 136 1068 175 109 1069 123 110 1070 290 143 1071 263 169 1072 241 94 1073 105 143 1074 263 94 1075 105 113 1076 247 112 1077 101 98 1078 210 111 1079 246 179 1080 449 170 1081 410 178 1082 436 171 1083 408 170 1084 410 179 1085 449 172 1086 411 180 1087 416 181 1088 420 172 1089 411 181 1090 420 182 1091 435 174 1092 480 173 1093 454 237 1094 461 237 1095 461 251 1096 475 174 1097 480 236 1098 457 175 1099 441 254 1100 453 175 1101 441 236 1102 457 176 1103 467 235 1104 481 239 1105 482 173 1106 454 239 1107 482 237 1108 461 173 1109 454 219 1110 493 207 1111 489 184 1112 490 229 1113 484 207 1114 489 219 1115 493 223 1116 483 195 1117 487 233 1118 479 195 1119 487 223 1120 483 201 1121 486 200 1122 440 222 1123 448 207 1124 419 217 1125 409 207 1126 419 222 1127 448 226 1128 495 196 1129 504 234 1130 494 196 1131 504 226 1132 495 204 1133 503 230 1134 499 200 1135 491 209 1136 498 222 1137 488 200 1138 491 230 1139 499 221 1140 511 171 1141 408 179 1142 449 217 1143 510 171 1144 408 221 1145 511 207 1146 489 220 1147 512 198 1148 513 220 1149 512 207 1150 489 217 1151 510 174 1152 480 241 1153 532 213 1154 524 213 1155 524 241 1156 532 229 1157 484 241 1158 532 174 1159 480 278 1160 527 225 1161 507 211 1162 516 172 1163 411 211 1164 516 225 1165 507 188 1166 508 224 1167 528 211 1168 516 203 1169 519 233 1170 479 211 1171 516 224 1172 528 177 1173 541 195 1174 487 215 1175 529 215 1176 529 195 1177 487 186 1178 545 238 1179 466 214 1180 474 241 1181 460 229 1182 456 241 1183 460 214 1184 474 214 1185 474 200 1186 440 229 1187 456 207 1188 419 229 1189 456 200 1190 440 217 1191 409 180 1192 485 171 1193 492 180 1194 485 217 1195 409 222 1196 448 228 1197 537 212 1198 555 235 1199 481 212 1200 555 228 1201 537 191 1202 538 227 1203 628 212 1204 555 206 1205 627 234 1206 494 212 1207 555 227 1208 628 170 1209 410 196 1210 504 216 1211 629 216 1212 629 196 1213 504 189 1214 630 175 1215 441 238 1216 561 240 1217 562 232 1218 579 238 1219 561 175 1220 441 214 1221 560 238 1222 561 232 1223 579 200 1224 491 231 1225 584 193 1226 585 231 1227 584 200 1228 491 214 1229 560 180 1230 416 218 1231 586 181 1232 420 218 1233 586 180 1234 416 222 1235 488 217 1236 510 185 1237 631 199 1238 632 207 1239 489 198 1240 513 184 1241 490 197 1242 633 183 1243 634 229 1244 484 211 1245 516 188 1246 508 203 1247 519 233 1248 479 202 1249 587 187 1250 588 201 1251 486 186 1252 545 195 1253 487 191 1254 538 183 1255 634 206 1256 627 206 1257 627 183 1258 634 197 1259 633 205 1260 636 184 1261 490 190 1262 635 190 1263 635 184 1264 490 198 1265 513 204 1266 503 199 1267 632 189 1268 630 189 1269 630 199 1270 632 185 1271 631 201 1272 486 194 1273 590 186 1274 545 194 1275 590 201 1276 486 210 1277 589 202 1278 587 193 1279 585 187 1280 588 193 1281 585 202 1282 587 209 1283 498 188 1284 508 208 1285 592 203 1286 519 208 1287 592 188 1288 508 192 1289 591 212 1290 555 191 1291 538 206 1292 627 234 1293 494 205 1294 636 190 1295 635 204 1296 503 189 1297 630 196 1298 504 214 1299 560 194 1300 590 210 1301 589 200 1302 491 193 1303 585 209 1304 498 208 1305 592 192 1306 591 222 1307 488 175 1308 672 176 1309 673 173 1310 551 173 1311 551 174 1312 552 175 1313 672 232 1314 414 175 1315 718 174 1316 719 232 1317 414 174 1318 719 213 1319 413 191 1320 431 194 1321 749 183 1322 426 194 1323 749 191 1324 431 186 1325 748 228 1326 742 186 1327 744 191 1328 745 186 1329 744 228 1330 742 215 1331 743 187 1332 582 184 1333 580 205 1334 581 184 1335 580 187 1336 582 193 1337 583 206 1338 683 223 1339 685 227 1340 682 223 1341 685 206 1342 683 201 1343 684 210 1344 686 201 1345 687 206 1346 442 206 1347 442 197 1348 447 210 1349 686 193 1350 670 231 1351 671 219 1352 424 193 1353 670 219 1354 424 184 1355 433 204 1356 675 208 1357 677 199 1358 674 208 1359 677 204 1360 675 203 1361 676 226 1362 444 203 1363 696 204 1364 697 203 1365 696 226 1366 444 224 1367 445 209 1368 698 202 1369 699 190 1370 438 190 1371 438 198 1372 451 209 1373 698 198 1374 681 230 1375 679 209 1376 680 230 1377 679 198 1378 681 220 1379 678 192 1380 712 188 1381 713 189 1382 428 189 1383 428 185 1384 429 192 1385 712 181 1386 730 218 1387 731 221 1388 418 181 1389 730 221 1390 418 179 1391 421 182 1392 690 179 1393 688 178 1394 689 179 1395 688 182 1396 690 181 1397 691 189 1398 709 225 1399 711 216 1400 708 225 1401 711 189 1402 709 188 1403 710 219 1404 493 197 1405 633 229 1406 484 233 1407 479 187 1408 588 223 1409 483 234 1410 494 190 1411 635 226 1412 495 230 1413 499 208 1414 592 222 1415 488 221 1416 511 185 1417 631 217 1418 510 217 1419 510 199 1420 632 220 1421 512 229 1422 484 183 1423 634 213 1424 524 172 1425 411 182 1426 435 225 1427 507 224 1428 528 202 1429 587 233 1430 479 215 1431 529 176 1432 467 177 1433 541 235 1434 481 173 1435 454 228 1436 537 227 1437 628 205 1438 636 234 1439 494 216 1440 629 178 1441 436 170 1442 410 232 1443 579 194 1444 590 214 1445 560 214 1446 560 210 1447 589 231 1448 584 222 1449 488 192 1450 591 218 1451 586 183 1452 634 228 1453 537 213 1454 524 173 1455 454 213 1456 524 228 1457 537 194 1458 434 228 1459 473 183 1460 423 228 1461 473 194 1462 434 215 1463 458 215 1464 529 194 1465 590 232 1466 579 232 1467 579 176 1468 467 215 1469 529 173 1470 455 232 1471 412 213 1472 415 232 1473 412 173 1474 455 176 1475 478 187 1476 588 231 1477 584 223 1478 483 210 1479 589 223 1480 483 231 1481 584 219 1482 463 187 1483 427 205 1484 446 187 1485 427 219 1486 463 231 1487 477 227 1488 628 219 1489 493 205 1490 636 227 1491 628 197 1492 633 219 1493 493 210 1494 468 227 1495 437 223 1496 452 227 1497 437 210 1498 468 197 1499 472 199 1500 632 226 1501 495 220 1502 512 190 1503 635 220 1504 512 226 1505 495 224 1506 469 199 1507 439 208 1508 450 199 1509 439 224 1510 469 226 1511 471 224 1512 528 208 1513 592 230 1514 499 230 1515 499 202 1516 587 224 1517 528 190 1518 464 230 1519 430 220 1520 443 230 1521 430 190 1522 464 202 1523 476 192 1524 591 225 1525 507 218 1526 586 182 1527 435 218 1528 586 225 1529 507 185 1530 432 216 1531 459 192 1532 425 225 1533 470 192 1534 425 216 1535 459 216 1536 629 185 1537 631 221 1538 511 221 1539 511 178 1540 436 216 1541 629 218 1542 422 182 1543 462 221 1544 417 178 1545 465 221 1546 417 182 1547 462 278 1548 527 174 1549 480 251 1550 475 311 1551 593 177 1552 541 236 1553 457 177 1554 541 176 1555 467 236 1556 457 254 1557 453 175 1558 441 240 1559 562 243 1560 640 245 1561 638 244 1562 639 243 1563 640 242 1564 637 245 1565 638 248 1566 596 247 1567 594 249 1568 595 246 1569 597 247 1570 594 248 1571 596 250 1572 641 252 1573 642 237 1574 461 237 1575 461 252 1576 642 251 1577 475 236 1578 457 253 1579 598 255 1580 599 253 1581 598 236 1582 457 254 1583 453 239 1584 482 256 1585 643 250 1586 641 239 1587 482 250 1588 641 237 1589 461 258 1590 647 257 1591 644 260 1592 645 260 1593 645 259 1594 646 258 1595 647 264 1596 601 262 1597 603 261 1598 600 262 1599 603 264 1600 601 263 1601 602 258 1602 523 265 1603 520 267 1604 521 258 1605 523 267 1606 521 266 1607 522 271 1608 649 269 1609 651 268 1610 648 269 1611 651 271 1612 649 270 1613 650 266 1614 607 267 1615 604 273 1616 605 273 1617 605 272 1618 606 266 1619 607 242 1620 637 265 1621 652 274 1622 653 274 1623 653 245 1624 638 242 1625 637 258 1626 647 275 1627 655 265 1628 652 275 1629 655 258 1630 647 276 1631 654 252 1632 642 241 1633 532 278 1634 527 241 1635 532 277 1636 656 257 1637 644 277 1638 656 241 1639 532 252 1640 642 281 1641 608 279 1642 610 247 1643 594 279 1644 610 281 1645 608 280 1646 609 281 1647 608 261 1648 600 283 1649 611 281 1650 608 283 1651 611 282 1652 612 264 1653 601 285 1654 615 284 1655 613 264 1656 601 284 1657 613 286 1658 614 241 1659 460 257 1660 547 287 1661 548 241 1662 460 287 1663 548 238 1664 466 257 1665 547 258 1666 523 266 1667 522 257 1668 547 266 1669 522 287 1670 548 265 1671 520 242 1672 549 246 1673 550 265 1674 520 246 1675 550 267 1676 521 290 1677 657 288 1678 659 256 1679 643 288 1680 659 290 1681 657 289 1682 658 290 1683 657 268 1684 648 292 1685 660 290 1686 657 292 1687 660 291 1688 661 271 1689 649 243 1690 640 293 1691 662 271 1692 649 293 1693 662 294 1694 663 238 1695 561 287 1696 616 295 1697 617 238 1698 561 295 1699 617 253 1700 598 238 1701 561 253 1702 598 240 1703 562 266 1704 607 296 1705 619 287 1706 616 296 1707 619 266 1708 607 297 1709 618 246 1710 597 298 1711 620 267 1712 604 298 1713 620 246 1714 597 248 1715 596 265 1716 652 300 1717 664 299 1718 665 258 1719 647 259 1720 646 276 1721 654 301 1722 666 257 1723 644 302 1724 667 281 1725 608 282 1726 612 280 1727 609 261 1728 600 304 1729 621 303 1730 622 263 1731 602 264 1732 601 286 1733 614 302 1734 667 289 1735 658 291 1736 661 291 1737 661 301 1738 666 302 1739 667 259 1740 646 306 1741 669 305 1742 668 305 1743 668 276 1744 654 259 1745 646 294 1746 663 300 1747 664 270 1748 650 300 1749 664 294 1750 663 299 1751 665 263 1752 602 308 1753 624 307 1754 623 308 1755 624 263 1756 602 286 1757 614 303 1758 622 297 1759 618 272 1760 606 297 1761 618 303 1762 622 304 1763 621 280 1764 609 310 1765 625 309 1766 626 310 1767 625 280 1768 609 282 1769 612 290 1770 657 291 1771 661 289 1772 658 268 1773 648 305 1774 668 306 1775 669 270 1776 650 271 1777 649 294 1778 663 287 1779 616 307 1780 623 308 1781 624 266 1782 607 272 1783 606 297 1784 618 310 1785 625 267 1786 604 309 1787 626 255 1788 701 253 1789 702 250 1790 700 250 1791 700 253 1792 702 252 1793 703 295 1794 741 252 1795 506 253 1796 740 252 1797 506 295 1798 741 277 1799 505 289 1800 727 308 1801 725 286 1802 726 308 1803 725 289 1804 727 302 1805 724 286 1806 754 288 1807 546 289 1808 554 288 1809 546 286 1810 754 284 1811 755 306 1812 737 259 1813 514 304 1814 736 304 1815 736 259 1816 514 297 1817 565 262 1818 556 291 1819 759 292 1820 518 291 1821 759 262 1822 556 263 1823 758 263 1824 715 307 1825 716 291 1826 714 291 1827 714 307 1828 716 301 1829 717 297 1830 694 260 1831 692 296 1832 693 260 1833 692 297 1834 694 259 1835 695 270 1836 747 310 1837 542 282 1838 746 310 1839 542 270 1840 747 300 1841 526 282 1842 722 269 1843 720 270 1844 721 269 1845 720 282 1846 722 283 1847 723 303 1848 535 272 1849 728 305 1850 530 305 1851 530 272 1852 728 276 1853 729 273 1854 707 276 1855 705 272 1856 706 276 1857 705 273 1858 707 275 1859 704 280 1860 559 309 1861 738 294 1862 540 294 1863 540 309 1864 738 299 1865 739 248 1866 752 274 1867 750 298 1868 751 274 1869 750 248 1870 752 245 1871 753 244 1872 757 245 1873 497 249 1874 756 249 1875 756 245 1876 497 248 1877 500 279 1878 733 294 1879 735 293 1880 732 294 1881 735 279 1882 733 280 1883 734 260 1884 645 257 1885 644 301 1886 666 261 1887 600 262 1888 603 304 1889 621 268 1890 648 269 1891 651 305 1892 668 273 1893 605 267 1894 604 310 1895 625 274 1896 653 265 1897 652 299 1898 665 265 1899 652 275 1900 655 300 1901 664 257 1902 644 277 1903 656 302 1904 667 247 1905 594 279 1906 610 249 1907 595 283 1908 611 261 1909 600 303 1910 622 284 1911 613 285 1912 615 255 1913 599 256 1914 643 288 1915 659 250 1916 641 292 1917 660 268 1918 648 306 1919 669 293 1920 662 243 1921 640 244 1922 639 295 1923 617 287 1924 616 308 1925 624 287 1926 616 296 1927 619 307 1928 623 267 1929 604 298 1930 620 309 1931 626 288 1932 659 302 1933 667 277 1934 656 277 1935 656 250 1936 641 288 1937 659 308 1938 576 288 1939 553 284 1940 570 288 1941 553 308 1942 576 302 1943 544 255 1944 599 295 1945 617 284 1946 613 308 1947 624 284 1948 613 295 1949 617 250 1950 536 277 1951 563 295 1952 502 250 1953 536 295 1954 502 255 1955 509 262 1956 603 307 1957 623 296 1958 619 296 1959 619 304 1960 621 262 1961 603 260 1962 572 306 1963 574 304 1964 515 260 1965 572 304 1966 515 296 1967 564 301 1968 666 292 1969 660 260 1970 645 306 1971 669 260 1972 645 292 1973 660 307 1974 569 262 1975 575 292 1976 517 307 1977 569 292 1978 517 301 1979 557 269 1980 651 300 1981 664 275 1982 655 275 1983 655 305 1984 668 269 1985 651 283 1986 568 310 1987 578 300 1988 525 283 1989 568 300 1990 525 269 1991 543 310 1992 625 283 1993 611 273 1994 605 303 1995 622 273 1996 605 283 1997 611 305 1998 571 275 1999 573 273 2000 531 305 2001 571 273 2002 531 303 2003 534 279 2004 610 309 2005 626 298 2006 620 298 2007 620 249 2008 595 279 2009 610 293 2010 567 309 2011 539 279 2012 558 309 2013 539 293 2014 567 299 2015 577 299 2016 665 293 2017 662 274 2018 653 244 2019 639 274 2020 653 293 2021 662 249 2022 533 274 2023 496 244 2024 501 274 2025 496 249 2026 533 298 2027 566 278 2028 527 251 2029 475 252 2030 642 285 2031 615 311 2032 593 236 2033 457 285 2034 615 236 2035 457 255 2036 599 254 2037 453 240 2038 562 253 2039 598 321 2040 801 312 2041 762 320 2042 788 313 2043 760 312 2044 762 321 2045 801 314 2046 763 322 2047 768 323 2048 772 314 2049 763 323 2050 772 324 2051 787 316 2052 832 315 2053 806 379 2054 813 379 2055 813 393 2056 827 316 2057 832 378 2058 809 317 2059 793 396 2060 805 317 2061 793 378 2062 809 318 2063 819 377 2064 833 381 2065 834 315 2066 806 381 2067 834 379 2068 813 315 2069 806 361 2070 845 349 2071 841 326 2072 842 371 2073 836 349 2074 841 361 2075 845 365 2076 835 337 2077 839 375 2078 831 337 2079 839 365 2080 835 343 2081 838 342 2082 792 364 2083 800 349 2084 771 359 2085 761 349 2086 771 364 2087 800 368 2088 847 338 2089 856 376 2090 846 338 2091 856 368 2092 847 346 2093 855 372 2094 851 342 2095 843 351 2096 850 364 2097 840 342 2098 843 372 2099 851 363 2100 863 313 2101 760 321 2102 801 359 2103 862 313 2104 760 363 2105 863 349 2106 841 362 2107 864 340 2108 865 362 2109 864 349 2110 841 359 2111 862 316 2112 832 383 2113 884 355 2114 876 355 2115 876 383 2116 884 371 2117 836 383 2118 884 316 2119 832 420 2120 879 367 2121 859 353 2122 868 314 2123 763 353 2124 868 367 2125 859 330 2126 860 366 2127 880 353 2128 868 345 2129 871 375 2130 831 353 2131 868 366 2132 880 319 2133 893 337 2134 839 357 2135 881 357 2136 881 337 2137 839 328 2138 897 380 2139 818 356 2140 826 383 2141 812 371 2142 808 383 2143 812 356 2144 826 356 2145 826 342 2146 792 371 2147 808 349 2148 771 371 2149 808 342 2150 792 359 2151 761 322 2152 837 313 2153 844 322 2154 837 359 2155 761 364 2156 800 370 2157 889 354 2158 907 377 2159 833 354 2160 907 370 2161 889 333 2162 890 369 2163 980 354 2164 907 348 2165 979 376 2166 846 354 2167 907 369 2168 980 312 2169 762 338 2170 856 358 2171 981 358 2172 981 338 2173 856 331 2174 982 317 2175 793 380 2176 913 382 2177 914 374 2178 931 380 2179 913 317 2180 793 356 2181 912 380 2182 913 374 2183 931 342 2184 843 373 2185 936 335 2186 937 373 2187 936 342 2188 843 356 2189 912 322 2190 768 360 2191 938 323 2192 772 360 2193 938 322 2194 768 364 2195 840 359 2196 862 327 2197 983 341 2198 984 349 2199 841 340 2200 865 326 2201 842 339 2202 985 325 2203 986 371 2204 836 353 2205 868 330 2206 860 345 2207 871 375 2208 831 344 2209 939 329 2210 940 343 2211 838 328 2212 897 337 2213 839 333 2214 890 325 2215 986 348 2216 979 348 2217 979 325 2218 986 339 2219 985 347 2220 988 326 2221 842 332 2222 987 332 2223 987 326 2224 842 340 2225 865 346 2226 855 341 2227 984 331 2228 982 331 2229 982 341 2230 984 327 2231 983 343 2232 838 336 2233 942 328 2234 897 336 2235 942 343 2236 838 352 2237 941 344 2238 939 335 2239 937 329 2240 940 335 2241 937 344 2242 939 351 2243 850 330 2244 860 350 2245 944 345 2246 871 350 2247 944 330 2248 860 334 2249 943 354 2250 907 333 2251 890 348 2252 979 376 2253 846 347 2254 988 332 2255 987 346 2256 855 331 2257 982 338 2258 856 356 2259 912 336 2260 942 352 2261 941 342 2262 843 335 2263 937 351 2264 850 350 2265 944 334 2266 943 364 2267 840 317 2268 1024 318 2269 1025 315 2270 903 315 2271 903 316 2272 904 317 2273 1024 374 2274 766 317 2275 1070 316 2276 1071 374 2277 766 316 2278 1071 355 2279 765 333 2280 783 336 2281 1101 325 2282 778 336 2283 1101 333 2284 783 328 2285 1100 370 2286 1094 328 2287 1096 333 2288 1097 328 2289 1096 370 2290 1094 357 2291 1095 329 2292 934 326 2293 932 347 2294 933 326 2295 932 329 2296 934 335 2297 935 348 2298 1035 365 2299 1037 369 2300 1034 365 2301 1037 348 2302 1035 343 2303 1036 352 2304 1038 343 2305 1039 348 2306 794 348 2307 794 339 2308 799 352 2309 1038 335 2310 1022 373 2311 1023 361 2312 776 335 2313 1022 361 2314 776 326 2315 785 346 2316 1027 350 2317 1029 341 2318 1026 350 2319 1029 346 2320 1027 345 2321 1028 368 2322 796 345 2323 1048 346 2324 1049 345 2325 1048 368 2326 796 366 2327 797 351 2328 1050 344 2329 1051 332 2330 790 332 2331 790 340 2332 803 351 2333 1050 340 2334 1033 372 2335 1031 351 2336 1032 372 2337 1031 340 2338 1033 362 2339 1030 334 2340 1064 330 2341 1065 331 2342 780 331 2343 780 327 2344 781 334 2345 1064 323 2346 1082 360 2347 1083 363 2348 770 323 2349 1082 363 2350 770 321 2351 773 324 2352 1042 321 2353 1040 320 2354 1041 321 2355 1040 324 2356 1042 323 2357 1043 331 2358 1061 367 2359 1063 358 2360 1060 367 2361 1063 331 2362 1061 330 2363 1062 361 2364 845 339 2365 985 371 2366 836 375 2367 831 329 2368 940 365 2369 835 376 2370 846 332 2371 987 368 2372 847 372 2373 851 350 2374 944 364 2375 840 363 2376 863 327 2377 983 359 2378 862 359 2379 862 341 2380 984 362 2381 864 371 2382 836 325 2383 986 355 2384 876 314 2385 763 324 2386 787 367 2387 859 366 2388 880 344 2389 939 375 2390 831 357 2391 881 318 2392 819 319 2393 893 377 2394 833 315 2395 806 370 2396 889 369 2397 980 347 2398 988 376 2399 846 358 2400 981 320 2401 788 312 2402 762 374 2403 931 336 2404 942 356 2405 912 356 2406 912 352 2407 941 373 2408 936 364 2409 840 334 2410 943 360 2411 938 325 2412 986 370 2413 889 355 2414 876 315 2415 806 355 2416 876 370 2417 889 336 2418 786 370 2419 825 325 2420 775 370 2421 825 336 2422 786 357 2423 810 357 2424 881 336 2425 942 374 2426 931 374 2427 931 318 2428 819 357 2429 881 315 2430 807 374 2431 764 355 2432 767 374 2433 764 315 2434 807 318 2435 830 329 2436 940 373 2437 936 365 2438 835 352 2439 941 365 2440 835 373 2441 936 361 2442 815 329 2443 779 347 2444 798 329 2445 779 361 2446 815 373 2447 829 369 2448 980 361 2449 845 347 2450 988 369 2451 980 339 2452 985 361 2453 845 352 2454 820 369 2455 789 365 2456 804 369 2457 789 352 2458 820 339 2459 824 341 2460 984 368 2461 847 362 2462 864 332 2463 987 362 2464 864 368 2465 847 366 2466 821 341 2467 791 350 2468 802 341 2469 791 366 2470 821 368 2471 823 366 2472 880 350 2473 944 372 2474 851 372 2475 851 344 2476 939 366 2477 880 332 2478 816 372 2479 782 362 2480 795 372 2481 782 332 2482 816 344 2483 828 334 2484 943 367 2485 859 360 2486 938 324 2487 787 360 2488 938 367 2489 859 327 2490 784 358 2491 811 334 2492 777 367 2493 822 334 2494 777 358 2495 811 358 2496 981 327 2497 983 363 2498 863 363 2499 863 320 2500 788 358 2501 981 360 2502 774 324 2503 814 363 2504 769 320 2505 817 363 2506 769 324 2507 814 420 2508 879 316 2509 832 393 2510 827 453 2511 945 319 2512 893 378 2513 809 319 2514 893 318 2515 819 378 2516 809 396 2517 805 317 2518 793 382 2519 914 385 2520 992 387 2521 990 386 2522 991 385 2523 992 384 2524 989 387 2525 990 390 2526 948 389 2527 946 391 2528 947 388 2529 949 389 2530 946 390 2531 948 392 2532 993 394 2533 994 379 2534 813 379 2535 813 394 2536 994 393 2537 827 378 2538 809 395 2539 950 397 2540 951 395 2541 950 378 2542 809 396 2543 805 381 2544 834 398 2545 995 392 2546 993 381 2547 834 392 2548 993 379 2549 813 400 2550 999 399 2551 996 402 2552 997 402 2553 997 401 2554 998 400 2555 999 406 2556 953 404 2557 955 403 2558 952 404 2559 955 406 2560 953 405 2561 954 400 2562 875 407 2563 872 409 2564 873 400 2565 875 409 2566 873 408 2567 874 413 2568 1001 411 2569 1003 410 2570 1000 411 2571 1003 413 2572 1001 412 2573 1002 408 2574 959 409 2575 956 415 2576 957 415 2577 957 414 2578 958 408 2579 959 384 2580 989 407 2581 1004 416 2582 1005 416 2583 1005 387 2584 990 384 2585 989 400 2586 999 417 2587 1007 407 2588 1004 417 2589 1007 400 2590 999 418 2591 1006 394 2592 994 383 2593 884 420 2594 879 383 2595 884 419 2596 1008 399 2597 996 419 2598 1008 383 2599 884 394 2600 994 423 2601 960 421 2602 962 389 2603 946 421 2604 962 423 2605 960 422 2606 961 423 2607 960 403 2608 952 425 2609 963 423 2610 960 425 2611 963 424 2612 964 406 2613 953 427 2614 967 426 2615 965 406 2616 953 426 2617 965 428 2618 966 383 2619 812 399 2620 899 429 2621 900 383 2622 812 429 2623 900 380 2624 818 399 2625 899 400 2626 875 408 2627 874 399 2628 899 408 2629 874 429 2630 900 407 2631 872 384 2632 901 388 2633 902 407 2634 872 388 2635 902 409 2636 873 432 2637 1009 430 2638 1011 398 2639 995 430 2640 1011 432 2641 1009 431 2642 1010 432 2643 1009 410 2644 1000 434 2645 1012 432 2646 1009 434 2647 1012 433 2648 1013 413 2649 1001 385 2650 992 435 2651 1014 413 2652 1001 435 2653 1014 436 2654 1015 380 2655 913 429 2656 968 437 2657 969 380 2658 913 437 2659 969 395 2660 950 380 2661 913 395 2662 950 382 2663 914 408 2664 959 438 2665 971 429 2666 968 438 2667 971 408 2668 959 439 2669 970 388 2670 949 440 2671 972 409 2672 956 440 2673 972 388 2674 949 390 2675 948 407 2676 1004 442 2677 1016 441 2678 1017 400 2679 999 401 2680 998 418 2681 1006 443 2682 1018 399 2683 996 444 2684 1019 423 2685 960 424 2686 964 422 2687 961 403 2688 952 446 2689 973 445 2690 974 405 2691 954 406 2692 953 428 2693 966 444 2694 1019 431 2695 1010 433 2696 1013 433 2697 1013 443 2698 1018 444 2699 1019 401 2700 998 448 2701 1021 447 2702 1020 447 2703 1020 418 2704 1006 401 2705 998 436 2706 1015 442 2707 1016 412 2708 1002 442 2709 1016 436 2710 1015 441 2711 1017 405 2712 954 450 2713 976 449 2714 975 450 2715 976 405 2716 954 428 2717 966 445 2718 974 439 2719 970 414 2720 958 439 2721 970 445 2722 974 446 2723 973 422 2724 961 452 2725 977 451 2726 978 452 2727 977 422 2728 961 424 2729 964 432 2730 1009 433 2731 1013 431 2732 1010 410 2733 1000 447 2734 1020 448 2735 1021 412 2736 1002 413 2737 1001 436 2738 1015 429 2739 968 449 2740 975 450 2741 976 408 2742 959 414 2743 958 439 2744 970 452 2745 977 409 2746 956 451 2747 978 395 2748 1054 392 2749 1052 397 2750 1053 392 2751 1052 395 2752 1054 394 2753 1055 437 2754 1093 394 2755 858 395 2756 1092 394 2757 858 437 2758 1093 419 2759 857 431 2760 1079 450 2761 1077 428 2762 1078 450 2763 1077 431 2764 1079 444 2765 1076 428 2766 1106 430 2767 898 431 2768 906 430 2769 898 428 2770 1106 426 2771 1107 448 2772 1089 401 2773 866 446 2774 1088 446 2775 1088 401 2776 866 439 2777 917 404 2778 908 433 2779 1111 434 2780 870 433 2781 1111 404 2782 908 405 2783 1110 405 2784 1067 449 2785 1068 433 2786 1066 433 2787 1066 449 2788 1068 443 2789 1069 439 2790 1046 402 2791 1044 438 2792 1045 402 2793 1044 439 2794 1046 401 2795 1047 412 2796 1099 452 2797 894 424 2798 1098 452 2799 894 412 2800 1099 442 2801 878 424 2802 1074 411 2803 1072 412 2804 1073 411 2805 1072 424 2806 1074 425 2807 1075 414 2808 1080 447 2809 882 445 2810 887 447 2811 882 414 2812 1080 418 2813 1081 415 2814 1059 418 2815 1057 414 2816 1058 418 2817 1057 415 2818 1059 417 2819 1056 422 2820 911 451 2821 1090 436 2822 892 436 2823 892 451 2824 1090 441 2825 1091 390 2826 1104 416 2827 1102 440 2828 1103 416 2829 1102 390 2830 1104 387 2831 1105 386 2832 1109 387 2833 849 391 2834 1108 391 2835 1108 387 2836 849 390 2837 852 421 2838 1085 436 2839 1087 435 2840 1084 436 2841 1087 421 2842 1085 422 2843 1086 402 2844 997 399 2845 996 443 2846 1018 403 2847 952 404 2848 955 446 2849 973 410 2850 1000 411 2851 1003 447 2852 1020 415 2853 957 409 2854 956 452 2855 977 416 2856 1005 407 2857 1004 441 2858 1017 407 2859 1004 417 2860 1007 442 2861 1016 399 2862 996 419 2863 1008 444 2864 1019 389 2865 946 421 2866 962 391 2867 947 425 2868 963 403 2869 952 445 2870 974 426 2871 965 427 2872 967 397 2873 951 398 2874 995 430 2875 1011 392 2876 993 434 2877 1012 410 2878 1000 448 2879 1021 435 2880 1014 385 2881 992 386 2882 991 437 2883 969 429 2884 968 450 2885 976 429 2886 968 438 2887 971 449 2888 975 409 2889 956 440 2890 972 451 2891 978 430 2892 1011 444 2893 1019 419 2894 1008 419 2895 1008 392 2896 993 430 2897 1011 450 2898 928 430 2899 905 426 2900 922 430 2901 905 450 2902 928 444 2903 896 397 2904 951 437 2905 969 426 2906 965 450 2907 976 426 2908 965 437 2909 969 392 2910 888 419 2911 915 437 2912 854 392 2913 888 437 2914 854 397 2915 861 404 2916 955 449 2917 975 438 2918 971 438 2919 971 446 2920 973 404 2921 955 402 2922 924 448 2923 926 446 2924 867 402 2925 924 446 2926 867 438 2927 916 443 2928 1018 434 2929 1012 402 2930 997 448 2931 1021 402 2932 997 434 2933 1012 449 2934 921 404 2935 927 434 2936 869 449 2937 921 434 2938 869 443 2939 909 411 2940 1003 442 2941 1016 417 2942 1007 417 2943 1007 447 2944 1020 411 2945 1003 425 2946 920 452 2947 930 442 2948 877 425 2949 920 442 2950 877 411 2951 895 452 2952 977 425 2953 963 415 2954 957 445 2955 974 415 2956 957 425 2957 963 447 2958 923 417 2959 925 415 2960 883 447 2961 923 415 2962 883 445 2963 886 421 2964 962 451 2965 978 440 2966 972 440 2967 972 391 2968 947 421 2969 962 435 2970 919 451 2971 891 421 2972 910 451 2973 891 435 2974 919 441 2975 929 441 2976 1017 435 2977 1014 416 2978 1005 386 2979 991 416 2980 1005 435 2981 1014 416 2982 848 386 2983 853 391 2984 885 416 2985 848 391 2986 885 440 2987 918 420 2988 879 393 2989 827 394 2990 994 427 2991 967 453 2992 945 378 2993 809 427 2994 967 378 2995 809 397 2996 951 396 2997 805 382 2998 914 395 2999 950 463 3000 1153 454 3001 1114 462 3002 1140 455 3003 1112 454 3004 1114 463 3005 1153 456 3006 1115 464 3007 1120 465 3008 1124 456 3009 1115 465 3010 1124 466 3011 1139 458 3012 1184 457 3013 1158 521 3014 1165 521 3015 1165 535 3016 1179 458 3017 1184 520 3018 1161 459 3019 1145 538 3020 1157 459 3021 1145 520 3022 1161 460 3023 1171 519 3024 1185 523 3025 1186 457 3026 1158 523 3027 1186 521 3028 1165 457 3029 1158 503 3030 1197 491 3031 1193 468 3032 1194 513 3033 1188 491 3034 1193 503 3035 1197 507 3036 1187 479 3037 1191 517 3038 1183 479 3039 1191 507 3040 1187 485 3041 1190 484 3042 1144 506 3043 1152 491 3044 1123 501 3045 1113 491 3046 1123 506 3047 1152 510 3048 1199 480 3049 1208 518 3050 1198 480 3051 1208 510 3052 1199 488 3053 1207 514 3054 1203 484 3055 1195 493 3056 1202 506 3057 1192 484 3058 1195 514 3059 1203 505 3060 1215 455 3061 1112 463 3062 1153 501 3063 1214 455 3064 1112 505 3065 1215 491 3066 1193 504 3067 1216 482 3068 1217 504 3069 1216 491 3070 1193 501 3071 1214 458 3072 1184 525 3073 1236 497 3074 1228 497 3075 1228 525 3076 1236 513 3077 1188 525 3078 1236 458 3079 1184 562 3080 1231 509 3081 1211 495 3082 1220 456 3083 1115 495 3084 1220 509 3085 1211 472 3086 1212 508 3087 1232 495 3088 1220 487 3089 1223 517 3090 1183 495 3091 1220 508 3092 1232 461 3093 1245 479 3094 1191 499 3095 1233 499 3096 1233 479 3097 1191 470 3098 1249 522 3099 1170 498 3100 1178 525 3101 1164 513 3102 1160 525 3103 1164 498 3104 1178 498 3105 1178 484 3106 1144 513 3107 1160 491 3108 1123 513 3109 1160 484 3110 1144 501 3111 1113 464 3112 1189 455 3113 1196 464 3114 1189 501 3115 1113 506 3116 1152 512 3117 1241 496 3118 1259 519 3119 1185 496 3120 1259 512 3121 1241 475 3122 1242 511 3123 1332 496 3124 1259 490 3125 1331 518 3126 1198 496 3127 1259 511 3128 1332 454 3129 1114 480 3130 1208 500 3131 1333 500 3132 1333 480 3133 1208 473 3134 1334 459 3135 1145 522 3136 1265 524 3137 1266 516 3138 1283 522 3139 1265 459 3140 1145 498 3141 1264 522 3142 1265 516 3143 1283 484 3144 1195 515 3145 1288 477 3146 1289 515 3147 1288 484 3148 1195 498 3149 1264 464 3150 1120 502 3151 1290 465 3152 1124 502 3153 1290 464 3154 1120 506 3155 1192 501 3156 1214 469 3157 1335 483 3158 1336 491 3159 1193 482 3160 1217 468 3161 1194 481 3162 1337 467 3163 1338 513 3164 1188 495 3165 1220 472 3166 1212 487 3167 1223 517 3168 1183 486 3169 1291 471 3170 1292 485 3171 1190 470 3172 1249 479 3173 1191 475 3174 1242 467 3175 1338 490 3176 1331 490 3177 1331 467 3178 1338 481 3179 1337 489 3180 1340 468 3181 1194 474 3182 1339 474 3183 1339 468 3184 1194 482 3185 1217 488 3186 1207 483 3187 1336 473 3188 1334 473 3189 1334 483 3190 1336 469 3191 1335 485 3192 1190 478 3193 1294 470 3194 1249 478 3195 1294 485 3196 1190 494 3197 1293 486 3198 1291 477 3199 1289 471 3200 1292 477 3201 1289 486 3202 1291 493 3203 1202 472 3204 1212 492 3205 1296 487 3206 1223 492 3207 1296 472 3208 1212 476 3209 1295 496 3210 1259 475 3211 1242 490 3212 1331 518 3213 1198 489 3214 1340 474 3215 1339 488 3216 1207 473 3217 1334 480 3218 1208 498 3219 1264 478 3220 1294 494 3221 1293 484 3222 1195 477 3223 1289 493 3224 1202 492 3225 1296 476 3226 1295 506 3227 1192 459 3228 1376 460 3229 1377 457 3230 1255 457 3231 1255 458 3232 1256 459 3233 1376 516 3234 1118 459 3235 1422 458 3236 1423 516 3237 1118 458 3238 1423 497 3239 1117 475 3240 1135 478 3241 1453 467 3242 1130 478 3243 1453 475 3244 1135 470 3245 1452 512 3246 1446 470 3247 1448 475 3248 1449 470 3249 1448 512 3250 1446 499 3251 1447 471 3252 1286 468 3253 1284 489 3254 1285 468 3255 1284 471 3256 1286 477 3257 1287 490 3258 1387 507 3259 1389 511 3260 1386 507 3261 1389 490 3262 1387 485 3263 1388 494 3264 1390 485 3265 1391 490 3266 1146 490 3267 1146 481 3268 1151 494 3269 1390 477 3270 1374 515 3271 1375 503 3272 1128 477 3273 1374 503 3274 1128 468 3275 1137 488 3276 1379 492 3277 1381 483 3278 1378 492 3279 1381 488 3280 1379 487 3281 1380 510 3282 1148 487 3283 1400 488 3284 1401 487 3285 1400 510 3286 1148 508 3287 1149 493 3288 1402 486 3289 1403 474 3290 1142 474 3291 1142 482 3292 1155 493 3293 1402 482 3294 1385 514 3295 1383 493 3296 1384 514 3297 1383 482 3298 1385 504 3299 1382 476 3300 1416 472 3301 1417 473 3302 1132 473 3303 1132 469 3304 1133 476 3305 1416 465 3306 1434 502 3307 1435 505 3308 1122 465 3309 1434 505 3310 1122 463 3311 1125 466 3312 1394 463 3313 1392 462 3314 1393 463 3315 1392 466 3316 1394 465 3317 1395 473 3318 1413 509 3319 1415 500 3320 1412 509 3321 1415 473 3322 1413 472 3323 1414 503 3324 1197 481 3325 1337 513 3326 1188 517 3327 1183 471 3328 1292 507 3329 1187 518 3330 1198 474 3331 1339 510 3332 1199 514 3333 1203 492 3334 1296 506 3335 1192 505 3336 1215 469 3337 1335 501 3338 1214 501 3339 1214 483 3340 1336 504 3341 1216 513 3342 1188 467 3343 1338 497 3344 1228 456 3345 1115 466 3346 1139 509 3347 1211 508 3348 1232 486 3349 1291 517 3350 1183 499 3351 1233 460 3352 1171 461 3353 1245 519 3354 1185 457 3355 1158 512 3356 1241 511 3357 1332 489 3358 1340 518 3359 1198 500 3360 1333 462 3361 1140 454 3362 1114 516 3363 1283 478 3364 1294 498 3365 1264 498 3366 1264 494 3367 1293 515 3368 1288 506 3369 1192 476 3370 1295 502 3371 1290 467 3372 1338 512 3373 1241 497 3374 1228 457 3375 1158 497 3376 1228 512 3377 1241 478 3378 1138 512 3379 1177 467 3380 1127 512 3381 1177 478 3382 1138 499 3383 1162 499 3384 1233 478 3385 1294 516 3386 1283 516 3387 1283 460 3388 1171 499 3389 1233 457 3390 1159 516 3391 1116 497 3392 1119 516 3393 1116 457 3394 1159 460 3395 1182 471 3396 1292 515 3397 1288 507 3398 1187 494 3399 1293 507 3400 1187 515 3401 1288 503 3402 1167 471 3403 1131 489 3404 1150 471 3405 1131 503 3406 1167 515 3407 1181 511 3408 1332 503 3409 1197 489 3410 1340 511 3411 1332 481 3412 1337 503 3413 1197 494 3414 1172 511 3415 1141 507 3416 1156 511 3417 1141 494 3418 1172 481 3419 1176 483 3420 1336 510 3421 1199 504 3422 1216 474 3423 1339 504 3424 1216 510 3425 1199 508 3426 1173 483 3427 1143 492 3428 1154 483 3429 1143 508 3430 1173 510 3431 1175 508 3432 1232 492 3433 1296 514 3434 1203 514 3435 1203 486 3436 1291 508 3437 1232 474 3438 1168 514 3439 1134 504 3440 1147 514 3441 1134 474 3442 1168 486 3443 1180 476 3444 1295 509 3445 1211 502 3446 1290 466 3447 1139 502 3448 1290 509 3449 1211 469 3450 1136 500 3451 1163 476 3452 1129 509 3453 1174 476 3454 1129 500 3455 1163 500 3456 1333 469 3457 1335 505 3458 1215 505 3459 1215 462 3460 1140 500 3461 1333 502 3462 1126 466 3463 1166 505 3464 1121 462 3465 1169 505 3466 1121 466 3467 1166 562 3468 1231 458 3469 1184 535 3470 1179 595 3471 1297 461 3472 1245 520 3473 1161 461 3474 1245 460 3475 1171 520 3476 1161 538 3477 1157 459 3478 1145 524 3479 1266 527 3480 1344 529 3481 1342 528 3482 1343 527 3483 1344 526 3484 1341 529 3485 1342 532 3486 1300 531 3487 1298 533 3488 1299 530 3489 1301 531 3490 1298 532 3491 1300 534 3492 1345 536 3493 1346 521 3494 1165 521 3495 1165 536 3496 1346 535 3497 1179 520 3498 1161 537 3499 1302 539 3500 1303 537 3501 1302 520 3502 1161 538 3503 1157 523 3504 1186 540 3505 1347 534 3506 1345 523 3507 1186 534 3508 1345 521 3509 1165 542 3510 1351 541 3511 1348 544 3512 1349 544 3513 1349 543 3514 1350 542 3515 1351 548 3516 1305 546 3517 1307 545 3518 1304 546 3519 1307 548 3520 1305 547 3521 1306 542 3522 1227 549 3523 1224 551 3524 1225 542 3525 1227 551 3526 1225 550 3527 1226 555 3528 1353 553 3529 1355 552 3530 1352 553 3531 1355 555 3532 1353 554 3533 1354 550 3534 1311 551 3535 1308 557 3536 1309 557 3537 1309 556 3538 1310 550 3539 1311 526 3540 1341 549 3541 1356 558 3542 1357 558 3543 1357 529 3544 1342 526 3545 1341 542 3546 1351 559 3547 1359 549 3548 1356 559 3549 1359 542 3550 1351 560 3551 1358 536 3552 1346 525 3553 1236 562 3554 1231 525 3555 1236 561 3556 1360 541 3557 1348 561 3558 1360 525 3559 1236 536 3560 1346 565 3561 1312 563 3562 1314 531 3563 1298 563 3564 1314 565 3565 1312 564 3566 1313 565 3567 1312 545 3568 1304 567 3569 1315 565 3570 1312 567 3571 1315 566 3572 1316 548 3573 1305 569 3574 1319 568 3575 1317 548 3576 1305 568 3577 1317 570 3578 1318 525 3579 1164 541 3580 1251 571 3581 1252 525 3582 1164 571 3583 1252 522 3584 1170 541 3585 1251 542 3586 1227 550 3587 1226 541 3588 1251 550 3589 1226 571 3590 1252 549 3591 1224 526 3592 1253 530 3593 1254 549 3594 1224 530 3595 1254 551 3596 1225 574 3597 1361 572 3598 1363 540 3599 1347 572 3600 1363 574 3601 1361 573 3602 1362 574 3603 1361 552 3604 1352 576 3605 1364 574 3606 1361 576 3607 1364 575 3608 1365 555 3609 1353 527 3610 1344 577 3611 1366 555 3612 1353 577 3613 1366 578 3614 1367 522 3615 1265 571 3616 1320 579 3617 1321 522 3618 1265 579 3619 1321 537 3620 1302 522 3621 1265 537 3622 1302 524 3623 1266 550 3624 1311 580 3625 1323 571 3626 1320 580 3627 1323 550 3628 1311 581 3629 1322 530 3630 1301 582 3631 1324 551 3632 1308 582 3633 1324 530 3634 1301 532 3635 1300 549 3636 1356 584 3637 1368 583 3638 1369 542 3639 1351 543 3640 1350 560 3641 1358 585 3642 1370 541 3643 1348 586 3644 1371 565 3645 1312 566 3646 1316 564 3647 1313 545 3648 1304 588 3649 1325 587 3650 1326 547 3651 1306 548 3652 1305 570 3653 1318 586 3654 1371 573 3655 1362 575 3656 1365 575 3657 1365 585 3658 1370 586 3659 1371 543 3660 1350 590 3661 1373 589 3662 1372 589 3663 1372 560 3664 1358 543 3665 1350 578 3666 1367 584 3667 1368 554 3668 1354 584 3669 1368 578 3670 1367 583 3671 1369 547 3672 1306 592 3673 1328 591 3674 1327 592 3675 1328 547 3676 1306 570 3677 1318 587 3678 1326 581 3679 1322 556 3680 1310 581 3681 1322 587 3682 1326 588 3683 1325 564 3684 1313 594 3685 1329 593 3686 1330 594 3687 1329 564 3688 1313 566 3689 1316 574 3690 1361 575 3691 1365 573 3692 1362 552 3693 1352 589 3694 1372 590 3695 1373 554 3696 1354 555 3697 1353 578 3698 1367 571 3699 1320 591 3700 1327 592 3701 1328 550 3702 1311 556 3703 1310 581 3704 1322 594 3705 1329 551 3706 1308 593 3707 1330 539 3708 1405 537 3709 1406 534 3710 1404 534 3711 1404 537 3712 1406 536 3713 1407 579 3714 1445 536 3715 1210 537 3716 1444 536 3717 1210 579 3718 1445 561 3719 1209 573 3720 1431 592 3721 1429 570 3722 1430 592 3723 1429 573 3724 1431 586 3725 1428 570 3726 1458 572 3727 1250 573 3728 1258 572 3729 1250 570 3730 1458 568 3731 1459 590 3732 1441 543 3733 1218 588 3734 1440 588 3735 1440 543 3736 1218 581 3737 1269 546 3738 1260 575 3739 1463 576 3740 1222 575 3741 1463 546 3742 1260 547 3743 1462 547 3744 1419 591 3745 1420 575 3746 1418 575 3747 1418 591 3748 1420 585 3749 1421 581 3750 1398 544 3751 1396 580 3752 1397 544 3753 1396 581 3754 1398 543 3755 1399 554 3756 1451 594 3757 1246 566 3758 1450 594 3759 1246 554 3760 1451 584 3761 1230 566 3762 1426 553 3763 1424 554 3764 1425 553 3765 1424 566 3766 1426 567 3767 1427 587 3768 1239 556 3769 1432 589 3770 1234 589 3771 1234 556 3772 1432 560 3773 1433 557 3774 1411 560 3775 1409 556 3776 1410 560 3777 1409 557 3778 1411 559 3779 1408 564 3780 1263 593 3781 1442 578 3782 1244 578 3783 1244 593 3784 1442 583 3785 1443 532 3786 1456 558 3787 1454 582 3788 1455 558 3789 1454 532 3790 1456 529 3791 1457 528 3792 1461 529 3793 1201 533 3794 1460 533 3795 1460 529 3796 1201 532 3797 1204 563 3798 1437 578 3799 1439 577 3800 1436 578 3801 1439 563 3802 1437 564 3803 1438 544 3804 1349 541 3805 1348 585 3806 1370 545 3807 1304 546 3808 1307 588 3809 1325 552 3810 1352 553 3811 1355 589 3812 1372 557 3813 1309 551 3814 1308 594 3815 1329 558 3816 1357 549 3817 1356 583 3818 1369 549 3819 1356 559 3820 1359 584 3821 1368 541 3822 1348 561 3823 1360 586 3824 1371 531 3825 1298 563 3826 1314 533 3827 1299 567 3828 1315 545 3829 1304 587 3830 1326 568 3831 1317 569 3832 1319 539 3833 1303 540 3834 1347 572 3835 1363 534 3836 1345 576 3837 1364 552 3838 1352 590 3839 1373 577 3840 1366 527 3841 1344 528 3842 1343 579 3843 1321 571 3844 1320 592 3845 1328 571 3846 1320 580 3847 1323 591 3848 1327 551 3849 1308 582 3850 1324 593 3851 1330 572 3852 1363 586 3853 1371 561 3854 1360 561 3855 1360 534 3856 1345 572 3857 1363 592 3858 1280 572 3859 1257 568 3860 1274 572 3861 1257 592 3862 1280 586 3863 1248 539 3864 1303 579 3865 1321 568 3866 1317 592 3867 1328 568 3868 1317 579 3869 1321 534 3870 1240 561 3871 1267 579 3872 1206 534 3873 1240 579 3874 1206 539 3875 1213 546 3876 1307 591 3877 1327 580 3878 1323 580 3879 1323 588 3880 1325 546 3881 1307 544 3882 1276 590 3883 1278 588 3884 1219 544 3885 1276 588 3886 1219 580 3887 1268 585 3888 1370 576 3889 1364 544 3890 1349 590 3891 1373 544 3892 1349 576 3893 1364 591 3894 1273 546 3895 1279 576 3896 1221 591 3897 1273 576 3898 1221 585 3899 1261 553 3900 1355 584 3901 1368 559 3902 1359 559 3903 1359 589 3904 1372 553 3905 1355 567 3906 1272 594 3907 1282 584 3908 1229 567 3909 1272 584 3910 1229 553 3911 1247 594 3912 1329 567 3913 1315 557 3914 1309 587 3915 1326 557 3916 1309 567 3917 1315 589 3918 1275 559 3919 1277 557 3920 1235 589 3921 1275 557 3922 1235 587 3923 1238 563 3924 1314 593 3925 1330 582 3926 1324 582 3927 1324 533 3928 1299 563 3929 1314 577 3930 1271 593 3931 1243 563 3932 1262 593 3933 1243 577 3934 1271 583 3935 1281 583 3936 1369 577 3937 1366 558 3938 1357 528 3939 1343 558 3940 1357 577 3941 1366 533 3942 1237 558 3943 1200 528 3944 1205 558 3945 1200 533 3946 1237 582 3947 1270 562 3948 1231 535 3949 1179 536 3950 1346 569 3951 1319 595 3952 1297 520 3953 1161 569 3954 1319 520 3955 1161 539 3956 1303 538 3957 1157 524 3958 1266 537 3959 1302 598 3960 1467 599 3961 1464 597 3962 1466 597 3963 1466 599 3964 1464 596 3965 1465 600 3966 1469 601 3967 1468 598 3968 1467 598 3969 1467 601 3970 1468 599 3971 1464 605 3972 1492 602 3973 1493 596 3974 1490 596 3975 1490 599 3976 1491 605 3977 1492 596 3978 1476 603 3979 1478 597 3980 1479 603 3981 1478 596 3982 1476 602 3983 1477 604 3984 1486 600 3985 1484 598 3986 1485 600 3987 1484 604 3988 1486 606 3989 1487 600 3990 1480 607 3991 1482 601 3992 1483 607 3993 1482 600 3994 1480 606 3995 1481 607 3996 1495 605 3997 1492 601 3998 1494 599 3999 1491 601 4000 1494 605 4001 1492 603 4002 1489 604 4003 1486 597 4004 1488 598 4005 1485 597 4006 1488 604 4007 1486 605 4008 1473 604 4009 1470 602 4010 1472 602 4011 1472 604 4012 1470 603 4013 1471 604 4014 1470 605 4015 1473 607 4016 1475 607 4017 1475 606 4018 1474 604 4019 1470 609 4020 1519 608 4021 1516 616 4022 1517 609 4023 1519 616 4024 1517 617 4025 1518 613 4026 1522 612 4027 1523 608 4028 1520 613 4029 1522 608 4030 1520 609 4031 1521 618 4032 1526 609 4033 1524 617 4034 1525 609 4035 1524 618 4036 1526 613 4037 1527 615 4038 1531 610 4039 1529 614 4040 1530 610 4041 1529 615 4042 1531 611 4043 1528 619 4044 1534 610 4045 1532 616 4046 1533 610 4047 1532 619 4048 1534 614 4049 1535 617 4050 1518 616 4051 1517 610 4052 1536 617 4053 1518 610 4054 1536 611 4055 1538 618 4056 1526 611 4057 1539 615 4058 1540 611 4059 1539 618 4060 1526 617 4061 1525 619 4062 1534 608 4063 1537 612 4064 1541 608 4065 1537 619 4066 1534 616 4067 1533 622 4068 1544 621 4069 1543 623 4070 1545 620 4071 1542 623 4072 1545 621 4073 1543 624 4074 1548 620 4075 1546 625 4076 1549 623 4077 1547 620 4078 1546 624 4079 1548 626 4080 1552 623 4081 1550 624 4082 1553 623 4083 1550 626 4084 1552 622 4085 1551 630 4086 1557 628 4087 1555 627 4088 1554 628 4089 1555 630 4090 1557 629 4091 1556 631 4092 1560 628 4093 1558 629 4094 1561 628 4095 1558 631 4096 1560 621 4097 1559 627 4098 1563 628 4099 1562 622 4100 1544 621 4101 1543 622 4102 1544 628 4103 1562 627 4104 1564 626 4105 1552 630 4106 1565 626 4107 1552 627 4108 1564 622 4109 1551 631 4110 1560 625 4111 1567 620 4112 1566 631 4113 1560 620 4114 1566 621 4115 1559 633 4116 1569 635 4117 1571 634 4118 1570 635 4119 1571 633 4120 1569 632 4121 1568 636 4122 1574 632 4123 1572 637 4124 1575 635 4125 1573 632 4126 1572 636 4127 1574 638 4128 1578 635 4129 1576 636 4130 1579 635 4131 1576 638 4132 1578 634 4133 1577 642 4134 1583 640 4135 1581 639 4136 1580 640 4137 1581 642 4138 1583 641 4139 1582 643 4140 1586 640 4141 1584 641 4142 1587 640 4143 1584 643 4144 1586 633 4145 1585 640 4146 1588 634 4147 1570 639 4148 1589 634 4149 1570 640 4150 1588 633 4151 1569 639 4152 1590 638 4153 1578 642 4154 1591 638 4155 1578 639 4156 1590 634 4157 1577 643 4158 1586 637 4159 1593 632 4160 1592 643 4161 1586 632 4162 1592 633 4163 1585 647 4164 1597 646 4165 1596 645 4166 1595 647 4167 1597 645 4168 1595 644 4169 1594 649 4170 1600 648 4171 1599 644 4172 1598 649 4173 1600 644 4174 1598 645 4175 1601 650 4176 1604 645 4177 1602 646 4178 1605 645 4179 1602 650 4180 1604 649 4181 1603 652 4182 1607 654 4183 1609 653 4184 1608 654 4185 1609 652 4186 1607 651 4187 1606 655 4188 1612 654 4189 1610 647 4190 1613 654 4191 1610 655 4192 1612 653 4193 1611 654 4194 1615 651 4195 1614 646 4196 1596 654 4197 1615 646 4198 1596 647 4199 1597 650 4200 1604 651 4201 1617 652 4202 1616 651 4203 1617 650 4204 1604 646 4205 1605 655 4206 1612 644 4207 1619 648 4208 1618 644 4209 1619 655 4210 1612 647 4211 1613 659 4212 1622 656 4213 1620 658 4214 1621 656 4215 1620 659 4216 1622 657 4217 1623 663 4218 1626 662 4219 1627 660 4220 1624 663 4221 1626 660 4222 1624 661 4223 1625 660 4224 1631 656 4225 1628 661 4226 1630 661 4227 1630 656 4228 1628 657 4229 1629 659 4230 1633 661 4231 1635 657 4232 1632 661 4233 1635 659 4234 1633 663 4235 1634 658 4236 1637 662 4237 1638 659 4238 1636 659 4239 1636 662 4240 1638 663 4241 1639 656 4242 1641 660 4243 1642 658 4244 1640 662 4245 1643 658 4246 1640 660 4247 1642 666 4248 1646 665 4249 1645 664 4250 1644 666 4251 1646 664 4252 1644 667 4253 1647 670 4254 1650 668 4255 1648 671 4256 1651 668 4257 1648 670 4258 1650 669 4259 1649 669 4260 1654 664 4261 1652 668 4262 1655 664 4263 1652 669 4264 1654 667 4265 1653 666 4266 1657 669 4267 1659 670 4268 1658 669 4269 1659 666 4270 1657 667 4271 1656 671 4272 1662 665 4273 1661 666 4274 1660 666 4275 1660 670 4276 1663 671 4277 1662 668 4278 1666 665 4279 1664 671 4280 1667 665 4281 1664 668 4282 1666 664 4283 1665

+
+
+
+ + + 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.0000001.000000 + 30.0000000.0000003.333333 + + + + + +
diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_RoofB_01/model.config b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_RoofB_01/model.config new file mode 100755 index 0000000..b49b78b --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_RoofB_01/model.config @@ -0,0 +1,11 @@ + + + aws_robomaker_warehouse_RoofB_01 + 1.0 + model.sdf + + + + + + diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_RoofB_01/model.sdf b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_RoofB_01/model.sdf new file mode 100755 index 0000000..33e4e9c --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_RoofB_01/model.sdf @@ -0,0 +1,56 @@ + + + + + + 1000 + 0 0 0 0 0 0 + + 834024.533 + 0 + 0 + 459441.200 + 0 + 1302083.333 + + + + + + model://aws_robomaker_warehouse_RoofB_01/meshes/aws_robomaker_warehouse_RoofB_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + model://aws_robomaker_warehouse_RoofB_01/meshes/aws_robomaker_warehouse_RoofB_01_visual.DAE + + + 3 + + + 1 + + diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfD_01/materials/textures/aws_robomaker_warehouse_ShelfD_01.png b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfD_01/materials/textures/aws_robomaker_warehouse_ShelfD_01.png new file mode 100755 index 0000000..d33ba54 Binary files /dev/null and b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfD_01/materials/textures/aws_robomaker_warehouse_ShelfD_01.png differ diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfD_01/materials/textures/aws_robomaker_warehouse_ShelfD_02.png b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfD_01/materials/textures/aws_robomaker_warehouse_ShelfD_02.png new file mode 100755 index 0000000..4b7e610 Binary files /dev/null and b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfD_01/materials/textures/aws_robomaker_warehouse_ShelfD_02.png differ diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfD_01/materials/textures/aws_robomaker_warehouse_ShelfD_03.png b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfD_01/materials/textures/aws_robomaker_warehouse_ShelfD_03.png new file mode 100755 index 0000000..b28b289 Binary files /dev/null and b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfD_01/materials/textures/aws_robomaker_warehouse_ShelfD_03.png differ diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfD_01/materials/textures/aws_robomaker_warehouse_ShelfD_04.png b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfD_01/materials/textures/aws_robomaker_warehouse_ShelfD_04.png new file mode 100755 index 0000000..e76fcdd Binary files /dev/null and b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfD_01/materials/textures/aws_robomaker_warehouse_ShelfD_04.png differ diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_collision.DAE b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_collision.DAE new file mode 100755 index 0000000..0c5642a --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_collision.DAE @@ -0,0 +1,327 @@ + + + FBX COLLADA exporter2019-05-15T10:09:41Z2019-05-15T10:09:41ZZ_UP + + + + + +-45.044750 -57.560341 195.803909 +42.866188 -57.560341 195.803955 +-45.044750 133.195770 195.803955 +42.866188 133.195770 195.803986 +-45.044781 -57.560341 -195.804031 +42.866158 -57.560341 -195.804001 +-45.044781 133.195770 -195.803986 +42.866158 133.195770 -195.803970 +-44.361427 -128.142014 1.402283 +42.927315 -128.142014 1.402374 +-44.361427 133.195755 1.402374 +42.927315 133.195755 1.402420 +-44.361412 -128.141998 -4.198639 +42.927338 -128.141998 -4.198563 +-44.361412 133.195786 -4.198517 +42.927338 133.195786 -4.198456 +-44.361458 -128.142029 -190.318237 +42.927284 -128.142029 -190.318130 +42.927284 133.195740 -190.318039 +-44.361458 133.195740 -190.318130 +-44.361443 -128.142014 -195.919159 +-44.361443 133.195770 -195.919022 +42.927307 133.195770 -195.918884 +42.927307 -128.142014 -195.919037 +-44.361401 -128.141998 195.912140 +42.927341 -128.141998 195.912231 +-44.361401 133.195770 195.912231 +42.927341 133.195770 195.912277 +-44.361378 -128.141983 190.311218 +42.927372 -128.141983 190.311295 +-44.361378 133.195801 190.311340 +42.927372 133.195801 190.311401 + + + + + + + + + + + +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +1.000000 -0.000000 0.000004 +1.000000 -0.000000 0.000004 +1.000000 -0.000000 0.000004 +1.000000 -0.000000 0.000004 +1.000000 -0.000000 0.000004 +1.000000 -0.000000 0.000004 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-1.000000 0.000000 -0.000003 +-1.000000 0.000000 -0.000003 +-1.000000 0.000000 -0.000003 +-1.000000 0.000000 -0.000003 +-1.000000 0.000000 -0.000003 +-1.000000 0.000000 -0.000003 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +0.000001 0.000001 -1.000000 +0.000001 0.000001 -1.000000 +0.000001 0.000001 -1.000000 +0.000001 0.000001 -1.000000 +0.000001 0.000001 -1.000000 +0.000001 0.000001 -1.000000 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +1.000000 -0.000000 0.000004 +1.000000 -0.000000 0.000004 +1.000000 -0.000000 0.000004 +1.000000 -0.000000 0.000004 +1.000000 -0.000000 0.000004 +1.000000 -0.000000 0.000004 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-1.000000 0.000000 -0.000003 +-1.000000 0.000000 -0.000003 +-1.000000 0.000000 -0.000003 +-1.000000 0.000000 -0.000003 +-1.000000 0.000000 -0.000003 +-1.000000 0.000000 -0.000003 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +1.000000 -0.000000 0.000005 +1.000000 -0.000000 0.000005 +1.000000 -0.000000 0.000005 +1.000000 -0.000000 0.000005 +1.000000 -0.000000 0.000005 +1.000000 -0.000000 0.000005 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-1.000000 0.000000 -0.000004 +-1.000000 0.000000 -0.000004 +-1.000000 0.000000 -0.000004 +-1.000000 0.000000 -0.000004 +-1.000000 0.000000 -0.000004 +-1.000000 0.000000 -0.000004 + + + + + + + + + + + +1.000000 0.000000 +0.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +1.000000 0.000000 +0.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +1.000000 0.000000 +0.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +1.000000 0.000000 +0.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +1.000000 0.000000 +0.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +1.000000 0.000000 +0.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +1.000000 0.000000 +0.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +1.000000 0.000000 +1.000000 0.000000 +0.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 + + + + + + + + + + + +

2 0 2 0 1 0 3 2 3 3 3 3 0 4 0 1 5 1 7 6 7 5 7 5 4 8 4 4 9 4 6 10 6 7 11 7 5 12 11 1 13 9 0 14 8 0 15 8 4 16 10 5 17 11 7 18 15 3 19 13 1 20 12 1 21 12 5 22 14 7 23 15 2 24 17 7 25 18 6 26 19 7 27 18 2 28 17 3 29 16 0 30 21 6 31 22 4 32 23 6 33 22 0 34 21 2 35 20 10 36 26 8 37 24 11 38 27 11 39 27 8 40 24 9 41 25 15 42 31 13 43 29 12 44 28 12 45 28 14 46 30 15 47 31 12 48 34 9 49 33 8 50 32 9 51 33 12 52 34 13 53 35 13 54 38 11 55 37 9 56 36 11 57 37 13 58 38 15 59 39 15 60 42 14 61 43 11 62 40 10 63 41 11 64 40 14 65 43 14 66 46 12 67 47 10 68 44 8 69 45 10 70 44 12 71 47 19 72 51 16 73 48 18 74 50 18 75 50 16 76 48 17 77 49 22 78 54 23 79 55 20 80 52 20 81 52 21 82 53 22 83 54 20 84 57 17 85 59 16 86 56 17 87 59 20 88 57 23 89 58 23 90 61 18 91 63 17 92 60 18 93 63 23 94 61 22 95 62 22 96 65 21 97 66 18 98 64 19 99 67 18 100 64 21 101 66 21 102 69 20 103 70 19 104 68 16 105 71 19 106 68 20 107 70 26 108 74 24 109 72 27 110 75 27 111 75 24 112 72 25 113 73 31 114 79 29 115 77 28 116 76 28 117 76 30 118 78 31 119 79 28 120 82 25 121 81 24 122 80 25 123 81 28 124 82 29 125 83 29 126 86 27 127 85 25 128 84 27 129 85 29 130 86 31 131 87 31 132 90 30 133 91 27 134 88 26 135 89 27 136 88 30 137 91 30 138 94 28 139 95 26 140 92 24 141 93 26 142 92 28 143 95

+
+
+
+ + + -0.000000 -0.000000 -1.000000 0.000000 -1.000000 0.000000 0.000000 -1.072197 0.000000 1.000000 -0.000000 131.071121 0.000000 0.000000 0.000000 1.0000001.000000 + 30.0000000.0000003.333333 + + + + + +
diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_visual.DAE b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_visual.DAE new file mode 100755 index 0000000..936caad --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_visual.DAE @@ -0,0 +1,3947 @@ + + + FBX COLLADA exporter2019-05-27T02:52:26Z2019-05-27T02:52:26ZZ_UP + + + ../materials/textures/aws_robomaker_warehouse_ShelfD_01.png + + + ../materials/textures/aws_robomaker_warehouse_ShelfD_03.png + + + ../materials/textures/aws_robomaker_warehouse_ShelfD_02.png + + + ../materials/textures/aws_robomaker_warehouse_ShelfD_04.png + + + + + + + + + + + + + + + + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + 0.800000 0.800000 0.800000 1.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + +-195.859329 -40.864964 11.286113 +-195.859360 -43.970364 11.286113 +-195.851028 -43.964931 -0.039542 +-195.359573 -41.130783 11.389088 +-190.846634 -43.704540 11.389088 +-195.851028 -40.870392 -0.039542 +-190.355179 -40.870392 -0.039542 +-190.355179 -43.964924 -0.039542 +-190.346863 -40.864960 11.286113 +-190.346848 -43.970367 11.286113 +-195.359573 -43.704540 11.389088 +-190.846634 -41.130779 11.389088 +-195.337234 -41.142639 261.250977 +-195.337234 -43.692688 261.250977 +-190.868851 -41.142639 261.250977 +-190.868851 -43.692688 261.250977 +190.346771 43.270035 11.286113 +190.346771 40.164623 11.286113 +190.355118 40.170067 -0.039542 +190.846558 43.004219 11.389088 +195.359558 40.430462 11.389088 +190.355118 43.264599 -0.039542 +195.850967 43.264603 -0.039542 +195.850967 40.170063 -0.039542 +195.859314 43.270039 11.286113 +195.859314 40.164627 11.286113 +190.846558 40.430454 11.389088 +195.359558 43.004223 11.389088 +190.868851 42.992374 261.250977 +190.868851 40.442318 261.250977 +195.337234 42.992374 261.250977 +195.337219 40.442322 261.250977 +-195.859329 43.269913 11.286113 +-195.859360 40.164501 11.286113 +-195.851028 40.169945 -0.039542 +-195.359573 43.004097 11.389088 +-190.846634 40.430340 11.389088 +-195.851028 43.264477 -0.039542 +-190.355179 43.264481 -0.039542 +-190.355179 40.169941 -0.039542 +-190.346863 43.269917 11.286113 +-190.346848 40.164505 11.286113 +-195.359573 40.430332 11.389088 +-190.846634 43.004101 11.389088 +-195.337234 42.992252 261.250977 +-195.337234 40.442196 261.250977 +-190.868851 42.992252 261.250977 +-190.868851 40.442200 261.250977 +-1.349450 43.269974 11.286113 +-1.349450 40.164562 11.286113 +-1.341129 40.170006 -0.039542 +-0.849689 43.004158 11.389088 +3.663298 40.430401 11.389088 +-1.341129 43.264538 -0.039542 +4.154719 43.264542 -0.039542 +4.154719 40.170002 -0.039542 +4.163049 43.269978 11.286113 +4.163049 40.164566 11.286113 +-0.849689 40.430393 11.389088 +3.663298 43.004162 11.389088 +-0.827415 42.992317 261.250977 +-0.827372 40.442257 261.250977 +3.640989 42.992317 261.250977 +3.641029 40.442261 261.250977 +-1.349419 -40.864902 11.286113 +-1.349419 -43.970303 11.286113 +-1.341098 -43.964870 -0.039542 +-0.849659 -41.130722 11.389088 +3.663328 -43.704479 11.389088 +-1.341098 -40.870331 -0.039542 +4.154749 -40.870331 -0.039542 +4.154749 -43.964863 -0.039542 +4.163079 -40.864899 11.286113 +4.163079 -43.970306 11.286113 +-0.849659 -43.704479 11.389088 +3.663328 -41.130718 11.389088 +-0.827342 -41.142578 261.250977 +-0.827328 -43.692627 261.250977 +3.641059 -41.142570 261.250977 +3.641079 -43.692623 261.250977 +190.346832 -40.864841 11.286113 +190.346817 -43.970242 11.286113 +190.355148 -43.964809 -0.039542 +190.846603 -41.130661 11.389088 +195.359573 -43.704418 11.389088 +190.355164 -40.870270 -0.039542 +195.850998 -40.870270 -0.039542 +195.850998 -43.964802 -0.039542 +195.859329 -40.864838 11.286113 +195.859344 -43.970245 11.286113 +190.846588 -43.704418 11.389088 +195.359573 -41.130657 11.389088 +190.868866 -41.142517 261.250977 +190.868881 -43.692566 261.250977 +195.337250 -41.142517 261.250977 +195.337265 -43.692566 261.250977 +-195.319946 -41.125313 13.878565 +-195.319916 40.434727 66.278061 +-190.886261 -41.125309 13.878560 +-195.319916 40.434727 70.460434 +-190.886246 -41.125320 9.696195 +-190.886246 40.434731 70.460434 +-195.319946 -41.125324 9.696195 +-190.886261 40.434731 66.278061 +-195.319992 -41.186462 144.465973 +-195.320007 40.434692 195.103180 +-195.320007 40.434704 199.280792 +-190.886292 -41.186459 144.465958 +-190.886322 40.434708 199.280792 +-190.886292 -41.186459 141.219635 +-190.886322 40.434696 195.103180 +-195.320007 -41.186462 141.219635 +-195.319946 -41.125320 134.569077 +-195.319916 40.434727 77.097397 +-195.319946 -41.125313 130.386719 +-190.886246 40.434731 77.097397 +-190.886261 40.434731 81.279785 +-190.886261 -41.125309 130.386734 +-190.886246 -41.125313 134.569077 +-195.319916 40.434727 81.279785 +190.824371 -41.125099 13.878565 +190.824371 40.434959 66.278061 +195.258072 -41.125080 13.878560 +190.824371 40.434959 70.460434 +195.258057 40.434978 70.460434 +195.258072 -41.125092 9.696197 +190.824371 -41.125111 9.696197 +195.258057 40.434978 66.278061 +190.824402 -41.186249 144.465973 +190.824356 40.434921 195.103180 +190.824341 40.434937 199.280792 +195.258087 -41.186234 144.465958 +195.258057 40.434948 199.280792 +195.258102 -41.186234 141.219635 +195.258057 40.434937 195.103180 +190.824402 -41.186249 141.219635 +190.824387 -41.125107 134.569061 +190.824402 40.434959 77.097397 +190.824387 -41.125099 130.386719 +195.258072 40.434978 77.097397 +195.258072 40.434978 81.279762 +195.258087 -41.125080 130.386719 +195.258087 -41.125088 134.569061 +190.824402 40.434959 81.279762 +-1.008084 -41.125114 13.878565 +-1.008087 40.434952 66.278061 +3.425621 -41.125095 13.878560 +-1.008087 40.434952 70.460434 +3.425587 40.434975 70.460434 +3.425621 -41.125103 9.696197 +-1.008084 -41.125122 9.696197 +3.425587 40.434975 66.278061 +-1.008060 -41.186264 144.465973 +-1.008118 40.434917 195.103180 +-1.008118 40.434925 199.280792 +3.425625 -41.186237 144.465958 +3.425590 40.434948 199.280792 +3.425625 -41.186237 141.219635 +3.425591 40.434937 195.103180 +-1.008060 -41.186264 141.219635 +-1.008083 -41.125118 134.569061 +-1.008064 40.434952 77.097397 +-1.008083 -41.125114 130.386719 +3.425602 40.434975 77.097397 +3.425602 40.434975 81.279762 +3.425617 -41.125095 130.386719 +3.425617 -41.125099 134.569061 +-1.008064 40.434952 81.279762 +190.734039 -41.267357 256.299133 +190.734024 41.439137 256.299133 +190.734039 -41.267357 259.323669 +190.734024 41.439137 259.323669 +195.278412 -41.267353 256.299133 +195.278397 41.439140 256.299133 +195.278412 -41.267353 259.323669 +195.278397 41.439140 259.323669 +-0.895264 -41.267330 256.299133 +-0.895294 41.439167 256.299133 +-0.895264 -41.267330 259.323669 +-0.895294 41.439167 259.323669 +3.649109 -41.267326 256.299133 +3.649078 41.439171 256.299133 +3.649109 -41.267326 259.323669 +3.649078 41.439171 259.323669 +-195.473846 -41.267296 256.299133 +-195.473846 41.439198 256.299133 +-195.473846 -41.267296 259.323669 +-195.473846 41.439198 259.323669 +-190.929474 -41.267292 256.299133 +-190.929474 41.439201 256.299133 +-190.929474 -41.267292 259.323669 +-190.929474 41.439201 259.323669 +-192.431396 43.978455 242.102509 +193.438141 38.358398 242.087494 +193.430084 38.361370 236.206406 +-192.438629 38.361286 242.092499 +-192.453064 43.978455 236.216309 +-192.438629 38.361286 236.206406 +193.430084 43.984470 236.206406 +193.430084 43.984474 242.092499 +-192.401535 -42.179398 140.859955 +-192.401535 -42.179398 134.975082 +-192.401535 41.115921 134.975082 +193.412735 41.116199 134.975098 +193.412781 -42.179111 134.975098 +-192.401535 41.115925 140.859955 +193.412735 41.116199 140.859955 +193.412781 -42.179111 140.859970 +-192.401535 -42.179398 76.744461 +-192.401535 -42.179398 70.859596 +-192.401535 41.115921 70.859589 +193.412735 41.116199 70.859596 +193.412781 -42.179111 70.859596 +-192.401535 41.115925 76.744453 +193.412735 41.116199 76.744476 +193.412781 -42.179111 76.744469 +193.412735 41.116207 196.922226 +-192.401535 -42.179398 196.922226 +-192.401535 41.115925 202.807083 +193.412781 -42.179111 202.807083 +-192.401535 -42.179394 202.807083 +193.412781 -42.179111 196.922226 +193.412735 41.116207 202.807083 +-192.401535 41.115921 196.922226 +-178.586426 -22.605822 96.767853 +-100.603027 -22.747538 76.381248 +-100.603027 -22.747660 96.767883 +-178.586426 -22.605822 76.381271 +-178.499023 25.176352 76.381271 +-100.516235 25.034750 76.381248 +-100.516235 25.034674 96.767883 +-178.499023 25.176443 96.767868 +-88.826538 -22.605822 96.767853 +-10.843140 -22.747538 76.381248 +-10.843140 -22.747660 96.767883 +-88.826538 -22.605822 76.381271 +-88.739136 25.176352 76.381271 +-10.756348 25.034750 76.381248 +-10.756348 25.034674 96.767883 +-88.739136 25.176443 96.767868 +-88.826538 -22.605829 117.386749 +-10.843140 -22.747545 97.000168 +-10.843140 -22.747667 117.386780 +-88.826538 -22.605829 97.000153 +-88.739136 25.176348 97.000153 +-10.756348 25.034746 97.000168 +-10.756348 25.034670 117.386780 +-88.739136 25.176439 117.386765 +-141.678711 -37.821102 161.109482 +-141.536987 40.162300 140.722885 +-141.536865 40.162300 161.109512 +-141.678711 -37.821102 140.722916 +-189.460815 -37.733696 140.722916 +-189.319214 40.249088 140.722885 +-189.319214 40.249088 161.109512 +-189.460938 -37.733696 161.109512 +-140.153320 40.249947 160.851883 +-140.295044 -37.733456 140.465286 +-140.295166 -37.733456 160.851913 +-140.153320 40.249947 140.465317 +-92.371216 40.162540 140.465317 +-92.512817 -37.820244 140.465286 +-92.512817 -37.820244 160.851913 +-92.371094 40.162540 160.851913 +-141.678711 -37.821102 181.615875 +-141.536987 40.162300 161.229279 +-141.536865 40.162300 181.615906 +-141.678711 -37.821102 161.229309 +-189.460815 -37.733696 161.229309 +-189.319214 40.249088 161.229279 +-189.319214 40.249088 181.615906 +-189.460938 -37.733696 181.615906 +-7.677246 25.034624 161.328079 +-85.660645 25.176350 140.941483 +-85.660645 25.176472 161.328110 +-7.677246 25.034624 140.941513 +-7.764648 -22.747478 140.941513 +-85.747437 -22.605879 140.941483 +-85.747437 -22.605879 161.328110 +-7.764648 -22.747601 161.328110 +-2.784668 17.029882 181.470779 +-79.266479 32.261143 161.084213 +-79.266357 32.261265 181.470810 +-2.784668 17.029882 161.084183 +-12.117798 -29.831873 161.084183 +-88.598877 -14.600979 161.084213 +-88.598877 -14.600979 181.470810 +-12.117798 -29.832056 181.470810 +69.007202 29.278488 123.836227 +69.301392 -25.122681 76.618340 +69.007202 29.278488 76.618340 +69.301392 -25.122711 123.836227 +4.720093 -25.279179 76.618340 +4.426025 29.122051 76.618340 +5.848633 29.125500 123.836227 +4.720459 -25.279179 123.836227 +4.426636 29.122051 123.836227 +136.298462 -25.122673 123.836197 +136.004517 29.278511 76.618362 +136.004517 29.278511 123.836197 +136.298462 -25.122673 76.618362 +71.717651 -25.279171 76.618370 +71.423218 29.122059 76.618370 +72.846191 29.125507 123.836227 +71.717651 -25.279171 123.836227 +71.423462 29.122059 123.836227 +189.951172 -36.224636 75.382462 +137.447266 39.841038 75.382462 +189.951172 39.841278 75.382446 +137.447266 -36.224880 75.382469 +137.447266 39.841038 82.989067 +189.951172 -36.224636 82.989067 +189.951172 39.841278 82.989052 +137.447266 -36.224880 82.989075 +189.951172 -36.224636 83.132347 +137.447266 39.841038 83.132355 +189.951172 39.841278 83.132332 +137.447266 -36.224880 83.132370 +137.447266 39.841038 90.738976 +189.951172 -36.224636 90.738960 +189.951172 39.841278 90.738960 +137.447266 -36.224880 90.738976 +189.950439 -36.224316 90.860062 +137.446289 39.841358 90.860062 +189.950439 39.841599 90.860062 +137.446289 -36.224560 90.860062 +137.446289 39.841358 98.466629 +189.950439 -36.224316 98.466629 +189.950439 39.841599 98.466629 +137.446289 -36.224560 98.466629 +-112.536499 29.278488 250.422791 +-112.242310 -25.122681 203.204910 +-112.536499 29.278488 203.204910 +-112.242310 -25.122711 250.422791 +-176.823608 -25.279179 203.204910 +-177.117676 29.122051 203.204910 +-175.695068 29.125500 250.422791 +-176.823242 -25.279179 250.422791 +-177.117065 29.122051 250.422791 +-18.152100 11.615347 250.422791 +-40.757202 -37.867748 203.204910 +-18.152100 11.615347 203.204910 +-40.757202 -37.867809 250.422791 +-99.419067 -10.857553 203.204910 +-76.813843 38.625538 203.204910 +-75.521606 38.030567 250.422791 +-99.418701 -10.857737 250.422791 +-76.813232 38.625294 250.422791 +82.850586 25.034658 161.436584 +4.867188 25.176378 141.049973 +4.867188 25.176500 161.436615 +82.850586 25.034658 141.049988 +82.763184 -22.747515 141.049988 +4.780396 -22.605909 141.049973 +4.780396 -22.605833 161.436615 +82.763184 -22.747606 161.436584 +82.850586 25.034658 182.055481 +4.867188 25.176382 161.668884 +4.867188 25.176504 182.055511 +82.850586 25.034658 161.668884 +82.763184 -22.747519 161.668884 +4.780396 -22.605909 161.668884 +4.780396 -22.605833 182.055511 +82.763184 -22.747610 182.055481 +135.996216 -38.568268 141.181595 +83.492310 37.497406 141.181595 +135.996216 37.497650 141.181580 +83.492310 -38.568512 141.181595 +83.492310 37.497406 148.788193 +135.996216 -38.568268 148.788193 +135.996216 37.497650 148.788193 +83.492310 -38.568512 148.788208 +135.996216 -38.568268 148.931473 +83.492310 37.497406 148.931488 +135.996216 37.497650 148.931473 +83.492310 -38.568512 148.931503 +83.492310 37.497406 156.538101 +135.996216 -38.568268 156.538101 +135.996216 37.497650 156.538101 +83.492310 -38.568512 156.538101 +135.995483 -38.567944 156.659195 +83.491333 37.497730 156.659195 +135.995483 37.497971 156.659195 +83.491333 -38.568188 156.659195 +83.491333 37.497730 164.265762 +135.995483 -38.567944 164.265762 +135.995483 37.497971 164.265762 +83.491333 -38.568188 164.265762 +142.044067 -42.379524 164.358704 +102.814697 41.308594 164.358688 +154.598511 32.643188 164.358704 +90.260132 -33.714111 164.358688 +102.814697 41.308594 171.965317 +142.044067 -42.379524 171.965332 +154.598511 32.643188 171.965332 +90.260132 -33.714111 171.965317 +142.044067 -42.379524 172.238983 +102.814697 41.308594 172.238968 +154.598511 32.643188 172.238983 +90.260132 -33.714111 172.238968 +102.814697 41.308594 179.845657 +142.044067 -42.379524 179.845642 +154.598511 32.643188 179.845642 +90.260132 -33.714111 179.845657 +189.735352 -38.568268 141.181595 +137.231445 37.497406 141.181595 +189.735352 37.497650 141.181580 +137.231445 -38.568512 141.181595 +137.231445 37.497406 148.788193 +189.735352 -38.568268 148.788193 +189.735352 37.497650 148.788193 +137.231445 -38.568512 148.788208 +189.735352 -38.568268 148.931473 +137.231445 37.497406 148.931488 +189.735352 37.497650 148.931473 +137.231445 -38.568512 148.931503 +137.231445 37.497406 156.538101 +189.735352 -38.568268 156.538101 +189.735352 37.497650 156.538101 +137.231445 -38.568512 156.538101 +82.850586 25.034658 222.664795 +4.867188 25.176378 202.278183 +4.867188 25.176500 222.664825 +82.850586 25.034658 202.278198 +82.763184 -22.747515 202.278198 +4.780396 -22.605909 202.278183 +4.780396 -22.605833 222.664825 +82.763184 -22.747606 222.664795 +102.337402 -31.465485 203.762085 +166.477905 35.082581 203.762085 +176.892090 -16.378141 203.762070 +91.923218 19.995256 203.762100 +166.477905 35.082581 211.368668 +102.337402 -31.465485 211.368668 +176.892090 -16.378141 211.368698 +91.923218 19.995256 211.368698 +102.337402 -31.465485 211.511978 +166.477905 35.082581 211.511978 +176.892090 -16.378141 211.511948 +91.923218 19.995256 211.511993 +166.477905 35.082581 219.118607 +102.337402 -31.465485 219.118576 +176.892090 -16.378141 219.118576 +91.923218 19.995256 219.118607 +102.336304 -31.465559 219.239685 +166.476807 35.082733 219.239685 +176.890991 -16.378218 219.239685 +91.922119 19.995378 219.239685 +166.476807 35.082733 226.846252 +102.336304 -31.465559 226.846252 +176.890991 -16.378218 226.846252 +91.922119 19.995378 226.846252 +102.337402 -31.465477 227.116623 +166.477905 35.082588 227.116623 +176.892090 -16.378136 227.116623 +91.923218 19.995262 227.116623 +166.477905 35.082588 234.723190 +102.337402 -31.465477 234.723190 +176.892090 -16.378136 234.723190 +91.923218 19.995262 234.723206 +-195.319946 -41.125313 13.878565 +190.824371 -41.125099 13.878565 + + + + + + + + + + + +-0.956333 0.263761 0.125924 +-0.951559 -0.257087 -0.168648 +-0.956403 -0.263505 0.125933 +-0.951559 -0.257087 -0.168648 +-0.956333 0.263761 0.125924 +-0.951498 0.257330 -0.168618 +-0.085984 -0.990457 -0.107708 +0.089169 -0.993226 0.074504 +-0.089036 -0.993235 0.074540 +0.089169 -0.993226 0.074504 +-0.085984 -0.990457 -0.107708 +0.086116 -0.990450 -0.107670 +0.956429 -0.263562 0.125613 +0.951558 -0.257089 -0.168647 +0.956359 0.263819 0.125605 +0.956359 0.263819 0.125605 +0.951558 -0.257089 -0.168647 +0.951499 0.257328 -0.168619 +0.086342 0.990400 -0.107949 +-0.089268 0.993198 0.074763 +0.089400 0.993189 0.074727 +-0.089268 0.993198 0.074763 +0.086342 0.990400 -0.107949 +-0.086212 0.990407 -0.107986 +-0.059645 0.051639 0.996883 +-0.178085 -0.324917 0.928824 +-0.059645 -0.051640 0.996883 +-0.178085 -0.324917 0.928824 +-0.059645 0.051639 0.996883 +-0.178122 0.324574 0.928937 +0.256743 -0.799623 0.542850 +-0.059645 -0.051640 0.996883 +-0.178085 -0.324917 0.928824 +-0.059645 -0.051640 0.996883 +0.256743 -0.799623 0.542850 +0.059645 -0.051639 0.996883 +0.178121 0.324575 0.928937 +0.059645 -0.051639 0.996883 +0.178086 -0.324915 0.928825 +0.059645 -0.051639 0.996883 +0.178121 0.324575 0.928937 +0.059645 0.051640 0.996883 +-0.256944 0.799388 0.543100 +0.059645 0.051640 0.996883 +0.178121 0.324575 0.928937 +0.059645 0.051640 0.996883 +-0.256944 0.799388 0.543100 +-0.059645 0.051639 0.996883 +-0.956754 0.286993 -0.047506 +-0.935847 -0.302400 0.180955 +-0.956902 -0.286501 -0.047494 +-0.935847 -0.302400 0.180955 +-0.956754 0.286993 -0.047506 +-0.935699 0.302882 0.180917 +-0.094927 -0.995157 -0.025505 +0.097942 -0.990243 0.099126 +0.094684 -0.995181 -0.025483 +0.097942 -0.990243 0.099126 +-0.094927 -0.995157 -0.025505 +-0.097945 -0.990243 0.099122 +0.957125 -0.285780 -0.047344 +0.935975 -0.302063 0.180856 +0.956974 0.286285 -0.047354 +0.956974 0.286285 -0.047354 +0.935975 -0.302063 0.180856 +0.935830 0.302532 0.180824 +0.094891 0.995160 -0.025542 +0.098119 0.990255 0.098831 +-0.095144 0.995135 -0.025563 +-0.095144 0.995135 -0.025563 +0.098119 0.990255 0.098831 +-0.098117 0.990255 0.098834 +0.673789 -0.697405 -0.244203 +0.226954 -0.935891 -0.269445 +0.000000 0.000000 1.000000 +0.226954 -0.935891 -0.269445 +0.673789 -0.697405 -0.244203 +0.000000 0.000000 1.000000 +-0.956341 0.264048 0.125261 +-0.951550 -0.257121 -0.168644 +-0.956450 -0.263645 0.125275 +-0.951550 -0.257121 -0.168644 +-0.956341 0.264048 0.125261 +-0.951446 0.257519 -0.168624 +-0.089283 -0.993155 0.075314 +-0.086285 -0.990402 -0.107976 +0.089316 -0.993153 0.075303 +0.089316 -0.993153 0.075303 +-0.086285 -0.990402 -0.107976 +0.086320 -0.990400 -0.107968 +0.956375 -0.263778 0.125574 +0.951481 -0.257288 -0.168778 +0.956265 0.264181 0.125560 +0.956265 0.264181 0.125560 +0.951481 -0.257288 -0.168778 +0.951378 0.257683 -0.168759 +0.089277 0.993155 0.075311 +-0.086253 0.990409 -0.107936 +-0.089247 0.993157 0.075321 +-0.086253 0.990409 -0.107936 +0.089277 0.993155 0.075311 +0.086286 0.990407 -0.107928 +-0.178425 0.325176 0.928668 +-0.059706 -0.051712 0.996876 +-0.059706 0.051713 0.996876 +-0.178425 0.325176 0.928668 +-0.178431 -0.325180 0.928666 +-0.059706 -0.051712 0.996876 +0.256999 -0.799754 0.542536 +-0.059706 -0.051712 0.996876 +-0.178431 -0.325180 0.928666 +-0.059706 -0.051712 0.996876 +0.256999 -0.799754 0.542536 +0.059722 -0.051734 0.996873 +0.178656 0.325122 0.928643 +0.059722 -0.051734 0.996873 +0.178585 -0.325143 0.928649 +0.059722 -0.051734 0.996873 +0.178656 0.325122 0.928643 +0.059722 0.051734 0.996874 +0.178656 0.325122 0.928643 +-0.256760 0.799853 0.542503 +-0.059706 0.051713 0.996876 +0.178656 0.325122 0.928643 +-0.059706 0.051713 0.996876 +0.059722 0.051734 0.996874 +-0.956947 0.286356 -0.047456 +-0.935859 0.302824 0.180182 +-0.956803 -0.286841 -0.047442 +-0.956803 -0.286841 -0.047442 +-0.935859 0.302824 0.180182 +-0.935721 -0.303220 0.180234 +-0.094809 -0.995169 -0.025488 +-0.097976 -0.990204 0.099478 +0.094855 -0.995165 -0.025491 +0.094855 -0.995165 -0.025491 +-0.097976 -0.990204 0.099478 +0.098011 -0.990200 0.099489 +0.957038 -0.286079 -0.047293 +0.935925 0.302646 0.180138 +0.957166 0.285648 -0.047304 +0.935925 0.302646 0.180138 +0.957038 -0.286079 -0.047293 +0.935784 -0.303054 0.180183 +0.095311 0.995118 -0.025619 +-0.098322 0.990228 0.098898 +-0.095272 0.995122 -0.025614 +-0.098322 0.990228 0.098898 +0.095311 0.995118 -0.025619 +0.098367 0.990224 0.098898 +0.673762 -0.697531 -0.243917 +0.226358 -0.936044 -0.269414 +0.000000 0.000000 1.000000 +0.226358 -0.936044 -0.269414 +0.673762 -0.697531 -0.243917 +0.000000 0.000000 1.000000 +-0.956289 0.263933 0.125901 +-0.951550 -0.257121 -0.168644 +-0.956398 -0.263530 0.125914 +-0.951550 -0.257121 -0.168644 +-0.956289 0.263933 0.125901 +-0.951446 0.257519 -0.168624 +-0.086211 -0.990407 -0.107986 +0.089337 -0.993152 0.075283 +-0.089204 -0.993161 0.075319 +0.089337 -0.993152 0.075283 +-0.086211 -0.990407 -0.107986 +0.086343 -0.990400 -0.107948 +0.956424 -0.263587 0.125595 +0.951550 -0.257123 -0.168644 +0.956315 0.263991 0.125581 +0.956315 0.263991 0.125581 +0.951550 -0.257123 -0.168644 +0.951446 0.257518 -0.168624 +0.086309 0.990407 -0.107909 +-0.089167 0.993164 0.075327 +0.089299 0.993155 0.075291 +-0.089167 0.993164 0.075327 +0.086309 0.990407 -0.107909 +-0.086179 0.990414 -0.107946 +-0.178090 0.325226 0.928715 +-0.059651 -0.051645 0.996882 +-0.059652 0.051644 0.996882 +-0.178090 0.325226 0.928715 +-0.178095 -0.325230 0.928713 +-0.059651 -0.051645 0.996882 +0.256694 -0.799886 0.542485 +-0.059651 -0.051645 0.996882 +-0.178095 -0.325230 0.928713 +-0.059651 -0.051645 0.996882 +0.256694 -0.799886 0.542485 +0.059652 -0.051644 0.996882 +0.178089 0.325227 0.928715 +0.059652 -0.051644 0.996882 +0.178095 -0.325229 0.928713 +0.059652 -0.051644 0.996882 +0.178089 0.325227 0.928715 +0.059651 0.051645 0.996882 +-0.256630 0.799822 0.542611 +0.059651 0.051645 0.996882 +0.178089 0.325227 0.928715 +0.059651 0.051645 0.996882 +-0.256630 0.799822 0.542611 +-0.059652 0.051644 0.996882 +-0.956880 0.286574 -0.047493 +-0.935838 0.302474 0.180875 +-0.956759 -0.286980 -0.047481 +-0.956759 -0.286980 -0.047481 +-0.935838 0.302474 0.180875 +-0.935700 -0.302870 0.180926 +-0.094892 -0.995161 -0.025495 +0.097974 -0.990204 0.099482 +0.094649 -0.995185 -0.025473 +0.097974 -0.990204 0.099482 +-0.094892 -0.995161 -0.025495 +-0.097976 -0.990204 0.099478 +0.956983 -0.286258 -0.047331 +0.935969 0.302125 0.180782 +0.957099 0.285866 -0.047341 +0.935969 0.302125 0.180782 +0.956983 -0.286258 -0.047331 +0.935829 -0.302532 0.180827 +0.095103 0.995138 -0.025600 +0.098324 0.990228 0.098895 +-0.095356 0.995113 -0.025622 +-0.095356 0.995113 -0.025622 +0.098324 0.990228 0.098895 +-0.098322 0.990228 0.098898 +0.673856 -0.697530 -0.243660 +0.226673 -0.935971 -0.269403 +0.000000 0.000000 1.000000 +0.226673 -0.935971 -0.269403 +0.673856 -0.697530 -0.243660 +0.000000 0.000000 1.000000 +-0.956352 0.263771 0.125762 +-0.951619 -0.256956 -0.168510 +-0.956461 -0.263369 0.125776 +-0.951619 -0.256956 -0.168510 +-0.956352 0.263771 0.125762 +-0.951515 0.257354 -0.168490 +-0.089353 -0.993150 0.075299 +0.086346 -0.990399 -0.107951 +0.089354 -0.993150 0.075299 +0.086346 -0.990399 -0.107951 +-0.089353 -0.993150 0.075299 +-0.086359 -0.990397 -0.107966 +0.956325 -0.263968 0.125553 +0.951413 -0.257453 -0.168912 +0.956215 0.264371 0.125539 +0.956215 0.264371 0.125539 +0.951413 -0.257453 -0.168912 +0.951309 0.257848 -0.168893 +0.089316 0.993152 0.075307 +0.086312 0.990407 -0.107912 +-0.089317 0.993152 0.075306 +-0.089317 0.993152 0.075306 +0.086312 0.990407 -0.107912 +-0.086327 0.990404 -0.107926 +-0.178271 0.325213 0.928685 +-0.059706 -0.051712 0.996876 +-0.059706 0.051711 0.996876 +-0.178271 0.325213 0.928685 +-0.178277 -0.325216 0.928683 +-0.059706 -0.051712 0.996876 +0.256917 -0.799827 0.542467 +-0.059706 -0.051712 0.996876 +-0.178277 -0.325216 0.928683 +-0.059706 -0.051712 0.996876 +0.256917 -0.799827 0.542467 +0.059652 -0.051644 0.996882 +0.178243 0.325190 0.928698 +0.059652 -0.051644 0.996882 +0.178249 -0.325192 0.928697 +0.059652 -0.051644 0.996882 +0.178243 0.325190 0.928698 +0.059651 0.051645 0.996882 +0.178243 0.325190 0.928698 +-0.256620 0.799901 0.542499 +-0.059706 0.051711 0.996876 +0.178243 0.325190 0.928698 +-0.059706 0.051711 0.996876 +0.059651 0.051645 0.996882 +-0.957030 0.286087 -0.047416 +-0.935837 0.303084 0.179859 +-0.956867 -0.286633 -0.047410 +-0.956867 -0.286633 -0.047410 +-0.935837 0.303084 0.179859 +-0.935699 -0.303480 0.179911 +-0.094954 -0.995155 -0.025518 +0.098066 -0.990195 0.099485 +0.094767 -0.995173 -0.025490 +0.098066 -0.990195 0.099485 +-0.094954 -0.995155 -0.025518 +-0.097939 -0.990209 0.099471 +0.956875 -0.286606 -0.047402 +0.936065 0.302173 0.180203 +0.957021 0.286115 -0.047424 +0.936065 0.302173 0.180203 +0.956875 -0.286606 -0.047402 +0.935925 -0.302580 0.180248 +0.095227 0.995126 -0.025611 +-0.098284 0.990233 0.098891 +-0.095347 0.995114 -0.025629 +-0.098284 0.990233 0.098891 +0.095227 0.995126 -0.025611 +0.098417 0.990219 0.098898 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.226395 -0.936031 -0.269427 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.673754 -0.697512 -0.243992 +-0.956396 0.263599 0.125785 +-0.951627 -0.256922 -0.168514 +-0.956465 -0.263343 0.125794 +-0.951627 -0.256922 -0.168514 +-0.956396 0.263599 0.125785 +-0.951567 0.257165 -0.168484 +-0.089186 -0.993223 0.074520 +0.086118 -0.990449 -0.107673 +0.089186 -0.993223 0.074520 +0.086118 -0.990449 -0.107673 +-0.089186 -0.993223 0.074520 +-0.086131 -0.990447 -0.107688 +0.956330 -0.263943 0.125571 +0.951421 -0.257419 -0.168916 +0.956260 0.264199 0.125562 +0.956260 0.264199 0.125562 +0.951421 -0.257419 -0.168916 +0.951362 0.257659 -0.168887 +0.089417 0.993186 0.074743 +0.086345 0.990399 -0.107952 +-0.089418 0.993186 0.074743 +-0.089418 0.993186 0.074743 +0.086345 0.990399 -0.107952 +-0.086360 0.990397 -0.107965 +-0.178304 0.324561 0.928907 +-0.059699 -0.051708 0.996876 +-0.059699 0.051707 0.996876 +-0.178304 0.324561 0.928907 +-0.178267 -0.324903 0.928794 +-0.059699 -0.051708 0.996876 +0.256966 -0.799563 0.542832 +-0.059699 -0.051708 0.996876 +-0.178267 -0.324903 0.928794 +-0.059699 -0.051708 0.996876 +0.256966 -0.799563 0.542832 +0.059645 -0.051639 0.996883 +0.178275 0.324538 0.928920 +0.059645 -0.051639 0.996883 +0.178239 -0.324879 0.928808 +0.059645 -0.051639 0.996883 +0.178275 0.324538 0.928920 +0.059645 0.051640 0.996883 +0.178275 0.324538 0.928920 +-0.256935 0.799467 0.542989 +-0.059699 0.051707 0.996876 +0.178275 0.324538 0.928920 +-0.059699 0.051707 0.996876 +0.059645 0.051640 0.996883 +-0.956866 0.286632 -0.047435 +-0.935846 -0.303009 0.179939 +-0.956902 -0.286501 -0.047494 +-0.935846 -0.303009 0.179939 +-0.956866 0.286632 -0.047435 +-0.935697 0.303492 0.179901 +-0.095030 -0.995147 -0.025535 +0.098035 -0.990234 0.099129 +0.094837 -0.995166 -0.025510 +0.098035 -0.990234 0.099129 +-0.095030 -0.995147 -0.025535 +-0.097908 -0.990248 0.099115 +0.957016 -0.286134 -0.047418 +0.935926 0.302580 0.180245 +0.956863 0.286642 -0.047436 +0.935926 0.302580 0.180245 +0.957016 -0.286134 -0.047418 +0.936071 -0.302110 0.180277 +0.094939 0.995156 -0.025539 +0.098212 0.990246 0.098834 +-0.095136 0.995136 -0.025567 +-0.095136 0.995136 -0.025567 +0.098212 0.990246 0.098834 +-0.098079 0.990259 0.098827 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.226723 -0.935942 -0.269462 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.673674 -0.697371 -0.244617 +-0.956385 0.263876 0.125285 +-0.951559 -0.257087 -0.168648 +-0.956455 -0.263620 0.125293 +-0.951559 -0.257087 -0.168648 +-0.956385 0.263876 0.125285 +-0.951498 0.257330 -0.168618 +-0.089116 -0.993229 0.074535 +0.086092 -0.990450 -0.107689 +0.089148 -0.993226 0.074524 +0.086092 -0.990450 -0.107689 +-0.089116 -0.993229 0.074535 +-0.086054 -0.990453 -0.107695 +0.956379 -0.263753 0.125592 +0.951490 -0.257253 -0.168783 +0.956260 0.264199 0.125562 +0.956260 0.264199 0.125562 +0.951490 -0.257253 -0.168783 +0.951362 0.257659 -0.168887 +0.089378 0.993189 0.074747 +-0.086283 0.990403 -0.107973 +-0.089348 0.993191 0.074758 +-0.086283 0.990403 -0.107973 +0.089378 0.993189 0.074747 +0.086319 0.990400 -0.107968 +-0.178472 0.324536 0.928883 +-0.059699 -0.051708 0.996876 +-0.059699 0.051708 0.996876 +-0.178472 0.324536 0.928883 +-0.178435 -0.324879 0.928771 +-0.059699 -0.051708 0.996876 +0.257002 -0.799500 0.542909 +-0.059699 -0.051708 0.996876 +-0.178435 -0.324879 0.928771 +-0.059699 -0.051708 0.996876 +0.257002 -0.799500 0.542909 +0.059731 -0.051751 0.996872 +0.178702 0.324482 0.928858 +0.059731 -0.051751 0.996872 +0.178666 -0.324823 0.928746 +0.059731 -0.051751 0.996872 +0.178702 0.324482 0.928858 +0.059731 0.051751 0.996872 +0.178702 0.324482 0.928858 +-0.256990 0.799500 0.542914 +-0.059699 0.051708 0.996876 +0.178702 0.324482 0.928858 +-0.059699 0.051708 0.996876 +0.059731 0.051751 0.996872 +-0.956757 0.286982 -0.047514 +-0.935868 -0.302749 0.180262 +-0.956956 -0.286326 -0.047458 +-0.935868 -0.302749 0.180262 +-0.956757 0.286982 -0.047514 +-0.935719 0.303231 0.180224 +-0.094845 -0.995166 -0.025498 +-0.097945 -0.990243 0.099122 +0.094967 -0.995153 -0.025514 +0.094967 -0.995153 -0.025514 +-0.097945 -0.990243 0.099122 +0.097986 -0.990238 0.099129 +0.957180 -0.285601 -0.047306 +0.935931 -0.302584 0.180211 +0.957030 0.286102 -0.047321 +0.957030 0.286102 -0.047321 +0.935931 -0.302584 0.180211 +0.935785 0.303054 0.180179 +0.095140 0.995136 -0.025563 +-0.098117 0.990255 0.098834 +-0.095138 0.995136 -0.025569 +-0.098117 0.990255 0.098834 +0.095140 0.995136 -0.025563 +0.098162 0.990250 0.098834 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.226665 -0.935948 -0.269490 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.673679 -0.697392 -0.244541 +-0.985878 0.095453 -0.137597 +-0.785782 0.352552 -0.508188 +-0.948297 0.180918 -0.260770 +0.188900 -0.559726 0.806860 +0.117083 -0.566086 0.815989 +-0.117067 -0.566069 0.816003 +-0.117067 -0.566069 0.816003 +-0.400048 -0.522404 0.753031 +-0.188881 -0.559749 0.806849 +0.949914 -0.178127 0.256776 +0.986163 -0.094499 0.136209 +0.985921 0.095316 -0.137386 +0.948917 0.179845 -0.259252 +0.985921 0.095316 -0.137386 +0.986163 -0.094499 0.136209 +0.118984 0.565957 -0.815803 +-0.402828 0.521709 -0.752030 +-0.191917 0.559413 -0.806365 +-0.402828 0.521709 -0.752030 +0.118984 0.565957 -0.815803 +-0.118970 0.565940 -0.815818 +-0.986592 -0.090992 0.135485 +-0.986292 0.090913 -0.137707 +-0.949902 0.172190 -0.260838 +-0.986592 -0.090992 0.135485 +-0.949886 -0.174273 0.259509 +-0.986292 0.090913 -0.137707 +-0.127399 -0.552974 0.823401 +0.187097 -0.547674 0.815505 +0.127645 -0.552942 0.823384 +0.187097 -0.547674 0.815505 +-0.127399 -0.552974 0.823401 +-0.187114 -0.547656 0.815513 +0.950045 0.171961 -0.260470 +0.793917 0.334985 -0.507425 +0.986635 -0.090843 0.135274 +0.949880 -0.174293 0.259518 +0.986635 -0.090843 0.135274 +0.793917 0.334985 -0.507425 +-0.128212 0.546391 -0.827659 +-0.189856 0.540902 -0.819378 +0.128199 0.546376 -0.827670 +0.128199 0.546376 -0.827670 +-0.189856 0.540902 -0.819378 +0.190238 0.540878 -0.819305 +-0.952583 -0.166438 -0.254722 +-0.790247 -0.335178 -0.512997 +-0.985580 0.092551 0.141657 +-0.951152 0.168869 0.258442 +-0.985580 0.092551 0.141657 +-0.790247 -0.335178 -0.512997 +-0.191430 -0.536859 -0.821668 +-0.119608 -0.543026 -0.831154 +0.191447 -0.536835 -0.821679 +0.191447 -0.536835 -0.821679 +-0.119608 -0.543026 -0.831154 +0.119633 -0.543044 -0.831139 +0.985626 0.092411 0.141429 +0.985872 -0.091621 -0.140219 +0.952724 -0.166185 -0.254363 +0.985626 0.092411 0.141429 +0.951738 0.167865 0.256935 +0.985872 -0.091621 -0.140219 +-0.194528 0.536525 0.821157 +0.121217 0.542938 0.830978 +0.194545 0.536501 0.821169 +0.121217 0.542938 0.830978 +-0.194528 0.536525 0.821157 +-0.121214 0.542919 0.830991 +-0.985878 0.095453 -0.137597 +-0.785836 0.352512 -0.508131 +-0.948300 0.180912 -0.260762 +0.189033 -0.559712 0.806839 +0.117169 -0.566081 0.815981 +-0.116913 -0.566079 0.816018 +-0.116913 -0.566079 0.816018 +-0.399963 -0.522425 0.753061 +-0.188687 -0.559770 0.806880 +0.949519 -0.178811 0.257762 +0.986075 -0.094797 0.136638 +0.985809 0.095692 -0.137928 +0.948612 0.180368 -0.260006 +0.985809 0.095692 -0.137928 +0.986075 -0.094797 0.136638 +0.119011 0.565956 -0.815801 +-0.402699 0.521741 -0.752077 +-0.191627 0.559445 -0.806412 +-0.402699 0.521741 -0.752077 +0.119011 0.565956 -0.815801 +-0.118817 0.565950 -0.815833 +-0.986517 -0.091247 0.135864 +-0.986322 0.090812 -0.137555 +-0.949604 0.172688 -0.261593 +-0.986517 -0.091247 0.135864 +-0.949961 -0.174146 0.259320 +-0.986322 0.090812 -0.137555 +-0.127234 -0.552986 0.823418 +0.187154 -0.547668 0.815496 +0.127630 -0.552943 0.823386 +0.187154 -0.547668 0.815496 +-0.127234 -0.552986 0.823418 +-0.186852 -0.547684 0.815554 +0.950054 0.171945 -0.260445 +0.793896 0.335000 -0.507449 +0.986635 -0.090843 0.135274 +0.949890 -0.174277 0.259494 +0.986635 -0.090843 0.135274 +0.793896 0.335000 -0.507449 +-0.128057 0.546402 -0.827676 +-0.189613 0.540928 -0.819417 +0.128240 0.546373 -0.827666 +0.128240 0.546373 -0.827666 +-0.189613 0.540928 -0.819417 +0.190188 0.540884 -0.819313 +-0.952535 -0.166521 -0.254848 +-0.790176 -0.335228 -0.513074 +-0.985558 0.092622 0.141765 +-0.951117 0.168929 0.258533 +-0.985558 0.092622 0.141765 +-0.790176 -0.335228 -0.513074 +-0.191162 -0.536887 -0.821711 +-0.119490 -0.543033 -0.831166 +0.191647 -0.536814 -0.821646 +0.191647 -0.536814 -0.821646 +-0.119490 -0.543033 -0.831166 +0.119703 -0.543039 -0.831132 +0.985542 0.092678 0.141836 +0.985795 -0.091868 -0.140598 +0.952450 -0.166654 -0.255081 +0.985542 0.092678 0.141836 +0.951478 0.168306 0.257610 +0.985795 -0.091868 -0.140598 +-0.194599 0.536518 0.821146 +0.121481 0.542921 0.830951 +0.194915 0.536461 0.821107 +0.121481 0.542921 0.830951 +-0.194599 0.536518 0.821146 +-0.121183 0.542921 0.830994 +-0.985856 0.095525 -0.137702 +-0.785680 0.352625 -0.508294 +-0.948300 0.180912 -0.260762 +0.188901 -0.559726 0.806860 +0.117160 -0.566081 0.815982 +-0.116875 -0.566082 0.816022 +-0.949680 -0.178545 0.257350 +-0.399920 -0.522436 0.753077 +-0.116875 -0.566082 0.816022 +-0.116875 -0.566082 0.816022 +-0.399920 -0.522436 0.753077 +-0.188554 -0.559785 0.806901 +0.949368 -0.179071 0.258136 +0.986032 -0.094942 0.136847 +0.985776 0.095802 -0.138086 +0.948459 0.180629 -0.260382 +0.985776 0.095802 -0.138086 +0.986032 -0.094942 0.136847 +0.118945 0.565960 -0.815807 +-0.402578 0.521772 -0.752120 +-0.191581 0.559451 -0.806419 +-0.402578 0.521772 -0.752120 +0.118945 0.565960 -0.815807 +-0.118740 0.565955 -0.815840 +-0.986509 -0.091273 0.135901 +-0.986344 0.090742 -0.137449 +-0.949604 0.172688 -0.261593 +-0.986509 -0.091273 0.135901 +-0.950036 -0.174020 0.259132 +-0.986344 0.090742 -0.137449 +-0.127197 -0.552989 0.823422 +0.187102 -0.547673 0.815504 +0.127672 -0.552940 0.823381 +0.187102 -0.547673 0.815504 +-0.127197 -0.552989 0.823422 +-0.186917 -0.547677 0.815544 +0.949970 0.172086 -0.260659 +0.793655 0.335173 -0.507711 +0.986614 -0.090913 0.135379 +0.949731 -0.174546 0.259895 +0.986614 -0.090913 0.135379 +0.793655 0.335173 -0.507711 +-0.128090 0.546399 -0.827672 +-0.189482 0.540942 -0.819438 +0.128198 0.546376 -0.827670 +0.128198 0.546376 -0.827670 +-0.189482 0.540942 -0.819438 +0.190254 0.540877 -0.819302 +-0.952463 -0.166645 -0.255038 +-0.790096 -0.335284 -0.513160 +-0.985535 0.092693 0.141874 +-0.951044 0.169051 0.258720 +-0.985535 0.092693 0.141874 +-0.790096 -0.335284 -0.513160 +-0.191225 -0.536880 -0.821701 +-0.119451 -0.543036 -0.831170 +0.191581 -0.536821 -0.821657 +0.191581 -0.536821 -0.821657 +-0.119451 -0.543036 -0.831170 +0.119781 -0.543034 -0.831124 +0.985512 0.092773 0.141981 +0.985722 -0.092103 -0.140957 +0.952378 -0.166776 -0.255268 +0.985512 0.092773 0.141981 +0.951260 0.168674 0.258173 +0.985722 -0.092103 -0.140957 +-0.194551 0.536523 0.821154 +0.121467 0.542922 0.830952 +0.195050 0.536446 0.821085 +0.121467 0.542922 0.830952 +-0.194551 0.536523 0.821154 +-0.121223 0.542918 0.830990 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.167885 0.000000 -0.985807 +0.167809 0.000000 -0.985819 +0.167818 0.000000 -0.985818 +0.167809 0.000000 -0.985819 +-0.167885 0.000000 -0.985807 +-0.167884 0.000000 -0.985807 +0.167832 0.000000 0.985816 +-0.167908 0.000000 0.985803 +0.167841 0.000000 0.985814 +-0.167908 0.000000 0.985803 +0.167832 0.000000 0.985816 +-0.167907 0.000000 0.985803 +-0.973544 0.000000 0.228498 +-0.973536 0.000000 -0.228534 +-0.973544 0.000000 0.228500 +-0.973544 0.000000 0.228500 +-0.973536 0.000000 -0.228534 +-0.973535 0.000000 -0.228536 +0.005896 -0.999955 0.007463 +-0.005899 -0.999955 0.007463 +-0.005899 -0.999955 -0.007465 +0.005896 -0.999955 0.007463 +-0.005899 -0.999955 -0.007465 +0.005896 -0.999955 -0.007465 +0.973508 0.000000 0.228655 +0.973493 0.000001 -0.228717 +0.973502 0.000001 0.228679 +0.973502 0.000001 0.228679 +0.973493 0.000001 -0.228717 +0.973487 0.000000 -0.228740 +-0.005894 0.999955 0.007457 +0.005901 0.999955 0.007469 +0.005900 0.999955 -0.007472 +-0.005894 0.999955 0.007457 +0.005900 0.999955 -0.007472 +-0.005894 0.999955 -0.007458 +0.119255 -0.230420 -0.965756 +-0.119296 -0.230417 -0.965752 +-0.119294 0.230486 -0.965736 +0.119255 -0.230420 -0.965756 +-0.119294 0.230486 -0.965736 +0.119260 0.230488 -0.965739 +-0.119278 0.230454 0.965745 +0.119256 -0.230416 0.965757 +0.119256 0.230498 0.965737 +0.119256 -0.230416 0.965757 +-0.119278 0.230454 0.965745 +-0.119277 -0.230394 0.965759 +-0.951550 -0.257151 0.168601 +-0.951532 0.257219 0.168599 +-0.951533 0.257221 -0.168588 +-0.951550 -0.257151 0.168601 +-0.951533 0.257221 -0.168588 +-0.951551 -0.257152 -0.168590 +-0.086139 -0.990439 0.107754 +0.086113 -0.990440 -0.107764 +0.086114 -0.990440 0.107763 +0.086113 -0.990440 -0.107764 +-0.086139 -0.990439 0.107754 +-0.086140 -0.990440 -0.107745 +0.951475 0.257352 0.168716 +0.951493 -0.257284 0.168719 +0.951494 -0.257282 -0.168717 +0.951475 0.257352 0.168716 +0.951494 -0.257282 -0.168717 +0.951476 0.257351 -0.168714 +-0.086168 0.990433 0.107786 +0.086136 0.990435 0.107787 +0.086133 0.990435 -0.107791 +-0.086168 0.990433 0.107786 +0.086133 0.990435 -0.107791 +-0.086168 0.990433 -0.107781 +0.119237 -0.230393 -0.965765 +-0.119278 -0.230390 -0.965760 +-0.119276 0.230459 -0.965744 +0.119237 -0.230393 -0.965765 +-0.119276 0.230459 -0.965744 +0.119242 0.230461 -0.965748 +-0.119295 0.230481 0.965737 +0.119256 -0.230416 0.965757 +0.119256 0.230498 0.965737 +0.119256 -0.230416 0.965757 +-0.119295 0.230481 0.965737 +-0.119295 -0.230422 0.965751 +-0.951533 0.257221 -0.168588 +-0.951551 -0.257151 0.168595 +-0.951533 0.257219 0.168593 +-0.951551 -0.257151 0.168595 +-0.951533 0.257221 -0.168588 +-0.951551 -0.257152 -0.168590 +-0.086139 -0.990439 0.107750 +0.086113 -0.990440 -0.107764 +0.086115 -0.990441 0.107752 +0.086113 -0.990440 -0.107764 +-0.086139 -0.990439 0.107750 +-0.086140 -0.990440 -0.107745 +0.951496 -0.257286 0.168702 +0.951476 0.257351 -0.168714 +0.951477 0.257354 0.168699 +0.951476 0.257351 -0.168714 +0.951496 -0.257286 0.168702 +0.951494 -0.257282 -0.168717 +-0.086168 0.990433 0.107782 +0.086137 0.990437 0.107776 +0.086133 0.990435 -0.107791 +-0.086168 0.990433 0.107782 +0.086133 0.990435 -0.107791 +-0.086168 0.990433 -0.107781 +0.119255 -0.230420 -0.965756 +-0.119296 -0.230417 -0.965752 +-0.119294 0.230486 -0.965736 +0.119255 -0.230420 -0.965756 +-0.119294 0.230486 -0.965736 +0.119260 0.230488 -0.965739 +-0.119261 0.230427 0.965754 +0.119221 -0.230362 0.965774 +0.119222 0.230444 0.965755 +0.119221 -0.230362 0.965774 +-0.119261 0.230427 0.965754 +-0.119260 -0.230367 0.965768 +-0.951548 -0.257149 0.168612 +-0.951530 0.257217 0.168610 +-0.951533 0.257221 -0.168588 +-0.951548 -0.257149 0.168612 +-0.951533 0.257221 -0.168588 +-0.951551 -0.257152 -0.168590 +0.086114 -0.990440 0.107763 +-0.086138 -0.990438 0.107762 +-0.086140 -0.990440 -0.107745 +0.086114 -0.990440 0.107763 +-0.086140 -0.990440 -0.107745 +0.086114 -0.990441 -0.107757 +0.951475 0.257352 0.168716 +0.951493 -0.257284 0.168719 +0.951495 -0.257285 -0.168707 +0.951475 0.257352 0.168716 +0.951495 -0.257285 -0.168707 +0.951477 0.257353 -0.168704 +-0.086168 0.990432 0.107794 +0.086136 0.990436 0.107787 +0.086134 0.990436 -0.107784 +-0.086168 0.990432 0.107794 +0.086134 0.990436 -0.107784 +-0.086168 0.990433 -0.107781 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.002425 0.999997 0.000000 +0.000000 0.000000 1.000000 +0.002423 -0.999997 -0.000001 +0.002423 -0.999997 -0.000001 +0.002423 -0.999997 -0.000001 +0.002423 -0.999997 -0.000001 +0.002423 -0.999997 0.000000 +0.002423 -0.999997 -0.000001 +-0.999985 -0.005401 0.000013 +-0.999985 -0.005401 0.000013 +-0.999985 -0.005401 0.000013 +-0.999985 -0.005401 0.000013 +-0.999985 -0.005401 0.000013 +-0.999985 -0.005405 0.000008 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +0.999985 0.005403 0.000000 +0.999985 0.005403 0.000000 +0.999985 0.005403 0.000000 +0.999985 0.005403 0.000000 +0.999985 0.005403 0.000000 +0.999985 0.005403 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.002424 0.999997 0.000000 +0.000000 0.000000 1.000000 +0.002423 -0.999997 0.000000 +0.002423 -0.999997 0.000000 +0.002423 -0.999997 0.000000 +0.002423 -0.999997 0.000000 +0.002423 -0.999997 0.000000 +0.002423 -0.999997 0.000000 +-0.999985 -0.005408 0.000005 +-0.999985 -0.005408 0.000005 +-0.999985 -0.005408 0.000005 +-0.999985 -0.005408 0.000005 +-0.999985 -0.005408 0.000005 +-0.999985 -0.005412 0.000000 +-0.002423 0.999997 0.000000 +-0.002423 0.999997 0.000000 +-0.002423 0.999997 0.000000 +-0.002423 0.999997 0.000000 +-0.002423 0.999997 0.000000 +-0.002423 0.999997 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.002425 0.999997 0.000000 +0.000000 0.000000 1.000000 +0.002423 -0.999997 -0.000001 +0.002423 -0.999997 -0.000001 +0.002423 -0.999997 -0.000001 +0.002423 -0.999997 -0.000001 +0.002423 -0.999997 0.000000 +0.002423 -0.999997 -0.000001 +-0.999985 -0.005401 0.000013 +-0.999985 -0.005401 0.000013 +-0.999985 -0.005401 0.000013 +-0.999985 -0.005401 0.000013 +-0.999985 -0.005401 0.000013 +-0.999985 -0.005405 0.000008 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +0.909584 -0.415520 -0.000001 +0.909584 -0.415520 0.000000 +0.909584 -0.415520 0.000000 +0.909584 -0.415520 0.000000 +0.909584 -0.415520 0.000000 +0.909584 -0.415520 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.418241 0.908336 -0.000001 +0.000000 0.000000 1.000000 +-0.418235 -0.908339 -0.000001 +-0.418235 -0.908339 -0.000001 +-0.418235 -0.908339 -0.000001 +-0.418235 -0.908339 -0.000001 +-0.418234 -0.908339 0.000000 +-0.418235 -0.908339 -0.000001 +-0.909581 0.415526 0.000014 +-0.909583 0.415522 0.000009 +-0.909581 0.415526 0.000014 +-0.909583 0.415522 0.000009 +-0.909581 0.415526 0.000014 +-0.909581 0.415526 0.000014 +0.418236 0.908339 0.000000 +0.418235 0.908339 -0.000001 +0.418235 0.908339 -0.000001 +0.418235 0.908339 -0.000001 +0.418235 0.908339 -0.000001 +0.418235 0.908339 -0.000001 +-0.001817 -0.999998 0.000000 +-0.001819 -0.999998 -0.000006 +-0.001819 -0.999998 -0.000006 +-0.001819 -0.999998 -0.000006 +-0.001819 -0.999998 -0.000006 +-0.001819 -0.999998 -0.000006 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.999998 -0.001816 0.000000 +0.999998 -0.001816 0.000000 +0.999998 -0.001816 0.000000 +0.999998 -0.001816 0.000000 +0.999998 -0.001816 0.000000 +0.999998 -0.001816 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999998 0.001829 0.000000 +-0.999998 0.001829 0.000000 +-0.999998 0.001829 0.000000 +-0.999998 0.001829 0.000000 +-0.999998 0.001829 0.000000 +-0.999998 0.001829 0.000000 +0.001816 0.999998 0.000004 +0.001818 0.999998 -0.000004 +0.001818 0.999998 -0.000004 +0.001818 0.999998 -0.000004 +0.001818 0.999998 -0.000004 +0.001818 0.999998 -0.000004 +-0.001817 -0.999998 0.000000 +-0.001819 -0.999998 -0.000006 +-0.001819 -0.999998 -0.000006 +-0.001819 -0.999998 -0.000006 +-0.001819 -0.999998 -0.000006 +-0.001819 -0.999998 -0.000006 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.999998 -0.001816 0.000000 +0.999998 -0.001816 0.000000 +0.999998 -0.001816 0.000000 +0.999998 -0.001816 0.000000 +0.999998 -0.001816 0.000000 +0.999998 -0.001816 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999998 0.001829 0.000000 +-0.999998 0.001829 0.000000 +-0.999998 0.001829 0.000000 +-0.999998 0.001829 0.000000 +-0.999998 0.001829 0.000000 +-0.999998 0.001829 0.000000 +0.001816 0.999998 0.000004 +0.001818 0.999998 -0.000004 +0.001818 0.999998 -0.000004 +0.001818 0.999998 -0.000004 +0.001818 0.999998 -0.000004 +0.001818 0.999998 -0.000004 +-0.001817 -0.999998 0.000000 +-0.001819 -0.999998 -0.000006 +-0.001819 -0.999998 -0.000006 +-0.001819 -0.999998 -0.000006 +-0.001819 -0.999998 -0.000006 +-0.001819 -0.999998 -0.000006 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.999998 -0.001816 0.000000 +0.999998 -0.001816 0.000000 +0.999998 -0.001816 0.000000 +0.999998 -0.001816 0.000000 +0.999998 -0.001816 0.000000 +0.999998 -0.001816 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999998 0.001829 0.000000 +-0.999998 0.001829 0.000000 +-0.999998 0.001829 0.000000 +-0.999998 0.001829 0.000000 +-0.999998 0.001829 0.000000 +-0.999998 0.001829 0.000000 +0.001816 0.999998 -0.000004 +0.001818 0.999998 0.000004 +0.001816 0.999998 -0.000004 +0.001816 0.999998 -0.000004 +0.001816 0.999998 -0.000004 +0.001816 0.999998 -0.000004 +0.999998 -0.001817 0.000000 +0.999998 -0.001819 -0.000006 +0.999998 -0.001819 -0.000006 +0.999998 -0.001819 -0.000006 +0.999998 -0.001819 -0.000006 +0.999998 -0.001819 -0.000006 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.001816 0.999998 0.000000 +0.001816 0.999998 0.000000 +0.001816 0.999998 0.000000 +0.001816 0.999998 0.000000 +0.001816 0.999998 0.000000 +0.001816 0.999998 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000001 0.000000 1.000000 +-0.001829 -0.999998 0.000000 +-0.001829 -0.999998 0.000000 +-0.001829 -0.999998 0.000000 +-0.001829 -0.999998 0.000000 +-0.001829 -0.999998 0.000000 +-0.001829 -0.999998 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001817 -0.000006 +-0.999998 0.001817 -0.000006 +-0.999998 0.001817 -0.000006 +-0.999998 0.001817 -0.000006 +-0.999998 0.001817 -0.000006 +-0.999998 0.001817 0.000000 +-0.999998 0.001819 -0.000006 +-0.999998 0.001819 -0.000006 +-0.999998 0.001819 -0.000006 +-0.999998 0.001819 -0.000006 +-0.999998 0.001819 -0.000006 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.001816 -0.999998 0.000000 +-0.001816 -0.999998 0.000000 +-0.001816 -0.999998 0.000000 +-0.001816 -0.999998 0.000000 +-0.001816 -0.999998 0.000000 +-0.001816 -0.999998 0.000000 +-0.000001 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.001829 0.999998 0.000000 +0.001829 0.999998 0.000000 +0.001829 0.999998 0.000000 +0.001829 0.999998 0.000000 +0.001829 0.999998 0.000000 +0.001829 0.999998 0.000000 +0.999998 -0.001816 0.000000 +0.999998 -0.001817 -0.000006 +0.999998 -0.001817 -0.000006 +0.999998 -0.001817 -0.000006 +0.999998 -0.001817 -0.000006 +0.999998 -0.001817 -0.000006 +0.999998 -0.001817 0.000000 +0.999998 -0.001819 -0.000006 +0.999998 -0.001819 -0.000006 +0.999998 -0.001819 -0.000006 +0.999998 -0.001819 -0.000006 +0.999998 -0.001819 -0.000006 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.001816 0.999998 0.000000 +0.001816 0.999998 0.000000 +0.001816 0.999998 0.000000 +0.001816 0.999998 0.000000 +0.001816 0.999998 0.000000 +0.001816 0.999998 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000001 0.000000 1.000000 +-0.001829 -0.999998 0.000000 +-0.001829 -0.999998 0.000000 +-0.001829 -0.999998 0.000000 +-0.001829 -0.999998 0.000000 +-0.001829 -0.999998 0.000000 +-0.001829 -0.999998 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001817 -0.000006 +-0.999998 0.001817 -0.000006 +-0.999998 0.001817 -0.000006 +-0.999998 0.001817 -0.000006 +-0.999998 0.001817 -0.000006 +0.001817 0.999998 0.000000 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000001 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +-0.001816 -0.999998 0.000000 +-0.001817 -0.999998 -0.000006 +-0.001817 -0.999998 -0.000006 +-0.001817 -0.999998 -0.000006 +-0.001817 -0.999998 -0.000006 +-0.001817 -0.999998 -0.000006 +0.195313 0.980741 0.000000 +0.195315 0.980741 -0.000007 +0.195315 0.980741 -0.000007 +0.195315 0.980741 -0.000007 +0.195313 0.980741 0.000000 +0.195315 0.980740 -0.000007 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.980741 0.195313 0.000005 +-0.980741 0.195313 0.000005 +-0.980741 0.195313 0.000005 +-0.980741 0.195313 0.000005 +-0.980741 0.195313 0.000005 +-0.980741 0.195311 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000001 0.000001 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.980738 -0.195326 -0.000002 +0.980738 -0.195326 -0.000002 +0.980738 -0.195326 -0.000002 +0.980738 -0.195326 -0.000002 +0.980738 -0.195326 -0.000002 +0.980738 -0.195327 0.000000 +-0.195311 -0.980741 -0.000009 +-0.195311 -0.980741 -0.000009 +-0.195313 -0.980741 0.000000 +-0.195311 -0.980741 -0.000009 +-0.195311 -0.980741 -0.000009 +-0.195311 -0.980741 -0.000009 +0.001817 0.999998 0.000000 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +-0.001816 -0.999998 0.000004 +-0.001818 -0.999998 -0.000004 +-0.001818 -0.999998 -0.000004 +-0.001818 -0.999998 -0.000004 +-0.001816 -0.999998 0.000004 +-0.001818 -0.999998 -0.000004 +0.001817 0.999998 0.000000 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +-0.001816 -0.999998 -0.000004 +-0.001818 -0.999998 0.000004 +-0.001816 -0.999998 -0.000004 +-0.001816 -0.999998 -0.000004 +-0.001816 -0.999998 -0.000004 +-0.001816 -0.999998 -0.000004 +0.001817 0.999998 0.000000 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +-0.001816 -0.999998 0.000004 +-0.001818 -0.999998 -0.000004 +-0.001818 -0.999998 -0.000004 +-0.001818 -0.999998 -0.000004 +-0.001816 -0.999998 0.000004 +-0.001818 -0.999998 -0.000004 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.000001 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.165043 -0.986286 0.000000 +-0.165043 -0.986286 0.000000 +-0.165043 -0.986286 0.000000 +-0.165043 -0.986286 0.000000 +-0.165043 -0.986286 0.000000 +-0.165043 -0.986286 0.000000 +0.986286 -0.165047 0.000000 +0.986286 -0.165047 0.000000 +0.986286 -0.165047 0.000000 +0.986286 -0.165047 0.000000 +0.986286 -0.165047 0.000000 +0.986286 -0.165047 0.000000 +0.165043 0.986286 0.000000 +0.165043 0.986286 0.000000 +0.165043 0.986286 0.000000 +0.165043 0.986286 0.000000 +0.165043 0.986286 0.000000 +0.165043 0.986286 0.000000 +-0.986286 0.165049 0.000000 +-0.986285 0.165049 0.000000 +-0.986285 0.165048 0.000000 +-0.986286 0.165049 0.000000 +-0.986285 0.165048 0.000000 +-0.986285 0.165049 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.165043 -0.986286 0.000000 +-0.165043 -0.986286 0.000000 +-0.165043 -0.986286 0.000000 +-0.165043 -0.986286 0.000000 +-0.165043 -0.986286 0.000000 +-0.165043 -0.986286 0.000000 +0.986286 -0.165047 0.000000 +0.986286 -0.165047 0.000000 +0.986286 -0.165047 0.000000 +0.986286 -0.165047 0.000000 +0.986286 -0.165047 0.000000 +0.986286 -0.165047 0.000000 +0.165043 0.986286 0.000000 +0.165043 0.986286 0.000000 +0.165043 0.986286 0.000000 +0.165043 0.986286 0.000000 +0.165043 0.986286 0.000000 +0.165043 0.986286 0.000000 +-0.986285 0.165048 0.000000 +-0.986285 0.165048 0.000000 +-0.986285 0.165048 0.000000 +-0.986285 0.165048 0.000000 +-0.986285 0.165048 0.000000 +-0.986285 0.165048 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.000001 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000001 0.000000 1.000000 +-0.000001 0.000000 1.000000 +0.000001 0.000000 1.000000 +-0.000001 0.000000 1.000000 +-0.000001 0.000000 1.000000 +-0.000001 0.000000 1.000000 +-0.980131 -0.198351 0.000000 +-0.980131 -0.198351 0.000000 +-0.980131 -0.198351 0.000000 +-0.980131 -0.198351 0.000000 +-0.980131 -0.198351 0.000000 +-0.980131 -0.198351 0.000000 +0.198346 -0.980132 0.000000 +0.198346 -0.980132 0.000000 +0.198346 -0.980132 0.000000 +0.198346 -0.980132 0.000000 +0.198346 -0.980132 0.000000 +0.198346 -0.980132 0.000000 +0.980131 0.198351 0.000000 +0.980131 0.198351 0.000000 +0.980131 0.198351 0.000000 +0.980131 0.198351 0.000000 +0.980131 0.198351 0.000000 +0.980131 0.198351 0.000000 +-0.198345 0.980132 0.000000 +-0.198345 0.980132 0.000000 +-0.198345 0.980132 0.000000 +-0.198345 0.980132 0.000000 +-0.198345 0.980132 0.000000 +-0.198345 0.980132 0.000000 +-0.000001 0.000000 -1.000000 +-0.000001 0.000000 -1.000000 +-0.000001 0.000000 -1.000000 +-0.000001 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000001 0.000000 -1.000000 +0.000000 -0.000001 1.000000 +0.000000 -0.000001 1.000000 +0.000000 -0.000001 1.000000 +0.000000 -0.000001 1.000000 +0.000000 -0.000001 1.000000 +0.000000 -0.000001 1.000000 +-0.980131 -0.198351 0.000000 +-0.980131 -0.198351 0.000000 +-0.980131 -0.198351 0.000000 +-0.980131 -0.198351 0.000000 +-0.980131 -0.198351 0.000000 +-0.980131 -0.198351 0.000000 +0.198346 -0.980132 0.000000 +0.198346 -0.980132 0.000000 +0.198346 -0.980132 0.000000 +0.198346 -0.980132 0.000000 +0.198346 -0.980132 0.000000 +0.198346 -0.980132 0.000000 +0.980131 0.198351 0.000000 +0.980131 0.198351 0.000000 +0.980131 0.198351 0.000000 +0.980131 0.198351 0.000000 +0.980131 0.198351 0.000000 +0.980131 0.198351 0.000000 +-0.198345 0.980132 0.000000 +-0.198345 0.980132 0.000000 +-0.198345 0.980132 0.000000 +-0.198345 0.980132 0.000000 +-0.198345 0.980132 0.000000 +-0.198345 0.980132 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.980131 -0.198350 0.000000 +-0.980131 -0.198350 0.000000 +-0.980131 -0.198350 0.000000 +-0.980131 -0.198350 0.000000 +-0.980131 -0.198350 0.000000 +-0.980131 -0.198350 0.000000 +0.198346 -0.980132 0.000000 +0.198346 -0.980132 0.000000 +0.198346 -0.980132 0.000000 +0.198346 -0.980132 0.000000 +0.198346 -0.980132 0.000000 +0.198346 -0.980132 0.000000 +0.980131 0.198350 0.000000 +0.980131 0.198350 0.000000 +0.980131 0.198350 0.000000 +0.980131 0.198350 0.000000 +0.980131 0.198350 0.000000 +0.980131 0.198350 0.000000 +-0.198346 0.980132 0.000000 +-0.198346 0.980132 0.000000 +-0.198346 0.980132 0.000000 +-0.198346 0.980132 0.000000 +-0.198346 0.980132 0.000000 +-0.198346 0.980132 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.980131 -0.198351 0.000000 +-0.980131 -0.198351 0.000000 +-0.980131 -0.198351 0.000000 +-0.980131 -0.198351 0.000000 +-0.980131 -0.198351 0.000000 +-0.980131 -0.198351 0.000000 +0.198346 -0.980132 0.000000 +0.198346 -0.980132 0.000000 +0.198346 -0.980132 0.000000 +0.198346 -0.980132 0.000000 +0.198346 -0.980132 0.000000 +0.198346 -0.980132 0.000000 +0.980131 0.198351 0.000000 +0.980131 0.198351 0.000000 +0.980131 0.198351 0.000000 +0.980131 0.198351 0.000000 +0.980131 0.198351 0.000000 +0.980131 0.198351 0.000000 +-0.198345 0.980132 0.000000 +-0.198345 0.980132 0.000000 +-0.198345 0.980132 0.000000 +-0.198345 0.980132 0.000000 +-0.198345 0.980132 0.000000 +-0.198345 0.980132 0.000000 + + + + + + + + + + + +0.109020 0.038880 +0.482223 0.042625 +0.108463 0.039541 +0.485226 0.420580 +0.484530 0.420580 +0.484251 0.418555 +0.108657 0.418238 +0.485016 0.418868 +0.108657 0.418238 +0.483024 0.420597 +0.483024 0.420597 +0.110760 0.421926 +0.485227 0.420580 +0.110760 0.421926 +0.484531 0.420580 +0.482733 0.042185 +0.110670 0.040689 +0.111451 0.041893 +0.488313 0.420300 +0.108120 0.417948 +0.108120 0.417948 +0.485263 0.419226 +0.488313 0.420300 +0.484090 0.418566 +0.110622 0.421852 +0.110622 0.421852 +0.110296 0.419281 +0.109371 0.419068 +0.109371 0.419069 +0.110296 0.419281 +0.481478 0.043648 +0.481478 0.043648 +0.484252 0.420631 +0.484252 0.420631 +0.109020 0.038880 +0.482223 0.042625 +0.108463 0.039541 +0.485226 0.420580 +0.484530 0.420580 +0.484252 0.418555 +0.108657 0.418238 +0.485016 0.418868 +0.108657 0.418238 +0.483024 0.420597 +0.483024 0.420597 +0.110760 0.421926 +0.485226 0.420580 +0.110760 0.421926 +0.484531 0.420580 +0.482733 0.042185 +0.110669 0.040688 +0.111451 0.041893 +0.488313 0.420300 +0.108120 0.417948 +0.108120 0.417948 +0.485263 0.419226 +0.488313 0.420300 +0.484092 0.418565 +0.110622 0.421852 +0.110622 0.421852 +0.110296 0.419281 +0.109371 0.419068 +0.109371 0.419069 +0.110296 0.419281 +0.481478 0.043648 +0.481478 0.043648 +0.484252 0.420631 +0.484252 0.420631 +0.109020 0.038880 +0.482223 0.042625 +0.108463 0.039541 +0.485226 0.420580 +0.484530 0.420580 +0.484252 0.418555 +0.108657 0.418238 +0.485016 0.418868 +0.108657 0.418238 +0.483024 0.420597 +0.483024 0.420597 +0.110760 0.421926 +0.485226 0.420580 +0.110760 0.421926 +0.484531 0.420580 +0.482733 0.042185 +0.110670 0.040689 +0.111451 0.041893 +0.488313 0.420300 +0.108120 0.417948 +0.108120 0.417948 +0.485263 0.419226 +0.488313 0.420300 +0.484090 0.418566 +0.110622 0.421852 +0.110622 0.421852 +0.110296 0.419281 +0.109371 0.419068 +0.109371 0.419069 +0.110296 0.419281 +0.481478 0.043648 +0.481478 0.043648 +0.484252 0.420631 +0.484252 0.420631 +0.109020 0.038880 +0.482223 0.042625 +0.108463 0.039541 +0.485226 0.420580 +0.484530 0.420580 +0.484252 0.418555 +0.108657 0.418238 +0.485016 0.418868 +0.108657 0.418238 +0.483024 0.420597 +0.483024 0.420597 +0.110760 0.421926 +0.485226 0.420580 +0.110760 0.421926 +0.484531 0.420580 +0.482733 0.042185 +0.110669 0.040688 +0.111451 0.041893 +0.488313 0.420300 +0.108120 0.417948 +0.108120 0.417948 +0.485263 0.419226 +0.488313 0.420300 +0.484092 0.418565 +0.110622 0.421852 +0.110622 0.421852 +0.110296 0.419281 +0.109371 0.419068 +0.109371 0.419069 +0.110296 0.419281 +0.481478 0.043648 +0.481478 0.043648 +0.484252 0.420631 +0.484252 0.420631 +0.109020 0.038880 +0.482223 0.042625 +0.108463 0.039541 +0.485226 0.420580 +0.484530 0.420580 +0.484252 0.418555 +0.108657 0.418238 +0.485016 0.418868 +0.108657 0.418238 +0.483024 0.420597 +0.483024 0.420597 +0.110760 0.421926 +0.485227 0.420580 +0.110760 0.421926 +0.484531 0.420580 +0.482733 0.042185 +0.110669 0.040688 +0.111451 0.041893 +0.488313 0.420300 +0.108120 0.417948 +0.108120 0.417948 +0.485263 0.419226 +0.488313 0.420300 +0.484092 0.418565 +0.110622 0.421852 +0.110622 0.421852 +0.110296 0.419281 +0.109371 0.419068 +0.109371 0.419069 +0.110296 0.419281 +0.481478 0.043648 +0.481478 0.043648 +0.484252 0.420631 +0.484252 0.420631 +0.109020 0.038880 +0.482223 0.042625 +0.108463 0.039541 +0.485226 0.420580 +0.484530 0.420580 +0.484252 0.418555 +0.108657 0.418238 +0.485016 0.418868 +0.108657 0.418238 +0.483024 0.420597 +0.483024 0.420597 +0.110760 0.421926 +0.485227 0.420580 +0.110760 0.421926 +0.484531 0.420580 +0.482733 0.042185 +0.110670 0.040689 +0.111451 0.041893 +0.488313 0.420300 +0.108120 0.417948 +0.108120 0.417948 +0.485263 0.419226 +0.488313 0.420300 +0.484092 0.418565 +0.110622 0.421852 +0.110622 0.421852 +0.110296 0.419281 +0.109371 0.419068 +0.109371 0.419069 +0.110296 0.419281 +0.481478 0.043648 +0.481478 0.043648 +0.484252 0.420631 +0.484252 0.420631 +0.479846 0.420580 +0.114013 0.420894 +0.478853 0.420580 +0.113937 0.420889 +0.478853 0.420580 +0.478224 0.420580 +0.478224 0.420580 +0.114014 0.420907 +0.480622 0.420580 +0.113936 0.420877 +0.478853 0.420580 +0.114201 0.420162 +0.113941 0.420203 +0.113903 0.420285 +0.113980 0.420279 +0.478224 0.420580 +0.478224 0.420580 +0.113977 0.420238 +0.478853 0.420580 +0.113901 0.420246 +0.478853 0.420580 +0.113977 0.420226 +0.478224 0.420580 +0.478853 0.420580 +0.113938 0.420150 +0.478854 0.420580 +0.114012 0.420873 +0.113935 0.420856 +0.113935 0.420857 +0.114012 0.420872 +0.113979 0.420267 +0.478224 0.420580 +0.478853 0.420580 +0.113941 0.420203 +0.478853 0.420580 +0.478224 0.420580 +0.478224 0.420580 +0.113979 0.420279 +0.478853 0.420580 +0.113903 0.420285 +0.478853 0.420580 +0.114013 0.420894 +0.113936 0.420889 +0.113936 0.420877 +0.114014 0.420907 +0.479846 0.420580 +0.114013 0.420894 +0.478853 0.420580 +0.478853 0.420580 +0.113936 0.420889 +0.478224 0.420580 +0.114014 0.420907 +0.478224 0.420580 +0.480624 0.420580 +0.478853 0.420580 +0.113936 0.420877 +0.114201 0.420162 +0.113941 0.420203 +0.113903 0.420285 +0.113980 0.420279 +0.478224 0.420580 +0.478224 0.420580 +0.113977 0.420238 +0.478853 0.420580 +0.113901 0.420246 +0.478853 0.420580 +0.113977 0.420226 +0.478224 0.420580 +0.478853 0.420580 +0.113938 0.420150 +0.478854 0.420580 +0.114012 0.420873 +0.113935 0.420856 +0.113935 0.420857 +0.114012 0.420872 +0.113979 0.420267 +0.478224 0.420580 +0.478853 0.420580 +0.113941 0.420203 +0.478853 0.420580 +0.478224 0.420580 +0.478224 0.420580 +0.113979 0.420279 +0.478853 0.420580 +0.113903 0.420285 +0.478853 0.420580 +0.114013 0.420894 +0.113936 0.420889 +0.113936 0.420877 +0.114014 0.420907 +0.479846 0.420580 +0.114013 0.420894 +0.478853 0.420580 +0.478853 0.420580 +0.113936 0.420889 +0.478224 0.420580 +0.114014 0.420907 +0.478224 0.420580 +0.480626 0.420580 +0.478853 0.420580 +0.113936 0.420877 +0.114201 0.420162 +0.113941 0.420203 +0.113903 0.420285 +0.113980 0.420279 +0.478224 0.420580 +0.478224 0.420580 +0.113977 0.420238 +0.478853 0.420580 +0.113901 0.420246 +0.478853 0.420580 +0.113977 0.420226 +0.478224 0.420580 +0.478853 0.420580 +0.113938 0.420150 +0.478854 0.420580 +0.114012 0.420873 +0.113935 0.420856 +0.113935 0.420857 +0.114012 0.420872 +0.113979 0.420267 +0.478224 0.420580 +0.478853 0.420580 +0.113941 0.420203 +0.478853 0.420580 +0.478224 0.420580 +0.478224 0.420580 +0.113979 0.420279 +0.478853 0.420580 +0.113903 0.420285 +0.478853 0.420580 +0.114013 0.420894 +0.113936 0.420889 +0.113936 0.420877 +0.114014 0.420907 +0.489049 0.036961 +0.105430 0.036961 +0.489049 0.420580 +0.105430 0.420580 +0.105430 0.036961 +0.489049 0.036961 +0.105430 0.420580 +0.489049 0.420580 +0.105430 0.036961 +0.489049 0.036961 +0.105430 0.420580 +0.489049 0.420580 +0.105430 0.036961 +0.489049 0.036961 +0.105430 0.420580 +0.489049 0.420580 +0.489049 0.036961 +0.105430 0.036961 +0.489049 0.420580 +0.105430 0.420580 +0.105430 0.036961 +0.489049 0.036961 +0.105430 0.420580 +0.489049 0.420580 +0.105430 0.036961 +0.489049 0.036961 +0.105430 0.420580 +0.489049 0.420580 +0.105430 0.036961 +0.489049 0.036961 +0.105430 0.420580 +0.489049 0.420580 +0.489049 0.036961 +0.105430 0.036961 +0.489049 0.420580 +0.105430 0.420580 +0.105430 0.036961 +0.489049 0.036961 +0.105430 0.420580 +0.489049 0.420580 +0.105430 0.036961 +0.489049 0.036961 +0.105430 0.420580 +0.489049 0.420580 +0.105430 0.036961 +0.489049 0.036961 +0.105430 0.420580 +0.489049 0.420580 +0.467426 0.244300 +0.317890 0.040957 +0.467429 0.037310 +0.472758 0.037231 +0.460787 0.037387 +0.466120 0.037309 +0.466120 0.244456 +0.460787 0.244456 +0.109426 0.039190 +0.326357 0.039046 +0.331686 0.039125 +0.331689 0.042629 +0.110978 0.040957 +0.110978 0.037531 +0.317890 0.037531 +0.318047 0.041049 +0.326360 0.044104 +0.331690 0.043948 +0.331690 0.047687 +0.326357 0.047609 +0.109426 0.246102 +0.105999 0.246102 +0.105999 0.039190 +0.109582 0.246194 +0.109738 0.246194 +0.109738 0.246259 +0.318203 0.041049 +0.318203 0.041114 +0.109582 0.246415 +0.109517 0.246415 +0.318047 0.041269 +0.317982 0.041269 +0.109634 0.246185 +0.109582 0.038878 +0.317982 0.041114 +0.110666 0.041049 +0.109738 0.039033 +0.109738 0.039098 +0.110821 0.041049 +0.110886 0.041114 +0.109582 0.039098 +0.109517 0.039033 +0.472758 0.244300 +0.467426 0.037231 +0.110886 0.041269 +0.110821 0.041269 +0.472761 0.037153 +0.472761 0.244379 +0.460784 0.037309 +0.460784 0.037153 +0.110811 0.041124 +0.318047 0.037218 +0.466122 0.037153 +0.466122 0.037309 +0.109517 0.038878 +0.105687 0.246194 +0.318203 0.037374 +0.318203 0.037439 +0.105842 0.246194 +0.105907 0.246259 +0.318047 0.037439 +0.317982 0.037374 +0.105907 0.246415 +0.105842 0.246415 +0.326357 0.042629 +0.331690 0.038969 +0.317982 0.037218 +0.467422 0.244379 +0.105687 0.246259 +0.105687 0.039033 +0.110886 0.037218 +0.110886 0.037374 +0.466123 0.244535 +0.105842 0.038878 +0.110821 0.037439 +0.110666 0.037439 +0.105907 0.038878 +0.105907 0.039033 +0.331692 0.043792 +0.110666 0.037374 +0.105842 0.039098 +0.105687 0.039098 +0.109508 0.246437 +0.105916 0.246311 +0.109803 0.246102 +0.110821 0.037218 +0.318057 0.041124 +0.110978 0.041334 +0.110770 0.037448 +0.331692 0.038968 +0.318268 0.040957 +0.109592 0.039023 +0.331692 0.043947 +0.109803 0.039190 +0.105665 0.246185 +0.105622 0.039190 +0.326355 0.043948 +0.110601 0.040957 +0.317890 0.037153 +0.318057 0.037364 +0.110895 0.037196 +0.105832 0.039023 +0.326353 0.043792 +0.326353 0.047843 +0.326353 0.047687 +0.331692 0.047687 +0.331692 0.047843 +0.326353 0.038968 +0.326353 0.038813 +0.326353 0.042708 +0.460784 0.244535 +0.331692 0.042708 +0.281940 0.050610 +0.278248 0.257787 +0.278293 0.050600 +0.281895 0.257798 +0.368193 0.257639 +0.364549 0.257632 +0.368252 0.050499 +0.364594 0.050444 +0.283384 0.050612 +0.312978 0.259726 +0.105804 0.338885 +0.362544 0.257786 +0.477727 0.037227 +0.474133 0.116347 +0.362473 0.050586 +0.313003 0.338815 +0.484093 0.199272 +0.474140 0.037264 +0.477722 0.116253 +0.487648 0.120214 +0.484098 0.120246 +0.487680 0.199235 +0.283454 0.257811 +0.105778 0.259796 +0.276961 0.050610 +0.273269 0.257787 +0.273314 0.050600 +0.276916 0.257798 +0.378151 0.257639 +0.374507 0.257632 +0.378210 0.050499 +0.374552 0.050444 +0.189941 0.257786 +0.192105 0.050612 +0.271263 0.257786 +0.110782 0.050612 +0.487685 0.037227 +0.484091 0.116347 +0.110852 0.257811 +0.271194 0.050586 +0.474135 0.199272 +0.484098 0.037264 +0.487680 0.116253 +0.477690 0.120214 +0.474140 0.120246 +0.477722 0.199235 +0.189872 0.050586 +0.192174 0.257811 +0.114100 0.042156 +0.321277 0.045848 +0.114090 0.045803 +0.321288 0.042201 +0.373172 0.257639 +0.369528 0.257632 +0.373231 0.050499 +0.105804 0.420207 +0.312978 0.341048 +0.379634 0.037225 +0.458802 0.244353 +0.479212 0.199274 +0.369573 0.050444 +0.482706 0.037227 +0.479112 0.116347 +0.105778 0.341118 +0.479196 0.120231 +0.379713 0.244379 +0.479118 0.037264 +0.482702 0.116253 +0.482824 0.120214 +0.482857 0.199235 +0.313003 0.420137 +0.458717 0.037231 +0.016244 0.715841 +0.756345 0.522332 +0.756346 0.715841 +0.016243 0.522332 +0.009526 0.061000 +0.749637 0.514493 +0.009526 0.514494 +0.749636 0.060999 +0.969477 0.480355 +0.969577 0.938728 +0.771464 0.938319 +0.771396 0.480706 +0.007192 0.039423 +0.751630 0.039423 +0.007192 0.498972 +0.751630 0.498972 +0.779207 0.499082 +0.779286 0.040707 +0.977371 0.041060 +0.977311 0.498670 +0.016243 0.911620 +0.756344 0.718111 +0.756344 0.911620 +0.016243 0.718111 +0.016244 0.715841 +0.756345 0.522332 +0.756346 0.715841 +0.016243 0.522332 +0.009526 0.061000 +0.749637 0.514493 +0.009526 0.514494 +0.749636 0.060999 +0.969477 0.480355 +0.969577 0.938728 +0.771464 0.938319 +0.771396 0.480706 +0.007192 0.039423 +0.751630 0.039423 +0.007192 0.498972 +0.751630 0.498972 +0.779207 0.499082 +0.779286 0.040707 +0.977371 0.041060 +0.977311 0.498670 +0.016243 0.911620 +0.756344 0.718111 +0.756344 0.911620 +0.016243 0.718111 +0.016244 0.715841 +0.756345 0.522332 +0.756346 0.715841 +0.016243 0.522332 +0.009526 0.061000 +0.749637 0.514493 +0.009526 0.514494 +0.749636 0.060999 +0.969477 0.480355 +0.969577 0.938728 +0.771464 0.938319 +0.771396 0.480706 +0.007192 0.039423 +0.751630 0.039423 +0.007192 0.498972 +0.751630 0.498972 +0.779207 0.499082 +0.779286 0.040707 +0.977371 0.041060 +0.977311 0.498670 +0.756344 0.911620 +0.016243 0.718111 +0.756344 0.718111 +0.016243 0.911620 +0.016244 0.715841 +0.756345 0.522332 +0.756346 0.715841 +0.016243 0.522332 +0.009526 0.061000 +0.749637 0.514493 +0.009526 0.514494 +0.749636 0.060999 +0.969477 0.480355 +0.969577 0.938728 +0.771464 0.938319 +0.771396 0.480706 +0.007192 0.039423 +0.751630 0.039423 +0.007192 0.498972 +0.751630 0.498972 +0.779207 0.499082 +0.779286 0.040707 +0.977371 0.041060 +0.977311 0.498670 +0.016243 0.911620 +0.756344 0.718111 +0.756344 0.911620 +0.016243 0.718111 +0.016244 0.715841 +0.756345 0.522332 +0.756346 0.715841 +0.016243 0.522332 +0.009526 0.061000 +0.749637 0.514493 +0.009526 0.514494 +0.749636 0.060999 +0.969477 0.480355 +0.969577 0.938728 +0.771464 0.938319 +0.771396 0.480706 +0.007192 0.039423 +0.751630 0.039423 +0.007192 0.498972 +0.751630 0.498972 +0.779207 0.499082 +0.779286 0.040707 +0.977371 0.041060 +0.977311 0.498670 +0.016243 0.911620 +0.756344 0.718111 +0.756344 0.911620 +0.016243 0.718111 +0.016244 0.715841 +0.756345 0.522332 +0.756346 0.715841 +0.016243 0.522332 +0.009526 0.061000 +0.749637 0.514493 +0.009526 0.514494 +0.749636 0.060999 +0.969477 0.480355 +0.969577 0.938728 +0.771464 0.938319 +0.771396 0.480706 +0.007192 0.039423 +0.751630 0.039423 +0.007192 0.498972 +0.751630 0.498972 +0.779207 0.499082 +0.779286 0.040707 +0.977371 0.041060 +0.977311 0.498670 +0.016243 0.911620 +0.756344 0.718111 +0.756344 0.911620 +0.016243 0.718111 +0.016244 0.715841 +0.756345 0.522332 +0.756346 0.715841 +0.016243 0.522332 +0.009526 0.061000 +0.749637 0.514493 +0.009526 0.514494 +0.749636 0.060999 +0.969477 0.480355 +0.969577 0.938728 +0.771464 0.938319 +0.771396 0.480706 +0.007192 0.039423 +0.751630 0.039423 +0.007192 0.498972 +0.751630 0.498972 +0.779207 0.499082 +0.779286 0.040707 +0.977371 0.041060 +0.977311 0.498670 +0.016243 0.911620 +0.756344 0.718111 +0.756344 0.911620 +0.016243 0.718111 +0.016244 0.715841 +0.756345 0.522332 +0.756346 0.715841 +0.016243 0.522332 +0.009526 0.061000 +0.749637 0.514493 +0.009526 0.514494 +0.749636 0.060999 +0.969477 0.480355 +0.969577 0.938728 +0.771464 0.938319 +0.771396 0.480706 +0.007192 0.039423 +0.751630 0.039423 +0.007192 0.498972 +0.751630 0.498972 +0.779207 0.499082 +0.779286 0.040707 +0.977371 0.041060 +0.977311 0.498670 +0.756344 0.911620 +0.016243 0.718111 +0.756344 0.718111 +0.016243 0.911620 +0.486957 0.692024 +0.027038 0.424800 +0.486954 0.424800 +0.027038 0.692024 +0.506996 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.966910 0.036168 +0.029544 0.043430 +0.489461 0.415225 +0.029544 0.415224 +0.489461 0.035380 +0.029544 0.035380 +0.037422 0.971548 +0.407335 0.698761 +0.409054 0.971742 +0.039211 0.698717 +0.965462 0.676852 +0.505546 0.676852 +0.505546 0.409621 +0.965459 0.409621 +0.914572 0.962378 +0.922325 0.705031 +0.570344 0.705031 +0.570343 0.962377 +0.027038 0.692024 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.424800 +0.506996 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.966910 0.036168 +0.029544 0.043430 +0.489461 0.415225 +0.029544 0.415224 +0.489461 0.035380 +0.029544 0.035380 +0.037422 0.971548 +0.039211 0.698717 +0.409054 0.971742 +0.407335 0.698761 +0.965462 0.676852 +0.505546 0.676852 +0.505546 0.409621 +0.965459 0.409621 +0.914572 0.962378 +0.922325 0.705031 +0.570344 0.705031 +0.570343 0.962377 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.206126 +1.014936 0.691973 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.206126 +0.170286 0.691973 +0.229772 0.173002 +0.933648 0.102615 +0.933648 0.173002 +0.229772 0.102615 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.206126 +1.014936 0.691973 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.206126 +0.170286 0.691973 +0.229772 0.173002 +0.933648 0.102615 +0.933648 0.173002 +0.229772 0.102615 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.206126 +1.014936 0.691973 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.691973 +0.170286 0.206126 +0.933648 0.173002 +0.229772 0.173002 +0.229772 0.102615 +0.933648 0.102615 +0.486957 0.692024 +0.027038 0.424800 +0.486954 0.424800 +0.027038 0.692024 +0.506996 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.966910 0.036168 +0.029544 0.043430 +0.489461 0.415225 +0.029544 0.415224 +0.489461 0.035380 +0.029544 0.035380 +0.037422 0.971548 +0.407335 0.698761 +0.409054 0.971742 +0.039211 0.698717 +0.965462 0.676852 +0.505546 0.676852 +0.505546 0.409621 +0.965459 0.409621 +0.914572 0.962378 +0.922325 0.705031 +0.570344 0.705031 +0.570343 0.962377 +0.486957 0.692024 +0.027038 0.424800 +0.486954 0.424800 +0.027038 0.692024 +0.506996 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.966910 0.036168 +0.029544 0.043430 +0.489461 0.415225 +0.029544 0.415224 +0.489461 0.035380 +0.037422 0.971548 +0.407335 0.698761 +0.409054 0.971742 +0.039211 0.698717 +0.965462 0.676852 +0.505546 0.676852 +0.505546 0.409621 +0.965459 0.409621 +0.914572 0.962378 +0.922325 0.705031 +0.570344 0.705031 +0.570343 0.962377 +0.016244 0.715841 +0.756345 0.522332 +0.756346 0.715841 +0.016243 0.522332 +0.009526 0.061000 +0.749637 0.514493 +0.009526 0.514494 +0.749636 0.060999 +0.969477 0.480355 +0.969577 0.938728 +0.771464 0.938319 +0.771396 0.480706 +0.007192 0.039423 +0.751630 0.039423 +0.007192 0.498972 +0.751630 0.498972 +0.779207 0.499082 +0.779286 0.040707 +0.977371 0.041060 +0.977311 0.498670 +0.016243 0.911620 +0.756344 0.718111 +0.756344 0.911620 +0.016243 0.718111 +0.016244 0.715841 +0.756345 0.522332 +0.756346 0.715841 +0.016243 0.522332 +0.009526 0.061000 +0.749637 0.514493 +0.009526 0.514494 +0.749636 0.060999 +0.969477 0.480355 +0.969577 0.938728 +0.771464 0.938319 +0.771396 0.480706 +0.007192 0.039423 +0.751630 0.039423 +0.007192 0.498972 +0.751630 0.498972 +0.779207 0.499082 +0.779286 0.040707 +0.977371 0.041060 +0.977311 0.498670 +0.756344 0.911620 +0.016243 0.718111 +0.756344 0.718111 +0.016243 0.911620 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.206126 +1.014936 0.691973 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.206126 +0.170286 0.691973 +0.229772 0.173002 +0.933648 0.102615 +0.933648 0.173002 +0.229772 0.102615 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.206126 +1.014936 0.691973 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.206126 +0.170286 0.691973 +0.229772 0.173002 +0.933648 0.102615 +0.933648 0.173002 +0.229772 0.102615 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.206126 +1.014936 0.691973 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.691973 +0.170286 0.206126 +0.933648 0.173002 +0.229772 0.173002 +0.229772 0.102615 +0.933648 0.102615 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.691973 +1.014936 0.206126 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.691973 +0.170286 0.206126 +0.933648 0.173002 +0.229772 0.173002 +0.229772 0.102615 +0.933648 0.102615 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.206126 +1.014936 0.691973 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.691973 +0.170286 0.206126 +0.933648 0.173002 +0.229772 0.173002 +0.229772 0.102615 +0.933648 0.102615 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.206126 +1.014936 0.691973 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.206126 +0.170286 0.691973 +0.229772 0.173002 +0.933648 0.102615 +0.933648 0.173002 +0.229772 0.102615 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.206126 +1.014936 0.691973 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.206126 +0.170286 0.691973 +0.229772 0.173002 +0.933648 0.102615 +0.933648 0.173002 +0.229772 0.102615 +0.016244 0.715841 +0.756345 0.522332 +0.756346 0.715841 +0.016243 0.522332 +0.009526 0.061000 +0.749637 0.514493 +0.009526 0.514494 +0.749636 0.060999 +0.969477 0.480355 +0.969577 0.938728 +0.771464 0.938319 +0.771396 0.480706 +0.007192 0.039423 +0.751630 0.039423 +0.007192 0.498972 +0.751630 0.498972 +0.779207 0.499082 +0.779286 0.040707 +0.977371 0.041060 +0.977311 0.498670 +0.016243 0.911620 +0.756344 0.718111 +0.756344 0.911620 +0.016243 0.718111 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.206126 +1.014936 0.691973 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.206126 +0.170286 0.691973 +0.229772 0.173002 +0.933648 0.102615 +0.933648 0.173002 +0.229772 0.102615 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.206126 +1.014936 0.691973 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.206126 +0.170286 0.691973 +0.229772 0.173002 +0.933648 0.102615 +0.933648 0.173002 +0.229772 0.102615 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.206126 +1.014936 0.691973 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.691973 +0.170286 0.206126 +0.933648 0.173002 +0.229772 0.173002 +0.229772 0.102615 +0.933648 0.102615 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.206126 +1.014936 0.691973 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.691973 +0.170286 0.206126 +0.229772 0.173002 +0.933648 0.102615 +0.933648 0.173002 +0.229772 0.102615 +0.489049 0.420727 +0.489049 0.420727 +0.489049 0.420727 +0.489049 0.420727 +0.489049 0.420727 +0.489049 0.420727 +0.489049 0.420727 +0.489049 0.420727 +0.489049 0.420727 +0.489049 0.420727 +0.489049 0.420727 +0.489049 0.420727 +0.480370 0.420580 +0.479846 0.420580 +0.480371 0.420580 +0.479846 0.420580 +0.480371 0.420580 +0.479845 0.420580 +0.029544 0.035377 +0.029544 0.035379 +0.029544 0.035377 +0.029544 0.035376 +0.113937 0.420873 + + + + + + + + + + + +

0 0 6 2 1 31 1 2 7 2 3 31 0 4 6 5 5 0 2 6 16 9 7 23 1 8 19 9 9 23 2 10 16 7 11 1 9 12 8 7 13 17 8 14 21 8 15 21 7 16 17 6 17 30 6 18 2 0 19 5 8 20 20 0 21 5 6 22 2 5 23 15 3 24 11 1 25 7 10 26 3 1 27 7 3 28 11 0 29 6 9 30 22 10 31 24 1 32 19 10 33 24 9 34 22 4 35 14 8 36 21 4 37 13 9 38 8 4 39 13 8 40 21 11 41 12 0 42 18 11 43 25 8 44 20 11 45 25 0 46 18 3 47 4 12 48 26 10 49 3 13 50 32 10 51 3 12 52 26 3 53 11 13 54 27 4 55 14 15 56 9 4 57 14 13 58 27 10 59 24 15 60 29 4 61 13 14 62 33 14 63 33 4 64 13 11 65 12 14 66 28 11 67 25 12 68 10 12 69 10 11 70 25 3 71 4 12 72 1187 15 73 1186 14 74 33 15 75 1186 12 76 1187 13 77 32 16 78 40 18 79 65 17 80 41 18 81 65 16 82 40 21 83 34 17 84 53 18 85 50 25 86 57 25 87 57 18 88 50 23 89 35 25 90 42 23 91 51 24 92 55 24 93 55 23 94 51 22 95 64 24 96 54 21 97 49 16 98 39 21 99 49 24 100 54 22 101 36 16 102 40 26 103 37 19 104 45 16 105 40 17 106 41 26 107 37 25 108 56 26 109 58 17 110 53 26 111 58 25 112 56 20 113 48 24 114 55 20 115 47 25 116 42 20 117 47 24 118 55 27 119 46 24 120 54 16 121 52 19 122 38 24 123 54 19 124 38 27 125 59 28 126 60 19 127 45 29 128 66 29 129 66 19 130 45 26 131 37 29 132 61 26 133 58 31 134 43 31 135 43 26 136 58 20 137 48 31 138 63 27 139 46 30 140 67 27 141 46 31 142 63 20 143 47 30 144 62 19 145 38 28 146 44 19 147 38 30 148 62 27 149 59 28 150 1189 31 151 1188 30 152 67 31 153 1188 28 154 1189 29 155 66 32 156 74 34 157 99 33 158 75 34 159 99 32 160 74 37 161 68 34 162 84 41 163 91 33 164 87 41 165 91 34 166 84 39 167 69 41 168 76 39 169 85 40 170 89 40 171 89 39 172 85 38 173 98 38 174 70 32 175 73 40 176 88 32 177 73 38 178 70 37 179 83 32 180 74 42 181 71 35 182 79 32 183 74 33 184 75 42 185 71 41 186 90 42 187 92 33 188 87 42 189 92 41 190 90 36 191 82 40 192 89 36 193 81 41 194 76 36 195 81 40 196 89 43 197 80 32 198 86 43 199 93 40 200 88 43 201 93 32 202 86 35 203 72 44 204 94 35 205 79 45 206 100 45 207 100 35 208 79 42 209 71 45 210 95 36 211 82 47 212 77 36 213 82 45 214 95 42 215 92 47 216 97 43 217 80 46 218 101 43 219 80 47 220 97 36 221 81 46 222 96 43 223 93 44 224 78 44 225 78 43 226 93 35 227 72 44 228 1191 47 229 1190 46 230 101 47 231 1190 44 232 1191 45 233 100 48 234 108 50 235 133 49 236 109 50 237 133 48 238 108 53 239 102 49 240 121 55 241 103 57 242 125 55 243 103 49 244 121 50 245 118 57 246 110 55 247 119 56 248 123 56 249 123 55 250 119 54 251 132 56 252 122 54 253 104 48 254 107 48 255 107 54 256 104 53 257 117 48 258 108 58 259 105 51 260 113 48 261 108 49 262 109 58 263 105 57 264 124 58 265 126 49 266 121 58 267 126 57 268 124 52 269 116 56 270 123 52 271 115 57 272 110 52 273 115 56 274 123 59 275 114 56 276 122 48 277 120 51 278 106 56 279 122 51 280 106 59 281 127 60 282 128 51 283 113 61 284 134 61 285 134 51 286 113 58 287 105 61 288 129 52 289 116 63 290 111 52 291 116 61 292 129 58 293 126 63 294 131 59 295 114 62 296 135 59 297 114 63 298 131 52 299 115 62 300 130 51 301 106 60 302 112 51 303 106 62 304 130 59 305 127 62 306 135 61 307 134 63 308 1192 61 309 134 62 310 135 60 311 1193 64 312 142 66 313 167 65 314 143 66 315 167 64 316 142 69 317 136 65 318 155 71 319 137 73 320 159 71 321 137 65 322 155 66 323 152 73 324 144 71 325 153 72 326 157 72 327 157 71 328 153 70 329 166 72 330 156 70 331 138 64 332 141 64 333 141 70 334 138 69 335 151 64 336 142 74 337 139 67 338 147 64 339 142 65 340 143 74 341 139 73 342 158 74 343 160 65 344 155 74 345 160 73 346 158 68 347 150 72 348 157 68 349 149 73 350 144 68 351 149 72 352 157 75 353 148 72 354 156 64 355 154 67 356 140 72 357 156 67 358 140 75 359 161 76 360 162 74 361 139 77 362 168 74 363 139 76 364 162 67 365 147 77 366 163 68 367 150 79 368 145 68 369 150 77 370 163 74 371 160 79 372 165 75 373 148 78 374 169 75 375 148 79 376 165 68 377 149 78 378 164 75 379 161 76 380 146 76 381 146 75 382 161 67 383 140 78 384 169 77 385 168 79 386 1194 77 387 168 78 388 169 76 389 1195 80 390 176 82 391 201 81 392 177 82 393 201 80 394 176 85 395 170 81 396 189 87 397 171 89 398 193 87 399 171 81 400 189 82 401 186 89 402 178 87 403 187 88 404 191 88 405 191 87 406 187 86 407 200 88 408 190 85 409 185 80 410 175 85 411 185 88 412 190 86 413 172 80 414 176 90 415 173 83 416 181 80 417 176 81 418 177 90 419 173 89 420 192 90 421 194 81 422 189 90 423 194 89 424 192 84 425 184 88 426 191 84 427 183 89 428 178 84 429 183 88 430 191 91 431 182 88 432 190 80 433 188 83 434 174 88 435 190 83 436 174 91 437 195 92 438 196 90 439 173 93 440 202 90 441 173 92 442 196 83 443 181 93 444 197 90 445 194 95 446 179 95 447 179 90 448 194 84 449 184 95 450 199 84 451 183 94 452 203 94 453 203 84 454 183 91 455 182 94 456 198 83 457 174 92 458 180 83 459 174 94 460 198 91 461 195 94 462 203 93 463 202 95 464 1196 93 465 202 94 466 203 92 467 1197 97 468 205 102 469 215 96 470 204 98 471 206 101 472 208 99 473 207 99 474 207 460 475 216 98 476 206 101 477 211 98 478 218 103 479 209 100 480 210 103 481 209 98 482 218 100 483 217 97 484 214 103 485 213 97 486 214 100 487 217 102 488 212 104 489 219 105 490 221 111 491 230 104 492 219 106 493 220 105 494 221 106 495 223 107 496 224 108 497 222 107 498 224 106 499 223 104 500 231 109 501 226 110 502 1198 107 503 233 108 504 225 107 505 233 110 506 1198 111 507 229 105 508 227 109 509 232 109 510 232 105 511 227 110 512 228 113 513 235 114 514 1199 119 515 245 112 516 234 119 517 245 114 518 1199 114 519 237 113 520 246 117 521 236 117 522 236 113 523 246 115 524 238 116 525 239 117 526 241 115 527 248 116 528 239 118 529 240 117 530 241 119 531 244 118 532 243 116 533 247 118 534 243 119 535 244 112 536 242 121 537 250 126 538 260 120 539 249 122 540 251 124 541 252 123 542 253 123 543 253 461 544 261 122 545 251 124 546 255 122 547 263 127 548 254 125 549 256 127 550 254 122 551 263 125 552 262 121 553 258 127 554 259 121 555 258 125 556 262 126 557 257 128 558 264 129 559 266 135 560 275 128 561 264 130 562 265 129 563 266 130 564 268 131 565 269 132 566 267 131 567 269 130 568 268 128 569 276 133 570 271 134 571 1200 131 572 278 132 573 270 131 574 278 134 575 1200 135 576 274 129 577 272 133 578 277 133 579 277 129 580 272 134 581 273 137 582 280 138 583 1201 143 584 290 136 585 279 143 586 290 138 587 1201 138 588 282 137 589 291 141 590 281 141 591 281 137 592 291 139 593 283 140 594 284 141 595 286 139 596 293 140 597 284 142 598 285 141 599 286 143 600 289 142 601 288 140 602 292 142 603 288 143 604 289 136 605 287 145 606 295 150 607 305 144 608 294 146 609 296 148 610 297 147 611 298 145 612 1208 144 613 306 147 614 298 147 615 298 144 616 306 146 617 296 148 618 300 146 619 308 151 620 299 149 621 301 151 622 299 146 623 308 149 624 307 145 625 303 151 626 304 145 627 303 149 628 307 150 629 302 152 630 309 153 631 311 159 632 320 152 633 309 154 634 310 153 635 311 154 636 313 155 637 314 156 638 312 155 639 314 154 640 313 152 641 321 157 642 316 158 643 1202 155 644 323 156 645 315 155 646 323 158 647 1202 159 648 319 153 649 317 157 650 322 157 651 322 153 652 317 158 653 318 161 654 325 162 655 1203 167 656 335 160 657 324 167 658 335 162 659 1203 162 660 327 161 661 336 165 662 326 165 663 326 161 664 336 163 665 328 164 666 329 165 667 331 163 668 338 164 669 329 166 670 330 165 671 331 167 672 334 166 673 333 164 674 337 166 675 333 167 676 334 160 677 332 171 678 342 168 679 339 170 680 341 168 681 339 171 682 342 169 683 340 175 684 346 174 685 345 172 686 343 175 687 346 172 688 343 173 689 344 172 690 349 169 691 348 173 692 350 169 693 348 172 694 349 168 695 347 174 696 354 175 697 353 171 698 351 171 699 351 170 700 352 174 701 354 179 702 358 176 703 355 178 704 357 176 705 355 179 706 358 177 707 356 183 708 362 182 709 361 180 710 359 183 711 362 180 712 359 181 713 360 180 714 365 177 715 364 181 716 366 177 717 364 180 718 365 176 719 363 182 720 370 183 721 369 179 722 367 179 723 367 178 724 368 182 725 370 187 726 374 184 727 371 186 728 373 184 729 371 187 730 374 185 731 372 191 732 378 190 733 377 188 734 375 191 735 378 188 736 375 189 737 376 188 738 381 185 739 380 189 740 382 185 741 380 188 742 381 184 743 379 190 744 386 191 745 385 187 746 383 187 747 383 186 748 384 190 749 386 197 750 429 198 751 430 194 752 390 198 753 430 197 754 429 196 755 387 199 756 394 195 757 392 193 758 393 195 759 392 199 760 394 192 761 436 192 762 451 196 763 396 195 764 398 195 765 398 196 766 396 197 767 452 193 768 475 195 769 486 197 770 473 193 771 475 197 772 473 194 773 437 193 774 406 194 775 483 199 776 405 199 777 405 194 778 483 198 779 404 192 780 470 199 781 488 198 782 478 192 783 470 198 784 478 196 785 469 204 786 513 201 787 510 202 788 521 204 789 513 202 790 521 203 791 507 205 792 508 207 793 509 206 794 522 207 795 509 205 796 508 200 797 514 200 798 515 205 799 519 202 800 518 200 801 515 202 802 518 201 803 520 200 804 501 204 805 502 207 806 500 204 807 502 200 808 501 201 809 499 206 810 512 207 811 516 204 812 511 206 813 512 204 814 511 203 815 517 205 816 504 206 817 506 203 818 505 205 819 504 203 820 505 202 821 503 212 822 537 209 823 534 210 824 545 212 825 537 210 826 545 211 827 531 213 828 532 215 829 533 214 830 546 215 831 533 213 832 532 208 833 538 210 834 542 208 835 539 213 836 543 208 837 539 210 838 542 209 839 544 208 840 525 212 841 526 215 842 524 212 843 526 208 844 525 209 845 523 215 846 540 211 847 541 214 848 536 211 849 541 215 850 540 212 851 535 213 852 528 214 853 530 211 854 529 213 855 528 211 856 529 210 857 527 221 858 562 217 859 555 223 860 569 221 861 562 223 862 569 216 863 554 218 864 556 219 865 557 222 866 564 219 867 557 218 868 556 220 869 570 220 870 558 218 871 563 223 872 567 220 873 558 223 874 567 217 875 568 219 876 548 220 877 549 217 878 547 219 879 548 217 880 547 221 881 550 222 882 561 219 883 565 221 884 560 222 885 561 221 886 560 216 887 566 218 888 552 222 889 559 216 890 553 218 891 552 216 892 553 223 893 551 461 894 525 123 895 123 121 896 121 461 897 525 121 898 121 120 899 120 460 900 460 99 901 99 97 902 97 460 903 460 97 904 97 96 905 96

+

+

291 906 766 289 907 764 288 908 763 288 909 763 289 910 764 290 911 765 289 912 769 292 913 767 290 914 768 292 915 767 293 916 770 290 917 768 288 918 773 294 919 771 291 920 772 294 921 771 295 922 774 291 923 772 295 924 774 294 925 771 296 926 775 294 927 771 293 928 1204 296 929 775 291 930 778 295 931 776 289 932 777 295 933 776 292 934 779 289 935 777 296 936 781 293 937 782 295 938 780 295 939 780 293 940 782 292 941 783 288 942 787 290 943 786 294 944 784 294 945 784 290 946 786 293 947 785 299 948 790 297 949 788 298 950 789 297 951 788 300 952 791 298 953 789 300 954 794 301 955 792 298 956 793 301 957 792 302 958 795 298 959 793 299 960 798 303 961 796 297 962 797 303 963 796 304 964 799 297 965 797 304 966 799 303 967 796 305 968 800 303 969 796 302 970 1205 305 971 800 297 972 803 304 973 801 301 974 802 297 975 803 301 976 802 300 977 804 305 978 806 302 979 807 304 980 805 304 981 805 302 982 807 301 983 808 299 984 812 298 985 811 303 986 809 303 987 809 298 988 811 302 989 810 333 990 870 331 991 868 330 992 867 330 993 867 331 994 868 332 995 869 331 996 873 334 997 871 332 998 872 334 999 871 335 1000 874 332 1001 872 330 1002 877 336 1003 875 333 1004 876 336 1005 875 337 1006 878 333 1007 876 337 1008 878 336 1009 875 338 1010 879 336 1011 875 335 1012 1206 338 1013 879 333 1014 882 337 1015 880 331 1016 881 337 1017 880 334 1018 883 331 1019 881 338 1020 885 335 1021 886 337 1022 884 337 1023 884 335 1024 886 334 1025 887 330 1026 891 332 1027 890 336 1028 888 336 1029 888 332 1030 890 335 1031 889 342 1032 895 340 1033 893 339 1034 892 339 1035 892 340 1036 893 341 1037 894 344 1038 899 341 1039 897 343 1040 896 343 1041 896 341 1042 897 340 1043 898 342 1044 901 339 1045 902 345 1046 900 342 1047 901 345 1048 900 346 1049 903 345 1050 900 344 1051 1207 346 1052 903 342 1053 906 346 1054 904 340 1055 905 346 1056 904 343 1057 907 340 1058 905 347 1059 909 343 1060 911 346 1061 908 343 1062 911 347 1063 909 344 1064 910 339 1065 915 341 1066 914 345 1067 912 345 1068 912 341 1069 914 344 1070 913

+

227 1071 574 225 1072 572 224 1073 571 226 1074 573 224 1075 571 225 1076 572 228 1077 576 225 1078 575 227 1079 578 225 1080 575 228 1081 576 229 1082 577 230 1083 579 226 1084 580 225 1085 581 230 1086 579 225 1087 581 229 1088 582 230 1089 583 231 1090 584 226 1091 585 231 1092 584 224 1093 586 226 1094 585 224 1095 587 231 1096 588 228 1097 589 224 1098 587 228 1099 589 227 1100 590 229 1101 594 228 1102 592 230 1103 591 231 1104 593 230 1105 591 228 1106 592 235 1107 598 233 1108 596 232 1109 595 234 1110 597 232 1111 595 233 1112 596 236 1113 600 233 1114 599 235 1115 602 233 1116 599 236 1117 600 237 1118 601 238 1119 603 234 1120 604 233 1121 605 238 1122 603 233 1123 605 237 1124 606 238 1125 607 239 1126 608 234 1127 609 239 1128 608 232 1129 610 234 1130 609 232 1131 611 239 1132 612 236 1133 613 232 1134 611 236 1135 613 235 1136 614 237 1137 618 236 1138 616 238 1139 615 239 1140 617 238 1141 615 236 1142 616 243 1143 622 241 1144 620 240 1145 619 242 1146 621 240 1147 619 241 1148 620 244 1149 624 241 1150 623 243 1151 626 241 1152 623 244 1153 624 245 1154 625 246 1155 627 242 1156 628 241 1157 629 246 1158 627 241 1159 629 245 1160 630 246 1161 631 247 1162 632 242 1163 633 247 1164 632 240 1165 634 242 1166 633 240 1167 635 247 1168 636 244 1169 637 240 1170 635 244 1171 637 243 1172 638 247 1173 639 246 1174 642 245 1175 640 247 1176 639 245 1177 640 244 1178 641 251 1179 646 249 1180 644 248 1181 643 250 1182 645 248 1183 643 249 1184 644 252 1185 648 249 1186 647 251 1187 650 249 1188 647 252 1189 648 253 1190 649 249 1191 653 254 1192 651 250 1193 652 254 1194 651 249 1195 653 253 1196 654 250 1197 657 254 1198 655 255 1199 656 250 1200 657 255 1201 656 248 1202 658 248 1203 659 255 1204 660 252 1205 661 248 1206 659 252 1207 661 251 1208 662 253 1209 666 252 1210 664 254 1211 663 255 1212 665 254 1213 663 252 1214 664 259 1215 670 257 1216 668 256 1217 667 258 1218 669 256 1219 667 257 1220 668 261 1221 673 257 1222 671 260 1223 672 257 1224 671 259 1225 674 260 1226 672 262 1227 675 258 1228 676 257 1229 677 262 1230 675 257 1231 677 261 1232 678 256 1233 682 258 1234 681 263 1235 680 263 1236 680 258 1237 681 262 1238 679 256 1239 683 263 1240 684 260 1241 685 256 1242 683 260 1243 685 259 1244 686 261 1245 690 260 1246 688 262 1247 687 263 1248 689 262 1249 687 260 1250 688 267 1251 694 265 1252 692 264 1253 691 266 1254 693 264 1255 691 265 1256 692 268 1257 696 265 1258 695 267 1259 698 265 1260 695 268 1261 696 269 1262 697 265 1263 701 270 1264 699 266 1265 700 270 1266 699 265 1267 701 269 1268 702 266 1269 705 270 1270 703 271 1271 704 266 1272 705 271 1273 704 264 1274 706 264 1275 707 271 1276 708 268 1277 709 264 1278 707 268 1279 709 267 1280 710 269 1281 714 268 1282 712 270 1283 711 271 1284 713 270 1285 711 268 1286 712 275 1287 718 273 1288 716 272 1289 715 274 1290 717 272 1291 715 273 1292 716 276 1293 720 277 1294 721 273 1295 719 276 1296 720 273 1297 719 275 1298 722 273 1299 725 278 1300 723 274 1301 724 278 1302 723 273 1303 725 277 1304 726 274 1305 729 279 1306 728 272 1307 730 279 1308 728 274 1309 729 278 1310 727 272 1311 731 279 1312 732 276 1313 733 272 1314 731 276 1315 733 275 1316 734 277 1317 738 276 1318 736 278 1319 735 279 1320 737 278 1321 735 276 1322 736 283 1323 742 282 1324 741 280 1325 739 282 1326 741 283 1327 742 281 1328 740 284 1329 744 285 1330 745 281 1331 743 281 1332 743 283 1333 746 284 1334 744 286 1335 747 282 1336 748 281 1337 749 286 1338 747 281 1339 749 285 1340 750 282 1341 753 287 1342 752 280 1343 754 287 1344 752 282 1345 753 286 1346 751 280 1347 755 287 1348 756 284 1349 757 280 1350 755 284 1351 757 283 1352 758 285 1353 760 287 1354 759 286 1355 762 287 1356 759 285 1357 760 284 1358 761 351 1359 919 349 1360 917 348 1361 916 350 1362 918 348 1363 916 349 1364 917 352 1365 921 353 1366 922 349 1367 920 352 1368 921 349 1369 920 351 1370 923 354 1371 924 350 1372 925 349 1373 926 354 1374 924 349 1375 926 353 1376 927 350 1377 930 355 1378 929 348 1379 931 355 1380 929 350 1381 930 354 1382 928 348 1383 932 355 1384 933 352 1385 934 348 1386 932 352 1387 934 351 1388 935 353 1389 939 355 1390 938 354 1391 936 355 1392 938 353 1393 939 352 1394 937 359 1395 943 357 1396 941 356 1397 940 358 1398 942 356 1399 940 357 1400 941 360 1401 945 361 1402 946 357 1403 944 360 1404 945 357 1405 944 359 1406 947 362 1407 948 358 1408 949 357 1409 950 362 1410 948 357 1411 950 361 1412 951 358 1413 954 363 1414 953 356 1415 955 363 1416 953 358 1417 954 362 1418 952 356 1419 956 363 1420 957 360 1421 958 356 1422 956 360 1423 958 359 1424 959 363 1425 960 362 1426 963 361 1427 961 363 1428 960 361 1429 961 360 1430 962 423 1431 1093 421 1432 1091 420 1433 1090 422 1434 1092 420 1435 1090 421 1436 1091 424 1437 1095 425 1438 1096 421 1439 1094 424 1440 1095 421 1441 1094 423 1442 1097 426 1443 1098 422 1444 1099 421 1445 1100 426 1446 1098 421 1447 1100 425 1448 1101 422 1449 1104 427 1450 1103 420 1451 1105 427 1452 1103 422 1453 1104 426 1454 1102 420 1455 1106 427 1456 1107 424 1457 1108 420 1458 1106 424 1459 1108 423 1460 1109 425 1461 1113 427 1462 1112 426 1463 1110 427 1464 1112 425 1465 1113 424 1466 1111

+

309 1467 816 307 1468 814 306 1469 813 306 1470 813 307 1471 814 308 1472 815 312 1473 819 310 1474 817 311 1475 818 310 1476 817 313 1477 820 311 1478 818 311 1479 818 313 1480 820 309 1481 821 311 1482 818 309 1483 821 306 1484 822 312 1485 819 311 1486 818 306 1487 823 312 1488 819 306 1489 823 308 1490 824 308 1491 826 307 1492 825 312 1493 819 310 1494 817 312 1495 819 307 1496 825 307 1497 830 309 1498 828 310 1499 827 313 1500 829 310 1501 827 309 1502 828 317 1503 834 315 1504 832 314 1505 831 314 1506 831 315 1507 832 316 1508 833 320 1509 837 318 1510 835 319 1511 836 318 1512 835 321 1513 838 319 1514 836 319 1515 836 321 1516 838 317 1517 839 319 1518 836 317 1519 839 314 1520 840 320 1521 837 319 1522 836 314 1523 841 320 1524 837 314 1525 841 316 1526 842 316 1527 844 315 1528 843 320 1529 837 318 1530 835 320 1531 837 315 1532 843 315 1533 848 317 1534 846 318 1535 845 321 1536 847 318 1537 845 317 1538 846 325 1539 852 323 1540 850 322 1541 849 322 1542 849 323 1543 850 324 1544 851 328 1545 855 326 1546 853 327 1547 854 326 1548 853 329 1549 856 327 1550 854 327 1551 854 329 1552 856 325 1553 857 327 1554 854 325 1555 857 322 1556 858 328 1557 855 327 1558 854 322 1559 859 328 1560 855 322 1561 859 324 1562 860 326 1563 853 328 1564 855 324 1565 861 326 1566 853 324 1567 861 323 1568 862 329 1569 863 326 1570 864 323 1571 865 329 1572 863 323 1573 865 325 1574 866 367 1575 967 365 1576 965 364 1577 964 364 1578 964 365 1579 965 366 1580 966 370 1581 970 368 1582 968 369 1583 969 368 1584 968 371 1585 971 369 1586 969 369 1587 969 371 1588 971 367 1589 972 369 1590 969 367 1591 972 364 1592 973 370 1593 970 369 1594 969 364 1595 974 370 1596 970 364 1597 974 366 1598 975 366 1599 977 365 1600 976 370 1601 970 368 1602 968 370 1603 970 365 1604 976 365 1605 981 367 1606 979 368 1607 978 371 1608 980 368 1609 978 367 1610 979 375 1611 985 373 1612 983 372 1613 982 372 1614 982 373 1615 983 374 1616 984 378 1617 988 376 1618 986 377 1619 987 376 1620 986 379 1621 989 377 1622 987 375 1623 990 377 1624 987 379 1625 989 377 1626 987 375 1627 990 372 1628 991 378 1629 988 377 1630 987 372 1631 992 378 1632 988 372 1633 992 374 1634 993 374 1635 995 373 1636 994 378 1637 988 376 1638 986 378 1639 988 373 1640 994 373 1641 999 375 1642 997 376 1643 996 379 1644 998 376 1645 996 375 1646 997 383 1647 1003 381 1648 1001 380 1649 1000 380 1650 1000 381 1651 1001 382 1652 1002 386 1653 1006 384 1654 1004 385 1655 1005 384 1656 1004 387 1657 1007 385 1658 1005 383 1659 1008 385 1660 1005 387 1661 1007 385 1662 1005 383 1663 1008 380 1664 1009 386 1665 1006 385 1666 1005 380 1667 1010 386 1668 1006 380 1669 1010 382 1670 1011 384 1671 1004 386 1672 1006 382 1673 1012 384 1674 1004 382 1675 1012 381 1676 1013 387 1677 1014 384 1678 1015 381 1679 1016 387 1680 1014 381 1681 1016 383 1682 1017 389 1683 1019 388 1684 1018 391 1685 1021 388 1686 1018 389 1687 1019 390 1688 1020 393 1689 1023 394 1690 1024 392 1691 1022 392 1692 1022 395 1693 1025 393 1694 1023 391 1695 1027 388 1696 1026 395 1697 1025 393 1698 1023 395 1699 1025 388 1700 1026 394 1701 1024 393 1702 1023 388 1703 1028 394 1704 1024 388 1705 1028 390 1706 1029 392 1707 1022 394 1708 1024 390 1709 1030 392 1710 1022 390 1711 1030 389 1712 1031 395 1713 1032 392 1714 1033 389 1715 1034 395 1716 1032 389 1717 1034 391 1718 1035 397 1719 1037 396 1720 1036 399 1721 1039 396 1722 1036 397 1723 1037 398 1724 1038 401 1725 1041 402 1726 1042 400 1727 1040 400 1728 1040 403 1729 1043 401 1730 1041 401 1731 1041 403 1732 1043 399 1733 1044 401 1734 1041 399 1735 1044 396 1736 1045 402 1737 1042 401 1738 1041 396 1739 1046 402 1740 1042 396 1741 1046 398 1742 1047 398 1743 1048 400 1744 1040 402 1745 1042 400 1746 1040 398 1747 1048 397 1748 1049 403 1749 1050 400 1750 1051 397 1751 1052 403 1752 1050 397 1753 1052 399 1754 1053 407 1755 1057 405 1756 1055 404 1757 1054 404 1758 1054 405 1759 1055 406 1760 1056 410 1761 1060 408 1762 1058 409 1763 1059 408 1764 1058 411 1765 1061 409 1766 1059 409 1767 1059 411 1768 1061 407 1769 1062 409 1770 1059 407 1771 1062 404 1772 1063 410 1773 1060 409 1774 1059 404 1775 1064 410 1776 1060 404 1777 1064 406 1778 1065 406 1779 1067 405 1780 1066 410 1781 1060 408 1782 1058 410 1783 1060 405 1784 1066 405 1785 1071 407 1786 1069 408 1787 1068 411 1788 1070 408 1789 1068 407 1790 1069 415 1791 1075 413 1792 1073 412 1793 1072 412 1794 1072 413 1795 1073 414 1796 1074 418 1797 1078 416 1798 1076 417 1799 1077 416 1800 1076 419 1801 1079 417 1802 1077 415 1803 1080 417 1804 1077 419 1805 1079 417 1806 1077 415 1807 1080 412 1808 1081 418 1809 1078 417 1810 1077 412 1811 1082 418 1812 1078 412 1813 1082 414 1814 1083 414 1815 1085 413 1816 1084 418 1817 1078 416 1818 1076 418 1819 1078 413 1820 1084 413 1821 1089 415 1822 1087 416 1823 1086 419 1824 1088 416 1825 1086 415 1826 1087 430 1827 1116 428 1828 1114 429 1829 1115 428 1830 1114 431 1831 1117 429 1832 1115 433 1833 1119 432 1834 1118 435 1835 1121 432 1836 1118 433 1837 1119 434 1838 1120 433 1839 1119 435 1840 1121 431 1841 1122 433 1842 1119 431 1843 1122 428 1844 1123 433 1845 1119 430 1846 1125 434 1847 1120 430 1848 1125 433 1849 1119 428 1850 1124 430 1851 1127 432 1852 1118 434 1853 1120 432 1854 1118 430 1855 1127 429 1856 1126 429 1857 1131 431 1858 1129 432 1859 1128 435 1860 1130 432 1861 1128 431 1862 1129 438 1863 1134 436 1864 1132 437 1865 1133 436 1866 1132 439 1867 1135 437 1868 1133 441 1869 1137 440 1870 1136 443 1871 1139 440 1872 1136 441 1873 1137 442 1874 1138 441 1875 1137 443 1876 1139 439 1877 1140 441 1878 1137 439 1879 1140 436 1880 1141 442 1881 1138 441 1882 1137 436 1883 1142 442 1884 1138 436 1885 1142 438 1886 1143 438 1887 1145 437 1888 1144 442 1889 1138 440 1890 1136 442 1891 1138 437 1892 1144 437 1893 1149 439 1894 1147 440 1895 1146 443 1896 1148 440 1897 1146 439 1898 1147 446 1899 1152 444 1900 1150 445 1901 1151 444 1902 1150 447 1903 1153 445 1904 1151 449 1905 1155 448 1906 1154 451 1907 1157 448 1908 1154 449 1909 1155 450 1910 1156 449 1911 1155 451 1912 1157 447 1913 1158 449 1914 1155 447 1915 1158 444 1916 1159 450 1917 1156 449 1918 1155 444 1919 1160 450 1920 1156 444 1921 1160 446 1922 1161 448 1923 1154 450 1924 1156 446 1925 1162 448 1926 1154 446 1927 1162 445 1928 1163 451 1929 1164 448 1930 1165 445 1931 1166 451 1932 1164 445 1933 1166 447 1934 1167 454 1935 1170 452 1936 1168 453 1937 1169 452 1938 1168 455 1939 1171 453 1940 1169 457 1941 1173 456 1942 1172 459 1943 1175 456 1944 1172 457 1945 1173 458 1946 1174 457 1947 1173 459 1948 1175 455 1949 1176 457 1950 1173 455 1951 1176 452 1952 1177 458 1953 1174 457 1954 1173 452 1955 1178 458 1956 1174 452 1957 1178 454 1958 1179 456 1959 1172 458 1960 1174 454 1961 1180 456 1962 1172 454 1963 1180 453 1964 1181 453 1965 1185 455 1966 1183 456 1967 1182 459 1968 1184 456 1969 1182 455 1970 1183

+
+
+
+ + + + + + + + + 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.0000001.000000 + 30.0000000.0000003.333333 + + + + + +
diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfD_01/model.config b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfD_01/model.config new file mode 100755 index 0000000..c91fbb1 --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfD_01/model.config @@ -0,0 +1,11 @@ + + + aws_robomaker_warehouse_ShelfD_01 + 1.0 + model.sdf + + + + + + diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfD_01/model.sdf b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfD_01/model.sdf new file mode 100755 index 0000000..17c326e --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfD_01/model.sdf @@ -0,0 +1,46 @@ + + + + + + 30 + + 907.144 + 0 + 0 + 104.950 + 0 + 824.248 + + + + + + model://aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + model://aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_visual.DAE + + + 1 + + +1 + + diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfE_01/.DS_Store b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfE_01/.DS_Store new file mode 100755 index 0000000..e0c25bd Binary files /dev/null and b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfE_01/.DS_Store differ diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfE_01/materials/.DS_Store b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfE_01/materials/.DS_Store new file mode 100755 index 0000000..616b3e2 Binary files /dev/null and b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfE_01/materials/.DS_Store differ diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfE_01/materials/textures/aws_robomaker_warehouse_ShelfE_01.png b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfE_01/materials/textures/aws_robomaker_warehouse_ShelfE_01.png new file mode 100755 index 0000000..d33ba54 Binary files /dev/null and b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfE_01/materials/textures/aws_robomaker_warehouse_ShelfE_01.png differ diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfE_01/materials/textures/aws_robomaker_warehouse_ShelfE_02.png b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfE_01/materials/textures/aws_robomaker_warehouse_ShelfE_02.png new file mode 100755 index 0000000..b28b289 Binary files /dev/null and b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfE_01/materials/textures/aws_robomaker_warehouse_ShelfE_02.png differ diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfE_01/materials/textures/aws_robomaker_warehouse_ShelfE_03.png b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfE_01/materials/textures/aws_robomaker_warehouse_ShelfE_03.png new file mode 100755 index 0000000..4b7e610 Binary files /dev/null and b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfE_01/materials/textures/aws_robomaker_warehouse_ShelfE_03.png differ diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfE_01/materials/textures/aws_robomaker_warehouse_ShelfE_04.png b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfE_01/materials/textures/aws_robomaker_warehouse_ShelfE_04.png new file mode 100755 index 0000000..e76fcdd Binary files /dev/null and b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfE_01/materials/textures/aws_robomaker_warehouse_ShelfE_04.png differ diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_collision.DAE b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_collision.DAE new file mode 100755 index 0000000..5922d31 --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_collision.DAE @@ -0,0 +1,327 @@ + + + FBX COLLADA exporter2019-05-15T10:11:35Z2019-05-15T10:11:35ZZ_UP + + + + + +-45.044750 -57.560341 195.803909 +42.866188 -57.560341 195.803955 +-45.044750 133.195770 195.803955 +42.866188 133.195770 195.803986 +-45.044781 -57.560341 -195.804031 +42.866158 -57.560341 -195.804001 +-45.044781 133.195770 -195.803986 +42.866158 133.195770 -195.803970 +-44.361427 -128.142014 1.402283 +42.927315 -128.142014 1.402374 +-44.361427 133.195755 1.402374 +42.927315 133.195755 1.402420 +-44.361412 -128.141998 -4.198639 +42.927338 -128.141998 -4.198563 +-44.361412 133.195786 -4.198517 +42.927338 133.195786 -4.198456 +-44.361458 -128.142029 -190.318237 +42.927284 -128.142029 -190.318130 +42.927284 133.195740 -190.318039 +-44.361458 133.195740 -190.318130 +-44.361443 -128.142014 -195.919159 +-44.361443 133.195770 -195.919022 +42.927307 133.195770 -195.918884 +42.927307 -128.142014 -195.919037 +-44.361401 -128.141998 195.912140 +42.927341 -128.141998 195.912231 +-44.361401 133.195770 195.912231 +42.927341 133.195770 195.912277 +-44.361378 -128.141983 190.311218 +42.927372 -128.141983 190.311295 +-44.361378 133.195801 190.311340 +42.927372 133.195801 190.311401 + + + + + + + + + + + +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +1.000000 -0.000000 0.000004 +1.000000 -0.000000 0.000004 +1.000000 -0.000000 0.000004 +1.000000 -0.000000 0.000004 +1.000000 -0.000000 0.000004 +1.000000 -0.000000 0.000004 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-1.000000 0.000000 -0.000003 +-1.000000 0.000000 -0.000003 +-1.000000 0.000000 -0.000003 +-1.000000 0.000000 -0.000003 +-1.000000 0.000000 -0.000003 +-1.000000 0.000000 -0.000003 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +0.000001 0.000001 -1.000000 +0.000001 0.000001 -1.000000 +0.000001 0.000001 -1.000000 +0.000001 0.000001 -1.000000 +0.000001 0.000001 -1.000000 +0.000001 0.000001 -1.000000 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +1.000000 -0.000000 0.000004 +1.000000 -0.000000 0.000004 +1.000000 -0.000000 0.000004 +1.000000 -0.000000 0.000004 +1.000000 -0.000000 0.000004 +1.000000 -0.000000 0.000004 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-1.000000 0.000000 -0.000003 +-1.000000 0.000000 -0.000003 +-1.000000 0.000000 -0.000003 +-1.000000 0.000000 -0.000003 +-1.000000 0.000000 -0.000003 +-1.000000 0.000000 -0.000003 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +1.000000 -0.000000 0.000005 +1.000000 -0.000000 0.000005 +1.000000 -0.000000 0.000005 +1.000000 -0.000000 0.000005 +1.000000 -0.000000 0.000005 +1.000000 -0.000000 0.000005 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-1.000000 0.000000 -0.000004 +-1.000000 0.000000 -0.000004 +-1.000000 0.000000 -0.000004 +-1.000000 0.000000 -0.000004 +-1.000000 0.000000 -0.000004 +-1.000000 0.000000 -0.000004 + + + + + + + + + + + +1.000000 0.000000 +0.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +1.000000 0.000000 +0.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +1.000000 0.000000 +0.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +1.000000 0.000000 +0.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +1.000000 0.000000 +0.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +1.000000 0.000000 +0.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +1.000000 0.000000 +0.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +1.000000 0.000000 +1.000000 0.000000 +0.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 + + + + + + + + + + + +

2 0 2 0 1 0 3 2 3 3 3 3 0 4 0 1 5 1 7 6 7 5 7 5 4 8 4 4 9 4 6 10 6 7 11 7 5 12 11 1 13 9 0 14 8 0 15 8 4 16 10 5 17 11 7 18 15 3 19 13 1 20 12 1 21 12 5 22 14 7 23 15 2 24 17 7 25 18 6 26 19 7 27 18 2 28 17 3 29 16 0 30 21 6 31 22 4 32 23 6 33 22 0 34 21 2 35 20 10 36 26 8 37 24 11 38 27 11 39 27 8 40 24 9 41 25 15 42 31 13 43 29 12 44 28 12 45 28 14 46 30 15 47 31 12 48 34 9 49 33 8 50 32 9 51 33 12 52 34 13 53 35 13 54 38 11 55 37 9 56 36 11 57 37 13 58 38 15 59 39 15 60 42 14 61 43 11 62 40 10 63 41 11 64 40 14 65 43 14 66 46 12 67 47 10 68 44 8 69 45 10 70 44 12 71 47 19 72 51 16 73 48 18 74 50 18 75 50 16 76 48 17 77 49 22 78 54 23 79 55 20 80 52 20 81 52 21 82 53 22 83 54 20 84 57 17 85 59 16 86 56 17 87 59 20 88 57 23 89 58 23 90 61 18 91 63 17 92 60 18 93 63 23 94 61 22 95 62 22 96 65 21 97 66 18 98 64 19 99 67 18 100 64 21 101 66 21 102 69 20 103 70 19 104 68 16 105 71 19 106 68 20 107 70 26 108 74 24 109 72 27 110 75 27 111 75 24 112 72 25 113 73 31 114 79 29 115 77 28 116 76 28 117 76 30 118 78 31 119 79 28 120 82 25 121 81 24 122 80 25 123 81 28 124 82 29 125 83 29 126 86 27 127 85 25 128 84 27 129 85 29 130 86 31 131 87 31 132 90 30 133 91 27 134 88 26 135 89 27 136 88 30 137 91 30 138 94 28 139 95 26 140 92 24 141 93 26 142 92 28 143 95

+
+
+
+ + + -0.000000 -0.000000 -1.000000 0.000000 -1.000000 0.000000 0.000000 -1.072197 0.000000 1.000000 -0.000000 131.071121 0.000000 0.000000 0.000000 1.0000001.000000 + 30.0000000.0000003.333333 + + + + + +
diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_visual.DAE b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_visual.DAE new file mode 100755 index 0000000..2caad6b --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_visual.DAE @@ -0,0 +1,3689 @@ + + + FBX COLLADA exporter2019-05-27T02:53:28Z2019-05-27T02:53:28ZZ_UP + + + ../materials/textures/aws_robomaker_warehouse_ShelfE_01.png + + + ../materials/textures/aws_robomaker_warehouse_ShelfE_03.png + + + ../materials/textures/aws_robomaker_warehouse_ShelfE_02.png + + + ../materials/textures/aws_robomaker_warehouse_ShelfE_03.png + + + + + + + + + + + + + + + + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + 0.800000 0.800000 0.800000 1.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + +-195.859360 -43.970364 11.286113 +-190.346848 -43.970360 11.286113 +-195.851028 -40.870396 -0.039542 +-195.851028 -43.964931 -0.039542 +-190.355179 -40.870392 -0.039542 +-190.355179 -43.964924 -0.039542 +-195.859344 -40.864964 11.286113 +-190.346863 -40.864960 11.286113 +-195.359573 -41.130783 11.389088 +-195.359573 -43.704540 11.389088 +-190.846634 -41.130779 11.389088 +-190.846634 -43.704540 11.389087 +-195.337234 -41.142639 261.250977 +-195.337234 -43.692688 261.250977 +-190.868851 -41.142639 261.250977 +-190.868851 -43.692688 261.250977 +190.346771 40.164623 11.286113 +195.859314 40.164623 11.286113 +190.355118 43.264595 -0.039542 +190.355118 40.170063 -0.039542 +195.850967 43.264603 -0.039542 +195.850967 40.170067 -0.039542 +190.346802 43.270035 11.286113 +195.859314 43.270039 11.286113 +190.846542 43.004223 11.389088 +190.846558 40.430458 11.389088 +195.359558 43.004227 11.389088 +195.359573 40.430462 11.389087 +190.868851 42.992374 261.250977 +190.868851 40.442318 261.250977 +195.337234 42.992374 261.250977 +195.337219 40.442322 261.250977 +-195.859360 40.164501 11.286113 +-190.346848 40.164501 11.286113 +-195.851028 43.264473 -0.039542 +-195.851028 40.169941 -0.039542 +-190.355179 43.264481 -0.039542 +-190.355179 40.169945 -0.039542 +-195.859344 43.269913 11.286113 +-190.346863 43.269917 11.286113 +-195.359573 43.004101 11.389088 +-195.359573 40.430336 11.389088 +-190.846634 43.004105 11.389088 +-190.846634 40.430340 11.389087 +-195.337234 42.992252 261.250977 +-195.337234 40.442196 261.250977 +-190.868851 42.992252 261.250977 +-190.868851 40.442200 261.250977 +-1.349450 40.164562 11.286113 +4.163049 40.164562 11.286113 +-1.341129 43.264534 -0.039542 +-1.341129 40.170002 -0.039542 +4.154719 43.264542 -0.039542 +4.154719 40.170006 -0.039542 +-1.349450 43.269974 11.286113 +4.163049 43.269978 11.286113 +-0.849689 43.004162 11.389088 +-0.849689 40.430397 11.389088 +3.663298 43.004166 11.389088 +3.663298 40.430401 11.389087 +-0.827415 42.992313 261.250977 +-0.827372 40.442257 261.250977 +3.640989 42.992317 261.250977 +3.641029 40.442265 261.250977 +-1.349419 -43.970303 11.286113 +4.163079 -43.970299 11.286113 +-1.341098 -40.870335 -0.039542 +-1.341098 -43.964870 -0.039542 +4.154749 -40.870331 -0.039542 +4.154749 -43.964863 -0.039542 +-1.349419 -40.864902 11.286113 +4.163079 -40.864899 11.286113 +-0.849659 -41.130722 11.389088 +-0.849659 -43.704479 11.389088 +3.663328 -41.130718 11.389088 +3.663328 -43.704479 11.389087 +-0.827342 -41.142574 261.250977 +-0.827328 -43.692627 261.250977 +3.641059 -41.142570 261.250977 +3.641079 -43.692627 261.250977 +190.346817 -43.970242 11.286113 +195.859329 -43.970238 11.286113 +190.355164 -40.870274 -0.039542 +190.355164 -43.964809 -0.039542 +195.850998 -40.870270 -0.039542 +195.850998 -43.964802 -0.039542 +190.346817 -40.864841 11.286113 +195.859329 -40.864838 11.286113 +190.846588 -41.130661 11.389088 +190.846588 -43.704418 11.389088 +195.359573 -41.130657 11.389088 +195.359573 -43.704418 11.389087 +190.868866 -41.142517 261.250977 +190.868881 -43.692566 261.250977 +195.337250 -41.142517 261.250977 +195.337265 -43.692566 261.250977 +-195.319946 -41.125313 13.878565 +-195.319916 40.434727 66.278061 +-190.886261 -41.125309 13.878560 +-195.319916 40.434727 70.460434 +-190.886246 -41.125320 9.696195 +-190.886246 40.434731 70.460434 +-195.319946 -41.125324 9.696195 +-190.886261 40.434731 66.278061 +-195.319992 -41.186462 144.465973 +-195.320007 40.434692 195.103180 +-195.320007 40.434704 199.280792 +-190.886292 -41.186459 144.465958 +-190.886322 40.434708 199.280792 +-190.886292 -41.186459 141.219635 +-190.886322 40.434696 195.103180 +-195.320007 -41.186462 141.219635 +-195.319946 -41.125320 134.569077 +-195.319916 40.434727 77.097397 +-195.319946 -41.125313 130.386719 +-190.886246 40.434731 77.097397 +-190.886261 40.434731 81.279785 +-190.886261 -41.125309 130.386734 +-190.886246 -41.125313 134.569077 +-195.319916 40.434727 81.279785 +190.824371 -41.125099 13.878565 +190.824371 40.434959 66.278061 +195.258072 -41.125080 13.878560 +190.824371 40.434959 70.460434 +195.258057 40.434978 70.460434 +195.258072 -41.125092 9.696197 +190.824371 -41.125111 9.696197 +195.258057 40.434978 66.278061 +190.824402 -41.186249 144.465973 +190.824356 40.434921 195.103180 +190.824341 40.434937 199.280792 +195.258087 -41.186234 144.465958 +195.258057 40.434948 199.280792 +195.258102 -41.186234 141.219635 +195.258057 40.434937 195.103180 +190.824402 -41.186249 141.219635 +190.824387 -41.125107 134.569061 +190.824402 40.434959 77.097397 +190.824387 -41.125099 130.386719 +195.258072 40.434978 77.097397 +195.258072 40.434978 81.279762 +195.258087 -41.125080 130.386719 +195.258087 -41.125088 134.569061 +190.824402 40.434959 81.279762 +-1.008084 -41.125114 13.878565 +-1.008087 40.434952 66.278061 +3.425621 -41.125095 13.878560 +-1.008087 40.434952 70.460434 +3.425587 40.434975 70.460434 +3.425621 -41.125103 9.696197 +-1.008084 -41.125122 9.696197 +3.425587 40.434975 66.278061 +-1.008060 -41.186264 144.465973 +-1.008118 40.434917 195.103180 +-1.008118 40.434925 199.280792 +3.425625 -41.186237 144.465958 +3.425590 40.434948 199.280792 +3.425625 -41.186237 141.219635 +3.425591 40.434937 195.103180 +-1.008060 -41.186264 141.219635 +-1.008083 -41.125118 134.569061 +-1.008064 40.434952 77.097397 +-1.008083 -41.125114 130.386719 +3.425602 40.434975 77.097397 +3.425602 40.434975 81.279762 +3.425617 -41.125095 130.386719 +3.425617 -41.125099 134.569061 +-1.008064 40.434952 81.279762 +190.734039 -41.267357 256.299133 +190.734024 41.439137 256.299133 +190.734039 -41.267357 259.323669 +190.734024 41.439137 259.323669 +195.278412 -41.267353 256.299133 +195.278397 41.439140 256.299133 +195.278412 -41.267353 259.323669 +195.278397 41.439140 259.323669 +-0.895264 -41.267330 256.299133 +-0.895294 41.439167 256.299133 +-0.895264 -41.267330 259.323669 +-0.895294 41.439167 259.323669 +3.649109 -41.267326 256.299133 +3.649078 41.439171 256.299133 +3.649109 -41.267326 259.323669 +3.649078 41.439171 259.323669 +-195.473846 -41.267296 256.299133 +-195.473846 41.439198 256.299133 +-195.473846 -41.267296 259.323669 +-195.473846 41.439198 259.323669 +-190.929474 -41.267292 256.299133 +-190.929474 41.439201 256.299133 +-190.929474 -41.267292 259.323669 +-190.929474 41.439201 259.323669 +-192.401459 38.361286 242.060989 +193.412613 38.361374 242.060989 +-192.401459 43.984394 236.176102 +-192.401459 38.361290 236.176102 +193.412598 43.984470 236.176102 +193.412613 38.361374 236.176102 +-192.401459 43.984390 242.060989 +193.412628 43.984474 242.060989 +-192.401535 -42.179398 140.859955 +193.412781 -42.179111 140.859970 +-192.401535 41.115921 134.975082 +-192.401505 -42.179394 134.975082 +193.412735 41.116199 134.975098 +193.412781 -42.179108 134.975098 +-192.401535 41.115921 140.859955 +193.412735 41.116199 140.859955 +-192.401535 -42.179398 76.744461 +193.412781 -42.179111 76.744469 +-192.401535 41.115921 70.859589 +-192.401505 -42.179394 70.859589 +193.412735 41.116199 70.859596 +193.412781 -42.179108 70.859596 +-192.401535 41.115921 76.744453 +193.412735 41.116199 76.744476 +-192.401535 41.115921 196.922226 +193.412735 41.116207 196.922226 +-192.401535 -42.179398 196.922226 +-192.401535 -42.179394 202.807083 +193.412781 -42.179111 196.922226 +193.412781 -42.179111 202.807083 +193.412735 41.116207 202.807083 +-192.401535 41.115925 202.807083 +-100.515869 25.034658 96.767853 +-178.499268 25.176374 76.381248 +-178.499268 25.176497 96.767883 +-100.515869 25.034658 76.381271 +-100.603271 -22.747515 76.381271 +-178.586060 -22.605913 76.381248 +-178.586060 -22.605837 96.767883 +-100.603271 -22.747606 96.767868 +-10.756012 25.034658 96.767853 +-88.739410 25.176374 76.381248 +-88.739410 25.176497 96.767883 +-10.756012 25.034658 76.381271 +-10.843414 -22.747515 76.381271 +-88.826202 -22.605913 76.381248 +-88.826202 -22.605837 96.767883 +-10.843414 -22.747606 96.767868 +-136.529434 -37.821102 161.109482 +-136.387711 40.162300 140.722885 +-136.387589 40.162300 161.109512 +-136.529434 -37.821102 140.722916 +-184.311539 -37.733696 140.722916 +-184.169937 40.249088 140.722885 +-184.169937 40.249088 161.109512 +-184.311661 -37.733696 161.109512 +72.596710 29.278488 123.836227 +72.890900 -25.122681 76.618340 +72.596710 29.278488 76.618340 +72.890900 -25.122711 123.836227 +8.309597 -25.279179 76.618340 +8.015530 29.122051 76.618340 +9.438137 29.125500 123.836227 +8.309963 -25.279179 123.836227 +8.016140 29.122051 123.836227 +189.951172 -36.224636 75.382462 +137.447266 39.841038 75.382462 +189.951172 39.841278 75.382446 +137.447266 -36.224880 75.382469 +137.447266 39.841038 82.989067 +189.951172 -36.224636 82.989067 +189.951172 39.841278 82.989052 +137.447266 -36.224880 82.989075 +189.951172 -36.224636 83.132347 +137.447266 39.841038 83.132355 +189.951172 39.841278 83.132332 +137.447266 -36.224880 83.132370 +137.447266 39.841038 90.738976 +189.951172 -36.224636 90.738960 +189.951172 39.841278 90.738960 +137.447266 -36.224880 90.738976 +-112.536499 29.278488 250.422791 +-112.242310 -25.122681 203.204910 +-112.536499 29.278488 203.204910 +-112.242310 -25.122711 250.422791 +-176.823608 -25.279179 203.204910 +-177.117676 29.122051 203.204910 +-175.695068 29.125500 250.422791 +-176.823242 -25.279179 250.422791 +-177.117065 29.122051 250.422791 +95.399185 25.034658 161.436584 +17.415787 25.176378 141.049973 +17.415787 25.176500 161.436615 +95.399185 25.034658 141.049988 +95.311783 -22.747515 141.049988 +17.328995 -22.605909 141.049973 +17.328995 -22.605833 161.436615 +95.311783 -22.747606 161.436584 +95.399185 25.034658 182.055481 +17.415787 25.176382 161.668884 +17.415787 25.176504 182.055511 +95.399185 25.034658 161.668884 +95.311783 -22.747519 161.668884 +17.328995 -22.605909 161.668884 +17.328995 -22.605833 182.055511 +95.311783 -22.747610 182.055481 +82.850586 25.034658 222.664795 +4.867188 25.176378 202.278183 +4.867188 25.176500 222.664825 +82.850586 25.034658 202.278198 +82.763184 -22.747515 202.278198 +4.780396 -22.605909 202.278183 +4.780396 -22.605833 222.664825 +82.763184 -22.747606 222.664795 +-92.589783 -24.403721 203.107849 +-16.469368 28.020813 203.107849 +-16.523869 -24.483076 203.107834 +-92.535278 28.100182 203.107864 +-16.469368 28.020813 210.714432 +-92.589783 -24.403721 210.714432 +-16.523869 -24.483076 210.714462 +-92.535278 28.100182 210.714462 +-92.589783 -24.403721 210.857742 +-16.469368 28.020813 210.857742 +-16.523869 -24.483076 210.857712 +-92.535278 28.100182 210.857758 +-16.469368 28.020813 218.464371 +-92.589783 -24.403721 218.464340 +-16.523869 -24.483076 218.464340 +-92.535278 28.100182 218.464371 +-92.590866 -24.403788 218.585449 +-16.470409 28.020967 218.585449 +-16.524956 -24.483145 218.585449 +-92.536324 28.100309 218.585449 +-16.470409 28.020967 226.192017 +-92.590866 -24.403788 226.192017 +-16.524956 -24.483145 226.192017 +-92.536324 28.100309 226.192017 +162.264526 25.034658 222.664795 +84.281128 25.176378 202.278183 +84.281128 25.176500 222.664825 +162.264526 25.034658 202.278198 +162.177124 -22.747515 202.278198 +84.194336 -22.605909 202.278183 +84.194336 -22.605833 222.664825 +162.177124 -22.747606 222.664795 +162.264526 25.034658 243.283691 +84.281128 25.176382 222.897095 +84.281128 25.176504 243.283722 +162.264526 25.034658 222.897095 +162.177124 -22.747519 222.897095 +84.194336 -22.605909 222.897095 +84.194336 -22.605833 243.283722 +162.177124 -22.747610 243.283691 +66.539444 -9.329350 242.569305 +156.241531 12.946537 242.569305 +137.709412 -36.178265 242.569305 +85.071533 39.795441 242.569305 +156.241531 12.946537 250.175873 +66.539444 -9.329350 250.175873 +137.709412 -36.178265 250.175873 +85.071533 39.795441 250.175873 +-2.835217 29.278488 188.737320 +-2.541027 -25.122681 141.519440 +-2.835217 29.278488 141.519440 +-2.541027 -25.122711 188.737320 +-67.122330 -25.279179 141.519440 +-67.416397 29.122051 141.519440 +-65.993790 29.125500 188.737320 +-67.121964 -25.279179 188.737320 +-67.415787 29.122051 188.737320 +-74.777939 -36.224636 141.372421 +-127.281845 39.841038 141.372421 +-74.777939 39.841278 141.372391 +-127.281845 -36.224880 141.372421 +-127.281845 39.841038 148.979019 +-74.777939 -36.224636 148.979019 +-74.777939 39.841278 148.979004 +-127.281845 -36.224880 148.979019 +-74.777939 -36.224636 149.122299 +-127.281845 39.841038 149.122299 +-74.777939 39.841278 149.122284 +-127.281845 -36.224880 149.122330 +-127.281845 39.841038 156.728928 +-74.777939 -36.224636 156.728912 +-74.777939 39.841278 156.728912 +-127.281845 -36.224880 156.728928 +-74.778671 -36.224316 156.850021 +-127.282822 39.841358 156.850021 +-74.778671 39.841599 156.850021 +-127.282822 -36.224560 156.850021 +-127.282822 39.841358 164.456589 +-74.778671 -36.224316 164.456589 +-74.778671 39.841599 164.456589 +-127.282822 -36.224560 164.456589 +-74.777939 -36.224632 164.726944 +-127.281845 39.841042 164.726944 +-74.777939 39.841278 164.726944 +-127.281845 -36.224876 164.726944 +-127.281845 39.841042 172.333511 +-74.777939 -36.224632 172.333511 +-74.777939 39.841278 172.333511 +-127.281845 -36.224876 172.333542 +130.889359 -36.224636 75.382462 +78.385452 39.841038 75.382462 +130.889359 39.841278 75.382446 +78.385452 -36.224880 75.382469 +78.385452 39.841038 82.989067 +130.889359 -36.224636 82.989067 +130.889359 39.841278 82.989052 +78.385452 -36.224880 82.989075 +130.889359 -36.224636 83.132347 +78.385452 39.841038 83.132355 +130.889359 39.841278 83.132332 +78.385452 -36.224880 83.132370 +78.385452 39.841038 90.738976 +130.889359 -36.224636 90.738960 +130.889359 39.841278 90.738960 +78.385452 -36.224880 90.738976 +130.888626 -36.224316 90.860062 +78.384476 39.841358 90.860062 +130.888626 39.841599 90.860062 +78.384476 -36.224560 90.860062 +78.384476 39.841358 98.466629 +130.888626 -36.224316 98.466629 +130.888626 39.841599 98.466629 +78.384476 -36.224560 98.466629 +130.889359 -36.224632 98.737000 +78.385452 39.841042 98.737000 +130.889359 39.841278 98.737000 +78.385452 -36.224876 98.737000 +78.385452 39.841042 106.343567 +130.889359 -36.224632 106.343567 +130.889359 39.841278 106.343567 +78.385452 -36.224876 106.343582 +169.132980 29.278488 188.737320 +169.427170 -25.122681 141.519440 +169.132980 29.278488 141.519440 +169.427170 -25.122711 188.737320 +104.845879 -25.279179 141.519440 +104.551811 29.122051 141.519440 +105.974419 29.125500 188.737320 +104.846245 -25.279179 188.737320 +104.552422 29.122051 188.737320 + + + + + + + + + + + +0.119405 -0.230384 -0.965746 +-0.119235 -0.230441 -0.965754 +-0.119211 0.230672 -0.965701 +-0.119211 0.230672 -0.965701 +0.119380 0.230616 -0.965694 +0.119405 -0.230384 -0.965746 +-0.956403 -0.263505 0.125933 +-0.956333 0.263761 0.125924 +-0.951498 0.257330 -0.168618 +-0.951498 0.257330 -0.168618 +-0.951559 -0.257087 -0.168648 +-0.956403 -0.263505 0.125933 +0.089169 -0.993226 0.074504 +-0.089036 -0.993235 0.074540 +-0.085984 -0.990457 -0.107708 +-0.085984 -0.990457 -0.107708 +0.086116 -0.990450 -0.107670 +0.089169 -0.993226 0.074504 +0.956359 0.263819 0.125605 +0.956429 -0.263562 0.125613 +0.951558 -0.257089 -0.168647 +0.951558 -0.257089 -0.168647 +0.951499 0.257328 -0.168619 +0.956359 0.263819 0.125605 +-0.089268 0.993198 0.074763 +0.089400 0.993189 0.074727 +0.086342 0.990400 -0.107949 +0.086342 0.990400 -0.107949 +-0.086212 0.990407 -0.107986 +-0.089268 0.993198 0.074763 +-0.059645 -0.051640 0.996883 +-0.059645 0.051639 0.996883 +-0.178122 0.324574 0.928937 +-0.178122 0.324574 0.928937 +-0.178085 -0.324917 0.928824 +-0.059645 -0.051640 0.996883 +0.059645 -0.051639 0.996883 +-0.059645 -0.051640 0.996883 +-0.178085 -0.324917 0.928824 +-0.178085 -0.324917 0.928824 +0.178086 -0.324915 0.928825 +0.059645 -0.051639 0.996883 +0.059645 0.051640 0.996883 +0.059645 -0.051639 0.996883 +0.178086 -0.324915 0.928825 +0.178086 -0.324915 0.928825 +0.178121 0.324575 0.928937 +0.059645 0.051640 0.996883 +-0.059645 0.051639 0.996883 +0.059645 0.051640 0.996883 +0.178121 0.324575 0.928937 +0.178121 0.324575 0.928937 +-0.178122 0.324574 0.928937 +-0.059645 0.051639 0.996883 +-0.956902 -0.286501 -0.047494 +-0.956754 0.286993 -0.047506 +-0.935699 0.302882 0.180917 +-0.935699 0.302882 0.180917 +-0.935847 -0.302400 0.180955 +-0.956902 -0.286501 -0.047494 +0.094684 -0.995181 -0.025483 +-0.094927 -0.995157 -0.025505 +-0.097945 -0.990243 0.099122 +-0.097945 -0.990243 0.099122 +0.097942 -0.990243 0.099126 +0.094684 -0.995181 -0.025483 +0.956974 0.286285 -0.047354 +0.957125 -0.285780 -0.047344 +0.935975 -0.302063 0.180856 +0.935975 -0.302063 0.180856 +0.935830 0.302532 0.180824 +0.956974 0.286285 -0.047354 +-0.095144 0.995135 -0.025563 +0.094891 0.995160 -0.025542 +0.098119 0.990255 0.098831 +0.098119 0.990255 0.098831 +-0.098117 0.990255 0.098834 +-0.095144 0.995135 -0.025563 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.119375 -0.230443 -0.965736 +-0.119330 -0.230456 -0.965738 +-0.119314 0.230833 -0.965650 +-0.119314 0.230833 -0.965650 +0.119359 0.230820 -0.965648 +0.119375 -0.230443 -0.965736 +-0.956450 -0.263645 0.125275 +-0.956341 0.264048 0.125261 +-0.951446 0.257519 -0.168624 +-0.951446 0.257519 -0.168624 +-0.951550 -0.257121 -0.168644 +-0.956450 -0.263645 0.125275 +0.089316 -0.993153 0.075303 +-0.089283 -0.993155 0.075314 +-0.086285 -0.990402 -0.107976 +-0.086285 -0.990402 -0.107976 +0.086320 -0.990400 -0.107968 +0.089316 -0.993153 0.075303 +0.956265 0.264181 0.125560 +0.956375 -0.263778 0.125574 +0.951481 -0.257288 -0.168778 +0.951481 -0.257288 -0.168778 +0.951378 0.257683 -0.168759 +0.956265 0.264181 0.125560 +-0.089247 0.993157 0.075321 +0.089277 0.993155 0.075311 +0.086286 0.990407 -0.107928 +0.086286 0.990407 -0.107928 +-0.086253 0.990409 -0.107936 +-0.089247 0.993157 0.075321 +-0.059706 -0.051712 0.996876 +-0.059706 0.051713 0.996876 +-0.178425 0.325176 0.928668 +-0.178425 0.325176 0.928668 +-0.178431 -0.325180 0.928666 +-0.059706 -0.051712 0.996876 +0.059722 -0.051734 0.996873 +-0.059706 -0.051712 0.996876 +-0.178431 -0.325180 0.928666 +-0.178431 -0.325180 0.928666 +0.178585 -0.325143 0.928649 +0.059722 -0.051734 0.996873 +0.059722 0.051734 0.996874 +0.059722 -0.051734 0.996873 +0.178585 -0.325143 0.928649 +0.178585 -0.325143 0.928649 +0.178656 0.325122 0.928643 +0.059722 0.051734 0.996874 +-0.059706 0.051713 0.996876 +0.059722 0.051734 0.996874 +0.178656 0.325122 0.928643 +0.178656 0.325122 0.928643 +-0.178425 0.325176 0.928668 +-0.059706 0.051713 0.996876 +-0.956803 -0.286841 -0.047442 +-0.956947 0.286356 -0.047456 +-0.935859 0.302824 0.180182 +-0.935859 0.302824 0.180182 +-0.935721 -0.303220 0.180234 +-0.956803 -0.286841 -0.047442 +0.094855 -0.995165 -0.025491 +-0.094809 -0.995169 -0.025488 +-0.097976 -0.990204 0.099478 +-0.097976 -0.990204 0.099478 +0.098011 -0.990200 0.099489 +0.094855 -0.995165 -0.025491 +0.957166 0.285648 -0.047304 +0.957038 -0.286079 -0.047293 +0.935784 -0.303054 0.180183 +0.935784 -0.303054 0.180183 +0.935925 0.302646 0.180138 +0.957166 0.285648 -0.047304 +-0.095272 0.995122 -0.025614 +0.095311 0.995118 -0.025619 +0.098367 0.990224 0.098898 +0.098367 0.990224 0.098898 +-0.098322 0.990228 0.098898 +-0.095272 0.995122 -0.025614 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.119401 -0.230417 -0.965739 +-0.119231 -0.230474 -0.965746 +-0.119216 0.230850 -0.965658 +-0.119216 0.230850 -0.965658 +0.119385 0.230794 -0.965651 +0.119401 -0.230417 -0.965739 +-0.956398 -0.263530 0.125914 +-0.956289 0.263933 0.125901 +-0.951446 0.257519 -0.168624 +-0.951446 0.257519 -0.168624 +-0.951550 -0.257121 -0.168644 +-0.956398 -0.263530 0.125914 +0.089337 -0.993152 0.075283 +-0.089204 -0.993161 0.075319 +-0.086211 -0.990407 -0.107986 +-0.086211 -0.990407 -0.107986 +0.086343 -0.990400 -0.107948 +0.089337 -0.993152 0.075283 +0.956315 0.263991 0.125581 +0.956424 -0.263587 0.125595 +0.951550 -0.257123 -0.168644 +0.951550 -0.257123 -0.168644 +0.951446 0.257518 -0.168624 +0.956315 0.263991 0.125581 +-0.089167 0.993164 0.075327 +0.089299 0.993155 0.075291 +0.086309 0.990407 -0.107909 +0.086309 0.990407 -0.107909 +-0.086179 0.990414 -0.107946 +-0.089167 0.993164 0.075327 +-0.059651 -0.051645 0.996882 +-0.059652 0.051644 0.996882 +-0.178090 0.325226 0.928715 +-0.178090 0.325226 0.928715 +-0.178095 -0.325230 0.928713 +-0.059651 -0.051645 0.996882 +0.059652 -0.051644 0.996882 +-0.059651 -0.051645 0.996882 +-0.178095 -0.325230 0.928713 +-0.178095 -0.325230 0.928713 +0.178095 -0.325229 0.928713 +0.059652 -0.051644 0.996882 +0.059651 0.051645 0.996882 +0.059652 -0.051644 0.996882 +0.178095 -0.325229 0.928713 +0.178095 -0.325229 0.928713 +0.178089 0.325227 0.928715 +0.059651 0.051645 0.996882 +-0.059652 0.051644 0.996882 +0.059651 0.051645 0.996882 +0.178089 0.325227 0.928715 +0.178089 0.325227 0.928715 +-0.178090 0.325226 0.928715 +-0.059652 0.051644 0.996882 +-0.956759 -0.286980 -0.047481 +-0.956880 0.286574 -0.047493 +-0.935838 0.302474 0.180875 +-0.935838 0.302474 0.180875 +-0.935700 -0.302870 0.180926 +-0.956759 -0.286980 -0.047481 +0.094649 -0.995185 -0.025473 +-0.094892 -0.995161 -0.025495 +-0.097976 -0.990204 0.099478 +-0.097976 -0.990204 0.099478 +0.097974 -0.990204 0.099482 +0.094649 -0.995185 -0.025473 +0.957099 0.285866 -0.047341 +0.956983 -0.286258 -0.047331 +0.935829 -0.302532 0.180827 +0.935829 -0.302532 0.180827 +0.935969 0.302125 0.180782 +0.957099 0.285866 -0.047341 +-0.095356 0.995113 -0.025622 +0.095103 0.995138 -0.025600 +0.098324 0.990228 0.098895 +0.098324 0.990228 0.098895 +-0.098322 0.990228 0.098898 +-0.095356 0.995113 -0.025622 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.119406 -0.230420 -0.965737 +-0.119429 -0.230438 -0.965730 +-0.119413 0.230814 -0.965642 +-0.119413 0.230814 -0.965642 +0.119389 0.230797 -0.965649 +0.119406 -0.230420 -0.965737 +-0.956461 -0.263369 0.125776 +-0.956352 0.263771 0.125762 +-0.951515 0.257354 -0.168490 +-0.951515 0.257354 -0.168490 +-0.951619 -0.256956 -0.168510 +-0.956461 -0.263369 0.125776 +0.089354 -0.993150 0.075299 +-0.089353 -0.993150 0.075299 +-0.086359 -0.990397 -0.107966 +-0.086359 -0.990397 -0.107966 +0.086346 -0.990399 -0.107951 +0.089354 -0.993150 0.075299 +0.956215 0.264371 0.125539 +0.956325 -0.263968 0.125553 +0.951413 -0.257453 -0.168912 +0.951413 -0.257453 -0.168912 +0.951309 0.257848 -0.168893 +0.956215 0.264371 0.125539 +-0.089317 0.993152 0.075306 +0.089316 0.993152 0.075307 +0.086312 0.990407 -0.107912 +0.086312 0.990407 -0.107912 +-0.086327 0.990404 -0.107926 +-0.089317 0.993152 0.075306 +-0.059706 -0.051712 0.996876 +-0.059706 0.051711 0.996876 +-0.178271 0.325213 0.928685 +-0.178271 0.325213 0.928685 +-0.178277 -0.325216 0.928683 +-0.059706 -0.051712 0.996876 +0.059652 -0.051644 0.996882 +-0.059706 -0.051712 0.996876 +-0.178277 -0.325216 0.928683 +-0.178277 -0.325216 0.928683 +0.178249 -0.325192 0.928697 +0.059652 -0.051644 0.996882 +0.059651 0.051645 0.996882 +0.059652 -0.051644 0.996882 +0.178249 -0.325192 0.928697 +0.178249 -0.325192 0.928697 +0.178243 0.325190 0.928698 +0.059651 0.051645 0.996882 +-0.059706 0.051711 0.996876 +0.059651 0.051645 0.996882 +0.178243 0.325190 0.928698 +0.178243 0.325190 0.928698 +-0.178271 0.325213 0.928685 +-0.059706 0.051711 0.996876 +-0.956867 -0.286633 -0.047410 +-0.957030 0.286087 -0.047416 +-0.935837 0.303084 0.179859 +-0.935837 0.303084 0.179859 +-0.935699 -0.303480 0.179911 +-0.956867 -0.286633 -0.047410 +0.094767 -0.995173 -0.025490 +-0.094954 -0.995155 -0.025518 +-0.097939 -0.990209 0.099471 +-0.097939 -0.990209 0.099471 +0.098066 -0.990195 0.099485 +0.094767 -0.995173 -0.025490 +0.957021 0.286115 -0.047424 +0.956875 -0.286606 -0.047402 +0.935925 -0.302580 0.180248 +0.935925 -0.302580 0.180248 +0.936065 0.302173 0.180203 +0.957021 0.286115 -0.047424 +-0.095347 0.995114 -0.025629 +0.095227 0.995126 -0.025611 +0.098417 0.990219 0.098898 +0.098417 0.990219 0.098898 +-0.098284 0.990233 0.098891 +-0.095347 0.995114 -0.025629 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.119409 -0.230387 -0.965745 +-0.119432 -0.230405 -0.965738 +-0.119409 0.230636 -0.965686 +-0.119409 0.230636 -0.965686 +0.119385 0.230620 -0.965692 +0.119409 -0.230387 -0.965745 +-0.956465 -0.263343 0.125794 +-0.956396 0.263599 0.125785 +-0.951567 0.257165 -0.168484 +-0.951567 0.257165 -0.168484 +-0.951627 -0.256922 -0.168514 +-0.956465 -0.263343 0.125794 +0.089186 -0.993223 0.074520 +-0.089186 -0.993223 0.074520 +-0.086131 -0.990447 -0.107688 +-0.086131 -0.990447 -0.107688 +0.086118 -0.990449 -0.107673 +0.089186 -0.993223 0.074520 +0.956260 0.264199 0.125562 +0.956330 -0.263943 0.125571 +0.951421 -0.257419 -0.168916 +0.951421 -0.257419 -0.168916 +0.951362 0.257659 -0.168887 +0.956260 0.264199 0.125562 +-0.089418 0.993186 0.074743 +0.089417 0.993186 0.074743 +0.086345 0.990399 -0.107952 +0.086345 0.990399 -0.107952 +-0.086360 0.990397 -0.107965 +-0.089418 0.993186 0.074743 +-0.059699 -0.051708 0.996876 +-0.059699 0.051707 0.996876 +-0.178304 0.324561 0.928907 +-0.178304 0.324561 0.928907 +-0.178267 -0.324903 0.928794 +-0.059699 -0.051708 0.996876 +0.059645 -0.051639 0.996883 +-0.059699 -0.051708 0.996876 +-0.178267 -0.324903 0.928794 +-0.178267 -0.324903 0.928794 +0.178239 -0.324879 0.928808 +0.059645 -0.051639 0.996883 +0.059645 0.051640 0.996883 +0.059645 -0.051639 0.996883 +0.178239 -0.324879 0.928808 +0.178239 -0.324879 0.928808 +0.178275 0.324538 0.928920 +0.059645 0.051640 0.996883 +-0.059699 0.051707 0.996876 +0.059645 0.051640 0.996883 +0.178275 0.324538 0.928920 +0.178275 0.324538 0.928920 +-0.178304 0.324561 0.928907 +-0.059699 0.051707 0.996876 +-0.956902 -0.286501 -0.047494 +-0.956866 0.286632 -0.047435 +-0.935697 0.303492 0.179901 +-0.935697 0.303492 0.179901 +-0.935846 -0.303009 0.179939 +-0.956902 -0.286501 -0.047494 +0.094837 -0.995166 -0.025510 +-0.095030 -0.995147 -0.025535 +-0.097908 -0.990248 0.099115 +-0.097908 -0.990248 0.099115 +0.098035 -0.990234 0.099129 +0.094837 -0.995166 -0.025510 +0.956863 0.286642 -0.047436 +0.957016 -0.286134 -0.047418 +0.936071 -0.302110 0.180277 +0.936071 -0.302110 0.180277 +0.935926 0.302580 0.180245 +0.956863 0.286642 -0.047436 +-0.095136 0.995136 -0.025567 +0.094939 0.995156 -0.025539 +0.098212 0.990246 0.098834 +0.098212 0.990246 0.098834 +-0.098079 0.990259 0.098827 +-0.095136 0.995136 -0.025567 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.119379 -0.230410 -0.965743 +-0.119329 -0.230419 -0.965747 +-0.119305 0.230651 -0.965695 +-0.119305 0.230651 -0.965695 +0.119354 0.230643 -0.965691 +0.119379 -0.230410 -0.965743 +-0.956455 -0.263620 0.125293 +-0.956385 0.263876 0.125285 +-0.951498 0.257330 -0.168618 +-0.951498 0.257330 -0.168618 +-0.951559 -0.257087 -0.168648 +-0.956455 -0.263620 0.125293 +0.089148 -0.993226 0.074524 +-0.089116 -0.993229 0.074535 +-0.086054 -0.990453 -0.107695 +-0.086054 -0.990453 -0.107695 +0.086092 -0.990450 -0.107689 +0.089148 -0.993226 0.074524 +0.956260 0.264199 0.125562 +0.956379 -0.263753 0.125592 +0.951490 -0.257253 -0.168783 +0.951490 -0.257253 -0.168783 +0.951362 0.257659 -0.168887 +0.956260 0.264199 0.125562 +-0.089348 0.993191 0.074758 +0.089378 0.993189 0.074747 +0.086319 0.990400 -0.107968 +0.086319 0.990400 -0.107968 +-0.086283 0.990403 -0.107973 +-0.089348 0.993191 0.074758 +-0.059699 -0.051708 0.996876 +-0.059699 0.051708 0.996876 +-0.178472 0.324536 0.928883 +-0.178472 0.324536 0.928883 +-0.178435 -0.324879 0.928771 +-0.059699 -0.051708 0.996876 +0.059731 -0.051751 0.996872 +-0.059699 -0.051708 0.996876 +-0.178435 -0.324879 0.928771 +-0.178435 -0.324879 0.928771 +0.178666 -0.324823 0.928746 +0.059731 -0.051751 0.996872 +0.059731 0.051751 0.996872 +0.059731 -0.051751 0.996872 +0.178666 -0.324823 0.928746 +0.178666 -0.324823 0.928746 +0.178702 0.324482 0.928858 +0.059731 0.051751 0.996872 +-0.059699 0.051708 0.996876 +0.059731 0.051751 0.996872 +0.178702 0.324482 0.928858 +0.178702 0.324482 0.928858 +-0.178472 0.324536 0.928883 +-0.059699 0.051708 0.996876 +-0.956956 -0.286326 -0.047458 +-0.956757 0.286982 -0.047514 +-0.935719 0.303231 0.180224 +-0.935719 0.303231 0.180224 +-0.935868 -0.302749 0.180262 +-0.956956 -0.286326 -0.047458 +0.094967 -0.995153 -0.025514 +-0.094845 -0.995166 -0.025498 +-0.097945 -0.990243 0.099122 +-0.097945 -0.990243 0.099122 +0.097986 -0.990238 0.099129 +0.094967 -0.995153 -0.025514 +0.957030 0.286102 -0.047321 +0.957180 -0.285601 -0.047306 +0.935931 -0.302584 0.180211 +0.935931 -0.302584 0.180211 +0.935785 0.303054 0.180179 +0.957030 0.286102 -0.047321 +-0.095138 0.995136 -0.025569 +0.095140 0.995136 -0.025563 +0.098162 0.990250 0.098834 +0.098162 0.990250 0.098834 +-0.098117 0.990255 0.098834 +-0.095138 0.995136 -0.025569 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.985978 -0.095115 0.137113 +-0.949755 -0.178415 0.257163 +-0.985878 0.095453 -0.137597 +-0.985878 0.095453 -0.137597 +-0.948297 0.180918 -0.260770 +-0.985978 -0.095115 0.137113 +0.188900 -0.559726 0.806860 +0.117083 -0.566086 0.815989 +-0.117067 -0.566069 0.816003 +-0.117067 -0.566069 0.816003 +-0.188881 -0.559749 0.806849 +0.188900 -0.559726 0.806860 +0.985921 0.095316 -0.137386 +0.949914 -0.178127 0.256776 +0.986163 -0.094499 0.136209 +0.986163 -0.094499 0.136209 +0.948917 0.179845 -0.259252 +0.985921 0.095316 -0.137386 +-0.118970 0.565940 -0.815818 +-0.191917 0.559413 -0.806365 +0.191932 0.559391 -0.806377 +0.191932 0.559391 -0.806377 +0.118984 0.565957 -0.815803 +-0.118970 0.565940 -0.815818 +-0.986292 0.090913 -0.137707 +-0.949902 0.172190 -0.260838 +-0.986592 -0.090992 0.135485 +-0.986592 -0.090992 0.135485 +-0.949886 -0.174273 0.259509 +-0.986292 0.090913 -0.137707 +-0.187114 -0.547656 0.815513 +0.187097 -0.547674 0.815505 +0.127645 -0.552942 0.823384 +0.127645 -0.552942 0.823384 +-0.127399 -0.552974 0.823401 +-0.187114 -0.547656 0.815513 +0.986635 -0.090843 0.135274 +0.950045 0.171961 -0.260470 +0.986295 0.090899 -0.137697 +0.986295 0.090899 -0.137697 +0.949880 -0.174293 0.259518 +0.986635 -0.090843 0.135274 +0.128199 0.546376 -0.827670 +-0.128212 0.546391 -0.827659 +-0.189856 0.540902 -0.819378 +-0.189856 0.540902 -0.819378 +0.190238 0.540878 -0.819305 +0.128199 0.546376 -0.827670 +-0.985580 0.092551 0.141657 +-0.952583 -0.166438 -0.254722 +-0.985690 -0.092197 -0.141119 +-0.985690 -0.092197 -0.141119 +-0.951152 0.168869 0.258442 +-0.985580 0.092551 0.141657 +-0.119608 -0.543026 -0.831154 +0.119633 -0.543044 -0.831139 +0.191447 -0.536835 -0.821679 +0.191447 -0.536835 -0.821679 +-0.191430 -0.536859 -0.821668 +-0.119608 -0.543026 -0.831154 +0.985872 -0.091621 -0.140219 +0.952724 -0.166185 -0.254363 +0.985626 0.092411 0.141429 +0.985626 0.092411 0.141429 +0.951738 0.167865 0.256935 +0.985872 -0.091621 -0.140219 +0.194545 0.536501 0.821169 +-0.194528 0.536525 0.821157 +-0.121214 0.542919 0.830991 +-0.121214 0.542919 0.830991 +0.121217 0.542938 0.830978 +0.194545 0.536501 0.821169 +-0.985980 -0.095111 0.137106 +-0.949749 -0.178426 0.257179 +-0.985878 0.095453 -0.137597 +-0.985878 0.095453 -0.137597 +-0.948300 0.180912 -0.260762 +-0.985980 -0.095111 0.137106 +0.189033 -0.559712 0.806839 +0.117169 -0.566081 0.815981 +-0.116913 -0.566079 0.816018 +-0.116913 -0.566079 0.816018 +-0.188687 -0.559770 0.806880 +0.189033 -0.559712 0.806839 +0.985809 0.095692 -0.137928 +0.949519 -0.178811 0.257762 +0.986075 -0.094797 0.136638 +0.986075 -0.094797 0.136638 +0.948612 0.180368 -0.260006 +0.985809 0.095692 -0.137928 +-0.118817 0.565950 -0.815833 +-0.191627 0.559445 -0.806412 +0.192003 0.559383 -0.806366 +0.192003 0.559383 -0.806366 +0.119011 0.565956 -0.815801 +-0.118817 0.565950 -0.815833 +-0.986322 0.090812 -0.137555 +-0.949604 0.172688 -0.261593 +-0.986517 -0.091247 0.135864 +-0.986517 -0.091247 0.135864 +-0.949961 -0.174146 0.259320 +-0.986322 0.090812 -0.137555 +-0.186852 -0.547684 0.815554 +0.187154 -0.547668 0.815496 +0.127630 -0.552943 0.823386 +0.127630 -0.552943 0.823386 +-0.127234 -0.552986 0.823418 +-0.186852 -0.547684 0.815554 +0.986635 -0.090843 0.135274 +0.950054 0.171945 -0.260445 +0.986295 0.090899 -0.137697 +0.986295 0.090899 -0.137697 +0.949890 -0.174277 0.259494 +0.986635 -0.090843 0.135274 +0.128240 0.546373 -0.827666 +-0.128057 0.546402 -0.827676 +-0.189613 0.540928 -0.819417 +-0.189613 0.540928 -0.819417 +0.190188 0.540884 -0.819313 +0.128240 0.546373 -0.827666 +-0.985558 0.092622 0.141765 +-0.952535 -0.166521 -0.254848 +-0.985679 -0.092233 -0.141174 +-0.985679 -0.092233 -0.141174 +-0.951117 0.168929 0.258533 +-0.985558 0.092622 0.141765 +-0.119490 -0.543033 -0.831166 +0.119703 -0.543039 -0.831132 +0.191647 -0.536814 -0.821646 +0.191647 -0.536814 -0.821646 +-0.191162 -0.536887 -0.821711 +-0.119490 -0.543033 -0.831166 +0.985795 -0.091868 -0.140598 +0.952450 -0.166654 -0.255081 +0.985542 0.092678 0.141836 +0.985542 0.092678 0.141836 +0.951478 0.168306 0.257610 +0.985795 -0.091868 -0.140598 +0.194915 0.536461 0.821107 +-0.194599 0.536518 0.821146 +-0.121183 0.542921 0.830994 +-0.121183 0.542921 0.830994 +0.121481 0.542921 0.830951 +0.194915 0.536461 0.821107 +-0.985980 -0.095111 0.137106 +-0.949680 -0.178545 0.257350 +-0.985856 0.095525 -0.137702 +-0.985856 0.095525 -0.137702 +-0.948300 0.180912 -0.260762 +-0.985980 -0.095111 0.137106 +0.188901 -0.559726 0.806860 +0.117160 -0.566081 0.815982 +-0.116875 -0.566082 0.816022 +-0.116875 -0.566082 0.816022 +-0.188554 -0.559785 0.806901 +0.188901 -0.559726 0.806860 +0.985776 0.095802 -0.138086 +0.949368 -0.179071 0.258136 +0.986032 -0.094942 0.136847 +0.986032 -0.094942 0.136847 +0.948459 0.180629 -0.260382 +0.985776 0.095802 -0.138086 +-0.118740 0.565955 -0.815840 +-0.191581 0.559451 -0.806419 +0.192003 0.559383 -0.806366 +0.192003 0.559383 -0.806366 +0.118945 0.565960 -0.815807 +-0.118740 0.565955 -0.815840 +-0.986344 0.090742 -0.137449 +-0.949604 0.172688 -0.261593 +-0.986509 -0.091273 0.135901 +-0.986509 -0.091273 0.135901 +-0.950036 -0.174020 0.259132 +-0.986344 0.090742 -0.137449 +-0.186917 -0.547677 0.815544 +0.187102 -0.547673 0.815504 +0.127672 -0.552940 0.823381 +0.127672 -0.552940 0.823381 +-0.127197 -0.552989 0.823422 +-0.186917 -0.547677 0.815544 +0.986614 -0.090913 0.135379 +0.949970 0.172086 -0.260659 +0.986252 0.091039 -0.137908 +0.986252 0.091039 -0.137908 +0.949731 -0.174546 0.259895 +0.986614 -0.090913 0.135379 +0.128198 0.546376 -0.827670 +-0.128090 0.546399 -0.827672 +-0.189482 0.540942 -0.819438 +-0.189482 0.540942 -0.819438 +0.190254 0.540877 -0.819302 +0.128198 0.546376 -0.827670 +-0.985535 0.092693 0.141874 +-0.952463 -0.166645 -0.255038 +-0.985657 -0.092303 -0.141281 +-0.985657 -0.092303 -0.141281 +-0.951044 0.169051 0.258720 +-0.985535 0.092693 0.141874 +-0.119451 -0.543036 -0.831170 +0.119781 -0.543034 -0.831124 +0.191581 -0.536821 -0.821657 +0.191581 -0.536821 -0.821657 +-0.191225 -0.536880 -0.821701 +-0.119451 -0.543036 -0.831170 +0.985722 -0.092103 -0.140957 +0.952378 -0.166776 -0.255268 +0.985512 0.092773 0.141981 +0.985512 0.092773 0.141981 +0.951260 0.168674 0.258173 +0.985722 -0.092103 -0.140957 +0.195050 0.536446 0.821085 +-0.194551 0.536523 0.821154 +-0.121223 0.542918 0.830990 +-0.121223 0.542918 0.830990 +0.121467 0.542922 0.830952 +0.195050 0.536446 0.821085 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.167818 0.000000 -0.985818 +-0.167885 0.000000 -0.985807 +-0.167884 0.000000 -0.985807 +-0.167884 0.000000 -0.985807 +0.167809 0.000000 -0.985819 +0.167818 0.000000 -0.985818 +0.167841 0.000000 0.985814 +0.167832 0.000000 0.985816 +-0.167907 0.000000 0.985803 +-0.167907 0.000000 0.985803 +-0.167908 0.000000 0.985803 +0.167841 0.000000 0.985814 +-0.973544 0.000000 0.228500 +-0.973544 0.000000 0.228498 +-0.973536 0.000000 -0.228534 +-0.973536 0.000000 -0.228534 +-0.973535 0.000000 -0.228536 +-0.973544 0.000000 0.228500 +0.005896 -0.999955 0.007463 +-0.005899 -0.999955 0.007463 +-0.005899 -0.999955 -0.007465 +-0.005899 -0.999955 -0.007465 +0.005896 -0.999955 -0.007465 +0.005896 -0.999955 0.007463 +0.973502 0.000001 0.228679 +0.973508 0.000000 0.228655 +0.973493 0.000001 -0.228717 +0.973493 0.000001 -0.228717 +0.973487 0.000000 -0.228740 +0.973502 0.000001 0.228679 +-0.005894 0.999955 0.007457 +0.005901 0.999955 0.007469 +0.005900 0.999955 -0.007472 +0.005900 0.999955 -0.007472 +-0.005894 0.999955 -0.007458 +-0.005894 0.999955 0.007457 +0.119255 -0.230420 -0.965756 +-0.119296 -0.230417 -0.965752 +-0.119294 0.230486 -0.965736 +-0.119294 0.230486 -0.965736 +0.119260 0.230488 -0.965739 +0.119255 -0.230420 -0.965756 +0.119256 -0.230416 0.965757 +0.119256 0.230498 0.965737 +-0.119278 0.230454 0.965745 +-0.119278 0.230454 0.965745 +-0.119277 -0.230394 0.965759 +0.119256 -0.230416 0.965757 +-0.951550 -0.257151 0.168601 +-0.951532 0.257219 0.168599 +-0.951533 0.257221 -0.168588 +-0.951533 0.257221 -0.168588 +-0.951551 -0.257152 -0.168590 +-0.951550 -0.257151 0.168601 +0.086114 -0.990440 0.107763 +-0.086139 -0.990439 0.107754 +-0.086140 -0.990440 -0.107745 +-0.086140 -0.990440 -0.107745 +0.086113 -0.990440 -0.107764 +0.086114 -0.990440 0.107763 +0.951475 0.257352 0.168716 +0.951493 -0.257284 0.168719 +0.951494 -0.257282 -0.168717 +0.951494 -0.257282 -0.168717 +0.951476 0.257351 -0.168714 +0.951475 0.257352 0.168716 +-0.086168 0.990433 0.107786 +0.086136 0.990435 0.107787 +0.086133 0.990435 -0.107791 +0.086133 0.990435 -0.107791 +-0.086168 0.990433 -0.107781 +-0.086168 0.990433 0.107786 +0.119237 -0.230393 -0.965765 +-0.119278 -0.230390 -0.965760 +-0.119276 0.230459 -0.965744 +-0.119276 0.230459 -0.965744 +0.119242 0.230461 -0.965748 +0.119237 -0.230393 -0.965765 +0.119256 -0.230416 0.965757 +0.119256 0.230498 0.965737 +-0.119295 0.230481 0.965737 +-0.119295 0.230481 0.965737 +-0.119295 -0.230422 0.965751 +0.119256 -0.230416 0.965757 +-0.951551 -0.257151 0.168595 +-0.951533 0.257219 0.168593 +-0.951533 0.257221 -0.168588 +-0.951533 0.257221 -0.168588 +-0.951551 -0.257152 -0.168590 +-0.951551 -0.257151 0.168595 +0.086115 -0.990441 0.107752 +-0.086139 -0.990439 0.107750 +-0.086140 -0.990440 -0.107745 +-0.086140 -0.990440 -0.107745 +0.086113 -0.990440 -0.107764 +0.086115 -0.990441 0.107752 +0.951477 0.257354 0.168699 +0.951496 -0.257286 0.168702 +0.951494 -0.257282 -0.168717 +0.951494 -0.257282 -0.168717 +0.951476 0.257351 -0.168714 +0.951477 0.257354 0.168699 +-0.086168 0.990433 0.107782 +0.086137 0.990437 0.107776 +0.086133 0.990435 -0.107791 +0.086133 0.990435 -0.107791 +-0.086168 0.990433 -0.107781 +-0.086168 0.990433 0.107782 +0.119255 -0.230420 -0.965756 +-0.119296 -0.230417 -0.965752 +-0.119294 0.230486 -0.965736 +-0.119294 0.230486 -0.965736 +0.119260 0.230488 -0.965739 +0.119255 -0.230420 -0.965756 +0.119221 -0.230362 0.965774 +0.119222 0.230444 0.965755 +-0.119261 0.230427 0.965754 +-0.119261 0.230427 0.965754 +-0.119260 -0.230367 0.965768 +0.119221 -0.230362 0.965774 +-0.951548 -0.257149 0.168612 +-0.951530 0.257217 0.168610 +-0.951533 0.257221 -0.168588 +-0.951533 0.257221 -0.168588 +-0.951551 -0.257152 -0.168590 +-0.951548 -0.257149 0.168612 +0.086114 -0.990440 0.107763 +-0.086138 -0.990438 0.107762 +-0.086140 -0.990440 -0.107745 +-0.086140 -0.990440 -0.107745 +0.086114 -0.990441 -0.107757 +0.086114 -0.990440 0.107763 +0.951475 0.257352 0.168716 +0.951493 -0.257284 0.168719 +0.951495 -0.257285 -0.168707 +0.951495 -0.257285 -0.168707 +0.951477 0.257353 -0.168704 +0.951475 0.257352 0.168716 +-0.086168 0.990432 0.107794 +0.086136 0.990436 0.107787 +0.086134 0.990436 -0.107784 +0.086134 0.990436 -0.107784 +-0.086168 0.990433 -0.107781 +-0.086168 0.990432 0.107794 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.002423 -0.999997 -0.000001 +0.002423 -0.999997 -0.000001 +0.002423 -0.999997 -0.000001 +0.002423 -0.999997 0.000000 +0.002423 -0.999997 0.000000 +0.002423 -0.999997 0.000000 +-0.999985 -0.005401 0.000013 +-0.999985 -0.005401 0.000013 +-0.999985 -0.005401 0.000013 +-0.999985 -0.005405 0.000008 +-0.999985 -0.005405 0.000008 +-0.999985 -0.005405 0.000008 +-0.002425 0.999997 0.000000 +-0.002425 0.999997 0.000000 +-0.002425 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.002423 -0.999997 -0.000001 +0.002423 -0.999997 -0.000001 +0.002423 -0.999997 -0.000001 +0.002423 -0.999997 0.000000 +0.002423 -0.999997 0.000000 +0.002423 -0.999997 0.000000 +-0.999985 -0.005401 0.000013 +-0.999985 -0.005401 0.000013 +-0.999985 -0.005401 0.000013 +-0.999985 -0.005405 0.000008 +-0.999985 -0.005405 0.000008 +-0.999985 -0.005405 0.000008 +-0.002425 0.999997 0.000000 +-0.002425 0.999997 0.000000 +-0.002425 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.002423 -0.999997 -0.000001 +0.002423 -0.999997 -0.000001 +0.002423 -0.999997 -0.000001 +0.002423 -0.999997 0.000000 +0.002423 -0.999997 0.000000 +0.002423 -0.999997 0.000000 +-0.999985 -0.005401 0.000013 +-0.999985 -0.005401 0.000013 +-0.999985 -0.005401 0.000013 +-0.999985 -0.005405 0.000008 +-0.999985 -0.005405 0.000008 +-0.999985 -0.005405 0.000008 +-0.002425 0.999997 0.000000 +-0.002425 0.999997 0.000000 +-0.002425 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.002423 -0.999997 -0.000001 +0.002423 -0.999997 -0.000001 +0.002423 -0.999997 -0.000001 +0.002423 -0.999997 0.000000 +0.002423 -0.999997 0.000000 +0.002423 -0.999997 0.000000 +-0.999985 -0.005401 0.000013 +-0.999985 -0.005401 0.000013 +-0.999985 -0.005401 0.000013 +-0.999985 -0.005405 0.000008 +-0.999985 -0.005405 0.000008 +-0.999985 -0.005405 0.000008 +-0.002425 0.999997 0.000000 +-0.002425 0.999997 0.000000 +-0.002425 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.001817 0.999998 0.000000 +0.001817 0.999998 0.000000 +0.001817 0.999998 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +-0.001818 -0.999998 -0.000004 +-0.001818 -0.999998 -0.000004 +-0.001818 -0.999998 -0.000004 +-0.001816 -0.999998 0.000004 +-0.001816 -0.999998 0.000004 +-0.001816 -0.999998 0.000004 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.001817 0.999998 0.000000 +0.001817 0.999998 0.000000 +0.001817 0.999998 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +-0.001818 -0.999998 -0.000004 +-0.001818 -0.999998 -0.000004 +-0.001818 -0.999998 -0.000004 +-0.001816 -0.999998 0.000004 +-0.001816 -0.999998 0.000004 +-0.001816 -0.999998 0.000004 +0.999998 -0.001819 -0.000006 +0.999998 -0.001819 -0.000006 +0.999998 -0.001819 -0.000006 +0.999998 -0.001817 0.000000 +0.999998 -0.001817 0.000000 +0.999998 -0.001817 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.001816 0.999998 0.000000 +0.001816 0.999998 0.000000 +0.001816 0.999998 0.000000 +0.001816 0.999998 0.000000 +0.001816 0.999998 0.000000 +0.001816 0.999998 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000001 0.000000 1.000000 +0.000001 0.000000 1.000000 +0.000001 0.000000 1.000000 +-0.001829 -0.999998 0.000000 +-0.001829 -0.999998 0.000000 +-0.001829 -0.999998 0.000000 +-0.001829 -0.999998 0.000000 +-0.001829 -0.999998 0.000000 +-0.001829 -0.999998 0.000000 +-0.999998 0.001817 -0.000006 +-0.999998 0.001817 -0.000006 +-0.999998 0.001817 -0.000006 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.001817 0.999998 0.000000 +0.001817 0.999998 0.000000 +0.001817 0.999998 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +-0.001818 -0.999998 -0.000004 +-0.001818 -0.999998 -0.000004 +-0.001818 -0.999998 -0.000004 +-0.001816 -0.999998 0.000004 +-0.001816 -0.999998 0.000004 +-0.001816 -0.999998 0.000004 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.001817 0.999998 0.000000 +0.001817 0.999998 0.000000 +0.001817 0.999998 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +-0.001816 -0.999998 -0.000004 +-0.001816 -0.999998 -0.000004 +-0.001816 -0.999998 -0.000004 +-0.001818 -0.999998 0.000004 +-0.001818 -0.999998 0.000004 +-0.001818 -0.999998 0.000004 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.001817 0.999998 0.000000 +0.001817 0.999998 0.000000 +0.001817 0.999998 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +-0.001818 -0.999998 -0.000004 +-0.001818 -0.999998 -0.000004 +-0.001818 -0.999998 -0.000004 +-0.001816 -0.999998 0.000004 +-0.001816 -0.999998 0.000004 +-0.001816 -0.999998 0.000004 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.001817 0.999998 0.000000 +0.001817 0.999998 0.000000 +0.001817 0.999998 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +-0.001818 -0.999998 -0.000004 +-0.001818 -0.999998 -0.000004 +-0.001818 -0.999998 -0.000004 +-0.001816 -0.999998 0.000004 +-0.001816 -0.999998 0.000004 +-0.001816 -0.999998 0.000004 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.001817 0.999998 0.000000 +0.001817 0.999998 0.000000 +0.001817 0.999998 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +-0.001816 -0.999998 -0.000004 +-0.001816 -0.999998 -0.000004 +-0.001816 -0.999998 -0.000004 +-0.001818 -0.999998 0.000004 +-0.001818 -0.999998 0.000004 +-0.001818 -0.999998 0.000004 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000001 1.000000 +0.000000 0.000001 1.000000 +0.000000 0.000001 1.000000 +0.000000 -0.000001 1.000000 +0.000000 -0.000001 1.000000 +0.000000 -0.000001 1.000000 +-0.999999 0.001038 0.000000 +-0.999999 0.001038 0.000000 +-0.999999 0.001038 0.000000 +-0.999999 0.001038 0.000000 +-0.999999 0.001038 0.000000 +-0.999999 0.001038 0.000000 +-0.001043 -0.999999 0.000000 +-0.001043 -1.000000 0.000000 +-0.001043 -0.999999 0.000000 +-0.001043 -0.999999 0.000000 +-0.001043 -0.999999 0.000000 +-0.001043 -0.999999 0.000000 +0.999999 -0.001038 0.000000 +1.000000 -0.001038 0.000000 +0.999999 -0.001038 0.000000 +1.000000 -0.001038 0.000000 +1.000000 -0.001038 0.000000 +1.000000 -0.001038 0.000000 +0.001043 0.999999 0.000000 +0.001043 0.999999 0.000000 +0.001043 0.999999 0.000000 +0.001043 0.999999 0.000000 +0.001043 0.999999 0.000000 +0.001043 0.999999 0.000000 +0.000000 0.000001 -1.000000 +0.000000 0.000001 -1.000000 +0.000000 0.000001 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -0.000001 1.000000 +0.000000 -0.000001 1.000000 +0.000000 -0.000001 1.000000 +0.000000 -0.000001 1.000000 +0.000000 -0.000001 1.000000 +0.000000 -0.000001 1.000000 +-0.999999 0.001038 0.000000 +-0.999999 0.001038 0.000000 +-1.000000 0.001038 0.000000 +-1.000000 0.001038 0.000000 +-0.999999 0.001038 0.000000 +-1.000000 0.001038 0.000000 +-0.001043 -0.999999 0.000000 +-0.001043 -0.999999 0.000000 +-0.001043 -0.999999 0.000000 +-0.001043 -0.999999 0.000000 +-0.001043 -0.999999 0.000000 +-0.001043 -0.999999 0.000000 +1.000000 -0.001038 0.000000 +0.999999 -0.001038 0.000000 +0.999999 -0.001038 0.000000 +1.000000 -0.001038 0.000000 +0.999999 -0.001038 0.000000 +0.999999 -0.001038 0.000000 +0.001043 0.999999 0.000000 +0.001043 0.999999 0.000000 +0.001043 0.999999 0.000000 +0.001043 0.999999 0.000000 +0.001043 0.999999 0.000000 +0.001043 0.999999 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999999 0.001039 0.000000 +-0.999999 0.001039 0.000000 +-1.000000 0.001039 0.000000 +-1.000000 0.001039 0.000000 +-0.999999 0.001039 0.000000 +-0.999999 0.001039 0.000000 +-0.001043 -0.999999 0.000000 +-0.001043 -0.999999 0.000000 +-0.001043 -0.999999 0.000000 +-0.001043 -0.999999 0.000000 +-0.001043 -0.999999 0.000000 +-0.001043 -0.999999 0.000000 +0.999999 -0.001039 0.000000 +0.999999 -0.001039 0.000000 +1.000000 -0.001039 0.000000 +1.000000 -0.001039 0.000000 +0.999999 -0.001039 0.000000 +0.999999 -0.001039 0.000000 +0.001043 0.999999 0.000000 +0.001043 0.999999 0.000000 +0.001043 0.999999 0.000000 +0.001043 0.999999 0.000000 +0.001043 0.999999 0.000000 +0.001043 0.999999 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.935637 0.352964 0.000000 +-0.935637 0.352964 0.000000 +-0.935637 0.352964 0.000000 +-0.935637 0.352964 0.000000 +-0.935637 0.352964 0.000000 +-0.935637 0.352964 0.000000 +-0.352969 -0.935635 0.000000 +-0.352969 -0.935635 0.000000 +-0.352969 -0.935635 0.000000 +-0.352969 -0.935635 0.000000 +-0.352969 -0.935635 0.000000 +-0.352969 -0.935635 0.000000 +0.935637 -0.352965 0.000000 +0.935637 -0.352965 0.000000 +0.935637 -0.352965 0.000000 +0.935637 -0.352965 0.000000 +0.935637 -0.352965 0.000000 +0.935637 -0.352965 0.000000 +0.352969 0.935635 0.000000 +0.352969 0.935635 0.000000 +0.352969 0.935635 0.000000 +0.352969 0.935635 0.000000 +0.352969 0.935635 0.000000 +0.352969 0.935635 0.000000 +-0.000001 0.000000 -1.000000 +-0.000001 0.000000 -1.000000 +-0.000001 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000001 0.000000 -1.000000 +-0.000001 0.000000 -1.000000 +-0.000001 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000001 0.000000 1.000000 +0.000001 0.000000 1.000000 +0.000001 0.000000 1.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 + + + + + + + + + + + +0.480507 0.045007 +0.480507 0.412535 +0.108983 0.413764 +0.108319 0.417867 +0.108120 0.417948 +0.108319 0.417867 +0.108120 0.417948 +0.485016 0.418868 +0.485263 0.418876 +0.109020 0.038880 +0.109020 0.042880 +0.108667 0.039200 +0.481756 0.043443 +0.482223 0.042625 +0.485110 0.418890 +0.485263 0.419226 +0.484531 0.420580 +0.484252 0.420580 +0.484252 0.420580 +0.484531 0.420580 +0.482229 0.042758 +0.481756 0.043443 +0.110650 0.039983 +0.110831 0.039988 +0.110760 0.421926 +0.110622 0.421852 +0.110622 0.421852 +0.110760 0.421926 +0.484252 0.420631 +0.109614 0.418992 +0.484531 0.420630 +0.109371 0.419085 +0.484252 0.420631 +0.109614 0.418992 +0.484531 0.420630 +0.109371 0.419085 +0.480507 0.045007 +0.480507 0.412535 +0.108983 0.413764 +0.108319 0.417867 +0.108120 0.417948 +0.108319 0.417867 +0.108120 0.417948 +0.485016 0.418868 +0.485263 0.418876 +0.109020 0.038880 +0.109020 0.042880 +0.108667 0.039200 +0.481756 0.043443 +0.482223 0.042625 +0.485110 0.418890 +0.485263 0.419226 +0.484531 0.420580 +0.484252 0.420580 +0.484252 0.420580 +0.484531 0.420580 +0.482229 0.042758 +0.481756 0.043443 +0.110650 0.039983 +0.110831 0.039988 +0.110760 0.421926 +0.110622 0.421852 +0.110622 0.421852 +0.110760 0.421926 +0.484252 0.420631 +0.109614 0.418992 +0.484531 0.420630 +0.109371 0.419085 +0.484252 0.420631 +0.109614 0.418992 +0.484531 0.420630 +0.109371 0.419085 +0.480507 0.045007 +0.480507 0.412535 +0.108983 0.413764 +0.108319 0.417867 +0.108120 0.417948 +0.108319 0.417867 +0.108120 0.417948 +0.485016 0.418868 +0.485263 0.418876 +0.109020 0.038880 +0.109020 0.042880 +0.108667 0.039200 +0.481756 0.043443 +0.482223 0.042625 +0.485110 0.418890 +0.485263 0.419226 +0.484531 0.420580 +0.484252 0.420580 +0.484252 0.420580 +0.484531 0.420580 +0.482229 0.042758 +0.481756 0.043443 +0.110650 0.039983 +0.110831 0.039988 +0.110760 0.421926 +0.110622 0.421852 +0.110622 0.421852 +0.110760 0.421926 +0.484252 0.420631 +0.109614 0.418992 +0.484531 0.420630 +0.109371 0.419085 +0.484252 0.420631 +0.109614 0.418992 +0.484531 0.420630 +0.109371 0.419085 +0.480507 0.045007 +0.480507 0.412535 +0.108983 0.413764 +0.108319 0.417867 +0.108120 0.417948 +0.108319 0.417867 +0.108120 0.417948 +0.485016 0.418868 +0.485263 0.418876 +0.109020 0.038880 +0.109020 0.042880 +0.108667 0.039200 +0.481756 0.043443 +0.482223 0.042625 +0.485110 0.418890 +0.485263 0.419226 +0.484531 0.420580 +0.484252 0.420580 +0.484252 0.420580 +0.484531 0.420580 +0.482229 0.042758 +0.481756 0.043443 +0.110650 0.039983 +0.110831 0.039988 +0.110760 0.421926 +0.110622 0.421852 +0.110622 0.421852 +0.110760 0.421926 +0.484252 0.420631 +0.109614 0.418992 +0.484531 0.420630 +0.109371 0.419085 +0.484252 0.420631 +0.109614 0.418992 +0.484531 0.420630 +0.109371 0.419085 +0.480507 0.045007 +0.480507 0.412535 +0.108983 0.413764 +0.108319 0.417867 +0.108120 0.417948 +0.108319 0.417867 +0.108120 0.417948 +0.485016 0.418868 +0.485263 0.418876 +0.109020 0.038880 +0.109020 0.042880 +0.108667 0.039200 +0.481756 0.043443 +0.482223 0.042625 +0.485110 0.418890 +0.485263 0.419226 +0.484531 0.420580 +0.484252 0.420580 +0.484252 0.420580 +0.484531 0.420580 +0.482229 0.042758 +0.481756 0.043443 +0.110650 0.039983 +0.110831 0.039988 +0.110760 0.421926 +0.110622 0.421852 +0.110622 0.421852 +0.110760 0.421926 +0.484252 0.420631 +0.109614 0.418992 +0.484531 0.420630 +0.109371 0.419085 +0.484252 0.420631 +0.109614 0.418992 +0.484531 0.420630 +0.109371 0.419085 +0.480507 0.045007 +0.480507 0.412535 +0.108983 0.413764 +0.108319 0.417867 +0.108120 0.417948 +0.108319 0.417867 +0.108120 0.417948 +0.485016 0.418868 +0.485263 0.418876 +0.109020 0.038880 +0.109020 0.042880 +0.108667 0.039200 +0.481756 0.043443 +0.482223 0.042625 +0.485110 0.418890 +0.485263 0.419226 +0.484531 0.420580 +0.484252 0.420580 +0.484252 0.420580 +0.484531 0.420580 +0.482229 0.042758 +0.481756 0.043443 +0.110650 0.039983 +0.110831 0.039988 +0.110760 0.421926 +0.110622 0.421852 +0.110622 0.421852 +0.110760 0.421926 +0.484252 0.420631 +0.109614 0.418992 +0.484531 0.420630 +0.109371 0.419085 +0.484252 0.420631 +0.109614 0.418992 +0.484531 0.420630 +0.109371 0.419085 +0.478224 0.420580 +0.114013 0.420894 +0.478224 0.420580 +0.478853 0.420580 +0.113937 0.420889 +0.478853 0.420580 +0.478224 0.420580 +0.478224 0.420580 +0.114014 0.420907 +0.478853 0.420580 +0.113936 0.420877 +0.478853 0.420580 +0.113979 0.420267 +0.113904 0.420297 +0.113903 0.420285 +0.113980 0.420279 +0.478224 0.420580 +0.478224 0.420580 +0.113977 0.420238 +0.478853 0.420580 +0.113901 0.420246 +0.478853 0.420580 +0.478224 0.420580 +0.113977 0.420226 +0.478224 0.420580 +0.478853 0.420580 +0.113901 0.420258 +0.478854 0.420580 +0.114012 0.420873 +0.113935 0.420856 +0.113935 0.420857 +0.114012 0.420872 +0.478224 0.420580 +0.113979 0.420267 +0.478224 0.420580 +0.478853 0.420580 +0.113904 0.420297 +0.478853 0.420580 +0.478224 0.420580 +0.478224 0.420580 +0.113979 0.420279 +0.478853 0.420580 +0.113903 0.420285 +0.478853 0.420580 +0.114013 0.420894 +0.113936 0.420889 +0.113936 0.420877 +0.114014 0.420907 +0.478224 0.420580 +0.478224 0.420580 +0.114013 0.420894 +0.478853 0.420580 +0.478853 0.420580 +0.113936 0.420889 +0.478224 0.420580 +0.114014 0.420907 +0.478224 0.420580 +0.478853 0.420580 +0.478853 0.420580 +0.113936 0.420877 +0.113979 0.420267 +0.113904 0.420297 +0.113903 0.420285 +0.113980 0.420279 +0.478224 0.420580 +0.478224 0.420580 +0.113977 0.420238 +0.478853 0.420580 +0.113901 0.420246 +0.478853 0.420580 +0.478224 0.420580 +0.113977 0.420226 +0.478224 0.420580 +0.478853 0.420580 +0.113901 0.420258 +0.478854 0.420580 +0.114012 0.420873 +0.113935 0.420856 +0.113935 0.420857 +0.114012 0.420872 +0.478224 0.420580 +0.113979 0.420267 +0.478224 0.420580 +0.478853 0.420580 +0.113904 0.420297 +0.478853 0.420580 +0.478224 0.420580 +0.478224 0.420580 +0.113979 0.420279 +0.478853 0.420580 +0.113903 0.420285 +0.478853 0.420580 +0.114013 0.420894 +0.113936 0.420889 +0.113936 0.420877 +0.114014 0.420907 +0.478224 0.420580 +0.478224 0.420580 +0.114013 0.420894 +0.478853 0.420580 +0.478853 0.420580 +0.113936 0.420889 +0.478224 0.420580 +0.114014 0.420907 +0.478224 0.420580 +0.478853 0.420580 +0.478853 0.420580 +0.113936 0.420877 +0.113979 0.420267 +0.113904 0.420297 +0.113903 0.420285 +0.113980 0.420279 +0.478224 0.420580 +0.478224 0.420580 +0.113977 0.420238 +0.478853 0.420580 +0.113901 0.420246 +0.478853 0.420580 +0.478224 0.420580 +0.113977 0.420226 +0.478224 0.420580 +0.478853 0.420580 +0.113901 0.420258 +0.478854 0.420580 +0.114012 0.420873 +0.113935 0.420856 +0.113935 0.420857 +0.114012 0.420872 +0.478224 0.420580 +0.113979 0.420267 +0.478224 0.420580 +0.478853 0.420580 +0.113904 0.420297 +0.478853 0.420580 +0.478224 0.420580 +0.478224 0.420580 +0.113979 0.420279 +0.478853 0.420580 +0.113903 0.420285 +0.478853 0.420580 +0.114013 0.420894 +0.113936 0.420889 +0.113936 0.420877 +0.114014 0.420907 +0.489049 0.036961 +0.105430 0.036961 +0.489049 0.420580 +0.105430 0.420580 +0.105430 0.036961 +0.489049 0.036961 +0.105430 0.420580 +0.489049 0.420580 +0.105430 0.036961 +0.489049 0.036961 +0.105430 0.420580 +0.489049 0.420580 +0.105430 0.036961 +0.489049 0.036961 +0.105430 0.420580 +0.489049 0.420580 +0.489049 0.036961 +0.105430 0.036961 +0.489049 0.420580 +0.105430 0.420580 +0.105430 0.036961 +0.489049 0.036961 +0.105430 0.420580 +0.489049 0.420580 +0.105430 0.036961 +0.489049 0.036961 +0.105430 0.420580 +0.489049 0.420580 +0.105430 0.036961 +0.489049 0.036961 +0.105430 0.420580 +0.489049 0.420580 +0.489049 0.036961 +0.105430 0.036961 +0.489049 0.420580 +0.105430 0.420580 +0.105430 0.036961 +0.489049 0.036961 +0.105430 0.420580 +0.489049 0.420580 +0.105430 0.036961 +0.489049 0.036961 +0.105430 0.420580 +0.489049 0.420580 +0.105430 0.036961 +0.489049 0.036961 +0.105430 0.420580 +0.489049 0.420580 +0.467426 0.244300 +0.467426 0.037231 +0.472758 0.037231 +0.326355 0.038969 +0.331690 0.038969 +0.331689 0.042629 +0.110811 0.041124 +0.110811 0.037364 +0.331690 0.047687 +0.326355 0.047687 +0.105832 0.246269 +0.472758 0.244300 +0.460786 0.037309 +0.466120 0.037309 +0.326357 0.042629 +0.466120 0.244456 +0.109592 0.246269 +0.318057 0.041124 +0.331690 0.043948 +0.109592 0.039023 +0.318057 0.037364 +0.105832 0.039023 +0.326355 0.043948 +0.460787 0.244456 +0.281892 0.257795 +0.278296 0.257795 +0.278296 0.050602 +0.281892 0.050602 +0.368191 0.050504 +0.364597 0.257639 +0.364599 0.050504 +0.368191 0.257582 +0.283385 0.257786 +0.283384 0.050612 +0.362543 0.050612 +0.362544 0.257786 +0.487685 0.120209 +0.487685 0.199272 +0.474133 0.116347 +0.474135 0.037227 +0.312987 0.338839 +0.105849 0.338894 +0.484093 0.199272 +0.484093 0.120209 +0.477727 0.116290 +0.477727 0.037227 +0.105794 0.259772 +0.312932 0.259717 +0.276913 0.257795 +0.273317 0.257795 +0.273317 0.050602 +0.276913 0.050602 +0.378149 0.050504 +0.374555 0.257639 +0.374557 0.050504 +0.189941 0.050612 +0.189941 0.257786 +0.110783 0.257786 +0.110782 0.050612 +0.477727 0.120209 +0.477727 0.199272 +0.378149 0.257582 +0.484091 0.116347 +0.484093 0.037227 +0.271218 0.050602 +0.271273 0.257740 +0.474135 0.199272 +0.474135 0.120209 +0.487685 0.116290 +0.487685 0.037227 +0.192150 0.257795 +0.192095 0.050658 +0.321285 0.042204 +0.321285 0.045800 +0.114092 0.045800 +0.114092 0.042204 +0.373170 0.050504 +0.369576 0.257639 +0.369578 0.050504 +0.312978 0.420207 +0.105804 0.420207 +0.105804 0.341048 +0.312978 0.341048 +0.482861 0.120209 +0.482861 0.199272 +0.479212 0.199274 +0.479212 0.120207 +0.373170 0.257582 +0.479112 0.116347 +0.479114 0.037227 +0.458811 0.244307 +0.379689 0.244363 +0.482706 0.116290 +0.482706 0.037227 +0.379634 0.037225 +0.458754 0.037227 +0.016244 0.715841 +0.756345 0.522332 +0.756346 0.715841 +0.016243 0.522332 +0.009526 0.061000 +0.749637 0.514493 +0.009526 0.514494 +0.749636 0.060999 +0.969477 0.480355 +0.969577 0.938728 +0.771464 0.938319 +0.771396 0.480706 +0.007192 0.039423 +0.751630 0.039423 +0.007192 0.498972 +0.751630 0.498972 +0.779207 0.499082 +0.779286 0.040707 +0.977371 0.041060 +0.977311 0.498670 +0.016243 0.911620 +0.756344 0.718111 +0.756344 0.911620 +0.016243 0.718111 +0.016244 0.715841 +0.756345 0.522332 +0.756346 0.715841 +0.016243 0.522332 +0.009526 0.061000 +0.749637 0.514493 +0.009526 0.514494 +0.749636 0.060999 +0.969477 0.480355 +0.969577 0.938728 +0.771464 0.938319 +0.771396 0.480706 +0.007192 0.039423 +0.751630 0.039423 +0.007192 0.498972 +0.751630 0.498972 +0.779207 0.499082 +0.779286 0.040707 +0.977371 0.041060 +0.977311 0.498670 +0.016243 0.911620 +0.756344 0.718111 +0.756344 0.911620 +0.016243 0.718111 +0.016244 0.715841 +0.756345 0.522332 +0.756346 0.715841 +0.016243 0.522332 +0.009526 0.061000 +0.749637 0.514493 +0.009526 0.514494 +0.749636 0.060999 +0.969477 0.480355 +0.969577 0.938728 +0.771464 0.938319 +0.771396 0.480706 +0.007192 0.039423 +0.751630 0.039423 +0.007192 0.498972 +0.751630 0.498972 +0.779207 0.499082 +0.779286 0.040707 +0.977371 0.041060 +0.977311 0.498670 +0.016243 0.911620 +0.756344 0.718111 +0.756344 0.911620 +0.016243 0.718111 +0.486957 0.692024 +0.027038 0.424800 +0.486954 0.424800 +0.027038 0.692024 +0.506996 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.966910 0.036168 +0.029544 0.043430 +0.489461 0.415225 +0.029544 0.415224 +0.489461 0.035380 +0.029544 0.035380 +0.037422 0.971548 +0.407335 0.698761 +0.409054 0.971742 +0.039211 0.698717 +0.965462 0.676852 +0.505546 0.676852 +0.505546 0.409621 +0.965459 0.409621 +0.914572 0.962378 +0.922325 0.705031 +0.922325 0.962378 +0.570344 0.705031 +0.570343 0.962377 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.206126 +1.014936 0.691973 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.206126 +0.170286 0.691973 +0.229772 0.173002 +0.933648 0.102615 +0.933648 0.173002 +0.229772 0.102615 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.206126 +1.014936 0.691973 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.206126 +0.170286 0.691973 +0.229772 0.173002 +0.933648 0.102615 +0.933648 0.173002 +0.229772 0.102615 +0.486957 0.692024 +0.027038 0.424800 +0.486954 0.424800 +0.027038 0.692024 +0.506996 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.966910 0.036168 +0.029544 0.043430 +0.489461 0.415225 +0.029544 0.415224 +0.489461 0.035380 +0.029544 0.035380 +0.037422 0.971548 +0.407335 0.698761 +0.409054 0.971742 +0.039211 0.698717 +0.965462 0.676852 +0.505546 0.676852 +0.505546 0.409621 +0.965459 0.409621 +0.914572 0.962378 +0.922325 0.705031 +0.922325 0.962378 +0.570344 0.705031 +0.570343 0.962377 +0.016244 0.715841 +0.756345 0.522332 +0.756346 0.715841 +0.016243 0.522332 +0.009526 0.061000 +0.749637 0.514493 +0.009526 0.514494 +0.749636 0.060999 +0.969477 0.480355 +0.969577 0.938728 +0.771464 0.938319 +0.771396 0.480706 +0.007192 0.039423 +0.751630 0.039423 +0.007192 0.498972 +0.751630 0.498972 +0.779207 0.499082 +0.779286 0.040707 +0.977371 0.041060 +0.977311 0.498670 +0.016243 0.911620 +0.756344 0.718111 +0.756344 0.911620 +0.016243 0.718111 +0.016244 0.715841 +0.756345 0.522332 +0.756346 0.715841 +0.016243 0.522332 +0.009526 0.061000 +0.749637 0.514493 +0.009526 0.514494 +0.749636 0.060999 +0.969477 0.480355 +0.969577 0.938728 +0.771464 0.938319 +0.771396 0.480706 +0.007192 0.039423 +0.751630 0.039423 +0.007192 0.498972 +0.751630 0.498972 +0.779207 0.499082 +0.779286 0.040707 +0.977371 0.041060 +0.977311 0.498670 +0.756344 0.911620 +0.016243 0.718111 +0.756344 0.718111 +0.016243 0.911620 +0.016244 0.715841 +0.756345 0.522332 +0.756346 0.715841 +0.016243 0.522332 +0.009526 0.061000 +0.749637 0.514493 +0.009526 0.514494 +0.749636 0.060999 +0.969477 0.480355 +0.969577 0.938728 +0.771464 0.938319 +0.771396 0.480706 +0.007192 0.039423 +0.751630 0.039423 +0.007192 0.498972 +0.751630 0.498972 +0.779207 0.499082 +0.779286 0.040707 +0.977371 0.041060 +0.977311 0.498670 +0.016243 0.911620 +0.756344 0.718111 +0.756344 0.911620 +0.016243 0.718111 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.206126 +1.014936 0.691973 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.206126 +0.170286 0.691973 +0.229772 0.173002 +0.933648 0.102615 +0.933648 0.173002 +0.229772 0.102615 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.206126 +1.014936 0.691973 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.206126 +0.170286 0.691973 +0.229772 0.173002 +0.933648 0.102615 +0.933648 0.173002 +0.229772 0.102615 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.206126 +1.014936 0.691973 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.691973 +0.170286 0.206126 +0.933648 0.173002 +0.229772 0.173002 +0.229772 0.102615 +0.933648 0.102615 +0.016244 0.715841 +0.756345 0.522332 +0.756346 0.715841 +0.016243 0.522332 +0.009526 0.061000 +0.749637 0.514493 +0.009526 0.514494 +0.749636 0.060999 +0.969477 0.480355 +0.969577 0.938728 +0.771464 0.938319 +0.771396 0.480706 +0.007192 0.039423 +0.751630 0.039423 +0.007192 0.498972 +0.751630 0.498972 +0.779207 0.499082 +0.779286 0.040707 +0.977371 0.041060 +0.977311 0.498670 +0.016243 0.911620 +0.756344 0.718111 +0.756344 0.911620 +0.016243 0.718111 +0.016244 0.715841 +0.756345 0.522332 +0.756346 0.715841 +0.016243 0.522332 +0.009526 0.061000 +0.749637 0.514493 +0.009526 0.514494 +0.749636 0.060999 +0.969477 0.480355 +0.969577 0.938728 +0.771464 0.938319 +0.771396 0.480706 +0.007192 0.039423 +0.751630 0.039423 +0.007192 0.498972 +0.751630 0.498972 +0.779207 0.499082 +0.779286 0.040707 +0.977371 0.041060 +0.977311 0.498670 +0.756344 0.911620 +0.016243 0.718111 +0.756344 0.718111 +0.016243 0.911620 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.206126 +1.014936 0.691973 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.691973 +0.170286 0.206126 +0.933648 0.173002 +0.229772 0.173002 +0.229772 0.102615 +0.933648 0.102615 +0.486957 0.692024 +0.027038 0.424800 +0.486954 0.424800 +0.027038 0.692024 +0.506996 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.966910 0.036168 +0.029544 0.043430 +0.489461 0.415225 +0.029544 0.415224 +0.489461 0.035380 +0.029544 0.035380 +0.037422 0.971548 +0.407335 0.698761 +0.409054 0.971742 +0.039211 0.698717 +0.965462 0.676852 +0.505546 0.676852 +0.505546 0.409621 +0.965459 0.409621 +0.914572 0.962378 +0.922325 0.705031 +0.922325 0.962378 +0.570344 0.705031 +0.570343 0.962377 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.206126 +1.014936 0.691973 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.206126 +0.170286 0.691973 +0.229772 0.173002 +0.933648 0.102615 +0.933648 0.173002 +0.229772 0.102615 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.206126 +1.014936 0.691973 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.206126 +0.170286 0.691973 +0.229772 0.173002 +0.933648 0.102615 +0.933648 0.173002 +0.229772 0.102615 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.206126 +1.014936 0.691973 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.691973 +0.170286 0.206126 +0.933648 0.173002 +0.229772 0.173002 +0.229772 0.102615 +0.933648 0.102615 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.206126 +1.014936 0.691973 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.691973 +0.170286 0.206126 +0.229772 0.173002 +0.933648 0.102615 +0.933648 0.173002 +0.229772 0.102615 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.206126 +1.014936 0.691973 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.206126 +0.170286 0.691973 +0.229772 0.173002 +0.933648 0.102615 +0.933648 0.173002 +0.229772 0.102615 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.206126 +1.014936 0.691973 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.206126 +0.170286 0.691973 +0.229772 0.173002 +0.933648 0.102615 +0.933648 0.173002 +0.229772 0.102615 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.206126 +1.014936 0.691973 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.691973 +0.170286 0.206126 +0.933648 0.173002 +0.229772 0.173002 +0.229772 0.102615 +0.933648 0.102615 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.206126 +1.014936 0.691973 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.691973 +0.170286 0.206126 +0.229772 0.173002 +0.933648 0.102615 +0.933648 0.173002 +0.229772 0.102615 +0.486957 0.692024 +0.027038 0.424800 +0.486954 0.424800 +0.027038 0.692024 +0.506996 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.966910 0.036168 +0.029544 0.043430 +0.489461 0.415225 +0.029544 0.415224 +0.489461 0.035380 +0.029544 0.035380 +0.037422 0.971548 +0.407335 0.698761 +0.409054 0.971742 +0.039211 0.698717 +0.965462 0.676852 +0.505546 0.676852 +0.505546 0.409621 +0.965459 0.409621 +0.914572 0.962378 +0.922325 0.705031 +0.922325 0.962378 +0.570344 0.705031 +0.570343 0.962377 + + + + + + + + + + + +

5 0 2 3 1 10 2 2 0 2 3 0 4 4 1 5 5 2 0 6 7 6 7 3 2 8 9 2 9 9 3 10 12 0 11 7 1 12 8 0 13 4 3 14 22 3 15 22 5 16 13 1 17 8 7 18 15 1 19 5 5 20 23 5 21 23 4 22 21 7 23 15 6 24 14 7 25 6 4 26 11 4 27 11 2 28 20 6 29 14 9 30 17 8 31 24 6 32 3 6 33 3 0 34 7 9 35 17 11 36 19 9 37 25 0 38 4 0 39 4 1 40 8 11 41 19 10 42 18 11 43 27 1 44 5 1 45 5 7 46 15 10 47 18 8 48 16 10 49 26 7 50 6 7 51 6 6 52 14 8 53 16 13 54 28 12 55 29 8 56 24 8 57 24 9 58 17 13 59 28 15 60 30 13 61 31 9 62 25 9 63 25 11 64 19 15 65 30 14 66 32 15 67 33 11 68 27 11 69 27 10 70 18 14 71 32 12 72 34 14 73 35 10 74 26 10 75 26 8 76 16 12 77 34 12 78 34 13 79 28 15 80 30 15 81 30 14 82 32 12 83 34 21 84 38 19 85 46 18 86 36 18 87 36 20 88 37 21 89 38 16 90 43 22 91 39 18 92 45 18 93 45 19 94 48 16 95 43 17 96 44 16 97 40 19 98 58 19 99 58 21 100 49 17 101 44 23 102 51 17 103 41 21 104 59 21 105 59 20 106 57 23 107 51 22 108 50 23 109 42 20 110 47 20 111 47 18 112 56 22 113 50 25 114 53 24 115 60 22 116 39 22 117 39 16 118 43 25 119 53 27 120 55 25 121 61 16 122 40 16 123 40 17 124 44 27 125 55 26 126 54 27 127 63 17 128 41 17 129 41 23 130 51 26 131 54 24 132 52 26 133 62 23 134 42 23 135 42 22 136 50 24 137 52 29 138 64 28 139 65 24 140 60 24 141 60 25 142 53 29 143 64 31 144 66 29 145 67 25 146 61 25 147 61 27 148 55 31 149 66 30 150 68 31 151 69 27 152 63 27 153 63 26 154 54 30 155 68 28 156 70 30 157 71 26 158 62 26 159 62 24 160 52 28 161 70 28 162 70 29 163 64 31 164 66 31 165 66 30 166 68 28 167 70 37 168 74 35 169 82 34 170 72 34 171 72 36 172 73 37 173 74 32 174 79 38 175 75 34 176 81 34 177 81 35 178 84 32 179 79 33 180 80 32 181 76 35 182 94 35 183 94 37 184 85 33 185 80 39 186 87 33 187 77 37 188 95 37 189 95 36 190 93 39 191 87 38 192 86 39 193 78 36 194 83 36 195 83 34 196 92 38 197 86 41 198 89 40 199 96 38 200 75 38 201 75 32 202 79 41 203 89 43 204 91 41 205 97 32 206 76 32 207 76 33 208 80 43 209 91 42 210 90 43 211 99 33 212 77 33 213 77 39 214 87 42 215 90 40 216 88 42 217 98 39 218 78 39 219 78 38 220 86 40 221 88 45 222 100 44 223 101 40 224 96 40 225 96 41 226 89 45 227 100 47 228 102 45 229 103 41 230 97 41 231 97 43 232 91 47 233 102 46 234 104 47 235 105 43 236 99 43 237 99 42 238 90 46 239 104 44 240 106 46 241 107 42 242 98 42 243 98 40 244 88 44 245 106 44 246 106 45 247 100 47 248 102 47 249 102 46 250 104 44 251 106 53 252 110 51 253 118 50 254 108 50 255 108 52 256 109 53 257 110 48 258 115 54 259 111 50 260 117 50 261 117 51 262 120 48 263 115 49 264 116 48 265 112 51 266 130 51 267 130 53 268 121 49 269 116 55 270 123 49 271 113 53 272 131 53 273 131 52 274 129 55 275 123 54 276 122 55 277 114 52 278 119 52 279 119 50 280 128 54 281 122 57 282 125 56 283 132 54 284 111 54 285 111 48 286 115 57 287 125 59 288 127 57 289 133 48 290 112 48 291 112 49 292 116 59 293 127 58 294 126 59 295 135 49 296 113 49 297 113 55 298 123 58 299 126 56 300 124 58 301 134 55 302 114 55 303 114 54 304 122 56 305 124 61 306 136 60 307 137 56 308 132 56 309 132 57 310 125 61 311 136 63 312 138 61 313 139 57 314 133 57 315 133 59 316 127 63 317 138 62 318 140 63 319 141 59 320 135 59 321 135 58 322 126 62 323 140 60 324 142 62 325 143 58 326 134 58 327 134 56 328 124 60 329 142 60 330 142 61 331 136 63 332 138 63 333 138 62 334 140 60 335 142 69 336 146 67 337 154 66 338 144 66 339 144 68 340 145 69 341 146 64 342 151 70 343 147 66 344 153 66 345 153 67 346 156 64 347 151 65 348 152 64 349 148 67 350 166 67 351 166 69 352 157 65 353 152 71 354 159 65 355 149 69 356 167 69 357 167 68 358 165 71 359 159 70 360 158 71 361 150 68 362 155 68 363 155 66 364 164 70 365 158 73 366 161 72 367 168 70 368 147 70 369 147 64 370 151 73 371 161 75 372 163 73 373 169 64 374 148 64 375 148 65 376 152 75 377 163 74 378 162 75 379 171 65 380 149 65 381 149 71 382 159 74 383 162 72 384 160 74 385 170 71 386 150 71 387 150 70 388 158 72 389 160 77 390 172 76 391 173 72 392 168 72 393 168 73 394 161 77 395 172 79 396 174 77 397 175 73 398 169 73 399 169 75 400 163 79 401 174 78 402 176 79 403 177 75 404 171 75 405 171 74 406 162 78 407 176 76 408 178 78 409 179 74 410 170 74 411 170 72 412 160 76 413 178 76 414 178 77 415 172 79 416 174 79 417 174 78 418 176 76 419 178 85 420 182 83 421 190 82 422 180 82 423 180 84 424 181 85 425 182 80 426 187 86 427 183 82 428 189 82 429 189 83 430 192 80 431 187 81 432 188 80 433 184 83 434 202 83 435 202 85 436 193 81 437 188 87 438 195 81 439 185 85 440 203 85 441 203 84 442 201 87 443 195 86 444 194 87 445 186 84 446 191 84 447 191 82 448 200 86 449 194 89 450 197 88 451 204 86 452 183 86 453 183 80 454 187 89 455 197 91 456 199 89 457 205 80 458 184 80 459 184 81 460 188 91 461 199 90 462 198 91 463 207 81 464 185 81 465 185 87 466 195 90 467 198 88 468 196 90 469 206 87 470 186 87 471 186 86 472 194 88 473 196 93 474 208 92 475 209 88 476 204 88 477 204 89 478 197 93 479 208 95 480 210 93 481 211 89 482 205 89 483 205 91 484 199 95 485 210 94 486 212 95 487 213 91 488 207 91 489 207 90 490 198 94 491 212 92 492 214 94 493 215 90 494 206 90 495 206 88 496 196 92 497 214 92 498 214 93 499 208 95 500 210 95 501 210 94 502 212 92 503 214 96 504 216 99 505 218 97 506 217 97 507 217 102 508 228 96 509 216 98 510 219 101 511 221 99 512 220 99 513 220 96 514 229 98 515 219 103 516 222 101 517 224 98 518 231 98 519 231 100 520 223 103 521 222 102 522 225 97 523 227 103 524 226 103 525 226 100 526 230 102 527 225 105 528 234 111 529 244 104 530 232 104 531 232 106 532 233 105 533 234 104 534 245 107 535 237 108 536 235 108 537 235 106 538 236 104 539 245 107 540 247 109 541 240 110 542 238 110 543 238 108 544 239 107 545 247 109 546 246 111 547 243 105 548 241 105 549 241 110 550 242 109 551 246 119 552 260 113 553 250 114 554 248 114 555 248 112 556 249 119 557 260 113 558 261 115 559 253 117 560 251 117 561 251 114 562 252 113 563 261 117 564 256 115 565 263 116 566 254 116 567 254 118 568 255 117 569 256 116 570 262 119 571 259 112 572 257 112 573 257 118 574 258 116 575 262 120 576 264 123 577 265 121 578 266 121 579 266 126 580 276 120 581 264 122 582 267 124 583 268 123 584 269 123 585 269 120 586 277 122 587 267 127 588 270 124 589 271 122 590 279 122 591 279 125 592 272 127 593 270 126 594 273 121 595 274 127 596 275 127 597 275 125 598 278 126 599 273 129 600 282 135 601 292 128 602 280 128 603 280 130 604 281 129 605 282 128 606 293 131 607 285 132 608 283 132 609 283 130 610 284 128 611 293 131 612 295 133 613 288 134 614 286 134 615 286 132 616 287 131 617 295 133 618 294 135 619 291 129 620 289 129 621 289 134 622 290 133 623 294 143 624 308 137 625 298 138 626 296 138 627 296 136 628 297 143 629 308 137 630 309 139 631 301 141 632 299 141 633 299 138 634 300 137 635 309 141 636 304 139 637 311 140 638 302 140 639 302 142 640 303 141 641 304 140 642 310 143 643 307 136 644 305 136 645 305 142 646 306 140 647 310 144 648 312 147 649 313 145 650 314 145 651 314 150 652 324 144 653 312 146 654 315 148 655 316 147 656 317 147 657 317 144 658 325 146 659 315 151 660 318 148 661 319 146 662 327 146 663 327 149 664 320 151 665 318 150 666 321 145 667 322 151 668 323 151 669 323 149 670 326 150 671 321 153 672 330 159 673 340 152 674 328 152 675 328 154 676 329 153 677 330 152 678 341 155 679 333 156 680 331 156 681 331 154 682 332 152 683 341 155 684 343 157 685 336 158 686 334 158 687 334 156 688 335 155 689 343 157 690 342 159 691 339 153 692 337 153 693 337 158 694 338 157 695 342 167 696 356 161 697 346 162 698 344 162 699 344 160 700 345 167 701 356 161 702 357 163 703 349 165 704 347 165 705 347 162 706 348 161 707 357 165 708 352 163 709 359 164 710 350 164 711 350 166 712 351 165 713 352 164 714 358 167 715 355 160 716 353 160 717 353 166 718 354 164 719 358 168 720 360 170 721 362 171 722 363 171 723 363 169 724 361 168 725 360 172 726 364 173 727 365 175 728 367 175 729 367 174 730 366 172 731 364 168 732 368 169 733 369 173 734 371 173 735 371 172 736 370 168 737 368 171 738 372 170 739 373 174 740 375 174 741 375 175 742 374 171 743 372 176 744 376 178 745 378 179 746 379 179 747 379 177 748 377 176 749 376 180 750 380 181 751 381 183 752 383 183 753 383 182 754 382 180 755 380 176 756 384 177 757 385 181 758 387 181 759 387 180 760 386 176 761 384 179 762 388 178 763 389 182 764 391 182 765 391 183 766 390 179 767 388 184 768 392 186 769 394 187 770 395 187 771 395 185 772 393 184 773 392 188 774 396 189 775 397 191 776 399 191 777 399 190 778 398 188 779 396 184 780 400 185 781 401 189 782 403 189 783 403 188 784 402 184 785 400 187 786 404 186 787 405 190 788 407 190 789 407 191 790 406 187 791 404 197 792 410 195 793 419 194 794 408 194 795 408 196 796 409 197 797 410 193 798 423 199 799 431 198 800 420 198 801 420 192 802 421 193 803 423 192 804 413 198 805 422 194 806 411 194 807 411 195 808 412 192 809 413 193 810 415 192 811 428 195 812 425 195 813 425 197 814 414 193 815 415 199 816 416 193 817 417 197 818 430 197 819 430 196 820 426 199 821 416 198 822 418 199 823 429 196 824 427 196 825 427 194 826 424 198 827 418 205 828 442 203 829 443 202 830 440 202 831 440 204 832 441 205 833 442 201 834 449 207 835 454 206 836 455 206 837 455 200 838 448 201 839 449 200 840 450 206 841 451 202 842 444 202 843 444 203 844 445 200 845 450 201 846 433 200 847 434 203 848 435 203 849 435 205 850 432 201 851 433 207 852 446 201 853 447 205 854 453 205 855 453 204 856 452 207 857 446 206 858 437 207 859 438 204 860 436 204 861 436 202 862 439 206 863 437 213 864 465 211 865 466 210 866 463 210 867 463 212 868 464 213 869 465 209 870 473 215 871 478 214 872 479 214 873 479 208 874 472 209 875 473 208 876 474 214 877 475 210 878 467 210 879 467 211 880 468 208 881 474 209 882 457 208 883 458 211 884 459 211 885 459 213 886 456 209 887 457 215 888 470 209 889 471 213 890 477 213 891 477 212 892 476 215 893 470 214 894 461 215 895 462 212 896 460 212 897 460 210 898 469 214 899 461 220 900 489 218 901 490 216 902 487 216 903 487 217 904 488 220 905 489 221 906 498 222 907 499 223 908 502 223 909 502 219 910 503 221 911 498 219 912 493 223 913 494 216 914 491 216 915 491 218 916 492 219 917 493 221 918 481 219 919 482 218 920 483 218 921 483 220 922 480 221 923 481 222 924 496 221 925 497 220 926 501 220 927 501 217 928 500 222 929 496 223 930 485 222 931 486 217 932 484 217 933 484 216 934 495 223 935 485

+

+

248 936 576 249 937 577 250 938 578 249 939 577 248 940 576 251 941 579 252 942 580 250 943 581 249 944 582 250 945 581 252 946 580 253 947 583 254 948 584 251 949 585 248 950 586 251 951 585 254 952 584 255 953 587 256 954 588 255 955 587 254 956 584 255 957 589 249 958 590 251 959 591 249 960 590 255 961 589 252 962 592 255 963 593 256 964 594 253 965 595 255 966 593 253 967 595 252 968 596 254 969 597 253 970 598 256 971 599 253 972 598 254 973 597 250 974 600 254 975 597 248 976 601 250 977 600 273 978 638 274 979 639 275 980 640 274 981 639 273 982 638 276 983 641 277 984 642 275 985 643 274 986 644 275 987 643 277 988 642 278 989 645 279 990 646 276 991 647 273 992 648 276 993 647 279 994 646 280 995 649 281 996 650 280 997 649 279 998 646 280 999 651 274 1000 652 276 1001 653 274 1002 652 280 1003 651 277 1004 654 280 1005 655 281 1006 656 278 1007 657 280 1008 655 278 1009 657 277 1010 658 279 1011 659 278 1012 660 281 1013 661 278 1014 660 279 1015 659 275 1016 662 279 1017 659 273 1018 663 275 1019 662 354 1020 856 355 1021 857 356 1022 858 355 1023 857 354 1024 856 357 1025 859 358 1026 860 356 1027 861 355 1028 862 356 1029 861 358 1030 860 359 1031 863 360 1032 864 357 1033 865 354 1034 866 357 1035 865 360 1036 864 361 1037 867 362 1038 868 361 1039 867 360 1040 864 361 1041 869 355 1042 870 357 1043 871 355 1044 870 361 1045 869 358 1046 872 361 1047 873 362 1048 874 359 1049 875 361 1050 873 359 1051 875 358 1052 876 360 1053 877 359 1054 878 362 1055 879 359 1056 878 360 1057 877 356 1058 880 360 1059 877 354 1060 881 356 1061 880 427 1062 1026 428 1063 1027 429 1064 1028 428 1065 1027 427 1066 1026 430 1067 1029 431 1068 1030 429 1069 1031 428 1070 1032 429 1071 1031 431 1072 1030 432 1073 1033 433 1074 1034 430 1075 1035 427 1076 1036 430 1077 1035 433 1078 1034 434 1079 1037 435 1080 1038 434 1081 1037 433 1082 1034 434 1083 1039 428 1084 1040 430 1085 1041 428 1086 1040 434 1087 1039 431 1088 1042 434 1089 1043 435 1090 1044 432 1091 1045 434 1092 1043 432 1093 1045 431 1094 1046 433 1095 1047 432 1096 1048 435 1097 1049 432 1098 1048 433 1099 1047 429 1100 1050 433 1101 1047 427 1102 1051 429 1103 1050

+

224 1104 504 225 1105 505 226 1106 506 225 1107 505 224 1108 504 227 1109 507 225 1110 508 228 1111 509 229 1112 510 228 1113 509 225 1114 508 227 1115 511 230 1116 512 226 1117 513 225 1118 514 230 1119 512 225 1120 514 229 1121 515 230 1122 516 231 1123 517 226 1124 518 231 1125 517 224 1126 519 226 1127 518 224 1128 520 231 1129 521 228 1130 522 224 1131 520 228 1132 522 227 1133 523 230 1134 524 228 1135 525 231 1136 526 228 1137 525 230 1138 524 229 1139 527 232 1140 528 233 1141 529 234 1142 530 233 1143 529 232 1144 528 235 1145 531 233 1146 532 236 1147 533 237 1148 534 236 1149 533 233 1150 532 235 1151 535 238 1152 536 234 1153 537 233 1154 538 238 1155 536 233 1156 538 237 1157 539 238 1158 540 239 1159 541 234 1160 542 239 1161 541 232 1162 543 234 1163 542 232 1164 544 239 1165 545 236 1166 546 232 1167 544 236 1168 546 235 1169 547 238 1170 548 236 1171 549 239 1172 550 236 1173 549 238 1174 548 237 1175 551 240 1176 552 241 1177 553 242 1178 554 241 1179 553 240 1180 552 243 1181 555 241 1182 556 244 1183 557 245 1184 558 244 1185 557 241 1186 556 243 1187 559 246 1188 560 242 1189 561 241 1190 562 246 1191 560 241 1192 562 245 1193 563 246 1194 564 247 1195 565 242 1196 566 247 1197 565 240 1198 567 242 1199 566 240 1200 568 247 1201 569 244 1202 570 240 1203 568 244 1204 570 243 1205 571 246 1206 572 244 1207 573 247 1208 574 244 1209 573 246 1210 572 245 1211 575 282 1212 664 283 1213 665 284 1214 666 283 1215 665 282 1216 664 285 1217 667 283 1218 668 286 1219 669 287 1220 670 286 1221 669 283 1222 668 285 1223 671 288 1224 672 284 1225 673 283 1226 674 288 1227 672 283 1228 674 287 1229 675 288 1230 676 289 1231 677 284 1232 678 289 1233 677 282 1234 679 284 1235 678 282 1236 680 289 1237 681 286 1238 682 282 1239 680 286 1240 682 285 1241 683 288 1242 684 286 1243 685 289 1244 686 286 1245 685 288 1246 684 287 1247 687 290 1248 688 291 1249 689 292 1250 690 291 1251 689 290 1252 688 293 1253 691 291 1254 692 294 1255 693 295 1256 694 294 1257 693 291 1258 692 293 1259 695 296 1260 696 292 1261 697 291 1262 698 296 1263 696 291 1264 698 295 1265 699 296 1266 700 297 1267 701 292 1268 702 297 1269 701 290 1270 703 292 1271 702 290 1272 704 297 1273 705 294 1274 706 290 1275 704 294 1276 706 293 1277 707 297 1278 708 295 1279 709 294 1280 710 295 1281 709 297 1282 708 296 1283 711 298 1284 712 299 1285 713 300 1286 714 299 1287 713 298 1288 712 301 1289 715 299 1290 716 302 1291 717 303 1292 718 302 1293 717 299 1294 716 301 1295 719 304 1296 720 300 1297 721 299 1298 722 304 1299 720 299 1300 722 303 1301 723 304 1302 724 305 1303 725 300 1304 726 305 1305 725 298 1306 727 300 1307 726 298 1308 728 305 1309 729 302 1310 730 298 1311 728 302 1312 730 301 1313 731 304 1314 732 302 1315 733 305 1316 734 302 1317 733 304 1318 732 303 1319 735 330 1320 790 331 1321 791 332 1322 792 331 1323 791 330 1324 790 333 1325 793 331 1326 794 334 1327 795 335 1328 796 334 1329 795 331 1330 794 333 1331 797 336 1332 798 332 1333 799 331 1334 800 336 1335 798 331 1336 800 335 1337 801 336 1338 802 337 1339 803 332 1340 804 337 1341 803 330 1342 805 332 1343 804 330 1344 806 337 1345 807 334 1346 808 330 1347 806 334 1348 808 333 1349 809 336 1350 810 334 1351 811 337 1352 812 334 1353 811 336 1354 810 335 1355 813 338 1356 814 339 1357 815 340 1358 816 339 1359 815 338 1360 814 341 1361 817 339 1362 818 342 1363 819 343 1364 820 342 1365 819 339 1366 818 341 1367 821 344 1368 822 340 1369 823 339 1370 824 344 1371 822 339 1372 824 343 1373 825 344 1374 826 345 1375 827 340 1376 828 345 1377 827 338 1378 829 340 1379 828 338 1380 830 345 1381 831 342 1382 832 338 1383 830 342 1384 832 341 1385 833 345 1386 834 343 1387 835 342 1388 836 343 1389 835 345 1390 834 344 1391 837

+

257 1392 602 258 1393 603 259 1394 604 258 1395 603 257 1396 602 260 1397 605 261 1398 606 262 1399 607 263 1400 608 262 1401 607 261 1402 606 264 1403 609 262 1404 607 264 1405 609 260 1406 610 262 1407 607 260 1408 610 257 1409 611 263 1410 608 262 1411 607 257 1412 612 263 1413 608 257 1414 612 259 1415 613 263 1416 608 258 1417 614 261 1418 606 258 1419 614 263 1420 608 259 1421 615 261 1422 616 260 1423 617 264 1424 618 260 1425 617 261 1426 616 258 1427 619 265 1428 620 266 1429 621 267 1430 622 266 1431 621 265 1432 620 268 1433 623 269 1434 624 270 1435 625 271 1436 626 270 1437 625 269 1438 624 272 1439 627 270 1440 625 272 1441 627 268 1442 628 270 1443 625 268 1444 628 265 1445 629 271 1446 626 270 1447 625 265 1448 630 271 1449 626 265 1450 630 267 1451 631 271 1452 626 266 1453 632 269 1454 624 266 1455 632 271 1456 626 267 1457 633 269 1458 634 268 1459 635 272 1460 636 268 1461 635 269 1462 634 266 1463 637 306 1464 736 307 1465 737 308 1466 738 307 1467 737 306 1468 736 309 1469 739 310 1470 740 311 1471 741 312 1472 742 311 1473 741 310 1474 740 313 1475 743 311 1476 741 313 1477 743 309 1478 744 311 1479 741 309 1480 744 306 1481 745 312 1482 742 311 1483 741 306 1484 746 312 1485 742 306 1486 746 308 1487 747 312 1488 742 307 1489 748 310 1490 740 307 1491 748 312 1492 742 308 1493 749 310 1494 750 309 1495 751 313 1496 752 309 1497 751 310 1498 750 307 1499 753 314 1500 754 315 1501 755 316 1502 756 315 1503 755 314 1504 754 317 1505 757 318 1506 758 319 1507 759 320 1508 760 319 1509 759 318 1510 758 321 1511 761 319 1512 759 321 1513 761 317 1514 762 319 1515 759 317 1516 762 314 1517 763 320 1518 760 319 1519 759 314 1520 764 320 1521 760 314 1522 764 316 1523 765 320 1524 760 315 1525 766 318 1526 758 315 1527 766 320 1528 760 316 1529 767 318 1530 768 317 1531 769 321 1532 770 317 1533 769 318 1534 768 315 1535 771 322 1536 772 323 1537 773 324 1538 774 323 1539 773 322 1540 772 325 1541 775 326 1542 776 327 1543 777 328 1544 778 327 1545 777 326 1546 776 329 1547 779 327 1548 777 329 1549 779 325 1550 780 327 1551 777 325 1552 780 322 1553 781 328 1554 778 327 1555 777 322 1556 782 328 1557 778 322 1558 782 324 1559 783 326 1560 776 328 1561 778 324 1562 784 326 1563 776 324 1564 784 323 1565 785 329 1566 786 326 1567 787 323 1568 788 329 1569 786 323 1570 788 325 1571 789 346 1572 838 347 1573 839 348 1574 840 347 1575 839 346 1576 838 349 1577 841 350 1578 842 351 1579 843 352 1580 844 351 1581 843 350 1582 842 353 1583 845 351 1584 843 353 1585 845 349 1586 846 351 1587 843 349 1588 846 346 1589 847 352 1590 844 351 1591 843 346 1592 848 352 1593 844 346 1594 848 348 1595 849 350 1596 842 352 1597 844 348 1598 850 350 1599 842 348 1600 850 347 1601 851 353 1602 852 350 1603 853 347 1604 854 353 1605 852 347 1606 854 349 1607 855 363 1608 882 364 1609 883 365 1610 884 364 1611 883 363 1612 882 366 1613 885 367 1614 886 368 1615 887 369 1616 888 368 1617 887 367 1618 886 370 1619 889 368 1620 887 370 1621 889 366 1622 890 368 1623 887 366 1624 890 363 1625 891 369 1626 888 368 1627 887 363 1628 892 369 1629 888 363 1630 892 365 1631 893 369 1632 888 364 1633 894 367 1634 886 364 1635 894 369 1636 888 365 1637 895 367 1638 896 366 1639 897 370 1640 898 366 1641 897 367 1642 896 364 1643 899 371 1644 900 372 1645 901 373 1646 902 372 1647 901 371 1648 900 374 1649 903 375 1650 904 376 1651 905 377 1652 906 376 1653 905 375 1654 904 378 1655 907 376 1656 905 378 1657 907 374 1658 908 376 1659 905 374 1660 908 371 1661 909 377 1662 906 376 1663 905 371 1664 910 377 1665 906 371 1666 910 373 1667 911 377 1668 906 372 1669 912 375 1670 904 372 1671 912 377 1672 906 373 1673 913 375 1674 914 374 1675 915 378 1676 916 374 1677 915 375 1678 914 372 1679 917 379 1680 918 380 1681 919 381 1682 920 380 1683 919 379 1684 918 382 1685 921 383 1686 922 384 1687 923 385 1688 924 384 1689 923 383 1690 922 386 1691 925 384 1692 923 386 1693 925 382 1694 926 384 1695 923 382 1696 926 379 1697 927 385 1698 924 384 1699 923 379 1700 928 385 1701 924 379 1702 928 381 1703 929 383 1704 922 385 1705 924 381 1706 930 383 1707 922 381 1708 930 380 1709 931 386 1710 932 383 1711 933 380 1712 934 386 1713 932 380 1714 934 382 1715 935 387 1716 936 388 1717 937 389 1718 938 388 1719 937 387 1720 936 390 1721 939 391 1722 940 392 1723 941 393 1724 942 392 1725 941 391 1726 940 394 1727 943 392 1728 941 394 1729 943 390 1730 944 392 1731 941 390 1732 944 387 1733 945 393 1734 942 392 1735 941 387 1736 946 393 1737 942 387 1738 946 389 1739 947 391 1740 940 393 1741 942 389 1742 948 391 1743 940 389 1744 948 388 1745 949 391 1746 950 390 1747 951 394 1748 952 390 1749 951 391 1750 950 388 1751 953 395 1752 954 396 1753 955 397 1754 956 396 1755 955 395 1756 954 398 1757 957 399 1758 958 400 1759 959 401 1760 960 400 1761 959 399 1762 958 402 1763 961 400 1764 959 402 1765 961 398 1766 962 400 1767 959 398 1768 962 395 1769 963 401 1770 960 400 1771 959 395 1772 964 401 1773 960 395 1774 964 397 1775 965 401 1776 960 396 1777 966 399 1778 958 396 1779 966 401 1780 960 397 1781 967 399 1782 968 398 1783 969 402 1784 970 398 1785 969 399 1786 968 396 1787 971 403 1788 972 404 1789 973 405 1790 974 404 1791 973 403 1792 972 406 1793 975 407 1794 976 408 1795 977 409 1796 978 408 1797 977 407 1798 976 410 1799 979 408 1800 977 410 1801 979 406 1802 980 408 1803 977 406 1804 980 403 1805 981 409 1806 978 408 1807 977 403 1808 982 409 1809 978 403 1810 982 405 1811 983 409 1812 978 404 1813 984 407 1814 976 404 1815 984 409 1816 978 405 1817 985 407 1818 986 406 1819 987 410 1820 988 406 1821 987 407 1822 986 404 1823 989 411 1824 990 412 1825 991 413 1826 992 412 1827 991 411 1828 990 414 1829 993 415 1830 994 416 1831 995 417 1832 996 416 1833 995 415 1834 994 418 1835 997 416 1836 995 418 1837 997 414 1838 998 416 1839 995 414 1840 998 411 1841 999 417 1842 996 416 1843 995 411 1844 1000 417 1845 996 411 1846 1000 413 1847 1001 415 1848 994 417 1849 996 413 1850 1002 415 1851 994 413 1852 1002 412 1853 1003 418 1854 1004 415 1855 1005 412 1856 1006 418 1857 1004 412 1858 1006 414 1859 1007 419 1860 1008 420 1861 1009 421 1862 1010 420 1863 1009 419 1864 1008 422 1865 1011 423 1866 1012 424 1867 1013 425 1868 1014 424 1869 1013 423 1870 1012 426 1871 1015 424 1872 1013 426 1873 1015 422 1874 1016 424 1875 1013 422 1876 1016 419 1877 1017 425 1878 1014 424 1879 1013 419 1880 1018 425 1881 1014 419 1882 1018 421 1883 1019 423 1884 1012 425 1885 1014 421 1886 1020 423 1887 1012 421 1888 1020 420 1889 1021 423 1890 1022 422 1891 1023 426 1892 1024 422 1893 1023 423 1894 1022 420 1895 1025

+
+
+
+ + + + + + + + + 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 3.020157 0.000000 0.000000 0.000000 1.0000001.000000 + 30.0000000.0000003.333333 + + + + + +
diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfE_01/model.config b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfE_01/model.config new file mode 100755 index 0000000..cddf840 --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfE_01/model.config @@ -0,0 +1,11 @@ + + + aws_robomaker_warehouse_ShelfE_01 + 1.0 + model.sdf + + + + + + diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfE_01/model.sdf b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfE_01/model.sdf new file mode 100755 index 0000000..d615c9e --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfE_01/model.sdf @@ -0,0 +1,46 @@ + + + + + + 30 + + 907.144 + 0 + 0 + 104.950 + 0 + 824.248 + + + + + + model://aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + model://aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_visual.DAE + + + 1 + + +1 + + diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfF_01/materials/textures/aws_robomaker_warehouse_ShelfF_01.png b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfF_01/materials/textures/aws_robomaker_warehouse_ShelfF_01.png new file mode 100755 index 0000000..6a8add8 Binary files /dev/null and b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfF_01/materials/textures/aws_robomaker_warehouse_ShelfF_01.png differ diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfF_01/materials/textures/aws_robomaker_warehouse_ShelfF_02.png b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfF_01/materials/textures/aws_robomaker_warehouse_ShelfF_02.png new file mode 100755 index 0000000..b28b289 Binary files /dev/null and b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfF_01/materials/textures/aws_robomaker_warehouse_ShelfF_02.png differ diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfF_01/materials/textures/aws_robomaker_warehouse_ShelfF_03.png b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfF_01/materials/textures/aws_robomaker_warehouse_ShelfF_03.png new file mode 100755 index 0000000..2738ccc Binary files /dev/null and b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfF_01/materials/textures/aws_robomaker_warehouse_ShelfF_03.png differ diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfF_01/meshes/aws_robomaker_warehouse_ShelfF_01_collision.DAE b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfF_01/meshes/aws_robomaker_warehouse_ShelfF_01_collision.DAE new file mode 100755 index 0000000..cc88e55 --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfF_01/meshes/aws_robomaker_warehouse_ShelfF_01_collision.DAE @@ -0,0 +1,575 @@ + + + FBX COLLADA exporter2019-05-16T06:18:19Z2019-05-16T06:18:19ZZ_UP + + + + + +-109.909821 -899.415955 0.000000 +100.279144 -899.415955 0.000000 +-109.909821 905.263123 0.000000 +100.279144 905.263123 0.000000 +-109.909821 -899.415955 652.940002 +100.279144 -899.415955 652.940002 +-109.909821 905.263123 652.940002 +100.279144 905.263123 652.940002 +-109.909821 -884.415955 0.000000 +-109.909821 -452.497528 0.000000 +-109.909821 -437.497528 0.000000 +-109.909821 -15.096558 0.000000 +-109.909821 -0.096619 0.000000 +100.279144 -0.096558 0.000000 +100.279144 -15.096558 0.000000 +100.279144 -437.497528 0.000000 +100.279144 -452.497528 0.000000 +100.279144 -884.415894 0.000000 +100.279144 -884.415955 652.940002 +100.279144 -452.497528 652.940002 +100.279144 -437.497528 652.940002 +100.279144 -15.096558 652.940002 +100.279144 -0.096619 652.940002 +-109.909821 -0.096558 652.940002 +-109.909821 -15.096558 652.940002 +-109.909821 -437.497528 652.940002 +-109.909821 -452.497528 652.940002 +-109.909821 -884.415894 652.940002 +100.279144 434.116791 0.000000 +-109.909821 434.116760 0.000000 +-109.909821 434.116791 652.940002 +100.279144 434.116760 652.940002 +100.279144 449.116821 0.000000 +-109.909821 449.116821 0.000000 +-109.909821 449.116821 652.940002 +100.279144 449.116821 652.940002 +-109.909813 890.263123 652.940002 +100.279144 890.263123 652.940002 +100.279144 890.263123 0.000000 +-109.909821 890.263123 0.000000 +100.279144 890.263123 164.188065 +100.279144 449.116821 164.188065 +100.279144 434.116791 164.188065 +100.279144 -0.096572 164.188065 +100.279144 -15.096560 164.188065 +100.279144 -437.497528 164.188065 +100.279144 -452.497528 164.188065 +100.279144 -884.415894 164.188065 +100.279144 -899.415955 164.188065 +-109.909821 -899.415955 164.188065 +-109.909821 -884.415894 164.188065 +-109.909821 -452.497528 164.188065 +-109.909821 -437.497528 164.188065 +-109.909821 -15.096558 164.188065 +-109.909821 -0.096604 164.188065 +-109.909821 434.116760 164.188065 +-109.909821 449.116821 164.188065 +-109.909821 890.263123 164.188065 +-109.909821 905.263184 164.188065 +100.279144 905.263184 164.188065 + + + + + + + + + + + +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 -0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.000000 1.000000 -0.000000 +-0.000000 1.000000 -0.000000 +-0.000000 1.000000 -0.000000 +-0.000000 1.000000 -0.000000 +-0.000000 1.000000 -0.000000 +-0.000000 1.000000 -0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 -0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.000000 1.000000 0.000000 +-0.000000 1.000000 0.000000 +-0.000000 1.000000 0.000000 +-0.000000 1.000000 0.000000 +-0.000000 1.000000 0.000000 +-0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 + + + + + + + + + + + +1.000000 0.000000 +0.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +1.000000 0.166667 +1.000000 0.333333 +1.000000 0.500000 +1.000000 0.666667 +1.000000 0.833333 +0.833333 0.000000 +0.666667 0.000000 +0.500000 0.000000 +0.333333 0.000000 +0.166667 0.000000 +0.000000 0.833333 +0.000000 0.666667 +0.000000 0.500000 +0.000000 0.333333 +0.000000 0.166667 +0.833333 0.000000 +0.666667 0.000000 +0.500000 0.000000 +0.333333 0.000000 +0.166667 0.000000 +1.000000 0.166667 +1.000000 0.333333 +1.000000 0.500000 +1.000000 0.666667 +1.000000 0.833333 +0.166667 1.000000 +0.333333 1.000000 +0.500000 1.000000 +0.666667 1.000000 +0.833333 1.000000 +0.000000 0.833333 +0.000000 0.666667 +0.000000 0.500000 +0.000000 0.333333 +0.000000 0.166667 +0.166667 1.000000 +0.333333 1.000000 +0.500000 1.000000 +0.666667 1.000000 +0.833333 1.000000 +0.000000 0.912466 +0.912466 0.000000 +1.000000 0.912466 +0.087534 0.000000 +0.000000 0.912466 +0.087534 1.000000 +1.000000 0.912466 +0.912466 1.000000 +0.000000 0.923029 +0.923029 0.000000 +1.000000 0.923029 +0.076971 0.000000 +0.000000 0.923029 +0.076971 1.000000 +1.000000 0.923029 +0.923029 1.000000 +0.000000 0.977027 +0.022973 1.000000 +1.000000 0.977027 +0.977027 1.000000 +0.000000 0.977027 +0.977027 0.000000 +1.000000 0.977027 +0.022973 0.000000 +0.977027 0.240683 +0.923029 0.240683 +0.912466 0.240683 +0.833333 0.240683 +0.666667 0.240683 +0.500000 0.240683 +0.333333 0.240683 +0.166667 0.240683 +1.000000 0.240683 +0.000000 0.240683 +0.000000 0.240683 +1.000000 0.240683 +0.833333 0.240683 +0.666667 0.240683 +0.500000 0.240683 +0.333333 0.240683 +0.166667 0.240683 +0.087534 0.240683 +0.076971 0.240683 +0.022973 0.240683 +1.000000 0.240683 +0.000000 0.240683 +1.000000 0.240683 +0.000000 0.240683 + + + + + + + + + + + +

16 0 37 9 1 25 10 2 26 16 3 37 10 4 26 15 5 36 26 6 57 20 7 46 25 8 56 20 9 46 26 10 57 19 11 45 49 12 98 1 13 9 48 14 96 1 15 9 49 16 98 0 17 8 46 18 94 15 19 41 45 20 93 15 21 41 46 22 94 16 23 42 59 24 111 2 25 17 58 26 108 2 27 17 59 28 111 3 29 16 14 30 35 11 31 27 12 32 28 14 33 35 12 34 28 13 35 34 8 36 24 1 37 1 0 38 0 1 39 1 8 40 24 17 41 38 30 42 68 23 43 54 31 44 70 31 45 70 23 46 54 22 47 48 22 48 48 23 49 54 24 50 55 22 51 48 24 52 55 21 53 47 25 54 56 21 55 47 24 56 55 21 57 47 25 58 56 20 59 46 18 60 44 27 61 58 4 62 4 18 63 44 4 64 4 5 65 5 26 66 57 27 67 58 19 68 45 19 69 45 27 70 58 18 71 44 43 72 91 14 73 40 13 74 39 14 75 40 43 76 91 44 77 92 18 78 49 48 79 97 47 80 95 48 81 97 18 82 49 5 83 14 19 84 50 47 85 95 46 86 94 47 87 95 19 88 50 18 89 49 49 90 99 8 91 29 0 92 21 8 93 29 49 94 99 50 95 100 52 96 102 9 97 30 51 98 101 9 99 30 52 100 102 10 101 31 23 102 59 55 103 105 54 104 104 55 105 105 23 106 59 30 107 69 24 108 60 54 109 104 53 110 103 54 111 104 24 112 60 23 113 59 28 114 64 29 115 66 33 116 74 28 117 64 33 118 74 32 119 72 35 120 78 34 121 76 30 122 68 35 123 78 30 124 68 31 125 70 42 126 90 32 127 73 41 128 89 32 129 73 42 130 90 28 131 65 30 132 69 56 133 106 55 134 105 56 135 106 30 136 69 34 137 77 36 138 80 35 139 78 37 140 82 35 141 78 36 142 80 34 143 76 34 144 77 36 145 81 56 146 106 36 147 81 57 148 107 56 149 106 38 150 84 39 151 86 2 152 2 38 153 84 2 154 2 3 155 3 36 156 80 7 157 7 6 158 6 7 159 7 36 160 80 37 161 82 40 162 88 3 163 13 59 164 110 3 165 13 40 166 88 38 167 85 57 168 107 36 169 81 6 170 22 6 171 22 58 172 109 57 173 107 4 174 10 49 175 98 5 176 11 5 177 11 49 178 98 48 179 96 46 180 94 20 181 51 19 182 50 20 183 51 46 184 94 45 185 93 7 186 18 59 187 111 6 188 19 6 189 19 59 190 111 58 191 108 24 192 60 53 193 103 25 194 61 25 195 61 53 196 103 52 197 102 22 198 53 43 199 91 31 200 71 31 201 71 43 202 91 42 203 90 21 204 52 44 205 92 22 206 53 22 207 53 44 208 92 43 209 91 20 210 51 44 211 92 21 212 52 44 213 92 20 214 51 45 215 93 48 216 97 1 217 12 47 218 95 47 219 95 1 220 12 17 221 43 27 222 63 50 223 100 4 224 23 4 225 23 50 226 100 49 227 99 26 228 62 51 229 101 27 230 63 27 231 63 51 232 101 50 233 100 25 234 61 52 235 102 26 236 62 26 237 62 52 238 102 51 239 101 54 240 104 12 241 33 53 242 103 53 243 103 12 244 33 11 245 32 31 246 71 42 247 90 35 248 79 35 249 79 42 250 90 41 251 89 56 252 106 33 253 75 55 254 105 55 255 105 33 256 75 29 257 67 35 258 79 41 259 89 37 260 83 37 261 83 41 262 89 40 263 88 37 264 83 40 265 88 7 266 15 7 267 15 40 268 88 59 269 110 58 270 109 2 271 20 57 272 107 57 273 107 2 274 20 39 275 87 47 276 95 17 277 43 50 278 100 50 279 100 17 280 43 8 281 24 46 282 94 51 283 101 9 284 30 46 285 94 9 286 30 16 287 37 50 288 100 51 289 101 47 290 95 47 291 95 51 292 101 46 293 94 53 294 103 14 295 35 44 296 92 14 297 35 53 298 103 11 299 32 52 300 102 44 301 92 45 302 93 44 303 92 52 304 102 53 305 103 52 306 102 45 307 93 15 308 41 52 309 102 15 310 41 10 311 26 43 312 91 13 313 39 54 314 104 54 315 104 13 316 39 12 317 28 54 318 104 55 319 105 43 320 91 43 321 91 55 322 105 42 323 90 42 324 90 55 325 105 29 326 67 42 327 90 29 328 67 28 329 64 41 330 89 32 331 73 56 332 106 56 333 106 32 334 73 33 335 74 56 336 106 57 337 107 41 338 89 41 339 89 57 340 107 40 341 88 40 342 88 57 343 107 39 344 87 40 345 88 39 346 87 38 347 84

+
+
+
+ + + 1.000000 0.000000 0.000000 5.565578 0.000000 1.000000 0.000000 -2.923615 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.0000001.000000 + 30.0000000.0000003.333333 + + + + + +
diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfF_01/meshes/aws_robomaker_warehouse_ShelfF_01_visual.DAE b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfF_01/meshes/aws_robomaker_warehouse_ShelfF_01_visual.DAE new file mode 100755 index 0000000..065be92 --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfF_01/meshes/aws_robomaker_warehouse_ShelfF_01_visual.DAE @@ -0,0 +1,15734 @@ + + + FBX COLLADA exporter2019-05-27T02:54:39Z2019-05-27T02:54:39ZZ_UP + + + ../materials/textures/aws_robomaker_warehouse_ShelfF_01.png + + + ../materials/textures/aws_robomaker_warehouse_ShelfF_02.png + + + ../materials/textures/aws_robomaker_warehouse_ShelfF_03.png + + + + + + + + + + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + +-104.344238 0.000031 887.339539 +-91.344238 0.000031 887.339539 +-104.344238 614.091614 887.339539 +-91.344238 614.091614 887.339539 +-104.344238 0.000031 902.339539 +-91.344238 0.000031 902.339539 +-104.344238 614.091614 902.339539 +-91.344238 614.091614 902.339539 +92.844727 0.000031 887.339539 +92.844727 614.091614 887.339539 +105.844727 614.091614 887.339539 +105.844727 0.000031 887.339539 +92.844727 0.000031 902.339539 +105.844727 0.000031 902.339539 +105.844727 614.091614 902.339539 +92.844727 614.091614 902.339539 +-96.219147 34.111694 887.339539 +99.260559 169.685135 887.339539 +99.260559 156.685135 887.339539 +-96.219147 21.111694 887.339539 +-96.219147 34.111694 902.339539 +-96.219147 21.111694 902.339539 +99.260559 156.685135 902.339539 +99.260559 169.685135 902.339539 +-96.219147 342.438934 887.339539 +99.260559 471.540375 887.339539 +99.260559 458.540375 887.339539 +-96.219147 329.438934 887.339539 +-96.219147 342.438934 902.339539 +-96.219147 329.438934 902.339539 +99.260559 458.540375 902.339539 +99.260559 471.540375 902.339539 +-96.219147 318.660126 887.339539 +99.260559 190.825317 887.339539 +99.260559 177.825317 887.339539 +-96.219147 305.660126 887.339539 +-96.219147 318.660126 902.339539 +-96.219147 305.660126 902.339539 +99.260559 177.825317 902.339539 +99.260559 190.825317 902.339539 +-96.219147 558.273315 887.339539 +99.260559 558.273315 887.339539 +99.260559 545.273315 887.339539 +-96.219147 545.273315 887.339539 +-96.219147 558.273315 902.339539 +-96.219147 545.273315 902.339539 +99.260559 545.273315 902.339539 +99.260559 558.273315 902.339539 +-104.344238 0.000000 440.421143 +-104.344238 614.091614 440.421143 +-91.344238 614.091614 440.421143 +-91.344238 0.000000 440.421143 +-104.344238 0.000000 455.421143 +-91.344238 0.000000 455.421143 +-91.344238 614.091614 455.421143 +-104.344238 614.091614 455.421143 +92.844727 0.000000 440.421143 +92.844727 614.091614 440.421143 +105.844727 614.091614 440.421143 +105.844727 0.000000 440.421143 +92.844727 0.000000 455.421143 +105.844727 0.000000 455.421143 +105.844727 614.091614 455.421143 +92.844727 614.091614 455.421143 +-96.219147 34.111694 440.421143 +99.260559 169.685120 440.421143 +99.260559 156.685120 440.421143 +-96.219147 21.111694 440.421143 +-96.219147 34.111694 455.421143 +-96.219147 21.111694 455.421143 +99.260559 156.685120 455.421143 +99.260559 169.685120 455.421143 +-96.219147 342.438904 440.421143 +99.260559 471.540375 440.421143 +99.260559 458.540375 440.421143 +-96.219147 329.438904 440.421143 +-96.219147 342.438904 455.421143 +-96.219147 329.438904 455.421143 +99.260559 458.540375 455.421143 +99.260559 471.540375 455.421143 +-96.219147 318.660095 440.421143 +99.260559 190.825302 440.421143 +99.260559 177.825287 440.421143 +-96.219147 305.660095 440.421143 +-96.219147 318.660095 455.421143 +-96.219147 305.660095 455.421143 +99.260559 177.825287 455.421143 +99.260559 190.825302 455.421173 +-96.219147 558.273254 440.421143 +99.260559 558.273254 440.421143 +99.260559 545.273254 440.421143 +-96.219147 545.273254 440.421143 +-96.219147 558.273254 455.421143 +-96.219147 545.273254 455.421143 +99.260559 545.273254 455.421143 +99.260559 558.273254 455.421143 +-104.344238 -0.000031 3.020142 +-104.344238 614.091553 3.020142 +-91.344238 614.091553 3.020142 +-91.344238 -0.000031 3.020142 +-104.344238 -0.000031 18.020142 +-91.344238 -0.000031 18.020142 +-91.344238 614.091553 18.020142 +-104.344238 614.091553 18.020142 +92.844727 -0.000031 3.020142 +92.844727 614.091553 3.020142 +105.844727 614.091553 3.020142 +105.844727 -0.000031 3.020142 +92.844727 -0.000031 18.020142 +105.844727 -0.000031 18.020142 +105.844727 614.091553 18.020142 +92.844727 614.091553 18.020142 +-96.219147 34.111694 3.020142 +99.260559 169.685089 3.020142 +99.260559 156.685104 3.020142 +-96.219147 21.111694 3.020142 +-96.219147 34.111694 18.020142 +-96.219147 21.111694 18.020142 +99.260559 156.685089 18.020142 +99.260559 169.685089 18.020142 +-96.219147 342.438904 3.020142 +99.260559 471.540344 3.020142 +99.260559 458.540344 3.020142 +-96.219147 329.438904 3.020142 +-96.219147 342.438904 18.020142 +-96.219147 329.438904 18.020142 +99.260559 458.540344 18.020142 +99.260559 471.540344 18.020142 +-96.219147 318.660095 3.020142 +99.260559 190.825287 3.020142 +99.260559 177.825256 3.020142 +-96.219147 305.660095 3.020142 +-96.219147 318.660095 18.020142 +-96.219147 305.660095 18.020142 +99.260559 177.825256 18.020142 +99.260559 190.825272 18.020203 +-96.219147 558.273254 3.020142 +99.260559 558.273254 3.020142 +99.260559 545.273254 3.020142 +-96.219147 545.273254 3.020142 +-96.219147 558.273254 18.020142 +-96.219147 545.273254 18.020142 +99.260559 545.273254 18.020142 +99.260559 558.273254 18.020142 +-104.344238 -0.000061 -446.193176 +-104.344238 614.091553 -446.193176 +-91.344238 614.091553 -446.193176 +-91.344238 -0.000061 -446.193176 +-104.344238 -0.000061 -431.193176 +-91.344238 -0.000061 -431.193176 +-91.344238 614.091553 -431.193176 +-104.344238 614.091553 -431.193176 +92.844727 -0.000061 -446.193176 +92.844727 614.091553 -446.193176 +105.844727 614.091553 -446.193176 +105.844727 -0.000061 -446.193176 +92.844727 -0.000061 -431.193176 +105.844727 -0.000061 -431.193176 +105.844727 614.091553 -431.193176 +92.844727 614.091553 -431.193176 +-96.219147 34.111664 -446.193176 +99.260559 169.685059 -446.193176 +99.260559 156.685089 -446.193176 +-96.219147 21.111664 -446.193176 +-96.219147 34.111664 -431.193176 +-96.219147 21.111664 -431.193176 +99.260559 156.685059 -431.193176 +99.260559 169.685059 -431.193176 +-96.219147 342.438873 -446.193176 +99.260559 471.540344 -446.193176 +99.260559 458.540344 -446.193176 +-96.219147 329.438873 -446.193176 +-96.219147 342.438873 -431.193176 +-96.219147 329.438873 -431.193176 +99.260559 458.540314 -431.193176 +99.260559 471.540314 -431.193176 +-96.219147 318.660065 -446.193176 +99.260559 190.825272 -446.193176 +99.260559 177.825241 -446.193176 +-96.219147 305.660065 -446.193176 +-96.219147 318.660065 -431.193176 +-96.219147 305.660065 -431.193176 +99.260559 177.825226 -431.193176 +99.260559 190.825256 -431.193176 +-96.219147 558.273254 -446.193176 +99.260559 558.273254 -446.193176 +99.260559 545.273254 -446.193176 +-96.219147 545.273254 -446.193176 +-96.219147 558.273193 -431.193176 +-96.219147 545.273193 -431.193176 +99.260559 545.273193 -431.193176 +99.260559 558.273193 -431.193176 +-104.344238 -0.000092 -902.339539 +-104.344238 614.091492 -902.339539 +-91.344238 614.091492 -902.339539 +-91.344238 -0.000092 -902.339539 +-104.344238 -0.000092 -887.339539 +-91.344238 -0.000092 -887.339539 +-91.344238 614.091492 -887.339539 +-104.344238 614.091492 -887.339539 +92.844727 -0.000092 -902.339539 +92.844727 614.091492 -902.339539 +105.844727 614.091492 -902.339539 +105.844727 -0.000092 -902.339539 +92.844727 -0.000092 -887.339539 +105.844727 -0.000092 -887.339539 +105.844727 614.091492 -887.339539 +92.844727 614.091492 -887.339539 +-96.219147 34.111633 -902.339539 +99.260559 169.685028 -902.339539 +99.260559 156.685074 -902.339539 +-96.219147 21.111633 -902.339539 +-96.219147 34.111633 -887.339539 +-96.219147 21.111633 -887.339539 +99.260559 156.685043 -887.339539 +99.260559 169.685028 -887.339539 +-96.219147 342.438843 -902.339539 +99.260559 471.540314 -902.339539 +99.260559 458.540314 -902.339539 +-96.219147 329.438843 -902.339539 +-96.219147 342.438843 -887.339539 +-96.219147 329.438843 -887.339539 +99.260559 458.540283 -887.339539 +99.260559 471.540283 -887.339539 +-96.219147 318.660034 -902.339539 +99.260559 190.825256 -902.339539 +99.260559 177.825226 -902.339539 +-96.219147 305.660034 -902.339539 +-96.219147 318.660034 -887.339539 +-96.219147 305.660034 -887.339539 +99.260559 177.825211 -887.339539 +99.260559 190.825241 -887.339539 +-96.219147 558.273254 -902.339539 +99.260559 558.273254 -902.339539 +99.260559 545.273254 -902.339539 +-96.219147 545.273254 -902.339539 +-96.219147 558.273193 -887.339539 +-96.219147 545.273193 -887.339539 +99.260559 545.273193 -887.339539 +99.260559 558.273193 -887.339539 +-99.241058 479.273254 -896.629211 +99.260559 479.273254 -896.629211 +99.260559 459.814392 -896.629211 +-99.241058 459.814392 -896.629211 +-99.241058 479.273346 902.339539 +-99.241058 459.814484 902.339539 +99.260559 459.814484 902.339539 +99.260559 479.273346 902.339539 +-99.241058 183.646896 -896.629211 +99.260559 183.646896 -896.629211 +99.260559 164.188019 -896.629211 +-99.241058 164.188019 -896.629211 +-99.241058 183.646973 902.339539 +-99.241058 164.188126 902.339539 +99.260559 164.188126 902.339539 +99.260559 183.646973 902.339539 +-96.219147 329.713470 887.339539 +99.260559 329.713470 887.339539 +99.260559 316.713470 887.339539 +-96.219147 316.713470 887.339539 +-96.219147 329.713470 902.339539 +-96.219147 316.713470 902.339539 +99.260559 316.713470 902.339539 +99.260559 329.713470 902.339539 +-96.219147 329.713440 440.421143 +99.260559 329.713440 440.421143 +99.260559 316.713440 440.421143 +-96.219147 316.713440 440.421143 +-96.219147 329.713440 455.421143 +-96.219147 316.713440 455.421143 +99.260559 316.713440 455.421143 +99.260559 329.713440 455.421143 +-96.219147 329.713440 3.020142 +99.260559 329.713440 3.020142 +99.260559 316.713440 3.020142 +-96.219147 316.713440 3.020142 +-96.219147 329.713409 18.020142 +-96.219147 316.713409 18.020142 +99.260559 316.713409 18.020142 +99.260559 329.713409 18.020142 +-96.219147 329.713440 -446.193176 +99.260559 329.713440 -446.193176 +99.260559 316.713440 -446.193176 +-96.219147 316.713440 -446.193176 +-96.219147 329.713379 -431.193176 +-96.219147 316.713379 -431.193176 +99.260559 316.713379 -431.193176 +99.260559 329.713379 -431.193176 +-96.219147 329.713409 -902.339539 +99.260559 329.713409 -902.339539 +99.260559 316.713409 -902.339539 +-96.219147 316.713409 -902.339539 +-96.219147 329.713379 -887.339539 +-96.219147 316.713379 -887.339539 +99.260559 316.713379 -887.339539 +99.260559 329.713379 -887.339539 +-105.844757 567.987732 -896.629211 +-88.513672 567.987732 -896.629211 +-88.513672 532.745239 -896.629211 +-105.844757 532.745239 -896.629211 +-105.844757 567.987793 902.339539 +-105.844757 532.745422 902.339539 +-88.513672 532.745422 902.339539 +-88.513672 567.987793 902.339539 +-15.810349 184.344681 -723.537659 +-15.810349 220.753220 -723.537659 +58.811157 220.753220 -723.555725 +58.811157 184.344681 -723.555725 +-15.429932 184.344681 -673.737244 +59.191650 184.344681 -673.755188 +59.191650 220.753220 -673.755188 +-15.438255 220.753220 -674.834045 +-15.429932 220.753220 -673.737244 +-15.810432 221.386520 -723.537659 +-15.810432 257.795105 -723.537659 +58.811157 257.795105 -723.555725 +58.811157 221.386520 -723.555725 +-15.430016 221.386520 -673.737366 +59.191650 221.386520 -673.755188 +59.191650 257.795105 -673.755188 +-15.438339 257.795105 -674.834045 +-15.430016 257.795105 -673.737366 +-15.810364 184.344681 -673.767639 +-15.810364 220.753220 -673.767639 +58.811218 220.753220 -673.785583 +58.811218 184.344681 -673.785583 +-15.429863 184.344696 -623.967224 +59.191635 184.344696 -623.985168 +59.191635 220.753220 -623.985291 +-15.438271 220.753220 -625.064148 +-15.429863 220.753220 -623.967224 +-91.014145 184.344681 -723.537659 +-91.014145 220.753220 -723.537659 +-16.392563 220.753220 -723.555603 +-16.392563 184.344681 -723.555603 +-90.633644 184.344681 -673.737244 +-16.012062 184.344681 -673.755188 +-16.012062 220.753220 -673.755310 +-90.642044 220.753220 -674.834045 +-90.633644 220.753220 -673.737244 +-91.014145 221.386520 -723.537659 +-91.014145 257.795105 -723.537659 +-16.392555 257.795105 -723.555725 +-16.392555 221.386520 -723.555725 +-90.633728 221.386520 -673.737244 +-16.012138 221.386520 -673.755310 +-16.012138 257.795105 -673.755310 +-90.642044 257.795105 -674.834167 +-90.633728 257.795105 -673.737244 +-91.014221 258.270355 -723.537659 +-91.014221 294.678894 -723.537659 +-16.392555 294.678894 -723.555725 +-16.392555 258.270355 -723.555725 +-90.633812 258.270355 -673.737244 +-16.012222 258.270355 -673.755310 +-16.012222 294.678894 -673.755310 +-90.642044 294.678894 -674.834167 +-90.633812 294.678894 -673.737244 +-91.014076 184.344681 -673.767639 +-91.014076 220.753220 -673.767639 +-16.392494 220.753220 -673.785706 +-16.392494 184.344681 -673.785706 +-90.633659 184.344696 -623.967224 +-16.012077 184.344696 -623.985168 +-16.012077 220.753220 -623.985291 +-90.641983 220.753220 -625.064026 +-90.633659 220.753220 -623.967224 +-91.014160 221.386520 -673.767639 +-91.014160 257.795105 -673.767639 +-16.392662 257.795105 -673.785706 +-16.392662 221.386520 -673.785706 +-90.633827 221.386520 -623.967346 +-16.012161 221.386520 -623.985168 +-16.012161 257.795105 -623.985291 +-90.642059 257.795105 -625.064148 +-90.633827 257.795105 -623.967346 +-91.014244 258.270355 -673.767639 +-91.014244 294.678894 -673.767639 +-16.392654 294.678894 -673.785706 +-16.392654 258.270355 -673.785706 +-90.633827 258.270355 -623.967346 +-16.012238 258.270355 -623.985291 +-16.012238 294.678894 -623.985413 +-90.642059 294.678894 -625.064148 +-90.633827 294.678894 -623.967346 +-91.014389 295.428833 -723.537659 +-91.014389 331.837433 -723.537659 +-16.392555 331.837433 -723.555847 +-16.392555 295.428833 -723.555847 +-90.633888 295.428833 -673.737366 +-16.012306 295.428833 -673.755432 +-16.012306 331.837433 -673.755432 +-90.642044 331.837433 -674.834290 +-90.633888 331.837433 -673.737366 +50.234726 184.344681 -527.757874 +50.234726 220.753220 -527.757874 +50.252762 220.753220 -453.136414 +50.252762 184.344696 -453.136414 +0.434303 184.344681 -527.377502 +0.452232 184.344696 -452.755920 +0.452332 220.753220 -452.755920 +1.531166 220.753220 -527.385803 +0.434303 220.753220 -527.377502 +50.234741 221.386520 -527.757996 +50.234741 257.795105 -527.757996 +50.252762 257.795105 -453.136414 +50.252762 221.386520 -453.136414 +0.434402 221.386520 -527.377625 +0.452332 221.386520 -452.755920 +0.452332 257.795105 -452.755920 +1.531174 257.795105 -527.385925 +0.434402 257.795105 -527.377625 +0.464661 184.344681 -527.757996 +0.464661 220.753220 -527.757996 +0.482689 220.753220 -453.136292 +0.482689 184.344696 -453.136292 +-49.335667 184.344681 -527.377380 +-49.317738 184.344696 -452.755920 +-49.317638 220.753220 -452.755920 +-48.238800 220.753220 -527.385803 +-49.335667 220.753220 -527.377380 +0.464760 221.386520 -527.757996 +0.464760 257.795105 -527.757996 +0.482788 257.795105 -453.136414 +0.482788 221.386520 -453.136414 +-49.335667 221.386520 -527.377625 +-49.317638 221.386520 -452.756042 +-49.317638 257.795105 -452.756042 +-48.238800 257.795105 -527.385803 +-49.335667 257.795105 -527.377625 +0.464760 258.270355 -527.757996 +0.464760 294.678894 -527.757996 +0.482788 294.678894 -453.136536 +0.482788 258.270355 -453.136536 +-49.335663 258.270355 -527.377747 +-49.317635 258.270355 -452.756165 +-49.317539 294.678894 -452.756165 +-48.238705 294.678894 -527.385925 +-49.335663 294.678894 -527.377747 +50.234772 184.344681 -602.961731 +50.234772 220.753220 -602.961731 +50.252701 220.753220 -528.340149 +50.252701 184.344681 -528.340149 +0.434341 184.344681 -602.581238 +0.452271 184.344681 -527.959656 +0.452370 220.753220 -527.959656 +1.531113 220.753220 -602.589661 +0.434341 220.753220 -602.581238 +50.234772 221.386520 -602.961731 +50.234772 257.795105 -602.961731 +50.252808 257.795105 -528.340149 +50.252808 221.386520 -528.340149 +0.434349 221.386520 -602.581360 +0.452370 221.386520 -527.959656 +0.452370 257.795105 -527.959778 +1.531212 257.795105 -602.589661 +0.434349 257.795105 -602.581360 +0.464699 184.344681 -602.961609 +0.464699 220.753220 -602.961609 +0.482727 220.753220 -528.340027 +0.482727 184.344681 -528.340027 +-49.335728 184.344681 -602.581238 +-49.317699 184.344681 -527.959656 +-49.317600 220.753220 -527.959656 +-48.238861 220.753220 -602.589539 +-49.335728 220.753220 -602.581238 +0.464706 221.386520 -602.961731 +0.464706 257.795105 -602.961731 +0.482735 257.795105 -528.340271 +0.482735 221.386520 -528.340271 +-49.335625 221.386520 -602.581360 +-49.317696 221.386520 -527.959778 +-49.317596 257.795105 -527.959778 +-48.238762 257.795105 -602.589661 +-49.335625 257.795105 -602.581360 +0.464706 258.270355 -602.961853 +0.464706 294.678894 -602.961853 +0.482834 294.678894 -528.340271 +0.482834 258.270355 -528.340271 +-49.335625 258.270355 -602.581360 +-49.317596 258.270355 -527.959778 +-49.317497 294.678894 -527.959778 +-48.238762 294.678894 -602.589661 +-49.335625 294.678894 -602.581360 +0.464760 295.428833 -527.758118 +0.464760 331.837433 -527.758118 +0.482895 331.837433 -453.136658 +0.482895 295.428833 -453.136658 +-49.335560 295.428833 -527.377991 +-49.317539 295.428833 -452.756165 +-49.317539 331.837433 -452.756165 +-48.238602 331.837433 -527.386047 +-49.335560 331.837433 -527.377991 +50.234726 479.563110 -703.469055 +50.234726 515.971619 -703.469055 +50.252762 515.971619 -628.847595 +50.252762 479.563110 -628.847595 +0.434303 479.563110 -703.088684 +0.452232 479.563110 -628.467102 +0.452332 515.971619 -628.467102 +1.531166 515.971619 -703.096985 +0.434303 515.971619 -703.088684 +0.464661 479.563110 -703.469177 +0.464661 515.971619 -703.469177 +0.482689 515.971619 -628.847473 +0.482689 479.563110 -628.847473 +-49.335667 479.563110 -703.088562 +-49.317738 479.563110 -628.467102 +-49.317638 515.971619 -628.467102 +-48.238800 515.971619 -703.096985 +-49.335667 515.971619 -703.088562 +0.464760 516.604919 -703.469177 +0.464760 553.013489 -703.469177 +0.482788 553.013489 -628.847595 +0.482788 516.604919 -628.847595 +-49.335667 516.604919 -703.088806 +-49.317638 516.604919 -628.467224 +-49.317638 553.013489 -628.467224 +-48.238800 553.013489 -703.096985 +-49.335667 553.013489 -703.088806 +50.234772 479.563080 -778.672913 +50.234772 515.971619 -778.672913 +50.252701 515.971619 -704.051331 +50.252701 479.563110 -704.051331 +0.434341 479.563080 -778.292419 +0.452271 479.563110 -703.670837 +0.452370 515.971619 -703.670837 +1.531113 515.971619 -778.300842 +0.434341 515.971619 -778.292419 +50.234772 516.604919 -778.672913 +50.234772 553.013489 -778.672913 +50.252808 553.013489 -704.051331 +50.252808 516.604919 -704.051331 +0.434349 516.604919 -778.292542 +0.452370 516.604919 -703.670837 +0.452370 553.013489 -703.670959 +1.531212 553.013489 -778.300842 +0.434349 553.013489 -778.292542 +50.234772 553.488770 -778.673035 +50.234772 589.897278 -778.673035 +50.252808 589.897278 -704.051331 +50.252808 553.488770 -704.051331 +0.434349 553.488770 -778.292542 +0.452377 553.488770 -703.670959 +0.452377 589.897278 -703.670959 +1.531212 589.897278 -778.300842 +0.434349 589.897278 -778.292542 +0.464699 479.563080 -778.672791 +0.464699 515.971619 -778.672791 +0.482727 515.971619 -704.051208 +0.482727 479.563110 -704.051208 +-49.335728 479.563080 -778.292419 +-49.317699 479.563110 -703.670837 +-49.317600 515.971619 -703.670837 +-48.238861 515.971619 -778.300720 +-49.335728 515.971619 -778.292419 +0.464706 516.604919 -778.672913 +0.464706 553.013489 -778.672913 +0.482735 553.013489 -704.051453 +0.482735 516.604919 -704.051453 +-49.335625 516.604919 -778.292542 +-49.317696 516.604919 -703.670959 +-49.317596 553.013489 -703.670959 +-48.238762 553.013489 -778.300842 +-49.335625 553.013489 -778.292542 +0.464706 553.488770 -778.673035 +0.464706 589.897278 -778.673035 +0.482834 589.897278 -704.051453 +0.482834 553.488770 -704.051453 +-49.335625 553.488770 -778.292542 +-49.317596 553.488770 -703.670959 +-49.317497 589.897278 -703.670959 +-48.238762 589.897278 -778.300842 +-49.335625 589.897278 -778.292542 +0.464806 590.647217 -778.673035 +0.464806 627.055847 -778.673035 +0.482834 627.055847 -704.051575 +0.482834 590.647217 -704.051575 +-49.335526 590.647217 -778.292664 +-49.317497 590.647217 -703.671082 +-49.317497 627.055847 -703.671082 +-48.238663 627.055847 -778.300842 +-49.335526 627.055847 -778.292664 +0.559647 479.789673 -324.522034 +0.559647 516.198181 -324.522034 +75.181152 516.198181 -324.540100 +75.181152 479.789673 -324.540100 +0.940063 479.789673 -274.721619 +75.561646 479.789673 -274.739563 +75.561646 516.198181 -274.739563 +0.931740 516.198181 -275.818420 +0.940063 516.198181 -274.721619 +0.559563 516.831482 -324.522034 +0.559563 553.240112 -324.522034 +75.181152 553.240112 -324.540100 +75.181152 516.831482 -324.540100 +0.939980 516.831482 -274.721741 +75.561646 516.831482 -274.739563 +75.561646 553.240112 -274.739563 +0.931656 553.240112 -275.818420 +0.939980 553.240112 -274.721741 +0.559631 479.789673 -274.752014 +0.559631 516.198181 -274.752014 +75.181213 516.198181 -274.769958 +75.181213 479.789673 -274.769958 +0.940132 479.789673 -224.951599 +75.561630 479.789673 -224.969543 +75.561630 516.198181 -224.969666 +0.931725 516.198181 -226.048523 +0.940132 516.198181 -224.951599 +-74.644150 479.789673 -324.522034 +-74.644150 516.198181 -324.522034 +-0.022568 516.198181 -324.539978 +-0.022568 479.789673 -324.539978 +-74.263649 479.789673 -274.721619 +0.357933 479.789673 -274.739563 +0.357933 516.198181 -274.739685 +-74.272049 516.198181 -275.818420 +-74.263649 516.198181 -274.721619 +-74.644150 516.831482 -324.522034 +-74.644150 553.240112 -324.522034 +-0.022560 553.240112 -324.540100 +-0.022560 516.831482 -324.540100 +-74.263733 516.831482 -274.721619 +0.357857 516.831482 -274.739685 +0.357857 553.240112 -274.739685 +-74.272049 553.240112 -275.818542 +-74.263733 553.240112 -274.721619 +-74.644226 553.715332 -324.522034 +-74.644226 590.123840 -324.522034 +-0.022560 590.123840 -324.540100 +-0.022560 553.715332 -324.540100 +-74.263817 553.715332 -274.721619 +0.357773 553.715332 -274.739685 +0.357773 590.123840 -274.739685 +-74.272049 590.123840 -275.818542 +-74.263817 590.123840 -274.721619 +-74.644081 479.789673 -274.752014 +-74.644081 516.198181 -274.752014 +-0.022499 516.198181 -274.770081 +-0.022499 479.789673 -274.770081 +-74.263664 479.789673 -224.951599 +0.357918 479.789673 -224.969543 +0.357918 516.198181 -224.969666 +-74.271988 516.198181 -226.048401 +-74.263664 516.198181 -224.951599 +-74.644165 516.831482 -274.752014 +-74.644165 553.240112 -274.752014 +-0.022667 553.240112 -274.770081 +-0.022667 516.831482 -274.770081 +-74.263832 516.831482 -224.951721 +0.357834 516.831482 -224.969543 +0.357834 553.240112 -224.969666 +-74.272064 553.240112 -226.048523 +-74.263832 553.240112 -224.951721 +50.234726 184.344711 -212.832336 +50.234726 220.753220 -212.832336 +50.252762 220.753220 -138.210876 +50.252762 184.344711 -138.210876 +0.434303 184.344711 -212.451965 +0.452232 184.344711 -137.830383 +0.452332 220.753220 -137.830383 +1.531166 220.753220 -212.460266 +0.434303 220.753220 -212.451965 +50.234741 221.386520 -212.832458 +50.234741 257.795135 -212.832458 +50.252762 257.795135 -138.210876 +50.252762 221.386520 -138.210876 +0.434402 221.386520 -212.452087 +0.452332 221.386520 -137.830383 +0.452332 257.795135 -137.830383 +1.531174 257.795135 -212.460388 +0.434402 257.795135 -212.452087 +0.464661 184.344711 -212.832458 +0.464661 220.753220 -212.832458 +0.482689 220.753220 -138.210754 +0.482689 184.344711 -138.210754 +-49.335667 184.344711 -212.451843 +-49.317738 184.344711 -137.830383 +-49.317638 220.753220 -137.830383 +-48.238800 220.753220 -212.460266 +-49.335667 220.753220 -212.451843 +0.464760 221.386520 -212.832458 +0.464760 257.795135 -212.832458 +0.482788 257.795135 -138.210876 +0.482788 221.386520 -138.210876 +-49.335667 221.386520 -212.452087 +-49.317638 221.386520 -137.830505 +-49.317638 257.795135 -137.830505 +-48.238800 257.795135 -212.460266 +-49.335667 257.795135 -212.452087 +0.464760 258.270355 -212.832458 +0.464760 294.678894 -212.832458 +0.482788 294.678894 -138.210999 +0.482788 258.270355 -138.210999 +-49.335663 258.270355 -212.452209 +-49.317635 258.270355 -137.830627 +-49.317539 294.678894 -137.830627 +-48.238705 294.678894 -212.460388 +-49.335663 294.678894 -212.452209 +50.234772 184.344696 -288.036194 +50.234772 220.753220 -288.036194 +50.252701 220.753220 -213.414612 +50.252701 184.344711 -213.414612 +0.434341 184.344696 -287.655701 +0.452271 184.344711 -213.034119 +0.452370 220.753220 -213.034119 +1.531113 220.753220 -287.664124 +0.434341 220.753220 -287.655701 +50.234772 221.386520 -288.036194 +50.234772 257.795135 -288.036194 +50.252808 257.795135 -213.414612 +50.252808 221.386520 -213.414612 +0.434349 221.386520 -287.655823 +0.452370 221.386520 -213.034119 +0.452370 257.795135 -213.034241 +1.531212 257.795135 -287.664124 +0.434349 257.795135 -287.655823 +0.464699 184.344696 -288.036072 +0.464699 220.753220 -288.036072 +0.482727 220.753220 -213.414490 +0.482727 184.344711 -213.414490 +-49.335728 184.344696 -287.655701 +-49.317699 184.344711 -213.034119 +-49.317600 220.753220 -213.034119 +-48.238861 220.753220 -287.664001 +-49.335728 220.753220 -287.655701 +-15.810349 184.344711 25.065125 +-15.810349 220.753235 25.065125 +58.811157 220.753235 25.047119 +58.811157 184.344711 25.047119 +-15.429932 184.344727 74.865540 +59.191650 184.344727 74.847656 +59.191650 220.753235 74.847534 +-15.438255 220.753235 73.768677 +-15.429932 220.753235 74.865540 +-15.810364 184.344727 74.835205 +-15.810364 220.753235 74.835205 +58.811218 220.753235 74.817200 +58.811218 184.344727 74.817200 +-15.429863 184.344727 124.635559 +59.191635 184.344727 124.617615 +59.191635 220.753235 124.617493 +-15.438271 220.753235 123.538635 +-15.429863 220.753235 124.635559 +-15.810448 221.386536 74.835083 +-15.810448 257.795135 74.835083 +58.811127 257.795135 74.817078 +58.811127 221.386536 74.817078 +-15.430031 221.386536 124.635559 +59.191559 221.386536 124.617493 +59.191559 257.795135 124.617493 +-15.438271 257.795135 123.538635 +-15.430031 257.795135 124.635559 +-91.014145 184.344711 25.065063 +-91.014145 220.753235 25.065063 +-16.392563 220.753235 25.047180 +-16.392563 184.344711 25.047180 +-90.633644 184.344727 74.865540 +-16.012062 184.344727 74.847595 +-16.012062 220.753235 74.847473 +-90.642044 220.753235 73.768738 +-90.633644 220.753235 74.865540 +-91.014145 221.386536 25.065063 +-91.014145 257.795135 25.065063 +-16.392555 257.795135 25.047058 +-16.392555 221.386536 25.047058 +-90.633728 221.386536 74.865540 +-16.012138 221.386536 74.847473 +-16.012138 257.795135 74.847473 +-90.642044 257.795135 73.768616 +-90.633728 257.795135 74.865540 +-91.014221 258.270386 25.065063 +-91.014221 294.678894 25.065063 +-16.392555 294.678894 25.047058 +-16.392555 258.270386 25.047058 +-90.633812 258.270386 74.865479 +-16.012222 258.270386 74.847473 +-16.012222 294.678894 74.847473 +-90.642044 294.678894 73.768616 +-90.633812 294.678894 74.865479 +-91.014076 184.344727 74.835144 +-91.014076 220.753235 74.835144 +-16.392494 220.753235 74.817139 +-16.392494 184.344727 74.817139 +-90.633659 184.344727 124.635559 +-16.012077 184.344727 124.617554 +-16.012077 220.753235 124.617493 +-90.641983 220.753235 123.538696 +-90.633659 220.753235 124.635559 +-91.014160 221.386536 74.835144 +-91.014160 257.795135 74.835144 +-16.392662 257.795135 74.817139 +-16.392662 221.386536 74.817139 +-90.633827 221.386536 124.635498 +-16.012161 221.386536 124.617554 +-16.012161 257.795135 124.617432 +-90.642059 257.795135 123.538635 +-90.633827 257.795135 124.635498 +-91.014244 258.270386 74.835144 +-91.014244 294.678894 74.835144 +-16.392654 294.678894 74.817017 +-16.392654 258.270386 74.817017 +-90.633827 258.270386 124.635498 +-16.012238 258.270386 124.617432 +-16.012238 294.678894 124.617371 +-90.642059 294.678894 123.538635 +-90.633827 294.678894 124.635498 +-91.014389 295.428864 25.065063 +-91.014389 331.837463 25.065063 +-16.392555 331.837463 25.046936 +-16.392555 295.428864 25.046936 +-90.633888 295.428864 74.865417 +-16.012306 295.428864 74.847412 +-16.012306 331.837463 74.847412 +-90.642044 331.837463 73.768555 +-90.633888 331.837463 74.865417 +50.234726 184.344727 207.836487 +50.234726 220.753265 207.836487 +50.252762 220.753265 282.458008 +50.252762 184.344742 282.458008 +0.434303 184.344727 208.216919 +0.452232 184.344742 282.838501 +0.452332 220.753265 282.838501 +1.531166 220.753265 208.208618 +0.434303 220.753265 208.216919 +50.234741 221.386566 207.836426 +50.234741 257.795166 207.836426 +50.252762 257.795166 282.458008 +50.252762 221.386566 282.458008 +0.434402 221.386566 208.216858 +0.452332 221.386566 282.838501 +0.452332 257.795166 282.838501 +1.531174 257.795166 208.208496 +0.434402 257.795166 208.216858 +0.464661 184.344727 207.836487 +0.464661 220.753265 207.836487 +0.482689 220.753265 282.458069 +0.482689 184.344742 282.458069 +-49.335667 184.344727 208.216980 +-49.317738 184.344742 282.838501 +-49.317638 220.753265 282.838501 +-48.238800 220.753265 208.208557 +-49.335667 220.753265 208.216980 +0.464760 221.386566 207.836426 +0.464760 257.795166 207.836426 +0.482788 257.795166 282.457947 +0.482788 221.386566 282.458008 +-49.335667 221.386566 208.216797 +-49.317638 221.386566 282.838440 +-49.317638 257.795166 282.838379 +-48.238800 257.795166 208.208557 +-49.335667 257.795166 208.216797 +0.464760 258.270386 207.836426 +0.464760 294.678925 207.836426 +0.482788 294.678925 282.457886 +0.482788 258.270386 282.457886 +-49.335663 258.270386 208.216736 +-49.317635 258.270386 282.838318 +-49.317539 294.678925 282.838318 +-48.238705 294.678925 208.208496 +-49.335663 294.678925 208.216736 +50.234772 184.344727 132.632690 +50.234772 220.753265 132.632690 +50.252701 220.753265 207.254272 +50.252701 184.344727 207.254272 +0.434341 184.344727 133.013184 +0.452271 184.344727 207.634766 +0.452370 220.753265 207.634766 +1.531113 220.753265 133.004822 +0.434341 220.753265 133.013184 +50.234772 221.386566 132.632690 +50.234772 257.795166 132.632690 +50.252808 257.795166 207.254272 +50.252808 221.386566 207.254272 +0.434349 221.386566 133.013123 +0.452370 221.386566 207.634705 +0.452370 257.795166 207.634705 +1.531212 257.795166 133.004822 +0.434349 257.795166 133.013123 +50.234772 258.270386 132.632629 +50.234772 294.678925 132.632629 +50.252808 294.678925 207.254272 +50.252808 258.270386 207.254272 +0.434349 258.270386 133.013000 +0.452377 258.270386 207.634644 +0.452377 294.678925 207.634644 +1.531212 294.678925 133.004822 +0.434349 294.678925 133.013000 +0.464699 184.344727 132.632751 +0.464699 220.753265 132.632751 +0.482727 220.753265 207.254333 +0.482727 184.344727 207.254333 +-49.335728 184.344727 133.013184 +-49.317699 184.344727 207.634766 +-49.317600 220.753265 207.634766 +-48.238861 220.753265 133.004883 +-49.335728 220.753265 133.013184 +0.464706 221.386566 132.632690 +0.464706 257.795166 132.632690 +0.482735 257.795166 207.254211 +0.482735 221.386566 207.254211 +-49.335625 221.386566 133.013000 +-49.317696 221.386566 207.634705 +-49.317596 257.795166 207.634705 +-48.238762 257.795166 133.004761 +-49.335625 257.795166 133.013000 +0.464706 258.270386 132.632629 +0.464706 294.678925 132.632629 +0.482834 294.678925 207.254211 +0.482834 258.270386 207.254211 +-49.335625 258.270386 133.013000 +-49.317596 258.270386 207.634583 +-49.317497 294.678925 207.634583 +-48.238762 294.678925 133.004761 +-49.335625 294.678925 133.013000 +0.464806 295.428894 132.632507 +0.464806 331.837494 132.632507 +0.482834 331.837494 207.254028 +0.482834 295.428894 207.254028 +-49.335526 295.428894 133.012939 +-49.317497 295.428894 207.634521 +-49.317497 331.837494 207.634521 +-48.238663 331.837494 133.004700 +-49.335526 331.837494 133.012939 +50.234726 184.108826 364.416748 +50.234726 220.517365 364.416748 +50.252762 220.517365 439.038269 +50.252762 184.108841 439.038269 +0.434303 184.108826 364.797180 +0.452232 184.108841 439.418762 +0.452332 220.517365 439.418762 +1.531166 220.517365 364.788879 +0.434303 220.517365 364.797180 +0.464661 184.108826 364.416748 +0.464661 220.517365 364.416748 +0.482689 220.517365 439.038330 +0.482689 184.108841 439.038330 +-49.335667 184.108826 364.797241 +-49.317738 184.108841 439.418762 +-49.317638 220.517365 439.418762 +-48.238800 220.517365 364.788818 +-49.335667 220.517365 364.797241 +0.464760 221.150665 364.416687 +0.464760 257.559265 364.416687 +0.482788 257.559265 439.038239 +0.482788 221.150665 439.038239 +-49.335667 221.150665 364.797058 +-49.317638 221.150665 439.418671 +-49.317638 257.559265 439.418671 +-48.238800 257.559265 364.788818 +-49.335667 257.559265 364.797058 +50.234772 184.108826 289.212952 +50.234772 220.517365 289.212952 +50.252701 220.517365 363.834534 +50.252701 184.108826 363.834534 +0.434341 184.108826 289.593445 +0.452271 184.108826 364.215027 +0.452370 220.517365 364.215027 +1.531113 220.517365 289.585083 +0.434341 220.517365 289.593445 +50.234772 221.150665 289.212952 +50.234772 257.559265 289.212952 +50.252808 257.559265 363.834534 +50.252808 221.150665 363.834534 +0.434349 221.150665 289.593384 +0.452370 221.150665 364.214966 +0.452370 257.559265 364.214966 +1.531212 257.559265 289.585083 +0.434349 257.559265 289.593384 +0.464699 184.108826 289.213013 +0.464699 220.517365 289.213013 +0.482727 220.517365 363.834595 +0.482727 184.108826 363.834595 +-49.335728 184.108826 289.593445 +-49.317699 184.108826 364.215027 +-49.317600 220.517365 364.215027 +-48.238861 220.517365 289.585144 +-49.335728 220.517365 289.593445 +0.464706 221.150665 289.212952 +0.464706 257.559265 289.212952 +0.482735 257.559265 363.834473 +0.482735 221.150665 363.834473 +-49.335625 221.150665 289.593323 +-49.317696 221.150665 364.214966 +-49.317596 257.559265 364.214966 +-48.238762 257.559265 289.585022 +-49.335625 257.559265 289.593262 +85.526978 480.048401 -90.746643 +85.526978 522.092957 -90.746643 +85.547791 522.092957 -4.573608 +85.547791 480.048431 -4.573608 +28.017448 480.048401 -90.307190 +28.038155 480.048431 -4.134277 +28.038261 522.092957 -4.134277 +29.284103 522.092957 -90.316895 +28.017448 522.092957 -90.307190 +85.526978 523.448792 -90.746643 +85.526978 565.493408 -90.746643 +85.547791 565.493408 -4.573608 +85.547791 523.448792 -4.573608 +28.017448 523.448792 -90.307190 +28.038155 523.448792 -4.134277 +28.038261 565.493408 -4.134338 +29.284103 565.493408 -90.316895 +28.017448 565.493408 -90.307190 +85.526978 567.092346 -90.746643 +85.526978 609.136902 -90.746643 +85.547791 609.136902 -4.573608 +85.547791 567.092407 -4.573608 +28.017448 567.092346 -90.307190 +28.038155 567.092407 -4.134338 +28.038261 609.136902 -4.134338 +29.284103 609.136902 -90.316895 +28.017448 609.136902 -90.307190 +26.951828 480.048401 -90.746582 +26.951828 522.092957 -90.746582 +26.972641 522.092957 -4.573547 +26.972641 480.048431 -4.573547 +-30.557693 480.048401 -90.307190 +-30.536880 480.048431 -4.134277 +-30.536880 522.092957 -4.134277 +-29.291031 522.092957 -90.316895 +-30.557693 522.092957 -90.307190 +26.951828 523.448792 -90.746582 +26.951828 565.493408 -90.746582 +26.972641 565.493408 -4.573608 +26.972641 523.448792 -4.573547 +-30.557693 523.448792 -90.307190 +-30.536880 523.448792 -4.134277 +-30.536880 565.493408 -4.134277 +-29.291031 565.493408 -90.316895 +-30.557693 565.493408 -90.307190 +26.951828 567.092346 -90.746582 +26.951828 609.136902 -90.746582 +26.972641 609.136902 -4.573608 +26.972641 567.092407 -4.573608 +-30.557693 567.092346 -90.307190 +-30.536880 567.092407 -4.134277 +-30.536880 609.136902 -4.134277 +-29.291031 609.136902 -90.316895 +-30.557693 609.136902 -90.307190 +52.878479 610.492737 -90.746521 +52.878479 652.537292 -90.746521 +52.899307 652.537292 -4.573608 +52.899307 610.492737 -4.573608 +-4.631035 610.492737 -90.307190 +-4.610222 610.492737 -4.134338 +-4.610222 652.537292 -4.134338 +-3.364380 652.537292 -90.316833 +-4.631035 652.537292 -90.307190 +-4.233650 480.048401 -208.807556 +-4.233650 522.092957 -208.807556 +81.939331 522.092957 -208.828308 +81.939331 480.048401 -208.828308 +-3.794334 480.048401 -151.297913 +82.378632 480.048401 -151.318787 +82.378632 522.092957 -151.318787 +-3.803947 522.092957 -152.564636 +-3.794334 522.092957 -151.298035 +-4.233582 480.048401 -150.232239 +-4.233582 522.092957 -150.232239 +81.939392 522.092957 -150.253113 +81.939392 480.048401 -150.253113 +-3.794266 480.048401 -92.722778 +82.378723 480.048401 -92.743591 +82.378723 522.092957 -92.743591 +-3.803879 522.092957 -93.989441 +-3.794266 522.092957 -92.722839 +-4.233582 523.448792 -150.232239 +-4.233582 565.493408 -150.232239 +81.939392 565.493408 -150.253113 +81.939392 523.448792 -150.253113 +-3.794266 523.448792 -92.722778 +82.378723 523.448792 -92.743591 +82.378723 565.493408 -92.743591 +-3.803879 565.493408 -93.989441 +-3.794266 565.493408 -92.722839 +-91.382088 480.048401 -208.807556 +-91.382088 522.092957 -208.807556 +-5.209229 522.092957 -208.828308 +-5.209229 480.048401 -208.828308 +-90.942780 480.048401 -151.298035 +-4.769806 480.048401 -151.318787 +-4.769798 522.092957 -151.318787 +-90.952393 522.092957 -152.564636 +-90.942780 522.092957 -151.298035 +-91.382133 480.048401 -150.232361 +-91.382133 522.092957 -150.232361 +-5.209160 522.092957 -150.253113 +-5.209160 480.048401 -150.252991 +-90.942703 480.048401 -92.722778 +-4.769730 480.048401 -92.743530 +-4.769730 522.092957 -92.743591 +-90.952324 522.092957 -93.989380 +-90.942703 522.092957 -92.722778 +-91.382133 523.448792 -150.232361 +-91.382133 565.493408 -150.232361 +-5.209160 565.493408 -150.253113 +-5.209160 523.448792 -150.253113 +-90.942703 523.448792 -92.722778 +-4.769730 523.448792 -92.743530 +-4.769730 565.493408 -92.743591 +-90.952324 565.493408 -93.989380 +-90.942703 565.493408 -92.722778 +-91.382133 567.092346 -150.232361 +-91.382133 609.136902 -150.232361 +-5.209160 609.136902 -150.253113 +-5.209160 567.092346 -150.253113 +-90.942703 567.092346 -92.722778 +-4.769730 567.092346 -92.743530 +-4.769730 609.136902 -92.743591 +-90.952324 609.136902 -93.989380 +-90.942703 609.136902 -92.722778 +-91.382057 610.492737 -134.833191 +-91.382057 652.537292 -134.833191 +-5.209091 652.537292 -134.854004 +-5.209091 610.492737 -134.854004 +-90.942741 610.492737 -77.323669 +-4.769661 610.492737 -77.344360 +-4.769661 652.537292 -77.344482 +-90.952354 652.537292 -78.590271 +-90.942741 652.537292 -77.323669 +-30.522522 480.048401 -90.746521 +-30.522522 522.092957 -90.746521 +-30.501816 522.092957 -4.573608 +-30.501816 480.048431 -4.573608 +-88.032043 480.048401 -90.307190 +-88.011345 480.048431 -4.134216 +-88.011230 522.092957 -4.134216 +-86.765388 522.092957 -90.316772 +-88.032043 522.092957 -90.307190 +-30.522522 523.448792 -90.746521 +-30.522522 565.493408 -90.746521 +-30.501816 565.493408 -4.573608 +-30.501816 523.448792 -4.573608 +-88.032043 523.448792 -90.307190 +-88.011345 523.448792 -4.134216 +-88.011230 565.493408 -4.134216 +-86.765388 565.493408 -90.316833 +-88.032043 565.493408 -90.307190 +-30.522522 567.092346 -90.746521 +-30.522522 609.136902 -90.746521 +-30.501816 609.136902 -4.573608 +-30.501816 567.092407 -4.573608 +-88.032043 567.092346 -90.307190 +-88.011345 567.092407 -4.134216 +-88.011230 609.136902 -4.134216 +-86.765388 609.136902 -90.316833 +-88.032043 609.136902 -90.307190 +91.900269 480.451111 326.717590 +91.900269 522.495667 326.717590 +91.921082 522.495667 412.890625 +91.921082 480.451111 412.890625 +34.390747 480.451111 327.157043 +34.411438 480.451111 413.329926 +34.411560 522.495667 413.329926 +35.657394 522.495667 327.147339 +34.390747 522.495667 327.157043 +33.325119 480.451111 326.717651 +33.325119 522.495667 326.717651 +33.345932 522.495667 412.890656 +33.345932 480.451111 412.890656 +-24.184402 480.451111 327.157043 +-24.163589 480.451111 413.329956 +-24.163589 522.495667 413.329956 +-22.917740 522.495667 327.147339 +-24.184402 522.495667 327.157043 +2.139641 480.451111 208.656738 +2.139641 522.495667 208.656738 +88.312622 522.495667 208.635925 +88.312622 480.451111 208.635925 +2.578957 480.451111 266.166260 +88.751923 480.451111 266.145447 +88.751923 522.495667 266.145447 +2.569344 522.495667 264.899536 +2.578957 522.495667 266.166138 +2.139641 523.851501 208.656738 +2.139641 565.896057 208.656738 +88.312622 565.896057 208.635925 +88.312622 523.851501 208.635925 +2.578957 523.851501 266.166260 +88.751923 523.851501 266.145447 +88.751923 565.896057 266.145447 +2.569344 565.896057 264.899536 +2.578957 565.896057 266.166138 +2.139709 480.451111 267.231934 +2.139709 522.495667 267.231934 +88.312683 522.495667 267.211121 +88.312683 480.451111 267.211121 +2.579025 480.451111 324.741455 +88.752014 480.451111 324.720642 +88.752014 522.495667 324.720642 +2.569412 522.495667 323.474792 +2.579025 522.495667 324.741394 +-85.008797 480.451111 208.656677 +-85.008797 522.495667 208.656677 +1.164063 522.495667 208.635864 +1.164063 480.451111 208.635864 +-84.569489 480.451111 266.166199 +1.603485 480.451111 266.145508 +1.603493 522.495667 266.145386 +-84.579102 522.495667 264.899597 +-84.569489 522.495667 266.166199 +-85.008797 523.851501 208.656677 +-85.008797 565.896057 208.656677 +1.164063 565.896057 208.635864 +1.164063 523.851501 208.635864 +-84.569489 523.851501 266.166199 +1.603485 523.851501 266.145508 +1.603493 565.896057 266.145386 +-84.579102 565.896057 264.899597 +-84.569489 565.896057 266.166199 +-85.008797 567.495056 208.656677 +-85.008797 609.539612 208.656677 +1.164063 609.539612 208.635864 +1.164063 567.495056 208.635864 +-84.569489 567.495056 266.166199 +1.603485 567.495056 266.145508 +1.603493 609.539612 266.145386 +-84.579102 609.539612 264.899597 +-84.569489 609.539612 266.166199 +-85.008842 480.451111 267.231934 +-85.008842 522.495667 267.231873 +1.164131 522.495667 267.211182 +1.164131 480.451111 267.211182 +-84.569412 480.451111 324.741455 +1.603561 480.451111 324.720703 +1.603561 522.495667 324.720642 +-84.579033 522.495667 323.474854 +-84.569412 522.495667 324.741455 +-85.008842 523.851501 267.231873 +-85.008842 565.896057 267.231873 +1.164131 565.896057 267.211182 +1.164131 523.851501 267.211182 +-84.569412 523.851501 324.741455 +1.603561 523.851501 324.720703 +1.603561 565.896057 324.720642 +-84.579033 565.896057 323.474854 +-84.569412 565.896057 324.741455 +-24.149231 480.451111 326.717712 +-24.149231 522.495667 326.717712 +-24.128525 522.495667 412.890625 +-24.128525 480.451111 412.890625 +-81.658752 480.451111 327.157043 +-81.638054 480.451111 413.330048 +-81.637939 522.495667 413.330048 +-80.392097 522.495667 327.147461 +-81.658752 522.495667 327.157043 +-24.149231 523.851501 326.717712 +-24.149231 565.896057 326.717712 +-24.128525 565.896057 412.890625 +-24.128525 523.851501 412.890625 +-81.658752 523.851501 327.157043 +-81.638054 523.851501 413.330048 +-81.637939 565.896057 413.330048 +-80.392097 565.896057 327.147400 +-81.658752 565.896057 327.157043 +2.139641 271.101929 469.782440 +2.139641 313.146515 469.782440 +88.312622 313.146515 469.761597 +88.312622 271.101929 469.761597 +2.578957 271.101959 527.291992 +88.751923 271.101959 527.271179 +88.751923 313.146515 527.271179 +2.569336 313.146515 526.025269 +2.578957 313.146515 527.291870 +91.900269 184.057999 587.843201 +91.900269 226.102570 587.843201 +91.921082 226.102570 674.016235 +91.921082 184.057999 674.016235 +34.390747 184.057999 588.282593 +34.411438 184.057999 674.455566 +34.411560 226.102570 674.455566 +35.657394 226.102570 588.272949 +34.390747 226.102570 588.282593 +33.325119 184.057999 587.843262 +33.325119 226.102570 587.843262 +33.345932 226.102570 674.016296 +33.345932 184.057999 674.016296 +-24.184402 184.057999 588.282654 +-24.163589 184.057999 674.455566 +-24.163589 226.102570 674.455566 +-22.917740 226.102570 588.272949 +-24.184402 226.102570 588.282654 +2.139641 184.057999 469.782349 +2.139641 226.102554 469.782349 +88.312622 226.102554 469.761536 +88.312622 184.057999 469.761536 +2.578957 184.057999 527.291870 +88.751923 184.057999 527.271057 +88.751923 226.102554 527.271057 +2.569344 226.102554 526.025146 +2.578957 226.102554 527.291809 +2.139641 227.458389 469.782349 +2.139641 269.502960 469.782318 +88.312622 269.502960 469.761505 +88.312622 227.458389 469.761536 +2.578957 227.458389 527.291870 +88.751923 227.458389 527.271057 +88.751923 269.502960 527.271057 +2.569344 269.502960 526.025146 +2.578957 269.502960 527.291809 +2.139709 184.057999 528.357544 +2.139709 226.102554 528.357544 +88.312683 226.102554 528.336731 +88.312683 184.057999 528.336731 +2.579025 184.057999 585.867126 +88.752014 184.057999 585.846252 +88.752014 226.102570 585.846252 +2.569412 226.102570 584.600403 +2.579025 226.102570 585.867004 +-85.008797 184.057999 469.782288 +-85.008797 226.102554 469.782288 +1.164063 226.102554 469.761475 +1.164063 184.057999 469.761475 +-84.569489 184.057999 527.291870 +1.603485 184.057999 527.271118 +1.603493 226.102554 527.270996 +-84.579102 226.102554 526.025208 +-84.569489 226.102554 527.291870 +-85.008797 227.458389 469.782288 +-85.008797 269.502960 469.782288 +1.164063 269.502960 469.761475 +1.164063 227.458389 469.761475 +-84.569489 227.458389 527.291870 +1.603485 227.458389 527.271118 +1.603493 269.502960 527.270996 +-84.579102 269.502960 526.025208 +-84.569489 269.502960 527.291870 +-85.008797 271.101929 469.782288 +-85.008797 313.146515 469.782288 +1.164063 313.146515 469.761475 +1.164063 271.101929 469.761475 +-84.569489 271.101959 527.291870 +1.603485 271.101959 527.271118 +1.603493 313.146515 527.270996 +-84.579102 313.146515 526.025208 +-84.569489 313.146515 527.291870 +-85.008842 184.057999 528.357483 +-85.008842 226.102554 528.357483 +1.164131 226.102554 528.336792 +1.164131 184.057999 528.336792 +-84.569412 184.057999 585.867065 +1.603561 184.057999 585.846313 +1.603561 226.102570 585.846252 +-84.579033 226.102570 584.600403 +-84.569412 226.102570 585.867065 +-24.149231 184.057999 587.843323 +-24.149231 226.102570 587.843323 +-24.128525 226.102570 674.016235 +-24.128525 184.057999 674.016235 +-81.658752 184.057999 588.282654 +-81.638054 184.057999 674.455688 +-81.637939 226.102570 674.455688 +-80.392097 226.102570 588.273071 +-81.658752 226.102570 588.282654 +-24.149231 227.458389 587.843323 +-24.149231 269.502960 587.843323 +-24.128525 269.502960 674.016235 +-24.128525 227.458389 674.016235 +-81.658752 227.458389 588.282654 +-81.638054 227.458389 674.455688 +-81.637939 269.502960 674.455688 +-80.392097 269.502960 588.273071 +-81.658752 269.502960 588.282654 +91.900269 184.057999 795.948608 +91.900269 226.102570 795.948608 +91.921082 226.102570 882.121582 +91.921082 184.057999 882.121582 +34.390747 184.057999 796.388000 +34.411438 184.057999 882.560913 +34.411560 226.102570 882.560913 +35.657394 226.102570 796.378296 +34.390747 226.102570 796.388000 +91.900269 227.458389 795.948608 +91.900269 269.502960 795.948547 +91.921082 269.502960 882.121582 +91.921082 227.458389 882.121582 +34.390747 227.458389 796.388000 +34.411438 227.458389 882.560913 +34.411560 269.502960 882.560913 +35.657394 269.502960 796.378296 +34.390747 269.502960 796.388000 +33.325119 184.057999 795.948608 +33.325119 226.102570 795.948608 +33.345932 226.102570 882.121643 +33.345932 184.057999 882.121643 +-24.184402 184.057999 796.388000 +-24.163589 184.057999 882.560913 +-24.163589 226.102570 882.560913 +-22.917740 226.102570 796.378296 +-24.184402 226.102570 796.388000 +33.325119 227.458389 795.948608 +33.325119 269.502960 795.948608 +33.345932 269.502960 882.121582 +33.345932 227.458389 882.121643 +-24.184402 227.458389 796.388000 +-24.163589 227.458389 882.560913 +-24.163589 269.502960 882.560913 +-22.917740 269.502960 796.378296 +-24.184402 269.502960 796.388000 +2.139641 184.057999 677.887695 +2.139641 226.102554 677.887695 +88.312622 226.102554 677.866882 +88.312622 184.057999 677.866882 +2.578957 184.057999 735.397217 +88.751923 184.057999 735.376404 +88.751923 226.102554 735.376404 +2.569344 226.102554 734.130554 +2.578957 226.102554 735.397095 +2.139709 184.057999 736.462891 +2.139709 226.102554 736.462891 +88.312683 226.102554 736.442078 +88.312683 184.057999 736.442078 +2.579025 184.057999 793.972412 +88.752014 184.057999 793.951599 +88.752014 226.102570 793.951599 +2.569412 226.102570 792.705750 +2.579025 226.102570 793.972351 +-85.008797 184.057999 677.887634 +-85.008797 226.102554 677.887634 +1.164063 226.102554 677.866821 +1.164063 184.057999 677.866821 +-84.569489 184.057999 735.397156 +1.603485 184.057999 735.376465 +1.603493 226.102554 735.376343 +-84.579102 226.102554 734.130554 +-84.569489 226.102554 735.397156 +-85.008842 184.057999 736.462830 +-85.008842 226.102554 736.462830 +1.164131 226.102554 736.442139 +1.164131 184.057999 736.442139 +-84.569412 184.057999 793.972412 +1.603561 184.057999 793.951660 +1.603561 226.102570 793.951599 +-84.579033 226.102570 792.705811 +-84.569412 226.102570 793.972412 +-85.008842 227.458389 736.462830 +-85.008842 269.502960 736.462830 +1.164131 269.502960 736.442139 +1.164131 227.458389 736.442139 +-84.569412 227.458389 793.972412 +1.603561 227.458389 793.951660 +1.603561 269.502960 793.951599 +-84.579033 269.502960 792.705811 +-84.569412 269.502960 793.972412 +-24.149231 184.057999 795.948669 +-24.149231 226.102570 795.948669 +-24.128525 226.102570 882.121582 +-24.128525 184.057999 882.121582 +-81.658752 184.057999 796.388000 +-81.638054 184.057999 882.561035 +-81.637939 226.102570 882.561035 +-80.392097 226.102570 796.378357 +-81.658752 226.102570 796.388000 +-24.149231 227.458389 795.948669 +-24.149231 269.502960 795.948669 +-24.128525 269.502960 882.121582 +-24.128525 227.458389 882.121582 +-81.658752 227.458389 796.388000 +-81.638054 227.458389 882.561035 +-81.637939 269.502960 882.560974 +-80.392097 269.502960 796.378357 +-81.658752 269.502960 796.388000 +-24.149231 271.101959 795.948669 +-24.149231 313.146515 795.948669 +-24.128525 313.146515 882.121582 +-24.128525 271.101959 882.121582 +-81.658752 271.101959 796.388000 +-81.638054 271.101959 882.560974 +-81.637939 313.146515 882.560974 +-80.392097 313.146515 796.378357 +-81.658752 313.146515 796.388000 +-77.193710 323.720703 -756.664978 +-33.610245 323.720703 -756.664978 +-77.193710 323.720703 -816.330750 +-33.610245 323.720703 -816.330750 +-77.193710 207.784164 -756.664978 +-33.610245 207.784164 -756.664978 +-77.193710 207.784164 -816.330750 +-33.610245 207.784164 -816.330750 +-75.061211 183.350571 -759.405579 +-35.742756 183.350571 -759.405579 +-75.061211 183.350571 -813.590149 +-35.742756 183.350571 -813.590149 +-75.692474 323.720703 -814.756287 +-75.692474 323.720703 -758.239441 +-35.111488 323.720703 -758.239441 +-35.111488 323.720703 -814.756287 +-73.638229 290.395111 -811.888855 +-73.638229 290.395111 -760.920227 +-37.165726 290.395111 -760.920227 +-37.165726 290.395111 -811.888855 +-73.250549 302.476257 -817.289246 +-29.667084 302.476257 -817.289246 +-73.250549 302.476257 -876.955017 +-29.667084 302.476257 -876.955017 +-73.250549 207.739456 -817.289246 +-29.667084 207.739456 -817.289246 +-73.250549 207.739456 -876.955017 +-29.667084 207.739456 -876.955017 +-71.118050 183.305862 -820.029846 +-31.799591 183.305862 -820.029846 +-71.118050 183.305862 -874.214417 +-31.799591 183.305862 -874.214417 +-71.749313 302.476257 -875.380554 +-71.749313 302.476257 -818.863708 +-31.168327 302.476257 -818.863708 +-31.168327 302.476257 -875.380554 +-69.695068 269.171295 -872.513123 +-69.695068 269.171295 -821.544495 +-33.222565 269.171295 -821.544495 +-33.222565 269.171295 -872.513123 +-26.671051 270.610443 -817.289246 +16.912415 270.610443 -817.289246 +-26.671051 270.610443 -876.955017 +16.912415 270.610443 -876.955017 +-26.671051 207.739456 -817.289246 +16.912415 207.739456 -817.289246 +-26.671051 207.739456 -876.955017 +16.912415 207.739456 -876.955017 +-24.538544 183.305862 -820.029846 +14.779907 183.305862 -820.029846 +-24.538544 183.305862 -874.214417 +14.779907 183.305862 -874.214417 +-25.169815 270.610443 -875.380554 +-25.169815 270.610443 -818.863708 +15.411171 270.610443 -818.863708 +15.411171 270.610443 -875.380554 +-23.115570 237.339645 -872.513123 +-23.115570 237.339661 -821.544495 +13.356934 237.339661 -821.544495 +13.356934 237.339645 -872.513123 +-28.594971 313.097931 -755.184143 +14.988495 313.097931 -755.184143 +-28.594971 313.097931 -814.849915 +14.988495 313.097931 -814.849915 +-28.594971 207.784164 -755.184143 +14.988495 207.784164 -755.184143 +-28.594971 207.784164 -814.849915 +14.988495 207.784164 -814.849915 +-26.462471 183.350571 -757.924744 +12.855988 183.350571 -757.924744 +-26.462471 183.350571 -812.109314 +12.855988 183.350571 -812.109314 +-27.093735 313.097931 -813.275452 +-27.093735 313.097931 -756.758606 +13.487251 313.097931 -756.758606 +13.487251 313.097931 -813.275452 +-25.039490 279.802094 -810.408020 +-25.039490 279.802094 -759.439392 +11.433014 279.802094 -759.439392 +11.433014 279.802094 -810.408020 +-77.193710 621.170898 -499.427917 +-33.610245 621.170898 -499.427917 +-77.193710 621.170898 -559.093689 +-33.610245 621.170898 -559.093689 +-77.193710 505.234375 -499.427917 +-33.610245 505.234375 -499.427917 +-77.193710 505.234375 -559.093689 +-33.610245 505.234375 -559.093689 +-75.061211 480.800781 -502.168518 +-35.742756 480.800781 -502.168518 +-75.061211 480.800781 -556.353088 +-35.742756 480.800781 -556.353088 +-75.692474 621.170898 -557.519226 +-75.692474 621.170898 -501.002380 +-35.111488 621.170898 -501.002380 +-35.111488 621.170898 -557.519226 +-73.638229 587.845337 -554.651794 +-73.638229 587.845337 -503.683167 +-37.165726 587.845337 -503.683167 +-37.165726 587.845337 -554.651794 +-73.250549 599.926453 -560.052185 +-29.667084 599.926453 -560.052185 +-73.250549 599.926453 -619.717957 +-29.667084 599.926453 -619.717957 +-73.250549 505.189667 -560.052185 +-29.667084 505.189667 -560.052185 +-73.250549 505.189667 -619.717957 +-29.667084 505.189667 -619.717957 +-71.118050 480.756073 -562.792786 +-31.799591 480.756073 -562.792786 +-71.118050 480.756073 -616.977356 +-31.799591 480.756073 -616.977356 +-71.749313 599.926453 -618.143494 +-71.749313 599.926453 -561.626648 +-31.168327 599.926453 -561.626648 +-31.168327 599.926453 -618.143494 +-69.695068 566.621460 -615.276062 +-69.695068 566.621460 -564.307434 +-33.222565 566.621460 -564.307434 +-33.222565 566.621460 -615.276062 +-26.671051 568.060669 -560.052185 +16.912415 568.060669 -560.052185 +-26.671051 568.060669 -619.717957 +16.912415 568.060669 -619.717957 +-26.671051 505.189667 -560.052185 +16.912415 505.189667 -560.052185 +-26.671051 505.189667 -619.717957 +16.912415 505.189667 -619.717957 +-24.538544 480.756073 -562.792786 +14.779907 480.756073 -562.792786 +-24.538544 480.756073 -616.977356 +14.779907 480.756073 -616.977356 +-25.169815 568.060669 -618.143494 +-25.169815 568.060669 -561.626648 +15.411171 568.060669 -561.626648 +15.411171 568.060669 -618.143494 +-23.115570 534.789856 -615.276062 +-23.115570 534.789856 -564.307434 +13.356934 534.789856 -564.307434 +13.356934 534.789856 -615.276062 +-28.594971 610.548096 -497.947083 +14.988495 610.548096 -497.947083 +-28.594971 610.548096 -557.612854 +14.988495 610.548096 -557.612854 +-28.594971 505.234375 -497.947083 +14.988495 505.234375 -497.947083 +-28.594971 505.234375 -557.612854 +14.988495 505.234375 -557.612854 +-26.462471 480.800781 -500.687683 +12.855988 480.800781 -500.687683 +-26.462471 480.800781 -554.872253 +12.855988 480.800781 -554.872253 +-27.093735 610.548096 -556.038391 +-27.093735 610.548096 -499.521545 +13.487251 610.548096 -499.521545 +13.487251 610.548096 -556.038391 +-25.039490 577.252319 -553.170959 +-25.039490 577.252319 -502.202332 +11.433014 577.252319 -502.202332 +11.433014 577.252319 -553.170959 +-84.032951 619.746216 -426.448669 +-84.032959 619.746216 -382.865173 +-24.367188 619.746216 -426.448669 +-24.367188 619.746216 -382.865173 +-84.032951 503.809662 -426.448669 +-84.032959 503.809662 -382.865173 +-24.367188 503.809662 -426.448669 +-24.367188 503.809662 -382.865173 +-81.292358 479.376068 -424.316101 +-81.292358 479.376068 -384.997620 +-27.107788 479.376068 -424.316101 +-27.107788 479.376068 -384.997620 +-25.941643 619.746216 -424.947449 +-82.458504 619.746216 -424.947449 +-82.458504 619.746216 -384.366394 +-25.941650 619.746216 -384.366394 +-28.809067 586.420593 -422.893127 +-79.777740 586.420593 -422.893127 +-79.777740 586.420593 -386.420593 +-28.809067 586.420593 -386.420593 +-23.408691 598.501770 -422.505432 +-23.408691 598.501770 -378.922058 +36.257080 598.501770 -422.505432 +36.257080 598.501770 -378.922058 +-23.408691 503.764954 -422.505432 +-23.408691 503.764954 -378.922058 +36.257080 503.764954 -422.505432 +36.257080 503.764954 -378.922058 +-20.668091 479.331360 -420.372986 +-20.668091 479.331360 -381.054504 +33.516479 479.331360 -420.372986 +33.516479 479.331360 -381.054504 +34.682617 598.501770 -421.004211 +-21.834236 598.501770 -421.004211 +-21.834236 598.501770 -380.423279 +34.682617 598.501770 -380.423279 +31.815201 565.196777 -418.950012 +-19.153473 565.196777 -418.950012 +-19.153473 565.196777 -382.477478 +31.815201 565.196777 -382.477478 +-23.408691 566.635925 -375.925964 +-23.408691 566.635925 -332.342468 +36.257080 566.635925 -375.925964 +36.257080 566.635925 -332.342468 +-23.408691 503.764954 -375.925964 +-23.408691 503.764954 -332.342468 +36.257080 503.764954 -375.925964 +36.257080 503.764954 -332.342468 +-20.668091 479.331360 -373.793518 +-20.668091 479.331360 -334.475037 +33.516479 479.331360 -373.793518 +33.516479 479.331360 -334.475037 +34.682617 566.635925 -374.424744 +-21.834236 566.635925 -374.424744 +-21.834236 566.635925 -333.843689 +34.682617 566.635925 -333.843689 +31.815201 533.365173 -372.370544 +-19.153473 533.365173 -372.370544 +-19.153473 533.365173 -335.898010 +31.815201 533.365173 -335.898010 +-85.513794 609.123413 -377.849915 +-85.513802 609.123413 -334.266418 +-25.848022 609.123413 -377.849915 +-25.848022 609.123413 -334.266418 +-85.513794 503.809662 -377.849915 +-85.513802 503.809662 -334.266418 +-25.848022 503.809662 -377.849915 +-25.848022 503.809662 -334.266418 +-82.773193 479.376068 -375.717346 +-82.773193 479.376068 -336.398987 +-28.588623 479.376068 -375.717346 +-28.588623 479.376068 -336.398987 +-27.422485 609.123413 -376.348694 +-83.939339 609.123413 -376.348694 +-83.939339 609.123413 -335.767639 +-27.422485 609.123413 -335.767639 +-30.289902 575.827576 -374.294373 +-81.258575 575.827576 -374.294373 +-81.258575 575.827576 -337.821960 +-30.289909 575.827576 -337.821960 +-77.193710 323.720703 -300.636536 +-33.610245 323.720703 -300.636536 +-77.193710 323.720703 -360.302307 +-33.610245 323.720703 -360.302307 +-77.193710 207.784180 -300.636536 +-33.610245 207.784180 -300.636536 +-77.193710 207.784180 -360.302307 +-33.610245 207.784180 -360.302307 +-75.061211 183.350601 -303.377136 +-35.742756 183.350601 -303.377136 +-75.061211 183.350601 -357.561707 +-35.742756 183.350601 -357.561707 +-75.692474 323.720703 -358.727844 +-75.692474 323.720703 -302.210999 +-35.111488 323.720703 -302.210999 +-35.111488 323.720703 -358.727844 +-73.638229 290.395111 -355.860413 +-73.638229 290.395111 -304.891785 +-37.165726 290.395111 -304.891785 +-37.165726 290.395111 -355.860413 +-73.250549 302.476288 -361.260803 +-29.667084 302.476288 -361.260803 +-73.250549 302.476288 -420.926575 +-29.667084 302.476288 -420.926575 +-73.250549 207.739471 -361.260803 +-29.667084 207.739471 -361.260803 +-73.250549 207.739471 -420.926575 +-29.667084 207.739471 -420.926575 +-71.118050 183.305878 -364.001404 +-31.799591 183.305878 -364.001404 +-71.118050 183.305878 -418.185974 +-31.799591 183.305878 -418.185974 +-71.749313 302.476288 -419.352112 +-71.749313 302.476288 -362.835266 +-31.168327 302.476288 -362.835266 +-31.168327 302.476288 -419.352112 +-69.695068 269.171295 -416.484680 +-69.695068 269.171295 -365.516052 +-33.222565 269.171295 -365.516052 +-33.222565 269.171295 -416.484680 +-26.671051 270.610443 -361.260803 +16.912415 270.610443 -361.260803 +-26.671051 270.610443 -420.926575 +16.912415 270.610443 -420.926575 +-26.671051 207.739471 -361.260803 +16.912415 207.739471 -361.260803 +-26.671051 207.739471 -420.926575 +16.912415 207.739471 -420.926575 +-24.538544 183.305878 -364.001404 +14.779907 183.305878 -364.001404 +-24.538544 183.305878 -418.185974 +14.779907 183.305878 -418.185974 +-25.169815 270.610443 -419.352112 +-25.169815 270.610443 -362.835266 +15.411171 270.610443 -362.835266 +15.411171 270.610443 -419.352112 +-23.115570 237.339661 -416.484680 +-23.115570 237.339676 -365.516052 +13.356934 237.339676 -365.516052 +13.356934 237.339661 -416.484680 +-28.594971 313.097931 -299.155701 +14.988495 313.097931 -299.155701 +-28.594971 313.097931 -358.821472 +14.988495 313.097931 -358.821472 +-28.594971 207.784180 -299.155701 +14.988495 207.784180 -299.155701 +-28.594971 207.784180 -358.821472 +14.988495 207.784180 -358.821472 +-26.462471 183.350601 -301.896301 +12.855988 183.350601 -301.896301 +-26.462471 183.350601 -356.080872 +12.855988 183.350601 -356.080872 +-27.093735 313.097931 -357.247009 +-27.093735 313.097931 -300.730164 +13.487251 313.097931 -300.730164 +13.487251 313.097931 -357.247009 +-25.039490 279.802124 -354.379578 +-25.039490 279.802124 -303.410950 +11.433014 279.802124 -303.410950 +11.433014 279.802124 -354.379578 +-77.193710 323.720734 -8.791321 +-33.610245 323.720734 -8.791321 +-77.193710 323.720734 -68.457092 +-33.610245 323.720734 -68.457092 +-77.193710 207.784195 -8.791321 +-33.610245 207.784195 -8.791321 +-77.193710 207.784195 -68.457092 +-33.610245 207.784195 -68.457092 +-75.061211 183.350616 -11.531921 +-35.742756 183.350616 -11.531921 +-75.061211 183.350616 -65.716492 +-35.742756 183.350616 -65.716492 +-75.692474 323.720734 -66.882629 +-75.692474 323.720734 -10.365784 +-35.111488 323.720734 -10.365784 +-35.111488 323.720734 -66.882629 +-73.638229 290.395142 -64.015198 +-73.638229 290.395142 -13.046570 +-37.165726 290.395142 -13.046570 +-37.165726 290.395142 -64.015198 +-73.250549 302.476288 -69.415588 +-29.667084 302.476288 -69.415588 +-73.250549 302.476288 -129.081360 +-29.667084 302.476288 -129.081360 +-73.250549 207.739487 -69.415588 +-29.667084 207.739487 -69.415588 +-73.250549 207.739471 -129.081360 +-29.667084 207.739471 -129.081360 +-71.118050 183.305893 -72.156189 +-31.799591 183.305893 -72.156189 +-71.118050 183.305893 -126.340759 +-31.799591 183.305893 -126.340759 +-71.749313 302.476288 -127.506897 +-71.749313 302.476288 -70.990051 +-31.168327 302.476288 -70.990051 +-31.168327 302.476288 -127.506897 +-69.695068 269.171295 -124.639465 +-69.695068 269.171295 -73.670837 +-33.222565 269.171295 -73.670837 +-33.222565 269.171295 -124.639465 +-28.594971 313.097931 -7.310486 +14.988495 313.097931 -7.310486 +-28.594971 313.097931 -66.976257 +14.988495 313.097931 -66.976257 +-28.594971 207.784195 -7.310486 +14.988495 207.784195 -7.310486 +-28.594971 207.784195 -66.976257 +14.988495 207.784195 -66.976257 +-26.462471 183.350616 -10.051086 +12.855988 183.350616 -10.051086 +-26.462471 183.350616 -64.235657 +12.855988 183.350616 -64.235657 +-27.093735 313.097931 -65.401794 +-27.093735 313.097931 -8.884949 +13.487251 313.097931 -8.884949 +13.487251 313.097931 -65.401794 +-25.039490 279.802124 -62.534363 +-25.039490 279.802124 -11.565735 +11.433014 279.802124 -11.565735 +11.433014 279.802124 -62.534363 +-84.032951 619.746216 49.376282 +-84.032959 619.746216 92.959778 +-24.367188 619.746216 49.376343 +-24.367188 619.746216 92.959778 +-84.032951 503.809692 49.376343 +-84.032959 503.809692 92.959778 +-24.367188 503.809692 49.376343 +-24.367188 503.809692 92.959778 +-81.292358 479.376099 51.508850 +-81.292358 479.376099 90.827271 +-27.107788 479.376099 51.508850 +-27.107788 479.376099 90.827271 +-25.941643 619.746216 50.877563 +-82.458504 619.746216 50.877563 +-82.458504 619.746216 91.458557 +-25.941650 619.746216 91.458557 +-28.809067 586.420654 52.931824 +-79.777740 586.420654 52.931824 +-79.777740 586.420654 89.404297 +-28.809067 586.420654 89.404297 +-23.408691 598.501770 53.319458 +-23.408691 598.501770 96.902954 +36.257080 598.501770 53.319458 +36.257080 598.501770 96.902954 +-23.408691 503.764984 53.319458 +-23.408691 503.764984 96.902954 +36.257080 503.764984 53.319519 +36.257080 503.764984 96.902954 +-20.668091 479.331390 55.451965 +-20.668091 479.331390 94.770447 +33.516479 479.331390 55.451965 +33.516479 479.331390 94.770447 +34.682617 598.501770 54.820740 +-21.834236 598.501770 54.820740 +-21.834236 598.501770 95.401733 +34.682617 598.501770 95.401733 +31.815201 565.196838 56.874939 +-19.153473 565.196838 56.874939 +-19.153473 565.196838 93.347473 +31.815201 565.196838 93.347473 +-23.408691 566.635986 99.898987 +-23.408691 566.635986 143.482422 +36.257080 566.635986 99.898987 +36.257080 566.635986 143.482483 +-23.408691 503.764984 99.898987 +-23.408691 503.764984 143.482483 +36.257080 503.764984 99.898987 +36.257080 503.764984 143.482483 +-20.668091 479.331390 102.031494 +-20.668091 479.331390 141.349915 +33.516479 479.331390 102.031494 +33.516479 479.331390 141.349976 +34.682617 566.635986 101.400208 +-21.834236 566.635986 101.400208 +-21.834236 566.635986 141.981201 +34.682617 566.635986 141.981201 +31.815201 533.365173 103.454468 +-19.153473 533.365173 103.454468 +-19.153473 533.365173 139.926941 +31.815201 533.365173 139.926941 +-85.513794 609.123474 97.975037 +-85.513802 609.123474 141.558533 +-25.848022 609.123474 97.975037 +-25.848022 609.123474 141.558533 +-85.513794 503.809692 97.975037 +-85.513802 503.809692 141.558533 +-25.848022 503.809692 97.975037 +-25.848022 503.809692 141.558533 +-82.773193 479.376099 100.107544 +-82.773193 479.376099 139.426025 +-28.588623 479.376099 100.107544 +-28.588623 479.376099 139.426025 +-27.422485 609.123474 99.476318 +-83.939339 609.123474 99.476318 +-83.939339 609.123474 140.057312 +-27.422485 609.123474 140.057312 +-30.289902 575.827637 101.530518 +-81.258575 575.827637 101.530518 +-81.258575 575.827637 138.003052 +-30.289909 575.827637 138.003052 +-28.921051 598.501831 657.552368 +-28.921051 598.501831 701.135803 +30.744720 598.501831 657.552368 +30.744720 598.501831 701.135803 +-28.921051 503.765015 657.552368 +-28.921051 503.765015 701.135803 +30.744720 503.765015 657.552368 +30.744720 503.765015 701.135803 +-26.180450 479.331421 659.684875 +-26.180450 479.331421 699.003296 +28.004120 479.331421 659.684875 +28.004120 479.331421 699.003296 +29.170258 598.501831 659.053589 +-27.346596 598.501831 659.053528 +-27.346596 598.501831 699.634521 +29.170258 598.501831 699.634521 +26.302841 565.196838 661.107849 +-24.665833 565.196838 661.107849 +-24.665833 565.196838 697.580322 +26.302841 565.196838 697.580322 +-28.921051 566.635986 704.131836 +-28.921051 566.635986 747.715332 +30.744720 566.635986 704.131836 +30.744720 566.635986 747.715332 +-28.921051 503.765015 704.131836 +-28.921051 503.765015 747.715332 +30.744720 503.765015 704.131836 +30.744720 503.765015 747.715332 +-26.180450 479.331421 706.264343 +-26.180450 479.331421 745.582764 +28.004120 479.331421 706.264343 +28.004120 479.331421 745.582764 +29.170258 566.635986 705.633057 +-27.346596 566.635986 705.633057 +-27.346596 566.635986 746.214050 +29.170258 566.635986 746.214050 +26.302841 533.365234 707.687317 +-24.665833 533.365234 707.687317 +-24.665833 533.365234 744.159851 +26.302841 533.365234 744.159851 +-91.026154 609.123474 702.207886 +-91.026154 609.123474 745.791382 +-31.360382 609.123474 702.207886 +-31.360382 609.123474 745.791382 +-91.026154 503.809723 702.207886 +-91.026154 503.809723 745.791382 +-31.360382 503.809723 702.207886 +-31.360382 503.809723 745.791382 +-88.285553 479.376129 704.340454 +-88.285553 479.376129 743.658875 +-34.100983 479.376129 704.340454 +-34.100983 479.376129 743.658875 +-32.934845 609.123474 703.709167 +-89.451698 609.123474 703.709167 +-89.451698 609.123474 744.290161 +-32.934845 609.123474 744.290161 +-35.802265 575.827637 705.763367 +-86.770935 575.827637 705.763367 +-86.770935 575.827637 742.235901 +-35.802265 575.827637 742.235901 +-77.193710 619.746277 874.443726 +-33.610245 619.746277 874.443726 +-77.193710 619.746277 814.777954 +-33.610245 619.746277 814.777954 +-77.193710 503.809723 874.443726 +-33.610245 503.809723 874.443726 +-77.193710 503.809723 814.777954 +-33.610245 503.809723 814.777954 +-75.061211 479.376129 871.703125 +-35.742756 479.376129 871.703125 +-75.061211 479.376129 817.518555 +-35.742756 479.376129 817.518555 +-75.692474 619.746277 816.352417 +-75.692474 619.746277 872.869263 +-35.111488 619.746277 872.869263 +-35.111488 619.746277 816.352417 +-73.638229 586.420654 819.219849 +-73.638229 586.420654 870.188477 +-37.165726 586.420654 870.188477 +-37.165726 586.420654 819.219849 +-73.250549 598.501831 813.819458 +-29.667084 598.501831 813.819458 +-73.250549 598.501831 754.153687 +-29.667084 598.501831 754.153687 +-73.250549 503.765015 813.819458 +-29.667084 503.765015 813.819458 +-73.250549 503.765015 754.153687 +-29.667084 503.765015 754.153687 +-71.118050 479.331421 811.078857 +-31.799591 479.331421 811.078857 +-71.118050 479.331421 756.894287 +-31.799591 479.331421 756.894287 +-71.749313 598.501831 755.728149 +-71.749313 598.501831 812.244995 +-31.168327 598.501831 812.244995 +-31.168327 598.501831 755.728149 +-69.695068 565.196838 758.595581 +-69.695068 565.196838 809.564270 +-33.222565 565.196838 809.564270 +-33.222565 565.196838 758.595581 +-26.671051 566.635986 813.819458 +16.912415 566.635986 813.819458 +-26.671051 566.635986 754.153687 +16.912415 566.635986 754.153687 +-26.671051 503.765015 813.819458 +16.912415 503.765015 813.819458 +-26.671051 503.765015 754.153687 +16.912415 503.765015 754.153687 +-24.538544 479.331421 811.078857 +14.779907 479.331421 811.078857 +-24.538544 479.331421 756.894287 +14.779907 479.331421 756.894287 +-25.169815 566.635986 755.728149 +-25.169815 566.635986 812.244995 +15.411171 566.635986 812.244995 +15.411171 566.635986 755.728149 +-23.115570 533.365234 758.595581 +-23.115570 533.365234 809.564270 +13.356934 533.365234 809.564270 +13.356934 533.365234 758.595581 +-28.594971 609.123474 875.924561 +14.988495 609.123474 875.924561 +-28.594971 609.123474 816.258789 +14.988495 609.123474 816.258789 +-28.594971 503.809723 875.924561 +14.988495 503.809723 875.924561 +-28.594971 503.809723 816.258789 +14.988495 503.809723 816.258789 +-26.462471 479.376129 873.183960 +12.855988 479.376129 873.183960 +-26.462471 479.376129 818.999390 +12.855988 479.376129 818.999390 +-27.093735 609.123474 817.833252 +-27.093735 609.123474 874.350098 +13.487251 609.123474 874.350098 +13.487251 609.123474 817.833252 +-25.039490 575.827637 820.700684 +-25.039490 575.827637 871.669312 +11.433014 575.827637 871.669312 +11.433014 575.827637 820.700684 + + + + + + + + + + + +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.569896 -0.821717 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.569896 -0.821717 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.569896 0.821717 0.000000 +-0.569896 0.821717 0.000000 +-0.569896 0.821717 0.000000 +-0.569896 0.821717 0.000000 +-0.569896 0.821717 0.000000 +-0.569896 0.821717 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.551094 -0.834443 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.551094 -0.834443 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.551095 0.834443 0.000000 +-0.551094 0.834443 0.000000 +-0.551095 0.834443 0.000000 +-0.551095 0.834443 0.000000 +-0.551095 0.834443 0.000000 +-0.551094 0.834443 0.000000 +0.000000 0.000000 -1.000000 +-0.547313 -0.836928 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.547313 -0.836928 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.547313 0.836928 0.000000 +0.547313 0.836928 0.000000 +0.547313 0.836928 0.000000 +0.547313 0.836928 0.000000 +0.547313 0.836928 0.000000 +0.547313 0.836928 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.569896 -0.821717 0.000000 +0.569896 -0.821717 0.000000 +0.569896 -0.821717 0.000000 +0.569896 -0.821717 0.000000 +0.569896 -0.821717 0.000000 +0.569896 -0.821717 0.000000 +-0.569896 0.821717 0.000000 +-0.569896 0.821717 0.000000 +-0.569896 0.821717 0.000000 +-0.569896 0.821717 0.000000 +-0.569896 0.821717 0.000000 +-0.569896 0.821717 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.551094 -0.834443 0.000000 +0.551094 -0.834443 0.000000 +0.551094 -0.834443 0.000000 +0.551094 -0.834443 0.000000 +0.551094 -0.834443 0.000000 +0.551094 -0.834443 0.000000 +-0.551094 0.834443 0.000000 +-0.551094 0.834443 0.000000 +-0.551094 0.834443 0.000000 +-0.551094 0.834443 0.000000 +-0.551094 0.834443 0.000000 +-0.551094 0.834443 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000001 -0.000001 1.000000 +-0.000001 -0.000001 1.000000 +-0.000001 -0.000001 1.000000 +-0.000001 -0.000001 1.000000 +-0.000001 -0.000001 1.000000 +-0.000001 -0.000001 1.000000 +-0.547313 -0.836928 0.000000 +-0.547313 -0.836928 0.000000 +-0.547313 -0.836928 0.000000 +-0.547313 -0.836928 0.000000 +-0.547313 -0.836928 0.000000 +-0.547313 -0.836928 0.000000 +0.547313 0.836928 0.000000 +0.547313 0.836928 0.000000 +0.547313 0.836928 0.000000 +0.547313 0.836928 0.000000 +0.547313 0.836928 0.000000 +0.547313 0.836928 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.569896 -0.821717 0.000000 +0.569895 -0.821717 0.000000 +0.569895 -0.821717 0.000000 +0.569896 -0.821717 0.000000 +0.569895 -0.821717 0.000000 +0.569896 -0.821717 0.000000 +-0.569895 0.821717 0.000000 +-0.569895 0.821717 0.000000 +-0.569895 0.821717 0.000000 +-0.569895 0.821717 0.000000 +-0.569895 0.821717 0.000000 +-0.569895 0.821717 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.551094 -0.834443 0.000000 +0.551095 -0.834443 0.000000 +0.551094 -0.834443 0.000000 +0.551094 -0.834443 0.000000 +0.551094 -0.834443 0.000000 +0.551094 -0.834443 0.000000 +-0.551094 0.834443 0.000000 +-0.551094 0.834443 0.000000 +-0.551094 0.834443 0.000000 +-0.551094 0.834443 0.000000 +-0.551094 0.834443 0.000000 +-0.551094 0.834443 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000002 -0.000002 1.000000 +-0.000002 -0.000002 1.000000 +-0.000002 -0.000002 1.000000 +-0.000002 -0.000002 1.000000 +-0.000002 -0.000002 1.000000 +-0.000002 -0.000002 1.000000 +-0.547313 -0.836928 0.000000 +-0.547313 -0.836928 0.000000 +-0.547313 -0.836928 0.000000 +-0.547313 -0.836928 0.000000 +-0.547313 -0.836928 0.000000 +-0.547313 -0.836928 0.000000 +0.547313 0.836928 0.000000 +0.547313 0.836928 0.000000 +0.547313 0.836928 0.000000 +0.547313 0.836928 0.000000 +0.547313 0.836928 0.000000 +0.547313 0.836928 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -1.000000 -0.000001 +0.000000 -1.000000 -0.000001 +0.000000 -1.000000 -0.000001 +0.000000 -1.000000 -0.000001 +0.000000 -1.000000 -0.000001 +0.000000 -1.000000 -0.000001 +0.000000 1.000000 0.000001 +0.000000 1.000000 0.000001 +0.000000 1.000000 0.000001 +0.000000 1.000000 0.000001 +0.000000 1.000000 0.000001 +0.000000 1.000000 0.000001 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.569895 -0.821717 -0.000001 +0.569895 -0.821717 -0.000001 +0.569895 -0.821717 -0.000001 +0.569895 -0.821717 -0.000001 +0.569895 -0.821717 -0.000001 +0.569895 -0.821717 -0.000001 +-0.569895 0.821717 0.000000 +-0.569895 0.821717 0.000000 +-0.569895 0.821717 0.000000 +-0.569895 0.821717 0.000000 +-0.569895 0.821717 0.000000 +-0.569895 0.821717 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.551094 -0.834443 0.000000 +0.551094 -0.834443 0.000000 +0.551094 -0.834443 0.000000 +0.551094 -0.834443 0.000000 +0.551094 -0.834443 0.000000 +0.551094 -0.834443 0.000000 +-0.551094 0.834443 0.000000 +-0.551094 0.834443 0.000000 +-0.551094 0.834443 0.000000 +-0.551094 0.834443 0.000000 +-0.551094 0.834443 0.000000 +-0.551094 0.834443 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.547313 -0.836928 0.000000 +-0.547313 -0.836928 0.000000 +-0.547313 -0.836928 0.000000 +-0.547313 -0.836928 0.000000 +-0.547313 -0.836928 0.000000 +-0.547313 -0.836928 0.000000 +0.547313 0.836928 0.000000 +0.547313 0.836928 0.000000 +0.547313 0.836928 0.000000 +0.547313 0.836928 0.000000 +0.547313 0.836928 0.000000 +0.547313 0.836928 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -1.000000 -0.000002 +0.000000 -1.000000 -0.000002 +0.000000 -1.000000 -0.000002 +0.000000 -1.000000 -0.000002 +0.000000 -1.000000 -0.000002 +0.000000 -1.000000 -0.000002 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.569896 -0.821717 -0.000001 +0.569896 -0.821717 -0.000001 +0.569896 -0.821717 -0.000001 +0.569896 -0.821717 -0.000001 +0.569896 -0.821717 -0.000001 +0.569896 -0.821717 -0.000001 +-0.569895 0.821717 0.000000 +-0.569895 0.821717 0.000000 +-0.569895 0.821717 0.000000 +-0.569895 0.821717 0.000000 +-0.569895 0.821717 0.000000 +-0.569895 0.821717 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.551094 -0.834443 0.000000 +0.551095 -0.834443 0.000000 +0.551094 -0.834443 0.000000 +0.551094 -0.834443 0.000000 +0.551094 -0.834443 0.000000 +0.551094 -0.834443 0.000000 +-0.551095 0.834443 0.000001 +-0.551095 0.834443 0.000001 +-0.551095 0.834443 0.000001 +-0.551095 0.834443 0.000001 +-0.551095 0.834443 0.000001 +-0.551095 0.834443 0.000001 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.547313 -0.836928 0.000000 +-0.547313 -0.836928 0.000000 +-0.547313 -0.836928 0.000000 +-0.547313 -0.836928 0.000000 +-0.547313 -0.836928 0.000000 +-0.547313 -0.836928 0.000000 +0.547313 0.836928 0.000000 +0.547313 0.836928 0.000000 +0.547313 0.836928 0.000000 +0.547313 0.836928 0.000000 +0.547313 0.836928 0.000000 +0.547313 0.836928 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -1.000000 -0.000002 +0.000000 -1.000000 -0.000002 +0.000000 -1.000000 -0.000002 +0.000000 -1.000000 -0.000002 +0.000000 -1.000000 -0.000002 +0.000000 -1.000000 -0.000002 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -1.000000 -0.000002 +0.000000 -1.000000 -0.000002 +0.000000 -1.000000 -0.000002 +0.000000 -1.000000 -0.000002 +0.000000 -1.000000 -0.000002 +0.000000 -1.000000 -0.000002 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -1.000000 -0.000002 +0.000000 -1.000000 -0.000002 +0.000000 -1.000000 -0.000002 +0.000000 -1.000000 -0.000002 +0.000000 -1.000000 -0.000002 +0.000000 -1.000000 -0.000002 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -1.000000 -0.000002 +0.000000 -1.000000 -0.000002 +0.000000 -1.000000 -0.000002 +0.000000 -1.000000 -0.000002 +0.000000 -1.000000 -0.000002 +0.000000 -1.000000 -0.000002 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999971 0.000000 0.007589 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.000240 0.000000 1.000000 +0.000240 0.000000 1.000000 +0.000240 0.000000 1.000000 +-0.999971 0.000001 0.007639 +-0.999971 0.000001 0.007639 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999971 0.000000 0.007590 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.000239 0.000000 1.000000 +0.000239 0.000000 1.000000 +0.000239 0.000000 1.000000 +-0.999971 0.000001 0.007639 +-0.999971 0.000001 0.007639 +-0.999971 0.000000 0.007640 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999971 0.000000 0.007664 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 -0.000001 0.007640 +-0.999971 -0.000001 0.007640 +-0.999971 0.000000 0.007640 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999971 0.000000 0.007658 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 -0.000001 0.007640 +-0.999971 -0.000001 0.007640 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999971 0.000000 0.007581 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000002 0.007639 +-0.999971 0.000002 0.007639 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999972 0.000000 0.007505 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007637 +0.999971 0.000000 -0.007637 +0.999971 0.000000 -0.007637 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000004 0.007638 +-0.999971 0.000004 0.007638 +-0.999971 0.000000 0.007641 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999971 0.000000 0.007589 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000001 0.007639 +-0.999971 0.000001 0.007639 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999972 0.000000 0.007505 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.000240 0.000000 1.000000 +0.000240 0.000000 1.000000 +0.000240 0.000000 1.000000 +-0.999971 0.000004 0.007637 +-0.999971 0.000004 0.007637 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999972 0.000000 0.007505 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000004 0.007639 +-0.999971 0.000004 0.007639 +-0.999971 0.000000 0.007642 +-0.000244 0.000000 -1.000000 +-0.000244 0.000000 -1.000000 +-0.000244 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999972 0.000000 0.007435 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007635 +0.999971 0.000000 -0.007635 +0.999971 0.000000 -0.007635 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000006 0.007640 +-0.999971 0.000006 0.007640 +-0.999971 0.000000 0.007645 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007638 0.000002 -0.999971 +-0.007638 0.000002 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000241 +1.000000 0.000000 -0.000241 +1.000000 0.000000 -0.000241 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000000 0.000240 +-1.000000 0.000000 0.000240 +-1.000000 0.000000 0.000240 +-0.007638 0.000002 -0.999971 +-0.007638 0.000002 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007679 0.000000 -0.999970 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007643 -0.000001 -0.999971 +-0.007643 -0.000001 -0.999971 +-0.007642 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007456 0.000000 -0.999972 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007638 0.000005 -0.999971 +-0.007638 0.000005 -0.999971 +-0.007642 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007456 0.000000 -0.999972 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000000 0.000243 +-1.000000 0.000000 0.000243 +-1.000000 0.000000 0.000243 +-0.007635 0.000005 -0.999971 +-0.007635 0.000005 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007679 0.000000 -0.999970 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007640 -0.000001 -0.999971 +-0.007640 -0.000001 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007640 0.000003 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000000 0.000241 +-1.000000 0.000000 0.000241 +-1.000000 0.000000 0.000241 +-0.007638 0.000002 -0.999971 +-0.007638 0.000002 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000000 0.000243 +-1.000000 0.000000 0.000243 +-1.000000 0.000000 0.000243 +-0.007638 0.000002 -0.999971 +-0.007638 0.000002 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007638 0.000002 -0.999971 +-0.007638 0.000002 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000243 +1.000000 0.000000 -0.000243 +1.000000 0.000000 -0.000243 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000000 0.000243 +-1.000000 0.000000 0.000243 +-1.000000 0.000000 0.000243 +-0.007640 0.000002 -0.999971 +-0.007640 0.000002 -0.999971 +-0.007642 0.000000 -0.999971 +1.000000 0.000000 -0.000243 +1.000000 0.000000 -0.000243 +1.000000 0.000000 -0.000243 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007344 0.000000 -0.999973 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000000 0.000241 +-1.000000 0.000000 0.000241 +-1.000000 0.000000 0.000241 +-0.007633 0.000009 -0.999971 +-0.007633 0.000009 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007638 0.000002 -0.999971 +-0.007638 0.000002 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007679 0.000000 -0.999970 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007643 -0.000001 -0.999971 +-0.007643 -0.000001 -0.999971 +-0.007642 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007456 0.000000 -0.999972 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007638 0.000005 -0.999971 +-0.007638 0.000005 -0.999971 +-0.007642 0.000000 -0.999971 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007679 0.000000 -0.999970 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007640 -0.000001 -0.999971 +-0.007640 -0.000001 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007640 0.000003 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000000 0.000241 +-1.000000 0.000000 0.000241 +-1.000000 0.000000 0.000241 +-0.007638 0.000002 -0.999971 +-0.007638 0.000002 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007640 0.000002 -0.999971 +-0.007640 0.000002 -0.999971 +-0.007642 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000000 0.000243 +-1.000000 0.000000 0.000243 +-1.000000 0.000000 0.000243 +-0.007638 0.000002 -0.999971 +-0.007638 0.000002 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007638 0.000002 -0.999971 +-0.007638 0.000002 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000243 +1.000000 0.000000 -0.000243 +1.000000 0.000000 -0.000243 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000000 0.000243 +-1.000000 0.000000 0.000243 +-1.000000 0.000000 0.000243 +-0.007640 0.000002 -0.999971 +-0.007640 0.000002 -0.999971 +-0.007642 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007456 0.000000 -0.999972 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007638 0.000005 -0.999971 +-0.007638 0.000005 -0.999971 +-0.007642 0.000000 -0.999971 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999971 0.000000 0.007589 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.000240 0.000000 1.000000 +0.000240 0.000000 1.000000 +0.000240 0.000000 1.000000 +-0.999971 0.000001 0.007639 +-0.999971 0.000001 0.007639 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999971 0.000000 0.007590 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.000239 0.000000 1.000000 +0.000239 0.000000 1.000000 +0.000239 0.000000 1.000000 +-0.999971 0.000001 0.007639 +-0.999971 0.000001 0.007639 +-0.999971 0.000000 0.007640 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999971 0.000000 0.007664 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 -0.000001 0.007640 +-0.999971 -0.000001 0.007640 +-0.999971 0.000000 0.007640 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999971 0.000000 0.007658 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 -0.000001 0.007640 +-0.999971 -0.000001 0.007640 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999971 0.000000 0.007581 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000002 0.007639 +-0.999971 0.000002 0.007639 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999972 0.000000 0.007505 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007637 +0.999971 0.000000 -0.007637 +0.999971 0.000000 -0.007637 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000004 0.007638 +-0.999971 0.000004 0.007638 +-0.999971 0.000000 0.007641 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999971 0.000000 0.007589 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000001 0.007639 +-0.999971 0.000001 0.007639 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999972 0.000000 0.007505 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.000240 0.000000 1.000000 +0.000240 0.000000 1.000000 +0.000240 0.000000 1.000000 +-0.999971 0.000004 0.007637 +-0.999971 0.000004 0.007637 +-0.999971 0.000000 0.007640 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007638 0.000002 -0.999971 +-0.007638 0.000002 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000241 +1.000000 0.000000 -0.000241 +1.000000 0.000000 -0.000241 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000000 0.000240 +-1.000000 0.000000 0.000240 +-1.000000 0.000000 0.000240 +-0.007638 0.000002 -0.999971 +-0.007638 0.000002 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007679 0.000000 -0.999970 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007643 -0.000001 -0.999971 +-0.007643 -0.000001 -0.999971 +-0.007642 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007456 0.000000 -0.999972 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007638 0.000005 -0.999971 +-0.007638 0.000005 -0.999971 +-0.007642 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007456 0.000000 -0.999972 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000000 0.000243 +-1.000000 0.000000 0.000243 +-1.000000 0.000000 0.000243 +-0.007635 0.000005 -0.999971 +-0.007635 0.000005 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007679 0.000000 -0.999970 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007640 -0.000001 -0.999971 +-0.007640 -0.000001 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007640 0.000003 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000000 0.000241 +-1.000000 0.000000 0.000241 +-1.000000 0.000000 0.000241 +-0.007638 0.000002 -0.999971 +-0.007638 0.000002 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000000 0.000243 +-1.000000 0.000000 0.000243 +-1.000000 0.000000 0.000243 +-0.007638 0.000002 -0.999971 +-0.007638 0.000002 -0.999971 +-0.007639 0.000000 -0.999971 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999971 0.000000 0.007588 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.000241 0.000000 1.000000 +0.000241 0.000000 1.000000 +0.000241 0.000000 1.000000 +-0.999971 0.000002 0.007639 +-0.999971 0.000002 0.007639 +-0.999971 0.000000 0.007640 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999971 0.000000 0.007664 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 -0.000001 0.007640 +-0.999971 -0.000001 0.007640 +-0.999971 0.000000 0.007640 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999972 0.000000 0.007511 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000004 0.007639 +-0.999971 0.000004 0.007639 +-0.999971 0.000000 0.007641 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999971 0.000000 0.007658 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 -0.000001 0.007640 +-0.999971 -0.000001 0.007640 +-0.999971 0.000000 0.007640 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999971 0.000000 0.007581 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000002 0.007639 +-0.999971 0.000002 0.007639 +-0.999971 0.000000 0.007640 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999972 0.000000 0.007505 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007637 +0.999971 0.000000 -0.007637 +0.999971 0.000000 -0.007637 +0.000241 0.000000 1.000000 +0.000241 0.000000 1.000000 +0.000241 0.000000 1.000000 +-0.999971 0.000004 0.007638 +-0.999971 0.000004 0.007638 +-0.999971 0.000000 0.007641 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999971 0.000000 0.007588 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000002 0.007639 +-0.999971 0.000002 0.007639 +-0.999971 0.000000 0.007640 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999972 0.000000 0.007505 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000004 0.007637 +-0.999971 0.000004 0.007637 +-0.999971 0.000000 0.007640 +-0.000243 0.000000 -1.000000 +-0.000243 0.000000 -1.000000 +-0.000243 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999972 0.000000 0.007505 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000243 0.000000 1.000000 +0.000243 0.000000 1.000000 +0.000243 0.000000 1.000000 +-0.999971 0.000004 0.007639 +-0.999971 0.000004 0.007639 +-0.999971 0.000000 0.007642 +-0.000243 0.000000 -1.000000 +-0.000243 0.000000 -1.000000 +-0.000243 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999972 0.000000 0.007435 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007635 +0.999971 0.000000 -0.007635 +0.999971 0.000000 -0.007635 +0.000241 0.000000 1.000000 +0.000241 0.000000 1.000000 +0.000241 0.000000 1.000000 +-0.999971 0.000006 0.007640 +-0.999971 0.000006 0.007640 +-0.999971 0.000000 0.007645 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007639 0.000002 -0.999971 +-0.007639 0.000002 -0.999971 +-0.007641 0.000000 -0.999971 +1.000000 0.000000 -0.000241 +1.000000 0.000000 -0.000241 +1.000000 0.000000 -0.000241 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007624 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000000 0.000240 +-1.000000 0.000000 0.000240 +-1.000000 0.000000 0.000240 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007679 0.000000 -0.999970 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007640 -0.000001 -0.999971 +-0.007640 -0.000001 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007512 0.000000 -0.999972 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000002 0.999971 +0.007639 0.000002 0.999971 +0.007639 0.000002 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007638 0.000004 -0.999971 +-0.007638 0.000004 -0.999971 +-0.007641 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007511 0.000000 -0.999972 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +-1.000000 0.000000 0.000243 +-1.000000 0.000000 0.000243 +-1.000000 0.000000 0.000243 +-0.007636 0.000004 -0.999971 +-0.007636 0.000004 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007624 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007640 0.000000 -0.999971 +-0.007640 0.000000 -0.999971 +-0.007641 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +-1.000000 0.000000 0.000241 +-1.000000 0.000000 0.000241 +-1.000000 0.000000 0.000241 +-0.007639 0.000002 -0.999971 +-0.007639 0.000002 -0.999971 +-0.007641 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007456 0.000000 -0.999972 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007638 0.000005 -0.999971 +-0.007638 0.000005 -0.999971 +-0.007642 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +-1.000000 0.000000 0.000243 +-1.000000 0.000000 0.000243 +-1.000000 0.000000 0.000243 +-0.007639 0.000002 -0.999971 +-0.007639 0.000002 -0.999971 +-0.007641 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007512 0.000000 -0.999972 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007636 0.000004 -0.999971 +-0.007636 0.000004 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000243 +1.000000 0.000000 -0.000243 +1.000000 0.000000 -0.000243 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007512 0.000000 -0.999972 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000000 0.000243 +-1.000000 0.000000 0.000243 +-1.000000 0.000000 0.000243 +-0.007638 0.000004 -0.999971 +-0.007638 0.000004 -0.999971 +-0.007641 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007512 0.000000 -0.999972 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007639 0.000004 -0.999971 +-0.007639 0.000004 -0.999971 +-0.007642 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007639 0.000002 -0.999971 +-0.007639 0.000002 -0.999971 +-0.007641 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007679 0.000000 -0.999970 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007640 -0.000001 -0.999971 +-0.007640 -0.000001 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007512 0.000000 -0.999972 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007638 0.000004 -0.999971 +-0.007638 0.000004 -0.999971 +-0.007641 0.000000 -0.999971 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007624 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007640 0.000000 -0.999971 +-0.007640 0.000000 -0.999971 +-0.007641 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +-1.000000 0.000000 0.000241 +-1.000000 0.000000 0.000241 +-1.000000 0.000000 0.000241 +-0.007639 0.000002 -0.999971 +-0.007639 0.000002 -0.999971 +-0.007641 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +-1.000000 0.000000 0.000243 +-1.000000 0.000000 0.000243 +-1.000000 0.000000 0.000243 +-0.007639 0.000002 -0.999971 +-0.007639 0.000002 -0.999971 +-0.007641 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007512 -0.000002 -0.999972 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007638 0.000002 -0.999971 +-0.007638 0.000002 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007661 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007641 -0.000001 -0.999971 +-0.007641 -0.000001 -0.999971 +-0.007641 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007661 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007639 0.000001 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007641 -0.000001 -0.999971 +-0.007641 -0.000001 -0.999971 +-0.007641 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007661 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007641 -0.000001 -0.999971 +-0.007641 -0.000001 -0.999971 +-0.007641 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007661 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007640 -0.000001 -0.999971 +-0.007640 -0.000001 -0.999971 +-0.007640 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007661 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000001 0.999971 +0.007638 0.000000 0.999971 +0.007639 0.000001 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007640 -0.000001 -0.999971 +-0.007640 -0.000001 -0.999971 +-0.007640 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007661 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007640 -0.000001 -0.999971 +-0.007640 -0.000001 -0.999971 +-0.007640 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007613 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007639 0.000001 -0.999971 +-0.007639 0.000001 -0.999971 +-0.007640 0.000000 -0.999971 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000241 0.000003 1.000000 +0.000241 0.000003 1.000000 +0.000241 0.000003 1.000000 +-0.999971 0.000002 0.007639 +-0.999971 0.000002 0.007639 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000241 0.000001 1.000000 +0.000241 0.000001 1.000000 +0.000241 0.000001 1.000000 +-0.999971 0.000001 0.007639 +-0.999971 0.000001 0.007639 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000241 0.000001 1.000000 +0.000241 0.000001 1.000000 +0.000241 0.000001 1.000000 +-0.999971 0.000001 0.007639 +-0.999971 0.000001 0.007639 +-0.999971 0.000000 0.007640 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.000241 0.000000 1.000000 +0.000241 0.000000 1.000000 +0.000241 0.000000 1.000000 +-0.999971 0.000001 0.007639 +-0.999971 0.000001 0.007639 +-0.999971 0.000000 0.007640 +-0.000241 0.000000 -1.000000 +-0.000239 -0.000003 -1.000000 +-0.000241 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000001 0.007641 +-0.999971 0.000001 0.007641 +-0.999971 0.000000 0.007642 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000001 0.007641 +-0.999971 0.000001 0.007641 +-0.999971 0.000000 0.007642 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000001 0.007641 +-0.999971 0.000001 0.007641 +-0.999971 0.000000 0.007642 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000001 0.007639 +-0.999971 0.000001 0.007639 +-0.999971 0.000000 0.007640 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007565 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007639 0.000002 -0.999971 +-0.007639 0.000002 -0.999971 +-0.007641 0.000000 -0.999971 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007613 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007639 0.000001 -0.999971 +-0.007639 0.000001 -0.999971 +-0.007640 0.000000 -0.999971 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007613 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007639 0.000001 -0.999971 +-0.007639 0.000001 -0.999971 +-0.007640 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007661 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007641 -0.000001 -0.999971 +-0.007641 -0.000001 -0.999971 +-0.007641 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007661 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007640 -0.000001 -0.999971 +-0.007640 -0.000001 -0.999971 +-0.007640 0.000000 -0.999971 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000240 0.000003 1.000000 +0.000240 0.000003 1.000000 +0.000240 0.000003 1.000000 +-0.999971 0.000002 0.007639 +-0.999971 0.000002 0.007639 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000240 0.000003 1.000000 +0.000240 0.000003 1.000000 +0.000240 0.000003 1.000000 +-0.999971 0.000002 0.007639 +-0.999971 0.000002 0.007639 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000241 0.000001 1.000000 +0.000241 0.000001 1.000000 +0.000241 0.000001 1.000000 +-0.999971 0.000001 0.007639 +-0.999971 0.000001 0.007639 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000001 0.007639 +-0.999971 0.000001 0.007639 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000001 0.007639 +-0.999971 0.000001 0.007639 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000001 0.007639 +-0.999971 0.000001 0.007639 +-0.999971 0.000000 0.007640 +-0.000240 -0.000001 -1.000000 +-0.000241 0.000000 -1.000000 +-0.000240 -0.000001 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000001 0.007641 +-0.999971 0.000001 0.007641 +-0.999971 0.000000 0.007642 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000001 0.007641 +-0.999971 0.000001 0.007641 +-0.999971 0.000000 0.007642 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007565 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007641 0.000000 0.999971 +0.007641 0.000000 0.999971 +0.007641 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007639 0.000002 -0.999971 +-0.007639 0.000002 -0.999971 +-0.007641 0.000000 -0.999971 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007613 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007641 0.000000 0.999971 +0.007641 0.000000 0.999971 +0.007641 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007639 0.000001 -0.999971 +-0.007639 0.000001 -0.999971 +-0.007640 0.000000 -0.999971 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000240 0.000002 1.000000 +0.000240 0.000002 1.000000 +0.000240 0.000002 1.000000 +-0.999971 0.000001 0.007639 +-0.999971 0.000001 0.007639 +-0.999971 0.000000 0.007640 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007661 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007640 -0.000001 -0.999971 +-0.007640 -0.000001 -0.999971 +-0.007640 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007661 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007640 -0.000001 -0.999971 +-0.007640 -0.000001 -0.999971 +-0.007640 0.000000 -0.999971 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000240 0.000002 1.000000 +0.000240 0.000002 1.000000 +0.000240 0.000002 1.000000 +-0.999971 0.000002 0.007639 +-0.999971 0.000002 0.007639 +-0.999971 0.000000 0.007640 +-0.000242 -0.000001 -1.000000 +-0.000242 -0.000001 -1.000000 +-0.000242 -0.000001 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000240 0.000002 1.000000 +0.000240 0.000002 1.000000 +0.000240 0.000002 1.000000 +-0.999971 0.000002 0.007639 +-0.999971 0.000002 0.007639 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000241 0.000002 1.000000 +0.000241 0.000002 1.000000 +0.000241 0.000002 1.000000 +-0.999971 0.000002 0.007639 +-0.999971 0.000002 0.007639 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000001 0.007639 +-0.999971 0.000001 0.007639 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000001 0.007639 +-0.999971 0.000001 0.007639 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000001 0.007639 +-0.999971 0.000001 0.007639 +-0.999971 0.000000 0.007640 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000001 0.007641 +-0.999971 0.000001 0.007641 +-0.999971 0.000000 0.007642 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007589 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007639 0.000001 -0.999971 +-0.007639 0.000001 -0.999971 +-0.007640 0.000000 -0.999971 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007589 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007641 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007641 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007639 0.000001 -0.999971 +-0.007639 0.000001 -0.999971 +-0.007640 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007661 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007640 -0.000001 -0.999971 +-0.007640 -0.000001 -0.999971 +-0.007640 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007661 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007640 -0.000001 -0.999971 +-0.007640 -0.000001 -0.999971 +-0.007640 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007661 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007640 -0.000001 -0.999971 +-0.007640 -0.000001 -0.999971 +-0.007640 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007661 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007640 -0.000001 -0.999971 +-0.007640 -0.000001 -0.999971 +-0.007640 0.000000 -0.999971 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000241 0.000002 1.000000 +0.000241 0.000002 1.000000 +0.000241 0.000002 1.000000 +-0.999971 0.000002 0.007639 +-0.999971 0.000002 0.007639 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000240 0.000002 1.000000 +0.000240 0.000002 1.000000 +0.000240 0.000002 1.000000 +-0.999971 0.000002 0.007639 +-0.999971 0.000002 0.007639 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000001 0.007639 +-0.999971 0.000001 0.007639 +-0.999971 0.000000 0.007640 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000001 0.007641 +-0.999971 0.000001 0.007641 +-0.999971 0.000000 0.007642 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000001 0.007641 +-0.999971 0.000001 0.007641 +-0.999971 0.000000 0.007642 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007589 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007639 0.000001 -0.999971 +-0.007639 0.000001 -0.999971 +-0.007640 0.000000 -0.999971 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007589 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007639 0.000001 -0.999971 +-0.007639 0.000001 -0.999971 +-0.007640 0.000000 -0.999971 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007583 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007639 0.000001 -0.999971 +-0.007639 0.000001 -0.999971 +-0.007640 0.000000 -0.999971 +-0.999972 0.000000 0.007505 +-0.999972 0.000000 0.007505 +-0.999972 0.000000 0.007505 +-0.999972 0.000000 0.007505 +-0.999972 0.000000 0.007505 +-0.999972 0.000000 0.007505 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007613 0.000000 -0.999971 +-0.007613 0.000000 -0.999971 +-0.007613 0.000000 -0.999971 +-0.007661 0.000000 -0.999971 +-0.007661 0.000000 -0.999971 +-0.007661 0.000000 -0.999971 +-0.007661 0.000000 -0.999971 +-0.007661 0.000000 -0.999971 +-0.007661 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007613 0.000000 -0.999971 +-0.007613 0.000000 -0.999971 +-0.007613 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007613 0.000000 -0.999971 +-0.007613 0.000000 -0.999971 +-0.007613 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007565 0.000000 -0.999971 +-0.007565 0.000000 -0.999971 +-0.007565 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007565 0.000000 -0.999971 +-0.007565 0.000000 -0.999971 +-0.007565 0.000000 -0.999971 +-0.007661 0.000000 -0.999971 +-0.007661 0.000000 -0.999971 +-0.007661 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007512 0.000000 -0.999972 +-0.007512 0.000000 -0.999972 +-0.007512 0.000000 -0.999972 +-0.007679 0.000000 -0.999971 +-0.007679 0.000000 -0.999970 +-0.007679 0.000000 -0.999970 +-0.999972 0.000000 0.007435 +-0.999972 0.000000 0.007435 +-0.999972 0.000000 0.007435 +-0.999972 0.000000 0.007505 +-0.999972 0.000000 0.007505 +-0.999972 0.000000 0.007505 +-0.999971 0.000000 0.007581 +-0.999971 0.000000 0.007581 +-0.999971 0.000000 0.007581 +-0.999971 0.000000 0.007658 +-0.999971 0.000000 0.007658 +-0.999971 0.000000 0.007658 +-0.999971 0.000000 0.007588 +-0.999971 0.000000 0.007588 +-0.999971 0.000000 0.007588 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +-0.999972 0.000000 0.007511 +-0.999972 0.000000 0.007511 +-0.999972 0.000000 0.007511 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +-0.007641 0.000002 -0.999971 +-0.007641 0.000002 -0.999971 +-0.007641 0.000002 -0.999971 +-0.007661 0.000000 -0.999971 +-0.007661 0.000000 -0.999971 +-0.007661 0.000000 -0.999971 +-0.007613 0.000000 -0.999971 +-0.007613 0.000000 -0.999971 +-0.007613 0.000000 -0.999971 +-0.007640 0.000001 -0.999971 +-0.007640 0.000001 -0.999971 +-0.007640 0.000001 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000240 0.000000 1.000000 +0.000240 0.000000 1.000000 +0.000240 0.000000 1.000000 +-0.000241 -0.000001 -1.000000 +-0.000241 -0.000001 -1.000000 +-0.000241 -0.000001 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007661 0.000000 -0.999971 +-0.007661 0.000000 -0.999971 +-0.007661 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007613 0.000000 -0.999971 +-0.007613 0.000000 -0.999971 +-0.007613 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007565 0.000000 -0.999971 +-0.007565 0.000000 -0.999971 +-0.007565 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007661 0.000000 -0.999971 +-0.007661 0.000000 -0.999971 +-0.007661 0.000000 -0.999971 +-0.007641 -0.000001 -0.999971 +-0.007641 -0.000001 -0.999971 +-0.007641 -0.000001 -0.999971 +-0.007661 0.000000 -0.999971 +-0.007661 0.000000 -0.999971 +-0.007661 0.000000 -0.999971 +-0.007661 0.000000 -0.999971 +-0.007661 0.000000 -0.999971 +-0.007661 0.000000 -0.999971 +-0.007640 -0.000001 -0.999971 +-0.007640 -0.000001 -0.999971 +-0.007640 -0.000001 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999971 0.000000 0.007595 +-0.999971 0.000000 0.007595 +-0.999971 0.000000 0.007595 +-0.007565 0.000000 -0.999971 +-0.007565 0.000000 -0.999971 +-0.007565 0.000000 -0.999971 +-0.007641 0.000002 -0.999971 +-0.007641 0.000002 -0.999971 +-0.007641 0.000002 -0.999971 +-0.007661 0.000000 -0.999971 +-0.007661 0.000000 -0.999971 +-0.007661 0.000000 -0.999971 +-0.007641 -0.000001 -0.999971 +-0.007641 -0.000001 -0.999971 +-0.007641 -0.000001 -0.999971 +-0.007661 0.000000 -0.999971 +-0.007661 0.000000 -0.999971 +-0.007661 0.000000 -0.999971 +-0.007640 -0.000001 -0.999971 +-0.007640 -0.000001 -0.999971 +-0.007640 -0.000001 -0.999971 +-0.999971 0.000000 0.007595 +-0.999971 0.000000 0.007595 +-0.999971 0.000000 0.007595 +0.000241 0.000001 1.000000 +0.000241 0.000001 1.000000 +0.000241 0.000001 1.000000 +-0.014447 0.030105 0.999442 +-0.014447 0.030105 0.999442 +-0.014447 0.030105 0.999442 +0.000241 0.000001 1.000000 +0.000241 0.000001 1.000000 +0.000241 0.000001 1.000000 +-0.007613 0.000000 -0.999971 +-0.007613 0.000000 -0.999971 +-0.007613 0.000000 -0.999971 +-0.007640 0.000000 -0.999971 +-0.007640 0.000000 -0.999971 +-0.007640 0.000000 -0.999971 +-0.999971 0.000000 0.007664 +-0.999971 0.000000 0.007664 +-0.999971 0.000000 0.007664 +0.000240 0.000003 1.000000 +0.000240 0.000003 1.000000 +0.000240 0.000003 1.000000 +-0.999971 0.000000 0.007589 +-0.999971 0.000000 0.007589 +-0.999971 0.000000 0.007589 +0.000240 0.000003 1.000000 +0.000240 0.000003 1.000000 +0.000240 0.000003 1.000000 +-0.999972 0.000000 0.007505 +-0.999972 0.000000 0.007505 +-0.999972 0.000000 0.007505 +0.000239 0.000003 1.000000 +0.000239 0.000003 1.000000 +0.000239 0.000003 1.000000 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-0.007641 0.000000 -0.999971 +-0.007641 0.000000 -0.999971 +-0.007641 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000001 0.999971 +0.007639 0.000001 0.999971 +0.007639 0.000001 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007640 0.000000 -0.999971 +-0.007640 0.000000 -0.999971 +-0.007640 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +-0.007661 0.000000 -0.999971 +-0.007661 0.000000 -0.999971 +-0.007661 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.007613 0.000000 -0.999971 +-0.007613 0.000000 -0.999971 +-0.007613 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007640 0.000000 -0.999971 +-0.007640 0.000000 -0.999971 +-0.007640 0.000000 -0.999971 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999971 0.000000 0.007589 +-0.999971 0.000000 0.007589 +-0.999971 0.000000 0.007589 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999971 0.000000 0.007589 +-0.999971 0.000000 0.007589 +-0.999971 0.000000 0.007589 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999971 0.000000 0.007589 +-0.999971 0.000000 0.007589 +-0.999971 0.000000 0.007589 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.000241 0.000000 1.000000 +0.000241 0.000000 1.000000 +0.000241 0.000000 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.000239 -0.000003 -1.000000 +-0.000239 -0.000003 -1.000000 +-0.000239 -0.000003 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.000241 0.000001 1.000000 +0.000241 0.000001 1.000000 +0.000241 0.000001 1.000000 +-0.999971 0.000000 0.007642 +-0.999971 0.000000 0.007642 +-0.999971 0.000000 0.007642 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +-0.999971 0.000000 0.007642 +-0.999971 0.000000 0.007642 +-0.999971 0.000000 0.007642 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +-0.999971 0.000000 0.007642 +-0.999971 0.000000 0.007642 +-0.999971 0.000000 0.007642 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999971 0.000000 0.007589 +-0.999971 0.000000 0.007589 +-0.999971 0.000000 0.007589 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.000240 0.000003 1.000000 +0.000240 0.000003 1.000000 +0.000240 0.000003 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +-0.007613 0.000000 -0.999971 +-0.007613 0.000000 -0.999971 +-0.007613 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-0.007640 0.000000 -0.999971 +-0.007640 0.000000 -0.999971 +-0.007640 0.000000 -0.999971 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.999971 0.000000 0.007588 +-0.999971 0.000000 0.007588 +-0.999971 0.000000 0.007588 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.000240 0.000000 1.000000 +0.000240 0.000000 1.000000 +0.000240 0.000000 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.999971 0.000000 0.007590 +-0.999971 0.000000 0.007590 +-0.999971 0.000000 0.007590 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.000239 0.000000 1.000000 +0.000239 0.000000 1.000000 +0.000239 0.000000 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +-0.999971 0.000000 0.007658 +-0.999971 0.000000 0.007658 +-0.999971 0.000000 0.007658 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.000240 0.000003 1.000000 +0.000240 0.000003 1.000000 +0.000240 0.000003 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.999971 0.000000 0.007581 +-0.999971 0.000000 0.007581 +-0.999971 0.000000 0.007581 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.999972 0.000000 0.007505 +-0.999972 0.000000 0.007505 +-0.999972 0.000000 0.007505 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007637 +0.999971 0.000000 -0.007637 +0.999971 0.000000 -0.007637 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000000 0.007641 +-0.999971 0.000000 0.007641 +-0.999971 0.000000 0.007641 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +-0.007679 0.000000 -0.999971 +-0.007679 0.000000 -0.999970 +-0.007679 0.000000 -0.999971 +-0.007642 0.000000 -0.999971 +-0.007642 0.000000 -0.999971 +-0.007642 0.000000 -0.999971 +-0.007456 0.000000 -0.999972 +-0.007456 0.000000 -0.999972 +-0.007456 0.000000 -0.999972 +-0.007642 0.000000 -0.999971 +-0.007642 0.000000 -0.999971 +-0.007642 0.000000 -0.999971 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +-0.007679 0.000000 -0.999970 +-0.007679 0.000000 -0.999970 +-0.007679 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000003 0.999971 +0.007640 0.000003 0.999971 +0.007640 0.000003 0.999971 +-1.000000 0.000000 0.000241 +-1.000000 0.000000 0.000241 +-1.000000 0.000000 0.000241 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007642 0.000000 -0.999971 +-0.007642 0.000000 -0.999971 +-0.007642 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000003 0.000242 +-1.000000 0.000003 0.000242 +-1.000000 0.000003 0.000242 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000243 +1.000000 0.000000 -0.000243 +1.000000 0.000000 -0.000243 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000003 0.000242 +-1.000000 0.000003 0.000242 +-1.000000 0.000003 0.000242 +-0.007642 0.000000 -0.999971 +-0.007642 0.000000 -0.999971 +-0.007642 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-0.007642 0.000006 -0.999971 +-0.007642 0.000006 -0.999971 +-0.007642 0.000006 -0.999971 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.999971 0.000000 0.007589 +-0.999971 0.000000 0.007589 +-0.999971 0.000000 0.007589 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.000240 0.000000 1.000000 +0.000240 0.000000 1.000000 +0.000240 0.000000 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.999971 0.000000 0.007590 +-0.999971 0.000000 0.007590 +-0.999971 0.000000 0.007590 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.000239 0.000000 1.000000 +0.000239 0.000000 1.000000 +0.000239 0.000000 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +-0.999971 0.000000 0.007664 +-0.999971 0.000000 0.007664 +-0.999971 0.000000 0.007664 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000240 0.000003 1.000000 +0.000240 0.000003 1.000000 +0.000240 0.000003 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +-0.999971 0.000000 0.007658 +-0.999971 0.000000 0.007658 +-0.999971 0.000000 0.007658 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.000240 0.000003 1.000000 +0.000240 0.000003 1.000000 +0.000240 0.000003 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.999971 0.000000 0.007581 +-0.999971 0.000000 0.007581 +-0.999971 0.000000 0.007581 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.999972 0.000000 0.007505 +-0.999972 0.000000 0.007505 +-0.999972 0.000000 0.007505 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007637 +0.999971 0.000000 -0.007637 +0.999971 0.000000 -0.007637 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000000 0.007641 +-0.999971 0.000000 0.007641 +-0.999971 0.000000 0.007641 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.999971 0.000000 0.007589 +-0.999971 0.000000 0.007589 +-0.999971 0.000000 0.007589 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000240 0.000003 1.000000 +0.000240 0.000003 1.000000 +0.000240 0.000003 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.999972 0.000000 0.007505 +-0.999972 0.000000 0.007505 +-0.999972 0.000000 0.007505 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.000239 0.000003 1.000000 +0.000239 0.000003 1.000000 +0.000239 0.000003 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.999972 0.000000 0.007505 +-0.999972 0.000000 0.007505 +-0.999972 0.000000 0.007505 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000240 0.000003 1.000000 +0.000240 0.000003 1.000000 +0.000240 0.000003 1.000000 +-0.999971 0.000000 0.007642 +-0.999971 0.000000 0.007642 +-0.999971 0.000000 0.007642 +-0.000244 0.000000 -1.000000 +-0.000244 0.000000 -1.000000 +-0.000244 0.000000 -1.000000 +-0.999972 0.000000 0.007435 +-0.999972 0.000000 0.007435 +-0.999972 0.000000 0.007435 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007635 +0.999971 0.000000 -0.007635 +0.999971 0.000000 -0.007635 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000000 0.007645 +-0.999971 0.000000 0.007645 +-0.999971 0.000000 0.007645 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000241 +1.000000 0.000000 -0.000241 +1.000000 0.000000 -0.000241 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000000 0.000240 +-1.000000 0.000000 0.000240 +-1.000000 0.000000 0.000240 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +-0.007679 0.000000 -0.999971 +-0.007679 0.000000 -0.999970 +-0.007679 0.000000 -0.999970 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-0.007642 0.000000 -0.999971 +-0.007642 0.000000 -0.999971 +-0.007642 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +-0.007456 0.000000 -0.999972 +-0.007456 0.000000 -0.999972 +-0.007456 0.000000 -0.999972 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007642 0.000000 -0.999971 +-0.007642 0.000000 -0.999971 +-0.007642 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +-0.007456 0.000000 -0.999972 +-0.007456 0.000000 -0.999972 +-0.007456 0.000000 -0.999972 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000003 0.000242 +-1.000000 0.000003 0.000242 +-1.000000 0.000003 0.000242 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +-0.007679 0.000000 -0.999970 +-0.007679 0.000000 -0.999970 +-0.007679 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000003 0.999971 +0.007640 0.000003 0.999971 +0.007640 0.000003 0.999971 +-1.000000 0.000000 0.000241 +-1.000000 0.000000 0.000241 +-1.000000 0.000000 0.000241 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000003 0.000242 +-1.000000 0.000003 0.000242 +-1.000000 0.000003 0.000242 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000243 +1.000000 0.000000 -0.000243 +1.000000 0.000000 -0.000243 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000003 0.000242 +-1.000000 0.000003 0.000242 +-1.000000 0.000003 0.000242 +-0.007642 0.000000 -0.999971 +-0.007642 0.000000 -0.999971 +-0.007642 0.000000 -0.999971 +1.000000 0.000000 -0.000243 +1.000000 0.000000 -0.000243 +1.000000 0.000000 -0.000243 +-0.007344 0.000000 -0.999973 +-0.007344 0.000000 -0.999973 +-0.007344 0.000000 -0.999973 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000000 0.000241 +-1.000000 0.000000 0.000241 +-1.000000 0.000000 0.000241 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000241 +1.000000 0.000000 -0.000241 +1.000000 0.000000 -0.000241 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000000 0.000240 +-1.000000 0.000000 0.000240 +-1.000000 0.000000 0.000240 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +-0.007679 0.000000 -0.999971 +-0.007679 0.000000 -0.999970 +-0.007679 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-0.007642 0.000000 -0.999971 +-0.007642 0.000000 -0.999971 +-0.007642 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +-0.007456 0.000000 -0.999972 +-0.007456 0.000000 -0.999972 +-0.007456 0.000000 -0.999972 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007642 0.000000 -0.999971 +-0.007642 0.000000 -0.999971 +-0.007642 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +-0.007456 0.000000 -0.999972 +-0.007456 0.000000 -0.999972 +-0.007456 0.000000 -0.999972 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000003 0.000242 +-1.000000 0.000003 0.000242 +-1.000000 0.000003 0.000242 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +-0.007679 0.000000 -0.999971 +-0.007679 0.000000 -0.999970 +-0.007679 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000003 0.999971 +0.007640 0.000003 0.999971 +0.007640 0.000003 0.999971 +-1.000000 0.000000 0.000241 +-1.000000 0.000000 0.000241 +-1.000000 0.000000 0.000241 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000003 0.000242 +-1.000000 0.000003 0.000242 +-1.000000 0.000003 0.000242 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.000240 0.000003 1.000000 +0.000240 0.000003 1.000000 +0.000240 0.000003 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +-0.999971 0.000000 0.007664 +-0.999971 0.000000 0.007664 +-0.999971 0.000000 0.007664 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000240 0.000003 1.000000 +0.000240 0.000003 1.000000 +0.000240 0.000003 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000000 0.007641 +-0.999971 0.000000 0.007641 +-0.999971 0.000000 0.007641 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.000240 0.000003 1.000000 +0.000240 0.000003 1.000000 +0.000240 0.000003 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007637 +0.999971 0.000000 -0.007637 +0.999971 0.000000 -0.007637 +0.000241 0.000000 1.000000 +0.000241 0.000000 1.000000 +0.000241 0.000000 1.000000 +-0.999971 0.000000 0.007641 +-0.999971 0.000000 0.007641 +-0.999971 0.000000 0.007641 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +-0.999971 0.000000 0.007588 +-0.999971 0.000000 0.007588 +-0.999971 0.000000 0.007588 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000241 0.000002 1.000000 +0.000241 0.000002 1.000000 +0.000241 0.000002 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.000240 0.000003 1.000000 +0.000240 0.000003 1.000000 +0.000240 0.000003 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.000243 0.000000 -1.000000 +-0.000243 0.000000 -1.000000 +-0.000243 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000242 0.000002 1.000000 +0.000242 0.000002 1.000000 +0.000242 0.000002 1.000000 +-0.999971 0.000000 0.007642 +-0.999971 0.000000 0.007642 +-0.999971 0.000000 0.007642 +-0.000243 0.000000 -1.000000 +-0.000243 0.000000 -1.000000 +-0.000243 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007635 +0.999971 0.000000 -0.007635 +0.999971 0.000000 -0.007635 +0.000241 0.000000 1.000000 +0.000241 0.000000 1.000000 +0.000241 0.000000 1.000000 +-0.999971 0.000000 0.007645 +-0.999971 0.000000 0.007645 +-0.999971 0.000000 0.007645 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-0.007641 0.000000 -0.999971 +-0.007641 0.000000 -0.999971 +-0.007641 0.000000 -0.999971 +1.000000 0.000000 -0.000241 +1.000000 0.000000 -0.000241 +1.000000 0.000000 -0.000241 +-0.007624 0.000000 -0.999971 +-0.007624 0.000000 -0.999971 +-0.007624 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000000 0.000240 +-1.000000 0.000000 0.000240 +-1.000000 0.000000 0.000240 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +-0.007679 0.000000 -0.999971 +-0.007679 0.000000 -0.999970 +-0.007679 0.000000 -0.999970 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +-0.007512 0.000000 -0.999972 +-0.007512 0.000000 -0.999972 +-0.007512 0.000000 -0.999972 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000002 0.999971 +0.007639 0.000002 0.999971 +0.007639 0.000002 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007641 0.000000 -0.999971 +-0.007641 0.000000 -0.999971 +-0.007641 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +-0.007511 0.000000 -0.999972 +-0.007511 0.000000 -0.999972 +-0.007511 0.000000 -0.999972 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +-1.000000 0.000003 0.000242 +-1.000000 0.000003 0.000242 +-1.000000 0.000003 0.000242 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +-0.007624 0.000000 -0.999971 +-0.007624 0.000000 -0.999971 +-0.007624 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-0.007641 0.000000 -0.999971 +-0.007641 0.000000 -0.999971 +-0.007641 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +-1.000000 0.000000 0.000241 +-1.000000 0.000000 0.000241 +-1.000000 0.000000 0.000241 +-0.007641 0.000000 -0.999971 +-0.007641 0.000000 -0.999971 +-0.007641 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +-0.007456 0.000000 -0.999972 +-0.007456 0.000000 -0.999972 +-0.007456 0.000000 -0.999972 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007642 0.000000 -0.999971 +-0.007642 0.000000 -0.999971 +-0.007642 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +-1.000000 0.000003 0.000242 +-1.000000 0.000003 0.000242 +-1.000000 0.000003 0.000242 +-0.007641 0.000000 -0.999971 +-0.007641 0.000000 -0.999971 +-0.007641 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +-0.007512 0.000000 -0.999972 +-0.007512 0.000000 -0.999972 +-0.007512 0.000000 -0.999972 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000243 +1.000000 0.000000 -0.000243 +1.000000 0.000000 -0.000243 +-0.007512 0.000000 -0.999972 +-0.007512 0.000000 -0.999972 +-0.007512 0.000000 -0.999972 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000003 0.000242 +-1.000000 0.000003 0.000242 +-1.000000 0.000003 0.000242 +-0.007641 0.000000 -0.999971 +-0.007641 0.000000 -0.999971 +-0.007641 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +-0.007512 0.000000 -0.999972 +-0.007512 0.000000 -0.999972 +-0.007512 0.000000 -0.999972 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007642 0.000000 -0.999971 +-0.007642 0.000000 -0.999971 +-0.007642 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-0.007641 0.000000 -0.999971 +-0.007641 0.000000 -0.999971 +-0.007641 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007641 0.000000 -0.999971 +-0.007641 0.000000 -0.999971 +-0.007641 0.000000 -0.999971 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +-0.007624 0.000000 -0.999971 +-0.007624 0.000000 -0.999971 +-0.007624 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-0.007641 0.000000 -0.999971 +-0.007641 0.000000 -0.999971 +-0.007641 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +-1.000000 0.000000 0.000241 +-1.000000 0.000000 0.000241 +-1.000000 0.000000 0.000241 +-0.007641 0.000000 -0.999971 +-0.007641 0.000000 -0.999971 +-0.007641 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +-1.000000 0.000003 0.000242 +-1.000000 0.000003 0.000242 +-1.000000 0.000003 0.000242 +-0.007641 0.000000 -0.999971 +-0.007641 0.000000 -0.999971 +-0.007641 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +-0.007512 -0.000002 -0.999972 +-0.007512 -0.000002 -0.999972 +-0.007512 -0.000002 -0.999972 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-0.007641 0.000000 -0.999971 +-0.007641 0.000000 -0.999971 +-0.007641 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007640 0.000000 -0.999971 +-0.007640 0.000000 -0.999971 +-0.007640 0.000000 -0.999971 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.000242 -0.000001 -1.000000 +-0.000242 -0.000001 -1.000000 +-0.000242 -0.000001 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.000241 0.000003 1.000000 +0.000241 0.000003 1.000000 +0.000241 0.000003 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.000241 0.000003 1.000000 +0.000241 0.000003 1.000000 +0.000241 0.000003 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.000241 0.000003 1.000000 +0.000241 0.000003 1.000000 +0.000241 0.000003 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.000241 0.000001 1.000000 +0.000241 0.000001 1.000000 +0.000241 0.000001 1.000000 +-0.999971 0.000000 0.007642 +-0.999971 0.000000 0.007642 +-0.999971 0.000000 0.007642 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007641 0.000000 0.999971 +0.007641 0.000000 0.999971 +0.007641 0.000000 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007641 0.000000 0.999971 +0.007641 0.000000 0.999971 +0.007641 0.000000 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-0.007641 0.000000 -0.999971 +-0.007641 0.000000 -0.999971 +-0.007641 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-0.007640 0.000000 -0.999971 +-0.007640 0.000000 -0.999971 +-0.007640 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-0.007641 -0.000001 -0.999971 +-0.007641 -0.000001 -0.999971 +-0.007641 -0.000001 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +-0.007661 0.000000 -0.999971 +-0.007661 0.000000 -0.999971 +-0.007661 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007640 0.000000 -0.999971 +-0.007640 0.000000 -0.999971 +-0.007640 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007640 0.000000 -0.999971 +-0.007640 0.000000 -0.999971 +-0.007640 0.000000 -0.999971 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.000240 0.000003 1.000000 +0.000240 0.000003 1.000000 +0.000240 0.000003 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.000241 0.000001 1.000000 +0.000241 0.000001 1.000000 +0.000241 0.000001 1.000000 +-0.999971 0.000000 0.007642 +-0.999971 0.000000 0.007642 +-0.999971 0.000000 0.007642 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.000241 0.000001 1.000000 +0.000241 0.000001 1.000000 +0.000241 0.000001 1.000000 +-0.999971 0.000000 0.007642 +-0.999971 0.000000 0.007642 +-0.999971 0.000000 0.007642 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007641 0.000000 0.999971 +0.007641 0.000000 0.999971 +0.007641 0.000000 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-0.007640 0.000000 -0.999971 +-0.007640 0.000000 -0.999971 +-0.007640 0.000000 -0.999971 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007641 0.000001 0.999971 +0.007641 0.000001 0.999971 +0.007641 0.000001 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-0.007640 0.000000 -0.999971 +-0.007640 0.000000 -0.999971 +-0.007640 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007456 0.000000 -0.999972 +-0.007456 0.000000 -0.999972 +-0.007456 0.000000 -0.999972 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-0.007641 0.000000 -0.999971 +-0.007641 0.000000 -0.999971 +-0.007641 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +-0.007661 0.000000 -0.999971 +-0.007661 0.000000 -0.999971 +-0.007661 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007640 0.000000 -0.999971 +-0.007640 0.000000 -0.999971 +-0.007640 0.000000 -0.999971 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999971 0.000000 0.007589 +-0.999971 0.000000 0.007589 +-0.999971 0.000000 0.007589 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999971 0.000000 0.007589 +-0.999971 0.000000 0.007589 +-0.999971 0.000000 0.007589 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.000240 0.000003 1.000000 +0.000240 0.000003 1.000000 +0.000240 0.000003 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.000240 0.000003 1.000000 +0.000240 0.000003 1.000000 +0.000240 0.000003 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.000241 0.000001 1.000000 +0.000241 0.000001 1.000000 +0.000241 0.000001 1.000000 +-0.999971 0.000000 0.007642 +-0.999971 0.000000 0.007642 +-0.999971 0.000000 0.007642 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.000241 0.000001 1.000000 +0.000241 0.000001 1.000000 +0.000241 0.000001 1.000000 +-0.999971 0.000000 0.007642 +-0.999971 0.000000 0.007642 +-0.999971 0.000000 0.007642 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007641 0.000000 0.999971 +0.007641 0.000000 0.999971 +0.007641 0.000000 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-0.007641 0.000000 -0.999971 +-0.007641 0.000000 -0.999971 +-0.007641 0.000000 -0.999971 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007641 0.000000 0.999971 +0.007641 0.000000 0.999971 +0.007641 0.000000 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-0.007640 0.000000 -0.999971 +-0.007640 0.000000 -0.999971 +-0.007640 0.000000 -0.999971 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998106 0.061525 0.000000 +0.998106 0.061525 0.000000 +0.998106 0.061525 0.000000 +0.000000 0.080183 -0.996780 +0.000000 0.080183 -0.996780 +0.000000 0.080183 -0.996780 +-0.998106 0.061525 0.000000 +-0.998106 0.061525 0.000000 +-0.998106 0.061525 0.000000 +0.000000 0.085726 0.996319 +0.000000 0.085726 0.996319 +0.000000 0.085726 0.996319 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998103 0.061563 0.000000 +0.998103 0.061563 0.000000 +0.998103 0.061563 0.000000 +0.000000 0.080233 -0.996776 +0.000000 0.080233 -0.996776 +0.000000 0.080233 -0.996776 +-0.998103 0.061563 0.000000 +-0.998103 0.061563 0.000000 +-0.998103 0.061563 0.000000 +0.000000 0.085779 0.996314 +0.000000 0.085779 0.996314 +0.000000 0.085779 0.996314 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998099 0.061626 0.000000 +0.998099 0.061626 0.000000 +0.998099 0.061626 0.000000 +0.000000 0.080315 -0.996770 +0.000000 0.080314 -0.996770 +0.000000 0.080314 -0.996770 +-0.998099 0.061626 0.000000 +-0.998099 0.061626 0.000000 +-0.998099 0.061626 0.000000 +0.000000 0.085866 0.996307 +0.000000 0.085866 0.996307 +0.000000 0.085866 0.996307 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998102 0.061580 0.000000 +0.998102 0.061580 0.000000 +0.998102 0.061580 0.000000 +0.000000 0.080254 -0.996774 +0.000000 0.080254 -0.996774 +0.000000 0.080254 -0.996774 +-0.998102 0.061579 0.000000 +-0.998102 0.061579 0.000000 +-0.998102 0.061579 0.000000 +0.000000 0.085802 0.996312 +0.000000 0.085802 0.996312 +0.000000 0.085802 0.996312 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998106 0.061525 0.000000 +0.998106 0.061525 0.000000 +0.998106 0.061525 0.000000 +0.000000 0.080183 -0.996780 +0.000000 0.080183 -0.996780 +0.000000 0.080183 -0.996780 +-0.998106 0.061525 0.000000 +-0.998106 0.061525 0.000000 +-0.998106 0.061525 0.000000 +0.000000 0.085726 0.996319 +0.000000 0.085726 0.996319 +0.000000 0.085726 0.996319 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998103 0.061563 0.000000 +0.998103 0.061563 0.000000 +0.998103 0.061563 0.000000 +0.000000 0.080233 -0.996776 +0.000000 0.080233 -0.996776 +0.000000 0.080233 -0.996776 +-0.998103 0.061563 0.000000 +-0.998103 0.061563 0.000000 +-0.998103 0.061563 0.000000 +0.000000 0.085779 0.996314 +0.000000 0.085779 0.996314 +0.000000 0.085779 0.996314 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998099 0.061626 0.000000 +0.998099 0.061626 0.000000 +0.998099 0.061626 0.000000 +0.000000 0.080314 -0.996770 +0.000000 0.080314 -0.996770 +0.000000 0.080314 -0.996770 +-0.998099 0.061626 0.000000 +-0.998099 0.061626 0.000000 +-0.998099 0.061626 0.000000 +0.000000 0.085866 0.996307 +0.000000 0.085866 0.996307 +0.000000 0.085866 0.996307 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998102 0.061580 0.000000 +0.998102 0.061580 0.000000 +0.998102 0.061580 0.000000 +0.000000 0.080255 -0.996774 +0.000000 0.080255 -0.996774 +0.000000 0.080255 -0.996774 +-0.998102 0.061579 0.000000 +-0.998102 0.061579 0.000000 +-0.998102 0.061579 0.000000 +0.000000 0.085802 0.996312 +0.000000 0.085802 0.996312 +0.000000 0.085802 0.996312 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -0.086950 -0.996213 +0.000000 -0.086950 -0.996213 +0.000000 -0.086950 -0.996213 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.000000 -0.086945 0.996213 +0.000000 -0.086945 0.996213 +0.000000 -0.086945 0.996213 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.061527 0.998105 +0.000000 0.061527 0.998105 +0.000000 0.061527 0.998105 +0.996780 0.080182 0.000000 +0.996780 0.080183 0.000000 +0.996780 0.080182 0.000000 +0.000000 0.061523 -0.998106 +0.000000 0.061523 -0.998106 +0.000000 0.061523 -0.998106 +-0.996319 0.085726 0.000000 +-0.996319 0.085726 0.000000 +-0.996319 0.085726 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -0.086945 -0.996213 +0.000000 -0.086945 -0.996213 +0.000000 -0.086945 -0.996213 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.000000 -0.086945 0.996213 +0.000000 -0.086945 0.996213 +0.000000 -0.086945 0.996213 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.061561 0.998103 +0.000000 0.061561 0.998103 +0.000000 0.061561 0.998103 +0.996776 0.080232 0.000000 +0.996776 0.080232 0.000000 +0.996776 0.080232 0.000000 +0.000000 0.061561 -0.998103 +0.000000 0.061561 -0.998103 +0.000000 0.061561 -0.998103 +-0.996314 0.085778 0.000000 +-0.996314 0.085778 0.000000 +-0.996314 0.085778 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -0.086945 -0.996213 +0.000000 -0.086945 -0.996213 +0.000000 -0.086945 -0.996213 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.000000 -0.086950 0.996213 +0.000000 -0.086950 0.996213 +0.000000 -0.086950 0.996213 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.061625 0.998099 +0.000000 0.061625 0.998099 +0.000000 0.061625 0.998099 +0.996770 0.080314 0.000000 +0.996770 0.080314 0.000000 +0.996770 0.080314 0.000000 +0.000000 0.061628 -0.998099 +0.000000 0.061628 -0.998099 +0.000000 0.061628 -0.998099 +-0.996307 0.085866 0.000000 +-0.996307 0.085866 0.000000 +-0.996307 0.085866 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -0.086950 -0.996213 +0.000000 -0.086950 -0.996213 +0.000000 -0.086950 -0.996213 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.000000 -0.086950 0.996213 +0.000000 -0.086950 0.996213 +0.000000 -0.086950 0.996213 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.061582 0.998102 +0.000000 0.061582 0.998102 +0.000000 0.061582 0.998102 +0.996774 0.080254 0.000000 +0.996774 0.080254 0.000000 +0.996774 0.080254 0.000000 +0.000000 0.061582 -0.998102 +0.000000 0.061582 -0.998102 +0.000000 0.061582 -0.998102 +-0.996312 0.085802 0.000000 +-0.996312 0.085802 0.000000 +-0.996312 0.085802 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998106 0.061525 0.000000 +0.998106 0.061525 0.000000 +0.998106 0.061525 0.000000 +0.000000 0.080183 -0.996780 +0.000000 0.080183 -0.996780 +0.000000 0.080183 -0.996780 +-0.998106 0.061525 0.000000 +-0.998106 0.061525 0.000000 +-0.998106 0.061525 0.000000 +0.000000 0.085726 0.996319 +0.000000 0.085726 0.996319 +0.000000 0.085726 0.996319 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998103 0.061563 0.000000 +0.998103 0.061563 0.000000 +0.998103 0.061563 0.000000 +0.000000 0.080233 -0.996776 +0.000000 0.080233 -0.996776 +0.000000 0.080233 -0.996776 +-0.998103 0.061563 0.000000 +-0.998103 0.061563 0.000000 +-0.998103 0.061563 0.000000 +0.000000 0.085779 0.996314 +0.000000 0.085779 0.996314 +0.000000 0.085779 0.996314 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998099 0.061626 0.000000 +0.998099 0.061626 0.000000 +0.998099 0.061626 0.000000 +0.000000 0.080315 -0.996770 +0.000000 0.080314 -0.996770 +0.000000 0.080314 -0.996770 +-0.998099 0.061626 0.000000 +-0.998099 0.061626 0.000000 +-0.998099 0.061626 0.000000 +0.000000 0.085866 0.996307 +0.000000 0.085866 0.996307 +0.000000 0.085866 0.996307 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998102 0.061580 0.000000 +0.998102 0.061580 0.000000 +0.998102 0.061580 0.000000 +0.000000 0.080254 -0.996774 +0.000000 0.080254 -0.996774 +0.000000 0.080254 -0.996774 +-0.998102 0.061579 0.000000 +-0.998102 0.061579 0.000000 +-0.998102 0.061579 0.000000 +0.000000 0.085802 0.996312 +0.000000 0.085802 0.996312 +0.000000 0.085802 0.996312 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998106 0.061525 0.000000 +0.998106 0.061525 0.000000 +0.998106 0.061525 0.000000 +0.000000 0.080183 -0.996780 +0.000000 0.080183 -0.996780 +0.000000 0.080183 -0.996780 +-0.998106 0.061525 0.000000 +-0.998106 0.061525 0.000000 +-0.998106 0.061525 0.000000 +0.000000 0.085726 0.996319 +0.000000 0.085726 0.996319 +0.000000 0.085726 0.996319 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998103 0.061563 0.000000 +0.998103 0.061563 0.000000 +0.998103 0.061563 0.000000 +0.000000 0.080233 -0.996776 +0.000000 0.080233 -0.996776 +0.000000 0.080233 -0.996776 +-0.998103 0.061563 0.000000 +-0.998103 0.061563 0.000000 +-0.998103 0.061563 0.000000 +0.000000 0.085779 0.996314 +0.000000 0.085779 0.996314 +0.000000 0.085779 0.996314 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998102 0.061580 0.000000 +0.998102 0.061580 0.000000 +0.998102 0.061580 0.000000 +0.000000 0.080254 -0.996774 +0.000000 0.080254 -0.996774 +0.000000 0.080254 -0.996774 +-0.998102 0.061579 0.000000 +-0.998102 0.061579 0.000000 +-0.998102 0.061579 0.000000 +0.000000 0.085802 0.996312 +0.000000 0.085802 0.996312 +0.000000 0.085802 0.996312 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000000 -0.000001 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -0.086947 -0.996213 +0.000000 -0.086947 -0.996213 +0.000000 -0.086947 -0.996213 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.000000 -0.086947 0.996213 +0.000000 -0.086947 0.996213 +0.000000 -0.086947 0.996213 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.061525 0.998106 +0.000000 0.061525 0.998106 +0.000000 0.061525 0.998106 +0.996780 0.080183 0.000000 +0.996780 0.080183 0.000000 +0.996780 0.080183 0.000000 +0.000000 0.061525 -0.998106 +0.000000 0.061525 -0.998105 +0.000000 0.061525 -0.998105 +-0.996319 0.085726 0.000000 +-0.996319 0.085726 0.000000 +-0.996319 0.085726 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -0.000001 -1.000000 +0.000000 -0.000001 -1.000000 +0.000001 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000001 -0.086945 -0.996213 +0.000001 -0.086945 -0.996213 +0.000001 -0.086945 -0.996213 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.000000 -0.086947 0.996213 +0.000000 -0.086947 0.996213 +0.000000 -0.086947 0.996213 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.061561 0.998103 +0.000000 0.061561 0.998103 +0.000000 0.061561 0.998103 +0.996776 0.080232 0.000000 +0.996776 0.080232 0.000000 +0.996776 0.080232 0.000000 +0.000000 0.061563 -0.998103 +0.000000 0.061563 -0.998103 +0.000000 0.061563 -0.998103 +-0.996314 0.085778 0.000000 +-0.996314 0.085778 0.000000 +-0.996314 0.085778 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.000001 0.000001 1.000000 +0.000000 0.000000 1.000000 +-0.000001 0.000001 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -0.086947 -0.996213 +0.000000 -0.086947 -0.996213 +0.000000 -0.086947 -0.996213 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.000000 -0.086950 0.996213 +-0.000001 -0.086947 0.996213 +0.000000 -0.086950 0.996213 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.061626 0.998099 +0.000000 0.061626 0.998099 +0.000000 0.061626 0.998099 +0.996770 0.080314 0.000000 +0.996770 0.080314 0.000000 +0.996770 0.080314 0.000000 +0.000000 0.061626 -0.998099 +0.000000 0.061626 -0.998099 +0.000000 0.061626 -0.998099 +-0.996307 0.085866 0.000000 +-0.996307 0.085866 0.000000 +-0.996307 0.085866 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -0.086947 -0.996213 +0.000000 -0.086947 -0.996213 +0.000000 -0.086947 -0.996213 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.000000 -0.086947 0.996213 +0.000000 -0.086947 0.996213 +0.000000 -0.086947 0.996213 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.061578 0.998102 +0.000000 0.061578 0.998102 +0.000000 0.061578 0.998102 +0.996774 0.080254 0.000000 +0.996774 0.080254 0.000000 +0.996774 0.080254 0.000000 +0.000000 0.061580 -0.998102 +0.000000 0.061580 -0.998102 +0.000000 0.061580 -0.998102 +-0.996312 0.085802 0.000000 +-0.996312 0.085802 0.000000 +-0.996312 0.085802 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -0.086947 -0.996213 +0.000000 -0.086947 -0.996213 +0.000000 -0.086947 -0.996213 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.000000 -0.086947 0.996213 +0.000000 -0.086947 0.996213 +0.000000 -0.086947 0.996213 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.061563 0.998103 +0.000000 0.061563 0.998103 +0.000000 0.061563 0.998103 +0.996776 0.080232 0.000000 +0.996776 0.080232 0.000000 +0.996776 0.080232 0.000000 +0.000000 0.061562 -0.998103 +0.000000 0.061562 -0.998103 +0.000000 0.061562 -0.998103 +-0.996314 0.085778 0.000000 +-0.996314 0.085778 0.000000 +-0.996314 0.085778 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -0.086947 -0.996213 +0.000000 -0.086947 -0.996213 +0.000000 -0.086947 -0.996213 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.000000 -0.086947 0.996213 +0.000000 -0.086947 0.996213 +0.000000 -0.086947 0.996213 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.061626 0.998099 +0.000000 0.061626 0.998099 +0.000000 0.061626 0.998099 +0.996770 0.080314 0.000000 +0.996770 0.080314 0.000000 +0.996770 0.080314 0.000000 +0.000000 0.061625 -0.998099 +0.000000 0.061625 -0.998099 +0.000000 0.061625 -0.998099 +-0.996307 0.085866 0.000000 +-0.996307 0.085866 0.000000 +-0.996307 0.085866 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -0.086947 -0.996213 +0.000000 -0.086947 -0.996213 +0.000000 -0.086947 -0.996213 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.000000 -0.086947 0.996213 +0.000000 -0.086947 0.996213 +0.000000 -0.086947 0.996213 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.061580 0.998102 +0.000000 0.061580 0.998102 +0.000000 0.061580 0.998102 +0.996774 0.080254 0.000000 +0.996774 0.080254 0.000000 +0.996775 0.080254 0.000000 +0.000000 0.061579 -0.998102 +0.000000 0.061579 -0.998102 +0.000000 0.061579 -0.998102 +-0.996312 0.085802 0.000000 +-0.996312 0.085802 0.000000 +-0.996312 0.085802 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998105 0.061525 0.000000 +0.998106 0.061525 0.000000 +0.998106 0.061525 0.000000 +0.000000 0.080182 -0.996780 +0.000000 0.080182 -0.996780 +0.000000 0.080182 -0.996780 +-0.998106 0.061525 0.000000 +-0.998106 0.061525 0.000000 +-0.998106 0.061525 0.000000 +0.000000 0.085726 0.996319 +0.000000 0.085726 0.996319 +0.000000 0.085726 0.996319 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998103 0.061563 0.000000 +0.998103 0.061563 0.000000 +0.998103 0.061563 0.000000 +0.000000 0.080232 -0.996776 +0.000000 0.080232 -0.996776 +0.000000 0.080232 -0.996776 +-0.998103 0.061563 0.000000 +-0.998103 0.061563 0.000000 +-0.998103 0.061563 0.000000 +0.000000 0.085778 0.996314 +0.000000 0.085778 0.996314 +0.000000 0.085778 0.996314 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998099 0.061626 0.000000 +0.998099 0.061626 0.000000 +0.998099 0.061626 0.000000 +0.000000 0.080314 -0.996770 +0.000000 0.080314 -0.996770 +0.000000 0.080314 -0.996770 +-0.998099 0.061626 0.000000 +-0.998099 0.061626 0.000000 +-0.998099 0.061626 0.000000 +0.000000 0.085866 0.996307 +0.000000 0.085866 0.996307 +0.000000 0.085866 0.996307 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998102 0.061580 0.000000 +0.998102 0.061580 0.000000 +0.998102 0.061580 0.000000 +0.000000 0.080254 -0.996774 +0.000000 0.080254 -0.996774 +0.000000 0.080254 -0.996774 +-0.998102 0.061579 0.000000 +-0.998102 0.061579 0.000000 +-0.998102 0.061579 0.000000 +0.000000 0.085802 0.996312 +0.000000 0.085802 0.996312 +0.000000 0.085802 0.996312 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -0.086950 -0.996213 +0.000000 -0.086950 -0.996213 +0.000000 -0.086950 -0.996213 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.000000 -0.086945 0.996213 +0.000000 -0.086945 0.996213 +0.000000 -0.086945 0.996213 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.061527 0.998105 +0.000000 0.061527 0.998105 +0.000000 0.061527 0.998105 +0.996780 0.080183 0.000000 +0.996780 0.080183 0.000000 +0.996780 0.080183 0.000000 +0.000000 0.061523 -0.998106 +0.000000 0.061523 -0.998106 +0.000000 0.061523 -0.998106 +-0.996319 0.085726 0.000000 +-0.996319 0.085726 0.000000 +-0.996319 0.085726 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -0.086945 -0.996213 +0.000000 -0.086945 -0.996213 +0.000000 -0.086945 -0.996213 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.000000 -0.086945 0.996213 +0.000000 -0.086945 0.996213 +0.000000 -0.086945 0.996213 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.061561 0.998103 +0.000000 0.061561 0.998103 +0.000000 0.061561 0.998103 +0.996776 0.080232 0.000000 +0.996776 0.080232 0.000000 +0.996776 0.080232 0.000000 +0.000000 0.061561 -0.998103 +0.000000 0.061561 -0.998103 +0.000000 0.061561 -0.998103 +-0.996314 0.085778 0.000000 +-0.996314 0.085778 0.000000 +-0.996314 0.085778 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -0.086945 -0.996213 +0.000000 -0.086945 -0.996213 +0.000000 -0.086945 -0.996213 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.000000 -0.086950 0.996213 +0.000000 -0.086950 0.996213 +0.000000 -0.086950 0.996213 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.061625 0.998099 +0.000000 0.061625 0.998099 +0.000000 0.061625 0.998099 +0.996770 0.080314 0.000000 +0.996770 0.080314 0.000000 +0.996770 0.080314 0.000000 +0.000000 0.061628 -0.998099 +0.000000 0.061628 -0.998099 +0.000000 0.061628 -0.998099 +-0.996307 0.085866 0.000000 +-0.996307 0.085866 0.000000 +-0.996307 0.085866 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -0.086950 -0.996213 +0.000000 -0.086950 -0.996213 +0.000000 -0.086950 -0.996213 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.000000 -0.086950 0.996213 +0.000000 -0.086950 0.996213 +0.000000 -0.086950 0.996213 +-0.993768 -0.111467 0.000000 +-0.993768 -0.111467 0.000000 +-0.993768 -0.111467 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.061582 0.998102 +0.000000 0.061582 0.998102 +0.000000 0.061582 0.998102 +0.996774 0.080254 0.000000 +0.996774 0.080254 0.000000 +0.996774 0.080254 0.000000 +0.000000 0.061582 -0.998102 +0.000000 0.061582 -0.998102 +0.000000 0.061582 -0.998102 +-0.996312 0.085802 0.000000 +-0.996312 0.085802 0.000000 +-0.996312 0.085802 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998106 0.061525 0.000000 +0.998106 0.061525 0.000000 +0.998106 0.061525 0.000000 +0.000000 0.080183 -0.996780 +0.000000 0.080183 -0.996780 +0.000000 0.080183 -0.996780 +-0.998106 0.061525 0.000000 +-0.998106 0.061525 0.000000 +-0.998106 0.061525 0.000000 +0.000000 0.085726 0.996319 +0.000000 0.085726 0.996319 +0.000000 0.085726 0.996319 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.080233 -0.996776 +0.000000 0.080233 -0.996776 +0.000000 0.080233 -0.996776 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.080315 -0.996769 +0.000000 0.080315 -0.996770 +0.000000 0.080315 -0.996770 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998102 0.061580 0.000000 +0.998102 0.061580 0.000000 +0.998102 0.061580 0.000000 +0.000000 0.080255 -0.996774 +0.000000 0.080255 -0.996774 +0.000000 0.080255 -0.996774 +-0.998102 0.061579 0.000000 +-0.998102 0.061579 0.000000 +-0.998102 0.061579 0.000000 +0.000000 0.085802 0.996312 +0.000000 0.085802 0.996312 +0.000000 0.085802 0.996312 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.085779 0.996314 +0.000000 0.085779 0.996314 +0.000000 0.085779 0.996314 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998103 0.061563 0.000000 +0.998103 0.061563 0.000000 +0.998103 0.061563 0.000000 +-0.998103 0.061563 0.000000 +-0.998103 0.061563 0.000000 +-0.998103 0.061563 0.000000 +0.000000 0.085779 0.996314 +0.000000 0.085779 0.996314 +0.000000 0.085779 0.996314 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998099 0.061626 0.000000 +0.998099 0.061626 0.000000 +0.998099 0.061626 0.000000 +-0.998099 0.061626 0.000000 +-0.998099 0.061626 0.000000 +-0.998099 0.061626 0.000000 +0.000000 0.085866 0.996307 +0.000000 0.085866 0.996307 +0.000000 0.085866 0.996307 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998106 0.061525 0.000000 +0.998106 0.061525 0.000000 +0.998106 0.061525 0.000000 +0.000000 0.080183 -0.996780 +0.000000 0.080183 -0.996780 +0.000000 0.080183 -0.996780 +-0.998106 0.061525 0.000000 +-0.998106 0.061525 0.000000 +-0.998106 0.061525 0.000000 +0.000000 0.085726 0.996319 +0.000000 0.085726 0.996319 +0.000000 0.085726 0.996319 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998103 0.061563 0.000000 +0.998103 0.061563 0.000000 +0.998103 0.061563 0.000000 +0.000000 0.080233 -0.996776 +0.000000 0.080233 -0.996776 +0.000000 0.080233 -0.996776 +-0.998103 0.061563 0.000000 +-0.998103 0.061563 0.000000 +-0.998103 0.061563 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998102 0.061580 0.000000 +0.998102 0.061580 0.000000 +0.998102 0.061580 0.000000 +0.000000 0.080255 -0.996774 +0.000000 0.080255 -0.996774 +0.000000 0.080255 -0.996774 +-0.998102 0.061579 0.000000 +-0.998102 0.061579 0.000000 +-0.998102 0.061579 0.000000 +0.000000 0.085802 0.996312 +0.000000 0.085802 0.996312 +0.000000 0.085802 0.996312 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998106 0.061525 0.000000 +0.998106 0.061525 0.000000 +0.998106 0.061525 0.000000 +0.000000 0.080183 -0.996780 +0.000000 0.080183 -0.996780 +0.000000 0.080183 -0.996780 +-0.998106 0.061525 0.000000 +-0.998106 0.061525 0.000000 +-0.998106 0.061525 0.000000 +0.000000 0.085726 0.996319 +0.000000 0.085726 0.996319 +0.000000 0.085726 0.996319 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998103 0.061563 0.000000 +0.998103 0.061563 0.000000 +0.998103 0.061563 0.000000 +0.000000 0.080233 -0.996776 +0.000000 0.080233 -0.996776 +0.000000 0.080233 -0.996776 +-0.998103 0.061563 0.000000 +-0.998103 0.061563 0.000000 +-0.998103 0.061563 0.000000 +0.000000 0.085779 0.996314 +0.000000 0.085779 0.996314 +0.000000 0.085779 0.996314 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998099 0.061626 0.000000 +0.998099 0.061626 0.000000 +0.998099 0.061626 0.000000 +0.000000 0.080314 -0.996770 +0.000000 0.080314 -0.996770 +0.000000 0.080314 -0.996770 +-0.998099 0.061626 0.000000 +-0.998099 0.061626 0.000000 +-0.998099 0.061626 0.000000 +0.000000 0.085866 0.996307 +0.000000 0.085866 0.996307 +0.000000 0.085866 0.996307 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998102 0.061580 0.000000 +0.998102 0.061580 0.000000 +0.998102 0.061580 0.000000 +0.000000 0.080254 -0.996774 +0.000000 0.080254 -0.996774 +0.000000 0.080254 -0.996774 +-0.998102 0.061579 0.000000 +-0.998102 0.061579 0.000000 +-0.998102 0.061579 0.000000 +0.000000 0.085802 0.996312 +0.000000 0.085802 0.996312 +0.000000 0.085802 0.996312 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998105 0.061525 0.000000 +0.998106 0.061525 0.000000 +0.998105 0.061525 0.000000 +0.000000 0.080183 -0.996780 +0.000000 0.080183 -0.996780 +0.000000 0.080183 -0.996780 +-0.998105 0.061525 0.000000 +-0.998106 0.061525 0.000000 +-0.998105 0.061525 0.000000 +0.000000 0.085726 0.996319 +0.000000 0.085726 0.996319 +0.000000 0.085726 0.996319 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998103 0.061563 0.000000 +0.998103 0.061563 0.000000 +0.998103 0.061563 0.000000 +0.000000 0.080233 -0.996776 +0.000000 0.080233 -0.996776 +0.000000 0.080233 -0.996776 +-0.998103 0.061563 0.000000 +-0.998103 0.061563 0.000000 +-0.998103 0.061563 0.000000 +0.000000 0.085779 0.996314 +0.000000 0.085779 0.996314 +0.000000 0.085779 0.996314 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998099 0.061626 0.000000 +0.998099 0.061626 0.000000 +0.998099 0.061626 0.000000 +0.000000 0.080314 -0.996770 +0.000000 0.080314 -0.996770 +0.000000 0.080314 -0.996770 +-0.998099 0.061626 0.000000 +-0.998099 0.061626 0.000000 +-0.998099 0.061626 0.000000 +0.000000 0.085866 0.996307 +0.000000 0.085866 0.996307 +0.000000 0.085866 0.996307 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998102 0.061580 0.000000 +0.998102 0.061580 0.000000 +0.998102 0.061580 0.000000 +0.000000 0.080255 -0.996774 +0.000000 0.080255 -0.996774 +0.000000 0.080255 -0.996774 +-0.998102 0.061580 0.000000 +-0.998102 0.061580 0.000000 +-0.998102 0.061580 0.000000 +0.000000 0.085802 0.996312 +0.000000 0.085802 0.996312 +0.000000 0.085802 0.996312 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -0.000001 -1.000000 +0.000000 -0.000001 -1.000000 +0.000000 -0.000001 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -0.086947 -0.996213 +0.000000 -0.086947 -0.996213 +0.000000 -0.086947 -0.996213 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.000000 -0.086947 0.996213 +0.000000 -0.086947 0.996213 +0.000000 -0.086947 0.996213 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.061525 0.998106 +0.000000 0.061525 0.998105 +0.000000 0.061525 0.998106 +0.996780 0.080183 0.000000 +0.996780 0.080183 0.000000 +0.996780 0.080183 0.000000 +0.000000 0.061525 -0.998106 +0.000000 0.061525 -0.998105 +0.000000 0.061525 -0.998106 +-0.996319 0.085726 0.000000 +-0.996319 0.085726 0.000000 +-0.996319 0.085726 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -0.086947 -0.996213 +0.000000 -0.086947 -0.996213 +0.000000 -0.086947 -0.996213 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.000000 -0.086947 0.996213 +0.000000 -0.086947 0.996213 +0.000000 -0.086947 0.996213 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.061562 0.998103 +0.000000 0.061562 0.998103 +0.000000 0.061562 0.998103 +0.996776 0.080232 0.000000 +0.996776 0.080232 0.000000 +0.996776 0.080232 0.000000 +0.000000 0.061563 -0.998103 +0.000000 0.061563 -0.998103 +0.000000 0.061563 -0.998103 +-0.996314 0.085779 0.000000 +-0.996314 0.085779 0.000000 +-0.996314 0.085779 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -0.086947 -0.996213 +0.000000 -0.086947 -0.996213 +0.000000 -0.086947 -0.996213 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +-0.000001 -0.086947 0.996213 +-0.000001 -0.086947 0.996213 +-0.000001 -0.086947 0.996213 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.061626 0.998099 +0.000000 0.061626 0.998099 +0.000000 0.061626 0.998099 +0.996770 0.080314 0.000000 +0.996770 0.080314 0.000000 +0.996770 0.080314 0.000000 +0.000000 0.061626 -0.998099 +0.000000 0.061626 -0.998099 +0.000000 0.061626 -0.998099 +-0.996307 0.085866 0.000000 +-0.996307 0.085866 0.000000 +-0.996307 0.085866 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -0.086947 -0.996213 +0.000000 -0.086947 -0.996213 +0.000000 -0.086947 -0.996213 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.000000 -0.086947 0.996213 +0.000000 -0.086947 0.996213 +0.000000 -0.086947 0.996213 +-0.993768 -0.111467 0.000000 +-0.993768 -0.111467 0.000000 +-0.993768 -0.111467 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.061578 0.998102 +0.000000 0.061578 0.998102 +0.000000 0.061578 0.998102 +0.996774 0.080254 0.000000 +0.996774 0.080254 0.000000 +0.996775 0.080254 0.000000 +0.000000 0.061580 -0.998102 +0.000000 0.061580 -0.998102 +0.000000 0.061580 -0.998102 +-0.996312 0.085802 0.000000 +-0.996312 0.085802 0.000000 +-0.996312 0.085802 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -0.086947 -0.996213 +0.000000 -0.086947 -0.996213 +0.000000 -0.086947 -0.996213 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.000000 -0.086947 0.996213 +0.000000 -0.086947 0.996213 +0.000000 -0.086947 0.996213 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.061565 0.998103 +0.000000 0.061565 0.998103 +0.000000 0.061565 0.998103 +0.996776 0.080232 0.000000 +0.996776 0.080232 0.000000 +0.996776 0.080232 0.000000 +0.000000 0.061561 -0.998103 +0.000000 0.061561 -0.998103 +0.000000 0.061561 -0.998103 +-0.996314 0.085778 0.000000 +-0.996314 0.085778 0.000000 +-0.996314 0.085778 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -0.086947 -0.996213 +0.000000 -0.086947 -0.996213 +0.000000 -0.086947 -0.996213 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.000000 -0.086950 0.996213 +0.000000 -0.086950 0.996213 +0.000000 -0.086950 0.996213 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.061626 0.998099 +0.000000 0.061626 0.998099 +0.000000 0.061626 0.998099 +0.996770 0.080314 0.000000 +0.996770 0.080314 0.000000 +0.996770 0.080314 0.000000 +0.000000 0.061625 -0.998099 +0.000000 0.061625 -0.998099 +0.000000 0.061625 -0.998099 +-0.996307 0.085866 0.000000 +-0.996307 0.085866 0.000000 +-0.996307 0.085866 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -0.086950 -0.996213 +0.000000 -0.086950 -0.996213 +0.000000 -0.086950 -0.996213 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.000000 -0.086947 0.996213 +0.000000 -0.086947 0.996213 +0.000000 -0.086947 0.996213 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.061578 0.998102 +0.000000 0.061578 0.998102 +0.000000 0.061578 0.998102 +0.996774 0.080254 0.000000 +0.996774 0.080254 0.000000 +0.996775 0.080254 0.000000 +0.000000 0.061580 -0.998102 +0.000000 0.061580 -0.998102 +0.000000 0.061580 -0.998102 +-0.996312 0.085802 0.000000 +-0.996312 0.085802 0.000000 +-0.996312 0.085802 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998106 0.061525 0.000000 +0.998106 0.061525 0.000000 +0.998106 0.061525 0.000000 +0.000000 0.080183 -0.996780 +0.000000 0.080183 -0.996780 +0.000000 0.080183 -0.996780 +-0.998106 0.061525 0.000000 +-0.998106 0.061525 0.000000 +-0.998106 0.061525 0.000000 +0.000000 0.085726 0.996319 +0.000000 0.085726 0.996319 +0.000000 0.085726 0.996319 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998103 0.061563 0.000000 +0.998103 0.061563 0.000000 +0.998103 0.061563 0.000000 +0.000000 0.080231 -0.996776 +0.000000 0.080231 -0.996776 +0.000000 0.080231 -0.996776 +-0.998103 0.061563 0.000000 +-0.998103 0.061563 0.000000 +-0.998103 0.061563 0.000000 +0.000000 0.085779 0.996314 +0.000000 0.085779 0.996314 +0.000000 0.085779 0.996314 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998099 0.061626 0.000000 +0.998099 0.061626 0.000000 +0.998099 0.061626 0.000000 +0.000000 0.080313 -0.996770 +0.000000 0.080313 -0.996770 +0.000000 0.080313 -0.996770 +-0.998099 0.061626 0.000000 +-0.998099 0.061626 0.000000 +-0.998099 0.061626 0.000000 +0.000000 0.085866 0.996307 +0.000000 0.085866 0.996307 +0.000000 0.085866 0.996307 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998102 0.061580 0.000000 +0.998102 0.061580 0.000000 +0.998102 0.061580 0.000000 +0.000000 0.080254 -0.996774 +0.000000 0.080254 -0.996774 +0.000000 0.080254 -0.996774 +-0.998102 0.061579 0.000000 +-0.998102 0.061579 0.000000 +-0.998102 0.061579 0.000000 +0.000000 0.085802 0.996312 +0.000000 0.085802 0.996312 +0.000000 0.085802 0.996312 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 + + + + + + + + + + + +0.359897 0.758714 +0.625139 0.758714 +0.625139 0.764329 +0.359897 0.764329 +0.625139 0.758240 +0.625139 0.763855 +0.359897 0.763855 +0.359897 0.758240 +0.902056 0.885447 +0.636815 0.885447 +0.636815 0.878968 +0.902056 0.878968 +0.536490 0.826242 +0.536490 0.831857 +0.530011 0.831857 +0.530011 0.826242 +0.902056 0.864356 +0.636815 0.864356 +0.636815 0.857877 +0.902056 0.857877 +0.631329 0.718832 +0.896570 0.718832 +0.896570 0.724447 +0.631329 0.724447 +0.622396 0.718832 +0.622396 0.724447 +0.357154 0.724447 +0.357154 0.718832 +0.902056 0.737814 +0.636815 0.737814 +0.636815 0.731335 +0.902056 0.731335 +0.230680 0.731335 +0.230680 0.736950 +0.224201 0.736950 +0.224201 0.731335 +0.902056 0.727269 +0.636815 0.727269 +0.636815 0.720790 +0.902056 0.720790 +0.229084 0.723487 +0.126341 0.724820 +0.129481 0.720165 +0.634912 0.803989 +0.610953 0.707254 +0.614854 0.703215 +0.216620 0.931142 +0.132187 0.931142 +0.132187 0.924664 +0.216620 0.924664 +0.216620 0.888962 +0.132187 0.888962 +0.132187 0.882483 +0.216620 0.882483 +0.231827 0.739749 +0.130647 0.738764 +0.133787 0.734109 +0.570346 0.707254 +0.596246 0.801979 +0.592346 0.806018 +0.216620 0.825691 +0.132187 0.825691 +0.132187 0.819212 +0.216620 0.819212 +0.807150 0.938173 +0.722717 0.938173 +0.722717 0.931694 +0.807150 0.931694 +0.517625 0.703215 +0.540005 0.801585 +0.513725 0.707254 +0.350964 0.724528 +0.347824 0.729183 +0.250090 0.723089 +0.216620 0.853811 +0.132187 0.853811 +0.132187 0.847332 +0.216620 0.847332 +0.216620 0.920597 +0.132187 0.920597 +0.132187 0.914118 +0.216620 0.914118 +0.519687 0.781430 +0.435254 0.781430 +0.435254 0.775815 +0.519687 0.775815 +0.614593 0.775815 +0.614593 0.781430 +0.530161 0.781430 +0.530161 0.775815 +0.216620 0.748359 +0.132187 0.748359 +0.132187 0.741880 +0.216620 0.741880 +0.216620 0.787025 +0.132187 0.787025 +0.132187 0.780546 +0.216620 0.780546 +0.359897 0.723089 +0.625139 0.723089 +0.625139 0.728704 +0.359897 0.728704 +0.899313 0.723089 +0.899313 0.728704 +0.634072 0.728704 +0.634072 0.723089 +0.902056 0.801085 +0.636815 0.801085 +0.636815 0.794606 +0.902056 0.794606 +0.230680 0.843817 +0.230680 0.849432 +0.224201 0.849432 +0.224201 0.843817 +0.902056 0.811630 +0.636815 0.811630 +0.636815 0.805152 +0.902056 0.805152 +0.634072 0.758240 +0.899313 0.758240 +0.899313 0.763855 +0.634072 0.763855 +0.625139 0.740664 +0.625139 0.746279 +0.359897 0.746279 +0.359897 0.740664 +0.902056 0.832721 +0.636815 0.832721 +0.636815 0.826242 +0.902056 0.826242 +0.511885 0.808667 +0.511885 0.814282 +0.505406 0.814282 +0.505406 0.808667 +0.902056 0.843266 +0.636815 0.843266 +0.636815 0.836787 +0.902056 0.836787 +0.345081 0.723487 +0.242338 0.724820 +0.245478 0.720164 +0.348221 0.718832 +0.607438 0.721314 +0.611338 0.717275 +0.631397 0.818050 +0.627496 0.822089 +0.902056 0.948718 +0.817624 0.948718 +0.817624 0.942239 +0.902056 0.942239 +0.504855 0.706179 +0.420422 0.706179 +0.420422 0.699700 +0.504855 0.699700 +0.347824 0.859261 +0.246644 0.858276 +0.249784 0.853621 +0.350964 0.854606 +0.563315 0.707254 +0.567216 0.703215 +0.589216 0.801979 +0.585315 0.806018 +0.216620 0.765935 +0.132187 0.765935 +0.132187 0.759456 +0.216620 0.759456 +0.216620 0.836236 +0.132187 0.836236 +0.132187 0.829757 +0.216620 0.829757 +0.524655 0.703215 +0.547035 0.801585 +0.543135 0.805624 +0.520755 0.707254 +0.238482 0.706952 +0.235342 0.711607 +0.134469 0.710169 +0.137608 0.705514 +0.216620 0.941688 +0.132187 0.941688 +0.132187 0.935209 +0.216620 0.935209 +0.216620 0.910052 +0.132187 0.910052 +0.132187 0.903573 +0.216620 0.903573 +0.238482 0.728704 +0.154049 0.728704 +0.154049 0.723089 +0.238482 0.723089 +0.216620 0.864908 +0.216620 0.870522 +0.132187 0.870522 +0.132187 0.864908 +0.518915 0.737814 +0.434482 0.737814 +0.434482 0.731335 +0.518915 0.731335 +0.529460 0.790540 +0.445027 0.790540 +0.445027 0.784061 +0.529460 0.784061 +0.634072 0.740664 +0.899313 0.740664 +0.899313 0.746279 +0.634072 0.746279 +0.625139 0.705514 +0.625139 0.711129 +0.359897 0.711129 +0.359897 0.705514 +0.902056 0.853811 +0.636815 0.853811 +0.636815 0.847332 +0.902056 0.847332 +0.230680 0.752426 +0.230680 0.758041 +0.224201 0.758041 +0.224201 0.752426 +0.902056 0.822176 +0.636815 0.822176 +0.636815 0.815697 +0.902056 0.815697 +0.634072 0.705514 +0.899313 0.705514 +0.899313 0.711129 +0.634072 0.711129 +0.625139 0.687938 +0.625139 0.693553 +0.359897 0.693553 +0.359897 0.687938 +0.902056 0.790540 +0.636815 0.790540 +0.636815 0.784061 +0.902056 0.784061 +0.230680 0.907088 +0.230680 0.912703 +0.224201 0.912703 +0.224201 0.907088 +0.902056 0.779995 +0.636815 0.779995 +0.636815 0.773516 +0.902056 0.773516 +0.347824 0.738764 +0.245081 0.740096 +0.248221 0.735441 +0.350964 0.734109 +0.600408 0.717799 +0.604308 0.713760 +0.624367 0.814534 +0.620466 0.818574 +0.902056 0.895992 +0.817624 0.895992 +0.817624 0.889513 +0.902056 0.889513 +0.902056 0.906537 +0.817624 0.906537 +0.817624 0.900058 +0.902056 0.900058 +0.347824 0.764354 +0.246644 0.763369 +0.249784 0.758714 +0.350964 0.759699 +0.603276 0.801979 +0.599376 0.806018 +0.577376 0.707254 +0.581276 0.703215 +0.420493 0.727269 +0.336061 0.727269 +0.336061 0.720790 +0.420493 0.720790 +0.216620 0.776480 +0.132187 0.776480 +0.132187 0.770001 +0.216620 0.770001 +0.564225 0.805624 +0.541845 0.707254 +0.545746 0.703215 +0.568126 0.801585 +0.350964 0.706952 +0.347824 0.711607 +0.246950 0.710169 +0.250090 0.705514 +0.431038 0.787025 +0.346606 0.787025 +0.346606 0.780546 +0.431038 0.780546 +0.216620 0.899507 +0.132187 0.899507 +0.132187 0.893028 +0.216620 0.893028 +0.350964 0.763855 +0.266531 0.763855 +0.266531 0.758240 +0.350964 0.758240 +0.804407 0.775815 +0.804407 0.781430 +0.719974 0.781430 +0.719974 0.775815 +0.216620 0.737814 +0.132187 0.737814 +0.132187 0.731335 +0.216620 0.731335 +0.353707 0.695633 +0.269274 0.695633 +0.269274 0.689155 +0.353707 0.689155 +0.634072 0.687938 +0.899313 0.687938 +0.899313 0.693553 +0.634072 0.693553 +0.625139 0.853621 +0.625139 0.859236 +0.359897 0.859236 +0.359897 0.853621 +0.902056 0.769450 +0.636815 0.769450 +0.636815 0.762971 +0.902056 0.762971 +0.230680 0.921149 +0.230680 0.926764 +0.224201 0.926764 +0.224201 0.921149 +0.902056 0.758905 +0.636815 0.758905 +0.636815 0.752426 +0.902056 0.752426 +0.634072 0.853621 +0.899313 0.853621 +0.899313 0.859236 +0.634072 0.859236 +0.899313 0.758714 +0.899313 0.764329 +0.634072 0.764329 +0.634072 0.758714 +0.902056 0.748359 +0.636815 0.748359 +0.636815 0.741880 +0.902056 0.741880 +0.592731 0.826242 +0.592731 0.831857 +0.586252 0.831857 +0.586252 0.826242 +0.902056 0.874901 +0.636815 0.874901 +0.636815 0.868423 +0.902056 0.868423 +0.347824 0.714158 +0.245081 0.715491 +0.248221 0.710836 +0.350964 0.709503 +0.593378 0.714284 +0.597278 0.710245 +0.617336 0.811019 +0.613436 0.815059 +0.807150 0.895992 +0.722717 0.895992 +0.722717 0.889513 +0.807150 0.889513 +0.902056 0.938173 +0.817624 0.938173 +0.817624 0.931694 +0.902056 0.931694 +0.235342 0.859261 +0.134163 0.858276 +0.137302 0.853621 +0.238482 0.854606 +0.556285 0.707254 +0.560186 0.703215 +0.582186 0.801979 +0.578285 0.806018 +0.807150 0.906537 +0.722717 0.906537 +0.722717 0.900058 +0.807150 0.900058 +0.424008 0.737814 +0.339576 0.737814 +0.339576 0.731335 +0.424008 0.731335 +0.557195 0.805624 +0.534815 0.707254 +0.538715 0.703215 +0.561096 0.801585 +0.238482 0.689377 +0.235342 0.694032 +0.134469 0.692593 +0.137608 0.687938 +0.427523 0.765935 +0.343091 0.765935 +0.343091 0.759456 +0.427523 0.759456 +0.431038 0.776480 +0.346606 0.776480 +0.346606 0.770001 +0.431038 0.770001 +0.234967 0.781430 +0.150534 0.781430 +0.150534 0.775815 +0.234967 0.775815 +0.216620 0.857877 +0.216620 0.863492 +0.132187 0.863492 +0.132187 0.857877 +0.902056 0.927627 +0.817624 0.927627 +0.817624 0.921149 +0.902056 0.921149 +0.902056 0.917082 +0.817624 0.917082 +0.817624 0.910603 +0.902056 0.910603 +0.359897 0.734109 +0.625139 0.734109 +0.625139 0.739724 +0.359897 0.739724 +0.625139 0.709503 +0.625139 0.715118 +0.359897 0.715118 +0.359897 0.709503 +0.902056 0.716724 +0.636815 0.716724 +0.636815 0.710245 +0.902056 0.710245 +0.230680 0.703215 +0.230680 0.708830 +0.224201 0.708830 +0.224201 0.703215 +0.627882 0.695633 +0.362640 0.695633 +0.362640 0.689155 +0.627882 0.689155 +0.634072 0.734109 +0.899313 0.734109 +0.899313 0.739724 +0.634072 0.739724 +0.899313 0.709503 +0.899313 0.715118 +0.634072 0.715118 +0.634072 0.709503 +0.902056 0.706179 +0.636815 0.706179 +0.636815 0.699700 +0.902056 0.699700 +0.230680 0.745395 +0.230680 0.751011 +0.224201 0.751011 +0.224201 0.745395 +0.902056 0.695633 +0.636815 0.695633 +0.636815 0.689155 +0.902056 0.689155 +0.231827 0.714158 +0.129084 0.715491 +0.132224 0.710836 +0.234967 0.709503 +0.586348 0.710769 +0.590248 0.706730 +0.610306 0.807504 +0.606406 0.811544 +0.216620 0.815145 +0.132187 0.815145 +0.132187 0.808667 +0.216620 0.808667 +0.216620 0.804600 +0.132187 0.804600 +0.132187 0.798121 +0.216620 0.798121 +0.235342 0.764354 +0.134163 0.763369 +0.137302 0.758714 +0.238482 0.759699 +0.549255 0.707254 +0.553156 0.703215 +0.575156 0.801979 +0.571255 0.806018 +0.525945 0.769450 +0.441512 0.769450 +0.441512 0.762971 +0.525945 0.762971 +0.525945 0.779995 +0.441512 0.779995 +0.441512 0.773516 +0.525945 0.773516 +0.550165 0.805624 +0.527785 0.707254 +0.531685 0.703215 +0.554065 0.801585 +0.350964 0.689377 +0.347824 0.694032 +0.246950 0.692593 +0.250090 0.687938 +0.216620 0.878417 +0.132187 0.878417 +0.132187 0.871938 +0.216620 0.871938 +0.434553 0.797570 +0.350121 0.797570 +0.350121 0.791091 +0.434553 0.791091 +0.613821 0.824827 +0.529389 0.824827 +0.529389 0.819212 +0.613821 0.819212 +0.216620 0.752426 +0.216620 0.758041 +0.132187 0.758041 +0.132187 0.752426 +0.515400 0.727269 +0.430967 0.727269 +0.430967 0.720790 +0.515400 0.720790 +0.511885 0.716724 +0.427452 0.716724 +0.427452 0.710245 +0.511885 0.710245 +0.148913 0.282482 +0.045497 0.282481 +0.045497 0.272344 +0.148913 0.272344 +0.148913 0.259624 +0.148913 0.269762 +0.045497 0.269762 +0.045497 0.259624 +0.964980 0.177286 +0.964980 0.187424 +0.027754 0.187424 +0.027754 0.177286 +0.967071 0.173044 +0.967071 0.276459 +0.029845 0.276459 +0.029845 0.173044 +0.964980 0.198485 +0.964980 0.208623 +0.027754 0.208623 +0.027754 0.198485 +0.028022 0.134227 +0.028022 0.030812 +0.965247 0.030812 +0.965247 0.134227 +0.161816 0.257043 +0.058401 0.257043 +0.058401 0.246905 +0.161816 0.246905 +0.161816 0.234186 +0.161816 0.244323 +0.058401 0.244323 +0.058401 0.234186 +0.968082 0.155196 +0.968082 0.165334 +0.030856 0.165334 +0.030856 0.155196 +0.967071 0.166099 +0.967071 0.269514 +0.029845 0.269514 +0.029845 0.166099 +0.968082 0.218793 +0.968082 0.228931 +0.030856 0.228931 +0.030856 0.218793 +0.962770 0.030978 +0.962770 0.134393 +0.025544 0.134393 +0.025544 0.030978 +0.216620 0.796706 +0.132187 0.796706 +0.132187 0.791091 +0.216620 0.791091 +0.899313 0.775815 +0.899313 0.781430 +0.814881 0.781430 +0.814881 0.775815 +0.522430 0.758905 +0.437997 0.758905 +0.437997 0.752426 +0.522430 0.752426 +0.518915 0.748359 +0.434482 0.748359 +0.434482 0.741880 +0.518915 0.741880 +0.424008 0.747496 +0.339576 0.747496 +0.339576 0.741880 +0.424008 0.741880 +0.350964 0.740664 +0.350964 0.746279 +0.266531 0.746279 +0.266531 0.740664 +0.599761 0.815145 +0.515329 0.815145 +0.515329 0.808667 +0.599761 0.808667 +0.529460 0.801085 +0.445027 0.801085 +0.445027 0.794606 +0.529460 0.794606 +0.424780 0.781430 +0.340348 0.781430 +0.340348 0.775815 +0.424780 0.775815 +0.256057 0.740664 +0.256057 0.746279 +0.171625 0.746279 +0.171625 0.740664 +0.807150 0.927627 +0.722717 0.927627 +0.722717 0.921149 +0.807150 0.921149 +0.807150 0.917082 +0.722717 0.917082 +0.722717 0.910603 +0.807150 0.910603 +0.709500 0.781430 +0.625067 0.781430 +0.625067 0.775815 +0.709500 0.775815 +0.329873 0.775815 +0.329873 0.781430 +0.245441 0.781430 +0.245441 0.775815 +0.416978 0.716724 +0.332545 0.716724 +0.332545 0.710245 +0.416978 0.710245 +0.409948 0.706179 +0.325515 0.706179 +0.325515 0.699700 +0.409948 0.699700 +0.256057 0.763855 +0.171625 0.763855 +0.171625 0.758240 +0.256057 0.758240 +0.216620 0.840302 +0.216620 0.845917 +0.132187 0.845917 +0.132187 0.840302 +0.807150 0.948718 +0.722717 0.948718 +0.722717 0.942239 +0.807150 0.942239 +0.424008 0.755389 +0.339576 0.755389 +0.339576 0.748911 +0.424008 0.748911 +0.634912 0.703215 +0.634912 0.710701 +0.619690 0.710701 +0.619690 0.703215 +0.634912 0.720790 +0.634912 0.736012 +0.627426 0.736012 +0.627426 0.720790 +0.899313 0.716533 +0.899313 0.731756 +0.122294 0.731755 +0.122294 0.716533 +0.899313 0.712544 +0.899313 0.720030 +0.122294 0.720029 +0.122294 0.712544 +0.899313 0.741139 +0.899313 0.756361 +0.122294 0.756361 +0.122294 0.741139 +0.899313 0.694968 +0.899313 0.702454 +0.122294 0.702454 +0.122294 0.694968 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.503250 0.182172 +0.260475 0.182172 +0.266882 0.176062 +0.496844 0.176062 +0.202726 0.996046 +0.670755 0.996046 +0.004123 0.996046 +0.472024 0.996046 +0.677249 0.192456 +0.251604 0.192456 +0.429384 0.192456 +0.854111 0.192456 +0.765823 0.004091 +0.765823 0.182429 +0.516603 0.182429 +0.516603 0.004091 +0.670755 0.468044 +0.004123 0.468044 +0.670755 0.356586 +0.004123 0.356586 +0.202726 0.468044 +0.472024 0.468044 +0.202726 0.356586 +0.472024 0.356586 +0.260475 0.004834 +0.266882 0.010943 +0.503250 0.004834 +0.496844 0.010943 +0.004105 0.192456 +0.251604 0.345840 +0.004105 0.345840 +0.677249 0.345840 +0.429384 0.345840 +0.854111 0.345840 +0.941696 0.996046 +0.941696 0.468044 +0.941696 0.356586 +0.503250 0.182172 +0.260475 0.182172 +0.266882 0.176063 +0.496844 0.176063 +0.202726 0.899077 +0.670755 0.899077 +0.004123 0.899077 +0.472024 0.899077 +0.251893 0.192456 +0.677115 0.192456 +0.854111 0.192456 +0.429617 0.192456 +0.765823 0.004091 +0.765823 0.182429 +0.516603 0.182429 +0.516603 0.004091 +0.670755 0.468044 +0.004123 0.468044 +0.670755 0.356586 +0.004123 0.356586 +0.202726 0.468044 +0.472024 0.468044 +0.202726 0.356586 +0.472024 0.356586 +0.004105 0.192456 +0.004105 0.345840 +0.677115 0.345840 +0.260475 0.004834 +0.266882 0.010943 +0.503250 0.004834 +0.496844 0.010943 +0.429617 0.345840 +0.251893 0.345840 +0.854111 0.345840 +0.941696 0.899077 +0.941696 0.468044 +0.941696 0.356586 +0.503250 0.182172 +0.260475 0.182172 +0.266878 0.176066 +0.496844 0.176066 +0.670755 0.754753 +0.202726 0.754753 +0.472024 0.754753 +0.941696 0.754753 +0.251803 0.192456 +0.676793 0.192456 +0.854111 0.192456 +0.429464 0.192456 +0.765823 0.004091 +0.765823 0.182429 +0.516603 0.182429 +0.516603 0.004091 +0.202726 0.468044 +0.472024 0.468044 +0.202726 0.356586 +0.472024 0.356586 +0.670755 0.468044 +0.941696 0.468044 +0.670755 0.356586 +0.941696 0.356586 +0.004123 0.754753 +0.004123 0.468044 +0.004123 0.356586 +0.260475 0.004834 +0.266878 0.010943 +0.503250 0.004834 +0.496844 0.010943 +0.676793 0.345840 +0.429464 0.345840 +0.251803 0.345840 +0.854111 0.345840 +0.004105 0.192456 +0.004105 0.345840 +0.503250 0.182172 +0.260475 0.182172 +0.266884 0.176061 +0.496844 0.176061 +0.670755 0.949681 +0.202726 0.949681 +0.472024 0.949681 +0.941696 0.949681 +0.251692 0.192456 +0.677407 0.192456 +0.854111 0.192456 +0.429511 0.192456 +0.765823 0.004091 +0.765823 0.182429 +0.516603 0.182429 +0.516603 0.004091 +0.202726 0.468044 +0.472024 0.468044 +0.202726 0.356586 +0.472024 0.356586 +0.670755 0.468044 +0.941696 0.468044 +0.670755 0.356586 +0.941696 0.356586 +0.260475 0.004834 +0.266884 0.010943 +0.503250 0.004834 +0.496844 0.010943 +0.677407 0.345840 +0.429511 0.345840 +0.004105 0.192456 +0.251692 0.345840 +0.004105 0.345840 +0.854111 0.345840 +0.004123 0.949681 +0.004123 0.468044 +0.004123 0.356586 +0.503250 0.182172 +0.260475 0.182172 +0.266882 0.176062 +0.496844 0.176062 +0.202726 0.996046 +0.670755 0.996046 +0.004123 0.996046 +0.472024 0.996046 +0.677249 0.192456 +0.251604 0.192456 +0.429384 0.192456 +0.854111 0.192456 +0.765823 0.004091 +0.765823 0.182429 +0.516603 0.182429 +0.516603 0.004091 +0.670755 0.468044 +0.004123 0.468044 +0.670755 0.356586 +0.004123 0.356586 +0.202726 0.468044 +0.472024 0.468044 +0.202726 0.356586 +0.472024 0.356586 +0.260475 0.004834 +0.266882 0.010943 +0.503250 0.004834 +0.496844 0.010943 +0.004105 0.192456 +0.251604 0.345840 +0.004105 0.345840 +0.677249 0.345840 +0.429384 0.345840 +0.854111 0.345840 +0.941696 0.996046 +0.941696 0.468044 +0.941696 0.356586 +0.503250 0.182172 +0.260475 0.182172 +0.266882 0.176063 +0.496844 0.176063 +0.202726 0.899077 +0.670755 0.899077 +0.004123 0.899077 +0.472024 0.899077 +0.251893 0.192456 +0.677115 0.192456 +0.854111 0.192456 +0.429617 0.192456 +0.765823 0.004091 +0.765823 0.182429 +0.516603 0.182429 +0.516603 0.004091 +0.670755 0.468044 +0.004123 0.468044 +0.670755 0.356586 +0.004123 0.356586 +0.202726 0.468044 +0.472024 0.468044 +0.202726 0.356586 +0.472024 0.356586 +0.004105 0.192456 +0.004105 0.345840 +0.677115 0.345840 +0.260475 0.004834 +0.266882 0.010943 +0.503250 0.004834 +0.496844 0.010943 +0.429617 0.345840 +0.251893 0.345840 +0.854111 0.345840 +0.941696 0.899077 +0.941696 0.468044 +0.941696 0.356586 +0.503250 0.182172 +0.260475 0.182172 +0.266878 0.176066 +0.496844 0.176066 +0.670755 0.754753 +0.202726 0.754753 +0.472024 0.754753 +0.941696 0.754753 +0.251803 0.192456 +0.676793 0.192456 +0.854111 0.192456 +0.429464 0.192456 +0.765823 0.004091 +0.765823 0.182429 +0.516603 0.182429 +0.516603 0.004091 +0.202726 0.468044 +0.472024 0.468044 +0.202726 0.356586 +0.472024 0.356586 +0.670755 0.468044 +0.941696 0.468044 +0.670755 0.356586 +0.941696 0.356586 +0.004123 0.754753 +0.004123 0.468044 +0.004123 0.356586 +0.260475 0.004834 +0.266878 0.010943 +0.503250 0.004834 +0.496844 0.010943 +0.676793 0.345840 +0.429464 0.345840 +0.251803 0.345840 +0.854111 0.345840 +0.004105 0.192456 +0.004105 0.345840 +0.503250 0.182172 +0.260475 0.182172 +0.266884 0.176061 +0.496844 0.176061 +0.670755 0.949681 +0.202726 0.949681 +0.472024 0.949681 +0.941696 0.949681 +0.251692 0.192456 +0.677407 0.192456 +0.854111 0.192456 +0.429511 0.192456 +0.765823 0.004091 +0.765823 0.182429 +0.516603 0.182429 +0.516603 0.004091 +0.202726 0.468044 +0.472024 0.468044 +0.202726 0.356586 +0.472024 0.356586 +0.670755 0.468044 +0.941696 0.468044 +0.670755 0.356586 +0.941696 0.356586 +0.260475 0.004834 +0.266884 0.010943 +0.503250 0.004834 +0.496844 0.010943 +0.677407 0.345840 +0.429511 0.345840 +0.004105 0.192456 +0.251692 0.345840 +0.004105 0.345840 +0.854111 0.345840 +0.004123 0.949681 +0.004123 0.468044 +0.004123 0.356586 +0.503250 0.182172 +0.260475 0.182172 +0.266882 0.176062 +0.496844 0.176062 +0.202726 0.996046 +0.670755 0.996046 +0.004123 0.996046 +0.472024 0.996046 +0.677249 0.192456 +0.251604 0.192456 +0.429384 0.192456 +0.854111 0.192456 +0.765823 0.004091 +0.765823 0.182429 +0.516603 0.182429 +0.516603 0.004091 +0.670755 0.468044 +0.004123 0.468044 +0.670755 0.356586 +0.004123 0.356586 +0.202726 0.468044 +0.472024 0.468044 +0.202726 0.356586 +0.472024 0.356586 +0.260475 0.004834 +0.266882 0.010943 +0.503250 0.004834 +0.496844 0.010943 +0.004105 0.192456 +0.251604 0.345840 +0.004105 0.345840 +0.677249 0.345840 +0.429384 0.345840 +0.854111 0.345840 +0.941696 0.996046 +0.941696 0.468044 +0.941696 0.356586 +0.503250 0.182172 +0.260475 0.182172 +0.266882 0.176063 +0.496844 0.176063 +0.202726 0.899077 +0.670755 0.899077 +0.004123 0.899077 +0.472024 0.899077 +0.251893 0.192456 +0.677115 0.192456 +0.854111 0.192456 +0.429617 0.192456 +0.765823 0.004091 +0.765823 0.182429 +0.516603 0.182429 +0.516603 0.004091 +0.670755 0.468044 +0.004123 0.468044 +0.670755 0.356586 +0.004123 0.356586 +0.202726 0.468044 +0.472024 0.468044 +0.202726 0.356586 +0.472024 0.356586 +0.004105 0.192456 +0.004105 0.345840 +0.677115 0.345840 +0.260475 0.004834 +0.266882 0.010943 +0.503250 0.004834 +0.496844 0.010943 +0.429617 0.345840 +0.251893 0.345840 +0.854111 0.345840 +0.941696 0.899077 +0.941696 0.468044 +0.941696 0.356586 +0.503250 0.182172 +0.260475 0.182172 +0.266878 0.176066 +0.496844 0.176066 +0.670755 0.754753 +0.202726 0.754753 +0.472024 0.754753 +0.941696 0.754753 +0.251803 0.192456 +0.676793 0.192456 +0.854111 0.192456 +0.429464 0.192456 +0.765823 0.004091 +0.765823 0.182429 +0.516603 0.182429 +0.516603 0.004091 +0.202726 0.468044 +0.472024 0.468044 +0.202726 0.356586 +0.472024 0.356586 +0.670755 0.468044 +0.941696 0.468044 +0.670755 0.356586 +0.941696 0.356586 +0.004123 0.754753 +0.004123 0.468044 +0.004123 0.356586 +0.260475 0.004834 +0.266878 0.010943 +0.503250 0.004834 +0.496844 0.010943 +0.676793 0.345840 +0.429464 0.345840 +0.251803 0.345840 +0.854111 0.345840 +0.004105 0.192456 +0.004105 0.345840 +0.503250 0.182172 +0.260475 0.182172 +0.266884 0.176061 +0.496844 0.176061 +0.670755 0.949681 +0.202726 0.949681 +0.472024 0.949681 +0.941696 0.949681 +0.251692 0.192456 +0.677407 0.192456 +0.854111 0.192456 +0.429511 0.192456 +0.765823 0.004091 +0.765823 0.182429 +0.516603 0.182429 +0.516603 0.004091 +0.202726 0.468044 +0.472024 0.468044 +0.202726 0.356586 +0.472024 0.356586 +0.670755 0.468044 +0.941696 0.468044 +0.670755 0.356586 +0.941696 0.356586 +0.260475 0.004834 +0.266884 0.010943 +0.503250 0.004834 +0.496844 0.010943 +0.677407 0.345840 +0.429511 0.345840 +0.004105 0.192456 +0.251692 0.345840 +0.004105 0.345840 +0.854111 0.345840 +0.004123 0.949681 +0.004123 0.468044 +0.004123 0.356586 +0.503250 0.182172 +0.260475 0.182172 +0.266882 0.176062 +0.496844 0.176062 +0.202726 0.996046 +0.670755 0.996046 +0.004123 0.996046 +0.472024 0.996046 +0.677249 0.192456 +0.251604 0.192456 +0.429384 0.192456 +0.854111 0.192456 +0.765823 0.004091 +0.765823 0.182429 +0.516603 0.182429 +0.516603 0.004091 +0.670755 0.468044 +0.004123 0.468044 +0.670755 0.356586 +0.004123 0.356586 +0.202726 0.468044 +0.472024 0.468044 +0.202726 0.356586 +0.472024 0.356586 +0.260475 0.004834 +0.266882 0.010943 +0.503250 0.004834 +0.496844 0.010943 +0.004105 0.192456 +0.251604 0.345840 +0.004105 0.345840 +0.677249 0.345840 +0.429384 0.345840 +0.854111 0.345840 +0.941696 0.996046 +0.941696 0.468044 +0.941696 0.356586 +0.503250 0.182172 +0.260475 0.182172 +0.266882 0.176063 +0.496844 0.176063 +0.202726 0.899077 +0.670755 0.899077 +0.004123 0.899077 +0.472024 0.899077 +0.251893 0.192456 +0.677115 0.192456 +0.854111 0.192456 +0.429617 0.192456 +0.765823 0.004091 +0.765823 0.182429 +0.516603 0.182429 +0.516603 0.004091 +0.670755 0.468044 +0.004123 0.468044 +0.670755 0.356586 +0.004123 0.356586 +0.202726 0.468044 +0.472024 0.468044 +0.202726 0.356586 +0.472024 0.356586 +0.004105 0.192456 +0.004105 0.345840 +0.677115 0.345840 +0.260475 0.004834 +0.266882 0.010943 +0.503250 0.004834 +0.496844 0.010943 +0.429617 0.345840 +0.251893 0.345840 +0.854111 0.345840 +0.941696 0.899077 +0.941696 0.468044 +0.941696 0.356586 +0.503250 0.182172 +0.260475 0.182172 +0.266878 0.176066 +0.496844 0.176066 +0.670755 0.754753 +0.202726 0.754753 +0.472024 0.754753 +0.941696 0.754753 +0.251803 0.192456 +0.676793 0.192456 +0.854111 0.192456 +0.429464 0.192456 +0.765823 0.004091 +0.765823 0.182429 +0.516603 0.182429 +0.516603 0.004091 +0.202726 0.468044 +0.472024 0.468044 +0.202726 0.356586 +0.472024 0.356586 +0.670755 0.468044 +0.941696 0.468044 +0.670755 0.356586 +0.941696 0.356586 +0.004123 0.754753 +0.004123 0.468044 +0.004123 0.356586 +0.260475 0.004834 +0.266878 0.010943 +0.503250 0.004834 +0.496844 0.010943 +0.676793 0.345840 +0.429464 0.345840 +0.251803 0.345840 +0.854111 0.345840 +0.004105 0.192456 +0.004105 0.345840 +0.503250 0.182172 +0.260475 0.182172 +0.266884 0.176061 +0.496844 0.176061 +0.670755 0.949681 +0.202726 0.949681 +0.472024 0.949681 +0.941696 0.949681 +0.251692 0.192456 +0.677407 0.192456 +0.854111 0.192456 +0.429511 0.192456 +0.765823 0.004091 +0.765823 0.182429 +0.516603 0.182429 +0.516603 0.004091 +0.202726 0.468044 +0.472024 0.468044 +0.202726 0.356586 +0.472024 0.356586 +0.670755 0.468044 +0.941696 0.468044 +0.670755 0.356586 +0.941696 0.356586 +0.260475 0.004834 +0.266884 0.010943 +0.503250 0.004834 +0.496844 0.010943 +0.677407 0.345840 +0.429511 0.345840 +0.004105 0.192456 +0.251692 0.345840 +0.004105 0.345840 +0.854111 0.345840 +0.004123 0.949681 +0.004123 0.468044 +0.004123 0.356586 +0.503250 0.182172 +0.260475 0.182172 +0.266882 0.176062 +0.496844 0.176062 +0.202726 0.996046 +0.670755 0.996046 +0.004123 0.996046 +0.472024 0.996046 +0.677249 0.192456 +0.251604 0.192456 +0.429384 0.192456 +0.854111 0.192456 +0.765823 0.004091 +0.765823 0.182429 +0.516603 0.182429 +0.516603 0.004091 +0.670755 0.468044 +0.004123 0.468044 +0.670755 0.356586 +0.004123 0.356586 +0.202726 0.468044 +0.472024 0.468044 +0.202726 0.356586 +0.472024 0.356586 +0.260475 0.004834 +0.266882 0.010943 +0.503250 0.004834 +0.496844 0.010943 +0.004105 0.192456 +0.251604 0.345840 +0.004105 0.345840 +0.677249 0.345840 +0.429384 0.345840 +0.854111 0.345840 +0.941696 0.996046 +0.941696 0.468044 +0.941696 0.356586 +0.503250 0.182172 +0.260475 0.182172 +0.266882 0.176063 +0.496844 0.176063 +0.202726 0.899077 +0.670755 0.899077 +0.004123 0.899077 +0.472024 0.899077 +0.251893 0.192456 +0.677115 0.192456 +0.854111 0.192456 +0.429617 0.192456 +0.765823 0.004091 +0.765823 0.182429 +0.516603 0.182429 +0.516603 0.004091 +0.670755 0.468044 +0.004123 0.468044 +0.670755 0.356586 +0.004123 0.356586 +0.202726 0.468044 +0.472024 0.468044 +0.202726 0.356586 +0.472024 0.356586 +0.004105 0.192456 +0.004105 0.345840 +0.677115 0.345840 +0.260475 0.004834 +0.266882 0.010943 +0.503250 0.004834 +0.496844 0.010943 +0.429617 0.345840 +0.251893 0.345840 +0.854111 0.345840 +0.941696 0.899077 +0.941696 0.468044 +0.941696 0.356586 +0.503250 0.182172 +0.260475 0.182172 +0.266884 0.176061 +0.496844 0.176061 +0.670755 0.949681 +0.202726 0.949681 +0.472024 0.949681 +0.941696 0.949681 +0.251692 0.192456 +0.677407 0.192456 +0.854111 0.192456 +0.429511 0.192456 +0.765823 0.004091 +0.765823 0.182429 +0.516603 0.182429 +0.516603 0.004091 +0.202726 0.468044 +0.472024 0.468044 +0.202726 0.356586 +0.472024 0.356586 +0.670755 0.468044 +0.941696 0.468044 +0.670755 0.356586 +0.941696 0.356586 +0.260475 0.004834 +0.266884 0.010943 +0.503250 0.004834 +0.496844 0.010943 +0.677407 0.345840 +0.429511 0.345840 +0.004105 0.192456 +0.251692 0.345840 +0.004105 0.345840 +0.854111 0.345840 +0.004123 0.949681 +0.004123 0.468044 +0.004123 0.356586 +0.503250 0.182172 +0.260475 0.182172 +0.266882 0.176062 +0.496844 0.176062 +0.202726 0.996046 +0.670755 0.996046 +0.004123 0.996046 +0.472024 0.996046 +0.677249 0.192456 +0.251604 0.192456 +0.429384 0.192456 +0.854111 0.192456 +0.765823 0.004091 +0.765823 0.182429 +0.516603 0.182429 +0.516603 0.004091 +0.670755 0.468044 +0.004123 0.468044 +0.670755 0.356586 +0.004123 0.356586 +0.202726 0.468044 +0.472024 0.468044 +0.202726 0.356586 +0.472024 0.356586 +0.260475 0.004834 +0.266882 0.010943 +0.503250 0.004834 +0.496844 0.010943 +0.004105 0.192456 +0.251604 0.345840 +0.004105 0.345840 +0.677249 0.345840 +0.429384 0.345840 +0.854111 0.345840 +0.941696 0.996046 +0.941696 0.468044 +0.941696 0.356586 +0.503250 0.182172 +0.260475 0.182172 +0.266882 0.176063 +0.496844 0.176063 +0.202726 0.899077 +0.670755 0.899077 +0.004123 0.899077 +0.472024 0.899077 +0.251893 0.192456 +0.677115 0.192456 +0.854111 0.192456 +0.429617 0.192456 +0.765823 0.004091 +0.765823 0.182429 +0.516603 0.182429 +0.516603 0.004091 +0.670755 0.468044 +0.004123 0.468044 +0.670755 0.356586 +0.004123 0.356586 +0.202726 0.468044 +0.472024 0.468044 +0.202726 0.356586 +0.472024 0.356586 +0.004105 0.192456 +0.004105 0.345840 +0.677115 0.345840 +0.260475 0.004834 +0.266882 0.010943 +0.503250 0.004834 +0.496844 0.010943 +0.429617 0.345840 +0.251893 0.345840 +0.854111 0.345840 +0.941696 0.899077 +0.941696 0.468044 +0.941696 0.356586 +0.503250 0.182172 +0.260475 0.182172 +0.266878 0.176066 +0.496844 0.176066 +0.670755 0.754753 +0.202726 0.754753 +0.472024 0.754753 +0.941696 0.754753 +0.251803 0.192456 +0.676793 0.192456 +0.854111 0.192456 +0.429464 0.192456 +0.765823 0.004091 +0.765823 0.182429 +0.516603 0.182429 +0.516603 0.004091 +0.202726 0.468044 +0.472024 0.468044 +0.202726 0.356586 +0.472024 0.356586 +0.670755 0.468044 +0.941696 0.468044 +0.670755 0.356586 +0.941696 0.356586 +0.004123 0.754753 +0.004123 0.468044 +0.004123 0.356586 +0.260475 0.004834 +0.266878 0.010943 +0.503250 0.004834 +0.496844 0.010943 +0.676793 0.345840 +0.429464 0.345840 +0.251803 0.345840 +0.854111 0.345840 +0.004105 0.192456 +0.004105 0.345840 +0.503250 0.182172 +0.260475 0.182172 +0.266884 0.176061 +0.496844 0.176061 +0.670755 0.949681 +0.202726 0.949681 +0.472024 0.949681 +0.941696 0.949681 +0.251692 0.192456 +0.677407 0.192456 +0.854111 0.192456 +0.429511 0.192456 +0.765823 0.004091 +0.765823 0.182429 +0.516603 0.182429 +0.516603 0.004091 +0.202726 0.468044 +0.472024 0.468044 +0.202726 0.356586 +0.472024 0.356586 +0.670755 0.468044 +0.941696 0.468044 +0.670755 0.356586 +0.941696 0.356586 +0.260475 0.004834 +0.266884 0.010943 +0.503250 0.004834 +0.496844 0.010943 +0.677407 0.345840 +0.429511 0.345840 +0.004105 0.192456 +0.251692 0.345840 +0.004105 0.345840 +0.854111 0.345840 +0.004123 0.949681 +0.004123 0.468044 +0.004123 0.356586 +0.503250 0.182172 +0.260475 0.182172 +0.266882 0.176063 +0.496844 0.176063 +0.202726 0.899077 +0.670755 0.899077 +0.004123 0.899077 +0.472024 0.899077 +0.251893 0.192456 +0.677115 0.192456 +0.854111 0.192456 +0.429617 0.192456 +0.765823 0.004091 +0.765823 0.182429 +0.516603 0.182429 +0.516603 0.004091 +0.670755 0.468044 +0.004123 0.468044 +0.670755 0.356586 +0.004123 0.356586 +0.202726 0.468044 +0.472024 0.468044 +0.202726 0.356586 +0.472024 0.356586 +0.004105 0.192456 +0.004105 0.345840 +0.677115 0.345840 +0.260475 0.004834 +0.266882 0.010943 +0.503250 0.004834 +0.496844 0.010943 +0.429617 0.345840 +0.251893 0.345840 +0.854111 0.345840 +0.941696 0.899077 +0.941696 0.468044 +0.941696 0.356586 +0.503250 0.182172 +0.260475 0.182172 +0.266878 0.176066 +0.496844 0.176066 +0.670755 0.754753 +0.202726 0.754753 +0.472024 0.754753 +0.941696 0.754753 +0.251803 0.192456 +0.676793 0.192456 +0.854111 0.192456 +0.429464 0.192456 +0.765823 0.004091 +0.765823 0.182429 +0.516603 0.182429 +0.516603 0.004091 +0.202726 0.468044 +0.472024 0.468044 +0.202726 0.356586 +0.472024 0.356586 +0.670755 0.468044 +0.941696 0.468044 +0.670755 0.356586 +0.941696 0.356586 +0.004123 0.754753 +0.004123 0.468044 +0.004123 0.356586 +0.260475 0.004834 +0.266878 0.010943 +0.503250 0.004834 +0.496844 0.010943 +0.676793 0.345840 +0.429464 0.345840 +0.251803 0.345840 +0.854111 0.345840 +0.004105 0.192456 +0.004105 0.345840 +0.503250 0.182172 +0.260475 0.182172 +0.266884 0.176061 +0.496844 0.176061 +0.670755 0.949681 +0.202726 0.949681 +0.472024 0.949681 +0.941696 0.949681 +0.251692 0.192456 +0.677407 0.192456 +0.854111 0.192456 +0.429511 0.192456 +0.765823 0.004091 +0.765823 0.182429 +0.516603 0.182429 +0.516603 0.004091 +0.202726 0.468044 +0.472024 0.468044 +0.202726 0.356586 +0.472024 0.356586 +0.670755 0.468044 +0.941696 0.468044 +0.670755 0.356586 +0.941696 0.356586 +0.260475 0.004834 +0.266884 0.010943 +0.503250 0.004834 +0.496844 0.010943 +0.677407 0.345840 +0.429511 0.345840 +0.004105 0.192456 +0.251692 0.345840 +0.004105 0.345840 +0.854111 0.345840 +0.004123 0.949681 +0.004123 0.468044 +0.004123 0.356586 +0.503250 0.182172 +0.260475 0.182172 +0.266882 0.176062 +0.496844 0.176062 +0.202726 0.996046 +0.670755 0.996046 +0.004123 0.996046 +0.472024 0.996046 +0.677249 0.192456 +0.251604 0.192456 +0.429384 0.192456 +0.854111 0.192456 +0.765823 0.004091 +0.765823 0.182429 +0.516603 0.182429 +0.516603 0.004091 +0.670755 0.468044 +0.004123 0.468044 +0.670755 0.356586 +0.004123 0.356586 +0.202726 0.468044 +0.472024 0.468044 +0.202726 0.356586 +0.472024 0.356586 +0.260475 0.004834 +0.266882 0.010943 +0.503250 0.004834 +0.496844 0.010943 +0.004105 0.192456 +0.251604 0.345840 +0.004105 0.345840 +0.677249 0.345840 +0.429384 0.345840 +0.854111 0.345840 +0.941696 0.996046 +0.941696 0.468044 +0.941696 0.356586 +0.503250 0.182172 +0.260475 0.182172 +0.266882 0.176063 +0.496844 0.176063 +0.202726 0.899077 +0.670755 0.899077 +0.004123 0.899077 +0.472024 0.899077 +0.251893 0.192456 +0.677115 0.192456 +0.854111 0.192456 +0.429617 0.192456 +0.765823 0.004091 +0.765823 0.182429 +0.516603 0.182429 +0.516603 0.004091 +0.670755 0.468044 +0.004123 0.468044 +0.670755 0.356586 +0.004123 0.356586 +0.202726 0.468044 +0.472024 0.468044 +0.202726 0.356586 +0.472024 0.356586 +0.004105 0.192456 +0.004105 0.345840 +0.677115 0.345840 +0.260475 0.004834 +0.266882 0.010943 +0.503250 0.004834 +0.496844 0.010943 +0.429617 0.345840 +0.251893 0.345840 +0.854111 0.345840 +0.941696 0.899077 +0.941696 0.468044 +0.941696 0.356586 +0.503250 0.182172 +0.260475 0.182172 +0.266878 0.176066 +0.496844 0.176066 +0.670755 0.754753 +0.202726 0.754753 +0.472024 0.754753 +0.941696 0.754753 +0.251803 0.192456 +0.676793 0.192456 +0.854111 0.192456 +0.429464 0.192456 +0.765823 0.004091 +0.765823 0.182429 +0.516603 0.182429 +0.516603 0.004091 +0.202726 0.468044 +0.472024 0.468044 +0.202726 0.356586 +0.472024 0.356586 +0.670755 0.468044 +0.941696 0.468044 +0.670755 0.356586 +0.941696 0.356586 +0.004123 0.754753 +0.004123 0.468044 +0.004123 0.356586 +0.260475 0.004834 +0.266878 0.010943 +0.503250 0.004834 +0.496844 0.010943 +0.676793 0.345840 +0.429464 0.345840 +0.251803 0.345840 +0.854111 0.345840 +0.004105 0.192456 +0.004105 0.345840 +0.503250 0.182172 +0.260475 0.182172 +0.266884 0.176061 +0.496844 0.176061 +0.670755 0.949681 +0.202726 0.949681 +0.472024 0.949681 +0.941696 0.949681 +0.251692 0.192456 +0.677407 0.192456 +0.854111 0.192456 +0.429511 0.192456 +0.765823 0.004091 +0.765823 0.182429 +0.516603 0.182429 +0.516603 0.004091 +0.202726 0.468044 +0.472024 0.468044 +0.202726 0.356586 +0.472024 0.356586 +0.670755 0.468044 +0.941696 0.468044 +0.670755 0.356586 +0.941696 0.356586 +0.260475 0.004834 +0.266884 0.010943 +0.503250 0.004834 +0.496844 0.010943 +0.677407 0.345840 +0.429511 0.345840 +0.004105 0.192456 +0.251692 0.345840 +0.004105 0.345840 +0.854111 0.345840 +0.004123 0.949681 +0.004123 0.468044 +0.004123 0.356586 +0.213991 0.931142 +0.213990 0.924664 +0.214038 0.825691 +0.214038 0.819212 +0.134759 0.853811 +0.134759 0.847332 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035379 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035379 +0.029544 0.035379 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035379 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035379 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035379 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 + + + + + + + + + + + +

0 0 0 3 1 2 1 2 3 3 3 2 0 4 0 2 5 1 6 6 7 4 7 4 7 8 6 7 9 6 4 10 4 5 11 5 7 12 10 5 13 11 1 14 8 7 15 10 1 16 8 3 17 9 7 18 15 3 19 12 6 20 14 6 21 14 3 22 12 2 23 13 4 24 18 6 25 19 2 26 16 4 27 18 2 28 16 0 29 17 8 30 20 10 31 22 11 32 23 10 33 22 8 34 20 9 35 21 15 36 27 12 37 24 14 38 26 14 39 26 12 40 24 13 41 25 14 42 30 13 43 31 11 44 28 14 45 30 11 46 28 10 47 29 14 48 35 10 49 32 15 50 34 15 51 34 10 52 32 9 53 33 12 54 38 15 55 39 9 56 36 12 57 38 9 58 36 8 59 37 18 60 42 16 61 40 17 62 41 18 63 47 21 64 49 19 65 46 18 66 47 19 67 46 16 68 4530 21 69 49 22 70 48 20 71 4531 22 72 48 21 73 49 18 74 47 23 75 45 20 76 43 22 77 44 20 78 52 23 79 53 17 80 50 20 81 52 17 82 50 16 83 51 26 84 56 24 85 54 25 86 55 26 87 61 29 88 63 27 89 60 26 90 61 27 91 60 24 92 4532 29 93 63 30 94 62 28 95 4533 30 96 62 29 97 63 26 98 61 31 99 59 28 100 57 30 101 58 28 102 66 31 103 67 25 104 64 28 105 66 25 106 64 24 107 65 33 108 4534 37 109 77 35 110 74 33 111 69 35 112 70 32 113 68 38 114 76 37 115 77 34 116 75 37 117 72 39 118 73 36 119 71 36 120 80 39 121 81 33 122 78 36 123 80 33 124 78 32 125 79 40 126 82 42 127 84 43 128 85 42 129 84 40 130 82 41 131 83 44 132 86 46 133 88 47 134 89 46 135 88 44 136 86 45 137 87 43 138 90 42 139 91 45 140 93 46 141 92 45 142 93 42 143 91 44 144 96 47 145 97 41 146 94 44 147 96 41 148 94 40 149 95 48 150 98 50 151 100 51 152 101 50 153 100 48 154 98 49 155 99 55 156 105 52 157 102 54 158 104 54 159 104 52 160 102 53 161 103 51 162 106 54 163 108 53 164 109 54 165 108 51 166 106 50 167 107 54 168 113 50 169 110 55 170 112 55 171 112 50 172 110 49 173 111 49 174 114 52 175 116 55 176 117 52 177 116 49 178 114 48 179 115 56 180 118 58 181 120 59 182 121 58 183 120 56 184 118 57 185 119 63 186 125 60 187 122 62 188 124 62 189 124 60 190 122 61 191 123 59 192 126 62 193 128 61 194 129 62 195 128 59 196 126 58 197 127 62 198 133 58 199 130 63 200 132 63 201 132 58 202 130 57 203 131 57 204 134 60 205 136 63 206 137 60 207 136 57 208 134 56 209 135 64 210 138 65 211 139 66 212 140 66 213 140 67 214 141 64 215 138 71 216 145 68 217 142 70 218 144 69 219 143 70 220 144 68 221 142 70 222 148 69 223 149 67 224 146 70 225 148 67 226 146 66 227 147 68 228 152 71 229 153 65 230 150 68 231 152 65 232 150 64 233 151 72 234 154 73 235 155 74 236 156 74 237 156 75 238 157 72 239 154 79 240 161 76 241 158 78 242 160 77 243 159 78 244 160 76 245 158 78 246 164 77 247 165 75 248 162 78 249 164 75 250 162 74 251 163 76 252 168 79 253 169 73 254 166 76 255 168 73 256 166 72 257 167 80 258 170 81 259 171 83 260 173 82 261 172 83 262 173 81 263 171 85 264 175 86 265 176 87 266 177 87 267 177 84 268 174 85 269 175 86 270 180 85 271 181 83 272 178 86 273 180 83 274 178 82 275 179 84 276 184 87 277 185 81 278 182 84 279 184 81 280 182 80 281 183 88 282 186 90 283 188 91 284 189 90 285 188 88 286 186 89 287 187 92 288 190 94 289 192 95 290 193 94 291 192 92 292 190 93 293 191 94 294 196 93 295 197 91 296 194 94 297 196 91 298 194 90 299 195 92 300 200 95 301 201 89 302 198 92 303 200 89 304 198 88 305 199 96 306 202 98 307 204 99 308 205 98 309 204 96 310 202 97 311 203 103 312 209 100 313 206 102 314 208 102 315 208 100 316 206 101 317 207 102 318 212 101 319 213 99 320 210 102 321 212 99 322 210 98 323 211 98 324 214 103 325 216 102 326 217 103 327 216 98 328 214 97 329 215 100 330 220 103 331 221 97 332 218 100 333 220 97 334 218 96 335 219 104 336 222 106 337 224 107 338 225 106 339 224 104 340 222 105 341 223 111 342 229 108 343 226 110 344 228 110 345 228 108 346 226 109 347 227 110 348 232 109 349 233 107 350 230 110 351 232 107 352 230 106 353 231 110 354 237 106 355 234 111 356 236 111 357 236 106 358 234 105 359 235 108 360 240 111 361 241 105 362 238 108 363 240 105 364 238 104 365 239 112 366 242 113 367 243 114 368 244 114 369 244 115 370 245 112 371 242 119 372 249 116 373 246 118 374 248 117 375 247 118 376 248 116 377 246 118 378 252 117 379 253 115 380 250 118 381 252 115 382 250 114 383 251 116 384 256 119 385 257 113 386 254 116 387 256 113 388 254 112 389 255 120 390 258 121 391 259 122 392 260 122 393 260 123 394 261 120 395 258 127 396 265 124 397 262 126 398 264 125 399 263 126 400 264 124 401 262 126 402 268 125 403 269 123 404 266 126 405 268 123 406 266 122 407 267 124 408 272 127 409 273 121 410 270 124 411 272 121 412 270 120 413 271 128 414 274 129 415 275 131 416 277 130 417 276 131 418 277 129 419 275 133 420 279 134 421 280 135 422 281 135 423 281 132 424 278 133 425 279 134 426 284 133 427 285 131 428 282 134 429 284 131 430 282 130 431 283 132 432 288 135 433 289 129 434 286 132 435 288 129 436 286 128 437 287 136 438 290 138 439 292 139 440 293 138 441 292 136 442 290 137 443 291 140 444 294 142 445 296 143 446 297 142 447 296 140 448 294 141 449 295 142 450 300 141 451 301 139 452 298 142 453 300 139 454 298 138 455 299 140 456 304 143 457 305 137 458 302 140 459 304 137 460 302 136 461 303 144 462 306 146 463 308 147 464 309 146 465 308 144 466 306 145 467 307 151 468 313 148 469 310 150 470 312 150 471 312 148 472 310 149 473 311 150 474 316 149 475 317 147 476 314 150 477 316 147 478 314 146 479 315 150 480 321 146 481 318 151 482 320 151 483 320 146 484 318 145 485 319 148 486 324 151 487 325 145 488 322 148 489 324 145 490 322 144 491 323 152 492 326 154 493 328 155 494 329 154 495 328 152 496 326 153 497 327 159 498 333 156 499 330 158 500 332 158 501 332 156 502 330 157 503 331 158 504 336 157 505 337 155 506 334 158 507 336 155 508 334 154 509 335 158 510 341 154 511 338 159 512 340 159 513 340 154 514 338 153 515 339 156 516 344 159 517 345 153 518 342 156 519 344 153 520 342 152 521 343 160 522 346 161 523 347 162 524 348 162 525 348 163 526 349 160 527 346 167 528 353 164 529 350 166 530 352 165 531 351 166 532 352 164 533 350 166 534 356 165 535 357 163 536 354 166 537 356 163 538 354 162 539 355 164 540 360 167 541 361 161 542 358 164 543 360 161 544 358 160 545 359 168 546 362 169 547 363 170 548 364 170 549 364 171 550 365 168 551 362 175 552 369 172 553 366 174 554 368 173 555 367 174 556 368 172 557 366 174 558 372 173 559 373 171 560 370 174 561 372 171 562 370 170 563 371 172 564 376 175 565 377 169 566 374 172 567 376 169 568 374 168 569 375 176 570 378 177 571 379 179 572 381 178 573 380 179 574 381 177 575 379 181 576 383 182 577 384 183 578 385 183 579 385 180 580 382 181 581 383 182 582 388 181 583 389 179 584 386 182 585 388 179 586 386 178 587 387 180 588 392 183 589 393 177 590 390 180 591 392 177 592 390 176 593 391 184 594 394 186 595 396 187 596 397 186 597 396 184 598 394 185 599 395 188 600 398 190 601 400 191 602 401 190 603 400 188 604 398 189 605 399 190 606 404 189 607 405 187 608 402 190 609 404 187 610 402 186 611 403 188 612 408 191 613 409 185 614 406 188 615 408 185 616 406 184 617 407 192 618 410 194 619 412 195 620 413 194 621 412 192 622 410 193 623 411 199 624 417 196 625 414 198 626 416 198 627 416 196 628 414 197 629 415 195 630 418 198 631 420 197 632 421 198 633 420 195 634 418 194 635 419 198 636 425 194 637 422 199 638 424 199 639 424 194 640 422 193 641 423 193 642 426 196 643 428 199 644 429 196 645 428 193 646 426 192 647 427 200 648 430 202 649 432 203 650 433 202 651 432 200 652 430 201 653 431 207 654 437 204 655 434 206 656 436 206 657 436 204 658 434 205 659 435 203 660 438 206 661 440 205 662 441 206 663 440 203 664 438 202 665 439 206 666 445 202 667 442 207 668 444 207 669 444 202 670 442 201 671 443 201 672 446 204 673 448 207 674 449 204 675 448 201 676 446 200 677 447 208 678 450 209 679 451 210 680 452 210 681 452 211 682 453 208 683 450 215 684 457 212 685 454 214 686 456 213 687 455 214 688 456 212 689 454 214 690 460 213 691 461 211 692 458 214 693 460 211 694 458 210 695 459 212 696 464 215 697 465 209 698 462 212 699 464 209 700 462 208 701 463 216 702 466 217 703 467 218 704 468 218 705 468 219 706 469 216 707 466 223 708 473 220 709 470 222 710 472 221 711 471 222 712 472 220 713 470 222 714 476 221 715 477 219 716 474 222 717 476 219 718 474 218 719 475 220 720 480 223 721 481 217 722 478 220 723 480 217 724 478 216 725 479 224 726 482 225 727 483 227 728 485 226 729 484 227 730 485 225 731 483 229 732 487 230 733 488 231 734 489 231 735 489 228 736 486 229 737 487 230 738 492 229 739 493 227 740 490 230 741 492 227 742 490 226 743 491 228 744 496 231 745 497 225 746 494 228 747 496 225 748 494 224 749 495 232 750 498 234 751 500 235 752 501 234 753 500 232 754 498 233 755 499 236 756 502 238 757 504 239 758 505 238 759 504 236 760 502 237 761 503 238 762 508 237 763 509 235 764 506 238 765 508 235 766 506 234 767 507 236 768 512 239 769 513 233 770 510 236 771 512 233 772 510 232 773 511 242 774 516 243 775 517 240 776 514 242 777 516 240 778 514 241 779 515 244 780 518 246 781 520 247 782 521 246 783 520 244 784 518 245 785 519 244 786 525 240 787 522 245 788 524 245 789 524 240 790 522 243 791 523 242 792 527 246 793 528 245 794 529 245 795 529 243 796 526 242 797 527 241 798 531 247 799 532 246 800 533 246 801 533 242 802 530 241 803 531 247 804 537 241 805 534 244 806 536 244 807 536 241 808 534 240 809 535 250 810 540 251 811 541 248 812 538 250 813 540 248 814 538 249 815 539 252 816 542 254 817 544 255 818 545 254 819 544 252 820 542 253 821 543 252 822 549 248 823 546 253 824 548 253 825 548 248 826 546 251 827 547 253 828 553 251 829 550 254 830 552 254 831 552 251 832 550 250 833 551 249 834 555 255 835 556 254 836 557 254 837 557 250 838 554 249 839 555 255 840 561 249 841 558 252 842 560 252 843 560 249 844 558 248 845 559 256 846 562 258 847 564 259 848 565 258 849 564 256 850 562 257 851 563 260 852 566 262 853 568 263 854 569 262 855 568 260 856 566 261 857 567 259 858 570 258 859 571 261 860 573 262 861 572 261 862 573 258 863 571 260 864 576 263 865 577 257 866 574 260 867 576 257 868 574 256 869 575 264 870 578 266 871 580 267 872 581 266 873 580 264 874 578 265 875 579 268 876 582 270 877 584 271 878 585 270 879 584 268 880 582 269 881 583 270 882 588 269 883 589 267 884 586 270 885 588 267 886 586 266 887 587 268 888 592 271 889 593 265 890 590 268 891 592 265 892 590 264 893 591 272 894 594 274 895 596 275 896 597 274 897 596 272 898 594 273 899 595 276 900 598 278 901 600 279 902 601 278 903 600 276 904 598 277 905 599 278 906 604 277 907 605 275 908 602 278 909 604 275 910 602 274 911 603 276 912 608 279 913 609 273 914 606 276 915 608 273 916 606 272 917 607 280 918 610 282 919 612 283 920 613 282 921 612 280 922 610 281 923 611 284 924 614 286 925 616 287 926 617 286 927 616 284 928 614 285 929 615 286 930 620 285 931 621 283 932 618 286 933 620 283 934 618 282 935 619 284 936 624 287 937 625 281 938 622 284 939 624 281 940 622 280 941 623 288 942 626 290 943 628 291 944 629 290 945 628 288 946 626 289 947 627 292 948 630 294 949 632 295 950 633 294 951 632 292 952 630 293 953 631 294 954 636 293 955 637 291 956 634 294 957 636 291 958 634 290 959 635 292 960 640 295 961 641 289 962 638 292 963 640 289 964 638 288 965 639 299 966 645 296 967 642 298 968 644 298 969 644 296 970 642 297 971 643 300 972 646 302 973 648 303 974 649 302 975 648 300 976 646 301 977 647 300 978 653 296 979 650 301 980 652 301 981 652 296 982 650 299 983 651 301 984 657 299 985 654 302 986 656 302 987 656 299 988 654 298 989 655 297 990 659 303 991 660 302 992 661 302 993 661 298 994 658 297 995 659 303 996 665 297 997 662 300 998 664 300 999 664 297 1000 662 296 1001 663

+

306 1002 668 304 1003 666 305 1004 667 310 1005 670 311 1006 673 312 1007 674 306 1008 671 311 1009 673 310 1010 670 310 1011 677 307 1012 675 306 1013 676 310 1014 681 312 1015 682 308 1016 679 308 1017 686 311 1018 683 304 1019 685 315 1020 689 313 1021 687 314 1022 688 319 1023 691 320 1024 694 321 1025 695 315 1026 692 320 1027 694 319 1028 691 319 1029 698 316 1030 696 315 1031 697 319 1032 702 321 1033 703 317 1034 700 317 1035 707 320 1036 704 313 1037 706 324 1038 710 322 1039 708 323 1040 709 328 1041 712 329 1042 715 330 1043 716 324 1044 713 329 1045 715 328 1046 712 328 1047 719 325 1048 717 324 1049 718 328 1050 723 330 1051 724 326 1052 721 326 1053 728 329 1054 725 322 1055 727 333 1056 731 331 1057 729 332 1058 730 337 1059 733 338 1060 736 339 1061 737 333 1062 734 338 1063 736 337 1064 733 337 1065 740 334 1066 738 333 1067 739 337 1068 744 339 1069 745 335 1070 742 335 1071 749 338 1072 746 331 1073 748 342 1074 752 340 1075 750 341 1076 751 346 1077 754 347 1078 757 348 1079 758 342 1080 755 347 1081 757 346 1082 754 346 1083 761 343 1084 759 342 1085 760 346 1086 765 348 1087 766 344 1088 763 344 1089 770 347 1090 767 340 1091 769 351 1092 773 349 1093 771 350 1094 772 355 1095 775 356 1096 778 357 1097 779 351 1098 776 356 1099 778 355 1100 775 355 1101 782 352 1102 780 351 1103 781 355 1104 786 357 1105 787 353 1106 784 353 1107 791 356 1108 788 349 1109 790 360 1110 794 358 1111 792 359 1112 793 364 1113 796 365 1114 799 366 1115 800 360 1116 797 365 1117 799 364 1118 796 364 1119 803 361 1120 801 360 1121 802 364 1122 807 366 1123 808 362 1124 805 362 1125 812 365 1126 809 358 1127 811 369 1128 815 367 1129 813 368 1130 814 373 1131 817 374 1132 820 375 1133 821 369 1134 818 374 1135 820 373 1136 817 373 1137 824 370 1138 822 369 1139 823 373 1140 828 375 1141 829 371 1142 826 371 1143 833 374 1144 830 367 1145 832 378 1146 836 376 1147 834 377 1148 835 382 1149 838 383 1150 841 384 1151 842 378 1152 839 383 1153 841 382 1154 838 382 1155 845 379 1156 843 378 1157 844 382 1158 849 384 1159 850 380 1160 847 380 1161 854 383 1162 851 376 1163 853 387 1164 857 385 1165 855 386 1166 856 391 1167 859 392 1168 862 393 1169 863 387 1170 860 392 1171 862 391 1172 859 391 1173 866 388 1174 864 387 1175 865 391 1176 870 393 1177 871 389 1178 868 389 1179 875 392 1180 872 385 1181 874 396 1182 878 394 1183 876 395 1184 877 400 1185 880 401 1186 883 402 1187 884 396 1188 881 401 1189 883 400 1190 880 400 1191 887 397 1192 885 396 1193 886 400 1194 891 402 1195 892 398 1196 889 398 1197 896 401 1198 893 394 1199 895 405 1200 899 403 1201 897 404 1202 898 409 1203 901 410 1204 904 411 1205 905 405 1206 902 410 1207 904 409 1208 901 409 1209 908 406 1210 906 405 1211 907 409 1212 912 411 1213 913 407 1214 910 407 1215 917 410 1216 914 403 1217 916 414 1218 920 412 1219 918 413 1220 919 418 1221 922 419 1222 925 420 1223 926 414 1224 923 419 1225 925 418 1226 922 418 1227 929 415 1228 927 414 1229 928 418 1230 933 420 1231 934 416 1232 931 416 1233 938 419 1234 935 412 1235 937 423 1236 941 421 1237 939 422 1238 940 427 1239 943 428 1240 946 429 1241 947 423 1242 944 428 1243 946 427 1244 943 427 1245 950 424 1246 948 423 1247 949 427 1248 954 429 1249 955 425 1250 952 425 1251 959 428 1252 956 421 1253 958 432 1254 962 430 1255 960 431 1256 961 436 1257 964 437 1258 967 438 1259 968 432 1260 965 437 1261 967 436 1262 964 436 1263 971 433 1264 969 432 1265 970 436 1266 975 438 1267 976 434 1268 973 434 1269 980 437 1270 977 430 1271 979 441 1272 983 439 1273 981 440 1274 982 445 1275 985 446 1276 988 447 1277 989 441 1278 986 446 1279 988 445 1280 985 445 1281 992 442 1282 990 441 1283 991 445 1284 996 447 1285 997 443 1286 994 443 1287 1001 446 1288 998 439 1289 1000 450 1290 1004 448 1291 1002 449 1292 1003 454 1293 1006 455 1294 1009 456 1295 1010 450 1296 1007 455 1297 1009 454 1298 1006 454 1299 1013 451 1300 1011 450 1301 1012 454 1302 1017 456 1303 1018 452 1304 1015 452 1305 1022 455 1306 1019 448 1307 1021 459 1308 1025 457 1309 1023 458 1310 1024 463 1311 1027 464 1312 1030 465 1313 1031 459 1314 1028 464 1315 1030 463 1316 1027 463 1317 1034 460 1318 1032 459 1319 1033 463 1320 1038 465 1321 1039 461 1322 1036 461 1323 1043 464 1324 1040 457 1325 1042 468 1326 1046 466 1327 1044 467 1328 1045 472 1329 1048 473 1330 1051 474 1331 1052 468 1332 1049 473 1333 1051 472 1334 1048 472 1335 1055 469 1336 1053 468 1337 1054 472 1338 1059 474 1339 1060 470 1340 1057 470 1341 1064 473 1342 1061 466 1343 1063 477 1344 1067 475 1345 1065 476 1346 1066 481 1347 1069 482 1348 1072 483 1349 1073 477 1350 1070 482 1351 1072 481 1352 1069 481 1353 1076 478 1354 1074 477 1355 1075 481 1356 1080 483 1357 1081 479 1358 1078 479 1359 1085 482 1360 1082 475 1361 1084 486 1362 1088 484 1363 1086 485 1364 1087 490 1365 1090 491 1366 1093 492 1367 1094 486 1368 1091 491 1369 1093 490 1370 1090 490 1371 1097 487 1372 1095 486 1373 1096 490 1374 1101 492 1375 1102 488 1376 1099 488 1377 1106 491 1378 1103 484 1379 1105 495 1380 1109 493 1381 1107 494 1382 1108 499 1383 1111 500 1384 1114 501 1385 1115 495 1386 1112 500 1387 1114 499 1388 1111 499 1389 1118 496 1390 1116 495 1391 1117 499 1392 1122 501 1393 1123 497 1394 1120 497 1395 1127 500 1396 1124 493 1397 1126 504 1398 1130 502 1399 1128 503 1400 1129 508 1401 1132 509 1402 1135 510 1403 1136 504 1404 1133 509 1405 1135 508 1406 1132 508 1407 1139 505 1408 1137 504 1409 1138 508 1410 1143 510 1411 1144 506 1412 1141 506 1413 1148 509 1414 1145 502 1415 1147 513 1416 1151 511 1417 1149 512 1418 1150 517 1419 1153 518 1420 1156 519 1421 1157 513 1422 1154 518 1423 1156 517 1424 1153 517 1425 1160 514 1426 1158 513 1427 1159 517 1428 1164 519 1429 1165 515 1430 1162 515 1431 1169 518 1432 1166 511 1433 1168 522 1434 1172 520 1435 1170 521 1436 1171 526 1437 1174 527 1438 1177 528 1439 1178 522 1440 1175 527 1441 1177 526 1442 1174 526 1443 1181 523 1444 1179 522 1445 1180 526 1446 1185 528 1447 1186 524 1448 1183 524 1449 1190 527 1450 1187 520 1451 1189 531 1452 1193 529 1453 1191 530 1454 1192 535 1455 1195 536 1456 1198 537 1457 1199 531 1458 1196 536 1459 1198 535 1460 1195 535 1461 1202 532 1462 1200 531 1463 1201 535 1464 1206 537 1465 1207 533 1466 1204 533 1467 1211 536 1468 1208 529 1469 1210 540 1470 1214 538 1471 1212 539 1472 1213 544 1473 1216 545 1474 1219 546 1475 1220 540 1476 1217 545 1477 1219 544 1478 1216 544 1479 1223 541 1480 1221 540 1481 1222 544 1482 1227 546 1483 1228 542 1484 1225 542 1485 1232 545 1486 1229 538 1487 1231 549 1488 1235 547 1489 1233 548 1490 1234 553 1491 1237 554 1492 1240 555 1493 1241 549 1494 1238 554 1495 1240 553 1496 1237 553 1497 1244 550 1498 1242 549 1499 1243 553 1500 1248 555 1501 1249 551 1502 1246 551 1503 1253 554 1504 1250 547 1505 1252 558 1506 1256 556 1507 1254 557 1508 1255 562 1509 1258 563 1510 1261 564 1511 1262 558 1512 1259 563 1513 1261 562 1514 1258 562 1515 1265 559 1516 1263 558 1517 1264 562 1518 1269 564 1519 1270 560 1520 1267 560 1521 1274 563 1522 1271 556 1523 1273 567 1524 1277 565 1525 1275 566 1526 1276 571 1527 1279 572 1528 1282 573 1529 1283 567 1530 1280 572 1531 1282 571 1532 1279 571 1533 1286 568 1534 1284 567 1535 1285 571 1536 1290 573 1537 1291 569 1538 1288 569 1539 1295 572 1540 1292 565 1541 1294 576 1542 1298 574 1543 1296 575 1544 1297 580 1545 1300 581 1546 1303 582 1547 1304 576 1548 1301 581 1549 1303 580 1550 1300 580 1551 1307 579 1552 1308 576 1553 1306 580 1554 1311 582 1555 1312 578 1556 1309 578 1557 1316 575 1558 1314 574 1559 1315 585 1560 1319 583 1561 1317 584 1562 1318 589 1563 1321 590 1564 1324 591 1565 1325 585 1566 1322 590 1567 1324 589 1568 1321 589 1569 1328 586 1570 1326 585 1571 1327 589 1572 1332 591 1573 1333 587 1574 1330 587 1575 1337 590 1576 1334 583 1577 1336 594 1578 1340 592 1579 1338 593 1580 1339 598 1581 1342 599 1582 1345 600 1583 1346 594 1584 1343 599 1585 1345 598 1586 1342 598 1587 1349 595 1588 1347 594 1589 1348 598 1590 1353 600 1591 1354 596 1592 1351 596 1593 1358 599 1594 1355 592 1595 1357 603 1596 1361 601 1597 1359 602 1598 1360 607 1599 1363 608 1600 1366 609 1601 1367 603 1602 1364 608 1603 1366 607 1604 1363 607 1605 1370 604 1606 1368 603 1607 1369 607 1608 1374 609 1609 1375 605 1610 1372 605 1611 1379 608 1612 1376 601 1613 1378 612 1614 1382 610 1615 1380 611 1616 1381 616 1617 1384 617 1618 1387 618 1619 1388 612 1620 1385 617 1621 1387 616 1622 1384 616 1623 1391 613 1624 1389 612 1625 1390 616 1626 1395 618 1627 1396 614 1628 1393 614 1629 1400 617 1630 1397 610 1631 1399 621 1632 1403 619 1633 1401 620 1634 1402 625 1635 1405 626 1636 1408 627 1637 1409 621 1638 1406 626 1639 1408 625 1640 1405 625 1641 1412 622 1642 1410 621 1643 1411 625 1644 1416 627 1645 1417 623 1646 1414 623 1647 1421 626 1648 1418 619 1649 1420 630 1650 1424 628 1651 1422 629 1652 1423 634 1653 1426 635 1654 1429 636 1655 1430 630 1656 1427 635 1657 1429 634 1658 1426 634 1659 1433 631 1660 1431 630 1661 1432 634 1662 1437 636 1663 1438 632 1664 1435 632 1665 1442 635 1666 1439 628 1667 1441 639 1668 1445 637 1669 1443 638 1670 1444 643 1671 1447 644 1672 1450 645 1673 1451 639 1674 1448 644 1675 1450 643 1676 1447 643 1677 1454 640 1678 1452 639 1679 1453 643 1680 1458 645 1681 1459 641 1682 1456 641 1683 1463 644 1684 1460 637 1685 1462 648 1686 1466 646 1687 1464 647 1688 1465 652 1689 1468 653 1690 1471 654 1691 1472 648 1692 1469 653 1693 1471 652 1694 1468 652 1695 1475 649 1696 1473 648 1697 1474 652 1698 1479 654 1699 1480 650 1700 1477 650 1701 1484 653 1702 1481 646 1703 1483 657 1704 1487 655 1705 1485 656 1706 1486 661 1707 1489 662 1708 1492 663 1709 1493 657 1710 1490 662 1711 1492 661 1712 1489 661 1713 1496 658 1714 1494 657 1715 1495 661 1716 1500 663 1717 1501 659 1718 1498 659 1719 1505 662 1720 1502 655 1721 1504 666 1722 1508 664 1723 1506 665 1724 1507 667 1725 1512 668 1726 1510 664 1727 1511 670 1728 1514 671 1729 1517 672 1730 1518 666 1731 1515 671 1732 1517 670 1733 1514 670 1734 1521 667 1735 1519 666 1736 1520 670 1737 1525 672 1738 1526 668 1739 1523 668 1740 1530 671 1741 1527 664 1742 1529 675 1743 1533 673 1744 1531 674 1745 1532 679 1746 1535 680 1747 1538 681 1748 1539 675 1749 1536 680 1750 1538 679 1751 1535 679 1752 1542 676 1753 1540 675 1754 1541 679 1755 1546 681 1756 1547 677 1757 1544 677 1758 1551 680 1759 1548 673 1760 1550 684 1761 1554 682 1762 1552 683 1763 1553 688 1764 1556 689 1765 1559 690 1766 1560 684 1767 1557 689 1768 1559 688 1769 1556 688 1770 1563 685 1771 1561 684 1772 1562 688 1773 1567 690 1774 1568 686 1775 1565 686 1776 1572 689 1777 1569 682 1778 1571 693 1779 1575 691 1780 1573 692 1781 1574 697 1782 1577 698 1783 1580 699 1784 1581 693 1785 1578 698 1786 1580 697 1787 1577 697 1788 1584 694 1789 1582 693 1790 1583 697 1791 1588 699 1792 1589 695 1793 1586 695 1794 1593 698 1795 1590 691 1796 1592 702 1797 1596 700 1798 1594 701 1799 1595 706 1800 1598 707 1801 1601 708 1802 1602 702 1803 1599 707 1804 1601 706 1805 1598 706 1806 1605 703 1807 1603 702 1808 1604 706 1809 1609 708 1810 1610 704 1811 1607 704 1812 1614 707 1813 1611 700 1814 1613 711 1815 1617 709 1816 1615 710 1817 1616 712 1818 1621 713 1819 1619 709 1820 1620 715 1821 1623 716 1822 1626 717 1823 1627 711 1824 1624 716 1825 1626 715 1826 1623 715 1827 1630 712 1828 1628 711 1829 1629 715 1830 1634 717 1831 1635 713 1832 1632 713 1833 1639 716 1834 1636 709 1835 1638 720 1836 1642 718 1837 1640 719 1838 1641 724 1839 1644 725 1840 1647 726 1841 1648 720 1842 1645 725 1843 1647 724 1844 1644 724 1845 1651 721 1846 1649 720 1847 1650 724 1848 1655 726 1849 1656 722 1850 1653 722 1851 1660 725 1852 1657 718 1853 1659 729 1854 1663 727 1855 1661 728 1856 1662 733 1857 1665 734 1858 1668 735 1859 1669 729 1860 1666 734 1861 1668 733 1862 1665 733 1863 1672 730 1864 1670 729 1865 1671 733 1866 1676 735 1867 1677 731 1868 1674 731 1869 1681 734 1870 1678 727 1871 1680 738 1872 1684 736 1873 1682 737 1874 1683 742 1875 1686 743 1876 1689 744 1877 1690 738 1878 1687 743 1879 1689 742 1880 1686 742 1881 1693 739 1882 1691 738 1883 1692 742 1884 1697 744 1885 1698 740 1886 1695 740 1887 1702 743 1888 1699 736 1889 1701 747 1890 1705 745 1891 1703 746 1892 1704 751 1893 1707 752 1894 1710 753 1895 1711 747 1896 1708 752 1897 1710 751 1898 1707 751 1899 1714 748 1900 1712 747 1901 1713 751 1902 1718 753 1903 1719 749 1904 1716 749 1905 1723 752 1906 1720 745 1907 1722 756 1908 1726 754 1909 1724 755 1910 1725 760 1911 1728 761 1912 1731 762 1913 1732 756 1914 1729 761 1915 1731 760 1916 1728 760 1917 1735 757 1918 1733 756 1919 1734 760 1920 1739 762 1921 1740 758 1922 1737 758 1923 1744 761 1924 1741 754 1925 1743 765 1926 1747 763 1927 1745 764 1928 1746 766 1929 1751 767 1930 1749 763 1931 1750 769 1932 1753 770 1933 1756 771 1934 1757 765 1935 1754 770 1936 1756 769 1937 1753 769 1938 1760 766 1939 1758 765 1940 1759 769 1941 1764 771 1942 1765 767 1943 1762 767 1944 1769 770 1945 1766 763 1946 1768 774 1947 1772 772 1948 1770 773 1949 1771 778 1950 1774 779 1951 1777 780 1952 1778 774 1953 1775 779 1954 1777 778 1955 1774 778 1956 1781 775 1957 1779 774 1958 1780 778 1959 1785 780 1960 1786 776 1961 1783 776 1962 1790 779 1963 1787 772 1964 1789 783 1965 1793 781 1966 1791 782 1967 1792 787 1968 1795 788 1969 1798 789 1970 1799 783 1971 1796 788 1972 1798 787 1973 1795 787 1974 1802 784 1975 1800 783 1976 1801 787 1977 1806 789 1978 1807 785 1979 1804 785 1980 1811 788 1981 1808 781 1982 1810 792 1983 1814 790 1984 1812 791 1985 1813 796 1986 1816 797 1987 1819 798 1988 1820 792 1989 1817 797 1990 1819 796 1991 1816 796 1992 1823 793 1993 1821 792 1994 1822 796 1995 1827 798 1996 1828 794 1997 1825 794 1998 1832 797 1999 1829 790 2000 1831 801 2001 1835 799 2002 1833 800 2003 1834 805 2004 1837 806 2005 1840 807 2006 1841 801 2007 1838 806 2008 1840 805 2009 1837 805 2010 1844 802 2011 1842 801 2012 1843 805 2013 1848 807 2014 1849 803 2015 1846 803 2016 1853 806 2017 1850 799 2018 1852 810 2019 1856 808 2020 1854 809 2021 1855 814 2022 1858 815 2023 1861 816 2024 1862 810 2025 1859 815 2026 1861 814 2027 1858 814 2028 1865 811 2029 1863 810 2030 1864 814 2031 1869 816 2032 1870 812 2033 1867 812 2034 1874 815 2035 1871 808 2036 1873 819 2037 1877 817 2038 1875 818 2039 1876 823 2040 1879 824 2041 1882 825 2042 1883 819 2043 1880 824 2044 1882 823 2045 1879 823 2046 1886 820 2047 1884 819 2048 1885 823 2049 1890 825 2050 1891 821 2051 1888 821 2052 1895 824 2053 1892 817 2054 1894 828 2055 1898 826 2056 1896 827 2057 1897 832 2058 1900 833 2059 1903 834 2060 1904 828 2061 1901 833 2062 1903 832 2063 1900 832 2064 1907 829 2065 1905 828 2066 1906 832 2067 1911 834 2068 1912 830 2069 1909 830 2070 1916 833 2071 1913 826 2072 1915 837 2073 1919 835 2074 1917 836 2075 1918 841 2076 1921 842 2077 1924 843 2078 1925 837 2079 1922 842 2080 1924 841 2081 1921 841 2082 1928 838 2083 1926 837 2084 1927 841 2085 1932 843 2086 1933 839 2087 1930 839 2088 1937 842 2089 1934 835 2090 1936 846 2091 1940 844 2092 1938 845 2093 1939 850 2094 1942 851 2095 1945 852 2096 1946 846 2097 1943 851 2098 1945 850 2099 1942 850 2100 1949 847 2101 1947 846 2102 1948 850 2103 1953 852 2104 1954 848 2105 1951 848 2106 1958 851 2107 1955 844 2108 1957 855 2109 1961 853 2110 1959 854 2111 1960 859 2112 1963 860 2113 1966 861 2114 1967 855 2115 1964 860 2116 1966 859 2117 1963 859 2118 1970 856 2119 1968 855 2120 1969 859 2121 1974 861 2122 1975 857 2123 1972 857 2124 1979 860 2125 1976 853 2126 1978 864 2127 1982 862 2128 1980 863 2129 1981 868 2130 1984 869 2131 1987 870 2132 1988 864 2133 1985 869 2134 1987 868 2135 1984 868 2136 1991 865 2137 1989 864 2138 1990 868 2139 1995 870 2140 1996 866 2141 1993 866 2142 2000 869 2143 1997 862 2144 1999 873 2145 2003 871 2146 2001 872 2147 2002 877 2148 2005 878 2149 2008 879 2150 2009 873 2151 2006 878 2152 2008 877 2153 2005 877 2154 2012 874 2155 2010 873 2156 2011 877 2157 2016 879 2158 2017 875 2159 2014 875 2160 2021 878 2161 2018 871 2162 2020 882 2163 2024 880 2164 2022 881 2165 2023 886 2166 2026 887 2167 2029 888 2168 2030 882 2169 2027 887 2170 2029 886 2171 2026 886 2172 2033 883 2173 2031 882 2174 2032 886 2175 2037 888 2176 2038 884 2177 2035 884 2178 2042 887 2179 2039 880 2180 2041 891 2181 2045 889 2182 2043 890 2183 2044 895 2184 2047 896 2185 2050 897 2186 2051 891 2187 2048 896 2188 2050 895 2189 2047 895 2190 2054 892 2191 2052 891 2192 2053 895 2193 2058 897 2194 2059 893 2195 2056 893 2196 2063 896 2197 2060 889 2198 2062 900 2199 2066 898 2200 2064 899 2201 2065 904 2202 2068 905 2203 2071 906 2204 2072 900 2205 2069 905 2206 2071 904 2207 2068 904 2208 2075 901 2209 2073 900 2210 2074 904 2211 2079 906 2212 2080 902 2213 2077 902 2214 2084 905 2215 2081 898 2216 2083 909 2217 2087 907 2218 2085 908 2219 2086 913 2220 2089 914 2221 2092 915 2222 2093 909 2223 2090 914 2224 2092 913 2225 2089 913 2226 2096 910 2227 2094 909 2228 2095 913 2229 2100 915 2230 2101 911 2231 2098 911 2232 2105 914 2233 2102 907 2234 2104 918 2235 2108 916 2236 2106 917 2237 2107 922 2238 2110 923 2239 2113 924 2240 2114 918 2241 2111 923 2242 2113 922 2243 2110 922 2244 2117 919 2245 2115 918 2246 2116 922 2247 2121 924 2248 2122 920 2249 2119 920 2250 2126 923 2251 2123 916 2252 2125 927 2253 2129 925 2254 2127 926 2255 2128 931 2256 2131 932 2257 2134 933 2258 2135 927 2259 2132 932 2260 2134 931 2261 2131 931 2262 2138 928 2263 2136 927 2264 2137 931 2265 2142 933 2266 2143 929 2267 2140 929 2268 2147 932 2269 2144 925 2270 2146 936 2271 2150 934 2272 2148 935 2273 2149 940 2274 2152 941 2275 2155 942 2276 2156 936 2277 2153 941 2278 2155 940 2279 2152 940 2280 2159 937 2281 2157 936 2282 2158 940 2283 2163 942 2284 2164 938 2285 2161 938 2286 2168 941 2287 2165 934 2288 2167 945 2289 2171 943 2290 2169 944 2291 2170 949 2292 2173 950 2293 2176 951 2294 2177 945 2295 2174 950 2296 2176 949 2297 2173 949 2298 2180 946 2299 2178 945 2300 2179 949 2301 2184 951 2302 2185 947 2303 2182 947 2304 2189 950 2305 2186 943 2306 2188 954 2307 2192 952 2308 2190 953 2309 2191 958 2310 2194 959 2311 2197 960 2312 2198 954 2313 2195 959 2314 2197 958 2315 2194 958 2316 2201 955 2317 2199 954 2318 2200 958 2319 2205 960 2320 2206 956 2321 2203 956 2322 2210 959 2323 2207 952 2324 2209 963 2325 2213 961 2326 2211 962 2327 2212 967 2328 2215 968 2329 2218 969 2330 2219 963 2331 2216 968 2332 2218 967 2333 2215 967 2334 2222 964 2335 2220 963 2336 2221 967 2337 2226 969 2338 2227 965 2339 2224 965 2340 2231 968 2341 2228 961 2342 2230 972 2343 2234 970 2344 2232 971 2345 2233 976 2346 2236 977 2347 2239 978 2348 2240 972 2349 2237 977 2350 2239 976 2351 2236 976 2352 2243 973 2353 2241 972 2354 2242 976 2355 2247 978 2356 2248 974 2357 2245 974 2358 2252 977 2359 2249 970 2360 2251 981 2361 2255 979 2362 2253 980 2363 2254 985 2364 2257 986 2365 2260 987 2366 2261 981 2367 2258 986 2368 2260 985 2369 2257 985 2370 2264 982 2371 2262 981 2372 2263 985 2373 2268 987 2374 2269 983 2375 2266 983 2376 2273 986 2377 2270 979 2378 2272 990 2379 2276 988 2380 2274 989 2381 2275 994 2382 2278 995 2383 2281 996 2384 2282 990 2385 2279 995 2386 2281 994 2387 2278 994 2388 2285 991 2389 2283 990 2390 2284 994 2391 2289 996 2392 2290 992 2393 2287 992 2394 2294 995 2395 2291 988 2396 2293 999 2397 2297 997 2398 2295 998 2399 2296 1003 2400 2299 1004 2401 2302 1005 2402 2303 999 2403 2300 1004 2404 2302 1003 2405 2299 1003 2406 2306 1000 2407 2304 999 2408 2305 1003 2409 2310 1005 2410 2311 1001 2411 2308 1001 2412 2315 998 2413 2313 997 2414 2314 1008 2415 2318 1006 2416 2316 1007 2417 2317 1012 2418 2320 1013 2419 2323 1014 2420 2324 1008 2421 2321 1013 2422 2323 1012 2423 2320 1012 2424 2327 1009 2425 2325 1008 2426 2326 1012 2427 2331 1014 2428 2332 1010 2429 2329 1010 2430 2336 1007 2431 2334 1006 2432 2335 1017 2433 2339 1015 2434 2337 1016 2435 2338 1021 2436 2341 1022 2437 2344 1023 2438 2345 1017 2439 2342 1022 2440 2344 1021 2441 2341 1021 2442 2348 1018 2443 2346 1017 2444 2347 1021 2445 2352 1023 2446 2353 1019 2447 2350 1019 2448 2357 1022 2449 2354 1015 2450 2356 1026 2451 2360 1024 2452 2358 1025 2453 2359 1030 2454 2362 1031 2455 2365 1032 2456 2366 1026 2457 2363 1031 2458 2365 1030 2459 2362 1030 2460 2369 1027 2461 2367 1026 2462 2368 1030 2463 2373 1032 2464 2374 1028 2465 2371 1028 2466 2378 1025 2467 2376 1024 2468 2377 1035 2469 2381 1033 2470 2379 1034 2471 2380 1039 2472 2383 1040 2473 2386 1041 2474 2387 1035 2475 2384 1040 2476 2386 1039 2477 2383 1039 2478 2390 1036 2479 2388 1035 2480 2389 1039 2481 2394 1041 2482 2395 1037 2483 2392 1037 2484 2399 1034 2485 2397 1033 2486 2398 1044 2487 2402 1042 2488 2400 1043 2489 2401 1045 2490 2406 1046 2491 2404 1042 2492 2405 1048 2493 2408 1049 2494 2411 1050 2495 2412 1044 2496 2409 1049 2497 2411 1048 2498 2408 1048 2499 2415 1045 2500 2413 1044 2501 2414 1048 2502 2419 1050 2503 2420 1046 2504 2417 1046 2505 2424 1049 2506 2421 1042 2507 2423 1053 2508 2427 1051 2509 2425 1052 2510 2426 1058 2511 2432 1053 2512 2430 1052 2513 2431 1059 2514 2433 1057 2515 2429 1058 2516 2432 1057 2517 2436 1054 2518 2434 1053 2519 2435 1057 2520 2440 1059 2521 2441 1055 2522 2438 1055 2523 2445 1058 2524 2442 1051 2525 2444 1062 2526 2448 1060 2527 2446 1061 2528 2447 1067 2529 2453 1062 2530 2451 1061 2531 2452 1068 2532 2454 1066 2533 2450 1067 2534 2453 1066 2535 2457 1063 2536 2455 1062 2537 2456 1066 2538 2461 1068 2539 2462 1064 2540 2459 1064 2541 2466 1067 2542 2463 1060 2543 2465 1071 2544 2469 1069 2545 2467 1070 2546 2468 1076 2547 2474 1071 2548 2472 1070 2549 2473 1077 2550 2475 1076 2551 2474 1073 2552 4621 1075 2553 2478 1072 2554 2476 1071 2555 2477 1075 2556 2482 1077 2557 2483 1073 2558 2480 1073 2559 2487 1076 2560 2484 1069 2561 2486 1080 2562 2490 1078 2563 2488 1079 2564 2489 1085 2565 2495 1080 2566 2493 1079 2567 2494 1086 2568 2496 1084 2569 2492 1085 2570 2495 1084 2571 2499 1081 2572 2497 1080 2573 2498 1084 2574 2503 1086 2575 2504 1082 2576 2501 1082 2577 2508 1085 2578 2505 1078 2579 2507 1089 2580 2511 1087 2581 2509 1088 2582 2510 1094 2583 2516 1089 2584 2514 1088 2585 2515 1095 2586 2517 1093 2587 2513 1094 2588 2516 1093 2589 2520 1090 2590 2518 1089 2591 2519 1093 2592 2524 1095 2593 2525 1091 2594 2522 1091 2595 2529 1094 2596 2526 1087 2597 2528 1098 2598 2532 1096 2599 2530 1097 2600 2531 1103 2601 2537 1098 2602 2535 1097 2603 2536 1104 2604 2538 1102 2605 2534 1103 2606 2537 1102 2607 2541 1099 2608 2539 1098 2609 2540 1102 2610 2545 1104 2611 2546 1100 2612 2543 1100 2613 2550 1103 2614 2547 1096 2615 2549 1107 2616 2553 1105 2617 2551 1106 2618 2552 1112 2619 2558 1107 2620 2556 1106 2621 2557 1113 2622 2559 1111 2623 2555 1109 2624 4625 1111 2625 2562 1108 2626 2560 1107 2627 2561 1111 2628 2566 1113 2629 2567 1109 2630 2564 1109 2631 2571 1112 2632 2568 1105 2633 2570 1116 2634 2574 1114 2635 2572 1115 2636 2573 1117 2637 2578 1118 2638 2576 1114 2639 2577 1121 2640 2583 1116 2641 2581 1115 2642 2582 1122 2643 2584 1120 2644 2580 1121 2645 2583 1120 2646 2587 1117 2647 2585 1116 2648 2586 1120 2649 2591 1122 2650 2592 1118 2651 2589 1118 2652 2596 1121 2653 2593 1114 2654 2595 1125 2655 2599 1123 2656 2597 1124 2657 2598 1129 2658 2601 1130 2659 2604 1131 2660 2605 1125 2661 2602 1130 2662 2604 1129 2663 2601 1129 2664 2608 1126 2665 2606 1125 2666 2607 1129 2667 2612 1131 2668 2613 1127 2669 2610 1127 2670 2617 1124 2671 2615 1123 2672 2616 1134 2673 2620 1132 2674 2618 1133 2675 2619 1138 2676 2622 1139 2677 2625 1140 2678 2626 1134 2679 2623 1139 2680 2625 1138 2681 2622 1138 2682 2629 1135 2683 2627 1134 2684 2628 1138 2685 2633 1140 2686 2634 1136 2687 2631 1136 2688 2638 1139 2689 2635 1132 2690 2637 1143 2691 2641 1141 2692 2639 1142 2693 2640 1147 2694 2643 1148 2695 2646 1149 2696 2647 1143 2697 2644 1148 2698 2646 1147 2699 2643 1147 2700 2650 1144 2701 2648 1143 2702 2649 1147 2703 2654 1149 2704 2655 1145 2705 2652 1145 2706 2659 1148 2707 2656 1141 2708 2658 1152 2709 2662 1150 2710 2660 1151 2711 2661 1156 2712 2664 1157 2713 2667 1158 2714 2668 1152 2715 2665 1157 2716 2667 1156 2717 2664 1156 2718 2671 1153 2719 2669 1152 2720 2670 1156 2721 2675 1158 2722 2676 1154 2723 2673 1154 2724 2680 1157 2725 2677 1150 2726 2679 1161 2727 2683 1159 2728 2681 1160 2729 2682 1165 2730 2685 1166 2731 2688 1167 2732 2689 1161 2733 2686 1166 2734 2688 1165 2735 2685 1165 2736 2692 1162 2737 2690 1161 2738 2691 1165 2739 2696 1167 2740 2697 1163 2741 2694 1163 2742 2701 1166 2743 2698 1159 2744 2700 1170 2745 2704 1168 2746 2702 1169 2747 2703 1175 2748 2709 1170 2749 2707 1169 2750 2708 1176 2751 2710 1174 2752 2706 1175 2753 2709 1174 2754 2713 1171 2755 2711 1170 2756 2712 1174 2757 2717 1176 2758 2718 1172 2759 2715 1172 2760 2722 1175 2761 2719 1168 2762 2721 1179 2763 2725 1177 2764 2723 1178 2765 2724 1180 2766 2729 1181 2767 2727 1177 2768 2728 1184 2769 2734 1179 2770 2732 1178 2771 2733 1185 2772 2735 1183 2773 2731 1184 2774 2734 1183 2775 2738 1180 2776 2736 1179 2777 2737 1183 2778 2742 1185 2779 2743 1181 2780 2740 1181 2781 2747 1184 2782 2744 1177 2783 2746 1188 2784 2750 1186 2785 2748 1187 2786 2749 1193 2787 2755 1188 2788 2753 1187 2789 2754 1194 2790 2756 1193 2791 2755 1190 2792 4634 1192 2793 2759 1189 2794 2757 1188 2795 2758 1192 2796 2763 1194 2797 2764 1190 2798 2761 1190 2799 2768 1193 2800 2765 1186 2801 2767 1197 2802 2771 1195 2803 2769 1196 2804 2770 1202 2805 2776 1197 2806 2774 1196 2807 2775 1203 2808 2777 1202 2809 2776 1199 2810 4635 1201 2811 2780 1198 2812 2778 1197 2813 2779 1201 2814 2784 1203 2815 2785 1200 2816 2783 1199 2817 2789 1202 2818 2786 1195 2819 2788 1206 2820 2792 1204 2821 2790 1205 2822 2791 1211 2823 2797 1206 2824 2795 1205 2825 2796 1212 2826 2798 1211 2827 2797 1208 2828 4636 1210 2829 2801 1207 2830 2799 1206 2831 2800 1210 2832 2805 1212 2833 2806 1208 2834 2803 1208 2835 2810 1211 2836 2807 1204 2837 2809 1215 2838 2813 1213 2839 2811 1214 2840 2812 1220 2841 2818 1215 2842 2816 1214 2843 2817 1221 2844 2819 1220 2845 2818 1217 2846 4637 1219 2847 2822 1216 2848 2820 1215 2849 2821 1219 2850 2826 1221 2851 2827 1217 2852 2824 1217 2853 2831 1220 2854 2828 1213 2855 2830 1224 2856 2834 1225 2857 2835 1223 2858 2833 1229 2859 2839 1224 2860 2837 1223 2861 2838 1230 2862 2840 1229 2863 2839 1226 2864 4638 1228 2865 2843 1225 2866 2841 1224 2867 2842 1228 2868 2847 1230 2869 2848 1226 2870 2845 1226 2871 2852 1229 2872 2849 1222 2873 2851 1233 2874 2855 1231 2875 2853 1232 2876 2854 1238 2877 2860 1233 2878 2858 1232 2879 2859 1239 2880 2861 1238 2881 2860 1235 2882 4639 1237 2883 2864 1234 2884 2862 1233 2885 2863 1237 2886 2868 1239 2887 2869 1235 2888 2866 1235 2889 2873 1238 2890 2870 1231 2891 2872 1242 2892 2876 1240 2893 2874 1241 2894 2875 1246 2895 2878 1247 2896 2881 1248 2897 2882 1242 2898 2879 1247 2899 2881 1246 2900 2878 1246 2901 2885 1243 2902 2883 1242 2903 2884 1246 2904 2889 1248 2905 2890 1244 2906 2887 1244 2907 2894 1247 2908 2891 1240 2909 2893 1251 2910 2897 1249 2911 2895 1250 2912 2896 1255 2913 2899 1256 2914 2902 1257 2915 2903 1251 2916 2900 1256 2917 2902 1255 2918 2899 1255 2919 2906 1252 2920 2904 1251 2921 2905 1255 2922 2910 1257 2923 2911 1253 2924 2908 1253 2925 2915 1256 2926 2912 1249 2927 2914 1260 2928 2918 1258 2929 2916 1259 2930 2917 1265 2931 2923 1260 2932 2921 1259 2933 2922 1266 2934 2924 1265 2935 2923 1262 2936 4642 1264 2937 2927 1261 2938 2925 1260 2939 2926 1264 2940 2931 1266 2941 2932 1262 2942 2929 1262 2943 2936 1265 2944 2933 1258 2945 2935 1269 2946 2939 1267 2947 2937 1268 2948 2938 1273 2949 2941 1274 2950 2944 1275 2951 2945 1269 2952 2942 1274 2953 2944 1273 2954 2941 1273 2955 2948 1270 2956 2946 1269 2957 2947 1273 2958 2952 1275 2959 2953 1271 2960 2950 1271 2961 2957 1274 2962 2954 1267 2963 2956 1278 2964 2960 1276 2965 2958 1277 2966 2959 1282 2967 2962 1283 2968 2965 1284 2969 2966 1278 2970 2963 1283 2971 2965 1282 2972 2962 1282 2973 2969 1279 2974 2967 1278 2975 2968 1282 2976 2973 1284 2977 2974 1280 2978 2971 1280 2979 2978 1283 2980 2975 1276 2981 2977 1287 2982 2981 1285 2983 2979 1286 2984 2980 1292 2985 2986 1287 2986 2984 1286 2987 2985 1293 2988 2987 1292 2989 2986 1289 2990 4645 1291 2991 2990 1288 2992 2988 1287 2993 2989 1291 2994 2994 1293 2995 2995 1289 2996 2992 1289 2997 2999 1292 2998 2996 1285 2999 2998 1296 3000 3002 1294 3001 3000 1295 3002 3001 1301 3003 3007 1296 3004 3005 1295 3005 3006 1302 3006 3008 1301 3007 3007 1298 3008 4646 1300 3009 3011 1297 3010 3009 1296 3011 3010 1300 3012 3015 1302 3013 3016 1298 3014 3013 1298 3015 3020 1301 3016 3017 1294 3017 3019 1305 3018 3023 1303 3019 3021 1304 3020 3022 1310 3021 3028 1305 3022 3026 1304 3023 3027 1311 3024 3029 1310 3025 3028 1307 3026 4647 1309 3027 3032 1306 3028 3030 1305 3029 3031 1309 3030 3036 1311 3031 3037 1307 3032 3034 1307 3033 3041 1310 3034 3038 1303 3035 3040 1314 3036 3044 1312 3037 3042 1313 3038 3043 1319 3039 3049 1314 3040 3047 1313 3041 3048 1320 3042 3050 1319 3043 3049 1316 3044 4648 1318 3045 3053 1315 3046 3051 1314 3047 3052 1318 3048 3057 1320 3049 3058 1316 3050 3055 1316 3051 3062 1319 3052 3059 1312 3053 3061 1323 3054 3065 1321 3055 3063 1322 3056 3064 1328 3057 3070 1323 3058 3068 1322 3059 3069 1329 3060 3071 1328 3061 3070 1325 3062 4649 1327 3063 3074 1324 3064 3072 1323 3065 3073 1327 3066 3078 1329 3067 3079 1325 3068 3076 1325 3069 3083 1328 3070 3080 1321 3071 3082 1332 3072 3086 1333 3073 3087 1331 3074 3085 1337 3075 3091 1332 3076 3089 1331 3077 3090 1338 3078 3092 1337 3079 3091 1334 3080 4650 1336 3081 3095 1333 3082 3093 1332 3083 3094 1336 3084 3099 1338 3085 3100 1334 3086 3097 1334 3087 3104 1337 3088 3101 1330 3089 3103 1341 3090 3107 1339 3091 3105 1340 3092 3106 1346 3093 3112 1341 3094 3110 1340 3095 3111 1347 3096 3113 1346 3097 3112 1343 3098 4651 1345 3099 3116 1342 3100 3114 1341 3101 3115 1345 3102 3120 1347 3103 3121 1343 3104 3118 1343 3105 3125 1346 3106 3122 1339 3107 3124 1350 3108 3128 1348 3109 3126 1349 3110 3127 1354 3111 3130 1355 3112 3133 1356 3113 3134 1350 3114 3131 1355 3115 3133 1354 3116 3130 1354 3117 3137 1351 3118 3135 1350 3119 3136 1354 3120 3141 1356 3121 3142 1352 3122 3139 1352 3123 3146 1349 3124 3144 1348 3125 3145 1359 3126 3149 1357 3127 3147 1358 3128 3148 1363 3129 3151 1364 3130 3154 1365 3131 3155 1359 3132 3152 1364 3133 3154 1363 3134 3151 1363 3135 3158 1360 3136 3156 1359 3137 3157 1363 3138 3162 1365 3139 3163 1361 3140 3160 1361 3141 3167 1364 3142 3164 1357 3143 3166 1368 3144 3170 1366 3145 3168 1367 3146 3169 1372 3147 3172 1373 3148 3175 1374 3149 3176 1368 3150 3173 1373 3151 3175 1372 3152 3172 1372 3153 3179 1369 3154 3177 1368 3155 3178 1372 3156 3183 1374 3157 3184 1370 3158 3181 1370 3159 3188 1373 3160 3185 1366 3161 3187 1377 3162 3191 1375 3163 3189 1376 3164 3190 1381 3165 3193 1382 3166 3196 1383 3167 3197 1377 3168 3194 1382 3169 3196 1381 3170 3193 1381 3171 3200 1378 3172 3198 1377 3173 3199 1381 3174 3204 1383 3175 3205 1379 3176 3202 1379 3177 3209 1382 3178 3206 1375 3179 3208 1386 3180 3212 1384 3181 3210 1385 3182 3211 1390 3183 3214 1391 3184 3217 1392 3185 3218 1386 3186 3215 1391 3187 3217 1390 3188 3214 1390 3189 3221 1387 3190 3219 1386 3191 3220 1390 3192 3225 1392 3193 3226 1388 3194 3223 1388 3195 3230 1391 3196 3227 1384 3197 3229 1395 3198 3233 1393 3199 3231 1394 3200 3232 1399 3201 3235 1400 3202 3238 1401 3203 3239 1395 3204 3236 1400 3205 3238 1399 3206 3235 1399 3207 3242 1396 3208 3240 1395 3209 3241 1399 3210 3246 1401 3211 3247 1397 3212 3244 1397 3213 3251 1400 3214 3248 1393 3215 3250 1404 3216 3254 1402 3217 3252 1403 3218 3253 1409 3219 3259 1404 3220 3257 1403 3221 3258 1410 3222 3260 1409 3223 3259 1406 3224 4658 1408 3225 3263 1405 3226 3261 1404 3227 3262 1408 3228 3267 1410 3229 3268 1406 3230 3265 1406 3231 3272 1409 3232 3269 1402 3233 3271 1413 3234 3275 1411 3235 3273 1412 3236 3274 1418 3237 3280 1413 3238 3278 1412 3239 3279 1419 3240 3281 1418 3241 3280 1415 3242 4659 1417 3243 3284 1414 3244 3282 1413 3245 3283 1417 3246 3288 1419 3247 3289 1415 3248 3286 1415 3249 3293 1418 3250 3290 1411 3251 3292 1422 3252 3296 1420 3253 3294 1421 3254 3295 1427 3255 3301 1422 3256 3299 1421 3257 3300 1428 3258 3302 1427 3259 3301 1424 3260 4660 1426 3261 3305 1423 3262 3303 1422 3263 3304 1426 3264 3309 1428 3265 3310 1424 3266 3307 1424 3267 3314 1427 3268 3311 1420 3269 3313 1431 3270 3317 1429 3271 3315 1430 3272 3316 1436 3273 3322 1435 3274 3319 1430 3275 3321 1437 3276 3323 1436 3277 3322 1433 3278 4661 1435 3279 3326 1432 3280 3324 1431 3281 3325 1435 3282 3330 1437 3283 3331 1433 3284 3328 1433 3285 3335 1436 3286 3332 1429 3287 3334 1440 3288 3338 1438 3289 3336 1439 3290 3337 1445 3291 3343 1440 3292 3341 1439 3293 3342 1446 3294 3344 1445 3295 3343 1442 3296 4662 1444 3297 3347 1441 3298 3345 1440 3299 3346 1444 3300 3351 1446 3301 3352 1442 3302 3349 1442 3303 3356 1445 3304 3353 1438 3305 3355 1449 3306 3359 1447 3307 3357 1448 3308 3358 1453 3309 3361 1454 3310 3364 1455 3311 3365 1449 3312 3362 1454 3313 3364 1453 3314 3361 1453 3315 3368 1450 3316 3366 1449 3317 3367 1453 3318 3372 1455 3319 3373 1451 3320 3370 1451 3321 3377 1454 3322 3374 1447 3323 3376 1458 3324 3380 1456 3325 3378 1457 3326 3379 1462 3327 3382 1463 3328 3385 1464 3329 3386 1458 3330 3383 1463 3331 3385 1462 3332 3382 1462 3333 3389 1459 3334 3387 1458 3335 3388 1462 3336 3393 1464 3337 3394 1460 3338 3391 1460 3339 3398 1457 3340 3396 1456 3341 3397 1467 3342 3401 1465 3343 3399 1466 3344 3400 1471 3345 3403 1472 3346 3406 1473 3347 3407 1467 3348 3404 1472 3349 3406 1471 3350 3403 1471 3351 3410 1468 3352 3408 1467 3353 3409 1471 3354 3414 1473 3355 3415 1469 3356 3412 1469 3357 3419 1472 3358 3416 1465 3359 3418 806 3360 1840 803 3361 4591 807 3362 1841 797 3363 1819 794 3364 4590 798 3365 1820 1446 3366 3344 1444 3367 3340 1445 3368 3343 1437 3369 3323 1435 3370 3319 1436 3371 3322 1463 3372 3385 1460 3373 4664 1464 3374 3386 1382 3375 3196 1379 3376 4655 1383 3377 3197 1373 3378 3175 1370 3379 4654 1374 3380 3176 1419 3381 3281 1417 3382 3277 1418 3383 3280 1472 3384 3406 1469 3385 4665 1473 3386 3407 1428 3387 3302 1426 3388 3298 1427 3389 3301 1435 3390 3319 1431 3391 3320 1430 3392 3321 1410 3393 3260 1408 3394 3256 1409 3395 3259 1274 3396 2944 1271 3397 4643 1275 3398 2945 1311 3399 3029 1309 3400 3025 1310 3401 3028 1364 3402 3154 1361 3403 4653 1365 3404 3155 1347 3405 3113 1345 3406 3109 1346 3407 3112 1355 3408 3133 1352 3409 4652 1356 3410 3134 1283 3411 2965 1280 3412 4644 1284 3413 2966 1320 3414 3050 1318 3415 3046 1319 3416 3049 1329 3417 3071 1327 3418 3067 1328 3419 3070 1293 3420 2987 1291 3421 2983 1292 3422 2986 1302 3423 3008 1300 3424 3004 1301 3425 3007 1338 3426 3092 1336 3427 3088 1337 3428 3091 1266 3429 2924 1264 3430 2920 1265 3431 2923 950 3432 2176 947 3433 4607 951 3434 2177 941 3435 2155 938 3436 4606 942 3437 2156 815 3438 1861 812 3439 4592 816 3440 1862 779 3441 1777 776 3442 4588 780 3443 1778 770 3444 1756 767 3445 4587 771 3446 1757 761 3447 1731 758 3448 4586 762 3449 1732 734 3450 1668 731 3451 4583 735 3452 1669 878 3453 2008 875 3454 4599 879 3455 2009 752 3456 1710 749 3457 4585 753 3458 1711 932 3459 2134 929 3460 4605 933 3461 2135 1352 3462 3146 1355 3463 3143 1349 3464 3144 1400 3465 3238 1397 3466 4657 1401 3467 3239 1454 3468 3364 1451 3469 4663 1455 3470 3365 1460 3471 3398 1463 3472 3395 1457 3473 3396 1212 3474 2798 1210 3475 2794 1211 3476 2797 1203 3477 2777 1201 3478 2773 1202 3479 2776 1203 3480 2785 1199 3481 2782 1200 3482 2783 1225 3483 2835 1222 3484 2832 1223 3485 2833 1221 3486 2819 1219 3487 2815 1220 3488 2818 1157 3489 2667 1154 3490 4630 1158 3491 2668 1239 3492 2861 1237 3493 2857 1238 3494 2860 1256 3495 2902 1253 3496 4641 1257 3497 2903 1230 3498 2840 1228 3499 2836 1229 3500 2839 1247 3501 2881 1244 3502 4640 1248 3503 2882 1194 3504 2756 1192 3505 2752 1193 3506 2755 995 3507 2281 992 3508 4612 996 3509 2282 1001 3510 2315 1004 3511 2312 998 3512 2313 1004 3513 2302 1001 3514 4613 1005 3515 2303 1022 3516 2344 1019 3517 4615 1023 3518 2345 1028 3519 2378 1031 3520 2375 1025 3521 2376 1077 3522 2475 1075 3523 2471 1076 3524 2474 1094 3525 2516 1091 3526 4623 1095 3527 2517 1130 3528 2604 1127 3529 4627 1131 3530 2605 1127 3531 2617 1130 3532 2614 1124 3533 2615 1013 3534 2323 1010 3535 4614 1014 3536 2324 1010 3537 2336 1013 3538 2333 1007 3539 2334 1031 3540 2365 1028 3541 4616 1032 3542 2366 1037 3543 2399 1040 3544 2396 1034 3545 2397 1103 3546 2537 1100 3547 4624 1104 3548 2538 1100 3549 2543 1101 3550 2544 1102 3551 2545 1111 3552 2555 1112 3553 2558 1109 3554 4625 1109 3555 2564 1110 3556 2565 1111 3557 2566 1139 3558 2625 1136 3559 4628 1140 3560 2626 1139 3561 2635 1133 3562 2636 1132 3563 2637 608 3564 1366 605 3565 4569 609 3566 1367 605 3567 1372 606 3568 1373 607 3569 1374 644 3570 1450 641 3571 4573 645 3572 1451 641 3573 1456 642 3574 1457 643 3575 1458 653 3576 1471 650 3577 4574 654 3578 1472 650 3579 1477 651 3580 1478 652 3581 1479 990 3582 2276 991 3583 2277 988 3584 2274 990 3585 2279 989 3586 2280 995 3587 2281 994 3588 2285 993 3589 2286 991 3590 2283 992 3591 2287 993 3592 2288 994 3593 2289 995 3594 2291 989 3595 2292 988 3596 2293 999 3597 2297 1000 3598 2298 997 3599 2295 999 3600 2300 998 3601 2301 1004 3602 2302 1003 3603 2306 1002 3604 2307 1000 3605 2304 1001 3606 2308 1002 3607 2309 1003 3608 2310 1008 3609 2318 1009 3610 2319 1006 3611 2316 1008 3612 2321 1007 3613 2322 1013 3614 2323 1012 3615 2327 1011 3616 2328 1009 3617 2325 1010 3618 2329 1011 3619 2330 1012 3620 2331 1017 3621 2339 1018 3622 2340 1015 3623 2337 1017 3624 2342 1016 3625 2343 1022 3626 2344 1021 3627 2348 1020 3628 2349 1018 3629 2346 1019 3630 2350 1020 3631 2351 1021 3632 2352 1022 3633 2354 1016 3634 2355 1015 3635 2356 1026 3636 2360 1027 3637 2361 1024 3638 2358 1026 3639 2363 1025 3640 2364 1031 3641 2365 1030 3642 2369 1029 3643 2370 1027 3644 2367 1028 3645 2371 1029 3646 2372 1030 3647 2373 1035 3648 2381 1036 3649 2382 1033 3650 2379 1040 3651 2386 1037 3652 4617 1041 3653 2387 1035 3654 2384 1034 3655 2385 1040 3656 2386 1039 3657 2390 1038 3658 2391 1036 3659 2388 1037 3660 2392 1038 3661 2393 1039 3662 2394 1044 3663 2402 1045 3664 2403 1042 3665 2400 1045 3666 2406 1047 3667 2407 1046 3668 2404 1049 3669 2411 1046 3670 4618 1050 3671 2412 1044 3672 2409 1043 3673 2410 1049 3674 2411 1048 3675 2415 1047 3676 2416 1045 3677 2413 1046 3678 2417 1047 3679 2418 1048 3680 2419 1049 3681 2421 1043 3682 2422 1042 3683 2423 1053 3684 2427 1054 3685 2428 1051 3686 2425 1058 3687 2432 1057 3688 2429 1053 3689 2430 1058 3690 2432 1055 3691 4619 1059 3692 2433 1057 3693 2436 1056 3694 2437 1054 3695 2434 1055 3696 2438 1056 3697 2439 1057 3698 2440 1058 3699 2442 1052 3700 2443 1051 3701 2444 1062 3702 2448 1063 3703 2449 1060 3704 2446 1067 3705 2453 1066 3706 2450 1062 3707 2451 1067 3708 2453 1064 3709 4620 1068 3710 2454 1066 3711 2457 1065 3712 2458 1063 3713 2455 1064 3714 2459 1065 3715 2460 1066 3716 2461 1067 3717 2463 1061 3718 2464 1060 3719 2465 1071 3720 2469 1072 3721 2470 1069 3722 2467 1076 3723 2474 1075 3724 2471 1071 3725 2472 1075 3726 2478 1074 3727 2479 1072 3728 2476 1073 3729 2480 1074 3730 2481 1075 3731 2482 1076 3732 2484 1070 3733 2485 1069 3734 2486 1080 3735 2490 1081 3736 2491 1078 3737 2488 1085 3738 2495 1084 3739 2492 1080 3740 2493 1085 3741 2495 1082 3742 4622 1086 3743 2496 1084 3744 2499 1083 3745 2500 1081 3746 2497 1082 3747 2501 1083 3748 2502 1084 3749 2503 1085 3750 2505 1079 3751 2506 1078 3752 2507 1089 3753 2511 1090 3754 2512 1087 3755 2509 1094 3756 2516 1093 3757 2513 1089 3758 2514 1093 3759 2520 1092 3760 2521 1090 3761 2518 1091 3762 2522 1092 3763 2523 1093 3764 2524 1094 3765 2526 1088 3766 2527 1087 3767 2528 1098 3768 2532 1099 3769 2533 1096 3770 2530 1103 3771 2537 1102 3772 2534 1098 3773 2535 1102 3774 2541 1101 3775 2542 1099 3776 2539 1103 3777 2547 1097 3778 2548 1096 3779 2549 1107 3780 2553 1108 3781 2554 1105 3782 2551 1112 3783 2558 1111 3784 2555 1107 3785 2556 1111 3786 2562 1110 3787 2563 1108 3788 2560 1112 3789 2568 1106 3790 2569 1105 3791 2570 1116 3792 2574 1117 3793 2575 1114 3794 2572 1117 3795 2578 1119 3796 2579 1118 3797 2576 1121 3798 2583 1120 3799 2580 1116 3800 2581 1121 3801 2583 1118 3802 4626 1122 3803 2584 1120 3804 2587 1119 3805 2588 1117 3806 2585 1118 3807 2589 1119 3808 2590 1120 3809 2591 1121 3810 2593 1115 3811 2594 1114 3812 2595 1125 3813 2599 1126 3814 2600 1123 3815 2597 1125 3816 2602 1124 3817 2603 1130 3818 2604 1129 3819 2608 1128 3820 2609 1126 3821 2606 1127 3822 2610 1128 3823 2611 1129 3824 2612 1134 3825 2620 1135 3826 2621 1132 3827 2618 1134 3828 2623 1133 3829 2624 1139 3830 2625 1138 3831 2629 1137 3832 2630 1135 3833 2627 1136 3834 2631 1137 3835 2632 1138 3836 2633 1143 3837 2641 1144 3838 2642 1141 3839 2639 1148 3840 2646 1145 3841 4629 1149 3842 2647 1143 3843 2644 1142 3844 2645 1148 3845 2646 1147 3846 2650 1146 3847 2651 1144 3848 2648 1145 3849 2652 1146 3850 2653 1147 3851 2654 1148 3852 2656 1142 3853 2657 1141 3854 2658 585 3855 1319 586 3856 1320 583 3857 1317 590 3858 1324 587 3859 4567 591 3860 1325 585 3861 1322 584 3862 1323 590 3863 1324 589 3864 1328 588 3865 1329 586 3866 1326 587 3867 1330 588 3868 1331 589 3869 1332 590 3870 1334 584 3871 1335 583 3872 1336 594 3873 1340 595 3874 1341 592 3875 1338 599 3876 1345 596 3877 4568 600 3878 1346 594 3879 1343 593 3880 1344 599 3881 1345 598 3882 1349 597 3883 1350 595 3884 1347 596 3885 1351 597 3886 1352 598 3887 1353 599 3888 1355 593 3889 1356 592 3890 1357 603 3891 1361 604 3892 1362 601 3893 1359 603 3894 1364 602 3895 1365 608 3896 1366 607 3897 1370 606 3898 1371 604 3899 1368 608 3900 1376 602 3901 1377 601 3902 1378 612 3903 1382 613 3904 1383 610 3905 1380 617 3906 1387 614 3907 4570 618 3908 1388 612 3909 1385 611 3910 1386 617 3911 1387 616 3912 1391 615 3913 1392 613 3914 1389 614 3915 1393 615 3916 1394 616 3917 1395 617 3918 1397 611 3919 1398 610 3920 1399 621 3921 1403 622 3922 1404 619 3923 1401 626 3924 1408 623 3925 4571 627 3926 1409 621 3927 1406 620 3928 1407 626 3929 1408 625 3930 1412 624 3931 1413 622 3932 1410 623 3933 1414 624 3934 1415 625 3935 1416 626 3936 1418 620 3937 1419 619 3938 1420 630 3939 1424 631 3940 1425 628 3941 1422 635 3942 1429 632 3943 4572 636 3944 1430 630 3945 1427 629 3946 1428 635 3947 1429 634 3948 1433 633 3949 1434 631 3950 1431 632 3951 1435 633 3952 1436 634 3953 1437 635 3954 1439 629 3955 1440 628 3956 1441 639 3957 1445 640 3958 1446 637 3959 1443 639 3960 1448 638 3961 1449 644 3962 1450 643 3963 1454 642 3964 1455 640 3965 1452 644 3966 1460 638 3967 1461 637 3968 1462 648 3969 1466 649 3970 1467 646 3971 1464 648 3972 1469 647 3973 1470 653 3974 1471 652 3975 1475 651 3976 1476 649 3977 1473 653 3978 1481 647 3979 1482 646 3980 1483 500 3981 1114 497 3982 4557 501 3983 1115 500 3984 1124 494 3985 1125 493 3986 1126 509 3987 1135 506 3988 4558 510 3989 1136 509 3990 1145 503 3991 1146 502 3992 1147 518 3993 1156 515 3994 4559 519 3995 1157 518 3996 1166 512 3997 1167 511 3998 1168 522 3999 1172 523 4000 1173 520 4001 1170 527 4002 1177 524 4003 4560 528 4004 1178 522 4005 1175 521 4006 1176 527 4007 1177 526 4008 1181 525 4009 1182 523 4010 1179 524 4011 1183 525 4012 1184 526 4013 1185 527 4014 1187 521 4015 1188 520 4016 1189 531 4017 1193 532 4018 1194 529 4019 1191 536 4020 1198 533 4021 4561 537 4022 1199 531 4023 1196 530 4024 1197 536 4025 1198 535 4026 1202 534 4027 1203 532 4028 1200 533 4029 1204 534 4030 1205 535 4031 1206 536 4032 1208 530 4033 1209 529 4034 1210 540 4035 1214 541 4036 1215 538 4037 1212 545 4038 1219 542 4039 4562 546 4040 1220 540 4041 1217 539 4042 1218 545 4043 1219 544 4044 1223 543 4045 1224 541 4046 1221 542 4047 1225 543 4048 1226 544 4049 1227 545 4050 1229 539 4051 1230 538 4052 1231 549 4053 1235 550 4054 1236 547 4055 1233 554 4056 1240 551 4057 4563 555 4058 1241 549 4059 1238 548 4060 1239 554 4061 1240 553 4062 1244 552 4063 1245 550 4064 1242 551 4065 1246 552 4066 1247 553 4067 1248 554 4068 1250 548 4069 1251 547 4070 1252 558 4071 1256 559 4072 1257 556 4073 1254 563 4074 1261 560 4075 4564 564 4076 1262 558 4077 1259 557 4078 1260 563 4079 1261 562 4080 1265 561 4081 1266 559 4082 1263 560 4083 1267 561 4084 1268 562 4085 1269 563 4086 1271 557 4087 1272 556 4088 1273 567 4089 1277 568 4090 1278 565 4091 1275 572 4092 1282 569 4093 4565 573 4094 1283 567 4095 1280 566 4096 1281 572 4097 1282 571 4098 1286 570 4099 1287 568 4100 1284 569 4101 1288 570 4102 1289 571 4103 1290 572 4104 1292 566 4105 1293 565 4106 1294 576 4107 1298 577 4108 1299 574 4109 1296 579 4110 1308 577 4111 1305 576 4112 1306 578 4113 1316 581 4114 1313 575 4115 1314 306 4116 668 307 4117 669 304 4118 666 311 4119 673 308 4120 4536 312 4121 674 306 4122 671 305 4123 672 311 4124 673 310 4125 677 309 4126 678 307 4127 675 308 4128 679 309 4129 680 310 4130 681 311 4131 683 305 4132 684 304 4133 685 315 4134 689 316 4135 690 313 4136 687 320 4137 694 317 4138 4537 321 4139 695 315 4140 692 314 4141 693 320 4142 694 319 4143 698 318 4144 699 316 4145 696 317 4146 700 318 4147 701 319 4148 702 320 4149 704 314 4150 705 313 4151 706 324 4152 710 325 4153 711 322 4154 708 329 4155 715 326 4156 4538 330 4157 716 324 4158 713 323 4159 714 329 4160 715 328 4161 719 327 4162 720 325 4163 717 326 4164 721 327 4165 722 328 4166 723 329 4167 725 323 4168 726 322 4169 727 333 4170 731 334 4171 732 331 4172 729 338 4173 736 335 4174 4539 339 4175 737 333 4176 734 332 4177 735 338 4178 736 337 4179 740 336 4180 741 334 4181 738 335 4182 742 336 4183 743 337 4184 744 338 4185 746 332 4186 747 331 4187 748 342 4188 752 343 4189 753 340 4190 750 347 4191 757 344 4192 4540 348 4193 758 342 4194 755 341 4195 756 347 4196 757 346 4197 761 345 4198 762 343 4199 759 344 4200 763 345 4201 764 346 4202 765 347 4203 767 341 4204 768 340 4205 769 351 4206 773 352 4207 774 349 4208 771 356 4209 778 353 4210 4541 357 4211 779 351 4212 776 350 4213 777 356 4214 778 355 4215 782 354 4216 783 352 4217 780 353 4218 784 354 4219 785 355 4220 786 356 4221 788 350 4222 789 349 4223 790 360 4224 794 361 4225 795 358 4226 792 365 4227 799 362 4228 4542 366 4229 800 360 4230 797 359 4231 798 365 4232 799 364 4233 803 363 4234 804 361 4235 801 362 4236 805 363 4237 806 364 4238 807 365 4239 809 359 4240 810 358 4241 811 369 4242 815 370 4243 816 367 4244 813 374 4245 820 371 4246 4543 375 4247 821 369 4248 818 368 4249 819 374 4250 820 373 4251 824 372 4252 825 370 4253 822 371 4254 826 372 4255 827 373 4256 828 374 4257 830 368 4258 831 367 4259 832 378 4260 836 379 4261 837 376 4262 834 383 4263 841 380 4264 4544 384 4265 842 378 4266 839 377 4267 840 383 4268 841 382 4269 845 381 4270 846 379 4271 843 380 4272 847 381 4273 848 382 4274 849 383 4275 851 377 4276 852 376 4277 853 387 4278 857 388 4279 858 385 4280 855 392 4281 862 389 4282 4545 393 4283 863 387 4284 860 386 4285 861 392 4286 862 391 4287 866 390 4288 867 388 4289 864 389 4290 868 390 4291 869 391 4292 870 392 4293 872 386 4294 873 385 4295 874 396 4296 878 397 4297 879 394 4298 876 401 4299 883 398 4300 4546 402 4301 884 396 4302 881 395 4303 882 401 4304 883 400 4305 887 399 4306 888 397 4307 885 398 4308 889 399 4309 890 400 4310 891 401 4311 893 395 4312 894 394 4313 895 405 4314 899 406 4315 900 403 4316 897 410 4317 904 407 4318 4547 411 4319 905 405 4320 902 404 4321 903 410 4322 904 409 4323 908 408 4324 909 406 4325 906 407 4326 910 408 4327 911 409 4328 912 410 4329 914 404 4330 915 403 4331 916 414 4332 920 415 4333 921 412 4334 918 419 4335 925 416 4336 4548 420 4337 926 414 4338 923 413 4339 924 419 4340 925 418 4341 929 417 4342 930 415 4343 927 416 4344 931 417 4345 932 418 4346 933 419 4347 935 413 4348 936 412 4349 937 423 4350 941 424 4351 942 421 4352 939 428 4353 946 425 4354 4549 429 4355 947 423 4356 944 422 4357 945 428 4358 946 427 4359 950 426 4360 951 424 4361 948 425 4362 952 426 4363 953 427 4364 954 428 4365 956 422 4366 957 421 4367 958 432 4368 962 433 4369 963 430 4370 960 437 4371 967 434 4372 4550 438 4373 968 432 4374 965 431 4375 966 437 4376 967 436 4377 971 435 4378 972 433 4379 969 434 4380 973 435 4381 974 436 4382 975 437 4383 977 431 4384 978 430 4385 979 441 4386 983 442 4387 984 439 4388 981 446 4389 988 443 4390 4551 447 4391 989 441 4392 986 440 4393 987 446 4394 988 445 4395 992 444 4396 993 442 4397 990 443 4398 994 444 4399 995 445 4400 996 446 4401 998 440 4402 999 439 4403 1000 450 4404 1004 451 4405 1005 448 4406 1002 455 4407 1009 452 4408 4552 456 4409 1010 450 4410 1007 449 4411 1008 455 4412 1009 454 4413 1013 453 4414 1014 451 4415 1011 452 4416 1015 453 4417 1016 454 4418 1017 455 4419 1019 449 4420 1020 448 4421 1021 459 4422 1025 460 4423 1026 457 4424 1023 464 4425 1030 461 4426 4553 465 4427 1031 459 4428 1028 458 4429 1029 464 4430 1030 463 4431 1034 462 4432 1035 460 4433 1032 461 4434 1036 462 4435 1037 463 4436 1038 464 4437 1040 458 4438 1041 457 4439 1042 468 4440 1046 469 4441 1047 466 4442 1044 473 4443 1051 470 4444 4554 474 4445 1052 468 4446 1049 467 4447 1050 473 4448 1051 472 4449 1055 471 4450 1056 469 4451 1053 470 4452 1057 471 4453 1058 472 4454 1059 473 4455 1061 467 4456 1062 466 4457 1063 477 4458 1067 478 4459 1068 475 4460 1065 482 4461 1072 479 4462 4555 483 4463 1073 477 4464 1070 476 4465 1071 482 4466 1072 481 4467 1076 480 4468 1077 478 4469 1074 479 4470 1078 480 4471 1079 481 4472 1080 482 4473 1082 476 4474 1083 475 4475 1084 486 4476 1088 487 4477 1089 484 4478 1086 491 4479 1093 488 4480 4556 492 4481 1094 486 4482 1091 485 4483 1092 491 4484 1093 490 4485 1097 489 4486 1098 487 4487 1095 488 4488 1099 489 4489 1100 490 4490 1101 491 4491 1103 485 4492 1104 484 4493 1105 657 4494 1487 658 4495 1488 655 4496 1485 662 4497 1492 659 4498 4575 663 4499 1493 657 4500 1490 656 4501 1491 662 4502 1492 661 4503 1496 660 4504 1497 658 4505 1494 659 4506 1498 660 4507 1499 661 4508 1500 662 4509 1502 656 4510 1503 655 4511 1504 666 4512 1508 667 4513 1509 664 4514 1506 667 4515 1512 669 4516 1513 668 4517 1510 671 4518 1517 668 4519 4576 672 4520 1518 666 4521 1515 665 4522 1516 671 4523 1517 670 4524 1521 669 4525 1522 667 4526 1519 668 4527 1523 669 4528 1524 670 4529 1525 671 4530 1527 665 4531 1528 664 4532 1529 675 4533 1533 676 4534 1534 673 4535 1531 680 4536 1538 677 4537 4577 681 4538 1539 675 4539 1536 674 4540 1537 680 4541 1538 679 4542 1542 678 4543 1543 676 4544 1540 677 4545 1544 678 4546 1545 679 4547 1546 680 4548 1548 674 4549 1549 673 4550 1550 684 4551 1554 685 4552 1555 682 4553 1552 689 4554 1559 686 4555 4578 690 4556 1560 684 4557 1557 683 4558 1558 689 4559 1559 688 4560 1563 687 4561 1564 685 4562 1561 686 4563 1565 687 4564 1566 688 4565 1567 689 4566 1569 683 4567 1570 682 4568 1571 693 4569 1575 694 4570 1576 691 4571 1573 698 4572 1580 695 4573 4579 699 4574 1581 693 4575 1578 692 4576 1579 698 4577 1580 697 4578 1584 696 4579 1585 694 4580 1582 695 4581 1586 696 4582 1587 697 4583 1588 698 4584 1590 692 4585 1591 691 4586 1592 702 4587 1596 703 4588 1597 700 4589 1594 707 4590 1601 704 4591 4580 708 4592 1602 702 4593 1599 701 4594 1600 707 4595 1601 706 4596 1605 705 4597 1606 703 4598 1603 704 4599 1607 705 4600 1608 706 4601 1609 707 4602 1611 701 4603 1612 700 4604 1613 711 4605 1617 712 4606 1618 709 4607 1615 712 4608 1621 714 4609 1622 713 4610 1619 716 4611 1626 713 4612 4581 717 4613 1627 711 4614 1624 710 4615 1625 716 4616 1626 715 4617 1630 714 4618 1631 712 4619 1628 713 4620 1632 714 4621 1633 715 4622 1634 716 4623 1636 710 4624 1637 709 4625 1638 720 4626 1642 721 4627 1643 718 4628 1640 725 4629 1647 722 4630 4582 726 4631 1648 720 4632 1645 719 4633 1646 725 4634 1647 724 4635 1651 723 4636 1652 721 4637 1649 722 4638 1653 723 4639 1654 724 4640 1655 725 4641 1657 719 4642 1658 718 4643 1659 729 4644 1663 730 4645 1664 727 4646 1661 729 4647 1666 728 4648 1667 734 4649 1668 733 4650 1672 732 4651 1673 730 4652 1670 731 4653 1674 732 4654 1675 733 4655 1676 734 4656 1678 728 4657 1679 727 4658 1680 738 4659 1684 739 4660 1685 736 4661 1682 743 4662 1689 740 4663 4584 744 4664 1690 738 4665 1687 737 4666 1688 743 4667 1689 742 4668 1693 741 4669 1694 739 4670 1691 740 4671 1695 741 4672 1696 742 4673 1697 743 4674 1699 737 4675 1700 736 4676 1701 747 4677 1705 748 4678 1706 745 4679 1703 747 4680 1708 746 4681 1709 752 4682 1710 751 4683 1714 750 4684 1715 748 4685 1712 749 4686 1716 750 4687 1717 751 4688 1718 752 4689 1720 746 4690 1721 745 4691 1722 756 4692 1726 757 4693 1727 754 4694 1724 756 4695 1729 755 4696 1730 761 4697 1731 760 4698 1735 759 4699 1736 757 4700 1733 758 4701 1737 759 4702 1738 760 4703 1739 761 4704 1741 755 4705 1742 754 4706 1743 765 4707 1747 766 4708 1748 763 4709 1745 766 4710 1751 768 4711 1752 767 4712 1749 765 4713 1754 764 4714 1755 770 4715 1756 769 4716 1760 768 4717 1761 766 4718 1758 767 4719 1762 768 4720 1763 769 4721 1764 770 4722 1766 764 4723 1767 763 4724 1768 774 4725 1772 775 4726 1773 772 4727 1770 774 4728 1775 773 4729 1776 779 4730 1777 778 4731 1781 777 4732 1782 775 4733 1779 776 4734 1783 777 4735 1784 778 4736 1785 779 4737 1787 773 4738 1788 772 4739 1789 783 4740 1793 784 4741 1794 781 4742 1791 788 4743 1798 785 4744 4589 789 4745 1799 783 4746 1796 782 4747 1797 788 4748 1798 787 4749 1802 786 4750 1803 784 4751 1800 785 4752 1804 786 4753 1805 787 4754 1806 788 4755 1808 782 4756 1809 781 4757 1810 792 4758 1814 793 4759 1815 790 4760 1812 792 4761 1817 791 4762 1818 797 4763 1819 796 4764 1823 795 4765 1824 793 4766 1821 794 4767 1825 795 4768 1826 796 4769 1827 797 4770 1829 791 4771 1830 790 4772 1831 801 4773 1835 802 4774 1836 799 4775 1833 801 4776 1838 800 4777 1839 806 4778 1840 805 4779 1844 804 4780 1845 802 4781 1842 803 4782 1846 804 4783 1847 805 4784 1848 806 4785 1850 800 4786 1851 799 4787 1852 810 4788 1856 811 4789 1857 808 4790 1854 810 4791 1859 809 4792 1860 815 4793 1861 814 4794 1865 813 4795 1866 811 4796 1863 812 4797 1867 813 4798 1868 814 4799 1869 815 4800 1871 809 4801 1872 808 4802 1873 819 4803 1877 820 4804 1878 817 4805 1875 824 4806 1882 821 4807 4593 825 4808 1883 819 4809 1880 818 4810 1881 824 4811 1882 823 4812 1886 822 4813 1887 820 4814 1884 821 4815 1888 822 4816 1889 823 4817 1890 824 4818 1892 818 4819 1893 817 4820 1894 828 4821 1898 829 4822 1899 826 4823 1896 833 4824 1903 830 4825 4594 834 4826 1904 828 4827 1901 827 4828 1902 833 4829 1903 832 4830 1907 831 4831 1908 829 4832 1905 830 4833 1909 831 4834 1910 832 4835 1911 833 4836 1913 827 4837 1914 826 4838 1915 837 4839 1919 838 4840 1920 835 4841 1917 842 4842 1924 839 4843 4595 843 4844 1925 837 4845 1922 836 4846 1923 842 4847 1924 841 4848 1928 840 4849 1929 838 4850 1926 839 4851 1930 840 4852 1931 841 4853 1932 842 4854 1934 836 4855 1935 835 4856 1936 846 4857 1940 847 4858 1941 844 4859 1938 851 4860 1945 848 4861 4596 852 4862 1946 846 4863 1943 845 4864 1944 851 4865 1945 850 4866 1949 849 4867 1950 847 4868 1947 848 4869 1951 849 4870 1952 850 4871 1953 851 4872 1955 845 4873 1956 844 4874 1957 855 4875 1961 856 4876 1962 853 4877 1959 860 4878 1966 857 4879 4597 861 4880 1967 855 4881 1964 854 4882 1965 860 4883 1966 859 4884 1970 858 4885 1971 856 4886 1968 857 4887 1972 858 4888 1973 859 4889 1974 860 4890 1976 854 4891 1977 853 4892 1978 864 4893 1982 865 4894 1983 862 4895 1980 869 4896 1987 866 4897 4598 870 4898 1988 864 4899 1985 863 4900 1986 869 4901 1987 868 4902 1991 867 4903 1992 865 4904 1989 866 4905 1993 867 4906 1994 868 4907 1995 869 4908 1997 863 4909 1998 862 4910 1999 873 4911 2003 874 4912 2004 871 4913 2001 873 4914 2006 872 4915 2007 878 4916 2008 877 4917 2012 876 4918 2013 874 4919 2010 875 4920 2014 876 4921 2015 877 4922 2016 878 4923 2018 872 4924 2019 871 4925 2020 882 4926 2024 883 4927 2025 880 4928 2022 887 4929 2029 884 4930 4600 888 4931 2030 882 4932 2027 881 4933 2028 887 4934 2029 886 4935 2033 885 4936 2034 883 4937 2031 884 4938 2035 885 4939 2036 886 4940 2037 887 4941 2039 881 4942 2040 880 4943 2041 891 4944 2045 892 4945 2046 889 4946 2043 896 4947 2050 893 4948 4601 897 4949 2051 891 4950 2048 890 4951 2049 896 4952 2050 895 4953 2054 894 4954 2055 892 4955 2052 893 4956 2056 894 4957 2057 895 4958 2058 896 4959 2060 890 4960 2061 889 4961 2062 900 4962 2066 901 4963 2067 898 4964 2064 905 4965 2071 902 4966 4602 906 4967 2072 900 4968 2069 899 4969 2070 905 4970 2071 904 4971 2075 903 4972 2076 901 4973 2073 902 4974 2077 903 4975 2078 904 4976 2079 905 4977 2081 899 4978 2082 898 4979 2083 909 4980 2087 910 4981 2088 907 4982 2085 914 4983 2092 911 4984 4603 915 4985 2093 909 4986 2090 908 4987 2091 914 4988 2092 913 4989 2096 912 4990 2097 910 4991 2094 911 4992 2098 912 4993 2099 913 4994 2100 914 4995 2102 908 4996 2103 907 4997 2104 918 4998 2108 919 4999 2109 916 5000 2106 923 5001 2113 920 5002 4604 924 5003 2114 918 5004 2111 917 5005 2112 923 5006 2113 922 5007 2117 921 5008 2118 919 5009 2115 920 5010 2119 921 5011 2120 922 5012 2121 923 5013 2123 917 5014 2124 916 5015 2125 927 5016 2129 928 5017 2130 925 5018 2127 927 5019 2132 926 5020 2133 932 5021 2134 931 5022 2138 930 5023 2139 928 5024 2136 929 5025 2140 930 5026 2141 931 5027 2142 932 5028 2144 926 5029 2145 925 5030 2146 936 5031 2150 937 5032 2151 934 5033 2148 936 5034 2153 935 5035 2154 941 5036 2155 940 5037 2159 939 5038 2160 937 5039 2157 938 5040 2161 939 5041 2162 940 5042 2163 941 5043 2165 935 5044 2166 934 5045 2167 945 5046 2171 946 5047 2172 943 5048 2169 945 5049 2174 944 5050 2175 950 5051 2176 949 5052 2180 948 5053 2181 946 5054 2178 947 5055 2182 948 5056 2183 949 5057 2184 950 5058 2186 944 5059 2187 943 5060 2188 954 5061 2192 955 5062 2193 952 5063 2190 959 5064 2197 956 5065 4608 960 5066 2198 954 5067 2195 953 5068 2196 959 5069 2197 958 5070 2201 957 5071 2202 955 5072 2199 956 5073 2203 957 5074 2204 958 5075 2205 959 5076 2207 953 5077 2208 952 5078 2209 963 5079 2213 964 5080 2214 961 5081 2211 968 5082 2218 965 5083 4609 969 5084 2219 963 5085 2216 962 5086 2217 968 5087 2218 967 5088 2222 966 5089 2223 964 5090 2220 965 5091 2224 966 5092 2225 967 5093 2226 968 5094 2228 962 5095 2229 961 5096 2230 972 5097 2234 973 5098 2235 970 5099 2232 977 5100 2239 974 5101 4610 978 5102 2240 972 5103 2237 971 5104 2238 977 5105 2239 976 5106 2243 975 5107 2244 973 5108 2241 974 5109 2245 975 5110 2246 976 5111 2247 977 5112 2249 971 5113 2250 970 5114 2251 981 5115 2255 982 5116 2256 979 5117 2253 986 5118 2260 983 5119 4611 987 5120 2261 981 5121 2258 980 5122 2259 986 5123 2260 985 5124 2264 984 5125 2265 982 5126 2262 983 5127 2266 984 5128 2267 985 5129 2268 986 5130 2270 980 5131 2271 979 5132 2272 1314 5133 3044 1315 5134 3045 1312 5135 3042 1323 5136 3065 1324 5137 3066 1321 5138 3063 1333 5139 3087 1330 5140 3084 1331 5141 3085 1260 5142 2918 1261 5143 2919 1258 5144 2916 1265 5145 2923 1264 5146 2920 1260 5147 2921 1264 5148 2927 1263 5149 2928 1261 5150 2925 1262 5151 2929 1263 5152 2930 1264 5153 2931 1265 5154 2933 1259 5155 2934 1258 5156 2935 1269 5157 2939 1270 5158 2940 1267 5159 2937 1269 5160 2942 1268 5161 2943 1274 5162 2944 1273 5163 2948 1272 5164 2949 1270 5165 2946 1271 5166 2950 1272 5167 2951 1273 5168 2952 1274 5169 2954 1268 5170 2955 1267 5171 2956 1278 5172 2960 1279 5173 2961 1276 5174 2958 1278 5175 2963 1277 5176 2964 1283 5177 2965 1282 5178 2969 1281 5179 2970 1279 5180 2967 1280 5181 2971 1281 5182 2972 1282 5183 2973 1283 5184 2975 1277 5185 2976 1276 5186 2977 1287 5187 2981 1288 5188 2982 1285 5189 2979 1292 5190 2986 1291 5191 2983 1287 5192 2984 1291 5193 2990 1290 5194 2991 1288 5195 2988 1289 5196 2992 1290 5197 2993 1291 5198 2994 1292 5199 2996 1286 5200 2997 1285 5201 2998 1296 5202 3002 1297 5203 3003 1294 5204 3000 1301 5205 3007 1300 5206 3004 1296 5207 3005 1300 5208 3011 1299 5209 3012 1297 5210 3009 1298 5211 3013 1299 5212 3014 1300 5213 3015 1301 5214 3017 1295 5215 3018 1294 5216 3019 1305 5217 3023 1306 5218 3024 1303 5219 3021 1310 5220 3028 1309 5221 3025 1305 5222 3026 1309 5223 3032 1308 5224 3033 1306 5225 3030 1307 5226 3034 1308 5227 3035 1309 5228 3036 1310 5229 3038 1304 5230 3039 1303 5231 3040 1319 5232 3049 1318 5233 3046 1314 5234 3047 1318 5235 3053 1317 5236 3054 1315 5237 3051 1316 5238 3055 1317 5239 3056 1318 5240 3057 1319 5241 3059 1313 5242 3060 1312 5243 3061 1328 5244 3070 1327 5245 3067 1323 5246 3068 1327 5247 3074 1326 5248 3075 1324 5249 3072 1325 5250 3076 1326 5251 3077 1327 5252 3078 1328 5253 3080 1322 5254 3081 1321 5255 3082 1337 5256 3091 1336 5257 3088 1332 5258 3089 1336 5259 3095 1335 5260 3096 1333 5261 3093 1334 5262 3097 1335 5263 3098 1336 5264 3099 1337 5265 3101 1331 5266 3102 1330 5267 3103 1341 5268 3107 1342 5269 3108 1339 5270 3105 1346 5271 3112 1345 5272 3109 1341 5273 3110 1345 5274 3116 1344 5275 3117 1342 5276 3114 1343 5277 3118 1344 5278 3119 1345 5279 3120 1346 5280 3122 1340 5281 3123 1339 5282 3124 1350 5283 3128 1351 5284 3129 1348 5285 3126 1350 5286 3131 1349 5287 3132 1355 5288 3133 1354 5289 3137 1353 5290 3138 1351 5291 3135 1352 5292 3139 1353 5293 3140 1354 5294 3141 1359 5295 3149 1360 5296 3150 1357 5297 3147 1359 5298 3152 1358 5299 3153 1364 5300 3154 1363 5301 3158 1362 5302 3159 1360 5303 3156 1361 5304 3160 1362 5305 3161 1363 5306 3162 1364 5307 3164 1358 5308 3165 1357 5309 3166 1368 5310 3170 1369 5311 3171 1366 5312 3168 1368 5313 3173 1367 5314 3174 1373 5315 3175 1372 5316 3179 1371 5317 3180 1369 5318 3177 1370 5319 3181 1371 5320 3182 1372 5321 3183 1373 5322 3185 1367 5323 3186 1366 5324 3187 1377 5325 3191 1378 5326 3192 1375 5327 3189 1377 5328 3194 1376 5329 3195 1382 5330 3196 1381 5331 3200 1380 5332 3201 1378 5333 3198 1379 5334 3202 1380 5335 3203 1381 5336 3204 1382 5337 3206 1376 5338 3207 1375 5339 3208 1386 5340 3212 1387 5341 3213 1384 5342 3210 1391 5343 3217 1388 5344 4656 1392 5345 3218 1386 5346 3215 1385 5347 3216 1391 5348 3217 1390 5349 3221 1389 5350 3222 1387 5351 3219 1388 5352 3223 1389 5353 3224 1390 5354 3225 1391 5355 3227 1385 5356 3228 1384 5357 3229 1395 5358 3233 1396 5359 3234 1393 5360 3231 1395 5361 3236 1394 5362 3237 1400 5363 3238 1399 5364 3242 1398 5365 3243 1396 5366 3240 1397 5367 3244 1398 5368 3245 1399 5369 3246 1400 5370 3248 1394 5371 3249 1393 5372 3250 1404 5373 3254 1405 5374 3255 1402 5375 3252 1409 5376 3259 1408 5377 3256 1404 5378 3257 1408 5379 3263 1407 5380 3264 1405 5381 3261 1406 5382 3265 1407 5383 3266 1408 5384 3267 1409 5385 3269 1403 5386 3270 1402 5387 3271 1413 5388 3275 1414 5389 3276 1411 5390 3273 1418 5391 3280 1417 5392 3277 1413 5393 3278 1417 5394 3284 1416 5395 3285 1414 5396 3282 1415 5397 3286 1416 5398 3287 1417 5399 3288 1418 5400 3290 1412 5401 3291 1411 5402 3292 1422 5403 3296 1423 5404 3297 1420 5405 3294 1427 5406 3301 1426 5407 3298 1422 5408 3299 1426 5409 3305 1425 5410 3306 1423 5411 3303 1424 5412 3307 1425 5413 3308 1426 5414 3309 1427 5415 3311 1421 5416 3312 1420 5417 3313 1431 5418 3317 1432 5419 3318 1429 5420 3315 1435 5421 3326 1434 5422 3327 1432 5423 3324 1433 5424 3328 1434 5425 3329 1435 5426 3330 1436 5427 3332 1430 5428 3333 1429 5429 3334 1440 5430 3338 1441 5431 3339 1438 5432 3336 1445 5433 3343 1444 5434 3340 1440 5435 3341 1444 5436 3347 1443 5437 3348 1441 5438 3345 1442 5439 3349 1443 5440 3350 1444 5441 3351 1445 5442 3353 1439 5443 3354 1438 5444 3355 1449 5445 3359 1450 5446 3360 1447 5447 3357 1449 5448 3362 1448 5449 3363 1454 5450 3364 1453 5451 3368 1452 5452 3369 1450 5453 3366 1451 5454 3370 1452 5455 3371 1453 5456 3372 1454 5457 3374 1448 5458 3375 1447 5459 3376 1458 5460 3380 1459 5461 3381 1456 5462 3378 1458 5463 3383 1457 5464 3384 1463 5465 3385 1462 5466 3389 1461 5467 3390 1459 5468 3387 1460 5469 3391 1461 5470 3392 1462 5471 3393 1467 5472 3401 1468 5473 3402 1465 5474 3399 1467 5475 3404 1466 5476 3405 1472 5477 3406 1471 5478 3410 1470 5479 3411 1468 5480 3408 1469 5481 3412 1470 5482 3413 1471 5483 3414 1472 5484 3416 1466 5485 3417 1465 5486 3418 495 5487 1109 496 5488 1110 493 5489 1107 495 5490 1112 494 5491 1113 500 5492 1114 499 5493 1118 498 5494 1119 496 5495 1116 497 5496 1120 498 5497 1121 499 5498 1122 504 5499 1130 505 5500 1131 502 5501 1128 504 5502 1133 503 5503 1134 509 5504 1135 508 5505 1139 507 5506 1140 505 5507 1137 506 5508 1141 507 5509 1142 508 5510 1143 513 5511 1151 514 5512 1152 511 5513 1149 513 5514 1154 512 5515 1155 518 5516 1156 517 5517 1160 516 5518 1161 514 5519 1158 515 5520 1162 516 5521 1163 517 5522 1164 581 5523 1303 578 5524 4566 582 5525 1304 576 5526 1301 575 5527 1302 581 5528 1303 578 5529 1309 579 5530 1310 580 5531 1311 1152 5532 2662 1153 5533 2663 1150 5534 2660 1152 5535 2665 1151 5536 2666 1157 5537 2667 1156 5538 2671 1155 5539 2672 1153 5540 2669 1154 5541 2673 1155 5542 2674 1156 5543 2675 1157 5544 2677 1151 5545 2678 1150 5546 2679 1161 5547 2683 1162 5548 2684 1159 5549 2681 1166 5550 2688 1163 5551 4631 1167 5552 2689 1161 5553 2686 1160 5554 2687 1166 5555 2688 1165 5556 2692 1164 5557 2693 1162 5558 2690 1163 5559 2694 1164 5560 2695 1165 5561 2696 1166 5562 2698 1160 5563 2699 1159 5564 2700 1170 5565 2704 1171 5566 2705 1168 5567 2702 1175 5568 2709 1174 5569 2706 1170 5570 2707 1175 5571 2709 1172 5572 4632 1176 5573 2710 1174 5574 2713 1173 5575 2714 1171 5576 2711 1172 5577 2715 1173 5578 2716 1174 5579 2717 1175 5580 2719 1169 5581 2720 1168 5582 2721 1179 5583 2725 1180 5584 2726 1177 5585 2723 1180 5586 2729 1182 5587 2730 1181 5588 2727 1184 5589 2734 1183 5590 2731 1179 5591 2732 1184 5592 2734 1181 5593 4633 1185 5594 2735 1183 5595 2738 1182 5596 2739 1180 5597 2736 1181 5598 2740 1182 5599 2741 1183 5600 2742 1184 5601 2744 1178 5602 2745 1177 5603 2746 1188 5604 2750 1189 5605 2751 1186 5606 2748 1193 5607 2755 1192 5608 2752 1188 5609 2753 1192 5610 2759 1191 5611 2760 1189 5612 2757 1190 5613 2761 1191 5614 2762 1192 5615 2763 1193 5616 2765 1187 5617 2766 1186 5618 2767 1197 5619 2771 1198 5620 2772 1195 5621 2769 1202 5622 2776 1201 5623 2773 1197 5624 2774 1201 5625 2780 1200 5626 2781 1198 5627 2778 1202 5628 2786 1196 5629 2787 1195 5630 2788 1206 5631 2792 1207 5632 2793 1204 5633 2790 1211 5634 2797 1210 5635 2794 1206 5636 2795 1210 5637 2801 1209 5638 2802 1207 5639 2799 1208 5640 2803 1209 5641 2804 1210 5642 2805 1211 5643 2807 1205 5644 2808 1204 5645 2809 1215 5646 2813 1216 5647 2814 1213 5648 2811 1220 5649 2818 1219 5650 2815 1215 5651 2816 1219 5652 2822 1218 5653 2823 1216 5654 2820 1217 5655 2824 1218 5656 2825 1219 5657 2826 1220 5658 2828 1214 5659 2829 1213 5660 2830 1229 5661 2839 1228 5662 2836 1224 5663 2837 1228 5664 2843 1227 5665 2844 1225 5666 2841 1226 5667 2845 1227 5668 2846 1228 5669 2847 1229 5670 2849 1223 5671 2850 1222 5672 2851 1233 5673 2855 1234 5674 2856 1231 5675 2853 1238 5676 2860 1237 5677 2857 1233 5678 2858 1237 5679 2864 1236 5680 2865 1234 5681 2862 1235 5682 2866 1236 5683 2867 1237 5684 2868 1238 5685 2870 1232 5686 2871 1231 5687 2872 1242 5688 2876 1243 5689 2877 1240 5690 2874 1242 5691 2879 1241 5692 2880 1247 5693 2881 1246 5694 2885 1245 5695 2886 1243 5696 2883 1244 5697 2887 1245 5698 2888 1246 5699 2889 1247 5700 2891 1241 5701 2892 1240 5702 2893 1251 5703 2897 1252 5704 2898 1249 5705 2895 1251 5706 2900 1250 5707 2901 1256 5708 2902 1255 5709 2906 1254 5710 2907 1252 5711 2904 1253 5712 2908 1254 5713 2909 1255 5714 2910 1256 5715 2912 1250 5716 2913 1249 5717 2914

+

1476 5718 3424 1480 5719 3440 1474 5720 3427 1477 5721 3426 1481 5722 3437 1476 5723 3424 1475 5724 3425 1479 5725 3436 1477 5726 3454 1474 5727 3427 1478 5728 3441 1475 5729 3425 1484 5730 3442 1478 5731 3441 1480 5732 3440 1481 5733 3437 1485 5734 3439 1480 5735 3440 1481 5736 3455 1479 5737 3436 1483 5738 3438 1478 5739 3441 1482 5740 3443 1479 5741 3436 1474 5742 3421 1486 5743 3423 1476 5744 3420 1474 5745 3421 1475 5746 3444 1488 5747 3445 1475 5748 3444 1477 5749 3446 1489 5750 3447 1486 5751 3423 1477 5752 3446 1476 5753 3420 1487 5754 3429 1490 5755 3450 1486 5756 3448 1488 5757 3430 1491 5758 3449 1487 5759 3429 1489 5760 3428 1493 5761 3451 1488 5762 3430 1486 5763 3431 1490 5764 3453 1489 5765 3428 1490 5766 3435 1492 5767 3433 1493 5768 3434 1496 5769 3461 1500 5770 3477 1494 5771 3464 1497 5772 3463 1501 5773 3474 1496 5774 3461 1495 5775 3462 1499 5776 3473 1497 5777 3491 1494 5778 3464 1498 5779 3478 1495 5780 3462 1498 5781 3478 1500 5782 3477 1504 5783 3479 1501 5784 3474 1505 5785 3476 1500 5786 3477 1503 5787 3475 1501 5788 3492 1499 5789 3473 1498 5790 3478 1502 5791 3480 1499 5792 3473 1494 5793 3458 1506 5794 3460 1496 5795 3457 1494 5796 3458 1495 5797 3484 1508 5798 3485 1495 5799 3484 1497 5800 3486 1509 5801 3487 1497 5802 3486 1496 5803 3457 1506 5804 3460 1507 5805 3466 1510 5806 3488 1506 5807 3468 1508 5808 3467 1511 5809 3483 1507 5810 3466 1509 5811 3465 1513 5812 3489 1508 5813 3481 1506 5814 3468 1510 5815 3488 1509 5816 3465 1510 5817 3472 1512 5818 3470 1513 5819 3471 1520 5820 3514 1514 5821 3501 1516 5822 3498 1517 5823 3500 1521 5824 3511 1516 5825 3498 1519 5826 3510 1517 5827 3500 1515 5828 3499 1514 5829 3518 1518 5830 3519 1515 5831 3499 1518 5832 3515 1520 5833 3514 1524 5834 3516 1521 5835 3511 1525 5836 3513 1520 5837 3514 1523 5838 3512 1521 5839 3511 1519 5840 3510 1518 5841 3519 1522 5842 3520 1519 5843 3510 1514 5844 3495 1526 5845 3497 1516 5846 3494 1514 5847 3495 1515 5848 3521 1528 5849 3522 1515 5850 3521 1517 5851 3523 1529 5852 3524 1516 5853 3494 1529 5854 3524 1517 5855 3523 1527 5856 3503 1530 5857 3526 1526 5858 3505 1528 5859 3504 1531 5860 3525 1527 5861 3503 1529 5862 3502 1533 5863 3527 1528 5864 3529 1526 5865 3505 1530 5866 3526 1529 5867 3502 1530 5868 3509 1532 5869 3507 1533 5870 3508 1536 5871 3535 1540 5872 3551 1534 5873 3538 1537 5874 3537 1541 5875 3548 1536 5876 3535 1535 5877 3536 1539 5878 3547 1537 5879 3537 1534 5880 3565 1538 5881 3566 1535 5882 3536 1544 5883 3553 1538 5884 3552 1540 5885 3551 1541 5886 3548 1545 5887 3550 1540 5888 3551 1541 5889 3548 1539 5890 3547 1543 5891 3549 1538 5892 3566 1542 5893 3567 1539 5894 3547 1534 5895 3532 1546 5896 3534 1536 5897 3531 1534 5898 3532 1535 5899 3555 1548 5900 3556 1535 5901 3555 1537 5902 3557 1549 5903 3558 1536 5904 3531 1549 5905 3558 1537 5906 3557 1547 5907 3540 1550 5908 3560 1546 5909 3542 1548 5910 3541 1551 5911 3559 1547 5912 3540 1549 5913 3539 1553 5914 3562 1548 5915 3561 1546 5916 3542 1550 5917 3560 1549 5918 3539 1550 5919 3546 1552 5920 3544 1553 5921 3545 1556 5922 3572 1560 5923 3588 1554 5924 3575 1557 5925 3574 1561 5926 3585 1556 5927 3572 1555 5928 3573 1559 5929 3584 1557 5930 3602 1554 5931 3575 1558 5932 3589 1555 5933 3573 1564 5934 3590 1558 5935 3589 1560 5936 3588 1561 5937 3585 1565 5938 3587 1560 5939 3588 1561 5940 3603 1559 5941 3584 1563 5942 3586 1558 5943 3589 1562 5944 3591 1559 5945 3584 1554 5946 3569 1566 5947 3571 1556 5948 3568 1554 5949 3569 1555 5950 3592 1568 5951 3593 1555 5952 3592 1557 5953 3594 1569 5954 3595 1566 5955 3571 1557 5956 3594 1556 5957 3568 1567 5958 3577 1570 5959 3598 1566 5960 3596 1568 5961 3578 1571 5962 3597 1567 5963 3577 1569 5964 3576 1573 5965 3599 1568 5966 3578 1566 5967 3579 1570 5968 3601 1569 5969 3576 1570 5970 3583 1572 5971 3581 1573 5972 3582 1576 5973 3609 1580 5974 3625 1574 5975 3612 1577 5976 3611 1581 5977 3622 1576 5978 3609 1575 5979 3610 1579 5980 3621 1577 5981 3639 1574 5982 3612 1578 5983 3626 1575 5984 3610 1578 5985 3626 1580 5986 3625 1584 5987 3627 1581 5988 3622 1585 5989 3624 1580 5990 3625 1583 5991 3623 1581 5992 3640 1579 5993 3621 1578 5994 3626 1582 5995 3628 1579 5996 3621 1574 5997 3606 1586 5998 3608 1576 5999 3605 1574 6000 3606 1575 6001 3632 1588 6002 3633 1575 6003 3632 1577 6004 3634 1589 6005 3635 1577 6006 3634 1576 6007 3605 1586 6008 3608 1587 6009 3614 1590 6010 3636 1586 6011 3616 1588 6012 3615 1591 6013 3631 1587 6014 3614 1589 6015 3613 1593 6016 3637 1588 6017 3629 1586 6018 3616 1590 6019 3636 1589 6020 3613 1590 6021 3620 1592 6022 3618 1593 6023 3619 1600 6024 3662 1594 6025 3649 1596 6026 3646 1597 6027 3648 1601 6028 3659 1596 6029 3646 1599 6030 3658 1597 6031 3648 1595 6032 3647 1594 6033 3666 1598 6034 3667 1595 6035 3647 1598 6036 3663 1600 6037 3662 1604 6038 3664 1601 6039 3659 1605 6040 3661 1600 6041 3662 1603 6042 3660 1601 6043 3659 1599 6044 3658 1598 6045 3667 1602 6046 3668 1599 6047 3658 1594 6048 3643 1606 6049 3645 1596 6050 3642 1594 6051 3643 1595 6052 3669 1608 6053 3670 1595 6054 3669 1597 6055 3671 1609 6056 3672 1596 6057 3642 1609 6058 3672 1597 6059 3671 1607 6060 3651 1610 6061 3674 1606 6062 3653 1608 6063 3652 1611 6064 3673 1607 6065 3651 1609 6066 3650 1613 6067 3675 1608 6068 3677 1606 6069 3653 1610 6070 3674 1609 6071 3650 1610 6072 3657 1612 6073 3655 1613 6074 3656 1616 6075 3683 1620 6076 3699 1614 6077 3686 1617 6078 3685 1621 6079 3696 1616 6080 3683 1615 6081 3684 1619 6082 3695 1617 6083 3685 1614 6084 3713 1618 6085 3714 1615 6086 3684 1624 6087 3701 1618 6088 3700 1620 6089 3699 1621 6090 3696 1625 6091 3698 1620 6092 3699 1621 6093 3696 1619 6094 3695 1623 6095 3697 1618 6096 3714 1622 6097 3715 1619 6098 3695 1614 6099 3680 1626 6100 3682 1616 6101 3679 1614 6102 3680 1615 6103 3703 1628 6104 3704 1615 6105 3703 1617 6106 3705 1629 6107 3706 1616 6108 3679 1629 6109 3706 1617 6110 3705 1627 6111 3688 1630 6112 3708 1626 6113 3690 1628 6114 3689 1631 6115 3707 1627 6116 3688 1629 6117 3687 1633 6118 3710 1628 6119 3709 1626 6120 3690 1630 6121 3708 1629 6122 3687 1630 6123 3694 1632 6124 3692 1633 6125 3693 1636 6126 3720 1640 6127 3736 1634 6128 3723 1637 6129 3722 1641 6130 3733 1636 6131 3720 1635 6132 3721 1639 6133 3732 1637 6134 3750 1634 6135 3723 1638 6136 3737 1635 6137 3721 1644 6138 3738 1638 6139 3737 1640 6140 3736 1641 6141 3733 1645 6142 3735 1640 6143 3736 1641 6144 3751 1639 6145 3732 1643 6146 3734 1638 6147 3737 1642 6148 3739 1639 6149 3732 1634 6150 3717 1646 6151 3719 1636 6152 3716 1634 6153 3717 1635 6154 3740 1648 6155 3741 1635 6156 3740 1637 6157 3742 1649 6158 3743 1646 6159 3719 1637 6160 3742 1636 6161 3716 1647 6162 3725 1650 6163 3746 1646 6164 3744 1648 6165 3726 1651 6166 3745 1647 6167 3725 1649 6168 3724 1653 6169 3747 1648 6170 3726 1646 6171 3727 1650 6172 3749 1649 6173 3724 1650 6174 3731 1652 6175 3729 1653 6176 3730 1656 6177 3757 1660 6178 3773 1654 6179 3760 1657 6180 3759 1661 6181 3770 1656 6182 3757 1655 6183 3758 1659 6184 3769 1657 6185 3787 1654 6186 3760 1658 6187 3774 1655 6188 3758 1658 6189 3774 1660 6190 3773 1664 6191 3775 1661 6192 3770 1665 6193 3772 1660 6194 3773 1663 6195 3771 1661 6196 3788 1659 6197 3769 1658 6198 3774 1662 6199 3776 1659 6200 3769 1654 6201 3754 1666 6202 3756 1656 6203 3753 1654 6204 3754 1655 6205 3780 1668 6206 3781 1655 6207 3780 1657 6208 3782 1669 6209 3783 1657 6210 3782 1656 6211 3753 1666 6212 3756 1667 6213 3762 1670 6214 3784 1666 6215 3764 1668 6216 3763 1671 6217 3779 1667 6218 3762 1669 6219 3761 1673 6220 3785 1668 6221 3777 1666 6222 3764 1670 6223 3784 1669 6224 3761 1670 6225 3768 1672 6226 3766 1673 6227 3767 1680 6228 3810 1674 6229 3797 1676 6230 3794 1677 6231 3796 1681 6232 3807 1676 6233 3794 1679 6234 3806 1677 6235 3796 1675 6236 3795 1674 6237 3814 1678 6238 3815 1675 6239 3795 1678 6240 3811 1680 6241 3810 1684 6242 3812 1681 6243 3807 1685 6244 3809 1680 6245 3810 1683 6246 3808 1681 6247 3807 1679 6248 3806 1678 6249 3815 1682 6250 3816 1679 6251 3806 1674 6252 3791 1686 6253 3793 1676 6254 3790 1674 6255 3791 1675 6256 3817 1688 6257 3818 1675 6258 3817 1677 6259 3819 1689 6260 3820 1676 6261 3790 1689 6262 3820 1677 6263 3819 1687 6264 3799 1690 6265 3822 1686 6266 3801 1688 6267 3800 1691 6268 3821 1687 6269 3799 1689 6270 3798 1693 6271 3823 1688 6272 3825 1686 6273 3801 1690 6274 3822 1689 6275 3798 1690 6276 3805 1692 6277 3803 1693 6278 3804 1696 6279 3831 1700 6280 3847 1694 6281 3834 1697 6282 3833 1701 6283 3844 1696 6284 3831 1695 6285 3832 1699 6286 3843 1697 6287 3833 1694 6288 3861 1698 6289 3862 1695 6290 3832 1704 6291 3849 1698 6292 3848 1700 6293 3847 1701 6294 3844 1705 6295 3846 1700 6296 3847 1701 6297 3844 1699 6298 3843 1703 6299 3845 1698 6300 3862 1702 6301 3863 1699 6302 3843 1694 6303 3828 1706 6304 3830 1696 6305 3827 1694 6306 3828 1695 6307 3851 1708 6308 3852 1695 6309 3851 1697 6310 3853 1709 6311 3854 1696 6312 3827 1709 6313 3854 1697 6314 3853 1707 6315 3836 1710 6316 3856 1706 6317 3838 1708 6318 3837 1711 6319 3855 1707 6320 3836 1709 6321 3835 1713 6322 3858 1708 6323 3857 1706 6324 3838 1710 6325 3856 1709 6326 3835 1710 6327 3842 1712 6328 3840 1713 6329 3841 1716 6330 3868 1720 6331 3884 1714 6332 3871 1717 6333 3870 1721 6334 3881 1716 6335 3868 1715 6336 3869 1719 6337 3880 1717 6338 3898 1714 6339 3871 1718 6340 3885 1715 6341 3869 1724 6342 3886 1718 6343 3885 1720 6344 3884 1721 6345 3881 1725 6346 3883 1720 6347 3884 1721 6348 3899 1719 6349 3880 1723 6350 3882 1718 6351 3885 1722 6352 3887 1719 6353 3880 1714 6354 3865 1726 6355 3867 1716 6356 3864 1714 6357 3865 1715 6358 3888 1728 6359 3889 1715 6360 3888 1717 6361 3890 1729 6362 3891 1726 6363 3867 1717 6364 3890 1716 6365 3864 1727 6366 3873 1730 6367 3894 1726 6368 3892 1728 6369 3874 1731 6370 3893 1727 6371 3873 1729 6372 3872 1733 6373 3895 1728 6374 3874 1726 6375 3875 1730 6376 3897 1729 6377 3872 1730 6378 3879 1732 6379 3877 1733 6380 3878 1736 6381 3905 1740 6382 3921 1734 6383 3908 1737 6384 3907 1741 6385 3918 1736 6386 3905 1735 6387 3906 1739 6388 3917 1737 6389 3935 1734 6390 3908 1738 6391 3922 1735 6392 3906 1738 6393 3922 1740 6394 3921 1744 6395 3923 1741 6396 3918 1745 6397 3920 1740 6398 3921 1743 6399 3919 1741 6400 3936 1739 6401 3917 1738 6402 3922 1742 6403 3924 1739 6404 3917 1734 6405 3902 1746 6406 3904 1736 6407 3901 1734 6408 3902 1735 6409 3928 1748 6410 3929 1735 6411 3928 1737 6412 3930 1749 6413 3931 1737 6414 3930 1736 6415 3901 1746 6416 3904 1747 6417 3910 1750 6418 3932 1746 6419 3912 1748 6420 3911 1751 6421 3927 1747 6422 3910 1749 6423 3909 1753 6424 3933 1748 6425 3925 1746 6426 3912 1750 6427 3932 1749 6428 3909 1750 6429 3916 1752 6430 3914 1753 6431 3915 1760 6432 3958 1754 6433 3945 1756 6434 3942 1757 6435 3944 1761 6436 3955 1756 6437 3942 1759 6438 3954 1757 6439 3944 1755 6440 3943 1754 6441 3962 1758 6442 3963 1755 6443 3943 1758 6444 3959 1760 6445 3958 1764 6446 3960 1761 6447 3955 1765 6448 3957 1760 6449 3958 1763 6450 3956 1761 6451 3955 1759 6452 3954 1758 6453 3963 1762 6454 3964 1759 6455 3954 1754 6456 3939 1766 6457 3941 1756 6458 3938 1754 6459 3939 1755 6460 3965 1768 6461 3966 1755 6462 3965 1757 6463 3967 1769 6464 3968 1756 6465 3938 1769 6466 3968 1757 6467 3967 1767 6468 3947 1770 6469 3970 1766 6470 3949 1768 6471 3948 1771 6472 3969 1767 6473 3947 1769 6474 3946 1773 6475 3971 1768 6476 3973 1766 6477 3949 1770 6478 3970 1769 6479 3946 1770 6480 3953 1772 6481 3951 1773 6482 3952 1776 6483 3979 1780 6484 3995 1774 6485 3982 1777 6486 3981 1781 6487 3992 1776 6488 3979 1775 6489 3980 1779 6490 3991 1777 6491 3981 1774 6492 4009 1778 6493 4010 1775 6494 3980 1784 6495 3997 1778 6496 3996 1780 6497 3995 1781 6498 3992 1785 6499 3994 1780 6500 3995 1781 6501 3992 1779 6502 3991 1783 6503 3993 1778 6504 4010 1782 6505 4011 1779 6506 3991 1774 6507 3976 1786 6508 3978 1776 6509 3975 1774 6510 3976 1775 6511 3999 1788 6512 4000 1775 6513 3999 1777 6514 4001 1789 6515 4002 1776 6516 3975 1789 6517 4002 1777 6518 4001 1787 6519 3984 1790 6520 4004 1786 6521 3986 1788 6522 3985 1791 6523 4003 1787 6524 3984 1789 6525 3983 1793 6526 4006 1788 6527 4005 1786 6528 3986 1790 6529 4004 1789 6530 3983 1790 6531 3990 1792 6532 3988 1793 6533 3989 1796 6534 4016 1800 6535 4032 1794 6536 4019 1797 6537 4018 1801 6538 4029 1796 6539 4016 1795 6540 4017 1799 6541 4028 1797 6542 4046 1794 6543 4019 1798 6544 4033 1795 6545 4017 1804 6546 4034 1798 6547 4033 1800 6548 4032 1801 6549 4029 1805 6550 4031 1800 6551 4032 1801 6552 4047 1799 6553 4028 1803 6554 4030 1798 6555 4033 1802 6556 4035 1799 6557 4028 1794 6558 4013 1806 6559 4015 1796 6560 4012 1794 6561 4013 1795 6562 4036 1808 6563 4037 1795 6564 4036 1797 6565 4038 1809 6566 4039 1806 6567 4015 1797 6568 4038 1796 6569 4012 1807 6570 4021 1810 6571 4042 1806 6572 4040 1808 6573 4022 1811 6574 4041 1807 6575 4021 1809 6576 4020 1813 6577 4043 1808 6578 4022 1806 6579 4023 1810 6580 4045 1809 6581 4020 1810 6582 4027 1812 6583 4025 1813 6584 4026 1816 6585 4053 1820 6586 4069 1814 6587 4056 1817 6588 4055 1821 6589 4066 1816 6590 4053 1815 6591 4054 1819 6592 4065 1817 6593 4083 1814 6594 4056 1818 6595 4070 1815 6596 4054 1818 6597 4070 1820 6598 4069 1824 6599 4071 1821 6600 4066 1825 6601 4068 1820 6602 4069 1823 6603 4067 1821 6604 4084 1819 6605 4065 1818 6606 4070 1822 6607 4072 1819 6608 4065 1814 6609 4050 1826 6610 4052 1816 6611 4049 1814 6612 4050 1815 6613 4076 1828 6614 4077 1815 6615 4076 1817 6616 4078 1829 6617 4079 1817 6618 4078 1816 6619 4049 1826 6620 4052 1827 6621 4058 1830 6622 4080 1826 6623 4060 1828 6624 4059 1831 6625 4075 1827 6626 4058 1829 6627 4057 1833 6628 4081 1828 6629 4073 1826 6630 4060 1830 6631 4080 1829 6632 4057 1830 6633 4064 1832 6634 4062 1833 6635 4063 1836 6636 4090 1840 6637 4106 1834 6638 4093 1837 6639 4092 1841 6640 4103 1836 6641 4090 1835 6642 4091 1839 6643 4102 1837 6644 4092 1834 6645 4120 1838 6646 4121 1835 6647 4091 1844 6648 4108 1838 6649 4107 1840 6650 4106 1841 6651 4103 1845 6652 4105 1840 6653 4106 1841 6654 4103 1839 6655 4102 1843 6656 4104 1838 6657 4121 1842 6658 4122 1839 6659 4102 1834 6660 4087 1846 6661 4089 1836 6662 4086 1834 6663 4087 1835 6664 4110 1848 6665 4111 1835 6666 4110 1837 6667 4112 1849 6668 4113 1836 6669 4086 1849 6670 4113 1837 6671 4112 1847 6672 4095 1850 6673 4115 1846 6674 4097 1848 6675 4096 1851 6676 4114 1847 6677 4095 1849 6678 4094 1853 6679 4117 1848 6680 4116 1846 6681 4097 1850 6682 4115 1849 6683 4094 1850 6684 4101 1852 6685 4099 1853 6686 4100 1856 6687 4127 1860 6688 4143 1854 6689 4130 1857 6690 4129 1861 6691 4140 1856 6692 4127 1855 6693 4128 1859 6694 4139 1857 6695 4157 1854 6696 4130 1858 6697 4144 1855 6698 4128 1864 6699 4145 1858 6700 4144 1860 6701 4143 1861 6702 4140 1865 6703 4142 1860 6704 4143 1861 6705 4158 1859 6706 4139 1863 6707 4141 1858 6708 4144 1862 6709 4146 1859 6710 4139 1854 6711 4124 1866 6712 4126 1856 6713 4123 1854 6714 4124 1855 6715 4147 1868 6716 4148 1855 6717 4147 1857 6718 4149 1869 6719 4150 1866 6720 4126 1857 6721 4149 1856 6722 4123 1867 6723 4132 1870 6724 4153 1866 6725 4151 1868 6726 4133 1871 6727 4152 1867 6728 4132 1869 6729 4131 1873 6730 4154 1868 6731 4133 1866 6732 4134 1870 6733 4156 1869 6734 4131 1870 6735 4138 1872 6736 4136 1873 6737 4137 1876 6738 4164 1880 6739 4180 1874 6740 4167 1877 6741 4166 1881 6742 4177 1876 6743 4164 1875 6744 4165 1879 6745 4176 1877 6746 4194 1874 6747 4167 1878 6748 4181 1875 6749 4165 1878 6750 4181 1880 6751 4180 1884 6752 4182 1881 6753 4177 1885 6754 4179 1880 6755 4180 1883 6756 4178 1881 6757 4195 1879 6758 4176 1878 6759 4181 1882 6760 4183 1879 6761 4176 1874 6762 4161 1886 6763 4163 1876 6764 4160 1874 6765 4161 1875 6766 4187 1888 6767 4188 1875 6768 4187 1877 6769 4189 1889 6770 4190 1877 6771 4189 1876 6772 4160 1886 6773 4163 1887 6774 4169 1890 6775 4191 1886 6776 4171 1888 6777 4170 1891 6778 4186 1887 6779 4169 1889 6780 4168 1893 6781 4192 1888 6782 4184 1886 6783 4171 1890 6784 4191 1889 6785 4168 1890 6786 4175 1892 6787 4173 1893 6788 4174 1900 6789 4217 1894 6790 4204 1896 6791 4201 1897 6792 4203 1901 6793 4214 1896 6794 4201 1899 6795 4213 1897 6796 4203 1895 6797 4202 1894 6798 4221 1898 6799 4222 1895 6800 4202 1898 6801 4218 1900 6802 4217 1904 6803 4219 1901 6804 4214 1905 6805 4216 1900 6806 4217 1903 6807 4215 1901 6808 4214 1899 6809 4213 1898 6810 4222 1902 6811 4223 1899 6812 4213 1894 6813 4198 1906 6814 4200 1896 6815 4197 1894 6816 4198 1895 6817 4224 1908 6818 4225 1895 6819 4224 1897 6820 4226 1909 6821 4227 1896 6822 4197 1909 6823 4227 1897 6824 4226 1907 6825 4206 1910 6826 4229 1906 6827 4208 1908 6828 4207 1911 6829 4228 1907 6830 4206 1909 6831 4205 1913 6832 4230 1908 6833 4232 1906 6834 4208 1910 6835 4229 1909 6836 4205 1910 6837 4212 1912 6838 4210 1913 6839 4211 1916 6840 4238 1920 6841 4254 1914 6842 4241 1917 6843 4240 1921 6844 4251 1916 6845 4238 1915 6846 4239 1919 6847 4250 1917 6848 4240 1914 6849 4268 1918 6850 4269 1915 6851 4239 1924 6852 4256 1918 6853 4255 1920 6854 4254 1921 6855 4251 1925 6856 4253 1920 6857 4254 1921 6858 4251 1919 6859 4250 1923 6860 4252 1918 6861 4269 1922 6862 4270 1919 6863 4250 1914 6864 4235 1926 6865 4237 1916 6866 4234 1914 6867 4235 1915 6868 4258 1928 6869 4259 1915 6870 4258 1917 6871 4260 1929 6872 4261 1916 6873 4234 1929 6874 4261 1917 6875 4260 1927 6876 4243 1930 6877 4263 1926 6878 4245 1928 6879 4244 1931 6880 4262 1927 6881 4243 1929 6882 4242 1933 6883 4265 1928 6884 4264 1926 6885 4245 1930 6886 4263 1929 6887 4242 1930 6888 4249 1932 6889 4247 1933 6890 4248 1936 6891 4275 1940 6892 4291 1934 6893 4278 1937 6894 4277 1941 6895 4288 1936 6896 4275 1935 6897 4276 1939 6898 4287 1937 6899 4305 1934 6900 4278 1938 6901 4292 1935 6902 4276 1938 6903 4292 1940 6904 4291 1944 6905 4293 1941 6906 4288 1945 6907 4290 1940 6908 4291 1943 6909 4289 1941 6910 4306 1939 6911 4287 1938 6912 4292 1942 6913 4294 1939 6914 4287 1934 6915 4272 1946 6916 4274 1936 6917 4271 1934 6918 4272 1935 6919 4298 1948 6920 4299 1935 6921 4298 1937 6922 4300 1949 6923 4301 1937 6924 4300 1936 6925 4271 1946 6926 4274 1947 6927 4280 1950 6928 4302 1946 6929 4282 1948 6930 4281 1951 6931 4297 1947 6932 4280 1949 6933 4279 1953 6934 4303 1948 6935 4295 1946 6936 4282 1950 6937 4302 1949 6938 4279 1950 6939 4286 1952 6940 4284 1953 6941 4285 1960 6942 4328 1954 6943 4315 1956 6944 4312 1957 6945 4314 1961 6946 4325 1956 6947 4312 1959 6948 4324 1957 6949 4314 1955 6950 4313 1954 6951 4332 1958 6952 4333 1955 6953 4313 1958 6954 4329 1960 6955 4328 1964 6956 4330 1961 6957 4325 1965 6958 4327 1960 6959 4328 1963 6960 4326 1961 6961 4325 1959 6962 4324 1958 6963 4333 1962 6964 4334 1959 6965 4324 1954 6966 4309 1966 6967 4311 1956 6968 4308 1954 6969 4309 1955 6970 4335 1968 6971 4336 1955 6972 4335 1957 6973 4337 1969 6974 4338 1956 6975 4308 1969 6976 4338 1957 6977 4337 1967 6978 4317 1970 6979 4340 1966 6980 4319 1968 6981 4318 1971 6982 4339 1967 6983 4317 1969 6984 4316 1973 6985 4341 1968 6986 4343 1966 6987 4319 1970 6988 4340 1969 6989 4316 1970 6990 4323 1972 6991 4321 1973 6992 4322 1976 6993 4349 1980 6994 4365 1974 6995 4352 1977 6996 4351 1981 6997 4362 1976 6998 4349 1975 6999 4350 1979 7000 4361 1977 7001 4351 1974 7002 4379 1978 7003 4380 1975 7004 4350 1984 7005 4367 1978 7006 4366 1980 7007 4365 1981 7008 4362 1985 7009 4364 1980 7010 4365 1981 7011 4362 1979 7012 4361 1983 7013 4363 1978 7014 4380 1982 7015 4381 1979 7016 4361 1974 7017 4346 1986 7018 4348 1976 7019 4345 1974 7020 4346 1975 7021 4369 1988 7022 4370 1975 7023 4369 1977 7024 4371 1989 7025 4372 1976 7026 4345 1989 7027 4372 1977 7028 4371 1987 7029 4354 1990 7030 4374 1986 7031 4356 1988 7032 4355 1991 7033 4373 1987 7034 4354 1989 7035 4353 1993 7036 4376 1988 7037 4375 1986 7038 4356 1990 7039 4374 1989 7040 4353 1990 7041 4360 1992 7042 4358 1993 7043 4359 1996 7044 4386 2000 7045 4402 1994 7046 4389 1997 7047 4388 2001 7048 4399 1996 7049 4386 1995 7050 4387 1999 7051 4398 1997 7052 4416 1994 7053 4389 1998 7054 4403 1995 7055 4387 2004 7056 4404 1998 7057 4403 2000 7058 4402 2001 7059 4399 2005 7060 4401 2000 7061 4402 2001 7062 4417 1999 7063 4398 2003 7064 4400 1998 7065 4403 2002 7066 4405 1999 7067 4398 1994 7068 4383 2006 7069 4385 1996 7070 4382 1994 7071 4383 1995 7072 4406 2008 7073 4407 1995 7074 4406 1997 7075 4408 2009 7076 4409 2006 7077 4385 1997 7078 4408 1996 7079 4382 2007 7080 4391 2010 7081 4412 2006 7082 4410 2008 7083 4392 2011 7084 4411 2007 7085 4391 2009 7086 4390 2013 7087 4413 2008 7088 4392 2006 7089 4393 2010 7090 4415 2009 7091 4390 2010 7092 4397 2012 7093 4395 2013 7094 4396 2016 7095 4423 2020 7096 4439 2014 7097 4426 2017 7098 4425 2021 7099 4436 2016 7100 4423 2015 7101 4424 2019 7102 4435 2017 7103 4453 2014 7104 4426 2018 7105 4440 2015 7106 4424 2018 7107 4440 2020 7108 4439 2024 7109 4441 2021 7110 4436 2025 7111 4438 2020 7112 4439 2023 7113 4437 2021 7114 4454 2019 7115 4435 2018 7116 4440 2022 7117 4442 2019 7118 4435 2014 7119 4420 2026 7120 4422 2016 7121 4419 2014 7122 4420 2015 7123 4446 2028 7124 4447 2015 7125 4446 2017 7126 4448 2029 7127 4449 2017 7128 4448 2016 7129 4419 2026 7130 4422 2027 7131 4428 2030 7132 4450 2026 7133 4430 2028 7134 4429 2031 7135 4445 2027 7136 4428 2029 7137 4427 2033 7138 4451 2028 7139 4443 2026 7140 4430 2030 7141 4450 2029 7142 4427 2030 7143 4434 2032 7144 4432 2033 7145 4433 2040 7146 4476 2034 7147 4463 2036 7148 4460 2037 7149 4462 2041 7150 4473 2036 7151 4460 2039 7152 4472 2037 7153 4462 2035 7154 4461 2034 7155 4480 2038 7156 4481 2035 7157 4461 2038 7158 4477 2040 7159 4476 2044 7160 4478 2041 7161 4473 2045 7162 4475 2040 7163 4476 2043 7164 4474 2041 7165 4473 2039 7166 4472 2038 7167 4481 2042 7168 4482 2039 7169 4472 2034 7170 4457 2046 7171 4459 2036 7172 4456 2034 7173 4457 2035 7174 4483 2048 7175 4484 2035 7176 4483 2037 7177 4485 2049 7178 4486 2036 7179 4456 2049 7180 4486 2037 7181 4485 2047 7182 4465 2050 7183 4488 2046 7184 4467 2048 7185 4466 2051 7186 4487 2047 7187 4465 2049 7188 4464 2053 7189 4489 2048 7190 4491 2046 7191 4467 2050 7192 4488 2049 7193 4464 2050 7194 4471 2052 7195 4469 2053 7196 4470 2056 7197 4497 2060 7198 4513 2054 7199 4500 2057 7200 4499 2061 7201 4510 2056 7202 4497 2055 7203 4498 2059 7204 4509 2057 7205 4499 2054 7206 4527 2058 7207 4528 2055 7208 4498 2064 7209 4515 2058 7210 4514 2060 7211 4513 2061 7212 4510 2065 7213 4512 2060 7214 4513 2061 7215 4510 2059 7216 4509 2063 7217 4511 2058 7218 4528 2062 7219 4529 2059 7220 4509 2054 7221 4494 2066 7222 4496 2056 7223 4493 2054 7224 4494 2055 7225 4517 2068 7226 4518 2055 7227 4517 2057 7228 4519 2069 7229 4520 2056 7230 4493 2069 7231 4520 2057 7232 4519 2067 7233 4502 2070 7234 4522 2066 7235 4504 2068 7236 4503 2071 7237 4521 2067 7238 4502 2069 7239 4501 2073 7240 4524 2068 7241 4523 2066 7242 4504 2070 7243 4522 2069 7244 4501 2070 7245 4508 2072 7246 4506 2073 7247 4507 1640 7248 3736 1638 7249 3737 1634 7250 3723 1641 7251 3733 1640 7252 3736 1636 7253 3720 1639 7254 3732 1641 7255 3751 1637 7256 3750 1638 7257 3737 1639 7258 3732 1635 7259 3721 1644 7260 3738 1642 7261 3739 1638 7262 3737 1645 7263 3735 1644 7264 3738 1640 7265 3736 1643 7266 3734 1645 7267 3752 1641 7268 3751 1642 7269 3739 1643 7270 3734 1639 7271 3732 1634 7272 3717 1647 7273 3718 1646 7274 3719 1648 7275 3741 1647 7276 3718 1634 7277 3717 1649 7278 3743 1648 7279 3741 1635 7280 3740 1646 7281 3719 1649 7282 3743 1637 7283 3742 1647 7284 3725 1651 7285 3745 1650 7286 3746 1648 7287 3726 1652 7288 3748 1651 7289 3745 1653 7290 3747 1652 7291 3748 1648 7292 3726 1650 7293 3749 1653 7294 3747 1649 7295 3724 1650 7296 3731 1651 7297 3728 1652 7298 3729 1660 7299 3773 1658 7300 3774 1654 7301 3760 1661 7302 3770 1660 7303 3773 1656 7304 3757 1659 7305 3769 1661 7306 3788 1657 7307 3787 1658 7308 3774 1659 7309 3769 1655 7310 3758 1664 7311 3775 1662 7312 3776 1658 7313 3774 1665 7314 3772 1664 7315 3775 1660 7316 3773 1663 7317 3771 1665 7318 3789 1661 7319 3788 1662 7320 3776 1663 7321 3771 1659 7322 3769 1654 7323 3754 1667 7324 3755 1666 7325 3756 1668 7326 3781 1667 7327 3755 1654 7328 3754 1669 7329 3783 1668 7330 3781 1655 7331 3780 1666 7332 3756 1669 7333 3783 1657 7334 3782 1667 7335 3762 1671 7336 3779 1670 7337 3784 1668 7338 3763 1672 7339 3786 1671 7340 3779 1673 7341 3785 1672 7342 3778 1668 7343 3777 1670 7344 3784 1673 7345 3785 1669 7346 3761 1670 7347 3768 1671 7348 3765 1672 7349 3766 1680 7350 3810 1678 7351 3811 1674 7352 3797 1681 7353 3807 1680 7354 3810 1676 7355 3794 1679 7356 3806 1681 7357 3807 1677 7358 3796 1678 7359 3815 1679 7360 3806 1675 7361 3795 1684 7362 3812 1682 7363 3813 1678 7364 3811 1685 7365 3809 1684 7366 3812 1680 7367 3810 1683 7368 3808 1685 7369 3809 1681 7370 3807 1682 7371 3816 1683 7372 3808 1679 7373 3806 1674 7374 3791 1687 7375 3792 1686 7376 3793 1688 7377 3818 1687 7378 3792 1674 7379 3791 1689 7380 3820 1688 7381 3818 1675 7382 3817 1676 7383 3790 1686 7384 3793 1689 7385 3820 1687 7386 3799 1691 7387 3821 1690 7388 3822 1688 7389 3800 1692 7390 3824 1691 7391 3821 1693 7392 3823 1692 7393 3826 1688 7394 3825 1690 7395 3822 1693 7396 3823 1689 7397 3798 1690 7398 3805 1691 7399 3802 1692 7400 3803 1700 7401 3847 1698 7402 3848 1694 7403 3834 1701 7404 3844 1700 7405 3847 1696 7406 3831 1699 7407 3843 1701 7408 3844 1697 7409 3833 1698 7410 3862 1699 7411 3843 1695 7412 3832 1704 7413 3849 1702 7414 3850 1698 7415 3848 1705 7416 3846 1704 7417 3849 1700 7418 3847 1703 7419 3845 1705 7420 3846 1701 7421 3844 1702 7422 3863 1703 7423 3845 1699 7424 3843 1694 7425 3828 1707 7426 3829 1706 7427 3830 1708 7428 3852 1707 7429 3829 1694 7430 3828 1709 7431 3854 1708 7432 3852 1695 7433 3851 1696 7434 3827 1706 7435 3830 1709 7436 3854 1707 7437 3836 1711 7438 3855 1710 7439 3856 1708 7440 3837 1712 7441 3860 1711 7442 3855 1713 7443 3858 1712 7444 3859 1708 7445 3857 1710 7446 3856 1713 7447 3858 1709 7448 3835 1710 7449 3842 1711 7450 3839 1712 7451 3840 1720 7452 3884 1718 7453 3885 1714 7454 3871 1721 7455 3881 1720 7456 3884 1716 7457 3868 1719 7458 3880 1721 7459 3899 1717 7460 3898 1718 7461 3885 1719 7462 3880 1715 7463 3869 1724 7464 3886 1722 7465 3887 1718 7466 3885 1725 7467 3883 1724 7468 3886 1720 7469 3884 1723 7470 3882 1725 7471 3900 1721 7472 3899 1722 7473 3887 1723 7474 3882 1719 7475 3880 1714 7476 3865 1727 7477 3866 1726 7478 3867 1728 7479 3889 1727 7480 3866 1714 7481 3865 1729 7482 3891 1728 7483 3889 1715 7484 3888 1726 7485 3867 1729 7486 3891 1717 7487 3890 1727 7488 3873 1731 7489 3893 1730 7490 3894 1728 7491 3874 1732 7492 3896 1731 7493 3893 1733 7494 3895 1732 7495 3896 1728 7496 3874 1730 7497 3897 1733 7498 3895 1729 7499 3872 1730 7500 3879 1731 7501 3876 1732 7502 3877 1738 7503 3922 1739 7504 3917 1735 7505 3906 1742 7506 3924 1743 7507 3919 1739 7508 3917 1748 7509 3929 1747 7510 3903 1734 7511 3902 1748 7512 3911 1752 7513 3934 1751 7514 3927 1758 7515 3963 1759 7516 3954 1755 7517 3943 1762 7518 3964 1763 7519 3956 1759 7520 3954 1768 7521 3966 1767 7522 3940 1754 7523 3939 1768 7524 3948 1772 7525 3972 1771 7526 3969 1780 7527 3995 1778 7528 3996 1774 7529 3982 1781 7530 3992 1780 7531 3995 1776 7532 3979 1779 7533 3991 1781 7534 3992 1777 7535 3981 1778 7536 4010 1779 7537 3991 1775 7538 3980 1784 7539 3997 1782 7540 3998 1778 7541 3996 1785 7542 3994 1784 7543 3997 1780 7544 3995 1783 7545 3993 1785 7546 3994 1781 7547 3992 1782 7548 4011 1783 7549 3993 1779 7550 3991 1774 7551 3976 1787 7552 3977 1786 7553 3978 1788 7554 4000 1787 7555 3977 1774 7556 3976 1789 7557 4002 1788 7558 4000 1775 7559 3999 1776 7560 3975 1786 7561 3978 1789 7562 4002 1787 7563 3984 1791 7564 4003 1790 7565 4004 1788 7566 3985 1792 7567 4008 1791 7568 4003 1793 7569 4006 1792 7570 4007 1788 7571 4005 1790 7572 4004 1793 7573 4006 1789 7574 3983 1790 7575 3990 1791 7576 3987 1792 7577 3988 1821 7578 4066 1820 7579 4069 1816 7580 4053 1825 7581 4068 1824 7582 4071 1820 7583 4069 1826 7584 4052 1829 7585 4079 1817 7586 4078 1830 7587 4080 1833 7588 4081 1829 7589 4057 1740 7590 3921 1738 7591 3922 1734 7592 3908 1741 7593 3918 1740 7594 3921 1736 7595 3905 1739 7596 3917 1741 7597 3936 1737 7598 3935 1744 7599 3923 1742 7600 3924 1738 7601 3922 1745 7602 3920 1744 7603 3923 1740 7604 3921 1743 7605 3919 1745 7606 3937 1741 7607 3936 1734 7608 3902 1747 7609 3903 1746 7610 3904 1749 7611 3931 1748 7612 3929 1735 7613 3928 1746 7614 3904 1749 7615 3931 1737 7616 3930 1747 7617 3910 1751 7618 3927 1750 7619 3932 1753 7620 3933 1752 7621 3926 1748 7622 3925 1750 7623 3932 1753 7624 3933 1749 7625 3909 1750 7626 3916 1751 7627 3913 1752 7628 3914 1760 7629 3958 1758 7630 3959 1754 7631 3945 1761 7632 3955 1760 7633 3958 1756 7634 3942 1759 7635 3954 1761 7636 3955 1757 7637 3944 1764 7638 3960 1762 7639 3961 1758 7640 3959 1765 7641 3957 1764 7642 3960 1760 7643 3958 1763 7644 3956 1765 7645 3957 1761 7646 3955 1754 7647 3939 1767 7648 3940 1766 7649 3941 1769 7650 3968 1768 7651 3966 1755 7652 3965 1756 7653 3938 1766 7654 3941 1769 7655 3968 1767 7656 3947 1771 7657 3969 1770 7658 3970 1773 7659 3971 1772 7660 3974 1768 7661 3973 1770 7662 3970 1773 7663 3971 1769 7664 3946 1770 7665 3953 1771 7666 3950 1772 7667 3951 1800 7668 4032 1798 7669 4033 1794 7670 4019 1801 7671 4029 1800 7672 4032 1796 7673 4016 1799 7674 4028 1801 7675 4047 1797 7676 4046 1798 7677 4033 1799 7678 4028 1795 7679 4017 1804 7680 4034 1802 7681 4035 1798 7682 4033 1805 7683 4031 1804 7684 4034 1800 7685 4032 1803 7686 4030 1805 7687 4048 1801 7688 4047 1802 7689 4035 1803 7690 4030 1799 7691 4028 1794 7692 4013 1807 7693 4014 1806 7694 4015 1808 7695 4037 1807 7696 4014 1794 7697 4013 1809 7698 4039 1808 7699 4037 1795 7700 4036 1806 7701 4015 1809 7702 4039 1797 7703 4038 1807 7704 4021 1811 7705 4041 1810 7706 4042 1808 7707 4022 1812 7708 4044 1811 7709 4041 1813 7710 4043 1812 7711 4044 1808 7712 4022 1810 7713 4045 1813 7714 4043 1809 7715 4020 1810 7716 4027 1811 7717 4024 1812 7718 4025 1820 7719 4069 1818 7720 4070 1814 7721 4056 1819 7722 4065 1821 7723 4084 1817 7724 4083 1818 7725 4070 1819 7726 4065 1815 7727 4054 1824 7728 4071 1822 7729 4072 1818 7730 4070 1823 7731 4067 1825 7732 4085 1821 7733 4084 1822 7734 4072 1823 7735 4067 1819 7736 4065 1814 7737 4050 1827 7738 4051 1826 7739 4052 1828 7740 4077 1827 7741 4051 1814 7742 4050 1829 7743 4079 1828 7744 4077 1815 7745 4076 1827 7746 4058 1831 7747 4075 1830 7748 4080 1828 7749 4059 1832 7750 4082 1831 7751 4075 1833 7752 4081 1832 7753 4074 1828 7754 4073 1830 7755 4064 1831 7756 4061 1832 7757 4062 1840 7758 4106 1838 7759 4107 1834 7760 4093 1841 7761 4103 1840 7762 4106 1836 7763 4090 1839 7764 4102 1841 7765 4103 1837 7766 4092 1838 7767 4121 1839 7768 4102 1835 7769 4091 1844 7770 4108 1842 7771 4109 1838 7772 4107 1845 7773 4105 1844 7774 4108 1840 7775 4106 1843 7776 4104 1845 7777 4105 1841 7778 4103 1842 7779 4122 1843 7780 4104 1839 7781 4102 1834 7782 4087 1847 7783 4088 1846 7784 4089 1848 7785 4111 1847 7786 4088 1834 7787 4087 1849 7788 4113 1848 7789 4111 1835 7790 4110 1836 7791 4086 1846 7792 4089 1849 7793 4113 1847 7794 4095 1851 7795 4114 1850 7796 4115 1848 7797 4096 1852 7798 4119 1851 7799 4114 1853 7800 4117 1852 7801 4118 1848 7802 4116 1850 7803 4115 1853 7804 4117 1849 7805 4094 1850 7806 4101 1851 7807 4098 1852 7808 4099 1480 7809 3440 1478 7810 3441 1474 7811 3427 1481 7812 3437 1480 7813 3440 1476 7814 3424 1479 7815 3436 1481 7816 3455 1477 7817 3454 1478 7818 3441 1479 7819 3436 1475 7820 3425 1484 7821 3442 1482 7822 3443 1478 7823 3441 1485 7824 3439 1484 7825 3442 1480 7826 3440 1483 7827 3438 1485 7828 3456 1481 7829 3455 1482 7830 3443 1483 7831 3438 1479 7832 3436 1474 7833 3421 1487 7834 3422 1486 7835 3423 1488 7836 3445 1487 7837 3422 1474 7838 3421 1489 7839 3447 1488 7840 3445 1475 7841 3444 1486 7842 3423 1489 7843 3447 1477 7844 3446 1487 7845 3429 1491 7846 3449 1490 7847 3450 1488 7848 3430 1492 7849 3452 1491 7850 3449 1493 7851 3451 1492 7852 3452 1488 7853 3430 1490 7854 3453 1493 7855 3451 1489 7856 3428 1490 7857 3435 1491 7858 3432 1492 7859 3433 1500 7860 3477 1498 7861 3478 1494 7862 3464 1501 7863 3474 1500 7864 3477 1496 7865 3461 1499 7866 3473 1501 7867 3492 1497 7868 3491 1498 7869 3478 1499 7870 3473 1495 7871 3462 1504 7872 3479 1502 7873 3480 1498 7874 3478 1505 7875 3476 1504 7876 3479 1500 7877 3477 1503 7878 3475 1505 7879 3493 1501 7880 3492 1502 7881 3480 1503 7882 3475 1499 7883 3473 1494 7884 3458 1507 7885 3459 1506 7886 3460 1508 7887 3485 1507 7888 3459 1494 7889 3458 1509 7890 3487 1508 7891 3485 1495 7892 3484 1506 7893 3460 1509 7894 3487 1497 7895 3486 1507 7896 3466 1511 7897 3483 1510 7898 3488 1508 7899 3467 1512 7900 3490 1511 7901 3483 1513 7902 3489 1512 7903 3482 1508 7904 3481 1510 7905 3488 1513 7906 3489 1509 7907 3465 1510 7908 3472 1511 7909 3469 1512 7910 3470 1520 7911 3514 1518 7912 3515 1514 7913 3501 1521 7914 3511 1520 7915 3514 1516 7916 3498 1519 7917 3510 1521 7918 3511 1517 7919 3500 1518 7920 3519 1519 7921 3510 1515 7922 3499 1524 7923 3516 1522 7924 3517 1518 7925 3515 1525 7926 3513 1524 7927 3516 1520 7928 3514 1523 7929 3512 1525 7930 3513 1521 7931 3511 1522 7932 3520 1523 7933 3512 1519 7934 3510 1514 7935 3495 1527 7936 3496 1526 7937 3497 1528 7938 3522 1527 7939 3496 1514 7940 3495 1529 7941 3524 1528 7942 3522 1515 7943 3521 1516 7944 3494 1526 7945 3497 1529 7946 3524 1527 7947 3503 1531 7948 3525 1530 7949 3526 1528 7950 3504 1532 7951 3528 1531 7952 3525 1533 7953 3527 1532 7954 3530 1528 7955 3529 1530 7956 3526 1533 7957 3527 1529 7958 3502 1530 7959 3509 1531 7960 3506 1532 7961 3507 1540 7962 3551 1538 7963 3552 1534 7964 3538 1541 7965 3548 1540 7966 3551 1536 7967 3535 1539 7968 3547 1541 7969 3548 1537 7970 3537 1538 7971 3566 1539 7972 3547 1535 7973 3536 1544 7974 3553 1542 7975 3554 1538 7976 3552 1545 7977 3550 1544 7978 3553 1540 7979 3551 1543 7980 3549 1545 7981 3550 1541 7982 3548 1542 7983 3567 1543 7984 3549 1539 7985 3547 1534 7986 3532 1547 7987 3533 1546 7988 3534 1548 7989 3556 1547 7990 3533 1534 7991 3532 1549 7992 3558 1548 7993 3556 1535 7994 3555 1536 7995 3531 1546 7996 3534 1549 7997 3558 1547 7998 3540 1551 7999 3559 1550 8000 3560 1548 8001 3541 1552 8002 3564 1551 8003 3559 1553 8004 3562 1552 8005 3563 1548 8006 3561 1550 8007 3560 1553 8008 3562 1549 8009 3539 1550 8010 3546 1551 8011 3543 1552 8012 3544 1560 8013 3588 1558 8014 3589 1554 8015 3575 1561 8016 3585 1560 8017 3588 1556 8018 3572 1559 8019 3584 1561 8020 3603 1557 8021 3602 1558 8022 3589 1559 8023 3584 1555 8024 3573 1564 8025 3590 1562 8026 3591 1558 8027 3589 1565 8028 3587 1564 8029 3590 1560 8030 3588 1563 8031 3586 1565 8032 3604 1561 8033 3603 1562 8034 3591 1563 8035 3586 1559 8036 3584 1554 8037 3569 1567 8038 3570 1566 8039 3571 1568 8040 3593 1567 8041 3570 1554 8042 3569 1569 8043 3595 1568 8044 3593 1555 8045 3592 1566 8046 3571 1569 8047 3595 1557 8048 3594 1567 8049 3577 1571 8050 3597 1570 8051 3598 1568 8052 3578 1572 8053 3600 1571 8054 3597 1573 8055 3599 1572 8056 3600 1568 8057 3578 1570 8058 3601 1573 8059 3599 1569 8060 3576 1570 8061 3583 1571 8062 3580 1572 8063 3581 1580 8064 3625 1578 8065 3626 1574 8066 3612 1581 8067 3622 1580 8068 3625 1576 8069 3609 1579 8070 3621 1581 8071 3640 1577 8072 3639 1578 8073 3626 1579 8074 3621 1575 8075 3610 1584 8076 3627 1582 8077 3628 1578 8078 3626 1585 8079 3624 1584 8080 3627 1580 8081 3625 1583 8082 3623 1585 8083 3641 1581 8084 3640 1582 8085 3628 1583 8086 3623 1579 8087 3621 1574 8088 3606 1587 8089 3607 1586 8090 3608 1588 8091 3633 1587 8092 3607 1574 8093 3606 1589 8094 3635 1588 8095 3633 1575 8096 3632 1586 8097 3608 1589 8098 3635 1577 8099 3634 1587 8100 3614 1591 8101 3631 1590 8102 3636 1588 8103 3615 1592 8104 3638 1591 8105 3631 1593 8106 3637 1592 8107 3630 1588 8108 3629 1590 8109 3636 1593 8110 3637 1589 8111 3613 1590 8112 3620 1591 8113 3617 1592 8114 3618 1600 8115 3662 1598 8116 3663 1594 8117 3649 1601 8118 3659 1600 8119 3662 1596 8120 3646 1599 8121 3658 1601 8122 3659 1597 8123 3648 1598 8124 3667 1599 8125 3658 1595 8126 3647 1604 8127 3664 1602 8128 3665 1598 8129 3663 1605 8130 3661 1604 8131 3664 1600 8132 3662 1603 8133 3660 1605 8134 3661 1601 8135 3659 1602 8136 3668 1603 8137 3660 1599 8138 3658 1594 8139 3643 1607 8140 3644 1606 8141 3645 1608 8142 3670 1607 8143 3644 1594 8144 3643 1609 8145 3672 1608 8146 3670 1595 8147 3669 1596 8148 3642 1606 8149 3645 1609 8150 3672 1607 8151 3651 1611 8152 3673 1610 8153 3674 1608 8154 3652 1612 8155 3676 1611 8156 3673 1613 8157 3675 1612 8158 3678 1608 8159 3677 1610 8160 3674 1613 8161 3675 1609 8162 3650 1610 8163 3657 1611 8164 3654 1612 8165 3655 1620 8166 3699 1618 8167 3700 1614 8168 3686 1621 8169 3696 1620 8170 3699 1616 8171 3683 1619 8172 3695 1621 8173 3696 1617 8174 3685 1618 8175 3714 1619 8176 3695 1615 8177 3684 1624 8178 3701 1622 8179 3702 1618 8180 3700 1625 8181 3698 1624 8182 3701 1620 8183 3699 1623 8184 3697 1625 8185 3698 1621 8186 3696 1622 8187 3715 1623 8188 3697 1619 8189 3695 1614 8190 3680 1627 8191 3681 1626 8192 3682 1628 8193 3704 1627 8194 3681 1614 8195 3680 1629 8196 3706 1628 8197 3704 1615 8198 3703 1616 8199 3679 1626 8200 3682 1629 8201 3706 1627 8202 3688 1631 8203 3707 1630 8204 3708 1628 8205 3689 1632 8206 3712 1631 8207 3707 1633 8208 3710 1632 8209 3711 1628 8210 3709 1630 8211 3708 1633 8212 3710 1629 8213 3687 1630 8214 3694 1631 8215 3691 1632 8216 3692 1860 8217 4143 1858 8218 4144 1854 8219 4130 1861 8220 4140 1860 8221 4143 1856 8222 4127 1859 8223 4139 1861 8224 4158 1857 8225 4157 1858 8226 4144 1859 8227 4139 1855 8228 4128 1864 8229 4145 1862 8230 4146 1858 8231 4144 1865 8232 4142 1864 8233 4145 1860 8234 4143 1863 8235 4141 1865 8236 4159 1861 8237 4158 1862 8238 4146 1863 8239 4141 1859 8240 4139 1854 8241 4124 1867 8242 4125 1866 8243 4126 1868 8244 4148 1867 8245 4125 1854 8246 4124 1869 8247 4150 1868 8248 4148 1855 8249 4147 1866 8250 4126 1869 8251 4150 1857 8252 4149 1867 8253 4132 1871 8254 4152 1870 8255 4153 1868 8256 4133 1872 8257 4155 1871 8258 4152 1873 8259 4154 1872 8260 4155 1868 8261 4133 1870 8262 4156 1873 8263 4154 1869 8264 4131 1870 8265 4138 1871 8266 4135 1872 8267 4136 1880 8268 4180 1878 8269 4181 1874 8270 4167 1881 8271 4177 1880 8272 4180 1876 8273 4164 1879 8274 4176 1881 8275 4195 1877 8276 4194 1878 8277 4181 1879 8278 4176 1875 8279 4165 1884 8280 4182 1882 8281 4183 1878 8282 4181 1885 8283 4179 1884 8284 4182 1880 8285 4180 1883 8286 4178 1885 8287 4196 1881 8288 4195 1882 8289 4183 1883 8290 4178 1879 8291 4176 1874 8292 4161 1887 8293 4162 1886 8294 4163 1888 8295 4188 1887 8296 4162 1874 8297 4161 1889 8298 4190 1888 8299 4188 1875 8300 4187 1886 8301 4163 1889 8302 4190 1877 8303 4189 1887 8304 4169 1891 8305 4186 1890 8306 4191 1888 8307 4170 1892 8308 4193 1891 8309 4186 1893 8310 4192 1892 8311 4185 1888 8312 4184 1890 8313 4191 1893 8314 4192 1889 8315 4168 1890 8316 4175 1891 8317 4172 1892 8318 4173 1900 8319 4217 1898 8320 4218 1894 8321 4204 1901 8322 4214 1900 8323 4217 1896 8324 4201 1899 8325 4213 1901 8326 4214 1897 8327 4203 1898 8328 4222 1899 8329 4213 1895 8330 4202 1904 8331 4219 1902 8332 4220 1898 8333 4218 1905 8334 4216 1904 8335 4219 1900 8336 4217 1903 8337 4215 1905 8338 4216 1901 8339 4214 1902 8340 4223 1903 8341 4215 1899 8342 4213 1894 8343 4198 1907 8344 4199 1906 8345 4200 1908 8346 4225 1907 8347 4199 1894 8348 4198 1909 8349 4227 1908 8350 4225 1895 8351 4224 1896 8352 4197 1906 8353 4200 1909 8354 4227 1907 8355 4206 1911 8356 4228 1910 8357 4229 1908 8358 4207 1912 8359 4231 1911 8360 4228 1913 8361 4230 1912 8362 4233 1908 8363 4232 1910 8364 4229 1913 8365 4230 1909 8366 4205 1910 8367 4212 1911 8368 4209 1912 8369 4210 1920 8370 4254 1918 8371 4255 1914 8372 4241 1921 8373 4251 1920 8374 4254 1916 8375 4238 1919 8376 4250 1921 8377 4251 1917 8378 4240 1918 8379 4269 1919 8380 4250 1915 8381 4239 1924 8382 4256 1922 8383 4257 1918 8384 4255 1925 8385 4253 1924 8386 4256 1920 8387 4254 1923 8388 4252 1925 8389 4253 1921 8390 4251 1922 8391 4270 1923 8392 4252 1919 8393 4250 1914 8394 4235 1927 8395 4236 1926 8396 4237 1928 8397 4259 1927 8398 4236 1914 8399 4235 1929 8400 4261 1928 8401 4259 1915 8402 4258 1916 8403 4234 1926 8404 4237 1929 8405 4261 1927 8406 4243 1931 8407 4262 1930 8408 4263 1928 8409 4244 1932 8410 4267 1931 8411 4262 1933 8412 4265 1932 8413 4266 1928 8414 4264 1930 8415 4263 1933 8416 4265 1929 8417 4242 1930 8418 4249 1931 8419 4246 1932 8420 4247 1940 8421 4291 1938 8422 4292 1934 8423 4278 1941 8424 4288 1940 8425 4291 1936 8426 4275 1939 8427 4287 1941 8428 4306 1937 8429 4305 1938 8430 4292 1939 8431 4287 1935 8432 4276 1944 8433 4293 1942 8434 4294 1938 8435 4292 1945 8436 4290 1944 8437 4293 1940 8438 4291 1943 8439 4289 1945 8440 4307 1941 8441 4306 1942 8442 4294 1943 8443 4289 1939 8444 4287 1934 8445 4272 1947 8446 4273 1946 8447 4274 1948 8448 4299 1947 8449 4273 1934 8450 4272 1949 8451 4301 1948 8452 4299 1935 8453 4298 1946 8454 4274 1949 8455 4301 1937 8456 4300 1947 8457 4280 1951 8458 4297 1950 8459 4302 1948 8460 4281 1952 8461 4304 1951 8462 4297 1953 8463 4303 1952 8464 4296 1948 8465 4295 1950 8466 4302 1953 8467 4303 1949 8468 4279 1950 8469 4286 1951 8470 4283 1952 8471 4284 1960 8472 4328 1958 8473 4329 1954 8474 4315 1961 8475 4325 1960 8476 4328 1956 8477 4312 1959 8478 4324 1961 8479 4325 1957 8480 4314 1958 8481 4333 1959 8482 4324 1955 8483 4313 1964 8484 4330 1962 8485 4331 1958 8486 4329 1965 8487 4327 1964 8488 4330 1960 8489 4328 1963 8490 4326 1965 8491 4327 1961 8492 4325 1962 8493 4334 1963 8494 4326 1959 8495 4324 1954 8496 4309 1967 8497 4310 1966 8498 4311 1968 8499 4336 1967 8500 4310 1954 8501 4309 1969 8502 4338 1968 8503 4336 1955 8504 4335 1956 8505 4308 1966 8506 4311 1969 8507 4338 1967 8508 4317 1971 8509 4339 1970 8510 4340 1968 8511 4318 1972 8512 4342 1971 8513 4339 1973 8514 4341 1972 8515 4344 1968 8516 4343 1970 8517 4340 1973 8518 4341 1969 8519 4316 1970 8520 4323 1971 8521 4320 1972 8522 4321 1980 8523 4365 1978 8524 4366 1974 8525 4352 1981 8526 4362 1980 8527 4365 1976 8528 4349 1979 8529 4361 1981 8530 4362 1977 8531 4351 1978 8532 4380 1979 8533 4361 1975 8534 4350 1984 8535 4367 1982 8536 4368 1978 8537 4366 1985 8538 4364 1984 8539 4367 1980 8540 4365 1983 8541 4363 1985 8542 4364 1981 8543 4362 1982 8544 4381 1983 8545 4363 1979 8546 4361 1974 8547 4346 1987 8548 4347 1986 8549 4348 1988 8550 4370 1987 8551 4347 1974 8552 4346 1989 8553 4372 1988 8554 4370 1975 8555 4369 1976 8556 4345 1986 8557 4348 1989 8558 4372 1987 8559 4354 1991 8560 4373 1990 8561 4374 1988 8562 4355 1992 8563 4378 1991 8564 4373 1993 8565 4376 1992 8566 4377 1988 8567 4375 1990 8568 4374 1993 8569 4376 1989 8570 4353 1990 8571 4360 1991 8572 4357 1992 8573 4358 2000 8574 4402 1998 8575 4403 1994 8576 4389 2001 8577 4399 2000 8578 4402 1996 8579 4386 1999 8580 4398 2001 8581 4417 1997 8582 4416 1998 8583 4403 1999 8584 4398 1995 8585 4387 2004 8586 4404 2002 8587 4405 1998 8588 4403 2005 8589 4401 2004 8590 4404 2000 8591 4402 2003 8592 4400 2005 8593 4418 2001 8594 4417 2002 8595 4405 2003 8596 4400 1999 8597 4398 1994 8598 4383 2007 8599 4384 2006 8600 4385 2008 8601 4407 2007 8602 4384 1994 8603 4383 2009 8604 4409 2008 8605 4407 1995 8606 4406 2006 8607 4385 2009 8608 4409 1997 8609 4408 2007 8610 4391 2011 8611 4411 2010 8612 4412 2008 8613 4392 2012 8614 4414 2011 8615 4411 2013 8616 4413 2012 8617 4414 2008 8618 4392 2010 8619 4415 2013 8620 4413 2009 8621 4390 2010 8622 4397 2011 8623 4394 2012 8624 4395 2020 8625 4439 2018 8626 4440 2014 8627 4426 2021 8628 4436 2020 8629 4439 2016 8630 4423 2019 8631 4435 2021 8632 4454 2017 8633 4453 2018 8634 4440 2019 8635 4435 2015 8636 4424 2024 8637 4441 2022 8638 4442 2018 8639 4440 2025 8640 4438 2024 8641 4441 2020 8642 4439 2023 8643 4437 2025 8644 4455 2021 8645 4454 2022 8646 4442 2023 8647 4437 2019 8648 4435 2014 8649 4420 2027 8650 4421 2026 8651 4422 2028 8652 4447 2027 8653 4421 2014 8654 4420 2029 8655 4449 2028 8656 4447 2015 8657 4446 2026 8658 4422 2029 8659 4449 2017 8660 4448 2027 8661 4428 2031 8662 4445 2030 8663 4450 2028 8664 4429 2032 8665 4452 2031 8666 4445 2033 8667 4451 2032 8668 4444 2028 8669 4443 2030 8670 4450 2033 8671 4451 2029 8672 4427 2030 8673 4434 2031 8674 4431 2032 8675 4432 2040 8676 4476 2038 8677 4477 2034 8678 4463 2041 8679 4473 2040 8680 4476 2036 8681 4460 2039 8682 4472 2041 8683 4473 2037 8684 4462 2038 8685 4481 2039 8686 4472 2035 8687 4461 2044 8688 4478 2042 8689 4479 2038 8690 4477 2045 8691 4475 2044 8692 4478 2040 8693 4476 2043 8694 4474 2045 8695 4475 2041 8696 4473 2042 8697 4482 2043 8698 4474 2039 8699 4472 2034 8700 4457 2047 8701 4458 2046 8702 4459 2048 8703 4484 2047 8704 4458 2034 8705 4457 2049 8706 4486 2048 8707 4484 2035 8708 4483 2036 8709 4456 2046 8710 4459 2049 8711 4486 2047 8712 4465 2051 8713 4487 2050 8714 4488 2048 8715 4466 2052 8716 4490 2051 8717 4487 2053 8718 4489 2052 8719 4492 2048 8720 4491 2050 8721 4488 2053 8722 4489 2049 8723 4464 2050 8724 4471 2051 8725 4468 2052 8726 4469 2060 8727 4513 2058 8728 4514 2054 8729 4500 2061 8730 4510 2060 8731 4513 2056 8732 4497 2059 8733 4509 2061 8734 4510 2057 8735 4499 2058 8736 4528 2059 8737 4509 2055 8738 4498 2064 8739 4515 2062 8740 4516 2058 8741 4514 2065 8742 4512 2064 8743 4515 2060 8744 4513 2063 8745 4511 2065 8746 4512 2061 8747 4510 2062 8748 4529 2063 8749 4511 2059 8750 4509 2054 8751 4494 2067 8752 4495 2066 8753 4496 2068 8754 4518 2067 8755 4495 2054 8756 4494 2069 8757 4520 2068 8758 4518 2055 8759 4517 2056 8760 4493 2066 8761 4496 2069 8762 4520 2067 8763 4502 2071 8764 4521 2070 8765 4522 2068 8766 4503 2072 8767 4526 2071 8768 4521 2073 8769 4524 2072 8770 4525 2068 8771 4523 2070 8772 4522 2073 8773 4524 2069 8774 4501 2070 8775 4508 2071 8776 4505 2072 8777 4506

+
+
+
+ + + + + + + + + 1.000000 0.000000 0.000000 0.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1.0000001.000000 + 30.0000000.0000003.333333 + + + + + +
diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfF_01/model.config b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfF_01/model.config new file mode 100755 index 0000000..adb8edd --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfF_01/model.config @@ -0,0 +1,11 @@ + + + aws_robomaker_warehouse_ShelfF_01 + 1.0 + model.sdf + + + + + + diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfF_01/model.sdf b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfF_01/model.sdf new file mode 100755 index 0000000..bcc9aef --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_ShelfF_01/model.sdf @@ -0,0 +1,46 @@ + + + + + + 30 + + 907.144 + 0 + 0 + 104.950 + 0 + 824.248 + + + + + + model://aws_robomaker_warehouse_ShelfF_01/meshes/aws_robomaker_warehouse_ShelfF_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + model://aws_robomaker_warehouse_ShelfF_01/meshes/aws_robomaker_warehouse_ShelfF_01_visual.DAE + + + 1 + + +1 + + diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_TrashCanC_01/materials/textures/aws_robomaker_warehouse_TrashCanC_01.png b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_TrashCanC_01/materials/textures/aws_robomaker_warehouse_TrashCanC_01.png new file mode 100755 index 0000000..252756a Binary files /dev/null and b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_TrashCanC_01/materials/textures/aws_robomaker_warehouse_TrashCanC_01.png differ diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_TrashCanC_01/meshes/aws_robomaker_warehouse_TrashCanC_01_collision.DAE b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_TrashCanC_01/meshes/aws_robomaker_warehouse_TrashCanC_01_collision.DAE new file mode 100755 index 0000000..2bce352 --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_TrashCanC_01/meshes/aws_robomaker_warehouse_TrashCanC_01_collision.DAE @@ -0,0 +1,724 @@ + + + FBX COLLADA exporter2019-03-21T05:48:15Z2019-03-21T05:48:15ZZ_UP + + + + + +73.948090 -45.443611 130.823112 +73.948112 -45.443619 110.171623 +63.734142 -35.842438 23.716797 +67.833038 -39.073685 100.779701 +39.877193 -45.443611 130.823112 +39.877193 -45.443619 110.171623 +39.877193 -35.842438 23.716797 +39.877193 -39.073685 100.779701 +73.948090 -23.254808 130.823112 +73.948112 -23.254808 110.171623 +63.734142 -23.254808 23.716797 +67.833038 -23.254808 100.779701 +39.877193 -23.254808 130.823112 +39.877193 -23.254808 23.716797 +62.144539 -23.254814 3.300064 +62.144539 -35.842449 3.300064 +39.877197 -35.842445 3.300079 +39.877197 -23.254810 3.300079 +-73.948090 -45.443611 130.823112 +-39.877193 -45.443611 130.823112 +-39.877193 -45.443619 110.171623 +-73.948112 -45.443619 110.171623 +-39.877193 -39.073685 100.779701 +-67.833038 -39.073685 100.779701 +-63.734142 -35.842438 23.716797 +-63.734142 -23.254808 23.716797 +-67.833038 -23.254808 100.779701 +-73.948090 -23.254808 130.823112 +-39.877193 -23.254808 130.823112 +-39.877193 -35.842438 23.716797 +-73.948112 -23.254808 110.171623 +-39.877193 -23.254808 23.716797 +-62.144539 -23.254814 3.300064 +-62.144539 -35.842449 3.300064 +-39.877197 -35.842445 3.300079 +-39.877197 -23.254810 3.300079 +73.948090 45.443619 130.823112 +39.877193 45.443619 130.823112 +39.877193 45.443623 110.171623 +73.948112 45.443623 110.171623 +39.877193 39.073692 100.779701 +67.833038 39.073692 100.779701 +63.734142 35.842445 23.716797 +63.734142 23.254814 23.716797 +67.833038 23.254814 100.779701 +73.948090 23.254814 130.823112 +39.877193 23.254814 130.823112 +39.877193 35.842445 23.716797 +73.948112 23.254814 110.171623 +39.877193 23.254814 23.716797 +62.144539 23.254820 3.300064 +62.144539 35.842453 3.300064 +39.877197 35.842453 3.300079 +39.877197 23.254818 3.300079 +-73.948090 45.443619 130.823112 +-73.948112 45.443623 110.171623 +-39.877193 45.443623 110.171623 +-39.877193 45.443619 130.823112 +-67.833038 39.073692 100.779701 +-39.877193 39.073692 100.779701 +-67.833038 23.254814 100.779701 +-63.734142 23.254814 23.716797 +-63.734142 35.842445 23.716797 +-39.877193 23.254814 130.823112 +-73.948090 23.254814 130.823112 +-39.877193 35.842445 23.716797 +-73.948112 23.254814 110.171623 +-39.877193 23.254814 23.716797 +-62.144539 23.254820 3.300064 +-39.877197 23.254818 3.300079 +-39.877197 35.842453 3.300079 +-62.144539 35.842453 3.300064 + + + + + + + + + + + +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -0.827605 -0.561311 +0.000000 -0.827605 -0.561311 +0.000000 -0.827605 -0.561311 +0.000000 -0.827605 -0.561311 +0.000000 -0.827605 -0.561311 +0.000000 -0.827605 -0.561311 +0.998588 0.000000 -0.053114 +0.998588 0.000000 -0.053114 +0.998589 0.000000 -0.053114 +0.998589 0.000000 -0.053114 +0.998588 0.000000 -0.053114 +0.998589 0.000000 -0.053114 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -0.999122 -0.041893 +0.000000 -0.999122 -0.041893 +0.000000 -0.999122 -0.041893 +0.000000 -0.999122 -0.041893 +0.000000 -0.999122 -0.041893 +0.000000 -0.999122 -0.041893 +1.000000 0.000000 0.000001 +1.000000 0.000000 0.000001 +1.000000 0.000000 0.000001 +1.000000 0.000000 0.000001 +1.000000 0.000000 0.000001 +1.000000 0.000000 0.000001 +0.838022 0.000000 -0.545636 +0.838022 0.000000 -0.545636 +0.838022 0.000000 -0.545636 +0.838022 0.000000 -0.545636 +0.838022 0.000000 -0.545636 +0.838022 0.000000 -0.545636 +-0.000001 0.000000 -1.000000 +-0.000001 0.000000 -1.000000 +-0.000001 0.000000 -1.000000 +-0.000001 0.000000 -1.000000 +-0.000001 0.000000 -1.000000 +-0.000001 0.000000 -1.000000 +0.996983 0.000000 -0.077623 +0.996983 0.000000 -0.077623 +0.996983 0.000000 -0.077623 +0.996983 0.000000 -0.077623 +0.996983 0.000000 -0.077623 +0.996983 0.000000 -0.077623 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -0.827605 -0.561311 +0.000000 -0.827605 -0.561311 +0.000000 -0.827605 -0.561311 +0.000000 -0.827605 -0.561311 +0.000000 -0.827605 -0.561311 +0.000000 -0.827605 -0.561311 +-0.998588 0.000000 -0.053114 +-0.998588 0.000000 -0.053114 +-0.998589 0.000000 -0.053114 +-0.998589 0.000000 -0.053114 +-0.998589 0.000000 -0.053114 +-0.998588 0.000000 -0.053114 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -0.827605 -0.561311 +0.000000 -0.827605 -0.561311 +0.000000 -0.827605 -0.561311 +0.000000 -0.827605 -0.561311 +0.000000 -0.827605 -0.561311 +0.000000 -0.827605 -0.561311 +0.000000 -0.999122 -0.041893 +0.000000 -0.999122 -0.041893 +0.000000 -0.999122 -0.041893 +0.000000 -0.999122 -0.041893 +0.000000 -0.999122 -0.041893 +0.000000 -0.999122 -0.041893 +-1.000000 0.000000 0.000001 +-1.000000 0.000000 0.000001 +-1.000000 0.000000 0.000001 +-1.000000 0.000000 0.000001 +-1.000000 0.000000 0.000001 +-1.000000 0.000000 0.000001 +-0.838022 0.000000 -0.545636 +-0.838022 0.000000 -0.545636 +-0.838022 0.000000 -0.545636 +-0.838022 0.000000 -0.545636 +-0.838022 0.000000 -0.545636 +-0.838022 0.000000 -0.545636 +-0.998589 0.000000 -0.053114 +-0.998589 0.000000 -0.053114 +-0.998589 0.000000 -0.053114 +-0.998589 0.000000 -0.053114 +-0.998589 0.000000 -0.053114 +-0.998589 0.000000 -0.053114 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +-0.996983 0.000000 -0.077623 +-0.996983 0.000000 -0.077623 +-0.996983 0.000000 -0.077623 +-0.996983 0.000000 -0.077623 +-0.996983 0.000000 -0.077623 +-0.996983 0.000000 -0.077623 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +-0.000000 1.000000 -0.000000 +-0.000000 1.000000 -0.000000 +-0.000000 1.000000 -0.000000 +-0.000000 1.000000 -0.000000 +-0.000000 1.000000 -0.000000 +-0.000000 1.000000 -0.000000 +0.000000 -0.999122 -0.041893 +0.000000 -0.999122 -0.041893 +0.000000 -0.999122 -0.041893 +0.000000 -0.999122 -0.041893 +0.000000 -0.999122 -0.041893 +0.000000 -0.999122 -0.041893 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.838022 0.000000 -0.545636 +0.838022 0.000000 -0.545636 +0.838022 0.000000 -0.545636 +0.838022 0.000000 -0.545636 +0.838022 0.000000 -0.545636 +0.838022 0.000000 -0.545636 +-1.000000 0.000000 0.000001 +-1.000000 0.000000 0.000001 +-1.000000 0.000000 0.000001 +-1.000000 0.000000 0.000001 +-1.000000 0.000000 0.000001 +-1.000000 0.000000 0.000001 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.827605 -0.561311 +0.000000 0.827605 -0.561311 +0.000000 0.827605 -0.561311 +0.000000 0.827605 -0.561311 +0.000000 0.827605 -0.561311 +0.000000 0.827605 -0.561311 +0.998588 0.000000 -0.053114 +0.998588 0.000000 -0.053114 +0.998589 0.000000 -0.053114 +0.998589 0.000000 -0.053114 +0.998589 0.000000 -0.053114 +0.998588 0.000000 -0.053114 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.999122 -0.041893 +0.000000 0.999122 -0.041893 +0.000000 0.999122 -0.041893 +0.000000 0.999122 -0.041893 +0.000000 0.999122 -0.041893 +0.000000 0.999122 -0.041893 +1.000000 0.000000 0.000001 +1.000000 0.000000 0.000001 +1.000000 0.000000 0.000001 +1.000000 0.000000 0.000001 +1.000000 0.000000 0.000001 +1.000000 0.000000 0.000001 +0.838022 0.000000 -0.545636 +0.838022 0.000000 -0.545636 +0.838022 0.000000 -0.545636 +0.838022 0.000000 -0.545636 +0.838022 0.000000 -0.545636 +0.838022 0.000000 -0.545636 +0.998589 0.000000 -0.053114 +0.998589 0.000000 -0.053114 +0.998589 0.000000 -0.053114 +0.998589 0.000000 -0.053114 +0.998589 0.000000 -0.053114 +0.998589 0.000000 -0.053114 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.000001 0.000000 -1.000000 +-0.000001 0.000000 -1.000000 +-0.000001 0.000000 -1.000000 +-0.000001 0.000000 -1.000000 +-0.000001 0.000000 -1.000000 +-0.000001 0.000000 -1.000000 +0.996983 0.000000 -0.077623 +0.996983 0.000000 -0.077623 +0.996983 0.000000 -0.077623 +0.996983 0.000000 -0.077623 +0.996983 0.000000 -0.077623 +0.996983 0.000000 -0.077623 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +0.000000 -1.000000 -0.000000 +0.000000 -1.000000 -0.000000 +0.000000 -1.000000 -0.000000 +0.000000 -1.000000 -0.000000 +0.000000 -1.000000 -0.000000 +0.000000 -1.000000 -0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.999122 -0.041893 +0.000000 0.999122 -0.041893 +0.000000 0.999122 -0.041893 +0.000000 0.999122 -0.041893 +0.000000 0.999122 -0.041893 +0.000000 0.999122 -0.041893 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.827605 -0.561311 +0.000000 0.827605 -0.561311 +0.000000 0.827605 -0.561311 +0.000000 0.827605 -0.561311 +0.000000 0.827605 -0.561311 +0.000000 0.827605 -0.561311 +-0.998588 0.000000 -0.053114 +-0.998588 0.000000 -0.053114 +-0.998589 0.000000 -0.053114 +-0.998589 0.000000 -0.053114 +-0.998588 0.000000 -0.053114 +-0.998589 0.000000 -0.053114 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.827605 -0.561311 +0.000000 0.827605 -0.561311 +0.000000 0.827605 -0.561311 +0.000000 0.827605 -0.561311 +0.000000 0.827605 -0.561311 +0.000000 0.827605 -0.561311 +0.000000 0.999122 -0.041893 +0.000000 0.999122 -0.041893 +0.000000 0.999122 -0.041893 +0.000000 0.999122 -0.041893 +0.000000 0.999122 -0.041893 +0.000000 0.999122 -0.041893 +-1.000000 0.000000 0.000001 +-1.000000 0.000000 0.000001 +-1.000000 0.000000 0.000001 +-1.000000 0.000000 0.000001 +-1.000000 0.000000 0.000001 +-1.000000 0.000000 0.000001 +-0.838022 0.000000 -0.545636 +-0.838022 0.000000 -0.545636 +-0.838022 0.000000 -0.545636 +-0.838022 0.000000 -0.545636 +-0.838022 0.000000 -0.545636 +-0.838022 0.000000 -0.545636 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +-0.996983 0.000000 -0.077623 +-0.996983 0.000000 -0.077623 +-0.996983 0.000000 -0.077623 +-0.996983 0.000000 -0.077623 +-0.996983 0.000000 -0.077623 +-0.996983 0.000000 -0.077623 +-0.000000 1.000000 0.000000 +-0.000000 1.000000 0.000000 +-0.000000 1.000000 0.000000 +-0.000000 1.000000 0.000000 +-0.000000 1.000000 0.000000 +-0.000000 1.000000 0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 -0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000001 +1.000000 0.000000 0.000001 +1.000000 0.000000 0.000001 +1.000000 0.000000 0.000001 +1.000000 0.000000 0.000001 +1.000000 0.000000 0.000001 +-0.838022 0.000000 -0.545636 +-0.838022 0.000000 -0.545636 +-0.838022 0.000000 -0.545636 +-0.838022 0.000000 -0.545636 +-0.838022 0.000000 -0.545636 +-0.838022 0.000000 -0.545636 + + + + + + + + + + + +1.000000 0.000000 +1.000000 0.000000 +1.000000 0.000000 +1.000000 0.000000 +0.500000 0.000000 +0.500000 0.000000 +0.500000 0.000000 +0.500000 0.000000 +1.000000 0.500000 +1.000000 0.500000 +1.000000 0.500000 +1.000000 0.500000 +0.500000 0.500000 +0.500000 0.500000 +1.000000 0.500000 +1.000000 0.000000 +0.500000 0.000000 +0.500000 0.500000 +0.500000 0.750000 +1.000000 0.758827 +1.000000 0.750000 +0.250000 0.000000 +0.250000 0.000000 +0.244569 0.500000 +0.244569 0.750000 +0.244569 0.000000 +0.246922 0.000000 +0.263138 0.000000 +0.263138 0.000000 +0.263138 0.500000 +0.239137 0.500000 +0.239137 0.750000 +0.250000 0.000000 +1.000000 0.000000 +0.500000 0.000000 +0.500000 0.000000 +1.000000 0.000000 +1.000000 0.750000 +0.500000 0.000000 +1.000000 0.000000 +1.000000 0.000000 +1.000000 0.500000 +1.000000 0.500000 +1.000000 0.500000 +0.500000 0.500000 +0.263138 0.000000 +0.263138 0.000000 +0.250000 0.000000 +0.250000 0.000000 +0.500000 0.000000 +1.000000 0.750000 +0.500000 0.758827 +1.000000 0.500000 +0.500000 0.500000 +0.244569 0.000000 +0.250000 0.500000 +1.000000 0.500000 +1.000000 0.000000 +0.500000 0.000000 +0.500000 0.500000 +0.244569 0.758827 +0.239137 0.000000 +0.244569 0.500000 +0.239137 0.750000 +0.246922 0.000000 +0.263138 0.500000 +0.500000 0.758827 +1.000000 0.729501 +1.000000 0.729501 +0.500000 0.729501 +1.000000 0.767654 +1.000000 0.756892 +1.000000 0.750000 +0.244569 0.761770 +0.239137 0.767654 +0.239137 0.767654 +1.000000 0.750000 +1.000000 0.753446 +1.000000 0.758827 +0.500000 0.767654 +1.000000 0.729501 +0.500000 0.729501 +1.000000 0.729500 +0.250000 0.767654 +0.263138 0.729501 +0.263138 0.729501 +1.000000 0.000000 +0.500000 0.000000 +0.500000 0.000000 +1.000000 0.000000 +0.500000 0.000000 +1.000000 0.000000 +1.000000 0.000000 +1.000000 0.500000 +1.000000 0.500000 +1.000000 0.500000 +0.500000 0.500000 +0.263138 0.000000 +0.263138 0.000000 +0.250000 0.000000 +0.248461 0.000000 +0.500000 0.000000 +1.000000 0.500000 +1.000000 0.750000 +1.000000 0.750000 +0.500000 0.500000 +0.244569 0.000000 +0.250000 0.500000 +1.000000 0.729501 +0.500000 0.729501 +1.000000 0.500000 +1.000000 0.000000 +0.500000 0.000000 +0.500000 0.500000 +0.500000 0.758827 +0.250000 0.750000 +1.000000 0.758827 +1.000000 0.756892 +0.239137 0.000000 +0.244569 0.500000 +0.239137 0.750000 +0.246922 0.000000 +0.263138 0.500000 +0.263138 0.729501 +1.000000 0.000000 +1.000000 0.000000 +0.500000 0.000000 +0.500000 0.000000 +1.000000 0.000000 +0.500000 0.000000 +1.000000 0.500000 +1.000000 0.500000 +1.000000 0.000000 +0.500000 0.500000 +1.000000 0.500000 +0.263138 0.000000 +0.263138 0.000000 +0.250000 0.000000 +0.250000 0.000000 +0.500000 0.000000 +1.000000 0.500000 +1.000000 0.753446 +1.000000 0.758827 +0.500000 0.500000 +0.244569 0.500000 +0.250000 0.000000 +0.500000 0.729501 +1.000000 0.729501 +1.000000 0.500000 +0.500000 0.500000 +0.500000 0.000000 +1.000000 0.000000 +0.500000 0.750000 +0.250000 0.750000 +1.000000 0.756892 +1.000000 0.767654 +0.239137 0.500000 +0.244569 0.000000 +0.239137 0.750000 +0.248461 0.000000 +0.263138 0.500000 +0.263138 0.729501 +1.000000 0.750000 +0.500000 0.767654 +1.000000 0.729501 +0.244569 0.758827 +0.239137 0.767654 +1.000000 0.750000 +0.500000 0.758827 +1.000000 0.729500 +0.244569 0.758827 +0.239137 0.767654 +-0.010863 0.500000 +-0.009854 0.727779 +-0.008555 0.757142 +-0.008555 1.015969 +0.500000 1.017654 + + + + + + + + + + + +

0 0 0 5 1 5 1 2 1 5 3 5 0 4 0 4 5 4 7 6 7 3 7 3 5 8 5 1 9 1 5 10 5 3 11 3 3 12 3 2 13 2 11 14 11 11 15 11 2 16 2 10 17 10 12 18 12 0 19 0 8 20 8 0 21 0 12 22 12 4 23 4 7 24 7 2 25 2 3 26 3 2 27 2 7 28 7 6 29 6 8 30 8 0 31 0 9 32 9 0 33 0 1 34 1 9 35 9 3 36 3 9 37 9 1 38 1 9 39 9 3 40 3 11 41 11 16 42 16 14 43 14 15 44 15 14 45 14 16 46 16 17 47 17 2 48 2 14 49 14 10 50 10 14 51 14 2 52 2 15 53 15 6 54 6 15 55 15 2 56 2 15 57 15 6 58 6 16 59 16 13 60 13 17 61 17 6 62 6 6 63 6 17 64 17 16 65 16 10 66 10 14 67 14 13 68 13 13 69 13 14 70 14 17 71 17 28 72 44 4 73 4 12 74 12 4 75 4 28 76 44 19 77 34 18 78 33 20 79 35 19 80 34 20 81 35 18 82 33 21 83 36 20 84 35 21 85 36 23 86 39 20 87 35 23 88 39 22 89 38 24 90 40 23 91 39 26 92 42 26 93 42 25 94 41 24 95 40 27 96 43 18 97 33 28 98 44 28 99 44 18 100 33 19 101 34 4 102 4 19 103 34 20 104 35 4 105 4 20 106 35 5 107 5 22 108 38 5 109 5 20 110 35 5 111 5 22 112 38 7 113 7 23 114 39 24 115 40 22 116 38 22 117 38 24 118 40 29 119 49 18 120 33 27 121 43 30 122 52 18 123 33 30 124 52 21 125 36 21 126 36 30 127 52 23 128 39 30 129 52 26 130 42 23 131 39 60 132 130 25 133 41 26 134 42 25 135 41 60 136 130 61 137 131 6 138 6 29 139 49 31 140 53 6 141 6 31 142 53 13 143 13 34 144 58 32 145 56 35 146 59 32 147 56 34 148 58 33 149 57 24 150 40 32 151 56 33 152 57 32 153 56 24 154 40 25 155 41 29 156 49 33 157 57 34 158 58 33 159 57 29 160 49 24 161 40 31 162 53 29 163 49 35 164 59 29 165 49 34 166 58 35 167 59 25 168 41 31 169 53 32 170 56 31 171 53 35 172 59 32 173 56 22 174 38 6 175 6 7 176 7 6 177 6 22 178 38 29 179 49 63 180 133 28 181 44 46 182 96 46 183 96 28 184 44 12 185 12 9 186 9 44 187 94 48 188 102 44 189 94 9 190 9 11 191 11 64 192 134 30 193 52 27 194 43 30 195 52 64 196 134 66 197 140 36 198 86 38 199 88 37 200 87 38 201 88 36 202 86 39 203 89 38 204 88 39 205 89 41 206 91 38 207 88 41 208 91 40 209 90 42 210 92 41 211 91 44 212 94 44 213 94 43 214 93 42 215 92 36 216 86 37 217 87 46 218 96 36 219 86 46 220 96 45 221 95 41 222 91 42 223 92 40 224 90 40 225 90 42 226 92 47 227 101 36 228 86 45 229 95 48 230 102 36 231 86 48 232 102 39 233 89 39 234 89 48 235 102 41 236 91 48 237 102 44 238 94 41 239 91 11 240 11 43 241 93 44 242 94 43 243 93 11 244 11 10 245 10 45 246 95 46 247 96 8 248 8 46 249 96 12 250 12 8 251 8 52 252 112 50 253 110 53 254 113 50 255 110 52 256 112 51 257 111 42 258 92 50 259 110 51 260 111 50 261 110 42 262 92 43 263 93 47 264 101 51 265 111 52 266 112 51 267 111 47 268 101 42 269 92 49 270 105 47 271 101 53 272 113 47 273 101 52 274 112 53 275 113 43 276 93 49 277 105 50 278 110 49 279 105 53 280 113 50 281 110 31 282 172 67 283 175 13 284 13 13 285 13 67 286 175 49 287 176 43 288 93 10 289 10 13 290 13 13 291 13 49 292 105 43 293 93 40 294 90 65 295 139 59 296 129 65 297 139 40 298 90 47 299 101 37 300 87 57 301 127 63 302 133 37 303 87 63 304 133 46 305 96 54 306 124 56 307 126 55 308 125 56 309 126 54 310 124 57 311 127 59 312 129 58 313 128 56 314 126 55 315 125 56 316 126 58 317 128 58 318 128 62 319 132 60 320 130 60 321 130 62 322 132 61 323 131 57 324 127 54 325 124 63 326 133 54 327 124 64 328 134 63 329 133 38 330 88 56 331 126 37 332 87 57 333 127 37 334 87 56 335 126 40 336 90 59 337 129 38 338 88 56 339 126 38 340 88 59 341 129 59 342 129 62 343 132 58 344 128 62 345 132 59 346 129 65 347 139 64 348 134 54 349 124 66 350 140 54 351 124 55 352 125 66 353 140 58 354 128 66 355 140 55 356 125 66 357 140 58 358 128 60 359 130 49 360 105 67 361 143 65 362 139 49 363 105 65 364 139 47 365 101 63 366 133 64 367 134 28 368 44 64 369 134 27 370 43 28 371 44 68 372 148 70 373 150 69 374 149 70 375 150 68 376 148 71 377 151 62 378 132 68 379 148 61 380 131 68 381 148 62 382 132 71 383 151 65 384 139 71 385 151 62 386 132 71 387 151 65 388 139 70 389 150 67 390 143 69 391 149 65 392 139 65 393 139 69 394 149 70 395 150 61 396 131 68 397 148 67 398 143 67 399 143 68 400 148 69 401 149 25 402 41 67 403 143 31 404 53 67 405 143 25 406 41 61 407 131 45 408 95 8 409 8 9 410 9 45 411 95 9 412 9 48 413 102 60 414 130 26 415 42 66 416 140 30 417 52 66 418 140 26 419 42

+
+
+
+ + + 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.0000001.000000 + 30.0000000.0000003.333333 + + + + + +
diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_TrashCanC_01/meshes/aws_robomaker_warehouse_TrashCanC_01_visual.DAE b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_TrashCanC_01/meshes/aws_robomaker_warehouse_TrashCanC_01_visual.DAE new file mode 100755 index 0000000..4a1b714 --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_TrashCanC_01/meshes/aws_robomaker_warehouse_TrashCanC_01_visual.DAE @@ -0,0 +1,5186 @@ + + + FBX COLLADA exporter2019-05-24T10:41:56Z2019-05-24T10:41:56ZZ_UP + + + ../materials/textures/aws_robomaker_warehouse_TrashCanC_01.png + + + + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + +71.401909 -39.300514 124.688263 +71.401924 41.480721 124.688271 +71.401909 -39.300526 119.246025 +65.696968 44.532944 119.246033 +65.795555 -20.014954 124.688263 +65.795555 -20.014954 129.204849 +71.364082 -33.759178 129.204865 +71.364090 41.486977 129.204865 +71.364082 -33.759178 130.572052 +65.795578 44.484856 124.688271 +65.795578 44.484856 129.204880 +65.088181 -42.352749 124.688263 +71.401924 41.480721 119.246033 +59.481823 -31.953896 124.688263 +59.481823 -31.953896 129.204865 +65.050354 -36.811394 129.204865 +71.364090 41.486965 130.572052 +69.823471 -41.589695 124.688263 +70.000336 43.757866 124.688271 +69.823471 -41.589695 119.246025 +69.975677 43.769882 119.246033 +62.286385 -26.238655 124.688263 +62.286385 -26.238655 129.204849 +69.785652 -36.048340 129.204865 +69.971970 43.762566 129.204865 +69.785652 -36.048340 130.572052 +69.806374 43.776142 130.572052 +38.155067 44.532944 119.246033 +28.887484 44.532944 119.246033 +28.887484 44.484856 124.688271 +38.155067 44.484856 124.688271 +28.887484 44.484856 129.204880 +38.155067 44.484856 129.204880 +65.133194 44.539200 130.572052 +65.088181 -42.352749 119.246025 +65.050354 -36.811394 130.572052 +0.000000 44.532944 119.246033 +0.000000 44.539200 130.572052 +38.155064 38.942123 119.246033 +28.887480 38.942123 119.246033 +28.887480 38.894035 124.688271 +38.155064 38.894035 124.688271 +28.887480 38.894035 129.204880 +38.155064 38.894035 129.204880 +-71.401909 -39.300526 119.246025 +-71.401924 41.480721 119.246033 +-71.401924 41.480721 124.688271 +-71.401909 -39.300514 124.688263 +-28.887484 44.532944 119.246033 +-28.887484 44.484856 124.688271 +-70.000336 43.757866 124.688271 +-65.795578 44.484856 124.688271 +-65.795555 -20.014954 124.688263 +-65.795555 -20.014954 129.204849 +-28.887484 44.484856 129.204880 +-65.795578 44.484856 129.204880 +-69.971970 43.762566 129.204865 +-71.364090 41.486977 129.204865 +-71.364082 -33.759178 129.204865 +-71.364090 41.486965 130.572052 +-71.364082 -33.759178 130.572052 +-65.696968 44.532944 119.246033 +-59.481823 -31.953896 124.688263 +-65.088181 -42.352749 124.688263 +-59.481823 -31.953896 129.204865 +-65.050354 -36.811394 129.204865 +-65.133194 44.539200 130.572052 +-65.088181 -42.352749 119.246025 +-69.823471 -41.589695 119.246025 +-69.823471 -41.589695 124.688263 +-69.975677 43.769882 119.246033 +-62.286385 -26.238655 124.688263 +-62.286385 -26.238655 129.204849 +-69.785652 -36.048340 129.204865 +-69.785652 -36.048340 130.572052 +-65.050354 -36.811394 130.572052 +-69.806374 43.776142 130.572052 +-38.155067 44.484856 124.688271 +-38.155067 44.532944 119.246033 +-38.155067 44.484856 129.204880 +-38.155064 38.894035 129.204880 +-28.887480 38.894035 129.204880 +-28.887480 38.894035 124.688271 +-28.887480 38.942123 119.246033 +-38.155064 38.942123 119.246033 +-38.155064 38.894035 124.688271 +-58.682518 -35.234798 24.205990 +58.682518 -35.234798 24.205990 +-63.082516 30.834759 24.205990 +63.082516 30.834759 24.205990 +-62.344437 -37.280159 114.311317 +66.744438 -32.880165 114.311317 +-66.744438 32.880127 114.311317 +62.344437 37.280117 114.311317 +-67.875870 -44.578415 111.675568 +72.275864 -40.178425 111.675568 +-72.275864 40.178383 111.675568 +67.875870 44.578373 111.675568 +-67.875854 -44.578407 119.486084 +72.275856 -40.178406 119.486084 +-72.275856 40.178371 119.486084 +67.875854 44.578373 119.486084 +-61.537354 -25.933434 119.486061 +57.137352 -30.333424 119.486061 +-57.137352 30.333387 119.486061 +61.537354 25.933397 119.486061 +-63.082516 -30.834793 24.205990 +63.082516 -30.834793 24.205990 +-58.682518 35.234760 24.205990 +58.682518 35.234760 24.205990 +-66.744438 -32.880165 114.311317 +62.344437 -37.280159 114.311317 +-62.344437 37.280117 114.311317 +66.744438 32.880127 114.311317 +-72.275864 -40.178425 111.675568 +67.875870 -44.578415 111.675568 +-67.875870 44.578373 111.675568 +72.275864 40.178383 111.675568 +-72.275856 -40.178406 119.486084 +67.875854 -44.578407 119.486084 +-67.875854 44.578373 119.486084 +72.275856 40.178371 119.486084 +-57.137352 -30.333424 119.486061 +61.537354 -25.933434 119.486061 +-61.537354 25.933397 119.486061 +57.137352 30.333387 119.486061 +-61.982513 -34.134792 24.205990 +61.982513 -34.134792 24.205990 +-61.982513 34.134758 24.205990 +61.982513 34.134758 24.205990 +-65.644440 -36.180161 114.311317 +65.644440 -36.180161 114.311317 +-65.644440 36.180126 114.311317 +65.644440 36.180126 114.311317 +-71.175873 -43.478416 111.675568 +71.175873 -43.478416 111.675568 +-71.175873 43.478382 111.675568 +71.175873 43.478382 111.675568 +-71.175858 -43.478405 119.486084 +71.175858 -43.478405 119.486084 +-71.175858 43.478371 119.486084 +71.175858 43.478371 119.486084 +-60.437359 -29.233433 119.486061 +60.437359 -29.233433 119.486061 +-60.437359 29.233397 119.486061 +60.437359 29.233397 119.486061 +50.893700 36.303509 98.584373 +52.939297 36.303509 98.584373 +50.893700 36.303509 114.288940 +52.939297 36.303509 114.288940 +50.893700 43.803059 114.288940 +52.939297 43.803059 114.288940 +37.914577 36.303509 98.584373 +39.960175 36.303509 98.584373 +37.914577 36.303509 114.288940 +39.960175 36.303509 114.288940 +37.914577 43.803059 114.288940 +39.960175 43.803059 114.288940 +24.935450 36.303509 98.584373 +26.981047 36.303509 98.584373 +24.935450 36.303509 114.288940 +26.981047 36.303509 114.288940 +24.935450 43.803059 114.288940 +26.981047 43.803059 114.288940 +11.956321 36.303509 98.584373 +14.001920 36.303509 98.584373 +11.956321 36.303509 114.288940 +14.001920 36.303509 114.288940 +11.956321 43.803059 114.288940 +14.001920 43.803059 114.288940 +1.022792 36.303509 98.584373 +1.022792 36.303509 114.288940 +1.022792 43.803059 114.288940 +-52.939301 36.303509 98.584373 +-52.939301 43.803059 114.288940 +-52.939301 36.303509 114.288940 +-50.893707 36.303509 98.584373 +-50.893707 43.803059 114.288940 +-50.893707 36.303509 114.288940 +-39.960190 36.303509 98.584373 +-39.960190 43.803059 114.288940 +-39.960190 36.303509 114.288940 +-37.914589 36.303509 98.584373 +-37.914589 43.803059 114.288940 +-37.914589 36.303509 114.288940 +-26.981058 36.303509 98.584373 +-26.981058 43.803059 114.288940 +-26.981058 36.303509 114.288940 +-24.935457 36.303509 98.584373 +-24.935457 43.803059 114.288940 +-24.935457 36.303509 114.288940 +-14.001928 36.303509 98.584373 +-14.001928 43.803059 114.288940 +-14.001928 36.303509 114.288940 +-11.956332 36.303509 98.584373 +-11.956332 43.803059 114.288940 +-11.956332 36.303509 114.288940 +-1.022804 36.303509 114.288940 +-0.511402 36.303509 98.584373 +-1.022804 43.803059 114.288940 +52.939297 -36.303551 98.584373 +52.939297 -43.803101 114.288940 +52.939297 -36.303551 114.288940 +50.893700 -36.303551 98.584373 +50.893700 -43.803101 114.288940 +50.893700 -36.303551 114.288940 +39.960175 -36.303551 98.584373 +39.960175 -43.803101 114.288940 +39.960175 -36.303551 114.288940 +37.914577 -36.303551 98.584373 +37.914577 -43.803101 114.288940 +37.914577 -36.303551 114.288940 +26.981047 -36.303551 98.584373 +26.981047 -43.803101 114.288940 +26.981047 -36.303551 114.288940 +24.935450 -36.303551 98.584373 +24.935450 -43.803101 114.288940 +24.935450 -36.303551 114.288940 +14.001920 -36.303551 98.584373 +14.001920 -43.803101 114.288940 +14.001920 -36.303551 114.288940 +11.956321 -36.303551 98.584373 +11.956321 -43.803101 114.288940 +11.956321 -36.303551 114.288940 +1.022792 -36.303551 98.584373 +1.022792 -43.803101 114.288940 +1.022792 -36.303551 114.288940 +-1.022804 -43.803101 114.288940 +-52.939301 -36.303551 98.584373 +-52.939301 -36.303551 114.288940 +-52.939301 -43.803101 114.288940 +-50.893707 -43.803101 114.288940 +-50.893707 -36.303551 98.584373 +-50.893707 -36.303551 114.288940 +-39.960190 -36.303551 98.584373 +-39.960190 -36.303551 114.288940 +-39.960190 -43.803101 114.288940 +-37.914589 -43.803101 114.288940 +-37.914589 -36.303551 98.584373 +-37.914589 -36.303551 114.288940 +-26.981058 -36.303551 98.584373 +-26.981058 -36.303551 114.288940 +-26.981058 -43.803101 114.288940 +-24.935457 -43.803101 114.288940 +-24.935457 -36.303551 98.584373 +-24.935457 -36.303551 114.288940 +-14.001928 -36.303551 98.584373 +-14.001928 -36.303551 114.288940 +-14.001928 -43.803101 114.288940 +-11.956332 -43.803101 114.288940 +-11.956332 -36.303551 98.584373 +-11.956332 -36.303551 114.288940 +-0.511402 -36.303551 98.584373 +-1.022804 -36.303551 114.288940 +-64.623444 14.001894 98.584373 +-72.122993 14.001894 114.288940 +-64.623444 14.001894 114.288940 +-64.623444 11.956286 98.584373 +-72.122993 11.956286 114.288940 +-64.623444 11.956286 114.288940 +-64.623444 1.022792 98.584373 +-72.122993 1.022792 114.288940 +-64.623444 1.022792 114.288940 +-64.623444 -1.022828 98.584373 +-72.122993 -1.022828 114.288940 +-64.623444 -1.022828 114.288940 +-64.623444 -11.956358 98.584373 +-72.122993 -11.956358 114.288940 +-64.623444 -11.956358 114.288940 +-64.623444 -14.001966 98.584373 +-72.122993 -14.001966 114.288940 +-64.623444 -14.001966 114.288940 +64.623444 14.001894 98.584373 +72.122993 14.001894 114.288940 +64.623444 14.001894 114.288940 +64.623444 11.956286 98.584373 +72.122993 11.956286 114.288940 +64.623444 11.956286 114.288940 +64.623444 1.022792 98.584373 +72.122993 1.022792 114.288940 +64.623444 1.022792 114.288940 +64.623444 -1.022828 98.584373 +72.122993 -1.022828 114.288940 +64.623444 -1.022828 114.288940 +64.623444 -11.956358 98.584373 +72.122993 -11.956358 114.288940 +64.623444 -11.956358 114.288940 +64.623444 -14.001966 98.584373 +72.122993 -14.001966 114.288940 +64.623444 -14.001966 114.288940 +60.347473 -30.725693 13.085787 +59.774971 -30.725693 9.838970 +58.126526 -30.725693 6.983769 +55.600948 -30.725693 4.864561 +52.502869 -30.725693 3.736954 +49.205967 -30.725693 3.736954 +46.107891 -30.725693 4.864562 +43.582321 -30.725693 6.983769 +41.933868 -30.725693 9.838970 +41.361366 -30.725693 13.085785 +41.933868 -30.725693 16.332600 +43.582317 -30.725693 19.187801 +46.107891 -30.725693 21.307009 +49.205963 -30.725693 22.434618 +52.502865 -30.725693 22.434618 +55.600948 -30.725693 21.307014 +58.126514 -30.725693 19.187807 +59.774971 -30.725693 16.332607 +60.347473 -25.927771 13.085786 +59.774971 -25.927771 9.838970 +58.126526 -25.927771 6.983769 +55.600948 -25.927771 4.864561 +52.502869 -25.927771 3.736954 +49.205967 -25.927771 3.736954 +46.107891 -25.927771 4.864562 +43.582321 -25.927771 6.983769 +41.933868 -25.927771 9.838970 +41.361366 -25.927771 13.085784 +41.933868 -25.927771 16.332600 +43.582317 -25.927771 19.187801 +46.107891 -25.927771 21.307009 +49.205963 -25.927771 22.434618 +52.502865 -25.927771 22.434618 +55.600948 -25.927771 21.307014 +58.126514 -25.927771 19.187807 +59.774971 -25.927771 16.332607 +-60.347462 -30.725693 13.085787 +-59.774979 -30.725693 9.838970 +-59.774979 -25.927771 9.838970 +-60.347462 -25.927771 13.085786 +-58.126534 -30.725693 6.983769 +-58.126534 -25.927771 6.983769 +-55.600937 -30.725693 4.864561 +-55.600937 -25.927771 4.864561 +-52.502869 -30.725693 3.736954 +-52.502869 -25.927771 3.736954 +-49.205963 -30.725693 3.736954 +-49.205963 -25.927771 3.736954 +-46.107899 -30.725693 4.864562 +-46.107899 -25.927771 4.864562 +-43.582314 -30.725693 6.983769 +-43.582314 -25.927771 6.983769 +-41.933857 -30.725693 9.838970 +-41.933857 -25.927771 9.838970 +-41.361366 -30.725693 13.085785 +-41.361366 -25.927771 13.085784 +-41.933857 -30.725693 16.332600 +-41.933857 -25.927771 16.332600 +-43.582314 -30.725693 19.187801 +-43.582314 -25.927771 19.187801 +-46.107887 -30.725693 21.307009 +-46.107887 -25.927771 21.307009 +-49.205963 -30.725693 22.434618 +-49.205963 -25.927771 22.434618 +-52.502865 -30.725693 22.434618 +-52.502865 -25.927771 22.434618 +-55.600937 -30.725693 21.307014 +-55.600937 -25.927771 21.307014 +-58.126514 -30.725693 19.187807 +-58.126514 -25.927771 19.187807 +-59.774979 -30.725693 16.332607 +-59.774979 -25.927771 16.332607 +60.347473 30.725647 13.085784 +59.774971 30.725647 9.838969 +59.774971 25.927723 9.838969 +60.347473 25.927723 13.085784 +58.126526 30.725647 6.983766 +58.126526 25.927723 6.983767 +55.600948 30.725647 4.864559 +55.600948 25.927723 4.864559 +52.502869 30.725647 3.736951 +52.502869 25.927723 3.736951 +49.205967 30.725647 3.736951 +49.205967 25.927723 3.736951 +46.107895 30.725647 4.864560 +46.107895 25.927723 4.864560 +43.582317 30.725647 6.983766 +43.582317 25.927723 6.983767 +41.933868 30.725647 9.838967 +41.933868 25.927723 9.838967 +41.361366 30.725647 13.085782 +41.361366 25.927723 13.085783 +41.933868 30.725647 16.332598 +41.933868 25.927723 16.332598 +43.582317 30.725647 19.187798 +43.582317 25.927723 19.187798 +46.107891 30.725647 21.307007 +46.107891 25.927723 21.307007 +49.205967 30.725647 22.434614 +49.205967 25.927723 22.434614 +52.502865 30.725647 22.434616 +52.502865 25.927723 22.434616 +55.600948 30.725647 21.307011 +55.600948 25.927723 21.307011 +58.126514 30.725647 19.187803 +58.126514 25.927723 19.187805 +59.774971 30.725647 16.332605 +59.774971 25.927723 16.332605 +-60.347462 30.725647 13.085784 +-60.347462 25.927723 13.085784 +-59.774979 25.927723 9.838969 +-59.774979 30.725647 9.838969 +-58.126534 25.927723 6.983767 +-58.126534 30.725647 6.983766 +-55.600937 25.927723 4.864559 +-55.600937 30.725647 4.864559 +-52.502869 25.927723 3.736951 +-52.502869 30.725647 3.736951 +-49.205963 25.927723 3.736951 +-49.205963 30.725647 3.736951 +-46.107899 25.927723 4.864560 +-46.107899 30.725647 4.864560 +-43.582314 25.927723 6.983767 +-43.582314 30.725647 6.983766 +-41.933857 25.927723 9.838967 +-41.933857 30.725647 9.838967 +-41.361366 25.927723 13.085783 +-41.361366 30.725647 13.085782 +-41.933857 25.927723 16.332598 +-41.933857 30.725647 16.332598 +-43.582314 25.927723 19.187798 +-43.582314 30.725647 19.187798 +-46.107887 25.927723 21.307007 +-46.107887 30.725647 21.307007 +-49.205963 25.927723 22.434614 +-49.205963 30.725647 22.434614 +-52.502865 25.927723 22.434616 +-52.502865 30.725647 22.434616 +-55.600937 25.927723 21.307011 +-55.600937 30.725647 21.307011 +-58.126514 25.927723 19.187805 +-58.126514 30.725647 19.187803 +-59.774979 25.927723 16.332605 +-59.774979 30.725647 16.332605 +49.165504 -31.833576 12.980597 +52.524448 -31.833576 12.980596 +49.165504 -24.726522 12.980600 +52.524448 -24.726522 12.980596 +51.956390 -31.833576 24.916767 +55.315327 -31.833576 24.916767 +51.956390 -24.726522 24.916767 +55.315327 -24.726522 24.916767 +49.725330 -24.726522 12.641880 +50.285149 -24.726522 12.438480 +50.844975 -24.726522 12.370875 +51.404797 -24.726522 12.438569 +51.964622 -24.726522 12.641838 +51.964622 -31.833576 12.641846 +51.404797 -31.833576 12.438583 +50.844975 -31.833576 12.370832 +50.285149 -31.833576 12.438583 +49.725330 -31.833576 12.641846 +49.165504 -31.549501 12.980596 +52.524448 -31.549501 12.980596 +49.165504 -25.010597 12.980596 +52.524448 -25.010597 12.980596 +51.956390 -31.549501 24.916767 +55.315327 -31.549501 24.916767 +51.956390 -25.010597 24.916767 +55.315327 -25.010597 24.916767 +49.725330 -25.010586 12.641838 +50.285149 -25.010597 12.438583 +50.844975 -25.010597 12.370832 +51.404797 -25.010597 12.438583 +51.964622 -25.010597 12.641838 +51.964622 -31.549501 12.641838 +51.404797 -31.549501 12.438583 +50.844975 -31.549501 12.370832 +50.285149 -31.549501 12.438583 +49.725330 -31.549501 12.641838 +52.037685 -31.619381 13.955422 +50.604675 -31.619381 13.433851 +50.303543 -31.619381 13.955422 +51.933098 -31.619381 14.548533 +52.037685 -24.876726 13.955422 +51.736553 -24.876726 13.433851 +51.170616 -24.876726 13.227865 +50.604675 -24.876726 13.433851 +50.303543 -24.876726 13.955422 +50.408127 -24.876726 14.548532 +50.869488 -24.876726 14.935658 +51.471745 -24.876726 14.935658 +51.933098 -24.876726 14.548533 +51.736553 -31.619381 13.433851 +51.170616 -31.619381 13.227865 +50.408127 -31.619381 14.548532 +50.869488 -31.619381 14.935658 +51.471745 -31.619381 14.935658 +-52.524448 -31.833576 12.980596 +-55.315334 -31.833576 24.916767 +-51.956390 -31.833576 24.916767 +-49.165504 -31.833576 12.980597 +-52.524448 -24.726522 12.980596 +-49.165504 -24.726522 12.980600 +-51.956390 -24.726522 24.916767 +-55.315334 -24.726522 24.916767 +-49.725327 -31.833576 12.641846 +-51.964615 -31.833576 12.641846 +-50.285156 -31.833576 12.438583 +-51.404785 -31.833576 12.438583 +-50.844975 -31.833576 12.370832 +-51.964615 -24.726522 12.641838 +-49.725327 -24.726522 12.641880 +-51.404785 -24.726522 12.438569 +-50.285156 -24.726522 12.438480 +-50.844975 -24.726522 12.370875 +-51.956390 -31.549501 24.916767 +-55.315334 -31.549501 24.916767 +-52.524448 -31.549501 12.980596 +-49.165504 -31.549501 12.980596 +-51.956390 -25.010597 24.916767 +-49.165504 -25.010597 12.980596 +-52.524448 -25.010597 12.980596 +-55.315334 -25.010597 24.916767 +-51.964615 -31.549501 12.641838 +-49.725327 -31.549501 12.641838 +-51.404785 -31.549501 12.438583 +-50.285156 -31.549501 12.438583 +-50.844975 -31.549501 12.370832 +-49.725327 -25.010586 12.641838 +-51.964615 -25.010597 12.641838 +-50.285156 -25.010597 12.438583 +-51.404785 -25.010597 12.438583 +-50.844975 -25.010597 12.370832 +-52.037682 -31.619381 13.955422 +-51.736553 -31.619381 13.433851 +-51.736553 -24.876726 13.433851 +-52.037682 -24.876726 13.955422 +-51.170612 -31.619381 13.227865 +-51.170612 -24.876726 13.227865 +-50.604675 -31.619381 13.433851 +-50.604675 -24.876726 13.433851 +-50.303535 -31.619381 13.955422 +-50.303535 -24.876726 13.955422 +-50.408127 -31.619381 14.548532 +-50.408127 -24.876726 14.548532 +-50.869488 -31.619381 14.935658 +-50.869488 -24.876726 14.935658 +-51.471741 -31.619381 14.935658 +-51.471741 -24.876726 14.935658 +-51.933090 -31.619381 14.548533 +-51.933090 -24.876726 14.548533 +52.524441 31.833542 12.980596 +55.315327 31.833542 24.916767 +51.956390 31.833542 24.916767 +49.165504 31.833542 12.980597 +52.524441 24.726486 12.980596 +49.165504 24.726486 12.980600 +51.956390 24.726486 24.916767 +55.315327 24.726486 24.916767 +49.725327 31.833542 12.641846 +51.964622 31.833542 12.641846 +50.285156 31.833542 12.438583 +51.404793 31.833542 12.438583 +50.844975 31.833542 12.370832 +51.964622 24.726486 12.641838 +49.725327 24.726486 12.641880 +51.404793 24.726486 12.438569 +50.285156 24.726486 12.438480 +50.844975 24.726486 12.370875 +51.956390 31.549465 24.916767 +55.315327 31.549465 24.916767 +52.524441 31.549465 12.980596 +49.165504 31.549465 12.980596 +51.956390 25.010550 24.916767 +49.165504 25.010550 12.980596 +52.524441 25.010550 12.980596 +55.315327 25.010550 24.916767 +51.964622 31.549465 12.641838 +49.725327 31.549465 12.641838 +51.404793 31.549465 12.438583 +50.285156 31.549465 12.438583 +50.844975 31.549465 12.370832 +49.725327 25.010550 12.641838 +51.964622 25.010550 12.641838 +50.285156 25.010550 12.438583 +51.404793 25.010550 12.438583 +50.844975 25.010550 12.370832 +52.037682 31.619347 13.955422 +51.736557 31.619347 13.433851 +51.736557 24.876690 13.433851 +52.037682 24.876690 13.955422 +51.170616 31.619347 13.227865 +51.170616 24.876690 13.227865 +50.604675 31.619347 13.433851 +50.604675 24.876690 13.433851 +50.303543 31.619347 13.955422 +50.303543 24.876690 13.955422 +50.408127 31.619347 14.548532 +50.408127 24.876690 14.548532 +50.869488 31.619347 14.935658 +50.869488 24.876690 14.935658 +51.471745 31.619347 14.935658 +51.471745 24.876690 14.935658 +51.933098 31.619347 14.548533 +51.933098 24.876690 14.548533 +-52.524448 31.833542 12.980596 +-49.165504 31.833542 12.980597 +-51.956390 31.833542 24.916767 +-55.315334 31.833542 24.916767 +-52.524448 24.726486 12.980596 +-55.315334 24.726486 24.916767 +-51.956390 24.726486 24.916767 +-49.165504 24.726486 12.980600 +-49.725327 31.833542 12.641846 +-51.964615 31.833542 12.641846 +-50.285156 31.833542 12.438583 +-51.404785 31.833542 12.438583 +-50.844975 31.833542 12.370832 +-51.964615 24.726486 12.641838 +-49.725327 24.726486 12.641880 +-51.404785 24.726486 12.438569 +-50.285156 24.726486 12.438480 +-50.844975 24.726486 12.370875 +-51.956390 31.549465 24.916767 +-49.165504 31.549465 12.980596 +-52.524448 31.549465 12.980596 +-55.315334 31.549465 24.916767 +-51.956390 25.010550 24.916767 +-55.315334 25.010550 24.916767 +-52.524448 25.010550 12.980596 +-49.165504 25.010550 12.980596 +-49.725327 31.549465 12.641838 +-51.964615 31.549465 12.641838 +-50.285156 31.549465 12.438583 +-51.404785 31.549465 12.438583 +-50.844975 31.549465 12.370832 +-51.964615 25.010550 12.641838 +-49.725327 25.010550 12.641838 +-51.404785 25.010550 12.438583 +-50.285156 25.010550 12.438583 +-50.844975 25.010550 12.370832 +-52.037682 31.619347 13.955422 +-52.037682 24.876690 13.955422 +-51.736553 24.876690 13.433851 +-51.736553 31.619347 13.433851 +-51.170612 24.876690 13.227865 +-51.170612 31.619347 13.227865 +-50.604675 24.876690 13.433851 +-50.604675 31.619347 13.433851 +-50.303535 24.876690 13.955422 +-50.303535 31.619347 13.955422 +-50.408127 24.876690 14.548532 +-50.408127 31.619347 14.548532 +-50.869488 24.876690 14.935658 +-50.869488 31.619347 14.935658 +-51.471741 24.876690 14.935658 +-51.471741 31.619347 14.935658 +-51.933090 24.876690 14.548533 +-51.933090 31.619347 14.548533 +38.765221 41.980946 126.364548 +38.765221 43.170593 125.871796 +38.765221 43.663345 124.682159 +38.765221 43.170593 123.492523 +38.765221 41.980946 122.999756 +38.765221 40.791309 123.492523 +38.765221 40.298557 124.682159 +38.765221 40.791309 125.871796 +28.410164 41.980946 126.364548 +28.410164 43.170593 125.871796 +28.410164 43.663345 124.682159 +28.410164 43.170593 123.492523 +28.410164 41.980946 122.999756 +28.410164 40.791309 123.492523 +28.410164 40.298557 124.682159 +28.410164 40.791309 125.871796 +34.847843 41.980946 123.997856 +35.122620 42.644310 123.997856 +35.785976 42.919075 123.997856 +36.449337 42.644310 123.997856 +36.724110 41.980946 123.997856 +36.449337 41.317593 123.997856 +35.785976 41.042816 123.997856 +35.122620 41.317593 123.997856 +34.847843 41.980946 118.223709 +35.122620 42.644310 118.223709 +35.785976 42.919075 118.223709 +36.449337 42.644310 118.223709 +36.724110 41.980946 118.223709 +36.449337 41.317593 118.223709 +35.785976 41.042816 118.223709 +35.122620 41.317593 118.223709 +30.455627 41.980946 123.997856 +30.730400 42.644310 123.997856 +31.393763 42.919075 123.997856 +32.057121 42.644310 123.997856 +32.331894 41.980946 123.997856 +32.057121 41.317593 123.997856 +31.393763 41.042816 123.997856 +30.730402 41.317593 123.997856 +30.455627 41.980946 118.223709 +30.730402 42.644310 118.223709 +31.393763 42.919075 118.223709 +32.057121 42.644310 118.223709 +32.331894 41.980946 118.223709 +32.057121 41.317593 118.223709 +31.393763 41.042816 118.223709 +30.730402 41.317593 118.223709 +-28.410160 43.170593 125.871780 +-28.410160 41.980946 126.364548 +-38.765217 41.980946 126.364548 +-38.765217 43.170593 125.871780 +-28.410160 43.663345 124.682159 +-38.765217 43.663345 124.682159 +-28.410160 43.170593 123.492523 +-38.765217 43.170593 123.492523 +-28.410160 41.980946 122.999756 +-38.765217 41.980946 122.999756 +-28.410160 40.791309 123.492523 +-38.765217 40.791309 123.492523 +-28.410160 40.298557 124.682159 +-38.765217 40.298557 124.682159 +-28.410160 40.791309 125.871780 +-38.765217 40.791309 125.871780 +-34.847836 41.980946 123.997849 +-35.122620 42.644310 123.997849 +-35.122620 42.644310 118.223709 +-34.847836 41.980946 118.223709 +-35.785969 42.919075 123.997849 +-35.785969 42.919075 118.223709 +-36.449329 42.644310 123.997849 +-36.449329 42.644310 118.223709 +-36.724102 41.980946 123.997849 +-36.724102 41.980946 118.223709 +-36.449329 41.317593 123.997849 +-36.449329 41.317593 118.223709 +-35.785969 41.042816 123.997849 +-35.785969 41.042816 118.223709 +-35.122620 41.317593 123.997849 +-35.122620 41.317593 118.223709 +-30.455622 41.980946 123.997849 +-30.730396 42.644310 123.997849 +-30.730396 42.644310 118.223709 +-30.455622 41.980946 118.223709 +-31.393757 42.919075 123.997849 +-31.393757 42.919075 118.223709 +-32.057114 42.644310 123.997849 +-32.057114 42.644310 118.223709 +-32.331894 41.980946 123.997849 +-32.331894 41.980946 118.223709 +-32.057114 41.317593 123.997849 +-32.057114 41.317593 118.223709 +-31.393757 41.042816 123.997849 +-31.393757 41.042816 118.223709 +-30.730396 41.317593 123.997849 +-30.730396 41.317593 118.223709 + + + + + + + + + + + +0.954794 -0.297269 0.000001 +0.961660 0.274243 -0.000988 +0.962188 0.272384 0.000000 +0.962188 0.272384 0.000000 +0.954794 -0.297267 0.000000 +0.954794 -0.297269 0.000001 +-0.000000 1.000000 0.000561 +-0.000000 0.999999 -0.001678 +0.001038 0.999992 0.003826 +0.001038 0.999992 0.003826 +0.000000 0.999961 0.008836 +-0.000000 1.000000 0.000561 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +0.967232 -0.253893 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +0.967232 -0.253893 0.000000 +0.967232 -0.253893 0.000000 +0.000646 0.999660 -0.026085 +0.001038 0.999992 0.003826 +-0.000000 0.999999 -0.001678 +-0.000003 -0.000000 -1.000000 +-0.000004 -0.000002 -1.000000 +-0.000003 -0.000000 -1.000000 +0.000002 -0.000000 -1.000000 +-0.000003 -0.000000 -1.000000 +-0.000003 -0.000000 -1.000000 +0.000002 -0.000000 -1.000000 +-0.000003 -0.000000 -1.000000 +0.000001 -0.000001 -1.000000 +0.954794 -0.297268 -0.000000 +0.957663 0.287503 0.014966 +0.955706 0.294323 0.000002 +0.955706 0.294323 0.000002 +0.954794 -0.297268 0.000000 +0.954794 -0.297268 -0.000000 +0.060145 0.998104 -0.013067 +0.000646 0.999660 -0.026085 +-0.000000 0.999999 -0.001678 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.534109 -0.845416 0.000000 +0.079799 -0.996811 0.000000 +0.079799 -0.996811 0.000000 +0.079799 -0.996811 0.000000 +0.534108 -0.845416 0.000000 +0.534109 -0.845416 0.000000 +0.561036 0.827791 0.000337 +0.962188 0.272384 0.000000 +0.961660 0.274243 -0.000988 +0.961660 0.274243 -0.000988 +0.558547 0.829473 0.000612 +0.561036 0.827791 0.000337 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.884768 -0.466031 0.000000 +0.897736 -0.440534 0.000000 +0.897736 -0.440534 0.000000 +0.897736 -0.440534 0.000000 +0.884768 -0.466031 0.000000 +0.884768 -0.466031 0.000000 +0.000000 -0.000001 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 -0.000001 -1.000000 +-0.000000 -0.000001 -1.000000 +0.000000 -0.000001 -1.000000 +0.000000 -0.000001 -1.000000 +0.534108 -0.845416 0.000000 +0.079799 -0.996811 0.000000 +0.079799 -0.996811 0.000000 +0.079799 -0.996811 0.000000 +0.534108 -0.845416 0.000000 +0.534108 -0.845416 0.000000 +0.527538 0.848563 0.040552 +0.955706 0.294323 0.000002 +0.957663 0.287503 0.014966 +0.957663 0.287503 0.014966 +0.579778 0.812153 0.065308 +0.527538 0.848563 0.040552 +0.954794 -0.297267 0.000000 +0.534109 -0.845416 0.000000 +0.534108 -0.845416 0.000000 +0.534108 -0.845416 0.000000 +0.954794 -0.297269 0.000001 +0.954794 -0.297267 0.000000 +0.058423 0.998284 0.003992 +0.561036 0.827791 0.000337 +0.558547 0.829473 0.000612 +0.558547 0.829473 0.000612 +0.087074 0.996176 0.007225 +0.058423 0.998284 0.003992 +-0.000000 -0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +0.967232 -0.253893 0.000000 +0.884768 -0.466031 0.000000 +0.884768 -0.466031 0.000000 +0.884768 -0.466031 0.000000 +0.967232 -0.253893 0.000000 +0.967232 -0.253893 0.000000 +0.000001 -0.000001 -1.000000 +0.000000 -0.000001 -1.000000 +0.000000 -0.000001 -1.000000 +0.000000 -0.000001 -1.000000 +0.000002 -0.000000 -1.000000 +0.000001 -0.000001 -1.000000 +0.954794 -0.297268 0.000000 +0.534108 -0.845416 0.000000 +0.534108 -0.845416 0.000000 +0.534108 -0.845416 0.000000 +0.954794 -0.297268 -0.000000 +0.954794 -0.297268 0.000000 +0.060145 0.998104 -0.013067 +0.527538 0.848563 0.040552 +0.579778 0.812153 0.065308 +0.579778 0.812153 0.065308 +0.073338 0.997265 0.009197 +0.060145 0.998104 -0.013067 +0.058423 0.998284 0.003992 +0.087074 0.996176 0.007225 +0.000000 0.999961 0.008836 +0.000000 0.999961 0.008836 +0.000000 0.999990 0.004418 +0.058423 0.998284 0.003992 +0.073338 0.997265 0.009197 +0.058423 0.998284 0.003992 +0.000000 0.999990 0.004418 +0.000000 0.999990 0.004418 +0.000000 0.999649 -0.026483 +0.073338 0.997265 0.009197 +0.060145 0.998104 -0.013067 +0.073338 0.997265 0.009197 +0.000000 0.999649 -0.026483 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.999649 -0.026483 +0.000646 0.999660 -0.026085 +0.060145 0.998104 -0.013067 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 -0.000001 -0.000000 +1.000000 -0.000001 -0.000000 +1.000000 -0.000001 -0.000000 +1.000000 -0.000001 -0.000000 +1.000000 -0.000001 -0.000000 +1.000000 -0.000001 -0.000000 +1.000000 -0.000001 -0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 -0.000000 +1.000000 -0.000001 -0.000000 +-1.000000 0.000001 0.000000 +-1.000000 0.000001 0.000000 +-1.000000 0.000001 0.000000 +-1.000000 0.000001 0.000000 +-1.000000 0.000001 0.000000 +-1.000000 0.000001 0.000000 +-1.000000 0.000001 0.000000 +-1.000000 0.000001 0.000000 +-1.000000 0.000001 0.000000 +-1.000000 0.000001 0.000000 +-1.000000 0.000001 0.000000 +-1.000000 0.000001 0.000000 +0.000000 0.999961 0.008836 +0.000000 0.999961 0.008836 +0.000000 0.999990 0.004418 +0.000000 0.999990 0.004418 +0.000000 0.999990 0.004418 +0.000000 0.999961 0.008836 +0.000000 0.999990 0.004418 +0.000000 0.999990 0.004418 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.999990 0.004418 +-0.954794 -0.297269 0.000001 +-0.954794 -0.297267 0.000000 +-0.962188 0.272384 0.000000 +-0.962188 0.272384 0.000000 +-0.961660 0.274243 -0.000988 +-0.954794 -0.297269 0.000001 +-0.000000 1.000000 0.000561 +0.000000 0.999961 0.008836 +-0.001038 0.999992 0.003826 +-0.001038 0.999992 0.003826 +-0.000000 0.999999 -0.001678 +-0.000000 1.000000 0.000561 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +-0.967232 -0.253893 0.000000 +-0.967232 -0.253893 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-0.967232 -0.253893 0.000000 +-0.000000 0.999999 -0.001678 +-0.001038 0.999992 0.003826 +-0.000646 0.999660 -0.026085 +-0.000002 -0.000000 -1.000000 +-0.000001 -0.000001 -1.000000 +0.000003 -0.000000 -1.000000 +0.000003 -0.000000 -1.000000 +0.000004 -0.000002 -1.000000 +0.000003 -0.000000 -1.000000 +-0.000002 -0.000000 -1.000000 +0.000003 -0.000000 -1.000000 +0.000003 -0.000000 -1.000000 +-0.954794 -0.297268 -0.000000 +-0.954794 -0.297268 0.000000 +-0.955706 0.294323 0.000002 +-0.955706 0.294323 0.000002 +-0.957663 0.287503 0.014966 +-0.954794 -0.297268 -0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -0.000001 -1.000000 +0.000000 -0.000001 -1.000000 +-0.000000 -0.000001 -1.000000 +0.000000 0.000000 -1.000000 +0.079799 -0.996811 0.000000 +-0.079799 -0.996811 0.000000 +-0.079799 -0.996811 0.000000 +-0.079799 -0.996811 0.000000 +0.079799 -0.996811 0.000000 +0.079799 -0.996811 0.000000 +-0.534109 -0.845416 0.000000 +-0.534108 -0.845416 0.000000 +-0.079799 -0.996811 0.000000 +-0.079799 -0.996811 0.000000 +-0.079799 -0.996811 0.000000 +-0.534109 -0.845416 0.000000 +-0.561036 0.827791 0.000337 +-0.558547 0.829473 0.000612 +-0.961660 0.274243 -0.000988 +-0.961660 0.274243 -0.000988 +-0.962188 0.272384 0.000000 +-0.561036 0.827791 0.000337 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.884768 -0.466031 0.000000 +-0.884768 -0.466031 0.000000 +-0.897736 -0.440534 0.000000 +-0.897736 -0.440534 0.000000 +-0.897736 -0.440534 0.000000 +-0.884768 -0.466031 0.000000 +-0.000000 -0.000001 -1.000000 +-0.000000 -0.000001 -1.000000 +0.000000 -0.000001 -1.000000 +0.000000 -0.000001 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 -0.000001 -1.000000 +-0.534108 -0.845416 0.000000 +-0.534108 -0.845416 0.000000 +-0.079799 -0.996811 0.000000 +-0.079799 -0.996811 0.000000 +-0.079799 -0.996811 0.000000 +-0.534108 -0.845416 0.000000 +-0.527538 0.848563 0.040552 +-0.579778 0.812153 0.065307 +-0.957663 0.287503 0.014966 +-0.957663 0.287503 0.014966 +-0.955706 0.294323 0.000002 +-0.527538 0.848563 0.040552 +-0.954794 -0.297267 0.000000 +-0.954794 -0.297269 0.000001 +-0.534108 -0.845416 0.000000 +-0.534108 -0.845416 0.000000 +-0.534109 -0.845416 0.000000 +-0.954794 -0.297267 0.000000 +-0.058423 0.998284 0.003992 +-0.087074 0.996176 0.007225 +-0.558547 0.829473 0.000612 +-0.558547 0.829473 0.000612 +-0.561036 0.827791 0.000337 +-0.058423 0.998284 0.003992 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -0.000000 1.000000 +-0.967232 -0.253893 0.000000 +-0.967232 -0.253893 0.000000 +-0.884768 -0.466031 0.000000 +-0.884768 -0.466031 0.000000 +-0.884768 -0.466031 0.000000 +-0.967232 -0.253893 0.000000 +-0.000001 -0.000001 -1.000000 +-0.000002 -0.000000 -1.000000 +-0.000000 -0.000001 -1.000000 +-0.000000 -0.000001 -1.000000 +-0.000000 -0.000001 -1.000000 +-0.000001 -0.000001 -1.000000 +-0.954794 -0.297268 0.000000 +-0.954794 -0.297268 -0.000000 +-0.534108 -0.845416 0.000000 +-0.534108 -0.845416 0.000000 +-0.534108 -0.845416 0.000000 +-0.954794 -0.297268 0.000000 +-0.060145 0.998104 -0.013067 +-0.073338 0.997265 0.009197 +-0.579778 0.812153 0.065307 +-0.579778 0.812153 0.065307 +-0.527538 0.848563 0.040552 +-0.060145 0.998104 -0.013067 +-0.058423 0.998284 0.003992 +0.000000 0.999990 0.004418 +0.000000 0.999961 0.008836 +0.000000 0.999961 0.008836 +-0.087074 0.996176 0.007225 +-0.058423 0.998284 0.003992 +-0.073338 0.997265 0.009197 +0.000000 0.999649 -0.026483 +0.000000 0.999990 0.004418 +0.000000 0.999990 0.004418 +-0.058423 0.998284 0.003992 +-0.073338 0.997265 0.009197 +0.000000 0.999649 -0.026483 +-0.073338 0.997265 0.009197 +-0.060145 0.998104 -0.013067 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.000000 0.999999 -0.001678 +-0.000646 0.999660 -0.026085 +0.000000 0.999649 -0.026483 +0.000000 0.999649 -0.026483 +-0.060145 0.998104 -0.013067 +-0.000000 0.999999 -0.001678 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.079799 -0.996811 0.000000 +0.079799 -0.996811 0.000000 +0.079799 -0.996811 0.000000 +0.079799 -0.996811 0.000000 +-0.079799 -0.996811 0.000000 +-0.079799 -0.996811 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-1.000000 -0.000001 -0.000000 +-1.000000 -0.000001 -0.000000 +-1.000000 -0.000001 -0.000000 +-1.000000 -0.000001 -0.000000 +-1.000000 -0.000001 -0.000000 +-1.000000 -0.000001 -0.000000 +-1.000000 -0.000001 -0.000000 +-1.000000 -0.000001 -0.000000 +-1.000000 -0.000001 0.000000 +-1.000000 -0.000001 0.000000 +-1.000000 -0.000001 0.000000 +-1.000000 -0.000001 -0.000000 +1.000000 0.000001 0.000000 +1.000000 0.000001 0.000000 +1.000000 0.000001 0.000000 +1.000000 0.000001 0.000000 +1.000000 0.000001 0.000000 +1.000000 0.000001 0.000000 +1.000000 0.000001 0.000000 +1.000000 0.000001 0.000000 +1.000000 0.000001 0.000000 +1.000000 0.000001 0.000000 +1.000000 0.000001 0.000000 +1.000000 0.000001 0.000000 +0.000000 0.999961 0.008836 +0.000000 0.999990 0.004418 +0.000000 0.999990 0.004418 +0.000000 0.999990 0.004418 +0.000000 0.999961 0.008836 +0.000000 0.999961 0.008836 +0.000000 0.999990 0.004418 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.999990 0.004418 +0.000000 0.999990 0.004418 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.156433 -0.987270 -0.028768 +0.156433 -0.987270 -0.028768 +0.163765 -0.986072 -0.029039 +0.163765 -0.986072 -0.029039 +-0.163765 -0.986072 -0.029039 +-0.156433 -0.987270 -0.028768 +0.986405 -0.158422 -0.043684 +0.986405 0.158422 -0.043684 +0.985884 0.161615 -0.043735 +0.985884 0.161615 -0.043735 +0.985884 -0.161615 -0.043735 +0.986405 -0.158422 -0.043684 +0.156432 0.987270 -0.028768 +-0.156432 0.987270 -0.028768 +-0.163764 0.986072 -0.029039 +-0.163764 0.986072 -0.029039 +0.163764 0.986072 -0.029039 +0.156432 0.987270 -0.028768 +-0.986405 0.158422 -0.043684 +-0.986405 -0.158422 -0.043684 +-0.985884 -0.161615 -0.043735 +-0.985884 -0.161615 -0.043735 +-0.985884 0.161615 -0.043735 +-0.986405 0.158422 -0.043684 +0.033583 0.316870 -0.947874 +-0.033583 0.316870 -0.947874 +-0.061187 0.297691 -0.952699 +-0.061187 0.297691 -0.952699 +0.061187 0.297691 -0.952699 +0.033583 0.316870 -0.947874 +-0.397146 0.030264 -0.917256 +-0.397146 -0.030264 -0.917256 +-0.342229 -0.078768 -0.936309 +-0.342229 -0.078768 -0.936309 +-0.342228 0.078768 -0.936310 +-0.397146 0.030264 -0.917256 +-0.033583 -0.316870 -0.947874 +0.033583 -0.316870 -0.947874 +0.061186 -0.297691 -0.952699 +0.061186 -0.297691 -0.952699 +-0.061186 -0.297691 -0.952699 +-0.033583 -0.316870 -0.947874 +0.397146 -0.030264 -0.917256 +0.397146 0.030264 -0.917256 +0.342228 0.078768 -0.936309 +0.342228 0.078768 -0.936309 +0.342228 -0.078768 -0.936309 +0.397146 -0.030264 -0.917256 +-0.160182 -0.987087 0.000001 +0.160182 -0.987087 0.000001 +0.160182 -0.987087 0.000001 +0.160182 -0.987087 0.000001 +-0.160182 -0.987087 0.000001 +-0.160182 -0.987087 0.000001 +0.987088 -0.160182 0.000001 +0.987088 0.160181 0.000002 +0.987087 0.160182 0.000001 +0.987087 0.160182 0.000001 +0.987088 -0.160182 0.000002 +0.987088 -0.160182 0.000001 +0.160181 0.987088 0.000000 +-0.160181 0.987088 0.000001 +-0.160182 0.987087 0.000000 +-0.160182 0.987087 0.000000 +0.160182 0.987087 0.000001 +0.160181 0.987088 0.000000 +-0.987088 0.160181 0.000001 +-0.987087 -0.160182 0.000002 +-0.987088 -0.160182 0.000001 +-0.987088 -0.160182 0.000001 +-0.987088 0.160182 0.000002 +-0.987088 0.160181 0.000001 +0.000000 0.000001 1.000000 +-0.000000 0.000001 1.000000 +-0.000000 0.000001 1.000000 +-0.000000 0.000001 1.000000 +0.000000 0.000001 1.000000 +0.000000 0.000001 1.000000 +-0.000002 0.000000 1.000000 +-0.000002 -0.000000 1.000000 +-0.000002 -0.000000 1.000000 +-0.000002 -0.000000 1.000000 +-0.000002 0.000000 1.000000 +-0.000002 0.000000 1.000000 +-0.000000 -0.000001 1.000000 +0.000000 -0.000001 1.000000 +0.000000 -0.000001 1.000000 +0.000000 -0.000001 1.000000 +-0.000000 -0.000001 1.000000 +-0.000000 -0.000001 1.000000 +0.000002 -0.000000 1.000000 +0.000002 0.000000 1.000000 +0.000002 0.000000 1.000000 +0.000002 0.000000 1.000000 +0.000002 -0.000000 1.000000 +0.000002 -0.000000 1.000000 +0.708894 -0.703891 -0.044788 +0.163765 -0.986072 -0.029039 +0.156433 -0.987270 -0.028768 +0.156433 -0.987270 -0.028768 +0.703799 -0.708992 -0.044697 +0.708894 -0.703891 -0.044788 +-0.703799 -0.708992 -0.044697 +-0.156433 -0.987270 -0.028768 +-0.163765 -0.986072 -0.029039 +-0.163765 -0.986072 -0.029039 +-0.708894 -0.703891 -0.044788 +-0.703799 -0.708992 -0.044697 +0.708894 0.703892 -0.044788 +0.985884 0.161615 -0.043735 +0.986405 0.158422 -0.043684 +0.986405 0.158422 -0.043684 +0.703798 0.708992 -0.044697 +0.708894 0.703892 -0.044788 +-0.708894 0.703892 -0.044788 +-0.163764 0.986072 -0.029039 +-0.156432 0.987270 -0.028768 +-0.156432 0.987270 -0.028768 +-0.703798 0.708992 -0.044697 +-0.708894 0.703892 -0.044788 +0.191333 0.201883 -0.960539 +0.342228 0.078768 -0.936309 +0.397146 0.030264 -0.917256 +0.397146 0.030264 -0.917256 +0.211413 0.186282 -0.959481 +0.191333 0.201883 -0.960539 +-0.191333 0.201883 -0.960539 +-0.061187 0.297691 -0.952699 +-0.033583 0.316870 -0.947874 +-0.033583 0.316870 -0.947874 +-0.211413 0.186282 -0.959481 +-0.191333 0.201883 -0.960539 +0.191333 -0.201883 -0.960539 +0.061186 -0.297691 -0.952699 +0.033583 -0.316870 -0.947874 +0.033583 -0.316870 -0.947874 +0.211413 -0.186282 -0.959481 +0.191333 -0.201883 -0.960539 +-0.191333 -0.201884 -0.960539 +-0.342229 -0.078768 -0.936309 +-0.397146 -0.030264 -0.917256 +-0.397146 -0.030264 -0.917256 +-0.211413 -0.186282 -0.959481 +-0.191333 -0.201884 -0.960539 +-0.707107 -0.707106 0.000002 +-0.987088 -0.160182 0.000001 +-0.987087 -0.160182 0.000002 +-0.987087 -0.160182 0.000002 +-0.707107 -0.707106 0.000002 +-0.707107 -0.707106 0.000002 +0.707107 -0.707107 0.000002 +0.160182 -0.987087 0.000001 +0.160182 -0.987087 0.000001 +0.160182 -0.987087 0.000001 +0.707107 -0.707107 0.000002 +0.707107 -0.707107 0.000002 +-0.707107 0.707107 0.000002 +-0.160182 0.987087 0.000000 +-0.160181 0.987088 0.000001 +-0.160181 0.987088 0.000001 +-0.707107 0.707107 0.000002 +-0.707107 0.707107 0.000002 +0.707107 0.707106 0.000002 +0.987087 0.160182 0.000001 +0.987088 0.160181 0.000002 +0.987088 0.160181 0.000002 +0.707107 0.707107 0.000002 +0.707107 0.707106 0.000002 +0.000001 0.000001 1.000000 +0.000002 0.000000 1.000000 +0.000002 0.000000 1.000000 +0.000002 0.000000 1.000000 +0.000001 0.000001 1.000000 +0.000001 0.000001 1.000000 +-0.000001 0.000001 1.000000 +-0.000000 0.000001 1.000000 +-0.000000 0.000001 1.000000 +-0.000000 0.000001 1.000000 +-0.000001 0.000001 1.000000 +-0.000001 0.000001 1.000000 +0.000001 -0.000001 1.000000 +0.000000 -0.000001 1.000000 +0.000000 -0.000001 1.000000 +0.000000 -0.000001 1.000000 +0.000001 -0.000001 1.000000 +0.000001 -0.000001 1.000000 +-0.000001 -0.000001 1.000000 +-0.000002 -0.000000 1.000000 +-0.000002 -0.000000 1.000000 +-0.000002 -0.000000 1.000000 +-0.000001 -0.000001 1.000000 +-0.000001 -0.000001 1.000000 +0.985884 -0.161615 -0.043735 +0.708894 -0.703891 -0.044788 +0.703799 -0.708992 -0.044697 +0.703799 -0.708992 -0.044697 +0.986405 -0.158422 -0.043684 +0.985884 -0.161615 -0.043735 +-0.986405 -0.158422 -0.043684 +-0.703799 -0.708992 -0.044697 +-0.708894 -0.703891 -0.044788 +-0.708894 -0.703891 -0.044788 +-0.985884 -0.161615 -0.043735 +-0.986405 -0.158422 -0.043684 +0.163764 0.986072 -0.029039 +0.708894 0.703892 -0.044788 +0.703798 0.708992 -0.044697 +0.703798 0.708992 -0.044697 +0.156432 0.987270 -0.028768 +0.163764 0.986072 -0.029039 +-0.985884 0.161615 -0.043735 +-0.708894 0.703892 -0.044788 +-0.703798 0.708992 -0.044697 +-0.703798 0.708992 -0.044697 +-0.986405 0.158422 -0.043684 +-0.985884 0.161615 -0.043735 +0.061187 0.297691 -0.952699 +0.191333 0.201883 -0.960539 +0.211413 0.186282 -0.959481 +0.211413 0.186282 -0.959481 +0.033583 0.316870 -0.947874 +0.061187 0.297691 -0.952699 +-0.342228 0.078768 -0.936310 +-0.191333 0.201883 -0.960539 +-0.211413 0.186282 -0.959481 +-0.211413 0.186282 -0.959481 +-0.397146 0.030264 -0.917256 +-0.342228 0.078768 -0.936310 +0.342228 -0.078768 -0.936309 +0.191333 -0.201883 -0.960539 +0.211413 -0.186282 -0.959481 +0.211413 -0.186282 -0.959481 +0.397146 -0.030264 -0.917256 +0.342228 -0.078768 -0.936309 +-0.061186 -0.297691 -0.952699 +-0.191333 -0.201884 -0.960539 +-0.211413 -0.186282 -0.959481 +-0.211413 -0.186282 -0.959481 +-0.033583 -0.316870 -0.947874 +-0.061186 -0.297691 -0.952699 +-0.160182 -0.987087 0.000001 +-0.707107 -0.707106 0.000002 +-0.707107 -0.707106 0.000002 +-0.707107 -0.707106 0.000002 +-0.160182 -0.987087 0.000001 +-0.160182 -0.987087 0.000001 +0.987088 -0.160182 0.000002 +0.707107 -0.707107 0.000002 +0.707107 -0.707107 0.000002 +0.707107 -0.707107 0.000002 +0.987088 -0.160182 0.000001 +0.987088 -0.160182 0.000002 +-0.987088 0.160182 0.000002 +-0.707107 0.707107 0.000002 +-0.707107 0.707107 0.000002 +-0.707107 0.707107 0.000002 +-0.987088 0.160181 0.000001 +-0.987088 0.160182 0.000002 +0.160182 0.987087 0.000001 +0.707107 0.707106 0.000002 +0.707107 0.707107 0.000002 +0.707107 0.707107 0.000002 +0.160181 0.987088 0.000000 +0.160182 0.987087 0.000001 +0.000000 0.000001 1.000000 +0.000001 0.000001 1.000000 +0.000001 0.000001 1.000000 +0.000001 0.000001 1.000000 +0.000000 0.000001 1.000000 +0.000000 0.000001 1.000000 +-0.000002 0.000000 1.000000 +-0.000001 0.000001 1.000000 +-0.000001 0.000001 1.000000 +-0.000001 0.000001 1.000000 +-0.000002 0.000000 1.000000 +-0.000002 0.000000 1.000000 +0.000002 -0.000000 1.000000 +0.000001 -0.000001 1.000000 +0.000001 -0.000001 1.000000 +0.000001 -0.000001 1.000000 +0.000002 -0.000000 1.000000 +0.000002 -0.000000 1.000000 +-0.000000 -0.000001 1.000000 +-0.000001 -0.000001 1.000000 +-0.000001 -0.000001 1.000000 +-0.000001 -0.000001 1.000000 +-0.000000 -0.000001 1.000000 +-0.000000 -0.000001 1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.902388 -0.430926 +0.000000 0.902387 -0.430926 +0.000000 0.902388 -0.430926 +0.000000 0.902388 -0.430926 +0.000000 0.902387 -0.430926 +0.000000 0.902388 -0.430926 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.902388 -0.430926 +0.000000 0.902387 -0.430926 +0.000000 0.902388 -0.430926 +0.000000 0.902388 -0.430926 +0.000000 0.902387 -0.430926 +0.000000 0.902388 -0.430926 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.999470 0.000000 -0.032547 +-0.999470 0.000000 -0.032547 +-0.999470 0.000000 -0.032547 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 -0.902388 -0.430926 +0.000000 -0.902387 -0.430926 +0.000000 -0.902388 -0.430926 +0.000000 -0.902388 -0.430926 +0.000000 -0.902387 -0.430926 +0.000000 -0.902388 -0.430926 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -0.902388 -0.430926 +0.000000 -0.902387 -0.430926 +0.000000 -0.902388 -0.430926 +0.000000 -0.902388 -0.430926 +0.000000 -0.902387 -0.430926 +0.000000 -0.902388 -0.430926 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.999470 0.000000 -0.032547 +-0.999470 0.000000 -0.032547 +-0.999470 0.000000 -0.032547 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.902387 0.000000 -0.430926 +-0.902387 0.000000 -0.430926 +-0.902387 0.000000 -0.430926 +-0.902387 0.000000 -0.430926 +-0.902387 0.000000 -0.430926 +-0.902387 0.000000 -0.430926 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.902387 0.000000 -0.430926 +-0.902387 0.000000 -0.430926 +-0.902387 0.000000 -0.430926 +-0.902387 0.000000 -0.430926 +-0.902387 0.000000 -0.430926 +-0.902387 0.000000 -0.430926 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.902387 0.000000 -0.430926 +-0.902387 0.000000 -0.430926 +-0.902387 0.000000 -0.430926 +-0.902387 0.000000 -0.430926 +-0.902387 0.000000 -0.430926 +-0.902387 0.000000 -0.430926 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.902387 0.000000 -0.430926 +0.902387 0.000000 -0.430926 +0.902387 0.000000 -0.430926 +0.902387 0.000000 -0.430926 +0.902387 0.000000 -0.430926 +0.902387 0.000000 -0.430926 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.902387 0.000000 -0.430926 +0.902387 0.000000 -0.430926 +0.902387 0.000000 -0.430926 +0.902387 0.000000 -0.430926 +0.902387 0.000000 -0.430926 +0.902387 0.000000 -0.430926 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.902387 0.000000 -0.430926 +0.902387 0.000000 -0.430926 +0.902387 0.000000 -0.430926 +0.902387 0.000000 -0.430926 +0.902387 0.000000 -0.430926 +0.902387 0.000000 -0.430926 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 -0.000000 +0.939693 0.000000 -0.342019 +0.939693 -0.000000 -0.342020 +0.939693 -0.000000 -0.342020 +1.000000 -0.000000 -0.000000 +1.000000 0.000000 -0.000000 +0.939693 0.000000 -0.342019 +0.766045 0.000000 -0.642787 +0.766045 0.000000 -0.642787 +0.766045 0.000000 -0.642787 +0.939693 -0.000000 -0.342020 +0.939693 0.000000 -0.342019 +0.766045 0.000000 -0.642787 +0.499999 0.000000 -0.866026 +0.499999 0.000000 -0.866026 +0.499999 0.000000 -0.866026 +0.766045 0.000000 -0.642787 +0.766045 0.000000 -0.642787 +0.499999 0.000000 -0.866026 +0.173648 0.000000 -0.984808 +0.173648 0.000000 -0.984808 +0.173648 0.000000 -0.984808 +0.499999 0.000000 -0.866026 +0.499999 0.000000 -0.866026 +0.173648 0.000000 -0.984808 +-0.173648 0.000000 -0.984808 +-0.173648 0.000000 -0.984808 +-0.173648 0.000000 -0.984808 +0.173648 0.000000 -0.984808 +0.173648 0.000000 -0.984808 +-0.173648 0.000000 -0.984808 +-0.500000 0.000000 -0.866025 +-0.500000 0.000000 -0.866025 +-0.500000 0.000000 -0.866025 +-0.173648 0.000000 -0.984808 +-0.173648 0.000000 -0.984808 +-0.500000 0.000000 -0.866025 +-0.766044 0.000000 -0.642788 +-0.766044 0.000000 -0.642788 +-0.766044 0.000000 -0.642788 +-0.500000 0.000000 -0.866025 +-0.500000 0.000000 -0.866025 +-0.766044 0.000000 -0.642788 +-0.939692 -0.000000 -0.342020 +-0.939692 0.000000 -0.342021 +-0.939692 0.000000 -0.342021 +-0.766044 0.000000 -0.642788 +-0.766044 0.000000 -0.642788 +-0.939692 -0.000000 -0.342020 +-1.000000 -0.000000 0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-0.939692 0.000000 -0.342021 +-0.939692 -0.000000 -0.342020 +-1.000000 -0.000000 0.000000 +-0.939693 0.000000 0.342020 +-0.939693 0.000000 0.342020 +-0.939693 0.000000 0.342020 +-1.000000 0.000000 -0.000000 +-1.000000 -0.000000 0.000000 +-0.939693 0.000000 0.342020 +-0.766045 0.000000 0.642787 +-0.766045 0.000000 0.642787 +-0.766045 0.000000 0.642787 +-0.939693 0.000000 0.342020 +-0.939693 0.000000 0.342020 +-0.766045 0.000000 0.642787 +-0.500000 0.000000 0.866025 +-0.500000 0.000000 0.866025 +-0.500000 0.000000 0.866025 +-0.766045 0.000000 0.642787 +-0.766045 0.000000 0.642787 +-0.500000 0.000000 0.866025 +-0.173649 0.000000 0.984808 +-0.173649 0.000000 0.984808 +-0.173649 0.000000 0.984808 +-0.500000 0.000000 0.866025 +-0.500000 0.000000 0.866025 +-0.173649 0.000000 0.984808 +0.173647 0.000000 0.984808 +0.173647 0.000000 0.984808 +0.173647 0.000000 0.984808 +-0.173649 0.000000 0.984808 +-0.173649 0.000000 0.984808 +0.173647 0.000000 0.984808 +0.500000 0.000000 0.866026 +0.500000 0.000000 0.866026 +0.500000 0.000000 0.866026 +0.173647 0.000000 0.984808 +0.173647 0.000000 0.984808 +0.500000 0.000000 0.866026 +0.766044 0.000000 0.642788 +0.766044 0.000000 0.642788 +0.766044 0.000000 0.642788 +0.500000 0.000000 0.866026 +0.500000 0.000000 0.866026 +0.766044 0.000000 0.642788 +0.939692 0.000000 0.342021 +0.939692 0.000000 0.342021 +0.939692 0.000000 0.342021 +0.766044 0.000000 0.642788 +0.766044 0.000000 0.642788 +0.939692 0.000000 0.342021 +1.000000 0.000000 -0.000000 +1.000000 -0.000000 -0.000000 +1.000000 -0.000000 -0.000000 +0.939692 0.000000 0.342021 +0.939692 0.000000 0.342021 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-0.939694 -0.000000 -0.342017 +-0.939694 -0.000000 -0.342017 +-0.939694 0.000000 -0.342017 +-1.000000 0.000000 -0.000000 +-0.939694 0.000000 -0.342017 +-0.939694 -0.000000 -0.342017 +-0.766044 0.000000 -0.642789 +-0.766044 0.000000 -0.642789 +-0.766043 0.000000 -0.642789 +-0.939694 0.000000 -0.342017 +-0.766043 0.000000 -0.642789 +-0.766044 0.000000 -0.642789 +-0.499998 0.000000 -0.866026 +-0.499998 0.000000 -0.866026 +-0.499998 0.000000 -0.866026 +-0.766043 0.000000 -0.642789 +-0.499998 0.000000 -0.866026 +-0.499998 0.000000 -0.866026 +-0.173649 0.000000 -0.984808 +-0.173649 0.000000 -0.984808 +-0.173649 0.000000 -0.984808 +-0.499998 0.000000 -0.866026 +-0.173649 0.000000 -0.984808 +-0.173649 0.000000 -0.984808 +0.173649 0.000000 -0.984808 +0.173649 0.000000 -0.984808 +0.173649 0.000000 -0.984808 +-0.173649 0.000000 -0.984808 +0.173649 0.000000 -0.984808 +0.173649 0.000000 -0.984808 +0.499999 0.000000 -0.866026 +0.499999 0.000000 -0.866026 +0.499999 0.000000 -0.866026 +0.173649 0.000000 -0.984808 +0.499999 0.000000 -0.866026 +0.499999 0.000000 -0.866026 +0.766043 0.000000 -0.642789 +0.766043 0.000000 -0.642789 +0.766043 0.000000 -0.642789 +0.499999 0.000000 -0.866026 +0.766043 0.000000 -0.642789 +0.766043 0.000000 -0.642789 +0.939693 0.000000 -0.342019 +0.939693 0.000000 -0.342019 +0.939693 -0.000000 -0.342019 +0.766043 0.000000 -0.642789 +0.939693 -0.000000 -0.342019 +0.939693 0.000000 -0.342019 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 -0.000000 0.000000 +0.939693 -0.000000 -0.342019 +1.000000 -0.000000 0.000000 +1.000000 0.000000 -0.000000 +0.939693 0.000000 0.342019 +0.939693 0.000000 0.342019 +0.939693 0.000000 0.342019 +1.000000 -0.000000 0.000000 +0.939693 0.000000 0.342019 +0.939693 0.000000 0.342019 +0.766044 0.000000 0.642788 +0.766044 0.000000 0.642788 +0.766044 0.000000 0.642788 +0.939693 0.000000 0.342019 +0.766044 0.000000 0.642788 +0.766044 0.000000 0.642788 +0.500000 0.000000 0.866025 +0.500000 0.000000 0.866025 +0.500000 0.000000 0.866025 +0.766044 0.000000 0.642788 +0.500000 0.000000 0.866025 +0.500000 0.000000 0.866025 +0.173648 0.000000 0.984808 +0.173648 0.000000 0.984808 +0.173648 0.000000 0.984808 +0.500000 0.000000 0.866025 +0.173648 0.000000 0.984808 +0.173648 0.000000 0.984808 +-0.173648 0.000000 0.984808 +-0.173648 0.000000 0.984808 +-0.173648 0.000000 0.984808 +0.173648 0.000000 0.984808 +-0.173648 0.000000 0.984808 +-0.173648 0.000000 0.984808 +-0.499999 0.000000 0.866026 +-0.499999 0.000000 0.866026 +-0.499999 0.000000 0.866026 +-0.173648 0.000000 0.984808 +-0.499999 0.000000 0.866026 +-0.499999 0.000000 0.866026 +-0.766043 0.000000 0.642789 +-0.766043 0.000000 0.642789 +-0.766043 0.000000 0.642789 +-0.499999 0.000000 0.866026 +-0.766043 0.000000 0.642789 +-0.766043 0.000000 0.642789 +-0.939693 0.000000 0.342019 +-0.939693 0.000000 0.342019 +-0.939693 0.000000 0.342019 +-0.766043 0.000000 0.642789 +-0.939693 0.000000 0.342019 +-0.939693 0.000000 0.342019 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-0.939693 0.000000 0.342019 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +0.939693 0.000000 -0.342020 +0.939693 0.000000 -0.342020 +0.939693 -0.000000 -0.342019 +1.000000 0.000000 -0.000000 +0.939693 -0.000000 -0.342019 +0.939693 0.000000 -0.342020 +0.766045 -0.000000 -0.642787 +0.766045 -0.000000 -0.642787 +0.766045 -0.000000 -0.642787 +0.939693 -0.000000 -0.342019 +0.766045 -0.000000 -0.642787 +0.766045 -0.000000 -0.642787 +0.500000 -0.000000 -0.866026 +0.500000 -0.000000 -0.866026 +0.500000 0.000000 -0.866026 +0.766045 -0.000000 -0.642787 +0.500000 0.000000 -0.866026 +0.500000 -0.000000 -0.866026 +0.173648 0.000000 -0.984808 +0.173648 0.000000 -0.984808 +0.173648 0.000000 -0.984808 +0.500000 0.000000 -0.866026 +0.173648 0.000000 -0.984808 +0.173648 0.000000 -0.984808 +-0.173649 0.000000 -0.984808 +-0.173649 0.000000 -0.984808 +-0.173649 0.000000 -0.984808 +0.173648 0.000000 -0.984808 +-0.173649 0.000000 -0.984808 +-0.173649 0.000000 -0.984808 +-0.500000 0.000000 -0.866025 +-0.500000 0.000000 -0.866025 +-0.500000 -0.000000 -0.866025 +-0.173649 0.000000 -0.984808 +-0.500000 -0.000000 -0.866025 +-0.500000 0.000000 -0.866025 +-0.766044 -0.000000 -0.642788 +-0.766044 -0.000000 -0.642788 +-0.766044 -0.000000 -0.642788 +-0.500000 -0.000000 -0.866025 +-0.766044 -0.000000 -0.642788 +-0.766044 -0.000000 -0.642788 +-0.939693 -0.000000 -0.342020 +-0.939693 -0.000000 -0.342020 +-0.939693 -0.000000 -0.342020 +-0.766044 -0.000000 -0.642788 +-0.939693 -0.000000 -0.342020 +-0.939693 -0.000000 -0.342020 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 -0.000000 -0.000000 +-0.939693 -0.000000 -0.342020 +-1.000000 -0.000000 -0.000000 +-1.000000 0.000000 0.000000 +-0.939693 0.000000 0.342020 +-0.939693 0.000000 0.342020 +-0.939693 0.000000 0.342020 +-1.000000 -0.000000 -0.000000 +-0.939693 0.000000 0.342020 +-0.939693 0.000000 0.342020 +-0.766045 0.000000 0.642787 +-0.766045 0.000000 0.642787 +-0.766045 0.000000 0.642787 +-0.939693 0.000000 0.342020 +-0.766045 0.000000 0.642787 +-0.766045 0.000000 0.642787 +-0.500000 0.000000 0.866025 +-0.500000 0.000000 0.866025 +-0.500000 0.000000 0.866025 +-0.766045 0.000000 0.642787 +-0.500000 0.000000 0.866025 +-0.500000 0.000000 0.866025 +-0.173648 0.000000 0.984808 +-0.173648 0.000000 0.984808 +-0.173648 0.000000 0.984808 +-0.500000 0.000000 0.866025 +-0.173648 0.000000 0.984808 +-0.173648 0.000000 0.984808 +0.173647 0.000000 0.984808 +0.173647 0.000000 0.984808 +0.173647 0.000000 0.984808 +-0.173648 0.000000 0.984808 +0.173647 0.000000 0.984808 +0.173647 0.000000 0.984808 +0.500000 0.000000 0.866026 +0.500000 0.000000 0.866026 +0.500000 0.000000 0.866026 +0.173647 0.000000 0.984808 +0.500000 0.000000 0.866026 +0.500000 0.000000 0.866026 +0.766044 0.000000 0.642788 +0.766044 0.000000 0.642788 +0.766044 0.000000 0.642788 +0.500000 0.000000 0.866026 +0.766044 0.000000 0.642788 +0.766044 0.000000 0.642788 +0.939692 0.000000 0.342021 +0.939692 0.000000 0.342021 +0.939692 0.000000 0.342021 +0.766044 0.000000 0.642788 +0.939692 0.000000 0.342021 +0.939692 0.000000 0.342021 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +0.939692 0.000000 0.342021 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 -0.000000 +-0.939694 -0.000000 -0.342017 +-0.939694 0.000000 -0.342017 +-0.939694 0.000000 -0.342017 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-0.939694 -0.000000 -0.342017 +-0.766044 -0.000000 -0.642789 +-0.766044 -0.000000 -0.642789 +-0.766044 -0.000000 -0.642789 +-0.939694 0.000000 -0.342017 +-0.939694 -0.000000 -0.342017 +-0.766044 -0.000000 -0.642789 +-0.499998 0.000000 -0.866026 +-0.499998 -0.000000 -0.866026 +-0.499998 -0.000000 -0.866026 +-0.766044 -0.000000 -0.642789 +-0.766044 -0.000000 -0.642789 +-0.499998 0.000000 -0.866026 +-0.173649 0.000000 -0.984808 +-0.173649 0.000000 -0.984808 +-0.173649 0.000000 -0.984808 +-0.499998 -0.000000 -0.866026 +-0.499998 0.000000 -0.866026 +-0.173649 0.000000 -0.984808 +0.173649 0.000000 -0.984808 +0.173649 0.000000 -0.984808 +0.173649 0.000000 -0.984808 +-0.173649 0.000000 -0.984808 +-0.173649 0.000000 -0.984808 +0.173649 0.000000 -0.984808 +0.500000 -0.000000 -0.866026 +0.500000 0.000000 -0.866026 +0.500000 0.000000 -0.866026 +0.173649 0.000000 -0.984808 +0.173649 0.000000 -0.984808 +0.500000 -0.000000 -0.866026 +0.766043 -0.000000 -0.642789 +0.766043 -0.000000 -0.642789 +0.766043 -0.000000 -0.642789 +0.500000 0.000000 -0.866026 +0.500000 -0.000000 -0.866026 +0.766043 -0.000000 -0.642789 +0.939693 -0.000000 -0.342019 +0.939693 -0.000000 -0.342019 +0.939693 -0.000000 -0.342019 +0.766043 -0.000000 -0.642789 +0.766043 -0.000000 -0.642789 +0.939693 -0.000000 -0.342019 +1.000000 -0.000000 -0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.939693 -0.000000 -0.342019 +0.939693 -0.000000 -0.342019 +1.000000 -0.000000 -0.000000 +0.939693 0.000000 0.342019 +0.939693 0.000000 0.342019 +0.939693 0.000000 0.342019 +1.000000 0.000000 0.000000 +1.000000 -0.000000 -0.000000 +0.939693 0.000000 0.342019 +0.766044 0.000000 0.642788 +0.766044 0.000000 0.642788 +0.766044 0.000000 0.642788 +0.939693 0.000000 0.342019 +0.939693 0.000000 0.342019 +0.766044 0.000000 0.642788 +0.500000 0.000000 0.866025 +0.500000 0.000000 0.866025 +0.500000 0.000000 0.866025 +0.766044 0.000000 0.642788 +0.766044 0.000000 0.642788 +0.500000 0.000000 0.866025 +0.173648 0.000000 0.984808 +0.173648 0.000000 0.984808 +0.173648 0.000000 0.984808 +0.500000 0.000000 0.866025 +0.500000 0.000000 0.866025 +0.173648 0.000000 0.984808 +-0.173648 0.000000 0.984808 +-0.173648 0.000000 0.984808 +-0.173648 0.000000 0.984808 +0.173648 0.000000 0.984808 +0.173648 0.000000 0.984808 +-0.173648 0.000000 0.984808 +-0.499999 0.000000 0.866026 +-0.499999 0.000000 0.866026 +-0.499999 0.000000 0.866026 +-0.173648 0.000000 0.984808 +-0.173648 0.000000 0.984808 +-0.499999 0.000000 0.866026 +-0.766043 0.000000 0.642789 +-0.766043 0.000000 0.642789 +-0.766043 0.000000 0.642789 +-0.499999 0.000000 0.866026 +-0.499999 0.000000 0.866026 +-0.766043 0.000000 0.642789 +-0.939693 0.000000 0.342019 +-0.939693 0.000000 0.342019 +-0.939693 0.000000 0.342019 +-0.766043 0.000000 0.642789 +-0.766043 0.000000 0.642789 +-0.939693 0.000000 0.342019 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-0.939693 0.000000 0.342019 +-0.939693 0.000000 0.342019 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.000001 -1.000000 -0.000009 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.000001 -1.000000 -0.000000 +0.000000 -1.000000 0.000000 +-0.000001 -1.000000 -0.000009 +-0.000001 -1.000000 -0.000009 +-0.000005 -1.000000 -0.000032 +-0.000001 -1.000000 -0.000000 +-0.000005 -1.000000 0.000015 +-0.000001 -1.000000 -0.000000 +-0.000005 -1.000000 -0.000032 +-0.000005 -1.000000 -0.000032 +0.000000 -1.000000 0.000054 +-0.000005 -1.000000 0.000015 +0.000000 -1.000000 0.000054 +0.000000 -1.000000 0.000000 +-0.000005 -1.000000 0.000015 +0.809111 0.000000 -0.587656 +0.973737 0.000000 -0.227676 +0.973737 0.000000 -0.227676 +0.973737 0.000000 -0.227676 +0.809110 -0.000003 -0.587657 +0.809111 0.000000 -0.587656 +-0.973737 0.000000 0.227677 +-0.973737 0.000000 0.227677 +-0.973737 0.000000 0.227677 +-0.973737 0.000000 0.227677 +-0.973737 0.000000 0.227677 +-0.973737 0.000000 0.227677 +-0.973737 -0.000003 0.227677 +-0.973737 0.000000 0.227677 +-0.973737 -0.000000 0.227677 +-0.973737 -0.000000 0.227677 +-0.973737 -0.000003 0.227677 +-0.973737 -0.000003 0.227677 +0.973737 0.000000 -0.227676 +0.809111 0.000000 -0.587656 +0.809111 0.000000 -0.587656 +0.809111 0.000000 -0.587656 +0.973737 0.000000 -0.227676 +0.973737 0.000000 -0.227676 +0.431554 -0.000021 -0.902087 +0.809111 0.000000 -0.587656 +0.809110 -0.000003 -0.587657 +0.809110 -0.000003 -0.587657 +0.431556 -0.000021 -0.902086 +0.431554 -0.000021 -0.902087 +-0.517703 -0.000008 -0.855561 +-0.431563 -0.000021 -0.902083 +-0.431565 -0.000022 -0.902082 +-0.431565 -0.000022 -0.902082 +-0.517701 -0.000003 -0.855562 +-0.517703 -0.000008 -0.855561 +0.232218 -0.000004 -0.972664 +0.431554 -0.000021 -0.902087 +0.431556 -0.000021 -0.902086 +0.431556 -0.000021 -0.902086 +0.232219 0.000000 -0.972663 +0.232218 -0.000004 -0.972664 +-0.431563 -0.000021 -0.902083 +-0.232215 0.000000 -0.972664 +-0.232217 -0.000004 -0.972664 +-0.232217 -0.000004 -0.972664 +-0.431565 -0.000022 -0.902082 +-0.431563 -0.000021 -0.902083 +-0.232215 0.000000 -0.972664 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.232217 -0.000004 -0.972664 +-0.232215 0.000000 -0.972664 +0.000000 0.000000 -1.000000 +0.232218 -0.000004 -0.972664 +0.232219 0.000000 -0.972663 +0.232219 0.000000 -0.972663 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.431540 0.000119 -0.902094 +-0.517708 0.000014 -0.855557 +-0.517697 0.000044 -0.855564 +-0.517697 0.000044 -0.855564 +-0.431571 0.000065 -0.902079 +-0.431540 0.000119 -0.902094 +0.809111 0.000000 -0.587656 +0.431565 -0.000007 -0.902082 +0.431568 0.000000 -0.902080 +0.431568 0.000000 -0.902080 +0.809111 0.000000 -0.587656 +0.809111 0.000000 -0.587656 +-0.232300 -0.000284 -0.972644 +-0.431540 0.000119 -0.902094 +-0.431571 0.000065 -0.902079 +-0.431571 0.000065 -0.902079 +-0.232283 -0.000276 -0.972648 +-0.232300 -0.000284 -0.972644 +0.431565 -0.000007 -0.902082 +0.232180 -0.000019 -0.972673 +0.232167 -0.000042 -0.972676 +0.232167 -0.000042 -0.972676 +0.431568 0.000000 -0.902080 +0.431565 -0.000007 -0.902082 +0.232180 -0.000019 -0.972673 +0.000091 0.000075 -1.000000 +0.000114 0.000121 -1.000000 +0.000114 0.000121 -1.000000 +0.232167 -0.000042 -0.972676 +0.232180 -0.000019 -0.972673 +0.000091 0.000075 -1.000000 +-0.232300 -0.000284 -0.972644 +-0.232283 -0.000276 -0.972648 +-0.232283 -0.000276 -0.972648 +0.000114 0.000121 -1.000000 +0.000091 0.000075 -1.000000 +0.984808 0.000000 -0.173645 +0.642787 0.000000 -0.766045 +0.642787 0.000000 -0.766045 +0.642787 0.000000 -0.766045 +0.984808 0.000000 -0.173645 +0.984808 0.000000 -0.173645 +0.642787 0.000000 -0.766045 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.642787 0.000000 -0.766045 +0.642787 0.000000 -0.766045 +0.000001 0.000000 -1.000000 +-0.642786 0.000000 -0.766046 +-0.642786 0.000000 -0.766046 +-0.642786 0.000000 -0.766046 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +-0.642786 0.000000 -0.766046 +-0.984808 0.000000 -0.173648 +-0.984808 0.000000 -0.173648 +-0.984808 0.000000 -0.173648 +-0.642786 0.000000 -0.766046 +-0.642786 0.000000 -0.766046 +-0.984808 0.000000 -0.173648 +-0.866024 0.000000 0.500002 +-0.866024 0.000000 0.500002 +-0.866024 0.000000 0.500002 +-0.984808 0.000000 -0.173648 +-0.984808 0.000000 -0.173648 +-0.866024 0.000000 0.500002 +-0.342020 0.000000 0.939693 +-0.342020 0.000000 0.939693 +-0.342020 0.000000 0.939693 +-0.866024 0.000000 0.500002 +-0.866024 0.000000 0.500002 +-0.342020 0.000000 0.939693 +0.342022 0.000000 0.939692 +0.342022 0.000000 0.939692 +0.342022 0.000000 0.939692 +-0.342020 0.000000 0.939693 +-0.342020 0.000000 0.939693 +0.342022 0.000000 0.939692 +0.866024 0.000000 0.500002 +0.866024 0.000000 0.500002 +0.866024 0.000000 0.500002 +0.342022 0.000000 0.939692 +0.342022 0.000000 0.939692 +0.866024 0.000000 0.500002 +0.984808 0.000000 -0.173645 +0.984808 0.000000 -0.173645 +0.984808 0.000000 -0.173645 +0.866024 0.000000 0.500002 +0.866024 0.000000 0.500002 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000001 -1.000000 -0.000009 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000001 -1.000000 -0.000000 +0.000005 -1.000000 -0.000032 +0.000001 -1.000000 -0.000009 +0.000001 -1.000000 -0.000009 +0.000000 -1.000000 0.000000 +0.000001 -1.000000 -0.000000 +0.000005 -1.000000 0.000015 +0.000000 -1.000000 0.000054 +0.000005 -1.000000 -0.000032 +0.000005 -1.000000 -0.000032 +0.000001 -1.000000 -0.000000 +0.000005 -1.000000 0.000015 +0.000000 -1.000000 0.000054 +0.000005 -1.000000 0.000015 +0.000000 -1.000000 0.000000 +-0.809109 0.000000 -0.587658 +-0.809108 -0.000003 -0.587659 +-0.973737 0.000000 -0.227677 +-0.973737 0.000000 -0.227677 +-0.973737 0.000000 -0.227677 +-0.809109 0.000000 -0.587658 +0.973737 0.000000 0.227677 +0.973737 0.000000 0.227677 +0.973737 0.000001 0.227677 +0.973737 0.000001 0.227677 +0.973737 0.000001 0.227677 +0.973737 0.000000 0.227677 +0.973737 -0.000004 0.227677 +0.973737 -0.000004 0.227677 +0.973737 -0.000000 0.227677 +0.973737 -0.000000 0.227677 +0.973737 0.000000 0.227677 +0.973737 -0.000004 0.227677 +-0.973737 0.000000 -0.227677 +-0.973737 0.000000 -0.227677 +-0.809109 0.000000 -0.587658 +-0.809109 0.000000 -0.587658 +-0.809109 0.000000 -0.587658 +-0.973737 0.000000 -0.227677 +-0.431551 -0.000021 -0.902089 +-0.431552 -0.000021 -0.902088 +-0.809108 -0.000003 -0.587659 +-0.809108 -0.000003 -0.587659 +-0.809109 0.000000 -0.587658 +-0.431551 -0.000021 -0.902089 +0.517705 -0.000008 -0.855559 +0.517703 -0.000003 -0.855560 +0.431564 -0.000022 -0.902083 +0.431564 -0.000022 -0.902083 +0.431562 -0.000021 -0.902083 +0.517705 -0.000008 -0.855559 +-0.232218 -0.000004 -0.972664 +-0.232219 0.000000 -0.972663 +-0.431552 -0.000021 -0.902088 +-0.431552 -0.000021 -0.902088 +-0.431551 -0.000021 -0.902089 +-0.232218 -0.000004 -0.972664 +0.431562 -0.000021 -0.902083 +0.431564 -0.000022 -0.902083 +0.232214 -0.000004 -0.972665 +0.232214 -0.000004 -0.972665 +0.232213 0.000000 -0.972665 +0.431562 -0.000021 -0.902083 +0.232213 0.000000 -0.972665 +0.232214 -0.000004 -0.972665 +-0.000001 0.000000 -1.000000 +-0.000001 0.000000 -1.000000 +-0.000001 0.000000 -1.000000 +0.232213 0.000000 -0.972665 +-0.000001 0.000000 -1.000000 +-0.000001 0.000000 -1.000000 +-0.232219 0.000000 -0.972663 +-0.232219 0.000000 -0.972663 +-0.232218 -0.000004 -0.972664 +-0.000001 0.000000 -1.000000 +0.431539 0.000119 -0.902094 +0.431569 0.000065 -0.902080 +0.517700 0.000044 -0.855562 +0.517700 0.000044 -0.855562 +0.517711 0.000014 -0.855556 +0.431539 0.000119 -0.902094 +-0.809109 0.000000 -0.587658 +-0.809109 0.000000 -0.587658 +-0.431565 0.000000 -0.902082 +-0.431565 0.000000 -0.902082 +-0.431562 -0.000007 -0.902083 +-0.809109 0.000000 -0.587658 +0.232298 -0.000284 -0.972645 +0.232281 -0.000276 -0.972649 +0.431569 0.000065 -0.902080 +0.431569 0.000065 -0.902080 +0.431539 0.000119 -0.902094 +0.232298 -0.000284 -0.972645 +-0.431562 -0.000007 -0.902083 +-0.431565 0.000000 -0.902082 +-0.232167 -0.000042 -0.972676 +-0.232167 -0.000042 -0.972676 +-0.232180 -0.000019 -0.972673 +-0.431562 -0.000007 -0.902083 +-0.232180 -0.000019 -0.972673 +-0.232167 -0.000042 -0.972676 +-0.000114 0.000121 -1.000000 +-0.000114 0.000121 -1.000000 +-0.000091 0.000075 -1.000000 +-0.232180 -0.000019 -0.972673 +-0.000091 0.000075 -1.000000 +-0.000114 0.000121 -1.000000 +0.232281 -0.000276 -0.972649 +0.232281 -0.000276 -0.972649 +0.232298 -0.000284 -0.972645 +-0.000091 0.000075 -1.000000 +-0.984809 0.000000 -0.173640 +-0.984809 0.000000 -0.173640 +-0.642788 0.000000 -0.766044 +-0.642788 0.000000 -0.766044 +-0.642788 0.000000 -0.766044 +-0.984809 0.000000 -0.173640 +-0.642788 0.000000 -0.766044 +-0.642788 0.000000 -0.766044 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +-0.642788 0.000000 -0.766044 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.642783 0.000000 -0.766048 +0.642783 0.000000 -0.766048 +0.642783 0.000000 -0.766048 +0.000001 0.000000 -1.000000 +0.642783 0.000000 -0.766048 +0.642783 0.000000 -0.766048 +0.984808 0.000000 -0.173648 +0.984808 0.000000 -0.173648 +0.984808 0.000000 -0.173647 +0.642783 0.000000 -0.766048 +0.984808 0.000000 -0.173647 +0.984808 0.000000 -0.173648 +0.866021 0.000000 0.500008 +0.866021 0.000000 0.500008 +0.866021 0.000000 0.500008 +0.984808 0.000000 -0.173647 +0.866021 0.000000 0.500008 +0.866021 0.000000 0.500008 +0.342020 0.000000 0.939693 +0.342020 0.000000 0.939693 +0.342020 0.000000 0.939693 +0.866021 0.000000 0.500008 +0.342020 0.000000 0.939693 +0.342020 0.000000 0.939693 +-0.342024 0.000000 0.939691 +-0.342024 0.000000 0.939691 +-0.342024 0.000000 0.939691 +0.342020 0.000000 0.939693 +-0.342024 0.000000 0.939691 +-0.342024 0.000000 0.939691 +-0.866024 0.000000 0.500003 +-0.866024 0.000000 0.500003 +-0.866024 0.000000 0.500003 +-0.342024 0.000000 0.939691 +-0.866024 0.000000 0.500003 +-0.866024 0.000000 0.500003 +-0.984809 0.000000 -0.173640 +-0.984809 0.000000 -0.173640 +-0.984809 0.000000 -0.173640 +-0.866024 0.000000 0.500003 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.809113 0.000000 -0.587653 +0.809112 0.000003 -0.587655 +0.973737 0.000000 -0.227677 +0.973737 0.000000 -0.227677 +0.973737 0.000000 -0.227677 +0.809113 0.000000 -0.587653 +-0.973737 -0.000000 0.227677 +-0.973737 0.000000 0.227677 +-0.973737 -0.000001 0.227677 +-0.973737 -0.000001 0.227677 +-0.973737 -0.000001 0.227677 +-0.973737 -0.000000 0.227677 +-0.973737 0.000004 0.227677 +-0.973737 0.000004 0.227677 +-0.973737 0.000000 0.227677 +-0.973737 0.000000 0.227677 +-0.973737 0.000000 0.227677 +-0.973737 0.000004 0.227677 +0.973737 0.000000 -0.227677 +0.973737 0.000000 -0.227677 +0.809113 0.000000 -0.587653 +0.809113 0.000000 -0.587653 +0.809113 0.000000 -0.587653 +0.973737 0.000000 -0.227677 +0.431556 0.000021 -0.902086 +0.431558 0.000021 -0.902085 +0.809112 0.000003 -0.587655 +0.809112 0.000003 -0.587655 +0.809113 0.000000 -0.587653 +0.431556 0.000021 -0.902086 +-0.517705 0.000008 -0.855559 +-0.517703 0.000003 -0.855560 +-0.431564 0.000022 -0.902083 +-0.431564 0.000022 -0.902083 +-0.431562 0.000021 -0.902083 +-0.517705 0.000008 -0.855559 +0.232217 0.000004 -0.972664 +0.232219 0.000000 -0.972664 +0.431558 0.000021 -0.902085 +0.431558 0.000021 -0.902085 +0.431556 0.000021 -0.902086 +0.232217 0.000004 -0.972664 +-0.431562 0.000021 -0.902083 +-0.431564 0.000022 -0.902083 +-0.232214 0.000004 -0.972665 +-0.232214 0.000004 -0.972665 +-0.232213 0.000000 -0.972665 +-0.431562 0.000021 -0.902083 +-0.232213 0.000000 -0.972665 +-0.232214 0.000004 -0.972665 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.232213 0.000000 -0.972665 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.232219 0.000000 -0.972664 +0.232219 0.000000 -0.972664 +0.232217 0.000004 -0.972664 +-0.000000 0.000000 -1.000000 +-0.431539 -0.000119 -0.902094 +-0.431569 -0.000065 -0.902080 +-0.517700 -0.000044 -0.855562 +-0.517700 -0.000044 -0.855562 +-0.517711 -0.000014 -0.855556 +-0.431539 -0.000119 -0.902094 +0.809113 0.000000 -0.587653 +0.809113 0.000000 -0.587653 +0.431570 0.000000 -0.902079 +0.431570 0.000000 -0.902079 +0.431567 0.000007 -0.902081 +0.809113 0.000000 -0.587653 +-0.232298 0.000284 -0.972645 +-0.232281 0.000276 -0.972649 +-0.431569 -0.000065 -0.902080 +-0.431569 -0.000065 -0.902080 +-0.431539 -0.000119 -0.902094 +-0.232298 0.000284 -0.972645 +0.431567 0.000007 -0.902081 +0.431570 0.000000 -0.902079 +0.232166 0.000042 -0.972676 +0.232166 0.000042 -0.972676 +0.232179 0.000019 -0.972673 +0.431567 0.000007 -0.902081 +0.232179 0.000019 -0.972673 +0.232166 0.000042 -0.972676 +0.000113 -0.000121 -1.000000 +0.000113 -0.000121 -1.000000 +0.000090 -0.000075 -1.000000 +0.232179 0.000019 -0.972673 +0.000090 -0.000075 -1.000000 +0.000113 -0.000121 -1.000000 +-0.232281 0.000276 -0.972649 +-0.232281 0.000276 -0.972649 +-0.232298 0.000284 -0.972645 +0.000090 -0.000075 -1.000000 +0.984809 0.000000 -0.173643 +0.984809 0.000000 -0.173643 +0.642790 0.000000 -0.766042 +0.642790 0.000000 -0.766042 +0.642790 0.000000 -0.766042 +0.984809 0.000000 -0.173643 +0.642790 0.000000 -0.766042 +0.642790 0.000000 -0.766042 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.642790 0.000000 -0.766042 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.642786 0.000000 -0.766046 +-0.642786 0.000000 -0.766046 +-0.642786 0.000000 -0.766046 +-0.000000 0.000000 -1.000000 +-0.642786 0.000000 -0.766046 +-0.642786 0.000000 -0.766046 +-0.984808 0.000000 -0.173648 +-0.984808 0.000000 -0.173648 +-0.984808 0.000000 -0.173648 +-0.642786 0.000000 -0.766046 +-0.984808 0.000000 -0.173648 +-0.984808 0.000000 -0.173648 +-0.866024 0.000000 0.500002 +-0.866024 0.000000 0.500002 +-0.866024 0.000000 0.500002 +-0.984808 0.000000 -0.173648 +-0.866024 0.000000 0.500002 +-0.866024 0.000000 0.500002 +-0.342020 0.000000 0.939693 +-0.342020 0.000000 0.939693 +-0.342020 0.000000 0.939693 +-0.866024 0.000000 0.500002 +-0.342020 0.000000 0.939693 +-0.342020 0.000000 0.939693 +0.342022 0.000000 0.939692 +0.342022 0.000000 0.939692 +0.342022 0.000000 0.939692 +-0.342020 0.000000 0.939693 +0.342022 0.000000 0.939692 +0.342022 0.000000 0.939692 +0.866026 0.000000 0.500000 +0.866026 0.000000 0.500000 +0.866026 0.000000 0.500000 +0.342022 0.000000 0.939692 +0.866026 0.000000 0.500000 +0.866026 0.000000 0.500000 +0.984809 0.000000 -0.173643 +0.984809 0.000000 -0.173643 +0.984809 0.000000 -0.173643 +0.866026 0.000000 0.500000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.809109 0.000000 -0.587658 +-0.973737 0.000000 -0.227677 +-0.973737 0.000000 -0.227677 +-0.973737 0.000000 -0.227677 +-0.809108 0.000003 -0.587659 +-0.809109 0.000000 -0.587658 +0.973737 0.000000 0.227677 +0.973737 0.000000 0.227677 +0.973737 0.000000 0.227677 +0.973737 0.000000 0.227677 +0.973737 0.000000 0.227677 +0.973737 0.000000 0.227677 +0.973737 0.000003 0.227677 +0.973737 0.000000 0.227677 +0.973737 0.000000 0.227677 +0.973737 0.000000 0.227677 +0.973737 0.000003 0.227677 +0.973737 0.000003 0.227677 +-0.973737 0.000000 -0.227677 +-0.809109 0.000000 -0.587658 +-0.809109 0.000000 -0.587658 +-0.809109 0.000000 -0.587658 +-0.973737 0.000000 -0.227677 +-0.973737 0.000000 -0.227677 +-0.431551 0.000021 -0.902089 +-0.809109 0.000000 -0.587658 +-0.809108 0.000003 -0.587659 +-0.809108 0.000003 -0.587659 +-0.431552 0.000021 -0.902088 +-0.431551 0.000021 -0.902089 +0.517705 0.000008 -0.855559 +0.431562 0.000021 -0.902083 +0.431564 0.000022 -0.902083 +0.431564 0.000022 -0.902083 +0.517703 0.000003 -0.855560 +0.517705 0.000008 -0.855559 +-0.232218 0.000004 -0.972664 +-0.431551 0.000021 -0.902089 +-0.431552 0.000021 -0.902088 +-0.431552 0.000021 -0.902088 +-0.232219 0.000000 -0.972663 +-0.232218 0.000004 -0.972664 +0.431562 0.000021 -0.902083 +0.232213 0.000000 -0.972665 +0.232214 0.000004 -0.972665 +0.232214 0.000004 -0.972665 +0.431564 0.000022 -0.902083 +0.431562 0.000021 -0.902083 +0.232213 0.000000 -0.972665 +-0.000001 0.000000 -1.000000 +-0.000001 0.000000 -1.000000 +-0.000001 0.000000 -1.000000 +0.232214 0.000004 -0.972665 +0.232213 0.000000 -0.972665 +-0.000001 0.000000 -1.000000 +-0.232218 0.000004 -0.972664 +-0.232219 0.000000 -0.972663 +-0.232219 0.000000 -0.972663 +-0.000001 0.000000 -1.000000 +-0.000001 0.000000 -1.000000 +0.431539 -0.000119 -0.902094 +0.517711 -0.000014 -0.855556 +0.517700 -0.000044 -0.855562 +0.517700 -0.000044 -0.855562 +0.431569 -0.000065 -0.902080 +0.431539 -0.000119 -0.902094 +-0.809109 0.000000 -0.587658 +-0.431562 0.000007 -0.902083 +-0.431565 0.000000 -0.902082 +-0.431565 0.000000 -0.902082 +-0.809109 0.000000 -0.587658 +-0.809109 0.000000 -0.587658 +0.232298 0.000284 -0.972645 +0.431539 -0.000119 -0.902094 +0.431569 -0.000065 -0.902080 +0.431569 -0.000065 -0.902080 +0.232281 0.000276 -0.972649 +0.232298 0.000284 -0.972645 +-0.431562 0.000007 -0.902083 +-0.232180 0.000019 -0.972673 +-0.232167 0.000042 -0.972676 +-0.232167 0.000042 -0.972676 +-0.431565 0.000000 -0.902082 +-0.431562 0.000007 -0.902083 +-0.232180 0.000019 -0.972673 +-0.000091 -0.000075 -1.000000 +-0.000114 -0.000121 -1.000000 +-0.000114 -0.000121 -1.000000 +-0.232167 0.000042 -0.972676 +-0.232180 0.000019 -0.972673 +-0.000091 -0.000075 -1.000000 +0.232298 0.000284 -0.972645 +0.232281 0.000276 -0.972649 +0.232281 0.000276 -0.972649 +-0.000114 -0.000121 -1.000000 +-0.000091 -0.000075 -1.000000 +-0.984809 0.000000 -0.173640 +-0.642788 0.000000 -0.766044 +-0.642788 0.000000 -0.766044 +-0.642788 0.000000 -0.766044 +-0.984809 0.000000 -0.173640 +-0.984809 0.000000 -0.173640 +-0.642788 0.000000 -0.766044 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +-0.642788 0.000000 -0.766044 +-0.642788 0.000000 -0.766044 +0.000001 0.000000 -1.000000 +0.642783 0.000000 -0.766048 +0.642783 0.000000 -0.766048 +0.642783 0.000000 -0.766048 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.642783 0.000000 -0.766048 +0.984808 0.000000 -0.173647 +0.984808 0.000000 -0.173648 +0.984808 0.000000 -0.173648 +0.642783 0.000000 -0.766048 +0.642783 0.000000 -0.766048 +0.984808 0.000000 -0.173647 +0.866021 0.000000 0.500008 +0.866021 0.000000 0.500008 +0.866021 0.000000 0.500008 +0.984808 0.000000 -0.173648 +0.984808 0.000000 -0.173647 +0.866021 0.000000 0.500008 +0.342020 0.000000 0.939693 +0.342020 0.000000 0.939693 +0.342020 0.000000 0.939693 +0.866021 0.000000 0.500008 +0.866021 0.000000 0.500008 +0.342020 0.000000 0.939693 +-0.342024 0.000000 0.939691 +-0.342024 0.000000 0.939691 +-0.342024 0.000000 0.939691 +0.342020 0.000000 0.939693 +0.342020 0.000000 0.939693 +-0.342024 0.000000 0.939691 +-0.866024 0.000000 0.500003 +-0.866024 0.000000 0.500003 +-0.866024 0.000000 0.500003 +-0.342024 0.000000 0.939691 +-0.342024 0.000000 0.939691 +-0.866024 0.000000 0.500003 +-0.984809 0.000000 -0.173640 +-0.984809 0.000000 -0.173640 +-0.984809 0.000000 -0.173640 +-0.866024 0.000000 0.500003 +-0.866024 0.000000 0.500003 +0.000000 0.707106 0.707108 +0.000000 -0.000002 1.000000 +0.000000 -0.000002 1.000000 +0.000000 -0.000002 1.000000 +0.000000 0.707106 0.707108 +0.000000 0.707106 0.707108 +0.000000 1.000000 0.000000 +0.000000 0.707106 0.707108 +0.000000 0.707106 0.707108 +0.000000 0.707106 0.707108 +0.000000 1.000000 -0.000000 +0.000000 1.000000 0.000000 +0.000000 0.707109 -0.707104 +0.000000 1.000000 0.000000 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000000 +0.000000 0.707109 -0.707104 +0.000000 0.707109 -0.707104 +0.000000 -0.000002 -1.000000 +0.000000 0.707109 -0.707104 +0.000000 0.707109 -0.707104 +0.000000 0.707109 -0.707104 +0.000000 -0.000002 -1.000000 +0.000000 -0.000002 -1.000000 +0.000000 -0.707111 -0.707103 +0.000000 -0.000002 -1.000000 +0.000000 -0.000002 -1.000000 +0.000000 -0.000002 -1.000000 +0.000000 -0.707111 -0.707103 +0.000000 -0.707111 -0.707103 +0.000000 -1.000000 -0.000000 +0.000000 -0.707111 -0.707103 +0.000000 -0.707111 -0.707103 +0.000000 -0.707111 -0.707103 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 -0.000000 +0.000000 -0.707107 0.707107 +0.000000 -1.000000 -0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.000002 1.000000 +0.000000 -0.000002 1.000000 +0.000000 -0.000002 1.000000 +0.000000 -0.707107 0.707107 +-1.000000 -0.000003 0.000000 +-0.707103 0.707111 0.000000 +-0.707103 0.707110 0.000000 +-0.707103 0.707110 0.000000 +-1.000000 -0.000003 0.000000 +-1.000000 -0.000003 0.000000 +-0.707103 0.707111 0.000000 +-0.000001 1.000000 0.000000 +-0.000001 1.000000 0.000000 +-0.000001 1.000000 0.000000 +-0.707103 0.707110 0.000000 +-0.707103 0.707111 0.000000 +-0.000001 1.000000 0.000000 +0.707104 0.707110 0.000000 +0.707104 0.707110 0.000000 +0.707104 0.707110 0.000000 +-0.000001 1.000000 0.000000 +-0.000001 1.000000 0.000000 +0.707104 0.707110 0.000000 +1.000000 -0.000003 0.000000 +1.000000 -0.000003 0.000000 +1.000000 -0.000003 0.000000 +0.707104 0.707110 0.000000 +0.707104 0.707110 0.000000 +1.000000 -0.000003 0.000000 +0.707107 -0.707106 0.000000 +0.707107 -0.707106 0.000000 +0.707107 -0.707106 0.000000 +1.000000 -0.000003 0.000000 +1.000000 -0.000003 0.000000 +0.707107 -0.707106 0.000000 +-0.000001 -1.000000 0.000000 +-0.000001 -1.000000 0.000000 +-0.000001 -1.000000 0.000000 +0.707107 -0.707106 0.000000 +0.707107 -0.707106 0.000000 +-0.000001 -1.000000 0.000000 +-0.707106 -0.707108 0.000000 +-0.707106 -0.707107 0.000000 +-0.707106 -0.707107 0.000000 +-0.000001 -1.000000 0.000000 +-0.000001 -1.000000 0.000000 +-0.707106 -0.707108 0.000000 +-1.000000 -0.000003 0.000000 +-1.000000 -0.000003 0.000000 +-1.000000 -0.000003 0.000000 +-0.707106 -0.707107 0.000000 +-0.707106 -0.707108 0.000000 +-1.000000 -0.000004 -0.000000 +-0.707104 0.707110 -0.000000 +-0.707103 0.707110 -0.000000 +-0.707103 0.707110 -0.000000 +-1.000000 -0.000003 0.000000 +-1.000000 -0.000004 -0.000000 +-0.707104 0.707110 -0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 -0.000000 +0.000001 1.000000 -0.000000 +-0.707103 0.707110 -0.000000 +-0.707104 0.707110 -0.000000 +0.000001 1.000000 0.000000 +0.707104 0.707109 0.000000 +0.707104 0.707109 0.000000 +0.707104 0.707109 0.000000 +0.000001 1.000000 -0.000000 +0.000001 1.000000 0.000000 +0.707104 0.707109 0.000000 +1.000000 -0.000003 0.000000 +1.000000 -0.000003 0.000000 +1.000000 -0.000003 0.000000 +0.707104 0.707109 0.000000 +0.707104 0.707109 0.000000 +1.000000 -0.000003 0.000000 +0.707107 -0.707106 0.000000 +0.707107 -0.707106 0.000000 +0.707107 -0.707106 0.000000 +1.000000 -0.000003 0.000000 +1.000000 -0.000003 0.000000 +0.707107 -0.707106 0.000000 +0.000000 -1.000000 0.000000 +0.000001 -1.000000 0.000000 +0.000001 -1.000000 0.000000 +0.707107 -0.707106 0.000000 +0.707107 -0.707106 0.000000 +0.000000 -1.000000 0.000000 +-0.707106 -0.707107 0.000000 +-0.707106 -0.707107 0.000000 +-0.707106 -0.707107 0.000000 +0.000001 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.707106 -0.707107 0.000000 +-1.000000 -0.000004 -0.000000 +-1.000000 -0.000003 0.000000 +-1.000000 -0.000003 0.000000 +-0.707106 -0.707107 0.000000 +-0.707106 -0.707107 0.000000 +0.000000 0.707108 0.707106 +0.000000 0.707108 0.707106 +0.000000 -0.000002 1.000000 +0.000000 -0.000002 1.000000 +0.000000 -0.000002 1.000000 +0.000000 0.707108 0.707106 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +0.000000 0.707108 0.707106 +0.000000 0.707108 0.707106 +0.000000 0.707108 0.707106 +0.000000 1.000000 0.000002 +0.000000 0.707109 -0.707104 +0.000000 0.707109 -0.707104 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +0.000000 0.707109 -0.707104 +0.000000 -0.000002 -1.000000 +0.000000 -0.000002 -1.000000 +0.000000 0.707109 -0.707104 +0.000000 0.707109 -0.707104 +0.000000 0.707109 -0.707104 +0.000000 -0.000002 -1.000000 +0.000000 -0.707111 -0.707103 +0.000000 -0.707111 -0.707103 +0.000000 -0.000002 -1.000000 +0.000000 -0.000002 -1.000000 +0.000000 -0.000002 -1.000000 +0.000000 -0.707111 -0.707103 +0.000000 -1.000000 0.000002 +0.000000 -1.000000 0.000002 +0.000000 -0.707111 -0.707103 +0.000000 -0.707111 -0.707103 +0.000000 -0.707111 -0.707103 +0.000000 -1.000000 0.000002 +0.000000 -0.707109 0.707104 +0.000000 -0.707109 0.707105 +0.000000 -1.000000 0.000002 +0.000000 -1.000000 0.000002 +0.000000 -1.000000 0.000002 +0.000000 -0.707109 0.707104 +0.000000 -0.707109 0.707104 +0.000000 -0.000002 1.000000 +0.000000 -0.000002 1.000000 +0.000000 -0.000002 1.000000 +0.000000 -0.707109 0.707105 +0.000000 -0.707109 0.707104 +1.000000 -0.000003 0.000000 +1.000000 -0.000003 0.000000 +0.707101 0.707112 0.000000 +0.707101 0.707112 0.000000 +0.707101 0.707113 0.000000 +1.000000 -0.000003 0.000000 +0.707101 0.707113 0.000000 +0.707101 0.707112 0.000000 +0.000003 1.000000 0.000000 +0.000003 1.000000 0.000000 +0.000003 1.000000 0.000000 +0.707101 0.707113 0.000000 +0.000003 1.000000 0.000000 +0.000003 1.000000 0.000000 +-0.707104 0.707110 0.000000 +-0.707104 0.707110 0.000000 +-0.707104 0.707109 0.000000 +0.000003 1.000000 0.000000 +-0.707104 0.707109 0.000000 +-0.707104 0.707110 0.000000 +-1.000000 -0.000003 0.000000 +-1.000000 -0.000003 0.000000 +-1.000000 -0.000003 0.000000 +-0.707104 0.707109 0.000000 +-1.000000 -0.000003 0.000000 +-1.000000 -0.000003 0.000000 +-0.707107 -0.707106 0.000000 +-0.707107 -0.707106 0.000000 +-0.707107 -0.707106 0.000000 +-1.000000 -0.000003 0.000000 +-0.707107 -0.707106 0.000000 +-0.707107 -0.707106 0.000000 +0.000003 -1.000000 0.000000 +0.000003 -1.000000 0.000000 +0.000003 -1.000000 0.000000 +-0.707107 -0.707106 0.000000 +0.000003 -1.000000 0.000000 +0.000003 -1.000000 0.000000 +0.707104 -0.707110 0.000000 +0.707104 -0.707110 0.000000 +0.707104 -0.707110 0.000000 +0.000003 -1.000000 0.000000 +0.707104 -0.707110 0.000000 +0.707104 -0.707110 0.000000 +1.000000 -0.000003 0.000000 +1.000000 -0.000003 0.000000 +1.000000 -0.000003 0.000000 +0.707104 -0.707110 0.000000 +1.000000 -0.000003 0.000000 +1.000000 -0.000003 0.000000 +0.707103 0.707110 0.000000 +0.707103 0.707110 0.000000 +0.707103 0.707110 0.000000 +1.000000 -0.000003 0.000000 +0.707103 0.707110 0.000000 +0.707103 0.707110 0.000000 +-0.000001 1.000000 0.000000 +-0.000001 1.000000 0.000000 +-0.000001 1.000000 0.000000 +0.707103 0.707110 0.000000 +-0.000001 1.000000 0.000000 +-0.000001 1.000000 0.000000 +-0.707101 0.707112 0.000000 +-0.707101 0.707112 0.000000 +-0.707101 0.707112 0.000000 +-0.000001 1.000000 0.000000 +-0.707101 0.707112 0.000000 +-0.707101 0.707112 0.000000 +-1.000000 -0.000003 0.000000 +-1.000000 -0.000003 0.000000 +-1.000000 -0.000003 0.000000 +-0.707101 0.707112 0.000000 +-1.000000 -0.000003 0.000000 +-1.000000 -0.000003 0.000000 +-0.707104 -0.707109 0.000000 +-0.707104 -0.707109 0.000000 +-0.707104 -0.707109 0.000000 +-1.000000 -0.000003 0.000000 +-0.707104 -0.707109 0.000000 +-0.707104 -0.707109 0.000000 +-0.000001 -1.000000 0.000000 +-0.000001 -1.000000 0.000000 +-0.000001 -1.000000 0.000000 +-0.707104 -0.707109 0.000000 +-0.000001 -1.000000 0.000000 +-0.000001 -1.000000 0.000000 +0.707106 -0.707107 0.000000 +0.707106 -0.707107 0.000000 +0.707106 -0.707107 0.000000 +-0.000001 -1.000000 0.000000 +0.707106 -0.707107 0.000000 +0.707106 -0.707107 0.000000 +1.000000 -0.000003 0.000000 +1.000000 -0.000003 0.000000 +1.000000 -0.000003 0.000000 +0.707106 -0.707107 0.000000 + + + + + + + + + + + +0.962718 0.097492 +0.785926 0.097711 +0.785912 0.085800 +0.962703 0.085582 +0.533273 0.064974 +0.469898 0.065137 +0.469869 0.053197 +0.533243 0.053034 +0.780060 0.085807 +0.395865 0.350816 +0.613251 0.051819 +0.982278 0.145638 +0.841133 0.135570 +0.982291 0.135754 +0.533217 0.043125 +0.216895 0.351441 +0.076535 0.085205 +0.082372 0.085196 +0.247059 0.084938 +0.082367 0.082204 +0.247054 0.081946 +0.533200 0.040136 +0.159767 0.042734 +0.613208 0.063579 +0.192131 0.351658 +0.065963 0.081731 +0.013274 0.351410 +0.312722 0.009084 +0.312722 0.020994 +0.302225 0.020994 +0.780024 0.097718 +0.302919 0.096387 +0.288985 0.096387 +0.302919 0.106273 +0.288985 0.106272 +0.312566 0.040069 +0.302078 0.040031 +0.312556 0.043058 +0.076309 0.082201 +0.553539 0.052685 +0.553710 0.064443 +0.553397 0.042928 +0.159785 0.009079 +0.006628 0.136336 +0.026910 0.136284 +0.026885 0.126400 +0.026855 0.114489 +0.006573 0.114540 +0.006603 0.126451 +0.805329 0.115639 +0.805336 0.103728 +0.982127 0.103838 +0.982120 0.115748 +0.406516 0.065280 +0.406489 0.053339 +0.650881 0.014828 +0.200058 0.350984 +0.324980 0.052508 +0.987979 0.103842 +0.650882 0.024713 +0.509723 0.024723 +0.406467 0.043429 +0.085032 0.031363 +0.249725 0.032637 +0.255559 0.032681 +0.264814 0.032317 +0.085055 0.028370 +0.249748 0.029646 +0.325045 0.064512 +0.208742 0.350678 +0.095582 0.096380 +0.096565 0.020988 +0.095582 0.106264 +0.096531 0.039809 +0.005129 0.350608 +0.266143 0.029272 +0.017334 0.009083 +0.006837 0.020996 +0.006836 0.009084 +0.988022 0.115752 +0.014700 0.096387 +0.014701 0.106271 +0.006836 0.040069 +0.017348 0.043030 +0.006845 0.043063 +0.255803 0.029680 +0.385933 0.053281 +0.385781 0.065283 +0.386059 0.043320 +0.679412 0.039084 +0.659130 0.039084 +0.679412 0.060880 +0.679412 0.048969 +0.659130 0.048969 +0.659130 0.060880 +0.036229 0.566111 +0.277315 0.361151 +0.020460 0.361020 +0.600077 0.566528 +0.704641 0.062956 +0.977524 0.062956 +0.245847 0.121733 +0.372218 0.123456 +0.380255 0.319669 +0.232327 0.320416 +0.339240 0.086644 +0.612122 0.087465 +0.043215 0.121936 +0.169503 0.124203 +0.176784 0.320404 +0.028847 0.320467 +0.692888 0.040720 +0.989983 0.040720 +0.394534 0.333952 +0.217982 0.333981 +0.692888 0.019963 +0.989983 0.019963 +0.191072 0.334728 +0.014443 0.333964 +0.697932 0.131753 +0.400850 0.130459 +0.984710 0.183163 +0.808851 0.182199 +0.399403 0.125514 +0.696501 0.126805 +0.812907 0.174608 +0.988769 0.175780 +0.674296 0.162825 +0.424215 0.161736 +0.953406 0.206493 +0.839897 0.205871 +0.423040 0.094441 +0.673134 0.095528 +0.844239 0.151315 +0.957750 0.152071 +0.238531 0.121292 +0.224710 0.319119 +0.184505 0.319322 +0.176726 0.123984 +0.379442 0.123209 +0.387976 0.318567 +0.035904 0.121464 +0.021238 0.319137 +0.198376 0.333650 +0.210649 0.332829 +0.007119 0.332778 +0.401884 0.332938 +0.805506 0.167317 +0.705143 0.134191 +0.392191 0.123075 +0.991919 0.185611 +0.837994 0.145667 +0.681508 0.165264 +0.415828 0.092002 +0.960614 0.208940 +0.798235 0.165186 +0.797788 0.126875 +0.812769 0.133815 +0.793732 0.165239 +0.793285 0.126928 +0.778470 0.134216 +0.709693 0.212066 +0.709246 0.173754 +0.724227 0.180694 +0.705190 0.212118 +0.704742 0.173807 +0.689928 0.181095 +0.209812 0.202408 +0.209532 0.164095 +0.224482 0.171100 +0.205309 0.202441 +0.205028 0.164128 +0.190182 0.171351 +0.785520 0.211657 +0.785072 0.173345 +0.800053 0.180286 +0.781016 0.211710 +0.780569 0.173398 +0.765754 0.180686 +0.206917 0.160879 +0.206670 0.122566 +0.221614 0.129585 +0.203539 0.160901 +0.202166 0.122595 +0.741013 0.211981 +0.725751 0.180958 +0.740566 0.173670 +0.745069 0.173617 +0.745517 0.211929 +0.760050 0.180558 +0.202547 0.326199 +0.187420 0.295110 +0.202267 0.287886 +0.206770 0.287853 +0.207051 0.326166 +0.221721 0.294859 +0.205500 0.243982 +0.190374 0.212892 +0.205220 0.205669 +0.209723 0.205636 +0.210004 0.243949 +0.224674 0.212641 +0.205128 0.284751 +0.190001 0.253662 +0.204848 0.246438 +0.209351 0.246406 +0.209631 0.284719 +0.224302 0.253411 +0.187530 0.130236 +0.941787 0.247187 +0.926888 0.215988 +0.941787 0.208873 +0.946290 0.208873 +0.946291 0.247187 +0.961189 0.215987 +0.905656 0.247188 +0.890756 0.215989 +0.905655 0.208874 +0.910159 0.208874 +0.910159 0.247188 +0.925058 0.215988 +0.978855 0.247188 +0.963956 0.215989 +0.978855 0.208874 +0.983358 0.208874 +0.983359 0.247188 +0.998257 0.215988 +0.869514 0.247187 +0.854615 0.215987 +0.869513 0.208873 +0.874017 0.208873 +0.874017 0.247187 +0.888916 0.215987 +0.761604 0.179225 +0.746144 0.148300 +0.760912 0.140917 +0.765415 0.140836 +0.764981 0.179164 +0.836423 0.248501 +0.836422 0.210187 +0.851321 0.217301 +0.831919 0.248501 +0.831919 0.210187 +0.817020 0.217302 +0.765215 0.244214 +0.765214 0.205900 +0.780113 0.213015 +0.760711 0.244214 +0.760711 0.205900 +0.745812 0.213015 +0.727478 0.245819 +0.727478 0.207505 +0.742377 0.214620 +0.722974 0.245819 +0.722974 0.207505 +0.708075 0.214620 +0.798727 0.249138 +0.798726 0.210824 +0.813625 0.217939 +0.794223 0.249138 +0.794223 0.210824 +0.779324 0.217939 +0.780234 0.148116 +0.765162 0.139848 +0.765583 0.101536 +0.780403 0.108814 +0.760659 0.139798 +0.761080 0.101486 +0.746104 0.108437 +0.707895 0.280630 +0.708380 0.242319 +0.723188 0.249621 +0.703392 0.280573 +0.703877 0.242262 +0.688889 0.249187 +0.734623 0.164070 +0.734148 0.125758 +0.749134 0.132688 +0.730120 0.164126 +0.729645 0.125814 +0.714836 0.133113 +0.729753 0.124028 +0.714679 0.092913 +0.729538 0.085715 +0.734042 0.085690 +0.734256 0.124003 +0.748980 0.092721 +0.722946 0.315807 +0.708564 0.284366 +0.723579 0.277499 +0.728082 0.277573 +0.727449 0.315882 +0.742861 0.284933 +0.742406 0.279084 +0.728025 0.247643 +0.743039 0.240775 +0.747542 0.240850 +0.746909 0.279158 +0.762321 0.248210 +0.744231 0.678025 +0.725296 0.678025 +0.725296 0.650471 +0.744231 0.650471 +0.706360 0.678025 +0.706360 0.650471 +0.687424 0.678025 +0.687424 0.650471 +0.668488 0.678025 +0.668488 0.650471 +0.649551 0.678025 +0.649551 0.650471 +0.971420 0.678025 +0.971420 0.650471 +0.952487 0.678025 +0.952487 0.650471 +0.933556 0.678025 +0.933556 0.650471 +0.914624 0.678025 +0.914624 0.650471 +0.895692 0.678025 +0.895692 0.650471 +0.876761 0.678025 +0.876761 0.650471 +0.857829 0.678025 +0.857829 0.650471 +0.838898 0.678025 +0.838898 0.650471 +0.819952 0.678025 +0.819952 0.650471 +0.801033 0.678025 +0.801033 0.650471 +0.782100 0.678025 +0.782100 0.650471 +0.763166 0.678025 +0.763166 0.650471 +0.725958 0.683942 +0.725958 0.711495 +0.707019 0.711495 +0.707019 0.683942 +0.688080 0.711495 +0.688080 0.683942 +0.669141 0.711495 +0.669141 0.683942 +0.650201 0.711495 +0.650201 0.683942 +0.972069 0.711495 +0.972069 0.683942 +0.953142 0.711495 +0.953142 0.683942 +0.934215 0.711495 +0.934215 0.683942 +0.915287 0.711495 +0.915287 0.683942 +0.896359 0.711495 +0.896359 0.683942 +0.877429 0.711495 +0.877429 0.683942 +0.858499 0.711495 +0.858499 0.683942 +0.839567 0.711495 +0.839567 0.683942 +0.820615 0.711495 +0.820615 0.683942 +0.801702 0.711495 +0.801702 0.683942 +0.782768 0.711495 +0.782768 0.683942 +0.763832 0.711495 +0.763832 0.683942 +0.744895 0.711495 +0.744895 0.683942 +0.745805 0.716864 +0.745805 0.744417 +0.726878 0.744417 +0.726878 0.716864 +0.707951 0.744417 +0.707951 0.716864 +0.689025 0.744417 +0.689025 0.716864 +0.670099 0.744417 +0.670099 0.716864 +0.651172 0.744417 +0.651172 0.716864 +0.973028 0.744417 +0.973028 0.716864 +0.954086 0.744417 +0.954086 0.716864 +0.935145 0.744417 +0.935145 0.716864 +0.916206 0.744417 +0.916206 0.716864 +0.897267 0.744417 +0.897267 0.716864 +0.878330 0.744417 +0.878330 0.716864 +0.859394 0.744417 +0.859394 0.716864 +0.840459 0.744417 +0.840459 0.716864 +0.821525 0.744417 +0.821525 0.716864 +0.802593 0.744417 +0.802593 0.716864 +0.783663 0.744417 +0.783663 0.716864 +0.764733 0.744417 +0.764733 0.716864 +0.725776 0.645703 +0.706838 0.645703 +0.706838 0.618147 +0.725776 0.618147 +0.687901 0.645703 +0.687901 0.618147 +0.668963 0.645703 +0.668963 0.618147 +0.650025 0.645703 +0.650025 0.618147 +0.971923 0.645703 +0.971923 0.618147 +0.952992 0.645703 +0.952992 0.618147 +0.934061 0.645703 +0.934061 0.618147 +0.915129 0.645703 +0.915129 0.618147 +0.896197 0.645703 +0.896197 0.618147 +0.877264 0.645703 +0.877264 0.618147 +0.858330 0.645703 +0.858330 0.618147 +0.839396 0.645703 +0.839396 0.618147 +0.820461 0.645703 +0.820461 0.618147 +0.801525 0.645703 +0.801525 0.618147 +0.782589 0.645703 +0.782589 0.618147 +0.763652 0.645703 +0.763652 0.618147 +0.744714 0.645703 +0.744714 0.618147 +0.929712 0.897583 +0.930427 0.998107 +0.903560 0.992027 +0.902845 0.891502 +0.961986 0.792536 +0.988828 0.786346 +0.988521 0.886874 +0.961679 0.893063 +0.907936 0.889806 +0.925848 0.893860 +0.912782 0.889194 +0.921738 0.891220 +0.917384 0.889665 +0.965835 0.788797 +0.983730 0.784671 +0.969934 0.786142 +0.978880 0.784077 +0.974282 0.784568 +0.896920 0.884571 +0.870153 0.891075 +0.869282 0.790551 +0.896050 0.784047 +0.811491 0.992036 +0.811320 0.891508 +0.838153 0.897734 +0.838325 0.998262 +0.873088 0.786767 +0.890933 0.782431 +0.877156 0.784064 +0.886078 0.781896 +0.881485 0.782439 +0.816420 0.889840 +0.834309 0.893990 +0.821269 0.889253 +0.830214 0.891329 +0.825867 0.889750 +0.688145 0.825747 +0.682005 0.825747 +0.682005 0.788648 +0.688145 0.788648 +0.677858 0.825747 +0.677858 0.788648 +0.673712 0.825747 +0.673712 0.788648 +0.667571 0.825747 +0.667571 0.788648 +0.660875 0.825747 +0.660875 0.788648 +0.655700 0.825747 +0.655700 0.788648 +0.652039 0.825747 +0.652039 0.788648 +0.694841 0.825747 +0.694841 0.788648 +0.841662 0.897576 +0.868434 0.891093 +0.869227 0.991617 +0.842454 0.998100 +0.710152 0.898309 +0.711302 0.998830 +0.684409 0.992865 +0.683259 0.892345 +0.863319 0.889473 +0.845469 0.893795 +0.858465 0.888934 +0.849540 0.891095 +0.853871 0.889475 +0.706271 0.894603 +0.688342 0.890627 +0.702150 0.891981 +0.693186 0.889993 +0.697789 0.890446 +0.779887 0.991303 +0.779715 0.890775 +0.806548 0.897001 +0.806722 0.997528 +0.862394 0.885521 +0.835534 0.891631 +0.836139 0.791106 +0.863000 0.784996 +0.784815 0.889106 +0.802704 0.893257 +0.789665 0.888520 +0.798609 0.890595 +0.794263 0.889016 +0.840000 0.787379 +0.857908 0.783305 +0.844107 0.784735 +0.853061 0.782699 +0.848461 0.783175 +0.739616 0.788214 +0.739616 0.825320 +0.733474 0.825320 +0.733474 0.788214 +0.729326 0.825320 +0.729326 0.788214 +0.725179 0.825320 +0.725179 0.788214 +0.719037 0.825320 +0.719037 0.788214 +0.712339 0.825320 +0.712340 0.788214 +0.707163 0.825320 +0.707163 0.788214 +0.751490 0.825320 +0.751490 0.788214 +0.746312 0.825320 +0.746312 0.788214 +0.969708 0.898199 +0.996510 0.891839 +0.996843 0.992366 +0.970041 0.998726 +0.963770 0.898540 +0.964374 0.999066 +0.937514 0.992955 +0.936910 0.892430 +0.991401 0.890196 +0.973533 0.894436 +0.986548 0.889634 +0.977615 0.891755 +0.981954 0.890154 +0.959909 0.894813 +0.942003 0.890739 +0.955802 0.892169 +0.946850 0.890132 +0.951449 0.890609 +0.906181 0.883206 +0.907427 0.782686 +0.934171 0.789290 +0.932923 0.889811 +0.678776 0.992433 +0.651882 0.998389 +0.653067 0.897868 +0.679962 0.891913 +0.912551 0.781090 +0.930379 0.785492 +0.917407 0.780572 +0.926321 0.782774 +0.921997 0.781134 +0.656948 0.894163 +0.674879 0.890193 +0.661070 0.891543 +0.670036 0.889558 +0.665432 0.890008 +0.665386 0.786241 +0.665386 0.749135 +0.671527 0.749135 +0.671527 0.786241 +0.675674 0.749135 +0.675674 0.786241 +0.679822 0.749135 +0.679822 0.786241 +0.685964 0.749135 +0.685964 0.786241 +0.692661 0.749135 +0.692661 0.786241 +0.697838 0.749135 +0.697838 0.786241 +0.701499 0.749135 +0.701499 0.786241 +0.658689 0.749135 +0.658689 0.786241 +0.741987 0.897511 +0.742843 0.998036 +0.715967 0.991993 +0.715111 0.891468 +0.872759 0.897623 +0.899532 0.891140 +0.900325 0.991665 +0.873552 0.998148 +0.720200 0.889766 +0.738117 0.893794 +0.725046 0.889145 +0.734004 0.891161 +0.729648 0.889611 +0.876568 0.893843 +0.894416 0.889521 +0.880638 0.891142 +0.889561 0.888980 +0.884968 0.889522 +0.830122 0.884867 +0.803262 0.890977 +0.803868 0.790451 +0.830728 0.784342 +0.748488 0.992323 +0.748315 0.891795 +0.775149 0.898021 +0.775321 0.998548 +0.807729 0.786724 +0.825636 0.782651 +0.811836 0.784081 +0.820789 0.782044 +0.816189 0.782520 +0.753415 0.890127 +0.771305 0.894277 +0.758265 0.889540 +0.767210 0.891615 +0.762863 0.890037 +0.738349 0.786207 +0.732207 0.786207 +0.732207 0.749101 +0.738349 0.749101 +0.728060 0.786207 +0.728060 0.749101 +0.723912 0.786207 +0.723912 0.749101 +0.717770 0.786207 +0.717770 0.749101 +0.711073 0.786207 +0.711073 0.749101 +0.705896 0.786207 +0.705896 0.749101 +0.750222 0.786207 +0.750222 0.749101 +0.745045 0.786207 +0.745045 0.749101 +0.626234 0.061351 +0.623284 0.061351 +0.623284 0.039693 +0.626234 0.039693 +0.630928 0.061351 +0.630928 0.039693 +0.635622 0.061351 +0.635622 0.039693 +0.638572 0.061352 +0.638572 0.039693 +0.641522 0.061352 +0.641522 0.039693 +0.646216 0.061352 +0.646216 0.039693 +0.650910 0.061352 +0.650910 0.039693 +0.696806 0.090865 +0.696820 0.092437 +0.684184 0.092551 +0.684170 0.090980 +0.696835 0.094008 +0.684198 0.094123 +0.696735 0.083009 +0.684099 0.083123 +0.696749 0.084580 +0.684113 0.084695 +0.696764 0.086152 +0.684127 0.086266 +0.696778 0.087723 +0.684141 0.087838 +0.696792 0.089294 +0.684156 0.089409 +0.689627 0.076494 +0.689613 0.078065 +0.676977 0.077951 +0.676991 0.076380 +0.689599 0.079637 +0.676962 0.079522 +0.689698 0.068637 +0.677061 0.068523 +0.689684 0.070209 +0.677047 0.070095 +0.689670 0.071780 +0.677033 0.071666 +0.689655 0.073351 +0.677019 0.073237 +0.689641 0.074923 +0.677005 0.074809 +0.645476 0.067196 +0.645476 0.088854 +0.642526 0.088854 +0.642526 0.067196 +0.650170 0.067196 +0.650170 0.088854 +0.654864 0.067196 +0.654864 0.088854 +0.657814 0.067196 +0.657814 0.088854 +0.660764 0.067196 +0.660765 0.088854 +0.665458 0.067196 +0.665458 0.088854 +0.670152 0.067196 +0.670152 0.088854 +0.635789 0.088435 +0.632534 0.088427 +0.632548 0.088000 +0.635802 0.088060 +0.632561 0.087587 +0.635815 0.087666 +0.632677 0.090618 +0.635907 0.090221 +0.632621 0.090194 +0.635857 0.089850 +0.632574 0.089757 +0.635818 0.089493 +0.632543 0.089311 +0.635793 0.089145 +0.632531 0.088866 +0.635784 0.088795 +0.636294 0.080370 +0.633039 0.080362 +0.633052 0.079935 +0.636306 0.079995 +0.633065 0.079523 +0.636319 0.079601 +0.633181 0.082553 +0.636412 0.082156 +0.633125 0.082129 +0.636362 0.081785 +0.633078 0.081692 +0.636322 0.081429 +0.633047 0.081247 +0.636297 0.081080 +0.633035 0.080801 +0.636289 0.080730 +0.420844 0.326712 +0.420558 0.172494 +0.677403 0.172019 +0.677689 0.326237 +0.687378 0.316368 +0.687124 0.181632 +0.410869 0.182364 +0.411122 0.317100 +0.684906 0.323816 +0.413617 0.324318 +0.684629 0.174413 +0.413341 0.174915 +0.863789 0.435271 +0.860755 0.416581 +0.889682 0.416006 +0.886531 0.434678 +0.851512 0.400055 +0.899028 0.399539 +0.837173 0.387688 +0.913442 0.387261 +0.819470 0.380971 +0.931187 0.380653 +0.990353 0.678025 +0.800537 0.380713 +0.990353 0.650471 +0.950122 0.380514 +0.782658 0.386946 +0.967962 0.386858 +0.767988 0.398919 +0.982556 0.398922 +0.758299 0.415187 +0.992144 0.415250 +0.754757 0.433788 +0.995570 0.433873 +0.757791 0.452479 +0.992420 0.452544 +0.767035 0.469004 +0.983073 0.469012 +0.781373 0.481371 +0.968659 0.481290 +0.799077 0.488089 +0.950914 0.487897 +0.818010 0.488346 +0.931980 0.488037 +0.835889 0.482112 +0.914139 0.481692 +0.850558 0.470140 +0.899545 0.469628 +0.860248 0.453872 +0.889957 0.453300 +0.738093 0.553041 +0.861094 0.553253 +0.857800 0.534607 +0.734555 0.571642 +0.848328 0.518212 +0.724868 0.587911 +0.833819 0.506045 +0.710156 0.599911 +0.990994 0.711495 +0.816024 0.499575 +0.990994 0.683942 +0.692323 0.606123 +0.797089 0.499581 +0.673390 0.605868 +0.779298 0.506063 +0.655686 0.599154 +0.764796 0.518239 +0.641345 0.586789 +0.755334 0.534640 +0.632099 0.570265 +0.752052 0.553288 +0.629062 0.551575 +0.755346 0.571935 +0.632599 0.532974 +0.764819 0.588330 +0.642286 0.516704 +0.779329 0.600496 +0.656999 0.504703 +0.797124 0.606967 +0.674832 0.498492 +0.816059 0.606960 +0.693765 0.498747 +0.833849 0.600478 +0.711469 0.505461 +0.848351 0.588302 +0.725810 0.517826 +0.857812 0.571901 +0.735056 0.534350 +0.740236 0.432191 +0.994925 0.316443 +0.991606 0.297802 +0.736907 0.450831 +0.982112 0.281419 +0.727403 0.467208 +0.967587 0.269272 +0.712871 0.479347 +0.949784 0.262825 +0.695064 0.485784 +0.991971 0.744417 +0.930849 0.262856 +0.991971 0.716864 +0.676129 0.485743 +0.913066 0.269361 +0.658351 0.479227 +0.898581 0.281556 +0.643872 0.467024 +0.889141 0.297969 +0.634441 0.450605 +0.885883 0.316623 +0.631194 0.431951 +0.889202 0.335264 +0.634523 0.413310 +0.898696 0.351647 +0.644027 0.396933 +0.913221 0.363794 +0.658558 0.384793 +0.931025 0.370241 +0.676366 0.378357 +0.949960 0.370210 +0.695301 0.378398 +0.967742 0.363705 +0.713079 0.384914 +0.982227 0.351510 +0.727558 0.397117 +0.991668 0.335096 +0.736989 0.413536 +0.756574 0.316863 +0.759677 0.335541 +0.991761 0.573912 +0.995178 0.555288 +0.768982 0.352033 +0.982179 0.590244 +0.783366 0.364346 +0.967590 0.602314 +0.990852 0.645703 +0.801094 0.370998 +0.990852 0.618147 +0.949752 0.608666 +0.820029 0.371185 +0.930818 0.608535 +0.837885 0.364885 +0.913071 0.601935 +0.852510 0.352858 +0.898651 0.589663 +0.862139 0.336554 +0.889297 0.573200 +0.865611 0.317940 +0.886139 0.554531 +0.862507 0.299262 +0.889556 0.535907 +0.853202 0.282771 +0.899138 0.519575 +0.838818 0.270457 +0.913728 0.507505 +0.821090 0.263805 +0.931565 0.501153 +0.802156 0.263618 +0.950499 0.501284 +0.784301 0.269918 +0.968247 0.507883 +0.769676 0.281945 +0.982667 0.520155 +0.760046 0.298249 +0.992020 0.536619 +0.617349 0.999539 +0.018316 0.999095 +0.285228 0.558402 +0.012346 0.558264 +0.616788 0.566386 +0.634060 0.999396 +0.001606 0.998928 +0.019518 0.565944 +0.012847 0.360946 +0.004733 0.558189 +0.284927 0.361084 +0.292841 0.558336 +0.692536 0.045974 +0.989630 0.045974 +0.327186 0.069626 +0.624279 0.070519 +0.697381 0.065247 +0.984784 0.065247 +0.619375 0.089778 +0.331973 0.088914 +0.996890 0.048265 +0.685276 0.048265 +0.319919 0.071895 +0.631532 0.072833 +0.692888 0.023627 +0.989983 0.023627 +0.692888 0.002869 +0.989983 0.002870 +0.997596 0.040720 +0.685276 0.040720 +0.685276 0.019963 +0.997596 0.019963 +0.997596 0.023627 +0.685276 0.023627 +0.685276 0.002870 +0.997596 0.002870 +0.323245 0.020775 +0.464390 0.022671 +0.403506 0.350094 +0.324948 0.011657 +0.329968 0.008678 +0.494631 0.010890 +0.617003 0.546204 +0.617003 0.381527 +0.524043 0.552884 +0.460822 0.374847 +0.770722 0.085824 +0.708838 0.092493 +0.714997 0.079998 +0.692466 0.070998 +0.702831 0.069347 +0.613548 0.376517 +0.613594 0.551214 +0.554999 0.355201 +0.841120 0.145455 +0.585161 0.367184 +0.420487 0.368300 +0.415486 0.365288 +0.413844 0.356158 +0.304641 0.381527 +0.304641 0.546204 +0.397601 0.552884 +0.908389 0.080257 +0.908398 0.069626 +0.997318 0.103853 +0.318277 0.552884 +0.981488 0.092812 +0.997914 0.071348 +0.318458 0.374847 +0.308095 0.376517 +0.308050 0.551214 +0.253144 0.084929 +0.253140 0.081937 +0.078944 0.031316 +0.078967 0.028323 +0.477907 0.030534 +0.499594 0.014411 +0.568568 0.347429 +0.590147 0.363695 +0.067275 0.084786 +0.613110 0.042062 +0.770512 0.097735 +0.509723 0.014839 +0.325106 0.042547 +0.997534 0.115763 +0.326605 0.039549 +0.983284 0.117268 +0.806675 0.117071 +0.988433 0.120449 +0.393617 0.132834 +0.990008 0.129654 +0.848858 0.129412 +0.312455 0.053169 +0.302092 0.051499 +0.295960 0.086764 +0.289823 0.074256 +0.612905 0.331331 +0.436135 0.330853 +0.570677 0.343510 +0.801617 0.184566 +0.429535 0.343210 +0.431145 0.334012 +0.096426 0.074255 +0.096426 0.051497 +0.006836 0.053169 +0.023332 0.086765 +0.799250 0.103725 +0.799243 0.115635 +0.666518 0.014827 +0.666519 0.024712 +0.617907 0.334796 +0.584280 0.351218 +0.968803 0.097485 +0.968789 0.085574 +0.997915 0.145659 +0.997928 0.135774 +0.801660 0.120516 +0.835225 0.137068 +0.382560 0.118727 +0.370650 0.118665 +0.360766 0.118702 +0.330599 0.118813 +0.318688 0.118962 +0.340484 0.118777 +0.340438 0.106541 +0.360721 0.106467 +0.370605 0.106431 +0.382516 0.106492 +0.318643 0.106727 +0.330554 0.106578 +0.402948 0.089996 +0.391037 0.090030 +0.381152 0.089971 +0.350986 0.089792 +0.339077 0.089616 +0.360870 0.089851 +0.381080 0.102207 +0.360798 0.102086 +0.402875 0.102232 +0.390964 0.102266 +0.350913 0.102028 +0.339004 0.101852 +0.653860 0.061352 +0.653860 0.039693 +0.696721 0.081438 +0.684084 0.081552 +0.689712 0.067066 +0.677076 0.066952 +0.673102 0.088854 +0.673102 0.067196 +0.632732 0.091027 +0.635961 0.090612 +0.633237 0.082962 +0.636465 0.082547 +0.891075 0.756619 +0.991731 0.756619 +0.761135 0.756619 +0.861326 0.756619 +0.861402 0.771773 +0.891173 0.771773 +0.991731 0.771773 +0.761135 0.771773 +0.866686 0.756619 +0.885702 0.756619 +0.871562 0.756619 +0.880810 0.756619 +0.876184 0.756619 +0.866759 0.771773 +0.885802 0.771773 +0.871650 0.771773 +0.880903 0.771773 +0.876489 0.771773 +0.761135 0.754289 +0.991731 0.754289 +0.891075 0.754289 +0.861326 0.754289 +0.991731 0.769412 +0.891173 0.769412 +0.861402 0.769412 +0.761135 0.769412 +0.885702 0.754289 +0.866686 0.754289 +0.880810 0.754289 +0.871562 0.754289 +0.876184 0.754289 +0.885802 0.769412 +0.866759 0.769412 +0.880903 0.769412 +0.871650 0.769412 +0.876489 0.769412 +0.861216 0.749698 +0.890962 0.749698 +0.991731 0.749698 +0.761135 0.749698 +0.890445 0.753429 +0.991731 0.753429 +0.761135 0.753429 +0.860744 0.753429 +0.885598 0.749698 +0.866577 0.749698 +0.880715 0.749698 +0.871461 0.749698 +0.876288 0.749698 +0.885049 0.753429 +0.866072 0.753429 +0.880150 0.753429 +0.870924 0.753429 +0.875527 0.753429 +0.991731 0.747373 +0.890962 0.747373 +0.861216 0.747373 +0.761135 0.747373 +0.761135 0.751102 +0.991731 0.751102 +0.890445 0.751102 +0.860744 0.751102 +0.885598 0.747373 +0.866577 0.747373 +0.880715 0.747373 +0.871461 0.747373 +0.876288 0.747373 +0.885049 0.751102 +0.866072 0.751102 +0.880150 0.751102 +0.870924 0.751102 +0.875527 0.751102 +0.890771 0.761641 +0.861097 0.761641 +0.761135 0.761641 +0.991731 0.761641 +0.891116 0.767610 +0.991731 0.767610 +0.761135 0.767610 +0.861394 0.767610 +0.866438 0.761641 +0.885403 0.761641 +0.871304 0.761641 +0.880525 0.761641 +0.875913 0.761641 +0.885741 0.767610 +0.866744 0.767610 +0.880853 0.767610 +0.871615 0.767610 +0.876229 0.767610 +0.761135 0.763965 +0.861097 0.763965 +0.890771 0.763965 +0.991731 0.763965 +0.761135 0.765281 +0.991731 0.765281 +0.891116 0.765281 +0.861394 0.765281 +0.866438 0.763965 +0.885403 0.763965 +0.871304 0.763965 +0.880525 0.763965 +0.875913 0.763965 +0.885741 0.765281 +0.866744 0.765281 +0.880853 0.765281 +0.871615 0.765281 +0.876229 0.765281 +0.862726 0.773917 +0.761135 0.773917 +0.991731 0.773917 +0.892385 0.773917 +0.861499 0.760471 +0.891160 0.760471 +0.991731 0.760471 +0.761135 0.760471 +0.887061 0.773917 +0.868117 0.773917 +0.882215 0.773917 +0.873007 0.773917 +0.877618 0.773917 +0.866857 0.760471 +0.885814 0.760471 +0.871730 0.760471 +0.880949 0.760471 +0.876342 0.760471 +0.991731 0.776242 +0.761135 0.776242 +0.862726 0.776242 +0.892385 0.776242 +0.991731 0.758148 +0.891160 0.758148 +0.861499 0.758148 +0.761135 0.758148 +0.868117 0.776242 +0.887061 0.776242 +0.873007 0.776242 +0.882215 0.776242 +0.877618 0.776242 +0.885814 0.758148 +0.866857 0.758148 +0.880949 0.758148 +0.871730 0.758148 +0.876342 0.758148 +0.700017 0.825747 +0.700017 0.788648 +0.755151 0.825320 +0.755151 0.788214 +0.653511 0.749135 +0.653511 0.786241 +0.753884 0.786207 +0.753884 0.749101 +0.995494 0.178374 +0.703734 0.124428 +0.416982 0.164112 +0.832661 0.208239 +0.965736 0.153101 +0.680366 0.093152 + + + + + + + + + + + +

2 0 0 12 1 1 1 2 2 1 3 2 0 4 3 2 5 0 36 6 5 37 7 6 29 8 7 29 9 7 28 10 4 36 11 5 0 12 1006 1 13 1005 18 14 1007 0 15 1006 18 16 1007 9 17 1009 0 18 1006 9 19 1009 4 20 1010 4 21 11 9 22 973 10 23 12 10 24 12 5 25 13 4 26 11 31 27 14 29 28 7 37 29 6 10 30 955 24 31 958 7 32 959 5 33 956 10 34 955 7 35 959 5 36 956 7 37 959 6 38 960 6 39 18 7 40 17 16 41 19 16 42 19 8 43 20 6 44 18 33 45 21 31 46 14 37 47 6 35 48 964 33 49 963 37 50 980 17 51 28 11 52 29 34 53 42 34 54 42 19 55 27 17 56 28 18 57 8 1 58 2 12 59 1 12 60 1 20 61 30 18 62 8 21 63 1013 13 64 1014 11 65 1012 11 66 1012 17 67 1011 21 68 1013 22 69 33 14 70 34 13 71 32 13 72 32 21 73 31 22 74 33 23 75 968 15 76 969 14 77 967 14 78 967 22 79 966 23 80 968 25 81 37 35 82 22 15 83 36 15 84 36 23 85 35 25 86 37 26 87 38 16 88 19 7 89 17 7 90 17 24 91 16 26 92 38 0 93 3 17 94 1032 19 95 1031 19 96 1031 2 97 0 0 98 3 9 99 965 18 100 8 20 101 30 20 102 30 3 103 1000 9 104 965 4 105 1010 21 106 1036 17 107 1035 17 108 1035 0 109 1006 4 110 1010 5 111 13 22 112 1034 21 113 1033 21 114 1033 4 115 11 5 116 13 6 117 960 23 118 995 22 119 994 22 120 994 5 121 956 6 122 960 8 123 20 25 124 991 23 125 990 23 126 990 6 127 18 8 128 20 33 129 25 26 130 38 24 131 16 24 132 16 10 133 998 33 134 25 9 135 10 3 136 23 27 137 40 27 138 40 30 139 39 9 140 10 10 141 999 9 142 10 30 143 39 30 144 39 32 145 41 10 146 999 33 147 21 10 148 999 32 149 41 25 150 970 8 151 962 16 152 961 25 153 970 16 154 961 26 155 971 25 156 970 26 157 971 33 158 963 35 159 964 25 160 970 33 161 963 32 162 41 31 163 14 33 164 21 31 165 1039 32 166 1042 43 167 1043 43 168 1043 42 169 1044 31 170 1039 28 171 1037 29 172 1038 40 173 1045 40 174 1045 39 175 1046 28 176 1037 29 177 1038 31 178 1039 42 179 1044 42 180 1044 40 181 1045 29 182 1038 30 183 1040 27 184 1041 38 185 1047 38 186 1047 41 187 1048 30 188 1040 32 189 1042 30 190 1040 41 191 1048 41 192 1048 43 193 1043 32 194 1042 38 195 47 39 196 46 40 197 45 40 198 45 41 199 48 38 200 47 41 201 48 40 202 45 42 203 44 42 204 44 43 205 43 41 206 48 44 207 49 47 208 50 46 209 51 46 210 51 45 211 52 44 212 49 36 213 5 48 214 53 49 215 54 49 216 54 37 217 6 36 218 5 47 219 1015 52 220 1017 51 221 1019 47 222 1015 51 223 1019 50 224 1020 47 225 1015 50 226 1020 46 227 1016 52 228 55 53 229 59 55 230 60 55 231 60 51 232 1001 52 233 55 37 234 6 49 235 54 54 236 61 53 237 972 58 238 974 57 239 975 57 240 975 56 241 976 55 242 977 53 243 972 57 244 975 55 245 977 58 246 62 60 247 66 59 248 67 59 249 67 57 250 63 58 251 62 75 252 987 35 253 964 37 254 980 13 255 1014 62 256 1021 63 257 1022 63 258 1022 11 259 1012 13 260 1014 14 261 34 64 262 72 62 263 70 62 264 70 13 265 32 14 266 34 15 267 969 65 268 982 64 269 981 64 270 981 14 271 967 15 272 969 35 273 22 75 274 83 65 275 73 65 276 73 15 277 36 35 278 22 69 279 77 68 280 78 67 281 76 67 282 76 63 283 71 69 284 77 50 285 58 70 286 79 45 287 52 45 288 52 46 289 51 50 290 58 71 291 1024 69 292 1023 63 293 1022 63 294 1022 62 295 1021 71 296 1024 72 297 81 71 298 80 62 299 70 62 300 70 64 301 72 72 302 81 73 303 986 72 304 985 64 305 981 64 306 981 65 307 982 73 308 986 74 309 84 73 310 82 65 311 73 65 312 73 75 313 83 74 314 84 76 315 85 56 316 64 57 317 63 57 318 63 59 319 67 76 320 85 47 321 50 44 322 49 68 323 1026 68 324 1026 69 325 1025 47 326 50 51 327 983 61 328 1003 70 329 79 70 330 79 50 331 58 51 332 983 52 333 1017 47 334 1015 69 335 1029 69 336 1029 71 337 1030 52 338 1017 53 339 59 52 340 55 71 341 1027 71 342 1027 72 343 1028 53 344 59 58 345 974 53 346 972 72 347 996 72 348 996 73 349 997 58 350 974 60 351 66 58 352 62 73 353 992 73 354 992 74 355 993 60 356 66 66 357 75 55 358 65 56 359 64 56 360 64 76 361 85 66 362 75 51 363 57 77 364 86 78 365 87 78 366 87 61 367 68 51 368 57 55 369 1002 79 370 88 77 371 86 77 372 86 51 373 57 55 374 1002 79 375 88 55 376 1002 66 377 1004 59 378 979 60 379 978 74 380 988 76 381 989 59 382 979 74 383 988 66 384 984 76 385 989 74 386 988 66 387 984 74 388 988 75 389 987 37 390 6 54 391 61 79 392 88 79 393 88 66 394 1004 37 395 6 37 396 980 66 397 984 75 398 987 67 399 76 34 400 42 11 401 29 11 402 29 63 403 71 67 404 76 54 405 1051 81 406 1055 80 407 1056 80 408 1056 79 409 1054 54 410 1051 48 411 1049 83 412 1057 82 413 1058 82 414 1058 49 415 1050 48 416 1049 49 417 1050 82 418 1058 81 419 1055 81 420 1055 54 421 1051 49 422 1050 77 423 1052 85 424 1059 84 425 1060 84 426 1060 78 427 1053 77 428 1052 79 429 1054 80 430 1056 85 431 1059 85 432 1059 77 433 1052 79 434 1054 84 435 94 85 436 93 82 437 92 82 438 92 83 439 91 84 440 94 85 441 93 80 442 90 81 443 89 81 444 89 82 445 92 85 446 93 108 447 756 109 448 757 87 449 758 87 450 758 86 451 755 108 452 756 86 453 95 87 454 98 111 455 919 111 456 919 90 457 920 86 458 95 107 459 101 89 460 102 113 461 103 113 462 103 91 463 104 107 464 101 109 465 97 108 466 96 112 467 921 112 468 921 93 469 922 109 470 97 88 471 107 106 472 108 110 473 109 110 474 109 92 475 110 88 476 107 90 477 100 111 478 99 115 479 931 115 480 931 94 481 932 90 482 100 91 483 104 113 484 103 117 485 113 117 486 113 95 487 114 91 488 104 93 489 106 112 490 105 116 491 933 116 492 933 97 493 934 93 494 106 92 495 110 110 496 109 114 497 117 114 498 117 96 499 118 92 500 110 94 501 112 115 502 111 119 503 943 119 504 943 98 505 944 94 506 112 95 507 114 117 508 113 121 509 9 121 510 9 99 511 15 95 512 114 97 513 116 116 514 115 120 515 945 120 516 945 101 517 946 97 518 116 96 519 118 114 520 117 118 521 24 118 522 24 100 523 26 96 524 118 98 525 120 119 526 119 103 527 127 103 528 127 122 529 128 98 530 120 99 531 122 121 532 121 105 533 129 105 534 129 123 535 130 99 536 122 101 537 124 120 538 123 104 539 131 104 540 131 125 541 132 101 542 124 100 543 126 118 544 125 102 545 133 102 546 133 124 547 134 100 548 126 131 549 924 111 550 919 87 551 98 87 552 98 127 553 923 131 554 924 126 555 926 86 556 95 90 557 920 90 558 920 130 559 925 126 560 926 133 561 140 113 562 103 89 563 102 89 564 102 129 565 139 133 566 140 132 567 930 112 568 921 108 569 96 108 570 96 128 571 929 132 572 930 134 573 143 114 574 117 110 575 109 110 576 109 130 577 137 134 578 143 135 579 940 115 580 931 111 581 99 111 582 99 131 583 935 135 584 940 136 585 941 116 586 933 112 587 105 112 588 105 132 589 938 136 590 941 137 591 146 117 592 113 113 593 103 113 594 103 133 595 140 137 596 146 138 597 56 118 598 24 114 599 117 114 600 117 134 601 143 138 602 56 139 603 952 119 604 943 115 605 111 115 606 111 135 607 948 139 608 952 140 609 953 120 610 945 116 611 115 116 612 115 136 613 949 140 614 953 141 615 957 121 616 9 117 617 113 117 618 113 137 619 146 141 620 957 142 621 151 102 622 133 118 623 125 118 624 125 138 625 147 142 626 151 143 627 152 103 628 127 119 629 119 119 630 119 139 631 148 143 632 152 144 633 153 104 634 131 120 635 123 120 636 123 140 637 149 144 638 153 145 639 154 105 640 129 121 641 121 121 642 121 141 643 150 145 644 154 91 645 104 131 646 136 127 647 135 127 648 135 107 649 101 91 650 104 106 651 108 126 652 138 130 653 137 130 654 137 110 655 109 106 656 108 93 657 922 133 658 928 129 659 927 129 660 927 109 661 97 93 662 922 92 663 110 132 664 142 128 665 141 128 666 141 88 667 107 92 668 110 94 669 932 134 670 939 130 671 936 130 672 936 90 673 100 94 674 932 95 675 114 135 676 144 131 677 136 131 678 136 91 679 104 95 680 114 96 681 118 136 682 145 132 683 142 132 684 142 92 685 110 96 686 118 97 687 934 137 688 942 133 689 937 133 690 937 93 691 106 97 692 934 98 693 944 138 694 951 134 695 947 134 696 947 94 697 112 98 698 944 99 699 15 139 700 69 135 701 144 135 702 144 95 703 114 99 704 15 100 705 26 140 706 74 136 707 145 136 708 145 96 709 118 100 710 26 101 711 946 141 712 954 137 713 950 137 714 950 97 715 116 101 716 946 122 717 128 142 718 1227 138 719 1008 138 720 1008 98 721 120 122 722 128 123 723 130 143 724 1228 139 725 1018 139 726 1018 99 727 122 123 728 130 124 729 134 144 730 1229 140 731 1225 140 732 1225 100 733 126 124 734 134 125 735 132 145 736 1230 141 737 1226 141 738 1226 101 739 124 125 740 132 126 741 764 128 742 766 108 743 756 108 744 756 86 745 755 126 746 764 106 747 762 88 748 761 128 749 766 128 750 766 126 751 764 106 752 762 129 753 765 127 754 763 87 755 758 87 756 758 109 757 757 129 758 765 89 759 760 107 760 759 127 761 763 127 762 763 129 763 765 89 764 760 147 765 155 151 766 156 149 767 157 147 768 155 146 769 158 150 770 159 150 771 159 151 772 156 147 773 155 146 774 158 148 775 160 150 776 159 153 777 161 157 778 162 155 779 163 153 780 161 152 781 164 156 782 165 156 783 165 157 784 162 153 785 161 152 786 164 154 787 166 156 788 165 159 789 167 163 790 168 161 791 169 159 792 167 158 793 170 162 794 171 162 795 171 163 796 168 159 797 167 158 798 170 160 799 172 162 800 171 165 801 173 169 802 174 167 803 175 165 804 173 164 805 176 168 806 177 168 807 177 169 808 174 165 809 173 164 810 176 166 811 178 168 812 177 170 813 179 172 814 180 171 815 181 198 816 182 199 817 183 172 818 180 172 819 180 170 820 179 198 821 182 173 822 184 175 823 185 174 824 186 173 825 184 174 826 186 177 827 187 177 828 187 176 829 188 173 830 184 176 831 188 177 832 187 178 833 189 179 834 190 181 835 191 180 836 192 179 837 190 180 838 192 183 839 193 183 840 193 182 841 194 179 842 190 182 843 194 183 844 193 184 845 195 185 846 196 187 847 197 186 848 198 185 849 196 186 850 198 189 851 199 189 852 199 188 853 200 185 854 196 188 855 200 189 856 199 190 857 201 191 858 202 193 859 203 192 860 204 191 861 202 192 862 204 195 863 205 195 864 205 194 865 206 191 866 202 194 867 206 195 868 205 196 869 207 198 870 182 197 871 208 199 872 183 200 873 209 202 874 210 201 875 211 200 876 209 201 877 211 204 878 212 204 879 212 203 880 213 200 881 209 203 882 213 204 883 212 205 884 214 206 885 215 208 886 216 207 887 217 206 888 215 207 889 217 210 890 218 210 891 218 209 892 219 206 893 215 209 894 219 210 895 218 211 896 220 212 897 221 214 898 222 213 899 223 212 900 221 213 901 223 216 902 224 216 903 224 215 904 225 212 905 221 215 906 225 216 907 224 217 908 226 218 909 227 220 910 228 219 911 229 218 912 227 219 913 229 222 914 230 222 915 230 221 916 231 218 917 227 221 918 231 222 919 230 223 920 232 224 921 233 226 922 234 225 923 235 252 924 237 224 925 233 225 926 235 225 927 235 227 928 236 252 929 237 228 930 238 230 931 239 229 932 240 228 933 238 232 934 241 231 935 242 231 936 242 230 937 239 228 938 238 232 939 241 233 940 243 231 941 242 234 942 244 236 943 245 235 944 246 234 945 244 238 946 247 237 947 248 237 948 248 236 949 245 234 950 244 238 951 247 239 952 249 237 953 248 240 954 250 242 955 251 241 956 252 240 957 250 244 958 253 243 959 254 243 960 254 242 961 251 240 962 250 244 963 253 245 964 255 243 965 254 246 966 256 248 967 257 247 968 258 246 969 256 250 970 259 249 971 260 249 972 260 248 973 257 246 974 256 250 975 259 251 976 261 249 977 260 252 978 237 227 979 236 253 980 262 254 981 263 255 982 264 256 983 265 254 984 263 257 985 266 258 986 267 258 987 267 255 988 264 254 989 263 257 990 266 259 991 268 258 992 267 260 993 269 261 994 270 262 995 271 260 996 269 263 997 272 264 998 273 264 999 273 261 1000 270 260 1001 269 263 1002 272 265 1003 274 264 1004 273 266 1005 275 267 1006 276 268 1007 277 266 1008 275 269 1009 278 270 1010 279 270 1011 279 267 1012 276 266 1013 275 269 1014 278 271 1015 280 270 1016 279 272 1017 281 274 1018 282 273 1019 283 272 1020 281 273 1021 283 276 1022 284 276 1023 284 275 1024 285 272 1025 281 275 1026 285 276 1027 284 277 1028 286 278 1029 287 280 1030 288 279 1031 289 278 1032 287 279 1033 289 282 1034 290 282 1035 290 281 1036 291 278 1037 287 281 1038 291 282 1039 290 283 1040 292 284 1041 293 286 1042 294 285 1043 295 284 1044 293 285 1045 295 288 1046 296 288 1047 296 287 1048 297 284 1049 293 287 1050 297 288 1051 296 289 1052 298 290 1053 299 291 1054 300 309 1055 301 309 1056 301 308 1057 302 290 1058 299 291 1059 300 292 1060 303 310 1061 304 310 1062 304 309 1063 301 291 1064 300 292 1065 303 293 1066 305 311 1067 306 311 1068 306 310 1069 304 292 1070 303 293 1071 305 294 1072 307 312 1073 308 312 1074 308 311 1075 306 293 1076 305 294 1077 307 295 1078 309 313 1079 310 313 1080 310 312 1081 308 294 1082 307 295 1083 777 296 1084 311 314 1085 312 314 1086 312 313 1087 779 295 1088 777 296 1089 311 297 1090 313 315 1091 314 315 1092 314 314 1093 312 296 1094 311 297 1095 313 298 1096 315 316 1097 316 316 1098 316 315 1099 314 297 1100 313 298 1101 315 299 1102 317 317 1103 318 317 1104 318 316 1105 316 298 1106 315 299 1107 317 300 1108 319 318 1109 320 318 1110 320 317 1111 318 299 1112 317 300 1113 319 301 1114 321 319 1115 322 319 1116 322 318 1117 320 300 1118 319 301 1119 321 302 1120 323 320 1121 324 320 1122 324 319 1123 322 301 1124 321 302 1125 323 303 1126 325 321 1127 326 321 1128 326 320 1129 324 302 1130 323 303 1131 325 304 1132 327 322 1133 328 322 1134 328 321 1135 326 303 1136 325 304 1137 327 305 1138 329 323 1139 330 323 1140 330 322 1141 328 304 1142 327 305 1143 329 306 1144 331 324 1145 332 324 1146 332 323 1147 330 305 1148 329 306 1149 331 307 1150 333 325 1151 334 325 1152 334 324 1153 332 306 1154 331 307 1155 333 290 1156 299 308 1157 302 308 1158 302 325 1159 334 307 1160 333 321 1161 796 322 1162 798 323 1163 800 323 1164 800 320 1165 794 321 1166 796 320 1167 794 323 1168 800 324 1169 802 324 1170 802 319 1171 792 320 1172 794 319 1173 792 324 1174 802 325 1175 804 325 1176 804 318 1177 790 319 1178 792 318 1179 790 325 1180 804 308 1181 770 308 1182 770 317 1183 788 318 1184 790 317 1185 788 308 1186 770 309 1187 769 309 1188 769 316 1189 786 317 1190 788 316 1191 786 309 1192 769 310 1193 772 310 1194 772 315 1195 784 316 1196 786 315 1197 784 310 1198 772 311 1199 774 311 1200 774 314 1201 782 315 1202 784 314 1203 782 311 1204 774 312 1205 776 312 1206 776 313 1207 780 314 1208 782 295 1209 778 294 1210 775 293 1211 773 293 1212 773 296 1213 781 295 1214 778 296 1215 781 293 1216 773 292 1217 771 292 1218 771 297 1219 783 296 1220 781 297 1221 783 292 1222 771 291 1223 768 291 1224 768 298 1225 785 297 1226 783 298 1227 785 291 1228 768 290 1229 767 290 1230 767 299 1231 787 298 1232 785 299 1233 787 290 1234 767 307 1235 803 307 1236 803 300 1237 789 299 1238 787 300 1239 789 307 1240 803 306 1241 801 306 1242 801 301 1243 791 300 1244 789 301 1245 791 306 1246 801 305 1247 799 305 1248 799 302 1249 793 301 1250 791 302 1251 793 305 1252 799 304 1253 797 304 1254 797 303 1255 795 302 1256 793 326 1257 335 329 1258 336 328 1259 337 328 1260 337 327 1261 338 326 1262 335 327 1263 338 328 1264 337 331 1265 339 331 1266 339 330 1267 340 327 1268 338 330 1269 340 331 1270 339 333 1271 341 333 1272 341 332 1273 342 330 1274 340 332 1275 342 333 1276 341 335 1277 343 335 1278 343 334 1279 344 332 1280 342 334 1281 815 335 1282 813 337 1283 345 337 1284 345 336 1285 346 334 1286 815 336 1287 346 337 1288 345 339 1289 347 339 1290 347 338 1291 348 336 1292 346 338 1293 348 339 1294 347 341 1295 349 341 1296 349 340 1297 350 338 1298 348 340 1299 350 341 1300 349 343 1301 351 343 1302 351 342 1303 352 340 1304 350 342 1305 352 343 1306 351 345 1307 353 345 1308 353 344 1309 354 342 1310 352 344 1311 354 345 1312 353 347 1313 355 347 1314 355 346 1315 356 344 1316 354 346 1317 356 347 1318 355 349 1319 357 349 1320 357 348 1321 358 346 1322 356 348 1323 358 349 1324 357 351 1325 359 351 1326 359 350 1327 360 348 1328 358 350 1329 360 351 1330 359 353 1331 361 353 1332 361 352 1333 362 350 1334 360 352 1335 362 353 1336 361 355 1337 363 355 1338 363 354 1339 364 352 1340 362 354 1341 364 355 1342 363 357 1343 365 357 1344 365 356 1345 366 354 1346 364 356 1347 366 357 1348 365 359 1349 367 359 1350 367 358 1351 368 356 1352 366 358 1353 368 359 1354 367 361 1355 369 361 1356 369 360 1357 370 358 1358 368 360 1359 370 361 1360 369 329 1361 336 329 1362 336 326 1363 335 360 1364 370 353 1365 833 351 1366 831 357 1367 837 357 1368 837 355 1369 835 353 1370 833 351 1371 831 349 1372 829 359 1373 839 359 1374 839 357 1375 837 351 1376 831 349 1377 829 347 1378 827 361 1379 841 361 1380 841 359 1381 839 349 1382 829 347 1383 827 345 1384 825 329 1385 806 329 1386 806 361 1387 841 347 1388 827 345 1389 825 343 1390 823 328 1391 807 328 1392 807 329 1393 806 345 1394 825 343 1395 823 341 1396 821 331 1397 809 331 1398 809 328 1399 807 343 1400 823 341 1401 821 339 1402 819 333 1403 811 333 1404 811 331 1405 809 341 1406 821 339 1407 819 337 1408 817 335 1409 814 335 1410 814 333 1411 811 339 1412 819 336 1413 818 338 1414 820 332 1415 812 332 1416 812 334 1417 816 336 1418 818 338 1419 820 340 1420 822 330 1421 810 330 1422 810 332 1423 812 338 1424 820 340 1425 822 342 1426 824 327 1427 808 327 1428 808 330 1429 810 340 1430 822 342 1431 824 344 1432 826 326 1433 805 326 1434 805 327 1435 808 342 1436 824 344 1437 826 346 1438 828 360 1439 842 360 1440 842 326 1441 805 344 1442 826 346 1443 828 348 1444 830 358 1445 840 358 1446 840 360 1447 842 346 1448 828 348 1449 830 350 1450 832 356 1451 838 356 1452 838 358 1453 840 348 1454 830 350 1455 832 352 1456 834 354 1457 836 354 1458 836 356 1459 838 350 1460 832 362 1461 371 365 1462 372 364 1463 373 364 1464 373 363 1465 374 362 1466 371 363 1467 374 364 1468 373 367 1469 375 367 1470 375 366 1471 376 363 1472 374 366 1473 376 367 1474 375 369 1475 377 369 1476 377 368 1477 378 366 1478 376 368 1479 378 369 1480 377 371 1481 379 371 1482 379 370 1483 380 368 1484 378 370 1485 380 371 1486 379 373 1487 381 373 1488 381 372 1489 382 370 1490 380 372 1491 855 373 1492 853 375 1493 383 375 1494 383 374 1495 384 372 1496 855 374 1497 384 375 1498 383 377 1499 385 377 1500 385 376 1501 386 374 1502 384 376 1503 386 377 1504 385 379 1505 387 379 1506 387 378 1507 388 376 1508 386 378 1509 388 379 1510 387 381 1511 389 381 1512 389 380 1513 390 378 1514 388 380 1515 390 381 1516 389 383 1517 391 383 1518 391 382 1519 392 380 1520 390 382 1521 392 383 1522 391 385 1523 393 385 1524 393 384 1525 394 382 1526 392 384 1527 394 385 1528 393 387 1529 395 387 1530 395 386 1531 396 384 1532 394 386 1533 396 387 1534 395 389 1535 397 389 1536 397 388 1537 398 386 1538 396 388 1539 398 389 1540 397 391 1541 399 391 1542 399 390 1543 400 388 1544 398 390 1545 400 391 1546 399 393 1547 401 393 1548 401 392 1549 402 390 1550 400 392 1551 402 393 1552 401 395 1553 403 395 1554 403 394 1555 404 392 1556 402 394 1557 404 395 1558 403 397 1559 405 397 1560 405 396 1561 406 394 1562 404 396 1563 406 397 1564 405 365 1565 372 365 1566 372 362 1567 371 396 1568 406 389 1569 871 387 1570 869 393 1571 875 393 1572 875 391 1573 873 389 1574 871 387 1575 869 385 1576 867 395 1577 877 395 1578 877 393 1579 875 387 1580 869 385 1581 867 383 1582 865 397 1583 879 397 1584 879 395 1585 877 385 1586 867 383 1587 865 381 1588 863 365 1589 844 365 1590 844 397 1591 879 383 1592 865 381 1593 863 379 1594 861 364 1595 845 364 1596 845 365 1597 844 381 1598 863 379 1599 861 377 1600 859 367 1601 847 367 1602 847 364 1603 845 379 1604 861 377 1605 859 375 1606 857 369 1607 849 369 1608 849 367 1609 847 377 1610 859 375 1611 857 373 1612 854 371 1613 851 371 1614 851 369 1615 849 375 1616 857 372 1617 856 374 1618 858 368 1619 850 368 1620 850 370 1621 852 372 1622 856 374 1623 858 376 1624 860 366 1625 848 366 1626 848 368 1627 850 374 1628 858 376 1629 860 378 1630 862 363 1631 846 363 1632 846 366 1633 848 376 1634 860 378 1635 862 380 1636 864 362 1637 843 362 1638 843 363 1639 846 378 1640 862 380 1641 864 382 1642 866 396 1643 880 396 1644 880 362 1645 843 380 1646 864 382 1647 866 384 1648 868 394 1649 878 394 1650 878 396 1651 880 382 1652 866 384 1653 868 386 1654 870 392 1655 876 392 1656 876 394 1657 878 384 1658 868 386 1659 870 388 1660 872 390 1661 874 390 1662 874 392 1663 876 386 1664 870 398 1665 407 401 1666 408 400 1667 409 400 1668 409 399 1669 410 398 1670 407 401 1671 408 403 1672 411 402 1673 412 402 1674 412 400 1675 409 401 1676 408 403 1677 411 405 1678 413 404 1679 414 404 1680 414 402 1681 412 403 1682 411 405 1683 413 407 1684 415 406 1685 416 406 1686 416 404 1687 414 405 1688 413 407 1689 889 409 1690 417 408 1691 418 408 1692 418 406 1693 891 407 1694 889 409 1695 417 411 1696 419 410 1697 420 410 1698 420 408 1699 418 409 1700 417 411 1701 419 413 1702 421 412 1703 422 412 1704 422 410 1705 420 411 1706 419 413 1707 421 415 1708 423 414 1709 424 414 1710 424 412 1711 422 413 1712 421 415 1713 423 417 1714 425 416 1715 426 416 1716 426 414 1717 424 415 1718 423 417 1719 425 419 1720 427 418 1721 428 418 1722 428 416 1723 426 417 1724 425 419 1725 427 421 1726 429 420 1727 430 420 1728 430 418 1729 428 419 1730 427 421 1731 429 423 1732 431 422 1733 432 422 1734 432 420 1735 430 421 1736 429 423 1737 431 425 1738 433 424 1739 434 424 1740 434 422 1741 432 423 1742 431 425 1743 433 427 1744 435 426 1745 436 426 1746 436 424 1747 434 425 1748 433 427 1749 435 429 1750 437 428 1751 438 428 1752 438 426 1753 436 427 1754 435 429 1755 437 431 1756 439 430 1757 440 430 1758 440 428 1759 438 429 1760 437 431 1761 439 433 1762 441 432 1763 442 432 1764 442 430 1765 440 431 1766 439 433 1767 441 398 1768 407 399 1769 410 399 1770 410 432 1771 442 433 1772 441 424 1773 910 426 1774 912 428 1775 914 428 1776 914 422 1777 908 424 1778 910 422 1779 908 428 1780 914 430 1781 916 430 1782 916 420 1783 906 422 1784 908 420 1785 906 430 1786 916 432 1787 918 432 1788 918 418 1789 904 420 1790 906 418 1791 904 432 1792 918 399 1793 884 399 1794 884 416 1795 902 418 1796 904 416 1797 902 399 1798 884 400 1799 883 400 1800 883 414 1801 900 416 1802 902 414 1803 900 400 1804 883 402 1805 886 402 1806 886 412 1807 898 414 1808 900 412 1809 898 402 1810 886 404 1811 888 404 1812 888 410 1813 896 412 1814 898 410 1815 896 404 1816 888 406 1817 892 406 1818 892 408 1819 894 410 1820 896 409 1821 893 407 1822 890 405 1823 887 405 1824 887 411 1825 895 409 1826 893 411 1827 895 405 1828 887 403 1829 885 403 1830 885 413 1831 897 411 1832 895 413 1833 897 403 1834 885 401 1835 882 401 1836 882 415 1837 899 413 1838 897 415 1839 899 401 1840 882 398 1841 881 398 1842 881 417 1843 901 415 1844 899 417 1845 901 398 1846 881 433 1847 917 433 1848 917 419 1849 903 417 1850 901 419 1851 903 433 1852 917 431 1853 915 431 1854 915 421 1855 905 419 1856 903 421 1857 905 431 1858 915 429 1859 913 429 1860 913 423 1861 907 421 1862 905 423 1863 907 429 1864 913 427 1865 911 427 1866 911 425 1867 909 423 1868 907 438 1869 445 434 1870 446 435 1871 443 435 1872 443 439 1873 444 438 1874 445 440 1875 449 441 1876 450 437 1877 447 437 1878 447 436 1879 448 440 1880 449 435 1881 443 434 1882 446 451 1883 451 451 1884 451 447 1885 452 435 1886 443 447 1887 452 451 1888 451 450 1889 453 450 1890 453 448 1891 454 447 1892 452 450 1893 453 449 1894 455 448 1895 454 436 1896 448 437 1897 447 446 1898 456 446 1899 456 442 1900 457 436 1901 448 442 1902 457 446 1903 456 445 1904 458 445 1905 458 443 1906 459 442 1907 457 445 1908 458 444 1909 460 443 1910 459 453 1911 463 452 1912 464 456 1913 461 456 1914 461 457 1915 462 453 1916 463 455 1917 467 459 1918 468 458 1919 465 458 1920 465 454 1921 466 455 1922 467 469 1923 470 452 1924 464 453 1925 463 453 1926 463 465 1927 469 469 1928 470 468 1929 472 469 1930 470 465 1931 469 465 1932 469 466 1933 471 468 1934 472 466 1935 471 467 1936 473 468 1937 472 464 1938 475 455 1939 467 454 1940 466 454 1941 466 460 1942 474 464 1943 475 463 1944 477 464 1945 475 460 1946 474 460 1947 474 461 1948 476 463 1949 477 461 1950 476 462 1951 478 463 1952 477 453 1953 1093 457 1954 1092 439 1955 1074 439 1956 1074 435 1957 1073 453 1958 1093 456 1959 1091 452 1960 1094 434 1961 1076 434 1962 1076 438 1963 1075 456 1964 1091 454 1965 1096 458 1966 1095 440 1967 1079 440 1968 1079 436 1969 1078 454 1970 1096 459 1971 1098 455 1972 1097 437 1973 1077 437 1974 1077 441 1975 1080 459 1976 1098 465 1977 1099 453 1978 1093 435 1979 1073 435 1980 1073 447 1981 1082 465 1982 1099 452 1983 1094 469 1984 1100 451 1985 1081 451 1986 1081 434 1987 1076 452 1988 1094 466 1989 1101 465 1990 1099 447 1991 1082 447 1992 1082 448 1993 1084 466 1994 1101 469 1995 1100 468 1996 1102 450 1997 1083 450 1998 1083 451 1999 1081 469 2000 1100 468 2001 1102 467 2002 1103 449 2003 1085 449 2004 1085 450 2005 1083 468 2006 1102 467 2007 1103 466 2008 1101 448 2009 1084 448 2010 1084 449 2011 1085 467 2012 1103 460 2013 1104 454 2014 1096 436 2015 1078 436 2016 1078 442 2017 1087 460 2018 1104 455 2019 1097 464 2020 1105 446 2021 1086 446 2022 1086 437 2023 1077 455 2024 1097 461 2025 1106 460 2026 1104 442 2027 1087 442 2028 1087 443 2029 1089 461 2030 1106 464 2031 1105 463 2032 1107 445 2033 1088 445 2034 1088 446 2035 1086 464 2036 1105 463 2037 1107 462 2038 1108 444 2039 1090 444 2040 1090 445 2041 1088 463 2042 1107 462 2043 1108 461 2044 1106 443 2045 1089 443 2046 1089 444 2047 1090 462 2048 1108 470 2049 479 483 2050 480 475 2051 481 475 2052 481 474 2053 482 470 2054 479 483 2055 480 484 2056 483 476 2057 484 476 2058 484 475 2059 481 483 2060 480 484 2061 483 471 2062 485 477 2063 486 477 2064 486 476 2065 484 484 2066 483 471 2067 485 472 2068 487 478 2069 488 478 2070 488 477 2071 486 471 2072 485 472 2073 487 485 2074 489 479 2075 490 479 2076 490 478 2077 488 472 2078 487 485 2079 489 486 2080 491 480 2081 492 480 2082 492 479 2083 490 485 2084 489 486 2085 491 487 2086 493 481 2087 494 481 2088 494 480 2089 492 486 2090 491 487 2091 1217 473 2092 495 482 2093 496 482 2094 496 481 2095 1218 487 2096 1217 473 2097 495 470 2098 479 474 2099 482 474 2100 482 482 2101 496 473 2102 495 490 2103 499 489 2104 500 488 2105 497 488 2106 497 491 2107 498 490 2108 499 494 2109 503 493 2110 504 492 2111 501 492 2112 501 495 2113 502 494 2114 503 488 2115 497 497 2116 506 496 2117 505 496 2118 505 491 2119 498 488 2120 497 497 2121 506 499 2122 508 498 2123 507 498 2124 507 496 2125 505 497 2126 506 498 2127 507 499 2128 508 500 2129 509 493 2130 504 502 2131 511 501 2132 510 501 2133 510 492 2134 501 493 2135 504 502 2136 511 504 2137 513 503 2138 512 503 2139 512 501 2140 510 502 2141 511 503 2142 512 504 2143 513 505 2144 514 508 2145 517 507 2146 518 506 2147 515 506 2148 515 509 2149 516 508 2150 517 512 2151 521 511 2152 522 510 2153 519 510 2154 519 513 2155 520 512 2156 521 515 2157 523 514 2158 524 508 2159 517 508 2160 517 509 2161 516 515 2162 523 517 2163 525 516 2164 526 514 2165 524 514 2166 524 515 2167 523 517 2168 525 516 2169 526 517 2170 525 518 2171 527 520 2172 528 519 2173 529 511 2174 522 511 2175 522 512 2176 521 520 2177 528 522 2178 530 521 2179 531 519 2180 529 519 2181 529 520 2182 528 522 2183 530 521 2184 531 522 2185 530 523 2186 532 508 2187 1129 488 2188 1109 489 2189 1112 489 2190 1112 507 2191 1130 508 2192 1129 506 2193 1127 490 2194 1111 491 2195 1110 491 2196 1110 509 2197 1128 506 2198 1127 511 2199 1134 493 2200 1116 494 2201 1115 494 2202 1115 510 2203 1131 511 2204 1134 513 2205 1132 495 2206 1114 492 2207 1113 492 2208 1113 512 2209 1133 513 2210 1132 514 2211 1136 497 2212 1118 488 2213 1109 488 2214 1109 508 2215 1129 514 2216 1136 509 2217 1128 491 2218 1110 496 2219 1117 496 2220 1117 515 2221 1135 509 2222 1128 516 2223 1138 499 2224 1120 497 2225 1118 497 2226 1118 514 2227 1136 516 2228 1138 515 2229 1135 496 2230 1117 498 2231 1119 498 2232 1119 517 2233 1137 515 2234 1135 517 2235 1137 498 2236 1119 500 2237 1121 500 2238 1121 518 2239 1139 517 2240 1137 518 2241 1139 500 2242 1121 499 2243 1120 499 2244 1120 516 2245 1138 518 2246 1139 519 2247 1141 502 2248 1123 493 2249 1116 493 2250 1116 511 2251 1134 519 2252 1141 512 2253 1133 492 2254 1113 501 2255 1122 501 2256 1122 520 2257 1140 512 2258 1133 521 2259 1143 504 2260 1125 502 2261 1123 502 2262 1123 519 2263 1141 521 2264 1143 520 2265 1140 501 2266 1122 503 2267 1124 503 2268 1124 522 2269 1142 520 2270 1140 522 2271 1142 503 2272 1124 505 2273 1126 505 2274 1126 523 2275 1144 522 2276 1142 523 2277 1144 505 2278 1126 504 2279 1125 504 2280 1125 521 2281 1143 523 2282 1144 524 2283 533 527 2284 534 526 2285 535 526 2286 535 525 2287 536 524 2288 533 525 2289 536 526 2290 535 529 2291 537 529 2292 537 528 2293 538 525 2294 536 528 2295 538 529 2296 537 531 2297 539 531 2298 539 530 2299 540 528 2300 538 530 2301 540 531 2302 539 533 2303 541 533 2304 541 532 2305 542 530 2306 540 532 2307 542 533 2308 541 535 2309 543 535 2310 543 534 2311 544 532 2312 542 534 2313 544 535 2314 543 537 2315 545 537 2316 545 536 2317 546 534 2318 544 536 2319 1220 537 2320 1219 539 2321 547 539 2322 547 538 2323 548 536 2324 1220 538 2325 548 539 2326 547 541 2327 549 541 2328 549 540 2329 550 538 2330 548 540 2331 550 541 2332 549 527 2333 534 527 2334 534 524 2335 533 540 2336 550 544 2337 553 543 2338 554 542 2339 551 542 2340 551 545 2341 552 544 2342 553 548 2343 557 547 2344 558 546 2345 555 546 2346 555 549 2347 556 548 2348 557 542 2349 551 551 2350 560 550 2351 559 550 2352 559 545 2353 552 542 2354 551 551 2355 560 553 2356 562 552 2357 561 552 2358 561 550 2359 559 551 2360 560 552 2361 561 553 2362 562 554 2363 563 547 2364 558 556 2365 565 555 2366 564 555 2367 564 546 2368 555 547 2369 558 556 2370 565 558 2371 567 557 2372 566 557 2373 566 555 2374 564 556 2375 565 557 2376 566 558 2377 567 559 2378 568 562 2379 571 561 2380 572 560 2381 569 560 2382 569 563 2383 570 562 2384 571 566 2385 575 565 2386 576 564 2387 573 564 2388 573 567 2389 574 566 2390 575 569 2391 577 568 2392 578 562 2393 571 562 2394 571 563 2395 570 569 2396 577 571 2397 579 570 2398 580 568 2399 578 568 2400 578 569 2401 577 571 2402 579 570 2403 580 571 2404 579 572 2405 581 574 2406 582 573 2407 583 565 2408 576 565 2409 576 566 2410 575 574 2411 582 576 2412 584 575 2413 585 573 2414 583 573 2415 583 574 2416 582 576 2417 584 575 2418 585 576 2419 584 577 2420 586 562 2421 1165 542 2422 1145 543 2423 1148 543 2424 1148 561 2425 1166 562 2426 1165 560 2427 1163 544 2428 1147 545 2429 1146 545 2430 1146 563 2431 1164 560 2432 1163 565 2433 1170 547 2434 1152 548 2435 1151 548 2436 1151 564 2437 1167 565 2438 1170 567 2439 1168 549 2440 1150 546 2441 1149 546 2442 1149 566 2443 1169 567 2444 1168 568 2445 1172 551 2446 1154 542 2447 1145 542 2448 1145 562 2449 1165 568 2450 1172 563 2451 1164 545 2452 1146 550 2453 1153 550 2454 1153 569 2455 1171 563 2456 1164 570 2457 1174 553 2458 1156 551 2459 1154 551 2460 1154 568 2461 1172 570 2462 1174 569 2463 1171 550 2464 1153 552 2465 1155 552 2466 1155 571 2467 1173 569 2468 1171 571 2469 1173 552 2470 1155 554 2471 1157 554 2472 1157 572 2473 1175 571 2474 1173 572 2475 1175 554 2476 1157 553 2477 1156 553 2478 1156 570 2479 1174 572 2480 1175 573 2481 1177 556 2482 1159 547 2483 1152 547 2484 1152 565 2485 1170 573 2486 1177 566 2487 1169 546 2488 1149 555 2489 1158 555 2490 1158 574 2491 1176 566 2492 1169 575 2493 1179 558 2494 1161 556 2495 1159 556 2496 1159 573 2497 1177 575 2498 1179 574 2499 1176 555 2500 1158 557 2501 1160 557 2502 1160 576 2503 1178 574 2504 1176 576 2505 1178 557 2506 1160 559 2507 1162 559 2508 1162 577 2509 1180 576 2510 1178 577 2511 1180 559 2512 1162 558 2513 1161 558 2514 1161 575 2515 1179 577 2516 1180 578 2517 587 581 2518 588 580 2519 589 580 2520 589 579 2521 590 578 2522 587 579 2523 590 580 2524 589 583 2525 591 583 2526 591 582 2527 592 579 2528 590 582 2529 592 583 2530 591 585 2531 593 585 2532 593 584 2533 594 582 2534 592 584 2535 594 585 2536 593 587 2537 595 587 2538 595 586 2539 596 584 2540 594 586 2541 596 587 2542 595 589 2543 597 589 2544 597 588 2545 598 586 2546 596 588 2547 598 589 2548 597 591 2549 599 591 2550 599 590 2551 600 588 2552 598 590 2553 600 591 2554 599 593 2555 601 593 2556 601 592 2557 602 590 2558 600 592 2559 1222 593 2560 1221 595 2561 603 595 2562 603 594 2563 604 592 2564 1222 594 2565 604 595 2566 603 581 2567 588 581 2568 588 578 2569 587 594 2570 604 598 2571 607 597 2572 608 596 2573 605 596 2574 605 599 2575 606 598 2576 607 602 2577 611 601 2578 612 600 2579 609 600 2580 609 603 2581 610 602 2582 611 596 2583 605 597 2584 608 604 2585 613 604 2586 613 605 2587 614 596 2588 605 605 2589 614 604 2590 613 606 2591 615 606 2592 615 607 2593 616 605 2594 614 606 2595 615 608 2596 617 607 2597 616 603 2598 610 600 2599 609 609 2600 618 609 2601 618 610 2602 619 603 2603 610 610 2604 619 609 2605 618 611 2606 620 611 2607 620 612 2608 621 610 2609 619 611 2610 620 613 2611 622 612 2612 621 616 2613 625 615 2614 626 614 2615 623 614 2616 623 617 2617 624 616 2618 625 620 2619 629 619 2620 630 618 2621 627 618 2622 627 621 2623 628 620 2624 629 622 2625 632 615 2626 626 616 2627 625 616 2628 625 623 2629 631 622 2630 632 624 2631 634 622 2632 632 623 2633 631 623 2634 631 625 2635 633 624 2636 634 625 2637 633 626 2638 635 624 2639 634 627 2640 637 620 2641 629 621 2642 628 621 2643 628 628 2644 636 627 2645 637 629 2646 639 627 2647 637 628 2648 636 628 2649 636 630 2650 638 629 2651 639 630 2652 638 631 2653 640 629 2654 639 616 2655 1201 617 2656 1200 599 2657 1182 599 2658 1182 596 2659 1181 616 2660 1201 614 2661 1199 615 2662 1202 597 2663 1184 597 2664 1184 598 2665 1183 614 2666 1199 621 2667 1204 618 2668 1203 602 2669 1187 602 2670 1187 603 2671 1186 621 2672 1204 619 2673 1206 620 2674 1205 600 2675 1185 600 2676 1185 601 2677 1188 619 2678 1206 623 2679 1207 616 2680 1201 596 2681 1181 596 2682 1181 605 2683 1190 623 2684 1207 615 2685 1202 622 2686 1208 604 2687 1189 604 2688 1189 597 2689 1184 615 2690 1202 625 2691 1209 623 2692 1207 605 2693 1190 605 2694 1190 607 2695 1192 625 2696 1209 622 2697 1208 624 2698 1210 606 2699 1191 606 2700 1191 604 2701 1189 622 2702 1208 624 2703 1210 626 2704 1211 608 2705 1193 608 2706 1193 606 2707 1191 624 2708 1210 626 2709 1211 625 2710 1209 607 2711 1192 607 2712 1192 608 2713 1193 626 2714 1211 628 2715 1212 621 2716 1204 603 2717 1186 603 2718 1186 610 2719 1195 628 2720 1212 620 2721 1205 627 2722 1213 609 2723 1194 609 2724 1194 600 2725 1185 620 2726 1205 630 2727 1214 628 2728 1212 610 2729 1195 610 2730 1195 612 2731 1197 630 2732 1214 627 2733 1213 629 2734 1215 611 2735 1196 611 2736 1196 609 2737 1194 627 2738 1213 629 2739 1215 631 2740 1216 613 2741 1198 613 2742 1198 611 2743 1196 629 2744 1215 631 2745 1216 630 2746 1214 612 2747 1197 612 2748 1197 613 2749 1198 631 2750 1216 632 2751 641 635 2752 642 634 2753 643 634 2754 643 633 2755 644 632 2756 641 635 2757 642 637 2758 645 636 2759 646 636 2760 646 634 2761 643 635 2762 642 637 2763 645 639 2764 647 638 2765 648 638 2766 648 636 2767 646 637 2768 645 639 2769 647 641 2770 649 640 2771 650 640 2772 650 638 2773 648 639 2774 647 641 2775 649 643 2776 651 642 2777 652 642 2778 652 640 2779 650 641 2780 649 643 2781 651 645 2782 653 644 2783 654 644 2784 654 642 2785 652 643 2786 651 645 2787 1223 647 2788 655 646 2789 656 646 2790 656 644 2791 1224 645 2792 1223 647 2793 655 649 2794 657 648 2795 658 648 2796 658 646 2797 656 647 2798 655 649 2799 657 632 2800 641 633 2801 644 633 2802 644 648 2803 658 649 2804 657 659 2805 659 658 2806 660 650 2807 661 650 2808 661 651 2809 662 659 2810 659 660 2811 663 659 2812 659 651 2813 662 651 2814 662 652 2815 664 660 2816 663 661 2817 665 660 2818 663 652 2819 664 652 2820 664 653 2821 666 661 2822 665 662 2823 667 661 2824 665 653 2825 666 653 2826 666 654 2827 668 662 2828 667 663 2829 669 662 2830 667 654 2831 668 654 2832 668 655 2833 670 663 2834 669 664 2835 671 663 2836 669 655 2837 670 655 2838 670 656 2839 672 664 2840 671 665 2841 673 664 2842 671 656 2843 672 656 2844 672 657 2845 674 665 2846 673 665 2847 673 657 2848 674 650 2849 1062 650 2850 1062 658 2851 1061 665 2852 673 666 2853 675 667 2854 676 675 2855 677 675 2856 677 674 2857 678 666 2858 675 667 2859 676 668 2860 679 676 2861 680 676 2862 680 675 2863 677 667 2864 676 668 2865 1063 669 2866 681 677 2867 682 677 2868 682 676 2869 1064 668 2870 1063 669 2871 681 670 2872 683 678 2873 684 678 2874 684 677 2875 682 669 2876 681 670 2877 683 671 2878 685 679 2879 686 679 2880 686 678 2881 684 670 2882 683 671 2883 685 672 2884 687 680 2885 688 680 2886 688 679 2887 686 671 2888 685 672 2889 687 673 2890 689 681 2891 690 681 2892 690 680 2893 688 672 2894 687 673 2895 689 666 2896 675 674 2897 678 674 2898 678 681 2899 690 673 2900 689 682 2901 691 683 2902 692 691 2903 693 691 2904 693 690 2905 694 682 2906 691 683 2907 692 684 2908 695 692 2909 696 692 2910 696 691 2911 693 683 2912 692 684 2913 1065 685 2914 697 693 2915 698 693 2916 698 692 2917 1066 684 2918 1065 685 2919 697 686 2920 699 694 2921 700 694 2922 700 693 2923 698 685 2924 697 686 2925 699 687 2926 701 695 2927 702 695 2928 702 694 2929 700 686 2930 699 687 2931 701 688 2932 703 696 2933 704 696 2934 704 695 2935 702 687 2936 701 688 2937 703 689 2938 705 697 2939 706 697 2940 706 696 2941 704 688 2942 703 689 2943 705 682 2944 691 690 2945 694 690 2946 694 697 2947 706 689 2948 705 698 2949 707 701 2950 708 700 2951 709 700 2952 709 699 2953 710 698 2954 707 702 2955 711 703 2956 712 701 2957 708 701 2958 708 698 2959 707 702 2960 711 704 2961 713 705 2962 714 703 2963 712 703 2964 712 702 2965 711 704 2966 713 706 2967 715 707 2968 716 705 2969 714 705 2970 714 704 2971 713 706 2972 715 708 2973 717 709 2974 718 707 2975 716 707 2976 716 706 2977 715 708 2978 717 710 2979 719 711 2980 720 709 2981 718 709 2982 718 708 2983 717 710 2984 719 712 2985 721 713 2986 722 711 2987 720 711 2988 720 710 2989 719 712 2990 721 712 2991 721 699 2992 1068 700 2993 1067 700 2994 1067 713 2995 722 712 2996 721 714 2997 723 717 2998 724 716 2999 725 716 3000 725 715 3001 726 714 3002 723 715 3003 726 716 3004 725 719 3005 727 719 3006 727 718 3007 728 715 3008 726 718 3009 1070 719 3010 1069 721 3011 729 721 3012 729 720 3013 730 718 3014 1070 720 3015 730 721 3016 729 723 3017 731 723 3018 731 722 3019 732 720 3020 730 722 3021 732 723 3022 731 725 3023 733 725 3024 733 724 3025 734 722 3026 732 724 3027 734 725 3028 733 727 3029 735 727 3030 735 726 3031 736 724 3032 734 726 3033 736 727 3034 735 729 3035 737 729 3036 737 728 3037 738 726 3038 736 728 3039 738 729 3040 737 717 3041 724 717 3042 724 714 3043 723 728 3044 738 730 3045 739 733 3046 740 732 3047 741 732 3048 741 731 3049 742 730 3050 739 731 3051 742 732 3052 741 735 3053 743 735 3054 743 734 3055 744 731 3056 742 734 3057 1072 735 3058 1071 737 3059 745 737 3060 745 736 3061 746 734 3062 1072 736 3063 746 737 3064 745 739 3065 747 739 3066 747 738 3067 748 736 3068 746 738 3069 748 739 3070 747 741 3071 749 741 3072 749 740 3073 750 738 3074 748 740 3075 750 741 3076 749 743 3077 751 743 3078 751 742 3079 752 740 3080 750 742 3081 752 743 3082 751 745 3083 753 745 3084 753 744 3085 754 742 3086 752 744 3087 754 745 3088 753 733 3089 740 733 3090 740 730 3091 739 744 3092 754

+
+
+
+ + + + + + + + + 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.0000001.000000 + 30.0000000.0000003.333333 + + + + + +
diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_TrashCanC_01/model.config b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_TrashCanC_01/model.config new file mode 100755 index 0000000..28251bb --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_TrashCanC_01/model.config @@ -0,0 +1,11 @@ + + + aws_robomaker_warehouse_TrashCanC_01 + 1.0 + model.sdf + + + + + + diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_TrashCanC_01/model.sdf b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_TrashCanC_01/model.sdf new file mode 100755 index 0000000..483c066 --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_TrashCanC_01/model.sdf @@ -0,0 +1,46 @@ + + + + + + 1 + + 0.200 + 0 + 0 + 0.308 + 0 + 0.240 + + + + + + model://aws_robomaker_warehouse_TrashCanC_01/meshes/aws_robomaker_warehouse_TrashCanC_01_collision.DAE + 1 1 1 + + + + + + 0.4 + 0.4 + 0 0 0 + 0 + 0 + + + + + + + + model://aws_robomaker_warehouse_TrashCanC_01/meshes/aws_robomaker_warehouse_TrashCanC_01_visual.DAE + + + 1 + + +1 + + diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_WallB_01/materials/textures/aws_robomaker_warehouse_WallB_01.png b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_WallB_01/materials/textures/aws_robomaker_warehouse_WallB_01.png new file mode 100755 index 0000000..f635537 Binary files /dev/null and b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_WallB_01/materials/textures/aws_robomaker_warehouse_WallB_01.png differ diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_WallB_01/meshes/aws_robomaker_warehouse_WallB_01_collision.DAE b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_WallB_01/meshes/aws_robomaker_warehouse_WallB_01_collision.DAE new file mode 100755 index 0000000..eb18cdd --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_WallB_01/meshes/aws_robomaker_warehouse_WallB_01_collision.DAE @@ -0,0 +1,343 @@ + + + FBX COLLADA exporter2019-05-15T08:14:39Z2019-05-15T08:14:39ZZ_UP + + + + + +699.023682 1032.083740 0.000000 +699.023682 1045.333252 0.000000 +-699.023315 1032.083618 0.000000 +-699.023315 1045.333130 0.000000 +699.023682 1032.083740 901.986084 +699.023682 1045.333252 901.986084 +-699.023315 1032.083618 901.986084 +-699.023315 1045.333130 901.986084 +685.143066 1032.083740 0.000000 +685.143066 1045.333252 0.000000 +685.143066 1045.333252 901.986084 +685.143066 1032.083740 901.986084 +699.023682 -1045.333130 0.000000 +699.023682 -1045.333130 901.986084 +685.143066 -1045.333130 0.000000 +685.143066 -1045.333130 901.986084 +685.143066 -1032.083618 901.986084 +699.023682 -1032.083618 901.986084 +699.023682 -1032.083618 0.000000 +685.143066 -1032.083618 0.000000 +-699.023315 -1045.333130 0.000000 +-699.023315 -1045.333130 901.986084 +-699.023315 -1032.083618 901.986084 +-699.023315 -1032.083618 0.000000 +-686.135132 -1032.083618 901.986084 +-686.135132 -1045.333130 901.986084 +-686.135132 -1045.333130 0.000000 +-686.135132 -1032.083618 0.000000 +-686.135132 1032.083618 901.986084 +-686.135193 1045.333130 901.986084 +-686.135132 1045.333130 0.000000 +-686.135193 1032.083618 0.000000 + + + + + + + + + + + +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +-0.000000 1.000000 -0.000000 +-0.000000 1.000000 -0.000000 +-0.000000 1.000000 -0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.000000 1.000000 -0.000000 +-0.000000 1.000000 -0.000000 +-0.000000 1.000000 -0.000000 +-0.000000 1.000000 -0.000000 +-0.000000 1.000000 -0.000000 +-0.000000 1.000000 -0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -1.000000 -0.000000 +0.000000 -1.000000 -0.000000 +0.000000 -1.000000 -0.000000 +0.000000 -1.000000 -0.000000 +0.000000 -1.000000 -0.000000 +0.000000 -1.000000 -0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.000000 1.000000 -0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.000000 1.000000 -0.000000 +-0.000000 1.000000 -0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 + + + + + + + + + + + +1.000000 0.000000 +0.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +1.000000 0.009929 +0.990071 0.000000 +0.000000 0.009929 +0.009929 0.000000 +1.000000 0.009929 +0.009929 1.000000 +0.000000 0.009929 +0.990071 1.000000 +1.000000 0.000000 +1.000000 0.009929 +0.000000 1.000000 +0.000000 0.000000 +0.000000 0.009929 +0.000000 0.000000 +0.990071 0.000000 +0.000000 0.009929 +0.990071 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 0.000000 +0.990071 0.000000 +1.000000 0.009929 +0.000000 0.009929 +0.990071 0.000000 +0.000000 0.009929 +1.000000 0.009929 +1.000000 0.009929 +0.990071 0.000000 +0.000000 0.009929 +0.990071 1.000000 +0.000000 0.009929 +1.000000 0.009929 +0.990071 0.000000 +0.990071 0.000000 +1.000000 0.009929 +0.000000 0.989764 +0.010236 1.000000 +1.000000 0.989764 +0.989764 1.000000 +0.000000 0.989764 +0.989764 0.000000 +1.000000 0.989764 +0.010236 0.000000 + + + + + + + + + + + +

0 0 0 8 1 20 1 2 1 8 3 20 9 4 22 1 5 1 10 6 24 11 7 26 5 8 5 5 9 5 11 10 26 4 11 4 4 12 10 0 13 8 5 14 11 5 15 11 0 16 8 1 17 9 5 18 14 9 19 23 10 20 25 9 21 23 5 22 14 1 23 12 7 24 18 3 25 16 6 26 19 6 27 19 3 28 16 2 29 17 30 30 60 8 31 20 31 32 62 8 33 20 30 34 60 9 35 22 28 36 56 10 37 24 29 38 58 10 39 24 28 40 56 11 41 26 10 42 25 30 43 61 29 44 59 30 45 61 10 46 25 9 47 23 19 48 42 0 49 0 18 50 39 0 51 0 19 52 42 8 53 20 4 54 10 17 55 37 18 56 40 4 57 10 18 58 40 0 59 8 17 60 38 4 61 4 11 62 26 11 63 26 16 64 35 17 65 38 16 66 36 11 67 27 8 68 21 16 69 36 8 70 21 19 71 41 15 72 32 14 73 34 13 74 30 13 75 30 14 76 34 12 77 28 14 78 29 19 79 42 12 80 28 12 81 28 19 82 42 18 83 39 18 84 40 17 85 37 13 86 30 13 87 30 12 88 31 18 89 40 17 90 38 16 91 35 15 92 32 17 93 38 15 94 32 13 95 33 26 96 53 15 97 32 25 98 51 15 99 32 26 100 53 14 101 34 25 102 51 16 103 35 24 104 49 16 105 35 25 106 51 15 107 32 14 108 29 26 109 52 27 110 55 14 111 29 27 112 55 19 113 42 24 114 50 16 115 36 19 116 41 24 117 50 19 118 41 27 119 54 20 120 46 21 121 43 22 122 45 22 123 45 23 124 48 20 125 46 26 126 53 25 127 51 21 128 43 21 129 43 20 130 44 26 131 53 24 132 49 22 133 45 25 134 51 22 135 45 21 136 43 25 137 51 26 138 52 20 139 46 27 140 55 20 141 46 23 142 47 27 143 55 28 144 57 8 145 21 11 146 27 8 147 21 28 148 57 31 149 63 31 150 62 3 151 3 30 152 60 3 153 3 31 154 62 2 155 2 29 156 58 6 157 6 28 158 56 6 159 6 29 160 58 7 161 7 29 162 59 3 163 13 7 164 15 3 165 13 29 166 59 30 167 61 6 168 6 22 169 45 28 170 56 28 171 56 22 172 45 24 173 49 2 174 17 23 175 48 6 176 19 22 177 45 6 178 19 23 179 48 23 180 47 31 181 62 27 182 55 31 183 62 23 184 47 2 185 2 24 186 50 31 187 63 28 188 57 31 189 63 24 190 50 27 191 54

+
+
+
+ + + 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.0000001.000000 + 30.0000000.0000003.333333 + + + + + +
diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_WallB_01/meshes/aws_robomaker_warehouse_WallB_01_visual.DAE b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_WallB_01/meshes/aws_robomaker_warehouse_WallB_01_visual.DAE new file mode 100755 index 0000000..9356888 --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_WallB_01/meshes/aws_robomaker_warehouse_WallB_01_visual.DAE @@ -0,0 +1,289 @@ + + + FBX COLLADA exporter2019-05-24T10:55:29Z2019-05-24T10:55:29ZZ_UP + + + ../materials/textures/aws_robomaker_warehouse_WallB_01.png + + + + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + +699.023682 1045.333252 0.000000 +-699.023315 1045.333130 0.000000 +699.023682 1045.333252 901.986084 +-699.023315 1045.333130 901.986084 +685.143066 1032.083740 0.000000 +685.143066 1045.333252 901.986084 +685.143066 1032.083740 901.986084 +699.023682 -1045.333130 0.000000 +699.023682 -1045.333130 901.986084 +685.143066 -1032.083618 901.986084 +699.023682 -1032.083618 901.986084 +685.143066 -1032.083618 0.000000 +-699.023315 -1045.333130 0.000000 +-699.023315 -1045.333130 901.986084 +-686.135132 -1032.083618 901.986084 +-686.135132 -1045.333130 901.986084 +-686.135132 -1032.083618 0.000000 +-686.135132 1032.083618 901.986084 +-686.135193 1032.083618 0.000000 + + + + + + + + + + + +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 -0.000000 +0.000000 -1.000000 -0.000000 +0.000000 -1.000000 -0.000000 +-0.000000 1.000000 -0.000000 +-0.000000 1.000000 -0.000000 +-0.000000 1.000000 -0.000000 +-0.000000 1.000000 -0.000000 +-0.000000 1.000000 -0.000000 +-0.000000 1.000000 -0.000000 +-0.000000 1.000000 -0.000000 +-0.000000 1.000000 -0.000000 +-0.000000 1.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 + + + + + + + + + + + +1.423979 0.041268 +1.432463 0.041268 +1.432463 0.050156 +1.423979 0.050156 +0.657583 2.277837 +0.657583 2.286321 +0.080013 2.286321 +0.080013 2.277837 +0.133948 0.068165 +0.142837 0.068165 +0.142837 0.645734 +0.133948 0.645734 +1.439517 0.041268 +1.448001 0.041268 +1.448001 0.618837 +1.439517 0.618837 +0.080013 2.898408 +1.020908 0.068165 +1.432463 0.928227 +1.020908 0.645734 +1.423979 0.928227 +0.080013 2.320839 +0.080014 0.956087 +0.657583 0.956087 +0.102230 0.050156 +0.102230 0.041268 +1.538820 1.910483 +0.093746 0.050156 +1.401763 2.320839 +0.080014 0.947603 +0.093746 0.041268 +0.657583 0.947603 +1.401763 2.898408 +0.102230 0.928227 +0.961250 1.910483 +0.093746 0.928227 +2.778234 0.618837 +0.102230 0.936480 +2.154409 1.980973 +0.093746 0.936480 +0.961250 1.901595 +1.576840 1.980973 +1.432463 0.936480 +1.576841 0.659224 +1.423979 0.936480 +1.029160 0.068165 +1.029160 0.645734 +2.154409 0.659224 +1.538820 1.901595 +0.961250 1.023523 +1.538820 1.023523 +0.961250 1.015271 +1.538820 1.015271 +2.769750 0.618837 +2.769750 0.041268 +2.778234 0.041268 +2.181874 2.869334 +1.604305 2.869334 +1.604305 1.991262 +2.181875 1.991262 +2.167332 1.537295 +2.167332 0.659224 +2.744901 0.659224 +2.744901 1.537295 + + + + + + + + + + + +

6 0 3 2 1 1 5 2 2 5 3 2 17 4 20 6 5 3 2 6 1 6 7 3 10 8 25 10 9 22 0 10 5 2 11 6 7 12 31 10 13 22 8 14 29 10 15 22 7 16 31 0 17 5 13 18 36 3 19 15 1 20 12 13 21 36 1 22 12 12 23 55 17 24 20 5 25 2 3 26 42 10 27 25 9 28 24 8 29 30 10 30 25 6 31 3 9 32 24 9 33 32 6 34 16 4 35 21 9 36 32 4 37 21 11 38 28 15 39 49 7 40 26 8 41 34 12 42 52 15 43 49 13 44 51 15 45 49 12 46 52 7 47 26 9 48 24 14 49 33 15 50 35 15 51 35 14 52 33 13 53 39 14 54 59 9 55 56 11 56 57 14 57 59 11 58 57 16 59 58 17 60 63 4 61 61 6 62 62 4 63 61 17 64 63 18 65 60 5 66 10 1 67 45 3 68 46 0 69 8 5 70 10 2 71 11 5 72 10 0 73 8 1 74 45 14 75 43 18 76 38 17 77 41 18 78 38 14 79 43 16 80 47 9 81 24 15 82 35 8 83 30 3 84 42 13 85 39 17 86 20 17 87 20 13 88 39 14 89 33

+
+
+
+ + + + + + + + + 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.0000001.000000 + 30.0000000.0000003.333333 + + + + + +
diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_WallB_01/model.config b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_WallB_01/model.config new file mode 100755 index 0000000..ba404b6 --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_WallB_01/model.config @@ -0,0 +1,11 @@ + + + aws_robomaker_warehouse_WallB_01 + 1.0 + model.sdf + + + + + + diff --git a/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_WallB_01/model.sdf b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_WallB_01/model.sdf new file mode 100755 index 0000000..66af32f --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/models/aws_robomaker_warehouse_WallB_01/model.sdf @@ -0,0 +1,46 @@ + + + + + + 1000 + + 840083.33 + 0 + 0 + 475500.0 + 0 + 1302083.33 + + + + + + model://aws_robomaker_warehouse_WallB_01/meshes/aws_robomaker_warehouse_WallB_01_collision.DAE + 1 1 1 + + + + + + 0.5 + 0.5 + 0 0 0 + 0 + 0 + + + + + + + + model://aws_robomaker_warehouse_WallB_01/meshes/aws_robomaker_warehouse_WallB_01_visual.DAE + + + 2 + + +1 + + diff --git a/simulators/aws-robomaker-small-warehouse-world_h/package.xml b/simulators/aws-robomaker-small-warehouse-world_h/package.xml new file mode 100755 index 0000000..d0cd987 --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/package.xml @@ -0,0 +1,18 @@ + + + aws_robomaker_small_warehouse_world + 1.0.0 + + AWS RoboMaker package for a warehouse world to use in manufacturing and logistics robot applications. + + Apache 2.0 + AWS RoboMaker + AWS RoboMaker + catkin + gazebo_ros + gazebo + gazebo_plugins + + + + \ No newline at end of file diff --git a/simulators/aws-robomaker-small-warehouse-world_h/rviz/basic_data.rviz b/simulators/aws-robomaker-small-warehouse-world_h/rviz/basic_data.rviz new file mode 100755 index 0000000..63a035d --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/rviz/basic_data.rviz @@ -0,0 +1,314 @@ +Panels: + - Class: rviz/Displays + Help Height: 78 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /Odometry1/Shape1 + Splitter Ratio: 0.5 + Tree Height: 747 + - Class: rviz/Selection + Name: Selection + - Class: rviz/Tool Properties + Expanded: + - /2D Pose Estimate1 + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.588679016 + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: LaserScan + - Class: rviz/Tool Properties + Expanded: + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5 + - Class: rviz/Tool Properties + Expanded: ~ + Name: Tool Properties + Splitter Ratio: 0.5 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.0299999993 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Alpha: 0.699999988 + Class: rviz/Map + Color Scheme: map + Draw Behind: false + Enabled: true + Name: Map + Topic: /map + Unreliable: false + Use Timestamp: false + Value: true + - Angle Tolerance: 0.100000001 + Class: rviz/Odometry + Covariance: + Orientation: + Alpha: 0.5 + Color: 255; 255; 127 + Color Style: Unique + Frame: Local + Offset: 1 + Scale: 1 + Value: true + Position: + Alpha: 0.300000012 + Color: 204; 51; 204 + Scale: 1 + Value: true + Value: true + Enabled: false + Keep: 3 + Name: Odometry + Position Tolerance: 0.100000001 + Shape: + Alpha: 1 + Axes Length: 1 + Axes Radius: 0.100000001 + Color: 85; 0; 255 + Head Length: 0.300000012 + Head Radius: 0.100000001 + Shaft Length: 1 + Shaft Radius: 0.100000001 + Value: Arrow + Topic: /boxer_velocity_controller/odom + Unreliable: false + Value: false + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/LaserScan + Color: 255; 0; 0 + Color Transformer: FlatColor + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 6640 + Min Color: 0; 0; 0 + Min Intensity: 104 + Name: LaserScan + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.100000001 + Style: Flat Squares + Topic: /front/scan + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true + - Alpha: 1 + Axes Length: 1 + Axes Radius: 0.100000001 + Class: rviz/PoseWithCovariance + Color: 255; 25; 0 + Covariance: + Orientation: + Alpha: 0.5 + Color: 255; 255; 127 + Color Style: Unique + Frame: Local + Offset: 1 + Scale: 1 + Value: true + Position: + Alpha: 0.300000012 + Color: 204; 51; 204 + Scale: 1 + Value: true + Value: true + Enabled: true + Head Length: 0.100000001 + Head Radius: 0.0500000007 + Name: PoseWithCovariance + Shaft Length: 0.5 + Shaft Radius: 0.0500000007 + Shape: Arrow + Topic: /amcl_pose + Unreliable: false + Value: true + - Alpha: 1 + Buffer Length: 1 + Class: rviz/Path + Color: 25; 255; 0 + Enabled: true + Head Diameter: 0.300000012 + Head Length: 0.200000003 + Length: 0.300000012 + Line Style: Lines + Line Width: 0.0299999993 + Name: Path + Offset: + X: 0 + Y: 0 + Z: 0 + Pose Color: 255; 85; 255 + Pose Style: None + Radius: 0.0299999993 + Shaft Diameter: 0.100000001 + Shaft Length: 0.100000001 + Topic: /move_base/TrajectoryPlannerROS/global_plan + Unreliable: false + Value: true + - Alpha: 0.699999988 + Class: rviz/Map + Color Scheme: costmap + Draw Behind: false + Enabled: true + Name: Map + Topic: /move_base/local_costmap/costmap + Unreliable: false + Use Timestamp: false + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/PointCloud + Color: 255; 255; 255 + Color Transformer: Intensity + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 4096 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: PointCloud + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.100000001 + Style: Flat Squares + Topic: /obstacle_pc + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/LaserScan + Color: 85; 0; 255 + Color Transformer: FlatColor + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 999999 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: LaserScan + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.100000001 + Style: Flat Squares + Topic: /scan + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Default Light: true + Fixed Frame: map + Frame Rate: 30 + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + - Class: rviz/FocusCamera + - Class: rviz/Measure + - Class: rviz/SetInitialPose + Topic: /initialpose + - Class: rviz/SetGoal + Topic: /move_base_simple/goal + - Class: rviz/PublishPoint + Single click: true + Topic: /clicked_point + Value: true + Views: + Current: + Angle: 0 + Class: rviz/TopDownOrtho + Enable Stereo Rendering: + Stereo Eye Separation: 0.0599999987 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.00999999978 + Scale: 19.5390034 + Target Frame: + Value: TopDownOrtho (rviz) + X: 0 + Y: 0 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 1028 + Hide Left Dock: false + Hide Right Dock: false + QMainWindow State: 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 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 928 + X: 992 + Y: 24 diff --git a/simulators/aws-robomaker-small-warehouse-world_h/worlds/no_roof_small_warehouse.world b/simulators/aws-robomaker-small-warehouse-world_h/worlds/no_roof_small_warehouse.world new file mode 100755 index 0000000..91fece4 --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/worlds/no_roof_small_warehouse.world @@ -0,0 +1,244 @@ + + + + + 0 0 -9.8 + + 0.001 + 1 + 1000 + + + + + + + + model://aws_robomaker_warehouse_ShelfF_01 + + -5.795143 -0.956635 0 0 0 0 + + + + + model://aws_robomaker_warehouse_WallB_01 + + 0.0 0.0 0 0 0 0 + + + + + model://aws_robomaker_warehouse_ShelfE_01 + + 4.73156 0.57943 0 0 0 0 + + + + + model://aws_robomaker_warehouse_ShelfE_01 + + 4.73156 -4.827049 0 0 0 0 + + + + + model://aws_robomaker_warehouse_ShelfE_01 + + 4.73156 -8.6651 0 0 0 0 + + + + + model://aws_robomaker_warehouse_ShelfD_01 + + 4.73156 -1.242668 0 0 0 0 + + + + + model://aws_robomaker_warehouse_ShelfD_01 + + 4.73156 -3.038551 0 0 0 0 + + + + + model://aws_robomaker_warehouse_ShelfD_01 + + 4.73156 -6.750542 0 0 0 0 + + + + + + + model://aws_robomaker_warehouse_GroundB_01 + + 0.0 0.0 -0.090092 0 0 0 + + + + + model://aws_robomaker_warehouse_Lamp_01 + + 0 0 -4 0 0 0 + + + + + + + model://aws_robomaker_warehouse_Bucket_01 + + 0.433449 9.631706 0 0 0 -1.563161 + + + + + model://aws_robomaker_warehouse_Bucket_01 + + -1.8321 -6.3752 0 0 0 -1.563161 + + + + + model://aws_robomaker_warehouse_Bucket_01 + + 0.433449 8.59 0 0 0 -1.563161 + + + + + model://aws_robomaker_warehouse_ClutteringA_01 + + 5.708138 8.616844 -0.017477 0 0 0 + + + + + model://aws_robomaker_warehouse_ClutteringA_01 + + 3.408638 8.616844 -0.017477 0 0 0 + + + + + model://aws_robomaker_warehouse_ClutteringA_01 + + -1.491287 5.222435 -0.017477 0 0 -1.583185 + + + + + + model://aws_robomaker_warehouse_ClutteringC_01 + + 3.324959 3.822449 -0.012064 0 0 1.563871 + + + + + model://aws_robomaker_warehouse_ClutteringC_01 + + 5.54171 3.816475 -0.015663 0 0 -1.583191 + + + + + model://aws_robomaker_warehouse_ClutteringC_01 + + 5.384239 6.137154 0 0 0 3.150000 + + + + + model://aws_robomaker_warehouse_ClutteringC_01 + + 3.236 6.137154 0 0 0 3.150000 + + + + + model://aws_robomaker_warehouse_ClutteringC_01 + + -1.573677 2.301994 -0.015663 0 0 -3.133191 + + + + + model://aws_robomaker_warehouse_ClutteringC_01 + + -1.2196 9.407 -0.015663 0 0 1.563871 + + + + + model://aws_robomaker_warehouse_ClutteringD_01 + + -1.634682 -7.811813 -0.319559 0 0 0 + + + + + model://aws_robomaker_warehouse_TrashCanC_01 + + -1.592441 7.715420 0 0 0 0 + + + + + + model://aws_robomaker_warehouse_PalletJackB_01 + + -0.276098 -9.481944 0.023266 0 0 0 + + + + + 0 0 9 0 0 0 + 0.5 0.5 0.5 1 + 0.2 0.2 0.2 1 + + 80 + 0.3 + 0.01 + 0.001 + + 1 + 0.1 0.1 -1 + + + + + -4.70385 10.895 16.2659 -0 0.921795 -1.12701 + orbit + perspective + + + + + diff --git a/simulators/aws-robomaker-small-warehouse-world_h/worlds/small_warehouse.world b/simulators/aws-robomaker-small-warehouse-world_h/worlds/small_warehouse.world new file mode 100755 index 0000000..cb845fd --- /dev/null +++ b/simulators/aws-robomaker-small-warehouse-world_h/worlds/small_warehouse.world @@ -0,0 +1,237 @@ + + + + + 0 0 -9.8 + + 0.001 + 1 + 1000 + + + + + + model://aws_robomaker_warehouse_RoofB_01 + + 0.0 0.0 0 0 0 0 + + + + + model://aws_robomaker_warehouse_ShelfF_01 + + -5.795143 -0.956635 0 0 0 0 + + + + + model://aws_robomaker_warehouse_WallB_01 + + 0.0 0.0 0 0 0 0 + + + + + model://aws_robomaker_warehouse_ShelfE_01 + + 4.73156 0.57943 0 0 0 0 + + + + + model://aws_robomaker_warehouse_ShelfE_01 + + 4.73156 -4.827049 0 0 0 0 + + + + + model://aws_robomaker_warehouse_ShelfE_01 + + 4.73156 -8.6651 0 0 0 0 + + + + + model://aws_robomaker_warehouse_ShelfD_01 + + 4.73156 -1.242668 0 0 0 0 + + + + + model://aws_robomaker_warehouse_ShelfD_01 + + 4.73156 -3.038551 0 0 0 0 + + + + + model://aws_robomaker_warehouse_ShelfD_01 + + 4.73156 -6.750542 0 0 0 0 + + + + + + + model://aws_robomaker_warehouse_GroundB_01 + + 0.0 0.0 -0.090092 0 0 0 + + + + + model://aws_robomaker_warehouse_Lamp_01 + + 0 0 -4 0 0 0 + + + + + + + model://aws_robomaker_warehouse_Bucket_01 + + 0.433449 9.631706 0 0 0 -1.563161 + + + + + model://aws_robomaker_warehouse_Bucket_01 + + -1.8321 -6.3752 0 0 0 -1.563161 + + + + + model://aws_robomaker_warehouse_Bucket_01 + + 0.433449 8.59 0 0 0 -1.563161 + + + + + model://aws_robomaker_warehouse_ClutteringA_01 + + 5.708138 8.616844 -0.017477 0 0 0 + + + + + model://aws_robomaker_warehouse_ClutteringA_01 + + 3.408638 8.616844 -0.017477 0 0 0 + + + + + model://aws_robomaker_warehouse_ClutteringA_01 + + -1.491287 5.222435 -0.017477 0 0 -1.583185 + + + + + + model://aws_robomaker_warehouse_ClutteringC_01 + + 3.324959 3.822449 -0.012064 0 0 1.563871 + + + + + model://aws_robomaker_warehouse_ClutteringC_01 + + 5.54171 3.816475 -0.015663 0 0 -1.583191 + + + + + model://aws_robomaker_warehouse_ClutteringC_01 + + 5.384239 6.137154 0 0 0 3.150000 + + + + + model://aws_robomaker_warehouse_ClutteringC_01 + + 3.236 6.137154 0 0 0 3.150000 + + + + + model://aws_robomaker_warehouse_ClutteringC_01 + + -1.573677 2.301994 -0.015663 0 0 -3.133191 + + + + + model://aws_robomaker_warehouse_ClutteringC_01 + + -1.2196 9.407 -0.015663 0 0 1.563871 + + + + + model://aws_robomaker_warehouse_ClutteringD_01 + + -1.634682 -7.811813 -0.319559 0 0 0 + + + + + model://aws_robomaker_warehouse_TrashCanC_01 + + -1.592441 7.715420 0 0 0 0 + + + + + + model://aws_robomaker_warehouse_PalletJackB_01 + + -0.276098 -9.481944 0.023266 0 0 0 + + + + + 0 0 9 0 0 0 + 0.5 0.5 0.5 1 + 0.2 0.2 0.2 1 + + 80 + 0.3 + 0.01 + 0.001 + + 1 + 0.1 0.1 -1 + + + + + diff --git a/simulators/dynamic_logistics_warehouse_h/CMakeLists.txt b/simulators/dynamic_logistics_warehouse_h/CMakeLists.txt new file mode 100755 index 0000000..80172be --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/CMakeLists.txt @@ -0,0 +1,13 @@ +cmake_minimum_required(VERSION 2.8.3) +project(dynamic_logistics_warehouse) + +find_package(catkin REQUIRED COMPONENTS + gazebo_ros +) + +catkin_package() + +install(DIRECTORY launch models worlds maps rviz + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) + diff --git a/simulators/dynamic_logistics_warehouse_h/LICENSE b/simulators/dynamic_logistics_warehouse_h/LICENSE new file mode 100755 index 0000000..d159169 --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/LICENSE @@ -0,0 +1,339 @@ + GNU GENERAL PUBLIC LICENSE + Version 2, June 1991 + + Copyright (C) 1989, 1991 Free Software Foundation, Inc., + 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA + Everyone is permitted to copy and distribute verbatim copies + of this license document, but changing it is not allowed. + + Preamble + + The licenses for most software are designed to take away your +freedom to share and change it. By contrast, the GNU General Public +License is intended to guarantee your freedom to share and change free +software--to make sure the software is free for all its users. This +General Public License applies to most of the Free Software +Foundation's software and to any other program whose authors commit to +using it. (Some other Free Software Foundation software is covered by +the GNU Lesser General Public License instead.) You can apply it to +your programs, too. + + When we speak of free software, we are referring to freedom, not +price. Our General Public Licenses are designed to make sure that you +have the freedom to distribute copies of free software (and charge for +this service if you wish), that you receive source code or can get it +if you want it, that you can change the software or use pieces of it +in new free programs; and that you know you can do these things. + + To protect your rights, we need to make restrictions that forbid +anyone to deny you these rights or to ask you to surrender the rights. +These restrictions translate to certain responsibilities for you if you +distribute copies of the software, or if you modify it. + + For example, if you distribute copies of such a program, whether +gratis or for a fee, you must give the recipients all the rights that +you have. You must make sure that they, too, receive or can get the +source code. And you must show them these terms so they know their +rights. + + We protect your rights with two steps: (1) copyright the software, and +(2) offer you this license which gives you legal permission to copy, +distribute and/or modify the software. + + Also, for each author's protection and ours, we want to make certain +that everyone understands that there is no warranty for this free +software. If the software is modified by someone else and passed on, we +want its recipients to know that what they have is not the original, so +that any problems introduced by others will not reflect on the original +authors' reputations. + + Finally, any free program is threatened constantly by software +patents. We wish to avoid the danger that redistributors of a free +program will individually obtain patent licenses, in effect making the +program proprietary. To prevent this, we have made it clear that any +patent must be licensed for everyone's free use or not licensed at all. + + The precise terms and conditions for copying, distribution and +modification follow. + + GNU GENERAL PUBLIC LICENSE + TERMS AND CONDITIONS FOR COPYING, DISTRIBUTION AND MODIFICATION + + 0. This License applies to any program or other work which contains +a notice placed by the copyright holder saying it may be distributed +under the terms of this General Public License. The "Program", below, +refers to any such program or work, and a "work based on the Program" +means either the Program or any derivative work under copyright law: +that is to say, a work containing the Program or a portion of it, +either verbatim or with modifications and/or translated into another +language. (Hereinafter, translation is included without limitation in +the term "modification".) Each licensee is addressed as "you". + +Activities other than copying, distribution and modification are not +covered by this License; they are outside its scope. The act of +running the Program is not restricted, and the output from the Program +is covered only if its contents constitute a work based on the +Program (independent of having been made by running the Program). +Whether that is true depends on what the Program does. + + 1. You may copy and distribute verbatim copies of the Program's +source code as you receive it, in any medium, provided that you +conspicuously and appropriately publish on each copy an appropriate +copyright notice and disclaimer of warranty; keep intact all the +notices that refer to this License and to the absence of any warranty; +and give any other recipients of the Program a copy of this License +along with the Program. + +You may charge a fee for the physical act of transferring a copy, and +you may at your option offer warranty protection in exchange for a fee. + + 2. You may modify your copy or copies of the Program or any portion +of it, thus forming a work based on the Program, and copy and +distribute such modifications or work under the terms of Section 1 +above, provided that you also meet all of these conditions: + + a) You must cause the modified files to carry prominent notices + stating that you changed the files and the date of any change. + + b) You must cause any work that you distribute or publish, that in + whole or in part contains or is derived from the Program or any + part thereof, to be licensed as a whole at no charge to all third + parties under the terms of this License. + + c) If the modified program normally reads commands interactively + when run, you must cause it, when started running for such + interactive use in the most ordinary way, to print or display an + announcement including an appropriate copyright notice and a + notice that there is no warranty (or else, saying that you provide + a warranty) and that users may redistribute the program under + these conditions, and telling the user how to view a copy of this + License. (Exception: if the Program itself is interactive but + does not normally print such an announcement, your work based on + the Program is not required to print an announcement.) + +These requirements apply to the modified work as a whole. If +identifiable sections of that work are not derived from the Program, +and can be reasonably considered independent and separate works in +themselves, then this License, and its terms, do not apply to those +sections when you distribute them as separate works. But when you +distribute the same sections as part of a whole which is a work based +on the Program, the distribution of the whole must be on the terms of +this License, whose permissions for other licensees extend to the +entire whole, and thus to each and every part regardless of who wrote it. + +Thus, it is not the intent of this section to claim rights or contest +your rights to work written entirely by you; rather, the intent is to +exercise the right to control the distribution of derivative or +collective works based on the Program. + +In addition, mere aggregation of another work not based on the Program +with the Program (or with a work based on the Program) on a volume of +a storage or distribution medium does not bring the other work under +the scope of this License. + + 3. You may copy and distribute the Program (or a work based on it, +under Section 2) in object code or executable form under the terms of +Sections 1 and 2 above provided that you also do one of the following: + + a) Accompany it with the complete corresponding machine-readable + source code, which must be distributed under the terms of Sections + 1 and 2 above on a medium customarily used for software interchange; or, + + b) Accompany it with a written offer, valid for at least three + years, to give any third party, for a charge no more than your + cost of physically performing source distribution, a complete + machine-readable copy of the corresponding source code, to be + distributed under the terms of Sections 1 and 2 above on a medium + customarily used for software interchange; or, + + c) Accompany it with the information you received as to the offer + to distribute corresponding source code. (This alternative is + allowed only for noncommercial distribution and only if you + received the program in object code or executable form with such + an offer, in accord with Subsection b above.) + +The source code for a work means the preferred form of the work for +making modifications to it. For an executable work, complete source +code means all the source code for all modules it contains, plus any +associated interface definition files, plus the scripts used to +control compilation and installation of the executable. However, as a +special exception, the source code distributed need not include +anything that is normally distributed (in either source or binary +form) with the major components (compiler, kernel, and so on) of the +operating system on which the executable runs, unless that component +itself accompanies the executable. + +If distribution of executable or object code is made by offering +access to copy from a designated place, then offering equivalent +access to copy the source code from the same place counts as +distribution of the source code, even though third parties are not +compelled to copy the source along with the object code. + + 4. You may not copy, modify, sublicense, or distribute the Program +except as expressly provided under this License. Any attempt +otherwise to copy, modify, sublicense or distribute the Program is +void, and will automatically terminate your rights under this License. +However, parties who have received copies, or rights, from you under +this License will not have their licenses terminated so long as such +parties remain in full compliance. + + 5. You are not required to accept this License, since you have not +signed it. However, nothing else grants you permission to modify or +distribute the Program or its derivative works. These actions are +prohibited by law if you do not accept this License. Therefore, by +modifying or distributing the Program (or any work based on the +Program), you indicate your acceptance of this License to do so, and +all its terms and conditions for copying, distributing or modifying +the Program or works based on it. + + 6. Each time you redistribute the Program (or any work based on the +Program), the recipient automatically receives a license from the +original licensor to copy, distribute or modify the Program subject to +these terms and conditions. You may not impose any further +restrictions on the recipients' exercise of the rights granted herein. +You are not responsible for enforcing compliance by third parties to +this License. + + 7. If, as a consequence of a court judgment or allegation of patent +infringement or for any other reason (not limited to patent issues), +conditions are imposed on you (whether by court order, agreement or +otherwise) that contradict the conditions of this License, they do not +excuse you from the conditions of this License. If you cannot +distribute so as to satisfy simultaneously your obligations under this +License and any other pertinent obligations, then as a consequence you +may not distribute the Program at all. For example, if a patent +license would not permit royalty-free redistribution of the Program by +all those who receive copies directly or indirectly through you, then +the only way you could satisfy both it and this License would be to +refrain entirely from distribution of the Program. + +If any portion of this section is held invalid or unenforceable under +any particular circumstance, the balance of the section is intended to +apply and the section as a whole is intended to apply in other +circumstances. + +It is not the purpose of this section to induce you to infringe any +patents or other property right claims or to contest validity of any +such claims; this section has the sole purpose of protecting the +integrity of the free software distribution system, which is +implemented by public license practices. Many people have made +generous contributions to the wide range of software distributed +through that system in reliance on consistent application of that +system; it is up to the author/donor to decide if he or she is willing +to distribute software through any other system and a licensee cannot +impose that choice. + +This section is intended to make thoroughly clear what is believed to +be a consequence of the rest of this License. + + 8. If the distribution and/or use of the Program is restricted in +certain countries either by patents or by copyrighted interfaces, the +original copyright holder who places the Program under this License +may add an explicit geographical distribution limitation excluding +those countries, so that distribution is permitted only in or among +countries not thus excluded. In such case, this License incorporates +the limitation as if written in the body of this License. + + 9. The Free Software Foundation may publish revised and/or new versions +of the General Public License from time to time. Such new versions will +be similar in spirit to the present version, but may differ in detail to +address new problems or concerns. + +Each version is given a distinguishing version number. If the Program +specifies a version number of this License which applies to it and "any +later version", you have the option of following the terms and conditions +either of that version or of any later version published by the Free +Software Foundation. If the Program does not specify a version number of +this License, you may choose any version ever published by the Free Software +Foundation. + + 10. If you wish to incorporate parts of the Program into other free +programs whose distribution conditions are different, write to the author +to ask for permission. For software which is copyrighted by the Free +Software Foundation, write to the Free Software Foundation; we sometimes +make exceptions for this. Our decision will be guided by the two goals +of preserving the free status of all derivatives of our free software and +of promoting the sharing and reuse of software generally. + + NO WARRANTY + + 11. BECAUSE THE PROGRAM IS LICENSED FREE OF CHARGE, THERE IS NO WARRANTY +FOR THE PROGRAM, TO THE EXTENT PERMITTED BY APPLICABLE LAW. EXCEPT WHEN +OTHERWISE STATED IN WRITING THE COPYRIGHT HOLDERS AND/OR OTHER PARTIES +PROVIDE THE PROGRAM "AS IS" WITHOUT WARRANTY OF ANY KIND, EITHER EXPRESSED +OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF +MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. THE ENTIRE RISK AS +TO THE QUALITY AND PERFORMANCE OF THE PROGRAM IS WITH YOU. SHOULD THE +PROGRAM PROVE DEFECTIVE, YOU ASSUME THE COST OF ALL NECESSARY SERVICING, +REPAIR OR CORRECTION. + + 12. IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN WRITING +WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MAY MODIFY AND/OR +REDISTRIBUTE THE PROGRAM AS PERMITTED ABOVE, BE LIABLE TO YOU FOR DAMAGES, +INCLUDING ANY GENERAL, SPECIAL, INCIDENTAL OR CONSEQUENTIAL DAMAGES ARISING +OUT OF THE USE OR INABILITY TO USE THE PROGRAM (INCLUDING BUT NOT LIMITED +TO LOSS OF DATA OR DATA BEING RENDERED INACCURATE OR LOSSES SUSTAINED BY +YOU OR THIRD PARTIES OR A FAILURE OF THE PROGRAM TO OPERATE WITH ANY OTHER +PROGRAMS), EVEN IF SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE +POSSIBILITY OF SUCH DAMAGES. + + END OF TERMS AND CONDITIONS + + How to Apply These Terms to Your New Programs + + If you develop a new program, and you want it to be of the greatest +possible use to the public, the best way to achieve this is to make it +free software which everyone can redistribute and change under these terms. + + To do so, attach the following notices to the program. It is safest +to attach them to the start of each source file to most effectively +convey the exclusion of warranty; and each file should have at least +the "copyright" line and a pointer to where the full notice is found. + + + Copyright (C) + + This program is free software; you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation; either version 2 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License along + with this program; if not, write to the Free Software Foundation, Inc., + 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA. + +Also add information on how to contact you by electronic and paper mail. + +If the program is interactive, make it output a short notice like this +when it starts in an interactive mode: + + Gnomovision version 69, Copyright (C) year name of author + Gnomovision comes with ABSOLUTELY NO WARRANTY; for details type `show w'. + This is free software, and you are welcome to redistribute it + under certain conditions; type `show c' for details. + +The hypothetical commands `show w' and `show c' should show the appropriate +parts of the General Public License. Of course, the commands you use may +be called something other than `show w' and `show c'; they could even be +mouse-clicks or menu items--whatever suits your program. + +You should also get your employer (if you work as a programmer) or your +school, if any, to sign a "copyright disclaimer" for the program, if +necessary. Here is a sample; alter the names: + + Yoyodyne, Inc., hereby disclaims all copyright interest in the program + `Gnomovision' (which makes passes at compilers) written by James Hacker. + + , 1 April 1989 + Ty Coon, President of Vice + +This General Public License does not permit incorporating your program into +proprietary programs. If your program is a subroutine library, you may +consider it more useful to permit linking proprietary applications with the +library. If this is what you want to do, use the GNU Lesser General +Public License instead of this License. diff --git a/simulators/dynamic_logistics_warehouse_h/README.md b/simulators/dynamic_logistics_warehouse_h/README.md new file mode 100755 index 0000000..77dd76d --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/README.md @@ -0,0 +1,84 @@ + +# Dynamic_logistics_Warehouse + +Gazebo simulation of dynamics environment in warehouses. An extensive model of AWS-robomaker-small-warehouse. + +### Specifications: +* 9 Actors following different waypoints to perform trajectory path. +* 5 Light sources +* Shelves +* PalletJack +* Desks +* Trashcan +* Cluttering + + + + + +![test](https://user-images.githubusercontent.com/27731036/125352251-98e87180-e393-11eb-8feb-56853ab26f72.gif) + + + + + + + + + +## Building and Launching the Gazebo World with your ROS Applications + +* Create or update a **.rosinstall** file in the root directory of your ROS workspace. Add the following line to **.rosintall**: + + + +* Change the directory to your ROS workspace and run `rosws update` + +* Add the following include to the ROS launch file you are using: + + ```xml + + + + ... + + ``` + +* Build your application using `colcon` + + ```bash + rosws update + rosdep install --from-paths . --ignore-src -r -y + colcon build + ``` + +## Example: Running this world directly in Gazebo without a ROS application + +To open this world in Gazebo, change the directory to your ROS workspace root folder and run: + +```bash +cd dynamic-logistics-warehouse +export GAZEBO_MODEL_PATH=`pwd`/models +gazebo worlds/warehouse.world +``` + + + + + + +## Example: Running this world directly using ROS without a simulated robot + +To launch this base Gazebo world without a robot, clone this repository and run the following commands. **Note: ROS and gazebo must already be installed on the host.** + +```bash +# build for ROS +rosdep install --from-paths . --ignore-src -r -y +colcon build + +# run in ROS +source install/setup.sh +roslaunch dynamic_logistics_warehouse logistics_warehouse.launch +``` +### You can buy me a coffee via: +Buy Me A Coffee diff --git a/simulators/dynamic_logistics_warehouse_h/docs/images/gzweb_aws_warehouse.png b/simulators/dynamic_logistics_warehouse_h/docs/images/gzweb_aws_warehouse.png new file mode 100755 index 0000000..1145de3 Binary files /dev/null and b/simulators/dynamic_logistics_warehouse_h/docs/images/gzweb_aws_warehouse.png differ diff --git a/simulators/dynamic_logistics_warehouse_h/docs/images/models_boxes.png b/simulators/dynamic_logistics_warehouse_h/docs/images/models_boxes.png new file mode 100755 index 0000000..21cd47b Binary files /dev/null and b/simulators/dynamic_logistics_warehouse_h/docs/images/models_boxes.png differ diff --git a/simulators/dynamic_logistics_warehouse_h/docs/images/models_buckets.png b/simulators/dynamic_logistics_warehouse_h/docs/images/models_buckets.png new file mode 100755 index 0000000..086ec09 Binary files /dev/null and b/simulators/dynamic_logistics_warehouse_h/docs/images/models_buckets.png differ diff --git a/simulators/dynamic_logistics_warehouse_h/docs/images/models_ceiling_lamp.png b/simulators/dynamic_logistics_warehouse_h/docs/images/models_ceiling_lamp.png new file mode 100755 index 0000000..8bc3681 Binary files /dev/null and b/simulators/dynamic_logistics_warehouse_h/docs/images/models_ceiling_lamp.png differ diff --git a/simulators/dynamic_logistics_warehouse_h/docs/images/models_desk.png b/simulators/dynamic_logistics_warehouse_h/docs/images/models_desk.png new file mode 100755 index 0000000..bb37521 Binary files /dev/null and b/simulators/dynamic_logistics_warehouse_h/docs/images/models_desk.png differ diff --git a/simulators/dynamic_logistics_warehouse_h/docs/images/models_lift.png b/simulators/dynamic_logistics_warehouse_h/docs/images/models_lift.png new file mode 100755 index 0000000..ea698d3 Binary files /dev/null and b/simulators/dynamic_logistics_warehouse_h/docs/images/models_lift.png differ diff --git a/simulators/dynamic_logistics_warehouse_h/docs/images/models_shelves.png b/simulators/dynamic_logistics_warehouse_h/docs/images/models_shelves.png new file mode 100755 index 0000000..8d7542b Binary files /dev/null and b/simulators/dynamic_logistics_warehouse_h/docs/images/models_shelves.png differ diff --git a/simulators/dynamic_logistics_warehouse_h/docs/images/models_trashcan.png b/simulators/dynamic_logistics_warehouse_h/docs/images/models_trashcan.png new file mode 100755 index 0000000..af707e5 Binary files /dev/null and b/simulators/dynamic_logistics_warehouse_h/docs/images/models_trashcan.png differ diff --git a/simulators/dynamic_logistics_warehouse_h/docs/images/models_warehouse_ground_paint.png b/simulators/dynamic_logistics_warehouse_h/docs/images/models_warehouse_ground_paint.png new file mode 100755 index 0000000..0ca7a67 Binary files /dev/null and b/simulators/dynamic_logistics_warehouse_h/docs/images/models_warehouse_ground_paint.png differ diff --git a/simulators/dynamic_logistics_warehouse_h/docs/images/small_warehouse_gazebo.png b/simulators/dynamic_logistics_warehouse_h/docs/images/small_warehouse_gazebo.png new file mode 100755 index 0000000..7778fd9 Binary files /dev/null and b/simulators/dynamic_logistics_warehouse_h/docs/images/small_warehouse_gazebo.png differ diff --git a/simulators/dynamic_logistics_warehouse_h/launch/logistics_warehouse.launch b/simulators/dynamic_logistics_warehouse_h/launch/logistics_warehouse.launch new file mode 100755 index 0000000..0aa2b7c --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/launch/logistics_warehouse.launch @@ -0,0 +1,16 @@ + + + + + + + + + + + + + + diff --git a/simulators/dynamic_logistics_warehouse_h/maps/002/map.pgm b/simulators/dynamic_logistics_warehouse_h/maps/002/map.pgm new file mode 100755 index 0000000..37c3924 --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/maps/002/map.pgm @@ -0,0 +1,5 @@ +P5 +# CREATOR: map_saver.cpp 0.020 m/pix +1536 1504 +255 + \ No newline at end of file diff --git a/simulators/dynamic_logistics_warehouse_h/maps/002/map.yaml b/simulators/dynamic_logistics_warehouse_h/maps/002/map.yaml new file mode 100755 index 0000000..ed90b18 --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/maps/002/map.yaml @@ -0,0 +1,7 @@ +image: map.pgm +resolution: 0.020000 +origin: [-10.000000, -20.240000, 0.000000] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 + diff --git a/simulators/dynamic_logistics_warehouse_h/maps/005/map.pgm b/simulators/dynamic_logistics_warehouse_h/maps/005/map.pgm new file mode 100755 index 0000000..89e5384 --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/maps/005/map.pgm @@ -0,0 +1,5 @@ +P5 +# CREATOR: map_saver.cpp 0.050 m/pix +640 384 +255 + \ No newline at end of file diff --git a/simulators/dynamic_logistics_warehouse_h/maps/005/map.yaml b/simulators/dynamic_logistics_warehouse_h/maps/005/map.yaml new file mode 100755 index 0000000..fbaf3c8 --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/maps/005/map.yaml @@ -0,0 +1,8 @@ +image: map_rotated.png +resolution: 0.050000 +origin: [-7.000, -10.500000, 0.000000] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 + +# -3.071 3.583 diff --git a/simulators/dynamic_logistics_warehouse_h/maps/005/map_rotated.pgm b/simulators/dynamic_logistics_warehouse_h/maps/005/map_rotated.pgm new file mode 100755 index 0000000..c06a923 Binary files /dev/null and b/simulators/dynamic_logistics_warehouse_h/maps/005/map_rotated.pgm differ diff --git a/simulators/dynamic_logistics_warehouse_h/maps/005/map_rotated.png b/simulators/dynamic_logistics_warehouse_h/maps/005/map_rotated.png new file mode 100755 index 0000000..e1fe0ea Binary files /dev/null and b/simulators/dynamic_logistics_warehouse_h/maps/005/map_rotated.png differ diff --git a/simulators/dynamic_logistics_warehouse_h/maps/warehouse/critical_zones.png b/simulators/dynamic_logistics_warehouse_h/maps/warehouse/critical_zones.png new file mode 100755 index 0000000..fb5a153 Binary files /dev/null and b/simulators/dynamic_logistics_warehouse_h/maps/warehouse/critical_zones.png differ diff --git a/simulators/dynamic_logistics_warehouse_h/maps/warehouse/critical_zones.yaml b/simulators/dynamic_logistics_warehouse_h/maps/warehouse/critical_zones.yaml new file mode 100755 index 0000000..80a2da7 --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/maps/warehouse/critical_zones.yaml @@ -0,0 +1,7 @@ +image: critical_zones.png +resolution: 0.050000 +origin: [-51.224998, -51.224998, 0.000000] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 + diff --git a/simulators/dynamic_logistics_warehouse_h/maps/warehouse/direction_zones.png b/simulators/dynamic_logistics_warehouse_h/maps/warehouse/direction_zones.png new file mode 100755 index 0000000..4cead8a Binary files /dev/null and b/simulators/dynamic_logistics_warehouse_h/maps/warehouse/direction_zones.png differ diff --git a/simulators/dynamic_logistics_warehouse_h/maps/warehouse/direction_zones.yaml b/simulators/dynamic_logistics_warehouse_h/maps/warehouse/direction_zones.yaml new file mode 100755 index 0000000..34d534a --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/maps/warehouse/direction_zones.yaml @@ -0,0 +1,7 @@ +image: direction_zones.png +resolution: 0.050000 +origin: [-51.224998, -51.224998, 0.000000] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 + diff --git a/simulators/dynamic_logistics_warehouse_h/maps/warehouse/map_empty.png b/simulators/dynamic_logistics_warehouse_h/maps/warehouse/map_empty.png new file mode 100755 index 0000000..e9cb54a Binary files /dev/null and b/simulators/dynamic_logistics_warehouse_h/maps/warehouse/map_empty.png differ diff --git a/simulators/dynamic_logistics_warehouse_h/maps/warehouse/map_empty.yaml b/simulators/dynamic_logistics_warehouse_h/maps/warehouse/map_empty.yaml new file mode 100755 index 0000000..4045333 --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/maps/warehouse/map_empty.yaml @@ -0,0 +1,7 @@ +image: map_empty.png +resolution: 0.050000 +origin: [-51.224998, -51.224998, 0.000000] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 + diff --git a/simulators/dynamic_logistics_warehouse_h/maps/warehouse/preferred_zones.yaml b/simulators/dynamic_logistics_warehouse_h/maps/warehouse/preferred_zones.yaml new file mode 100755 index 0000000..7fc1e78 --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/maps/warehouse/preferred_zones.yaml @@ -0,0 +1,7 @@ +image: preferrred_zones.png +resolution: 0.050000 +origin: [-51.224998, -51.224998, 0.000000] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 + diff --git a/simulators/dynamic_logistics_warehouse_h/maps/warehouse/preferrred_zones.png b/simulators/dynamic_logistics_warehouse_h/maps/warehouse/preferrred_zones.png new file mode 100755 index 0000000..49ae274 Binary files /dev/null and b/simulators/dynamic_logistics_warehouse_h/maps/warehouse/preferrred_zones.png differ diff --git a/simulators/dynamic_logistics_warehouse_h/maps/warehouse/unpreferred_zones.yaml b/simulators/dynamic_logistics_warehouse_h/maps/warehouse/unpreferred_zones.yaml new file mode 100755 index 0000000..5974235 --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/maps/warehouse/unpreferred_zones.yaml @@ -0,0 +1,7 @@ +image: unpreferrred_zones.png +resolution: 0.050000 +origin: [-51.224998, -51.224998, 0.000000] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 + diff --git a/simulators/dynamic_logistics_warehouse_h/maps/warehouse/unpreferrred_zones.png b/simulators/dynamic_logistics_warehouse_h/maps/warehouse/unpreferrred_zones.png new file mode 100755 index 0000000..88f8562 Binary files /dev/null and b/simulators/dynamic_logistics_warehouse_h/maps/warehouse/unpreferrred_zones.png differ diff --git a/simulators/dynamic_logistics_warehouse_h/maps/warehouse/virtual_walls.png b/simulators/dynamic_logistics_warehouse_h/maps/warehouse/virtual_walls.png new file mode 100755 index 0000000..81346ab Binary files /dev/null and b/simulators/dynamic_logistics_warehouse_h/maps/warehouse/virtual_walls.png differ diff --git a/simulators/dynamic_logistics_warehouse_h/maps/warehouse/virtual_walls.yaml b/simulators/dynamic_logistics_warehouse_h/maps/warehouse/virtual_walls.yaml new file mode 100755 index 0000000..9840d0d --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/maps/warehouse/virtual_walls.yaml @@ -0,0 +1,7 @@ +image: virtual_walls.png +resolution: 0.050000 +origin: [-51.224998, -51.224998, 0.000000] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 + diff --git a/simulators/dynamic_logistics_warehouse_h/maps/warehouse/warehouse.pgm b/simulators/dynamic_logistics_warehouse_h/maps/warehouse/warehouse.pgm new file mode 100755 index 0000000..01077c0 --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/maps/warehouse/warehouse.pgm @@ -0,0 +1,5 @@ +P5 +# CREATOR: map_saver.cpp 0.050 m/pix +2048 2048 +255 + \ No newline at end of file diff --git a/simulators/dynamic_logistics_warehouse_h/maps/warehouse/warehouse.png b/simulators/dynamic_logistics_warehouse_h/maps/warehouse/warehouse.png new file mode 100755 index 0000000..1e93bee Binary files /dev/null and b/simulators/dynamic_logistics_warehouse_h/maps/warehouse/warehouse.png differ diff --git a/simulators/dynamic_logistics_warehouse_h/maps/warehouse/warehouse.yaml b/simulators/dynamic_logistics_warehouse_h/maps/warehouse/warehouse.yaml new file mode 100755 index 0000000..a394ba3 --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/maps/warehouse/warehouse.yaml @@ -0,0 +1,7 @@ +image: warehouse.png +resolution: 0.050000 +origin: [-51.224998, -51.224998, 0.000000] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 + diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ClutteringA_01/materials/textures/aws_robomaker_warehouse_ClutteringA_01.png b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ClutteringA_01/materials/textures/aws_robomaker_warehouse_ClutteringA_01.png new file mode 100755 index 0000000..b28b289 Binary files /dev/null and b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ClutteringA_01/materials/textures/aws_robomaker_warehouse_ClutteringA_01.png differ diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ClutteringA_01/materials/textures/aws_robomaker_warehouse_ClutteringA_02.png b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ClutteringA_01/materials/textures/aws_robomaker_warehouse_ClutteringA_02.png new file mode 100755 index 0000000..4b7e610 Binary files /dev/null and b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ClutteringA_01/materials/textures/aws_robomaker_warehouse_ClutteringA_02.png differ diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ClutteringA_01/materials/textures/aws_robomaker_warehouse_ClutteringA_03.png b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ClutteringA_01/materials/textures/aws_robomaker_warehouse_ClutteringA_03.png new file mode 100755 index 0000000..a8f1e1c Binary files /dev/null and b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ClutteringA_01/materials/textures/aws_robomaker_warehouse_ClutteringA_03.png differ diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_collision.DAE b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_collision.DAE new file mode 100755 index 0000000..553d82b --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_collision.DAE @@ -0,0 +1,327 @@ + + + FBX COLLADA exporter2019-03-18T11:45:58Z2019-03-18T11:45:58ZZ_UP + + + + + +-94.500908 -100.041384 3.000000 +62.468575 -100.041384 3.000000 +-94.500908 80.061399 3.000000 +62.468575 80.061399 3.000000 +-94.500908 -100.041384 111.551331 +62.468575 -100.041384 111.551331 +-94.500908 80.061399 111.551331 +62.468575 80.061399 111.551331 +29.526070 43.870054 3.000000 +96.793404 43.870054 3.000000 +29.526070 98.479551 3.000000 +96.793404 100.129454 3.000000 +29.526070 43.870054 73.674812 +96.793404 43.870054 73.674812 +29.526070 98.479551 73.674812 +96.793404 100.129454 73.674812 +56.843697 -49.131350 3.000000 +46.691963 22.638792 3.000000 +99.844673 23.109861 3.000000 +107.644112 -43.094973 3.000000 +56.843697 -49.131350 73.674812 +107.644112 -43.094973 73.674812 +99.844673 23.109861 73.674812 +46.691963 22.638792 73.674812 +-108.431084 -32.400026 3.000000 +-108.431084 18.446653 3.000000 +-88.055717 18.917723 3.000000 +-84.168144 -31.578005 3.000000 +-108.431084 -32.400026 73.674812 +-84.168144 -31.578005 73.674812 +-88.055717 18.917723 73.674812 +-108.431084 18.446653 73.674812 + + + + + + + + + + + +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.024520 0.999699 0.000000 +-0.024520 0.999699 0.000000 +-0.024520 0.999699 0.000000 +-0.024520 0.999699 0.000000 +-0.024520 0.999699 0.000000 +-0.024520 0.999699 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.117995 -0.993014 0.000000 +0.117995 -0.993014 0.000000 +0.117995 -0.993014 0.000000 +0.117995 -0.993014 0.000000 +0.117995 -0.993014 0.000000 +0.117995 -0.993014 0.000000 +0.993132 0.116999 0.000000 +0.993132 0.116999 0.000000 +0.993132 0.116999 0.000000 +0.993132 0.116999 0.000000 +0.993132 0.116999 0.000000 +0.993132 0.116999 0.000000 +-0.008862 0.999961 0.000000 +-0.008862 0.999961 0.000000 +-0.008862 0.999961 0.000000 +-0.008862 0.999961 0.000000 +-0.008862 0.999961 0.000000 +-0.008862 0.999961 0.000000 +-0.990144 -0.140054 0.000000 +-0.990144 -0.140054 0.000000 +-0.990144 -0.140054 0.000000 +-0.990144 -0.140054 0.000000 +-0.990144 -0.140054 0.000000 +-0.990144 -0.140054 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.033860 -0.999427 0.000000 +0.033860 -0.999427 0.000000 +0.033860 -0.999427 0.000000 +0.033860 -0.999427 0.000000 +0.033860 -0.999427 0.000000 +0.033860 -0.999427 0.000000 +0.997050 0.076761 0.000000 +0.997050 0.076761 0.000000 +0.997050 0.076761 0.000000 +0.997050 0.076761 0.000000 +0.997050 0.076761 0.000000 +0.997050 0.076761 0.000000 +-0.023113 0.999733 0.000000 +-0.023113 0.999733 0.000000 +-0.023113 0.999733 0.000000 +-0.023113 0.999733 0.000000 +-0.023113 0.999733 0.000000 +-0.023113 0.999733 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 + + + + + + + + + + + +1.000000 0.000000 +0.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +1.000000 0.000000 +0.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +1.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +0.000000 0.000000 +1.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +1.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +0.000000 0.000000 +1.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 + + + + + + + + + + + +

1 0 1 0 1 0 3 2 3 0 3 0 2 4 2 3 5 3 7 6 7 6 7 6 4 8 4 7 9 7 4 10 4 5 11 5 5 12 11 4 13 10 0 14 8 5 15 11 0 16 8 1 17 9 7 18 15 5 19 14 1 20 12 7 21 15 1 22 12 3 23 13 6 24 19 7 25 18 3 26 16 6 27 19 3 28 16 2 29 17 4 30 23 6 31 22 2 32 20 4 33 23 2 34 20 0 35 21 9 36 25 10 37 26 11 38 27 10 39 26 9 40 25 8 41 24 14 42 30 13 43 29 15 44 31 13 45 29 14 46 30 12 47 28 13 48 35 12 49 34 8 50 32 13 51 35 8 52 32 9 53 33 15 54 39 13 55 38 9 56 36 15 57 39 9 58 36 11 59 37 14 60 43 15 61 42 11 62 40 14 63 43 11 64 40 10 65 41 12 66 47 14 67 46 10 68 44 12 69 47 10 70 44 8 71 45 19 72 51 16 73 48 18 74 50 16 75 48 17 76 49 18 77 50 22 78 54 23 79 55 20 80 52 22 81 54 20 82 52 21 83 53 21 84 58 20 85 59 16 86 56 21 87 58 16 88 56 19 89 57 22 90 62 21 91 63 19 92 60 22 93 62 19 94 60 18 95 61 23 96 66 22 97 67 18 98 64 23 99 66 18 100 64 17 101 65 20 102 70 23 103 71 17 104 68 20 105 70 17 106 68 16 107 69 26 108 74 27 109 75 24 110 72 24 111 72 25 112 73 26 113 74 31 114 79 28 115 76 30 116 78 30 117 78 28 118 76 29 119 77 28 120 83 24 121 80 29 122 82 29 123 82 24 124 80 27 125 81 30 126 86 29 127 87 27 128 84 30 129 86 27 130 84 26 131 85 30 132 91 26 133 88 31 134 90 31 135 90 26 136 88 25 137 89 28 138 94 31 139 95 25 140 92 28 141 94 25 142 92 24 143 93

+
+
+
+ + + 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.0000001.000000 + 30.0000000.0000003.333333 + + + + + +
diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_visual.DAE b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_visual.DAE new file mode 100755 index 0000000..7b071bd --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_visual.DAE @@ -0,0 +1,1874 @@ + + + FBX COLLADA exporter2019-05-23T10:22:51Z2019-05-23T10:22:51ZZ_UP + + + ../materials/textures/aws_robomaker_warehouse_ClutteringA_01.png + + + ../materials/textures/aws_robomaker_warehouse_ClutteringA_02.png + + + ../materials/textures/aws_robomaker_warehouse_ClutteringA_03.png + + + + + + + + + + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + +0.762349 -0.606361 0.055429 +0.762349 -0.606361 0.494255 +0.673489 0.143674 0.494255 +0.673489 0.143674 0.055429 +1.358378 -0.535747 0.055429 +1.269518 0.214288 0.055429 +1.269519 0.214288 0.494255 +1.358378 -0.535747 0.494255 +0.686616 0.145229 0.494255 +0.727190 -0.442360 0.509501 +0.727190 0.276956 0.509501 +1.223694 0.276958 0.509501 +1.223696 -0.442358 0.509501 +0.654626 0.292200 0.055429 +0.654627 0.292200 0.494255 +0.670540 -0.462913 0.494255 +0.670540 -0.462913 0.055429 +0.054562 0.279554 0.055429 +0.070475 -0.475559 0.055429 +0.070476 -0.475559 0.494255 +0.067778 0.279833 0.494255 +0.054562 0.279554 0.494255 +0.049009 0.284453 0.055429 +0.049009 0.284453 0.494255 +0.064923 -0.470660 0.494255 +0.064923 -0.470661 0.055429 +-0.551056 0.271806 0.055429 +-0.535142 -0.483307 0.055429 +-0.535142 -0.483307 0.494255 +-0.537840 0.272085 0.494255 +-0.551055 0.271806 0.494255 +0.728582 -0.476027 0.055429 +0.728582 -0.476027 0.494255 +0.744496 -1.231140 0.494255 +0.744496 -1.231140 0.055429 +0.128518 -0.488673 0.055429 +0.144431 -1.243786 0.055429 +0.144431 -1.243786 0.494255 +0.141733 -0.488395 0.494255 +0.128518 -0.488673 0.494255 +0.113458 -0.487202 0.055429 +0.113459 -0.487202 0.494255 +0.129372 -1.242315 0.494255 +0.129372 -1.242316 0.055429 +-0.486606 -0.499848 0.055429 +-0.470693 -1.254962 0.055429 +-0.470692 -1.254962 0.494255 +-0.473390 -0.499570 0.494255 +-0.486606 -0.499848 0.494255 +-0.350717 -1.242098 0.502955 +-0.350717 -1.242099 0.941781 +-1.105990 -1.245517 0.941781 +-1.105990 -1.245517 0.502955 +-0.353434 -0.641907 0.502955 +-1.108707 -0.645325 0.502955 +-1.108707 -0.645325 0.941781 +-0.353374 -0.655125 0.941781 +-0.353434 -0.641907 0.941781 +-0.521947 -0.487202 0.055429 +-0.521946 -0.487202 0.494255 +-0.506033 -1.242315 0.494255 +-0.506033 -1.242316 0.055429 +-1.122011 -0.499848 0.055429 +-1.106098 -1.254962 0.055429 +-1.106098 -1.254962 0.494255 +-1.108795 -0.499570 0.494255 +-1.122011 -0.499848 0.494255 +0.414450 -1.246076 0.502955 +0.414450 -1.246077 0.941781 +-0.340823 -1.249495 0.941781 +-0.340823 -1.249495 0.502955 +0.411733 -0.645885 0.502955 +-0.343540 -0.649303 0.502955 +-0.343540 -0.649303 0.941781 +0.411793 -0.659103 0.941781 +0.411733 -0.645884 0.941781 +0.549717 -0.522866 0.457994 +0.549717 -0.522867 0.716063 +-0.436317 -0.570149 0.716063 +-0.436317 -0.570147 0.457994 +0.520747 0.081303 0.457994 +-0.465287 0.034019 0.457994 +0.520748 0.081303 0.716063 +-0.465287 0.034022 0.716063 +0.557365 -0.508447 0.724572 +0.557365 -0.508448 0.982641 +-0.426944 -0.583510 0.982641 +-0.426944 -0.583510 0.724572 +0.511375 0.094665 0.724573 +-0.472935 0.019601 0.724573 +0.511375 0.094664 0.982641 +-0.472935 0.019602 0.982641 +-1.130571 -0.501727 0.514184 +-1.130572 -0.501727 0.953010 +-1.133990 0.253546 0.953010 +-1.133990 0.253546 0.514184 +-0.530380 -0.499010 0.514184 +-0.533798 0.256263 0.514184 +-0.533798 0.256263 0.953010 +-0.543598 -0.499070 0.953010 +-0.530379 -0.499010 0.953010 +-0.590618 -0.387423 0.055429 +-0.590618 -0.387423 0.494255 +-1.345731 -0.403336 0.494255 +-1.345732 -0.403336 0.055429 +-0.603265 0.212642 0.055429 +-1.358378 0.196728 0.055429 +-1.358378 0.196728 0.494255 +-0.602986 0.199426 0.494255 +-0.603265 0.212642 0.494255 +-0.963410 0.251932 0.497822 +-0.963411 0.251932 0.936648 +-0.966830 1.007205 0.936648 +-0.966830 1.007206 0.497822 +-0.363219 0.254649 0.497822 +-0.366637 1.009923 0.497822 +-0.366638 1.009923 0.936648 +-0.376437 0.254589 0.936648 +-0.363219 0.254649 0.936648 +-0.423457 0.366237 0.055429 +-0.423457 0.366236 0.494255 +-1.178570 0.350323 0.494255 +-1.178571 0.350323 0.055429 +-0.436104 0.966301 0.055429 +-1.191217 0.950387 0.055429 +-1.191217 0.950387 0.494255 +-0.435825 0.953085 0.494255 +-0.436104 0.966301 0.494255 +-0.145074 0.178557 0.491724 +-0.145074 0.178557 0.930551 +-0.148493 0.933831 0.930551 +-0.148493 0.933831 0.491724 +0.455118 0.181274 0.491724 +0.451700 0.936548 0.491724 +0.451699 0.936548 0.930551 +0.441899 0.181214 0.930551 +0.455118 0.181274 0.930551 +0.394880 0.292862 0.055429 +0.394880 0.292861 0.494255 +-0.360234 0.276948 0.494255 +-0.360234 0.276948 0.055429 +0.382233 0.892926 0.055429 +-0.372880 0.877013 0.055429 +-0.372880 0.877013 0.494255 +0.382512 0.879710 0.494255 +0.382233 0.892926 0.494255 +0.464209 1.211223 0.487764 +0.464209 1.211223 0.926590 +1.219483 1.214642 0.926590 +1.219483 1.214642 0.487764 +0.466926 0.611031 0.487764 +1.222200 0.614450 0.487764 +1.222200 0.614450 0.926590 +0.466866 0.624250 0.926590 +0.466926 0.611031 0.926590 +1.164522 0.654896 0.055429 +1.164522 0.654896 0.494255 +0.409409 0.638982 0.494255 +0.409408 0.638982 0.055429 +1.151876 1.254961 0.055429 +0.396762 1.239047 0.055429 +0.396762 1.239047 0.494255 +1.152154 1.241745 0.494255 +1.151876 1.254961 0.494255 +-0.145074 0.178557 0.930911 +-0.145074 0.178557 1.369738 +-0.148493 0.933831 1.369738 +-0.148493 0.933831 0.930911 +0.455118 0.181274 0.930911 +0.451700 0.936548 0.930911 +0.451699 0.936548 1.369738 +0.441899 0.181214 1.369738 +0.455118 0.181274 1.369738 +0.557365 -0.508447 0.983359 +0.557365 -0.508448 1.241428 +-0.426944 -0.583510 1.241428 +-0.426944 -0.583510 0.983359 +0.511375 0.094665 0.983359 +-0.472935 0.019601 0.983359 +0.511375 0.094664 1.241428 +-0.472935 0.019602 1.241428 +-1.130571 -0.501727 0.955464 +-1.130572 -0.501727 1.394290 +-1.133990 0.253546 1.394290 +-1.133990 0.253547 0.955464 +-0.530380 -0.499010 0.955464 +-0.533798 0.256263 0.955464 +-0.533798 0.256263 1.394290 +-0.543598 -0.499070 1.394290 +-0.530379 -0.499010 1.394290 +0.727190 -0.442360 0.792406 +1.223696 -0.442358 0.792406 +1.223694 0.276958 0.792406 +0.727190 0.276956 0.792406 + + + + + + + + + + + +0.993055 0.117651 -0.000001 +0.993055 0.117651 -0.000001 +0.993055 0.117651 -0.000001 +0.993055 0.117651 -0.000001 +0.993055 0.117651 -0.000001 +0.993055 0.117651 -0.000001 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.117651 0.993055 0.000000 +0.117651 -0.993055 0.000000 +0.117651 -0.993055 0.000000 +0.117651 -0.993055 0.000000 +0.117651 -0.993055 0.000000 +0.117651 -0.993055 0.000000 +0.117651 -0.993055 0.000000 +-0.993055 -0.117651 0.000000 +-0.993055 -0.117651 0.000000 +-0.993055 -0.117651 0.000000 +-0.993055 -0.117651 0.000000 +-0.993055 -0.117651 0.000000 +-0.993055 -0.117651 0.000000 +-0.117651 0.993055 0.000000 +-0.117651 0.993055 0.000000 +-0.117651 0.993055 0.000000 +-0.117651 0.993055 0.000000 +-0.117651 0.993055 0.000000 +-0.117651 0.993055 0.000000 +0.999778 0.021070 -0.000001 +0.999778 0.021070 -0.000001 +0.999778 0.021070 -0.000001 +0.999778 0.021070 -0.000001 +0.999778 0.021070 -0.000001 +0.999778 0.021070 -0.000001 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.021070 0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.021070 0.999778 0.000000 +0.000000 0.000000 1.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.021070 0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.021070 0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +0.004527 -0.999990 -0.000001 +0.004527 -0.999990 -0.000001 +0.004527 -0.999990 -0.000001 +0.004527 -0.999990 -0.000001 +0.004527 -0.999990 -0.000001 +0.004527 -0.999990 -0.000001 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.999990 0.004527 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.004526 0.999990 0.000000 +-0.004526 0.999990 0.000000 +-0.004526 0.999990 0.000000 +-0.004526 0.999990 0.000000 +-0.004526 0.999990 0.000000 +-0.004526 0.999990 0.000000 +0.999990 0.004527 0.000000 +0.999990 0.004527 0.000000 +0.999990 0.004527 0.000000 +0.999990 0.004527 0.000000 +0.999990 0.004527 0.000000 +0.999990 0.004527 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.021070 0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.999990 0.004527 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.999990 0.004527 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.004526 0.999990 0.000000 +-0.004526 0.999990 0.000000 +-0.004526 0.999990 0.000000 +-0.004526 0.999990 0.000000 +-0.004526 0.999990 0.000000 +-0.004526 0.999990 0.000000 +0.999990 0.004527 0.000000 +0.999990 0.004527 0.000000 +0.999990 0.004527 0.000000 +0.999990 0.004527 0.000000 +0.999990 0.004527 0.000000 +0.999990 0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.004527 -0.999990 0.000000 +0.000000 0.000000 1.000000 +0.004527 -0.999990 0.000000 +0.000000 0.000000 1.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.999778 0.021070 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.004527 -0.999990 0.000000 +0.000000 0.000000 1.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.999778 0.021070 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.004527 -0.999990 0.000000 +0.000000 0.000000 1.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.999778 0.021070 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999990 -0.004527 0.000000 +0.999990 0.004527 0.000000 +0.999990 0.004527 0.000000 +0.999990 0.004527 0.000000 +0.999990 0.004527 0.000000 +0.999990 0.004527 0.000000 +0.999990 0.004527 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.999778 0.021070 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.004527 -0.999990 0.000000 +0.000000 0.000000 1.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +-0.999990 -0.004526 0.000000 +-0.999990 -0.004526 0.000000 +-0.999990 -0.004526 0.000000 +-0.999990 -0.004526 0.000000 +-0.999990 -0.004526 0.000000 +-0.999990 -0.004526 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.004527 -0.999990 0.000000 +0.000000 0.000000 1.000000 +0.004527 -0.999990 0.000000 +0.000000 0.000000 1.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.047896 -0.998852 -0.000005 +0.047896 -0.998852 -0.000005 +0.047896 -0.998852 -0.000005 +0.047896 -0.998852 -0.000005 +0.047896 -0.998852 -0.000005 +0.047896 -0.998852 -0.000005 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.998852 0.047894 -0.000002 +0.998852 0.047894 -0.000002 +0.998852 0.047894 -0.000002 +0.998852 0.047894 -0.000002 +0.998852 0.047894 -0.000002 +0.998852 0.047894 -0.000002 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.998852 -0.047894 0.000000 +-0.998852 -0.047894 0.000000 +-0.998852 -0.047894 0.000000 +-0.998852 -0.047894 0.000000 +-0.998852 -0.047894 0.000000 +-0.998852 -0.047894 0.000000 +-0.047897 0.998852 -0.000005 +-0.047897 0.998852 -0.000005 +-0.047897 0.998852 -0.000005 +-0.047897 0.998852 -0.000005 +-0.047897 0.998852 -0.000005 +-0.047897 0.998852 -0.000005 +0.076038 -0.997105 -0.000003 +0.076038 -0.997105 -0.000003 +0.076038 -0.997105 -0.000003 +0.076038 -0.997105 -0.000003 +0.076038 -0.997105 -0.000003 +0.076038 -0.997105 -0.000003 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.997105 0.076034 0.000000 +0.997105 0.076034 0.000000 +0.997105 0.076034 0.000000 +0.997105 0.076034 0.000000 +0.997105 0.076034 0.000000 +0.997105 0.076034 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.997105 -0.076035 0.000000 +-0.997105 -0.076035 0.000000 +-0.997105 -0.076035 0.000000 +-0.997105 -0.076035 0.000000 +-0.997105 -0.076035 0.000000 +-0.997105 -0.076035 0.000000 +-0.076039 0.997105 0.000000 +-0.076039 0.997105 0.000000 +-0.076039 0.997105 0.000000 +-0.076039 0.997105 0.000000 +-0.076039 0.997105 0.000000 +-0.076039 0.997105 0.000000 +0.076038 -0.997105 -0.000003 +0.076038 -0.997105 -0.000003 +0.076038 -0.997105 -0.000003 +0.076038 -0.997105 -0.000003 +0.076038 -0.997105 -0.000003 +0.076038 -0.997105 -0.000003 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.997105 0.076034 0.000000 +0.997105 0.076034 0.000000 +0.997105 0.076034 0.000000 +0.997105 0.076034 0.000000 +0.997105 0.076034 0.000000 +0.997105 0.076034 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.997105 -0.076035 0.000000 +-0.997105 -0.076035 0.000000 +-0.997105 -0.076035 0.000000 +-0.997105 -0.076035 0.000000 +-0.997105 -0.076035 0.000000 +-0.997105 -0.076035 0.000000 +-0.076039 0.997105 0.000000 +-0.076039 0.997105 0.000000 +-0.076039 0.997105 0.000000 +-0.076039 0.997105 0.000000 +-0.076039 0.997105 0.000000 +-0.076039 0.997105 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000004 -1.000000 0.000000 +0.000004 -1.000000 0.000000 +0.000004 -1.000000 0.000000 +0.000004 -1.000000 0.000000 +0.000004 -1.000000 0.000000 +0.000004 -1.000000 0.000000 +1.000000 0.000001 0.000000 +1.000000 0.000001 0.000000 +1.000000 0.000001 0.000000 +1.000000 0.000001 0.000000 +1.000000 0.000001 0.000000 +1.000000 0.000001 0.000000 +-0.000004 1.000000 0.000000 +-0.000004 1.000000 0.000000 +-0.000004 1.000000 0.000000 +-0.000004 1.000000 0.000000 +-0.000004 1.000000 0.000000 +-0.000004 1.000000 0.000000 +-1.000000 -0.000001 0.000000 +-1.000000 -0.000001 0.000000 +-1.000000 -0.000001 0.000000 +-1.000000 -0.000001 0.000000 +-1.000000 -0.000001 0.000000 +-1.000000 -0.000001 0.000000 + + + + + + + + + + + +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.505546 0.409621 +0.027038 0.424800 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.506996 0.036168 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.029544 0.035380 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.037422 0.971548 +0.039211 0.698717 +0.407335 0.698761 +0.409054 0.971742 +0.029544 0.043430 +0.570344 0.705031 +0.922325 0.705031 +0.570343 0.962377 +0.914572 0.962378 +0.238676 0.206126 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.691973 +0.217975 0.210005 +0.854670 0.918158 +0.150794 0.918158 +0.078207 0.207809 +0.288362 0.210005 +0.288362 0.695852 +0.854670 0.988546 +0.150794 0.988545 +0.010469 0.693656 +0.010469 0.207809 +0.171204 0.205139 +0.875080 0.205139 +0.875080 0.275526 +0.171204 0.275526 +0.147588 0.210005 +0.854670 0.847771 +0.150794 0.847770 +0.148885 0.207809 +0.854670 0.706996 +0.217975 0.695852 +0.078207 0.693656 +0.150794 0.706996 +0.875080 0.345913 +0.171204 0.345913 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.756345 0.522332 +0.756346 0.715841 +0.016244 0.715841 +0.016243 0.522332 +0.009526 0.514494 +0.009526 0.061000 +0.749636 0.060999 +0.749637 0.514493 +0.771396 0.480706 +0.969477 0.480355 +0.969577 0.938728 +0.771464 0.938319 +0.751630 0.039423 +0.751630 0.498972 +0.007192 0.498972 +0.007192 0.039423 +0.977311 0.498670 +0.779207 0.499082 +0.779286 0.040707 +0.977371 0.041060 +0.016243 0.718111 +0.756344 0.718111 +0.756344 0.911620 +0.016243 0.911620 +0.756345 0.522332 +0.756346 0.715841 +0.016244 0.715841 +0.016243 0.522332 +0.009526 0.514494 +0.009526 0.061000 +0.749636 0.060999 +0.749637 0.514493 +0.771396 0.480706 +0.969477 0.480355 +0.969577 0.938728 +0.771464 0.938319 +0.751630 0.039423 +0.751630 0.498972 +0.007192 0.498972 +0.007192 0.039423 +0.977311 0.498670 +0.779207 0.499082 +0.779286 0.040707 +0.977371 0.041060 +0.016243 0.718111 +0.756344 0.718111 +0.756344 0.911620 +0.016243 0.911620 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.756345 0.522332 +0.756346 0.715841 +0.016244 0.715841 +0.016243 0.522332 +0.009526 0.514494 +0.009526 0.061000 +0.749636 0.060999 +0.749637 0.514493 +0.771396 0.480706 +0.969477 0.480355 +0.969577 0.938728 +0.771464 0.938319 +0.751630 0.039423 +0.751630 0.498972 +0.007192 0.498972 +0.007192 0.039423 +0.977311 0.498670 +0.779207 0.499082 +0.779286 0.040707 +0.977371 0.041060 +0.016243 0.718111 +0.756344 0.718111 +0.756344 0.911620 +0.016243 0.911620 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.077201 0.210005 +0.854670 0.777384 +0.150794 0.777383 +0.219564 0.207809 +0.147588 0.695852 +0.148885 0.693656 +0.875080 0.416300 +0.171204 0.416300 +0.944549 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.240673 0.206126 +0.077201 0.695852 +0.219564 0.693656 +0.875080 0.486687 +0.171204 0.486687 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035379 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035381 +0.029544 0.035381 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035381 +0.006814 0.210005 +0.006814 0.695852 +0.287302 0.693656 +0.287302 0.207809 + + + + + + + + + + + +

6 0 6 7 1 7 5 2 5 7 3 7 4 4 4 5 5 5 0 6 8 5 7 10 4 8 11 5 9 10 0 10 8 3 11 9 6 12 15 8 13 20 7 14 14 8 15 20 1 16 13 7 17 14 1 18 13 8 19 20 2 20 12 2 21 12 8 22 20 3 23 566 7 24 19 1 25 16 4 26 18 1 27 16 0 28 17 4 29 18 1 30 1 2 31 2 0 32 0 2 33 2 3 34 3 0 35 0 6 36 23 5 37 21 8 38 24 8 39 24 5 40 21 3 41 22 14 42 54 15 43 55 13 44 53 15 45 55 16 46 56 13 47 53 18 48 60 17 49 57 16 50 59 16 51 59 17 52 57 13 53 58 14 54 63 20 55 64 15 56 62 20 57 64 19 58 61 15 59 62 19 60 61 20 61 64 21 62 65 21 63 65 20 64 64 17 65 567 15 66 67 19 67 68 16 68 66 19 69 68 18 70 69 16 71 66 19 72 72 21 73 73 18 74 71 21 75 73 17 76 70 18 77 71 14 78 75 13 79 76 20 80 74 20 81 74 13 82 76 17 83 77 23 84 79 24 85 80 22 86 78 24 87 80 25 88 81 22 89 78 27 90 85 26 91 82 25 92 84 25 93 84 26 94 82 22 95 83 23 96 88 29 97 89 24 98 87 29 99 89 28 100 86 24 101 87 28 102 86 29 103 89 30 104 90 29 105 89 26 106 568 30 107 90 24 108 92 28 109 93 25 110 91 28 111 93 27 112 94 25 113 91 30 114 98 26 115 95 28 116 97 28 117 97 26 118 95 27 119 96 23 120 100 22 121 101 29 122 99 29 123 99 22 124 101 26 125 102 32 126 104 33 127 105 31 128 103 33 129 105 34 130 106 31 131 103 36 132 110 35 133 107 34 134 109 34 135 109 35 136 107 31 137 108 32 138 113 38 139 114 33 140 112 38 141 114 37 142 111 33 143 112 37 144 111 38 145 114 39 146 115 39 147 115 38 148 114 35 149 569 33 150 117 37 151 118 34 152 116 37 153 118 36 154 119 34 155 116 35 156 120 37 157 122 39 158 123 37 159 122 35 160 120 36 161 121 32 162 125 31 163 126 38 164 124 38 165 124 31 166 126 35 167 127 41 168 129 42 169 130 40 170 128 42 171 130 43 172 131 40 173 128 45 174 135 44 175 132 43 176 134 43 177 134 44 178 132 40 179 133 41 180 138 47 181 139 42 182 137 47 183 139 46 184 136 42 185 137 46 186 136 47 187 139 48 188 140 48 189 140 47 190 139 44 191 570 42 192 142 46 193 143 43 194 141 46 195 143 45 196 144 43 197 141 48 198 148 44 199 145 46 200 147 46 201 147 44 202 145 45 203 146 41 204 150 40 205 151 47 206 149 47 207 149 40 208 151 44 209 152 50 210 154 51 211 155 49 212 153 51 213 155 52 214 156 49 215 153 52 216 159 53 217 157 49 218 158 53 219 157 52 220 159 54 221 160 55 222 161 56 223 164 53 224 571 56 225 164 55 226 161 51 227 162 56 228 164 51 229 162 50 230 163 51 231 167 55 232 168 52 233 166 55 234 168 54 235 169 52 236 166 57 237 173 53 238 170 55 239 172 55 240 172 53 241 170 54 242 171 50 243 175 49 244 176 56 245 174 56 246 174 49 247 176 53 248 177 59 249 179 60 250 180 58 251 178 60 252 180 61 253 181 58 254 178 63 255 185 62 256 182 61 257 184 61 258 184 62 259 182 58 260 183 59 261 188 65 262 189 60 263 187 65 264 189 64 265 186 60 266 187 64 267 186 65 268 189 66 269 190 66 270 190 65 271 189 62 272 572 60 273 192 64 274 193 61 275 191 64 276 193 63 277 194 61 278 191 66 279 198 62 280 195 64 281 197 64 282 197 62 283 195 63 284 196 59 285 200 58 286 201 65 287 199 65 288 199 58 289 201 62 290 202 68 291 204 69 292 205 67 293 203 69 294 205 70 295 206 67 296 203 67 297 208 70 298 209 71 299 207 70 300 209 72 301 210 71 302 207 73 303 211 71 304 573 75 305 215 73 306 211 74 307 214 71 308 573 74 309 214 73 310 211 69 311 212 74 312 214 69 313 212 68 314 213 69 315 217 73 316 218 70 317 216 73 318 218 72 319 219 70 320 216 71 321 220 73 322 222 75 323 223 73 324 222 71 325 220 72 326 221 68 327 225 67 328 226 74 329 224 74 330 224 67 331 226 71 332 227 93 333 277 94 334 278 92 335 276 94 336 278 95 337 279 92 338 276 92 339 281 95 340 282 96 341 280 96 342 280 95 343 282 97 344 283 98 345 284 94 346 285 99 347 287 94 348 285 93 349 286 99 350 287 100 351 288 98 352 284 96 353 574 99 354 287 96 355 574 98 356 284 94 357 290 98 358 291 95 359 289 98 360 291 97 361 292 95 362 289 100 363 296 96 364 293 98 365 295 98 366 295 96 367 293 97 368 294 93 369 298 92 370 299 99 371 297 99 372 297 92 373 299 96 374 300 102 375 302 103 376 303 101 377 301 103 378 303 104 379 304 101 380 301 101 381 306 104 382 307 105 383 305 104 384 307 106 385 308 105 386 305 107 387 309 108 388 312 105 389 575 108 390 312 107 391 309 103 392 310 108 393 312 103 394 310 102 395 311 103 396 315 107 397 316 106 398 317 103 399 315 106 400 317 104 401 314 109 402 321 105 403 318 107 404 320 107 405 320 105 406 318 106 407 319 102 408 323 101 409 324 108 410 322 108 411 322 101 412 324 105 413 325 111 414 327 112 415 328 110 416 326 112 417 328 113 418 329 110 419 326 110 420 331 113 421 332 114 422 330 114 423 330 113 424 332 115 425 333 116 426 334 112 427 335 117 428 337 112 429 335 111 430 336 117 431 337 117 432 337 114 433 576 116 434 334 112 435 340 116 436 341 113 437 339 116 438 341 115 439 342 113 440 339 118 441 346 114 442 343 116 443 345 116 444 345 114 445 343 115 446 344 111 447 348 110 448 349 117 449 347 117 450 347 110 451 349 114 452 350 120 453 352 121 454 353 119 455 351 121 456 353 122 457 354 119 458 351 122 459 357 123 460 355 119 461 356 123 462 355 122 463 357 124 464 358 125 465 359 126 466 362 123 467 577 126 468 362 125 469 359 121 470 360 126 471 362 121 472 360 120 473 361 121 474 365 125 475 366 124 476 367 121 477 365 124 478 367 122 479 364 127 480 371 123 481 368 125 482 370 125 483 370 123 484 368 124 485 369 120 486 373 119 487 374 126 488 372 126 489 372 119 490 374 123 491 375 129 492 377 130 493 378 128 494 376 130 495 378 131 496 379 128 497 376 128 498 381 131 499 382 132 500 380 132 501 380 131 502 382 133 503 383 134 504 384 130 505 385 135 506 387 130 507 385 129 508 386 135 509 387 135 510 387 132 511 578 134 512 384 130 513 390 134 514 391 131 515 389 134 516 391 133 517 392 131 518 389 132 519 393 134 520 395 136 521 396 134 522 395 132 523 393 133 524 394 129 525 398 128 526 399 135 527 397 135 528 397 128 529 399 132 530 400 138 531 402 139 532 403 137 533 401 139 534 403 140 535 404 137 536 401 140 537 407 141 538 405 137 539 406 141 540 405 140 541 407 142 542 408 143 543 409 144 544 412 141 545 579 144 546 412 143 547 409 139 548 410 144 549 412 139 550 410 138 551 411 139 552 415 143 553 416 142 554 417 139 555 415 142 556 417 140 557 414 145 558 421 141 559 418 143 560 420 143 561 420 141 562 418 142 563 419 138 564 423 137 565 424 144 566 422 144 567 422 137 568 424 141 569 425 147 570 427 148 571 428 146 572 426 148 573 428 149 574 429 146 575 426 151 576 433 150 577 430 149 578 432 150 579 430 146 580 431 149 581 432 153 582 437 148 583 435 147 584 436 148 585 435 153 586 437 152 587 434 152 588 434 153 589 437 154 590 438 154 591 438 153 592 437 150 593 580 148 594 440 152 595 441 149 596 439 152 597 441 151 598 442 149 599 439 150 600 443 152 601 445 154 602 446 152 603 445 150 604 443 151 605 444 147 606 448 146 607 449 153 608 447 153 609 447 146 610 449 150 611 450 156 612 452 157 613 453 155 614 451 157 615 453 158 616 454 155 617 451 155 618 456 160 619 458 159 620 455 160 621 458 155 622 456 158 623 457 161 624 459 162 625 462 159 626 581 162 627 462 161 628 459 157 629 460 162 630 462 157 631 460 156 632 461 157 633 465 161 634 466 160 635 467 157 636 465 160 637 467 158 638 464 163 639 471 159 640 468 161 641 470 161 642 470 159 643 468 160 644 469 156 645 473 155 646 474 162 647 472 162 648 472 155 649 474 159 650 475 165 651 477 166 652 478 164 653 476 166 654 478 167 655 479 164 656 476 164 657 481 167 658 482 168 659 480 168 660 480 167 661 482 169 662 483 170 663 484 166 664 485 171 665 487 166 666 485 165 667 486 171 668 487 171 669 487 168 670 582 170 671 484 166 672 490 170 673 491 167 674 489 170 675 491 169 676 492 167 677 489 168 678 493 170 679 495 172 680 496 170 681 495 168 682 493 169 683 494 165 684 498 164 685 499 171 686 497 171 687 497 164 688 499 168 689 500 182 690 526 183 691 527 181 692 525 183 693 527 184 694 528 181 695 525 181 696 530 186 697 532 185 698 529 186 699 532 181 700 530 184 701 531 187 702 533 183 703 534 188 704 536 183 705 534 182 706 535 188 707 536 189 708 537 187 709 533 185 710 583 188 711 536 185 712 583 187 713 533 183 714 539 187 715 540 184 716 538 187 717 540 186 718 541 184 719 538 189 720 545 185 721 542 187 722 544 187 723 544 185 724 542 186 725 543 182 726 547 181 727 548 188 728 546 188 729 546 181 730 548 185 731 549

+

79 732 231 76 733 228 78 734 230 77 735 229 78 736 230 76 737 228 76 738 233 79 739 234 81 740 235 76 741 233 81 742 235 80 743 232 82 744 237 77 745 238 76 746 239 82 747 237 76 748 239 80 749 236 83 750 240 77 751 242 82 752 243 77 753 242 83 754 240 78 755 241 81 756 247 78 757 245 83 758 246 78 759 245 81 760 247 79 761 244 83 762 250 82 763 251 80 764 248 83 765 250 80 766 248 81 767 249 87 768 255 84 769 252 86 770 254 85 771 253 86 772 254 84 773 252 84 774 257 87 775 258 89 776 259 84 777 257 89 778 259 88 779 256 90 780 261 85 781 262 84 782 263 90 783 261 84 784 263 88 785 260 91 786 264 85 787 266 90 788 267 85 789 266 91 790 264 86 791 265 86 792 269 91 793 270 89 794 271 86 795 269 89 796 271 87 797 268 88 798 272 89 799 273 90 800 275 91 801 274 90 802 275 89 803 273 176 804 504 173 805 501 175 806 503 174 807 502 175 808 503 173 809 501 173 810 506 176 811 507 178 812 508 173 813 506 178 814 508 177 815 505 179 816 510 174 817 511 173 818 512 179 819 510 173 820 512 177 821 509 180 822 513 174 823 515 179 824 516 174 825 515 180 826 513 175 827 514 175 828 518 180 829 519 178 830 520 175 831 518 178 832 520 176 833 517 177 834 521 178 835 522 179 836 524 180 837 523 179 838 524 178 839 522

+

9 840 25 10 841 26 12 842 28 12 843 28 10 844 26 11 845 27 192 846 560 193 847 561 191 848 559 193 849 561 190 850 558 191 851 559 191 852 585 190 853 584 9 854 33 191 855 585 9 856 33 12 857 34 192 858 50 191 859 47 12 860 35 192 861 50 12 862 35 11 863 36 193 864 587 192 865 586 11 866 37 193 867 587 11 868 37 10 869 38 190 870 564 193 871 565 10 872 39 190 873 564 10 874 39 9 875 40

+
+
+
+ + + + + + + + + 78.996956 0.000000 0.000000 0.000000 0.000000 78.996956 0.000000 0.000000 0.000000 0.000000 78.996956 0.000000 0.000000 0.000000 0.000000 1.0000001.000000 + 30.0000000.0000003.333333 + + + + + +
diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ClutteringA_01/model.config b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ClutteringA_01/model.config new file mode 100755 index 0000000..c3bf861 --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ClutteringA_01/model.config @@ -0,0 +1,11 @@ + + + aws_robomaker_warehouse_ClutteringA_01 + 1.0 + model.sdf + + + + + + diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ClutteringA_01/model.sdf b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ClutteringA_01/model.sdf new file mode 100755 index 0000000..629f0fc --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ClutteringA_01/model.sdf @@ -0,0 +1,55 @@ + + + + + + 2 + + 0.841 + 0 + 0 + 0.954 + 0 + 1.422 + + + + + + model://aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + model://aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_visual.DAE + + + 1 + + + 1 + + diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ClutteringC_01/materials/textures/aws_robomaker_warehouse_ClutteringC_01.png b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ClutteringC_01/materials/textures/aws_robomaker_warehouse_ClutteringC_01.png new file mode 100755 index 0000000..b28b289 Binary files /dev/null and b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ClutteringC_01/materials/textures/aws_robomaker_warehouse_ClutteringC_01.png differ diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ClutteringC_01/materials/textures/aws_robomaker_warehouse_ClutteringC_02.png b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ClutteringC_01/materials/textures/aws_robomaker_warehouse_ClutteringC_02.png new file mode 100755 index 0000000..4b7e610 Binary files /dev/null and b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ClutteringC_01/materials/textures/aws_robomaker_warehouse_ClutteringC_02.png differ diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_collision.DAE b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_collision.DAE new file mode 100755 index 0000000..4f4fd10 --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_collision.DAE @@ -0,0 +1,123 @@ + + + FBX COLLADA exporter2019-03-20T02:46:25Z2019-03-20T02:46:25ZZ_UP + + + + + +-88.666687 -102.994263 3.000000 +88.666687 -102.994263 3.000000 +-88.666687 102.994263 3.000000 +88.666687 102.994263 3.000000 +-88.666687 -102.994263 179.031189 +88.666687 -102.994263 179.031189 +-88.666687 102.994263 179.031189 +88.666687 102.994263 179.031189 + + + + + + + + + + + +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 + + + + + + + + + + + +1.000000 0.000000 +0.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 + + + + + + + + + + + +

1 0 1 0 1 0 3 2 3 0 3 0 2 4 2 3 5 3 7 6 7 6 7 6 4 8 4 7 9 7 4 10 4 5 11 5 5 12 11 4 13 10 0 14 8 5 15 11 0 16 8 1 17 9 7 18 15 5 19 14 1 20 12 7 21 15 1 22 12 3 23 13 6 24 19 7 25 18 3 26 16 6 27 19 3 28 16 2 29 17 4 30 23 6 31 22 2 32 20 4 33 23 2 34 20 0 35 21

+
+
+
+ + + 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.0000001.000000 + 30.0000000.0000003.333333 + + + + + +
diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_visual.DAE b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_visual.DAE new file mode 100755 index 0000000..3507fe5 --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_visual.DAE @@ -0,0 +1,2036 @@ + + + FBX COLLADA exporter2019-03-20T02:46:45Z2019-03-20T02:46:45ZZ_UP + + + ../materials/textures/aws_robomaker_warehouse_ClutteringC_01.png + + + + + + + + + + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + +1.067614 0.027155 0.952252 +1.067614 0.027155 1.391078 +1.083528 -0.727958 1.391078 +1.083528 -0.727958 0.952252 +0.467549 0.014509 0.952252 +0.483463 -0.740604 0.952252 +0.483463 -0.740604 1.391078 +0.480766 0.014787 1.391078 +0.467550 0.014509 1.391078 +-0.148068 -0.777457 0.043760 +-0.148068 -0.777457 0.482586 +-1.047329 -0.790820 0.482586 +-1.047329 -0.790820 0.043760 +-0.163129 -0.273580 0.043760 +-1.062389 -0.286942 0.043760 +-1.062389 -0.286943 0.482586 +-0.162797 -0.284678 0.482586 +-0.163129 -0.273580 0.482586 +-0.148068 -0.777457 0.496737 +-0.148068 -0.777457 0.935563 +-1.047329 -0.790820 0.935563 +-1.047329 -0.790820 0.496737 +-0.163129 -0.273580 0.496737 +-1.062389 -0.286942 0.496737 +-1.062389 -0.286943 0.935563 +-0.162797 -0.284678 0.935563 +-0.163129 -0.273580 0.935563 +-0.148068 -0.777457 0.952252 +-0.148068 -0.777457 1.391078 +-1.047329 -0.790820 1.391078 +-1.047329 -0.790820 0.952252 +-0.163129 -0.273580 0.952252 +-1.062389 -0.286942 0.952252 +-1.062389 -0.286943 1.391078 +-0.162797 -0.284678 1.391078 +-0.163129 -0.273580 1.391078 +-0.158738 -0.264175 0.043760 +-0.158738 -0.264175 0.482586 +-1.057999 -0.277538 0.482586 +-1.057999 -0.277538 0.043760 +-0.173799 0.239702 0.043760 +-1.073059 0.226339 0.043760 +-1.073059 0.226339 0.482586 +-0.173467 0.228604 0.482586 +-0.173799 0.239702 0.482586 +-0.158738 -0.264175 0.496737 +-0.158738 -0.264175 0.935563 +-1.057999 -0.277538 0.935563 +-1.057999 -0.277538 0.496737 +-0.173799 0.239702 0.496737 +-1.073059 0.226339 0.496737 +-1.073059 0.226339 0.935563 +-0.173467 0.228604 0.935563 +-0.173799 0.239702 0.935563 +-0.158738 -0.264175 0.952252 +-0.158738 -0.264175 1.391078 +-1.057999 -0.277538 1.391078 +-1.057999 -0.277538 0.952252 +-0.173799 0.239702 0.952252 +-1.073059 0.226339 0.952252 +-1.073059 0.226339 1.391078 +-0.173467 0.228604 1.391078 +-0.173799 0.239702 1.391078 +-0.154016 -0.491365 1.405229 +-0.154016 -0.491365 1.844055 +-1.053276 -0.504728 1.844055 +-1.053276 -0.504728 1.405229 +-0.169076 0.012512 1.405229 +-1.068336 -0.000851 1.405229 +-1.068336 -0.000851 1.844055 +-0.168745 0.001414 1.844055 +-0.169076 0.012512 1.844055 +1.067615 0.027155 0.043760 +1.067615 0.027155 0.482586 +1.083529 -0.727958 0.482586 +1.083529 -0.727958 0.043760 +0.467550 0.014509 0.043760 +0.483464 -0.740604 0.043760 +0.483464 -0.740604 0.482586 +0.480767 0.014787 0.482586 +0.467551 0.014509 0.482586 +1.067615 0.027155 0.496737 +1.067615 0.027155 0.935563 +1.083529 -0.727958 0.935563 +1.083529 -0.727958 0.496737 +0.467550 0.014509 0.496737 +0.483464 -0.740604 0.496737 +0.483464 -0.740604 0.935563 +0.480767 0.014787 0.935563 +0.467551 0.014509 0.935563 +0.456349 0.018195 0.043760 +0.456349 0.018195 0.482586 +0.472263 -0.736918 0.482586 +0.472263 -0.736918 0.043760 +-0.143716 0.005549 0.043760 +-0.127802 -0.749564 0.043760 +-0.127802 -0.749564 0.482586 +-0.130499 0.005827 0.482586 +-0.143715 0.005549 0.482586 +0.456349 0.018195 0.496737 +0.456349 0.018195 0.935563 +0.472263 -0.736918 0.935563 +0.472263 -0.736918 0.496737 +-0.143716 0.005549 0.496737 +-0.127802 -0.749564 0.496737 +-0.127802 -0.749564 0.935563 +-0.130499 0.005827 0.935563 +-0.143715 0.005549 0.935563 +0.456349 0.018195 0.952252 +0.456349 0.018195 1.391078 +0.472263 -0.736918 1.391078 +0.472263 -0.736918 0.952252 +-0.143716 0.005549 0.952252 +-0.127802 -0.749564 0.952252 +-0.127802 -0.749564 1.391078 +-0.130499 0.005827 1.391078 +-0.143715 0.005549 1.391078 +0.890204 -0.520833 1.405229 +0.890204 -0.520833 1.844055 +-0.009057 -0.534196 1.844055 +-0.009057 -0.534196 1.405229 +0.875143 -0.016957 1.405229 +-0.024117 -0.030319 1.405229 +-0.024117 -0.030320 1.844055 +0.875475 -0.028055 1.844055 +0.875143 -0.016957 1.844055 +1.051741 0.790819 0.043760 +1.051741 0.790819 0.482586 +1.067655 0.035707 0.482586 +1.067655 0.035707 0.043760 +0.451676 0.778173 0.043760 +0.467589 0.023060 0.043760 +0.467590 0.023060 0.482586 +0.464892 0.778451 0.482586 +0.451676 0.778173 0.482586 +1.051741 0.790819 0.496737 +1.051741 0.790819 0.935563 +1.067655 0.035707 0.935563 +1.067655 0.035707 0.496737 +0.451676 0.778173 0.496737 +0.467589 0.023060 0.496737 +0.467590 0.023060 0.935563 +0.464892 0.778451 0.935563 +0.451676 0.778173 0.935563 +1.051741 0.790819 0.952252 +1.051741 0.790819 1.391078 +1.067655 0.035707 1.391078 +1.067655 0.035707 0.952252 +0.451676 0.778173 0.952252 +0.467589 0.023060 0.952252 +0.467590 0.023060 1.391078 +0.464892 0.778451 1.391078 +0.451676 0.778173 1.391078 +0.440475 0.781860 0.043760 +0.440475 0.781860 0.482586 +0.456388 0.026747 0.482586 +0.456388 0.026747 0.043760 +-0.159590 0.769213 0.043760 +-0.143677 0.014100 0.043760 +-0.143676 0.014100 0.482586 +-0.146374 0.769491 0.482586 +-0.159590 0.769213 0.482586 +0.440475 0.781860 0.496737 +0.440475 0.781860 0.935563 +0.456388 0.026747 0.935563 +0.456388 0.026747 0.496737 +-0.159590 0.769213 0.496737 +-0.143677 0.014100 0.496737 +-0.143676 0.014100 0.935563 +-0.146374 0.769491 0.935563 +-0.159590 0.769213 0.935563 +0.440475 0.781860 0.952252 +0.440475 0.781860 1.391078 +0.456388 0.026747 1.391078 +0.456388 0.026747 0.952252 +-0.159590 0.769213 0.952252 +-0.143677 0.014100 0.952252 +-0.143676 0.014100 1.391078 +-0.146374 0.769491 1.391078 +-0.159590 0.769213 1.391078 +0.279776 0.779504 1.405229 +0.279776 0.779504 1.844055 +0.295690 0.024391 1.844055 +0.295690 0.024391 1.405229 +-0.320289 0.766858 1.405229 +-0.304376 0.011744 1.405229 +-0.304375 0.011744 1.844055 +-0.307073 0.767136 1.844055 +-0.320289 0.766858 1.844055 +-0.169208 0.239461 0.043760 +-0.169208 0.239461 0.482586 +-1.068468 0.226099 0.482586 +-1.068468 0.226099 0.043760 +-0.184268 0.743338 0.043760 +-1.083529 0.729976 0.043760 +-1.083529 0.729975 0.482586 +-0.183937 0.732240 0.482586 +-0.184268 0.743338 0.482586 +-0.169208 0.239461 0.496737 +-0.169208 0.239461 0.935563 +-1.068468 0.226099 0.935563 +-1.068468 0.226099 0.496737 +-0.184268 0.743338 0.496737 +-1.083529 0.729976 0.496737 +-1.083529 0.729975 0.935563 +-0.183937 0.732240 0.935563 +-0.184268 0.743338 0.935563 +-0.169208 0.239461 0.952252 +-0.169208 0.239461 1.391078 +-1.068468 0.226099 1.391078 +-1.068468 0.226099 0.952252 +-0.184268 0.743338 0.952252 +-1.083529 0.729976 0.952252 +-1.083529 0.729975 1.391078 +-0.183937 0.732240 1.391078 +-0.184268 0.743338 1.391078 + + + + + + + + + + + +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +0.999554 0.029877 -0.000000 +0.999554 0.029877 -0.000000 +0.999554 0.029877 -0.000000 +0.999554 0.029877 -0.000000 +0.999554 0.029877 -0.000000 +0.999554 0.029877 -0.000000 +0.999554 0.029877 -0.000000 +0.999554 0.029877 -0.000000 +0.999554 0.029877 -0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 + + + + + + + + + + + +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 + + + + + + + + + + + +

2 0 2 0 1 0 1 2 1 0 3 0 2 4 2 3 5 3 3 6 6 4 7 4 0 8 5 4 9 4 3 10 6 5 11 7 7 12 11 2 13 9 1 14 10 2 15 9 7 16 11 6 17 8 8 18 12 6 19 8 7 20 11 6 21 15 3 22 13 2 23 14 3 24 13 6 25 15 5 26 16 6 27 19 8 28 20 4 29 17 6 30 19 4 31 17 5 32 18 7 33 22 4 34 25 8 35 21 4 36 25 7 37 22 0 38 24 7 39 22 1 40 23 0 41 24 11 42 28 9 43 26 10 44 27 9 45 26 11 46 28 12 47 29 12 48 32 13 49 30 9 50 31 13 51 30 12 52 32 14 53 33 15 54 34 16 55 37 17 56 38 11 57 35 16 58 37 15 59 34 16 60 37 11 61 35 10 62 36 15 63 41 12 64 39 11 65 40 12 66 39 15 67 41 14 68 42 15 69 45 17 70 46 13 71 43 15 72 45 13 73 43 14 74 44 16 75 48 13 76 51 17 77 47 13 78 51 16 79 48 9 80 50 16 81 48 10 82 49 9 83 50 20 84 54 18 85 52 19 86 53 18 87 52 20 88 54 21 89 55 21 90 58 22 91 56 18 92 57 22 93 56 21 94 58 23 95 59 24 96 60 25 97 63 26 98 64 20 99 61 25 100 63 24 101 60 25 102 63 20 103 61 19 104 62 24 105 67 21 106 65 20 107 66 21 108 65 24 109 67 23 110 68 24 111 71 26 112 72 22 113 69 24 114 71 22 115 69 23 116 70 25 117 74 22 118 77 26 119 73 22 120 77 25 121 74 18 122 76 25 123 74 19 124 75 18 125 76 29 126 80 27 127 78 28 128 79 27 129 78 29 130 80 30 131 81 30 132 84 31 133 82 27 134 83 31 135 82 30 136 84 32 137 85 33 138 86 34 139 89 35 140 90 29 141 87 34 142 89 33 143 86 34 144 89 29 145 87 28 146 88 33 147 93 30 148 91 29 149 92 30 150 91 33 151 93 32 152 94 33 153 97 35 154 98 31 155 95 33 156 97 31 157 95 32 158 96 34 159 100 31 160 103 35 161 99 31 162 103 34 163 100 27 164 102 34 165 100 28 166 101 27 167 102 38 168 106 36 169 104 37 170 105 36 171 104 38 172 106 39 173 107 39 174 110 40 175 108 36 176 109 40 177 108 39 178 110 41 179 111 42 180 112 43 181 115 44 182 116 38 183 113 43 184 115 42 185 112 43 186 115 38 187 113 37 188 114 42 189 119 39 190 117 38 191 118 39 192 117 42 193 119 41 194 120 42 195 123 44 196 124 40 197 121 42 198 123 40 199 121 41 200 122 43 201 126 40 202 129 44 203 125 40 204 129 43 205 126 36 206 128 43 207 126 37 208 127 36 209 128 47 210 132 45 211 130 46 212 131 45 213 130 47 214 132 48 215 133 48 216 136 49 217 134 45 218 135 49 219 134 48 220 136 50 221 137 51 222 138 52 223 141 53 224 142 47 225 139 52 226 141 51 227 138 52 228 141 47 229 139 46 230 140 51 231 145 48 232 143 47 233 144 48 234 143 51 235 145 50 236 146 51 237 149 53 238 150 49 239 147 51 240 149 49 241 147 50 242 148 52 243 152 49 244 155 53 245 151 49 246 155 52 247 152 45 248 154 52 249 152 46 250 153 45 251 154 56 252 158 54 253 156 55 254 157 54 255 156 56 256 158 57 257 159 57 258 162 58 259 160 54 260 161 58 261 160 57 262 162 59 263 163 60 264 164 61 265 167 62 266 168 56 267 165 61 268 167 60 269 164 61 270 167 56 271 165 55 272 166 60 273 171 57 274 169 56 275 170 57 276 169 60 277 171 59 278 172 60 279 175 62 280 176 58 281 173 60 282 175 58 283 173 59 284 174 61 285 178 58 286 181 62 287 177 58 288 181 61 289 178 54 290 180 61 291 178 55 292 179 54 293 180 65 294 184 63 295 182 64 296 183 63 297 182 65 298 184 66 299 185 66 300 188 67 301 186 63 302 187 67 303 186 66 304 188 68 305 189 69 306 190 70 307 193 71 308 194 65 309 191 70 310 193 69 311 190 70 312 193 65 313 191 64 314 192 69 315 197 66 316 195 65 317 196 66 318 195 69 319 197 68 320 198 69 321 201 71 322 202 67 323 199 69 324 201 67 325 199 68 326 200 70 327 204 67 328 207 71 329 203 67 330 207 70 331 204 63 332 206 70 333 204 64 334 205 63 335 206 74 336 210 72 337 208 73 338 209 72 339 208 74 340 210 75 341 211 75 342 214 76 343 212 72 344 213 76 345 212 75 346 214 77 347 215 79 348 219 74 349 217 73 350 218 74 351 217 79 352 219 78 353 216 80 354 220 78 355 216 79 356 219 78 357 223 75 358 221 74 359 222 75 360 221 78 361 223 77 362 224 78 363 227 80 364 228 76 365 225 78 366 227 76 367 225 77 368 226 79 369 230 76 370 233 80 371 229 76 372 233 79 373 230 72 374 232 79 375 230 73 376 231 72 377 232 83 378 236 81 379 234 82 380 235 81 381 234 83 382 236 84 383 237 84 384 240 85 385 238 81 386 239 85 387 238 84 388 240 86 389 241 88 390 245 83 391 243 82 392 244 83 393 243 88 394 245 87 395 242 89 396 246 87 397 242 88 398 245 87 399 249 84 400 247 83 401 248 84 402 247 87 403 249 86 404 250 87 405 253 89 406 254 85 407 251 87 408 253 85 409 251 86 410 252 88 411 256 85 412 259 89 413 255 85 414 259 88 415 256 81 416 258 88 417 256 82 418 257 81 419 258 92 420 262 90 421 260 91 422 261 90 423 260 92 424 262 93 425 263 93 426 266 94 427 264 90 428 265 94 429 264 93 430 266 95 431 267 97 432 271 92 433 269 91 434 270 92 435 269 97 436 271 96 437 268 98 438 272 96 439 268 97 440 271 96 441 275 93 442 273 92 443 274 93 444 273 96 445 275 95 446 276 96 447 279 98 448 280 94 449 277 96 450 279 94 451 277 95 452 278 97 453 282 94 454 285 98 455 281 94 456 285 97 457 282 90 458 284 97 459 282 91 460 283 90 461 284 101 462 288 99 463 286 100 464 287 99 465 286 101 466 288 102 467 289 102 468 292 103 469 290 99 470 291 103 471 290 102 472 292 104 473 293 106 474 297 101 475 295 100 476 296 101 477 295 106 478 297 105 479 294 107 480 298 105 481 294 106 482 297 105 483 301 102 484 299 101 485 300 102 486 299 105 487 301 104 488 302 105 489 305 107 490 306 103 491 303 105 492 305 103 493 303 104 494 304 106 495 308 103 496 311 107 497 307 103 498 311 106 499 308 99 500 310 106 501 308 100 502 309 99 503 310 110 504 314 108 505 312 109 506 313 108 507 312 110 508 314 111 509 315 111 510 318 112 511 316 108 512 317 112 513 316 111 514 318 113 515 319 115 516 323 110 517 321 109 518 322 110 519 321 115 520 323 114 521 320 116 522 324 114 523 320 115 524 323 114 525 327 111 526 325 110 527 326 111 528 325 114 529 327 113 530 328 114 531 331 116 532 332 112 533 329 114 534 331 112 535 329 113 536 330 115 537 334 112 538 337 116 539 333 112 540 337 115 541 334 108 542 336 115 543 334 109 544 335 108 545 336 119 546 340 117 547 338 118 548 339 117 549 338 119 550 340 120 551 341 120 552 344 121 553 342 117 554 343 121 555 342 120 556 344 122 557 345 123 558 346 124 559 349 125 560 350 119 561 347 124 562 349 123 563 346 124 564 349 119 565 347 118 566 348 123 567 353 120 568 351 119 569 352 120 570 351 123 571 353 122 572 354 123 573 357 125 574 358 121 575 355 123 576 357 121 577 355 122 578 356 124 579 360 121 580 363 125 581 359 121 582 363 124 583 360 117 584 362 124 585 360 118 586 361 117 587 362 128 588 366 126 589 364 127 590 365 126 591 364 128 592 366 129 593 367 129 594 370 130 595 368 126 596 369 130 597 368 129 598 370 131 599 371 133 600 375 128 601 373 127 602 374 128 603 373 133 604 375 132 605 372 134 606 376 132 607 372 133 608 375 132 609 379 129 610 377 128 611 378 129 612 377 132 613 379 131 614 380 132 615 383 134 616 384 130 617 381 132 618 383 130 619 381 131 620 382 133 621 386 130 622 389 134 623 385 130 624 389 133 625 386 126 626 388 133 627 386 127 628 387 126 629 388 137 630 392 135 631 390 136 632 391 135 633 390 137 634 392 138 635 393 138 636 396 139 637 394 135 638 395 139 639 394 138 640 396 140 641 397 142 642 401 137 643 399 136 644 400 137 645 399 142 646 401 141 647 398 143 648 402 141 649 398 142 650 401 141 651 405 138 652 403 137 653 404 138 654 403 141 655 405 140 656 406 141 657 409 143 658 410 139 659 407 141 660 409 139 661 407 140 662 408 142 663 412 139 664 415 143 665 411 139 666 415 142 667 412 135 668 414 142 669 412 136 670 413 135 671 414 146 672 418 144 673 416 145 674 417 144 675 416 146 676 418 147 677 419 147 678 422 148 679 420 144 680 421 148 681 420 147 682 422 149 683 423 151 684 427 146 685 425 145 686 426 146 687 425 151 688 427 150 689 424 152 690 428 150 691 424 151 692 427 150 693 431 147 694 429 146 695 430 147 696 429 150 697 431 149 698 432 150 699 435 152 700 436 148 701 433 150 702 435 148 703 433 149 704 434 151 705 438 148 706 441 152 707 437 148 708 441 151 709 438 144 710 440 151 711 438 145 712 439 144 713 440 155 714 444 153 715 442 154 716 443 153 717 442 155 718 444 156 719 445 156 720 448 157 721 446 153 722 447 157 723 446 156 724 448 158 725 449 160 726 453 155 727 451 154 728 452 155 729 451 160 730 453 159 731 450 161 732 454 159 733 450 160 734 453 159 735 457 156 736 455 155 737 456 156 738 455 159 739 457 158 740 458 159 741 461 161 742 462 157 743 459 159 744 461 157 745 459 158 746 460 160 747 464 157 748 467 161 749 463 157 750 467 160 751 464 153 752 466 160 753 464 154 754 465 153 755 466 164 756 470 162 757 468 163 758 469 162 759 468 164 760 470 165 761 471 165 762 474 166 763 472 162 764 473 166 765 472 165 766 474 167 767 475 169 768 479 164 769 477 163 770 478 164 771 477 169 772 479 168 773 476 170 774 480 168 775 476 169 776 479 168 777 483 165 778 481 164 779 482 165 780 481 168 781 483 167 782 484 168 783 487 170 784 488 166 785 485 168 786 487 166 787 485 167 788 486 169 789 490 166 790 493 170 791 489 166 792 493 169 793 490 162 794 492 169 795 490 163 796 491 162 797 492 173 798 496 171 799 494 172 800 495 171 801 494 173 802 496 174 803 497 174 804 500 175 805 498 171 806 499 175 807 498 174 808 500 176 809 501 178 810 505 173 811 503 172 812 504 173 813 503 178 814 505 177 815 502 179 816 506 177 817 502 178 818 505 177 819 509 174 820 507 173 821 508 174 822 507 177 823 509 176 824 510 177 825 513 179 826 514 175 827 511 177 828 513 175 829 511 176 830 512 178 831 516 175 832 519 179 833 515 175 834 519 178 835 516 171 836 518 178 837 516 172 838 517 171 839 518 182 840 522 180 841 520 181 842 521 180 843 520 182 844 522 183 845 523 183 846 526 184 847 524 180 848 525 184 849 524 183 850 526 185 851 527 187 852 531 182 853 529 181 854 530 182 855 529 187 856 531 186 857 528 188 858 532 186 859 528 187 860 531 186 861 535 183 862 533 182 863 534 183 864 533 186 865 535 185 866 536 186 867 539 188 868 540 184 869 537 186 870 539 184 871 537 185 872 538 187 873 542 184 874 545 188 875 541 184 876 545 187 877 542 180 878 544 187 879 542 181 880 543 180 881 544 191 882 548 189 883 546 190 884 547 189 885 546 191 886 548 192 887 549 192 888 552 193 889 550 189 890 551 193 891 550 192 892 552 194 893 553 195 894 554 196 895 557 197 896 558 191 897 555 196 898 557 195 899 554 196 900 557 191 901 555 190 902 556 195 903 561 192 904 559 191 905 560 192 906 559 195 907 561 194 908 562 195 909 565 197 910 566 193 911 563 195 912 565 193 913 563 194 914 564 196 915 568 193 916 571 197 917 567 193 918 571 196 919 568 189 920 570 196 921 568 190 922 569 189 923 570 200 924 574 198 925 572 199 926 573 198 927 572 200 928 574 201 929 575 201 930 578 202 931 576 198 932 577 202 933 576 201 934 578 203 935 579 204 936 580 205 937 583 206 938 584 200 939 581 205 940 583 204 941 580 205 942 583 200 943 581 199 944 582 204 945 587 201 946 585 200 947 586 201 948 585 204 949 587 203 950 588 204 951 591 206 952 592 202 953 589 204 954 591 202 955 589 203 956 590 205 957 594 202 958 597 206 959 593 202 960 597 205 961 594 198 962 596 205 963 594 199 964 595 198 965 596 209 966 600 207 967 598 208 968 599 207 969 598 209 970 600 210 971 601 210 972 604 211 973 602 207 974 603 211 975 602 210 976 604 212 977 605 213 978 606 214 979 609 215 980 610 209 981 607 214 982 609 213 983 606 214 984 609 209 985 607 208 986 608 213 987 613 210 988 611 209 989 612 210 990 611 213 991 613 212 992 614 213 993 617 215 994 618 211 995 615 213 996 617 211 997 615 212 998 616 214 999 620 211 1000 623 215 1001 619 211 1002 623 214 1003 620 207 1004 622 214 1005 620 208 1006 621 207 1007 622

+

+

+
+
+
+ + + 1.672138 -114.084068 0.000000 0.000000 95.796867 1.991342 0.000000 0.000000 0.000000 0.000000 95.811455 0.000000 0.000000 0.000000 0.000000 1.0000001.000000 + 30.0000000.0000003.333333 + + + + + +
diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ClutteringC_01/model.config b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ClutteringC_01/model.config new file mode 100755 index 0000000..b842e6c --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ClutteringC_01/model.config @@ -0,0 +1,11 @@ + + + aws_robomaker_warehouse_ClutteringC_01 + 1.0 + model.sdf + + + + + + diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ClutteringC_01/model.sdf b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ClutteringC_01/model.sdf new file mode 100755 index 0000000..334a416 --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ClutteringC_01/model.sdf @@ -0,0 +1,55 @@ + + + + + + 1 + + 1.558 + 0 + 0 + 1.821 + 0 + 1.892 + + + + + + model://aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + model://aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_visual.DAE + + + 1 + + + 1 + + diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ClutteringD_01/materials/textures/aws_robomaker_warehouse_ClutteringD_01.png b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ClutteringD_01/materials/textures/aws_robomaker_warehouse_ClutteringD_01.png new file mode 100755 index 0000000..b28b289 Binary files /dev/null and b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ClutteringD_01/materials/textures/aws_robomaker_warehouse_ClutteringD_01.png differ diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ClutteringD_01/materials/textures/aws_robomaker_warehouse_ClutteringD_02.png b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ClutteringD_01/materials/textures/aws_robomaker_warehouse_ClutteringD_02.png new file mode 100755 index 0000000..4b7e610 Binary files /dev/null and b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ClutteringD_01/materials/textures/aws_robomaker_warehouse_ClutteringD_02.png differ diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ClutteringD_01/meshes/aws_robomaker_warehouse_ClutteringD_01_collision.DAE b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ClutteringD_01/meshes/aws_robomaker_warehouse_ClutteringD_01_collision.DAE new file mode 100755 index 0000000..08d4955 --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ClutteringD_01/meshes/aws_robomaker_warehouse_ClutteringD_01_collision.DAE @@ -0,0 +1,123 @@ + + + FBX COLLADA exporter2019-03-25T05:42:49Z2019-03-25T05:42:49ZZ_UP + + + + + +-50.844025 33.298004 -76.084843 +50.844025 33.298004 -76.084843 +-50.844025 182.463806 -76.084846 +50.844025 182.463806 -76.084846 +-50.844025 33.298012 76.084789 +50.844025 33.298012 76.084789 +-50.844025 182.463806 76.084789 +50.844025 182.463806 76.084789 + + + + + + + + + + + +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 + + + + + + + + + + + +1.000000 0.000000 +0.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 + + + + + + + + + + + +

1 0 1 0 1 0 3 2 3 0 3 0 2 4 2 3 5 3 7 6 7 6 7 6 4 8 4 7 9 7 4 10 4 5 11 5 5 12 11 4 13 10 0 14 8 5 15 11 0 16 8 1 17 9 5 18 14 3 19 13 7 20 15 3 21 13 5 22 14 1 23 12 6 24 19 7 25 18 3 26 16 6 27 19 3 28 16 2 29 17 4 30 23 6 31 22 2 32 20 4 33 23 2 34 20 0 35 21

+
+
+
+ + + 1.000000 0.000000 0.000000 0.000000 0.000000 -0.000000 -1.000000 0.000000 0.000000 1.000000 -0.000000 0.000000 0.000000 0.000000 0.000000 1.0000001.000000 + 30.0000000.0000003.333333 + + + + + +
diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ClutteringD_01/meshes/aws_robomaker_warehouse_ClutteringD_01_visual.DAE b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ClutteringD_01/meshes/aws_robomaker_warehouse_ClutteringD_01_visual.DAE new file mode 100755 index 0000000..5d51ad6 --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ClutteringD_01/meshes/aws_robomaker_warehouse_ClutteringD_01_visual.DAE @@ -0,0 +1,1420 @@ + + + FBX COLLADA exporter2019-03-25T05:43:02Z2019-03-25T05:43:02ZZ_UP + + + ../materials/textures/aws_robomaker_warehouse_ClutteringD_01.png + + + + + + + + + + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + +0.009253 -0.503716 0.419458 +0.009253 -0.503716 0.858284 +-0.890007 -0.517079 0.858284 +-0.890007 -0.517079 0.419458 +-0.005807 0.000161 0.419458 +-0.905068 -0.013201 0.419458 +-0.905068 -0.013202 0.858284 +-0.005476 -0.010937 0.858284 +-0.005807 0.000161 0.858284 +0.009254 -0.503716 0.865917 +0.009254 -0.503716 1.304744 +-0.890007 -0.517079 1.304744 +-0.890007 -0.517079 0.865917 +-0.005806 0.000160 0.865917 +-0.905068 -0.013202 0.865917 +-0.905068 -0.013202 1.304744 +-0.005475 -0.010937 1.304744 +-0.005806 0.000160 1.304744 +0.009255 -0.503716 1.310472 +0.009255 -0.503716 1.749298 +-0.890006 -0.517080 1.749298 +-0.890006 -0.517080 1.310472 +-0.005805 0.000160 1.310472 +-0.905068 -0.013202 1.310472 +-0.905067 -0.013203 1.749298 +-0.005474 -0.010937 1.749298 +-0.005805 0.000160 1.749298 +-0.001216 -0.000079 0.419458 +-0.001216 -0.000079 0.858284 +-0.900477 -0.013442 0.858284 +-0.900477 -0.013442 0.419458 +-0.016277 0.503797 0.419458 +-0.915537 0.490435 0.419458 +-0.915537 0.490434 0.858284 +-0.015945 0.492699 0.858284 +-0.016277 0.503797 0.858284 +-0.001215 -0.000080 0.865917 +-0.001215 -0.000080 1.304744 +-0.900476 -0.013443 1.304744 +-0.900476 -0.013443 0.865917 +-0.016275 0.503797 0.865917 +-0.915536 0.490434 0.865917 +-0.915536 0.490434 1.304744 +-0.015945 0.492699 1.304744 +-0.016275 0.503797 1.304744 +-0.001215 -0.000080 1.310472 +-0.001215 -0.000080 1.749298 +-0.900475 -0.013443 1.749298 +-0.900475 -0.013443 1.310472 +-0.016274 0.503797 1.310472 +-0.915535 0.490434 1.310472 +-0.915535 0.490433 1.749298 +-0.015944 0.492698 1.749298 +-0.016274 0.503797 1.749298 +0.915534 -0.490433 0.419458 +0.915534 -0.490433 0.858284 +0.016273 -0.503795 0.858284 +0.016273 -0.503795 0.419458 +0.900473 0.013444 0.419458 +0.001212 0.000082 0.419458 +0.001212 0.000081 0.858284 +0.900805 0.002347 0.858284 +0.900473 0.013444 0.858284 +0.915534 -0.490433 0.865917 +0.915534 -0.490433 1.304744 +0.016273 -0.503796 1.304744 +0.016273 -0.503796 0.865917 +0.900474 0.013444 0.865917 +0.001213 0.000081 0.865917 +0.001213 0.000081 1.304744 +0.900805 0.002346 1.304744 +0.900474 0.013444 1.304744 +0.915535 -0.490433 1.310472 +0.915535 -0.490433 1.749298 +0.016273 -0.503796 1.749298 +0.016273 -0.503796 1.310472 +0.900475 0.013444 1.310472 +0.001214 0.000081 1.310472 +0.001214 0.000081 1.749298 +0.900805 0.002346 1.749298 +0.900475 0.013444 1.749298 +0.905064 0.013204 0.419458 +0.905064 0.013204 0.858284 +0.005803 -0.000159 0.858284 +0.005803 -0.000159 0.419458 +0.890004 0.517081 0.419458 +-0.009257 0.503718 0.419458 +-0.009257 0.503717 0.858284 +0.890335 0.505983 0.858284 +0.890004 0.517081 0.858284 +0.905065 0.013204 0.865917 +0.905065 0.013204 1.304744 +0.005805 -0.000159 1.304744 +0.005805 -0.000159 0.865917 +0.890006 0.517080 0.865917 +-0.009256 0.503718 0.865917 +-0.009256 0.503717 1.304744 +0.890336 0.505982 1.304744 +0.890006 0.517080 1.304744 +0.905066 0.013204 1.310472 +0.905066 0.013204 1.749298 +0.005805 -0.000160 1.749298 +0.005805 -0.000160 1.310472 +0.890006 0.517080 1.310472 +-0.009255 0.503717 1.310472 +-0.009255 0.503716 1.749298 +0.890336 0.505982 1.749298 +0.890006 0.517080 1.749298 +0.009256 -0.503717 1.758337 +0.009256 -0.503717 2.197164 +-0.890004 -0.517080 2.197164 +-0.890004 -0.517080 1.758337 +-0.005803 0.000160 1.758337 +-0.905068 -0.013203 1.758337 +-0.905065 -0.013203 2.197164 +-0.005473 -0.010938 2.197164 +-0.005803 0.000160 2.197164 +-0.001214 -0.000080 1.758337 +-0.001214 -0.000080 2.197164 +-0.900473 -0.013444 2.197164 +-0.900473 -0.013444 1.758337 +-0.016271 0.503796 1.758337 +-0.915534 0.490433 1.758337 +-0.915534 0.490433 2.197164 +-0.015943 0.492697 2.197164 +-0.016271 0.503796 2.197164 +0.915537 -0.490433 1.758337 +0.915537 -0.490433 2.197164 +0.016273 -0.503797 2.197164 +0.016273 -0.503797 1.758337 +0.900476 0.013443 1.758337 +0.001215 0.000080 1.758337 +0.001215 0.000080 2.197164 +0.900805 0.002345 2.197164 +0.900476 0.013443 2.197164 +0.905067 0.013203 1.758337 +0.905067 0.013203 2.197164 +0.005807 -0.000160 2.197164 +0.005807 -0.000160 1.758337 +0.890007 0.517079 1.758337 +-0.009254 0.503716 1.758337 +-0.009254 0.503716 2.197164 +0.890337 0.505981 2.197164 +0.890007 0.517079 2.197164 + + + + + + + + + + + +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029878 -0.000000 +-0.999554 -0.029878 -0.000000 +-0.999554 -0.029878 -0.000000 +-0.999554 -0.029878 -0.000000 +-0.999554 -0.029878 -0.000000 +-0.999554 -0.029878 -0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029879 0.000001 +-0.999554 -0.029879 0.000001 +-0.999554 -0.029879 0.000001 +-0.999554 -0.029879 0.000001 +-0.999554 -0.029879 0.000001 +-0.999554 -0.029879 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.014859 -0.999890 0.000000 +0.014859 -0.999890 0.000000 +0.014859 -0.999890 0.000000 +0.014859 -0.999890 0.000000 +0.014859 -0.999890 0.000000 +0.014859 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029877 -0.000000 +-0.999554 -0.029877 -0.000000 +-0.999554 -0.029877 -0.000000 +-0.999554 -0.029877 -0.000000 +-0.999554 -0.029877 -0.000000 +-0.999554 -0.029877 -0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029875 -0.000000 +-0.999554 -0.029875 -0.000000 +-0.999554 -0.029875 -0.000000 +-0.999554 -0.029875 -0.000000 +-0.999554 -0.029875 -0.000000 +-0.999554 -0.029875 -0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +0.999554 0.029877 0.000001 +0.999554 0.029877 0.000001 +0.999554 0.029877 0.000001 +0.999554 0.029877 0.000001 +0.999554 0.029877 0.000001 +0.999554 0.029877 0.000001 +0.999554 0.029877 0.000001 +0.999554 0.029877 0.000001 +0.999554 0.029877 0.000001 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029875 -0.000000 +-0.999554 -0.029875 -0.000000 +-0.999554 -0.029875 -0.000000 +-0.999554 -0.029875 -0.000000 +-0.999554 -0.029875 -0.000000 +-0.999554 -0.029875 -0.000000 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029877 -0.000000 +-0.999554 -0.029877 -0.000000 +-0.999554 -0.029877 -0.000000 +-0.999554 -0.029877 -0.000000 +-0.999554 -0.029877 -0.000000 +-0.999554 -0.029877 -0.000000 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029877 -0.000000 +-0.999554 -0.029877 -0.000000 +-0.999554 -0.029877 -0.000000 +-0.999554 -0.029877 -0.000000 +-0.999554 -0.029877 -0.000000 +-0.999554 -0.029877 -0.000000 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +0.999554 0.029874 0.000002 +0.999554 0.029874 0.000002 +0.999554 0.029874 0.000002 +0.999554 0.029874 0.000002 +0.999554 0.029874 0.000002 +0.999554 0.029874 0.000002 +0.999554 0.029874 0.000002 +0.999554 0.029874 0.000002 +0.999554 0.029874 0.000002 +0.014859 -0.999890 0.000000 +0.014859 -0.999890 0.000000 +0.014859 -0.999890 0.000000 +0.014859 -0.999890 0.000000 +0.014859 -0.999890 0.000000 +0.014859 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029880 0.000003 +-0.999553 -0.029880 0.000003 +-0.999553 -0.029880 0.000003 +-0.999553 -0.029880 0.000003 +-0.999553 -0.029880 0.000003 +-0.999553 -0.029880 0.000003 +-0.014858 0.999890 -0.000000 +-0.014858 0.999890 -0.000000 +-0.014858 0.999890 -0.000000 +-0.014858 0.999890 -0.000000 +-0.014858 0.999890 -0.000000 +-0.014858 0.999890 -0.000000 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.014859 -0.999890 0.000000 +0.014859 -0.999890 0.000000 +0.014859 -0.999890 0.000000 +0.014859 -0.999890 0.000000 +0.014859 -0.999890 0.000000 +0.014859 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +0.999554 0.029870 0.000004 +0.999554 0.029870 0.000004 +0.999554 0.029870 0.000004 +0.999554 0.029870 0.000004 +0.999554 0.029870 0.000004 +0.999554 0.029870 0.000004 +0.999554 0.029870 0.000004 +0.999554 0.029870 0.000004 +0.999554 0.029870 0.000004 +0.014859 -0.999890 0.000000 +0.014859 -0.999890 0.000000 +0.014859 -0.999890 0.000000 +0.014859 -0.999890 0.000000 +0.014859 -0.999890 0.000000 +0.014859 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029872 -0.000000 +-0.999554 -0.029872 -0.000000 +-0.999554 -0.029872 -0.000000 +-0.999554 -0.029872 -0.000000 +-0.999554 -0.029872 -0.000000 +-0.999554 -0.029872 -0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +0.999554 0.029877 0.000003 +0.999554 0.029877 0.000003 +0.999554 0.029877 0.000003 +0.999554 0.029877 0.000003 +0.999554 0.029877 0.000003 +0.999554 0.029877 0.000003 +0.999554 0.029877 0.000003 +0.999554 0.029877 0.000003 +0.999554 0.029877 0.000003 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029877 -0.000000 +-0.999554 -0.029877 -0.000000 +-0.999554 -0.029877 -0.000000 +-0.999554 -0.029877 -0.000000 +-0.999554 -0.029877 -0.000000 +-0.999554 -0.029877 -0.000000 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +0.999554 0.029874 0.000002 +0.999554 0.029874 0.000002 +0.999554 0.029874 0.000002 +0.999554 0.029874 0.000002 +0.999554 0.029874 0.000002 +0.999554 0.029874 0.000002 +0.999554 0.029874 0.000002 +0.999554 0.029874 0.000002 +0.999554 0.029874 0.000002 + + + + + + + + + + + +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 + + + + + + + + + + + +

2 0 2 0 1 0 1 2 1 0 3 0 2 4 2 3 5 3 3 6 6 4 7 4 0 8 5 4 9 4 3 10 6 5 11 7 6 12 8 7 13 11 8 14 12 2 15 9 7 16 11 6 17 8 7 18 11 2 19 9 1 20 10 6 21 15 3 22 13 2 23 14 3 24 13 6 25 15 5 26 16 6 27 19 8 28 20 4 29 17 6 30 19 4 31 17 5 32 18 7 33 22 4 34 25 8 35 21 4 36 25 7 37 22 0 38 24 7 39 22 1 40 23 0 41 24 11 42 28 9 43 26 10 44 27 9 45 26 11 46 28 12 47 29 12 48 32 13 49 30 9 50 31 13 51 30 12 52 32 14 53 33 15 54 34 16 55 37 17 56 38 11 57 35 16 58 37 15 59 34 16 60 37 11 61 35 10 62 36 15 63 41 12 64 39 11 65 40 12 66 39 15 67 41 14 68 42 15 69 45 17 70 46 13 71 43 15 72 45 13 73 43 14 74 44 16 75 48 13 76 51 17 77 47 13 78 51 16 79 48 9 80 50 16 81 48 10 82 49 9 83 50 20 84 54 18 85 52 19 86 53 18 87 52 20 88 54 21 89 55 21 90 58 22 91 56 18 92 57 22 93 56 21 94 58 23 95 59 24 96 60 25 97 63 26 98 64 20 99 61 25 100 63 24 101 60 25 102 63 20 103 61 19 104 62 24 105 67 21 106 65 20 107 66 21 108 65 24 109 67 23 110 68 24 111 71 26 112 72 22 113 69 24 114 71 22 115 69 23 116 70 25 117 74 22 118 77 26 119 73 22 120 77 25 121 74 18 122 76 25 123 74 19 124 75 18 125 76 29 126 80 27 127 78 28 128 79 27 129 78 29 130 80 30 131 81 30 132 84 31 133 82 27 134 83 31 135 82 30 136 84 32 137 85 33 138 86 34 139 89 35 140 90 29 141 87 34 142 89 33 143 86 34 144 89 29 145 87 28 146 88 33 147 93 30 148 91 29 149 92 30 150 91 33 151 93 32 152 94 33 153 97 35 154 98 31 155 95 33 156 97 31 157 95 32 158 96 34 159 100 31 160 103 35 161 99 31 162 103 34 163 100 27 164 102 34 165 100 28 166 101 27 167 102 38 168 106 36 169 104 37 170 105 36 171 104 38 172 106 39 173 107 39 174 110 40 175 108 36 176 109 40 177 108 39 178 110 41 179 111 42 180 112 43 181 115 44 182 116 38 183 113 43 184 115 42 185 112 43 186 115 38 187 113 37 188 114 42 189 119 39 190 117 38 191 118 39 192 117 42 193 119 41 194 120 42 195 123 44 196 124 40 197 121 42 198 123 40 199 121 41 200 122 43 201 126 40 202 129 44 203 125 40 204 129 43 205 126 36 206 128 43 207 126 37 208 127 36 209 128 47 210 132 45 211 130 46 212 131 45 213 130 47 214 132 48 215 133 48 216 136 49 217 134 45 218 135 49 219 134 48 220 136 50 221 137 51 222 138 52 223 141 53 224 142 47 225 139 52 226 141 51 227 138 52 228 141 47 229 139 46 230 140 51 231 145 48 232 143 47 233 144 48 234 143 51 235 145 50 236 146 51 237 149 53 238 150 49 239 147 51 240 149 49 241 147 50 242 148 52 243 152 49 244 155 53 245 151 49 246 155 52 247 152 45 248 154 52 249 152 46 250 153 45 251 154 56 252 158 54 253 156 55 254 157 54 255 156 56 256 158 57 257 159 57 258 162 58 259 160 54 260 161 58 261 160 57 262 162 59 263 163 60 264 164 61 265 167 62 266 168 56 267 165 61 268 167 60 269 164 61 270 167 56 271 165 55 272 166 60 273 171 57 274 169 56 275 170 57 276 169 60 277 171 59 278 172 60 279 175 62 280 176 58 281 173 60 282 175 58 283 173 59 284 174 61 285 178 58 286 181 62 287 177 58 288 181 61 289 178 54 290 180 61 291 178 55 292 179 54 293 180 65 294 184 63 295 182 64 296 183 63 297 182 65 298 184 66 299 185 66 300 188 67 301 186 63 302 187 67 303 186 66 304 188 68 305 189 69 306 190 70 307 193 71 308 194 65 309 191 70 310 193 69 311 190 70 312 193 65 313 191 64 314 192 69 315 197 66 316 195 65 317 196 66 318 195 69 319 197 68 320 198 69 321 201 71 322 202 67 323 199 69 324 201 67 325 199 68 326 200 70 327 204 67 328 207 71 329 203 67 330 207 70 331 204 63 332 206 70 333 204 64 334 205 63 335 206 74 336 210 72 337 208 73 338 209 72 339 208 74 340 210 75 341 211 75 342 214 76 343 212 72 344 213 76 345 212 75 346 214 77 347 215 78 348 216 79 349 219 80 350 220 74 351 217 79 352 219 78 353 216 79 354 219 74 355 217 73 356 218 78 357 223 75 358 221 74 359 222 75 360 221 78 361 223 77 362 224 78 363 227 80 364 228 76 365 225 78 366 227 76 367 225 77 368 226 79 369 230 76 370 233 80 371 229 76 372 233 79 373 230 72 374 232 79 375 230 73 376 231 72 377 232 83 378 236 81 379 234 82 380 235 81 381 234 83 382 236 84 383 237 84 384 240 85 385 238 81 386 239 85 387 238 84 388 240 86 389 241 87 390 242 88 391 245 89 392 246 83 393 243 88 394 245 87 395 242 88 396 245 83 397 243 82 398 244 87 399 249 84 400 247 83 401 248 84 402 247 87 403 249 86 404 250 87 405 253 89 406 254 85 407 251 87 408 253 85 409 251 86 410 252 88 411 256 85 412 259 89 413 255 85 414 259 88 415 256 81 416 258 88 417 256 82 418 257 81 419 258 92 420 262 90 421 260 91 422 261 90 423 260 92 424 262 93 425 263 93 426 266 94 427 264 90 428 265 94 429 264 93 430 266 95 431 267 96 432 268 97 433 271 98 434 272 92 435 269 97 436 271 96 437 268 97 438 271 92 439 269 91 440 270 96 441 275 93 442 273 92 443 274 93 444 273 96 445 275 95 446 276 96 447 279 98 448 280 94 449 277 96 450 279 94 451 277 95 452 278 97 453 282 94 454 285 98 455 281 94 456 285 97 457 282 90 458 284 97 459 282 91 460 283 90 461 284 101 462 288 99 463 286 100 464 287 99 465 286 101 466 288 102 467 289 102 468 292 103 469 290 99 470 291 103 471 290 102 472 292 104 473 293 105 474 294 106 475 297 107 476 298 101 477 295 106 478 297 105 479 294 106 480 297 101 481 295 100 482 296 105 483 301 102 484 299 101 485 300 102 486 299 105 487 301 104 488 302 105 489 305 107 490 306 103 491 303 105 492 305 103 493 303 104 494 304 106 495 308 103 496 311 107 497 307 103 498 311 106 499 308 99 500 310 106 501 308 100 502 309 99 503 310 110 504 314 108 505 312 109 506 313 108 507 312 110 508 314 111 509 315 111 510 318 112 511 316 108 512 317 112 513 316 111 514 318 113 515 319 114 516 320 115 517 323 116 518 324 110 519 321 115 520 323 114 521 320 115 522 323 110 523 321 109 524 322 114 525 327 113 526 328 110 527 326 110 528 326 113 529 328 111 530 325 114 531 331 116 532 332 112 533 329 114 534 331 112 535 329 113 536 330 115 537 334 112 538 337 116 539 333 112 540 337 115 541 334 108 542 336 115 543 334 109 544 335 108 545 336 119 546 340 117 547 338 118 548 339 117 549 338 119 550 340 120 551 341 120 552 344 121 553 342 117 554 343 121 555 342 120 556 344 122 557 345 123 558 346 124 559 349 125 560 350 119 561 347 124 562 349 123 563 346 124 564 349 119 565 347 118 566 348 123 567 353 120 568 351 119 569 352 120 570 351 123 571 353 122 572 354 123 573 357 125 574 358 121 575 355 123 576 357 121 577 355 122 578 356 124 579 360 121 580 363 125 581 359 121 582 363 124 583 360 117 584 362 124 585 360 118 586 361 117 587 362 128 588 366 126 589 364 127 590 365 126 591 364 128 592 366 129 593 367 129 594 370 130 595 368 126 596 369 130 597 368 129 598 370 131 599 371 132 600 372 133 601 375 134 602 376 128 603 373 133 604 375 132 605 372 133 606 375 128 607 373 127 608 374 132 609 379 129 610 377 128 611 378 129 612 377 132 613 379 131 614 380 132 615 383 134 616 384 130 617 381 132 618 383 130 619 381 131 620 382 133 621 386 130 622 389 134 623 385 130 624 389 133 625 386 126 626 388 133 627 386 127 628 387 126 629 388 137 630 392 135 631 390 136 632 391 135 633 390 137 634 392 138 635 393 138 636 396 139 637 394 135 638 395 139 639 394 138 640 396 140 641 397 141 642 398 142 643 401 143 644 402 137 645 399 142 646 401 141 647 398 142 648 401 137 649 399 136 650 400 141 651 405 138 652 403 137 653 404 138 654 403 141 655 405 140 656 406 141 657 409 143 658 410 139 659 407 141 660 409 139 661 407 140 662 408 142 663 412 139 664 415 143 665 411 139 666 415 142 667 412 135 668 414 142 669 412 136 670 413 135 671 414

+

+

+
+
+
+ + + 1.447990 -98.791206 0.000000 0.000000 82.955384 1.724405 0.000000 0.000000 0.000000 0.000000 82.968018 0.000000 0.000000 0.000000 0.000000 1.0000001.000000 + 30.0000000.0000003.333333 + + + + + +
diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ClutteringD_01/model.config b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ClutteringD_01/model.config new file mode 100755 index 0000000..870fdd2 --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ClutteringD_01/model.config @@ -0,0 +1,11 @@ + + + aws_robomaker_warehouse_ClutteringD_01 + 1.0 + model.sdf + + + + + + diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ClutteringD_01/model.sdf b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ClutteringD_01/model.sdf new file mode 100755 index 0000000..51ac2cd --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ClutteringD_01/model.sdf @@ -0,0 +1,55 @@ + + + + + + 1 + + 1.558 + 0 + 0 + 1.821 + 0 + 1.892 + + + + + + model://aws_robomaker_warehouse_ClutteringD_01/meshes/aws_robomaker_warehouse_ClutteringD_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + model://aws_robomaker_warehouse_ClutteringD_01/meshes/aws_robomaker_warehouse_ClutteringD_01_visual.DAE + + + 1 + + +1 + + diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_DeskC_01/materials/textures/aws_robomaker_warehouse_DeskC_01.png b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_DeskC_01/materials/textures/aws_robomaker_warehouse_DeskC_01.png new file mode 100755 index 0000000..c4550df Binary files /dev/null and b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_DeskC_01/materials/textures/aws_robomaker_warehouse_DeskC_01.png differ diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_DeskC_01/materials/textures/aws_robomaker_warehouse_DeskC_02.png b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_DeskC_01/materials/textures/aws_robomaker_warehouse_DeskC_02.png new file mode 100755 index 0000000..b28b289 Binary files /dev/null and b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_DeskC_01/materials/textures/aws_robomaker_warehouse_DeskC_02.png differ diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_DeskC_01/materials/textures/aws_robomaker_warehouse_DeskC_03.png b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_DeskC_01/materials/textures/aws_robomaker_warehouse_DeskC_03.png new file mode 100755 index 0000000..4b7e610 Binary files /dev/null and b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_DeskC_01/materials/textures/aws_robomaker_warehouse_DeskC_03.png differ diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_DeskC_01/materials/textures/aws_robomaker_warehouse_DeskC_03.psd b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_DeskC_01/materials/textures/aws_robomaker_warehouse_DeskC_03.psd new file mode 100755 index 0000000..aa1d82a Binary files /dev/null and b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_DeskC_01/materials/textures/aws_robomaker_warehouse_DeskC_03.psd differ diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_DeskC_01/materials/textures/aws_robomaker_warehouse_DeskC_04.png b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_DeskC_01/materials/textures/aws_robomaker_warehouse_DeskC_04.png new file mode 100755 index 0000000..b9b6716 Binary files /dev/null and b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_DeskC_01/materials/textures/aws_robomaker_warehouse_DeskC_04.png differ diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_DeskC_01/meshes/aws_robomaker_warehouse_DeskC_01_collision.DAE b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_DeskC_01/meshes/aws_robomaker_warehouse_DeskC_01_collision.DAE new file mode 100755 index 0000000..1981666 --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_DeskC_01/meshes/aws_robomaker_warehouse_DeskC_01_collision.DAE @@ -0,0 +1,1224 @@ + + + FBX COLLADA exporter2019-05-15T10:12:35Z2019-05-15T10:12:35ZZ_UP + + file://C:\Users\Administrator\Desktop\Amazon1\aws_Desk_01\materials\textures\aws_Desk_01.png + + + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + +-44.096615 74.151184 89.855537 +-44.096645 -74.151169 89.855537 +40.481560 77.766258 89.855537 +40.481537 -77.766273 89.855537 +-44.096615 74.151184 94.565582 +-40.481571 -77.766258 94.565582 +40.481560 77.766258 94.565582 +44.096615 -74.151176 94.565582 +-40.481541 77.766273 89.855537 +-40.481571 -77.766258 89.855537 +44.096638 74.151161 89.855537 +44.096615 -74.151176 89.855537 +-40.481541 77.766273 94.565582 +-44.096645 -74.151169 94.565582 +44.096638 74.151161 94.565582 +40.481537 -77.766273 94.565582 +-43.694942 76.159561 89.855537 +-42.489918 77.364586 89.855537 +-42.489948 -77.364571 89.855537 +-43.694973 -76.159546 89.855537 +42.489937 77.364563 89.855537 +43.694962 76.159538 89.855537 +43.694939 -76.159554 89.855537 +42.489914 -77.364578 89.855537 +-42.489918 77.364586 94.565582 +-43.694942 76.159561 94.565582 +-43.694973 -76.159546 94.565582 +-42.489948 -77.364571 94.565582 +43.694962 76.159538 94.565582 +42.489937 77.364563 94.565582 +42.489914 -77.364578 94.565582 +43.694939 -76.159554 94.565582 +-44.096615 74.151184 95.154335 +-44.096645 -74.151169 95.154335 +-43.694973 -76.159546 95.154335 +-42.489948 -77.364571 95.154335 +-40.481571 -77.766258 95.154335 +40.481537 -77.766273 95.154335 +42.489914 -77.364578 95.154335 +43.694939 -76.159554 95.154335 +44.096615 -74.151176 95.154335 +44.096638 74.151161 95.154335 +43.694962 76.159538 95.154335 +42.489937 77.364563 95.154335 +40.481560 77.766258 95.154335 +-40.481541 77.766273 95.154335 +-42.489918 77.364586 95.154335 +-43.694942 76.159561 95.154335 +-44.096615 74.151184 94.565582 +-40.481571 -77.766258 94.565582 +40.481560 77.766258 94.565582 +44.096615 -74.151176 94.565582 +-40.481541 77.766273 94.565582 +-44.096645 -74.151169 94.565582 +44.096638 74.151161 94.565582 +40.481537 -77.766273 94.565582 +-42.489918 77.364586 94.565582 +-43.694942 76.159561 94.565582 +-43.694973 -76.159546 94.565582 +-42.489948 -77.364571 94.565582 +43.694962 76.159538 94.565582 +42.489937 77.364563 94.565582 +42.489914 -77.364578 94.565582 +43.694939 -76.159554 94.565582 +27.984621 -65.935883 0.000000 +36.987133 -65.935890 0.000000 +27.984623 65.935913 0.000000 +36.987137 65.935905 0.000000 +27.984621 -65.935883 90.633247 +36.987133 -65.935890 90.633247 +27.984623 65.935913 90.633247 +36.987137 65.935905 90.633247 +27.984623 -61.610500 0.000000 +27.984621 61.610512 0.000000 +36.987133 61.610512 0.000000 +36.987137 -61.610500 0.000000 +36.987137 -61.610500 90.633247 +36.987133 61.610512 90.633247 +27.984621 61.610512 90.633247 +27.984623 -61.610500 90.633247 +36.987133 -65.935890 18.550392 +27.984621 -65.935883 18.550392 +36.987137 65.935905 18.550392 +27.984623 65.935913 18.550392 +36.987133 61.610512 18.550392 +36.987137 -61.610500 18.550392 +27.984623 -61.610500 18.550392 +27.984621 61.610512 18.550392 +36.987133 -65.935890 14.262986 +36.987137 65.935905 14.262986 +27.984623 65.935913 14.262986 +36.987137 -61.610500 14.262986 +27.984621 61.610512 14.262986 +27.984621 -65.935883 14.262986 +36.987133 61.610512 14.262986 +27.984623 -61.610500 14.262986 +-37.371159 -65.935890 0.000000 +-28.368649 -65.935890 0.000000 +-37.371166 65.935905 0.000000 +-28.368656 65.935905 0.000000 +-37.371159 -65.935890 90.633247 +-28.368649 -65.935890 90.633247 +-37.371166 65.935905 90.633247 +-28.368656 65.935905 90.633247 +-37.371159 -61.610504 0.000000 +-37.371166 61.610512 0.000000 +-28.368656 61.610512 0.000000 +-28.368649 -61.610504 0.000000 +-28.368649 -61.610504 90.633247 +-28.368656 61.610512 90.633247 +-37.371166 61.610512 90.633247 +-37.371159 -61.610504 90.633247 +-28.368649 -65.935890 18.550392 +-37.371159 -65.935890 18.550392 +-28.368656 65.935905 18.550392 +-37.371166 65.935905 18.550392 +-28.368656 61.610512 18.550392 +-28.368649 -61.610504 18.550392 +-37.371159 -61.610504 18.550392 +-37.371166 61.610512 18.550392 +-28.368649 -65.935890 14.262986 +-28.368656 65.935905 14.262986 +-37.371166 65.935905 14.262986 +-28.368649 -61.610504 14.262986 +-37.371166 61.610512 14.262986 +-37.371159 -65.935890 14.262986 +-28.368656 61.610512 14.262986 +-37.371159 -61.610504 14.262986 +-13.446186 14.462212 95.483948 +36.117062 14.462212 95.483948 +-13.446186 75.304901 95.483948 +36.117062 75.304901 95.483948 +-13.446186 14.462212 144.011230 +36.117062 14.462212 144.011230 +-13.446186 75.304901 144.011230 +36.117062 75.304901 144.011230 +-13.446186 -65.250519 95.483948 +36.117062 -65.250519 95.483948 +-13.446186 3.149231 95.483948 +36.117062 3.149231 95.483948 +-13.446186 -65.250519 144.011230 +36.117062 -65.250519 144.011230 +-13.446186 3.149231 144.011230 +36.117062 3.149231 144.011230 + + + + + + + + + + + +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.995133 -0.098537 0.000000 +-0.995133 0.098537 0.000000 +-0.995133 0.098537 0.000000 +-0.995133 -0.098537 0.000000 +-0.995133 0.098537 0.000000 +-0.995133 -0.098537 0.000000 +0.098542 -0.995133 0.000000 +-0.098541 -0.995133 0.000000 +-0.098541 -0.995133 0.000000 +0.098542 -0.995133 0.000000 +-0.098541 -0.995133 0.000000 +0.098542 -0.995133 0.000000 +0.995133 0.098538 0.000000 +0.995133 -0.098538 0.000000 +0.995133 -0.098538 0.000000 +0.995133 0.098538 0.000000 +0.995133 -0.098538 0.000000 +0.995133 0.098538 0.000000 +-0.098540 0.995133 0.000000 +0.098542 0.995133 0.000000 +0.098542 0.995133 0.000000 +-0.098540 0.995133 0.000000 +0.098542 0.995133 0.000000 +-0.098540 0.995133 0.000000 +-0.995133 -0.098537 0.000000 +-0.995133 -0.098537 0.000000 +-0.980581 -0.196115 0.000000 +-0.980581 -0.196115 0.000000 +-0.995133 -0.098537 0.000000 +-0.980581 -0.196115 0.000000 +-0.980581 0.196115 0.000000 +-0.980581 0.196115 0.000000 +-0.995133 0.098537 0.000000 +-0.995133 0.098537 0.000000 +-0.980581 0.196115 0.000000 +-0.995133 0.098537 0.000000 +0.098542 -0.995133 0.000000 +0.098542 -0.995133 0.000000 +0.196125 -0.980579 0.000000 +0.196125 -0.980579 0.000000 +0.098542 -0.995133 0.000000 +0.196125 -0.980579 0.000000 +0.995133 0.098538 0.000000 +0.995133 0.098538 0.000000 +0.980581 0.196116 0.000000 +0.980581 0.196116 0.000000 +0.995133 0.098538 0.000000 +0.980581 0.196116 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.196122 -0.980579 0.000000 +-0.196122 -0.980579 0.000000 +-0.098541 -0.995133 0.000000 +-0.098541 -0.995133 0.000000 +-0.196122 -0.980579 0.000000 +-0.098541 -0.995133 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.098540 0.995133 0.000000 +-0.098540 0.995133 0.000000 +-0.196122 0.980579 0.000000 +-0.196122 0.980579 0.000000 +-0.098540 0.995133 0.000000 +-0.196122 0.980579 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.980581 -0.196117 0.000000 +0.980581 -0.196117 0.000000 +0.995133 -0.098538 0.000000 +0.995133 -0.098538 0.000000 +0.980581 -0.196117 0.000000 +0.995133 -0.098538 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.196125 0.980579 0.000000 +0.196125 0.980579 0.000000 +0.098542 0.995133 0.000000 +0.098542 0.995133 0.000000 +0.196125 0.980579 0.000000 +0.098542 0.995133 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.980581 -0.196115 0.000000 +-0.980581 -0.196115 0.000000 +-0.980581 -0.196115 0.000000 +-0.980581 -0.196115 0.000000 +-0.980581 -0.196115 0.000000 +-0.980581 -0.196115 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.196122 -0.980580 0.000000 +-0.196122 -0.980580 0.000000 +-0.196122 -0.980580 0.000000 +-0.196122 -0.980580 0.000000 +-0.196122 -0.980580 0.000000 +-0.196122 -0.980580 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +0.196125 -0.980579 0.000000 +0.196125 -0.980579 0.000000 +0.196125 -0.980579 0.000000 +0.196125 -0.980579 0.000000 +0.196125 -0.980579 0.000000 +0.196125 -0.980579 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.980581 -0.196117 0.000000 +0.980581 -0.196117 0.000000 +0.980581 -0.196117 0.000000 +0.980581 -0.196117 0.000000 +0.980581 -0.196117 0.000000 +0.980581 -0.196117 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +0.980581 0.196117 0.000000 +0.980581 0.196117 0.000000 +0.980581 0.196117 0.000000 +0.980581 0.196117 0.000000 +0.980581 0.196117 0.000000 +0.980581 0.196117 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.196125 0.980579 0.000000 +0.196125 0.980579 0.000000 +0.196125 0.980579 0.000000 +0.196125 0.980579 0.000000 +0.196125 0.980579 0.000000 +0.196125 0.980579 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.196122 0.980580 0.000000 +-0.196122 0.980580 0.000000 +-0.196122 0.980580 0.000000 +-0.196122 0.980580 0.000000 +-0.196122 0.980580 0.000000 +-0.196122 0.980580 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.980581 0.196115 0.000000 +-0.980581 0.196115 0.000000 +-0.980581 0.196115 0.000000 +-0.980581 0.196115 0.000000 +-0.980581 0.196115 0.000000 +-0.980581 0.196115 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000001 -1.000000 0.000000 +-0.000001 -1.000000 0.000000 +-0.000001 -1.000000 0.000000 +-0.000001 -1.000000 0.000000 +-0.000001 -1.000000 0.000000 +-0.000001 -1.000000 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.000001 -1.000000 0.000000 +-0.000001 -1.000000 0.000000 +-0.000001 -1.000000 0.000000 +-0.000001 -1.000000 0.000000 +-0.000001 -1.000000 0.000000 +-0.000001 -1.000000 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.000001 -1.000000 0.000000 +-0.000001 -1.000000 0.000000 +-0.000001 -1.000000 0.000000 +-0.000001 -1.000000 0.000000 +-0.000001 -1.000000 0.000000 +-0.000001 -1.000000 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 + + + + + + + + + + + +0.579139 0.446804 +0.576821 0.457549 +0.573698 0.053096 +0.575739 0.061897 +0.589360 0.048403 +0.592868 0.459541 +0.563212 0.045241 +0.028627 0.045211 +0.018884 0.026461 +0.571741 0.027248 +0.015722 0.063922 +0.019124 0.448828 +0.005502 0.462322 +0.001993 0.051185 +0.031650 0.465484 +0.566234 0.465515 +0.575977 0.484265 +0.023121 0.483477 +0.584626 0.039438 +0.588445 0.470220 +0.022647 0.048570 +0.011366 0.033315 +0.021163 0.457629 +0.010236 0.471286 +0.568987 0.048584 +0.579109 0.033070 +0.583495 0.477411 +0.572214 0.462156 +0.018040 0.053177 +0.006416 0.040506 +0.025874 0.462141 +0.015752 0.477654 +0.492728 0.609730 +0.493178 0.983298 +0.031504 0.983855 +0.031053 0.610287 +0.145240 0.568377 +0.436617 0.567900 +0.436667 0.572985 +0.145290 0.573462 +0.454310 0.567727 +0.454359 0.572813 +0.469033 0.567586 +0.469082 0.572673 +0.062037 0.594887 +0.467714 0.594043 +0.492339 0.593785 +0.492414 0.600863 +0.459939 0.558897 +0.459894 0.553811 +0.442248 0.559053 +0.442203 0.553968 +0.150867 0.559248 +0.150821 0.554163 +0.133177 0.559415 +0.133128 0.554329 +0.118456 0.559557 +0.118407 0.554471 +0.466655 0.585821 +0.060981 0.586666 +0.036348 0.586924 +0.036274 0.579844 +0.127549 0.568553 +0.127599 0.573638 +0.060907 0.579586 +0.062112 0.601967 +0.467789 0.601122 +0.466581 0.578742 +0.512822 0.944557 +0.511907 0.618459 +0.506170 0.975643 +0.037405 0.595148 +0.037480 0.602228 +0.499686 0.982019 +0.474658 0.558767 +0.474613 0.553682 +0.024999 0.982873 +0.018565 0.979944 +0.012324 0.975126 +0.011410 0.649029 +0.018062 0.617942 +0.491281 0.585561 +0.491207 0.578482 +0.024546 0.611567 +0.112829 0.568699 +0.112880 0.573784 +0.499232 0.610713 +0.505666 0.613641 +1.000000 0.000000 +0.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +1.000000 0.032800 +1.000000 0.967200 +0.967200 0.000000 +0.032800 0.000000 +0.000000 0.967200 +0.000000 0.032800 +0.967200 0.000000 +0.032800 0.000000 +1.000000 0.032800 +1.000000 0.967200 +0.032800 1.000000 +0.967200 1.000000 +0.000000 0.967200 +0.000000 0.032800 +0.032800 1.000000 +0.967200 1.000000 +1.000000 0.500000 +0.000000 0.500000 +0.000000 0.500000 +1.000000 0.500000 +1.000000 0.500000 +0.000000 0.500000 +1.000000 0.500000 +0.000000 0.500000 +0.967200 0.500000 +0.032800 0.500000 +0.967200 0.500000 +0.032800 0.500000 +1.000000 0.250000 +0.000000 0.250000 +1.000000 0.250000 +0.000000 0.250000 +1.000000 0.250000 +0.000000 0.250000 +0.032800 0.250000 +0.032800 0.250000 +0.000000 0.250000 +1.000000 0.250000 +0.967200 0.250000 +0.967200 0.250000 +1.000000 0.000000 +0.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +1.000000 0.032800 +1.000000 0.967200 +0.967200 0.000000 +0.032800 0.000000 +0.000000 0.967200 +0.000000 0.032800 +0.967200 0.000000 +0.032800 0.000000 +1.000000 0.032800 +1.000000 0.967200 +0.032800 1.000000 +0.967200 1.000000 +0.000000 0.967200 +0.000000 0.032800 +0.032800 1.000000 +0.967200 1.000000 +1.000000 0.500000 +0.000000 0.500000 +0.000000 0.500000 +1.000000 0.500000 +1.000000 0.500000 +0.000000 0.500000 +1.000000 0.500000 +0.000000 0.500000 +0.967200 0.500000 +0.032800 0.500000 +0.967200 0.500000 +0.032800 0.500000 +1.000000 0.250000 +0.000000 0.250000 +1.000000 0.250000 +0.000000 0.250000 +1.000000 0.250000 +0.000000 0.250000 +0.032800 0.250000 +0.032800 0.250000 +0.000000 0.250000 +1.000000 0.250000 +0.967200 0.250000 +0.967200 0.250000 +1.000000 0.000000 +0.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +1.000000 0.000000 +0.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 + + + + + + + + + + + +

19 0 2 0 1 0 16 2 1 0 3 0 19 4 2 1 5 3 13 6 4 4 7 5 0 8 0 13 9 4 0 10 0 1 11 3 15 12 8 5 13 9 9 14 6 15 15 8 9 16 6 3 17 7 14 18 12 7 19 13 11 20 10 14 21 12 11 22 10 10 23 11 12 24 16 6 25 17 2 26 14 12 27 16 2 28 14 8 29 15 13 30 4 1 31 3 26 32 18 26 33 18 1 34 3 19 35 2 25 36 19 16 37 1 4 38 5 4 39 5 16 40 1 0 41 0 15 42 8 3 43 7 30 44 21 30 45 21 3 46 7 23 47 20 14 48 12 10 49 11 28 50 23 28 51 23 10 52 11 21 53 22 26 54 18 19 55 2 27 56 25 27 57 25 19 58 2 18 59 24 27 60 25 18 61 24 5 62 9 5 63 9 18 64 24 9 65 6 24 66 26 17 67 27 25 68 19 25 69 19 17 70 27 16 71 1 12 72 16 8 73 15 24 74 26 24 75 26 8 76 15 17 77 27 30 78 21 23 79 20 31 80 29 31 81 29 23 82 20 22 83 28 31 84 29 22 85 28 7 86 13 7 87 13 22 88 28 11 89 10 28 90 23 21 91 22 29 92 31 29 93 31 21 94 22 20 95 30 29 96 31 20 97 30 6 98 17 6 99 17 20 100 30 2 101 14 45 102 32 36 103 33 44 104 35 44 105 35 36 106 33 37 107 34 33 108 38 32 109 39 48 110 36 33 111 38 48 112 36 53 113 37 34 114 41 33 115 38 53 116 37 34 117 41 53 118 37 58 119 40 35 120 43 34 121 41 58 122 40 35 123 43 58 124 40 59 125 42 36 126 65 35 127 72 59 128 71 36 129 65 59 130 71 49 131 44 37 132 66 36 133 65 49 134 44 37 135 66 49 136 44 55 137 45 38 138 47 37 139 66 55 140 45 38 141 47 55 142 45 62 143 46 39 144 49 38 145 75 62 146 74 39 147 49 62 148 74 63 149 48 40 150 51 39 151 49 63 152 48 40 153 51 63 154 48 51 155 50 41 156 53 40 157 51 51 158 50 41 159 53 51 160 50 54 161 52 42 162 55 41 163 53 54 164 52 42 165 55 54 166 52 60 167 54 43 168 57 42 169 55 60 170 54 43 171 57 60 172 54 61 173 56 44 174 67 43 175 82 61 176 81 44 177 67 61 178 81 50 179 58 45 180 64 44 181 67 50 182 58 45 183 64 50 184 58 52 185 59 46 186 61 45 187 64 52 188 59 46 189 61 52 190 59 56 191 60 47 192 63 46 193 85 56 194 84 47 195 63 56 196 84 57 197 62 32 198 39 47 199 63 57 200 62 32 201 39 57 202 62 48 203 36 44 204 35 38 205 76 43 206 83 38 207 76 44 208 35 37 209 34 43 210 83 39 211 77 42 212 80 43 213 83 38 214 76 39 215 77 40 216 78 42 217 80 39 218 77 42 219 80 40 220 78 41 221 79 36 222 33 45 223 32 46 224 86 46 225 86 35 226 73 36 227 33 35 228 73 46 229 86 47 230 87 35 231 73 47 232 87 34 233 70 32 234 69 34 235 70 47 236 87 34 237 70 32 238 69 33 239 68 23 240 20 2 241 14 20 242 30 2 243 14 23 244 20 3 245 7 22 246 28 20 247 30 21 248 22 20 249 30 22 250 28 23 251 20 21 252 22 11 253 10 22 254 28 11 255 10 21 256 22 10 257 11 9 258 6 2 259 14 3 260 7 2 261 14 9 262 6 8 263 15 9 264 6 17 265 27 8 266 15 17 267 27 9 268 6 18 269 24 18 270 24 16 271 1 17 272 27 16 273 1 18 274 24 19 275 2 93 276 148 65 277 97 88 278 140 65 279 97 93 280 148 64 281 96 89 282 143 66 283 105 90 284 144 66 285 105 89 286 143 67 287 104 74 288 116 73 289 113 66 290 90 74 291 116 66 292 90 67 293 91 72 294 112 65 295 89 64 296 88 65 297 89 72 298 112 75 299 117 70 300 94 77 301 121 71 302 95 77 303 121 70 304 94 78 305 124 79 306 125 69 307 93 76 308 120 69 309 93 79 310 125 68 311 92 94 312 150 67 313 101 89 314 142 67 315 101 94 316 150 74 317 118 85 318 137 76 319 122 69 320 102 69 321 102 80 322 129 85 323 137 95 324 151 64 325 109 93 326 149 64 327 109 95 328 151 72 329 114 87 330 139 78 331 126 70 332 110 70 333 110 83 334 135 87 335 139 68 336 98 81 337 130 69 338 99 69 339 99 81 340 130 80 341 128 82 342 133 70 343 107 71 344 106 70 345 107 82 346 133 83 347 134 77 348 123 84 349 136 71 350 103 71 351 103 84 352 136 82 353 132 85 354 137 80 355 129 88 356 141 85 357 137 88 358 141 91 359 146 79 360 127 86 361 138 68 362 111 68 363 111 86 364 138 81 365 131 87 366 139 83 367 135 90 368 145 87 369 139 90 370 145 92 371 147 80 372 128 81 373 130 93 374 148 80 375 128 93 376 148 88 377 140 83 378 134 82 379 133 89 380 143 83 381 134 89 382 143 90 383 144 84 384 136 94 385 150 82 386 132 82 387 132 94 388 150 89 389 142 86 390 138 95 391 151 81 392 131 81 393 131 95 394 151 93 395 149 88 396 141 65 397 100 91 398 146 91 399 146 65 400 100 75 401 119 90 402 145 66 403 108 92 404 147 92 405 147 66 406 108 73 407 115 86 408 110 87 409 111 92 410 116 86 411 110 92 412 116 95 413 119 84 414 108 85 415 109 91 416 115 84 417 108 91 418 115 94 419 118 87 420 111 86 421 110 84 422 108 84 423 108 86 424 110 85 425 109 95 426 119 94 427 118 91 428 115 94 429 118 95 430 119 92 431 116 73 432 115 94 433 150 92 434 116 94 435 150 73 436 115 74 437 116 75 438 119 95 439 151 91 440 115 95 441 151 75 442 119 72 443 112 78 444 124 87 445 139 77 446 123 77 447 123 87 448 139 84 449 108 76 450 120 85 451 137 79 452 127 79 453 127 85 454 137 86 455 110 125 456 212 97 457 161 120 458 204 97 459 161 125 460 212 96 461 160 121 462 207 98 463 169 122 464 208 98 465 169 121 466 207 99 467 168 106 468 180 105 469 177 98 470 154 106 471 180 98 472 154 99 473 155 97 474 153 96 475 152 104 476 176 97 477 153 104 478 176 107 479 181 103 480 159 102 481 158 110 482 188 103 483 159 110 484 188 109 485 185 108 486 184 111 487 189 100 488 156 108 489 184 100 490 156 101 491 157 126 492 214 99 493 165 121 494 206 99 495 165 126 496 214 106 497 182 117 498 201 108 499 186 101 500 166 101 501 166 112 502 193 117 503 201 127 504 215 96 505 173 125 506 213 96 507 173 127 508 215 104 509 178 119 510 203 110 511 190 102 512 174 102 513 174 115 514 199 119 515 203 100 516 162 113 517 194 101 518 163 101 519 163 113 520 194 112 521 192 103 522 170 114 523 197 102 524 171 102 525 171 114 526 197 115 527 198 109 528 187 116 529 200 103 530 167 103 531 167 116 532 200 114 533 196 117 534 201 112 535 193 120 536 205 117 537 201 120 538 205 123 539 210 111 540 191 118 541 202 100 542 175 100 543 175 118 544 202 113 545 195 119 546 203 115 547 199 122 548 209 119 549 203 122 550 209 124 551 211 125 552 212 112 553 192 113 554 194 112 555 192 125 556 212 120 557 204 115 558 198 114 559 197 121 560 207 115 561 198 121 562 207 122 563 208 116 564 200 126 565 214 114 566 196 114 567 196 126 568 214 121 569 206 127 570 215 113 571 195 118 572 202 113 573 195 127 574 215 125 575 213 120 576 205 97 577 164 123 578 210 123 579 210 97 580 164 107 581 183 122 582 209 98 583 172 124 584 211 124 585 211 98 586 172 105 587 179 118 588 174 119 589 175 124 590 180 118 591 174 124 592 180 127 593 183 116 594 172 117 595 173 123 596 179 116 597 172 123 598 179 126 599 182 119 600 175 118 601 174 116 602 172 116 603 172 118 604 174 117 605 173 127 606 183 126 607 182 123 608 179 126 609 182 127 610 183 124 611 180 105 612 179 126 613 214 124 614 180 126 615 214 105 616 179 106 617 180 123 618 179 107 619 183 127 620 215 127 621 215 107 622 183 104 623 176 110 624 188 119 625 203 109 626 187 109 627 187 119 628 203 116 629 172 108 630 184 117 631 201 111 632 191 111 633 191 117 634 201 118 635 174 129 636 217 128 637 216 131 638 219 128 639 216 130 640 218 131 641 219 135 642 223 134 643 222 132 644 220 135 645 223 132 646 220 133 647 221 133 648 227 132 649 226 128 650 224 133 651 227 128 652 224 129 653 225 135 654 231 133 655 230 129 656 228 135 657 231 129 658 228 131 659 229 134 660 235 135 661 234 131 662 232 134 663 235 131 664 232 130 665 233 132 666 239 134 667 238 130 668 236 132 669 239 130 670 236 128 671 237 137 672 241 136 673 240 139 674 243 136 675 240 138 676 242 139 677 243 143 678 247 142 679 246 140 680 244 143 681 247 140 682 244 141 683 245 141 684 251 140 685 250 136 686 248 141 687 251 136 688 248 137 689 249 143 690 255 141 691 254 137 692 252 143 693 255 137 694 252 139 695 253 142 696 259 143 697 258 139 698 256 142 699 259 139 700 256 138 701 257 140 702 263 142 703 262 138 704 260 140 705 263 138 706 260 136 707 261

+
+
+
+ + + 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.0000001.000000 + 30.0000000.0000003.333333 + + + + + +
diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_DeskC_01/meshes/aws_robomaker_warehouse_DeskC_01_visual.DAE b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_DeskC_01/meshes/aws_robomaker_warehouse_DeskC_01_visual.DAE new file mode 100755 index 0000000..398d91d --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_DeskC_01/meshes/aws_robomaker_warehouse_DeskC_01_visual.DAE @@ -0,0 +1,4729 @@ + + + FBX COLLADA exporter2019-05-24T05:15:49Z2019-05-24T05:15:49ZZ_UP + + + ../materials/textures/aws_robomaker_warehouse_DeskC_01.png + + + ../materials/textures/aws_robomaker_warehouse_DeskC_02.png + + + ../materials/textures/aws_robomaker_warehouse_DeskC_03.png + + + ../materials/textures/aws_robomaker_warehouse_DeskC_04.png + + + + + + + + + + + + + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + +-37.371174 -61.648491 -0.000007 +-37.371174 -65.510582 -0.000007 +-28.368664 -61.648491 -0.000007 +-28.793972 -65.935890 -0.000007 +-37.371174 -61.648491 90.633255 +-36.945866 -65.935890 90.633255 +-28.368664 -61.648491 90.633255 +-28.368664 -65.510582 90.633255 +-36.782421 -61.648491 -0.000007 +-36.782444 -65.004433 -0.000007 +-28.957417 -61.648491 -0.000007 +-29.382778 -65.429733 -0.000007 +-36.782421 -61.648491 90.633255 +-36.357136 -65.429733 90.633255 +-28.957417 -61.648491 90.633255 +-28.957462 -65.004433 90.633255 +-36.945866 -65.935890 -0.000007 +-28.368664 -65.510582 -0.000007 +-37.371174 -65.510582 90.633255 +-28.793972 -65.935890 90.633255 +-36.357136 -65.429733 -0.000007 +-28.957462 -65.004433 -0.000007 +-36.782444 -65.004433 90.633255 +-29.382778 -65.429733 90.633255 +-37.371159 61.648521 -0.000007 +-37.371159 65.510612 -0.000007 +-37.371159 65.510612 90.633255 +-37.371159 61.648521 90.633255 +-36.945850 65.935921 -0.000007 +-28.793957 65.935921 -0.000007 +-28.793957 65.935921 90.633255 +-36.945850 65.935921 90.633255 +-28.368649 65.510612 -0.000007 +-28.368649 61.648521 -0.000007 +-28.368649 61.648521 90.633255 +-28.368649 65.510612 90.633255 +-36.782429 65.004463 90.633255 +-36.782429 65.004463 -0.000007 +-36.782406 61.648521 -0.000007 +-36.782406 61.648521 90.633255 +-29.382763 65.429764 90.633255 +-29.382763 65.429764 -0.000007 +-36.357121 65.429764 -0.000007 +-36.357121 65.429764 90.633255 +-28.957401 61.648521 90.633255 +-28.957401 61.648521 -0.000007 +-28.957447 65.004463 -0.000007 +-28.957447 65.004463 90.633255 +36.987122 -61.648502 -0.000004 +36.987122 -65.510590 -0.000004 +36.987122 -65.510590 90.633263 +36.987122 -61.648502 90.633263 +36.561813 -65.935905 -0.000004 +28.409920 -65.935898 -0.000004 +28.409920 -65.935898 90.633263 +36.561813 -65.935905 90.633263 +27.984612 -65.510582 -0.000004 +27.984613 -61.648502 -0.000004 +27.984613 -61.648502 90.633263 +27.984612 -65.510582 90.633263 +36.398388 -65.004448 90.633263 +36.398388 -65.004448 -0.000004 +36.398376 -61.648502 -0.000004 +36.398376 -61.648502 90.633263 +28.998718 -65.429741 90.633263 +28.998718 -65.429741 -0.000004 +35.973080 -65.429749 -0.000004 +35.973080 -65.429749 90.633263 +28.573370 -61.648502 90.633263 +28.573370 -61.648502 -0.000004 +28.573410 -65.004440 -0.000004 +28.573410 -65.004440 90.633263 +36.987144 61.648502 -0.000004 +36.987144 61.648502 90.633263 +36.987144 65.510582 90.633263 +36.987144 65.510582 -0.000004 +36.561836 65.935890 -0.000004 +36.561836 65.935890 90.633263 +28.409943 65.935898 90.633263 +28.409943 65.935898 -0.000004 +27.984634 65.510590 -0.000004 +27.984634 65.510590 90.633263 +27.984632 61.648502 90.633263 +27.984632 61.648502 -0.000004 +36.398411 65.004448 90.633263 +36.398396 61.648502 90.633263 +36.398396 61.648502 -0.000004 +36.398411 65.004448 -0.000004 +28.998741 65.429756 90.633263 +35.973103 65.429749 90.633263 +35.973103 65.429749 -0.000004 +28.998741 65.429756 -0.000004 +28.573389 61.648502 90.633263 +28.573433 65.004456 90.633263 +28.573433 65.004456 -0.000004 +28.573389 61.648502 -0.000004 +-44.096615 74.151192 89.855537 +-44.096645 -74.151161 89.855537 +40.481560 77.766266 89.855537 +40.481537 -77.766266 89.855537 +-40.481541 77.766281 89.855537 +-40.481571 -77.766251 89.855537 +44.096638 74.151169 89.855537 +44.096615 -74.151169 89.855537 +-43.092430 76.762085 89.855537 +-43.092461 -76.762054 89.855537 +43.092449 76.762054 89.855537 +43.092426 -76.762054 89.855537 +-44.096615 74.151192 95.154335 +-44.096645 -74.151161 95.154335 +-43.092461 -76.762054 95.154335 +-40.481571 -77.766251 95.154335 +40.481537 -77.766266 95.154335 +43.092426 -76.762054 95.154335 +44.096615 -74.151169 95.154335 +44.096638 74.151169 95.154335 +43.092449 76.762054 95.154335 +40.481560 77.766266 95.154335 +-40.481541 77.766281 95.154335 +-43.092430 76.762085 95.154335 +-37.371159 65.163902 18.550394 +-37.371159 65.163902 14.688301 +-28.368649 65.163902 18.550394 +-28.793957 65.163902 14.262994 +-37.371174 -65.135574 18.550390 +-36.945866 -65.135574 14.262988 +-28.368664 -65.135574 18.550390 +-28.368664 -65.135574 14.688295 +-36.782406 65.163902 18.550394 +-36.782429 65.163902 15.194448 +-28.957401 65.163902 18.550394 +-29.382763 65.163902 14.769140 +-36.782421 -65.135574 18.550390 +-36.357136 -65.135574 14.769135 +-28.957417 -65.135574 18.550390 +-28.957462 -65.135574 15.194443 +-36.945850 65.163902 14.262994 +-28.368649 65.163902 14.688301 +-37.371174 -65.135574 14.688295 +-28.793972 -65.135574 14.262988 +-36.357121 65.163902 14.769140 +-28.957447 65.163902 15.194448 +-36.782444 -65.135574 15.194443 +-29.382778 -65.135574 14.769135 +36.987144 65.163887 18.550394 +36.987144 65.163887 14.688301 +36.987122 -65.135582 14.688295 +36.987122 -65.135582 18.550390 +36.561836 65.163887 14.262994 +28.409943 65.163895 14.262994 +28.409920 -65.135574 14.262988 +36.561813 -65.135582 14.262988 +27.984634 65.163895 14.688301 +27.984634 65.163895 18.550394 +27.984612 -65.135574 18.550390 +27.984612 -65.135574 14.688295 +36.398388 -65.135582 15.194441 +36.398411 65.163887 15.194448 +36.398399 65.163887 18.550394 +36.398376 -65.135582 18.550390 +28.998718 -65.135574 14.769133 +28.998741 65.163895 14.769140 +35.973103 65.163887 14.769140 +35.973080 -65.135582 14.769133 +28.573368 -65.135574 18.550390 +28.573391 65.163895 18.550394 +28.573433 65.163895 15.194448 +28.573410 -65.135574 15.194441 +-8.839386 -1.124335 120.142776 +-8.839371 -1.124274 143.656052 +31.564835 1.174650 143.656052 +31.564850 1.174649 120.142776 +-7.012421 -33.232262 120.142776 +33.391754 -30.933304 120.142776 +33.391754 -30.933304 143.656052 +-7.012421 -33.232262 143.656052 +-10.217209 0.013418 95.154068 +-10.217209 0.013487 120.323105 +33.032242 2.474308 120.323105 +33.032227 2.474310 95.154068 +-8.261658 -34.355511 95.154068 +34.987778 -31.894663 95.154068 +34.987778 -31.894663 120.323105 +-8.261658 -34.355511 120.323105 +33.170959 -61.850304 94.926239 +33.170959 -61.850349 106.544884 +-11.221756 -63.979034 106.544884 +-11.221756 -63.978981 94.926231 +31.866714 -34.649704 94.926239 +-12.525970 -36.778488 94.926239 +31.866760 -34.649704 106.544884 +-12.525970 -36.778381 106.544884 +33.515305 -61.201118 106.616203 +33.515335 -61.201187 118.234840 +-10.799744 -64.580566 118.234840 +-10.799744 -64.580566 106.616203 +31.444778 -34.048119 106.616203 +-12.870300 -37.427612 106.616203 +31.444778 -34.048187 118.234856 +-12.870300 -37.427559 118.234856 +33.515305 -61.201118 118.267174 +33.515335 -61.201187 129.885818 +-10.799744 -64.580566 129.885818 +-10.799744 -64.580566 118.267174 +31.444778 -34.048119 118.267174 +-12.870300 -37.427612 118.267174 +31.444778 -34.048187 129.885849 +-12.870300 -37.427559 129.885849 +9.794342 37.798069 119.188225 +3.209122 35.349949 98.549019 +3.852448 35.407131 98.492424 +4.444046 35.299751 96.616112 +5.399490 35.292645 95.483986 +5.622528 35.362576 96.034935 +3.935608 35.219280 96.259140 +17.493607 34.796902 95.325691 +17.494156 34.832615 95.657379 +6.781326 40.094135 109.247612 +6.490082 39.284817 108.072975 +6.291733 40.043987 109.247368 +5.982925 39.230625 108.075325 +6.049271 39.337070 106.686401 +5.520767 39.280712 106.691681 +5.627258 40.230923 105.617523 +5.081772 40.175091 105.624931 +10.942154 38.004017 120.243004 +10.193771 45.751507 120.243065 +10.177948 37.881214 119.711403 +9.418365 45.744717 119.711426 +9.024170 45.771511 119.188240 +6.081131 42.807156 109.417725 +5.642166 43.701550 108.350983 +6.329254 41.410091 109.760117 +2.021210 47.647732 98.549026 +4.871170 42.938259 105.795296 +5.180008 43.751621 106.967339 +4.833679 41.572155 105.282547 +3.276367 35.262211 97.473366 +2.066772 47.784870 97.473358 +2.701431 47.996349 96.259117 +4.149612 48.232090 95.483925 +15.958237 50.508831 95.325737 +19.289413 48.025524 95.305946 +17.425827 50.201374 95.317146 +18.597351 49.328053 95.310188 +20.283737 37.731731 95.306038 +19.958191 36.235332 95.309853 +18.861191 35.081440 95.317566 +19.957306 36.261181 95.594955 +18.861511 35.112644 95.625374 +17.432632 50.161282 95.624092 +15.966064 50.463970 95.657906 +4.383850 48.186581 96.034981 +3.217102 48.002018 96.616119 +2.692047 47.830471 97.593102 +2.666641 47.717113 98.491417 +9.312943 45.816120 119.056030 +6.147690 43.743908 108.349861 +9.641861 45.795330 119.476784 +10.359253 45.802021 119.963753 +19.294113 47.992107 95.580040 +20.282898 37.755699 95.579964 +6.569717 42.849995 109.418747 +6.811752 41.455944 109.761650 +8.399658 66.996185 138.911606 +8.491974 68.214172 137.726425 +8.395630 67.787796 138.502792 +14.055084 42.234097 120.488914 +14.542694 68.798599 103.251373 +13.243729 16.847363 138.911636 +14.866409 67.620819 102.066193 +14.718872 68.398560 102.474998 +19.710480 17.471996 102.066223 +19.618179 16.254036 103.251396 +19.714523 16.680370 102.475037 +13.567459 15.669559 137.726456 +13.391266 16.069614 138.502823 +3.899246 35.332874 97.593117 +10.083771 37.814251 119.056686 +10.406143 37.882626 119.476814 +11.113235 37.996014 119.963791 +18.602417 49.292431 95.596718 +5.385223 41.625027 105.274612 +5.415634 42.986820 105.788658 +7.937836 67.743698 138.421829 +7.942062 66.951996 138.830704 +12.786133 16.803127 138.830704 +12.933502 16.025257 138.421860 +14.085876 68.754532 103.170433 +14.261398 68.354462 102.393860 +8.034958 68.170090 137.645493 +19.161362 16.209816 103.170464 +19.257050 16.636074 102.393890 +13.110443 15.625324 137.645493 +25.414459 28.043316 95.179214 +25.418060 28.006012 95.191711 +25.389145 28.012619 95.191711 +25.377136 28.039730 95.191711 +22.731979 55.814083 95.179199 +22.694641 55.810474 95.191696 +36.761642 29.139393 95.179214 +36.765244 29.102077 95.191711 +22.728348 55.851398 95.191696 +22.691940 55.838467 95.201073 +36.798965 29.142998 95.191711 +36.792343 29.114094 95.191711 +34.075546 56.947475 95.191696 +34.079163 56.910137 95.179199 +34.116486 56.913746 95.191696 +34.103546 56.950184 95.201073 +14.409119 67.576645 101.985069 +19.253174 17.427784 101.985085 +22.694656 55.810482 95.466698 +22.691940 55.838467 95.457314 +22.682190 55.809261 95.429199 +22.691040 55.847797 95.429199 +22.682190 55.809261 95.229202 +22.691040 55.847797 95.229195 +25.364685 28.038525 95.429207 +25.377136 28.039730 95.466713 +25.390060 28.003307 95.457336 +25.380737 28.002392 95.429214 +25.364685 28.038525 95.229210 +25.380737 28.002392 95.229210 +34.112885 56.951077 95.229195 +34.128922 56.914928 95.229195 +34.128922 56.914928 95.429199 +34.112885 56.951077 95.429199 +34.103546 56.950184 95.457329 +34.116486 56.913746 95.466705 +36.798965 29.142998 95.466713 +36.811401 29.144199 95.429214 +36.811401 29.144199 95.229210 +36.802567 29.105679 95.229210 +36.802567 29.105679 95.429207 +36.801682 29.115009 95.457329 +25.414459 28.043316 95.479210 +25.418060 28.006012 95.466713 +36.765244 29.102077 95.466698 +36.761642 29.139393 95.479210 +22.731979 55.814083 95.479195 +22.728348 55.851398 95.466690 +34.079163 56.910137 95.479195 +34.075546 56.947475 95.466698 +34.074356 56.959904 95.429199 +22.727173 55.863857 95.429192 +34.074356 56.959904 95.229195 +22.727173 55.863857 95.229195 +25.419266 27.993565 95.429207 +25.419266 27.993565 95.229210 +36.766434 29.089626 95.429214 +36.766434 29.089626 95.229210 +8.875153 62.633190 130.125168 +12.347427 62.968586 110.341133 +16.347610 21.556057 110.341148 +12.875320 21.220657 130.125198 +5.706863 43.796139 106.963295 +33.308685 61.916687 95.506653 +31.478622 62.127151 96.195732 +31.523453 61.126381 95.942497 +24.229050 65.209167 95.209259 +22.995453 65.245811 95.508545 +24.239578 65.976151 95.865448 +23.196915 64.997963 95.351723 +22.472351 64.432724 95.414940 +23.190933 64.390694 95.194878 +25.852982 66.261078 96.083122 +25.923660 65.550308 95.186516 +28.548569 66.531967 96.164497 +28.618683 65.845886 95.192871 +30.931152 66.653091 95.941063 +31.052338 65.991043 95.195488 +32.716156 65.789085 95.279411 +32.894592 66.274818 95.492935 +33.526642 65.612503 95.414780 +32.975647 64.083923 95.162445 +33.857742 64.266319 95.414543 +31.305969 63.900269 95.003670 +28.854935 63.638275 94.980034 +26.152710 63.350006 94.989548 +33.863617 62.887047 95.414757 +33.082840 62.283501 95.303398 +31.504776 61.670441 95.259155 +29.162766 60.772652 96.164505 +29.101639 61.318420 95.265442 +26.405197 61.048401 95.256676 +26.465652 60.516106 96.083031 +24.739441 60.474792 95.837830 +24.700653 61.005707 95.276756 +24.403503 63.164505 95.021141 +22.546204 62.959801 95.414940 +23.302948 62.962952 95.166229 +23.578613 61.270309 95.309288 +23.000015 61.238602 95.430061 +23.550720 60.775475 95.516197 +33.125885 62.488159 95.720337 +33.013794 64.099106 95.809570 +29.052628 61.811325 96.436462 +26.344406 61.535881 96.350693 +24.622101 61.428223 96.106300 +28.857330 63.655716 96.590515 +26.140381 63.366035 96.480820 +24.377808 63.177887 96.199455 +23.494446 61.460281 95.724808 +23.255325 63.058197 95.815071 +23.151169 64.675156 95.724678 +24.245789 64.955109 96.106339 +25.952560 65.210144 96.350792 +28.659363 65.498062 96.436424 +31.098511 65.690918 96.195641 +31.323120 63.918724 96.299789 +32.783615 65.694832 95.720421 + + + + + + + + + + + +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 -0.000007 0.000000 +1.000000 -0.000007 0.000000 +1.000000 -0.000007 0.000000 +1.000000 -0.000007 0.000000 +1.000000 -0.000007 0.000000 +1.000000 -0.000007 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000014 0.000000 +-1.000000 0.000014 0.000000 +-1.000000 0.000014 0.000000 +-1.000000 0.000014 0.000000 +-1.000000 0.000014 0.000000 +-1.000000 0.000014 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.707100 0.707113 0.000000 +0.707100 0.707113 0.000000 +0.707100 0.707113 0.000000 +0.707100 0.707113 0.000000 +0.707100 0.707113 0.000000 +0.707100 0.707113 0.000000 +-0.707094 0.707119 0.000000 +-0.707094 0.707119 0.000000 +-0.707094 0.707119 0.000000 +-0.707094 0.707119 0.000000 +-0.707094 0.707119 0.000000 +-0.707094 0.707119 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000007 0.000000 +1.000000 0.000007 0.000000 +1.000000 0.000007 0.000000 +1.000000 0.000007 0.000000 +1.000000 0.000007 0.000000 +1.000000 0.000007 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-1.000000 -0.000014 0.000000 +-1.000000 -0.000014 0.000000 +-1.000000 -0.000014 0.000000 +-1.000000 -0.000014 0.000000 +-1.000000 -0.000014 0.000000 +-1.000000 -0.000014 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.707101 -0.707113 0.000000 +0.707101 -0.707113 0.000000 +0.707101 -0.707113 0.000000 +0.707101 -0.707113 0.000000 +0.707101 -0.707113 0.000000 +0.707101 -0.707113 0.000000 +-0.707094 -0.707119 0.000000 +-0.707094 -0.707119 0.000000 +-0.707094 -0.707119 0.000000 +-0.707094 -0.707119 0.000000 +-0.707094 -0.707119 0.000000 +-0.707094 -0.707119 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.000001 -1.000000 0.000000 +-0.000001 -1.000000 0.000000 +-0.000001 -1.000000 0.000000 +-0.000001 -1.000000 0.000000 +-0.000001 -1.000000 0.000000 +-0.000001 -1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 -0.000003 0.000000 +-1.000000 -0.000003 0.000000 +-1.000000 -0.000003 0.000000 +-1.000000 -0.000003 0.000000 +-1.000000 -0.000003 0.000000 +-1.000000 -0.000003 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +1.000000 0.000012 0.000000 +1.000000 0.000012 0.000000 +1.000000 0.000012 0.000000 +1.000000 0.000012 0.000000 +1.000000 0.000012 0.000000 +1.000000 0.000012 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.707113 -0.707100 0.000000 +0.707113 -0.707100 0.000000 +0.707113 -0.707100 0.000000 +0.707113 -0.707100 0.000000 +0.707113 -0.707100 0.000000 +0.707113 -0.707100 0.000000 +-0.707113 -0.707100 0.000000 +-0.707113 -0.707100 0.000000 +-0.707113 -0.707100 0.000000 +-0.707113 -0.707100 0.000000 +-0.707113 -0.707100 0.000000 +-0.707113 -0.707100 0.000000 +-0.707101 0.707113 0.000000 +-0.707101 0.707113 0.000000 +-0.707101 0.707113 0.000000 +-0.707101 0.707113 0.000000 +-0.707101 0.707113 0.000000 +-0.707101 0.707113 0.000000 +0.707101 0.707113 0.000000 +0.707101 0.707113 0.000000 +0.707101 0.707113 0.000000 +0.707101 0.707113 0.000000 +0.707101 0.707113 0.000000 +0.707101 0.707113 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000005 0.000000 +-1.000000 0.000005 0.000000 +-1.000000 0.000005 0.000000 +-1.000000 0.000005 0.000000 +-1.000000 0.000005 0.000000 +-1.000000 0.000005 0.000000 +-0.000001 -1.000000 0.000000 +-0.000001 -1.000000 0.000000 +-0.000001 -1.000000 0.000000 +-0.000001 -1.000000 0.000000 +-0.000001 -1.000000 0.000000 +-0.000001 -1.000000 0.000000 +1.000000 -0.000013 0.000000 +1.000000 -0.000013 0.000000 +1.000000 -0.000013 0.000000 +1.000000 -0.000013 0.000000 +1.000000 -0.000013 0.000000 +1.000000 -0.000013 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.707101 -0.707113 0.000000 +-0.707101 -0.707113 0.000000 +-0.707101 -0.707113 0.000000 +-0.707101 -0.707113 0.000000 +-0.707101 -0.707113 0.000000 +-0.707101 -0.707113 0.000000 +0.707101 -0.707113 0.000000 +0.707101 -0.707113 0.000000 +0.707101 -0.707113 0.000000 +0.707101 -0.707113 0.000000 +0.707101 -0.707113 0.000000 +0.707101 -0.707113 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.182561 0.983195 0.000000 +-0.182559 0.983195 0.000000 +0.182561 0.983195 0.000000 +-0.182559 0.983195 0.000000 +0.182561 0.983195 0.000000 +-0.182559 0.983195 0.000000 +-0.707108 0.707105 0.000000 +-0.983195 0.182557 0.000000 +-0.983195 0.182557 0.000000 +-0.983195 0.182557 0.000000 +-0.707108 0.707105 0.000000 +-0.707108 0.707105 0.000000 +-0.707108 -0.707105 0.000000 +-0.707108 -0.707105 0.000000 +-0.182559 -0.983195 0.000000 +-0.182559 -0.983195 0.000000 +-0.707108 -0.707105 0.000000 +-0.182559 -0.983195 0.000000 +0.707109 -0.707104 0.000000 +0.707109 -0.707104 0.000000 +0.983195 -0.182558 0.000000 +0.983195 -0.182558 0.000000 +0.707109 -0.707104 0.000000 +0.983195 -0.182558 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.983195 -0.182556 0.000000 +-0.983195 0.182557 0.000000 +-0.983195 0.182557 0.000000 +-0.983195 -0.182556 0.000000 +-0.983195 0.182557 0.000000 +-0.983195 -0.182556 0.000000 +-0.983195 -0.182556 0.000000 +-0.983195 -0.182556 0.000000 +-0.707108 -0.707105 0.000000 +-0.707108 -0.707105 0.000000 +-0.983195 -0.182556 0.000000 +-0.707108 -0.707105 0.000000 +-0.182559 -0.983195 0.000000 +0.182561 -0.983195 0.000000 +-0.182559 -0.983195 0.000000 +0.182561 -0.983195 0.000000 +-0.182559 -0.983195 0.000000 +0.182561 -0.983195 0.000000 +0.182561 -0.983195 0.000000 +0.182561 -0.983195 0.000000 +0.707109 -0.707104 0.000000 +0.707109 -0.707104 0.000000 +0.182561 -0.983195 0.000000 +0.707109 -0.707104 0.000000 +0.983195 -0.182558 0.000000 +0.983195 0.182558 0.000000 +0.983195 -0.182558 0.000000 +0.983195 0.182558 0.000000 +0.983195 -0.182558 0.000000 +0.983195 0.182558 0.000000 +0.983195 0.182558 0.000000 +0.983195 0.182558 0.000000 +0.707109 0.707104 0.000000 +0.707109 0.707104 0.000000 +0.983195 0.182558 0.000000 +0.707109 0.707104 0.000000 +0.707109 0.707104 0.000000 +0.707109 0.707104 0.000000 +0.182561 0.983195 0.000000 +0.182561 0.983195 0.000000 +0.707109 0.707104 0.000000 +0.182561 0.983195 0.000000 +-0.182559 0.983195 0.000000 +-0.182559 0.983195 0.000000 +-0.707108 0.707105 0.000000 +-0.707108 0.707105 0.000000 +-0.182559 0.983195 0.000000 +-0.707108 0.707105 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 -0.000007 +1.000000 -0.000000 -0.000007 +1.000000 -0.000000 -0.000007 +1.000000 -0.000000 -0.000007 +1.000000 -0.000000 -0.000007 +1.000000 -0.000000 -0.000007 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +-1.000000 0.000000 0.000014 +-1.000000 0.000000 0.000014 +-1.000000 0.000000 0.000014 +-1.000000 0.000000 0.000014 +-1.000000 0.000000 0.000014 +-1.000000 0.000000 0.000014 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +-0.707106 0.000000 -0.707108 +-0.707106 0.000000 -0.707108 +-0.707106 0.000000 -0.707108 +-0.707106 0.000000 -0.707108 +-0.707106 0.000000 -0.707108 +-0.707106 0.000000 -0.707108 +0.707106 -0.000000 -0.707108 +0.707106 -0.000000 -0.707108 +0.707106 -0.000000 -0.707108 +0.707106 -0.000000 -0.707108 +0.707106 -0.000000 -0.707108 +0.707106 -0.000000 -0.707108 +0.707106 -0.000000 0.707107 +0.707106 -0.000000 0.707107 +0.707106 -0.000000 0.707107 +0.707106 -0.000000 0.707107 +0.707106 -0.000000 0.707107 +0.707106 -0.000000 0.707107 +-0.707100 0.000000 0.707114 +-0.707100 0.000000 0.707114 +-0.707100 0.000000 0.707114 +-0.707100 0.000000 0.707114 +-0.707100 0.000000 0.707114 +-0.707100 0.000000 0.707114 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 -0.000003 +-1.000000 0.000000 -0.000003 +-1.000000 0.000000 -0.000003 +-1.000000 0.000000 -0.000003 +-1.000000 0.000000 -0.000003 +-1.000000 0.000000 -0.000003 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +1.000000 -0.000000 0.000013 +1.000000 -0.000000 0.000013 +1.000000 -0.000000 0.000013 +1.000000 -0.000000 0.000013 +1.000000 -0.000000 0.000013 +1.000000 -0.000000 0.000013 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.707106 -0.000000 -0.707108 +0.707106 -0.000000 -0.707108 +0.707106 -0.000000 -0.707108 +0.707106 -0.000000 -0.707108 +0.707106 -0.000000 -0.707108 +0.707106 -0.000000 -0.707108 +-0.707106 0.000000 -0.707108 +-0.707106 0.000000 -0.707108 +-0.707106 0.000000 -0.707108 +-0.707106 0.000000 -0.707108 +-0.707106 0.000000 -0.707108 +-0.707106 0.000000 -0.707108 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +0.707107 -0.000000 0.707107 +0.707107 -0.000000 0.707107 +0.707107 -0.000000 0.707107 +0.707107 -0.000000 0.707107 +0.707107 -0.000000 0.707107 +0.707107 -0.000000 0.707107 +-0.056807 0.998385 -0.000001 +-0.056807 0.998385 -0.000001 +-0.056807 0.998385 -0.000001 +-0.056807 0.998385 -0.000001 +-0.056807 0.998385 -0.000001 +-0.056807 0.998385 -0.000001 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.998385 0.056807 0.000000 +0.998385 0.056807 0.000000 +0.998385 0.056807 0.000000 +0.998385 0.056807 0.000000 +0.998385 0.056807 0.000000 +0.998385 0.056807 0.000000 +0.056807 -0.998385 0.000000 +0.056807 -0.998385 0.000000 +0.056807 -0.998385 0.000000 +0.056807 -0.998385 0.000000 +0.056807 -0.998385 0.000000 +0.056807 -0.998385 0.000000 +-0.998385 -0.056809 0.000000 +-0.998385 -0.056809 0.000000 +-0.998385 -0.056809 0.000000 +-0.998385 -0.056809 0.000000 +-0.998385 -0.056809 0.000000 +-0.998385 -0.056809 0.000000 +-0.056807 0.998385 -0.000001 +-0.056807 0.998385 -0.000001 +-0.056807 0.998385 -0.000001 +-0.056807 0.998385 -0.000001 +-0.056807 0.998385 -0.000001 +-0.056807 0.998385 -0.000001 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.998385 0.056807 -0.000000 +0.998385 0.056807 -0.000000 +0.998385 0.056807 -0.000000 +0.998385 0.056807 -0.000000 +0.998385 0.056807 -0.000000 +0.998385 0.056807 -0.000000 +0.056807 -0.998385 0.000000 +0.056807 -0.998385 0.000000 +0.056807 -0.998385 0.000000 +0.056807 -0.998385 0.000000 +0.056807 -0.998385 0.000000 +0.056807 -0.998385 0.000000 +-0.998385 -0.056807 0.000000 +-0.998385 -0.056807 0.000000 +-0.998385 -0.056807 0.000000 +-0.998385 -0.056807 0.000000 +-0.998385 -0.056807 0.000000 +-0.998385 -0.056807 0.000000 +0.047896 -0.998852 -0.000004 +0.047896 -0.998852 -0.000004 +0.047896 -0.998852 -0.000004 +0.047896 -0.998852 -0.000004 +0.047896 -0.998852 -0.000004 +0.047896 -0.998852 -0.000004 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.998852 0.047893 -0.000002 +0.998852 0.047893 -0.000002 +0.998852 0.047893 -0.000002 +0.998852 0.047893 -0.000002 +0.998852 0.047893 -0.000002 +0.998852 0.047893 -0.000002 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.998852 -0.047893 0.000000 +-0.998852 -0.047893 0.000000 +-0.998853 -0.047893 0.000000 +-0.998852 -0.047893 0.000000 +-0.998853 -0.047893 0.000000 +-0.998852 -0.047893 0.000000 +-0.047897 0.998852 -0.000004 +-0.047897 0.998852 -0.000004 +-0.047897 0.998852 -0.000004 +-0.047897 0.998852 -0.000004 +-0.047897 0.998852 -0.000004 +-0.047897 0.998852 -0.000004 +0.076038 -0.997105 -0.000003 +0.076038 -0.997105 -0.000003 +0.076038 -0.997105 -0.000003 +0.076038 -0.997105 -0.000003 +0.076038 -0.997105 -0.000003 +0.076038 -0.997105 -0.000003 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.997105 0.076034 -0.000001 +0.997105 0.076034 -0.000001 +0.997105 0.076034 -0.000001 +0.997105 0.076034 -0.000001 +0.997105 0.076034 -0.000001 +0.997105 0.076034 -0.000001 +0.000000 -0.000001 1.000000 +0.000000 -0.000001 1.000000 +0.000000 -0.000001 1.000000 +0.000000 -0.000001 1.000000 +0.000000 -0.000001 1.000000 +0.000000 -0.000001 1.000000 +-0.997105 -0.076034 0.000000 +-0.997105 -0.076034 0.000000 +-0.997105 -0.076034 0.000000 +-0.997105 -0.076034 0.000000 +-0.997105 -0.076034 0.000000 +-0.997105 -0.076034 0.000000 +-0.076038 0.997105 0.000001 +-0.076038 0.997105 0.000001 +-0.076038 0.997105 0.000001 +-0.076038 0.997105 0.000001 +-0.076038 0.997105 0.000001 +-0.076038 0.997105 0.000001 +0.076038 -0.997105 -0.000003 +0.076038 -0.997105 -0.000003 +0.076038 -0.997105 -0.000003 +0.076038 -0.997105 -0.000003 +0.076038 -0.997105 -0.000003 +0.076038 -0.997105 -0.000003 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.997105 0.076034 -0.000001 +0.997105 0.076034 -0.000001 +0.997105 0.076034 -0.000001 +0.997105 0.076034 -0.000001 +0.997105 0.076034 -0.000001 +0.997105 0.076034 -0.000001 +0.000000 -0.000001 1.000000 +0.000000 -0.000001 1.000000 +0.000000 -0.000001 1.000000 +0.000000 -0.000001 1.000000 +0.000000 -0.000001 1.000000 +0.000000 -0.000001 1.000000 +-0.997105 -0.076034 0.000000 +-0.997105 -0.076034 0.000000 +-0.997105 -0.076034 0.000000 +-0.997105 -0.076034 0.000000 +-0.997105 -0.076034 0.000000 +-0.997105 -0.076034 0.000000 +-0.076038 0.997105 0.000001 +-0.076038 0.997105 0.000001 +-0.076038 0.997105 0.000001 +-0.076038 0.997105 0.000001 +-0.076038 0.997105 0.000001 +-0.076038 0.997105 0.000001 +-0.894910 -0.308786 0.322160 +-0.884446 -0.102399 0.455270 +-0.914800 -0.245199 0.320964 +0.034962 -0.993747 0.106042 +0.095796 -0.991586 0.087064 +0.095794 -0.991587 0.087061 +0.022914 -0.993696 0.109741 +0.095796 -0.991586 0.087064 +0.034962 -0.993747 0.106042 +0.022914 -0.993696 0.109741 +0.082047 -0.989854 0.116006 +0.080800 -0.989940 0.116145 +0.082047 -0.989854 0.116006 +0.022914 -0.993696 0.109741 +0.034962 -0.993747 0.106042 +-0.059996 0.589474 -0.805557 +-0.100291 0.944861 -0.311736 +-0.067044 0.650716 -0.756356 +-0.100291 0.944861 -0.311736 +-0.103584 0.975661 -0.193277 +-0.067044 0.650716 -0.756356 +-0.100291 0.944861 -0.311736 +-0.095563 0.937572 0.334406 +-0.103584 0.975661 -0.193277 +-0.095563 0.937572 0.334406 +-0.089447 0.894973 0.437060 +-0.103584 0.975661 -0.193277 +-0.095563 0.937572 0.334406 +-0.044960 0.540904 0.839882 +-0.089447 0.894973 0.437060 +-0.044960 0.540904 0.839882 +-0.039044 0.490865 0.870360 +-0.089447 0.894973 0.437060 +-0.696848 -0.067315 0.714052 +-0.695053 -0.067142 0.715817 +-0.564298 -0.054514 0.823769 +-0.564298 -0.054514 0.823769 +-0.695053 -0.067142 0.715817 +-0.564298 -0.054514 0.823769 +-0.888900 -0.068381 0.452968 +-0.695053 -0.067142 0.715817 +-0.696848 -0.067315 0.714052 +-0.695053 -0.067142 0.715817 +-0.888900 -0.068381 0.452968 +-0.884446 -0.102399 0.455270 +-0.945513 -0.091326 0.312512 +-0.888900 -0.068381 0.452968 +-0.944512 0.048460 0.324881 +-0.888900 -0.068381 0.452968 +-0.945513 -0.091332 0.312512 +-0.884446 -0.102399 0.455270 +-0.945513 -0.091332 0.312512 +-0.888900 -0.068381 0.452968 +-0.945513 -0.091326 0.312512 +-0.945512 -0.091327 0.312517 +-0.984184 -0.028610 0.174824 +-0.945512 -0.091330 0.312515 +-0.944512 0.048460 0.324881 +-0.984184 -0.028610 0.174824 +-0.945512 -0.091327 0.312517 +-0.984184 -0.028610 0.174824 +-0.970173 -0.166491 0.176198 +-0.945513 -0.091333 0.312513 +-0.984184 -0.028610 0.174824 +-0.945513 -0.091333 0.312513 +-0.945512 -0.091330 0.312515 +-0.970173 -0.166491 0.176198 +-0.945514 -0.091326 0.312510 +-0.945513 -0.091331 0.312511 +-0.945513 -0.091333 0.312513 +-0.970173 -0.166491 0.176198 +-0.945513 -0.091331 0.312511 +-0.953813 -0.092132 -0.285924 +-0.955152 -0.092262 -0.281376 +-0.984184 -0.028610 0.174824 +-0.970173 -0.166491 0.176198 +-0.984184 -0.028610 0.174824 +-0.955152 -0.092262 -0.281376 +-0.953813 -0.092132 -0.285924 +-0.693562 -0.066995 -0.717275 +-0.955152 -0.092262 -0.281376 +-0.693562 -0.066995 -0.717275 +-0.953813 -0.092132 -0.285924 +-0.690150 -0.066666 -0.720589 +-0.693562 -0.066995 -0.717275 +-0.690150 -0.066666 -0.720589 +-0.233076 -0.022519 -0.972198 +-0.233076 -0.022519 -0.972198 +-0.690150 -0.066666 -0.720589 +-0.235194 -0.022722 -0.971683 +-0.011215 -0.000976 -0.999937 +-0.233076 -0.022519 -0.972198 +-0.235194 -0.022722 -0.971683 +-0.233076 -0.022519 -0.972198 +-0.011215 -0.000976 -0.999937 +-0.009327 -0.001069 -0.999956 +-0.009327 -0.001069 -0.999956 +-0.011215 -0.000976 -0.999937 +-0.010358 -0.000892 -0.999946 +-0.010358 -0.000892 -0.999946 +-0.011215 -0.000976 -0.999937 +-0.005818 0.000164 -0.999983 +-0.010358 -0.000892 -0.999946 +-0.005818 0.000164 -0.999983 +-0.005818 0.000164 -0.999983 +-0.006246 -0.000758 -0.999980 +-0.009327 -0.001069 -0.999956 +-0.010358 -0.000892 -0.999946 +-0.009327 -0.001069 -0.999956 +-0.006246 -0.000758 -0.999980 +-0.005661 -0.001311 -0.999983 +-0.009327 -0.001069 -0.999956 +-0.005661 -0.001311 -0.999983 +-0.005661 -0.001311 -0.999983 +0.489289 -0.867677 0.087938 +0.876674 -0.478765 0.047187 +0.887842 -0.457921 0.045217 +0.876674 -0.478765 0.047187 +0.489289 -0.867677 0.087938 +0.477266 -0.874267 0.088739 +0.008796 0.990106 0.140044 +0.400480 0.909619 0.110493 +0.007350 0.990104 0.140140 +0.400480 0.909619 0.110493 +0.008796 0.990106 0.140044 +0.415477 0.903028 0.109176 +0.007350 0.990104 0.140140 +-0.144185 0.979960 0.137438 +0.008796 0.990106 0.140044 +-0.144185 0.979960 0.137438 +0.007350 0.990104 0.140140 +-0.136214 0.981444 0.134956 +-0.095436 0.987911 0.122162 +-0.144185 0.979960 0.137438 +-0.136214 0.981444 0.134956 +-0.136214 0.981444 0.134956 +-0.095437 0.987911 0.122165 +-0.095436 0.987911 0.122162 +-0.095403 0.987927 0.122062 +-0.095437 0.987911 0.122165 +-0.095398 0.987929 0.122050 +-0.095437 0.987911 0.122165 +-0.095403 0.987927 0.122062 +-0.095436 0.987911 0.122162 +-0.095359 0.987946 0.121941 +-0.095403 0.987927 0.122062 +-0.095398 0.987929 0.122050 +-0.095403 0.987927 0.122062 +-0.095359 0.987946 0.121941 +-0.095359 0.987946 0.121941 +-0.937979 0.111219 0.328370 +-0.944512 0.048460 0.324881 +-0.888900 -0.068381 0.452968 +-0.944512 0.048460 0.324881 +-0.937979 0.111219 0.328370 +-0.984184 -0.028610 0.174824 +0.907183 0.126177 -0.401369 +0.943226 0.162213 -0.289847 +0.987753 0.104459 -0.115896 +-0.095542 0.987799 0.122986 +-0.094443 0.987858 0.123362 +-0.095542 0.987799 0.122986 +-0.095542 0.987799 0.122986 +-0.094443 0.987858 0.123362 +-0.094442 0.987857 0.123362 +-0.094443 0.987858 0.123362 +-0.093352 0.987915 0.123734 +-0.094442 0.987857 0.123362 +-0.094442 0.987857 0.123362 +-0.093352 0.987915 0.123734 +-0.093352 0.987915 0.123734 +0.961460 0.274410 0.017123 +0.998675 -0.050885 0.007691 +0.997688 -0.067341 0.009147 +0.961460 0.274410 0.017123 +0.997688 -0.067341 0.009147 +0.953010 0.302233 0.020686 +0.076094 -0.897797 -0.433786 +0.044065 -0.488238 -0.871597 +0.048511 -0.545170 -0.836921 +0.048511 -0.545170 -0.836921 +0.079604 -0.942633 -0.324201 +0.076094 -0.897797 -0.433786 +-0.005119 0.065282 -0.997854 +0.044065 -0.488238 -0.871597 +-0.004444 0.058336 -0.998287 +0.044065 -0.488238 -0.871597 +-0.005119 0.065282 -0.997854 +0.048511 -0.545170 -0.836921 +-0.067044 0.650716 -0.756356 +-0.005119 0.065282 -0.997854 +-0.059996 0.589474 -0.805557 +-0.059996 0.589474 -0.805557 +-0.005119 0.065282 -0.997854 +-0.004444 0.058336 -0.998287 +0.980245 0.094682 0.173653 +0.980556 0.091409 0.173647 +0.980245 0.094683 0.173652 +0.980245 0.094682 0.173653 +0.980245 0.094683 0.173652 +0.980245 0.094681 0.173655 +0.980556 0.091409 0.173647 +0.980246 0.094685 0.173647 +0.980245 0.094683 0.173652 +0.980244 0.094688 0.173652 +0.980556 0.091409 0.173647 +0.980245 0.094682 0.173653 +0.980246 0.094685 0.173647 +0.980556 0.091409 0.173647 +0.980246 0.094685 0.173647 +0.980246 0.094685 0.173647 +0.980246 0.094685 0.173647 +0.980246 0.094685 0.173647 +0.980556 0.091409 0.173647 +0.980246 0.094686 0.173647 +0.980246 0.094685 0.173647 +0.980556 0.091409 0.173647 +0.980854 0.088165 0.173644 +0.980246 0.094686 0.173647 +0.980246 0.094686 0.173647 +0.980854 0.088165 0.173644 +0.980245 0.094686 0.173647 +0.980556 0.091409 0.173647 +0.981791 0.077091 0.173621 +0.980854 0.088165 0.173644 +0.981791 0.077091 0.173621 +0.980556 0.091409 0.173647 +0.981032 0.086166 0.173645 +0.981032 0.086166 0.173645 +0.980556 0.091409 0.173647 +0.980244 0.094688 0.173652 +0.981032 0.086166 0.173645 +0.980244 0.094688 0.173652 +0.980244 0.094688 0.173653 +0.489289 -0.867677 0.087938 +0.082047 -0.989854 0.116006 +0.477266 -0.874267 0.088739 +0.082047 -0.989854 0.116006 +0.489289 -0.867677 0.087938 +0.080800 -0.989940 0.116145 +0.095796 -0.991586 0.087064 +0.095787 -0.991596 0.086962 +0.095794 -0.991587 0.087061 +0.095787 -0.991597 0.086952 +0.095794 -0.991587 0.087061 +0.095787 -0.991596 0.086962 +0.095787 -0.991604 0.086867 +0.095787 -0.991597 0.086952 +0.095787 -0.991596 0.086962 +0.095787 -0.991597 0.086952 +0.095787 -0.991604 0.086867 +0.095787 -0.991604 0.086867 +0.913813 0.045537 -0.403575 +0.989072 0.085694 -0.119970 +0.956566 0.012053 -0.291267 +0.957507 -0.021930 -0.287574 +0.989072 0.085694 -0.119970 +0.913813 0.045537 -0.403575 +0.095697 -0.991544 0.087648 +0.096726 -0.991399 0.088164 +0.096719 -0.991400 0.088160 +0.095697 -0.991544 0.087648 +0.096719 -0.991400 0.088160 +0.095697 -0.991544 0.087648 +0.097741 -0.991254 0.088672 +0.096726 -0.991399 0.088164 +0.097741 -0.991254 0.088672 +0.096726 -0.991399 0.088164 +0.097741 -0.991254 0.088672 +0.096719 -0.991400 0.088160 +0.747958 0.660113 0.069351 +0.415477 0.903028 0.109176 +0.765427 0.640081 0.066459 +0.415477 0.903028 0.109176 +0.747958 0.660113 0.069351 +0.400480 0.909619 0.110493 +0.953010 0.302233 0.020686 +0.765427 0.640081 0.066459 +0.961460 0.274410 0.017123 +0.765427 0.640081 0.066459 +0.953010 0.302233 0.020686 +0.747958 0.660113 0.069351 +0.876674 -0.478765 0.047187 +0.997688 -0.067341 0.009147 +0.887842 -0.457921 0.045217 +0.998675 -0.050885 0.007691 +0.887842 -0.457921 0.045217 +0.997688 -0.067341 0.009147 +-0.039044 0.490865 0.870360 +0.018733 -0.063991 0.997775 +0.018089 -0.057084 0.998205 +0.018733 -0.063991 0.997775 +-0.039044 0.490865 0.870360 +-0.044960 0.540904 0.839882 +0.018733 -0.063991 0.997775 +0.066135 -0.646321 0.760194 +0.062316 -0.590375 0.804720 +0.062316 -0.590375 0.804720 +0.018089 -0.057084 0.998205 +0.018733 -0.063991 0.997775 +-0.189901 0.692069 0.696403 +-0.189905 0.692018 0.696453 +-0.190541 0.222693 0.956087 +-0.189905 0.692018 0.696453 +-0.190541 0.222691 0.956087 +-0.190541 0.222693 0.956087 +-0.190541 0.222691 0.956087 +-0.144401 -0.255027 0.956091 +-0.190541 0.222693 0.956087 +-0.144401 -0.255027 0.956091 +-0.190541 0.222691 0.956087 +-0.144399 -0.255045 0.956086 +-0.053930 -0.715570 0.696456 +-0.144401 -0.255027 0.956091 +-0.144399 -0.255045 0.956086 +-0.144401 -0.255027 0.956091 +-0.053930 -0.715570 0.696456 +-0.053918 -0.715611 0.696415 +0.987753 0.104459 -0.115896 +0.949992 0.091486 -0.298573 +0.949992 0.091488 -0.298573 +0.949992 0.091484 -0.298572 +0.989072 0.085694 -0.119970 +0.949992 0.091488 -0.298573 +0.949992 0.091488 -0.298573 +0.989072 0.085694 -0.119970 +0.987753 0.104459 -0.115896 +0.956566 0.012053 -0.291267 +0.989072 0.085694 -0.119970 +0.949993 0.091481 -0.298571 +0.949993 0.091481 -0.298571 +0.989072 0.085694 -0.119970 +0.949992 0.091484 -0.298572 +0.913813 0.045537 -0.403575 +0.949992 0.091485 -0.298572 +0.907183 0.126177 -0.401369 +0.907183 0.126177 -0.401369 +0.949992 0.091485 -0.298572 +0.949992 0.091490 -0.298571 +0.943226 0.162213 -0.289847 +0.907183 0.126177 -0.401369 +0.949992 0.091490 -0.298571 +0.686032 0.066194 -0.724554 +0.907183 0.126177 -0.401369 +0.687764 0.066360 -0.722895 +0.907183 0.126177 -0.401369 +0.686032 0.066194 -0.724554 +0.913813 0.045537 -0.403575 +0.987753 0.104459 -0.115896 +0.989072 0.085694 -0.119970 +0.955110 0.092195 0.281541 +0.987753 0.104459 -0.115896 +0.955110 0.092195 0.281541 +0.953695 0.092060 0.286341 +0.678939 0.065580 0.731260 +0.953695 0.092060 0.286341 +0.955110 0.092195 0.281541 +0.953695 0.092060 0.286341 +0.678939 0.065580 0.731260 +0.675427 0.065240 0.734535 +0.229456 0.022162 0.973067 +0.231462 0.022354 0.972587 +0.675427 0.065240 0.734535 +0.675427 0.065240 0.734535 +0.678939 0.065580 0.731260 +0.229456 0.022162 0.973067 +0.229456 0.022162 0.973067 +0.029721 0.002419 0.999555 +0.231462 0.022354 0.972587 +0.029721 0.002419 0.999555 +0.027664 0.003301 0.999612 +0.028855 0.002329 0.999581 +0.027664 0.003301 0.999612 +0.029721 0.002419 0.999555 +0.229456 0.022162 0.973067 +0.022922 -0.000632 0.999737 +0.028855 0.002329 0.999581 +0.022922 -0.000632 0.999737 +0.029721 0.002419 0.999555 +0.028855 0.002329 0.999581 +0.022922 -0.000632 0.999737 +0.028855 0.002329 0.999581 +0.027664 0.003301 0.999612 +0.024653 0.002956 0.999692 +0.022343 0.005161 0.999737 +0.027664 0.003301 0.999612 +0.022343 0.005161 0.999737 +0.024653 0.002956 0.999692 +0.027664 0.003301 0.999612 +0.022343 0.005161 0.999737 +-0.051697 0.970308 -0.236282 +0.054470 0.715626 -0.696357 +-0.051685 0.970295 -0.236340 +0.054470 0.715626 -0.696357 +-0.051697 0.970308 -0.236282 +0.054458 0.715668 -0.696314 +-0.134620 0.962300 0.236341 +-0.051697 0.970308 -0.236282 +-0.134630 0.962281 0.236412 +-0.134630 0.962281 0.236412 +-0.051697 0.970308 -0.236282 +-0.051685 0.970295 -0.236340 +-0.189905 0.692018 0.696453 +-0.134620 0.962300 0.236341 +-0.134630 0.962281 0.236412 +-0.134620 0.962300 0.236341 +-0.189905 0.692018 0.696453 +-0.189901 0.692069 0.696403 +0.165839 -0.872948 -0.458759 +0.190477 -0.692014 -0.696301 +0.165839 -0.872948 -0.458759 +0.190477 -0.692014 -0.696301 +0.165839 -0.872948 -0.458759 +0.190480 -0.691974 -0.696340 +-0.923439 -0.345052 -0.167928 +-0.969930 -0.213588 -0.116691 +-0.971514 -0.195910 -0.133340 +0.004824 -0.888495 0.458861 +-0.053918 -0.715611 0.696415 +-0.053930 -0.715570 0.696456 +-0.053918 -0.715611 0.696415 +0.004824 -0.888495 0.458861 +0.004824 -0.888495 0.458861 +-0.190545 -0.231267 -0.954048 +-0.160408 -0.194804 -0.967637 +-0.068716 -0.279452 -0.957698 +-0.160408 -0.194804 -0.967637 +-0.190545 -0.231267 -0.954048 +-0.261074 -0.120885 -0.957720 +-0.227399 0.187367 -0.955606 +-0.160408 -0.194804 -0.967637 +-0.261074 -0.120885 -0.957720 +-0.261074 -0.120885 -0.957720 +-0.325911 0.126454 -0.936905 +-0.227399 0.187367 -0.955606 +0.120916 -0.261176 -0.957688 +-0.068716 -0.279452 -0.957698 +-0.160408 -0.194804 -0.967637 +0.120916 -0.261176 -0.957688 +-0.160408 -0.194804 -0.967637 +0.194761 -0.160497 -0.967631 +-0.227399 0.187367 -0.955606 +-0.325911 0.126454 -0.936905 +-0.329093 0.271054 -0.904559 +-0.227399 0.187367 -0.955606 +-0.329093 0.271054 -0.904559 +-0.174379 0.297418 -0.938688 +0.120916 -0.261176 -0.957688 +0.194761 -0.160497 -0.967631 +0.231283 -0.190598 -0.954034 +0.231283 -0.190598 -0.954034 +0.194761 -0.160497 -0.967631 +0.279412 -0.068717 -0.957709 +-0.227399 0.187367 -0.955606 +0.126459 0.325880 -0.936915 +0.187396 0.227419 -0.955596 +0.126459 0.325880 -0.936915 +-0.227399 0.187367 -0.955606 +-0.174379 0.297418 -0.938688 +0.279412 -0.068717 -0.957709 +0.187396 0.227419 -0.955596 +0.297459 0.174288 -0.938692 +0.187396 0.227419 -0.955596 +0.279412 -0.068717 -0.957709 +0.194761 -0.160497 -0.967631 +0.187396 0.227419 -0.955596 +0.271080 0.329024 -0.904576 +0.297459 0.174288 -0.938692 +0.271080 0.329024 -0.904576 +0.187396 0.227419 -0.955596 +0.126459 0.325880 -0.936915 +0.686032 0.066194 -0.724554 +0.560466 0.054132 -0.826407 +0.560466 0.054132 -0.826407 +0.560466 0.054132 -0.826407 +0.686032 0.066194 -0.724554 +0.687764 0.066360 -0.722895 +0.144974 0.255092 -0.955987 +0.054458 0.715668 -0.696314 +0.144973 0.255098 -0.955985 +0.054458 0.715668 -0.696314 +0.144974 0.255092 -0.955987 +0.054470 0.715626 -0.696357 +0.191142 -0.222642 -0.955979 +0.144974 0.255092 -0.955987 +0.191140 -0.222622 -0.955984 +0.191140 -0.222622 -0.955984 +0.144974 0.255092 -0.955987 +0.144973 0.255098 -0.955985 +0.190477 -0.692014 -0.696301 +0.190480 -0.691974 -0.696340 +0.191142 -0.222642 -0.955979 +0.190477 -0.692014 -0.696301 +0.191142 -0.222642 -0.955979 +0.191140 -0.222622 -0.955984 +-0.962306 0.002818 0.271955 +-0.969875 0.119390 0.212341 +-0.990299 0.038395 0.133544 +-0.969875 0.119390 0.212341 +-0.979309 0.178460 0.095428 +-0.990299 0.038395 0.133544 +-0.979309 0.178460 0.095428 +-0.990313 0.038435 -0.133430 +-0.990299 0.038395 0.133544 +-0.990313 0.038435 -0.133430 +-0.979309 0.178460 0.095428 +-0.979309 0.178506 -0.095337 +-0.920325 -0.234400 0.313142 +-0.990299 0.038395 0.133544 +-0.955865 -0.248949 0.156033 +-0.990299 0.038395 0.133544 +-0.920325 -0.234400 0.313142 +-0.962306 0.002818 0.271955 +-0.871378 -0.386948 0.301614 +-0.920325 -0.234400 0.313142 +-0.955865 -0.248949 0.156033 +-0.871378 -0.386948 0.301614 +-0.955865 -0.248949 0.156033 +-0.902531 -0.400868 0.157301 +-0.990299 0.038395 0.133544 +-0.955899 -0.248885 -0.155927 +-0.955865 -0.248949 0.156033 +-0.955899 -0.248885 -0.155927 +-0.990299 0.038395 0.133544 +-0.990313 0.038435 -0.133430 +-0.969911 0.119520 -0.212103 +-0.990313 0.038435 -0.133430 +-0.979309 0.178506 -0.095337 +-0.990313 0.038435 -0.133430 +-0.969911 0.119520 -0.212103 +-0.962365 0.002879 -0.271746 +-0.990313 0.038435 -0.133430 +-0.917476 -0.246380 -0.312305 +-0.955899 -0.248885 -0.155927 +-0.917476 -0.246380 -0.312305 +-0.990313 0.038435 -0.133430 +-0.962365 0.002879 -0.271746 +-0.955865 -0.248949 0.156033 +-0.904328 -0.401518 -0.144827 +-0.902531 -0.400868 0.157301 +-0.904328 -0.401518 -0.144827 +-0.955865 -0.248949 0.156033 +-0.955899 -0.248885 -0.155927 +-0.904328 -0.401518 -0.144827 +-0.955899 -0.248885 -0.155927 +-0.871572 -0.386711 -0.301359 +-0.955899 -0.248885 -0.155927 +-0.917476 -0.246380 -0.312305 +-0.871572 -0.386711 -0.301359 +0.902676 0.400575 -0.157211 +0.955941 0.248771 -0.155853 +0.871496 0.386838 -0.301415 +0.955941 0.248771 -0.155853 +0.920454 0.234411 -0.312756 +0.871496 0.386838 -0.301415 +0.955945 0.248771 0.155830 +0.955941 0.248771 -0.155853 +0.902683 0.400573 0.157176 +0.902683 0.400573 0.157176 +0.955941 0.248771 -0.155853 +0.902676 0.400575 -0.157211 +0.920469 0.234411 0.312710 +0.955945 0.248771 0.155830 +0.871517 0.386839 0.301352 +0.871517 0.386839 0.301352 +0.955945 0.248771 0.155830 +0.902683 0.400573 0.157176 +0.990346 -0.038268 0.133232 +0.920469 0.234411 0.312710 +0.962475 -0.002661 0.271356 +0.920469 0.234411 0.312710 +0.990346 -0.038268 0.133232 +0.955945 0.248771 0.155830 +0.985875 -0.061392 -0.155824 +0.920454 0.234411 -0.312756 +0.955941 0.248771 -0.155853 +0.920454 0.234411 -0.312756 +0.985875 -0.061392 -0.155824 +0.947723 -0.066399 -0.312111 +0.955945 0.248771 0.155830 +0.990346 -0.038268 0.133232 +0.985875 -0.061392 -0.155824 +0.955945 0.248771 0.155830 +0.985875 -0.061392 -0.155824 +0.955941 0.248771 -0.155853 +0.964427 -0.221148 -0.144822 +0.929417 -0.213069 -0.301305 +0.985875 -0.061392 -0.155824 +0.985875 -0.061392 -0.155824 +0.929417 -0.213069 -0.301305 +0.947723 -0.066399 -0.312111 +0.979389 -0.178190 0.095109 +0.985875 -0.061392 -0.155824 +0.990346 -0.038268 0.133232 +0.985875 -0.061392 -0.155824 +0.979389 -0.178190 0.095109 +0.964427 -0.221148 -0.144822 +0.962475 -0.002661 0.271356 +0.970051 -0.119135 0.211679 +0.990346 -0.038268 0.133232 +0.970051 -0.119135 0.211679 +0.979389 -0.178190 0.095109 +0.990346 -0.038268 0.133232 +-0.140195 -0.170276 0.975373 +-0.297521 -0.174300 0.938670 +-0.271180 -0.329135 0.904506 +-0.140195 -0.170276 0.975373 +-0.271180 -0.329135 0.904506 +-0.126523 -0.326098 0.936831 +-0.140195 -0.170276 0.975373 +0.174277 -0.297782 0.938591 +0.170129 -0.140343 0.975377 +-0.126523 -0.326098 0.936831 +0.174277 -0.297782 0.938591 +-0.140195 -0.170276 0.975373 +-0.297521 -0.174300 0.938670 +-0.170151 0.140221 0.975391 +-0.325974 0.126570 0.936868 +-0.170151 0.140221 0.975391 +-0.297521 -0.174300 0.938670 +-0.140195 -0.170276 0.975373 +-0.329147 0.271195 0.904498 +-0.170151 0.140221 0.975391 +-0.174413 0.297532 0.938645 +-0.170151 0.140221 0.975391 +-0.329147 0.271195 0.904498 +-0.325974 0.126570 0.936868 +0.140124 0.170152 0.975404 +-0.140195 -0.170276 0.975373 +0.170129 -0.140343 0.975377 +-0.140195 -0.170276 0.975373 +0.140124 0.170152 0.975404 +-0.170151 0.140221 0.975391 +0.170129 -0.140343 0.975377 +0.328983 -0.271448 0.904481 +0.325848 -0.126699 0.936894 +0.328983 -0.271448 0.904481 +0.170129 -0.140343 0.975377 +0.174277 -0.297782 0.938591 +0.140124 0.170152 0.975404 +0.325848 -0.126699 0.936894 +0.297323 0.174270 0.938738 +0.325848 -0.126699 0.936894 +0.140124 0.170152 0.975404 +0.170129 -0.140343 0.975377 +-0.170151 0.140221 0.975391 +0.126351 0.325905 0.936921 +-0.174413 0.297532 0.938645 +0.126351 0.325905 0.936921 +-0.170151 0.140221 0.975391 +0.140124 0.170152 0.975404 +0.270893 0.329001 0.904641 +0.126351 0.325905 0.936921 +0.140124 0.170152 0.975404 +0.140124 0.170152 0.975404 +0.297323 0.174270 0.938738 +0.270893 0.329001 0.904641 +0.002624 0.962448 0.271453 +0.119029 0.970064 0.211678 +0.038200 0.990343 0.133269 +0.119029 0.970064 0.211678 +0.178011 0.979420 0.095118 +0.038200 0.990343 0.133269 +-0.234600 0.920346 0.312930 +0.038200 0.990343 0.133269 +-0.249008 0.955867 0.155927 +0.038200 0.990343 0.133269 +-0.234600 0.920346 0.312930 +0.002624 0.962448 0.271453 +0.038207 0.990342 -0.133275 +0.038200 0.990343 0.133269 +0.178011 0.979420 0.095118 +0.178011 0.979420 0.095118 +0.178025 0.979417 -0.095126 +0.038207 0.990342 -0.133275 +0.178025 0.979417 -0.095126 +0.119056 0.970055 -0.211704 +0.038207 0.990342 -0.133275 +0.038207 0.990342 -0.133275 +0.119056 0.970055 -0.211704 +0.002627 0.962444 -0.271469 +0.038207 0.990342 -0.133275 +-0.234614 0.920348 -0.312914 +-0.249014 0.955865 -0.155928 +-0.234614 0.920348 -0.312914 +0.038207 0.990342 -0.133275 +0.002627 0.962444 -0.271469 +-0.249008 0.955867 0.155927 +0.038200 0.990343 0.133269 +0.038207 0.990342 -0.133275 +-0.249008 0.955867 0.155927 +0.038207 0.990342 -0.133275 +-0.249014 0.955865 -0.155928 +-0.387173 0.871286 0.301593 +-0.234600 0.920346 0.312930 +-0.249008 0.955867 0.155927 +-0.387173 0.871286 0.301593 +-0.249008 0.955867 0.155927 +-0.401062 0.902441 0.157319 +-0.401076 0.902441 -0.157282 +-0.401062 0.902441 0.157319 +-0.249008 0.955867 0.155927 +-0.249008 0.955867 0.155927 +-0.249014 0.955865 -0.155928 +-0.401076 0.902441 -0.157282 +-0.401076 0.902441 -0.157282 +-0.249014 0.955865 -0.155928 +-0.387200 0.871285 -0.301559 +-0.249014 0.955865 -0.155928 +-0.234614 0.920348 -0.312914 +-0.387200 0.871285 -0.301559 +-0.002701 -0.962351 0.271797 +-0.119150 -0.969929 0.212230 +-0.038222 -0.990318 0.133453 +-0.119150 -0.969929 0.212230 +-0.178051 -0.979385 0.095407 +-0.038222 -0.990318 0.133453 +-0.178051 -0.979385 0.095407 +-0.220854 -0.964484 -0.144895 +-0.038222 -0.990318 0.133453 +-0.038222 -0.990318 0.133453 +-0.220854 -0.964484 -0.144895 +-0.061242 -0.985866 -0.155938 +0.234477 -0.920351 0.313009 +-0.038222 -0.990318 0.133453 +0.248936 -0.955876 0.155985 +-0.038222 -0.990318 0.133453 +0.234477 -0.920351 0.313009 +-0.002701 -0.962351 0.271797 +-0.061242 -0.985866 -0.155938 +-0.220854 -0.964484 -0.144895 +-0.212703 -0.929458 -0.301439 +-0.061242 -0.985866 -0.155938 +-0.212703 -0.929458 -0.301439 +-0.066213 -0.947665 -0.312326 +0.386984 -0.871383 0.301554 +0.234477 -0.920351 0.313009 +0.248936 -0.955876 0.155985 +0.386984 -0.871383 0.301554 +0.248936 -0.955876 0.155985 +0.400884 -0.902527 0.157281 +-0.038222 -0.990318 0.133453 +0.248903 -0.955896 -0.155918 +0.248936 -0.955876 0.155985 +0.248903 -0.955896 -0.155918 +-0.038222 -0.990318 0.133453 +-0.061242 -0.985866 -0.155938 +-0.061242 -0.985866 -0.155938 +0.246499 -0.917451 -0.312285 +0.248903 -0.955896 -0.155918 +0.246499 -0.917451 -0.312285 +-0.061242 -0.985866 -0.155938 +-0.066213 -0.947665 -0.312326 +0.248936 -0.955876 0.155985 +0.248903 -0.955896 -0.155918 +0.400884 -0.902527 0.157281 +0.400884 -0.902527 0.157281 +0.248903 -0.955896 -0.155918 +0.401588 -0.904296 -0.144833 +0.401588 -0.904296 -0.144833 +0.248903 -0.955896 -0.155918 +0.386858 -0.871508 -0.301354 +0.248903 -0.955896 -0.155918 +0.246499 -0.917451 -0.312285 +0.386858 -0.871508 -0.301354 +-0.993106 0.004527 -0.117131 +-0.990734 -0.022558 -0.133927 +-0.995209 -0.052149 -0.082701 +-0.993106 0.004527 -0.117131 +-0.995209 -0.052149 -0.082701 +-0.994818 -0.020939 -0.099492 +-0.993106 0.004527 -0.117131 +-0.973661 0.006392 -0.227910 +-0.990734 -0.022558 -0.133927 +-0.990734 -0.022558 -0.133927 +-0.973661 0.006392 -0.227910 +-0.976999 -0.021232 -0.212186 +-0.976999 -0.021232 -0.212186 +-0.973661 0.006392 -0.227910 +-0.963587 -0.049105 -0.262846 +-0.963587 -0.049105 -0.262846 +-0.973661 0.006392 -0.227910 +-0.969115 -0.018474 -0.245915 +-0.976999 -0.021232 -0.212186 +-0.955171 -0.136237 -0.262844 +-0.962998 -0.166167 -0.212185 +-0.955171 -0.136237 -0.262844 +-0.976999 -0.021232 -0.212186 +-0.963587 -0.049105 -0.262846 +-0.962998 -0.166167 -0.212185 +-0.955171 -0.136237 -0.262844 +-0.945716 -0.249931 -0.207738 +-0.945716 -0.249931 -0.207738 +-0.955171 -0.136237 -0.262844 +-0.954734 -0.167362 -0.245911 +-0.945716 -0.249931 -0.207738 +-0.971514 -0.195910 -0.133340 +-0.962998 -0.166167 -0.212185 +-0.990734 -0.022558 -0.133927 +-0.962998 -0.166167 -0.212185 +-0.971514 -0.195910 -0.133340 +-0.962998 -0.166167 -0.212185 +-0.990734 -0.022558 -0.133927 +-0.976999 -0.021232 -0.212186 +-0.986792 -0.139296 -0.082698 +-0.971514 -0.195910 -0.133340 +-0.969930 -0.213588 -0.116691 +-0.986792 -0.139296 -0.082698 +-0.969930 -0.213588 -0.116691 +-0.980435 -0.169852 -0.099487 +-0.995209 -0.052149 -0.082701 +-0.971514 -0.195910 -0.133340 +-0.986792 -0.139296 -0.082698 +-0.971514 -0.195910 -0.133340 +-0.995209 -0.052149 -0.082701 +-0.990734 -0.022558 -0.133927 +0.085296 -0.975419 0.203181 +0.076094 -0.897797 -0.433786 +0.079604 -0.942633 -0.324201 +0.079604 -0.942633 -0.324201 +0.084197 -0.944550 0.317389 +0.085296 -0.975419 0.203181 +0.084197 -0.944550 0.317389 +0.066135 -0.646321 0.760194 +0.085296 -0.975419 0.203181 +0.066135 -0.646321 0.760194 +0.084197 -0.944550 0.317389 +0.062316 -0.590375 0.804720 +0.987753 0.104459 -0.115896 +0.943226 0.162213 -0.289847 +0.949992 0.091484 -0.298574 +0.987753 0.104459 -0.115896 +0.949992 0.091484 -0.298574 +0.949992 0.091486 -0.298573 +-0.945513 -0.091334 0.312512 +-0.884446 -0.102399 0.455270 +-0.945513 -0.091332 0.312512 +-0.914800 -0.245199 0.320964 +-0.884446 -0.102399 0.455270 +-0.945513 -0.091334 0.312512 +0.913813 0.045537 -0.403575 +0.956566 0.012053 -0.291267 +0.949992 0.091478 -0.298574 +0.913813 0.045537 -0.403575 +0.949992 0.091478 -0.298574 +0.949992 0.091485 -0.298572 +-0.970173 -0.166491 0.176198 +-0.914800 -0.245199 0.320964 +-0.945514 -0.091326 0.312510 +0.371463 -0.209993 0.904388 +0.213507 -0.142220 0.966534 +0.212033 -0.234455 0.948722 +0.213507 -0.142220 0.966534 +0.371463 -0.209993 0.904388 +0.365035 -0.121486 0.923034 +-0.123553 0.677464 -0.725104 +-0.112032 0.393384 -0.912523 +-0.241238 0.474412 -0.846603 +-0.112032 0.393384 -0.912523 +-0.231824 0.382446 -0.894423 +-0.241238 0.474412 -0.846603 +-0.112032 0.393384 -0.912523 +-0.198358 0.110712 -0.973857 +-0.231824 0.382446 -0.894423 +-0.284254 0.110859 -0.952318 +-0.231824 0.382446 -0.894423 +-0.198358 0.110712 -0.973857 +-0.284254 0.110859 -0.952318 +-0.241238 0.474412 -0.846603 +-0.231824 0.382446 -0.894423 +-0.123553 0.677464 -0.725104 +-0.084240 0.761176 -0.643051 +-0.057199 0.465279 -0.883314 +-0.123553 0.677464 -0.725104 +-0.057199 0.465279 -0.883314 +-0.112032 0.393384 -0.912523 +-0.072786 0.788610 -0.610570 +-0.057199 0.465279 -0.883314 +-0.084240 0.761176 -0.643051 +-0.057199 0.465279 -0.883314 +-0.072786 0.788610 -0.610570 +-0.043677 0.485072 -0.873383 +0.005246 0.439375 -0.898288 +-0.043677 0.485072 -0.873383 +-0.032879 0.728711 -0.684032 +-0.072786 0.788610 -0.610570 +-0.032879 0.728711 -0.684032 +-0.043677 0.485072 -0.873383 +0.005246 0.439375 -0.898288 +0.112016 0.515381 -0.849609 +0.126415 0.309935 -0.942316 +0.112016 0.515381 -0.849609 +0.005246 0.439375 -0.898288 +-0.032879 0.728711 -0.684032 +0.112016 0.515381 -0.849609 +0.223820 0.139402 -0.964610 +0.126415 0.309935 -0.942316 +0.154594 0.009858 -0.987929 +0.223820 0.139402 -0.964610 +0.225859 0.025780 -0.973819 +0.223820 0.139402 -0.964610 +0.154594 0.009858 -0.987929 +0.126415 0.309935 -0.942316 +0.154594 0.009858 -0.987929 +0.043735 -0.005893 -0.999026 +0.126415 0.309935 -0.942316 +0.043735 -0.005893 -0.999026 +0.005246 0.439375 -0.898288 +0.126415 0.309935 -0.942316 +-0.008727 -0.014005 -0.999864 +-0.057199 0.465279 -0.883314 +0.004361 -0.012264 -0.999915 +0.004361 -0.012264 -0.999915 +-0.057199 0.465279 -0.883314 +-0.043677 0.485072 -0.873383 +0.004361 -0.012264 -0.999915 +0.005246 0.439375 -0.898288 +0.043735 -0.005893 -0.999026 +0.005246 0.439375 -0.898288 +0.004361 -0.012264 -0.999915 +-0.043677 0.485072 -0.873383 +0.213749 -0.303465 -0.928558 +0.154594 0.009858 -0.987929 +0.249843 -0.076274 -0.965278 +0.249843 -0.076274 -0.965278 +0.154594 0.009858 -0.987929 +0.225859 0.025780 -0.973819 +0.106868 -0.468740 -0.876848 +0.043735 -0.005893 -0.999026 +0.213749 -0.303465 -0.928558 +0.213749 -0.303465 -0.928558 +0.043735 -0.005893 -0.999026 +0.154594 0.009858 -0.987929 +0.213749 -0.303465 -0.928558 +0.249843 -0.076274 -0.965278 +0.260453 -0.515416 -0.816401 +0.260453 -0.515416 -0.816401 +0.133636 -0.758805 -0.637461 +0.106868 -0.468740 -0.876848 +0.260453 -0.515416 -0.816401 +0.106868 -0.468740 -0.876848 +0.213749 -0.303465 -0.928558 +0.133636 -0.758805 -0.637461 +0.092492 -0.830128 -0.549848 +0.059843 -0.526592 -0.848009 +0.133636 -0.758805 -0.637461 +0.059843 -0.526592 -0.848009 +0.106868 -0.468740 -0.876848 +0.076377 -0.818674 -0.569157 +0.059843 -0.526592 -0.848009 +0.092492 -0.830128 -0.549848 +0.059843 -0.526592 -0.848009 +0.076377 -0.818674 -0.569157 +0.043261 -0.517814 -0.854399 +-0.017401 -0.447683 -0.894023 +0.043261 -0.517814 -0.854399 +0.016557 -0.719952 -0.693827 +0.076377 -0.818674 -0.569157 +0.016557 -0.719952 -0.693827 +0.043261 -0.517814 -0.854399 +0.043261 -0.517814 -0.854399 +0.004361 -0.012264 -0.999915 +0.059843 -0.526592 -0.848009 +0.004361 -0.012264 -0.999915 +0.043261 -0.517814 -0.854399 +-0.008727 -0.014005 -0.999864 +0.059843 -0.526592 -0.848009 +0.004361 -0.012264 -0.999915 +0.106868 -0.468740 -0.876848 +0.106868 -0.468740 -0.876848 +0.004361 -0.012264 -0.999915 +0.043735 -0.005893 -0.999026 +0.043261 -0.517814 -0.854399 +-0.017401 -0.447683 -0.894023 +-0.008727 -0.014005 -0.999864 +-0.017401 -0.447683 -0.894023 +-0.052106 -0.020482 -0.998432 +-0.008727 -0.014005 -0.999864 +-0.052106 -0.020482 -0.998432 +-0.112032 0.393384 -0.912523 +-0.008727 -0.014005 -0.999864 +-0.008727 -0.014005 -0.999864 +-0.112032 0.393384 -0.912523 +-0.057199 0.465279 -0.883314 +-0.198358 0.110712 -0.973857 +-0.186357 -0.046392 -0.981386 +-0.285232 -0.051054 -0.957098 +-0.285232 -0.051054 -0.957098 +-0.284254 0.110859 -0.952318 +-0.198358 0.110712 -0.973857 +-0.052106 -0.020482 -0.998432 +-0.198358 0.110712 -0.973857 +-0.112032 0.393384 -0.912523 +-0.052106 -0.020482 -0.998432 +-0.186357 -0.046392 -0.981386 +-0.198358 0.110712 -0.973857 +-0.052106 -0.020482 -0.998432 +-0.017401 -0.447683 -0.894023 +-0.140344 -0.286276 -0.947813 +-0.140344 -0.286276 -0.947813 +-0.186357 -0.046392 -0.981386 +-0.052106 -0.020482 -0.998432 +-0.235710 -0.188135 -0.953439 +-0.186357 -0.046392 -0.981386 +-0.140344 -0.286276 -0.947813 +-0.186357 -0.046392 -0.981386 +-0.235710 -0.188135 -0.953439 +-0.285232 -0.051054 -0.957098 +-0.088877 -0.527350 -0.844987 +-0.017401 -0.447683 -0.894023 +0.016557 -0.719952 -0.693827 +-0.017401 -0.447683 -0.894023 +-0.088877 -0.527350 -0.844987 +-0.140344 -0.286276 -0.947813 +-0.437132 -0.198064 0.877317 +-0.339633 -0.296734 0.892524 +-0.377945 -0.191019 0.905908 +0.341452 0.036601 0.939186 +0.420796 -0.049727 0.905791 +0.403106 0.048794 0.913852 +0.341452 0.036601 0.939186 +0.365035 -0.121486 0.923034 +0.420796 -0.049727 0.905791 +0.052390 -0.159169 0.985860 +0.212033 -0.234455 0.948722 +0.213507 -0.142220 0.966534 +0.212033 -0.234455 0.948722 +0.052390 -0.159169 0.985860 +0.060567 -0.246807 0.967170 +0.052390 -0.159169 0.985860 +-0.074773 -0.173604 0.981973 +-0.063017 -0.264344 0.962367 +0.052390 -0.159169 0.985860 +-0.063017 -0.264344 0.962367 +0.060567 -0.246807 0.967170 +-0.210094 -0.285228 0.935150 +-0.074773 -0.173604 0.981973 +-0.225022 -0.190033 0.955643 +-0.074773 -0.173604 0.981973 +-0.210094 -0.285228 0.935150 +-0.063017 -0.264344 0.962367 +0.035931 0.003849 0.999347 +-0.092507 -0.010054 0.995661 +-0.074773 -0.173604 0.981973 +0.035931 0.003849 0.999347 +-0.074773 -0.173604 0.981973 +0.052390 -0.159169 0.985860 +-0.092507 -0.010054 0.995661 +-0.238985 -0.025723 0.970682 +-0.225022 -0.190033 0.955643 +-0.092507 -0.010054 0.995661 +-0.225022 -0.190033 0.955643 +-0.074773 -0.173604 0.981973 +-0.225022 -0.190033 0.955643 +-0.377945 -0.191019 0.905908 +-0.339633 -0.296734 0.892524 +-0.225022 -0.190033 0.955643 +-0.339633 -0.296734 0.892524 +-0.210094 -0.285228 0.935150 +-0.464748 -0.058780 0.883490 +-0.437132 -0.198064 0.877317 +-0.377945 -0.191019 0.905908 +-0.464748 -0.058780 0.883490 +-0.377945 -0.191019 0.905908 +-0.396619 -0.046873 0.916786 +-0.396619 -0.046873 0.916786 +-0.377945 -0.191019 0.905908 +-0.238985 -0.025723 0.970682 +-0.377945 -0.191019 0.905908 +-0.225022 -0.190033 0.955643 +-0.238985 -0.025723 0.970682 +-0.396619 -0.046873 0.916786 +-0.405341 0.115799 0.906802 +-0.459857 0.055365 0.886265 +-0.459857 0.055365 0.886265 +-0.464748 -0.058780 0.883490 +-0.396619 -0.046873 0.916786 +-0.263020 0.133742 0.955475 +-0.405341 0.115799 0.906802 +-0.238985 -0.025723 0.970682 +-0.405341 0.115799 0.906802 +-0.396619 -0.046873 0.916786 +-0.238985 -0.025723 0.970682 +-0.409500 0.212869 0.887128 +-0.263020 0.133742 0.955475 +-0.255343 0.225120 0.940277 +-0.263020 0.133742 0.955475 +-0.409500 0.212869 0.887128 +-0.405341 0.115799 0.906802 +-0.263020 0.133742 0.955475 +-0.092507 -0.010054 0.995661 +-0.106685 0.149303 0.983019 +-0.092507 -0.010054 0.995661 +-0.263020 0.133742 0.955475 +-0.238985 -0.025723 0.970682 +-0.255343 0.225120 0.940277 +-0.106685 0.149303 0.983019 +-0.112195 0.236344 0.965170 +-0.106685 0.149303 0.983019 +-0.255343 0.225120 0.940277 +-0.263020 0.133742 0.955475 +-0.106685 0.149303 0.983019 +0.019033 0.167169 0.985745 +-0.112195 0.236344 0.965170 +0.009152 0.254961 0.966908 +-0.112195 0.236344 0.965170 +0.019033 0.167169 0.985745 +0.157858 0.279605 0.947049 +0.009152 0.254961 0.966908 +0.019033 0.167169 0.985745 +0.157858 0.279605 0.947049 +0.019033 0.167169 0.985745 +0.178680 0.187001 0.965973 +-0.092507 -0.010054 0.995661 +0.035931 0.003849 0.999347 +-0.106685 0.149303 0.983019 +0.019033 0.167169 0.985745 +-0.106685 0.149303 0.983019 +0.035931 0.003849 0.999347 +0.178680 0.187001 0.965973 +0.019033 0.167169 0.985745 +0.035931 0.003849 0.999347 +0.178680 0.187001 0.965973 +0.035931 0.003849 0.999347 +0.193154 0.020749 0.980949 +0.035931 0.003849 0.999347 +0.213507 -0.142220 0.966534 +0.193154 0.020749 0.980949 +0.213507 -0.142220 0.966534 +0.035931 0.003849 0.999347 +0.052390 -0.159169 0.985860 +0.193154 0.020749 0.980949 +0.365035 -0.121486 0.923034 +0.341452 0.036601 0.939186 +0.365035 -0.121486 0.923034 +0.193154 0.020749 0.980949 +0.213507 -0.142220 0.966534 +0.324062 0.194740 0.925775 +0.341452 0.036601 0.939186 +0.396753 0.150574 0.905491 +0.341452 0.036601 0.939186 +0.403106 0.048794 0.913852 +0.396753 0.150574 0.905491 +0.324062 0.194740 0.925775 +0.178680 0.187001 0.965973 +0.193154 0.020749 0.980949 +0.324062 0.194740 0.925775 +0.193154 0.020749 0.980949 +0.341452 0.036601 0.939186 +0.316330 0.286373 0.904393 +0.157858 0.279605 0.947049 +0.178680 0.187001 0.965973 +0.316330 0.286373 0.904393 +0.178680 0.187001 0.965973 +0.324062 0.194740 0.925775 +0.420796 -0.049727 0.905791 +0.365035 -0.121486 0.923034 +0.371463 -0.209993 0.904388 +0.316330 0.286373 0.904393 +0.324062 0.194740 0.925775 +0.396753 0.150574 0.905491 +-0.459857 0.055365 0.886265 +-0.405341 0.115799 0.906802 +-0.409500 0.212869 0.887128 +-0.235710 -0.188135 -0.953439 +-0.140344 -0.286276 -0.947813 +-0.088877 -0.527350 -0.844987 + + + + + + + + + + + +0.693248 0.853291 +0.684005 0.853291 +0.684005 0.636373 +0.693248 0.636373 +0.680219 0.853291 +0.660708 0.853291 +0.660708 0.636373 +0.680219 0.636373 +0.656922 0.853291 +0.647679 0.853291 +0.647679 0.636373 +0.656922 0.636373 +0.883212 0.635500 +0.883212 0.852230 +0.875187 0.852230 +0.875187 0.635500 +0.763108 0.852890 +0.763108 0.635068 +0.779869 0.635068 +0.779869 0.852890 +0.757962 0.637031 +0.757962 0.853724 +0.749938 0.853724 +0.749938 0.637031 +0.644769 0.636163 +0.644769 0.853081 +0.635526 0.853081 +0.635526 0.636163 +0.631741 0.636163 +0.631741 0.853081 +0.612230 0.853081 +0.612230 0.636163 +0.608445 0.636163 +0.608445 0.853081 +0.599202 0.853081 +0.599202 0.636163 +0.948280 0.633473 +0.956347 0.633473 +0.956347 0.851355 +0.948280 0.851355 +0.866868 0.852494 +0.850220 0.852494 +0.850220 0.636140 +0.866868 0.636140 +0.945403 0.851480 +0.937335 0.851480 +0.937335 0.633598 +0.945403 0.633598 +0.584316 0.893899 +0.584382 0.903166 +0.585411 0.904181 +0.605017 0.904031 +0.606032 0.903000 +0.605961 0.893707 +0.533227 0.854091 +0.533227 0.638586 +0.585787 0.901940 +0.585728 0.893888 +0.539592 0.853920 +0.539592 0.638416 +0.603591 0.902824 +0.586817 0.902954 +0.604544 0.893718 +0.604606 0.901793 +0.606061 0.877411 +0.605910 0.886685 +0.604871 0.887691 +0.585272 0.887371 +0.584265 0.886332 +0.584417 0.877045 +0.604647 0.877388 +0.604515 0.885446 +0.550922 0.853447 +0.550922 0.636530 +0.560165 0.636530 +0.560165 0.853447 +0.563951 0.853447 +0.563951 0.636530 +0.583461 0.636530 +0.583461 0.853447 +0.587246 0.853447 +0.587246 0.636530 +0.596489 0.636530 +0.596489 0.853447 +0.921292 0.851691 +0.913225 0.851691 +0.913225 0.633809 +0.921292 0.633809 +0.837242 0.852069 +0.820595 0.852069 +0.820595 0.635732 +0.837242 0.635732 +0.897638 0.851908 +0.889586 0.851908 +0.889586 0.634423 +0.897638 0.634423 +0.695335 0.636475 +0.704578 0.636475 +0.704578 0.853392 +0.695335 0.853392 +0.708364 0.636475 +0.727875 0.636475 +0.727875 0.853392 +0.708364 0.853392 +0.731661 0.636475 +0.740904 0.636475 +0.740904 0.853392 +0.731661 0.853392 +0.925747 0.851490 +0.925747 0.633608 +0.933814 0.633608 +0.933814 0.851490 +0.807635 0.636015 +0.807635 0.852323 +0.790990 0.852323 +0.790990 0.636015 +0.910015 0.633874 +0.910015 0.851756 +0.901947 0.851756 +0.901947 0.633874 +0.603476 0.886452 +0.586707 0.886177 +0.585701 0.885138 +0.585833 0.877068 +0.547769 0.887408 +0.547757 0.878114 +0.548779 0.877090 +0.568372 0.877062 +0.569395 0.878083 +0.569409 0.887362 +0.549186 0.887406 +0.549175 0.879330 +0.550196 0.878305 +0.566958 0.878281 +0.567982 0.879302 +0.567994 0.887365 +0.569545 0.905561 +0.569274 0.896264 +0.568221 0.895272 +0.548640 0.895835 +0.547648 0.896885 +0.547913 0.906158 +0.567892 0.897523 +0.568128 0.905602 +0.587382 0.426196 +0.585064 0.436941 +0.579587 0.030232 +0.583982 0.041290 +0.597603 0.027795 +0.601111 0.438933 +0.571455 0.024633 +0.036870 0.024603 +0.027127 0.005853 +0.579984 0.006640 +0.023965 0.043314 +0.027367 0.428220 +0.013745 0.441714 +0.010236 0.030577 +0.039893 0.444876 +0.574477 0.444907 +0.584220 0.463657 +0.031364 0.462869 +0.592869 0.018830 +0.596688 0.449612 +0.028587 0.030265 +0.019609 0.012707 +0.031762 0.439277 +0.018479 0.450678 +0.577231 0.027976 +0.587352 0.012462 +0.591739 0.456803 +0.582760 0.439245 +0.026283 0.032569 +0.014659 0.019898 +0.034117 0.441533 +0.023996 0.457046 +0.492728 0.609730 +0.493178 0.983298 +0.031504 0.983855 +0.031053 0.610287 +0.145240 0.568377 +0.436617 0.567900 +0.436667 0.572985 +0.145290 0.573462 +0.454310 0.567727 +0.454359 0.572813 +0.469033 0.567586 +0.469082 0.572673 +0.062037 0.594887 +0.467714 0.594043 +0.492339 0.593785 +0.492414 0.600863 +0.459939 0.558897 +0.459894 0.553811 +0.442248 0.559053 +0.442203 0.553968 +0.150867 0.559248 +0.150821 0.554163 +0.133177 0.559415 +0.133128 0.554329 +0.118456 0.559557 +0.118407 0.554471 +0.466655 0.585821 +0.060981 0.586666 +0.036348 0.586924 +0.036274 0.579844 +0.127549 0.568553 +0.127599 0.573638 +0.625503 0.163947 +0.625503 0.154708 +0.937183 0.154709 +0.937183 0.163947 +0.625573 0.149269 +0.625573 0.129770 +0.937253 0.129771 +0.937253 0.149270 +0.625643 0.124331 +0.625643 0.115092 +0.937323 0.115093 +0.937323 0.124332 +0.937925 0.396277 +0.624686 0.396277 +0.624686 0.388209 +0.937925 0.388209 +0.935891 0.260304 +0.625256 0.260304 +0.625256 0.243677 +0.935891 0.243677 +0.936592 0.329363 +0.623353 0.329363 +0.623353 0.321295 +0.936592 0.321295 +0.625186 0.171237 +0.936866 0.171237 +0.936866 0.180475 +0.625186 0.180476 +0.625231 0.185915 +0.936910 0.185915 +0.936910 0.205414 +0.625231 0.205415 +0.625275 0.210854 +0.936954 0.210854 +0.936954 0.220092 +0.625275 0.220093 +0.937137 0.374874 +0.937137 0.382942 +0.623898 0.382942 +0.623898 0.374874 +0.935865 0.289309 +0.935865 0.305936 +0.625230 0.305936 +0.625230 0.289309 +0.937964 0.349675 +0.937964 0.357743 +0.624725 0.357743 +0.624725 0.349675 +0.550089 0.897010 +0.566841 0.896529 +0.549327 0.906118 +0.549097 0.898060 +0.535831 0.853920 +0.535831 0.638416 +0.529466 0.638586 +0.529466 0.854091 +0.746156 0.637031 +0.746156 0.853724 +0.886994 0.852230 +0.886994 0.635500 +0.543550 0.638544 +0.543550 0.853983 +0.975845 0.851574 +0.975845 0.636134 +0.846444 0.852494 +0.547311 0.853983 +0.547311 0.638544 +0.846444 0.636140 +0.972085 0.851645 +0.870644 0.852494 +0.870644 0.636140 +0.972085 0.636206 +0.961968 0.635701 +0.961968 0.851205 +0.965197 0.636034 +0.965197 0.851539 +0.787214 0.636015 +0.787214 0.852323 +0.958207 0.635792 +0.958207 0.851297 +0.968957 0.851447 +0.968957 0.635942 +0.811411 0.852323 +0.811411 0.636015 +0.989138 0.851209 +0.989138 0.635771 +0.978851 0.636018 +0.978851 0.851457 +0.816818 0.852069 +0.985377 0.635842 +0.985377 0.851281 +0.816818 0.635732 +0.982612 0.635946 +0.841019 0.852069 +0.841019 0.635732 +0.982612 0.851386 +0.624749 0.342220 +0.934007 0.342220 +0.952041 0.871238 +0.642783 0.871238 +0.934077 0.336824 +0.624819 0.336824 +0.951971 0.876634 +0.642713 0.876634 +0.935909 0.311357 +0.625274 0.311358 +0.935821 0.283888 +0.625186 0.283888 +0.624174 0.364068 +0.933431 0.364068 +0.626933 0.406347 +0.936190 0.406347 +0.624218 0.369465 +0.933475 0.369465 +0.936146 0.400950 +0.626889 0.400950 +0.935960 0.238256 +0.625325 0.238257 +0.625186 0.265725 +0.935822 0.265725 +0.060907 0.579586 +0.062112 0.601967 +0.467789 0.601122 +0.466581 0.578742 +0.512822 0.944557 +0.511907 0.618459 +0.506170 0.975643 +0.037405 0.595148 +0.037480 0.602228 +0.502928 0.978831 +0.474658 0.558767 +0.474613 0.553682 +0.024999 0.982873 +0.021782 0.981408 +0.012324 0.975126 +0.011410 0.649029 +0.018062 0.617942 +0.491281 0.585561 +0.491207 0.578482 +0.021304 0.614754 +0.112829 0.568699 +0.112880 0.573784 +0.499232 0.610713 +0.502449 0.612177 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.756345 0.522332 +0.756346 0.715841 +0.016244 0.715841 +0.016243 0.522332 +0.009526 0.514494 +0.009526 0.061000 +0.749636 0.060999 +0.749637 0.514493 +0.771396 0.480706 +0.969477 0.480355 +0.969577 0.938728 +0.771464 0.938319 +0.751630 0.039423 +0.751630 0.498972 +0.007192 0.498972 +0.007192 0.039423 +0.977311 0.498670 +0.779207 0.499082 +0.779286 0.040707 +0.977371 0.041060 +0.016243 0.718111 +0.756344 0.718111 +0.756344 0.911620 +0.016243 0.911620 +0.756345 0.522332 +0.756346 0.715841 +0.016244 0.715841 +0.016243 0.522332 +0.009526 0.514494 +0.009526 0.061000 +0.749636 0.060999 +0.749637 0.514493 +0.771396 0.480706 +0.969477 0.480355 +0.969577 0.938728 +0.771464 0.938319 +0.751630 0.039423 +0.751630 0.498972 +0.007192 0.498972 +0.007192 0.039423 +0.977311 0.498670 +0.779207 0.499082 +0.779286 0.040707 +0.977371 0.041060 +0.016243 0.718111 +0.756344 0.718111 +0.756344 0.911620 +0.016243 0.911620 +0.756345 0.522332 +0.756346 0.715841 +0.016244 0.715841 +0.016243 0.522332 +0.009526 0.514494 +0.009526 0.061000 +0.749636 0.060999 +0.749637 0.514493 +0.771396 0.480706 +0.969477 0.480355 +0.969577 0.938728 +0.771464 0.938319 +0.751630 0.039423 +0.751630 0.498972 +0.007192 0.498972 +0.007192 0.039423 +0.977311 0.498670 +0.779207 0.499082 +0.779286 0.040707 +0.977371 0.041060 +0.016243 0.718111 +0.756344 0.718111 +0.756344 0.911620 +0.016243 0.911620 +0.076009 0.659668 +0.040405 0.870361 +0.040314 0.874227 +0.037069 0.899302 +0.035123 0.917445 +0.036067 0.912130 +0.036463 0.900950 +0.002443 0.979329 +0.003126 0.975510 +0.123881 0.764180 +0.113109 0.773072 +0.123881 0.761861 +0.113109 0.770671 +0.114161 0.788940 +0.114161 0.786408 +0.131775 0.801371 +0.131775 0.798767 +0.077800 0.652873 +0.231486 0.652832 +0.076904 0.655335 +0.232727 0.655335 +0.234009 0.659668 +0.181193 0.758565 +0.198812 0.770915 +0.151387 0.755615 +0.284180 0.870361 +0.189087 0.795491 +0.199870 0.786682 +0.161591 0.801666 +0.038559 0.883301 +0.286743 0.883301 +0.289673 0.900950 +0.291565 0.917450 +0.313884 0.979243 +0.258789 0.994857 +0.297567 0.989676 +0.276978 0.993504 +0.054739 0.994854 +0.036692 0.993475 +0.005191 0.984123 +0.037158 0.990271 +0.005814 0.980520 +0.309611 0.980416 +0.312988 0.975418 +0.290242 0.912130 +0.288818 0.899302 +0.286377 0.885000 +0.284180 0.874227 +0.234334 0.662598 +0.198598 0.773346 +0.233286 0.659139 +0.232178 0.656982 +0.258138 0.991714 +0.055206 0.991714 +0.181193 0.760885 +0.151387 0.757914 +0.917480 0.016724 +0.902832 0.002441 +0.912313 0.006999 +0.697998 0.324219 +0.488770 0.002930 +0.917740 0.630165 +0.474121 0.017578 +0.479248 0.008118 +0.474121 0.631592 +0.488770 0.646240 +0.479248 0.641174 +0.902832 0.645264 +0.912476 0.640259 +0.038763 0.885000 +0.075785 0.662598 +0.076523 0.659139 +0.077356 0.657031 +0.276327 0.990297 +0.161560 0.804352 +0.189067 0.798075 +0.924072 0.640015 +0.923889 0.629002 +0.929443 0.629639 +0.929443 0.640015 +0.924072 0.015625 +0.929443 0.015625 +0.929443 0.005127 +0.924072 0.005127 +0.952393 0.438477 +0.952393 0.448974 +0.946840 0.437825 +0.947021 0.448974 +0.952393 0.011719 +0.946839 0.012472 +0.947021 0.004150 +0.952393 0.004150 +0.939027 0.016277 +0.939209 0.005127 +0.944759 0.016285 +0.944580 0.005127 +0.939026 0.441731 +0.944580 0.442383 +0.939209 0.449951 +0.944580 0.449951 +0.465820 0.997532 +0.465820 0.998001 +0.465332 0.997883 +0.465332 0.997532 +0.465820 0.648438 +0.465332 0.648438 +0.608398 0.997532 +0.608398 0.998001 +0.465820 0.647949 +0.465332 0.648193 +0.608887 0.997532 +0.608398 0.997883 +0.608398 0.647949 +0.608398 0.648438 +0.608887 0.648438 +0.232056 0.656982 +0.937256 0.004150 +0.937435 0.012377 +0.931702 0.012345 +0.931885 0.004150 +0.937256 0.625733 +0.931702 0.625106 +0.931885 0.633423 +0.937256 0.633423 +0.461182 0.995430 +0.461182 0.995773 +0.460693 0.995430 +0.460693 0.995888 +0.458252 0.995430 +0.458252 0.995888 +0.460693 0.653076 +0.461182 0.653076 +0.461182 0.652588 +0.460693 0.652588 +0.458252 0.653076 +0.458008 0.995773 +0.457764 0.995430 +0.457764 0.653076 +0.458252 0.652588 +0.457764 0.652588 +0.610840 0.647949 +0.610840 0.648438 +0.610352 0.648438 +0.613281 0.648438 +0.613281 0.647949 +0.613770 0.647949 +0.613770 0.648438 +0.613770 0.990982 +0.613281 0.990982 +0.610840 0.990982 +0.610352 0.990982 +0.610840 0.991440 +0.610352 0.991325 +0.613281 0.991440 +0.613770 0.991325 +0.316162 0.653076 +0.316162 0.652588 +0.316406 0.653076 +0.316650 0.652588 +0.455566 0.652588 +0.455566 0.653076 +0.316406 0.993172 +0.316162 0.992989 +0.316162 0.993332 +0.316650 0.993446 +0.455566 0.993172 +0.456055 0.652588 +0.456055 0.653076 +0.456055 0.992989 +0.455566 0.993446 +0.455811 0.993446 +0.531250 0.946991 +0.531250 0.947327 +0.530762 0.946991 +0.530762 0.947449 +0.530762 0.807007 +0.531250 0.807007 +0.528320 0.946991 +0.528320 0.947449 +0.527832 0.947327 +0.527832 0.946991 +0.528320 0.807007 +0.527832 0.807007 +0.531250 0.806641 +0.530762 0.806641 +0.528320 0.806641 +0.527832 0.806641 +0.528809 0.795410 +0.528809 0.795776 +0.528320 0.795410 +0.528320 0.795898 +0.525879 0.795898 +0.525879 0.795410 +0.528320 0.655518 +0.528809 0.655518 +0.525391 0.795776 +0.525391 0.795410 +0.528809 0.655029 +0.528320 0.655029 +0.525879 0.655518 +0.525391 0.655518 +0.525879 0.655029 +0.525391 0.655273 +0.018436 0.003174 +0.003487 0.018066 +0.008855 0.008240 +0.109802 0.071777 +0.447021 0.003296 +0.355469 0.072266 +0.461975 0.018066 +0.456665 0.008362 +0.355469 0.580811 +0.461975 0.634949 +0.447021 0.649719 +0.456665 0.644592 +0.018436 0.649719 +0.109802 0.580811 +0.003487 0.635010 +0.008855 0.644653 +0.199524 0.789022 +0.618760 0.701971 +0.624622 0.731381 +0.608861 0.731117 +0.614305 0.840637 +0.610003 0.858801 +0.599464 0.839324 +0.614604 0.856184 +0.620981 0.868252 +0.623697 0.857468 +0.596263 0.814862 +0.613157 0.815466 +0.597480 0.774683 +0.614940 0.775894 +0.604189 0.739801 +0.618940 0.740750 +0.625086 0.716951 +0.617957 0.712688 +0.629454 0.705243 +0.650593 0.717277 +0.650070 0.703481 +0.649395 0.741799 +0.647553 0.777635 +0.645497 0.817152 +0.670360 0.706880 +0.676903 0.719972 +0.681881 0.744036 +0.683415 0.717249 +0.694686 0.744572 +0.697385 0.779918 +0.681930 0.779343 +0.679453 0.818845 +0.693916 0.819903 +0.687272 0.845013 +0.675959 0.843364 +0.644160 0.842771 +0.642836 0.870925 +0.644570 0.859215 +0.670041 0.859255 +0.669297 0.868050 +0.677765 0.861308 +0.628068 0.705014 +0.633099 0.692272 +0.652679 0.705217 +0.606112 0.767729 +0.622465 0.768417 +0.605143 0.809154 +0.621303 0.809512 +0.621605 0.835821 +0.606380 0.835927 +0.650477 0.769427 +0.649135 0.810427 +0.648179 0.837387 +0.612033 0.854684 +0.623029 0.853820 +0.619852 0.862722 +0.646699 0.867883 +0.647533 0.855362 +0.669449 0.867321 +0.672204 0.855579 +0.675058 0.837698 +0.681496 0.858341 +0.691075 0.837494 +0.677130 0.811469 +0.693651 0.812230 +0.678492 0.770371 +0.694854 0.770804 +0.694127 0.734052 +0.678733 0.733223 +0.651772 0.731958 +0.654349 0.690826 +0.675465 0.694380 +0.677231 0.706674 +0.686427 0.703459 +0.029544 0.035380 +0.029544 0.035380 +0.902832 0.645265 +0.447020 0.650719 +0.678335 0.857072 +0.680362 0.704784 +0.623673 0.703078 +0.618413 0.855377 +0.583154 0.465906 +0.030298 0.465118 +0.602564 0.440517 +0.598141 0.451196 +0.591476 0.013939 +0.594235 0.017123 +0.581249 0.004701 +0.588617 0.010523 +0.595624 0.455114 +0.593149 0.458710 +0.008783 0.028993 +0.013206 0.018314 +0.599319 0.029387 +0.602827 0.440525 +0.594572 0.017143 +0.599306 0.026108 +0.028193 0.003604 +0.581050 0.004391 +0.018391 0.010363 +0.025909 0.003509 +0.015724 0.014396 +0.018199 0.010800 +0.012029 0.440122 +0.008520 0.028985 +0.016776 0.452365 +0.012042 0.443401 +0.019872 0.455569 +0.017113 0.452385 +0.030099 0.464808 +0.022731 0.458985 +0.592957 0.459147 +0.585438 0.466001 + + + + + + + + + + +-37.371174 -61.648491 +-37.371174 -65.510582 +-28.368664 -61.648491 +-28.793972 -65.935890 +-37.371174 -61.648491 +-36.945866 -65.935890 +-28.368664 -61.648491 +-28.368664 -65.510582 +-36.782421 -61.648491 +-36.782444 -65.004433 +-28.957417 -61.648491 +-29.382778 -65.429733 +-36.782421 -61.648491 +-36.357136 -65.429733 +-28.957417 -61.648491 +-28.957462 -65.004433 +-36.945866 -65.935890 +-28.368664 -65.510582 +-37.371174 -65.510582 +-28.793972 -65.935890 +-36.357136 -65.429733 +-28.957462 -65.004433 +-36.782444 -65.004433 +-29.382778 -65.429733 +-37.371159 61.648521 +-37.371159 65.510612 +-37.371159 65.510612 +-37.371159 61.648521 +-36.945850 65.935921 +-28.793957 65.935921 +-28.793957 65.935921 +-36.945850 65.935921 +-28.368649 65.510612 +-28.368649 61.648521 +-28.368649 61.648521 +-28.368649 65.510612 +-36.782429 65.004463 +-36.782429 65.004463 +-36.782406 61.648521 +-36.782406 61.648521 +-29.382763 65.429764 +-29.382763 65.429764 +-36.357121 65.429764 +-36.357121 65.429764 +-28.957401 61.648521 +-28.957401 61.648521 +-28.957447 65.004463 +-28.957447 65.004463 +36.987122 -61.648502 +36.987122 -65.510590 +36.987122 -65.510590 +36.987122 -61.648502 +36.561813 -65.935905 +28.409920 -65.935898 +28.409920 -65.935898 +36.561813 -65.935905 +27.984612 -65.510582 +27.984613 -61.648502 +27.984613 -61.648502 +27.984612 -65.510582 +36.398388 -65.004448 +36.398388 -65.004448 +36.398376 -61.648502 +36.398376 -61.648502 +28.998718 -65.429741 +28.998718 -65.429741 +35.973080 -65.429749 +35.973080 -65.429749 +28.573370 -61.648502 +28.573370 -61.648502 +28.573410 -65.004440 +28.573410 -65.004440 +36.987144 61.648502 +36.987144 61.648502 +36.987144 65.510582 +36.987144 65.510582 +36.561836 65.935890 +36.561836 65.935890 +28.409943 65.935898 +28.409943 65.935898 +27.984634 65.510590 +27.984634 65.510590 +27.984632 61.648502 +27.984632 61.648502 +36.398411 65.004448 +36.398396 61.648502 +36.398396 61.648502 +36.398411 65.004448 +28.998741 65.429756 +35.973103 65.429749 +35.973103 65.429749 +28.998741 65.429756 +28.573389 61.648502 +28.573433 65.004456 +28.573433 65.004456 +28.573389 61.648502 +-44.096615 74.151192 +-44.096645 -74.151161 +40.481560 77.766266 +40.481537 -77.766266 +-44.096615 74.151192 +-40.481571 -77.766251 +40.481560 77.766266 +44.096615 -74.151169 +-40.481541 77.766281 +-40.481571 -77.766251 +44.096638 74.151169 +44.096615 -74.151169 +-40.481541 77.766281 +-44.096645 -74.151161 +44.096638 74.151169 +40.481537 -77.766266 +-43.694942 76.159569 +-43.092430 76.762085 +-42.489948 -77.364563 +-43.092461 -76.762054 +42.489937 77.364571 +43.092449 76.762054 +43.694939 -76.159546 +43.092426 -76.762054 +-42.489918 77.364594 +-43.694942 76.159569 +-43.694973 -76.159538 +-42.489948 -77.364563 +43.694962 76.159546 +42.489937 77.364571 +42.489914 -77.364571 +43.694939 -76.159546 +-44.096615 74.151192 +-44.096645 -74.151161 +-43.694973 -76.159538 +-43.092461 -76.762054 +-40.481571 -77.766251 +40.481537 -77.766266 +42.489914 -77.364571 +43.092426 -76.762054 +44.096615 -74.151169 +44.096638 74.151169 +43.694962 76.159546 +43.092449 76.762054 +40.481560 77.766266 +-40.481541 77.766281 +-42.489918 77.364594 +-43.092430 76.762085 +-44.096615 74.151192 +-40.481571 -77.766251 +40.481560 77.766266 +44.096615 -74.151169 +-40.481541 77.766281 +-44.096645 -74.151161 +44.096638 74.151169 +40.481537 -77.766266 +-42.489918 77.364594 +-43.694942 76.159569 +-43.694973 -76.159538 +-42.489948 -77.364563 +43.694962 76.159546 +42.489937 77.364571 +42.489914 -77.364571 +43.694939 -76.159546 +-37.371159 65.163902 +-37.371159 65.163902 +-28.368649 65.163902 +-28.793957 65.163902 +-37.371174 -65.135574 +-36.945866 -65.135574 +-28.368664 -65.135574 +-28.368664 -65.135574 +-36.782406 65.163902 +-36.782429 65.163902 +-28.957401 65.163902 +-29.382763 65.163902 +-36.782421 -65.135574 +-36.357136 -65.135574 +-28.957417 -65.135574 +-28.957462 -65.135574 +-36.945850 65.163902 +-28.368649 65.163902 +-37.371174 -65.135574 +-28.793972 -65.135574 +-36.357121 65.163902 +-28.957447 65.163902 +-36.782444 -65.135574 +-29.382778 -65.135574 +36.987144 65.163887 +36.987144 65.163887 +36.987122 -65.135582 +36.987122 -65.135582 +36.561836 65.163887 +28.409943 65.163895 +28.409920 -65.135574 +36.561813 -65.135582 +27.984634 65.163895 +27.984634 65.163895 +27.984612 -65.135574 +27.984612 -65.135574 +36.398388 -65.135582 +36.398411 65.163887 +36.398399 65.163887 +36.398376 -65.135582 +28.998718 -65.135574 +28.998741 65.163895 +35.973103 65.163887 +35.973080 -65.135582 +28.573368 -65.135574 +28.573391 65.163895 +28.573433 65.163895 +28.573410 -65.135574 +-2.646059 -0.570249 +-2.646059 -0.570248 +-2.137325 -0.509977 +-2.137324 -0.509977 +-2.598163 -0.974524 +-2.089428 -0.914252 +-2.089428 -0.914252 +-2.599217 -0.965620 +-2.598163 -0.974524 +-2.664405 -0.556926 +-2.664405 -0.556925 +-2.119845 -0.492409 +-2.119846 -0.492409 +-2.613136 -0.989670 +-2.068577 -0.925154 +-2.068577 -0.925154 +-2.614266 -0.980139 +-2.613136 -0.989670 +-2.101421 -1.567498 +-2.101421 -1.567499 +-2.663376 -1.594445 +-2.663376 -1.594445 +-2.117931 -1.223174 +-2.679886 -1.250121 +-2.117931 -1.223174 +-2.679886 -1.250120 +-2.097062 -1.559281 +-2.097062 -1.559281 +-2.658034 -1.602060 +-2.658034 -1.602060 +-2.123273 -1.215558 +-2.684245 -1.258339 +-2.123273 -1.215559 +-2.684245 -1.258338 +-2.097062 -1.559281 +-2.097062 -1.559281 +-2.658034 -1.602060 +-2.658034 -1.602060 +-2.123273 -1.215558 +-2.684245 -1.258339 +-2.123273 -1.215559 +-2.684245 -1.258338 +0.971672 0.040333 +0.749525 0.021780 +0.751040 0.021702 +0.609253 0.533447 +0.595052 0.527934 +0.599732 0.523987 +0.607585 0.539592 +0.555664 0.411133 +0.558838 0.409912 +0.194946 0.947632 +0.183960 0.947571 +0.194132 0.943232 +0.182902 0.943110 +0.167450 0.947090 +0.166321 0.942673 +0.154785 0.947174 +0.153524 0.942566 +0.988037 0.041504 +0.988037 0.120605 +0.978272 0.040894 +0.978272 0.121216 +0.971672 0.121776 +0.867676 0.094970 +0.853979 0.103853 +0.870728 0.079223 +0.749526 0.148140 +0.828125 0.099121 +0.837402 0.104980 +0.849102 0.106045 +0.821167 0.084595 +0.837768 0.059692 +0.824463 0.068847 +0.738770 0.020996 +0.738770 0.149170 +0.724609 0.150635 +0.724609 0.019776 +0.707763 0.019165 +0.707723 0.151886 +0.585063 0.163273 +0.584961 0.002441 +0.554009 0.134778 +0.564392 0.155098 +0.556553 0.144321 +0.554199 0.029297 +0.556641 0.019776 +0.575439 0.003663 +0.004866 0.930957 +0.003824 0.973534 +0.043595 0.967987 +0.554443 0.311035 +0.555989 0.304851 +0.557373 0.312012 +0.559326 0.305908 +0.594727 0.190796 +0.590108 0.187032 +0.604126 0.181152 +0.602132 0.175090 +0.616048 0.172607 +0.615488 0.179169 +0.624512 0.181396 +0.626953 0.175049 +0.186271 0.802606 +0.406738 0.828430 +0.291126 0.846878 +0.814209 0.295898 +0.820964 0.297974 +0.902614 0.332144 +0.816162 0.293213 +1.650879 0.612793 +0.822429 0.307942 +0.249030 0.973453 +0.061462 0.972870 +0.061116 0.968236 +0.249634 0.968236 +0.230550 0.943359 +0.249359 0.947718 +0.229980 0.947754 +0.250280 0.943214 +0.211899 0.947697 +0.211772 0.943321 +0.014585 0.397461 +0.002347 0.409668 +0.006571 0.401734 +0.272446 0.587891 +0.002677 0.766296 +0.529295 0.397202 +0.014954 0.778381 +0.006956 0.774140 +0.530029 0.778351 +0.542480 0.766296 +0.538208 0.774170 +0.541992 0.409668 +0.537720 0.401672 +0.552735 0.401693 +0.555664 0.400635 +0.621745 0.541707 +0.620696 0.535186 +0.629876 0.532342 +0.632324 0.538656 +0.186279 0.929260 +0.291407 0.891380 +0.406761 0.910774 +0.812988 0.409668 +0.816708 0.405450 +0.819621 0.407308 +0.815185 0.412354 +0.823608 0.398438 +0.820557 0.397217 +0.023979 0.789520 +0.266662 0.973373 +0.267171 0.968272 +0.290934 0.968302 +0.043915 0.973083 +0.317993 0.948219 +0.301452 0.947479 +0.317953 0.943161 +0.301697 0.942413 +0.283854 0.942510 +0.283020 0.947289 +0.535278 0.984306 +0.526328 0.984466 +0.526855 0.979805 +0.535278 0.979801 +0.012798 0.984308 +0.012802 0.979805 +0.004325 0.979801 +0.004322 0.984306 +0.265310 0.852164 +0.258896 0.866341 +0.274838 0.890630 +0.261964 0.881694 +0.307220 0.871521 +0.304199 0.856018 +0.411621 0.829010 +0.411682 0.910301 +0.177643 0.930115 +0.177552 0.801605 +0.166718 0.800385 +0.166748 0.930984 +0.153639 0.931585 +0.153652 0.799543 +0.033523 0.787598 +0.033340 0.948563 +0.002057 0.816138 +0.004814 0.806652 +0.001982 0.921590 +0.023769 0.947106 +0.916504 0.816589 +0.924927 0.816589 +0.916015 0.821242 +0.924927 0.821060 +0.559082 0.816589 +0.559571 0.821243 +0.552734 0.821106 +0.552734 0.816589 +0.562926 0.807692 +0.553589 0.807556 +0.562833 0.802946 +0.553589 0.803040 +0.918945 0.807693 +0.919433 0.803040 +0.925781 0.807556 +0.925781 0.803040 +0.837402 0.668213 +0.837891 0.668213 +0.837891 0.668457 +0.837402 0.668457 +0.551758 0.668213 +0.551758 0.668457 +0.837402 0.551514 +0.837891 0.551514 +0.551270 0.668213 +0.551270 0.668457 +0.837402 0.551025 +0.837891 0.551025 +0.551270 0.551514 +0.551758 0.551514 +0.551758 0.551025 +0.551270 0.551025 +0.420166 0.829682 +0.420166 0.909836 +0.003565 0.993280 +0.010391 0.993134 +0.010388 0.997935 +0.003565 0.997781 +0.523926 0.993282 +0.523458 0.997936 +0.530273 0.997781 +0.530273 0.993280 +0.836914 0.841309 +0.837402 0.841309 +0.836914 0.841675 +0.837402 0.841675 +0.836914 0.843750 +0.837402 0.843750 +0.551758 0.841675 +0.551758 0.841309 +0.551270 0.841309 +0.551270 0.841675 +0.551758 0.843750 +0.837402 0.843994 +0.836914 0.844116 +0.551758 0.844116 +0.551270 0.843750 +0.551270 0.844116 +0.551270 0.832275 +0.551758 0.832275 +0.551270 0.832642 +0.551758 0.832642 +0.551758 0.830200 +0.551270 0.830200 +0.551270 0.829956 +0.551758 0.829834 +0.837402 0.829834 +0.837402 0.830200 +0.837402 0.832275 +0.837402 0.832642 +0.837402 0.832764 +0.837402 0.829956 +0.551758 0.794312 +0.551270 0.794189 +0.551758 0.793945 +0.551270 0.793945 +0.551270 0.677490 +0.551758 0.677490 +0.836426 0.793945 +0.836426 0.794312 +0.836914 0.794312 +0.836914 0.793945 +0.836426 0.677490 +0.551270 0.677246 +0.551758 0.677246 +0.836426 0.677246 +0.836914 0.677490 +0.836914 0.677246 +0.800293 0.597168 +0.800781 0.597168 +0.800293 0.597412 +0.800781 0.597412 +0.683594 0.597412 +0.683594 0.597168 +0.800293 0.599609 +0.800781 0.599609 +0.800781 0.599854 +0.800293 0.599854 +0.683594 0.599609 +0.683594 0.599854 +0.683105 0.597168 +0.683105 0.597412 +0.683105 0.599609 +0.683105 0.599854 +0.679688 0.587891 +0.680176 0.587891 +0.679688 0.588135 +0.680176 0.588135 +0.680176 0.590332 +0.679688 0.590332 +0.563477 0.588135 +0.562988 0.587891 +0.680176 0.590576 +0.679688 0.590576 +0.562988 0.588135 +0.563477 0.590332 +0.563477 0.590576 +0.562988 0.590332 +0.562988 0.590576 +0.002961 0.374878 +0.015907 0.387695 +0.007790 0.383118 +0.060760 0.298340 +0.002951 0.015869 +0.060669 0.092285 +0.015818 0.002930 +0.007632 0.007568 +0.486816 0.092285 +0.531494 0.002930 +0.544434 0.015869 +0.540304 0.007670 +0.544434 0.375122 +0.486816 0.298340 +0.531494 0.387695 +0.539571 0.383321 +0.269819 0.947703 +0.270874 0.942775 +0.274611 0.846327 +0.854668 0.059385 +0.864013 0.064697 +0.300781 0.885864 +0.751042 0.148232 +0.971320 0.121952 +0.407160 0.910657 +0.797716 0.609565 +0.777710 0.614441 +0.777385 0.603495 +0.583117 0.608575 +0.570150 0.607340 +0.582764 0.598572 +0.572266 0.610107 +0.564453 0.615357 +0.571533 0.616455 +0.599854 0.594604 +0.600382 0.606160 +0.627930 0.592896 +0.628215 0.604940 +0.653320 0.595255 +0.653381 0.605184 +0.670166 0.608398 +0.672526 0.603475 +0.678223 0.610595 +0.671631 0.626262 +0.680827 0.625000 +0.654460 0.627055 +0.629150 0.628011 +0.601319 0.629150 +0.679850 0.639486 +0.671712 0.645019 +0.655070 0.650467 +0.673828 0.649007 +0.655395 0.659119 +0.630615 0.663208 +0.630127 0.652649 +0.602234 0.653442 +0.602539 0.663330 +0.584554 0.660319 +0.584717 0.652639 +0.583252 0.629802 +0.564056 0.636535 +0.571696 0.631144 +0.573567 0.649007 +0.567871 0.648926 +0.572754 0.654216 +0.795654 0.616211 +0.804633 0.619249 +0.795898 0.632813 +0.752442 0.602702 +0.752442 0.614014 +0.724366 0.602824 +0.724365 0.614075 +0.706543 0.614746 +0.706027 0.604262 +0.752442 0.632813 +0.724366 0.632813 +0.706055 0.632772 +0.693251 0.608426 +0.694336 0.616211 +0.687988 0.614014 +0.684886 0.626943 +0.693848 0.632813 +0.686035 0.647990 +0.694336 0.649536 +0.706543 0.651001 +0.692437 0.656128 +0.706990 0.662048 +0.724365 0.651611 +0.724366 0.663167 +0.752442 0.651550 +0.752442 0.662842 +0.777900 0.661682 +0.777710 0.651093 +0.777832 0.632813 +0.806125 0.633572 +0.804199 0.647990 +0.795654 0.649414 +0.798286 0.655802 +0.407135 0.828603 +0.541993 0.409668 +0.545270 0.015872 +0.693316 0.653875 +0.797108 0.651577 +0.796978 0.613054 +0.693048 0.612950 + + + + + + + + + + +-37.371174 -61.648491 +-37.371174 -65.510582 +-28.368664 -61.648491 +-28.793972 -65.935890 +-37.371174 -61.648491 +-36.945866 -65.935890 +-28.368664 -61.648491 +-28.368664 -65.510582 +-36.782421 -61.648491 +-36.782444 -65.004433 +-28.957417 -61.648491 +-29.382778 -65.429733 +-36.782421 -61.648491 +-36.357136 -65.429733 +-28.957417 -61.648491 +-28.957462 -65.004433 +-36.945866 -65.935890 +-28.368664 -65.510582 +-37.371174 -65.510582 +-28.793972 -65.935890 +-36.357136 -65.429733 +-28.957462 -65.004433 +-36.782444 -65.004433 +-29.382778 -65.429733 +-37.371159 61.648521 +-37.371159 65.510612 +-37.371159 65.510612 +-37.371159 61.648521 +-36.945850 65.935921 +-28.793957 65.935921 +-28.793957 65.935921 +-36.945850 65.935921 +-28.368649 65.510612 +-28.368649 61.648521 +-28.368649 61.648521 +-28.368649 65.510612 +-36.782429 65.004463 +-36.782429 65.004463 +-36.782406 61.648521 +-36.782406 61.648521 +-29.382763 65.429764 +-29.382763 65.429764 +-36.357121 65.429764 +-36.357121 65.429764 +-28.957401 61.648521 +-28.957401 61.648521 +-28.957447 65.004463 +-28.957447 65.004463 +36.987122 -61.648502 +36.987122 -65.510590 +36.987122 -65.510590 +36.987122 -61.648502 +36.561813 -65.935905 +28.409920 -65.935898 +28.409920 -65.935898 +36.561813 -65.935905 +27.984612 -65.510582 +27.984613 -61.648502 +27.984613 -61.648502 +27.984612 -65.510582 +36.398388 -65.004448 +36.398388 -65.004448 +36.398376 -61.648502 +36.398376 -61.648502 +28.998718 -65.429741 +28.998718 -65.429741 +35.973080 -65.429749 +35.973080 -65.429749 +28.573370 -61.648502 +28.573370 -61.648502 +28.573410 -65.004440 +28.573410 -65.004440 +36.987144 61.648502 +36.987144 61.648502 +36.987144 65.510582 +36.987144 65.510582 +36.561836 65.935890 +36.561836 65.935890 +28.409943 65.935898 +28.409943 65.935898 +27.984634 65.510590 +27.984634 65.510590 +27.984632 61.648502 +27.984632 61.648502 +36.398411 65.004448 +36.398396 61.648502 +36.398396 61.648502 +36.398411 65.004448 +28.998741 65.429756 +35.973103 65.429749 +35.973103 65.429749 +28.998741 65.429756 +28.573389 61.648502 +28.573433 65.004456 +28.573433 65.004456 +28.573389 61.648502 +-44.096615 74.151192 +-44.096645 -74.151161 +40.481560 77.766266 +40.481537 -77.766266 +-44.096615 74.151192 +-40.481571 -77.766251 +40.481560 77.766266 +44.096615 -74.151169 +-40.481541 77.766281 +-40.481571 -77.766251 +44.096638 74.151169 +44.096615 -74.151169 +-40.481541 77.766281 +-44.096645 -74.151161 +44.096638 74.151169 +40.481537 -77.766266 +-43.694942 76.159569 +-43.092430 76.762085 +-42.489948 -77.364563 +-43.092461 -76.762054 +42.489937 77.364571 +43.092449 76.762054 +43.694939 -76.159546 +43.092426 -76.762054 +-42.489918 77.364594 +-43.694942 76.159569 +-43.694973 -76.159538 +-42.489948 -77.364563 +43.694962 76.159546 +42.489937 77.364571 +42.489914 -77.364571 +43.694939 -76.159546 +-44.096615 74.151192 +-44.096645 -74.151161 +-43.694973 -76.159538 +-43.092461 -76.762054 +-40.481571 -77.766251 +40.481537 -77.766266 +42.489914 -77.364571 +43.092426 -76.762054 +44.096615 -74.151169 +44.096638 74.151169 +43.694962 76.159546 +43.092449 76.762054 +40.481560 77.766266 +-40.481541 77.766281 +-42.489918 77.364594 +-43.092430 76.762085 +-44.096615 74.151192 +-40.481571 -77.766251 +40.481560 77.766266 +44.096615 -74.151169 +-40.481541 77.766281 +-44.096645 -74.151161 +44.096638 74.151169 +40.481537 -77.766266 +-42.489918 77.364594 +-43.694942 76.159569 +-43.694973 -76.159538 +-42.489948 -77.364563 +43.694962 76.159546 +42.489937 77.364571 +42.489914 -77.364571 +43.694939 -76.159546 +-37.371159 65.163902 +-37.371159 65.163902 +-28.368649 65.163902 +-28.793957 65.163902 +-37.371174 -65.135574 +-36.945866 -65.135574 +-28.368664 -65.135574 +-28.368664 -65.135574 +-36.782406 65.163902 +-36.782429 65.163902 +-28.957401 65.163902 +-29.382763 65.163902 +-36.782421 -65.135574 +-36.357136 -65.135574 +-28.957417 -65.135574 +-28.957462 -65.135574 +-36.945850 65.163902 +-28.368649 65.163902 +-37.371174 -65.135574 +-28.793972 -65.135574 +-36.357121 65.163902 +-28.957447 65.163902 +-36.782444 -65.135574 +-29.382778 -65.135574 +36.987144 65.163887 +36.987144 65.163887 +36.987122 -65.135582 +36.987122 -65.135582 +36.561836 65.163887 +28.409943 65.163895 +28.409920 -65.135574 +36.561813 -65.135582 +27.984634 65.163895 +27.984634 65.163895 +27.984612 -65.135574 +27.984612 -65.135574 +36.398388 -65.135582 +36.398411 65.163887 +36.398399 65.163887 +36.398376 -65.135582 +28.998718 -65.135574 +28.998741 65.163895 +35.973103 65.163887 +35.973080 -65.135582 +28.573368 -65.135574 +28.573391 65.163895 +28.573433 65.163895 +28.573410 -65.135574 +-2.646059 -0.570249 +-2.646059 -0.570248 +-2.137325 -0.509977 +-2.137324 -0.509977 +-2.598163 -0.974524 +-2.089428 -0.914252 +-2.089428 -0.914252 +-2.599217 -0.965620 +-2.598163 -0.974524 +-2.664405 -0.556926 +-2.664405 -0.556925 +-2.119845 -0.492409 +-2.119846 -0.492409 +-2.613136 -0.989670 +-2.068577 -0.925154 +-2.068577 -0.925154 +-2.614266 -0.980139 +-2.613136 -0.989670 +-2.101421 -1.567498 +-2.101421 -1.567499 +-2.663376 -1.594445 +-2.663376 -1.594445 +-2.117931 -1.223174 +-2.679886 -1.250121 +-2.117931 -1.223174 +-2.679886 -1.250120 +-2.097062 -1.559281 +-2.097062 -1.559281 +-2.658034 -1.602060 +-2.658034 -1.602060 +-2.123273 -1.215558 +-2.684245 -1.258339 +-2.123273 -1.215559 +-2.684245 -1.258338 +-2.097062 -1.559281 +-2.097062 -1.559281 +-2.658034 -1.602060 +-2.658034 -1.602060 +-2.123273 -1.215558 +-2.684245 -1.258339 +-2.123273 -1.215559 +-2.684245 -1.258338 +0.283854 0.166504 +0.597005 0.187988 +0.594868 0.188081 +0.148030 0.191569 +0.121538 0.189925 +0.129252 0.190837 +0.145691 0.190674 +0.667033 0.191203 +0.759114 0.210775 +0.664279 0.190929 +0.753557 0.210937 +0.439453 0.137451 +0.452392 0.143799 +0.435872 0.137695 +0.448975 0.144125 +0.464355 0.145508 +0.472431 0.143534 +0.309671 0.240428 +0.291382 0.251546 +0.313354 0.240845 +0.295532 0.251709 +0.273743 0.165527 +0.273804 0.072876 +0.277506 0.166016 +0.277506 0.072062 +0.283854 0.071289 +0.430990 0.103190 +0.449386 0.092469 +0.426616 0.121134 +0.597005 0.041016 +0.485880 0.098389 +0.472779 0.091797 +0.495138 0.115031 +0.490763 0.132894 +0.616333 0.189087 +0.616374 0.039429 +0.642497 0.037679 +0.642456 0.190430 +0.667053 0.036601 +0.758789 0.023112 +0.782369 0.056138 +0.774713 0.032871 +0.780355 0.045626 +0.782227 0.179199 +0.780273 0.190186 +0.766113 0.209229 +0.014773 0.191569 +0.029053 0.171712 +0.010074 0.191325 +0.015646 0.356852 +0.031342 0.367188 +0.029213 0.364421 +0.036530 0.366699 +0.664280 0.037133 +0.753068 0.023473 +0.121543 0.353285 +0.148041 0.351196 +0.129252 0.352214 +0.151733 0.351563 +0.171326 0.350097 +0.250732 0.524740 +0.184814 0.348308 +0.190362 0.348632 +0.494792 0.316732 +0.332478 0.294083 +0.504883 0.316040 +0.499797 0.315959 +0.499048 0.316885 +0.508789 0.315155 +0.502930 0.315267 +0.012662 0.331868 +0.012657 0.203125 +0.008057 0.202637 +0.008052 0.332031 +0.452931 0.092897 +0.434693 0.103516 +0.430359 0.121094 +0.888184 0.402832 +0.874023 0.389160 +0.883240 0.393799 +0.676758 0.690582 +0.475220 0.390137 +0.888443 0.976762 +0.461243 0.403564 +0.466125 0.394715 +0.461243 0.978142 +0.475220 0.991763 +0.466125 0.987077 +0.874023 0.990971 +0.883240 0.986284 +0.031235 0.169434 +0.023969 0.171224 +0.036377 0.169922 +0.171326 0.192139 +0.168976 0.192505 +0.184814 0.193522 +0.190358 0.193360 +0.332931 0.239874 +0.494792 0.216146 +0.499797 0.216553 +0.504883 0.216553 +0.499044 0.215827 +0.505920 0.217285 +0.502930 0.217285 +0.014733 0.343343 +0.010035 0.343750 +0.287110 0.270426 +0.291260 0.270386 +0.300293 0.287598 +0.296224 0.287923 +0.976563 0.990919 +0.976563 0.986190 +0.978760 0.986187 +0.979004 0.990919 +0.978929 0.985302 +0.976563 0.708557 +0.978760 0.708130 +0.976563 0.985298 +0.979004 0.704071 +0.976563 0.703002 +0.355042 0.263957 +0.350749 0.282878 +0.978760 0.205566 +0.978760 0.211507 +0.976563 0.204915 +0.976563 0.209880 +0.978760 0.012451 +0.976563 0.012940 +0.976563 0.008627 +0.978760 0.009034 +0.976563 0.504517 +0.976563 0.498309 +0.978939 0.504805 +0.978814 0.499166 +0.976563 0.697103 +0.976563 0.504516 +0.978760 0.697753 +0.976563 0.697753 +0.978760 0.701934 +0.008255 0.460938 +0.007919 0.460938 +0.007813 0.460938 +0.008255 0.137695 +0.007813 0.137695 +0.143188 0.460938 +0.008255 0.137207 +0.007813 0.137207 +0.143677 0.460938 +0.143555 0.460938 +0.143188 0.137207 +0.143188 0.137695 +0.143677 0.137695 +0.143555 0.137207 +0.978939 0.216312 +0.976563 0.216053 +0.978760 0.494141 +0.976563 0.216064 +0.976563 0.494152 +0.916992 0.991760 +0.916992 0.992081 +0.916504 0.991760 +0.916504 0.992188 +0.914063 0.991760 +0.914063 0.992188 +0.916504 0.673584 +0.916992 0.673584 +0.916992 0.673096 +0.916504 0.673096 +0.914063 0.673584 +0.914063 0.992081 +0.914063 0.673096 +0.914063 0.673340 +0.945313 0.673096 +0.945313 0.673584 +0.947754 0.673584 +0.947754 0.673096 +0.948242 0.673096 +0.948242 0.673584 +0.948242 0.991760 +0.947754 0.991760 +0.945313 0.991760 +0.945313 0.992188 +0.945313 0.992081 +0.947754 0.992188 +0.948242 0.992081 +0.857422 0.236328 +0.857910 0.236328 +0.857422 0.236816 +0.857910 0.236816 +0.857910 0.367188 +0.857422 0.366699 +0.539063 0.236816 +0.539063 0.236328 +0.539063 0.366699 +0.857422 0.367188 +0.539063 0.367188 +0.932617 0.210938 +0.932129 0.210938 +0.932129 0.080566 +0.932617 0.080566 +0.929688 0.210938 +0.929688 0.080566 +0.932617 0.080078 +0.932129 0.080078 +0.929688 0.080078 +0.916992 0.648193 +0.916992 0.648438 +0.916504 0.648193 +0.916504 0.648438 +0.914063 0.648438 +0.914063 0.648193 +0.916504 0.518066 +0.916992 0.518066 +0.916992 0.517578 +0.916504 0.517578 +0.914063 0.518066 +0.914063 0.517578 +0.914063 0.517822 +0.023209 0.386719 +0.009203 0.400513 +0.014234 0.391480 +0.108765 0.451172 +0.424683 0.386719 +0.338867 0.451172 +0.438660 0.400635 +0.433655 0.391663 +0.338867 0.926941 +0.438660 0.977459 +0.424683 0.991255 +0.433655 0.986458 +0.023209 0.991302 +0.108765 0.926941 +0.009203 0.977516 +0.014234 0.986508 +0.324463 0.296387 +0.310928 0.294874 +0.312988 0.294434 +0.346016 0.246548 +0.594866 0.040900 +0.284349 0.071082 +0.942017 0.357829 +0.937378 0.336487 +0.949127 0.336060 +0.228021 0.056003 +0.229919 0.041829 +0.237610 0.056763 +0.226624 0.043457 +0.219849 0.034913 +0.218811 0.042724 +0.239197 0.075195 +0.230194 0.075195 +0.239136 0.106201 +0.230489 0.106201 +0.237488 0.134155 +0.229116 0.134399 +0.224304 0.153076 +0.229940 0.155599 +0.219604 0.162109 +0.201863 0.154134 +0.203084 0.163900 +0.201731 0.134847 +0.201558 0.106608 +0.201396 0.075277 +0.185547 0.162435 +0.178426 0.153157 +0.172559 0.134522 +0.173503 0.154948 +0.165664 0.133850 +0.164246 0.106689 +0.171188 0.106689 +0.171234 0.075562 +0.164429 0.075684 +0.166239 0.055990 +0.172938 0.055847 +0.201335 0.055176 +0.193878 0.033569 +0.200155 0.042155 +0.177816 0.043457 +0.178630 0.036946 +0.171672 0.042806 +0.935058 0.356201 +0.931396 0.365560 +0.916341 0.356934 +0.950440 0.308105 +0.938232 0.307861 +0.950440 0.276123 +0.938232 0.275879 +0.937622 0.255615 +0.948853 0.255900 +0.916504 0.307617 +0.916992 0.275635 +0.917074 0.254720 +0.944092 0.242188 +0.936035 0.242432 +0.937907 0.236165 +0.923798 0.232620 +0.916992 0.241536 +0.900268 0.233764 +0.898193 0.242188 +0.896240 0.255249 +0.891439 0.240845 +0.884277 0.256470 +0.895263 0.275635 +0.882935 0.275635 +0.895263 0.307617 +0.882935 0.307617 +0.884338 0.336121 +0.895630 0.336243 +0.916423 0.336833 +0.915283 0.367025 +0.899292 0.364746 +0.897461 0.355957 +0.890828 0.358053 +0.495351 0.316521 +0.874023 0.990972 +0.424683 0.992189 +0.893735 0.241533 +0.895237 0.357237 +0.938347 0.357325 +0.939355 0.241475 + + + + + + + + + + + +

4 0 3 4 4 0 1 0 0 0 18 2 2 18 18 18 3 2 18 18 0 4 0 0 0 1 5 1 1 1 5 6 7 5 5 16 7 4 16 16 19 8 6 19 19 19 9 6 19 19 16 10 4 16 16 3 11 5 3 3 7 12 11 7 7 17 13 8 17 17 6 14 10 6 6 6 15 10 6 6 17 16 8 17 17 2 17 9 2 2 22 18 12 22 22 8 19 14 8 8 12 20 15 12 12 8 21 14 8 8 22 22 12 22 22 9 23 13 9 9 23 24 16 23 23 20 25 18 20 20 13 26 19 13 13 20 27 18 20 20 23 28 16 23 23 11 29 17 11 11 14 30 20 14 14 21 31 22 21 21 15 32 23 15 15 21 33 22 21 21 14 34 20 14 14 10 35 21 10 10 1 36 49 1 1 0 37 48 0 0 9 38 56 9 9 9 39 56 9 9 0 40 48 0 0 8 41 57 8 8 0 42 260 0 0 4 43 261 4 4 12 44 59 12 12 12 45 59 12 12 8 46 58 8 8 0 47 260 0 0 11 48 60 11 11 16 49 50 16 16 20 50 61 20 20 3 51 51 3 3 16 52 50 16 16 11 53 60 11 11 2 54 53 2 2 17 55 52 17 17 21 56 63 21 21 2 57 53 2 2 21 58 63 21 21 10 59 62 10 10 6 60 55 6 6 10 61 263 10 10 14 62 262 14 14 10 63 263 10 10 6 64 55 6 6 2 65 54 2 2 18 66 2 18 18 1 67 1 1 1 5 68 7 5 5 5 69 7 5 5 1 70 1 1 1 16 71 4 16 16 19 72 6 19 19 3 73 5 3 3 7 74 11 7 7 7 75 11 7 7 3 76 5 3 3 17 77 8 17 17 13 78 267 13 13 20 79 266 20 20 22 80 12 22 22 22 81 12 22 22 20 82 266 20 20 9 83 13 9 9 15 84 23 15 15 21 85 22 21 21 23 86 264 23 23 23 87 264 23 23 21 88 22 21 21 11 89 265 11 11 16 90 50 16 16 9 91 56 9 9 20 92 61 20 20 9 93 56 9 9 16 94 50 16 16 1 95 49 1 1 21 96 63 21 21 17 97 52 17 17 3 98 51 3 3 21 99 63 21 21 3 100 51 3 3 11 101 60 11 11 24 102 24 24 24 27 103 25 27 27 26 104 26 26 26 26 105 26 26 26 25 106 27 25 25 24 107 24 24 24 28 108 28 28 28 31 109 29 31 31 30 110 30 30 30 30 111 30 30 30 29 112 31 29 29 28 113 28 28 28 32 114 32 32 32 35 115 33 35 35 34 116 34 34 34 34 117 34 34 34 33 118 35 33 33 32 119 32 32 32 39 120 37 39 39 38 121 38 38 38 36 122 36 36 36 36 123 36 36 36 38 124 38 38 38 37 125 39 37 37 43 126 41 43 43 42 127 42 42 42 40 128 40 40 40 40 129 40 40 40 42 130 42 42 42 41 131 43 41 41 47 132 45 47 47 46 133 46 46 46 44 134 44 44 44 44 135 44 44 44 46 136 46 46 46 45 137 47 45 45 37 138 71 37 37 38 139 70 38 38 24 140 64 24 24 24 141 64 24 24 25 142 65 25 25 37 143 71 37 37 27 144 269 27 27 24 145 268 24 24 39 146 273 39 39 39 147 273 39 39 24 148 268 24 24 38 149 274 38 38 28 150 66 28 28 29 151 67 29 29 41 152 121 41 41 28 153 66 28 28 41 154 121 41 41 42 155 120 42 42 45 156 123 45 45 46 157 122 46 46 33 158 69 33 33 33 159 69 33 33 46 160 122 46 46 32 161 68 32 32 44 162 276 44 44 45 163 279 45 45 34 164 270 34 34 34 165 270 34 34 45 166 279 45 45 33 167 271 33 33 25 168 27 25 25 26 169 26 26 26 31 170 29 31 31 31 171 29 31 31 28 172 28 28 28 25 173 27 25 25 29 174 31 29 29 30 175 30 30 30 35 176 33 35 35 35 177 33 35 35 32 178 32 32 32 29 179 31 29 29 36 180 272 36 36 42 181 42 42 42 43 182 41 43 43 42 183 42 42 42 36 184 272 36 36 37 185 275 37 37 40 186 40 40 40 46 187 278 46 46 47 188 277 47 47 46 189 278 46 46 40 190 40 40 40 41 191 43 41 41 37 192 71 37 37 28 193 66 28 28 42 194 120 42 42 28 195 66 28 28 37 196 71 37 37 25 197 65 25 25 32 198 68 32 32 46 199 122 46 46 29 200 67 29 29 29 201 67 29 29 46 202 122 46 46 41 203 121 41 41 48 204 72 48 48 51 205 73 51 51 50 206 74 50 50 50 207 74 50 50 49 208 75 49 49 48 209 72 48 48 52 210 76 52 52 55 211 77 55 55 54 212 78 54 54 54 213 78 54 54 53 214 79 53 53 52 215 76 52 52 56 216 80 56 56 59 217 81 59 59 58 218 82 58 58 58 219 82 58 58 57 220 83 57 57 56 221 80 56 56 63 222 85 63 63 62 223 86 62 62 60 224 84 60 60 60 225 84 60 60 62 226 86 62 62 61 227 87 61 61 67 228 89 67 67 66 229 90 66 66 64 230 88 64 64 64 231 88 64 64 66 232 90 66 66 65 233 91 65 65 71 234 93 71 71 70 235 94 70 70 68 236 92 68 68 68 237 92 68 68 70 238 94 70 70 69 239 95 69 69 48 240 124 48 48 49 241 125 49 49 61 242 131 61 61 48 243 124 48 48 61 244 131 61 61 62 245 130 62 62 51 246 293 51 51 48 247 292 48 48 63 248 297 63 63 63 249 297 63 63 48 250 292 48 48 62 251 298 62 62 52 252 126 52 52 53 253 127 53 53 65 254 133 65 65 52 255 126 52 52 65 256 133 65 65 66 257 132 66 66 56 258 128 56 56 57 259 129 57 57 70 260 134 70 70 70 261 134 70 70 57 262 129 57 57 69 263 135 69 69 68 264 300 68 68 69 265 303 69 69 58 266 294 58 58 58 267 294 58 58 69 268 303 69 69 57 269 295 57 57 49 270 75 49 49 50 271 74 50 50 55 272 77 55 55 55 273 77 55 55 52 274 76 52 52 49 275 75 49 49 53 276 79 53 53 54 277 78 54 54 59 278 81 59 59 59 279 81 59 59 56 280 80 56 56 53 281 79 53 53 60 282 296 60 60 66 283 90 66 66 67 284 89 67 67 66 285 90 66 66 60 286 296 60 60 61 287 299 61 61 64 288 88 64 64 70 289 302 70 70 71 290 301 71 71 70 291 302 70 70 64 292 88 64 64 65 293 91 65 65 61 294 131 61 61 49 295 125 49 49 52 296 126 52 52 61 297 131 61 61 52 298 126 52 52 66 299 132 66 66 65 300 133 65 65 53 301 127 53 53 70 302 134 70 70 70 303 134 70 70 53 304 127 53 53 56 305 128 56 56 73 306 99 73 73 72 307 96 72 72 74 308 98 74 74 74 309 98 74 74 72 310 96 72 72 75 311 97 75 75 77 312 103 77 77 76 313 100 76 76 78 314 102 78 78 78 315 102 78 78 76 316 100 76 76 79 317 101 79 79 81 318 107 81 81 80 319 104 80 80 82 320 106 82 82 82 321 106 82 82 80 322 104 80 80 83 323 105 83 83 84 324 108 84 84 86 325 110 86 86 85 326 111 85 85 86 327 110 86 86 84 328 108 84 84 87 329 109 87 87 88 330 112 88 88 90 331 114 90 90 89 332 115 89 89 90 333 114 90 90 88 334 112 88 88 91 335 113 91 91 92 336 116 92 92 94 337 118 94 94 93 338 119 93 93 94 339 118 94 94 92 340 116 92 92 95 341 117 95 95 86 342 143 86 86 87 343 142 87 87 72 344 136 72 72 75 345 137 75 75 72 346 136 72 72 87 347 142 87 87 72 348 280 72 72 73 349 281 73 73 85 350 287 85 85 85 351 287 85 85 86 352 286 86 86 72 353 280 72 72 76 354 138 76 76 91 355 256 91 91 79 356 139 79 79 91 357 256 91 91 76 358 138 76 76 90 359 257 90 90 83 360 141 83 83 94 361 259 94 94 95 362 258 95 95 83 363 141 83 83 80 364 140 80 80 94 365 259 94 94 82 366 283 82 82 95 367 289 95 95 92 368 288 92 92 95 369 289 95 95 82 370 283 82 82 83 371 282 83 83 74 372 98 74 74 75 373 97 75 75 77 374 103 77 77 77 375 103 77 77 75 376 97 75 75 76 377 100 76 76 78 378 102 78 78 79 379 101 79 79 81 380 107 81 81 81 381 107 81 81 79 382 101 79 79 80 383 104 80 80 89 384 115 89 89 90 385 114 90 90 84 386 284 84 84 84 387 284 84 84 90 388 114 90 90 87 389 285 87 87 93 390 291 93 93 94 391 290 94 94 88 392 112 88 88 88 393 112 88 88 94 394 290 94 94 91 395 113 91 91 87 396 142 87 87 76 397 138 76 76 75 398 137 75 75 76 399 138 76 76 87 400 142 87 87 90 401 257 90 90 79 402 139 79 79 91 403 256 91 91 94 404 259 94 94 79 405 139 79 79 94 406 259 94 94 80 407 140 80 80 105 408 146 115 115 96 409 144 96 96 104 410 171 113 113 96 411 144 96 96 105 412 146 115 115 97 413 147 97 97 98 414 158 98 98 100 415 159 104 104 117 416 778 140 140 118 417 777 141 141 117 418 778 140 140 100 419 159 104 104 119 420 780 143 143 96 421 144 96 96 108 422 779 128 128 96 423 144 96 96 119 424 780 143 143 104 425 171 113 113 110 426 784 131 131 105 427 146 115 115 111 428 783 132 132 111 429 783 132 132 105 430 146 115 115 101 431 150 105 105 113 432 788 135 135 107 433 164 119 119 114 434 787 136 136 114 435 787 136 136 107 436 164 119 119 103 437 154 107 107 118 438 176 141 141 111 439 177 132 132 117 440 179 140 140 117 441 179 140 140 111 442 177 132 132 112 443 178 133 133 109 444 789 129 129 108 445 790 128 128 96 446 144 96 96 109 447 789 129 129 96 448 144 96 96 97 449 147 97 97 109 450 792 129 129 97 451 147 97 97 110 452 791 131 131 110 453 791 131 131 97 454 147 97 97 105 455 146 115 115 101 456 150 105 105 99 457 151 99 99 111 458 794 132 132 112 459 793 133 133 111 460 794 132 132 99 461 151 99 99 112 462 796 133 133 99 463 151 99 99 113 464 795 135 135 113 465 795 135 135 99 466 151 99 99 107 467 164 119 119 103 468 154 107 107 102 469 155 106 106 114 470 800 136 136 115 471 799 137 137 114 472 800 136 136 102 473 155 106 106 115 474 802 137 137 102 475 155 106 106 116 476 801 139 139 116 477 801 139 139 102 478 155 106 106 106 479 166 117 117 116 480 806 139 139 106 481 166 117 117 117 482 805 140 140 117 483 805 140 140 106 484 166 117 117 98 485 158 98 98 118 486 808 141 141 100 487 159 104 104 119 488 807 143 143 119 489 807 143 143 100 490 159 104 104 104 491 171 113 113 117 492 179 140 140 113 493 341 135 135 116 494 347 139 139 113 495 341 135 135 117 496 179 140 140 112 497 178 133 133 116 498 347 139 139 113 499 341 135 135 114 500 342 136 136 116 501 347 139 139 114 502 342 136 136 115 503 343 137 137 111 504 177 132 132 118 505 176 141 141 119 506 351 143 143 119 507 351 143 143 110 508 337 131 131 111 509 177 132 132 110 510 337 131 131 119 511 351 143 143 108 512 333 128 128 110 513 337 131 131 108 514 333 128 128 109 515 332 129 129 99 516 151 99 99 98 517 158 98 98 107 518 164 119 119 107 519 164 119 119 98 520 158 98 98 106 521 166 117 117 106 522 166 117 117 103 523 154 107 107 107 524 164 119 119 103 525 154 107 107 106 526 166 117 117 102 527 155 106 106 98 528 158 98 98 99 529 151 99 99 101 530 150 105 105 101 531 150 105 105 100 532 159 104 104 98 533 158 98 98 104 534 171 113 113 101 535 150 105 105 105 536 146 115 115 100 537 159 104 104 101 538 150 105 105 104 539 171 113 113 124 540 211 164 164 120 541 208 160 160 121 542 209 161 161 124 543 211 164 164 121 544 209 161 161 138 545 210 178 178 125 546 215 165 165 136 547 212 176 176 139 548 214 179 179 139 549 214 179 179 136 550 212 176 176 123 551 213 163 163 127 552 219 167 167 137 553 216 177 177 126 554 218 166 166 122 555 217 162 162 126 556 218 166 166 137 557 216 177 177 142 558 220 182 182 129 559 221 169 169 132 560 223 172 172 128 561 222 168 168 132 562 223 172 172 129 563 221 169 169 143 564 224 183 183 131 565 225 171 171 140 566 226 180 180 140 567 226 180 180 133 568 227 173 173 143 569 224 183 183 134 570 228 174 174 130 571 229 170 170 141 572 230 181 181 134 573 228 174 174 141 574 230 181 181 135 575 231 175 175 120 576 316 160 160 132 577 321 172 172 128 578 320 168 168 132 579 321 172 172 120 580 316 160 160 124 581 317 164 164 126 582 319 166 166 122 583 318 162 162 130 584 323 170 170 130 585 323 170 170 134 586 322 174 174 126 587 319 166 166 138 588 210 178 178 121 589 209 161 161 125 590 215 165 165 125 591 215 165 165 121 592 209 161 161 136 593 212 176 176 139 594 214 179 179 123 595 213 163 163 127 596 219 167 167 127 597 219 167 167 123 598 213 163 163 137 599 216 177 177 133 600 227 173 173 140 601 226 180 180 129 602 325 169 169 129 603 325 169 169 142 604 324 182 182 133 605 227 173 173 135 606 327 175 175 141 607 326 181 181 131 608 225 171 171 131 609 225 171 171 143 610 224 183 183 135 611 327 175 175 146 612 234 186 186 145 613 235 185 185 147 614 233 187 187 144 615 232 184 184 147 616 233 187 187 145 617 235 185 185 148 618 236 188 188 151 619 237 191 191 150 620 238 190 190 150 621 238 190 190 149 622 239 189 189 148 623 236 188 188 154 624 242 194 194 153 625 243 193 193 152 626 240 192 192 154 627 242 194 194 152 628 240 192 192 155 629 241 195 195 159 630 245 199 199 158 631 246 198 198 157 632 247 197 197 159 633 245 199 199 157 634 247 197 197 156 635 244 196 196 161 636 251 201 201 160 637 248 200 200 162 638 250 202 202 162 639 250 202 202 160 640 248 200 200 163 641 249 203 203 164 642 252 204 204 166 643 254 206 206 165 644 255 205 205 166 645 254 206 206 164 646 252 204 204 167 647 253 207 207 147 648 305 187 187 144 649 304 184 184 158 650 309 198 198 158 651 309 198 198 159 652 308 199 199 147 653 305 187 187 164 654 310 204 204 165 655 311 205 205 153 656 307 193 193 153 657 307 193 193 154 658 306 194 194 164 659 310 204 204 151 660 237 191 191 148 661 236 188 188 146 662 234 186 186 146 663 234 186 186 148 664 236 188 188 145 665 235 185 185 155 666 241 195 195 152 667 240 192 192 150 668 238 190 190 150 669 238 190 190 152 670 240 192 192 149 671 239 189 189 156 672 312 196 196 157 673 313 197 197 162 674 250 202 202 162 675 250 202 202 163 676 249 203 203 156 677 312 196 196 160 678 248 200 200 161 679 251 201 201 166 680 315 206 206 166 681 315 206 206 167 682 314 207 207 160 683 248 200 200

+

210 864 478 252 252 208 865 476 250 250 220 866 488 535 264 212 867 480 254 254 211 868 479 253 253 214 869 482 256 256 213 870 481 255 255 211 871 479 253 253 212 872 480 254 254 213 873 481 255 259 215 874 483 257 258 216 875 484 258 260 215 876 483 257 258 213 877 481 255 259 212 878 480 254 257 217 879 485 259 261 218 880 486 260 262 219 881 487 261 263 218 882 486 260 262 220 883 488 262 264 219 884 487 261 263 218 885 486 260 262 221 886 489 263 265 220 887 488 262 264 221 888 489 263 265 222 889 490 264 266 220 890 488 262 264 221 891 489 263 267 223 892 491 265 268 222 893 490 264 269 223 894 491 265 268 224 895 492 266 270 222 896 490 264 269 228 897 496 270 274 227 898 495 269 273 226 899 494 268 272 226 900 494 268 272 227 901 495 269 273 225 902 493 267 271 229 903 497 271 275 227 904 495 269 273 228 905 496 270 274 227 906 495 269 273 229 907 497 271 275 208 908 476 250 250 230 909 498 272 276 229 910 497 271 275 231 911 499 273 277 229 912 497 271 275 232 913 500 274 278 208 914 476 250 250 232 915 500 274 278 229 916 497 271 275 230 917 498 272 276 235 918 503 277 281 233 919 501 275 279 234 920 502 276 280 231 921 499 278 277 233 922 501 275 279 235 923 503 277 281 233 924 501 275 279 209 925 477 251 251 236 926 504 279 282 233 927 501 275 279 236 928 504 279 282 234 929 502 276 280 209 930 477 251 251 222 931 490 280 266 224 932 492 281 283 236 933 504 279 282 209 934 477 251 251 224 935 492 281 283 238 936 506 283 285 237 937 505 282 284 233 938 501 275 279 209 939 477 251 251 233 940 501 275 279 237 941 505 282 284 238 942 506 283 285 214 943 482 285 287 237 944 505 282 284 214 945 482 285 287 238 946 506 283 285 239 947 507 284 286 214 948 482 285 287 239 949 507 284 286 212 950 480 286 257 212 951 480 286 257 239 952 507 284 286 240 953 508 287 288 241 954 509 288 289 212 955 480 286 257 240 956 508 287 288 212 957 480 286 257 241 958 509 288 289 215 959 483 289 258 215 960 483 289 258 241 961 509 288 289 242 962 510 290 290 242 963 510 290 290 241 964 509 288 289 243 965 511 291 291 242 966 510 290 290 243 967 511 291 291 244 968 512 292 292 245 969 513 293 293 215 970 483 289 258 242 971 510 290 290 215 972 483 289 258 245 973 513 293 293 246 974 514 294 294 215 975 483 289 258 246 976 514 294 294 247 977 515 295 295 249 978 517 297 297 246 979 514 298 298 248 980 516 296 296 246 981 514 298 298 249 982 517 297 297 247 983 515 295 295 251 984 519 302 302 243 985 511 299 299 241 986 509 300 300 243 987 511 299 299 251 988 519 302 302 250 989 518 301 301 241 990 509 300 289 252 991 520 303 303 251 992 519 302 304 252 993 520 303 303 241 994 509 300 289 240 995 508 304 288 253 996 521 305 306 252 997 520 303 307 240 998 508 304 305 240 999 508 304 305 239 1000 507 306 308 253 1001 521 305 306 254 1002 522 308 310 239 1003 507 306 308 238 1004 506 307 309 239 1005 507 306 308 254 1006 522 308 310 253 1007 521 305 306 233 1008 501 310 312 254 1009 522 308 310 238 1010 506 307 309 254 1011 522 308 310 233 1012 501 310 312 255 1013 523 309 311 255 1014 523 538 488 231 1015 499 278 277 229 1016 497 271 275 231 1017 499 278 277 255 1018 523 538 488 233 1019 501 275 279 256 1020 524 312 313 257 1021 525 313 314 255 1022 523 311 311 229 1023 497 317 317 228 1024 496 315 315 256 1025 524 314 313 256 1026 524 314 313 228 1027 496 315 315 258 1028 526 316 316 228 1029 496 315 315 226 1030 494 318 318 258 1031 526 316 316 258 1032 526 316 316 226 1033 494 318 318 259 1034 527 319 319 260 1035 528 320 320 261 1036 529 321 321 245 1037 513 322 322 260 1038 528 320 320 245 1039 513 322 322 242 1040 510 323 323 257 1041 525 325 324 262 1042 530 326 325 230 1043 498 324 276 230 1044 498 324 276 231 1045 499 327 277 257 1046 525 325 324 232 1047 500 329 278 262 1048 530 326 325 263 1049 531 328 326 262 1050 530 326 325 232 1051 500 329 278 230 1052 498 324 276 219 1053 487 261 263 232 1054 500 329 278 217 1055 485 259 261 217 1056 485 259 261 232 1057 500 329 278 263 1058 531 328 326 264 1059 532 330 327 267 1060 535 333 330 265 1061 533 331 328 264 1062 532 330 327 265 1063 533 331 328 266 1064 534 332 329 267 1065 535 333 330 268 1066 536 334 331 265 1067 533 331 328 269 1068 537 335 332 267 1069 535 333 330 264 1070 532 330 327 268 1071 536 334 331 267 1072 535 333 330 270 1073 538 336 333 268 1074 536 334 331 270 1075 538 336 333 271 1076 539 337 334 267 1077 535 333 330 272 1078 540 338 335 270 1079 538 336 333 267 1080 535 333 330 273 1081 541 339 336 272 1082 540 338 335 272 1083 540 338 335 273 1084 541 339 336 274 1085 542 340 337 267 1086 535 333 330 293 1087 771 615 564 273 1088 541 339 336 293 1089 771 615 564 267 1090 535 333 330 275 1091 543 341 338 275 1092 543 341 338 267 1093 535 333 330 269 1094 537 335 332 275 1095 543 341 338 269 1096 537 335 332 276 1097 544 342 339 249 1098 517 344 297 215 1099 483 257 340 247 1100 515 343 341 215 1101 483 257 340 249 1102 517 344 297 216 1103 484 258 342 211 1104 479 253 253 277 1105 545 346 344 214 1106 482 256 256 237 1107 505 345 343 214 1108 482 256 256 277 1109 545 346 344 210 1110 478 347 345 237 1111 505 345 343 277 1112 545 346 344 237 1113 505 345 343 210 1114 478 347 345 209 1115 477 348 346 278 1116 546 351 348 210 1117 478 349 345 218 1118 486 350 347 208 1119 476 540 351 210 1120 478 349 345 278 1121 546 351 348 278 1122 546 352 348 279 1123 547 353 349 227 1124 495 354 350 278 1125 546 352 348 227 1126 495 354 350 208 1127 476 355 351 225 1128 493 356 352 279 1129 547 353 349 280 1130 548 357 353 279 1131 547 353 349 225 1132 493 356 352 227 1133 495 354 350 244 1134 512 360 355 250 1135 518 358 301 281 1136 549 359 354 250 1137 518 358 301 244 1138 512 360 355 243 1139 511 361 299 242 1140 510 323 323 281 1141 549 359 354 260 1142 528 320 320 281 1143 549 359 354 242 1144 510 323 323 244 1145 512 360 355 246 1146 514 298 298 245 1147 513 322 322 248 1148 516 362 296 261 1149 529 321 321 248 1150 516 362 296 245 1151 513 322 322 224 1152 492 365 270 282 1153 550 364 356 236 1154 504 366 357 282 1155 550 364 356 224 1156 492 365 270 223 1157 491 363 268 282 1158 550 364 356 283 1159 551 368 359 234 1160 502 367 358 234 1161 502 367 358 236 1162 504 366 357 282 1163 550 364 356 266 1164 555 372 363 284 1165 552 369 360 264 1166 554 371 362 284 1167 552 369 360 285 1168 553 370 361 264 1169 554 371 362 285 1170 553 370 367 269 1171 557 374 366 264 1172 554 371 364 269 1173 557 374 366 285 1174 553 370 367 286 1175 556 373 365 287 1176 559 376 369 269 1177 557 374 366 286 1178 556 373 365 269 1179 557 374 366 287 1180 559 376 369 276 1181 558 375 368 255 1182 523 311 311 283 1183 551 377 359 282 1184 550 378 356 223 1185 491 380 268 210 1186 478 349 345 282 1187 550 378 356 282 1188 550 378 356 210 1189 478 349 345 255 1190 523 311 311 218 1191 486 350 347 210 1192 478 349 345 221 1193 489 379 267 221 1194 489 379 267 210 1195 478 349 345 223 1196 491 380 268 278 1197 546 351 348 263 1198 531 381 370 256 1199 524 312 313 256 1200 524 312 313 263 1201 531 381 370 262 1202 530 382 371 257 1203 525 313 314 256 1204 524 312 313 262 1205 530 382 371 279 1206 547 384 349 256 1207 524 312 313 258 1208 526 383 316 256 1209 524 312 313 279 1210 547 384 349 278 1211 546 351 348 255 1212 523 311 311 210 1213 478 349 345 277 1214 545 385 344 255 1215 523 311 311 277 1216 545 385 344 254 1217 522 386 310 211 1218 479 388 253 254 1219 522 386 310 277 1220 545 385 344 254 1221 522 386 310 211 1222 479 388 253 253 1223 521 387 306 213 1224 481 389 255 252 1225 520 390 307 253 1226 521 387 306 253 1227 521 387 306 211 1228 479 388 253 213 1229 481 389 255 213 1230 481 389 255 251 1231 519 391 302 252 1232 520 390 307 251 1233 519 391 302 216 1234 484 392 342 260 1235 528 393 320 216 1236 484 392 342 251 1237 519 391 302 213 1238 481 389 255 250 1239 518 358 301 260 1240 528 393 320 281 1241 549 394 354 251 1242 519 391 302 260 1243 528 393 320 250 1244 518 358 301 260 1245 528 393 320 216 1246 484 392 342 261 1247 529 395 321 248 1248 516 296 296 216 1249 484 392 342 249 1250 517 396 297 261 1251 529 395 321 216 1252 484 392 342 248 1253 516 296 296 268 1254 560 397 372 289 1255 563 400 375 288 1256 562 399 374 289 1257 563 400 375 268 1258 560 397 372 271 1259 561 398 373 265 1260 564 401 376 268 1261 560 397 372 290 1262 565 402 377 290 1263 565 402 377 268 1264 560 397 372 288 1265 562 399 374 284 1266 566 403 378 265 1267 564 401 376 290 1268 565 402 377 265 1269 564 401 376 284 1270 566 403 378 266 1271 567 404 379 291 1272 568 405 380 274 1273 571 408 383 273 1274 570 407 382 274 1275 571 408 383 291 1276 568 405 380 292 1277 569 406 381 273 1278 772 616 565 293 1279 691 528 480 355 1280 692 529 481 293 1281 572 409 387 276 1282 575 412 388 287 1283 574 411 369 276 1284 575 412 388 293 1285 572 409 387 275 1286 573 410 386 296 1287 578 415 390 294 1288 576 413 389 295 1289 577 414 389 294 1290 576 413 389 296 1291 578 415 390 297 1292 579 416 391 298 1293 580 417 392 294 1294 576 413 389 297 1295 579 416 391 297 1296 579 416 391 299 1297 581 418 393 298 1298 580 417 392 301 1299 583 420 394 295 1300 577 414 389 294 1301 576 413 389 301 1302 583 420 394 294 1303 576 413 389 300 1304 582 419 394 298 1305 580 417 392 299 1306 581 418 393 303 1307 585 422 396 298 1308 580 417 392 303 1309 585 422 396 302 1310 584 421 395 301 1311 583 420 394 300 1312 582 419 394 305 1313 587 424 398 305 1314 587 424 398 300 1315 582 419 394 304 1316 586 423 397 298 1317 580 417 392 306 1318 588 425 399 307 1319 589 426 400 306 1320 588 425 399 298 1321 580 417 392 302 1322 584 421 395 304 1323 586 423 397 307 1324 589 426 400 308 1325 590 427 401 307 1326 589 426 400 304 1327 586 423 397 300 1328 582 419 394 307 1329 589 426 400 309 1330 588 428 402 308 1331 590 427 401 309 1332 588 428 402 307 1333 589 426 400 306 1334 588 425 399 279 1335 547 384 349 259 1336 591 429 319 280 1337 548 430 353 259 1338 591 429 319 279 1339 547 384 349 258 1340 526 383 316 310 1341 594 433 404 271 1342 592 431 373 270 1343 593 432 403 271 1344 592 431 373 310 1345 594 433 404 289 1346 595 434 375 311 1347 597 436 407 310 1348 594 433 406 272 1349 596 435 405 272 1350 596 435 405 310 1351 594 433 406 270 1352 593 432 403 274 1353 599 438 383 292 1354 598 437 381 311 1355 597 436 407 274 1356 599 438 383 311 1357 597 436 407 272 1358 596 435 405 312 1359 600 439 408 313 1360 601 440 409 314 1361 602 441 410 313 1362 601 440 409 315 1363 603 442 411 314 1364 602 441 410 315 1365 603 442 411 316 1366 604 443 412 314 1367 602 441 410 316 1368 604 443 412 315 1369 603 442 411 317 1370 605 444 413 319 1371 607 446 415 314 1372 602 441 410 318 1373 606 445 414 314 1374 602 441 410 319 1375 607 446 415 312 1376 600 439 408 320 1377 608 447 416 319 1378 607 446 415 318 1379 606 445 414 320 1380 608 447 416 318 1381 606 445 414 321 1382 609 448 417 314 1383 602 441 410 322 1384 610 449 418 318 1385 606 445 414 322 1386 610 449 418 314 1387 602 441 410 316 1388 604 443 412 303 1389 611 450 419 316 1390 604 443 412 317 1391 605 444 413 316 1392 604 443 412 303 1393 611 450 419 299 1394 612 451 412 316 1395 604 443 412 297 1396 613 452 418 322 1397 610 449 418 297 1398 613 452 418 316 1399 604 443 412 299 1400 612 451 412 318 1401 606 445 414 323 1402 614 453 420 321 1403 609 448 417 323 1404 614 453 420 318 1405 606 445 414 322 1406 610 449 418 323 1407 614 453 420 322 1408 610 449 418 296 1409 615 454 421 322 1410 610 449 418 297 1411 613 452 418 296 1412 615 454 421 324 1413 616 455 422 325 1414 617 456 423 309 1415 616 457 422 325 1416 617 456 423 308 1417 618 458 423 309 1418 616 457 422 326 1419 619 459 424 325 1420 617 456 423 327 1421 620 460 425 327 1422 620 460 425 325 1423 617 456 423 324 1424 616 455 422 329 1425 622 462 427 326 1426 619 459 424 328 1427 621 461 426 328 1428 621 461 426 326 1429 619 459 424 327 1430 620 460 425 331 1431 624 464 429 329 1432 622 462 427 330 1433 623 463 428 329 1434 622 462 427 331 1435 624 464 429 326 1436 619 459 424 332 1437 625 465 430 308 1438 618 458 423 325 1439 617 456 423 308 1440 618 458 423 332 1441 625 465 430 304 1442 626 466 430 326 1443 619 459 424 331 1444 624 464 429 332 1445 625 465 430 326 1446 619 459 424 332 1447 625 465 430 325 1448 617 456 423 333 1449 627 465 431 305 1450 628 467 432 332 1451 625 465 430 332 1452 625 465 430 305 1453 628 467 432 304 1454 626 466 430 334 1455 629 464 433 332 1456 625 465 430 331 1457 624 464 429 332 1458 625 465 430 334 1459 629 464 433 333 1460 627 465 431 330 1461 623 463 428 335 1462 630 468 434 331 1463 624 464 429 335 1464 630 468 434 334 1465 629 464 433 331 1466 624 464 429 336 1467 633 471 437 319 1468 631 469 435 320 1469 632 470 436 336 1470 633 471 437 320 1471 632 470 436 337 1472 634 472 438 336 1473 633 471 437 338 1474 635 473 439 339 1475 636 474 440 337 1476 634 472 438 338 1477 635 473 439 336 1478 633 471 437 319 1479 631 469 435 340 1480 637 475 441 312 1481 638 476 442 340 1482 637 475 441 319 1483 631 469 435 336 1484 633 471 437 313 1485 639 477 442 340 1486 637 475 441 341 1487 640 478 441 340 1488 637 475 441 313 1489 639 477 442 312 1490 638 476 442 342 1491 641 479 443 336 1492 633 471 437 339 1493 636 474 440 336 1494 633 471 437 342 1495 641 479 443 340 1496 637 475 441 339 1497 636 474 440 335 1498 642 480 439 330 1499 643 481 444 335 1500 642 480 439 339 1501 636 474 440 338 1502 635 473 439 342 1503 641 479 443 330 1504 643 481 444 329 1505 644 482 445 330 1506 643 481 444 342 1507 641 479 443 339 1508 636 474 440 340 1509 637 475 441 343 1510 645 483 445 341 1511 640 478 441 343 1512 645 483 445 340 1513 637 475 441 342 1514 641 479 443 328 1515 646 484 445 343 1516 645 483 445 342 1517 641 479 443 342 1518 641 479 443 329 1519 644 482 445 328 1520 646 484 445 343 1521 647 485 446 328 1522 648 486 446 344 1523 649 487 447 328 1524 648 486 446 327 1525 650 488 447 344 1526 649 487 447 341 1527 652 490 449 344 1528 649 487 447 345 1529 651 489 448 344 1530 649 487 447 341 1531 652 490 449 343 1532 647 485 446 346 1533 653 491 450 344 1534 649 487 447 327 1535 650 488 447 327 1536 650 488 447 324 1537 654 492 450 346 1538 653 491 450 324 1539 654 492 450 309 1540 655 493 450 346 1541 653 491 450 346 1542 653 491 450 309 1543 655 493 450 306 1544 656 494 450 346 1545 653 491 450 302 1546 658 496 451 347 1547 657 495 451 302 1548 658 496 451 346 1549 653 491 450 306 1550 656 494 450 345 1551 651 489 448 344 1552 649 487 447 346 1553 653 491 450 345 1554 651 489 448 346 1555 653 491 450 347 1556 657 495 451 313 1557 659 497 452 341 1558 652 490 449 345 1559 651 489 448 313 1560 659 497 452 345 1561 651 489 448 315 1562 660 498 453 317 1563 661 499 454 315 1564 660 498 453 345 1565 651 489 448 345 1566 651 489 448 347 1567 657 495 451 317 1568 661 499 454 317 1569 661 499 454 347 1570 657 495 451 303 1571 662 500 454 347 1572 657 495 451 302 1573 658 496 451 303 1574 662 500 454 337 1575 663 501 455 320 1576 664 502 456 348 1577 665 503 457 320 1578 664 502 456 321 1579 666 504 458 348 1580 665 503 457 321 1581 666 504 458 323 1582 667 505 459 348 1583 665 503 457 348 1584 665 503 457 323 1585 667 505 459 349 1586 668 506 460 338 1587 670 508 462 348 1588 665 503 457 350 1589 669 507 461 348 1590 665 503 457 338 1591 670 508 462 337 1592 663 501 455 349 1593 668 506 460 323 1594 667 505 459 296 1595 671 509 459 349 1596 668 506 460 296 1597 671 509 459 295 1598 672 510 460 335 1599 673 508 463 338 1600 670 508 462 350 1601 669 507 461 335 1602 673 508 463 350 1603 669 507 461 334 1604 674 511 464 348 1605 665 503 457 351 1606 675 512 465 350 1607 669 507 461 351 1608 675 512 465 348 1609 665 503 457 349 1610 668 506 460 349 1611 668 506 460 301 1612 676 513 465 351 1613 675 512 465 301 1614 676 513 465 349 1615 668 506 460 295 1616 672 510 460 350 1617 669 507 461 351 1618 675 512 465 334 1619 674 511 464 334 1620 674 511 464 351 1621 675 512 465 333 1622 677 514 466 333 1623 677 514 466 351 1624 675 512 465 305 1625 678 515 467 351 1626 675 512 465 301 1627 676 513 465 305 1628 678 515 467 290 1629 679 516 468 352 1630 682 519 471 285 1631 680 517 469 290 1632 679 516 468 285 1633 680 517 469 284 1634 681 518 470 290 1635 679 516 468 288 1636 683 520 472 352 1637 682 519 471 352 1638 682 519 471 288 1639 683 520 472 353 1640 684 521 473 353 1641 684 521 473 288 1642 683 520 472 310 1643 685 522 474 310 1644 685 522 474 288 1645 683 520 472 289 1646 686 523 475 353 1647 684 521 473 311 1648 688 525 477 354 1649 687 524 476 311 1650 688 525 477 353 1651 684 521 473 310 1652 685 522 474 354 1653 687 524 476 311 1654 688 525 477 291 1655 689 526 478 291 1656 689 526 478 311 1657 688 525 477 292 1658 690 527 479 291 1659 689 526 478 355 1660 692 529 481 354 1661 687 524 476 352 1662 682 519 471 354 1663 687 524 476 355 1664 692 529 481 354 1665 687 524 476 352 1666 682 519 471 353 1667 684 521 473 286 1668 693 530 482 355 1669 692 529 481 293 1670 691 528 480 286 1671 693 530 482 293 1672 691 528 480 287 1673 694 531 483 285 1674 680 517 469 355 1675 692 529 481 286 1676 693 530 482 355 1677 692 529 481 285 1678 680 517 469 352 1679 682 519 471 356 1680 695 532 485 257 1681 525 325 314 231 1682 499 327 484 231 1683 499 327 484 235 1684 503 533 486 356 1685 695 532 485 235 1686 503 533 486 283 1687 551 368 359 356 1688 695 532 485 283 1689 551 368 359 235 1690 503 533 486 234 1691 502 367 358 255 1692 523 311 311 257 1693 525 313 314 356 1694 695 534 485 255 1695 523 311 311 356 1696 695 534 485 283 1697 551 377 359 219 1698 487 536 263 208 1699 476 250 250 232 1700 500 274 278 220 1701 488 535 264 208 1702 476 250 250 219 1703 487 536 263 278 1704 546 351 348 218 1705 486 350 347 217 1706 485 537 487 278 1707 546 351 348 217 1708 485 537 487 263 1709 531 381 370 209 1710 477 251 251 220 1711 488 535 264 222 1712 490 280 266 357 1713 696 541 490 358 1714 697 542 491 359 1715 698 543 492 358 1716 697 542 491 357 1717 696 541 490 395 1718 736 581 530 362 1719 701 546 495 360 1720 699 544 493 361 1721 700 545 494 360 1722 699 544 493 363 1723 702 547 496 361 1724 700 545 494 360 1725 699 544 493 365 1726 704 549 498 363 1727 702 547 496 364 1728 703 548 497 363 1729 702 547 496 365 1730 704 549 498 364 1731 753 598 547 361 1732 756 601 550 363 1733 773 617 566 362 1734 701 546 495 366 1735 705 550 499 367 1736 706 551 500 362 1737 701 546 495 367 1738 706 551 500 360 1739 699 544 493 368 1740 707 552 501 367 1741 706 551 500 366 1742 705 550 499 367 1743 706 551 500 368 1744 707 552 501 369 1745 708 553 502 371 1746 710 555 504 369 1747 708 553 502 370 1748 709 554 503 368 1749 707 552 501 370 1750 709 554 503 369 1751 708 553 502 371 1752 710 555 504 373 1753 712 557 506 372 1754 711 556 505 373 1755 712 557 506 371 1756 710 555 504 370 1757 709 554 503 373 1758 768 613 562 374 1759 766 611 560 372 1760 774 618 567 375 1761 714 559 508 374 1762 713 558 507 376 1763 715 560 509 374 1764 713 558 507 375 1765 714 559 508 372 1766 711 556 505 375 1767 714 559 508 377 1768 716 561 510 372 1769 711 556 505 377 1770 716 561 510 371 1771 710 555 504 372 1772 711 556 505 379 1773 718 563 512 367 1774 706 551 500 378 1775 717 562 511 378 1776 717 562 511 367 1777 706 551 500 369 1778 708 553 502 378 1779 717 562 511 371 1780 710 555 504 377 1781 716 561 510 371 1782 710 555 504 378 1783 717 562 511 369 1784 708 553 502 381 1785 720 565 514 375 1786 714 559 508 380 1787 719 564 513 380 1788 719 564 513 375 1789 714 559 508 376 1790 715 560 509 382 1791 721 566 515 377 1792 716 561 510 381 1793 720 565 514 381 1794 720 565 514 377 1795 716 561 510 375 1796 714 559 508 381 1797 775 619 568 380 1798 737 582 531 357 1799 696 541 490 357 1800 722 567 516 359 1801 723 568 517 382 1802 721 566 515 357 1803 722 567 516 382 1804 721 566 515 381 1805 720 565 514 359 1806 723 568 517 383 1807 724 569 518 384 1808 725 570 519 359 1809 723 568 517 384 1810 725 570 519 382 1811 721 566 515 386 1812 727 572 521 384 1813 725 570 519 383 1814 724 569 518 384 1815 725 570 519 386 1816 727 572 521 385 1817 726 571 520 388 1818 729 574 523 385 1819 726 571 520 387 1820 728 573 522 386 1821 727 572 521 387 1822 728 573 522 385 1823 726 571 520 385 1824 726 571 520 378 1825 717 562 511 384 1826 725 570 519 378 1827 717 562 511 385 1828 726 571 520 379 1829 718 563 512 384 1830 725 570 519 378 1831 717 562 511 382 1832 721 566 515 382 1833 721 566 515 378 1834 717 562 511 377 1835 716 561 510 385 1836 726 571 520 388 1837 729 574 523 379 1838 718 563 512 388 1839 729 574 523 389 1840 730 575 524 379 1841 718 563 512 389 1842 730 575 524 360 1843 699 544 493 379 1844 718 563 512 379 1845 718 563 512 360 1846 699 544 493 367 1847 706 551 500 365 1848 704 549 498 391 1849 732 577 526 390 1850 731 576 525 390 1851 731 576 525 364 1852 703 548 497 365 1853 704 549 498 389 1854 730 575 524 365 1855 704 549 498 360 1856 699 544 493 389 1857 730 575 524 391 1858 732 577 526 365 1859 704 549 498 389 1860 730 575 524 388 1861 729 574 523 392 1862 733 578 527 392 1863 733 578 527 391 1864 732 577 526 389 1865 730 575 524 393 1866 734 579 528 391 1867 732 577 526 392 1868 733 578 527 391 1869 732 577 526 393 1870 734 579 528 390 1871 731 576 525 394 1872 735 580 529 388 1873 729 574 523 387 1874 728 573 522 388 1875 729 574 523 394 1876 735 580 529 392 1877 733 578 527 393 1878 750 595 544 394 1879 748 593 542 403 1880 749 594 543 396 1881 738 583 532 380 1882 737 582 531 376 1883 765 610 559 396 1884 738 583 532 395 1885 736 581 530 380 1886 737 582 531 397 1887 740 585 534 359 1888 698 543 492 358 1889 697 542 491 359 1890 698 543 492 397 1891 740 585 534 383 1892 739 584 533 397 1893 740 585 534 398 1894 742 587 536 386 1895 741 586 535 397 1896 740 585 534 386 1897 741 586 535 383 1898 739 584 533 387 1899 744 589 538 398 1900 742 587 536 399 1901 743 588 537 398 1902 742 587 536 387 1903 744 589 538 386 1904 741 586 535 400 1905 745 590 539 401 1906 746 591 540 398 1907 742 587 536 400 1908 745 590 539 398 1909 742 587 536 397 1910 740 585 534 401 1911 746 591 540 402 1912 747 592 541 399 1913 743 588 537 401 1914 746 591 540 399 1915 743 588 537 398 1916 742 587 536 399 1917 743 588 537 403 1918 749 594 543 394 1919 748 593 542 399 1920 743 588 537 394 1921 748 593 542 387 1922 744 589 538 390 1923 751 596 545 393 1924 750 595 544 403 1925 749 594 543 390 1926 751 596 545 403 1927 749 594 543 404 1928 752 597 546 404 1929 752 597 546 403 1930 749 594 543 402 1931 747 592 541 403 1932 749 594 543 399 1933 743 588 537 402 1934 747 592 541 404 1935 752 597 546 405 1936 754 599 548 364 1937 753 598 547 364 1938 753 598 547 390 1939 751 596 545 404 1940 752 597 546 406 1941 755 600 549 405 1942 754 599 548 402 1943 747 592 541 405 1944 754 599 548 404 1945 752 597 546 402 1946 747 592 541 361 1947 756 601 550 406 1948 755 600 549 362 1949 757 602 551 406 1950 755 600 549 361 1951 756 601 550 405 1952 754 599 548 406 1953 755 600 549 401 1954 746 591 540 407 1955 758 603 552 401 1956 746 591 540 406 1957 755 600 549 402 1958 747 592 541 362 1959 757 602 551 407 1960 758 603 552 366 1961 759 604 553 407 1962 758 603 552 362 1963 757 602 551 406 1964 755 600 549 407 1965 758 603 552 408 1966 760 605 554 366 1967 759 604 553 368 1968 761 606 555 366 1969 759 604 553 408 1970 760 605 554 370 1971 762 607 556 368 1972 761 606 555 408 1973 760 605 554 370 1974 762 607 556 408 1975 760 605 554 409 1976 763 608 557 401 1977 746 591 540 400 1978 745 590 539 407 1979 758 603 552 408 1980 760 605 554 407 1981 758 603 552 400 1982 745 590 539 409 1983 763 608 557 408 1984 760 605 554 400 1985 745 590 539 409 1986 763 608 557 400 1987 745 590 539 410 1988 764 609 558 400 1989 745 590 539 358 1990 697 542 491 410 1991 764 609 558 358 1992 697 542 491 400 1993 745 590 539 397 1994 740 585 534 410 1995 764 609 558 395 1996 736 581 530 396 1997 738 583 532 395 1998 736 581 530 410 1999 764 609 558 358 2000 697 542 491 411 2001 767 612 561 396 2002 738 583 532 374 2003 766 611 560 396 2004 738 583 532 376 2005 765 610 559 374 2006 766 611 560 411 2007 767 612 561 409 2008 763 608 557 410 2009 764 609 558 411 2010 767 612 561 410 2011 764 609 558 396 2012 738 583 532 373 2013 768 613 562 370 2014 762 607 556 409 2015 763 608 557 373 2016 768 613 562 409 2017 763 608 557 411 2018 767 612 561 380 2019 737 582 531 395 2020 736 581 530 357 2021 696 541 490 373 2022 768 613 562 411 2023 767 612 561 374 2024 766 611 560 364 2025 753 598 547 405 2026 754 599 548 361 2027 756 601 550 393 2028 750 595 544 392 2029 776 620 569 394 2030 748 593 542

+

169 684 353 209 209 170 685 354 210 210 168 686 352 208 208 170 687 354 210 210 171 688 355 211 211 168 689 352 208 208 173 690 359 213 213 172 691 356 212 212 171 692 358 211 211 172 693 356 212 212 168 694 357 208 208 171 695 358 211 211 175 696 364 216 216 170 697 361 210 210 169 698 362 209 209 170 699 361 210 210 175 700 364 216 216 174 701 360 214 214 174 702 367 214 214 171 703 365 211 211 170 704 366 210 210 171 705 365 211 211 174 706 367 214 214 173 707 368 213 213 175 708 372 216 216 172 709 369 212 212 174 710 371 214 214 174 711 371 214 214 172 712 369 212 212 173 713 370 213 213 169 714 375 209 209 168 715 376 208 208 175 716 374 216 216 175 717 374 216 216 168 718 376 208 208 172 719 377 212 212 178 720 380 219 219 179 721 381 220 220 177 722 379 218 218 177 723 379 218 218 179 724 381 220 220 176 725 378 217 217 180 726 382 221 221 176 727 383 217 217 181 728 385 222 222 181 729 385 222 222 176 730 383 217 217 179 731 384 220 220 177 732 388 218 218 182 733 386 223 223 178 734 387 219 219 182 735 386 223 223 177 736 388 218 218 183 737 390 225 225 178 738 392 219 219 182 739 393 223 223 181 740 394 222 222 178 741 392 219 219 181 742 394 222 222 179 743 391 220 220 180 744 395 221 221 182 745 397 223 223 183 746 398 225 225 182 747 397 223 223 180 748 395 221 221 181 749 396 222 222 177 750 401 218 218 176 751 402 217 217 183 752 400 225 225 183 753 400 225 225 176 754 402 217 217 180 755 403 221 221

+

187 756 407 229 229 184 757 404 226 226 186 758 406 228 228 185 759 405 227 227 186 760 406 228 228 184 761 404 226 226 184 762 409 226 226 187 763 410 229 229 189 764 411 231 231 184 765 409 226 226 189 766 411 231 231 188 767 408 230 230 190 768 413 232 232 185 769 414 227 227 184 770 415 226 226 190 771 413 232 232 184 772 415 226 226 188 773 412 230 230 191 774 416 233 233 185 775 418 227 227 190 776 419 232 232 185 777 418 227 227 191 778 416 233 233 186 779 417 228 228 186 780 421 228 228 191 781 422 233 233 189 782 423 231 231 186 783 421 228 228 189 784 423 231 231 187 785 420 229 229 191 786 426 233 233 190 787 427 232 232 188 788 424 230 230 191 789 426 233 233 188 790 424 230 230 189 791 425 231 231 195 792 431 237 237 192 793 428 234 234 194 794 430 236 236 193 795 429 235 235 194 796 430 236 236 192 797 428 234 234 192 798 433 234 234 195 799 434 237 237 197 800 435 239 239 192 801 433 234 234 197 802 435 239 239 196 803 432 238 238 198 804 437 240 240 193 805 438 235 235 192 806 439 234 234 198 807 437 240 240 192 808 439 234 234 196 809 436 238 238 199 810 440 241 241 193 811 442 235 235 198 812 443 240 240 193 813 442 235 235 199 814 440 241 241 194 815 441 236 236 194 816 445 236 236 199 817 446 241 241 197 818 447 239 239 194 819 445 236 236 197 820 447 239 239 195 821 444 237 237 196 822 448 238 238 197 823 449 239 239 198 824 451 240 240 199 825 450 241 241 198 826 451 240 240 197 827 449 239 239 203 828 455 245 245 200 829 452 242 242 202 830 454 244 244 201 831 453 243 243 202 832 454 244 244 200 833 452 242 242 200 834 457 242 242 203 835 458 245 245 205 836 459 247 247 200 837 457 242 242 205 838 459 247 247 204 839 456 246 246 206 840 461 248 248 201 841 462 243 243 200 842 463 242 242 206 843 461 248 248 200 844 463 242 242 204 845 460 246 246 207 846 464 249 249 201 847 466 243 243 206 848 467 248 248 201 849 466 243 243 207 850 464 249 249 202 851 465 244 244 202 852 469 244 244 207 853 470 249 249 205 854 471 247 247 202 855 469 244 244 205 856 471 247 247 203 857 468 245 245 204 858 472 246 246 205 859 473 247 247 206 860 475 248 248 207 861 474 249 249 206 862 475 248 248 205 863 473 247 247

+
+
+
+ + + + + + + + + 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.0000001.000000 + 30.0000000.0000003.333333 + + + + + +
diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_DeskC_01/model.config b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_DeskC_01/model.config new file mode 100755 index 0000000..8e7c565 --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_DeskC_01/model.config @@ -0,0 +1,11 @@ + + + aws_robomaker_warehouse_DeskC_01 + 1.0 + model.sdf + + + + + + diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_DeskC_01/model.sdf b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_DeskC_01/model.sdf new file mode 100755 index 0000000..0ae3cee --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_DeskC_01/model.sdf @@ -0,0 +1,46 @@ + + + + + + 1 + + 0.608 + 0 + 0 + 0.476 + 0 + 0.542 + + + + + + model://aws_robomaker_warehouse_DeskC_01/meshes/aws_robomaker_warehouse_DeskC_01_collision.DAE + 1 1 1 + + + + + + 0.3 + 0.3 + 0 0 0 + 0 + 0 + + + + + + + + model://aws_robomaker_warehouse_DeskC_01/meshes/aws_robomaker_warehouse_DeskC_01_visual.DAE + + + 1 + + +1 + + diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_GroundB_01/materials/textures/aws_robomaker_warehouse_GroundB_01.png b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_GroundB_01/materials/textures/aws_robomaker_warehouse_GroundB_01.png new file mode 100755 index 0000000..7ee66a8 Binary files /dev/null and b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_GroundB_01/materials/textures/aws_robomaker_warehouse_GroundB_01.png differ diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_GroundB_01/materials/textures/aws_robomaker_warehouse_GroundB_02.png b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_GroundB_01/materials/textures/aws_robomaker_warehouse_GroundB_02.png new file mode 100755 index 0000000..3e9d59a Binary files /dev/null and b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_GroundB_01/materials/textures/aws_robomaker_warehouse_GroundB_02.png differ diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_GroundB_01/meshes/aws_robomaker_warehouse_GroundB_01_collision.DAE b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_GroundB_01/meshes/aws_robomaker_warehouse_GroundB_01_collision.DAE new file mode 100755 index 0000000..3d2c3d5 --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_GroundB_01/meshes/aws_robomaker_warehouse_GroundB_01_collision.DAE @@ -0,0 +1,123 @@ + + + FBX COLLADA exporter2019-05-15T08:16:04Z2019-05-15T08:16:04ZZ_UP + + + + + +-699.023499 -1045.333252 -0.000123 +699.023499 -1045.333252 -0.000124 +-699.023499 -1045.333252 12.431540 +699.023499 -1045.333252 12.431539 +-699.023499 1045.333252 0.000128 +699.023499 1045.333252 0.000129 +-699.023499 1045.333130 12.431791 +699.023499 1045.333130 12.431792 + + + + + + + + + + + +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.000000 1.000000 0.000010 +-0.000000 1.000000 0.000010 +-0.000000 1.000000 0.000010 +-0.000000 1.000000 0.000010 +-0.000000 1.000000 0.000010 +-0.000000 1.000000 0.000010 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 + + + + + + + + + + + +1.000000 0.000000 +0.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 + + + + + + + + + + + +

3 0 3 2 1 2 0 2 0 3 3 3 0 4 0 1 5 1 6 6 6 5 7 5 4 8 4 5 9 5 6 10 6 7 11 7 1 12 9 0 13 8 5 14 11 0 15 8 4 16 10 5 17 11 7 18 15 3 19 13 1 20 12 7 21 15 1 22 12 5 23 14 6 24 19 3 25 16 7 26 18 3 27 16 6 28 19 2 29 17 6 30 22 0 31 21 2 32 20 0 33 21 6 34 22 4 35 23

+
+
+
+ + + 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.0000001.000000 + 30.0000000.0000003.333333 + + + + + +
diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_GroundB_01/meshes/aws_robomaker_warehouse_GroundB_01_visual.DAE b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_GroundB_01/meshes/aws_robomaker_warehouse_GroundB_01_visual.DAE new file mode 100755 index 0000000..9037e95 --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_GroundB_01/meshes/aws_robomaker_warehouse_GroundB_01_visual.DAE @@ -0,0 +1,706 @@ + + + FBX COLLADA exporter2019-05-15T08:15:48Z2019-05-15T08:15:48ZZ_UP + + + ../materials/textures/aws_robomaker_warehouse_GroundB_01.png + + + ../materials/textures/aws_robomaker_warehouse_GroundB_02.png + + + + + + + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + +-699.023499 -1045.333252 -0.000123 +699.023499 -1045.333252 -0.000124 +-699.023499 -1045.333252 12.431540 +699.023499 -1045.333252 12.431539 +-699.023499 1045.333252 0.000128 +699.023499 1045.333252 0.000129 +-699.023499 1045.333130 12.431791 +699.023499 1045.333130 12.431792 +-255.414734 -237.748291 12.445392 +44.585266 -237.748291 12.445392 +-255.414734 62.251705 12.445440 +44.585266 62.251705 12.445440 +-248.186340 -230.519897 12.445393 +37.356873 -230.519897 12.445393 +37.356873 55.023312 12.445439 +-248.186340 55.023312 12.445439 +-255.414734 -882.155273 12.445316 +44.585266 -882.155273 12.445316 +-255.414734 -582.155273 12.445366 +44.585266 -582.155273 12.445366 +-248.186340 -874.926880 12.445318 +37.356873 -874.926880 12.445318 +37.356873 -589.383667 12.445364 +-248.186340 -589.383667 12.445364 +-255.414734 -559.951782 12.445369 +44.585266 -559.951782 12.445369 +-255.414734 -259.951782 12.445388 +44.585266 -259.951782 12.445388 +-248.186340 -552.723389 12.445371 +37.356873 -552.723389 12.445371 +37.356873 -267.180176 12.445387 +-248.186340 -267.180176 12.445387 +-255.414734 84.455200 12.445444 +44.585266 84.455200 12.445444 +-255.414734 384.455200 12.445462 +44.585266 384.455200 12.445462 +-248.186340 91.683594 12.445445 +37.356873 91.683594 12.445445 +37.356873 377.226807 12.445461 +-248.186340 377.226807 12.445461 +-255.414734 406.658691 12.445527 +44.585266 406.658691 12.445527 +-255.414734 706.658691 12.445576 +44.585266 706.658691 12.445576 +-248.186340 413.887085 12.445528 +37.356873 413.887085 12.445528 +37.356873 699.430298 12.445575 +-248.186340 699.430298 12.445575 +132.339752 -1043.718018 12.445252 +141.445953 -1043.718018 12.445252 +132.339752 1046.807373 12.445501 +141.445953 1046.807373 12.445501 +141.445953 -908.130371 12.445269 +132.339752 -908.130371 12.445269 +141.445953 -983.652710 12.445258 +132.339752 -983.652710 12.445258 +141.445953 -992.508667 12.445259 +132.339752 -992.508667 12.445259 +-423.674530 -983.652710 12.445258 +-423.674530 -992.508667 12.445259 +141.445953 -899.566162 12.445268 +132.339752 -899.566162 12.445268 +-337.738800 -908.130371 12.445269 +-337.738800 -899.566162 12.445268 +-329.554382 -908.130371 12.445269 +-329.554382 -899.566162 12.445268 +-337.738800 1046.807373 12.445501 +-329.554382 1046.807373 12.445501 +-415.294403 -983.652710 12.445258 +-415.294403 -992.508667 12.445259 +-423.674530 1046.807373 12.445501 +-415.294403 1046.807373 12.445501 +-423.674530 883.609009 12.445482 +-415.294403 883.609009 12.445482 +-415.294403 959.849304 12.445491 +-423.674530 959.849304 12.445491 +-423.674591 875.711548 12.445481 +-415.294403 875.711609 12.445481 +-686.119019 883.609009 12.445482 +-686.119019 875.711548 12.445481 +-415.294403 968.018066 12.445493 +-423.674530 968.018066 12.445493 +-689.973267 959.849304 12.445491 +-689.973267 968.018066 12.445493 +215.702194 -1044.132324 12.445252 +224.808395 -1044.132324 12.445252 +215.702194 177.500122 12.445397 +224.808395 177.500122 12.445397 +224.808395 168.217163 12.445396 +215.702194 168.217163 12.445396 +700.987549 177.500122 12.445397 +700.987549 168.217163 12.445396 +215.702194 258.095581 12.445407 +224.808395 258.095581 12.445407 +224.808395 1046.807373 12.445501 +215.702194 1046.807373 12.445501 +224.808395 266.876099 12.445409 +215.702194 266.876099 12.445409 +700.987549 258.095581 12.445407 +700.987549 266.876099 12.445409 + + + + + + + + + + + +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.000000 1.000000 0.000010 +-0.000000 1.000000 0.000010 +-0.000000 1.000000 0.000010 +-0.000000 1.000000 0.000010 +-0.000000 1.000000 0.000010 +-0.000000 1.000000 0.000010 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 + + + + + + + + + + + +4.846894 2.550678 +4.846894 4.846265 +4.826477 4.846265 +4.826477 2.550678 +4.783730 2.550678 +4.804147 2.550678 +4.804147 4.846265 +4.783730 4.846265 +1.222342 2.572054 +4.655206 2.572054 +4.655206 4.867640 +1.222342 4.867640 +1.222341 4.953428 +4.655206 4.953428 +4.655205 4.973845 +1.222341 4.973845 +1.179594 0.114090 +4.612459 0.114091 +4.612458 2.409678 +1.179594 2.409678 +1.414463 2.740246 +1.414463 -0.692619 +1.434875 -0.692619 +1.434875 2.740246 +-1.691137 1.355757 +-1.976730 0.985989 +-1.933884 0.943143 +-1.733945 1.312949 +-1.976730 -0.792248 +-1.933884 -0.749402 +-1.691137 -0.420905 +-1.733945 -0.378097 +-1.799502 -0.426135 +-1.798186 -0.952645 +-1.755340 -0.995491 +-1.842348 -0.468980 +-1.798186 -2.730882 +-1.755340 -2.688036 +-1.799502 -2.204372 +-1.842348 -2.161526 +-1.799502 1.365183 +-1.798186 0.838673 +-1.755340 0.795827 +-1.842348 1.322337 +-1.798186 -0.939565 +-1.755340 -0.896719 +-1.799502 -0.413054 +-1.842348 -0.370208 +-1.730909 -0.433973 +-1.875866 -0.575192 +-1.833020 -0.618038 +-1.773717 -0.476781 +-1.875866 -2.353429 +-1.833020 -2.310584 +-1.730909 -2.210634 +-1.773717 -2.167826 +-1.958919 2.451030 +-1.717841 -0.433973 +-1.675033 -0.476781 +-2.001765 2.408185 +-1.717841 -2.210634 +-1.675033 -2.167826 +-1.958919 0.672793 +-2.001765 0.715639 +0.521328 0.470354 +0.521328 0.474995 +0.410392 1.020932 +0.410392 1.016567 +0.415033 1.016567 +-1.461452 0.891229 +0.495226 0.474995 +-1.461452 0.864380 +0.495226 0.470354 +-1.461452 0.858776 +-1.461452 0.864380 +-1.461452 0.858776 +0.415033 1.020932 +-1.461452 0.896788 +-1.461452 0.896788 +-1.461452 0.891229 +-1.461452 0.891229 +-1.461452 0.896788 +-1.461452 0.896788 +-1.461452 0.896788 +-1.461452 0.864380 +-1.461452 0.858776 +-1.461452 0.864380 +-1.461452 0.864380 +-1.461452 0.864380 +-1.461452 0.864380 +-1.461452 0.864380 +-1.461452 0.864380 +-1.461452 0.864380 +-1.461452 0.864380 +-1.461452 0.864380 +-1.461452 0.864380 +-1.461452 0.864380 +-1.461452 0.864380 +-1.461452 0.864380 +-1.461452 0.864380 +0.436771 0.036056 +0.441413 0.036056 +0.422756 0.026574 +0.422756 0.021932 +0.418024 0.026574 +0.418024 0.021932 +0.422756 0.269288 +0.418024 0.269288 +-1.767357 1.965086 +-1.767357 0.186848 +0.425656 0.029564 +0.430298 0.029564 +0.430298 0.034040 +0.425656 0.034040 +0.430297 0.431580 +0.425656 0.431580 +0.444403 0.403750 +0.448879 0.403750 +-1.724511 0.229694 +-1.724511 1.922239 +-1.855502 0.428975 +-1.898310 0.471783 +-1.855502 2.205637 +-1.898310 2.162829 +-1.842433 0.376135 +-1.842433 -1.400526 +-1.799625 -1.357718 +-1.799626 0.333327 +-1.743367 -2.377502 +-1.786175 -2.334694 +-1.743367 -0.600840 +-1.786175 -0.643649 +-1.795829 2.663701 +-1.795829 0.885463 +-1.752983 0.928309 +-1.752983 2.620854 +-1.855502 -1.400526 +-1.898310 -1.357718 +-1.855502 0.376135 +-1.898310 0.333327 +-1.842434 2.165865 +-1.842433 0.389204 +-1.799626 0.432011 +-1.799626 2.123057 +-1.743367 -0.587772 +-1.786175 -0.544964 +-1.743367 1.188889 +-1.786175 1.146081 +-1.842434 3.955595 +-1.842434 2.178934 +-1.799626 2.221741 +-1.799626 3.912786 +-1.743367 1.201958 +-1.786175 1.244766 +-1.743367 2.978619 +-1.786175 2.935811 +0.410392 0.024476 +0.415033 0.024476 +0.490712 0.474995 +0.490712 0.470354 +0.441413 0.654006 +0.436771 0.654006 +0.444403 0.646464 +0.448879 0.646464 + + + + + + + + + + + +

3 0 2 2 1 3 0 2 0 3 3 2 0 4 0 1 5 1 6 6 5 5 7 7 4 8 4 5 9 7 6 10 5 7 11 6 1 12 11 0 13 8 5 14 10 0 15 8 4 16 9 5 17 10 7 18 14 3 19 15 1 20 12 7 21 14 1 22 12 5 23 13 6 24 18 3 25 16 7 26 17 3 27 16 6 28 18 2 29 19 6 30 21 0 31 23 2 32 20 0 33 23 6 34 21 4 35 22

+

8 36 108 9 37 109 13 38 118 8 39 108 13 40 118 12 41 119 9 42 25 11 43 28 14 44 29 9 45 25 14 46 29 13 47 26 11 48 120 10 49 122 15 50 123 11 51 120 15 52 123 14 53 121 10 54 30 8 55 24 12 56 27 10 57 30 12 58 27 15 59 31 16 60 124 17 61 125 21 62 126 16 63 124 21 64 126 20 65 127 17 66 33 19 67 36 22 68 37 17 69 33 22 70 37 21 71 34 19 72 128 18 73 130 23 74 131 19 75 128 23 76 131 22 77 129 18 78 38 16 79 32 20 80 35 18 81 38 20 82 35 23 83 39 24 84 132 25 85 133 29 86 134 24 87 132 29 88 134 28 89 135 25 90 41 27 91 44 30 92 45 25 93 41 30 94 45 29 95 42 27 96 136 26 97 138 31 98 139 27 99 136 31 100 139 30 101 137 26 102 46 24 103 40 28 104 43 26 105 46 28 106 43 31 107 47 32 108 140 33 109 141 37 110 142 32 111 140 37 112 142 36 113 143 33 114 49 35 115 52 38 116 53 33 117 49 38 118 53 37 119 50 35 120 144 34 121 146 39 122 147 35 123 144 39 124 147 38 125 145 34 126 54 32 127 48 36 128 51 34 129 54 36 130 51 39 131 55 40 132 148 41 133 149 45 134 150 40 135 148 45 136 150 44 137 151 41 138 57 43 139 60 46 140 61 41 141 57 46 142 61 45 143 58 43 144 152 42 145 154 47 146 155 43 147 152 47 148 155 46 149 153 42 150 62 40 151 56 44 152 59 42 153 62 44 154 59 47 155 63 57 156 72 49 157 65 56 158 70 49 159 65 57 160 72 48 161 64 61 162 68 53 163 76 60 164 67 60 165 67 53 166 76 52 167 66 55 168 159 57 169 72 54 170 158 54 171 158 57 172 72 56 173 70 69 174 85 55 175 71 68 176 84 55 177 71 69 178 85 57 179 73 50 180 157 61 181 68 51 182 156 51 183 156 61 184 68 60 185 67 61 186 77 65 187 81 64 188 80 61 189 77 64 190 80 53 191 69 65 192 81 63 193 78 64 194 80 63 195 78 62 196 79 64 197 80 66 198 83 63 199 78 67 200 82 67 201 82 63 202 78 65 203 81 68 204 84 58 205 74 69 206 85 58 207 74 59 208 75 69 209 85 76 210 92 68 211 84 77 212 93 68 213 84 76 214 92 58 215 74 81 216 97 75 217 91 80 218 96 80 219 96 75 220 91 74 221 90 72 222 88 77 223 93 73 224 89 77 225 93 72 226 88 76 227 92 78 228 94 76 229 92 72 230 88 76 231 92 78 232 94 79 233 95 81 234 97 71 235 86 70 236 87 71 237 86 81 238 97 80 239 96 83 240 98 75 241 91 81 242 97 75 243 91 83 244 98 82 245 99 89 246 161 84 247 100 88 248 160 88 249 160 84 250 100 85 251 101 86 252 105 89 253 103 87 254 104 87 255 104 89 256 103 88 257 102 88 258 102 91 259 106 87 260 104 90 261 107 87 262 104 91 263 106 97 264 113 93 265 111 96 266 112 93 267 111 97 268 113 92 269 110 95 270 115 97 271 113 94 272 114 94 273 114 97 274 113 96 275 112 93 276 162 98 277 116 96 278 163 99 279 117 96 280 163 98 281 116

+
+
+
+ + + 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.0000001.000000 + 30.0000000.0000003.333333 + + + + + +
diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_GroundB_01/model.config b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_GroundB_01/model.config new file mode 100755 index 0000000..ab216e8 --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_GroundB_01/model.config @@ -0,0 +1,11 @@ + + + aws_robomaker_warehouse_GroundB_01 + 1.0 + model.sdf + + + + + + diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_GroundB_01/model.sdf b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_GroundB_01/model.sdf new file mode 100755 index 0000000..5e482bb --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_GroundB_01/model.sdf @@ -0,0 +1,46 @@ + + + + + + 1000 + + 1200083.33 + 0 + 0 + 8333416.66 + 0 + 2033333.33 + + + + + + model://aws_robomaker_warehouse_GroundB_01/meshes/aws_robomaker_warehouse_GroundB_01_collision.DAE + 1 1 1 + + + + + + 0.3 + 0.3 + 0 0 0 + 0 + 0 + + + + + + + + model://aws_robomaker_warehouse_GroundB_01/meshes/aws_robomaker_warehouse_GroundB_01_visual.DAE + + + 1 + + +1 + + diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_Lamp_01/materials/textures/aws_robomaker_warehouse_Lamp_01.png b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_Lamp_01/materials/textures/aws_robomaker_warehouse_Lamp_01.png new file mode 100755 index 0000000..9e4dd9c Binary files /dev/null and b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_Lamp_01/materials/textures/aws_robomaker_warehouse_Lamp_01.png differ diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_Lamp_01/meshes/aws_robomaker_warehouse_Lamp_01_collision.DAE b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_Lamp_01/meshes/aws_robomaker_warehouse_Lamp_01_collision.DAE new file mode 100755 index 0000000..672719c --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_Lamp_01/meshes/aws_robomaker_warehouse_Lamp_01_collision.DAE @@ -0,0 +1,123 @@ + + + FBX COLLADA exporter2019-04-04T08:27:36Z2019-04-04T08:27:36ZZ_UP + + + + + +-51.220013 -75.723572 -50.385498 +51.220005 -75.723572 -50.385498 +-51.220013 75.723572 -50.385498 +51.220005 75.723572 -50.385498 +-51.220005 -75.723572 50.385498 +51.220013 -75.723572 50.385498 +-51.220005 75.723572 50.385498 +51.220013 75.723572 50.385498 + + + + + + + + + + + +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 + + + + + + + + + + + +1.000000 0.000000 +0.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 + + + + + + + + + + + +

1 0 1 0 1 0 3 2 3 0 3 0 2 4 2 3 5 3 7 6 7 6 7 6 4 8 4 7 9 7 4 10 4 5 11 5 4 12 10 1 13 9 5 14 11 1 15 9 4 16 10 0 17 8 7 18 15 5 19 14 1 20 12 7 21 15 1 22 12 3 23 13 6 24 19 7 25 18 3 26 16 6 27 19 3 28 16 2 29 17 4 30 23 6 31 22 2 32 20 4 33 23 2 34 20 0 35 21

+
+
+
+ + + -0.999000 -0.000000 -0.000000 0.087481 -0.000000 0.000000 0.998995 0.000494 0.000000 1.002288 -0.000000 1325.909302 0.000000 0.000000 0.000000 1.0000001.000000 + 30.0000000.0000003.333333 + + + + + +
diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_Lamp_01/meshes/aws_robomaker_warehouse_Lamp_01_visual.DAE b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_Lamp_01/meshes/aws_robomaker_warehouse_Lamp_01_visual.DAE new file mode 100755 index 0000000..cad638a --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_Lamp_01/meshes/aws_robomaker_warehouse_Lamp_01_visual.DAE @@ -0,0 +1,1056 @@ + + + FBX COLLADA exporter2019-05-27T02:45:50Z2019-05-27T02:45:50ZZ_UP + + + ../materials/textures/aws_robomaker_warehouse_Lamp_01.png + + + + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + +51.162598 0.000000 -75.723511 +48.077148 17.498535 -75.723511 +39.192871 32.886719 -75.723511 +25.581543 44.308594 -75.723511 +8.884521 50.385742 -75.723511 +-8.884277 50.385742 -75.723511 +-25.581055 44.308594 -75.723511 +-39.192383 32.886719 -75.723511 +-48.076904 17.498535 -75.723511 +-51.162354 0.000000 -75.723511 +-48.076904 -17.498047 -75.723511 +-39.192871 -32.886230 -75.723511 +-25.581055 -44.308105 -75.723511 +-8.884277 -50.385254 -75.723511 +8.884521 -50.385254 -75.723511 +25.581543 -44.308105 -75.723511 +39.192871 -32.886719 -75.723511 +48.077148 -17.498047 -75.723511 +26.794434 0.000000 0.394409 +25.178711 9.164063 0.394409 +20.525879 17.223145 0.394409 +13.397461 23.204590 0.394409 +4.652832 26.387695 0.394409 +-4.652832 26.387695 0.394409 +-13.396973 23.204590 0.394409 +-20.525391 17.223145 0.394409 +-25.178223 9.164063 0.394409 +-26.794434 0.000000 0.394409 +-25.178223 -9.164063 0.394409 +-20.525391 -17.222656 0.394409 +-13.396973 -23.204102 0.394409 +-4.652832 -26.387207 0.394409 +4.652832 -26.387207 0.394409 +13.397461 -23.204102 0.394409 +20.525879 -17.222656 0.394409 +25.178711 -9.164063 0.394409 +9.227295 0.000000 0.394409 +8.670898 3.155762 0.394409 +7.068359 5.931641 0.394409 +4.613770 7.991211 0.394409 +1.602539 9.086914 0.394409 +-1.602051 9.086914 0.394409 +-4.613281 7.991211 0.394409 +-7.068359 5.931641 0.394409 +-8.670410 3.155762 0.394409 +-9.227051 0.000000 0.394409 +-8.670410 -3.155273 0.394409 +-7.068359 -5.931152 0.394409 +-4.613281 -7.991211 0.394409 +-1.602051 -9.086914 0.394409 +1.602539 -9.086914 0.394409 +4.613770 -7.991211 0.394409 +7.068359 -5.931152 0.394409 +8.670898 -3.155273 0.394409 +9.227295 0.000000 75.723511 +8.670898 3.155762 75.723511 +7.068359 5.931641 75.723511 +4.613770 7.991211 75.723511 +1.602539 9.086914 75.723511 +-1.602051 9.086914 75.723511 +-4.613281 7.991211 75.723511 +-7.068359 5.931641 75.723511 +-8.670410 3.155762 75.723511 +-9.227051 0.000000 75.723511 +-8.670410 -3.155273 75.723511 +-7.068359 -5.931152 75.723511 +-4.613281 -7.991211 75.723511 +-1.602051 -9.086914 75.723511 +1.602539 -9.086914 75.723511 +4.613770 -7.991211 75.723511 +7.068359 -5.931152 75.723511 +8.670898 -3.155273 75.723511 +36.223633 13.184570 -75.723511 +38.548340 0.000000 -75.723511 +36.223633 -13.184082 -75.723511 +29.529785 -24.778320 -75.723511 +19.274170 -33.383789 -75.723511 +6.693848 -37.962891 -75.723511 +-6.693848 -37.961914 -75.723511 +-19.273926 -33.383789 -75.723511 +-29.529297 -24.778320 -75.723511 +-36.223145 -13.184082 -75.723511 +-38.547852 0.000000 -75.723511 +-36.223145 13.184570 -75.723511 +-29.529297 24.778320 -75.723511 +-19.273926 33.383789 -75.723511 +-6.693848 37.962891 -75.723511 +6.693848 37.962891 -75.723511 +19.274414 33.383789 -75.723511 +29.529785 24.778320 -75.723511 +36.223633 13.184570 -61.747925 +38.548340 0.000000 -61.747925 +36.223633 -13.184082 -61.747925 +29.529785 -24.778320 -61.747925 +19.274170 -33.383789 -61.747925 +6.693848 -37.962891 -61.747925 +-6.693848 -37.961914 -61.747925 +-19.273926 -33.383789 -61.747925 +-29.529297 -24.778320 -61.747925 +-36.223145 -13.184082 -61.747925 +-38.547852 0.000000 -61.747925 +-36.223145 13.184570 -61.747925 +-29.529297 24.778320 -61.747925 +-19.273926 33.383789 -61.747925 +-6.693848 37.962891 -61.747925 +6.693848 37.962891 -61.747925 +19.274414 33.383789 -61.747925 +29.529785 24.778320 -61.747925 +36.223145 13.184570 -73.245483 +38.547852 0.000488 -73.245483 +36.223145 -13.183594 -73.245483 +29.529297 -24.778320 -73.245483 +19.273926 -33.383301 -73.245483 +6.693359 -37.962402 -73.245483 +-6.694092 -37.961914 -73.245483 +-19.274414 -33.383301 -73.245483 +-29.529785 -24.778320 -73.245483 +-36.223633 -13.183594 -73.245483 +-38.548340 0.000488 -73.245483 +-36.223633 13.184570 -73.245483 +-29.529785 24.778809 -73.245483 +-19.274414 33.383789 -73.245483 +-6.694092 37.962891 -73.245483 +6.693359 37.962891 -73.245483 +19.273926 33.383789 -73.245483 +29.529297 24.778809 -73.245483 + + + + + + + + + + + +0.952386 -0.000003 0.304893 +0.894952 0.325733 0.304893 +0.894954 0.325725 0.304894 +0.894954 0.325725 0.304894 +0.952387 -0.000001 0.304892 +0.952386 -0.000003 0.304893 +0.894952 0.325733 0.304893 +0.729579 0.612172 0.304895 +0.729572 0.612180 0.304894 +0.729572 0.612180 0.304894 +0.894954 0.325725 0.304894 +0.894952 0.325733 0.304893 +0.729579 0.612172 0.304895 +0.476202 0.824784 0.304898 +0.476208 0.824781 0.304897 +0.476208 0.824781 0.304897 +0.729572 0.612180 0.304894 +0.729579 0.612172 0.304895 +0.476202 0.824784 0.304898 +0.165379 0.937917 0.304896 +0.165393 0.937914 0.304899 +0.165393 0.937914 0.304899 +0.476208 0.824781 0.304897 +0.476202 0.824784 0.304898 +0.165379 0.937917 0.304896 +-0.165382 0.937916 0.304897 +-0.165405 0.937913 0.304895 +-0.165405 0.937913 0.304895 +0.165393 0.937914 0.304899 +0.165379 0.937917 0.304896 +-0.165382 0.937916 0.304897 +-0.476202 0.824784 0.304898 +-0.476212 0.824780 0.304895 +-0.476212 0.824780 0.304895 +-0.165405 0.937913 0.304895 +-0.165382 0.937916 0.304897 +-0.476202 0.824784 0.304898 +-0.729576 0.612175 0.304894 +-0.729573 0.612178 0.304896 +-0.729573 0.612178 0.304896 +-0.476212 0.824780 0.304895 +-0.476202 0.824784 0.304898 +-0.729576 0.612175 0.304894 +-0.894949 0.325739 0.304894 +-0.894945 0.325749 0.304894 +-0.894945 0.325749 0.304894 +-0.729573 0.612178 0.304896 +-0.729576 0.612175 0.304894 +-0.894949 0.325739 0.304894 +-0.952387 -0.000003 0.304893 +-0.952386 -0.000003 0.304895 +-0.952386 -0.000003 0.304895 +-0.894945 0.325749 0.304894 +-0.894949 0.325739 0.304894 +-0.952387 -0.000003 0.304893 +-0.894952 -0.325730 0.304895 +-0.894943 -0.325759 0.304891 +-0.894943 -0.325759 0.304891 +-0.952386 -0.000003 0.304895 +-0.952387 -0.000003 0.304893 +-0.894952 -0.325730 0.304895 +-0.729577 -0.612172 0.304898 +-0.729565 -0.612188 0.304894 +-0.729565 -0.612188 0.304894 +-0.894943 -0.325759 0.304891 +-0.894952 -0.325730 0.304895 +-0.729577 -0.612172 0.304898 +-0.476198 -0.824787 0.304897 +-0.476214 -0.824777 0.304899 +-0.476214 -0.824777 0.304899 +-0.729565 -0.612188 0.304894 +-0.729577 -0.612172 0.304898 +-0.476198 -0.824787 0.304897 +-0.165381 -0.937917 0.304895 +-0.165401 -0.937912 0.304899 +-0.165401 -0.937912 0.304899 +-0.476214 -0.824777 0.304899 +-0.476198 -0.824787 0.304897 +-0.165381 -0.937917 0.304895 +0.165380 -0.937916 0.304897 +0.165396 -0.937914 0.304895 +0.165396 -0.937914 0.304895 +-0.165401 -0.937912 0.304899 +-0.165381 -0.937917 0.304895 +0.165380 -0.937916 0.304897 +0.476192 -0.824789 0.304899 +0.476205 -0.824783 0.304896 +0.476205 -0.824783 0.304896 +0.165396 -0.937914 0.304895 +0.165380 -0.937916 0.304897 +0.476192 -0.824789 0.304899 +0.729576 -0.612175 0.304895 +0.729564 -0.612188 0.304897 +0.729564 -0.612188 0.304897 +0.476205 -0.824783 0.304896 +0.476192 -0.824789 0.304899 +0.729576 -0.612175 0.304895 +0.894954 -0.325728 0.304892 +0.894951 -0.325735 0.304894 +0.894951 -0.325735 0.304894 +0.729564 -0.612188 0.304897 +0.729576 -0.612175 0.304895 +0.894954 -0.325728 0.304892 +0.952386 -0.000003 0.304893 +0.952387 -0.000001 0.304892 +0.952387 -0.000001 0.304892 +0.894951 -0.325735 0.304894 +0.894954 -0.325728 0.304892 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 -0.000013 0.000000 +0.939701 0.341998 0.000000 +0.939701 0.341998 0.000000 +0.939701 0.341998 0.000000 +1.000000 -0.000013 0.000000 +1.000000 -0.000013 0.000000 +0.939701 0.341998 0.000000 +0.766049 0.642783 0.000000 +0.766049 0.642783 0.000000 +0.766049 0.642783 0.000000 +0.939701 0.341998 0.000000 +0.939701 0.341998 0.000000 +0.766049 0.642783 0.000000 +0.499955 0.866052 0.000000 +0.499955 0.866052 0.000000 +0.499955 0.866052 0.000000 +0.766049 0.642783 0.000000 +0.766049 0.642783 0.000000 +0.499955 0.866052 0.000000 +0.173606 0.984815 0.000000 +0.173606 0.984815 0.000000 +0.173606 0.984815 0.000000 +0.499955 0.866052 0.000000 +0.499955 0.866052 0.000000 +0.173606 0.984815 0.000000 +-0.173606 0.984815 0.000000 +-0.173606 0.984815 0.000000 +-0.173606 0.984815 0.000000 +0.173606 0.984815 0.000000 +0.173606 0.984815 0.000000 +-0.173606 0.984815 0.000000 +-0.499912 0.866076 0.000000 +-0.499912 0.866076 0.000000 +-0.499912 0.866076 0.000000 +-0.173606 0.984815 0.000000 +-0.173606 0.984815 0.000000 +-0.499912 0.866076 0.000000 +-0.766060 0.642769 0.000000 +-0.766060 0.642770 0.000000 +-0.766060 0.642770 0.000000 +-0.499912 0.866076 0.000000 +-0.499912 0.866076 0.000000 +-0.766060 0.642769 0.000000 +-0.939710 0.341972 0.000000 +-0.939710 0.341972 0.000000 +-0.939710 0.341972 0.000000 +-0.766060 0.642770 0.000000 +-0.766060 0.642769 0.000000 +-0.939710 0.341972 0.000000 +-1.000000 -0.000013 0.000000 +-1.000000 -0.000013 0.000000 +-1.000000 -0.000013 0.000000 +-0.939710 0.341972 0.000000 +-0.939710 0.341972 0.000000 +-1.000000 -0.000013 0.000000 +-0.939706 -0.341984 0.000000 +-0.939706 -0.341984 0.000000 +-0.939706 -0.341984 0.000000 +-1.000000 -0.000013 0.000000 +-1.000000 -0.000013 0.000000 +-0.939706 -0.341984 0.000000 +-0.766097 -0.642725 0.000000 +-0.766097 -0.642725 0.000000 +-0.766097 -0.642725 0.000000 +-0.939706 -0.341984 0.000000 +-0.939706 -0.341984 0.000000 +-0.766097 -0.642725 0.000000 +-0.499963 -0.866047 0.000000 +-0.499963 -0.866047 0.000000 +-0.499963 -0.866047 0.000000 +-0.766097 -0.642725 0.000000 +-0.766097 -0.642725 0.000000 +-0.499963 -0.866047 0.000000 +-0.173606 -0.984815 0.000000 +-0.173606 -0.984815 0.000000 +-0.173606 -0.984815 0.000000 +-0.499963 -0.866047 0.000000 +-0.499963 -0.866047 0.000000 +-0.173606 -0.984815 0.000000 +0.173606 -0.984815 0.000000 +0.173606 -0.984815 0.000000 +0.173606 -0.984815 0.000000 +-0.173606 -0.984815 0.000000 +-0.173606 -0.984815 0.000000 +0.173606 -0.984815 0.000000 +0.500005 -0.866022 0.000000 +0.500005 -0.866022 0.000000 +0.500005 -0.866022 0.000000 +0.173606 -0.984815 0.000000 +0.173606 -0.984815 0.000000 +0.500005 -0.866022 0.000000 +0.766086 -0.642738 0.000000 +0.766086 -0.642738 0.000000 +0.766086 -0.642738 0.000000 +0.500005 -0.866022 0.000000 +0.500005 -0.866022 0.000000 +0.766086 -0.642738 0.000000 +0.939696 -0.342011 0.000000 +0.939696 -0.342011 0.000000 +0.939696 -0.342011 0.000000 +0.766086 -0.642738 0.000000 +0.766086 -0.642738 0.000000 +0.939696 -0.342011 0.000000 +1.000000 -0.000013 0.000000 +1.000000 -0.000013 0.000000 +1.000000 -0.000013 0.000000 +0.939696 -0.342011 0.000000 +0.939696 -0.342011 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.939692 -0.342023 0.000000 +-1.000000 0.000003 0.000000 +-1.000000 0.000003 0.000000 +-1.000000 0.000003 0.000000 +-0.939692 -0.342023 0.000000 +-0.939692 -0.342023 0.000000 +-1.000000 0.000003 0.000000 +-0.939694 0.342017 0.000000 +-0.939694 0.342017 0.000000 +-0.939694 0.342017 0.000000 +-1.000000 0.000003 0.000000 +-1.000000 0.000003 0.000000 +-0.939694 0.342017 0.000000 +-0.766046 0.642786 0.000000 +-0.766046 0.642786 0.000000 +-0.766046 0.642786 0.000000 +-0.939694 0.342017 0.000000 +-0.939694 0.342017 0.000000 +-0.766046 0.642786 0.000000 +-0.500007 0.866021 0.000000 +-0.500007 0.866021 0.000000 +-0.500007 0.866021 0.000000 +-0.766046 0.642786 0.000000 +-0.766046 0.642786 0.000000 +-0.500007 0.866021 0.000000 +-0.173621 0.984813 0.000000 +-0.173621 0.984813 0.000000 +-0.173621 0.984813 0.000000 +-0.500007 0.866021 0.000000 +-0.500007 0.866021 0.000000 +-0.173621 0.984813 0.000000 +0.173662 0.984805 0.000000 +0.173662 0.984805 0.000000 +0.173662 0.984805 0.000000 +-0.173621 0.984813 0.000000 +-0.173621 0.984813 0.000000 +0.173662 0.984805 0.000000 +0.499985 0.866034 0.000000 +0.499985 0.866034 0.000000 +0.499985 0.866034 0.000000 +0.173662 0.984805 0.000000 +0.173662 0.984805 0.000000 +0.499985 0.866034 0.000000 +0.766050 0.642781 0.000000 +0.766050 0.642781 0.000000 +0.766050 0.642781 0.000000 +0.499985 0.866034 0.000000 +0.499985 0.866034 0.000000 +0.766050 0.642781 0.000000 +0.939694 0.342017 0.000000 +0.939694 0.342017 0.000000 +0.939694 0.342017 0.000000 +0.766050 0.642781 0.000000 +0.766050 0.642781 0.000000 +0.939694 0.342017 0.000000 +1.000000 0.000003 0.000000 +1.000000 0.000003 0.000000 +1.000000 0.000003 0.000000 +0.939694 0.342017 0.000000 +0.939694 0.342017 0.000000 +1.000000 0.000003 0.000000 +0.939692 -0.342023 0.000000 +0.939692 -0.342023 0.000000 +0.939692 -0.342023 0.000000 +1.000000 0.000003 0.000000 +1.000000 0.000003 0.000000 +0.939692 -0.342023 0.000000 +0.766044 -0.642788 0.000000 +0.766044 -0.642788 0.000000 +0.766044 -0.642788 0.000000 +0.939692 -0.342023 0.000000 +0.939692 -0.342023 0.000000 +0.766044 -0.642788 0.000000 +0.500015 -0.866017 0.000000 +0.500015 -0.866017 0.000000 +0.500015 -0.866017 0.000000 +0.766044 -0.642788 0.000000 +0.766044 -0.642788 0.000000 +0.500015 -0.866017 0.000000 +0.173659 -0.984806 0.000000 +0.173659 -0.984806 0.000000 +0.173659 -0.984806 0.000000 +0.500015 -0.866017 0.000000 +0.500015 -0.866017 0.000000 +0.173659 -0.984806 0.000000 +-0.173653 -0.984807 0.000000 +-0.173653 -0.984807 0.000000 +-0.173653 -0.984807 0.000000 +0.173659 -0.984806 0.000000 +0.173659 -0.984806 0.000000 +-0.173653 -0.984807 0.000000 +-0.500009 -0.866020 0.000000 +-0.500009 -0.866020 0.000000 +-0.500009 -0.866020 0.000000 +-0.173653 -0.984807 0.000000 +-0.173653 -0.984807 0.000000 +-0.500009 -0.866020 0.000000 +-0.766044 -0.642788 0.000000 +-0.766044 -0.642788 0.000000 +-0.766044 -0.642788 0.000000 +-0.500009 -0.866020 0.000000 +-0.500009 -0.866020 0.000000 +-0.766044 -0.642788 0.000000 +-0.939692 -0.342023 0.000000 +-0.939692 -0.342023 0.000000 +-0.939692 -0.342023 0.000000 +-0.766044 -0.642788 0.000000 +-0.766044 -0.642788 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 + + + + + + + + + + + +0.537122 0.103646 +0.549949 0.103646 +0.546895 0.161264 +0.595048 0.283608 +0.582256 0.283608 +0.585302 0.226150 +0.203520 0.310616 +0.190728 0.310616 +0.193775 0.253158 +0.188995 0.115589 +0.201786 0.115589 +0.198740 0.173047 +0.593077 0.146331 +0.605869 0.146331 +0.602822 0.203789 +0.028301 0.243705 +0.028301 0.231088 +0.540177 0.161264 +0.562003 0.104966 +0.553207 0.161955 +0.571830 0.107445 +0.592001 0.226150 +0.570235 0.282293 +0.579007 0.225461 +0.200474 0.253158 +0.178708 0.309301 +0.187479 0.252469 +0.192041 0.173047 +0.213807 0.116905 +0.205035 0.173736 +0.596123 0.203789 +0.617890 0.147647 +0.609117 0.204478 +0.084975 0.234092 +0.084975 0.240700 +0.558353 0.163253 +0.560436 0.279821 +0.573875 0.224167 +0.447449 0.136913 +0.449640 0.124488 +0.458057 0.127551 +0.456407 0.136914 +0.455949 0.113561 +0.462810 0.119319 +0.465614 0.105451 +0.470093 0.113208 +0.477470 0.101136 +0.479026 0.109957 +0.490088 0.101136 +0.488532 0.109957 +0.501944 0.105451 +0.312863 0.222985 +0.317110 0.228047 +0.306307 0.234284 +0.304844 0.232541 +0.319371 0.234256 +0.307086 0.236423 +0.319371 0.240864 +0.307086 0.238698 +0.317110 0.247073 +0.306307 0.240836 +0.312863 0.252135 +0.304844 0.242579 +0.541438 0.104749 +0.541438 0.106996 +0.487784 0.106996 +0.839139 0.234210 +0.840890 0.234210 +0.840890 0.287958 +0.839139 0.287958 +0.541438 0.070394 +0.541438 0.072371 +0.487784 0.072371 +0.487784 0.070394 +0.541438 0.074619 +0.337134 0.120611 +0.338885 0.120611 +0.338885 0.174360 +0.337134 0.174360 +0.341033 0.120611 +0.487784 0.104749 +0.541438 0.108973 +0.487784 0.108973 +0.541438 0.100524 +0.843039 0.234210 +0.843039 0.287958 +0.845325 0.234210 +0.845325 0.287958 +0.487784 0.074619 +0.541438 0.076866 +0.487784 0.076866 +0.541438 0.078843 +0.487784 0.078843 +0.341033 0.174360 +0.343319 0.120611 +0.343319 0.174360 +0.345470 0.120611 +0.345470 0.174360 +0.541438 0.102501 +0.497466 0.113209 +0.511609 0.113561 +0.504747 0.119319 +0.517918 0.124488 +0.509500 0.127551 +0.520109 0.136914 +0.511151 0.136914 +0.517918 0.149339 +0.505360 0.303902 +0.513904 0.303902 +0.513904 0.314202 +0.505360 0.314202 +0.523621 0.303902 +0.874778 0.234210 +0.874778 0.241937 +0.864247 0.241937 +0.864247 0.234210 +0.874778 0.251415 +0.400917 0.273772 +0.410633 0.273772 +0.410633 0.284072 +0.485761 0.108057 +0.485761 0.115783 +0.475230 0.115783 +0.475230 0.108057 +0.485761 0.125263 +0.523621 0.314202 +0.533338 0.303902 +0.533338 0.314202 +0.541882 0.303902 +0.541882 0.314202 +0.864247 0.251415 +0.874778 0.261503 +0.864247 0.261503 +0.874778 0.270982 +0.864247 0.270982 +0.694674 0.497425 +0.693653 0.498282 +0.692400 0.498738 +0.691067 0.498738 +0.689815 0.498282 +0.688794 0.497425 +0.688127 0.496271 +0.687896 0.494958 +0.688127 0.493646 +0.688794 0.492491 +0.689815 0.491634 +0.691067 0.491179 +0.692400 0.491179 +0.693653 0.491634 +0.694674 0.492491 +0.695340 0.493646 +0.695572 0.494958 +0.695340 0.496271 +0.307140 0.255439 +0.302874 0.243717 +0.300633 0.256586 +0.300633 0.244112 +0.294125 0.255439 +0.298392 0.243717 +0.288403 0.252135 +0.296421 0.242579 +0.284156 0.247073 +0.294959 0.240836 +0.281896 0.240864 +0.294181 0.238698 +0.281896 0.234256 +0.294181 0.236422 +0.284156 0.228047 +0.294959 0.234284 +0.288403 0.222985 +0.296421 0.232541 +0.294126 0.219681 +0.298392 0.231403 +0.300633 0.218534 +0.300633 0.231008 +0.307141 0.219681 +0.302874 0.231403 +0.400917 0.284072 +0.420350 0.273772 +0.420350 0.284072 +0.428893 0.273772 +0.428893 0.284072 +0.392372 0.273772 +0.392372 0.284072 +0.847474 0.234210 +0.847474 0.287958 +0.849226 0.234210 +0.849226 0.287958 +0.475230 0.125263 +0.485761 0.135349 +0.475230 0.135349 +0.485761 0.144829 +0.475230 0.144829 +0.485761 0.152555 +0.475230 0.152555 +0.509500 0.146275 +0.511609 0.160266 +0.504747 0.154508 +0.501944 0.168376 +0.497465 0.160619 +0.490088 0.172692 +0.488532 0.163870 +0.477470 0.172692 +0.479025 0.163871 +0.465614 0.168376 +0.470093 0.160619 +0.455949 0.160266 +0.462810 0.154508 +0.449640 0.149339 +0.458057 0.146275 +0.487784 0.102501 +0.487784 0.100524 +0.347220 0.120611 +0.347220 0.174360 +0.874778 0.278709 +0.864247 0.278709 +0.515241 0.107445 +0.525068 0.104966 +0.533864 0.161955 +0.528718 0.163253 +0.168908 0.306828 +0.182347 0.251174 +0.223606 0.119377 +0.210167 0.175031 +0.627689 0.150119 +0.614250 0.205773 + + + + + + + + + + + +

0 0 0 1 1 1 19 2 2 19 3 2 18 4 17 0 5 0 1 6 1 2 7 18 20 8 19 20 9 19 19 10 2 1 11 1 2 12 18 3 13 20 21 14 35 21 15 35 20 16 19 2 17 18 3 18 3 4 19 4 22 20 5 22 21 5 21 22 21 3 23 3 4 24 4 5 25 22 23 26 23 23 27 23 22 28 5 4 29 4 5 30 22 6 31 36 24 32 37 24 33 37 23 34 23 5 35 22 6 36 6 7 37 7 25 38 8 25 39 8 24 40 24 6 41 6 7 42 7 8 43 25 26 44 26 26 45 26 25 46 8 7 47 7 8 48 25 9 49 220 27 50 221 27 51 221 26 52 26 8 53 25 9 54 9 10 55 10 28 56 11 28 57 11 27 58 27 9 59 9 10 60 10 11 61 28 29 62 29 29 63 29 28 64 11 10 65 10 11 66 28 12 67 222 30 68 223 30 69 223 29 70 29 11 71 28 12 72 12 13 73 13 31 74 14 31 75 14 30 76 30 12 77 12 13 78 13 14 79 31 32 80 32 32 81 32 31 82 14 13 83 13 14 84 31 15 85 224 33 86 225 33 87 225 32 88 32 14 89 31 15 90 15 16 91 16 34 92 33 34 93 33 33 94 34 15 95 15 16 96 216 17 97 217 35 98 218 35 99 218 34 100 219 16 101 216 17 102 217 0 103 0 18 104 17 18 105 17 35 106 218 17 107 217 18 108 51 19 109 52 37 110 53 37 111 53 36 112 54 18 113 51 19 114 52 20 115 55 38 116 56 38 117 56 37 118 53 19 119 52 20 120 55 21 121 57 39 122 58 39 123 58 38 124 56 20 125 55 21 126 57 22 127 59 40 128 60 40 129 60 39 130 58 21 131 57 22 132 59 23 133 61 41 134 62 41 135 62 40 136 60 22 137 59 23 138 61 24 139 153 42 140 154 42 141 154 41 142 62 23 143 61 24 144 153 25 145 155 43 146 156 43 147 156 42 148 154 24 149 153 25 150 155 26 151 157 44 152 158 44 153 158 43 154 156 25 155 155 26 156 157 27 157 159 45 158 160 45 159 160 44 160 158 26 161 157 27 162 159 28 163 161 46 164 162 46 165 162 45 166 160 27 167 159 28 168 161 29 169 163 47 170 164 47 171 164 46 172 162 28 173 161 29 174 163 30 175 165 48 176 166 48 177 166 47 178 164 29 179 163 30 180 165 31 181 167 49 182 168 49 183 168 48 184 166 30 185 165 31 186 167 32 187 169 50 188 170 50 189 170 49 190 168 31 191 167 32 192 169 33 193 171 51 194 172 51 195 172 50 196 170 32 197 169 33 198 171 34 199 173 52 200 174 52 201 174 51 202 172 33 203 171 34 204 173 35 205 175 53 206 176 53 207 176 52 208 174 34 209 173 35 210 175 18 211 51 36 212 54 36 213 54 53 214 176 35 215 175 36 216 63 37 217 64 55 218 65 55 219 65 54 220 80 36 221 63 37 222 64 38 223 81 56 224 82 56 225 82 55 226 65 37 227 64 38 228 66 39 229 67 57 230 68 57 231 68 56 232 69 38 233 66 39 234 67 40 235 84 58 236 85 58 237 85 57 238 68 39 239 67 40 240 84 41 241 86 59 242 87 59 243 87 58 244 85 40 245 84 41 246 86 42 247 184 60 248 185 60 249 185 59 250 87 41 251 86 42 252 184 43 253 186 61 254 187 61 255 187 60 256 185 42 257 184 43 258 70 44 259 71 62 260 72 62 261 72 61 262 73 43 263 70 44 264 71 45 265 74 63 266 88 63 267 88 62 268 72 44 269 71 45 270 74 46 271 89 64 272 90 64 273 90 63 274 88 45 275 74 46 276 89 47 277 91 65 278 92 65 279 92 64 280 90 46 281 89 47 282 75 48 283 76 66 284 77 66 285 77 65 286 78 47 287 75 48 288 76 49 289 79 67 290 93 67 291 93 66 292 77 48 293 76 49 294 79 50 295 94 68 296 95 68 297 95 67 298 93 49 299 79 50 300 94 51 301 96 69 302 97 69 303 97 68 304 95 50 305 94 51 306 96 52 307 212 70 308 213 70 309 213 69 310 97 51 311 96 52 312 83 53 313 98 71 314 210 71 315 210 70 316 211 52 317 83 53 318 98 36 319 63 54 320 80 54 321 80 71 322 210 53 323 98 1 324 38 0 325 39 73 326 40 73 327 40 72 328 41 1 329 38 0 330 39 17 331 42 74 332 43 74 333 43 73 334 40 0 335 39 17 336 42 16 337 44 75 338 45 75 339 45 74 340 43 17 341 42 16 342 44 15 343 46 76 344 47 76 345 47 75 346 45 16 347 44 15 348 46 14 349 48 77 350 49 77 351 49 76 352 47 15 353 46 14 354 48 13 355 50 78 356 99 78 357 99 77 358 49 14 359 48 13 360 50 12 361 100 79 362 101 79 363 101 78 364 99 13 365 50 12 366 100 11 367 102 80 368 103 80 369 103 79 370 101 12 371 100 11 372 102 10 373 104 81 374 105 81 375 105 80 376 103 11 377 102 10 378 104 9 379 106 82 380 195 82 381 195 81 382 105 10 383 104 9 384 106 8 385 196 83 386 197 83 387 197 82 388 195 9 389 106 8 390 196 7 391 198 84 392 199 84 393 199 83 394 197 8 395 196 7 396 198 6 397 200 85 398 201 85 399 201 84 400 199 7 401 198 6 402 200 5 403 202 86 404 203 86 405 203 85 406 201 6 407 200 5 408 202 4 409 204 87 410 205 87 411 205 86 412 203 5 413 202 4 414 204 3 415 206 88 416 207 88 417 207 87 418 205 4 419 204 3 420 206 2 421 208 89 422 209 89 423 209 88 424 207 3 425 206 2 426 208 1 427 38 72 428 41 72 429 41 89 430 209 2 431 208 72 432 117 73 433 118 91 434 119 91 435 119 90 436 177 72 437 117 73 438 118 74 439 178 92 440 179 92 441 179 91 442 119 73 443 118 74 444 178 75 445 180 93 446 181 93 447 181 92 448 179 74 449 178 75 450 120 76 451 121 94 452 122 94 453 122 93 454 123 75 455 120 76 456 121 77 457 124 95 458 188 95 459 188 94 460 122 76 461 121 77 462 124 78 463 189 96 464 190 96 465 190 95 466 188 77 467 124 78 468 189 79 469 191 97 470 192 97 471 192 96 472 190 78 473 189 79 474 191 80 475 193 98 476 194 98 477 194 97 478 192 79 479 191 80 480 107 81 481 108 99 482 109 99 483 109 98 484 110 80 485 107 81 486 108 82 487 111 100 488 125 100 489 125 99 490 109 81 491 108 82 492 111 83 493 126 101 494 127 101 495 127 100 496 125 82 497 111 83 498 126 84 499 128 102 500 129 102 501 129 101 502 127 83 503 126 84 504 112 85 505 113 103 506 114 103 507 114 102 508 115 84 509 112 85 510 113 86 511 116 104 512 130 104 513 130 103 514 114 85 515 113 86 516 116 87 517 131 105 518 132 105 519 132 104 520 130 86 521 116 87 522 131 88 523 133 106 524 134 106 525 134 105 526 132 87 527 131 88 528 133 89 529 214 107 530 215 107 531 215 106 532 134 88 533 133 89 534 182 72 535 117 90 536 177 90 537 177 107 538 183 89 539 182 111 540 136 112 541 137 113 542 138 113 543 138 114 544 139 115 545 140 115 546 140 116 547 141 117 548 142 113 549 138 115 550 140 117 551 142 117 552 142 118 553 143 119 554 144 119 555 144 120 556 145 121 557 146 117 558 142 119 559 144 121 560 146 121 561 146 122 562 147 123 563 148 123 564 148 124 565 149 125 566 150 121 567 146 123 568 148 125 569 150 117 570 142 121 571 146 125 572 150 113 573 138 117 574 142 125 575 150 125 576 150 108 577 151 109 578 152 113 579 138 125 580 150 109 581 152 111 582 136 113 583 138 109 584 152 110 585 135 111 586 136 109 587 152

+
+
+
+ + + + + + + + + 0.999000 0.000000 0.000000 0.029575 0.000000 0.998995 0.000000 0.000251 0.000000 0.000000 1.002288 1325.909302 0.000000 0.000000 0.000000 1.0000001.000000 + 30.0000000.0000003.333333 + + + + + +
diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_Lamp_01/model.config b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_Lamp_01/model.config new file mode 100755 index 0000000..8121b47 --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_Lamp_01/model.config @@ -0,0 +1,11 @@ + + + aws_robomaker_warehouse_Lamp_01 + 1.0 + model.sdf + + + + + + diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_Lamp_01/model.sdf b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_Lamp_01/model.sdf new file mode 100755 index 0000000..9ef1c09 --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_Lamp_01/model.sdf @@ -0,0 +1,46 @@ + + + + + + 30 + + 907.144 + 0 + 0 + 104.950 + 0 + 824.248 + + + + + + model://aws_robomaker_warehouse_Lamp_01/meshes/aws_robomaker_warehouse_Lamp_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + model://aws_robomaker_warehouse_Lamp_01/meshes/aws_robomaker_warehouse_Lamp_01_visual.DAE + + + 1 + + +1 + + diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_PalletJackB_01/materials/textures/aws_robomaker_warehouse_PalletJackB_01.png b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_PalletJackB_01/materials/textures/aws_robomaker_warehouse_PalletJackB_01.png new file mode 100755 index 0000000..21c704c Binary files /dev/null and b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_PalletJackB_01/materials/textures/aws_robomaker_warehouse_PalletJackB_01.png differ diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_PalletJackB_01/materials/textures/aws_robomaker_warehouse_PalletJackB_02.png b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_PalletJackB_01/materials/textures/aws_robomaker_warehouse_PalletJackB_02.png new file mode 100755 index 0000000..9afb9b3 Binary files /dev/null and b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_PalletJackB_01/materials/textures/aws_robomaker_warehouse_PalletJackB_02.png differ diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_PalletJackB_01/meshes/aws_robomaker_warehouse_PalletJackB_01_collision.DAE b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_PalletJackB_01/meshes/aws_robomaker_warehouse_PalletJackB_01_collision.DAE new file mode 100755 index 0000000..dc0c1a2 --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_PalletJackB_01/meshes/aws_robomaker_warehouse_PalletJackB_01_collision.DAE @@ -0,0 +1,3373 @@ + + + FBX COLLADA exporter2019-03-28T09:56:39Z2019-03-28T09:56:39ZZ_UP + + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588235 0.588235 0.588235 1.000000 + + + 0.588235 0.588235 0.588235 1.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + +-43.491493 -9.846935 23.952991 +-39.490791 -9.846935 24.658491 +-39.490791 -4.445636 24.658491 +-43.491493 -4.445636 23.952991 +-47.009693 -9.846935 21.921791 +-47.009693 -4.445636 21.921791 +-49.620991 -9.846935 18.809792 +-49.620991 -4.445636 18.809792 +-51.010391 -9.846935 14.992290 +-51.010391 -4.445636 14.992290 +-51.010391 -9.846935 10.929891 +-51.010391 -4.445636 10.929891 +-49.620991 -9.846935 7.112391 +-49.620991 -4.445636 7.112391 +-47.009693 -9.846935 4.000391 +-47.009693 -4.445636 4.000391 +-43.491493 -9.846935 1.969191 +-43.491493 -4.445636 1.969191 +-39.490791 -9.846935 1.263691 +-39.490791 -4.445636 1.263691 +-35.489994 -9.846935 1.969191 +-35.489994 -4.445636 1.969191 +-31.971790 -9.846935 4.000391 +-31.971790 -4.445636 4.000391 +-29.360592 -9.846935 7.112391 +-29.360493 -4.445636 7.112391 +-27.971092 -9.846935 10.929891 +-27.971092 -4.445636 10.929891 +-27.971092 -9.846935 14.992290 +-27.971092 -4.445636 14.992290 +-29.360493 -9.846935 18.809792 +-29.360493 -4.445636 18.809792 +-31.971790 -9.846935 21.921791 +-31.971790 -4.445636 21.921791 +-35.489994 -9.846935 23.952991 +-35.489994 -4.445636 23.952991 +-43.491493 6.814264 23.952991 +-39.490791 6.814264 24.658491 +-39.490791 1.412965 24.658491 +-43.491493 1.412965 23.952991 +-47.009693 6.814264 21.921791 +-47.009693 1.412965 21.921791 +-49.620991 6.814264 18.809792 +-49.620991 1.412965 18.809792 +-51.010391 6.814264 14.992290 +-51.010391 1.412965 14.992290 +-51.010391 6.814264 10.929891 +-51.010391 1.412965 10.929891 +-49.620991 6.814264 7.112391 +-49.620991 1.412965 7.112391 +-47.009693 6.814264 4.000391 +-47.009693 1.412965 4.000391 +-43.491493 6.814264 1.969191 +-43.491493 1.412965 1.969191 +-39.490791 6.814264 1.263691 +-39.490791 1.412965 1.263691 +-35.489994 6.814264 1.969191 +-35.489994 1.412965 1.969191 +-31.971790 6.814264 4.000391 +-31.971790 1.412965 4.000391 +-29.360592 6.814264 7.112391 +-29.360493 1.412965 7.112391 +-27.971092 6.814264 10.929891 +-27.971092 1.412965 10.929891 +-27.971092 6.814264 14.992290 +-27.971092 1.412965 14.992290 +-29.360493 6.814264 18.809792 +-29.360493 1.412965 18.809792 +-31.971790 6.814264 21.921791 +-31.971790 1.412965 21.921791 +-35.489994 6.814264 23.952991 +-35.489994 1.412965 23.952991 +44.321407 15.830565 13.608291 +42.198505 15.830565 13.233991 +42.198505 19.891666 13.233991 +44.321407 19.891666 13.608291 +40.331608 15.830565 12.156091 +40.331608 19.891666 12.156091 +38.945908 15.830565 10.504791 +38.945908 19.891666 10.504791 +38.208611 15.830565 8.479091 +38.208611 19.891666 8.479091 +38.208611 15.830565 6.323390 +38.208611 19.891666 6.323390 +38.945908 15.830565 4.297691 +38.945908 19.891666 4.297691 +40.331608 15.830565 2.646291 +40.331608 19.891666 2.646291 +42.198505 15.830565 1.568491 +42.198505 19.891666 1.568491 +44.321407 15.830565 1.194091 +44.321407 19.891666 1.194091 +46.444408 15.830565 1.568491 +46.444408 19.891666 1.568491 +48.311310 15.830565 2.646291 +48.311310 19.891666 2.646291 +49.696907 15.830565 4.297691 +49.696907 19.891666 4.297691 +50.434208 15.830565 6.323390 +50.434208 19.891666 6.323390 +50.434208 15.830565 8.479091 +50.434208 19.891666 8.479091 +49.696907 15.830565 10.504791 +49.696907 19.891666 10.504791 +48.311310 15.830565 12.156091 +48.311310 19.891666 12.156091 +46.444408 15.830565 13.233991 +46.444408 19.891666 13.233991 +44.321407 -18.863235 13.608291 +42.198505 -18.863235 13.233991 +42.198505 -22.924335 13.233991 +44.321407 -22.924335 13.608291 +40.331608 -18.863235 12.156091 +40.331608 -22.924335 12.156091 +38.945908 -18.863235 10.504791 +38.945908 -22.924335 10.504791 +38.208611 -18.863235 8.479091 +38.208611 -22.924335 8.479091 +38.208611 -18.863235 6.323390 +38.208611 -22.924335 6.323390 +38.945908 -18.863235 4.297691 +38.945908 -22.924335 4.297691 +40.331608 -18.863235 2.646291 +40.331608 -22.924335 2.646291 +42.198505 -18.863235 1.568491 +42.198505 -22.924335 1.568491 +44.321407 -18.863235 1.194091 +44.321407 -22.924335 1.194091 +46.444408 -18.863235 1.568491 +46.444408 -22.924335 1.568491 +48.311310 -18.863235 2.646291 +48.311310 -22.924335 2.646291 +49.696907 -18.863235 4.297691 +49.696907 -22.924335 4.297691 +50.434208 -18.863235 6.323390 +50.434208 -22.924335 6.323390 +50.434208 -18.863235 8.479091 +50.434208 -22.924335 8.479091 +49.696907 -18.863235 10.504791 +49.696907 -22.924335 10.504791 +48.311310 -18.863235 12.156091 +48.311310 -22.924335 12.156091 +46.444408 -18.863235 13.233991 +46.444408 -22.924335 13.233991 +-26.551193 10.051767 8.147191 +65.077614 14.085981 8.147191 +-26.551193 25.475258 8.147191 +65.077614 21.550388 8.147191 +-26.551193 10.051767 14.167690 +65.077614 14.085981 14.167690 +-26.551193 25.475258 14.167690 +65.077614 21.550388 14.167690 +52.768509 25.475258 14.167690 +-11.961791 25.475258 8.147191 +-11.961791 10.051767 14.167690 +-11.961791 10.051767 8.147191 +-11.961791 25.475258 14.167690 +-25.527889 25.475258 8.147191 +-25.527889 10.051767 14.167690 +-25.527889 10.051767 8.147191 +-25.527889 25.475258 14.167690 +-11.961791 5.035481 53.648792 +-25.536491 5.035481 53.635590 +52.768509 10.051767 14.167690 +-11.961791 10.051767 13.330291 +-25.527889 10.051767 13.330291 +52.768509 25.475258 8.147191 +52.768509 10.051767 8.147191 +37.840710 20.088676 8.147191 +37.840710 15.625571 8.147191 +50.621807 20.088676 8.147191 +50.621807 15.625571 8.147191 +-11.326890 5.035481 53.648792 +-11.326890 5.035481 61.351391 +-11.326890 5.035481 53.635590 +-38.104794 5.035481 61.351391 +-25.536491 5.035481 53.635590 +-11.326890 -1.516335 53.648792 +-11.326890 -1.516335 61.351391 +-11.961791 -1.516335 13.330291 +-11.961791 -1.516335 14.167690 +-38.104794 5.035481 53.635590 +-38.104794 -1.516335 61.351391 +-25.527889 -1.516335 14.167690 +-37.267193 7.514789 30.846691 +-38.259289 7.514789 26.880592 +-25.532692 7.514789 27.432192 +-25.530293 7.514789 21.931791 +-25.532692 5.583035 27.432192 +-37.267193 5.583035 30.846691 +-38.259289 5.583035 26.880592 +-25.530293 5.583035 21.931791 +37.840710 20.088676 14.172491 +37.840710 15.625571 14.169190 +50.621807 20.088676 14.173890 +50.621807 15.625571 14.167791 +-26.551193 -13.084438 8.147191 +-26.551193 -28.507927 8.147191 +-25.527889 -28.507927 8.147191 +-25.527889 -13.084438 8.147191 +-26.551193 -13.084438 14.167690 +-25.527889 -13.084438 14.167690 +-25.527889 -28.507927 14.167690 +-26.551193 -28.507927 14.167690 +-25.527889 -13.084438 13.330291 +65.077614 -17.118652 8.147191 +65.077614 -24.583057 8.147191 +65.077614 -24.583057 14.167690 +65.077614 -17.118652 14.167690 +52.768509 -28.507927 8.147191 +52.768509 -28.507927 14.167690 +52.768509 -13.084438 8.147191 +52.768509 -13.084438 14.167690 +-11.961791 -28.507927 8.147191 +37.840710 -23.121346 8.147191 +37.840710 -18.658241 8.147191 +-11.961791 -13.084438 8.147191 +-11.961791 -13.084438 13.330291 +-11.961791 -28.507927 14.167690 +-25.536491 -8.068151 53.635590 +-11.961791 -8.068151 53.648792 +-11.961791 -13.084438 14.167690 +-11.961791 -1.516335 53.648792 +-25.527889 -1.516335 13.330291 +50.621807 -18.658241 8.147191 +50.621807 -23.121346 8.147191 +-11.326890 -8.068151 53.648792 +-11.326890 -8.068151 61.351391 +-38.104794 -8.068151 61.351391 +-11.326890 -8.068151 53.635590 +-25.536491 -8.068151 53.635590 +-38.104794 -8.068151 53.635590 +-38.104794 -1.516335 53.635590 +-25.536491 -1.516335 53.635590 +-25.532692 -10.547460 27.432192 +-25.530293 -10.547460 21.931791 +-38.259289 -10.547460 26.880592 +-37.267193 -10.547460 30.846691 +-25.530293 -8.615705 21.931791 +-38.259289 -8.615705 26.880592 +-25.532692 -8.615705 27.432192 +-37.267193 -8.615705 30.846691 +37.840710 -23.121346 14.172491 +37.840710 -18.658241 14.169190 +50.621807 -18.658241 14.167791 +50.621807 -23.121346 14.173890 +-33.549294 1.424371 10.896284 +-33.549297 -4.364129 10.896284 +-33.549294 1.424371 14.594985 +-33.549297 -4.364129 14.594985 +-41.235790 1.424372 10.896283 +-41.235794 -4.364128 10.896283 +-41.235790 1.424372 14.594984 +-41.235794 -4.364128 14.594984 +-32.404991 0.392671 11.022784 +-32.404991 -3.451929 11.022784 +-32.404995 0.392671 32.100487 +-32.404995 -3.451929 32.100487 +-35.993690 0.392671 11.022784 +-35.993690 -3.451929 11.022784 +-35.993694 0.392671 32.100483 +-35.993694 -3.451929 32.100483 +-46.667702 -1.516327 53.377083 +-46.667698 -6.459527 31.289381 +-29.835396 -6.459529 31.289385 +-46.667702 -6.459527 53.377083 +-29.835400 -6.459529 53.377083 +-46.667698 3.426873 31.289482 +-29.835396 3.426870 31.289486 +-29.835400 3.426870 53.377083 +-46.667702 3.426873 53.377083 +-46.667698 -1.516327 31.289381 +-29.835396 -1.516330 31.289385 +-29.835400 -1.516330 53.377083 +-41.219799 1.893072 51.678684 +-43.069313 0.400173 97.795525 +-43.069313 -3.432827 97.795525 +-41.219799 -4.925727 51.678684 +-45.298500 1.894173 51.675285 +-45.298500 -4.926826 51.675285 +-45.098412 -3.432527 97.794228 +-45.098412 0.399873 97.794228 +-43.148212 -1.516327 95.820427 +-44.992809 -6.806027 95.507317 +-43.147614 -6.806027 95.507317 +-43.148212 -1.516327 97.664223 +-43.147614 -6.931627 97.348320 +-44.992111 -1.516327 97.664223 +-44.992809 -6.931627 97.348228 +-44.992111 -1.516327 95.820427 +-44.993412 -10.413227 94.952721 +-43.146912 -10.413227 94.952827 +-43.147011 -10.842726 96.747032 +-44.993507 -10.842726 96.746925 +-43.147209 -13.182627 93.914925 +-44.993313 -13.889326 92.096825 +-43.146610 -13.889427 92.096825 +-43.147411 -14.555826 95.146126 +-43.146713 -15.683826 92.498726 +-44.991707 -14.555626 95.146019 +-44.993412 -15.683626 92.498726 +-44.991512 -13.182426 93.914833 +-44.994511 -14.089127 90.042931 +-43.145210 -14.089325 90.042931 +-43.145412 -15.932426 89.892036 +-44.994713 -15.932226 89.892036 +-44.997810 -13.581125 88.533119 +-43.141113 -13.581627 88.532829 +-43.141609 -15.092325 87.507927 +-44.998413 -15.091827 87.508232 +-44.992310 -12.060627 87.240929 +-43.148212 -12.060627 87.240929 +-43.148212 -13.112526 85.726219 +-44.992310 -13.112526 85.726219 +-44.992306 -1.810327 80.529320 +-43.148407 -1.810327 80.529320 +-43.148407 -2.820427 78.986824 +-44.992306 -2.820427 78.986824 +-44.993011 -12.282627 94.494026 +-43.146713 -12.282526 94.494026 +-43.146713 -13.229227 96.079124 +-44.993011 -13.229326 96.079124 +-43.147614 3.773273 95.507317 +-43.147614 3.898973 97.348320 +-44.992809 3.898973 97.348320 +-44.992809 3.773273 95.507317 +-44.993412 7.380474 94.952721 +-43.146912 7.380474 94.952827 +-43.147011 7.810073 96.747032 +-44.993507 7.810073 96.746925 +-44.991508 10.149773 93.914726 +-43.147205 10.149874 93.914925 +-43.147408 11.523172 95.146233 +-44.991703 11.522974 95.146019 +-44.993309 10.856672 92.096825 +-43.146606 10.856773 92.096825 +-43.146709 12.651073 92.498726 +-44.993408 12.650974 92.498726 +-44.997009 10.947073 89.486626 +-43.142105 10.947573 89.486412 +-43.142609 12.721174 89.037727 +-44.997509 12.720774 89.037819 +-43.143108 10.259373 88.135735 +-43.143505 11.576674 86.832527 +-44.996510 11.576374 86.832817 +-44.996109 10.259073 88.136024 +-43.148209 9.027973 87.240929 +-43.148209 10.079874 85.726219 +-44.992306 10.079773 85.726219 +-44.992306 9.027874 87.240929 +-43.148407 -1.222327 80.529320 +-43.148407 -0.212227 78.986824 +-44.992306 -0.212227 78.986824 +-44.992306 -1.222327 80.529320 +-43.146709 9.249874 94.494026 +-43.146709 10.196573 96.079124 +-44.993008 10.196672 96.079124 +-44.993008 9.249973 94.494026 +-43.772911 -11.534527 90.243629 +-44.279808 -11.534527 90.243629 +-44.383709 -8.683428 91.495613 +-44.508213 -3.241827 92.715614 +-43.669010 -8.683428 91.495613 +-43.544514 -3.241827 92.715614 +-43.774010 -11.239826 89.490929 +-43.662910 -8.450327 90.425819 +-43.541008 -3.217027 91.104225 +-44.511612 -3.217027 91.104225 +-44.389809 -8.450327 90.425819 +-44.278610 -11.239826 89.490929 +-25.536491 -1.516335 53.635590 + + + + + + + + + + + +-0.173664 0.000000 0.984805 +-0.173664 0.000000 0.984805 +-0.173664 0.000000 0.984805 +-0.173664 0.000000 0.984805 +-0.173664 0.000000 0.984805 +-0.173664 0.000000 0.984805 +-0.499994 0.000000 0.866029 +-0.499994 0.000000 0.866029 +-0.499994 0.000000 0.866029 +-0.499994 0.000000 0.866029 +-0.499994 0.000000 0.866029 +-0.499994 0.000000 0.866029 +-0.766042 0.000000 0.642790 +-0.766042 0.000000 0.642790 +-0.766042 0.000000 0.642790 +-0.766042 0.000000 0.642790 +-0.766042 0.000000 0.642790 +-0.766042 0.000000 0.642790 +-0.939697 0.000000 0.342008 +-0.939697 0.000000 0.342008 +-0.939697 0.000000 0.342008 +-0.939697 0.000000 0.342008 +-0.939697 0.000000 0.342008 +-0.939697 0.000000 0.342008 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.939697 0.000000 -0.342008 +-0.939697 0.000000 -0.342008 +-0.939697 0.000000 -0.342008 +-0.939697 0.000000 -0.342008 +-0.939697 0.000000 -0.342008 +-0.939697 0.000000 -0.342008 +-0.766042 0.000000 -0.642790 +-0.766042 0.000000 -0.642790 +-0.766042 0.000000 -0.642790 +-0.766042 0.000000 -0.642790 +-0.766042 0.000000 -0.642790 +-0.766042 0.000000 -0.642790 +-0.499994 0.000000 -0.866029 +-0.499994 0.000000 -0.866029 +-0.499994 0.000000 -0.866029 +-0.499994 0.000000 -0.866029 +-0.499994 0.000000 -0.866029 +-0.499994 0.000000 -0.866029 +-0.173664 0.000000 -0.984805 +-0.173664 0.000000 -0.984805 +-0.173664 0.000000 -0.984805 +-0.173664 0.000000 -0.984805 +-0.173664 0.000000 -0.984805 +-0.173664 0.000000 -0.984805 +0.173660 0.000000 -0.984806 +0.173660 0.000000 -0.984806 +0.173660 0.000000 -0.984806 +0.173660 0.000000 -0.984806 +0.173660 0.000000 -0.984806 +0.173660 0.000000 -0.984806 +0.499993 0.000000 -0.866029 +0.499993 0.000000 -0.866029 +0.499993 0.000000 -0.866029 +0.499993 0.000000 -0.866029 +0.499993 0.000000 -0.866029 +0.499993 0.000000 -0.866029 +0.766054 -0.000014 -0.642776 +0.766054 -0.000014 -0.642776 +0.766054 -0.000014 -0.642776 +0.766042 0.000000 -0.642790 +0.766042 0.000000 -0.642790 +0.766042 0.000000 -0.642790 +0.939697 -0.000017 -0.342008 +0.939697 -0.000017 -0.342008 +0.939697 -0.000017 -0.342008 +0.939689 0.000000 -0.342030 +0.939689 0.000000 -0.342030 +0.939689 0.000000 -0.342030 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.939697 0.000000 0.342008 +0.939697 0.000000 0.342008 +0.939697 0.000000 0.342008 +0.939697 0.000000 0.342008 +0.939697 0.000000 0.342008 +0.939697 0.000000 0.342008 +0.766042 0.000000 0.642790 +0.766042 0.000000 0.642790 +0.766042 0.000000 0.642790 +0.766042 0.000000 0.642790 +0.766042 0.000000 0.642790 +0.766042 0.000000 0.642790 +0.499993 0.000000 0.866029 +0.499993 0.000000 0.866029 +0.499993 0.000000 0.866029 +0.499993 0.000000 0.866029 +0.499993 0.000000 0.866029 +0.499993 0.000000 0.866029 +0.173660 0.000000 0.984806 +0.173660 0.000000 0.984806 +0.173660 0.000000 0.984806 +0.173660 0.000000 0.984806 +0.173660 0.000000 0.984806 +0.173660 0.000000 0.984806 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.173664 0.000000 0.984805 +-0.173664 0.000000 0.984805 +-0.173664 0.000000 0.984805 +-0.173664 0.000000 0.984805 +-0.173664 0.000000 0.984805 +-0.173664 0.000000 0.984805 +-0.499994 0.000000 0.866029 +-0.499994 0.000000 0.866029 +-0.499994 0.000000 0.866029 +-0.499994 0.000000 0.866029 +-0.499994 0.000000 0.866029 +-0.499994 0.000000 0.866029 +-0.766042 0.000000 0.642790 +-0.766042 0.000000 0.642790 +-0.766042 0.000000 0.642790 +-0.766042 0.000000 0.642790 +-0.766042 0.000000 0.642790 +-0.766042 0.000000 0.642790 +-0.939697 0.000000 0.342008 +-0.939697 0.000000 0.342008 +-0.939697 0.000000 0.342008 +-0.939697 0.000000 0.342008 +-0.939697 0.000000 0.342008 +-0.939697 0.000000 0.342008 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.939697 0.000000 -0.342008 +-0.939697 0.000000 -0.342008 +-0.939697 0.000000 -0.342008 +-0.939697 0.000000 -0.342008 +-0.939697 0.000000 -0.342008 +-0.939697 0.000000 -0.342008 +-0.766042 0.000000 -0.642790 +-0.766042 0.000000 -0.642790 +-0.766042 0.000000 -0.642790 +-0.766042 0.000000 -0.642790 +-0.766042 0.000000 -0.642790 +-0.766042 0.000000 -0.642790 +-0.499994 0.000000 -0.866029 +-0.499994 0.000000 -0.866029 +-0.499994 0.000000 -0.866029 +-0.499994 0.000000 -0.866029 +-0.499994 0.000000 -0.866029 +-0.499994 0.000000 -0.866029 +-0.173664 0.000000 -0.984805 +-0.173664 0.000000 -0.984805 +-0.173664 0.000000 -0.984805 +-0.173664 0.000000 -0.984805 +-0.173664 0.000000 -0.984805 +-0.173664 0.000000 -0.984805 +0.173660 0.000000 -0.984806 +0.173660 0.000000 -0.984806 +0.173660 0.000000 -0.984806 +0.173660 0.000000 -0.984806 +0.173660 0.000000 -0.984806 +0.173660 0.000000 -0.984806 +0.499993 0.000000 -0.866029 +0.499993 0.000000 -0.866029 +0.499993 0.000000 -0.866029 +0.499993 0.000000 -0.866029 +0.499993 0.000000 -0.866029 +0.499993 0.000000 -0.866029 +0.766054 0.000014 -0.642776 +0.766054 0.000014 -0.642776 +0.766054 0.000014 -0.642776 +0.766042 0.000000 -0.642790 +0.766042 0.000000 -0.642790 +0.766042 0.000000 -0.642790 +0.939689 0.000000 -0.342030 +0.939689 0.000000 -0.342030 +0.939689 0.000000 -0.342030 +0.939697 0.000017 -0.342008 +0.939697 0.000017 -0.342008 +0.939697 0.000017 -0.342008 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.939697 0.000000 0.342008 +0.939697 0.000000 0.342008 +0.939697 0.000000 0.342008 +0.939697 0.000000 0.342008 +0.939697 0.000000 0.342008 +0.939697 0.000000 0.342008 +0.766042 0.000000 0.642790 +0.766042 0.000000 0.642790 +0.766042 0.000000 0.642790 +0.766042 0.000000 0.642790 +0.766042 0.000000 0.642790 +0.766042 0.000000 0.642790 +0.499993 0.000000 0.866029 +0.499993 0.000000 0.866029 +0.499993 0.000000 0.866029 +0.499993 0.000000 0.866029 +0.499993 0.000000 0.866029 +0.499993 0.000000 0.866029 +0.173660 0.000000 0.984806 +0.173660 0.000000 0.984806 +0.173660 0.000000 0.984806 +0.173660 0.000000 0.984806 +0.173660 0.000000 0.984806 +0.173660 0.000000 0.984806 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.173637 0.000000 0.984810 +-0.173637 0.000000 0.984810 +-0.173637 0.000000 0.984810 +-0.173637 0.000000 0.984810 +-0.173637 0.000000 0.984810 +-0.173637 0.000000 0.984810 +-0.500016 0.000000 0.866016 +-0.500016 0.000000 0.866016 +-0.500016 0.000000 0.866016 +-0.500016 0.000000 0.866016 +-0.500016 0.000000 0.866016 +-0.500016 0.000000 0.866016 +-0.766023 0.000000 0.642814 +-0.766023 0.000000 0.642814 +-0.766023 0.000000 0.642814 +-0.766023 0.000000 0.642814 +-0.766023 0.000000 0.642814 +-0.766023 0.000000 0.642814 +-0.939692 0.000000 0.342021 +-0.939692 0.000000 0.342021 +-0.939692 0.000000 0.342021 +-0.939692 0.000000 0.342021 +-0.939692 0.000000 0.342021 +-0.939692 0.000000 0.342021 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.939692 0.000000 -0.342021 +-0.939692 0.000000 -0.342021 +-0.939692 0.000000 -0.342021 +-0.939692 0.000000 -0.342021 +-0.939692 0.000000 -0.342021 +-0.939692 0.000000 -0.342021 +-0.766042 0.000000 -0.642791 +-0.766042 0.000000 -0.642791 +-0.766042 0.000000 -0.642791 +-0.766042 0.000000 -0.642791 +-0.766042 0.000000 -0.642791 +-0.766042 0.000000 -0.642791 +-0.499981 0.000000 -0.866036 +-0.499981 0.000000 -0.866036 +-0.499981 0.000000 -0.866036 +-0.499981 0.000000 -0.866036 +-0.499981 0.000000 -0.866036 +-0.499981 0.000000 -0.866036 +-0.173682 0.000000 -0.984802 +-0.173682 0.000000 -0.984802 +-0.173682 0.000000 -0.984802 +-0.173682 0.000000 -0.984802 +-0.173682 0.000000 -0.984802 +-0.173682 0.000000 -0.984802 +0.173674 0.000000 -0.984803 +0.173674 0.000000 -0.984803 +0.173674 0.000000 -0.984803 +0.173674 0.000000 -0.984803 +0.173674 0.000000 -0.984803 +0.173674 0.000000 -0.984803 +0.499981 0.000000 -0.866037 +0.499980 0.000000 -0.866037 +0.499980 0.000000 -0.866037 +0.499981 0.000000 -0.866037 +0.499980 0.000000 -0.866037 +0.499980 0.000000 -0.866037 +0.766065 0.000000 -0.642763 +0.766065 0.000000 -0.642763 +0.766065 0.000000 -0.642763 +0.766065 0.000000 -0.642763 +0.766065 0.000000 -0.642763 +0.766065 0.000000 -0.642763 +0.939692 0.000000 -0.342023 +0.939692 0.000000 -0.342023 +0.939692 0.000000 -0.342023 +0.939692 0.000000 -0.342023 +0.939692 0.000000 -0.342023 +0.939692 0.000000 -0.342023 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.939692 0.000000 0.342023 +0.939692 0.000000 0.342023 +0.939692 0.000000 0.342023 +0.939692 0.000000 0.342023 +0.939692 0.000000 0.342023 +0.939692 0.000000 0.342023 +0.766046 0.000000 0.642786 +0.766046 0.000000 0.642786 +0.766046 0.000000 0.642785 +0.766046 0.000000 0.642785 +0.766046 0.000000 0.642786 +0.766046 0.000000 0.642786 +0.500015 0.000000 0.866017 +0.500015 0.000000 0.866017 +0.500015 0.000000 0.866017 +0.500015 0.000000 0.866017 +0.500015 0.000000 0.866017 +0.500015 0.000000 0.866017 +0.173629 0.000000 0.984811 +0.173629 0.000000 0.984811 +0.173629 0.000000 0.984811 +0.173629 0.000000 0.984811 +0.173629 0.000000 0.984811 +0.173629 0.000000 0.984811 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.173637 0.000000 0.984810 +-0.173637 0.000000 0.984810 +-0.173637 0.000000 0.984810 +-0.173637 0.000000 0.984810 +-0.173637 0.000000 0.984810 +-0.173637 0.000000 0.984810 +-0.500016 0.000000 0.866016 +-0.500016 0.000000 0.866016 +-0.500016 0.000000 0.866016 +-0.500016 0.000000 0.866016 +-0.500016 0.000000 0.866016 +-0.500016 0.000000 0.866016 +-0.766023 0.000000 0.642814 +-0.766023 0.000000 0.642814 +-0.766023 0.000000 0.642814 +-0.766023 0.000000 0.642814 +-0.766023 0.000000 0.642814 +-0.766023 0.000000 0.642814 +-0.939692 0.000000 0.342021 +-0.939692 0.000000 0.342021 +-0.939692 0.000000 0.342021 +-0.939692 0.000000 0.342021 +-0.939692 0.000000 0.342021 +-0.939692 0.000000 0.342021 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.939692 0.000000 -0.342021 +-0.939692 0.000000 -0.342021 +-0.939692 0.000000 -0.342021 +-0.939692 0.000000 -0.342021 +-0.939692 0.000000 -0.342021 +-0.939692 0.000000 -0.342021 +-0.766042 0.000000 -0.642791 +-0.766042 0.000000 -0.642791 +-0.766042 0.000000 -0.642791 +-0.766042 0.000000 -0.642791 +-0.766042 0.000000 -0.642791 +-0.766042 0.000000 -0.642791 +-0.499981 0.000000 -0.866036 +-0.499981 0.000000 -0.866036 +-0.499981 0.000000 -0.866036 +-0.499981 0.000000 -0.866036 +-0.499981 0.000000 -0.866036 +-0.499981 0.000000 -0.866036 +-0.173682 0.000000 -0.984802 +-0.173682 0.000000 -0.984802 +-0.173682 0.000000 -0.984802 +-0.173682 0.000000 -0.984802 +-0.173682 0.000000 -0.984802 +-0.173682 0.000000 -0.984802 +0.173674 0.000000 -0.984803 +0.173674 0.000000 -0.984803 +0.173674 0.000000 -0.984803 +0.173674 0.000000 -0.984803 +0.173674 0.000000 -0.984803 +0.173674 0.000000 -0.984803 +0.499981 0.000000 -0.866037 +0.499981 0.000000 -0.866037 +0.499980 0.000000 -0.866037 +0.499981 0.000000 -0.866037 +0.499980 0.000000 -0.866037 +0.499981 0.000000 -0.866037 +0.766065 0.000000 -0.642763 +0.766065 0.000000 -0.642763 +0.766065 0.000000 -0.642763 +0.766065 0.000000 -0.642763 +0.766065 0.000000 -0.642763 +0.766065 0.000000 -0.642763 +0.939692 0.000000 -0.342023 +0.939692 0.000000 -0.342023 +0.939692 0.000000 -0.342023 +0.939692 0.000000 -0.342023 +0.939692 0.000000 -0.342023 +0.939692 0.000000 -0.342023 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.939692 0.000000 0.342023 +0.939692 0.000000 0.342023 +0.939692 0.000000 0.342023 +0.939692 0.000000 0.342023 +0.939692 0.000000 0.342023 +0.939692 0.000000 0.342023 +0.766046 0.000000 0.642786 +0.766046 0.000000 0.642785 +0.766046 0.000000 0.642786 +0.766046 0.000000 0.642786 +0.766046 0.000000 0.642785 +0.766046 0.000000 0.642786 +0.500015 0.000000 0.866017 +0.500015 0.000000 0.866017 +0.500015 0.000000 0.866017 +0.500015 0.000000 0.866017 +0.500015 0.000000 0.866017 +0.500015 0.000000 0.866017 +0.173629 0.000000 0.984811 +0.173629 0.000000 0.984811 +0.173629 0.000000 0.984811 +0.173629 0.000000 0.984811 +0.173629 0.000000 0.984811 +0.173629 0.000000 0.984811 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.303790 0.952739 0.000000 +0.303790 0.952739 0.000000 +0.303790 0.952739 0.000000 +0.303790 0.952739 0.000000 +0.303790 0.952739 0.000000 +0.303790 0.952739 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.311442 -0.950265 0.000000 +0.311442 -0.950265 0.000000 +0.311442 -0.950265 0.000000 +0.311442 -0.950265 0.000000 +0.311442 -0.950265 0.000000 +0.311442 -0.950265 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.000447 0.888048 0.459751 +-0.000447 0.888048 0.459751 +-0.000447 0.888048 0.459751 +0.000000 0.887985 0.459873 +0.000000 0.887985 0.459873 +0.000000 0.887985 0.459873 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 -0.000218 +-1.000000 0.000000 -0.000218 +-1.000000 0.000000 -0.000218 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 -0.000218 +-1.000000 0.000000 -0.000218 +-1.000000 0.000000 -0.000218 +-1.000000 0.000000 -0.000218 +-1.000000 0.000000 -0.000218 +-1.000000 0.000000 -0.000218 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.362359 0.000000 -0.932038 +-0.362360 0.000000 -0.932038 +-0.362359 0.000000 -0.932038 +-0.362359 0.000000 -0.932038 +-0.362359 0.000000 -0.932038 +-0.362360 0.000000 -0.932038 +0.279392 0.000000 0.960177 +0.279392 0.000000 0.960177 +0.279392 0.000000 0.960177 +0.279392 0.000000 0.960177 +0.279392 0.000000 0.960177 +0.279392 0.000000 0.960177 +-0.970110 0.000000 0.242667 +-0.970110 0.000000 0.242667 +-0.970110 0.000000 0.242667 +-0.970110 0.000000 0.242667 +-0.970110 0.000000 0.242667 +-0.970110 0.000000 0.242667 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 0.000436 +1.000000 0.000000 0.000436 +1.000000 0.000000 0.000436 +1.000000 0.000000 0.000436 +1.000000 0.000000 0.000436 +1.000000 0.000000 0.000436 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -0.000269 1.000000 +0.000000 -0.000269 1.000000 +0.000000 -0.000269 1.000000 +0.000109 0.000024 1.000000 +0.000109 0.000024 1.000000 +0.000109 0.000024 1.000000 +0.000047 0.000000 1.000000 +0.000047 0.000000 1.000000 +0.000047 0.000000 1.000000 +0.006317 -0.001366 0.999979 +0.006317 -0.001366 0.999979 +0.006317 -0.001366 0.999979 +-0.000109 0.001195 0.999999 +-0.000109 0.001195 0.999999 +-0.000109 0.001195 0.999999 +0.000000 0.000891 1.000000 +0.000000 0.000891 1.000000 +0.000000 0.000891 1.000000 +-0.000176 -0.000740 1.000000 +-0.000176 -0.000740 1.000000 +-0.000176 -0.000740 1.000000 +-0.000030 0.000000 1.000000 +-0.000030 0.000000 1.000000 +-0.000030 0.000000 1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.303790 -0.952739 0.000000 +0.303790 -0.952739 0.000000 +0.303790 -0.952739 0.000000 +0.303790 -0.952739 0.000000 +0.303790 -0.952739 0.000000 +0.303790 -0.952739 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.311442 0.950265 0.000000 +0.311442 0.950265 0.000000 +0.311442 0.950265 0.000000 +0.311442 0.950265 0.000000 +0.311442 0.950265 0.000000 +0.311442 0.950265 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.000447 -0.888048 0.459751 +-0.000447 -0.888048 0.459751 +-0.000447 -0.888048 0.459751 +0.000000 -0.887985 0.459873 +0.000000 -0.887985 0.459873 +0.000000 -0.887985 0.459873 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 -0.000218 +-1.000000 0.000000 -0.000218 +-1.000000 0.000000 -0.000218 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 -0.000218 +-1.000000 0.000000 -0.000218 +-1.000000 0.000000 -0.000218 +-1.000000 0.000000 -0.000218 +-1.000000 0.000000 -0.000218 +-1.000000 0.000000 -0.000218 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.362360 0.000000 -0.932038 +-0.362359 0.000000 -0.932038 +-0.362359 0.000000 -0.932038 +-0.362360 0.000000 -0.932038 +-0.362359 0.000000 -0.932038 +-0.362359 0.000000 -0.932038 +0.279392 0.000000 0.960177 +0.279392 0.000000 0.960177 +0.279392 0.000000 0.960177 +0.279392 0.000000 0.960177 +0.279392 0.000000 0.960177 +0.279392 0.000000 0.960177 +-0.970110 0.000000 0.242667 +-0.970110 0.000000 0.242667 +-0.970110 0.000000 0.242667 +-0.970110 0.000000 0.242667 +-0.970110 0.000000 0.242667 +-0.970110 0.000000 0.242667 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +1.000000 0.000000 0.000436 +1.000000 0.000000 0.000436 +1.000000 0.000000 0.000436 +1.000000 0.000000 0.000436 +1.000000 0.000000 0.000436 +1.000000 0.000000 0.000436 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000269 1.000000 +0.000000 0.000269 1.000000 +0.000000 0.000269 1.000000 +0.000109 -0.000024 1.000000 +0.000109 -0.000024 1.000000 +0.000109 -0.000024 1.000000 +0.000047 0.000000 1.000000 +0.000047 0.000000 1.000000 +0.000047 0.000000 1.000000 +0.006317 0.001366 0.999979 +0.006317 0.001366 0.999979 +0.006317 0.001366 0.999979 +0.000000 -0.000891 1.000000 +0.000000 -0.000891 1.000000 +0.000000 -0.000891 1.000000 +-0.000109 -0.001195 0.999999 +-0.000109 -0.001195 0.999999 +-0.000109 -0.001195 0.999999 +-0.000030 0.000000 1.000000 +-0.000030 0.000000 1.000000 +-0.000030 0.000000 1.000000 +-0.000176 0.000740 1.000000 +-0.000176 0.000740 1.000000 +-0.000176 0.000740 1.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +-1.000000 0.000001 0.000000 +-1.000000 0.000001 0.000000 +-1.000000 0.000001 0.000000 +-1.000000 0.000001 0.000000 +-1.000000 0.000001 0.000000 +-1.000000 0.000001 0.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 0.000000 1.000000 +-0.000000 0.000000 1.000000 +-0.000000 0.000000 1.000000 +-0.000000 0.000000 1.000000 +-0.000000 0.000000 1.000000 +-0.000000 0.000000 1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 -0.000000 +-0.000001 0.000000 1.000000 +-0.000001 0.000000 1.000000 +-0.000001 0.000000 1.000000 +-0.000001 0.000000 1.000000 +-0.000001 0.000000 1.000000 +-0.000001 0.000000 1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 -0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000020 -1.000000 +0.000000 0.000020 -1.000000 +0.000000 0.000020 -1.000000 +0.000000 0.000020 -1.000000 +0.000000 0.000020 -1.000000 +0.000000 0.000020 -1.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +0.999197 0.000000 0.040073 +0.999197 0.000000 0.040073 +0.999197 0.000000 0.040073 +0.999197 0.000000 0.040073 +0.999197 0.000000 0.040073 +0.999197 0.000000 0.040073 +-0.999991 0.000000 0.004338 +-0.999991 0.000000 0.004338 +-0.999991 0.000000 0.004338 +-0.999991 0.000000 0.004338 +-0.999991 0.000000 0.004338 +-0.999991 0.000000 0.004338 +-0.000169 -0.999475 0.032385 +-0.000169 -0.999475 0.032385 +-0.000169 -0.999476 0.032385 +0.000242 -0.999476 0.032365 +0.000242 -0.999476 0.032365 +0.000242 -0.999476 0.032365 +-0.000639 0.000000 1.000000 +-0.000639 0.000000 1.000000 +-0.000639 0.000000 1.000000 +-0.000639 0.000000 1.000000 +-0.000639 0.000000 1.000000 +-0.000639 0.000000 1.000000 +-0.000168 0.999475 0.032385 +-0.000168 0.999476 0.032385 +-0.000168 0.999475 0.032385 +0.000243 0.999476 0.032365 +0.000243 0.999476 0.032365 +0.000243 0.999476 0.032365 +0.000000 0.059089 -0.998253 +0.000000 0.059089 -0.998253 +0.000000 0.059089 -0.998253 +0.000000 0.059089 -0.998253 +0.000000 0.059089 -0.998253 +0.000000 0.059089 -0.998253 +1.000000 0.000111 0.000000 +1.000000 0.000111 0.000000 +1.000000 0.000111 0.000000 +1.000000 0.000113 0.000008 +1.000000 0.000113 0.000008 +1.000000 0.000113 0.000008 +-0.000000 -0.058236 0.998303 +-0.000000 -0.058236 0.998303 +-0.000000 -0.058236 0.998303 +-0.000050 -0.058253 0.998302 +-0.000050 -0.058253 0.998302 +-0.000050 -0.058253 0.998302 +-1.000000 0.000129 0.000000 +-1.000000 0.000129 0.000000 +-1.000000 0.000129 0.000000 +-1.000000 0.000131 0.000009 +-1.000000 0.000131 0.000009 +-1.000000 0.000131 0.000009 +0.000000 0.151961 -0.988387 +0.000000 0.151961 -0.988386 +0.000000 0.151961 -0.988386 +0.000057 0.151933 -0.988391 +0.000057 0.151933 -0.988391 +0.000057 0.151933 -0.988391 +1.000000 0.000153 0.000010 +1.000000 0.000153 0.000010 +1.000000 0.000153 0.000010 +1.000000 0.000179 0.000098 +1.000000 0.000179 0.000098 +1.000000 0.000179 0.000098 +-0.000049 -0.151954 0.988388 +-0.000049 -0.151954 0.988388 +-0.000049 -0.151954 0.988388 +-0.000057 -0.151957 0.988387 +-0.000057 -0.151957 0.988387 +-0.000057 -0.151957 0.988387 +-1.000000 0.000169 -0.000013 +-1.000000 0.000169 -0.000013 +-1.000000 0.000169 -0.000013 +-1.000000 0.000177 0.000012 +-1.000000 0.000177 0.000012 +-1.000000 0.000177 0.000012 +0.000051 0.932023 -0.362400 +0.000051 0.932023 -0.362400 +0.000051 0.932023 -0.362400 +0.000119 0.932046 -0.362340 +0.000119 0.932046 -0.362340 +0.000119 0.932046 -0.362340 +1.000000 0.000065 0.000236 +1.000000 0.000065 0.000236 +1.000000 0.000065 0.000236 +1.000000 0.000015 0.000324 +1.000000 0.000015 0.000324 +1.000000 0.000015 0.000324 +-0.000123 -0.919973 0.391981 +-0.000123 -0.919973 0.391981 +-0.000123 -0.919973 0.391981 +-0.000100 -0.919968 0.391994 +-0.000100 -0.919968 0.391994 +-0.000100 -0.919968 0.391994 +-1.000000 0.000255 0.000891 +-1.000000 0.000255 0.000891 +-1.000000 0.000255 0.000891 +-1.000000 0.000520 0.000422 +-1.000000 0.000520 0.000422 +-1.000000 0.000520 0.000422 +0.000107 0.995297 -0.096868 +0.000107 0.995297 -0.096868 +0.000107 0.995297 -0.096868 +0.000054 0.995302 -0.096822 +0.000054 0.995302 -0.096822 +0.000054 0.995302 -0.096822 +1.000000 -0.000152 0.000513 +1.000000 -0.000152 0.000513 +1.000000 -0.000152 0.000513 +1.000000 0.000093 0.000673 +1.000000 0.000093 0.000673 +1.000000 0.000093 0.000673 +-0.000108 -0.995483 0.094939 +-0.000108 -0.995483 0.094939 +-0.000108 -0.995483 0.094939 +-0.000108 -0.995483 0.094939 +-0.000108 -0.995483 0.094939 +-0.000108 -0.995483 0.094939 +-1.000000 0.000182 0.000565 +-1.000000 0.000182 0.000565 +-1.000000 0.000182 0.000565 +-1.000000 0.000069 0.000492 +-1.000000 0.000069 0.000492 +-1.000000 0.000069 0.000492 +0.000306 0.947864 0.318674 +0.000306 0.947864 0.318674 +0.000306 0.947864 0.318674 +0.000102 0.947789 0.318899 +0.000102 0.947789 0.318899 +0.000102 0.947789 0.318899 +0.999999 -0.001138 0.001194 +0.999999 -0.001138 0.001194 +0.999999 -0.001138 0.001194 +0.999997 -0.000323 0.002604 +0.999997 -0.000323 0.002604 +0.999997 -0.000323 0.002604 +-0.000102 -0.943108 -0.332488 +-0.000102 -0.943107 -0.332488 +-0.000102 -0.943107 -0.332488 +-0.000308 -0.943158 -0.332346 +-0.000308 -0.943158 -0.332346 +-0.000308 -0.943157 -0.332346 +-0.999999 -0.000528 0.001366 +-0.999999 -0.000528 0.001366 +-0.999999 -0.000528 0.001366 +-0.999998 -0.000067 0.002163 +-0.999998 -0.000067 0.002163 +-0.999998 -0.000067 0.002163 +0.000000 0.647581 0.761997 +0.000000 0.647581 0.761997 +0.000000 0.647581 0.761997 +0.000294 0.647373 0.762173 +0.000294 0.647373 0.762173 +0.000294 0.647373 0.762173 +0.999996 0.001246 -0.002321 +0.999996 0.001246 -0.002321 +0.999997 0.001246 -0.002321 +0.999994 0.002936 -0.002039 +0.999994 0.002936 -0.002039 +0.999994 0.002936 -0.002039 +-0.000302 -0.668942 -0.743314 +-0.000302 -0.668942 -0.743314 +-0.000302 -0.668942 -0.743314 +0.000000 -0.669098 -0.743174 +0.000000 -0.669098 -0.743174 +0.000000 -0.669098 -0.743174 +-0.999996 0.002275 -0.001580 +-0.999996 0.002275 -0.001580 +-0.999996 0.002275 -0.001580 +-0.999997 0.001553 -0.001701 +-0.999997 0.001553 -0.001701 +-0.999997 0.001553 -0.001701 +0.000000 0.547792 0.836615 +0.000000 0.547792 0.836615 +0.000000 0.547792 0.836615 +0.000000 0.547792 0.836615 +0.000000 0.547792 0.836615 +0.000000 0.547792 0.836615 +1.000000 0.000013 -0.000009 +1.000000 0.000013 -0.000009 +1.000000 0.000013 -0.000009 +1.000000 0.000013 -0.000009 +1.000000 0.000013 -0.000009 +1.000000 0.000013 -0.000009 +0.000000 -0.547816 -0.836599 +0.000000 -0.547816 -0.836599 +0.000000 -0.547816 -0.836599 +-0.000000 -0.547816 -0.836599 +-0.000000 -0.547816 -0.836599 +-0.000000 -0.547816 -0.836599 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-0.000013 0.238366 -0.971175 +-0.000013 0.238366 -0.971176 +-0.000013 0.238366 -0.971175 +0.000056 0.238301 -0.971191 +0.000056 0.238301 -0.971191 +0.000056 0.238301 -0.971191 +1.000000 0.000087 0.000076 +1.000000 0.000087 0.000076 +1.000000 0.000087 0.000076 +1.000000 0.000107 0.000064 +1.000000 0.000107 0.000064 +1.000000 0.000107 0.000064 +-0.000056 -0.269463 0.963011 +-0.000056 -0.269463 0.963011 +-0.000056 -0.269463 0.963011 +0.000014 -0.269513 0.962997 +0.000014 -0.269513 0.962997 +0.000014 -0.269513 0.962997 +-1.000000 -0.000178 -0.000106 +-1.000000 -0.000178 -0.000106 +-1.000000 -0.000178 -0.000106 +-1.000000 -0.000190 -0.000099 +-1.000000 -0.000190 -0.000099 +-1.000000 -0.000190 -0.000099 +-0.000030 0.541254 -0.840859 +-0.000030 0.541254 -0.840859 +-0.000030 0.541254 -0.840859 +0.000101 0.541065 -0.840981 +0.000101 0.541065 -0.840981 +0.000101 0.541065 -0.840981 +1.000000 -0.000360 -0.000237 +1.000000 -0.000360 -0.000237 +1.000000 -0.000360 -0.000237 +1.000000 -0.000398 -0.000238 +1.000000 -0.000398 -0.000238 +1.000000 -0.000398 -0.000238 +0.000031 -0.575404 0.817869 +0.000031 -0.575404 0.817869 +0.000031 -0.575404 0.817869 +-0.000110 -0.575273 0.817961 +-0.000110 -0.575273 0.817961 +-0.000110 -0.575273 0.817961 +-1.000000 -0.000489 -0.000703 +-1.000000 -0.000489 -0.000703 +-1.000000 -0.000489 -0.000703 +-0.999999 -0.001203 -0.000719 +-0.999999 -0.001203 -0.000719 +-0.999999 -0.001203 -0.000719 +-0.000000 -0.059090 -0.998253 +-0.000000 -0.059090 -0.998253 +-0.000000 -0.059090 -0.998253 +-0.000000 -0.059090 -0.998253 +-0.000000 -0.059090 -0.998253 +-0.000000 -0.059090 -0.998253 +1.000000 -0.000113 0.000008 +1.000000 -0.000113 0.000008 +1.000000 -0.000113 0.000008 +1.000000 -0.000111 0.000000 +1.000000 -0.000111 0.000000 +1.000000 -0.000111 0.000000 +0.000000 0.058236 0.998303 +0.000000 0.058236 0.998303 +0.000000 0.058236 0.998303 +0.000000 0.058236 0.998303 +0.000000 0.058236 0.998303 +0.000000 0.058236 0.998303 +-1.000000 -0.000129 0.000000 +-1.000000 -0.000129 0.000000 +-1.000000 -0.000129 0.000000 +-1.000000 -0.000131 0.000009 +-1.000000 -0.000131 0.000009 +-1.000000 -0.000131 0.000009 +-0.000000 -0.151961 -0.988386 +-0.000000 -0.151961 -0.988386 +-0.000000 -0.151961 -0.988386 +0.000057 -0.151933 -0.988391 +0.000057 -0.151933 -0.988391 +0.000057 -0.151933 -0.988391 +1.000000 -0.000179 0.000098 +1.000000 -0.000179 0.000098 +1.000000 -0.000179 0.000098 +1.000000 -0.000153 0.000010 +1.000000 -0.000153 0.000010 +1.000000 -0.000153 0.000010 +-0.000057 0.151980 0.988384 +-0.000057 0.151980 0.988384 +-0.000057 0.151980 0.988384 +0.000000 0.151954 0.988388 +0.000000 0.151954 0.988388 +0.000000 0.151954 0.988388 +-1.000000 -0.000177 0.000012 +-1.000000 -0.000177 0.000012 +-1.000000 -0.000177 0.000012 +-1.000000 -0.000169 -0.000013 +-1.000000 -0.000169 -0.000013 +-1.000000 -0.000169 -0.000013 +0.000051 -0.932015 -0.362419 +0.000051 -0.932015 -0.362419 +0.000051 -0.932015 -0.362419 +0.000090 -0.932029 -0.362384 +0.000090 -0.932029 -0.362384 +0.000090 -0.932029 -0.362384 +1.000000 -0.000065 0.000236 +1.000000 -0.000065 0.000236 +1.000000 -0.000065 0.000236 +1.000000 -0.000015 0.000324 +1.000000 -0.000015 0.000324 +1.000000 -0.000015 0.000324 +-0.000049 0.919968 0.391994 +-0.000049 0.919968 0.391994 +-0.000049 0.919968 0.391994 +-0.000144 0.919991 0.391938 +-0.000144 0.919991 0.391938 +-0.000144 0.919991 0.391938 +-1.000000 -0.000520 0.000422 +-1.000000 -0.000520 0.000422 +-1.000000 -0.000520 0.000422 +-1.000000 -0.000255 0.000891 +-1.000000 -0.000255 0.000891 +-1.000000 -0.000255 0.000891 +0.000055 -0.999401 -0.034613 +0.000055 -0.999401 -0.034613 +0.000055 -0.999401 -0.034613 +0.000265 -0.999396 -0.034762 +0.000265 -0.999396 -0.034762 +0.000265 -0.999396 -0.034762 +0.999998 -0.000326 0.001713 +0.999999 -0.000326 0.001713 +0.999999 -0.000326 0.001713 +0.999999 0.000587 0.001197 +0.999999 0.000587 0.001197 +0.999999 0.000587 0.001197 +-0.000054 0.999797 0.020164 +-0.000054 0.999797 0.020164 +-0.000054 0.999797 0.020164 +-0.000215 0.999795 0.020250 +-0.000215 0.999795 0.020250 +-0.000215 0.999795 0.020250 +-0.999999 -0.000370 0.001405 +-0.999999 -0.000370 0.001405 +-0.999999 -0.000370 0.001405 +-0.999999 0.000018 0.001185 +-0.999999 0.000018 0.001185 +-0.999999 0.000018 0.001185 +0.000292 -0.891051 0.453904 +0.000292 -0.891051 0.453904 +0.000292 -0.891051 0.453904 +0.000215 -0.891008 0.453988 +0.000215 -0.891008 0.453988 +0.000215 -0.891008 0.453988 +1.000000 0.000085 -0.000786 +1.000000 0.000085 -0.000786 +1.000000 0.000085 -0.000786 +1.000000 -0.000067 -0.000372 +1.000000 -0.000067 -0.000372 +1.000000 -0.000067 -0.000372 +-0.000214 0.887579 -0.460655 +-0.000214 0.887579 -0.460655 +-0.000214 0.887579 -0.460655 +-0.000216 0.887580 -0.460654 +-0.000216 0.887580 -0.460654 +-0.000216 0.887580 -0.460654 +-1.000000 -0.000497 -0.000195 +-1.000000 -0.000497 -0.000195 +-1.000000 -0.000497 -0.000195 +-1.000000 -0.000399 -0.000463 +-1.000000 -0.000399 -0.000463 +-1.000000 -0.000399 -0.000463 +0.000032 -0.588033 0.808837 +0.000032 -0.588033 0.808837 +0.000032 -0.588033 0.808837 +0.000222 -0.587847 0.808972 +0.000222 -0.587847 0.808972 +0.000222 -0.587847 0.808972 +0.999997 -0.001670 -0.001992 +0.999997 -0.001670 -0.001992 +0.999997 -0.001670 -0.001992 +0.999994 -0.002753 -0.001912 +0.999994 -0.002753 -0.001912 +0.999994 -0.002753 -0.001912 +-0.000033 0.594535 -0.804070 +-0.000033 0.594535 -0.804070 +-0.000033 0.594535 -0.804070 +-0.000222 0.594384 -0.804181 +-0.000222 0.594384 -0.804181 +-0.000222 0.594384 -0.804181 +-0.999997 -0.001738 -0.001449 +-0.999997 -0.001738 -0.001449 +-0.999997 -0.001738 -0.001449 +-0.999997 -0.002053 -0.001426 +-0.999997 -0.002053 -0.001426 +-0.999997 -0.002053 -0.001426 +-0.000000 -0.547796 0.836612 +-0.000000 -0.547796 0.836612 +-0.000000 -0.547796 0.836612 +0.000029 -0.547792 0.836615 +0.000029 -0.547792 0.836615 +0.000029 -0.547792 0.836615 +1.000000 -0.000013 -0.000009 +1.000000 -0.000013 -0.000009 +1.000000 -0.000013 -0.000009 +1.000000 -0.000014 -0.000009 +1.000000 -0.000014 -0.000009 +1.000000 -0.000014 -0.000009 +0.000000 0.547819 -0.836597 +0.000000 0.547819 -0.836597 +0.000000 0.547819 -0.836597 +-0.000030 0.547816 -0.836599 +-0.000030 0.547816 -0.836599 +-0.000030 0.547816 -0.836599 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000056 -0.238289 -0.971194 +0.000056 -0.238289 -0.971194 +0.000056 -0.238289 -0.971194 +-0.000013 -0.238353 -0.971179 +-0.000013 -0.238353 -0.971179 +-0.000013 -0.238353 -0.971179 +1.000000 -0.000089 0.000077 +1.000000 -0.000089 0.000077 +1.000000 -0.000089 0.000077 +1.000000 -0.000108 0.000065 +1.000000 -0.000108 0.000065 +1.000000 -0.000108 0.000065 +-0.000056 0.269463 0.963011 +-0.000056 0.269463 0.963011 +-0.000056 0.269463 0.963011 +0.000014 0.269513 0.962997 +0.000014 0.269513 0.962997 +0.000014 0.269513 0.962997 +-1.000000 0.000179 -0.000107 +-1.000000 0.000179 -0.000107 +-1.000000 0.000179 -0.000107 +-1.000000 0.000192 -0.000099 +-1.000000 0.000192 -0.000099 +-1.000000 0.000192 -0.000099 +-0.000029 -0.541324 -0.840814 +-0.000029 -0.541324 -0.840814 +-0.000029 -0.541324 -0.840814 +0.000120 -0.541108 -0.840953 +0.000120 -0.541108 -0.840953 +0.000120 -0.541108 -0.840953 +1.000000 0.000398 -0.000238 +1.000000 0.000398 -0.000238 +1.000000 0.000398 -0.000238 +1.000000 0.000360 -0.000237 +1.000000 0.000360 -0.000237 +1.000000 0.000360 -0.000237 +0.000031 0.575404 0.817870 +0.000031 0.575404 0.817870 +0.000031 0.575404 0.817870 +-0.000157 0.575229 0.817992 +-0.000157 0.575229 0.817992 +-0.000157 0.575229 0.817992 +-1.000000 0.000489 -0.000703 +-1.000000 0.000489 -0.000703 +-1.000000 0.000489 -0.000703 +-0.999999 0.001203 -0.000719 +-0.999999 0.001203 -0.000719 +-0.999999 0.001203 -0.000719 +0.999282 -0.034750 -0.015064 +0.999282 -0.034750 -0.015064 +0.999282 -0.034750 -0.015064 +0.999367 -0.035523 -0.002042 +0.999367 -0.035523 -0.002042 +0.999367 -0.035523 -0.002042 +0.999727 -0.023366 0.000609 +0.999727 -0.023366 0.000609 +0.999727 -0.023366 0.000609 +0.999727 -0.023280 0.001817 +0.999727 -0.023280 0.001817 +0.999727 -0.023280 0.001817 +-0.999728 -0.023266 0.001751 +-0.999728 -0.023266 0.001751 +-0.999728 -0.023266 0.001751 +-0.999727 -0.023348 0.000613 +-0.999727 -0.023348 0.000613 +-0.999727 -0.023348 0.000613 +-0.999367 -0.035523 -0.002042 +-0.999367 -0.035523 -0.002042 +-0.999367 -0.035523 -0.002042 +-0.999281 -0.034743 -0.015193 +-0.999281 -0.034743 -0.015193 +-0.999281 -0.034743 -0.015193 +0.000000 0.999882 0.015389 +0.000000 0.999882 0.015389 +0.000000 0.999882 0.015389 +0.000000 0.999882 0.015389 +0.000000 0.999882 0.015389 +0.000000 0.999882 0.015389 +0.000000 0.128557 -0.991702 +0.000000 0.128557 -0.991702 +0.000000 0.128557 -0.991702 +0.000000 0.128557 -0.991702 +0.000000 0.128557 -0.991702 +0.000000 0.128557 -0.991702 +0.000000 0.317775 -0.948166 +0.000000 0.317775 -0.948166 +0.000000 0.317775 -0.948166 +0.000000 0.317775 -0.948166 +0.000000 0.317775 -0.948166 +0.000000 0.317775 -0.948166 +0.000000 -0.931173 -0.364577 +0.000000 -0.931173 -0.364577 +0.000000 -0.931173 -0.364577 +0.000000 -0.931173 -0.364577 +0.000000 -0.931173 -0.364577 +0.000000 -0.931173 -0.364577 +0.000000 -0.402066 0.915611 +0.000000 -0.402066 0.915611 +0.000000 -0.402066 0.915611 +0.000000 -0.402066 0.915611 +0.000000 -0.402066 0.915611 +0.000000 -0.402066 0.915611 +0.000000 -0.218768 0.975777 +0.000000 -0.218768 0.975777 +0.000000 -0.218768 0.975777 +-0.000000 -0.218768 0.975777 +-0.000000 -0.218768 0.975777 +-0.000000 -0.218768 0.975777 + + + + + + + + + + + +0.093513 0.445266 +0.093513 0.398749 +0.121630 0.398749 +0.121630 0.445266 +0.093513 0.491320 +0.121630 0.491320 +0.093513 0.536619 +0.121630 0.536619 +0.093513 0.580952 +0.121630 0.580952 +0.093513 0.624189 +0.121630 0.624189 +0.093513 0.666219 +0.121630 0.666219 +0.093513 0.706882 +0.121630 0.706882 +0.093513 0.745968 +0.121630 0.745968 +0.093513 0.783496 +0.121630 0.783496 +0.093513 0.043258 +0.093513 0.003616 +0.121630 0.003616 +0.121630 0.043258 +0.093513 0.084259 +0.121630 0.084259 +0.093513 0.126597 +0.121630 0.126597 +0.093513 0.170074 +0.121630 0.170074 +0.093513 0.214474 +0.121630 0.214474 +0.093513 0.259712 +0.121630 0.259712 +0.093513 0.305657 +0.121630 0.305657 +0.093513 0.352101 +0.121630 0.352101 +0.093513 0.445266 +0.093513 0.398749 +0.121630 0.398749 +0.121630 0.445266 +0.093513 0.491320 +0.121630 0.491320 +0.093513 0.536619 +0.121630 0.536619 +0.093513 0.580952 +0.121630 0.580952 +0.093513 0.624189 +0.121630 0.624189 +0.093513 0.666219 +0.121630 0.666219 +0.093513 0.706882 +0.121630 0.706882 +0.093513 0.745968 +0.121630 0.745968 +0.093513 0.783496 +0.121630 0.783496 +0.093513 0.043258 +0.093513 0.003616 +0.121630 0.003616 +0.121630 0.043258 +0.093513 0.084259 +0.121630 0.084259 +0.093513 0.126597 +0.121630 0.126597 +0.093513 0.170074 +0.121630 0.170074 +0.093513 0.214474 +0.121630 0.214474 +0.093513 0.259712 +0.121630 0.259712 +0.093513 0.305657 +0.121630 0.305657 +0.093513 0.352101 +0.121630 0.352101 +0.826497 0.683519 +0.826497 0.668769 +0.835791 0.668769 +0.835791 0.683519 +0.826497 0.654474 +0.835791 0.654474 +0.826497 0.640550 +0.835791 0.640550 +0.826497 0.626993 +0.835791 0.626993 +0.826497 0.613868 +0.835791 0.613868 +0.826497 0.600776 +0.835791 0.600776 +0.826497 0.587338 +0.835791 0.587338 +0.826497 0.573639 +0.835791 0.573639 +0.826497 0.559820 +0.835791 0.559820 +0.826497 0.807218 +0.826497 0.793395 +0.835791 0.793395 +0.835791 0.807218 +0.826497 0.779694 +0.835791 0.779694 +0.826497 0.766255 +0.835791 0.766255 +0.826497 0.753164 +0.835791 0.753164 +0.826497 0.740045 +0.835791 0.740045 +0.826497 0.726500 +0.835791 0.726500 +0.826497 0.712580 +0.835791 0.712580 +0.826497 0.698276 +0.835791 0.698276 +0.826497 0.683519 +0.826497 0.668769 +0.835791 0.668769 +0.835791 0.683519 +0.826497 0.654474 +0.835791 0.654474 +0.826497 0.640550 +0.835791 0.640550 +0.826497 0.626993 +0.835791 0.626993 +0.826497 0.613868 +0.835791 0.613868 +0.826497 0.600776 +0.835791 0.600776 +0.826497 0.587338 +0.835791 0.587338 +0.826497 0.573639 +0.835791 0.573639 +0.826497 0.559820 +0.835791 0.559820 +0.826497 0.807218 +0.826497 0.793395 +0.835791 0.793395 +0.835791 0.807218 +0.826497 0.779694 +0.835791 0.779694 +0.826497 0.766255 +0.835791 0.766255 +0.826497 0.753164 +0.835791 0.753164 +0.826497 0.740045 +0.835791 0.740045 +0.826497 0.726500 +0.835791 0.726500 +0.826497 0.712580 +0.835791 0.712580 +0.826497 0.698276 +0.835791 0.698276 +1.000000 0.000000 +0.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.500000 0.000000 +0.500000 0.000000 +0.500000 1.000000 +0.500000 1.000000 +0.750000 1.000000 +0.750000 0.000000 +0.250000 0.000000 +0.250000 1.000000 +0.750000 0.000000 +0.250000 0.000000 +0.250000 1.000000 +0.750000 1.000000 +0.875000 1.000000 +0.875000 0.000000 +0.125000 0.000000 +0.125000 1.000000 +0.875000 0.000000 +0.125000 0.000000 +0.125000 1.000000 +0.875000 1.000000 +0.875000 1.000000 +0.750000 1.000000 +0.250000 1.000000 +0.250000 0.000000 +0.125000 0.500000 +0.500000 0.500000 +0.250000 0.500000 +0.125000 0.500000 +0.593750 1.000000 +0.593750 0.000000 +0.500000 0.500000 +0.625000 0.708800 +0.625000 0.291200 +0.562500 0.708800 +0.562500 0.291200 +0.250000 1.000000 +0.250000 0.000000 +0.250000 1.000000 +0.250000 0.000000 +0.250000 1.000000 +0.250000 1.000000 +0.250000 1.000000 +0.500000 1.000000 +0.000000 1.000000 +0.625000 0.291200 +0.750000 0.000000 +0.250000 0.000000 +0.406250 0.000000 +0.250000 0.000000 +0.250000 0.500000 +0.250000 0.000000 +0.250000 1.000000 +0.125000 0.500000 +0.250000 0.000000 +0.250000 1.000000 +0.500000 0.750000 +0.500000 0.500000 +0.125000 0.500000 +0.250000 0.500000 +0.625000 0.500000 +0.203125 0.343750 +0.703125 1.000000 +0.125000 0.500000 +0.125000 0.127982 +0.125000 0.255963 +0.125000 0.250000 +0.125000 0.500000 +0.125000 0.255963 +0.125000 0.127982 +0.125000 0.250000 +0.171405 0.677520 +0.100895 0.959563 +0.090556 0.637775 +0.090556 0.637775 +0.129305 0.413608 +0.129305 0.358834 +0.129305 0.413608 +0.625000 0.708800 +0.625000 0.291200 +0.562500 0.291200 +0.562500 0.708800 +0.494699 0.741503 +0.438042 0.780345 +0.436228 0.250657 +0.496591 0.251554 +1.000000 0.000000 +1.000000 1.000000 +0.875000 1.000000 +0.875000 0.000000 +0.000000 0.000000 +0.125000 0.000000 +0.125000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +0.125000 0.000000 +0.125000 0.500000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +0.593750 0.000000 +0.500000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.593750 1.000000 +0.000000 1.000000 +0.000000 0.000000 +0.500000 0.500000 +0.500000 0.000000 +1.000000 0.000000 +1.000000 1.000000 +0.500000 1.000000 +0.500000 0.000000 +1.000000 0.000000 +1.000000 1.000000 +0.500000 0.500000 +0.750000 1.000000 +0.625000 0.708800 +0.625000 0.291200 +0.750000 0.000000 +0.250000 0.000000 +0.250000 0.500000 +0.750000 0.000000 +0.875000 0.000000 +0.875000 1.000000 +0.750000 1.000000 +1.000000 0.000000 +1.000000 1.000000 +0.875000 1.000000 +0.750000 1.000000 +0.250000 0.000000 +0.250000 1.000000 +0.250000 1.000000 +0.250000 0.000000 +0.125000 0.500000 +0.125000 1.000000 +0.250000 0.500000 +0.125000 0.500000 +0.250000 1.000000 +0.250000 1.000000 +0.562500 0.291200 +0.562500 0.708800 +0.250000 1.000000 +0.250000 0.000000 +0.250000 1.000000 +0.250000 0.000000 +0.250000 1.000000 +0.250000 0.000000 +0.250000 1.000000 +0.250000 1.000000 +0.250000 0.000000 +0.250000 0.000000 +0.250000 1.000000 +0.500000 0.750000 +0.500000 1.000000 +0.000000 1.000000 +0.500000 0.500000 +0.250000 0.500000 +0.625000 0.500000 +0.203125 0.343750 +0.703125 1.000000 +0.171405 0.677520 +0.100895 0.959563 +0.125000 0.500000 +0.125000 0.255963 +0.125000 0.127982 +0.125000 0.127982 +0.125000 0.255963 +0.125000 0.250000 +0.129305 0.413608 +0.129305 0.413608 +0.125000 0.250000 +0.090556 0.637775 +0.125000 0.500000 +0.125000 0.500000 +0.090556 0.637775 +0.129305 0.358834 +0.250000 0.000000 +0.406250 0.000000 +0.625000 0.291200 +0.750000 0.000000 +0.625000 0.708800 +0.625000 0.291200 +0.562500 0.291200 +0.562500 0.708800 +0.436228 0.250657 +0.496591 0.251554 +0.494699 0.741503 +0.438042 0.780345 +1.000000 0.000000 +0.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +1.000000 0.000000 +0.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.377324 0.003499 +0.361808 0.765063 +0.320989 0.765121 +0.303297 0.003605 +0.395489 0.003764 +0.469515 0.003799 +0.452554 0.765055 +0.411736 0.765036 +0.219929 0.004120 +0.209604 0.765772 +0.189226 0.766048 +0.176937 0.004702 +0.014284 0.902757 +0.055101 0.902876 +0.055042 0.923257 +0.014224 0.923138 +0.251390 0.766650 +0.241336 0.004994 +0.284328 0.005591 +0.271768 0.766933 +0.479330 0.459887 +0.487364 0.459887 +0.479330 0.526656 +0.487364 0.526656 +0.501809 0.459887 +0.501809 0.526656 +0.515050 0.459887 +0.515050 0.526656 +0.528874 0.459887 +0.528874 0.526656 +0.479330 0.572027 +0.487364 0.572027 +0.501809 0.572027 +0.515050 0.572027 +0.528874 0.572027 +0.479330 0.609095 +0.487364 0.609095 +0.479330 0.631422 +0.487364 0.631422 +0.501809 0.609095 +0.501809 0.631422 +0.515050 0.609095 +0.515050 0.631422 +0.528874 0.609095 +0.528874 0.631422 +0.479330 0.651815 +0.487364 0.651815 +0.501809 0.651815 +0.515050 0.651815 +0.528874 0.651815 +0.479330 0.668167 +0.487364 0.668167 +0.501809 0.668167 +0.515050 0.668167 +0.528874 0.668167 +0.479330 0.685906 +0.487364 0.685906 +0.501809 0.685906 +0.515050 0.685906 +0.528874 0.685906 +0.479330 0.777451 +0.487364 0.777451 +0.501809 0.777451 +0.515050 0.777451 +0.528874 0.777451 +0.479330 0.595957 +0.487364 0.595957 +0.501809 0.595957 +0.515050 0.595957 +0.528874 0.595957 +0.479330 0.391526 +0.487364 0.391526 +0.501809 0.391526 +0.515050 0.391526 +0.528874 0.391526 +0.479330 0.342195 +0.528874 0.342195 +0.487364 0.342195 +0.501809 0.342195 +0.515050 0.342195 +0.479330 0.297630 +0.479330 0.267134 +0.487364 0.297630 +0.501809 0.297630 +0.515050 0.297630 +0.528874 0.267134 +0.528874 0.297630 +0.487364 0.267134 +0.501809 0.267134 +0.515050 0.267134 +0.479330 0.227220 +0.528874 0.227220 +0.487364 0.227220 +0.501809 0.227220 +0.515050 0.227220 +0.479330 0.200766 +0.487364 0.200766 +0.501809 0.200766 +0.515050 0.200766 +0.528874 0.200766 +0.479330 0.177595 +0.487364 0.177595 +0.501809 0.177595 +0.515050 0.177595 +0.528874 0.177595 +0.479330 0.002954 +0.487364 0.002954 +0.501809 0.002954 +0.515050 0.002954 +0.528874 0.002954 +0.479330 0.314183 +0.487364 0.314183 +0.501809 0.314183 +0.515050 0.314183 +0.528874 0.314183 +0.182082 0.911611 +0.182594 0.927989 +0.152534 0.933244 +0.096470 0.943464 +0.151807 0.908221 +0.095169 0.901475 +0.181947 0.917439 +0.151927 0.916785 +0.096404 0.916062 +0.096807 0.928846 +0.152119 0.924684 +0.182103 0.922166 + + + + + + + + + + +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 + + + + + + + + + + + + + +

2 0 2 2 3 1 3 3 0 2 0 0 2 3 2 2 0 4 0 0 1 5 1 1 3 6 3 3 5 7 5 5 4 8 4 4 3 9 3 3 4 10 4 4 0 11 0 0 5 12 5 5 6 13 6 6 4 14 4 4 6 15 6 6 5 16 5 5 7 17 7 7 7 18 7 7 8 19 8 8 6 20 6 6 8 21 8 8 7 22 7 7 9 23 9 9 9 24 9 9 10 25 10 10 8 26 8 8 10 27 10 10 9 28 9 9 11 29 11 11 11 30 11 11 12 31 12 12 10 32 10 10 12 33 12 12 11 34 11 11 13 35 13 13 13 36 13 13 14 37 14 14 12 38 12 12 14 39 14 14 13 40 13 13 15 41 15 15 14 42 14 14 15 43 15 15 16 44 16 16 16 45 16 16 15 46 15 15 17 47 17 17 16 48 16 16 17 49 17 17 18 50 18 18 18 51 18 18 17 52 17 17 19 53 19 19 18 54 21 18 19 55 22 19 20 56 20 20 20 57 20 20 19 58 22 19 21 59 23 21 20 60 20 20 21 61 23 21 22 62 24 22 22 63 24 22 21 64 23 21 23 65 25 23 22 66 24 22 25 67 27 25 24 68 26 24 25 69 27 25 22 70 24 22 23 71 25 23 27 72 29 27 24 73 26 24 25 74 27 25 24 75 26 24 27 76 29 27 26 77 28 26 29 78 31 29 28 79 30 28 27 80 29 27 28 81 30 28 26 82 28 26 27 83 29 27 31 84 33 31 30 85 32 30 29 86 31 29 30 87 32 30 28 88 30 28 29 89 31 29 30 90 32 30 33 91 35 33 32 92 34 32 33 93 35 33 30 94 32 30 31 95 33 31 35 96 37 35 32 97 34 32 33 98 35 33 32 99 34 32 35 100 37 35 34 101 36 34 2 102 2 2 34 103 36 34 35 104 37 35 34 105 36 34 2 106 2 2 1 107 1 1 28 108 28 28 24 109 24 24 26 110 26 26 24 111 24 24 28 112 28 28 30 113 30 30 32 114 32 32 24 115 24 24 30 116 30 30 32 117 32 32 22 118 22 22 24 119 24 24 34 120 34 34 22 121 22 22 32 122 32 32 34 123 34 34 20 124 20 20 22 125 22 22 34 126 34 34 18 127 18 18 20 128 20 20 18 129 18 18 34 130 34 34 1 131 1 1 1 132 1 1 16 133 16 16 18 134 18 18 16 135 16 16 1 136 1 1 0 137 0 0 4 138 4 4 16 139 16 16 0 140 0 0 16 141 16 16 4 142 4 4 14 143 14 14 4 144 4 4 12 145 12 12 14 146 14 14 12 147 12 12 4 148 4 4 6 149 6 6 6 150 6 6 10 151 10 10 12 152 12 12 10 153 10 10 6 154 6 6 8 155 8 8 7 156 7 7 11 157 11 11 9 158 9 9 7 159 7 7 13 160 13 13 11 161 11 11 5 162 5 5 13 163 13 13 7 164 7 7 5 165 5 5 15 166 15 15 13 167 13 13 3 168 3 3 15 169 15 15 5 170 5 5 3 171 3 3 17 172 17 17 15 173 15 15 3 174 3 3 19 175 19 19 17 176 17 17 19 177 19 19 3 178 3 3 2 179 2 2 35 180 35 35 19 181 19 19 2 182 2 2 19 183 19 19 35 184 35 35 21 185 21 21 33 186 33 33 21 187 21 21 35 188 35 35 21 189 21 21 33 190 33 33 23 191 23 23 33 192 33 33 25 193 25 25 23 194 23 23 25 195 25 25 33 196 33 33 31 197 31 31 25 198 25 25 31 199 31 31 29 200 29 29 25 201 25 25 29 202 29 29 27 203 27 27 37 204 39 37 36 205 38 36 38 206 40 38 36 207 38 36 39 208 41 39 38 209 40 38 36 210 38 36 40 211 42 40 39 212 41 39 40 213 42 40 41 214 43 41 39 215 41 39 41 216 43 41 40 217 42 40 42 218 44 42 41 219 43 41 42 220 44 42 43 221 45 43 43 222 45 43 42 223 44 42 44 224 46 44 43 225 45 43 44 226 46 44 45 227 47 45 45 228 47 45 44 229 46 44 46 230 48 46 45 231 47 45 46 232 48 46 47 233 49 47 47 234 49 47 46 235 48 46 48 236 50 48 47 237 49 47 48 238 50 48 49 239 51 49 49 240 51 49 48 241 50 48 50 242 52 50 49 243 51 49 50 244 52 50 51 245 53 51 51 246 53 51 52 247 54 52 53 248 55 53 52 249 54 52 51 250 53 51 50 251 52 50 53 252 55 53 54 253 56 54 55 254 57 55 54 255 56 54 53 256 55 53 52 257 54 52 55 258 60 55 56 259 58 56 57 260 61 57 56 261 58 56 55 262 60 55 54 263 59 54 57 264 61 57 58 265 62 58 59 266 63 59 58 267 62 58 57 268 61 57 56 269 58 56 61 270 65 61 58 271 62 58 60 272 64 60 58 273 62 58 61 274 65 61 59 275 63 59 63 276 67 63 60 277 64 60 62 278 66 62 60 279 64 60 63 280 67 63 61 281 65 61 65 282 69 65 63 283 67 63 64 284 68 64 64 285 68 64 63 286 67 63 62 287 66 62 67 288 71 67 65 289 69 65 66 290 70 66 66 291 70 66 65 292 69 65 64 293 68 64 69 294 73 69 66 295 70 66 68 296 72 68 66 297 70 66 69 298 73 69 67 299 71 67 68 300 72 68 71 301 75 71 69 302 73 69 71 303 75 71 68 304 72 68 70 305 74 70 70 306 74 70 38 307 40 38 71 308 75 71 38 309 40 38 70 310 74 70 37 311 39 37 64 312 66 64 60 313 62 60 66 314 68 66 60 315 62 60 64 316 66 64 62 317 64 62 60 318 62 60 68 319 70 68 66 320 68 66 58 321 60 58 68 322 70 68 60 323 62 60 58 324 60 58 70 325 72 70 68 326 70 68 56 327 58 56 70 328 72 70 58 329 60 58 70 330 72 70 54 331 56 54 37 332 39 37 54 333 56 54 70 334 72 70 56 335 58 56 37 336 39 37 52 337 54 52 36 338 38 36 52 339 54 52 37 340 39 37 54 341 56 54 36 342 38 36 52 343 54 52 40 344 42 40 40 345 42 40 52 346 54 52 50 347 52 50 40 348 42 40 48 349 50 48 42 350 44 42 48 351 50 48 40 352 42 40 50 353 52 50 42 354 44 42 46 355 48 46 44 356 46 44 46 357 48 46 42 358 44 42 48 359 50 48 47 360 49 47 43 361 45 43 45 362 47 45 49 363 51 49 43 364 45 43 47 365 49 47 49 366 51 49 41 367 43 41 43 368 45 43 51 369 53 51 41 370 43 41 49 371 51 49 51 372 53 51 39 373 41 39 41 374 43 41 53 375 55 53 39 376 41 39 51 377 53 51 39 378 41 39 55 379 57 55 38 380 40 38 55 381 57 55 39 382 41 39 53 383 55 53 38 384 40 38 55 385 57 55 71 386 73 71 71 387 73 71 55 388 57 55 57 389 59 57 71 390 73 71 57 391 59 57 69 392 71 69 69 393 71 69 57 394 59 57 59 395 61 59 69 396 71 69 61 397 63 61 67 398 69 67 61 399 63 61 69 400 71 69 59 401 61 59 67 402 69 67 61 403 63 61 65 404 67 65 65 405 67 65 61 406 63 61 63 407 65 63 74 408 78 74 72 409 76 72 75 410 79 75 72 411 76 72 74 412 78 74 73 413 77 73 77 414 81 77 73 415 77 73 74 416 78 74 73 417 77 73 77 418 81 77 76 419 80 76 76 420 80 76 77 421 81 77 79 422 83 79 76 423 80 76 79 424 83 79 78 425 82 78 81 426 85 81 78 427 82 78 79 428 83 79 78 429 82 78 81 430 85 81 80 431 84 80 83 432 87 83 80 433 84 80 81 434 85 81 80 435 84 80 83 436 87 83 82 437 86 82 82 438 86 82 83 439 87 83 85 440 89 85 82 441 86 82 85 442 89 85 84 443 88 84 84 444 88 84 85 445 89 85 87 446 91 87 84 447 88 84 87 448 91 87 86 449 90 86 89 450 93 89 88 451 92 88 86 452 90 86 86 453 90 86 87 454 91 87 89 455 93 89 91 456 95 91 90 457 94 90 88 458 92 88 88 459 92 88 89 460 93 89 91 461 95 91 93 462 98 93 92 463 97 92 90 464 96 90 90 465 96 90 91 466 99 91 93 467 98 93 95 468 101 95 94 469 100 94 92 470 97 92 92 471 97 92 93 472 98 93 95 473 101 95 97 474 103 97 96 475 102 96 94 476 100 94 97 477 103 97 94 478 100 94 95 479 101 95 99 480 105 99 98 481 104 98 96 482 102 96 99 483 105 99 96 484 102 96 97 485 103 97 101 486 107 101 100 487 106 100 98 488 104 98 101 489 107 101 98 490 104 98 99 491 105 99 103 492 109 103 102 493 108 102 100 494 106 100 103 495 109 103 100 496 106 100 101 497 107 101 105 498 111 105 104 499 110 104 102 500 108 102 105 501 111 105 102 502 108 102 103 503 109 103 107 504 113 107 104 505 110 104 105 506 111 105 104 507 110 104 107 508 113 107 106 509 112 106 75 510 79 75 106 511 112 106 107 512 113 107 106 513 112 106 75 514 79 75 72 515 76 72 101 516 105 101 97 517 101 97 103 518 107 103 97 519 101 97 101 520 105 101 99 521 103 99 97 522 101 97 105 523 109 105 103 524 107 103 95 525 99 95 105 526 109 105 97 527 101 97 105 528 109 105 93 529 97 93 107 530 111 107 93 531 97 93 105 532 109 105 95 533 99 95 107 534 111 107 91 535 95 91 75 536 79 75 91 537 95 91 107 538 111 107 93 539 97 93 75 540 79 75 91 541 95 91 74 542 78 74 74 543 78 74 91 544 95 91 89 545 93 89 74 546 78 74 87 547 91 87 77 548 81 77 87 549 91 87 74 550 78 74 89 551 93 89 77 552 81 77 87 553 91 87 79 554 83 79 79 555 83 79 87 556 91 87 85 557 89 85 79 558 83 79 85 559 89 85 81 560 85 81 81 561 85 81 85 562 89 85 83 563 87 83 80 564 84 80 84 565 88 84 78 566 82 78 84 567 88 84 80 568 84 80 82 569 86 82 84 570 88 84 76 571 80 76 78 572 82 78 86 573 90 86 76 574 80 76 84 575 88 84 76 576 80 76 88 577 92 88 73 578 77 73 88 579 92 88 76 580 80 76 86 581 90 86 73 582 77 73 90 583 94 90 72 584 76 72 90 585 94 90 73 586 77 73 88 587 92 88 72 588 76 72 90 589 94 90 106 590 110 106 106 591 110 106 90 592 94 90 92 593 96 92 106 594 110 106 92 595 96 92 104 596 108 104 104 597 108 104 92 598 96 92 94 599 98 94 104 600 108 104 96 601 100 96 102 602 106 102 96 603 100 96 104 604 108 104 94 605 98 94 102 606 106 102 96 607 100 96 100 608 104 100 100 609 104 100 96 610 100 96 98 611 102 98 110 612 116 110 108 613 114 108 109 614 115 109 108 615 114 108 110 616 116 110 111 617 117 111 112 618 118 112 113 619 119 113 109 620 115 109 109 621 115 109 113 622 119 113 110 623 116 110 114 624 120 114 115 625 121 115 112 626 118 112 113 627 119 113 112 628 118 112 115 629 121 115 116 630 122 116 117 631 123 117 114 632 120 114 115 633 121 115 114 634 120 114 117 635 123 117 118 636 124 118 119 637 125 119 116 638 122 116 117 639 123 117 116 640 122 116 119 641 125 119 120 642 126 120 121 643 127 121 118 644 124 118 119 645 125 119 118 646 124 118 121 647 127 121 122 648 128 122 123 649 129 123 120 650 126 120 121 651 127 121 120 652 126 120 123 653 129 123 123 654 129 123 122 655 128 122 125 656 131 125 125 657 131 125 122 658 128 122 124 659 130 124 125 660 131 125 124 661 130 124 127 662 133 127 127 663 133 127 124 664 130 124 126 665 132 126 127 666 137 127 126 667 134 126 129 668 136 129 129 669 136 129 126 670 134 126 128 671 135 128 129 672 136 129 128 673 135 128 131 674 139 131 131 675 139 131 128 676 135 128 130 677 138 130 133 678 141 133 130 679 138 130 132 680 140 132 130 681 138 130 133 682 141 133 131 683 139 131 135 684 143 135 132 685 140 132 134 686 142 134 132 687 140 132 135 688 143 135 133 689 141 133 137 690 145 137 134 691 142 134 136 692 144 136 134 693 142 134 137 694 145 137 135 695 143 135 139 696 147 139 136 697 144 136 138 698 146 138 136 699 144 136 139 700 147 139 137 701 145 137 141 702 149 141 138 703 146 138 140 704 148 140 138 705 146 138 141 706 149 141 139 707 147 139 142 708 150 142 143 709 151 143 140 710 148 140 140 711 148 140 143 712 151 143 141 713 149 141 111 714 117 111 142 715 150 142 108 716 114 108 142 717 150 142 111 718 117 111 143 719 151 143 137 720 143 137 133 721 139 133 135 722 141 135 133 723 139 133 137 724 143 137 139 725 145 139 141 726 147 141 133 727 139 133 139 728 145 139 141 729 147 141 131 730 137 131 133 731 139 133 141 732 147 141 129 733 135 129 131 734 137 131 129 735 135 129 141 736 147 141 143 737 149 143 143 738 149 143 127 739 133 127 129 740 135 129 127 741 133 127 143 742 149 143 111 743 117 111 110 744 116 110 127 745 133 127 111 746 117 111 127 747 133 127 110 748 116 110 125 749 131 125 110 750 116 110 123 751 129 123 125 752 131 125 123 753 129 123 110 754 116 110 113 755 119 113 123 756 129 123 113 757 119 113 115 758 121 115 123 759 129 123 115 760 121 115 121 761 127 121 121 762 127 121 115 763 121 115 117 764 123 117 121 765 127 121 117 766 123 117 119 767 125 119 116 768 122 116 120 769 126 120 118 770 124 118 120 771 126 120 116 772 122 116 114 773 120 114 112 774 118 112 120 775 126 120 114 776 120 114 112 777 118 112 122 778 128 122 120 779 126 120 112 780 118 112 124 781 130 124 122 782 128 122 124 783 130 124 112 784 118 112 109 785 115 109 109 786 115 109 126 787 132 126 124 788 130 124 126 789 132 126 109 790 115 109 108 791 114 108 142 792 148 142 126 793 132 126 108 794 114 108 126 795 132 126 142 796 148 142 128 797 134 128 140 798 146 140 128 799 134 128 142 800 148 142 128 801 134 128 140 802 146 140 130 803 136 130 140 804 146 140 132 805 138 132 130 806 136 130 132 807 138 132 140 808 146 140 138 809 144 138 132 810 138 132 138 811 144 138 136 812 142 136 132 813 138 132 136 814 142 136 134 815 140 134 144 816 152 0 157 817 188 0 159 818 192 0 157 819 188 0 144 820 152 0 146 821 154 0 160 822 194 0 148 823 156 0 158 824 190 0 148 825 156 0 160 826 194 0 150 827 158 0 165 828 203 0 144 829 160 0 159 830 193 0 144 831 160 0 165 832 203 0 148 833 162 0 151 834 167 0 149 835 166 0 145 836 164 0 151 837 167 0 145 838 164 0 147 839 165 0 151 840 170 0 166 841 205 0 152 842 179 0 166 843 205 0 151 844 170 0 147 845 168 0 148 846 175 0 150 847 174 0 146 848 172 0 148 849 175 0 146 850 172 0 144 851 173 0 145 852 153 0 166 853 204 0 147 854 155 0 166 855 204 0 145 856 153 0 167 857 206 0 152 858 178 0 149 859 157 0 151 860 159 0 149 861 157 0 152 862 178 0 163 863 177 0 163 864 201 0 145 865 161 0 149 866 163 0 145 867 161 0 163 868 201 0 167 869 176 0 169 870 208 0 153 871 180 0 168 872 207 0 153 873 180 0 169 874 208 0 155 875 184 0 164 876 202 0 167 877 176 0 163 878 201 0 167 879 176 0 164 880 202 0 155 881 185 0 156 882 187 0 157 883 189 0 160 884 195 0 157 885 189 0 156 886 187 0 153 887 181 0 159 888 192 0 153 889 180 0 155 890 184 0 153 891 180 0 159 892 192 0 157 893 188 0 165 894 203 0 155 895 185 0 164 896 202 0 155 897 185 0 165 898 203 0 159 899 193 0 160 900 195 0 146 901 169 0 150 902 171 0 146 903 169 0 160 904 195 0 157 905 189 0 161 906 197 0 156 907 187 0 162 908 196 0 162 909 196 0 156 910 187 0 160 911 195 0 156 912 186 0 161 913 198 0 154 914 182 0 222 915 199 0 154 916 182 0 161 917 198 0 162 918 200 0 160 919 194 0 158 920 190 0 165 921 203 0 158 922 191 0 148 923 162 0 223 924 228 0 164 925 202 0 179 926 225 0 164 927 202 0 223 928 228 0 165 929 203 0 154 930 183 0 180 931 227 0 179 932 225 0 154 933 183 0 179 934 225 0 164 935 202 0 152 936 179 0 153 937 181 0 156 938 187 0 153 939 181 0 152 940 179 0 166 941 205 0 163 942 201 0 154 943 183 0 164 944 202 0 171 945 210 0 166 946 204 0 167 947 206 0 166 948 204 0 171 949 210 0 170 950 209 0 171 951 210 0 167 952 206 0 169 953 208 0 168 954 207 0 166 955 204 0 170 956 209 0 153 957 180 0 166 958 204 0 168 959 207 0 169 960 208 0 167 961 206 0 155 962 184 0 172 963 211 0 177 964 212 0 222 965 199 0 222 966 199 0 161 967 198 0 172 968 211 0 173 969 213 0 178 970 214 0 177 971 212 0 173 972 213 0 177 973 212 0 172 974 211 0 173 975 213 0 175 976 216 0 182 977 229 0 173 978 213 0 182 979 229 0 178 980 214 0 175 981 216 0 173 982 213 0 176 983 217 0 173 984 213 0 174 985 215 0 176 986 217 0 180 987 226 0 154 988 182 0 222 989 224 0 175 990 216 0 176 991 217 0 181 992 230 0 182 993 231 0 175 994 218 0 232 995 232 0 175 996 218 0 181 997 219 0 232 998 232 0 232 999 234 0 176 1000 198 0 370 1001 235 0 176 1002 198 0 232 1003 234 0 181 1004 219 0 165 1005 175 0 223 1006 237 0 158 1007 168 0 183 1008 236 0 158 1009 168 0 223 1010 237 0 162 1011 172 0 183 1012 247 0 233 1013 233 0 183 1014 247 0 162 1015 172 0 158 1016 246 0 187 1017 244 0 185 1018 239 0 186 1019 243 0 186 1020 243 0 185 1021 239 0 184 1022 240 0 191 1023 252 0 190 1024 250 0 185 1025 241 0 191 1026 252 0 185 1027 241 0 187 1028 245 0 189 1029 249 0 186 1030 242 0 184 1031 238 0 186 1032 242 0 189 1033 249 0 188 1034 248 0 190 1035 251 0 189 1036 249 0 184 1037 238 0 184 1038 238 0 185 1039 239 0 190 1040 251 0 190 1041 222 0 188 1042 220 0 189 1043 221 0 188 1044 220 0 190 1045 222 0 191 1046 223 0 187 1047 245 0 186 1048 243 0 188 1049 248 0 188 1050 248 0 191 1051 223 0 187 1052 245 0 193 1053 254 0 168 1054 207 0 192 1055 253 0 168 1056 207 0 193 1057 254 0 169 1058 208 0 195 1059 255 0 194 1060 256 0 170 1061 209 0 195 1062 255 0 170 1063 209 0 171 1064 210 0 195 1065 255 0 169 1066 208 0 193 1067 254 0 169 1068 208 0 195 1069 255 0 171 1070 210 0 192 1071 253 0 170 1072 209 0 194 1073 256 0 170 1074 209 0 192 1075 253 0 168 1076 207 0 154 1077 182 0 163 1078 177 0 193 1079 259 0 193 1080 259 0 163 1081 177 0 195 1082 260 0 163 1083 177 0 152 1084 178 0 195 1085 260 0 195 1086 260 0 152 1087 178 0 194 1088 257 0 152 1089 178 0 192 1090 258 0 194 1091 257 0 152 1092 178 0 156 1093 186 0 192 1094 258 0 156 1095 186 0 193 1096 259 0 192 1097 258 0 193 1098 259 0 156 1099 186 0 154 1100 182 0 197 1101 262 0 199 1102 264 0 198 1103 263 0 199 1104 264 0 197 1105 262 0 196 1106 261 0 200 1107 265 0 203 1108 268 0 201 1109 266 0 201 1110 266 0 203 1111 268 0 202 1112 267 0 204 1113 271 0 196 1114 269 0 200 1115 272 0 196 1116 269 0 204 1117 271 0 199 1118 270 0 207 1119 275 0 205 1120 273 0 208 1121 276 0 205 1122 273 0 207 1123 275 0 206 1124 274 0 207 1125 280 0 210 1126 279 0 209 1127 278 0 207 1128 280 0 209 1129 278 0 206 1130 277 0 200 1131 283 0 197 1132 281 0 203 1133 284 0 197 1134 281 0 200 1135 283 0 196 1136 282 0 209 1137 285 0 205 1138 287 0 206 1139 286 0 205 1140 287 0 209 1141 285 0 211 1142 288 0 208 1143 290 0 210 1144 292 0 207 1145 291 0 210 1146 292 0 208 1147 290 0 212 1148 289 0 212 1149 296 0 208 1150 295 0 205 1151 294 0 212 1152 296 0 205 1153 294 0 211 1154 293 0 213 1155 297 0 215 1156 299 0 214 1157 298 0 215 1158 299 0 213 1159 297 0 216 1160 300 0 217 1161 302 0 212 1162 296 0 211 1163 293 0 217 1164 302 0 211 1165 293 0 216 1166 301 0 218 1167 306 0 202 1168 305 0 198 1169 304 0 218 1170 306 0 198 1171 304 0 213 1172 303 0 213 1173 297 0 198 1174 263 0 199 1175 264 0 213 1176 297 0 199 1177 264 0 216 1178 300 0 204 1179 271 0 217 1180 302 0 216 1181 301 0 204 1182 271 0 216 1183 301 0 199 1184 270 0 203 1185 308 0 197 1186 307 0 202 1187 305 0 202 1188 305 0 197 1189 307 0 198 1190 304 0 219 1191 309 0 218 1192 306 0 220 1193 310 0 218 1194 306 0 219 1195 309 0 202 1196 305 0 220 1197 313 0 221 1198 311 0 222 1199 314 0 221 1200 311 0 220 1201 313 0 218 1202 312 0 219 1203 315 0 201 1204 266 0 202 1205 267 0 204 1206 271 0 200 1207 272 0 201 1208 316 0 217 1209 302 0 204 1210 271 0 223 1211 318 0 217 1212 302 0 223 1213 318 0 179 1214 317 0 221 1215 319 0 179 1216 317 0 180 1217 320 0 179 1218 317 0 221 1219 319 0 217 1220 302 0 210 1221 279 0 218 1222 306 0 213 1223 303 0 210 1224 279 0 213 1225 303 0 209 1226 278 0 212 1227 296 0 217 1228 302 0 221 1229 319 0 209 1230 285 0 224 1231 321 0 211 1232 288 0 224 1233 321 0 209 1234 285 0 225 1235 322 0 224 1236 321 0 215 1237 299 0 211 1238 288 0 214 1239 298 0 225 1240 322 0 209 1241 285 0 213 1242 297 0 214 1243 298 0 209 1244 285 0 215 1245 299 0 216 1246 300 0 211 1247 288 0 220 1248 313 0 222 1249 314 0 226 1250 323 0 226 1251 323 0 222 1252 314 0 177 1253 324 0 227 1254 325 0 177 1255 324 0 178 1256 326 0 177 1257 324 0 227 1258 325 0 226 1259 323 0 228 1260 327 0 227 1261 325 0 182 1262 328 0 178 1263 326 0 182 1264 328 0 227 1265 325 0 227 1266 325 0 228 1267 327 0 230 1268 330 0 227 1269 325 0 230 1270 330 0 229 1271 329 0 180 1272 331 0 222 1273 332 0 221 1274 311 0 228 1275 327 0 231 1276 333 0 230 1277 330 0 228 1278 335 0 182 1279 334 0 232 1280 337 0 228 1281 335 0 232 1282 337 0 231 1283 336 0 231 1284 336 0 370 1285 339 0 230 1286 313 0 370 1287 339 0 231 1288 336 0 232 1289 338 0 201 1290 277 0 183 1291 340 0 223 1292 341 0 201 1293 277 0 223 1294 341 0 204 1295 283 0 233 1296 344 0 183 1297 343 0 219 1298 281 0 219 1299 281 0 183 1300 343 0 201 1301 342 0 234 1302 345 0 237 1303 348 0 236 1304 347 0 234 1305 345 0 236 1306 347 0 235 1307 346 0 239 1308 351 0 238 1309 350 0 236 1310 352 0 235 1311 349 0 236 1312 352 0 238 1313 350 0 237 1314 355 0 234 1315 354 0 241 1316 356 0 240 1317 353 0 241 1318 356 0 234 1319 354 0 241 1320 356 0 239 1321 357 0 237 1322 355 0 237 1323 355 0 239 1324 357 0 236 1325 347 0 239 1326 358 0 240 1327 360 0 238 1328 359 0 240 1329 360 0 239 1330 358 0 241 1331 361 0 234 1332 345 0 235 1333 349 0 240 1334 353 0 240 1335 353 0 235 1336 349 0 238 1337 359 0 243 1338 363 0 214 1339 298 0 215 1340 299 0 214 1341 298 0 243 1342 363 0 242 1343 362 0 244 1344 364 0 225 1345 322 0 245 1346 365 0 225 1347 322 0 244 1348 364 0 224 1349 321 0 244 1350 364 0 215 1351 299 0 224 1352 321 0 215 1353 299 0 244 1354 364 0 243 1355 363 0 242 1356 362 0 225 1357 322 0 214 1358 298 0 225 1359 322 0 242 1360 362 0 245 1361 365 0 212 1362 289 0 221 1363 311 0 243 1364 366 0 212 1365 289 0 243 1366 366 0 244 1367 367 0 210 1368 292 0 212 1369 289 0 244 1370 367 0 210 1371 292 0 244 1372 367 0 245 1373 368 0 210 1374 292 0 242 1375 369 0 218 1376 312 0 242 1377 369 0 210 1378 292 0 245 1379 368 0 243 1380 366 0 221 1381 311 0 218 1382 312 0 243 1383 366 0 218 1384 312 0 242 1385 369 0 247 1386 371 145 248 1387 372 146 249 1388 373 147 248 1389 372 146 247 1390 371 145 246 1391 370 144 253 1392 377 151 252 1393 376 150 250 1394 374 148 253 1395 377 151 250 1396 374 148 251 1397 375 149 250 1398 380 148 247 1399 379 145 251 1400 381 149 247 1401 379 145 250 1402 380 148 246 1403 378 144 251 1404 384 149 249 1405 383 147 253 1406 385 151 249 1407 383 147 251 1408 384 149 247 1409 382 145 252 1410 389 150 253 1411 388 151 249 1412 386 147 252 1413 389 150 249 1414 386 147 248 1415 387 146 252 1416 392 150 248 1417 390 146 250 1418 393 148 250 1419 393 148 248 1420 390 146 246 1421 391 144 257 1422 397 155 255 1423 395 153 254 1424 394 152 254 1425 394 152 256 1426 396 154 257 1427 397 155 260 1428 400 158 259 1429 399 157 261 1430 401 159 259 1431 399 157 260 1432 400 158 258 1433 398 156 259 1434 405 157 258 1435 404 156 254 1436 402 152 259 1437 405 157 254 1438 402 152 255 1439 403 153 259 1440 408 157 257 1441 407 155 261 1442 409 159 257 1443 407 155 259 1444 408 157 255 1445 406 153 260 1446 413 158 261 1447 412 159 257 1448 410 155 260 1449 413 158 257 1450 410 155 256 1451 411 154 258 1452 417 156 260 1453 416 158 256 1454 414 154 258 1455 417 156 256 1456 414 154 254 1457 415 152 265 1458 420 163 264 1459 419 162 266 1460 421 164 264 1461 419 162 265 1462 420 163 263 1463 418 161 264 1464 425 162 263 1465 424 161 271 1466 422 169 271 1467 422 169 272 1468 423 170 264 1469 425 162 264 1470 428 162 273 1471 427 171 266 1472 429 164 273 1473 427 171 264 1474 428 162 272 1475 426 170 262 1476 431 160 266 1477 432 164 273 1478 430 171 266 1479 432 164 262 1480 431 160 265 1481 433 163 263 1482 437 161 265 1483 436 163 262 1484 434 160 262 1485 434 160 271 1486 435 169 263 1487 437 161 270 1488 441 168 268 1489 439 166 267 1490 438 165 268 1491 439 166 270 1492 441 168 269 1493 440 167 267 1494 445 165 272 1495 443 170 271 1496 442 169 272 1497 443 170 267 1498 445 165 268 1499 444 166 268 1500 449 166 273 1501 447 171 272 1502 446 170 273 1503 447 171 268 1504 449 166 269 1505 448 167 262 1506 451 160 273 1507 450 171 270 1508 452 168 270 1509 452 168 273 1510 450 171 269 1511 453 167 270 1512 457 168 267 1513 456 165 262 1514 454 160 262 1515 454 160 267 1516 456 165 271 1517 455 169 277 1518 461 175 275 1519 459 173 276 1520 460 174 275 1521 459 173 277 1522 461 175 274 1523 458 172 281 1524 465 179 278 1525 462 176 280 1526 464 178 278 1527 462 176 279 1528 463 177 280 1529 464 178 279 1530 469 177 276 1531 467 174 280 1532 468 178 276 1533 467 174 279 1534 469 177 277 1535 466 175 280 1536 473 178 275 1537 471 173 281 1538 472 179 275 1539 471 173 280 1540 473 178 276 1541 470 174 278 1542 476 176 281 1543 477 179 275 1544 474 173 278 1545 476 176 275 1546 474 173 274 1547 475 172 282 1548 479 180 284 1549 481 182 289 1550 478 187 283 1551 480 181 289 1552 478 187 284 1553 481 182 285 1554 482 183 286 1555 483 184 282 1556 479 180 284 1557 481 182 282 1558 479 180 286 1559 483 184 287 1560 484 185 286 1561 483 184 285 1562 482 183 286 1563 483 184 287 1564 484 185 288 1565 485 186 289 1566 486 187 288 1567 485 186 287 1568 484 185 288 1569 485 186 289 1570 486 187 283 1571 487 181 284 1572 481 182 290 1573 488 188 283 1574 480 181 290 1575 488 188 284 1576 481 182 291 1577 489 189 286 1578 483 184 292 1579 490 190 284 1580 481 182 284 1581 481 182 292 1582 490 190 291 1583 489 189 288 1584 485 186 292 1585 490 190 286 1586 483 184 292 1587 490 190 288 1588 485 186 293 1589 491 191 293 1590 491 191 283 1591 487 181 290 1592 492 188 283 1593 487 181 293 1594 491 191 288 1595 485 186 295 1596 495 193 301 1597 493 199 296 1598 496 194 301 1599 493 199 294 1600 494 192 296 1601 496 194 298 1602 498 196 294 1603 494 192 297 1604 497 195 294 1605 494 192 298 1606 498 196 296 1607 496 194 299 1608 499 197 298 1609 498 196 297 1610 497 195 298 1611 498 196 299 1612 499 197 300 1613 500 198 300 1614 500 198 301 1615 501 199 295 1616 502 193 301 1617 501 199 300 1618 500 198 299 1619 499 197 302 1620 503 200 296 1621 496 194 303 1622 504 201 296 1623 496 194 302 1624 503 200 295 1625 495 193 303 1626 504 201 298 1627 498 196 304 1628 505 202 298 1629 498 196 303 1630 504 201 296 1631 496 194 305 1632 506 203 298 1633 498 196 300 1634 500 198 298 1635 498 196 305 1636 506 203 304 1637 505 202 302 1638 507 200 300 1639 500 198 295 1640 502 193 300 1641 500 198 302 1642 507 200 305 1643 506 203 306 1644 508 204 303 1645 504 201 307 1646 509 205 303 1647 504 201 306 1648 508 204 302 1649 503 200 307 1650 509 205 304 1651 505 202 308 1652 510 206 304 1653 505 202 307 1654 509 205 303 1655 504 201 309 1656 511 207 304 1657 505 202 305 1658 506 203 304 1659 505 202 309 1660 511 207 308 1661 510 206 309 1662 511 207 305 1663 506 203 306 1664 512 204 305 1665 506 203 302 1666 507 200 306 1667 512 204 310 1668 513 208 306 1669 508 204 311 1670 514 209 306 1671 508 204 307 1672 509 205 311 1673 514 209 308 1674 510 206 312 1675 515 210 307 1676 509 205 307 1677 509 205 312 1678 515 210 311 1679 514 209 309 1680 511 207 312 1681 515 210 308 1682 510 206 312 1683 515 210 309 1684 511 207 313 1685 516 211 313 1686 516 211 306 1687 512 204 310 1688 517 208 306 1689 512 204 313 1690 516 211 309 1691 511 207 311 1692 514 209 315 1693 519 213 310 1694 513 208 314 1695 518 212 310 1696 513 208 315 1697 519 213 312 1698 515 210 316 1699 520 214 311 1700 514 209 311 1701 514 209 316 1702 520 214 315 1703 519 213 313 1704 516 211 316 1705 520 214 312 1706 515 210 316 1707 520 214 313 1708 516 211 317 1709 521 215 317 1710 521 215 310 1711 517 208 314 1712 522 212 310 1713 517 208 317 1714 521 215 313 1715 516 211 318 1716 523 216 291 1717 489 189 319 1718 524 217 291 1719 489 189 318 1720 523 216 290 1721 488 188 292 1722 490 190 319 1723 524 217 291 1724 489 189 319 1725 524 217 292 1726 490 190 320 1727 525 218 293 1728 491 191 321 1729 526 219 292 1730 490 190 321 1731 526 219 320 1732 525 218 292 1733 490 190 293 1734 491 191 318 1735 527 216 321 1736 526 219 318 1737 527 216 293 1738 491 191 290 1739 492 188 318 1740 523 216 319 1741 524 217 301 1742 493 199 301 1743 493 199 319 1744 524 217 294 1745 494 192 297 1746 497 195 294 1747 494 192 320 1748 525 218 319 1749 524 217 320 1750 525 218 294 1751 494 192 321 1752 526 219 299 1753 499 197 320 1754 525 218 299 1755 499 197 297 1756 497 195 320 1757 525 218 299 1758 499 197 321 1759 526 219 301 1760 501 199 301 1761 501 199 321 1762 526 219 318 1763 527 216 289 1764 478 187 325 1765 528 223 322 1766 529 220 289 1767 478 187 322 1768 529 220 282 1769 479 180 282 1770 479 180 322 1771 529 220 323 1772 530 221 282 1773 479 180 323 1774 530 221 285 1775 482 183 287 1776 484 185 323 1777 530 221 324 1778 531 222 323 1779 530 221 287 1780 484 185 285 1781 482 183 324 1782 531 222 289 1783 486 187 287 1784 484 185 289 1785 486 187 324 1786 531 222 325 1787 532 223 326 1788 533 224 322 1789 529 220 325 1790 528 223 322 1791 529 220 326 1792 533 224 327 1793 535 225 322 1794 529 220 327 1795 535 225 328 1796 536 226 322 1797 529 220 328 1798 536 226 323 1799 530 221 324 1800 531 222 328 1801 536 226 329 1802 537 227 328 1803 536 226 324 1804 531 222 323 1805 530 221 329 1806 537 227 325 1807 532 223 324 1808 531 222 325 1809 532 223 329 1810 537 227 326 1811 534 224 334 1812 539 232 335 1813 545 233 330 1814 538 228 330 1815 538 228 335 1816 545 233 331 1817 540 229 336 1818 546 234 332 1819 541 230 331 1820 540 229 336 1821 546 234 331 1822 540 229 335 1823 545 233 333 1824 542 231 336 1825 546 234 337 1826 547 235 336 1827 546 234 333 1828 542 231 332 1829 541 230 337 1830 547 235 330 1831 544 228 333 1832 542 231 330 1833 544 228 337 1834 547 235 334 1835 543 232 338 1836 548 236 335 1837 545 233 334 1838 539 232 335 1839 545 233 338 1840 548 236 339 1841 550 237 339 1842 550 237 336 1843 546 234 335 1844 545 233 336 1845 546 234 339 1846 550 237 340 1847 551 238 341 1848 552 239 337 1849 547 235 336 1850 546 234 341 1851 552 239 336 1852 546 234 340 1853 551 238 334 1854 543 232 337 1855 547 235 338 1856 549 236 337 1857 547 235 341 1858 552 239 338 1859 549 236 345 1860 553 243 339 1861 550 237 338 1862 548 236 339 1863 550 237 345 1864 553 243 342 1865 554 240 342 1866 554 240 340 1867 551 238 339 1868 550 237 340 1869 551 238 342 1870 554 240 343 1871 555 241 344 1872 556 242 341 1873 552 239 340 1874 551 238 344 1875 556 242 340 1876 551 238 343 1877 555 241 344 1878 556 242 345 1879 557 243 341 1880 552 239 341 1881 552 239 345 1882 557 243 338 1883 549 236 346 1884 559 244 345 1885 553 243 349 1886 558 247 345 1887 553 243 346 1888 559 244 342 1889 554 240 343 1890 555 241 342 1891 554 240 347 1892 560 245 342 1893 554 240 346 1894 559 244 347 1895 560 245 344 1896 556 242 347 1897 560 245 348 1898 561 246 347 1899 560 245 344 1900 556 242 343 1901 555 241 348 1902 561 246 345 1903 557 243 344 1904 556 242 345 1905 557 243 348 1906 561 246 349 1907 562 247 350 1908 564 248 349 1909 558 247 353 1910 563 251 349 1911 558 247 350 1912 564 248 346 1913 559 244 351 1914 565 249 347 1915 560 245 346 1916 559 244 346 1917 559 244 350 1918 564 248 351 1919 565 249 348 1920 561 246 351 1921 565 249 352 1922 566 250 351 1923 565 249 348 1924 561 246 347 1925 560 245 352 1926 566 250 349 1927 562 247 348 1928 561 246 349 1929 562 247 352 1930 566 250 353 1931 567 251 357 1932 568 255 327 1933 535 225 326 1934 533 224 327 1935 535 225 357 1936 568 255 354 1937 569 252 354 1938 569 252 328 1939 536 226 327 1940 535 225 328 1941 536 226 354 1942 569 252 355 1943 570 253 356 1944 571 254 329 1945 537 227 328 1946 536 226 356 1947 571 254 328 1948 536 226 355 1949 570 253 357 1950 572 255 329 1951 537 227 356 1952 571 254 329 1953 537 227 357 1954 572 255 326 1955 534 224 330 1956 538 228 354 1957 569 252 357 1958 568 255 354 1959 569 252 330 1960 538 228 331 1961 540 229 355 1962 570 253 354 1963 569 252 331 1964 540 229 355 1965 570 253 331 1966 540 229 332 1967 541 230 333 1968 542 231 356 1969 571 254 355 1970 570 253 333 1971 542 231 355 1972 570 253 332 1973 541 230 330 1974 544 228 356 1975 571 254 333 1976 542 231 356 1977 571 254 330 1978 544 228 357 1979 572 255 365 1980 580 263 358 1981 573 256 364 1982 579 262 358 1983 573 256 365 1984 580 263 362 1985 577 260 366 1986 581 264 362 1987 577 260 365 1988 580 263 362 1989 577 260 366 1990 581 264 363 1991 578 261 360 1992 575 258 361 1993 576 259 367 1994 582 265 360 1995 575 258 367 1996 582 265 368 1997 583 266 368 1998 583 266 359 1999 574 257 360 2000 575 258 359 2001 574 257 368 2002 583 266 369 2003 584 267 367 2004 582 265 361 2005 576 259 363 2006 578 261 367 2007 582 265 363 2008 578 261 366 2009 581 264 367 2010 582 265 365 2011 580 263 368 2012 583 266 365 2013 580 263 367 2014 582 265 366 2015 581 264 369 2016 584 267 368 2017 583 266 365 2018 580 263 369 2019 584 267 365 2020 580 263 364 2021 579 262 359 2022 574 257 369 2023 584 267 364 2024 579 262 359 2025 574 257 364 2026 579 262 358 2027 573 256 360 2028 575 258 359 2029 574 257 358 2030 573 256 360 2031 575 258 358 2032 573 256 362 2033 577 260 361 2034 576 259 360 2035 575 258 362 2036 577 260 361 2037 576 259 362 2038 577 260 363 2039 578 261

+
+
+
+ + + 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.0000001.000000 + 30.0000000.0000003.333333 + + + + + +
diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_PalletJackB_01/meshes/aws_robomaker_warehouse_PalletJackB_01_visual.DAE b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_PalletJackB_01/meshes/aws_robomaker_warehouse_PalletJackB_01_visual.DAE new file mode 100755 index 0000000..75f5487 --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_PalletJackB_01/meshes/aws_robomaker_warehouse_PalletJackB_01_visual.DAE @@ -0,0 +1,14389 @@ + + + FBX COLLADA exporter2019-05-27T02:24:52Z2019-05-27T02:24:52ZZ_UP + + + ../materials/textures/aws_robomaker_warehouse_PalletJackB_01.png + + + ../materials/textures/aws_robomaker_warehouse_PalletJackB_02.png + + + + + + + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + +0.643753 0.152121 0.138676 +0.643717 0.204227 0.138676 +0.643717 0.204227 0.106815 +0.643753 0.152121 0.106815 +0.635237 0.215456 0.138676 +0.634941 0.140295 0.138676 +0.634941 0.140295 0.106815 +0.635237 0.215456 0.106815 +0.618441 0.134194 0.138676 +0.618356 0.221812 0.138676 +0.618441 0.134194 0.106815 +0.618356 0.221812 0.106815 +0.583879 0.232880 0.138676 +0.582795 0.122474 0.138676 +0.582795 0.122474 0.106815 +0.583879 0.232880 0.106815 +0.528483 0.250665 0.138676 +0.526230 0.103876 0.138676 +0.526230 0.103876 0.084320 +0.528483 0.250665 0.084320 +0.510917 0.164164 0.138676 +0.505164 0.154273 0.138676 +0.335472 0.105908 0.084320 +0.335472 0.105908 0.138676 +-0.263088 0.247964 0.138676 +-0.263088 0.247964 0.084320 +0.336539 0.250010 0.084320 +0.336539 0.250010 0.138676 +-0.262971 0.112282 0.138676 +-0.262971 0.112282 0.084320 +0.374266 0.164164 0.084320 +0.374266 0.164164 0.138676 +0.371547 0.178185 0.138676 +0.371547 0.178185 0.084320 +0.374266 0.192207 0.138676 +0.374266 0.192207 0.084320 +0.380019 0.154273 0.084320 +0.380019 0.154273 0.138676 +0.380019 0.202097 0.138676 +0.380019 0.202097 0.084320 +0.497982 0.150142 0.084320 +0.497982 0.150142 0.138676 +0.387201 0.150142 0.138676 +0.387201 0.150142 0.084320 +0.505164 0.154273 0.084320 +0.510917 0.164164 0.084320 +0.505164 0.202097 0.084320 +0.505164 0.202097 0.138676 +0.510917 0.192207 0.138676 +0.510917 0.192207 0.084320 +0.513636 0.178185 0.084320 +0.513636 0.178185 0.138676 +0.497982 0.206228 0.138676 +0.387201 0.206228 0.138676 +0.497982 0.206228 0.084320 +0.387201 0.206228 0.084320 +-0.127360 0.244130 0.138858 +-0.248526 0.244130 0.138858 +-0.151246 0.023863 0.587088 +-0.224641 0.031921 0.587088 +-0.146783 0.048146 0.503330 +-0.229104 0.054287 0.503330 +-0.345318 0.040991 0.538917 +-0.345318 0.040991 0.612404 +-0.365603 0.021446 0.538917 +-0.379128 0.000397 0.538917 +-0.325032 0.048508 0.612404 +-0.365603 0.021446 0.612404 +-0.379128 0.000397 0.612404 +-0.325032 0.048508 0.538917 +-0.134185 0.028963 0.538917 +-0.134185 0.028963 0.606870 +-0.113900 0.000397 0.538917 +-0.167995 0.048508 0.611995 +-0.113900 0.000397 0.596112 +-0.167995 0.048508 0.538917 +-0.359436 0.031947 0.291840 +-0.354228 0.033659 0.287470 +-0.344224 0.033659 0.293246 +-0.345405 0.031947 0.299941 +-0.364977 0.031947 0.276615 +-0.358179 0.033659 0.276615 +-0.359436 0.031947 0.261391 +-0.354228 0.033659 0.265760 +-0.345405 0.031947 0.253290 +-0.344224 0.033659 0.259985 +-0.329449 0.031947 0.256103 +-0.332848 0.033659 0.261990 +-0.319035 0.031947 0.268514 +-0.325423 0.033659 0.270839 +-0.319035 0.031947 0.284716 +-0.325423 0.033659 0.282391 +-0.329449 0.031947 0.297127 +-0.332848 0.033659 0.291240 +-0.348386 0.070428 0.282568 +-0.342900 0.070428 0.285736 +-0.343781 0.070428 0.290734 +-0.352274 0.070428 0.285831 +-0.350553 0.070428 0.276615 +-0.355628 0.070428 0.276615 +-0.348386 0.070428 0.270662 +-0.352274 0.070428 0.267400 +-0.342900 0.070428 0.267495 +-0.343781 0.070428 0.262496 +-0.336661 0.070428 0.268595 +-0.334123 0.070428 0.264199 +-0.332589 0.070428 0.273448 +-0.327820 0.070428 0.271712 +-0.332589 0.070428 0.279783 +-0.327820 0.070428 0.281519 +-0.336661 0.070428 0.284636 +-0.334123 0.070428 0.289031 +-0.342900 0.074232 0.285736 +-0.348386 0.074232 0.282568 +-0.332589 0.074232 0.279783 +-0.336661 0.074232 0.284636 +-0.350553 0.074232 0.276615 +-0.348386 0.074232 0.270662 +-0.342900 0.074232 0.267495 +-0.336661 0.074232 0.268595 +-0.332589 0.074232 0.273448 +-0.374815 0.057187 0.267573 +-0.364105 0.057187 0.304235 +-0.227722 0.057187 0.264932 +-0.227722 0.057187 0.209872 +-0.374815 0.067899 0.267573 +-0.364105 0.067899 0.304235 +-0.376572 0.067899 0.274998 +-0.227722 0.067899 0.209872 +-0.227722 0.067899 0.264932 +-0.373342 0.057187 0.294117 +-0.375835 0.057187 0.288270 +-0.375835 0.067899 0.288270 +-0.373342 0.067899 0.294117 +-0.376572 0.057187 0.274998 +-0.146783 -0.015163 0.503330 +-0.229104 -0.015163 0.503330 +-0.151246 -0.015163 0.587088 +-0.224641 -0.015163 0.587088 +-0.113900 -0.015163 0.538917 +-0.140948 -0.015163 0.538917 +-0.379128 -0.015163 0.612404 +-0.140948 -0.015163 0.609441 +-0.352080 -0.015163 0.538917 +0.643753 -0.182447 0.138676 +0.643717 -0.234553 0.138676 +0.643753 -0.182447 0.106815 +0.643717 -0.234553 0.106815 +0.635237 -0.245782 0.138676 +0.634941 -0.170621 0.138676 +0.634941 -0.170621 0.106815 +0.635237 -0.245782 0.106815 +0.618356 -0.252138 0.138676 +0.618441 -0.164520 0.138676 +0.618441 -0.164520 0.106815 +0.618356 -0.252138 0.106815 +0.583879 -0.263206 0.138676 +0.582795 -0.152800 0.138676 +0.582795 -0.152800 0.106815 +0.583879 -0.263206 0.106815 +0.528483 -0.280991 0.138676 +0.526230 -0.134202 0.138676 +0.526230 -0.134202 0.084320 +0.528483 -0.280991 0.084320 +0.510917 -0.194490 0.138676 +0.505164 -0.184599 0.138676 +0.335472 -0.136234 0.138676 +0.335472 -0.136234 0.084320 +0.336539 -0.280336 0.138676 +0.336539 -0.280336 0.084320 +-0.263088 -0.278290 0.084320 +-0.263088 -0.278290 0.138676 +-0.262971 -0.142608 0.138676 +-0.262971 -0.142608 0.084320 +0.374266 -0.194490 0.084320 +0.371547 -0.208511 0.084320 +0.371547 -0.208511 0.138676 +0.374266 -0.194490 0.138676 +0.374266 -0.222533 0.084320 +0.374266 -0.222533 0.138676 +0.380019 -0.184599 0.138676 +0.380019 -0.184599 0.084320 +0.380019 -0.232423 0.084320 +0.380019 -0.232423 0.138676 +0.497982 -0.180468 0.084320 +0.387201 -0.180468 0.084320 +0.387201 -0.180468 0.138676 +0.497982 -0.180468 0.138676 +0.510917 -0.194490 0.084320 +0.505164 -0.184599 0.084320 +0.505164 -0.232423 0.084320 +0.510917 -0.222533 0.084320 +0.510917 -0.222533 0.138676 +0.505164 -0.232423 0.138676 +0.513636 -0.208511 0.084320 +0.513636 -0.208511 0.138676 +0.387201 -0.236554 0.138676 +0.497982 -0.236554 0.138676 +0.387201 -0.236554 0.084320 +0.497982 -0.236554 0.084320 +-0.127360 -0.274456 0.138858 +-0.146783 -0.078472 0.503330 +-0.127360 -0.015163 0.138858 +-0.248526 -0.274456 0.138858 +-0.229104 -0.084613 0.503330 +-0.151246 -0.054189 0.587088 +-0.224641 -0.062247 0.587088 +-0.134185 -0.059289 0.538917 +-0.113900 -0.030723 0.538917 +-0.127423 -0.015163 0.538917 +-0.325032 -0.078834 0.612404 +-0.167995 -0.078834 0.611995 +-0.167995 -0.078834 0.538917 +-0.325032 -0.078834 0.538917 +-0.345318 -0.071317 0.538917 +-0.345318 -0.071317 0.612404 +-0.365603 -0.051772 0.538917 +-0.379128 -0.030723 0.538917 +-0.379128 -0.030723 0.612404 +-0.365603 -0.051772 0.612404 +-0.167995 -0.015163 0.611995 +-0.113900 -0.030723 0.596112 +-0.134185 -0.059289 0.606870 +-0.167995 -0.015163 0.538917 +-0.325032 -0.015163 0.538917 +-0.379128 -0.015163 0.538917 +-0.345405 -0.062273 0.299941 +-0.344224 -0.063985 0.293246 +-0.354228 -0.063985 0.287470 +-0.359436 -0.062273 0.291840 +-0.358179 -0.063985 0.276615 +-0.364977 -0.062273 0.276615 +-0.354228 -0.063985 0.265760 +-0.359436 -0.062273 0.261391 +-0.344224 -0.063985 0.259985 +-0.345405 -0.062273 0.253290 +-0.332848 -0.063985 0.261990 +-0.329449 -0.062273 0.256103 +-0.325423 -0.063985 0.270839 +-0.319035 -0.062273 0.268514 +-0.325423 -0.063985 0.282391 +-0.319035 -0.062273 0.284716 +-0.332848 -0.063985 0.291240 +-0.329449 -0.062273 0.297127 +-0.348386 -0.100754 0.282568 +-0.352274 -0.100754 0.285831 +-0.343781 -0.100754 0.290734 +-0.342900 -0.100754 0.285736 +-0.350553 -0.100754 0.276615 +-0.355628 -0.100754 0.276615 +-0.348386 -0.100754 0.270662 +-0.352274 -0.100754 0.267400 +-0.342900 -0.100754 0.267495 +-0.343781 -0.100754 0.262496 +-0.336661 -0.100754 0.268595 +-0.334123 -0.100754 0.264199 +-0.332589 -0.100754 0.273448 +-0.327820 -0.100754 0.271712 +-0.332589 -0.100754 0.279783 +-0.327820 -0.100754 0.281519 +-0.336661 -0.100754 0.284636 +-0.334123 -0.100754 0.289031 +-0.336661 -0.104558 0.284636 +-0.332589 -0.104558 0.279783 +-0.348386 -0.104558 0.282568 +-0.342900 -0.104558 0.285736 +-0.350553 -0.104558 0.276615 +-0.348386 -0.104558 0.270662 +-0.342900 -0.104558 0.267495 +-0.336661 -0.104558 0.268595 +-0.332589 -0.104558 0.273448 +-0.374815 -0.087513 0.267573 +-0.227722 -0.087513 0.209872 +-0.227722 -0.087513 0.264932 +-0.364105 -0.087513 0.304235 +-0.376572 -0.098225 0.274998 +-0.364105 -0.098225 0.304235 +-0.374815 -0.098225 0.267573 +-0.227722 -0.098225 0.209872 +-0.227722 -0.098225 0.264932 +-0.373342 -0.098225 0.294117 +-0.375835 -0.098225 0.288270 +-0.375835 -0.087513 0.288270 +-0.373342 -0.087513 0.294117 +-0.376572 -0.087513 0.274998 +-0.248526 -0.015163 0.138858 +-0.325032 -0.015163 0.612404 +-0.365603 -0.015163 0.612404 +-0.113900 -0.015163 0.596112 +-0.394908 -0.098469 0.244618 +-0.434242 -0.098469 0.237682 +-0.468833 -0.098469 0.217711 +-0.494506 -0.098469 0.187114 +-0.508167 -0.098469 0.149582 +-0.508167 -0.098469 0.109640 +-0.494506 -0.098469 0.072108 +-0.468833 -0.098469 0.041511 +-0.434242 -0.098469 0.021540 +-0.394908 -0.098469 0.014605 +-0.355573 -0.098469 0.021540 +-0.320983 -0.098469 0.041511 +-0.295309 -0.098469 0.072108 +-0.281648 -0.098469 0.109640 +-0.281648 -0.098469 0.149582 +-0.295309 -0.098469 0.187114 +-0.320983 -0.098469 0.217711 +-0.355573 -0.098469 0.237682 +-0.394908 -0.073594 0.244618 +-0.434242 -0.073594 0.237682 +-0.468833 -0.073594 0.217711 +-0.494506 -0.073594 0.187114 +-0.508167 -0.073594 0.149582 +-0.508167 -0.073594 0.109640 +-0.494506 -0.073594 0.072108 +-0.468833 -0.073594 0.041511 +-0.434242 -0.073594 0.021540 +-0.394908 -0.073594 0.014605 +-0.355573 -0.073594 0.021540 +-0.320983 -0.073594 0.041511 +-0.295309 -0.073594 0.072108 +-0.281648 -0.073594 0.109640 +-0.281648 -0.073594 0.149582 +-0.295309 -0.073594 0.187114 +-0.320983 -0.073594 0.217711 +-0.355573 -0.073594 0.237682 +-0.430983 -0.073594 0.227496 +-0.394907 -0.073594 0.233853 +-0.358832 -0.073594 0.227496 +-0.327219 -0.073594 0.209257 +-0.303891 -0.073594 0.181479 +-0.291549 -0.073594 0.147597 +-0.291549 -0.073594 0.111625 +-0.303892 -0.073594 0.077743 +-0.327219 -0.073594 0.049965 +-0.358832 -0.073594 0.031726 +-0.394908 -0.073594 0.025369 +-0.430984 -0.073594 0.031726 +-0.462597 -0.073594 0.049965 +-0.485924 -0.073594 0.077743 +-0.498267 -0.073594 0.111625 +-0.498267 -0.073594 0.147596 +-0.485924 -0.073594 0.181479 +-0.462597 -0.073594 0.209257 +-0.394907 -0.045685 0.233853 +-0.430984 -0.045685 0.227496 +-0.462596 -0.045685 0.209258 +-0.485924 -0.045685 0.181479 +-0.498267 -0.045685 0.147597 +-0.498267 -0.045685 0.111625 +-0.485924 -0.045685 0.077743 +-0.462597 -0.045685 0.049965 +-0.430984 -0.045685 0.031726 +-0.394908 -0.045685 0.025369 +-0.358832 -0.045685 0.031726 +-0.327219 -0.045685 0.049965 +-0.303892 -0.045685 0.077743 +-0.291549 -0.045685 0.111625 +-0.291549 -0.045685 0.147597 +-0.303892 -0.045685 0.181479 +-0.327219 -0.045685 0.209258 +-0.358832 -0.045685 0.227496 +-0.434242 0.043268 0.237682 +-0.434242 0.068143 0.237682 +-0.394908 0.068143 0.244618 +-0.394908 0.043268 0.244618 +-0.468833 0.043268 0.217711 +-0.468833 0.068143 0.217711 +-0.494506 0.043268 0.187114 +-0.494506 0.068143 0.187114 +-0.508167 0.043268 0.149582 +-0.508167 0.068143 0.149582 +-0.508167 0.043268 0.109640 +-0.508167 0.068143 0.109640 +-0.494506 0.043268 0.072108 +-0.494506 0.068143 0.072108 +-0.468833 0.043268 0.041511 +-0.468833 0.068143 0.041511 +-0.434242 0.043268 0.021540 +-0.434242 0.068143 0.021540 +-0.394908 0.043268 0.014605 +-0.394908 0.068143 0.014605 +-0.355573 0.043268 0.021540 +-0.355573 0.068143 0.021540 +-0.320983 0.043268 0.041511 +-0.320983 0.068143 0.041511 +-0.295309 0.043268 0.072108 +-0.295309 0.068143 0.072108 +-0.281648 0.043268 0.109640 +-0.281648 0.068143 0.109640 +-0.281648 0.043268 0.149582 +-0.281648 0.068143 0.149582 +-0.295309 0.043268 0.187114 +-0.295309 0.068143 0.187114 +-0.320983 0.043268 0.217711 +-0.320983 0.068143 0.217711 +-0.355573 0.043268 0.237682 +-0.355573 0.068143 0.237682 +-0.394907 0.043268 0.233853 +-0.430983 0.043268 0.227496 +-0.358832 0.043268 0.227496 +-0.327219 0.043268 0.209257 +-0.303891 0.043268 0.181479 +-0.291549 0.043268 0.147597 +-0.291549 0.043268 0.111625 +-0.303892 0.043268 0.077743 +-0.327219 0.043268 0.049965 +-0.358832 0.043268 0.031726 +-0.394908 0.043268 0.025369 +-0.430984 0.043268 0.031726 +-0.462597 0.043268 0.049965 +-0.485924 0.043268 0.077743 +-0.498267 0.043268 0.111625 +-0.498267 0.043268 0.147596 +-0.485924 0.043268 0.181479 +-0.462597 0.043268 0.209257 +-0.430984 0.015359 0.227496 +-0.394907 0.015359 0.233853 +-0.462596 0.015359 0.209258 +-0.485924 0.015359 0.181479 +-0.498267 0.015359 0.147597 +-0.498267 0.015359 0.111625 +-0.485924 0.015359 0.077743 +-0.462597 0.015359 0.049965 +-0.430984 0.015359 0.031726 +-0.394908 0.015359 0.025369 +-0.358832 0.015359 0.031726 +-0.327219 0.015359 0.049965 +-0.303892 0.015359 0.077743 +-0.291549 0.015359 0.111625 +-0.291549 0.015359 0.147597 +-0.303892 0.015359 0.181479 +-0.327219 0.015359 0.209258 +-0.358832 0.015359 0.227496 +0.423930 0.168194 0.126336 +0.423930 0.188551 0.126336 +0.443215 0.188551 0.129734 +0.443215 0.168194 0.129734 +0.407032 0.168194 0.116587 +0.407032 0.188551 0.116587 +0.394562 0.168194 0.101738 +0.394562 0.188551 0.101738 +0.387964 0.168194 0.083626 +0.387964 0.188551 0.083626 +0.387964 0.168194 0.064398 +0.387964 0.188551 0.064398 +0.394562 0.168194 0.046287 +0.394562 0.188551 0.046287 +0.407032 0.168194 0.031438 +0.407032 0.188551 0.031438 +0.423930 0.168194 0.021688 +0.423930 0.188551 0.021688 +0.443214 0.168194 0.018290 +0.443214 0.188551 0.018290 +0.462499 0.168194 0.021688 +0.462499 0.188551 0.021688 +0.479397 0.168194 0.031438 +0.479397 0.188551 0.031438 +0.491867 0.168194 0.046287 +0.491867 0.188551 0.046287 +0.498464 0.168194 0.064398 +0.498464 0.188551 0.064398 +0.498465 0.168194 0.083626 +0.498464 0.188551 0.083626 +0.491867 0.168194 0.101738 +0.491867 0.188551 0.101738 +0.479397 0.168194 0.116587 +0.479397 0.188551 0.116587 +0.462498 0.168194 0.126336 +0.462499 0.188551 0.126336 +0.422188 0.188551 0.131781 +0.422188 0.197622 0.131781 +0.443214 0.197622 0.135488 +0.443214 0.188551 0.135489 +0.443214 0.168194 0.135489 +0.443214 0.159123 0.135489 +0.422188 0.159123 0.131781 +0.422188 0.168194 0.131781 +0.403698 0.188551 0.121106 +0.403698 0.197622 0.121106 +0.403698 0.159123 0.121106 +0.403698 0.168194 0.121106 +0.389974 0.188551 0.104750 +0.389974 0.197622 0.104750 +0.389974 0.159123 0.104750 +0.389974 0.168194 0.104750 +0.382672 0.188551 0.084688 +0.382672 0.197622 0.084688 +0.382672 0.159123 0.084688 +0.382672 0.168194 0.084688 +0.382672 0.188551 0.063337 +0.382672 0.197622 0.063337 +0.382672 0.159123 0.063337 +0.382672 0.168194 0.063337 +0.389974 0.188551 0.043274 +0.389974 0.197622 0.043274 +0.389974 0.159123 0.043274 +0.389974 0.168194 0.043274 +0.403698 0.188551 0.026919 +0.403698 0.197622 0.026919 +0.403698 0.159123 0.026919 +0.403698 0.168194 0.026919 +0.422188 0.188551 0.016244 +0.422188 0.197622 0.016244 +0.422188 0.159123 0.016244 +0.422188 0.168194 0.016244 +0.443214 0.188551 0.012536 +0.443214 0.197622 0.012536 +0.443214 0.159123 0.012536 +0.443214 0.168194 0.012536 +0.464240 0.188551 0.016244 +0.464240 0.197622 0.016244 +0.464241 0.159123 0.016244 +0.464240 0.168194 0.016244 +0.482730 0.188551 0.026919 +0.482730 0.197622 0.026919 +0.482731 0.159123 0.026919 +0.482730 0.168194 0.026919 +0.496454 0.188551 0.043274 +0.496454 0.197622 0.043274 +0.496454 0.159123 0.043274 +0.496454 0.168194 0.043274 +0.503757 0.188551 0.063337 +0.503757 0.197622 0.063337 +0.503757 0.159123 0.063337 +0.503757 0.168194 0.063337 +0.503757 0.188551 0.084688 +0.503757 0.197622 0.084688 +0.503757 0.159123 0.084688 +0.503757 0.168194 0.084688 +0.496454 0.188551 0.104750 +0.496454 0.197622 0.104750 +0.496454 0.159123 0.104750 +0.496454 0.168194 0.104750 +0.482730 0.188551 0.121106 +0.482730 0.197622 0.121106 +0.482731 0.159123 0.121106 +0.482730 0.168194 0.121106 +0.464240 0.188551 0.131781 +0.464240 0.197622 0.131781 +0.464241 0.159123 0.131781 +0.464240 0.168194 0.131781 +0.443215 -0.198520 0.129734 +0.443215 -0.218877 0.129734 +0.423930 -0.218877 0.126336 +0.423930 -0.198520 0.126336 +0.407032 -0.218877 0.116587 +0.407032 -0.198520 0.116587 +0.394562 -0.218877 0.101738 +0.394562 -0.198520 0.101738 +0.387964 -0.218877 0.083626 +0.387964 -0.198520 0.083626 +0.387964 -0.218877 0.064398 +0.387964 -0.198520 0.064398 +0.394562 -0.218877 0.046287 +0.394562 -0.198520 0.046287 +0.407032 -0.218877 0.031438 +0.407032 -0.198520 0.031438 +0.423930 -0.218877 0.021688 +0.423930 -0.198520 0.021688 +0.443214 -0.218877 0.018290 +0.443214 -0.198520 0.018290 +0.462499 -0.218877 0.021688 +0.462499 -0.198520 0.021688 +0.479397 -0.218877 0.031438 +0.479397 -0.198520 0.031438 +0.491867 -0.218877 0.046287 +0.491867 -0.198520 0.046287 +0.498464 -0.218877 0.064398 +0.498464 -0.198520 0.064398 +0.498464 -0.218877 0.083626 +0.498465 -0.198520 0.083626 +0.491867 -0.218877 0.101738 +0.491867 -0.198520 0.101738 +0.479397 -0.218877 0.116587 +0.479397 -0.198520 0.116587 +0.462499 -0.218877 0.126336 +0.462498 -0.198520 0.126336 +0.443214 -0.218877 0.135489 +0.443214 -0.227948 0.135488 +0.422188 -0.227948 0.131781 +0.422188 -0.218877 0.131781 +0.422188 -0.198520 0.131781 +0.422188 -0.189449 0.131781 +0.443214 -0.189449 0.135489 +0.443214 -0.198520 0.135489 +0.403698 -0.227948 0.121106 +0.403698 -0.218877 0.121106 +0.403698 -0.198520 0.121106 +0.403698 -0.189449 0.121106 +0.389974 -0.227948 0.104750 +0.389974 -0.218877 0.104750 +0.389974 -0.198520 0.104750 +0.389974 -0.189449 0.104750 +0.382672 -0.227948 0.084688 +0.382672 -0.218877 0.084688 +0.382672 -0.198520 0.084688 +0.382672 -0.189449 0.084688 +0.382672 -0.227948 0.063337 +0.382672 -0.218877 0.063337 +0.382672 -0.198520 0.063337 +0.382672 -0.189449 0.063337 +0.389974 -0.227948 0.043274 +0.389974 -0.218877 0.043274 +0.389974 -0.198520 0.043274 +0.389974 -0.189449 0.043274 +0.403698 -0.227948 0.026919 +0.403698 -0.218877 0.026919 +0.403698 -0.198520 0.026919 +0.403698 -0.189449 0.026919 +0.422188 -0.227948 0.016244 +0.422188 -0.218877 0.016244 +0.422188 -0.198520 0.016244 +0.422188 -0.189449 0.016244 +0.443214 -0.227948 0.012536 +0.443214 -0.218877 0.012536 +0.443214 -0.198520 0.012536 +0.443214 -0.189449 0.012536 +0.464240 -0.227948 0.016244 +0.464240 -0.218877 0.016244 +0.464240 -0.198520 0.016244 +0.464241 -0.189449 0.016244 +0.482730 -0.227948 0.026919 +0.482730 -0.218877 0.026919 +0.482730 -0.198520 0.026919 +0.482731 -0.189449 0.026919 +0.496454 -0.227948 0.043274 +0.496454 -0.218877 0.043274 +0.496454 -0.198520 0.043274 +0.496454 -0.189449 0.043274 +0.503757 -0.227948 0.063337 +0.503757 -0.218877 0.063337 +0.503757 -0.198520 0.063337 +0.503757 -0.189449 0.063337 +0.503757 -0.227948 0.084688 +0.503757 -0.218877 0.084688 +0.503757 -0.198520 0.084688 +0.503757 -0.189449 0.084688 +0.496454 -0.227948 0.104750 +0.496454 -0.218877 0.104750 +0.496454 -0.198520 0.104750 +0.496454 -0.189449 0.104750 +0.482730 -0.227948 0.121106 +0.482730 -0.218877 0.121106 +0.482730 -0.198520 0.121106 +0.482731 -0.189449 0.121106 +0.464240 -0.227948 0.131781 +0.464240 -0.218877 0.131781 +0.464240 -0.198520 0.131781 +0.464241 -0.189449 0.131781 +-0.347868 0.022133 0.330373 +-0.370303 0.009180 0.330373 +-0.379163 -0.015163 0.330373 +-0.370303 -0.039506 0.330373 +-0.347868 -0.052459 0.330373 +-0.322356 -0.047960 0.330373 +-0.305704 -0.028116 0.330373 +-0.305704 -0.002210 0.330373 +-0.322356 0.017634 0.330373 +-0.347868 0.022133 0.508813 +-0.370303 0.009180 0.508813 +-0.379163 -0.015163 0.508813 +-0.370303 -0.039506 0.508813 +-0.347868 -0.052459 0.508813 +-0.322356 -0.047960 0.508813 +-0.305704 -0.028116 0.508813 +-0.305704 -0.002210 0.508813 +-0.322356 0.017634 0.508813 +-0.345439 0.008356 0.508813 +-0.359586 0.000188 0.508813 +-0.365174 -0.015163 0.508813 +-0.359586 -0.030514 0.508813 +-0.345439 -0.038682 0.508813 +-0.329351 -0.035845 0.508813 +-0.318850 -0.023331 0.508813 +-0.318850 -0.006995 0.508813 +-0.329351 0.005519 0.508813 +-0.345439 0.008356 0.551350 +-0.359586 0.000188 0.551350 +-0.365174 -0.015163 0.551350 +-0.359586 -0.030514 0.551350 +-0.345439 -0.038682 0.551350 +-0.329351 -0.035845 0.551350 +-0.318850 -0.023331 0.551350 +-0.318850 -0.006995 0.551350 +-0.329351 0.005519 0.551350 +-0.344371 0.002302 0.330373 +-0.354877 -0.003763 0.330373 +-0.359026 -0.015163 0.330373 +-0.354877 -0.026563 0.330373 +-0.344371 -0.032628 0.330373 +-0.332424 -0.030522 0.330373 +-0.324627 -0.021229 0.330373 +-0.324627 -0.009097 0.330373 +-0.332424 0.000196 0.330373 +-0.344371 0.002302 0.113822 +-0.332424 0.000196 0.113822 +-0.324627 -0.009097 0.113822 +-0.324627 -0.021229 0.113822 +-0.332424 -0.030522 0.113822 +-0.344371 -0.032628 0.113822 +-0.354877 -0.026563 0.113822 +-0.359026 -0.015163 0.113822 +-0.354877 -0.003763 0.113822 +-0.413614 0.017520 0.516718 +-0.413614 -0.047846 0.516718 +-0.431833 0.002858 0.976774 +-0.431833 -0.033184 0.976774 +-0.451580 0.017520 0.516718 +-0.451580 -0.047846 0.516718 +-0.449829 0.002858 0.976774 +-0.449829 -0.033184 0.976774 +-0.442724 -0.068235 0.956731 +-0.435185 -0.068356 0.958751 +-0.433166 -0.068808 0.966291 +-0.438684 -0.015163 0.974951 +-0.438684 -0.069141 0.971810 +-0.444743 -0.069108 0.971269 +-0.448242 -0.068808 0.966291 +-0.447700 -0.068444 0.960230 +-0.447700 -0.015163 0.963374 +-0.442724 -0.097186 0.952555 +-0.435185 -0.097590 0.954535 +-0.433166 -0.099095 0.961925 +-0.438684 -0.100197 0.967335 +-0.444743 -0.100089 0.966804 +-0.448242 -0.099095 0.961925 +-0.447700 -0.097885 0.955984 +-0.435185 -0.134554 0.941584 +-0.433166 -0.140159 0.946633 +-0.438684 -0.144262 0.950330 +-0.446222 -0.142761 0.948977 +-0.448242 -0.137155 0.943927 +-0.442724 -0.133052 0.940230 +-0.442724 -0.139014 0.928059 +-0.435185 -0.140947 0.928670 +-0.433166 -0.148164 0.930949 +-0.438684 -0.153447 0.932618 +-0.446222 -0.151513 0.932007 +-0.448242 -0.144297 0.929728 +-0.442724 -0.141962 0.914640 +-0.435185 -0.143973 0.914897 +-0.433166 -0.151479 0.915860 +-0.438684 -0.156974 0.916565 +-0.446222 -0.154963 0.916307 +-0.448242 -0.147456 0.915344 +-0.442724 -0.142520 0.900295 +-0.435185 -0.144547 0.900129 +-0.433166 -0.152115 0.899510 +-0.438684 -0.157656 0.899057 +-0.446222 -0.155628 0.899222 +-0.448242 -0.148060 0.899842 +-0.442724 -0.140136 0.888675 +-0.435185 -0.142028 0.887846 +-0.433166 -0.149088 0.884753 +-0.438684 -0.154257 0.882489 +-0.446222 -0.152365 0.883317 +-0.448242 -0.145305 0.886410 +-0.442724 -0.134062 0.880228 +-0.435185 -0.135516 0.878789 +-0.433166 -0.140941 0.873423 +-0.438684 -0.144911 0.869493 +-0.446222 -0.143458 0.870932 +-0.448242 -0.138034 0.876299 +-0.442724 -0.121561 0.871032 +-0.435185 -0.122714 0.869373 +-0.433166 -0.127016 0.863180 +-0.438684 -0.130164 0.858645 +-0.446222 -0.129012 0.860305 +-0.448242 -0.124711 0.866498 +-0.442724 -0.019024 0.803887 +-0.435185 -0.020130 0.802197 +-0.433166 -0.024260 0.795891 +-0.438684 -0.027282 0.791275 +-0.446222 -0.026176 0.792964 +-0.448242 -0.022046 0.799270 +-0.435185 -0.015163 0.961895 +-0.442724 -0.015163 0.959875 +-0.444743 -0.115828 0.963804 +-0.438684 -0.115980 0.964327 +-0.433166 -0.114426 0.958997 +-0.435185 -0.112298 0.951708 +-0.442724 -0.111727 0.949754 +-0.447700 -0.112716 0.953139 +-0.448242 -0.114426 0.958997 +-0.446222 -0.130482 0.957545 +-0.438684 -0.131563 0.959262 +-0.433166 -0.128610 0.954571 +-0.435185 -0.124578 0.948160 +-0.442724 -0.123497 0.946441 +-0.448242 -0.126449 0.951136 +-0.435185 0.038029 0.958751 +-0.433166 -0.015163 0.969433 +-0.433166 0.038483 0.966291 +-0.438684 0.038814 0.971810 +-0.444743 -0.015163 0.974410 +-0.444743 0.038782 0.971269 +-0.448242 -0.015163 0.969433 +-0.448242 0.038483 0.966291 +-0.447700 0.038118 0.960230 +-0.442724 0.037909 0.956731 +-0.435185 0.067263 0.954535 +-0.433166 0.068769 0.961925 +-0.438684 0.069871 0.967335 +-0.444743 0.069763 0.966804 +-0.448242 0.068769 0.961925 +-0.447700 0.067559 0.955984 +-0.442724 0.066860 0.952555 +-0.435185 0.081972 0.951708 +-0.433166 0.084100 0.958997 +-0.438684 0.085654 0.964327 +-0.444743 0.085502 0.963804 +-0.448242 0.084100 0.958997 +-0.447700 0.082390 0.953139 +-0.442724 0.081400 0.949754 +-0.442724 0.102727 0.940230 +-0.435185 0.110621 0.928670 +-0.435185 0.104228 0.941584 +-0.433166 0.117839 0.930949 +-0.433166 0.109833 0.946633 +-0.438684 0.123122 0.932618 +-0.438684 0.113936 0.950330 +-0.444743 0.113534 0.949967 +-0.444743 0.122603 0.932455 +-0.448242 0.117839 0.930949 +-0.448242 0.109833 0.946633 +-0.447700 0.105327 0.942574 +-0.447700 0.112037 0.929117 +-0.442724 0.108688 0.928059 +-0.435185 0.113646 0.914897 +-0.433166 0.121153 0.915860 +-0.438684 0.126648 0.916565 +-0.444743 0.126109 0.916496 +-0.448242 0.121153 0.915860 +-0.447700 0.115119 0.915086 +-0.442724 0.111635 0.914640 +-0.435185 0.114221 0.900129 +-0.433166 0.121790 0.899510 +-0.438684 0.127329 0.899057 +-0.444743 0.126786 0.899101 +-0.448242 0.121790 0.899510 +-0.447700 0.115706 0.900008 +-0.442724 0.112193 0.900295 +-0.435185 0.111702 0.887846 +-0.433166 0.118762 0.884753 +-0.438684 0.123931 0.882489 +-0.444743 0.123424 0.882711 +-0.448242 0.118762 0.884753 +-0.447700 0.113087 0.887239 +-0.442724 0.109810 0.888675 +-0.435185 0.105190 0.878789 +-0.433166 0.110614 0.873423 +-0.438684 0.114586 0.869493 +-0.444743 0.114196 0.869879 +-0.448242 0.110614 0.873423 +-0.447700 0.106254 0.877737 +-0.442724 0.103735 0.880228 +-0.435185 0.092388 0.869373 +-0.433166 0.096689 0.863180 +-0.438684 0.099838 0.858645 +-0.444743 0.099529 0.859090 +-0.448242 0.096689 0.863180 +-0.447700 0.093232 0.868158 +-0.442724 0.091236 0.871032 +-0.435185 -0.010196 0.802197 +-0.433166 -0.006067 0.795891 +-0.438684 -0.003044 0.791275 +-0.444743 -0.003340 0.791727 +-0.447700 -0.004960 0.794201 +-0.448783 -0.007173 0.797580 +-0.447700 -0.009386 0.800960 +-0.442724 -0.011303 0.803887 +-0.435185 0.094252 0.948160 +-0.433166 0.098284 0.954571 +-0.438684 0.101236 0.959262 +-0.444743 0.100947 0.958802 +-0.448242 0.098284 0.954571 +-0.447700 0.095043 0.949418 +-0.442724 0.093171 0.946441 +-0.458525 -0.050293 0.479560 +-0.408804 -0.050293 0.508362 +-0.453385 -0.050293 0.533428 +-0.410645 -0.050293 0.533428 +-0.458525 -0.057032 0.479560 +-0.408804 -0.057032 0.508362 +-0.453385 -0.057032 0.533428 +-0.410645 -0.057032 0.533428 +-0.427501 -0.050293 0.455528 +-0.379586 -0.050293 0.484718 +-0.379586 -0.057032 0.484718 +-0.427501 -0.057032 0.455528 +-0.398920 -0.050293 0.455547 +-0.392822 -0.050293 0.457879 +-0.392822 -0.057032 0.457879 +-0.398920 -0.057032 0.455547 +-0.458525 0.019967 0.479560 +-0.453385 0.019967 0.533428 +-0.410645 0.019967 0.533428 +-0.408804 0.019967 0.508362 +-0.458525 0.026706 0.479560 +-0.408804 0.026706 0.508362 +-0.410645 0.026706 0.533428 +-0.453385 0.026706 0.533428 +-0.398920 0.019967 0.455547 +-0.392822 0.019967 0.457879 +-0.392822 0.026706 0.457879 +-0.398920 0.026706 0.455547 +-0.379586 0.019967 0.484718 +-0.427501 0.019967 0.455528 +-0.379586 0.026706 0.484718 +-0.427501 0.026706 0.455528 +-0.300337 -0.062632 0.314905 +-0.300337 0.025335 0.314905 +-0.464943 -0.062632 0.314905 +-0.464943 0.025335 0.314905 +-0.300337 -0.062632 0.340650 +-0.300337 0.025335 0.340650 +-0.464943 -0.062632 0.340650 +-0.464943 0.025335 0.340650 +-0.411579 -0.054043 0.509689 +-0.411579 0.020632 0.509689 +-0.452510 -0.054043 0.509689 +-0.452510 0.020632 0.509689 +-0.411579 -0.054043 0.519059 +-0.411579 0.020632 0.519059 +-0.452510 -0.054043 0.519059 +-0.452510 0.020632 0.519059 +-0.411579 -0.054043 0.490592 +-0.411579 0.020803 0.490592 +-0.452510 -0.054043 0.490592 +-0.452510 0.020803 0.490592 +-0.411579 -0.054043 0.499962 +-0.411579 0.020803 0.499962 +-0.452510 -0.054043 0.499962 +-0.452510 0.020803 0.499962 +-0.434868 -0.000483 0.334784 +-0.445664 -0.006716 0.334784 +-0.445664 -0.006716 0.497179 +-0.449927 -0.018430 0.334784 +-0.449927 -0.018430 0.497179 +-0.445664 -0.030145 0.334784 +-0.445664 -0.030145 0.497179 +-0.434868 -0.036378 0.334784 +-0.434868 -0.036378 0.497179 +-0.422591 -0.034213 0.334784 +-0.422591 -0.034213 0.497179 +-0.414578 -0.024663 0.334784 +-0.414578 -0.024663 0.497179 +-0.414578 -0.012197 0.334784 +-0.414578 -0.012197 0.497179 +-0.422591 -0.002648 0.334784 +-0.434868 -0.000483 0.497179 +-0.422591 -0.002648 0.497179 +-0.397435 0.039534 0.110252 +-0.385489 0.039534 0.112359 +-0.385489 -0.076395 0.112359 +-0.397435 -0.076395 0.110252 +-0.377691 0.039534 0.121652 +-0.377691 -0.076395 0.121652 +-0.377691 0.039534 0.133783 +-0.377691 -0.076395 0.133783 +-0.385489 0.039534 0.143076 +-0.385489 -0.076395 0.143076 +-0.397435 0.039534 0.145182 +-0.397435 -0.076395 0.145183 +-0.407941 0.039534 0.139117 +-0.407941 -0.076395 0.139117 +-0.412090 0.039534 0.127717 +-0.412090 -0.076395 0.127717 +-0.407941 0.039534 0.116318 +-0.407941 -0.076395 0.116318 +-0.335814 -0.013491 0.115999 +-0.335814 -0.021339 0.117383 +-0.393146 -0.021339 0.117383 +-0.393146 -0.013491 0.115999 +-0.335814 -0.026460 0.123487 +-0.393146 -0.026460 0.123487 +-0.335814 -0.026460 0.131455 +-0.393146 -0.026460 0.131455 +-0.335814 -0.021339 0.137559 +-0.393146 -0.021339 0.137559 +-0.335814 -0.013491 0.138943 +-0.393146 -0.013491 0.138943 +-0.335814 -0.006591 0.134959 +-0.393146 -0.006591 0.134959 +-0.335814 -0.003866 0.127471 +-0.393146 -0.003866 0.127471 +-0.335814 -0.006591 0.119983 +-0.393146 -0.006591 0.119983 +-0.436595 -0.033361 0.912128 +-0.443932 -0.033361 0.912128 +-0.442724 -0.075661 0.907796 +-0.437803 -0.075661 0.907796 +-0.438346 -0.093908 0.903420 +-0.442181 -0.093908 0.903420 +-0.437668 -0.033361 0.913747 +-0.442858 -0.033361 0.913747 +-0.438523 -0.075661 0.909415 +-0.442004 -0.075661 0.909415 +-0.438907 -0.093908 0.905040 +-0.441620 -0.093908 0.905040 +-0.438875 -0.111724 0.896412 +-0.441651 -0.111724 0.896412 +-0.439282 -0.112045 0.897264 +-0.441245 -0.112045 0.897264 +-0.438875 -0.113817 0.901842 +-0.438346 -0.095658 0.910665 +-0.437803 -0.077037 0.916535 +-0.436595 -0.033438 0.925877 +-0.437668 -0.033438 0.925877 +-0.438523 -0.077037 0.916535 +-0.438907 -0.095658 0.910665 +-0.439282 -0.113817 0.901842 +-0.441245 -0.113817 0.901842 +-0.441620 -0.095658 0.910665 +-0.442004 -0.077037 0.916535 +-0.442858 -0.033438 0.925877 +-0.443932 -0.033438 0.925877 +-0.442724 -0.077037 0.916535 +-0.442181 -0.095658 0.910665 +-0.441651 -0.113817 0.901842 + + + + + + + + + + + +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 0.000691 0.000000 +1.000000 0.000691 0.000000 +1.000000 0.000691 0.000000 +1.000000 0.000691 0.000000 +1.000000 0.000691 0.000000 +1.000000 0.000691 0.000000 +0.911684 -0.410892 0.000000 +0.602681 -0.797982 0.000000 +0.911684 -0.410893 0.000000 +0.911684 -0.410893 0.000000 +0.602681 -0.797982 0.000000 +0.602681 -0.797982 0.000000 +0.916173 0.400782 0.000000 +0.589034 0.808108 0.000000 +0.916173 0.400782 0.000000 +0.916173 0.400782 0.000000 +0.916173 0.400782 0.000000 +0.916173 0.400782 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.388846 -0.921303 0.000000 +0.302574 -0.953126 0.000000 +0.388846 -0.921303 0.000000 +0.388846 -0.921303 0.000000 +0.302574 -0.953126 0.000000 +0.302574 -0.953126 0.000000 +0.393221 0.919444 0.000000 +0.309391 0.950935 0.000000 +0.393221 0.919444 0.000000 +0.393221 0.919444 0.000000 +0.393221 0.919444 0.000000 +0.393221 0.919444 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.312340 -0.949970 0.000000 +0.312340 -0.949970 0.000000 +0.312340 -0.949970 0.000000 +0.312340 -0.949970 0.000000 +0.312340 -0.949970 0.000000 +0.312340 -0.949970 0.000000 +0.305661 0.952140 0.000000 +0.305661 0.952140 0.000000 +0.305661 0.952140 0.000000 +0.305661 0.952140 0.000000 +0.305661 0.952140 0.000000 +0.305661 0.952140 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.312341 -0.949970 0.000000 +0.312341 -0.949970 0.000000 +0.312341 -0.949970 0.000000 +0.312341 -0.949970 0.000000 +0.312341 -0.949970 0.000000 +0.312341 -0.949970 0.000000 +0.305684 0.952133 0.000000 +0.305684 0.952133 0.000000 +0.305684 0.952133 0.000000 +0.305684 0.952133 0.000000 +0.305684 0.952133 0.000000 +0.305684 0.952133 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.371145 -0.005697 -0.928557 +0.000000 0.000000 -1.000000 +0.371145 -0.005697 -0.928557 +-0.010652 -0.999943 0.000000 +-0.010652 -0.999943 0.000000 +-0.010652 -0.999943 0.000000 +-0.010652 -0.999943 0.000000 +-0.010652 -0.999943 0.000000 +-0.010652 -0.999943 0.000000 +-0.003412 0.999994 0.000000 +-0.003412 0.999994 0.000000 +-0.003412 0.999994 0.000000 +-0.003412 0.999994 0.000000 +-0.003412 0.999994 0.000000 +-0.003412 0.999994 0.000000 +-1.000000 -0.000862 0.000000 +-1.000000 -0.000862 0.000000 +-1.000000 -0.000862 0.000000 +-1.000000 -0.000862 0.000000 +-1.000000 -0.000862 0.000000 +-1.000000 -0.000862 0.000000 +0.981711 0.190376 0.000000 +0.981711 0.190376 0.000000 +0.981711 0.190376 0.000000 +0.981711 0.190376 0.000000 +0.981711 0.190376 0.000000 +0.981711 0.190376 0.000000 +0.981714 -0.190363 0.000000 +0.981714 -0.190363 0.000000 +0.981714 -0.190363 0.000000 +0.981714 -0.190363 0.000000 +0.981714 -0.190363 0.000000 +0.981714 -0.190363 0.000000 +0.864415 0.502779 0.000000 +0.864415 0.502779 0.000000 +0.864415 0.502779 0.000000 +0.864415 0.502779 0.000000 +0.864415 0.502779 0.000000 +0.864415 0.502779 0.000000 +0.864393 -0.502817 0.000000 +0.864393 -0.502817 0.000000 +0.864393 -0.502817 0.000000 +0.864393 -0.502817 0.000000 +0.864393 -0.502817 0.000000 +0.864393 -0.502817 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.864415 0.502779 0.000000 +-0.864415 0.502779 0.000000 +-0.864415 0.502779 0.000000 +-0.864415 0.502779 0.000000 +-0.864415 0.502779 0.000000 +-0.864415 0.502779 0.000000 +-0.864393 -0.502817 0.000000 +-0.864393 -0.502817 0.000000 +-0.864393 -0.502817 0.000000 +-0.864393 -0.502817 0.000000 +-0.864393 -0.502817 0.000000 +-0.864393 -0.502817 0.000000 +-0.981711 0.190378 0.000000 +-0.981711 0.190378 0.000000 +-0.981711 0.190378 0.000000 +-0.981711 0.190378 0.000000 +-0.981711 0.190378 0.000000 +-0.981711 0.190378 0.000000 +-0.981713 -0.190365 0.000000 +-0.981713 -0.190365 0.000000 +-0.981713 -0.190365 0.000000 +-0.981713 -0.190365 0.000000 +-0.981713 -0.190365 0.000000 +-0.981713 -0.190365 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.010650 -0.999943 0.000000 +-0.010650 -0.999943 0.000000 +-0.010650 -0.999943 0.000000 +-0.010650 -0.999943 0.000000 +-0.010650 -0.999943 0.000000 +-0.010650 -0.999943 0.000000 +-0.003413 0.999994 0.000000 +-0.003413 0.999994 0.000000 +-0.003413 0.999994 0.000000 +-0.003413 0.999994 0.000000 +-0.003413 0.999994 0.000000 +-0.003413 0.999994 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.498592 0.866837 0.000000 +0.498592 0.866836 0.000000 +0.498592 0.866837 0.000000 +0.498592 0.866837 0.000000 +0.498592 0.866836 0.000000 +0.498592 0.866837 0.000000 +0.498594 -0.866836 0.000000 +0.498594 -0.866836 0.000000 +0.498594 -0.866836 0.000000 +0.498594 -0.866836 0.000000 +0.498594 -0.866836 0.000000 +0.498594 -0.866836 0.000000 +-0.498594 0.866836 0.000000 +-0.498594 0.866836 0.000000 +-0.498594 0.866836 0.000000 +-0.498594 0.866836 0.000000 +-0.498594 0.866836 0.000000 +-0.498594 0.866836 0.000000 +-0.498595 -0.866835 0.000000 +-0.498595 -0.866835 0.000000 +-0.498595 -0.866835 0.000000 +-0.498595 -0.866835 0.000000 +-0.498595 -0.866835 0.000000 +-0.498595 -0.866835 0.000000 +0.998583 0.000000 0.053215 +0.998583 0.000000 0.053215 +0.998583 0.000000 0.053215 +0.998583 0.000000 0.053215 +0.998583 0.000000 0.053215 +0.998583 0.000000 0.053215 +0.065452 0.877396 0.475282 +0.000000 0.886900 0.461961 +0.065452 0.877396 0.475282 +0.000000 0.886900 0.461961 +0.065452 0.877396 0.475282 +0.065452 0.877396 0.475282 +0.998583 0.000000 0.053209 +0.998583 0.000000 0.053209 +0.998583 0.000000 0.053209 +0.998583 0.000000 0.053209 +0.998583 0.000000 0.053209 +0.998583 0.000000 0.053209 +0.105632 0.962130 0.251290 +0.105632 0.962130 0.251290 +0.105632 0.962131 0.251290 +0.105632 0.962130 0.251290 +0.071389 0.956976 0.281249 +0.105632 0.962131 0.251290 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.841303 0.540564 0.000000 +-0.841303 0.540564 0.000000 +-0.841303 0.540564 0.000000 +-0.841303 0.540564 0.000000 +-0.841303 0.540564 0.000000 +-0.841303 0.540564 0.000000 +-0.743494 0.668742 0.000000 +-0.743494 0.668742 0.000000 +-0.743494 0.668742 0.000000 +-0.743494 0.668742 0.000000 +-0.743494 0.668742 0.000000 +-0.743494 0.668742 0.000000 +-0.217041 0.976162 0.000000 +-0.217041 0.976163 0.000000 +-0.217041 0.976162 0.000000 +-0.217041 0.976162 0.000000 +-0.217041 0.976163 0.000000 +-0.217041 0.976162 0.000000 +0.217041 0.976163 0.000000 +0.554904 0.831914 0.000000 +0.217041 0.976163 0.000000 +0.554904 0.831914 0.000000 +0.217041 0.976163 0.000000 +0.554905 0.831914 0.000000 +0.153318 0.000000 0.988177 +0.033688 0.000000 0.999432 +0.033688 0.000000 0.999432 +0.033688 0.000000 0.999432 +0.153318 0.000000 0.988177 +0.033688 0.000000 0.999432 +0.841322 0.540535 0.000000 +0.841322 0.540535 0.000000 +0.841322 0.540535 0.000000 +0.841322 0.540535 0.000000 +0.841322 0.540535 0.000000 +0.841322 0.540535 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.129426 0.965918 0.224167 +-0.129426 0.965918 0.224167 +-0.129426 0.965918 0.224167 +-0.129426 0.965918 0.224167 +-0.129426 0.965918 0.224167 +-0.129427 0.965918 0.224167 +-0.243255 0.965913 0.088540 +-0.243241 0.965918 0.088526 +-0.243255 0.965913 0.088540 +-0.243255 0.965913 0.088540 +-0.243255 0.965913 0.088540 +-0.243255 0.965913 0.088540 +-0.243255 0.965913 -0.088537 +-0.243255 0.965913 -0.088537 +-0.243255 0.965913 -0.088537 +-0.243255 0.965913 -0.088537 +-0.243255 0.965913 -0.088537 +-0.243247 0.965915 -0.088537 +-0.129407 0.965920 -0.224171 +-0.129407 0.965920 -0.224171 +-0.129407 0.965920 -0.224171 +-0.129407 0.965920 -0.224171 +-0.129442 0.965910 -0.224195 +-0.129407 0.965920 -0.224171 +0.044935 0.965909 -0.254952 +0.044943 0.965916 -0.254926 +0.044943 0.965916 -0.254926 +0.044943 0.965916 -0.254926 +0.044935 0.965909 -0.254952 +0.044943 0.965916 -0.254926 +0.198311 0.965911 -0.166398 +0.198311 0.965911 -0.166398 +0.198305 0.965913 -0.166396 +0.198311 0.965911 -0.166398 +0.198311 0.965911 -0.166398 +0.198311 0.965911 -0.166398 +0.258867 0.965913 0.000000 +0.258867 0.965913 0.000000 +0.258867 0.965913 0.000000 +0.258867 0.965913 0.000000 +0.258867 0.965913 0.000000 +0.258867 0.965913 0.000000 +0.198306 0.965913 0.166394 +0.198308 0.965911 0.166400 +0.198306 0.965913 0.166394 +0.198308 0.965911 0.166400 +0.198306 0.965913 0.166394 +0.198306 0.965913 0.166394 +0.044955 0.965911 0.254941 +0.044955 0.965911 0.254941 +0.044959 0.965914 0.254928 +0.044955 0.965911 0.254941 +0.044955 0.965911 0.254941 +0.044955 0.965911 0.254941 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.500075 0.000000 0.865982 +-0.500075 0.000000 0.865982 +-0.500075 0.000000 0.865982 +-0.500075 0.000000 0.865982 +-0.500075 0.000000 0.865982 +-0.500075 0.000000 0.865982 +-0.939679 0.000000 0.342057 +-0.939679 0.000000 0.342057 +-0.939679 0.000000 0.342057 +-0.939679 0.000000 0.342057 +-0.939679 0.000000 0.342057 +-0.939679 0.000000 0.342057 +-0.939678 0.000000 -0.342059 +-0.939678 0.000000 -0.342059 +-0.939679 0.000000 -0.342059 +-0.939678 0.000000 -0.342059 +-0.939679 0.000000 -0.342059 +-0.939678 0.000000 -0.342059 +-0.499959 0.000000 -0.866049 +-0.499959 0.000000 -0.866049 +-0.499959 0.000000 -0.866049 +-0.499959 0.000000 -0.866049 +-0.499959 0.000000 -0.866049 +-0.499959 0.000000 -0.866049 +0.173633 0.000000 -0.984810 +0.173633 0.000000 -0.984810 +0.173633 0.000000 -0.984811 +0.173633 0.000000 -0.984810 +0.173633 0.000000 -0.984810 +0.173633 0.000000 -0.984811 +0.766056 0.000000 -0.642773 +0.766056 0.000000 -0.642773 +0.766056 0.000000 -0.642773 +0.766056 0.000000 -0.642773 +0.766056 0.000000 -0.642773 +0.766056 0.000000 -0.642773 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.766056 0.000000 0.642773 +0.766056 0.000000 0.642773 +0.766056 0.000000 0.642773 +0.766056 0.000000 0.642773 +0.766056 0.000000 0.642773 +0.766056 0.000000 0.642773 +0.173633 0.000000 0.984810 +0.173633 0.000000 0.984810 +0.173633 0.000000 0.984811 +0.173633 0.000000 0.984810 +0.173633 0.000000 0.984810 +0.173633 0.000000 0.984811 +-0.500010 0.000000 0.866020 +-0.500010 0.000000 0.866020 +-0.500010 0.000000 0.866020 +-0.500010 0.000000 0.866020 +-0.500010 0.000000 0.866020 +-0.500010 0.000000 0.866020 +-0.939701 0.000000 0.341997 +-0.939701 0.000000 0.341997 +-0.939701 0.000000 0.341997 +-0.939701 0.000000 0.341997 +-0.939701 0.000000 0.341997 +-0.939701 0.000000 0.341997 +-0.939694 0.000000 -0.342017 +-0.939694 0.000000 -0.342017 +-0.939694 0.000000 -0.342017 +-0.939694 0.000000 -0.342017 +-0.939694 0.000000 -0.342017 +-0.939694 0.000000 -0.342017 +-0.500009 0.000000 -0.866020 +-0.500009 0.000000 -0.866020 +-0.500009 0.000000 -0.866020 +-0.500009 0.000000 -0.866020 +-0.500009 0.000000 -0.866020 +-0.500009 0.000000 -0.866020 +0.173620 0.000000 -0.984813 +0.173620 0.000000 -0.984813 +0.173620 0.000000 -0.984813 +0.173620 0.000000 -0.984813 +0.173620 0.000000 -0.984813 +0.173620 0.000000 -0.984813 +0.766047 0.000000 -0.642785 +0.766047 0.000000 -0.642785 +0.766047 0.000000 -0.642785 +0.766047 0.000000 -0.642785 +0.766047 0.000000 -0.642785 +0.766047 0.000000 -0.642785 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.766046 0.000000 0.642785 +0.766046 0.000000 0.642785 +0.766046 0.000000 0.642785 +0.766046 0.000000 0.642785 +0.766046 0.000000 0.642785 +0.766046 0.000000 0.642785 +0.173680 0.000000 0.984802 +0.173680 0.000000 0.984802 +0.173680 0.000000 0.984802 +0.173680 0.000000 0.984802 +0.173680 0.000000 0.984802 +0.173680 0.000000 0.984802 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.498907 0.065052 0.864211 +-0.498907 0.065052 0.864211 +-0.498907 0.065052 0.864211 +-0.498907 0.065052 0.864211 +-0.498952 0.065037 0.864186 +-0.498907 0.065052 0.864211 +-0.937714 0.065058 0.341262 +-0.937700 0.065045 0.341304 +-0.937700 0.065045 0.341304 +-0.937700 0.065045 0.341304 +-0.937700 0.065045 0.341304 +-0.937700 0.065045 0.341304 +-0.937702 0.065057 -0.341295 +-0.937702 0.065057 -0.341295 +-0.937702 0.065057 -0.341295 +-0.937702 0.065057 -0.341295 +-0.937702 0.065057 -0.341295 +-0.937699 0.065055 -0.341305 +-0.498888 0.065059 -0.864221 +-0.498985 0.065027 -0.864168 +-0.498985 0.065027 -0.864168 +-0.498985 0.065027 -0.864168 +-0.498985 0.065027 -0.864168 +-0.498985 0.065027 -0.864168 +0.173205 0.065046 -0.982735 +0.173205 0.065046 -0.982735 +0.173205 0.065046 -0.982735 +0.173205 0.065046 -0.982735 +0.173205 0.065046 -0.982735 +0.173283 0.065024 -0.982723 +0.764432 0.065042 -0.641415 +0.764481 0.065065 -0.641355 +0.764481 0.065065 -0.641355 +0.764481 0.065065 -0.641355 +0.764481 0.065065 -0.641355 +0.764481 0.065065 -0.641355 +0.997882 0.065053 0.000000 +0.997882 0.065053 0.000000 +0.997882 0.065053 0.000000 +0.997882 0.065053 0.000000 +0.997882 0.065053 0.000000 +0.997882 0.065053 0.000000 +0.764431 0.065042 0.641416 +0.764431 0.065042 0.641416 +0.764431 0.065042 0.641416 +0.764431 0.065042 0.641416 +0.764431 0.065042 0.641416 +0.764439 0.065046 0.641406 +0.173283 0.065051 0.982722 +0.173289 0.065049 0.982720 +0.173289 0.065049 0.982721 +0.173289 0.065049 0.982721 +0.173289 0.065049 0.982720 +0.173289 0.065049 0.982721 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.365183 0.000000 -0.930936 +-0.365183 0.000000 -0.930936 +-0.365183 0.000000 -0.930936 +-0.365183 0.000000 -0.930936 +-0.365183 0.000000 -0.930936 +-0.365183 0.000000 -0.930936 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.276912 0.000000 0.960895 +0.276912 0.000000 0.960895 +0.276912 0.000000 0.960895 +0.276912 0.000000 0.960895 +0.276912 0.000000 0.960895 +0.276912 0.000000 0.960895 +-0.919875 0.000000 0.392213 +-0.919875 0.000000 0.392213 +-0.919875 0.000000 0.392213 +-0.919875 0.000000 0.392213 +-0.919875 0.000000 0.392213 +-0.919875 0.000000 0.392213 +-0.973126 0.000000 -0.230273 +-0.973126 0.000000 -0.230273 +-0.973126 0.000000 -0.230273 +-0.973126 0.000000 -0.230273 +-0.973126 0.000000 -0.230273 +-0.973126 0.000000 -0.230273 +-0.998788 0.000000 -0.049225 +-0.986019 0.000000 0.166631 +-0.998788 0.000000 -0.049225 +-0.986019 0.000000 0.166631 +-0.986019 0.000000 0.166631 +-0.998788 0.000000 -0.049225 +-0.669095 0.000000 0.743177 +-0.805887 0.000000 0.592069 +-0.805887 0.000000 0.592069 +-0.805887 0.000000 0.592069 +-0.669095 0.000000 0.743177 +-0.669094 0.000000 0.743177 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.998583 0.000000 0.053213 +-0.998583 0.000000 0.053213 +-0.998583 0.000000 0.053213 +-0.998583 0.000000 0.053213 +-0.998583 0.000000 0.053213 +-0.998583 0.000000 0.053213 +-0.998583 0.000000 0.053209 +-0.998583 0.000000 0.053209 +-0.998583 0.000000 0.053209 +-0.998583 0.000000 0.053209 +-0.998583 0.000000 0.053209 +-0.998583 0.000000 0.053209 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.517879 0.000000 0.855454 +0.355384 0.000000 0.934720 +0.517879 0.000000 0.855454 +0.002608 0.000000 0.999997 +0.002608 0.000000 0.999997 +0.002608 0.000000 0.999997 +0.002608 0.000000 0.999997 +0.002608 0.000000 0.999997 +0.002608 0.000000 0.999997 +1.000000 -0.000691 0.000000 +1.000000 -0.000691 0.000000 +1.000000 -0.000691 0.000000 +1.000000 -0.000691 0.000000 +1.000000 -0.000691 0.000000 +1.000000 -0.000691 0.000000 +0.602681 0.797982 0.000000 +0.911684 0.410893 0.000000 +0.602681 0.797982 0.000000 +0.911684 0.410893 0.000000 +0.602681 0.797982 0.000000 +0.911684 0.410892 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.589034 -0.808108 0.000000 +0.916173 -0.400782 0.000000 +0.916173 -0.400782 0.000000 +0.916173 -0.400782 0.000000 +0.589034 -0.808108 0.000000 +0.589034 -0.808108 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.302574 0.953126 0.000000 +0.388846 0.921303 0.000000 +0.302574 0.953126 0.000000 +0.388846 0.921303 0.000000 +0.302574 0.953126 0.000000 +0.388846 0.921303 0.000000 +0.393221 -0.919444 0.000000 +0.309391 -0.950935 0.000000 +0.393221 -0.919444 0.000000 +0.393221 -0.919444 0.000000 +0.309391 -0.950935 0.000000 +0.309391 -0.950935 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.312340 0.949970 0.000000 +0.312340 0.949970 0.000000 +0.312340 0.949970 0.000000 +0.312340 0.949970 0.000000 +0.312340 0.949970 0.000000 +0.312340 0.949970 0.000000 +0.305661 -0.952140 0.000000 +0.305661 -0.952140 0.000000 +0.305661 -0.952140 0.000000 +0.305661 -0.952140 0.000000 +0.305661 -0.952140 0.000000 +0.305661 -0.952140 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.312341 0.949970 0.000000 +0.312341 0.949970 0.000000 +0.312341 0.949970 0.000000 +0.312341 0.949970 0.000000 +0.312341 0.949970 0.000000 +0.312341 0.949970 0.000000 +0.305685 -0.952133 0.000000 +0.305684 -0.952133 0.000000 +0.305684 -0.952133 0.000000 +0.305684 -0.952133 0.000000 +0.305685 -0.952133 0.000000 +0.305684 -0.952133 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.375221 0.003684 -0.926928 +0.375221 0.003684 -0.926928 +0.375221 0.003684 -0.926928 +-0.010652 0.999943 0.000000 +-0.010652 0.999943 0.000000 +-0.010652 0.999943 0.000000 +-0.010652 0.999943 0.000000 +-0.010652 0.999943 0.000000 +-0.010652 0.999943 0.000000 +-0.003412 -0.999994 0.000000 +-0.003412 -0.999994 0.000000 +-0.003412 -0.999994 0.000000 +-0.003412 -0.999994 0.000000 +-0.003412 -0.999994 0.000000 +-0.003412 -0.999994 0.000000 +-1.000000 0.000862 0.000000 +-1.000000 0.000862 0.000000 +-1.000000 0.000862 0.000000 +-1.000000 0.000862 0.000000 +-1.000000 0.000862 0.000000 +-1.000000 0.000862 0.000000 +0.981711 -0.190376 0.000000 +0.981711 -0.190376 0.000000 +0.981711 -0.190376 0.000000 +0.981711 -0.190376 0.000000 +0.981711 -0.190376 0.000000 +0.981711 -0.190376 0.000000 +0.981714 0.190363 0.000000 +0.981714 0.190363 0.000000 +0.981714 0.190363 0.000000 +0.981714 0.190363 0.000000 +0.981714 0.190363 0.000000 +0.981714 0.190363 0.000000 +0.864415 -0.502779 0.000000 +0.864415 -0.502779 0.000000 +0.864415 -0.502779 0.000000 +0.864415 -0.502779 0.000000 +0.864415 -0.502779 0.000000 +0.864415 -0.502779 0.000000 +0.864393 0.502817 0.000000 +0.864393 0.502817 0.000000 +0.864393 0.502817 0.000000 +0.864393 0.502817 0.000000 +0.864393 0.502817 0.000000 +0.864393 0.502817 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.864415 -0.502779 0.000000 +-0.864415 -0.502779 0.000000 +-0.864415 -0.502779 0.000000 +-0.864415 -0.502779 0.000000 +-0.864415 -0.502779 0.000000 +-0.864415 -0.502779 0.000000 +-0.864393 0.502817 0.000000 +-0.864393 0.502817 0.000000 +-0.864393 0.502817 0.000000 +-0.864393 0.502817 0.000000 +-0.864393 0.502817 0.000000 +-0.864393 0.502817 0.000000 +-0.981711 -0.190378 0.000000 +-0.981711 -0.190378 0.000000 +-0.981711 -0.190378 0.000000 +-0.981711 -0.190378 0.000000 +-0.981711 -0.190378 0.000000 +-0.981711 -0.190378 0.000000 +-0.981713 0.190365 0.000000 +-0.981713 0.190365 0.000000 +-0.981713 0.190365 0.000000 +-0.981713 0.190365 0.000000 +-0.981713 0.190365 0.000000 +-0.981713 0.190365 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.010650 0.999943 0.000000 +-0.010650 0.999943 0.000000 +-0.010650 0.999943 0.000000 +-0.010650 0.999943 0.000000 +-0.010650 0.999943 0.000000 +-0.010650 0.999943 0.000000 +-0.003413 -0.999994 0.000000 +-0.003413 -0.999994 0.000000 +-0.003413 -0.999994 0.000000 +-0.003413 -0.999994 0.000000 +-0.003413 -0.999994 0.000000 +-0.003413 -0.999994 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.498592 -0.866836 0.000000 +0.498592 -0.866837 0.000000 +0.498592 -0.866837 0.000000 +0.498592 -0.866837 0.000000 +0.498592 -0.866837 0.000000 +0.498592 -0.866836 0.000000 +0.498594 0.866836 0.000000 +0.498594 0.866836 0.000000 +0.498594 0.866836 0.000000 +0.498594 0.866836 0.000000 +0.498594 0.866836 0.000000 +0.498594 0.866836 0.000000 +-0.498594 -0.866836 0.000000 +-0.498594 -0.866836 0.000000 +-0.498594 -0.866836 0.000000 +-0.498594 -0.866836 0.000000 +-0.498594 -0.866836 0.000000 +-0.498594 -0.866836 0.000000 +-0.498595 0.866835 0.000000 +-0.498595 0.866835 0.000000 +-0.498595 0.866835 0.000000 +-0.498595 0.866835 0.000000 +-0.498595 0.866835 0.000000 +-0.498595 0.866835 0.000000 +0.998583 0.000000 0.053215 +0.998583 0.000000 0.053215 +0.998583 0.000000 0.053215 +0.998583 0.000000 0.053215 +0.998583 0.000000 0.053215 +0.998583 0.000000 0.053215 +0.065452 -0.877396 0.475282 +0.000000 -0.886900 0.461961 +0.065452 -0.877396 0.475282 +0.000000 -0.886900 0.461961 +0.065452 -0.877396 0.475282 +0.065452 -0.877396 0.475282 +0.998583 0.000000 0.053209 +0.998583 0.000000 0.053209 +0.998583 0.000000 0.053209 +0.998583 0.000000 0.053209 +0.998583 0.000000 0.053209 +0.998583 0.000000 0.053209 +0.071389 -0.956976 0.281249 +0.071389 -0.956976 0.281249 +0.105632 -0.962130 0.251290 +0.071389 -0.956976 0.281249 +0.071389 -0.956976 0.281249 +0.071389 -0.956976 0.281249 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.841303 -0.540564 0.000000 +-0.841303 -0.540564 0.000000 +-0.841303 -0.540564 0.000000 +-0.841303 -0.540564 0.000000 +-0.841303 -0.540564 0.000000 +-0.841303 -0.540564 0.000000 +-0.743494 -0.668742 0.000000 +-0.743494 -0.668742 0.000000 +-0.743494 -0.668742 0.000000 +-0.743494 -0.668742 0.000000 +-0.743494 -0.668742 0.000000 +-0.743494 -0.668742 0.000000 +-0.217041 -0.976162 0.000000 +-0.217041 -0.976163 0.000000 +-0.217041 -0.976162 0.000000 +-0.217041 -0.976163 0.000000 +-0.217041 -0.976162 0.000000 +-0.217041 -0.976162 0.000000 +0.554905 -0.831914 0.000000 +0.217041 -0.976163 0.000000 +0.554904 -0.831914 0.000000 +0.554904 -0.831914 0.000000 +0.217041 -0.976163 0.000000 +0.217041 -0.976163 0.000000 +0.841322 -0.540535 0.000000 +0.841322 -0.540535 0.000000 +0.841322 -0.540535 0.000000 +0.841322 -0.540535 0.000000 +0.841322 -0.540535 0.000000 +0.841322 -0.540535 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.129426 -0.965918 0.224167 +-0.129426 -0.965918 0.224167 +-0.129426 -0.965918 0.224167 +-0.129426 -0.965918 0.224167 +-0.129426 -0.965918 0.224167 +-0.129427 -0.965918 0.224167 +-0.243241 -0.965918 0.088526 +-0.243241 -0.965918 0.088526 +-0.243241 -0.965918 0.088526 +-0.243241 -0.965918 0.088526 +-0.243241 -0.965918 0.088526 +-0.243255 -0.965913 0.088540 +-0.243255 -0.965913 -0.088537 +-0.243255 -0.965913 -0.088537 +-0.243255 -0.965913 -0.088537 +-0.243255 -0.965913 -0.088537 +-0.243247 -0.965915 -0.088537 +-0.243255 -0.965913 -0.088537 +-0.129442 -0.965910 -0.224195 +-0.129442 -0.965910 -0.224195 +-0.129407 -0.965920 -0.224171 +-0.129442 -0.965910 -0.224195 +-0.129442 -0.965910 -0.224195 +-0.129442 -0.965910 -0.224195 +0.044943 -0.965916 -0.254926 +0.044935 -0.965909 -0.254952 +0.044935 -0.965909 -0.254952 +0.044935 -0.965909 -0.254952 +0.044943 -0.965916 -0.254926 +0.044935 -0.965909 -0.254952 +0.198305 -0.965913 -0.166396 +0.198305 -0.965913 -0.166396 +0.198305 -0.965913 -0.166396 +0.198305 -0.965913 -0.166396 +0.198305 -0.965913 -0.166396 +0.198311 -0.965911 -0.166398 +0.258867 -0.965913 0.000000 +0.258867 -0.965913 0.000000 +0.258867 -0.965913 0.000000 +0.258867 -0.965913 0.000000 +0.258867 -0.965913 0.000000 +0.258867 -0.965913 0.000000 +0.198306 -0.965913 0.166394 +0.198308 -0.965911 0.166400 +0.198306 -0.965913 0.166394 +0.198308 -0.965911 0.166400 +0.198306 -0.965913 0.166394 +0.198306 -0.965913 0.166394 +0.044959 -0.965914 0.254928 +0.044959 -0.965914 0.254928 +0.044959 -0.965914 0.254928 +0.044959 -0.965914 0.254928 +0.044959 -0.965914 0.254928 +0.044955 -0.965911 0.254941 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.500075 0.000000 0.865982 +-0.500075 0.000000 0.865982 +-0.500075 0.000000 0.865982 +-0.500075 0.000000 0.865982 +-0.500075 0.000000 0.865982 +-0.500075 0.000000 0.865982 +-0.939679 0.000000 0.342057 +-0.939679 0.000000 0.342057 +-0.939679 0.000000 0.342057 +-0.939679 0.000000 0.342057 +-0.939679 0.000000 0.342057 +-0.939679 0.000000 0.342057 +-0.939678 0.000000 -0.342059 +-0.939678 0.000000 -0.342059 +-0.939679 0.000000 -0.342059 +-0.939678 0.000000 -0.342059 +-0.939678 0.000000 -0.342059 +-0.939679 0.000000 -0.342059 +-0.499959 0.000000 -0.866049 +-0.499959 0.000000 -0.866049 +-0.499959 0.000000 -0.866049 +-0.499959 0.000000 -0.866049 +-0.499959 0.000000 -0.866049 +-0.499959 0.000000 -0.866049 +0.173633 0.000000 -0.984810 +0.173633 0.000000 -0.984811 +0.173633 0.000000 -0.984810 +0.173633 0.000000 -0.984810 +0.173633 0.000000 -0.984811 +0.173633 0.000000 -0.984810 +0.766056 0.000000 -0.642773 +0.766056 0.000000 -0.642773 +0.766056 0.000000 -0.642773 +0.766056 0.000000 -0.642773 +0.766056 0.000000 -0.642773 +0.766056 0.000000 -0.642773 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.766056 0.000000 0.642773 +0.766056 0.000000 0.642773 +0.766056 0.000000 0.642773 +0.766056 0.000000 0.642773 +0.766056 0.000000 0.642773 +0.766056 0.000000 0.642773 +0.173633 0.000000 0.984810 +0.173633 0.000000 0.984810 +0.173633 0.000000 0.984811 +0.173633 0.000000 0.984810 +0.173633 0.000000 0.984811 +0.173633 0.000000 0.984810 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.498952 -0.065037 0.864186 +-0.498952 -0.065037 0.864186 +-0.498952 -0.065037 0.864186 +-0.498952 -0.065037 0.864186 +-0.498952 -0.065037 0.864186 +-0.498907 -0.065052 0.864211 +-0.937700 -0.065045 0.341304 +-0.937700 -0.065045 0.341304 +-0.937700 -0.065045 0.341304 +-0.937700 -0.065045 0.341304 +-0.937700 -0.065045 0.341304 +-0.937714 -0.065058 0.341262 +-0.937699 -0.065055 -0.341305 +-0.937699 -0.065055 -0.341305 +-0.937702 -0.065057 -0.341295 +-0.937699 -0.065055 -0.341305 +-0.937699 -0.065055 -0.341305 +-0.937699 -0.065055 -0.341305 +-0.498985 -0.065027 -0.864168 +-0.498985 -0.065027 -0.864168 +-0.498985 -0.065027 -0.864168 +-0.498985 -0.065027 -0.864168 +-0.498888 -0.065059 -0.864221 +-0.498985 -0.065027 -0.864168 +0.173283 -0.065024 -0.982723 +0.173283 -0.065024 -0.982723 +0.173283 -0.065024 -0.982723 +0.173283 -0.065024 -0.982723 +0.173283 -0.065024 -0.982723 +0.173205 -0.065046 -0.982735 +0.764432 -0.065042 -0.641415 +0.764481 -0.065065 -0.641355 +0.764432 -0.065042 -0.641415 +0.764432 -0.065042 -0.641415 +0.764432 -0.065042 -0.641415 +0.764432 -0.065042 -0.641415 +0.997882 -0.065053 0.000000 +0.997882 -0.065053 0.000000 +0.997882 -0.065053 0.000000 +0.997882 -0.065053 0.000000 +0.997882 -0.065053 0.000000 +0.997882 -0.065053 0.000000 +0.764439 -0.065046 0.641406 +0.764431 -0.065042 0.641416 +0.764431 -0.065042 0.641416 +0.764431 -0.065042 0.641416 +0.764431 -0.065042 0.641416 +0.764431 -0.065042 0.641416 +0.173289 -0.065049 0.982721 +0.173289 -0.065049 0.982721 +0.173289 -0.065049 0.982720 +0.173289 -0.065049 0.982720 +0.173283 -0.065051 0.982722 +0.173289 -0.065049 0.982721 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.365183 0.000000 -0.930936 +-0.365183 0.000000 -0.930936 +-0.365183 0.000000 -0.930936 +-0.365183 0.000000 -0.930936 +-0.365183 0.000000 -0.930936 +-0.365183 0.000000 -0.930936 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.276912 0.000000 0.960895 +0.276912 0.000000 0.960895 +0.276912 0.000000 0.960895 +0.276912 0.000000 0.960895 +0.276912 0.000000 0.960895 +0.276912 0.000000 0.960895 +-0.919875 0.000000 0.392213 +-0.919875 0.000000 0.392213 +-0.919875 0.000000 0.392213 +-0.919875 0.000000 0.392213 +-0.919875 0.000000 0.392213 +-0.919875 0.000000 0.392213 +-0.973126 0.000000 -0.230273 +-0.973126 0.000000 -0.230273 +-0.973126 0.000000 -0.230273 +-0.973126 0.000000 -0.230273 +-0.973126 0.000000 -0.230273 +-0.973126 0.000000 -0.230273 +-0.998788 0.000000 -0.049225 +-0.998788 0.000000 -0.049225 +-0.998788 0.000000 -0.049225 +-0.998788 0.000000 -0.049225 +-0.998788 0.000000 -0.049225 +-0.998788 0.000000 -0.049225 +-0.669095 0.000000 0.743177 +-0.669095 0.000000 0.743177 +-0.669094 0.000000 0.743177 +-0.669095 0.000000 0.743177 +-0.669095 0.000000 0.743177 +-0.805887 0.000000 0.592069 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.998583 0.000000 0.053213 +-0.998583 0.000000 0.053213 +-0.998583 0.000000 0.053213 +-0.998583 0.000000 0.053213 +-0.998583 0.000000 0.053213 +-0.998583 0.000000 0.053213 +-0.998583 0.000000 0.053209 +-0.998583 0.000000 0.053209 +-0.998583 0.000000 0.053209 +-0.998583 0.000000 0.053209 +-0.998583 0.000000 0.053209 +-0.998583 0.000000 0.053209 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.153318 0.000000 0.988177 +0.130071 -0.015485 0.991384 +0.153318 0.000000 0.988177 +0.153318 0.000000 0.988177 +0.153318 0.000000 0.988177 +0.355384 0.000000 0.934720 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.002608 0.000000 0.999997 +0.002608 0.000000 0.999997 +0.002608 0.000000 0.999997 +0.002608 0.000000 0.999997 +0.002608 0.000000 0.999997 +0.002608 0.000000 0.999997 +-0.173526 0.000000 0.984829 +-0.173526 0.000000 0.984829 +-0.173526 0.000000 0.984829 +-0.173526 0.000000 0.984829 +-0.173526 0.000000 0.984829 +-0.173526 0.000000 0.984829 +-0.499728 0.000000 0.866182 +-0.499728 0.000000 0.866182 +-0.499728 0.000000 0.866182 +-0.499728 0.000000 0.866182 +-0.499728 0.000000 0.866182 +-0.499728 0.000000 0.866182 +-0.765785 0.000000 0.643097 +-0.765785 0.000000 0.643097 +-0.765785 0.000000 0.643097 +-0.765785 0.000000 0.643097 +-0.765785 0.000000 0.643097 +-0.765785 0.000000 0.643097 +-0.939596 0.000000 0.342284 +-0.939596 0.000000 0.342284 +-0.939596 0.000000 0.342284 +-0.939596 0.000000 0.342284 +-0.939596 0.000000 0.342284 +-0.939596 0.000000 0.342284 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.939590 0.000000 -0.342301 +-0.939590 0.000000 -0.342301 +-0.939590 0.000000 -0.342301 +-0.939590 0.000000 -0.342301 +-0.939590 0.000000 -0.342301 +-0.939590 0.000000 -0.342301 +-0.765785 0.000000 -0.643097 +-0.765785 0.000000 -0.643097 +-0.765785 0.000000 -0.643097 +-0.765785 0.000000 -0.643097 +-0.765785 0.000000 -0.643097 +-0.765785 0.000000 -0.643097 +-0.499767 0.000000 -0.866160 +-0.499767 0.000000 -0.866160 +-0.499767 0.000000 -0.866160 +-0.499767 0.000000 -0.866160 +-0.499767 0.000000 -0.866160 +-0.499767 0.000000 -0.866160 +-0.173535 0.000000 -0.984828 +-0.173535 0.000000 -0.984828 +-0.173535 0.000000 -0.984828 +-0.173535 0.000000 -0.984828 +-0.173535 0.000000 -0.984828 +-0.173535 0.000000 -0.984828 +0.173526 0.000000 -0.984829 +0.173526 0.000000 -0.984829 +0.173526 0.000000 -0.984829 +0.173526 0.000000 -0.984829 +0.173526 0.000000 -0.984829 +0.173526 0.000000 -0.984829 +0.499767 0.000000 -0.866160 +0.499767 0.000000 -0.866160 +0.499767 0.000000 -0.866160 +0.499767 0.000000 -0.866160 +0.499767 0.000000 -0.866160 +0.499767 0.000000 -0.866160 +0.765785 0.000000 -0.643097 +0.765785 0.000000 -0.643097 +0.765785 0.000000 -0.643097 +0.765785 0.000000 -0.643097 +0.765785 0.000000 -0.643097 +0.765785 0.000000 -0.643097 +0.939607 0.000000 -0.342256 +0.939607 0.000000 -0.342256 +0.939607 0.000000 -0.342256 +0.939607 0.000000 -0.342256 +0.939607 0.000000 -0.342256 +0.939607 0.000000 -0.342256 +1.000000 0.000048 0.000000 +1.000000 0.000048 0.000000 +1.000000 0.000048 0.000000 +1.000000 0.000048 0.000000 +1.000000 0.000000 -0.000051 +1.000000 0.000048 0.000000 +0.939596 0.000000 0.342284 +0.939596 0.000000 0.342284 +0.939596 0.000000 0.342284 +0.939596 0.000000 0.342284 +0.939596 0.000000 0.342284 +0.939613 0.000045 0.342239 +0.765785 0.000000 0.643097 +0.765785 0.000000 0.643097 +0.765785 0.000000 0.643097 +0.765785 0.000000 0.643097 +0.765785 0.000000 0.643097 +0.765785 0.000000 0.643097 +0.499729 0.000000 0.866182 +0.499729 0.000000 0.866182 +0.499729 0.000000 0.866182 +0.499729 0.000000 0.866182 +0.499707 -0.000025 0.866195 +0.499729 0.000000 0.866182 +0.173535 -0.000009 0.984828 +0.173535 -0.000009 0.984828 +0.173535 -0.000009 0.984828 +0.173535 -0.000009 0.984828 +0.173544 0.000000 0.984826 +0.173535 -0.000009 0.984828 +-0.173673 0.000000 0.984803 +-0.173628 0.000109 0.984811 +-0.173628 0.000109 0.984811 +-0.173628 0.000109 0.984811 +-0.173628 0.000109 0.984811 +-0.173628 0.000109 0.984811 +-0.173673 0.000000 0.984803 +-0.173673 0.000000 0.984803 +-0.173673 0.000000 0.984803 +-0.173673 0.000000 0.984803 +-0.173673 0.000000 0.984803 +-0.173673 0.000000 0.984803 +-0.499992 0.000000 0.866030 +-0.499992 0.000000 0.866030 +-0.499992 0.000000 0.866030 +-0.499992 0.000000 0.866030 +-0.499992 0.000000 0.866030 +-0.499992 0.000000 0.866030 +-0.499992 0.000000 0.866030 +-0.499992 0.000000 0.866030 +-0.499992 0.000000 0.866030 +-0.499992 0.000000 0.866030 +-0.499992 0.000000 0.866030 +-0.499992 0.000000 0.866030 +-0.766052 0.000000 0.642779 +-0.766052 0.000000 0.642779 +-0.766052 0.000000 0.642779 +-0.766052 0.000000 0.642779 +-0.766052 0.000000 0.642779 +-0.766052 0.000000 0.642779 +-0.766052 0.000000 0.642779 +-0.766052 0.000000 0.642779 +-0.766052 0.000000 0.642779 +-0.766052 0.000000 0.642779 +-0.766052 0.000000 0.642779 +-0.766052 0.000000 0.642779 +-0.939692 0.000000 0.342021 +-0.939692 0.000000 0.342021 +-0.939692 0.000000 0.342021 +-0.939692 0.000000 0.342021 +-0.939692 0.000000 0.342021 +-0.939692 0.000000 0.342021 +-0.939692 0.000000 0.342021 +-0.939692 0.000000 0.342021 +-0.939692 0.000000 0.342021 +-0.939692 0.000000 0.342021 +-0.939692 0.000000 0.342021 +-0.939692 0.000000 0.342021 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.939698 0.000000 -0.342006 +-0.939698 0.000000 -0.342006 +-0.939698 0.000000 -0.342006 +-0.939698 0.000000 -0.342006 +-0.939698 0.000000 -0.342006 +-0.939698 0.000000 -0.342006 +-0.939698 0.000000 -0.342006 +-0.939698 0.000000 -0.342006 +-0.939698 0.000000 -0.342006 +-0.939698 0.000000 -0.342006 +-0.939698 0.000000 -0.342006 +-0.939698 0.000000 -0.342006 +-0.766032 0.000000 -0.642802 +-0.766032 0.000000 -0.642802 +-0.766032 0.000000 -0.642802 +-0.766032 0.000000 -0.642802 +-0.766032 0.000000 -0.642802 +-0.766032 0.000000 -0.642802 +-0.766032 0.000000 -0.642802 +-0.766032 0.000000 -0.642802 +-0.766032 0.000000 -0.642802 +-0.766032 0.000000 -0.642802 +-0.766032 0.000000 -0.642802 +-0.766032 0.000000 -0.642802 +-0.499992 0.000000 -0.866030 +-0.499992 0.000000 -0.866030 +-0.499992 0.000000 -0.866030 +-0.499992 0.000000 -0.866030 +-0.499992 0.000000 -0.866030 +-0.499992 0.000000 -0.866030 +-0.499992 0.000000 -0.866030 +-0.499992 0.000000 -0.866030 +-0.499992 0.000000 -0.866030 +-0.499992 0.000000 -0.866030 +-0.499992 0.000000 -0.866030 +-0.499992 0.000000 -0.866030 +-0.173673 0.000000 -0.984803 +-0.173673 0.000000 -0.984803 +-0.173673 0.000000 -0.984803 +-0.173673 0.000000 -0.984803 +-0.173673 0.000000 -0.984803 +-0.173673 0.000000 -0.984803 +-0.173673 0.000000 -0.984803 +-0.173673 0.000000 -0.984803 +-0.173673 0.000000 -0.984803 +-0.173673 0.000000 -0.984803 +-0.173673 0.000000 -0.984803 +-0.173673 0.000000 -0.984803 +0.173673 0.000000 -0.984803 +0.173673 0.000000 -0.984803 +0.173673 0.000000 -0.984803 +0.173673 0.000000 -0.984803 +0.173673 0.000000 -0.984803 +0.173673 0.000000 -0.984803 +0.173673 0.000000 -0.984803 +0.173665 0.000019 -0.984805 +0.173665 0.000019 -0.984805 +0.173665 0.000019 -0.984805 +0.173665 0.000019 -0.984805 +0.173665 0.000019 -0.984805 +0.499993 0.000000 -0.866029 +0.499993 0.000000 -0.866029 +0.499993 0.000000 -0.866029 +0.499993 0.000000 -0.866029 +0.499993 0.000000 -0.866029 +0.499993 0.000000 -0.866029 +0.499993 0.000054 -0.866029 +0.499992 0.000056 -0.866030 +0.499992 0.000056 -0.866030 +0.499992 0.000056 -0.866030 +0.499992 0.000056 -0.866030 +0.499992 0.000056 -0.866030 +0.766032 0.000000 -0.642802 +0.766032 0.000000 -0.642802 +0.766032 0.000000 -0.642802 +0.766032 0.000000 -0.642802 +0.766032 0.000000 -0.642802 +0.766032 0.000000 -0.642802 +0.766032 0.000000 -0.642802 +0.766032 0.000000 -0.642802 +0.766032 0.000000 -0.642802 +0.766032 0.000000 -0.642802 +0.766056 0.000086 -0.642774 +0.766032 0.000000 -0.642802 +0.939683 0.000000 -0.342048 +0.939683 0.000000 -0.342048 +0.939683 0.000000 -0.342048 +0.939683 0.000000 -0.342048 +0.939683 0.000000 -0.342048 +0.939683 0.000000 -0.342048 +0.939683 0.000000 -0.342048 +0.939683 0.000000 -0.342048 +0.939683 0.000000 -0.342048 +0.939683 0.000000 -0.342048 +0.939683 0.000000 -0.342048 +0.939683 0.000000 -0.342048 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.939677 0.000000 0.342063 +0.939677 0.000000 0.342063 +0.939677 0.000000 0.342063 +0.939677 0.000000 0.342063 +0.939677 0.000000 0.342063 +0.939677 0.000000 0.342063 +0.939677 0.000000 0.342063 +0.939677 0.000000 0.342063 +0.939677 0.000000 0.342063 +0.939677 0.000000 0.342063 +0.939677 0.000000 0.342063 +0.939677 0.000000 0.342063 +0.766052 0.000000 0.642779 +0.766052 0.000000 0.642779 +0.766052 0.000000 0.642779 +0.766052 0.000000 0.642779 +0.766052 0.000000 0.642779 +0.766052 0.000000 0.642779 +0.766075 0.000086 0.642751 +0.766075 0.000086 0.642751 +0.766075 0.000086 0.642751 +0.766075 0.000086 0.642751 +0.766075 0.000086 0.642751 +0.766052 0.000000 0.642779 +0.499993 0.000000 0.866030 +0.499993 0.000000 0.866029 +0.499993 0.000000 0.866030 +0.499993 0.000000 0.866030 +0.499993 0.000000 0.866030 +0.499993 0.000000 0.866029 +0.499993 0.000054 0.866029 +0.499993 0.000054 0.866029 +0.499993 0.000054 0.866029 +0.499993 0.000054 0.866029 +0.499993 0.000054 0.866029 +0.499992 0.000056 0.866030 +0.173673 0.000109 0.984803 +0.173628 0.000000 0.984811 +0.173628 0.000000 0.984811 +0.173628 0.000000 0.984811 +0.173628 0.000000 0.984811 +0.173628 0.000000 0.984811 +0.173673 0.000000 0.984803 +0.173673 0.000000 0.984803 +0.173673 0.000000 0.984803 +0.173673 0.000000 0.984803 +0.173673 0.000000 0.984803 +0.173665 0.000019 0.984805 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.173526 0.000000 0.984829 +-0.173526 0.000000 0.984829 +-0.173526 0.000000 0.984829 +-0.173526 0.000000 0.984829 +-0.173526 0.000000 0.984829 +-0.173526 0.000000 0.984829 +-0.499728 0.000000 0.866182 +-0.499728 0.000000 0.866182 +-0.499728 0.000000 0.866182 +-0.499728 0.000000 0.866182 +-0.499728 0.000000 0.866182 +-0.499728 0.000000 0.866182 +-0.765785 0.000000 0.643097 +-0.765785 0.000000 0.643097 +-0.765785 0.000000 0.643097 +-0.765785 0.000000 0.643097 +-0.765785 0.000000 0.643097 +-0.765785 0.000000 0.643097 +-0.939596 0.000000 0.342284 +-0.939596 0.000000 0.342284 +-0.939596 0.000000 0.342284 +-0.939596 0.000000 0.342284 +-0.939596 0.000000 0.342284 +-0.939596 0.000000 0.342284 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.939590 0.000000 -0.342301 +-0.939590 0.000000 -0.342301 +-0.939590 0.000000 -0.342301 +-0.939590 0.000000 -0.342301 +-0.939590 0.000000 -0.342301 +-0.939590 0.000000 -0.342301 +-0.765785 0.000000 -0.643097 +-0.765785 0.000000 -0.643097 +-0.765785 0.000000 -0.643097 +-0.765785 0.000000 -0.643097 +-0.765785 0.000000 -0.643097 +-0.765785 0.000000 -0.643097 +-0.499767 0.000000 -0.866160 +-0.499767 0.000000 -0.866160 +-0.499767 0.000000 -0.866160 +-0.499767 0.000000 -0.866160 +-0.499767 0.000000 -0.866160 +-0.499767 0.000000 -0.866160 +-0.173535 0.000000 -0.984828 +-0.173535 0.000000 -0.984828 +-0.173535 0.000000 -0.984828 +-0.173535 0.000000 -0.984828 +-0.173535 0.000000 -0.984828 +-0.173535 0.000000 -0.984828 +0.173526 0.000000 -0.984829 +0.173526 0.000000 -0.984829 +0.173526 0.000000 -0.984829 +0.173526 0.000000 -0.984829 +0.173526 0.000000 -0.984829 +0.173526 0.000000 -0.984829 +0.499767 0.000000 -0.866160 +0.499767 0.000000 -0.866160 +0.499767 0.000000 -0.866160 +0.499767 0.000000 -0.866160 +0.499767 0.000000 -0.866160 +0.499767 0.000000 -0.866160 +0.765785 0.000000 -0.643097 +0.765785 0.000000 -0.643097 +0.765785 0.000000 -0.643097 +0.765785 0.000000 -0.643097 +0.765785 0.000000 -0.643097 +0.765785 0.000000 -0.643097 +0.939607 0.000000 -0.342256 +0.939607 0.000000 -0.342256 +0.939607 0.000000 -0.342256 +0.939607 0.000000 -0.342256 +0.939607 0.000000 -0.342256 +0.939607 0.000000 -0.342256 +1.000000 0.000000 -0.000051 +1.000000 0.000000 -0.000051 +1.000000 -0.000048 0.000000 +1.000000 0.000000 -0.000051 +1.000000 0.000000 -0.000051 +1.000000 0.000000 -0.000051 +0.939596 0.000000 0.342284 +0.939596 0.000000 0.342284 +0.939596 0.000000 0.342284 +0.939596 0.000000 0.342284 +0.939613 -0.000045 0.342239 +0.939596 0.000000 0.342284 +0.765785 0.000000 0.643097 +0.765785 0.000000 0.643097 +0.765785 0.000000 0.643097 +0.765785 0.000000 0.643097 +0.765785 0.000000 0.643097 +0.765785 0.000000 0.643097 +0.499707 0.000025 0.866195 +0.499707 0.000025 0.866195 +0.499707 0.000025 0.866195 +0.499707 0.000025 0.866195 +0.499707 0.000025 0.866195 +0.499729 0.000000 0.866182 +0.173544 0.000000 0.984826 +0.173544 0.000000 0.984826 +0.173544 0.000000 0.984826 +0.173544 0.000000 0.984826 +0.173544 0.000000 0.984826 +0.173535 0.000009 0.984828 +-0.173673 0.000000 0.984803 +-0.173673 0.000000 0.984803 +-0.173673 0.000000 0.984803 +-0.173673 0.000000 0.984803 +-0.173673 0.000000 0.984803 +-0.173628 -0.000109 0.984811 +-0.173673 0.000000 0.984803 +-0.173673 0.000000 0.984803 +-0.173673 0.000000 0.984803 +-0.173673 0.000000 0.984803 +-0.173673 0.000000 0.984803 +-0.173673 0.000000 0.984803 +-0.499992 0.000000 0.866030 +-0.499992 0.000000 0.866030 +-0.499992 0.000000 0.866030 +-0.499992 0.000000 0.866030 +-0.499992 0.000000 0.866030 +-0.499992 0.000000 0.866030 +-0.499992 0.000000 0.866030 +-0.499992 0.000000 0.866030 +-0.499992 0.000000 0.866030 +-0.499992 0.000000 0.866030 +-0.499992 0.000000 0.866030 +-0.499992 0.000000 0.866030 +-0.766052 0.000000 0.642779 +-0.766052 0.000000 0.642779 +-0.766052 0.000000 0.642779 +-0.766052 0.000000 0.642779 +-0.766052 0.000000 0.642779 +-0.766052 0.000000 0.642779 +-0.766052 0.000000 0.642779 +-0.766052 0.000000 0.642779 +-0.766052 0.000000 0.642779 +-0.766052 0.000000 0.642779 +-0.766052 0.000000 0.642779 +-0.766052 0.000000 0.642779 +-0.939692 0.000000 0.342021 +-0.939692 0.000000 0.342021 +-0.939692 0.000000 0.342021 +-0.939692 0.000000 0.342021 +-0.939692 0.000000 0.342021 +-0.939692 0.000000 0.342021 +-0.939692 0.000000 0.342021 +-0.939692 0.000000 0.342021 +-0.939692 0.000000 0.342021 +-0.939692 0.000000 0.342021 +-0.939692 0.000000 0.342021 +-0.939692 0.000000 0.342021 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.939698 0.000000 -0.342006 +-0.939698 0.000000 -0.342006 +-0.939698 0.000000 -0.342006 +-0.939698 0.000000 -0.342006 +-0.939698 0.000000 -0.342006 +-0.939698 0.000000 -0.342006 +-0.939698 0.000000 -0.342006 +-0.939698 0.000000 -0.342006 +-0.939698 0.000000 -0.342006 +-0.939698 0.000000 -0.342006 +-0.939698 0.000000 -0.342006 +-0.939698 0.000000 -0.342006 +-0.766032 0.000000 -0.642802 +-0.766032 0.000000 -0.642802 +-0.766032 0.000000 -0.642802 +-0.766032 0.000000 -0.642802 +-0.766032 0.000000 -0.642802 +-0.766032 0.000000 -0.642802 +-0.766032 0.000000 -0.642802 +-0.766032 0.000000 -0.642802 +-0.766032 0.000000 -0.642802 +-0.766032 0.000000 -0.642802 +-0.766032 0.000000 -0.642802 +-0.766032 0.000000 -0.642802 +-0.499992 0.000000 -0.866030 +-0.499992 0.000000 -0.866030 +-0.499992 0.000000 -0.866030 +-0.499992 0.000000 -0.866030 +-0.499992 0.000000 -0.866030 +-0.499992 0.000000 -0.866030 +-0.499992 0.000000 -0.866030 +-0.499992 0.000000 -0.866030 +-0.499992 0.000000 -0.866030 +-0.499992 0.000000 -0.866030 +-0.499992 0.000000 -0.866030 +-0.499992 0.000000 -0.866030 +-0.173673 0.000000 -0.984803 +-0.173673 0.000000 -0.984803 +-0.173673 0.000000 -0.984803 +-0.173673 0.000000 -0.984803 +-0.173673 0.000000 -0.984803 +-0.173673 0.000000 -0.984803 +-0.173673 0.000000 -0.984803 +-0.173673 0.000000 -0.984803 +-0.173673 0.000000 -0.984803 +-0.173673 0.000000 -0.984803 +-0.173673 0.000000 -0.984803 +-0.173673 0.000000 -0.984803 +0.173673 0.000000 -0.984803 +0.173673 0.000000 -0.984803 +0.173673 0.000000 -0.984803 +0.173673 0.000000 -0.984803 +0.173673 0.000000 -0.984803 +0.173673 0.000000 -0.984803 +0.173673 0.000000 -0.984803 +0.173673 0.000000 -0.984803 +0.173673 0.000000 -0.984803 +0.173673 0.000000 -0.984803 +0.173673 0.000000 -0.984803 +0.173665 -0.000019 -0.984805 +0.499993 0.000000 -0.866029 +0.499993 0.000000 -0.866029 +0.499993 0.000000 -0.866029 +0.499993 0.000000 -0.866029 +0.499993 0.000000 -0.866029 +0.499993 0.000000 -0.866029 +0.499993 -0.000054 -0.866029 +0.499993 -0.000054 -0.866029 +0.499993 -0.000054 -0.866029 +0.499993 -0.000054 -0.866029 +0.499993 -0.000054 -0.866029 +0.499992 -0.000056 -0.866030 +0.766032 0.000000 -0.642802 +0.766032 0.000000 -0.642802 +0.766032 0.000000 -0.642802 +0.766032 0.000000 -0.642802 +0.766032 0.000000 -0.642802 +0.766032 0.000000 -0.642802 +0.766032 0.000000 -0.642802 +0.766056 -0.000086 -0.642774 +0.766056 -0.000086 -0.642774 +0.766056 -0.000086 -0.642774 +0.766056 -0.000086 -0.642774 +0.766056 -0.000086 -0.642774 +0.939683 0.000000 -0.342048 +0.939683 0.000000 -0.342048 +0.939683 0.000000 -0.342048 +0.939683 0.000000 -0.342048 +0.939683 0.000000 -0.342048 +0.939683 0.000000 -0.342048 +0.939683 0.000000 -0.342048 +0.939683 0.000000 -0.342048 +0.939683 0.000000 -0.342048 +0.939683 0.000000 -0.342048 +0.939683 0.000000 -0.342048 +0.939683 0.000000 -0.342048 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.939677 0.000000 0.342063 +0.939677 0.000000 0.342063 +0.939677 0.000000 0.342063 +0.939677 0.000000 0.342063 +0.939677 0.000000 0.342063 +0.939677 0.000000 0.342063 +0.939677 0.000000 0.342063 +0.939677 0.000000 0.342063 +0.939677 0.000000 0.342063 +0.939677 0.000000 0.342063 +0.939677 0.000000 0.342063 +0.939677 0.000000 0.342063 +0.766052 0.000000 0.642779 +0.766052 0.000000 0.642779 +0.766052 0.000000 0.642779 +0.766052 0.000000 0.642779 +0.766052 0.000000 0.642779 +0.766052 0.000000 0.642779 +0.766075 -0.000086 0.642751 +0.766075 -0.000086 0.642751 +0.766075 -0.000086 0.642751 +0.766075 -0.000086 0.642751 +0.766075 -0.000086 0.642751 +0.766052 0.000000 0.642779 +0.499993 0.000000 0.866030 +0.499993 0.000000 0.866030 +0.499993 0.000000 0.866029 +0.499993 0.000000 0.866030 +0.499993 0.000000 0.866029 +0.499993 0.000000 0.866030 +0.499993 -0.000054 0.866029 +0.499992 -0.000056 0.866030 +0.499992 -0.000056 0.866030 +0.499992 -0.000056 0.866030 +0.499992 -0.000056 0.866030 +0.499992 -0.000056 0.866030 +0.173673 -0.000109 0.984803 +0.173673 -0.000109 0.984803 +0.173673 -0.000109 0.984803 +0.173673 -0.000109 0.984803 +0.173673 -0.000109 0.984803 +0.173628 0.000000 0.984811 +0.173673 0.000000 0.984803 +0.173665 -0.000019 0.984805 +0.173665 -0.000019 0.984805 +0.173665 -0.000019 0.984805 +0.173665 -0.000019 0.984805 +0.173665 -0.000019 0.984805 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.442031 0.000000 0.897000 +0.355384 0.000000 0.934720 +0.442031 0.000000 0.897000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.442031 0.000000 0.897000 +0.442031 0.000000 0.897000 +0.517879 0.000000 0.855454 +0.449773 0.016898 0.892983 +0.449773 0.016898 0.892983 +0.449773 0.016898 0.892983 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.355106 -0.072741 -0.931992 +0.355106 -0.072741 -0.931992 +0.355106 -0.072741 -0.931992 +0.307115 -0.003015 -0.951668 +0.307115 -0.003015 -0.951668 +0.307115 -0.003015 -0.951668 +0.307115 0.003015 -0.951668 +0.307115 0.003015 -0.951668 +0.307115 0.003015 -0.951668 +0.355106 0.072741 -0.931992 +0.355106 0.072741 -0.931992 +0.355106 0.072741 -0.931992 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.173657 0.000000 0.984806 +-0.173657 0.000000 0.984806 +-0.173657 0.000000 0.984806 +-0.173657 0.000000 0.984806 +-0.173657 0.000000 0.984806 +-0.173657 0.000000 0.984806 +-0.499998 0.000000 0.866027 +-0.499998 0.000000 0.866027 +-0.499998 0.000000 0.866026 +-0.499998 0.000000 0.866026 +-0.499998 0.000000 0.866027 +-0.499998 0.000000 0.866027 +-0.766056 0.000000 0.642774 +-0.766056 0.000000 0.642774 +-0.766056 0.000000 0.642774 +-0.766056 0.000000 0.642774 +-0.766056 0.000000 0.642774 +-0.766056 0.000000 0.642774 +-0.939689 0.000000 0.342030 +-0.939689 0.000000 0.342030 +-0.939689 0.000000 0.342030 +-0.939689 0.000000 0.342030 +-0.939689 0.000000 0.342030 +-0.939689 0.000000 0.342030 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.939689 0.000000 -0.342030 +-0.939689 0.000000 -0.342030 +-0.939689 0.000000 -0.342030 +-0.939689 0.000000 -0.342030 +-0.939689 0.000000 -0.342030 +-0.939689 0.000000 -0.342030 +-0.766056 0.000000 -0.642774 +-0.766056 0.000000 -0.642774 +-0.766056 0.000000 -0.642774 +-0.766056 0.000000 -0.642774 +-0.766056 0.000000 -0.642774 +-0.766056 0.000000 -0.642774 +-0.499998 0.000000 -0.866027 +-0.499998 0.000000 -0.866027 +-0.499998 0.000000 -0.866027 +-0.499998 0.000000 -0.866027 +-0.499998 0.000000 -0.866027 +-0.499998 0.000000 -0.866027 +-0.173632 0.000000 -0.984810 +-0.173632 0.000000 -0.984811 +-0.173632 0.000000 -0.984811 +-0.173632 0.000000 -0.984810 +-0.173632 0.000000 -0.984811 +-0.173632 0.000000 -0.984811 +0.173628 0.000000 -0.984811 +0.173628 0.000000 -0.984811 +0.173628 0.000000 -0.984811 +0.173628 0.000000 -0.984811 +0.173628 0.000000 -0.984811 +0.173628 0.000000 -0.984811 +0.500008 0.000000 -0.866021 +0.500008 0.000000 -0.866021 +0.500008 0.000000 -0.866021 +0.500008 0.000000 -0.866021 +0.500008 0.000000 -0.866021 +0.500008 0.000000 -0.866021 +0.766043 0.000000 -0.642789 +0.766043 0.000000 -0.642789 +0.766043 0.000000 -0.642789 +0.766043 0.000000 -0.642789 +0.766043 0.000000 -0.642789 +0.766043 0.000000 -0.642789 +0.939689 0.000000 -0.342030 +0.939689 0.000000 -0.342030 +0.939689 0.000000 -0.342030 +0.939689 0.000000 -0.342030 +0.939689 0.000000 -0.342030 +0.939689 0.000000 -0.342030 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.939689 0.000000 0.342030 +0.939689 0.000000 0.342030 +0.939689 0.000000 0.342030 +0.939689 0.000000 0.342030 +0.939689 0.000000 0.342030 +0.939689 0.000000 0.342030 +0.766043 0.000000 0.642789 +0.766043 0.000000 0.642789 +0.766043 0.000000 0.642789 +0.766043 0.000000 0.642789 +0.766043 0.000000 0.642789 +0.766043 0.000000 0.642789 +0.500008 0.000000 0.866021 +0.500008 0.000000 0.866021 +0.500008 0.000000 0.866021 +0.500008 0.000000 0.866021 +0.500008 0.000000 0.866021 +0.500008 0.000000 0.866021 +0.173653 0.000000 0.984807 +0.173653 0.000000 0.984807 +0.173653 0.000000 0.984807 +0.173653 0.000000 0.984807 +0.173653 0.000000 0.984807 +0.173653 0.000000 0.984807 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.173533 -0.000006 0.984828 +-0.173533 -0.000006 0.984828 +-0.173533 -0.000006 0.984828 +-0.173533 -0.000006 0.984828 +-0.173533 -0.000006 0.984828 +-0.173538 0.000000 0.984827 +-0.499729 -0.000013 0.866182 +-0.499725 -0.000018 0.866184 +-0.499729 -0.000013 0.866182 +-0.499725 -0.000018 0.866184 +-0.499729 -0.000013 0.866182 +-0.499729 -0.000013 0.866182 +-0.765791 0.000005 0.643089 +-0.765794 0.000000 0.643086 +-0.765794 0.000000 0.643086 +-0.765794 0.000000 0.643086 +-0.765794 0.000000 0.643086 +-0.765794 0.000000 0.643086 +-0.939598 -0.000012 0.342279 +-0.939598 -0.000012 0.342279 +-0.939595 0.000000 0.342288 +-0.939598 -0.000012 0.342279 +-0.939598 -0.000012 0.342279 +-0.939598 -0.000012 0.342279 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.939595 0.000000 -0.342288 +-0.939595 0.000000 -0.342288 +-0.939595 0.000000 -0.342288 +-0.939595 0.000000 -0.342288 +-0.939595 0.000000 -0.342288 +-0.939595 0.000000 -0.342288 +-0.765794 0.000000 -0.643087 +-0.765794 0.000000 -0.643087 +-0.765794 0.000000 -0.643086 +-0.765794 0.000000 -0.643087 +-0.765794 0.000000 -0.643087 +-0.765794 0.000000 -0.643086 +-0.499737 0.000000 -0.866177 +-0.499737 0.000000 -0.866177 +-0.499737 0.000000 -0.866177 +-0.499737 0.000000 -0.866177 +-0.499737 0.000000 -0.866177 +-0.499737 0.000000 -0.866177 +-0.173538 0.000000 -0.984827 +-0.173538 0.000000 -0.984827 +-0.173538 0.000000 -0.984827 +-0.173538 0.000000 -0.984827 +-0.173538 0.000000 -0.984827 +-0.173538 0.000000 -0.984827 +0.173538 0.000000 -0.984827 +0.173538 0.000000 -0.984827 +0.173538 0.000000 -0.984827 +0.173538 0.000000 -0.984827 +0.173538 0.000000 -0.984827 +0.173538 0.000000 -0.984827 +0.499737 0.000000 -0.866177 +0.499737 0.000000 -0.866177 +0.499737 0.000000 -0.866177 +0.499737 0.000000 -0.866177 +0.499737 0.000000 -0.866177 +0.499737 0.000000 -0.866177 +0.765794 0.000000 -0.643086 +0.765794 0.000000 -0.643087 +0.765794 0.000000 -0.643087 +0.765794 0.000000 -0.643087 +0.765794 0.000000 -0.643087 +0.765794 0.000000 -0.643086 +0.939595 0.000000 -0.342288 +0.939595 0.000000 -0.342288 +0.939595 0.000000 -0.342288 +0.939595 0.000000 -0.342288 +0.939595 0.000000 -0.342288 +0.939595 0.000000 -0.342288 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.939595 0.000033 0.342288 +0.939595 0.000033 0.342288 +0.939595 0.000033 0.342288 +0.939595 0.000033 0.342288 +0.939604 0.000000 0.342264 +0.939595 0.000033 0.342288 +0.765805 -0.000023 0.643073 +0.765805 -0.000023 0.643073 +0.765805 -0.000023 0.643073 +0.765805 -0.000023 0.643073 +0.765780 0.000027 0.643102 +0.765805 -0.000023 0.643073 +0.499717 0.000000 0.866189 +0.499717 0.000000 0.866189 +0.499717 0.000000 0.866189 +0.499717 0.000000 0.866189 +0.499717 0.000000 0.866189 +0.499737 -0.000031 0.866177 +0.173542 0.000000 0.984827 +0.173542 0.000000 0.984826 +0.173542 0.000000 0.984826 +0.173542 0.000000 0.984826 +0.173542 0.000000 0.984827 +0.173542 0.000000 0.984826 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.173657 0.000000 0.984806 +-0.173657 0.000000 0.984806 +-0.173657 0.000000 0.984806 +-0.173657 0.000000 0.984806 +-0.173657 0.000000 0.984806 +-0.173657 0.000000 0.984806 +-0.499998 0.000000 0.866027 +-0.499998 0.000000 0.866026 +-0.499998 0.000000 0.866027 +-0.499998 0.000000 0.866026 +-0.499998 0.000000 0.866027 +-0.499998 0.000000 0.866027 +-0.766056 0.000000 0.642774 +-0.766056 0.000000 0.642774 +-0.766056 0.000000 0.642774 +-0.766056 0.000000 0.642774 +-0.766056 0.000000 0.642774 +-0.766056 0.000000 0.642774 +-0.939689 0.000000 0.342030 +-0.939689 0.000000 0.342030 +-0.939689 0.000000 0.342030 +-0.939689 0.000000 0.342030 +-0.939689 0.000000 0.342030 +-0.939689 0.000000 0.342030 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.939689 0.000000 -0.342030 +-0.939689 0.000000 -0.342030 +-0.939689 0.000000 -0.342030 +-0.939689 0.000000 -0.342030 +-0.939689 0.000000 -0.342030 +-0.939689 0.000000 -0.342030 +-0.766056 0.000000 -0.642774 +-0.766056 0.000000 -0.642774 +-0.766056 0.000000 -0.642774 +-0.766056 0.000000 -0.642774 +-0.766056 0.000000 -0.642774 +-0.766056 0.000000 -0.642774 +-0.499998 0.000000 -0.866027 +-0.499998 0.000000 -0.866027 +-0.499998 0.000000 -0.866027 +-0.499998 0.000000 -0.866027 +-0.499998 0.000000 -0.866027 +-0.499998 0.000000 -0.866027 +-0.173632 0.000000 -0.984811 +-0.173632 0.000000 -0.984810 +-0.173632 0.000000 -0.984811 +-0.173632 0.000000 -0.984810 +-0.173632 0.000000 -0.984811 +-0.173632 0.000000 -0.984811 +0.173628 0.000000 -0.984811 +0.173628 0.000000 -0.984811 +0.173628 0.000000 -0.984811 +0.173628 0.000000 -0.984811 +0.173628 0.000000 -0.984811 +0.173628 0.000000 -0.984811 +0.500008 0.000000 -0.866021 +0.500008 0.000000 -0.866021 +0.500008 0.000000 -0.866021 +0.500008 0.000000 -0.866021 +0.500008 0.000000 -0.866021 +0.500008 0.000000 -0.866021 +0.766043 0.000000 -0.642789 +0.766043 0.000000 -0.642789 +0.766043 0.000000 -0.642789 +0.766043 0.000000 -0.642789 +0.766043 0.000000 -0.642789 +0.766043 0.000000 -0.642789 +0.939689 0.000000 -0.342030 +0.939689 0.000000 -0.342030 +0.939689 0.000000 -0.342030 +0.939689 0.000000 -0.342030 +0.939689 0.000000 -0.342030 +0.939689 0.000000 -0.342030 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.939689 0.000000 0.342030 +0.939689 0.000000 0.342030 +0.939689 0.000000 0.342030 +0.939689 0.000000 0.342030 +0.939689 0.000000 0.342030 +0.939689 0.000000 0.342030 +0.766043 0.000000 0.642789 +0.766043 0.000000 0.642789 +0.766043 0.000000 0.642789 +0.766043 0.000000 0.642789 +0.766043 0.000000 0.642789 +0.766043 0.000000 0.642789 +0.500008 0.000000 0.866021 +0.500008 0.000000 0.866021 +0.500008 0.000000 0.866021 +0.500008 0.000000 0.866021 +0.500008 0.000000 0.866021 +0.500008 0.000000 0.866021 +0.173653 0.000000 0.984807 +0.173653 0.000000 0.984807 +0.173653 0.000000 0.984807 +0.173653 0.000000 0.984807 +0.173653 0.000000 0.984807 +0.173653 0.000000 0.984807 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.173538 0.000000 0.984827 +-0.173538 0.000000 0.984827 +-0.173538 0.000000 0.984827 +-0.173538 0.000000 0.984827 +-0.173533 0.000006 0.984828 +-0.173538 0.000000 0.984827 +-0.499725 0.000018 0.866184 +-0.499729 0.000013 0.866182 +-0.499725 0.000018 0.866184 +-0.499729 0.000013 0.866182 +-0.499725 0.000018 0.866184 +-0.499725 0.000018 0.866184 +-0.765791 -0.000005 0.643089 +-0.765791 -0.000005 0.643089 +-0.765791 -0.000005 0.643089 +-0.765791 -0.000005 0.643089 +-0.765794 0.000000 0.643086 +-0.765791 -0.000005 0.643089 +-0.939595 0.000000 0.342288 +-0.939595 0.000000 0.342288 +-0.939595 0.000000 0.342288 +-0.939595 0.000000 0.342288 +-0.939598 0.000012 0.342279 +-0.939595 0.000000 0.342288 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.939595 0.000000 -0.342288 +-0.939595 0.000000 -0.342288 +-0.939595 0.000000 -0.342288 +-0.939595 0.000000 -0.342288 +-0.939595 0.000000 -0.342288 +-0.939595 0.000000 -0.342288 +-0.765794 0.000000 -0.643086 +-0.765794 0.000000 -0.643087 +-0.765794 0.000000 -0.643087 +-0.765794 0.000000 -0.643087 +-0.765794 0.000000 -0.643086 +-0.765794 0.000000 -0.643087 +-0.499737 0.000000 -0.866177 +-0.499737 0.000000 -0.866177 +-0.499737 0.000000 -0.866177 +-0.499737 0.000000 -0.866177 +-0.499737 0.000000 -0.866177 +-0.499737 0.000000 -0.866177 +-0.173538 0.000000 -0.984827 +-0.173538 0.000000 -0.984827 +-0.173538 0.000000 -0.984827 +-0.173538 0.000000 -0.984827 +-0.173538 0.000000 -0.984827 +-0.173538 0.000000 -0.984827 +0.173538 0.000000 -0.984827 +0.173538 0.000000 -0.984827 +0.173538 0.000000 -0.984827 +0.173538 0.000000 -0.984827 +0.173538 0.000000 -0.984827 +0.173538 0.000000 -0.984827 +0.499737 0.000000 -0.866177 +0.499737 0.000000 -0.866177 +0.499737 0.000000 -0.866177 +0.499737 0.000000 -0.866177 +0.499737 0.000000 -0.866177 +0.499737 0.000000 -0.866177 +0.765794 0.000000 -0.643086 +0.765794 0.000000 -0.643087 +0.765794 0.000000 -0.643087 +0.765794 0.000000 -0.643087 +0.765794 0.000000 -0.643086 +0.765794 0.000000 -0.643087 +0.939595 0.000000 -0.342288 +0.939595 0.000000 -0.342288 +0.939595 0.000000 -0.342288 +0.939595 0.000000 -0.342288 +0.939595 0.000000 -0.342288 +0.939595 0.000000 -0.342288 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.939595 -0.000033 0.342288 +0.939595 -0.000033 0.342288 +0.939595 -0.000033 0.342288 +0.939595 -0.000033 0.342288 +0.939595 -0.000033 0.342288 +0.939604 0.000000 0.342264 +0.765805 0.000023 0.643073 +0.765805 0.000023 0.643073 +0.765805 0.000023 0.643073 +0.765805 0.000023 0.643073 +0.765805 0.000023 0.643073 +0.765780 -0.000027 0.643102 +0.499737 0.000031 0.866177 +0.499737 0.000031 0.866177 +0.499737 0.000031 0.866177 +0.499737 0.000031 0.866177 +0.499717 0.000000 0.866189 +0.499737 0.000031 0.866177 +0.173542 0.000000 0.984826 +0.173542 0.000000 0.984826 +0.173542 0.000000 0.984827 +0.173542 0.000000 0.984826 +0.173542 0.000000 0.984826 +0.173542 0.000000 0.984827 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.500005 0.866023 0.000000 +-0.500005 0.866023 0.000000 +-0.500005 0.866023 0.000000 +-0.500005 0.866023 0.000000 +-0.500005 0.866023 0.000000 +-0.500005 0.866023 0.000000 +-0.939694 0.342017 0.000000 +-0.939694 0.342017 0.000000 +-0.939694 0.342017 0.000000 +-0.939694 0.342017 0.000000 +-0.939694 0.342017 0.000000 +-0.939694 0.342017 0.000000 +-0.939694 -0.342017 0.000000 +-0.939694 -0.342017 0.000000 +-0.939694 -0.342017 0.000000 +-0.939694 -0.342017 0.000000 +-0.939694 -0.342017 0.000000 +-0.939694 -0.342017 0.000000 +-0.500005 -0.866023 0.000000 +-0.500005 -0.866023 0.000000 +-0.500005 -0.866023 0.000000 +-0.500005 -0.866023 0.000000 +-0.500005 -0.866023 0.000000 +-0.500005 -0.866023 0.000000 +0.173669 -0.984804 0.000000 +0.173669 -0.984804 0.000000 +0.173669 -0.984804 0.000000 +0.173669 -0.984804 0.000000 +0.173669 -0.984804 0.000000 +0.173669 -0.984804 0.000000 +0.766027 -0.642808 0.000000 +0.766027 -0.642808 0.000000 +0.766027 -0.642808 0.000000 +0.766027 -0.642808 0.000000 +0.766027 -0.642808 0.000000 +0.766027 -0.642808 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.766027 0.642808 0.000000 +0.766027 0.642808 0.000000 +0.766027 0.642808 0.000000 +0.766027 0.642808 0.000000 +0.766027 0.642808 0.000000 +0.766027 0.642808 0.000000 +0.173669 0.984804 0.000000 +0.173669 0.984804 0.000000 +0.173669 0.984804 0.000000 +0.173669 0.984804 0.000000 +0.173669 0.984804 0.000000 +0.173669 0.984804 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.500010 0.866020 0.000000 +-0.500010 0.866020 0.000000 +-0.500010 0.866020 0.000000 +-0.500010 0.866020 0.000000 +-0.500010 0.866020 0.000000 +-0.500010 0.866020 0.000000 +-0.939679 0.342057 0.000000 +-0.939679 0.342057 0.000000 +-0.939679 0.342057 0.000000 +-0.939679 0.342057 0.000000 +-0.939679 0.342057 0.000000 +-0.939679 0.342057 0.000000 +-0.939679 -0.342057 0.000000 +-0.939679 -0.342057 0.000000 +-0.939679 -0.342057 0.000000 +-0.939679 -0.342057 0.000000 +-0.939679 -0.342057 0.000000 +-0.939679 -0.342057 0.000000 +-0.500010 -0.866020 0.000000 +-0.500010 -0.866020 0.000000 +-0.500010 -0.866020 0.000000 +-0.500010 -0.866020 0.000000 +-0.500010 -0.866020 0.000000 +-0.500010 -0.866020 0.000000 +0.173663 -0.984805 0.000000 +0.173663 -0.984805 0.000000 +0.173663 -0.984805 0.000000 +0.173663 -0.984805 0.000000 +0.173663 -0.984805 0.000000 +0.173663 -0.984805 0.000000 +0.766029 -0.642806 0.000000 +0.766029 -0.642806 0.000000 +0.766029 -0.642806 0.000000 +0.766029 -0.642806 0.000000 +0.766029 -0.642806 0.000000 +0.766029 -0.642806 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.766029 0.642806 0.000000 +0.766029 0.642806 0.000000 +0.766029 0.642806 0.000000 +0.766029 0.642806 0.000000 +0.766029 0.642806 0.000000 +0.766029 0.642806 0.000000 +0.173663 0.984805 0.000000 +0.173663 0.984805 0.000000 +0.173663 0.984805 0.000000 +0.173663 0.984805 0.000000 +0.173663 0.984805 0.000000 +0.173663 0.984805 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.173602 0.984816 0.000000 +0.173602 0.984816 0.000000 +0.173602 0.984816 0.000000 +0.173602 0.984816 0.000000 +0.173602 0.984816 0.000000 +0.173602 0.984816 0.000000 +0.766075 0.642751 0.000000 +0.766075 0.642751 0.000000 +0.766075 0.642751 0.000000 +0.766075 0.642751 0.000000 +0.766075 0.642751 0.000000 +0.766075 0.642751 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.766075 -0.642751 0.000000 +0.766075 -0.642751 0.000000 +0.766075 -0.642751 0.000000 +0.766075 -0.642751 0.000000 +0.766075 -0.642751 0.000000 +0.766075 -0.642751 0.000000 +0.173602 -0.984816 0.000000 +0.173602 -0.984816 0.000000 +0.173602 -0.984816 0.000000 +0.173602 -0.984816 0.000000 +0.173602 -0.984816 0.000000 +0.173602 -0.984816 0.000000 +-0.499960 -0.866048 0.000000 +-0.499960 -0.866049 0.000000 +-0.499960 -0.866048 0.000000 +-0.499960 -0.866048 0.000000 +-0.499960 -0.866049 0.000000 +-0.499960 -0.866048 0.000000 +-0.939700 -0.342000 0.000000 +-0.939700 -0.342000 0.000000 +-0.939700 -0.342000 0.000000 +-0.939700 -0.342000 0.000000 +-0.939700 -0.342000 0.000000 +-0.939700 -0.342000 0.000000 +-0.939700 0.342000 0.000000 +-0.939700 0.342000 0.000000 +-0.939700 0.342000 0.000000 +-0.939700 0.342000 0.000000 +-0.939700 0.342000 0.000000 +-0.939700 0.342000 0.000000 +-0.499960 0.866048 0.000000 +-0.499960 0.866049 0.000000 +-0.499960 0.866048 0.000000 +-0.499960 0.866048 0.000000 +-0.499960 0.866049 0.000000 +-0.499960 0.866048 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.999217 0.000000 0.039571 +0.999217 0.000000 0.039571 +0.999217 0.000000 0.039571 +0.999217 0.000000 0.039571 +0.999217 0.000000 0.039571 +0.999217 0.000000 0.039571 +-0.999993 0.000000 0.003806 +-0.999993 0.000000 0.003806 +-0.999993 0.000000 0.003806 +-0.999993 0.000000 0.003806 +-0.999993 0.000000 0.003806 +-0.999993 0.000000 0.003806 +0.000000 -0.999493 0.031854 +0.000000 -0.999493 0.031854 +0.000000 -0.999493 0.031854 +0.000000 -0.999493 0.031854 +0.000000 -0.999492 0.031854 +0.000000 -0.999493 0.031854 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.999493 0.031854 +0.000000 0.999493 0.031854 +0.000000 0.999493 0.031854 +0.000000 0.999493 0.031854 +0.000000 0.999493 0.031854 +0.000000 0.999492 0.031854 +0.259379 0.057080 -0.964087 +0.259379 0.057080 -0.964087 +0.259379 0.057080 -0.964087 +0.259379 0.057080 -0.964087 +0.258521 0.057163 -0.964313 +0.259379 0.057080 -0.964087 +0.966091 0.015210 -0.257754 +0.965828 0.015188 -0.258739 +0.965828 0.015188 -0.258739 +0.965828 0.015188 -0.258739 +0.965828 0.015188 -0.258739 +0.965828 0.015188 -0.258739 +0.707866 -0.041207 0.705144 +0.706501 -0.041137 0.706515 +0.706501 -0.041137 0.706515 +0.706501 -0.041137 0.706515 +0.706501 -0.041137 0.706515 +0.706501 -0.041137 0.706515 +-0.258357 -0.056153 0.964416 +-0.258357 -0.056153 0.964416 +-0.258357 -0.056153 0.964416 +-0.258357 -0.056153 0.964416 +-0.258357 -0.056153 0.964416 +-0.259213 -0.056071 0.964191 +-0.706501 -0.041137 0.706515 +-0.706501 -0.041137 0.706515 +-0.706501 -0.041137 0.706515 +-0.706501 -0.041137 0.706515 +-0.706501 -0.041137 0.706515 +-0.707866 -0.041207 0.705144 +-0.965767 0.015202 -0.258965 +-0.965767 0.015202 -0.258965 +-0.965767 0.015202 -0.258965 +-0.965767 0.015202 -0.258965 +-0.965767 0.015202 -0.258965 +-0.966031 0.015223 -0.257979 +-0.707732 0.041755 -0.705246 +-0.706492 0.041691 -0.706492 +-0.706492 0.041691 -0.706492 +-0.706492 0.041691 -0.706492 +-0.707732 0.041755 -0.705246 +-0.706492 0.041691 -0.706492 +0.258716 0.137904 -0.956059 +0.258716 0.137904 -0.956059 +0.258716 0.137904 -0.956059 +0.258716 0.137904 -0.956059 +0.258539 0.137937 -0.956102 +0.258716 0.137904 -0.956059 +0.965884 0.036967 -0.256325 +0.965867 0.036967 -0.256386 +0.965867 0.036967 -0.256386 +0.965868 0.036967 -0.256386 +0.965867 0.036967 -0.256386 +0.965867 0.036967 -0.256386 +0.706715 -0.100936 0.700261 +0.706647 -0.100933 0.700331 +0.706647 -0.100933 0.700331 +0.706647 -0.100933 0.700331 +0.706647 -0.100933 0.700331 +0.706647 -0.100933 0.700331 +-0.258378 -0.137804 0.956165 +-0.258378 -0.137804 0.956165 +-0.258378 -0.137804 0.956165 +-0.258378 -0.137804 0.956165 +-0.258378 -0.137804 0.956165 +-0.258537 -0.137777 0.956126 +-0.706647 -0.100933 0.700331 +-0.706647 -0.100933 0.700331 +-0.706647 -0.100933 0.700331 +-0.706647 -0.100933 0.700331 +-0.706647 -0.100933 0.700331 +-0.706715 -0.100936 0.700261 +-0.965807 0.037000 -0.256609 +-0.965807 0.037000 -0.256609 +-0.965807 0.037000 -0.256609 +-0.965807 0.037000 -0.256609 +-0.965807 0.037000 -0.256609 +-0.965823 0.037000 -0.256549 +-0.706576 0.101026 -0.700389 +-0.706499 0.101022 -0.700466 +-0.706499 0.101022 -0.700466 +-0.706499 0.101022 -0.700466 +-0.706576 0.101026 -0.700389 +-0.706499 0.101022 -0.700466 +0.260078 0.182539 -0.948177 +0.260078 0.182539 -0.948177 +0.260078 0.182539 -0.948177 +0.260078 0.182539 -0.948177 +0.259102 0.182870 -0.948380 +0.260078 0.182539 -0.948177 +0.965987 0.048715 -0.253962 +0.965987 0.048715 -0.253962 +0.966128 0.048465 -0.253470 +0.965987 0.048715 -0.253962 +0.965987 0.048715 -0.253962 +0.965986 0.048715 -0.253962 +0.707281 -0.132502 0.694404 +0.707281 -0.132502 0.694404 +0.707650 -0.132297 0.694067 +0.707281 -0.132502 0.694404 +0.707281 -0.132502 0.694404 +0.707281 -0.132502 0.694404 +-0.258920 -0.180854 0.948816 +-0.259123 -0.180790 0.948773 +-0.259123 -0.180790 0.948773 +-0.259123 -0.180790 0.948773 +-0.259123 -0.180790 0.948773 +-0.259123 -0.180790 0.948773 +-0.707281 -0.132502 0.694404 +-0.707650 -0.132297 0.694067 +-0.707650 -0.132297 0.694067 +-0.707650 -0.132297 0.694067 +-0.707650 -0.132297 0.694067 +-0.707650 -0.132297 0.694067 +-0.966068 0.048507 -0.253691 +-0.966068 0.048507 -0.253691 +-0.966068 0.048507 -0.253691 +-0.966068 0.048507 -0.253691 +-0.965926 0.048757 -0.254184 +-0.966068 0.048507 -0.253691 +-0.708335 0.132976 -0.693238 +-0.708335 0.132976 -0.693238 +-0.708335 0.132976 -0.693238 +-0.708335 0.132976 -0.693238 +-0.708335 0.132976 -0.693238 +-0.707148 0.133667 -0.694316 +0.249793 0.869097 -0.426935 +0.249793 0.869097 -0.426935 +0.249793 0.869097 -0.426935 +0.249793 0.869097 -0.426935 +0.249793 0.869097 -0.426935 +0.257022 0.868415 -0.424023 +0.963654 0.238290 -0.120786 +0.963654 0.238290 -0.120786 +0.963654 0.238290 -0.120786 +0.963654 0.238290 -0.120786 +0.963654 0.238290 -0.120786 +0.965412 0.233331 -0.116344 +0.695676 -0.637891 0.330348 +0.695676 -0.637891 0.330348 +0.695676 -0.637891 0.330348 +0.695676 -0.637891 0.330348 +0.695676 -0.637891 0.330348 +0.703516 -0.632166 0.324702 +-0.251287 -0.858988 0.446088 +-0.251287 -0.858988 0.446088 +-0.251287 -0.858988 0.446088 +-0.251287 -0.858988 0.446088 +-0.256353 -0.858314 0.444500 +-0.251287 -0.858988 0.446088 +-0.965274 -0.233014 0.118112 +-0.963688 -0.237531 0.122004 +-0.965274 -0.233014 0.118112 +-0.965274 -0.233014 0.118112 +-0.965274 -0.233014 0.118112 +-0.965274 -0.233014 0.118112 +-0.704523 0.636975 -0.312907 +-0.694095 0.644238 -0.321231 +-0.704523 0.636975 -0.312907 +-0.704523 0.636975 -0.312907 +-0.704523 0.636975 -0.312907 +-0.704522 0.636975 -0.312907 +0.258717 0.943465 -0.207219 +0.258717 0.943465 -0.207219 +0.258717 0.943465 -0.207219 +0.258717 0.943465 -0.207219 +0.258717 0.943465 -0.207219 +0.258600 0.943487 -0.207262 +0.965955 0.252687 -0.055506 +0.965955 0.252687 -0.055506 +0.965955 0.252687 -0.055506 +0.965955 0.252687 -0.055506 +0.965955 0.252687 -0.055506 +0.965957 0.252680 -0.055503 +0.707121 -0.690624 0.151721 +0.707121 -0.690624 0.151720 +0.707121 -0.690624 0.151720 +0.707121 -0.690624 0.151720 +0.707121 -0.690624 0.151721 +0.707165 -0.690584 0.151695 +-0.258986 -0.943391 0.207219 +-0.258986 -0.943391 0.207219 +-0.258986 -0.943391 0.207219 +-0.258986 -0.943391 0.207219 +-0.258872 -0.943414 0.207255 +-0.258986 -0.943391 0.207219 +-0.965882 -0.252951 0.055564 +-0.965881 -0.252954 0.055565 +-0.965882 -0.252951 0.055564 +-0.965882 -0.252951 0.055564 +-0.965882 -0.252951 0.055564 +-0.965882 -0.252951 0.055564 +-0.707115 0.690634 -0.151702 +-0.707146 0.690606 -0.151682 +-0.707115 0.690634 -0.151702 +-0.707115 0.690634 -0.151702 +-0.707115 0.690634 -0.151702 +-0.707115 0.690634 -0.151702 +0.258607 0.965251 -0.037588 +0.258607 0.965251 -0.037588 +0.258607 0.965251 -0.037588 +0.258607 0.965251 -0.037588 +0.258607 0.965251 -0.037588 +0.258643 0.965242 -0.037577 +0.965956 0.258509 -0.010064 +0.965956 0.258509 -0.010064 +0.965956 0.258509 -0.010064 +0.965956 0.258509 -0.010064 +0.965957 0.258509 -0.010064 +0.965956 0.258509 -0.010064 +0.707162 -0.706517 0.027504 +0.707162 -0.706517 0.027504 +0.707162 -0.706517 0.027504 +0.707162 -0.706517 0.027504 +0.707144 -0.706534 0.027499 +0.707162 -0.706517 0.027504 +-0.258886 -0.965177 0.037574 +-0.258886 -0.965177 0.037574 +-0.258886 -0.965177 0.037574 +-0.258886 -0.965177 0.037574 +-0.258923 -0.965167 0.037565 +-0.258886 -0.965177 0.037574 +-0.965881 -0.258791 0.010075 +-0.965881 -0.258791 0.010075 +-0.965881 -0.258791 0.010075 +-0.965881 -0.258791 0.010075 +-0.965881 -0.258791 0.010075 +-0.965880 -0.258793 0.010075 +-0.707162 0.706516 -0.027513 +-0.707162 0.706516 -0.027513 +-0.707162 0.706516 -0.027513 +-0.707162 0.706516 -0.027513 +-0.707162 0.706516 -0.027513 +-0.707144 0.706535 -0.027506 +0.258645 0.946258 0.194164 +0.258645 0.946258 0.194164 +0.258645 0.946258 0.194164 +0.258645 0.946258 0.194164 +0.258822 0.946224 0.194090 +0.258645 0.946258 0.194164 +0.965956 0.253430 0.051980 +0.965937 0.253494 0.052016 +0.965956 0.253430 0.051980 +0.965956 0.253430 0.051980 +0.965956 0.253430 0.051980 +0.965956 0.253430 0.051980 +0.707141 -0.692651 -0.142078 +0.707132 -0.692659 -0.142083 +0.707141 -0.692651 -0.142078 +0.707141 -0.692651 -0.142078 +0.707141 -0.692651 -0.142078 +0.707141 -0.692651 -0.142078 +-0.258922 -0.946197 -0.194091 +-0.258922 -0.946197 -0.194091 +-0.258922 -0.946197 -0.194091 +-0.258922 -0.946197 -0.194091 +-0.258922 -0.946197 -0.194091 +-0.258893 -0.946203 -0.194100 +-0.965879 -0.253707 -0.052060 +-0.965879 -0.253707 -0.052060 +-0.965896 -0.253649 -0.052029 +-0.965879 -0.253707 -0.052060 +-0.965879 -0.253707 -0.052060 +-0.965879 -0.253707 -0.052060 +-0.707142 0.692650 0.142077 +-0.707142 0.692650 0.142077 +-0.707163 0.692632 0.142063 +-0.707142 0.692650 0.142077 +-0.707142 0.692650 0.142077 +-0.707142 0.692650 0.142077 +0.258801 0.784223 0.563929 +0.258801 0.784223 0.563929 +0.258801 0.784223 0.563929 +0.258801 0.784223 0.563929 +0.258832 0.784224 0.563914 +0.258801 0.784223 0.563929 +0.965944 0.210072 0.151067 +0.965936 0.210104 0.151077 +0.965936 0.210104 0.151077 +0.965936 0.210104 0.151077 +0.965936 0.210104 0.151077 +0.965936 0.210104 0.151077 +0.707137 -0.574045 -0.412830 +0.707110 -0.574073 -0.412838 +0.707110 -0.574073 -0.412838 +0.707110 -0.574073 -0.412838 +0.707110 -0.574073 -0.412838 +0.707110 -0.574073 -0.412838 +-0.258873 -0.784191 -0.563941 +-0.258873 -0.784191 -0.563941 +-0.258873 -0.784191 -0.563941 +-0.258873 -0.784191 -0.563941 +-0.258873 -0.784191 -0.563941 +-0.258891 -0.784190 -0.563934 +-0.965898 -0.210208 -0.151173 +-0.965898 -0.210208 -0.151173 +-0.965898 -0.210208 -0.151173 +-0.965898 -0.210208 -0.151173 +-0.965898 -0.210208 -0.151173 +-0.965883 -0.210264 -0.151192 +-0.707194 0.574009 0.412783 +-0.707194 0.574009 0.412783 +-0.707194 0.574009 0.412783 +-0.707194 0.574009 0.412783 +-0.707194 0.574009 0.412783 +-0.707151 0.574057 0.412789 +0.258631 0.572412 0.778110 +0.258631 0.572412 0.778110 +0.258631 0.572412 0.778110 +0.258631 0.572412 0.778110 +0.258631 0.572412 0.778110 +0.258848 0.572328 0.778099 +0.965945 0.153321 0.208427 +0.965945 0.153321 0.208427 +0.965945 0.153321 0.208427 +0.965945 0.153321 0.208427 +0.965945 0.153321 0.208427 +0.965945 0.153322 0.208428 +0.707113 -0.419004 -0.569585 +0.707113 -0.419004 -0.569585 +0.707113 -0.419004 -0.569585 +0.707113 -0.419004 -0.569585 +0.707113 -0.419004 -0.569585 +0.707158 -0.418966 -0.569558 +-0.258908 -0.572333 -0.778075 +-0.258908 -0.572333 -0.778076 +-0.258908 -0.572333 -0.778076 +-0.258908 -0.572333 -0.778076 +-0.258847 -0.572354 -0.778080 +-0.258908 -0.572333 -0.778075 +-0.965887 -0.153450 -0.208602 +-0.965884 -0.153460 -0.208610 +-0.965887 -0.153450 -0.208602 +-0.965887 -0.153450 -0.208602 +-0.965887 -0.153450 -0.208602 +-0.965887 -0.153450 -0.208602 +-0.707197 0.418923 0.569540 +-0.707197 0.418923 0.569540 +-0.707197 0.418923 0.569540 +-0.707197 0.418923 0.569540 +-0.707119 0.418993 0.569585 +-0.707197 0.418923 0.569540 +0.258706 0.529180 0.808108 +0.258706 0.529180 0.808108 +0.258706 0.529180 0.808109 +0.258706 0.529180 0.808109 +0.258706 0.529180 0.808108 +0.258635 0.529193 0.808123 +0.965959 0.141720 0.216422 +0.965959 0.141720 0.216422 +0.965959 0.141720 0.216422 +0.965959 0.141720 0.216422 +0.965959 0.141720 0.216422 +0.965945 0.141750 0.216463 +0.707116 -0.387371 -0.591549 +0.707116 -0.387371 -0.591549 +0.707116 -0.387371 -0.591549 +0.707116 -0.387371 -0.591549 +0.707116 -0.387371 -0.591549 +0.707116 -0.387371 -0.591549 +-0.258841 -0.529161 -0.808078 +-0.258841 -0.529161 -0.808078 +-0.258841 -0.529161 -0.808078 +-0.258841 -0.529161 -0.808078 +-0.258788 -0.529170 -0.808089 +-0.258841 -0.529161 -0.808078 +-0.965887 -0.141868 -0.216645 +-0.965887 -0.141868 -0.216645 +-0.965887 -0.141868 -0.216645 +-0.965887 -0.141868 -0.216645 +-0.965887 -0.141868 -0.216645 +-0.965883 -0.141878 -0.216660 +-0.707194 0.387325 0.591485 +-0.707195 0.387325 0.591485 +-0.707195 0.387325 0.591485 +-0.707195 0.387325 0.591485 +-0.707194 0.387325 0.591485 +-0.707122 0.387368 0.591544 +0.250230 0.264178 -0.931448 +0.250230 0.264178 -0.931448 +0.250230 0.264178 -0.931448 +0.250230 0.264178 -0.931448 +0.261145 0.259633 -0.929728 +0.250230 0.264178 -0.931448 +0.963926 0.078006 -0.254485 +0.963926 0.078006 -0.254485 +0.963926 0.078006 -0.254485 +0.963926 0.078006 -0.254485 +0.966420 0.072501 -0.246529 +0.963926 0.078006 -0.254485 +0.697611 -0.220750 0.681622 +0.697611 -0.220750 0.681622 +0.697611 -0.220750 0.681622 +0.697611 -0.220750 0.681622 +0.709164 -0.213105 0.672066 +0.697611 -0.220750 0.681622 +-0.260130 -0.297498 0.918601 +-0.260130 -0.297498 0.918601 +-0.260130 -0.297499 0.918601 +-0.260130 -0.297499 0.918601 +-0.260130 -0.297498 0.918601 +-0.252555 -0.300034 0.919889 +-0.709164 -0.213105 0.672066 +-0.964004 -0.080367 0.253453 +-0.709164 -0.213105 0.672066 +-0.709164 -0.213105 0.672066 +-0.709164 -0.213105 0.672066 +-0.709164 -0.213105 0.672066 +-0.966360 0.072564 -0.246745 +-0.966360 0.072564 -0.246745 +-0.966360 0.072564 -0.246745 +-0.695363 0.202761 -0.689463 +-0.695363 0.202761 -0.689463 +-0.695363 0.202761 -0.689463 +-0.695363 0.202761 -0.689463 +-0.695363 0.202761 -0.689463 +-0.709910 0.192173 -0.677567 +0.250892 0.528960 -0.810712 +0.250892 0.528960 -0.810713 +0.250892 0.528960 -0.810712 +0.250892 0.528960 -0.810713 +0.260084 0.524679 -0.810598 +0.250892 0.528960 -0.810712 +0.966238 0.142746 -0.214496 +0.966238 0.142746 -0.214496 +0.964081 0.149456 -0.219571 +0.966238 0.142746 -0.214496 +0.966238 0.142746 -0.214496 +0.966238 0.142746 -0.214496 +0.708345 -0.402275 0.580019 +0.708345 -0.402275 0.580019 +0.708345 -0.402275 0.580019 +0.708345 -0.402275 0.580019 +0.708345 -0.402275 0.580019 +0.698304 -0.411236 0.585880 +-0.259590 -0.554817 0.790437 +-0.259590 -0.554817 0.790437 +-0.259590 -0.554817 0.790437 +-0.259590 -0.554817 0.790437 +-0.259590 -0.554817 0.790437 +-0.253045 -0.557315 0.790802 +-0.964159 -0.151210 0.218021 +-0.964159 -0.151210 0.218021 +-0.964159 -0.151210 0.218021 +-0.964159 -0.151210 0.218021 +-0.964159 -0.151210 0.218021 +-0.966131 -0.145203 0.213323 +-0.696103 0.397757 -0.597687 +-0.696103 0.397757 -0.597687 +-0.696103 0.397757 -0.597687 +-0.696103 0.397757 -0.597687 +-0.696103 0.397757 -0.597687 +-0.708954 0.385378 -0.590651 +0.258521 -0.057163 -0.964313 +0.259379 -0.057080 -0.964087 +0.259379 -0.057080 -0.964087 +0.259379 -0.057080 -0.964087 +0.259379 -0.057080 -0.964087 +0.259379 -0.057080 -0.964087 +0.965828 -0.015188 -0.258739 +0.965828 -0.015188 -0.258739 +0.965828 -0.015188 -0.258739 +0.965828 -0.015188 -0.258739 +0.965828 -0.015188 -0.258739 +0.966091 -0.015210 -0.257754 +0.706501 0.041137 0.706515 +0.706501 0.041137 0.706515 +0.706501 0.041137 0.706515 +0.706501 0.041137 0.706515 +0.706501 0.041137 0.706515 +0.707866 0.041207 0.705144 +-0.259213 0.056071 0.964191 +-0.259213 0.056071 0.964191 +-0.259213 0.056071 0.964191 +-0.259213 0.056071 0.964191 +-0.258357 0.056153 0.964416 +-0.259213 0.056071 0.964191 +-0.707866 0.041207 0.705144 +-0.706501 0.041137 0.706515 +-0.706501 0.041137 0.706515 +-0.706501 0.041137 0.706515 +-0.706501 0.041137 0.706515 +-0.706501 0.041137 0.706515 +-0.966031 -0.015223 -0.257979 +-0.965767 -0.015202 -0.258965 +-0.965767 -0.015202 -0.258965 +-0.965767 -0.015202 -0.258965 +-0.965767 -0.015202 -0.258965 +-0.965767 -0.015202 -0.258965 +-0.706492 -0.041691 -0.706492 +-0.707732 -0.041755 -0.705246 +-0.706492 -0.041691 -0.706492 +-0.707732 -0.041755 -0.705246 +-0.706492 -0.041691 -0.706492 +-0.706492 -0.041691 -0.706492 +0.258539 -0.137937 -0.956102 +0.258715 -0.137904 -0.956059 +0.258715 -0.137904 -0.956059 +0.258715 -0.137904 -0.956059 +0.258715 -0.137904 -0.956059 +0.258715 -0.137904 -0.956059 +0.965867 -0.036967 -0.256386 +0.965867 -0.036967 -0.256386 +0.965867 -0.036967 -0.256386 +0.965867 -0.036967 -0.256386 +0.965867 -0.036967 -0.256386 +0.965884 -0.036967 -0.256325 +0.706647 0.100933 0.700331 +0.706647 0.100933 0.700331 +0.706647 0.100933 0.700331 +0.706647 0.100933 0.700331 +0.706647 0.100933 0.700331 +0.706715 0.100936 0.700261 +-0.258538 0.137777 0.956126 +-0.258538 0.137776 0.956125 +-0.258538 0.137776 0.956125 +-0.258538 0.137776 0.956125 +-0.258378 0.137804 0.956165 +-0.258538 0.137777 0.956126 +-0.706715 0.100936 0.700261 +-0.706647 0.100933 0.700331 +-0.706647 0.100933 0.700331 +-0.706647 0.100933 0.700331 +-0.706647 0.100933 0.700331 +-0.706647 0.100933 0.700331 +-0.965823 -0.037000 -0.256549 +-0.965807 -0.037000 -0.256610 +-0.965807 -0.037000 -0.256610 +-0.965807 -0.037000 -0.256610 +-0.965807 -0.037000 -0.256610 +-0.965807 -0.037000 -0.256610 +-0.706499 -0.101022 -0.700466 +-0.706576 -0.101026 -0.700389 +-0.706499 -0.101022 -0.700466 +-0.706576 -0.101026 -0.700389 +-0.706499 -0.101022 -0.700466 +-0.706499 -0.101022 -0.700466 +0.259101 -0.182870 -0.948380 +0.259101 -0.182870 -0.948380 +0.259101 -0.182870 -0.948380 +0.259101 -0.182870 -0.948380 +0.259101 -0.182870 -0.948380 +0.260079 -0.182539 -0.948177 +0.966129 -0.048465 -0.253470 +0.966129 -0.048465 -0.253470 +0.966129 -0.048465 -0.253470 +0.966129 -0.048465 -0.253470 +0.965986 -0.048715 -0.253962 +0.966129 -0.048465 -0.253470 +0.707650 0.132297 0.694067 +0.707650 0.132297 0.694067 +0.707650 0.132297 0.694067 +0.707650 0.132297 0.694067 +0.707281 0.132502 0.694404 +0.707650 0.132297 0.694067 +-0.259124 0.180790 0.948773 +-0.259124 0.180790 0.948773 +-0.259124 0.180790 0.948773 +-0.259124 0.180790 0.948773 +-0.258921 0.180854 0.948816 +-0.259124 0.180790 0.948773 +-0.707650 0.132297 0.694067 +-0.707650 0.132297 0.694067 +-0.707650 0.132297 0.694067 +-0.707650 0.132297 0.694067 +-0.707650 0.132297 0.694067 +-0.707281 0.132502 0.694404 +-0.966068 -0.048507 -0.253691 +-0.966068 -0.048507 -0.253691 +-0.966068 -0.048507 -0.253691 +-0.966068 -0.048507 -0.253691 +-0.966068 -0.048507 -0.253691 +-0.965926 -0.048757 -0.254184 +-0.708335 -0.132976 -0.693238 +-0.708335 -0.132976 -0.693238 +-0.707148 -0.133667 -0.694316 +-0.708335 -0.132976 -0.693238 +-0.708335 -0.132976 -0.693238 +-0.708335 -0.132976 -0.693238 +0.249792 -0.869098 -0.426934 +0.249792 -0.869098 -0.426934 +0.249792 -0.869098 -0.426934 +0.249792 -0.869098 -0.426934 +0.249792 -0.869098 -0.426934 +0.257016 -0.868415 -0.424025 +0.965412 -0.233331 -0.116344 +0.965412 -0.233331 -0.116344 +0.965412 -0.233331 -0.116344 +0.965412 -0.233331 -0.116344 +0.965412 -0.233331 -0.116344 +0.963654 -0.238290 -0.120786 +0.703517 0.632165 0.324702 +0.703517 0.632165 0.324702 +0.703517 0.632165 0.324702 +0.703517 0.632165 0.324702 +0.703517 0.632165 0.324702 +0.695676 0.637890 0.330349 +-0.251287 0.858988 0.446089 +-0.256356 0.858313 0.444500 +-0.256356 0.858313 0.444500 +-0.256356 0.858313 0.444500 +-0.256356 0.858313 0.444500 +-0.256356 0.858313 0.444500 +-0.695676 0.637890 0.330349 +-0.703517 0.632165 0.324702 +-0.703517 0.632165 0.324702 +-0.703517 0.632165 0.324702 +-0.703517 0.632165 0.324702 +-0.703517 0.632165 0.324702 +-0.963589 -0.238497 -0.120891 +-0.963589 -0.238497 -0.120891 +-0.963589 -0.238497 -0.120891 +-0.963589 -0.238497 -0.120891 +-0.963589 -0.238497 -0.120891 +-0.965351 -0.233535 -0.116446 +-0.694097 -0.644236 -0.321231 +-0.704525 -0.636973 -0.312906 +-0.704525 -0.636973 -0.312906 +-0.704525 -0.636973 -0.312906 +-0.704525 -0.636973 -0.312906 +-0.704525 -0.636973 -0.312906 +0.258711 -0.943466 -0.207221 +0.258711 -0.943466 -0.207221 +0.258711 -0.943466 -0.207221 +0.258711 -0.943466 -0.207221 +0.258711 -0.943466 -0.207221 +0.258600 -0.943488 -0.207261 +0.965954 -0.252688 -0.055507 +0.965954 -0.252688 -0.055507 +0.965957 -0.252679 -0.055502 +0.965954 -0.252688 -0.055507 +0.965954 -0.252688 -0.055507 +0.965954 -0.252688 -0.055507 +0.707122 0.690622 0.151720 +0.707122 0.690622 0.151720 +0.707165 0.690584 0.151696 +0.707122 0.690622 0.151720 +0.707122 0.690622 0.151720 +0.707122 0.690622 0.151720 +-0.258989 0.943390 0.207220 +-0.258878 0.943413 0.207255 +-0.258878 0.943413 0.207255 +-0.258878 0.943413 0.207255 +-0.258878 0.943413 0.207255 +-0.258878 0.943413 0.207255 +-0.707122 0.690622 0.151720 +-0.707165 0.690584 0.151696 +-0.707165 0.690584 0.151696 +-0.707165 0.690584 0.151696 +-0.707165 0.690584 0.151696 +-0.707165 0.690584 0.151696 +-0.965894 -0.252908 -0.055556 +-0.965897 -0.252899 -0.055551 +-0.965897 -0.252899 -0.055551 +-0.965897 -0.252899 -0.055551 +-0.965897 -0.252899 -0.055551 +-0.965897 -0.252899 -0.055551 +-0.707117 -0.690632 -0.151701 +-0.707145 -0.690607 -0.151684 +-0.707145 -0.690607 -0.151684 +-0.707145 -0.690607 -0.151684 +-0.707145 -0.690607 -0.151684 +-0.707145 -0.690607 -0.151684 +0.258607 -0.965251 -0.037588 +0.258607 -0.965251 -0.037588 +0.258607 -0.965251 -0.037588 +0.258607 -0.965251 -0.037588 +0.258607 -0.965251 -0.037588 +0.258871 -0.965183 -0.037506 +0.965957 -0.258508 -0.010064 +0.965957 -0.258508 -0.010064 +0.965957 -0.258507 -0.010064 +0.965957 -0.258508 -0.010064 +0.965957 -0.258508 -0.010064 +0.965957 -0.258508 -0.010064 +0.707146 0.706533 0.027498 +0.707146 0.706533 0.027498 +0.707162 0.706517 0.027503 +0.707146 0.706533 0.027498 +0.707146 0.706533 0.027498 +0.707146 0.706533 0.027498 +-0.258891 0.965178 0.037517 +-0.258701 0.965227 0.037566 +-0.258701 0.965227 0.037566 +-0.258701 0.965227 0.037566 +-0.258701 0.965227 0.037566 +-0.258701 0.965227 0.037566 +-0.707162 0.706517 0.027503 +-0.707162 0.706517 0.027503 +-0.707162 0.706517 0.027503 +-0.707162 0.706517 0.027503 +-0.707162 0.706517 0.027503 +-0.707146 0.706533 0.027498 +-0.965896 -0.258733 -0.010072 +-0.965896 -0.258733 -0.010072 +-0.965896 -0.258733 -0.010072 +-0.965896 -0.258733 -0.010072 +-0.965896 -0.258733 -0.010072 +-0.965896 -0.258734 -0.010072 +-0.707160 -0.706518 -0.027513 +-0.707140 -0.706538 -0.027506 +-0.707160 -0.706518 -0.027513 +-0.707140 -0.706538 -0.027506 +-0.707160 -0.706518 -0.027513 +-0.707160 -0.706518 -0.027513 +0.258869 -0.946215 0.194071 +0.258819 -0.946225 0.194092 +0.258819 -0.946225 0.194092 +0.258819 -0.946225 0.194092 +0.258819 -0.946225 0.194092 +0.258819 -0.946225 0.194092 +0.965956 -0.253429 0.051979 +0.965938 -0.253493 0.052015 +0.965938 -0.253493 0.052015 +0.965938 -0.253493 0.052015 +0.965938 -0.253493 0.052015 +0.965938 -0.253493 0.052015 +0.707142 0.692650 -0.142077 +0.707135 0.692656 -0.142081 +0.707135 0.692656 -0.142081 +0.707135 0.692656 -0.142081 +0.707135 0.692656 -0.142081 +0.707135 0.692656 -0.142081 +-0.258704 0.946254 -0.194101 +-0.258704 0.946254 -0.194101 +-0.258704 0.946254 -0.194101 +-0.258704 0.946254 -0.194101 +-0.258704 0.946254 -0.194101 +-0.258883 0.946216 -0.194046 +-0.707142 0.692650 -0.142077 +-0.707135 0.692656 -0.142081 +-0.707142 0.692650 -0.142077 +-0.707142 0.692650 -0.142077 +-0.707142 0.692650 -0.142077 +-0.707142 0.692650 -0.142077 +-0.965896 -0.253651 0.052025 +-0.965877 -0.253715 0.052061 +-0.965896 -0.253651 0.052025 +-0.965896 -0.253651 0.052025 +-0.965896 -0.253651 0.052025 +-0.965896 -0.253651 0.052025 +-0.707139 -0.692653 0.142078 +-0.707139 -0.692653 0.142078 +-0.707139 -0.692653 0.142078 +-0.707139 -0.692653 0.142078 +-0.707139 -0.692653 0.142078 +-0.707165 -0.692630 0.142061 +0.258798 -0.784223 0.563930 +0.258829 -0.784224 0.563915 +0.258829 -0.784224 0.563915 +0.258829 -0.784224 0.563915 +0.258829 -0.784224 0.563915 +0.258829 -0.784224 0.563915 +0.965936 -0.210104 0.151077 +0.965936 -0.210104 0.151077 +0.965936 -0.210104 0.151077 +0.965936 -0.210104 0.151077 +0.965936 -0.210104 0.151077 +0.965944 -0.210071 0.151067 +0.707113 0.574071 -0.412837 +0.707113 0.574071 -0.412837 +0.707113 0.574071 -0.412837 +0.707113 0.574071 -0.412837 +0.707113 0.574071 -0.412837 +0.707136 0.574047 -0.412831 +-0.258868 0.784191 -0.563943 +-0.258868 0.784191 -0.563943 +-0.258868 0.784191 -0.563943 +-0.258868 0.784191 -0.563943 +-0.258868 0.784191 -0.563943 +-0.258891 0.784190 -0.563934 +-0.707136 0.574047 -0.412831 +-0.707113 0.574071 -0.412837 +-0.707113 0.574071 -0.412837 +-0.707113 0.574071 -0.412837 +-0.707113 0.574071 -0.412837 +-0.707113 0.574071 -0.412837 +-0.965884 -0.210255 0.151199 +-0.965875 -0.210287 0.151209 +-0.965875 -0.210287 0.151209 +-0.965875 -0.210287 0.151209 +-0.965875 -0.210287 0.151209 +-0.965875 -0.210287 0.151209 +-0.707196 -0.574008 0.412782 +-0.707152 -0.574057 0.412789 +-0.707196 -0.574008 0.412782 +-0.707152 -0.574057 0.412789 +-0.707196 -0.574008 0.412782 +-0.707196 -0.574008 0.412782 +0.258847 -0.572329 0.778099 +0.258847 -0.572329 0.778099 +0.258847 -0.572329 0.778099 +0.258847 -0.572329 0.778099 +0.258847 -0.572329 0.778099 +0.258633 -0.572411 0.778110 +0.965945 -0.153322 0.208428 +0.965945 -0.153322 0.208428 +0.965945 -0.153322 0.208428 +0.965945 -0.153322 0.208428 +0.965945 -0.153322 0.208428 +0.965945 -0.153322 0.208427 +0.707157 0.418967 -0.569558 +0.707157 0.418967 -0.569558 +0.707157 0.418967 -0.569558 +0.707157 0.418967 -0.569558 +0.707157 0.418967 -0.569558 +0.707115 0.419003 -0.569583 +-0.258846 0.572355 -0.778080 +-0.258908 0.572334 -0.778075 +-0.258908 0.572334 -0.778075 +-0.258908 0.572334 -0.778075 +-0.258908 0.572334 -0.778075 +-0.258908 0.572334 -0.778075 +-0.707115 0.419003 -0.569583 +-0.707157 0.418967 -0.569558 +-0.707157 0.418967 -0.569558 +-0.707157 0.418967 -0.569558 +-0.707157 0.418967 -0.569558 +-0.707157 0.418967 -0.569558 +-0.965885 -0.153455 0.208609 +-0.965885 -0.153456 0.208610 +-0.965885 -0.153456 0.208610 +-0.965885 -0.153456 0.208610 +-0.965885 -0.153456 0.208610 +-0.965885 -0.153456 0.208610 +-0.707120 -0.418993 0.569585 +-0.707120 -0.418993 0.569585 +-0.707120 -0.418993 0.569585 +-0.707120 -0.418993 0.569585 +-0.707120 -0.418993 0.569585 +-0.707197 -0.418924 0.569540 +0.258636 -0.529193 0.808123 +0.258636 -0.529193 0.808123 +0.258636 -0.529193 0.808123 +0.258636 -0.529193 0.808123 +0.258636 -0.529193 0.808123 +0.258706 -0.529180 0.808109 +0.965945 -0.141750 0.216464 +0.965945 -0.141750 0.216464 +0.965945 -0.141750 0.216464 +0.965945 -0.141750 0.216464 +0.965945 -0.141750 0.216464 +0.965959 -0.141720 0.216422 +0.707118 0.387370 -0.591548 +0.707118 0.387370 -0.591548 +0.707118 0.387370 -0.591548 +0.707118 0.387370 -0.591548 +0.707118 0.387370 -0.591548 +0.707116 0.387371 -0.591549 +-0.258789 0.529170 -0.808089 +-0.258840 0.529161 -0.808078 +-0.258840 0.529161 -0.808078 +-0.258840 0.529161 -0.808078 +-0.258840 0.529161 -0.808078 +-0.258840 0.529161 -0.808078 +-0.707116 0.387371 -0.591549 +-0.707118 0.387370 -0.591548 +-0.707118 0.387370 -0.591548 +-0.707118 0.387370 -0.591548 +-0.707118 0.387370 -0.591548 +-0.707118 0.387370 -0.591548 +-0.965882 0.141878 -0.216660 +-0.965883 0.141879 -0.216660 +-0.965883 0.141879 -0.216660 +-0.965883 0.141879 -0.216660 +-0.965882 0.141878 -0.216660 +-0.965885 -0.141874 0.216653 +-0.965899 -0.141844 0.216611 +-0.965898 -0.141844 0.216611 +-0.965899 -0.141844 0.216611 +-0.707195 -0.387325 0.591485 +-0.707195 -0.387325 0.591485 +-0.707195 -0.387325 0.591485 +-0.707195 -0.387325 0.591485 +-0.707195 -0.387325 0.591485 +-0.707122 -0.387368 0.591544 +0.261147 -0.259632 -0.929728 +0.250230 -0.264178 -0.931448 +0.250230 -0.264178 -0.931448 +0.250230 -0.264178 -0.931448 +0.250230 -0.264178 -0.931448 +0.250230 -0.264178 -0.931448 +0.963926 -0.078006 -0.254484 +0.963926 -0.078006 -0.254484 +0.963926 -0.078006 -0.254484 +0.963926 -0.078006 -0.254484 +0.966420 -0.072500 -0.246529 +0.963926 -0.078006 -0.254484 +0.697612 0.220750 0.681621 +0.697612 0.220750 0.681621 +0.697612 0.220750 0.681621 +0.697612 0.220750 0.681621 +0.709164 0.213105 0.672066 +0.697612 0.220750 0.681621 +-0.252556 0.300034 0.919889 +-0.252556 0.300034 0.919889 +-0.252556 0.300034 0.919889 +-0.252556 0.300034 0.919889 +-0.260131 0.297498 0.918600 +-0.252556 0.300034 0.919889 +-0.697612 0.220750 0.681621 +-0.697612 0.220750 0.681621 +-0.697612 0.220750 0.681621 +-0.697612 0.220750 0.681621 +-0.709164 0.213105 0.672066 +-0.697612 0.220750 0.681621 +-0.963862 -0.078073 -0.254706 +-0.963862 -0.078073 -0.254706 +-0.963862 -0.078073 -0.254706 +-0.963862 -0.078073 -0.254706 +-0.966360 -0.072564 -0.246745 +-0.963862 -0.078073 -0.254706 +-0.695362 -0.202761 -0.689463 +-0.695362 -0.202761 -0.689463 +-0.709909 -0.192173 -0.677568 +-0.695362 -0.202761 -0.689463 +-0.695362 -0.202761 -0.689463 +-0.695362 -0.202761 -0.689463 +0.260084 -0.524679 -0.810597 +0.260084 -0.524679 -0.810597 +0.260084 -0.524679 -0.810597 +0.260084 -0.524679 -0.810597 +0.260084 -0.524679 -0.810597 +0.250892 -0.528961 -0.810712 +0.964081 -0.149456 -0.219571 +0.964081 -0.149456 -0.219571 +0.964080 -0.149456 -0.219571 +0.964081 -0.149456 -0.219571 +0.964080 -0.149456 -0.219571 +0.966238 -0.142745 -0.214495 +0.698304 0.411236 0.585880 +0.698304 0.411236 0.585880 +0.698304 0.411236 0.585880 +0.698304 0.411236 0.585880 +0.698304 0.411236 0.585880 +0.708346 0.402274 0.580018 +-0.253045 0.557316 0.790802 +-0.253045 0.557316 0.790802 +-0.253045 0.557316 0.790802 +-0.253045 0.557316 0.790802 +-0.259591 0.554817 0.790437 +-0.253045 0.557316 0.790802 +-0.708346 0.402274 0.580018 +-0.708346 0.402274 0.580018 +-0.708346 0.402274 0.580018 +-0.708346 0.402274 0.580018 +-0.708346 0.402274 0.580018 +-0.698304 0.411236 0.585880 +-0.966178 -0.142870 -0.214683 +-0.966178 -0.142870 -0.214683 +-0.966178 -0.142870 -0.214683 +-0.966178 -0.142870 -0.214683 +-0.966178 -0.142870 -0.214683 +-0.964017 -0.149586 -0.219763 +-0.708953 -0.385379 -0.590651 +-0.708953 -0.385379 -0.590651 +-0.708953 -0.385379 -0.590651 +-0.708953 -0.385379 -0.590651 +-0.696104 -0.397756 -0.597687 +-0.708953 -0.385379 -0.590651 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.357193 0.000000 -0.934031 +0.357193 0.000000 -0.934031 +0.357193 0.000000 -0.934031 +0.357193 0.000000 -0.934031 +0.357193 0.000000 -0.934031 +0.357193 0.000000 -0.934031 +0.997314 0.000000 0.073248 +0.997314 0.000000 0.073248 +0.997314 0.000000 0.073248 +0.997314 0.000000 0.073248 +0.997314 0.000000 0.073248 +0.997314 0.000000 0.073248 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.995479 0.000000 0.094987 +-0.995479 0.000000 0.094987 +-0.995479 0.000000 0.094987 +-0.995479 0.000000 0.094987 +-0.995479 0.000000 0.094987 +-0.995479 0.000000 0.094987 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.629059 0.000000 0.777358 +0.629059 0.000000 0.777358 +0.629059 0.000000 0.777358 +0.629059 0.000000 0.777358 +0.629059 0.000000 0.777358 +0.629059 0.000000 0.777358 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.612387 0.000000 -0.790558 +-0.612387 0.000000 -0.790558 +-0.612387 0.000000 -0.790558 +-0.612387 0.000000 -0.790558 +-0.612387 0.000000 -0.790558 +-0.612387 0.000000 -0.790558 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.896866 0.000000 -0.442302 +0.896866 0.000000 -0.442302 +0.896866 0.000000 -0.442302 +0.896866 0.000000 -0.442302 +0.896866 0.000000 -0.442302 +0.896866 0.000000 -0.442302 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000665 0.000000 -1.000000 +0.000665 0.000000 -1.000000 +0.000665 0.000000 -1.000000 +0.000665 0.000000 -1.000000 +0.000665 0.000000 -1.000000 +0.000665 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.357193 0.000000 -0.934031 +0.357193 0.000000 -0.934031 +0.357193 0.000000 -0.934031 +0.357193 0.000000 -0.934031 +0.357193 0.000000 -0.934031 +0.357193 0.000000 -0.934031 +0.997314 0.000000 0.073248 +0.997314 0.000000 0.073248 +0.997314 0.000000 0.073248 +0.997314 0.000000 0.073248 +0.997314 0.000000 0.073248 +0.997314 0.000000 0.073248 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.995479 0.000000 0.094987 +-0.995479 0.000000 0.094987 +-0.995479 0.000000 0.094987 +-0.995479 0.000000 0.094987 +-0.995479 0.000000 0.094987 +-0.995479 0.000000 0.094987 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.629059 0.000000 0.777358 +0.629059 0.000000 0.777358 +0.629059 0.000000 0.777358 +0.629059 0.000000 0.777358 +0.629059 0.000000 0.777358 +0.629059 0.000000 0.777358 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.612387 0.000000 -0.790558 +-0.612387 0.000000 -0.790558 +-0.612387 0.000000 -0.790558 +-0.612387 0.000000 -0.790558 +-0.612387 0.000000 -0.790558 +-0.612387 0.000000 -0.790558 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.896866 0.000000 -0.442302 +0.896866 0.000000 -0.442302 +0.896866 0.000000 -0.442302 +0.896866 0.000000 -0.442302 +0.896866 0.000000 -0.442302 +0.896866 0.000000 -0.442302 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000665 0.000000 -1.000000 +0.000665 0.000000 -1.000000 +0.000665 0.000000 -1.000000 +0.000665 0.000000 -1.000000 +0.000665 0.000000 -1.000000 +0.000665 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.499995 0.866028 0.000000 +-0.499995 0.866028 0.000000 +-0.499995 0.866028 0.000000 +-0.499995 0.866028 0.000000 +-0.499995 0.866028 0.000000 +-0.499995 0.866028 0.000000 +-0.939707 0.341980 0.000000 +-0.939707 0.341980 0.000000 +-0.939707 0.341980 0.000000 +-0.939707 0.341980 0.000000 +-0.939707 0.341980 0.000000 +-0.939707 0.341980 0.000000 +-0.939717 -0.341954 0.000000 +-0.939717 -0.341954 0.000000 +-0.939717 -0.341954 0.000000 +-0.939717 -0.341954 0.000000 +-0.939717 -0.341954 0.000000 +-0.939717 -0.341954 0.000000 +-0.499995 -0.866028 0.000000 +-0.499995 -0.866028 0.000000 +-0.499995 -0.866028 0.000000 +-0.499995 -0.866028 0.000000 +-0.499995 -0.866028 0.000000 +-0.499995 -0.866028 0.000000 +0.173667 -0.984805 0.000000 +0.173667 -0.984805 0.000000 +0.173667 -0.984805 0.000000 +0.173667 -0.984805 0.000000 +0.173667 -0.984805 0.000000 +0.173667 -0.984805 0.000000 +0.766060 -0.642769 0.000000 +0.766060 -0.642769 0.000000 +0.766060 -0.642769 0.000000 +0.766060 -0.642769 0.000000 +0.766060 -0.642769 0.000000 +0.766060 -0.642769 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.766027 0.642809 0.000000 +0.766027 0.642809 0.000000 +0.766027 0.642809 0.000000 +0.766027 0.642809 0.000000 +0.766027 0.642809 0.000000 +0.766027 0.642809 0.000000 +0.173667 0.984805 0.000000 +0.173667 0.984805 0.000000 +0.173667 0.984805 0.000000 +0.173667 0.984805 0.000000 +0.173667 0.984805 0.000000 +0.173667 0.984805 0.000000 +0.173696 0.000000 -0.984799 +0.173696 0.000000 -0.984799 +0.173696 0.000000 -0.984799 +0.173696 0.000000 -0.984799 +0.173696 0.000000 -0.984799 +0.173696 0.000000 -0.984799 +0.766035 0.000000 -0.642799 +0.766035 0.000000 -0.642799 +0.766035 0.000000 -0.642799 +0.766035 0.000000 -0.642799 +0.766035 0.000000 -0.642799 +0.766035 0.000000 -0.642799 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.766035 0.000000 0.642799 +0.766035 0.000000 0.642799 +0.766035 0.000000 0.642799 +0.766035 0.000000 0.642799 +0.766035 0.000000 0.642799 +0.766035 0.000000 0.642799 +0.173616 0.000008 0.984813 +0.173616 0.000008 0.984814 +0.173616 0.000008 0.984814 +0.173616 0.000008 0.984814 +0.173616 0.000008 0.984814 +0.173696 0.000000 0.984799 +-0.499960 0.000007 0.866049 +-0.499960 0.000007 0.866049 +-0.499960 0.000007 0.866048 +-0.499960 0.000007 0.866048 +-0.500022 0.000000 0.866013 +-0.499960 0.000007 0.866049 +-0.939700 0.000000 0.342000 +-0.939700 0.000000 0.342000 +-0.939700 0.000000 0.342000 +-0.939700 0.000000 0.342000 +-0.939700 0.000000 0.342000 +-0.939700 0.000000 0.342000 +-0.939690 0.000000 -0.342027 +-0.939690 0.000000 -0.342027 +-0.939690 0.000000 -0.342027 +-0.939690 0.000000 -0.342027 +-0.939690 0.000000 -0.342027 +-0.939690 0.000000 -0.342027 +-0.500022 0.000000 -0.866013 +-0.500022 0.000000 -0.866013 +-0.500022 0.000000 -0.866013 +-0.500022 0.000000 -0.866013 +-0.500022 0.000000 -0.866013 +-0.500022 0.000000 -0.866013 +0.000000 -0.173670 -0.984804 +0.000000 -0.173670 -0.984804 +0.000000 -0.173671 -0.984804 +0.000000 -0.173670 -0.984804 +0.000000 -0.173671 -0.984804 +0.000000 -0.173670 -0.984804 +0.000000 -0.766098 -0.642724 +0.000000 -0.766098 -0.642724 +0.000000 -0.766098 -0.642724 +0.000000 -0.766098 -0.642724 +0.000000 -0.766098 -0.642724 +0.000000 -0.766098 -0.642724 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -0.766098 0.642724 +0.000000 -0.766098 0.642724 +0.000000 -0.766098 0.642724 +0.000000 -0.766098 0.642724 +0.000000 -0.766098 0.642724 +0.000000 -0.766098 0.642724 +0.000000 -0.173671 0.984804 +0.000000 -0.173671 0.984804 +0.000000 -0.173671 0.984804 +0.000000 -0.173671 0.984804 +0.000000 -0.173671 0.984804 +0.000000 -0.173671 0.984804 +0.000000 0.500027 0.866010 +0.000000 0.500027 0.866010 +0.000000 0.500027 0.866010 +0.000000 0.500027 0.866010 +0.000000 0.500027 0.866010 +0.000000 0.500027 0.866010 +0.000000 0.939709 0.341975 +0.000000 0.939709 0.341975 +0.000000 0.939709 0.341975 +0.000000 0.939709 0.341975 +0.000000 0.939709 0.341975 +0.000000 0.939709 0.341975 +0.000000 0.939709 -0.341975 +0.000000 0.939709 -0.341975 +0.000000 0.939709 -0.341975 +0.000000 0.939709 -0.341975 +0.000000 0.939709 -0.341975 +0.000000 0.939709 -0.341975 +0.000000 0.500027 -0.866010 +0.000000 0.500027 -0.866010 +0.000000 0.500027 -0.866010 +0.000000 0.500027 -0.866010 +0.000000 0.500027 -0.866010 +0.000000 0.500027 -0.866010 +0.000000 -0.394046 0.919091 +0.000000 -0.394046 0.919091 +0.000000 -0.394046 0.919091 +0.000000 -0.394046 0.919091 +0.000000 -0.394046 0.919091 +0.000000 -0.394046 0.919091 +0.000000 -0.101879 0.994797 +0.000000 -0.101879 0.994797 +0.000000 -0.101879 0.994797 +0.000000 -0.101879 0.994797 +0.000000 -0.101879 0.994797 +0.000000 -0.101879 0.994797 +0.000000 -0.233160 0.972438 +0.000000 -0.233160 0.972438 +0.000000 -0.233160 0.972438 +0.000000 -0.233160 0.972438 +0.000000 -0.233160 0.972438 +0.000000 -0.233160 0.972438 +0.000000 -0.437022 0.899451 +0.000000 -0.437022 0.899451 +0.000000 -0.437022 0.899451 +0.000000 -0.437022 0.899451 +0.000000 -0.437022 0.899451 +0.000000 -0.437022 0.899451 +0.000000 -0.437022 0.899451 +0.000000 -0.437022 0.899451 +0.000000 -0.437022 0.899451 +0.000000 -0.437022 0.899451 +0.000000 -0.437022 0.899451 +0.000000 -0.437022 0.899451 +0.000000 -0.209514 0.977806 +0.000000 -0.209514 0.977806 +0.000000 -0.209514 0.977806 +0.000000 -0.209514 0.977806 +0.000000 -0.209514 0.977806 +0.000000 -0.209514 0.977805 +0.000000 -0.209514 0.977806 +0.000000 -0.209514 0.977806 +0.000000 -0.209514 0.977806 +0.000000 -0.209514 0.977806 +0.000000 -0.209514 0.977805 +0.000000 -0.209514 0.977806 +0.000000 -0.300650 0.953734 +0.000000 -0.300650 0.953734 +0.000000 -0.300650 0.953735 +0.000000 -0.300650 0.953735 +0.000000 -0.300650 0.953734 +0.000000 -0.300650 0.953734 +0.000000 -0.300650 0.953734 +0.000000 -0.300650 0.953734 +0.000000 -0.300650 0.953734 +0.000000 -0.300650 0.953734 +0.000000 -0.300650 0.953734 +0.000000 -0.300650 0.953734 +0.999619 -0.025773 -0.009934 +0.999641 -0.026062 -0.006295 +0.999641 -0.026062 -0.006295 +0.999641 -0.026062 -0.006295 +0.999641 -0.026062 -0.006295 +0.999640 -0.026062 -0.006295 +0.999582 -0.028117 -0.006792 +0.999605 -0.027771 -0.004373 +0.999605 -0.027771 -0.004373 +0.999605 -0.027771 -0.004373 +0.999605 -0.027771 -0.004373 +0.999605 -0.027771 -0.004373 +0.999596 -0.028094 -0.004423 +0.999617 -0.027663 -0.000155 +0.999617 -0.027663 -0.000155 +0.999617 -0.027663 -0.000155 +0.999617 -0.027663 -0.000155 +0.999617 -0.027663 -0.000155 +0.000000 0.999980 0.006348 +0.000000 0.999980 0.006348 +0.000000 0.999980 0.006348 +0.000000 0.999980 0.006348 +0.008450 0.999949 0.005600 +0.000000 0.999980 0.006348 +-0.999808 0.019581 0.000124 +-0.999808 0.019581 0.000124 +-0.999808 0.019581 0.000124 +-0.999808 0.019581 0.000124 +-0.999808 0.019581 0.000124 +-0.999796 0.019817 0.003830 +-0.999804 0.019433 0.003755 +-0.999804 0.019433 0.003755 +-0.999804 0.019433 0.003755 +-0.999804 0.019433 0.003755 +-0.999804 0.019433 0.003755 +-0.999790 0.019578 0.006091 +-0.999823 0.017938 0.005581 +-0.999823 0.017938 0.005581 +-0.999824 0.017938 0.005581 +-0.999823 0.017938 0.005581 +-0.999823 0.017938 0.005581 +-0.999819 0.017731 0.006863 +0.999819 0.017731 0.006863 +0.999823 0.017938 0.005581 +0.999824 0.017938 0.005581 +0.999824 0.017938 0.005581 +0.999823 0.017938 0.005581 +0.999824 0.017938 0.005581 +0.999790 0.019578 0.006091 +0.999804 0.019433 0.003755 +0.999804 0.019433 0.003755 +0.999804 0.019433 0.003755 +0.999804 0.019433 0.003755 +0.999804 0.019433 0.003755 +0.999797 0.019794 0.003825 +0.999809 0.019558 0.000124 +0.999809 0.019558 0.000124 +0.999809 0.019558 0.000124 +0.999809 0.019558 0.000124 +0.999809 0.019558 0.000124 +0.000000 0.999980 0.006348 +0.000000 0.999980 0.006348 +0.000000 0.999980 0.006348 +-0.008442 0.999949 0.005600 +0.000000 0.999980 0.006348 +0.000000 0.999980 0.006348 +-0.999617 -0.027663 -0.000155 +-0.999617 -0.027663 -0.000155 +-0.999617 -0.027663 -0.000155 +-0.999617 -0.027663 -0.000155 +-0.999617 -0.027663 -0.000155 +-0.999596 -0.028094 -0.004424 +-0.999605 -0.027771 -0.004373 +-0.999605 -0.027771 -0.004373 +-0.999605 -0.027771 -0.004373 +-0.999605 -0.027771 -0.004373 +-0.999605 -0.027771 -0.004373 +-0.999582 -0.028117 -0.006792 +-0.999639 -0.026112 -0.006307 +-0.999639 -0.026112 -0.006307 +-0.999639 -0.026112 -0.006307 +-0.999639 -0.026112 -0.006307 +-0.999639 -0.026112 -0.006307 +-0.999617 -0.025822 -0.009953 +0.000000 0.366056 -0.930593 +0.000000 0.366056 -0.930593 +0.000000 0.366056 -0.930593 +0.000000 0.366056 -0.930593 +0.000000 0.366056 -0.930593 +0.000000 0.366056 -0.930593 +0.000000 0.233211 -0.972426 +0.000000 0.233211 -0.972426 +0.000000 0.233211 -0.972426 +0.000000 0.233211 -0.972426 +0.000000 0.233211 -0.972426 +0.000000 0.233211 -0.972426 +0.000000 0.101876 -0.994797 +0.000000 0.101876 -0.994797 +0.000000 0.101876 -0.994797 +0.000000 0.101876 -0.994797 +0.000000 0.101876 -0.994797 +0.000000 0.101876 -0.994797 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -0.935795 -0.352543 +0.000000 -0.935795 -0.352544 +0.000000 -0.935795 -0.352544 +0.000000 -0.935795 -0.352544 +0.000000 -0.935795 -0.352543 +0.000000 -0.935795 -0.352543 +0.000000 -0.932577 -0.360972 +0.000000 -0.932577 -0.360972 +0.000000 -0.932577 -0.360972 +0.000000 -0.932577 -0.360972 +0.017064 -0.932949 -0.359603 +0.000000 -0.932577 -0.360972 +0.000000 -0.932577 -0.360972 +0.000000 -0.932577 -0.360972 +0.000000 -0.932577 -0.360972 +-0.017021 -0.932950 -0.359603 +0.000000 -0.932577 -0.360972 +0.000000 -0.932577 -0.360972 + + + + + + + + + + + +0.557290 0.646631 +0.551307 0.644150 +0.602577 0.644040 +0.596952 0.646380 +0.083823 0.998410 +0.083820 0.975838 +0.123281 0.975834 +0.123284 0.998406 +0.042331 0.667893 +0.017604 0.667811 +0.017628 0.661568 +0.042354 0.661650 +0.605460 0.640294 +0.548248 0.640408 +0.093631 0.661482 +0.118356 0.661512 +0.118348 0.667384 +0.093622 0.667354 +0.211487 0.647075 +0.262762 0.646947 +0.256791 0.649456 +0.217126 0.649390 +0.017646 0.656765 +0.042373 0.656847 +0.545559 0.634549 +0.608168 0.634268 +0.093637 0.656776 +0.118363 0.656807 +0.208585 0.643343 +0.265801 0.643191 +0.017671 0.650264 +0.042397 0.650346 +0.093646 0.650112 +0.118372 0.650142 +0.543528 0.628685 +0.610219 0.628246 +0.205844 0.637329 +0.268459 0.637318 +0.017694 0.643980 +0.042420 0.644061 +0.093655 0.643668 +0.118381 0.643699 +0.618485 0.603649 +0.534442 0.603355 +0.203761 0.631316 +0.270459 0.631445 +0.017797 0.616740 +0.042522 0.616821 +0.093692 0.617382 +0.118417 0.617412 +0.631766 0.564128 +0.520025 0.563158 +0.195364 0.606756 +0.279411 0.606071 +0.042683 0.573594 +0.000500 0.573457 +0.093751 0.575145 +0.135934 0.575196 +0.565843 0.551994 +0.558288 0.547940 +0.181844 0.564174 +0.293587 0.562727 +0.001014 0.434967 +0.043196 0.435104 +0.094551 0.000500 +0.136733 0.000551 +0.136128 0.435854 +0.093945 0.435802 +0.915021 0.588916 +0.872924 0.588922 +0.872909 0.490623 +0.915006 0.490618 +0.864341 0.382810 +0.864347 0.422101 +0.853311 0.422102 +0.853305 0.382812 +0.892182 0.363039 +0.851179 0.363038 +0.851179 0.352959 +0.892182 0.352960 +0.873182 0.382809 +0.873188 0.422099 +0.851179 0.344886 +0.892182 0.344886 +0.965184 0.382795 +0.965191 0.422086 +0.879590 0.422099 +0.879584 0.382808 +0.971593 0.422085 +0.971587 0.382794 +0.980428 0.382793 +0.980434 0.422083 +0.892182 0.255019 +0.851179 0.255019 +0.851179 0.246945 +0.892182 0.246945 +0.991464 0.382792 +0.991471 0.422082 +0.851179 0.236867 +0.892182 0.236867 +0.520689 0.427321 +0.522768 0.001171 +0.626045 0.000500 +0.630381 0.427457 +0.002614 0.000500 +0.044796 0.000636 +0.182565 0.427489 +0.184826 0.000500 +0.288109 0.000732 +0.292260 0.426887 +0.554598 0.463963 +0.555111 0.542844 +0.576528 0.553870 +0.587188 0.551873 +0.594690 0.547734 +0.575871 0.452695 +0.565211 0.454692 +0.557710 0.458831 +0.597801 0.542602 +0.597289 0.463720 +0.594112 0.458624 +0.586557 0.454570 +0.851179 0.260866 +0.892182 0.260866 +0.892182 0.339039 +0.851179 0.339039 +0.247869 0.454449 +0.237198 0.452497 +0.226522 0.454418 +0.255391 0.458556 +0.218987 0.458503 +0.258401 0.542562 +0.258528 0.463675 +0.247712 0.551758 +0.255247 0.547672 +0.218842 0.547621 +0.226364 0.551728 +0.237035 0.553679 +0.215834 0.463613 +0.215706 0.542502 +0.729383 0.005354 +0.635576 0.000500 +0.632752 0.300985 +0.696747 0.302203 +0.633392 0.364320 +0.690641 0.364909 +0.632752 0.377891 +0.196547 0.662159 +0.347338 0.924859 +0.778764 0.640494 +0.366022 0.985229 +0.795966 0.700842 +0.991236 0.187941 +0.897603 0.187941 +0.790917 0.976357 +0.780782 0.974249 +0.765362 0.780982 +0.755281 0.766191 +0.770411 0.786270 +0.426902 0.926822 +0.480263 0.926822 +0.775715 0.971087 +0.760514 0.957386 +0.738382 0.966251 +0.934409 0.962656 +0.918733 0.974249 +0.939830 0.957386 +0.696467 0.806938 +0.750022 0.914595 +0.696467 0.914595 +0.696467 0.791869 +0.696467 0.786296 +0.696467 0.772433 +0.785572 0.797915 +0.750322 0.806938 +0.750322 0.797441 +0.696467 0.949100 +0.696467 0.966251 +0.696467 0.942168 +0.750380 0.942631 +0.954074 0.766843 +0.750322 0.791869 +0.750321 0.772433 +0.951676 0.942631 +0.746265 0.942168 +0.749687 0.924092 +0.744381 0.949100 +0.913402 0.800443 +0.908593 0.976357 +0.795700 0.800057 +0.928626 0.795222 +0.933706 0.792076 +0.943882 0.781568 +0.696467 0.924092 +0.750321 0.755281 +0.696467 0.755281 +0.055147 0.926822 +0.046860 0.926822 +0.038404 0.926822 +0.029907 0.926822 +0.279028 0.926822 +0.270608 0.926822 +0.262215 0.926822 +0.253834 0.926822 +0.245559 0.926822 +0.046860 0.961117 +0.055147 0.961117 +0.055147 0.966040 +0.046860 0.966040 +0.038404 0.961117 +0.038404 0.966040 +0.029907 0.961117 +0.029907 0.966040 +0.279028 0.960971 +0.279028 0.965928 +0.270608 0.960971 +0.270608 0.965928 +0.262214 0.960971 +0.262214 0.965928 +0.253834 0.960971 +0.253834 0.965928 +0.245559 0.960971 +0.245559 0.965928 +0.046860 0.996637 +0.046860 0.993250 +0.055147 0.993250 +0.055147 0.996637 +0.038404 0.996637 +0.038404 0.993250 +0.029907 0.996637 +0.029907 0.993250 +0.279028 0.996661 +0.279028 0.993243 +0.270608 0.996661 +0.270608 0.993243 +0.262214 0.996661 +0.262214 0.993243 +0.253834 0.996661 +0.253834 0.993243 +0.245559 0.996661 +0.245559 0.993243 +0.055147 0.999483 +0.245559 0.999500 +0.253834 0.999500 +0.046860 0.999483 +0.038404 0.999483 +0.029907 0.999483 +0.279028 0.999500 +0.270608 0.999500 +0.262214 0.999500 +0.063399 0.926822 +0.063399 0.961117 +0.063399 0.966040 +0.063399 0.996637 +0.063399 0.993250 +0.836125 0.452884 +0.840614 0.451408 +0.845067 0.452977 +0.833700 0.456714 +0.834474 0.461106 +0.838085 0.464005 +0.842843 0.464055 +0.846522 0.461232 +0.847401 0.456857 +0.287406 0.926822 +0.287406 0.960971 +0.287406 0.965928 +0.287406 0.996661 +0.287406 0.993243 +0.287406 0.999500 +0.063399 0.999483 +0.249045 0.810003 +0.278280 0.808338 +0.285293 0.909943 +0.245559 0.923303 +0.835670 0.584352 +0.864882 0.586360 +0.860007 0.588735 +0.840533 0.587397 +0.019409 0.833743 +0.018725 0.949962 +0.010302 0.949919 +0.010986 0.833700 +0.467128 0.964594 +0.426902 0.964680 +0.426913 0.956315 +0.467138 0.956229 +0.412199 0.815518 +0.413082 0.711170 +0.421502 0.711233 +0.420617 0.815580 +0.500429 0.956233 +0.504936 0.956232 +0.504890 0.964349 +0.500382 0.964351 +0.514416 0.956231 +0.519826 0.956229 +0.519780 0.964347 +0.514370 0.964348 +0.509519 0.956232 +0.509473 0.964349 +0.495700 0.964351 +0.490618 0.964353 +0.490664 0.956236 +0.495746 0.956234 +0.253948 0.807016 +0.273438 0.805906 +0.833700 0.471013 +0.873255 0.484838 +0.855135 0.590027 +0.845397 0.589357 +0.258838 0.805112 +0.268583 0.804557 +0.850264 0.590234 +0.263717 0.804293 +0.991236 0.000500 +0.832179 0.377891 +0.897603 0.000500 +0.396048 0.662159 +0.396048 0.924859 +0.832179 0.640494 +0.396048 0.985229 +0.832179 0.700842 +0.790917 0.931724 +0.780783 0.931723 +0.755322 0.755281 +0.696467 0.976919 +0.765458 0.755314 +0.775595 0.755347 +0.426902 0.937392 +0.750380 0.931724 +0.480263 0.937392 +0.954115 0.755933 +0.770648 0.931724 +0.760514 0.931724 +0.738382 0.976919 +0.951676 0.931724 +0.928988 0.931724 +0.918733 0.931724 +0.939830 0.931724 +0.785731 0.755381 +0.908593 0.931724 +0.795867 0.755414 +0.913569 0.755800 +0.923705 0.755833 +0.933842 0.755867 +0.943978 0.755900 +0.444563 0.646631 +0.484225 0.646380 +0.489850 0.644040 +0.438580 0.644150 +0.490620 0.944497 +0.530081 0.944493 +0.530078 0.921921 +0.490618 0.921925 +0.086441 0.667893 +0.086465 0.661650 +0.061738 0.661568 +0.061715 0.667811 +0.492733 0.640294 +0.435521 0.640408 +0.137741 0.661482 +0.137733 0.667354 +0.162458 0.667384 +0.162467 0.661512 +0.324214 0.647075 +0.329853 0.649389 +0.369518 0.649456 +0.375489 0.646947 +0.086483 0.656847 +0.061757 0.656765 +0.495441 0.634268 +0.432832 0.634549 +0.137748 0.656776 +0.162473 0.656807 +0.321312 0.643342 +0.378528 0.643190 +0.086508 0.650346 +0.061781 0.650264 +0.137757 0.650112 +0.162482 0.650142 +0.497492 0.628246 +0.430801 0.628685 +0.381186 0.637318 +0.318571 0.637329 +0.086531 0.644061 +0.061805 0.643980 +0.137766 0.643668 +0.162491 0.643698 +0.505758 0.603650 +0.421715 0.603355 +0.383186 0.631445 +0.316488 0.631315 +0.086633 0.616821 +0.061907 0.616740 +0.137803 0.617382 +0.162528 0.617412 +0.519039 0.564128 +0.407298 0.563158 +0.308091 0.606755 +0.392138 0.606071 +0.086793 0.573594 +0.044611 0.573457 +0.137862 0.575145 +0.180044 0.575196 +0.453116 0.551994 +0.445561 0.547941 +0.294571 0.564174 +0.406314 0.562727 +0.087307 0.435104 +0.045124 0.434967 +0.138056 0.435802 +0.180238 0.435854 +0.180844 0.000551 +0.138661 0.000500 +0.959132 0.579114 +0.959117 0.480815 +0.917020 0.480821 +0.917035 0.579119 +0.864340 0.426921 +0.853305 0.426923 +0.853311 0.466213 +0.864347 0.466211 +0.848071 0.363039 +0.848071 0.352960 +0.807068 0.352959 +0.807068 0.363038 +0.873188 0.466210 +0.873182 0.426920 +0.848071 0.344886 +0.807068 0.344886 +0.965184 0.426906 +0.879584 0.426919 +0.879590 0.466209 +0.965191 0.466197 +0.971593 0.466195 +0.980434 0.466194 +0.980428 0.426904 +0.971587 0.426905 +0.848071 0.255019 +0.848071 0.246945 +0.807068 0.246945 +0.807068 0.255019 +0.991464 0.426902 +0.991470 0.466192 +0.848071 0.236867 +0.807068 0.236867 +0.517653 0.427457 +0.513318 0.000500 +0.410041 0.001171 +0.407962 0.427321 +0.088907 0.000636 +0.046725 0.000500 +0.404987 0.426887 +0.400836 0.000732 +0.297553 0.000500 +0.295292 0.427489 +0.442383 0.542844 +0.441871 0.463963 +0.463801 0.553870 +0.474461 0.551873 +0.481963 0.547734 +0.452484 0.454692 +0.463144 0.452695 +0.444982 0.458831 +0.484562 0.463720 +0.485074 0.542602 +0.473830 0.454570 +0.481385 0.458624 +0.807068 0.339039 +0.848071 0.339039 +0.848071 0.260866 +0.807068 0.260866 +0.360596 0.454448 +0.349925 0.452497 +0.339249 0.454417 +0.368118 0.458556 +0.331714 0.458503 +0.371255 0.463675 +0.371128 0.542562 +0.360439 0.551758 +0.367974 0.547672 +0.339091 0.551728 +0.331569 0.547621 +0.349762 0.553679 +0.328433 0.542502 +0.328561 0.463613 +0.000500 0.671961 +0.151291 0.934661 +0.200001 0.934661 +0.200001 0.671961 +0.733599 0.000500 +0.827407 0.005354 +0.794771 0.302203 +0.730775 0.300984 +0.169975 0.995031 +0.200001 0.995031 +0.788664 0.364909 +0.731416 0.364320 +0.770411 0.845083 +0.755281 0.825005 +0.755322 0.814095 +0.765458 0.814129 +0.775459 0.850371 +0.775595 0.814162 +0.892644 0.052157 +0.892344 0.159813 +0.838790 0.159813 +0.838790 0.052157 +0.838790 0.042660 +0.838790 0.037088 +0.892644 0.031515 +0.892644 0.037088 +0.838790 0.017652 +0.838789 0.000500 +0.892644 0.000500 +0.892644 0.017652 +0.785731 0.814195 +0.785572 0.856730 +0.890472 0.180455 +0.838790 0.180455 +0.838790 0.169311 +0.892010 0.169311 +0.923634 0.915435 +0.913494 0.917543 +0.913494 0.872910 +0.923634 0.872909 +0.880704 0.211470 +0.838789 0.211470 +0.838790 0.187387 +0.888587 0.187387 +0.795700 0.858871 +0.795867 0.814228 +0.913569 0.814614 +0.913402 0.859257 +0.923705 0.814647 +0.923546 0.857182 +0.933842 0.814681 +0.928626 0.854036 +0.943978 0.814714 +0.943882 0.840382 +0.954115 0.814748 +0.954074 0.825657 +0.986370 0.515110 +0.986370 0.520033 +0.978084 0.520033 +0.978084 0.515110 +0.969627 0.520033 +0.969627 0.515110 +0.961131 0.520033 +0.961131 0.515110 +0.757919 0.657098 +0.757919 0.662055 +0.749541 0.662055 +0.749541 0.657098 +0.741121 0.662055 +0.741121 0.657098 +0.732727 0.662055 +0.732727 0.657098 +0.724347 0.662055 +0.724347 0.657098 +0.716072 0.662055 +0.716072 0.657098 +0.994622 0.515110 +0.994622 0.520033 +0.978084 0.550630 +0.978084 0.547243 +0.986370 0.547243 +0.986370 0.550630 +0.969627 0.550630 +0.969627 0.547243 +0.961131 0.550630 +0.961131 0.547243 +0.749541 0.692788 +0.749541 0.689370 +0.757919 0.689370 +0.757919 0.692788 +0.741121 0.692788 +0.741121 0.689370 +0.732727 0.692788 +0.732727 0.689370 +0.724347 0.692788 +0.724347 0.689370 +0.716072 0.692788 +0.716072 0.689370 +0.994622 0.547243 +0.994622 0.550630 +0.497532 0.966032 +0.501985 0.967601 +0.490618 0.971337 +0.493043 0.967508 +0.986370 0.553476 +0.978084 0.553476 +0.969627 0.553476 +0.961131 0.553476 +0.757919 0.695627 +0.749541 0.695627 +0.741121 0.695627 +0.732727 0.695627 +0.724347 0.695627 +0.716072 0.695627 +0.994622 0.553476 +0.978084 0.480815 +0.986370 0.480815 +0.969627 0.480815 +0.961131 0.480815 +0.749541 0.622949 +0.757919 0.622949 +0.741121 0.622949 +0.732727 0.622949 +0.724347 0.622949 +0.716072 0.622949 +0.994622 0.480815 +0.504318 0.971480 +0.491392 0.975730 +0.503440 0.975855 +0.495002 0.978629 +0.499761 0.978678 +0.077504 0.863916 +0.074018 0.977215 +0.113751 0.963856 +0.106739 0.862251 +0.041641 0.920677 +0.061116 0.922015 +0.065991 0.919640 +0.036779 0.917632 +0.019409 0.716115 +0.010986 0.716072 +0.010302 0.832291 +0.018725 0.832334 +0.467128 0.974397 +0.467138 0.966032 +0.426913 0.966117 +0.426902 0.974482 +0.299472 0.972355 +0.307890 0.972418 +0.308774 0.868070 +0.300355 0.868008 +0.500382 0.954548 +0.504890 0.954547 +0.504936 0.946430 +0.500429 0.946431 +0.514370 0.954546 +0.519780 0.954544 +0.519826 0.946427 +0.514416 0.946428 +0.509472 0.954546 +0.509519 0.946429 +0.495746 0.946432 +0.490664 0.946433 +0.490618 0.954550 +0.495700 0.954549 +0.101896 0.859819 +0.082407 0.860929 +0.074363 0.818118 +0.034808 0.804293 +0.046506 0.922637 +0.056243 0.923307 +0.097042 0.858470 +0.087297 0.859025 +0.051373 0.923514 +0.092175 0.858206 +0.991048 0.191646 +0.991048 0.379087 +0.897415 0.379087 +0.897415 0.191646 +0.596923 0.919861 +0.543507 0.919861 +0.397495 0.657258 +0.596923 0.657258 +0.596923 0.980209 +0.560710 0.980209 +0.795818 0.872909 +0.795818 0.917543 +0.780617 0.912273 +0.785684 0.872909 +0.426902 0.952095 +0.426902 0.941526 +0.480263 0.941526 +0.480263 0.952095 +0.775550 0.909111 +0.775550 0.872909 +0.765415 0.872909 +0.765415 0.898572 +0.755281 0.883817 +0.755281 0.872909 +0.838789 0.222137 +0.880704 0.222138 +0.933889 0.872910 +0.933889 0.909111 +0.956577 0.872909 +0.956577 0.883817 +0.939310 0.903841 +0.944731 0.872909 +0.121630 0.445266 +0.093513 0.445266 +0.093513 0.398749 +0.121630 0.398749 +0.121630 0.491320 +0.093513 0.491320 +0.121630 0.536619 +0.093513 0.536619 +0.121630 0.580952 +0.093513 0.580952 +0.121630 0.624189 +0.093513 0.624189 +0.121630 0.666219 +0.093513 0.666219 +0.121630 0.706882 +0.093513 0.706882 +0.121630 0.745968 +0.093513 0.745968 +0.121630 0.783496 +0.093513 0.783496 +0.121630 0.043258 +0.093513 0.043258 +0.121630 0.084259 +0.093513 0.084259 +0.121630 0.126597 +0.093513 0.126597 +0.121630 0.170074 +0.093513 0.170074 +0.121630 0.214474 +0.093513 0.214474 +0.121630 0.259712 +0.093513 0.259712 +0.121630 0.305657 +0.093513 0.305657 +0.121630 0.352101 +0.093513 0.352101 +0.133073 0.398749 +0.133073 0.445266 +0.133073 0.352101 +0.133073 0.305657 +0.133073 0.259712 +0.133073 0.214474 +0.133073 0.170074 +0.133073 0.126597 +0.133073 0.084259 +0.133073 0.043258 +0.133073 0.003616 +0.133073 0.745968 +0.133073 0.706882 +0.133073 0.666219 +0.133073 0.624189 +0.133073 0.580952 +0.133073 0.536619 +0.133073 0.491320 +0.164606 0.445266 +0.164606 0.398749 +0.164606 0.491320 +0.164606 0.536619 +0.164606 0.580952 +0.164606 0.624189 +0.164606 0.666219 +0.164606 0.706882 +0.164606 0.745968 +0.164606 0.783496 +0.164606 0.043258 +0.164606 0.084259 +0.164606 0.126597 +0.164606 0.170074 +0.164606 0.214474 +0.164606 0.259712 +0.164606 0.305657 +0.164606 0.352101 +0.735709 0.113094 +0.736072 0.158310 +0.750833 0.070480 +0.779619 0.035610 +0.818596 0.012688 +0.863062 0.004478 +0.907653 0.011973 +0.946993 0.034266 +0.976336 0.068670 +0.121630 0.003616 +0.093513 0.003616 +0.992142 0.111035 +0.992505 0.156252 +0.977382 0.198865 +0.948595 0.233736 +0.909618 0.256659 +0.865152 0.264868 +0.820559 0.257374 +0.781219 0.235080 +0.751877 0.200675 +0.133073 0.783496 +0.788183 0.784364 +0.788032 0.825835 +0.774200 0.745484 +0.747926 0.713922 +0.712649 0.693377 +0.672570 0.686164 +0.632343 0.693123 +0.596716 0.713545 +0.570055 0.745111 +0.164606 0.003616 +0.555739 0.784032 +0.555588 0.825503 +0.569571 0.864383 +0.595844 0.895944 +0.631121 0.916490 +0.671201 0.923703 +0.711428 0.916744 +0.747056 0.896322 +0.773716 0.864755 +0.038368 0.445266 +0.010251 0.445266 +0.010251 0.398749 +0.038368 0.398749 +0.038368 0.491319 +0.010251 0.491319 +0.038368 0.536618 +0.010251 0.536618 +0.038368 0.580952 +0.010251 0.580952 +0.038368 0.624189 +0.010251 0.624189 +0.038368 0.666219 +0.010251 0.666219 +0.038368 0.706882 +0.010251 0.706882 +0.038368 0.745967 +0.010251 0.745967 +0.038368 0.783496 +0.010251 0.783496 +0.038368 0.043258 +0.010251 0.043258 +0.010251 0.003616 +0.038368 0.003616 +0.038368 0.084259 +0.010251 0.084259 +0.038368 0.126597 +0.010251 0.126597 +0.038368 0.170073 +0.010251 0.170073 +0.038368 0.214474 +0.010251 0.214474 +0.038368 0.259712 +0.010251 0.259712 +0.038368 0.305657 +0.010251 0.305657 +0.038368 0.352101 +0.010251 0.352101 +0.049811 0.398749 +0.049811 0.445266 +0.049811 0.352101 +0.049811 0.305657 +0.049811 0.259712 +0.049811 0.214474 +0.049811 0.170073 +0.049811 0.126597 +0.049811 0.084259 +0.049811 0.043258 +0.049811 0.003616 +0.049811 0.745967 +0.049811 0.783496 +0.049811 0.706882 +0.049811 0.666219 +0.049811 0.624189 +0.049811 0.580952 +0.049811 0.536618 +0.049811 0.491319 +0.081345 0.445266 +0.081345 0.398749 +0.081345 0.491319 +0.081345 0.536618 +0.081345 0.580952 +0.081345 0.624189 +0.081345 0.666219 +0.081345 0.706882 +0.081345 0.745967 +0.081345 0.783496 +0.081345 0.043258 +0.081345 0.003616 +0.081345 0.084259 +0.081345 0.126597 +0.081345 0.170073 +0.081345 0.214474 +0.081345 0.259712 +0.081345 0.305657 +0.081345 0.352101 +0.986570 0.606402 +1.000435 0.645324 +1.000158 0.686794 +0.985723 0.725672 +0.960392 0.574761 +0.958967 0.757157 +0.925177 0.554108 +0.923278 0.777470 +0.885120 0.546774 +0.883030 0.784307 +0.844872 0.553611 +0.842973 0.776973 +0.809182 0.573924 +0.807759 0.756320 +0.782426 0.605410 +0.781581 0.724679 +0.767992 0.644287 +0.767716 0.685757 +0.753612 0.473440 +0.737951 0.431021 +0.737742 0.385804 +0.753010 0.343242 +0.782838 0.507944 +0.781915 0.308470 +0.822102 0.530371 +0.820969 0.285680 +0.866669 0.538017 +0.865462 0.277622 +0.911163 0.529959 +0.910029 0.285267 +0.950217 0.507169 +0.949292 0.307694 +0.979122 0.472395 +0.978518 0.342198 +0.994390 0.429833 +0.994180 0.384616 +0.660137 0.844615 +0.681835 0.844615 +0.681835 0.858700 +0.660137 0.858700 +0.660137 0.830964 +0.681835 0.830964 +0.660137 0.817668 +0.681835 0.817668 +0.660137 0.804723 +0.681835 0.804723 +0.660137 0.792189 +0.681835 0.792189 +0.660137 0.779687 +0.681835 0.779687 +0.660137 0.766855 +0.681835 0.766855 +0.660137 0.753774 +0.681835 0.753774 +0.660137 0.740578 +0.681835 0.740578 +0.660137 0.963623 +0.681835 0.963623 +0.681835 0.976822 +0.660137 0.976822 +0.660137 0.950539 +0.681835 0.950539 +0.660137 0.937706 +0.681835 0.937706 +0.660137 0.925205 +0.681835 0.925205 +0.660137 0.912678 +0.681835 0.912678 +0.660137 0.899743 +0.681835 0.899743 +0.660137 0.886450 +0.681835 0.886450 +0.660137 0.872791 +0.681835 0.872791 +0.685647 0.844615 +0.694521 0.844615 +0.694521 0.858700 +0.685647 0.858700 +0.656326 0.858700 +0.647455 0.858700 +0.647455 0.844615 +0.656326 0.844615 +0.685647 0.830964 +0.694521 0.830964 +0.647455 0.830964 +0.656326 0.830964 +0.685647 0.817668 +0.694521 0.817668 +0.647455 0.817668 +0.656326 0.817668 +0.685647 0.804723 +0.694521 0.804723 +0.647455 0.804723 +0.656326 0.804723 +0.685647 0.792189 +0.694521 0.792189 +0.647455 0.792189 +0.656326 0.792189 +0.685647 0.779687 +0.694521 0.779687 +0.647455 0.779687 +0.656326 0.779687 +0.685647 0.766855 +0.694521 0.766855 +0.647455 0.766855 +0.656326 0.766855 +0.685647 0.753774 +0.694521 0.753774 +0.647455 0.753774 +0.656326 0.753774 +0.685647 0.740578 +0.694521 0.740578 +0.647455 0.740578 +0.656326 0.740578 +0.685647 0.963623 +0.694521 0.963623 +0.694521 0.976822 +0.685647 0.976822 +0.656326 0.976822 +0.647455 0.976822 +0.647455 0.963623 +0.656326 0.963623 +0.685647 0.950539 +0.694521 0.950539 +0.647455 0.950539 +0.656326 0.950539 +0.685647 0.937706 +0.694521 0.937706 +0.647455 0.937706 +0.656326 0.937706 +0.685647 0.925205 +0.694521 0.925205 +0.647455 0.925205 +0.656326 0.925205 +0.685647 0.912678 +0.694521 0.912678 +0.647455 0.912678 +0.656326 0.912678 +0.685647 0.899743 +0.694521 0.899743 +0.647455 0.899743 +0.656326 0.899743 +0.685647 0.886450 +0.694521 0.886450 +0.647455 0.886450 +0.656326 0.886450 +0.685647 0.872791 +0.694521 0.872791 +0.647455 0.872791 +0.656326 0.872791 +0.643318 0.607085 +0.637653 0.592359 +0.637714 0.576707 +0.643494 0.562020 +0.654025 0.619112 +0.654295 0.550067 +0.668485 0.626987 +0.668814 0.542291 +0.684951 0.629760 +0.685302 0.539629 +0.701438 0.627099 +0.701768 0.542403 +0.715958 0.619323 +0.716227 0.550278 +0.726759 0.607370 +0.726934 0.562304 +0.732538 0.592682 +0.732599 0.577031 +0.501246 0.855950 +0.507082 0.870618 +0.507203 0.886268 +0.501595 0.901014 +0.490399 0.844033 +0.490934 0.913076 +0.475850 0.836306 +0.476505 0.921000 +0.459352 0.833700 +0.460049 0.923829 +0.442896 0.836529 +0.443552 0.921223 +0.428468 0.844453 +0.429002 0.913495 +0.417807 0.856515 +0.418155 0.901579 +0.412199 0.871260 +0.412320 0.886911 +0.611126 0.858700 +0.632823 0.858700 +0.632823 0.844615 +0.611126 0.844615 +0.632823 0.830965 +0.611126 0.830965 +0.632823 0.817668 +0.611126 0.817668 +0.632823 0.804723 +0.611126 0.804723 +0.632823 0.792189 +0.611126 0.792189 +0.632823 0.779687 +0.611126 0.779687 +0.632823 0.766855 +0.611126 0.766855 +0.632823 0.753774 +0.611126 0.753774 +0.632823 0.740578 +0.611126 0.740578 +0.611126 0.976822 +0.632823 0.976822 +0.632823 0.963623 +0.611126 0.963623 +0.632823 0.950539 +0.611126 0.950539 +0.632823 0.937706 +0.611126 0.937706 +0.632823 0.925205 +0.611126 0.925205 +0.632823 0.912678 +0.611126 0.912678 +0.632823 0.899744 +0.611126 0.899744 +0.632823 0.886451 +0.611126 0.886451 +0.632823 0.872792 +0.611126 0.872792 +0.636635 0.858700 +0.645509 0.858700 +0.645509 0.844615 +0.636635 0.844615 +0.607314 0.844615 +0.598444 0.844615 +0.598444 0.858700 +0.607314 0.858700 +0.645509 0.830965 +0.636635 0.830965 +0.607314 0.830965 +0.598444 0.830965 +0.645509 0.817668 +0.636635 0.817668 +0.607314 0.817668 +0.598444 0.817668 +0.645509 0.804723 +0.636635 0.804723 +0.607314 0.804723 +0.598444 0.804723 +0.645509 0.792189 +0.636635 0.792189 +0.607314 0.792189 +0.598444 0.792189 +0.645509 0.779687 +0.636635 0.779687 +0.607314 0.779687 +0.598444 0.779687 +0.645509 0.766855 +0.636635 0.766855 +0.607314 0.766855 +0.598444 0.766855 +0.645509 0.753774 +0.636635 0.753774 +0.607314 0.753774 +0.598444 0.753774 +0.645509 0.740578 +0.636635 0.740578 +0.607314 0.740578 +0.598444 0.740578 +0.636635 0.976822 +0.645509 0.976822 +0.645509 0.963623 +0.636635 0.963623 +0.607314 0.963623 +0.598444 0.963623 +0.598444 0.976822 +0.607314 0.976822 +0.645509 0.950539 +0.636635 0.950539 +0.607314 0.950539 +0.598444 0.950539 +0.645509 0.937706 +0.636635 0.937706 +0.607314 0.937706 +0.598444 0.937706 +0.645509 0.925205 +0.636635 0.925205 +0.607314 0.925205 +0.598444 0.925205 +0.645509 0.912678 +0.636635 0.912678 +0.607314 0.912678 +0.598444 0.912678 +0.645509 0.899744 +0.636635 0.899744 +0.607314 0.899744 +0.598444 0.899744 +0.645509 0.886451 +0.636635 0.886451 +0.607314 0.886451 +0.598444 0.886451 +0.645509 0.872792 +0.636635 0.872792 +0.607314 0.872792 +0.598444 0.872792 +0.614087 0.650241 +0.608307 0.664929 +0.608246 0.680580 +0.613911 0.695307 +0.624888 0.638288 +0.624618 0.707333 +0.639407 0.630512 +0.639078 0.715208 +0.655895 0.627851 +0.655544 0.717982 +0.672361 0.630625 +0.672031 0.715320 +0.686820 0.638500 +0.686551 0.707544 +0.697527 0.650526 +0.697352 0.695591 +0.703192 0.665252 +0.703131 0.680903 +0.923096 0.670659 +0.928704 0.655913 +0.928583 0.640262 +0.922747 0.625594 +0.912435 0.682721 +0.911900 0.613678 +0.898006 0.690644 +0.897351 0.605951 +0.881551 0.693474 +0.880853 0.603345 +0.865054 0.690868 +0.864398 0.606174 +0.850504 0.683140 +0.849970 0.614098 +0.839657 0.671224 +0.839308 0.626160 +0.833821 0.656556 +0.833700 0.640905 +0.586734 0.208606 +0.586734 0.565608 +0.567089 0.208606 +0.606190 0.565608 +0.546909 0.208606 +0.625533 0.565608 +0.703055 0.208606 +0.395420 0.991461 +0.683476 0.208606 +0.387042 0.980082 +0.664111 0.208606 +0.387938 0.965979 +0.644821 0.208606 +0.397690 0.955753 +0.625533 0.208606 +0.411733 0.954187 +0.606190 0.208606 +0.567089 0.565608 +0.586734 0.068420 +0.567089 0.068420 +0.546909 0.068420 +0.723197 0.068420 +0.703055 0.068420 +0.683476 0.068420 +0.664111 0.068420 +0.644821 0.068420 +0.625533 0.068420 +0.606190 0.068420 +0.723197 0.208606 +0.586734 0.054419 +0.567089 0.054419 +0.546909 0.054419 +0.723197 0.054419 +0.703055 0.054419 +0.683476 0.054419 +0.664111 0.054419 +0.644821 0.054419 +0.625533 0.054419 +0.606190 0.054419 +0.586734 0.004051 +0.567089 0.004051 +0.546909 0.004051 +0.723197 0.004051 +0.703055 0.004051 +0.683476 0.004051 +0.664111 0.004051 +0.644821 0.004051 +0.625533 0.004051 +0.606190 0.004051 +0.586734 0.233166 +0.567089 0.233166 +0.546909 0.233166 +0.723197 0.233166 +0.703055 0.233166 +0.683476 0.233166 +0.664111 0.233166 +0.644821 0.233166 +0.625533 0.233166 +0.606190 0.233166 +0.427479 0.975573 +0.421813 0.988518 +0.409152 0.994793 +0.644821 0.565608 +0.664111 0.565608 +0.683476 0.565608 +0.703055 0.565608 +0.723197 0.565608 +0.546909 0.565608 +0.423498 0.962014 +0.241336 0.004994 +0.251390 0.766650 +0.209604 0.765772 +0.219929 0.004120 +0.284328 0.005591 +0.176937 0.004702 +0.189226 0.766048 +0.271768 0.766933 +0.377324 0.003499 +0.361808 0.765063 +0.320989 0.765121 +0.303297 0.003605 +0.395489 0.003764 +0.469515 0.003799 +0.452554 0.765055 +0.411736 0.765036 +0.055101 0.902876 +0.014284 0.902757 +0.014224 0.923138 +0.055042 0.923257 +0.508522 0.459887 +0.479330 0.526656 +0.484757 0.526656 +0.487364 0.526656 +0.494933 0.526656 +0.497286 0.526656 +0.504142 0.526656 +0.506332 0.459887 +0.506332 0.526656 +0.512860 0.526656 +0.517241 0.526656 +0.519489 0.526656 +0.526397 0.526656 +0.526397 0.459887 +0.531214 0.526656 +0.479330 0.563180 +0.484757 0.563180 +0.487364 0.563180 +0.494933 0.563180 +0.497286 0.563180 +0.504142 0.563180 +0.506332 0.563180 +0.512860 0.563180 +0.517241 0.563180 +0.519489 0.563180 +0.526397 0.563180 +0.531214 0.563180 +0.487364 0.609095 +0.489971 0.609095 +0.497286 0.609095 +0.499639 0.609095 +0.506332 0.609095 +0.508522 0.609095 +0.515051 0.609095 +0.517241 0.609095 +0.524067 0.609095 +0.526397 0.609095 +0.533681 0.609095 +0.479330 0.609095 +0.479330 0.624630 +0.484757 0.624630 +0.487364 0.624630 +0.494933 0.624630 +0.497286 0.624630 +0.504142 0.624630 +0.506332 0.624630 +0.512860 0.624630 +0.515051 0.624630 +0.521737 0.624630 +0.524067 0.624630 +0.531214 0.624630 +0.479330 0.638214 +0.484757 0.638214 +0.487364 0.638214 +0.494933 0.638214 +0.497286 0.638214 +0.504142 0.638214 +0.506332 0.638214 +0.512860 0.638214 +0.515051 0.638214 +0.521737 0.638214 +0.524067 0.638214 +0.531214 0.638214 +0.479330 0.651815 +0.484757 0.651815 +0.487364 0.651815 +0.494933 0.651815 +0.497286 0.651815 +0.504142 0.651815 +0.506332 0.651815 +0.512860 0.651815 +0.515051 0.651815 +0.521737 0.651815 +0.524067 0.651815 +0.531214 0.651815 +0.479330 0.663209 +0.484757 0.663209 +0.487364 0.663209 +0.494933 0.663209 +0.497286 0.663209 +0.504142 0.663209 +0.506332 0.663209 +0.512860 0.663209 +0.515051 0.663209 +0.521737 0.663209 +0.524067 0.663209 +0.531214 0.663209 +0.479330 0.673125 +0.484757 0.673125 +0.487364 0.673125 +0.494933 0.673125 +0.497286 0.673125 +0.504142 0.673125 +0.506332 0.673125 +0.512860 0.673125 +0.515051 0.673125 +0.521737 0.673125 +0.524067 0.673125 +0.531214 0.673125 +0.479330 0.685906 +0.484757 0.685906 +0.487364 0.685906 +0.494933 0.685906 +0.497286 0.685906 +0.504142 0.685906 +0.506332 0.685906 +0.512860 0.685906 +0.515051 0.685906 +0.521737 0.685906 +0.524067 0.685906 +0.531214 0.685906 +0.479330 0.777451 +0.484757 0.777451 +0.487364 0.777451 +0.494933 0.777451 +0.497286 0.777451 +0.504142 0.777451 +0.506332 0.777451 +0.512860 0.777451 +0.515051 0.777451 +0.521737 0.777451 +0.524067 0.777451 +0.531214 0.777451 +0.487365 0.459887 +0.499639 0.459887 +0.533681 0.459887 +0.517241 0.580873 +0.512860 0.580873 +0.506332 0.580873 +0.504142 0.580873 +0.497286 0.580873 +0.494933 0.580873 +0.487364 0.580873 +0.484757 0.580873 +0.479330 0.580873 +0.531214 0.580873 +0.526397 0.580873 +0.519489 0.580873 +0.521737 0.595957 +0.515051 0.595957 +0.512860 0.595957 +0.506332 0.595957 +0.504142 0.595957 +0.497286 0.595957 +0.494933 0.595957 +0.487364 0.595957 +0.484757 0.595957 +0.479330 0.595957 +0.531214 0.595957 +0.524067 0.595957 +0.479330 0.459887 +0.487365 0.391526 +0.479330 0.391526 +0.489972 0.459887 +0.489972 0.391526 +0.497286 0.459887 +0.497286 0.391526 +0.499639 0.391526 +0.506332 0.391526 +0.508522 0.391526 +0.512860 0.459887 +0.512860 0.391526 +0.519489 0.459887 +0.519489 0.391526 +0.521737 0.459887 +0.521737 0.391526 +0.526397 0.391526 +0.533681 0.391526 +0.487365 0.352210 +0.479330 0.352210 +0.489972 0.352210 +0.497286 0.352210 +0.499639 0.352210 +0.506332 0.352210 +0.508522 0.352210 +0.512860 0.352210 +0.519489 0.352210 +0.521737 0.352210 +0.526397 0.352210 +0.533681 0.352210 +0.487365 0.332180 +0.479330 0.332180 +0.489972 0.332180 +0.497286 0.332180 +0.499639 0.332180 +0.506332 0.332180 +0.508522 0.332180 +0.512860 0.332180 +0.519489 0.332180 +0.521737 0.332180 +0.526397 0.332180 +0.533681 0.332180 +0.479330 0.297630 +0.484757 0.297630 +0.487365 0.276860 +0.479330 0.276860 +0.487365 0.297630 +0.489972 0.276860 +0.494933 0.297630 +0.497286 0.276860 +0.497286 0.297630 +0.499639 0.276860 +0.504142 0.297630 +0.506332 0.276860 +0.506332 0.297630 +0.508522 0.276860 +0.512860 0.297630 +0.512860 0.276860 +0.517241 0.297630 +0.519489 0.276860 +0.519489 0.297630 +0.521737 0.276860 +0.526397 0.297630 +0.526397 0.276860 +0.531214 0.297630 +0.533681 0.276860 +0.487365 0.257408 +0.479330 0.257408 +0.489972 0.257408 +0.497286 0.257408 +0.499639 0.257408 +0.506332 0.257408 +0.508522 0.257408 +0.512860 0.257408 +0.519489 0.257408 +0.521737 0.257408 +0.526397 0.257408 +0.533681 0.257408 +0.487365 0.236545 +0.479330 0.236545 +0.489972 0.236545 +0.497286 0.236545 +0.499639 0.236545 +0.506332 0.236545 +0.508522 0.236545 +0.512860 0.236545 +0.519489 0.236545 +0.521737 0.236545 +0.526397 0.236545 +0.533681 0.236545 +0.487365 0.217895 +0.479330 0.217895 +0.489972 0.217895 +0.497286 0.217895 +0.499639 0.217895 +0.506332 0.217895 +0.508522 0.217895 +0.512860 0.217895 +0.519489 0.217895 +0.521737 0.217895 +0.526397 0.217895 +0.533681 0.217895 +0.487365 0.200766 +0.479330 0.200766 +0.489972 0.200766 +0.497286 0.200766 +0.499639 0.200766 +0.506332 0.200766 +0.508522 0.200766 +0.512860 0.200766 +0.519489 0.200766 +0.521737 0.200766 +0.526397 0.200766 +0.533681 0.200766 +0.487365 0.177595 +0.479330 0.177595 +0.489972 0.177595 +0.497286 0.177595 +0.499639 0.177595 +0.506332 0.177595 +0.508522 0.177595 +0.512860 0.177595 +0.519489 0.177595 +0.521737 0.177595 +0.526397 0.177595 +0.533681 0.177595 +0.487365 0.002954 +0.479330 0.002954 +0.489972 0.002954 +0.497286 0.002954 +0.499639 0.002954 +0.506332 0.002954 +0.508522 0.002954 +0.512860 0.002954 +0.517241 0.002954 +0.521737 0.002954 +0.526397 0.002954 +0.533681 0.002954 +0.487365 0.314183 +0.479330 0.314183 +0.489972 0.314183 +0.497286 0.314183 +0.499639 0.314183 +0.506332 0.314183 +0.508522 0.314183 +0.512860 0.314183 +0.519489 0.314183 +0.521737 0.314183 +0.526397 0.314183 +0.533681 0.314183 +0.533681 0.526656 +0.533681 0.563180 +0.536148 0.609095 +0.533681 0.624630 +0.533681 0.638214 +0.533681 0.651815 +0.533681 0.663209 +0.533681 0.673125 +0.533681 0.685906 +0.533681 0.777451 +0.533681 0.580873 +0.533681 0.595957 +0.536148 0.459887 +0.536148 0.391526 +0.536148 0.352210 +0.536148 0.332180 +0.533681 0.297630 +0.536148 0.276860 +0.536148 0.257408 +0.536148 0.236545 +0.536148 0.217895 +0.536148 0.200766 +0.536148 0.177595 +0.536148 0.002954 +0.536148 0.314183 +0.393687 0.928573 +0.403474 0.868076 +0.451773 0.871232 +0.452003 0.899695 +0.623960 0.995318 +0.641180 0.932563 +0.669164 0.927358 +0.681478 0.974168 +0.356871 0.933417 +0.349475 0.933380 +0.349513 0.925747 +0.356909 0.925784 +0.483277 0.928573 +0.426972 0.958022 +0.315623 0.925583 +0.588701 0.968263 +0.345479 0.938824 +0.284195 0.938798 +0.244574 0.932869 +0.273028 0.933007 +0.345476 0.946455 +0.273065 0.925378 +0.244611 0.925240 +0.284192 0.946429 +0.459274 0.960111 +0.466337 0.957926 +0.581284 0.929603 +0.580487 0.936954 +0.315586 0.933213 +0.389254 0.933579 +0.606866 0.907374 +0.389292 0.925945 +0.189432 0.918567 +0.237834 0.918281 +0.237788 0.910650 +0.189387 0.910936 +0.389921 0.938843 +0.389918 0.946474 +0.759447 0.987106 +0.698950 0.977320 +0.702106 0.929020 +0.730569 0.928790 +0.574012 0.933844 +0.517853 0.900968 +0.520068 0.872591 +0.568470 0.872812 +0.276845 0.912339 +0.284241 0.912366 +0.284214 0.919998 +0.276818 0.919973 +0.360688 0.912630 +0.389143 0.912727 +0.389117 0.920356 +0.360662 0.920259 +0.237491 0.933431 +0.189089 0.933717 +0.189045 0.926086 +0.237446 0.925800 +0.389711 0.958196 +0.328430 0.958707 +0.328366 0.951076 +0.389647 0.950564 +0.759447 0.897516 +0.788896 0.953821 +0.318104 0.920115 +0.318131 0.912484 +0.538754 0.960899 +0.484641 0.927595 +0.283989 0.959077 +0.283925 0.951447 +0.788800 0.914456 +0.790985 0.921520 +0.506386 0.960730 +0.499492 0.958058 +0.244435 0.919857 +0.244462 0.912223 +0.221834 0.895288 +0.035416 0.895288 +0.035416 0.795664 +0.221834 0.795664 +0.250991 0.895288 +0.250991 0.795664 +0.006259 0.795664 +0.006259 0.895288 +0.732613 0.574986 +0.732613 0.674609 +0.546195 0.674609 +0.546195 0.574986 +0.839833 0.809983 +0.839833 0.996401 +0.868990 0.809983 +0.868990 0.996401 +0.834025 0.996565 +0.834371 0.810147 +0.805214 0.810093 +0.804869 0.996511 +0.455998 0.857901 +0.409645 0.857901 +0.409645 0.773332 +0.455998 0.773332 +0.188349 0.950881 +0.272920 0.950881 +0.272920 0.997235 +0.188349 0.997235 +0.466610 0.857901 +0.466610 0.773332 +0.399033 0.773332 +0.399033 0.857901 +0.089025 0.940408 +0.089025 0.986762 +0.004263 0.986762 +0.004263 0.940408 +0.095861 0.951079 +0.180624 0.951079 +0.180624 0.997434 +0.095861 0.997434 +0.089025 0.929797 +0.004263 0.929797 +0.004263 0.997374 +0.089025 0.997374 +0.956615 0.997472 +0.943366 0.997431 +0.943615 0.801455 +0.956864 0.801496 +0.930116 0.997390 +0.930366 0.801413 +0.916868 0.997349 +0.917117 0.801372 +0.903619 0.997308 +0.903868 0.801331 +0.890370 0.997267 +0.890620 0.801290 +0.877121 0.997225 +0.877371 0.801248 +0.983112 0.997554 +0.983361 0.801578 +0.969863 0.997513 +0.970113 0.801537 +0.996361 0.997595 +0.996610 0.801619 +0.266964 0.775665 +0.280970 0.775665 +0.280970 0.904458 +0.266964 0.904458 +0.294975 0.775665 +0.294975 0.904458 +0.308980 0.775665 +0.308980 0.904458 +0.322985 0.775665 +0.322985 0.904458 +0.336990 0.775665 +0.336990 0.904458 +0.350994 0.775665 +0.350995 0.904458 +0.364999 0.775665 +0.365000 0.904458 +0.379004 0.775665 +0.379005 0.904458 +0.393009 0.775665 +0.393010 0.904458 +0.540293 0.782491 +0.540293 0.791412 +0.474616 0.791412 +0.474616 0.782491 +0.540293 0.800334 +0.474616 0.800334 +0.540293 0.809255 +0.474616 0.809255 +0.540293 0.818176 +0.474616 0.818176 +0.540293 0.827097 +0.474616 0.827097 +0.540293 0.836019 +0.474616 0.836019 +0.540293 0.844940 +0.474616 0.844940 +0.540293 0.853861 +0.474616 0.853861 +0.540293 0.862782 +0.474616 0.862782 +0.485622 0.976081 +0.506037 0.975331 +0.506027 0.980190 +0.485624 0.979393 +0.571276 0.973603 +0.571224 0.982616 +0.526249 0.980989 +0.526254 0.974755 +0.182082 0.911611 +0.161747 0.909280 +0.161898 0.908326 +0.182192 0.910924 +0.182594 0.927989 +0.182747 0.928670 +0.162604 0.932512 +0.162395 0.931568 +0.096910 0.945353 +0.096470 0.943464 +0.142672 0.934920 +0.142954 0.936166 +0.142071 0.905899 +0.141867 0.907161 +0.095169 0.901475 +0.095493 0.899560 +0.181947 0.917439 +0.162043 0.916969 +0.141811 0.916600 +0.096404 0.916062 +0.349862 0.986644 +0.142029 0.925506 +0.162210 0.923862 +0.182103 0.922166 +0.459255 0.974729 +0.455958 0.973619 +0.348308 0.975545 +0.348177 0.984724 +0.505883 0.969246 +0.485593 0.971211 +0.485583 0.984255 +0.505831 0.986273 +0.571999 0.995289 +0.525779 0.988612 +0.525866 0.967123 +0.572187 0.960930 +0.458296 0.979831 +0.457614 0.979601 +0.453635 0.978261 +0.454317 0.978491 +0.335408 0.984689 +0.335402 0.986601 +0.335675 0.973487 +0.335650 0.975382 +0.460242 0.974055 +0.350024 0.973670 +0.096807 0.928846 +0.455581 0.972485 +0.755363 0.803185 +0.954156 0.803839 +0.755281 0.862001 +0.956577 0.862001 +0.934066 0.872909 +0.933842 0.814680 +0.954115 0.814748 +0.046860 0.892527 +0.055147 0.892527 +0.038404 0.892527 +0.046860 0.892527 +0.029907 0.892527 +0.038404 0.892527 +0.279028 0.892673 +0.287406 0.892673 +0.270608 0.892673 +0.279028 0.892673 +0.262215 0.892673 +0.270608 0.892673 +0.253835 0.892673 +0.262216 0.892673 +0.245559 0.892673 +0.253834 0.892673 +0.055147 0.892527 +0.063399 0.892527 + + + + + + + + + + +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +0.000000 0.000000 0.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.000000 +1.000000 1.000000 1.000000 1.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.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.000000 0.000000 +0.000000 0.000000 0.000000 0.000000 + + + + + + + + + + + + + +

4 0 12 12 0 1 0 0 1 2 3 3 0 3 0 0 4 4 12 12 5 5 13 15 1 6 4 4 0 7 7 7 3 8 6 6 1 9 4 4 3 10 6 6 2 11 5 5 5 12 23 27 6 13 22 26 0 14 8 8 0 15 8 8 6 16 22 26 3 17 9 9 7 18 27 33 4 19 26 32 1 20 17 19 1 21 17 19 2 22 16 18 7 23 27 33 4 24 12 31 8 25 34 50 5 26 13 28 8 27 34 50 4 28 12 31 9 29 35 51 7 30 28 36 3 31 20 22 6 32 29 37 3 33 20 22 7 34 28 36 2 35 21 23 8 36 39 59 10 37 38 58 5 38 23 40 5 39 23 40 10 40 38 58 6 41 22 41 11 42 41 61 9 43 40 60 4 44 26 47 4 45 26 47 7 46 27 46 11 47 41 61 10 48 45 70 7 49 28 53 6 50 29 52 7 51 28 53 10 52 45 70 11 53 44 69 12 54 42 64 8 55 34 66 9 56 35 65 8 57 34 66 12 58 42 64 13 59 43 67 8 60 39 72 13 61 47 75 14 62 46 74 8 63 39 72 14 64 46 74 10 65 38 73 12 66 48 76 9 67 40 79 11 68 41 78 12 69 48 76 11 70 41 78 15 71 49 77 13 72 43 82 51 73 112 165 17 74 51 83 14 75 53 85 15 76 52 84 10 77 45 86 10 78 45 86 15 79 52 84 11 80 44 87 17 81 54 88 14 82 46 90 13 83 47 89 14 84 46 90 17 85 54 88 18 86 55 91 16 87 56 92 12 88 48 95 15 89 49 94 16 90 56 92 15 91 49 94 19 92 57 93 17 93 51 97 21 94 59 98 41 95 111 164 17 96 51 97 20 97 58 96 21 98 59 98 18 99 61 100 50 100 137 143 14 101 53 101 23 102 63 106 18 103 55 104 17 104 54 103 18 105 55 104 23 106 63 106 22 107 62 105 27 108 67 110 25 109 65 108 24 110 64 107 25 111 65 108 27 112 67 110 26 113 66 109 28 114 68 111 24 115 71 114 25 116 70 113 28 117 68 111 25 118 70 113 29 119 69 112 31 120 73 116 30 121 72 115 32 122 74 117 32 123 74 117 30 124 72 115 33 125 75 118 32 126 77 120 33 127 76 119 34 128 78 121 34 129 78 121 33 130 76 119 35 131 79 122 37 132 81 126 36 133 80 125 31 134 73 123 31 135 73 123 36 136 80 125 30 137 72 124 34 138 78 128 35 139 79 127 38 140 82 129 38 141 82 129 35 142 79 127 39 143 83 130 40 144 84 131 42 145 86 133 41 146 85 132 42 147 86 133 40 148 84 131 43 149 87 134 20 150 91 138 45 151 90 137 21 152 88 135 21 153 88 135 45 154 90 137 44 155 89 136 47 156 93 140 46 157 92 139 48 158 94 141 48 159 94 141 46 160 92 139 49 161 95 142 51 162 97 144 50 163 96 143 20 164 91 145 20 165 91 145 50 166 96 143 45 167 90 146 48 168 94 148 49 169 95 147 51 170 98 149 51 171 98 149 49 172 95 147 50 173 99 150 27 174 103 154 24 175 102 153 28 176 101 152 27 177 103 154 28 178 101 152 23 179 100 151 23 180 63 106 28 181 105 156 29 182 104 155 23 183 63 106 29 184 104 155 22 185 62 105 19 186 57 157 27 187 67 110 16 188 56 158 27 189 67 110 19 190 57 157 26 191 66 109 25 192 107 160 26 193 106 159 29 194 108 161 22 195 109 162 29 196 108 161 26 197 106 159 17 198 51 97 42 199 110 163 23 200 100 151 42 201 110 163 17 202 51 97 41 203 111 164 17 204 51 97 51 205 112 165 20 206 58 96 48 207 113 169 16 208 50 167 47 209 114 170 51 210 112 168 16 211 50 167 48 212 113 169 32 213 115 171 23 214 100 151 31 215 116 172 34 216 121 177 27 217 103 154 32 218 115 171 27 219 103 154 23 220 100 151 32 221 115 171 16 222 50 167 27 223 103 154 53 224 119 175 16 225 50 167 53 226 119 175 52 227 118 174 27 228 103 154 38 229 120 176 53 230 119 175 53 231 125 32 54 232 123 178 52 233 122 35 54 234 123 178 53 235 125 32 55 236 124 48 22 237 109 180 30 238 126 115 36 239 129 125 22 240 109 180 26 241 106 179 33 242 127 118 33 243 127 118 26 244 106 179 35 245 128 122 35 246 128 127 26 247 106 183 39 248 130 130 18 249 61 184 22 250 109 185 43 251 132 134 18 252 61 184 43 253 132 134 40 254 131 131 45 255 133 137 18 256 61 186 44 257 134 136 19 258 60 187 46 259 135 139 54 260 139 195 49 261 136 147 19 262 60 190 50 263 137 150 19 264 60 49 55 265 138 48 26 266 106 191 55 267 138 48 19 268 60 49 54 269 139 178 16 270 50 167 52 271 118 174 47 272 114 170 37 273 117 173 23 274 100 151 42 275 110 163 40 276 131 131 44 277 134 192 18 278 61 184 36 279 129 125 43 280 132 193 22 281 109 182 36 282 80 196 37 283 81 197 42 284 86 133 42 285 86 133 43 286 87 134 36 287 80 196 38 288 82 198 55 289 124 48 53 290 125 32 55 291 124 48 38 292 82 198 39 293 83 199 40 294 84 200 41 295 85 201 21 296 88 135 21 297 88 135 44 298 89 136 40 299 84 200 46 300 92 202 47 301 93 203 52 302 122 35 52 303 122 35 54 304 123 178 46 305 92 202 135 306 319 304 202 307 318 303 60 308 148 208 202 309 318 303 56 310 147 204 60 311 148 208 60 312 142 208 57 313 140 205 61 314 143 209 57 315 140 205 60 316 142 208 56 317 141 204 137 318 321 306 135 319 319 304 58 320 150 206 135 321 319 304 60 322 148 208 58 323 150 206 59 324 145 207 58 325 144 206 61 326 143 209 58 327 144 206 60 328 142 208 61 329 143 209 209 330 502 311 139 331 501 310 208 332 500 542 140 333 328 312 72 334 157 225 209 335 327 311 72 336 157 225 140 337 328 312 70 338 158 221 140 339 328 312 223 340 342 323 70 341 158 221 75 342 169 229 69 343 167 219 73 344 168 226 66 345 174 216 73 346 168 226 69 347 167 219 67 348 182 217 64 349 172 214 68 350 194 218 68 351 194 218 64 352 172 214 65 353 195 215 63 354 181 213 62 355 170 210 67 356 182 217 67 357 182 217 62 358 170 210 64 359 172 214 66 360 174 216 69 361 167 219 63 362 181 213 63 363 181 213 69 364 167 219 62 365 170 210 71 366 184 223 75 367 169 229 73 368 168 226 75 369 169 229 71 370 184 223 70 371 178 221 71 372 164 223 220 373 341 322 142 374 337 318 220 375 341 322 71 376 164 223 73 377 188 226 74 378 163 228 70 379 178 221 71 380 184 223 70 381 178 221 74 382 163 228 72 383 177 225 223 384 342 323 224 385 343 324 69 386 187 219 223 387 342 323 69 388 187 219 75 389 189 229 143 390 345 326 64 391 192 214 224 392 343 324 76 393 205 235 79 394 206 238 77 395 208 236 77 396 208 236 79 397 206 238 78 398 207 237 80 399 209 239 76 400 205 235 77 401 208 236 80 402 209 239 77 403 208 236 81 404 210 240 82 405 211 241 80 406 209 239 81 407 210 240 82 408 211 241 81 409 210 240 83 410 212 242 83 411 266 242 85 412 214 244 84 413 213 243 84 414 213 243 82 415 265 241 83 416 266 242 87 417 216 246 84 418 213 243 85 419 214 244 84 420 213 243 87 421 216 246 86 422 215 245 86 423 215 245 89 424 218 248 88 425 217 247 89 426 218 248 86 427 215 245 87 428 216 246 90 429 219 249 88 430 217 247 91 431 220 250 91 432 220 250 88 433 217 247 89 434 218 248 91 435 220 250 92 436 221 251 90 437 219 249 92 438 221 251 91 439 220 250 93 440 222 252 92 441 251 251 78 442 207 237 79 443 206 238 78 444 207 237 92 445 251 251 93 446 252 252 97 447 224 256 95 448 226 254 94 449 223 253 95 450 226 254 97 451 224 256 96 452 225 255 99 453 228 258 94 454 223 253 98 455 227 257 94 456 223 253 99 457 228 258 97 458 224 256 98 459 227 257 101 460 230 260 99 461 228 258 101 462 230 260 98 463 227 257 100 464 229 259 102 465 231 261 101 466 268 260 100 467 267 259 101 468 268 260 102 469 231 261 103 470 232 262 104 471 233 263 103 472 232 262 102 473 231 261 103 474 232 262 104 475 233 263 105 476 234 264 104 477 233 263 107 478 236 266 105 479 234 264 107 480 236 266 104 481 233 263 106 482 235 265 108 483 237 267 109 484 238 268 106 485 235 265 109 486 238 268 107 487 236 266 106 488 235 265 111 489 240 270 108 490 237 267 110 491 239 269 108 492 237 267 111 493 240 270 109 494 238 268 110 495 253 269 96 496 225 255 111 497 254 270 96 498 225 255 110 499 253 269 95 500 226 254 113 501 258 272 115 502 256 274 114 503 257 273 115 504 256 274 113 505 258 272 112 506 255 271 112 507 241 271 113 508 244 272 95 509 226 254 113 510 244 272 94 511 223 253 95 512 226 254 94 513 223 253 113 514 244 272 116 515 245 275 94 516 223 253 116 517 245 275 98 518 227 257 98 519 227 257 116 520 245 275 117 521 246 276 98 522 227 257 117 523 246 276 100 524 229 259 102 525 231 261 100 526 267 259 118 527 247 277 100 528 267 259 117 529 269 276 118 530 247 277 104 531 233 263 102 532 231 261 119 533 248 278 102 534 231 261 118 535 247 277 119 536 248 278 106 537 235 265 104 538 233 263 120 539 249 279 120 540 249 279 104 541 233 263 119 542 248 278 108 543 237 267 106 544 235 265 114 545 243 273 114 546 243 273 106 547 235 265 120 548 249 279 110 549 239 269 108 550 237 267 115 551 242 274 115 552 242 274 108 553 237 267 114 554 243 273 115 555 270 274 112 556 241 271 110 557 253 269 112 558 241 271 95 559 226 254 110 560 253 269 76 561 205 235 229 562 1875 576 79 563 206 238 79 564 206 238 229 565 1875 576 226 566 1876 573 80 567 209 239 231 568 1877 578 76 569 205 235 229 570 1878 576 76 571 205 235 231 572 1877 578 82 573 211 241 233 574 1879 580 80 575 209 239 231 576 1880 578 80 577 209 239 233 578 1879 580 233 579 1882 580 82 580 265 241 235 581 1881 582 235 582 1881 582 82 583 265 241 84 584 213 243 235 585 1884 582 84 586 213 243 237 587 1883 584 237 588 1883 584 84 589 213 243 86 590 215 245 239 591 1885 586 86 592 215 245 88 593 217 247 86 594 215 245 239 595 1885 586 237 596 1886 584 241 597 1887 588 88 598 217 247 90 599 219 249 88 600 217 247 241 601 1887 588 239 602 1888 586 243 603 1889 590 90 604 219 249 92 605 221 251 90 606 219 249 243 607 1889 590 241 608 1890 588 79 609 206 238 226 610 1891 573 92 611 251 251 92 612 251 251 226 613 1891 573 243 614 1892 590 120 615 263 279 113 616 258 272 114 617 257 273 119 618 262 278 113 619 258 272 120 620 263 279 113 621 258 272 119 622 262 278 116 623 259 275 118 624 261 277 116 625 259 275 119 626 262 278 116 627 259 275 118 628 261 277 117 629 260 276 78 630 207 237 96 631 225 255 97 632 224 256 97 633 224 256 77 634 208 236 78 635 207 237 99 636 228 258 81 637 210 240 97 638 224 256 77 639 208 236 97 640 224 256 81 641 210 240 81 642 210 240 99 643 228 258 101 644 230 260 81 645 210 240 101 646 230 260 83 647 212 242 83 648 266 242 101 649 268 260 85 650 214 244 85 651 214 244 101 652 268 260 103 653 232 262 85 654 214 244 105 655 234 264 87 656 216 246 105 657 234 264 85 658 214 244 103 659 232 262 87 660 216 246 105 661 234 264 89 662 218 248 107 663 236 266 89 664 218 248 105 665 234 264 91 666 220 250 107 667 236 266 109 668 238 268 107 669 236 266 91 670 220 250 89 671 218 248 111 672 240 270 93 673 222 252 91 674 220 250 111 675 240 270 91 676 220 250 109 677 238 268 96 678 225 255 78 679 207 237 111 680 254 270 111 681 254 270 78 682 207 237 93 683 252 252 121 684 271 284 123 685 273 286 122 686 272 285 121 687 271 284 122 688 272 285 134 689 305 298 123 690 273 286 121 691 271 284 124 692 274 287 126 693 276 289 129 694 308 293 125 695 275 288 126 696 276 289 125 697 275 288 127 698 278 291 133 699 309 297 127 700 278 291 132 701 313 296 126 702 276 289 127 703 278 291 133 704 309 297 121 705 279 284 128 706 281 292 124 707 280 287 128 708 281 292 121 709 279 284 125 710 282 288 128 711 286 292 129 712 285 293 123 713 284 286 123 714 284 286 124 715 283 287 128 716 286 292 129 717 290 293 126 718 289 289 122 719 288 285 129 720 290 293 122 721 288 285 123 722 287 286 133 723 294 297 131 724 292 295 130 725 291 294 131 726 292 295 133 727 294 297 132 728 293 296 134 729 295 298 127 730 298 291 121 731 296 284 127 732 298 291 125 733 297 288 121 734 296 284 131 735 292 295 132 736 293 296 134 737 295 298 132 738 293 296 127 739 298 291 134 740 295 298 126 741 302 289 130 742 291 294 122 743 303 285 130 744 291 294 126 745 302 289 133 746 294 297 134 747 305 298 122 748 272 285 130 749 312 294 134 750 305 298 130 751 312 294 131 752 314 295 128 753 307 292 125 754 275 288 129 755 308 293 285 756 315 302 57 757 152 205 202 758 317 303 202 759 317 303 57 760 152 205 56 761 153 204 61 762 149 209 285 763 316 302 136 764 320 305 285 765 316 302 61 766 149 209 57 767 146 205 59 768 151 207 136 769 320 305 138 770 322 307 136 771 320 305 59 772 151 207 61 773 149 209 63 774 161 213 286 775 323 308 66 776 154 216 67 777 162 217 287 778 334 316 286 779 323 308 287 780 334 316 67 781 162 217 68 782 179 218 68 783 159 218 225 784 331 314 141 785 329 313 225 786 331 314 68 787 159 218 65 788 160 215 287 789 682 316 141 790 685 313 218 791 684 557 72 792 177 225 74 793 163 228 288 794 335 317 288 795 335 317 139 796 326 310 72 797 177 225 71 798 164 223 142 799 337 318 74 800 183 228 73 801 188 226 66 802 154 216 286 803 323 308 73 804 188 226 286 805 323 308 220 806 341 322 144 807 352 333 145 808 351 332 146 809 353 334 145 810 351 332 147 811 354 335 146 812 353 334 144 813 355 336 150 814 370 354 149 815 369 353 150 816 370 354 144 817 355 336 146 818 358 339 148 819 359 340 144 820 347 328 149 821 360 341 144 822 347 328 148 823 359 340 145 824 348 329 151 825 374 363 145 826 362 345 148 827 373 360 145 828 362 345 151 829 374 363 147 830 363 346 151 831 375 364 146 832 367 350 147 833 366 349 146 834 367 350 151 835 375 364 150 836 376 367 153 837 382 378 148 838 359 357 149 839 360 356 148 840 359 357 153 841 382 378 152 842 381 377 149 843 369 368 154 844 386 386 153 845 385 385 154 846 386 386 149 847 369 368 150 848 370 371 152 849 387 388 155 850 388 391 148 851 373 373 148 852 373 373 155 853 388 391 151 854 374 374 151 855 375 383 154 856 391 398 150 857 376 380 154 858 391 398 151 859 375 383 155 860 392 399 157 861 390 393 156 862 389 392 153 863 382 394 153 864 382 394 156 865 389 392 152 866 381 395 157 867 393 401 153 868 385 400 158 869 394 402 153 870 385 400 154 871 386 403 158 872 394 402 152 873 387 405 156 874 395 404 155 875 388 406 156 876 395 404 159 877 396 407 155 878 388 406 161 879 398 409 195 880 459 494 157 881 390 410 159 882 399 412 154 883 391 414 155 884 392 413 154 885 391 414 159 886 399 412 158 887 400 415 158 888 394 418 161 889 401 416 157 890 393 419 161 891 401 416 158 892 394 418 162 893 402 417 160 894 403 420 159 895 396 422 156 896 395 421 159 897 396 422 160 898 403 420 163 899 404 423 195 900 459 494 161 901 398 426 164 902 405 424 164 903 405 424 161 904 398 426 165 905 406 425 158 906 400 429 194 907 484 471 162 908 408 430 166 909 409 431 161 910 401 434 162 911 402 433 166 912 409 431 162 913 402 433 167 914 410 432 168 915 411 435 171 916 414 438 170 917 413 437 168 918 411 435 170 919 413 437 169 920 412 436 172 921 415 439 170 922 417 441 171 923 416 440 170 924 417 441 172 925 415 439 173 926 418 442 174 927 419 443 177 928 422 446 176 929 421 445 176 930 421 445 175 931 420 444 174 932 419 443 175 933 423 447 176 934 426 450 179 935 425 449 179 936 425 449 178 937 424 448 175 938 423 447 177 939 422 451 181 940 428 453 180 941 427 452 181 942 428 453 177 943 422 451 174 944 419 454 178 945 424 455 179 946 425 458 183 947 430 457 183 948 430 457 182 949 429 456 178 950 424 455 185 951 432 460 184 952 431 459 186 953 433 461 187 954 434 462 186 955 433 461 184 956 431 459 165 957 435 463 188 958 437 465 164 959 436 464 188 960 437 465 165 961 435 463 189 962 438 466 190 963 439 467 193 964 442 470 192 965 441 469 192 966 441 469 191 967 440 468 190 968 439 467 194 969 443 471 195 970 444 474 164 971 436 473 164 972 436 473 188 973 437 472 194 974 443 471 191 975 440 475 192 976 441 478 195 977 446 477 195 978 446 477 194 979 445 476 191 980 440 475 171 981 448 480 168 982 447 479 172 983 449 481 166 984 450 482 172 985 449 481 168 986 447 479 166 987 409 431 173 988 452 484 172 989 451 483 173 990 452 484 166 991 409 431 167 992 410 432 168 993 411 435 163 994 404 486 160 995 403 485 163 996 404 486 168 997 411 435 169 998 412 436 173 999 454 488 169 1000 456 490 170 1001 455 489 169 1002 456 490 173 1003 454 488 167 1004 453 487 161 1005 398 426 166 1006 450 482 186 1007 458 492 161 1008 398 426 186 1009 458 492 187 1010 457 491 160 1011 397 495 195 1012 459 497 192 1013 460 496 160 1014 397 495 192 1015 460 496 193 1016 461 498 177 1017 462 499 166 1018 450 482 176 1019 463 500 176 1020 463 500 168 1021 447 479 179 1022 467 504 166 1023 450 482 168 1024 447 479 176 1025 463 500 160 1026 397 495 196 1027 465 502 168 1028 447 479 196 1029 465 502 160 1030 397 495 197 1031 466 503 168 1032 447 479 183 1033 468 505 179 1034 467 504 196 1035 469 360 197 1036 472 361 199 1037 471 506 196 1038 469 360 199 1039 471 506 198 1040 470 376 175 1041 474 444 167 1042 453 507 174 1043 473 443 178 1044 475 448 169 1045 456 508 175 1046 474 444 169 1047 456 508 167 1048 453 507 175 1049 474 444 178 1050 475 455 182 1051 477 456 169 1052 456 511 162 1053 408 513 185 1054 478 460 167 1055 453 512 185 1056 478 460 162 1057 408 513 184 1058 479 459 188 1059 480 465 189 1060 481 466 162 1061 408 514 163 1062 407 515 191 1063 482 468 194 1064 484 476 162 1065 408 517 194 1066 484 471 188 1067 480 472 163 1068 407 379 169 1069 456 519 198 1070 486 376 163 1071 407 379 198 1072 486 376 199 1073 485 506 160 1074 397 495 193 1075 461 498 197 1076 466 503 180 1077 464 501 186 1078 458 492 166 1079 450 482 161 1080 398 426 187 1081 457 491 165 1082 406 425 181 1083 476 453 167 1084 453 510 185 1085 478 521 190 1086 483 467 163 1087 407 515 199 1088 485 523 180 1089 427 525 181 1090 428 524 186 1091 433 461 186 1092 433 461 181 1093 428 524 185 1094 432 460 196 1095 469 360 198 1096 470 376 183 1097 430 526 183 1098 430 526 198 1099 470 376 182 1100 429 527 187 1101 434 529 184 1102 431 528 165 1103 435 463 165 1104 435 463 184 1105 431 528 189 1106 438 466 193 1107 442 531 190 1108 439 530 197 1109 472 361 197 1110 472 361 190 1111 439 530 199 1112 471 506 202 1113 490 535 135 1114 489 534 201 1115 488 533 201 1116 488 533 200 1117 487 532 202 1118 490 535 201 1119 494 533 203 1120 492 536 200 1121 491 532 203 1122 492 536 201 1123 494 533 204 1124 493 537 205 1125 495 538 135 1126 489 534 137 1127 496 539 135 1128 489 534 205 1129 495 538 201 1130 488 533 204 1131 493 537 205 1132 498 538 206 1133 497 540 205 1134 498 538 204 1135 493 537 201 1136 494 533 140 1137 504 546 208 1138 500 542 207 1139 499 541 208 1140 500 542 140 1141 504 546 209 1142 502 544 211 1143 506 548 210 1144 505 547 213 1145 508 550 211 1146 506 548 213 1147 508 550 212 1148 507 549 216 1149 513 555 219 1150 516 558 218 1151 515 557 218 1152 515 557 217 1153 514 556 216 1154 513 555 214 1155 510 552 215 1156 512 554 219 1157 516 558 219 1158 516 558 216 1159 513 555 214 1160 510 552 215 1161 512 554 213 1162 508 550 210 1163 505 547 213 1164 508 550 215 1165 512 554 214 1166 510 552 211 1167 506 548 212 1168 507 549 222 1169 530 566 222 1170 530 566 212 1171 507 549 207 1172 529 541 222 1173 530 566 207 1174 529 541 221 1175 527 565 221 1176 527 565 207 1177 529 541 208 1178 528 542 213 1179 534 550 223 1180 532 567 212 1181 531 549 223 1182 532 567 213 1183 534 550 224 1184 533 568 224 1185 533 568 213 1186 534 550 214 1187 538 552 214 1188 538 552 216 1189 540 555 224 1190 533 568 216 1191 540 555 217 1192 542 556 143 1193 537 570 226 1194 543 573 229 1195 546 576 228 1196 545 575 226 1197 543 573 228 1198 545 575 227 1199 544 574 231 1200 548 578 228 1201 545 575 229 1202 546 576 228 1203 545 575 231 1204 548 578 230 1205 547 577 231 1206 548 578 233 1207 550 580 230 1208 547 577 233 1209 550 580 232 1210 549 579 230 1211 547 577 232 1212 552 579 235 1213 554 582 234 1214 553 581 235 1215 554 582 232 1216 552 579 233 1217 551 580 235 1218 554 582 236 1219 555 583 234 1220 553 581 236 1221 555 583 235 1222 554 582 237 1223 556 584 237 1224 556 584 239 1225 558 586 238 1226 557 585 237 1227 556 584 238 1228 557 585 236 1229 555 583 239 1230 558 586 241 1231 560 588 240 1232 559 587 239 1233 558 586 240 1234 559 587 238 1235 557 585 240 1236 559 587 243 1237 562 590 242 1238 561 589 243 1239 562 590 240 1240 559 587 241 1241 560 588 243 1242 563 590 226 1243 543 573 227 1244 544 574 243 1245 563 590 227 1246 544 574 242 1247 564 589 245 1248 566 592 247 1249 568 594 246 1250 567 593 247 1251 568 594 245 1252 566 592 244 1253 565 591 249 1254 570 596 244 1255 565 591 245 1256 566 592 244 1257 565 591 249 1258 570 596 248 1259 569 595 249 1260 570 596 251 1261 572 598 248 1262 569 595 251 1263 572 598 250 1264 571 597 248 1265 569 595 252 1266 573 599 251 1267 575 598 253 1268 574 600 251 1269 575 598 252 1270 573 599 250 1271 576 597 253 1272 574 600 254 1273 577 601 252 1274 573 599 254 1275 577 601 253 1276 574 600 255 1277 578 602 255 1278 578 602 257 1279 580 604 254 1280 577 601 257 1281 580 604 256 1282 579 603 254 1283 577 601 256 1284 579 603 259 1285 582 606 258 1286 581 605 257 1287 580 604 259 1288 582 606 256 1289 579 603 261 1290 584 608 258 1291 581 605 259 1292 582 606 258 1293 581 605 261 1294 584 608 260 1295 583 607 246 1296 567 593 260 1297 586 607 261 1298 585 608 260 1299 586 607 246 1300 567 593 247 1301 568 594 264 1302 589 611 263 1303 588 610 262 1304 587 609 264 1305 589 611 262 1306 587 609 265 1307 590 612 247 1308 568 594 244 1309 565 591 264 1310 592 611 247 1311 568 594 264 1312 592 611 265 1313 591 612 264 1314 592 611 244 1315 565 591 266 1316 593 613 244 1317 565 591 248 1318 569 595 266 1319 593 613 266 1320 593 613 248 1321 569 595 267 1322 594 614 248 1323 569 595 250 1324 571 597 267 1325 594 614 267 1326 595 614 250 1327 576 597 268 1328 596 615 268 1329 596 615 250 1330 576 597 252 1331 573 599 268 1332 596 615 252 1333 573 599 269 1334 597 616 269 1335 597 616 252 1336 573 599 254 1337 577 601 256 1338 579 603 270 1339 598 617 254 1340 577 601 270 1341 598 617 269 1342 597 616 254 1343 577 601 258 1344 581 605 263 1345 599 610 256 1346 579 603 263 1347 599 610 270 1348 598 617 256 1349 579 603 260 1350 583 607 262 1351 600 609 258 1352 581 605 262 1353 600 609 263 1354 599 610 258 1355 581 605 260 1356 586 607 247 1357 568 594 265 1358 591 612 260 1359 586 607 265 1360 591 612 262 1361 601 609 264 1362 589 611 270 1363 613 617 263 1364 588 610 269 1365 615 616 264 1366 589 611 266 1367 614 613 264 1368 589 611 269 1369 615 616 270 1370 613 617 266 1371 614 613 268 1372 617 615 269 1373 615 616 268 1374 617 615 266 1375 614 613 267 1376 616 614 228 1377 545 575 245 1378 566 592 227 1379 544 574 227 1380 544 574 245 1381 566 592 246 1382 567 593 245 1383 566 592 228 1384 545 575 230 1385 547 577 245 1386 566 592 230 1387 547 577 249 1388 570 596 230 1389 547 577 251 1390 572 598 249 1391 570 596 251 1392 572 598 230 1393 547 577 232 1394 549 579 234 1395 553 581 253 1396 574 600 251 1397 575 598 251 1398 575 598 232 1399 552 579 234 1400 553 581 253 1401 574 600 234 1402 553 581 255 1403 578 602 255 1404 578 602 234 1405 553 581 236 1406 555 583 238 1407 557 585 257 1408 580 604 255 1409 578 602 238 1410 557 585 255 1411 578 602 236 1412 555 583 257 1413 580 604 240 1414 559 587 259 1415 582 606 240 1416 559 587 257 1417 580 604 238 1418 557 585 259 1419 582 606 240 1420 559 587 261 1421 584 608 242 1422 561 589 261 1423 584 608 240 1424 559 587 261 1425 585 608 242 1426 564 589 227 1427 544 574 227 1428 544 574 246 1429 567 593 261 1430 585 608 272 1431 619 628 271 1432 618 627 273 1433 620 629 274 1434 621 630 271 1435 618 627 284 1436 653 641 273 1437 620 629 271 1438 618 627 274 1439 621 630 277 1440 625 634 279 1441 654 636 276 1442 624 633 277 1443 625 634 276 1444 624 633 275 1445 622 631 275 1446 622 631 276 1447 624 633 280 1448 657 637 275 1449 622 631 280 1450 657 637 281 1451 660 638 278 1452 628 635 277 1453 627 634 271 1454 626 627 278 1455 628 635 271 1456 626 627 272 1457 629 628 278 1458 631 635 273 1459 633 629 279 1460 632 636 273 1461 633 629 278 1462 631 635 272 1463 630 628 276 1464 636 633 279 1465 635 636 274 1466 637 630 273 1467 634 629 274 1468 637 630 279 1469 635 636 280 1470 638 637 283 1471 641 640 282 1472 640 639 280 1473 638 637 282 1474 640 639 281 1475 639 638 275 1476 642 631 284 1477 645 641 271 1478 644 627 275 1479 642 631 271 1480 644 627 277 1481 643 634 281 1482 639 638 282 1483 640 639 284 1484 645 641 281 1485 639 638 284 1486 645 641 275 1487 642 631 283 1488 641 640 276 1489 650 633 274 1490 649 630 276 1491 650 633 283 1492 641 640 280 1493 638 637 283 1494 658 640 284 1495 653 641 282 1496 661 639 274 1497 621 630 284 1498 653 641 283 1499 658 640 279 1500 654 636 277 1501 625 634 278 1502 655 635 202 1503 665 535 200 1504 664 532 203 1505 663 536 203 1506 663 536 285 1507 662 645 202 1508 665 535 136 1509 666 646 285 1510 669 645 204 1511 667 537 285 1512 669 645 203 1513 668 536 204 1514 667 537 138 1515 670 647 136 1516 666 646 206 1517 671 540 136 1518 666 646 204 1519 667 537 206 1520 671 540 141 1521 676 650 217 1522 678 556 218 1523 677 557 217 1524 678 556 141 1525 676 650 225 1526 679 572 286 1527 672 648 287 1528 682 652 219 1529 683 558 219 1530 683 558 287 1531 682 652 218 1532 684 557 221 1533 527 565 208 1534 528 542 288 1535 687 653 288 1536 687 653 208 1537 528 542 139 1538 686 543 220 1539 525 563 211 1540 524 548 222 1541 692 566 220 1542 525 563 222 1543 692 566 142 1544 688 654 212 1545 531 549 223 1546 532 567 207 1547 499 541 286 1548 672 648 211 1549 524 548 220 1550 525 563 211 1551 524 548 286 1552 672 648 210 1553 673 547 435 1554 920 802 434 1555 919 801 436 1556 921 803 434 1557 919 801 433 1558 918 800 436 1559 921 803 434 1560 919 801 438 1561 923 805 433 1562 918 800 438 1563 923 805 437 1564 922 804 433 1565 918 800 437 1566 922 804 438 1567 923 805 439 1568 924 806 438 1569 923 805 440 1570 925 807 439 1571 924 806 439 1572 924 806 440 1573 925 807 441 1574 926 808 440 1575 925 807 442 1576 927 809 441 1577 926 808 441 1578 926 808 442 1579 927 809 443 1580 928 810 442 1581 927 809 444 1582 929 811 443 1583 928 810 443 1584 928 810 444 1585 929 811 445 1586 930 812 444 1587 929 811 446 1588 931 813 445 1589 930 812 445 1590 930 812 446 1591 931 813 447 1592 932 814 446 1593 931 813 448 1594 933 815 447 1595 932 814 448 1596 933 815 449 1597 934 816 447 1598 932 814 449 1599 934 816 448 1600 933 815 450 1601 935 817 449 1602 934 816 450 1603 935 817 451 1604 936 818 451 1605 936 818 450 1606 935 817 452 1607 937 819 451 1608 941 818 452 1609 940 819 453 1610 938 820 453 1611 938 820 452 1612 940 819 454 1613 939 821 453 1614 938 820 454 1615 939 821 455 1616 942 822 455 1617 942 822 454 1618 939 821 456 1619 943 823 458 1620 945 825 457 1621 944 824 456 1622 943 823 457 1623 944 824 455 1624 942 822 456 1625 943 823 460 1626 947 827 459 1627 946 826 458 1628 945 825 459 1629 946 826 457 1630 944 824 458 1631 945 825 462 1632 949 829 461 1633 948 828 460 1634 947 827 461 1635 948 828 459 1636 946 826 460 1637 947 827 463 1638 950 830 461 1639 948 828 464 1640 951 831 464 1641 951 831 461 1642 948 828 462 1643 949 829 465 1644 952 832 463 1645 950 830 466 1646 953 833 466 1647 953 833 463 1648 950 830 464 1649 951 831 466 1650 953 833 468 1651 955 835 465 1652 952 832 468 1653 955 835 467 1654 954 834 465 1655 952 832 468 1656 955 835 435 1657 920 802 467 1658 954 834 435 1659 920 802 436 1660 921 803 467 1661 954 834 469 1662 956 836 472 1663 959 839 470 1664 957 837 471 1665 958 838 470 1666 957 837 472 1667 959 839 476 1668 963 843 474 1669 961 841 473 1670 960 840 474 1671 961 841 476 1672 963 843 475 1673 962 842 477 1674 964 844 469 1675 956 836 478 1676 965 845 470 1677 957 837 478 1678 965 845 469 1679 956 836 480 1680 967 847 475 1681 962 842 476 1682 963 843 475 1683 962 842 480 1684 967 847 479 1685 966 846 478 1686 965 845 482 1687 969 849 477 1688 964 844 477 1689 964 844 482 1690 969 849 481 1691 968 848 480 1692 967 847 484 1693 971 851 479 1694 966 846 479 1695 966 846 484 1696 971 851 483 1697 970 850 482 1698 969 849 486 1699 973 853 481 1700 968 848 481 1701 968 848 486 1702 973 853 485 1703 972 852 484 1704 971 851 488 1705 975 855 483 1706 970 850 483 1707 970 850 488 1708 975 855 487 1709 974 854 486 1710 973 853 490 1711 977 857 485 1712 972 852 485 1713 972 852 490 1714 977 857 489 1715 976 856 488 1716 975 855 492 1717 979 859 487 1718 974 854 487 1719 974 854 492 1720 979 859 491 1721 978 858 490 1722 977 857 494 1723 981 861 489 1724 976 856 489 1725 976 856 494 1726 981 861 493 1727 980 860 492 1728 979 859 496 1729 983 863 491 1730 978 858 491 1731 978 858 496 1732 983 863 495 1733 982 862 494 1734 981 861 498 1735 985 865 493 1736 980 860 493 1737 980 860 498 1738 985 865 497 1739 984 864 496 1740 983 863 500 1741 987 867 495 1742 982 862 495 1743 982 862 500 1744 987 867 499 1745 986 866 497 1746 984 864 502 1747 989 869 501 1748 988 868 502 1749 989 869 497 1750 984 864 498 1751 985 865 500 1752 987 867 504 1753 991 871 499 1754 986 866 503 1755 990 870 499 1756 986 866 504 1757 991 871 501 1758 988 868 506 1759 993 873 505 1760 992 872 506 1761 993 873 501 1762 988 868 502 1763 989 869 504 1764 991 871 508 1765 995 875 503 1766 990 870 507 1767 994 874 503 1768 990 870 508 1769 995 875 505 1770 999 872 510 1771 997 877 509 1772 996 876 510 1773 997 877 505 1774 999 872 506 1775 998 873 508 1776 1000 875 512 1777 1003 879 507 1778 1001 874 511 1779 1002 878 507 1780 1001 874 512 1781 1003 879 509 1782 996 876 514 1783 1005 881 513 1784 1004 880 514 1785 1005 881 509 1786 996 876 510 1787 997 877 512 1788 1003 879 516 1789 1007 883 511 1790 1002 878 515 1791 1006 882 511 1792 1002 878 516 1793 1007 883 517 1794 1008 884 513 1795 1004 880 518 1796 1009 885 518 1797 1009 885 513 1798 1004 880 514 1799 1005 881 516 1800 1007 883 520 1801 1011 887 519 1802 1010 886 519 1803 1010 886 515 1804 1006 882 516 1805 1007 883 521 1806 1012 888 517 1807 1008 884 522 1808 1013 889 522 1809 1013 889 517 1810 1008 884 518 1811 1009 885 523 1812 1014 890 519 1813 1010 886 524 1814 1015 891 524 1815 1015 891 519 1816 1010 886 520 1817 1011 887 525 1818 1016 892 521 1819 1012 888 526 1820 1017 893 526 1821 1017 893 521 1822 1012 888 522 1823 1013 889 527 1824 1018 894 523 1825 1014 890 528 1826 1019 895 528 1827 1019 895 523 1828 1014 890 524 1829 1015 891 529 1830 1020 896 525 1831 1016 892 530 1832 1021 897 530 1833 1021 897 525 1834 1016 892 526 1835 1017 893 531 1836 1022 898 527 1837 1018 894 532 1838 1023 899 532 1839 1023 899 527 1840 1018 894 528 1841 1019 895 533 1842 1024 900 529 1843 1020 896 534 1844 1025 901 534 1845 1025 901 529 1846 1020 896 530 1847 1021 897 535 1848 1026 902 531 1849 1022 898 536 1850 1027 903 536 1851 1027 903 531 1852 1022 898 532 1853 1023 899 537 1854 1028 904 533 1855 1024 900 538 1856 1029 905 534 1857 1025 901 538 1858 1029 905 533 1859 1024 900 536 1860 1027 903 540 1861 1031 907 539 1862 1030 906 536 1863 1027 903 539 1864 1030 906 535 1865 1026 902 472 1866 959 839 537 1867 1028 904 471 1868 958 838 538 1869 1029 905 471 1870 958 838 537 1871 1028 904 540 1872 1031 907 473 1873 960 840 474 1874 961 841 540 1875 1031 907 474 1876 961 841 539 1877 1030 906 469 1878 956 836 435 1879 920 802 472 1880 959 839 435 1881 920 802 469 1882 956 836 434 1883 919 801 537 1884 1028 904 472 1885 959 839 435 1886 920 802 537 1887 1028 904 435 1888 920 802 468 1889 955 835 468 1890 955 835 466 1891 953 833 533 1892 1024 900 533 1893 1024 900 537 1894 1028 904 468 1895 955 835 466 1896 953 833 464 1897 951 831 529 1898 1020 896 529 1899 1020 896 533 1900 1024 900 466 1901 953 833 464 1902 951 831 462 1903 949 829 525 1904 1016 892 464 1905 951 831 525 1906 1016 892 529 1907 1020 896 462 1908 949 829 521 1909 1012 888 525 1910 1016 892 521 1911 1012 888 462 1912 949 829 460 1913 947 827 521 1914 1012 888 458 1915 945 825 517 1916 1008 884 458 1917 945 825 521 1918 1012 888 460 1919 947 827 517 1920 1008 884 456 1921 943 823 513 1922 1004 880 456 1923 943 823 517 1924 1008 884 458 1925 945 825 509 1926 996 876 513 1927 1004 880 454 1928 939 821 454 1929 939 821 513 1930 1004 880 456 1931 943 823 509 1932 996 876 452 1933 940 819 505 1934 999 872 452 1935 940 819 509 1936 996 876 454 1937 939 821 452 1938 937 819 450 1939 935 817 501 1940 988 868 452 1941 937 819 501 1942 988 868 505 1943 992 872 497 1944 984 864 501 1945 988 868 450 1946 935 817 450 1947 935 817 448 1948 933 815 497 1949 984 864 493 1950 980 860 497 1951 984 864 448 1952 933 815 493 1953 980 860 448 1954 933 815 446 1955 931 813 489 1956 976 856 493 1957 980 860 446 1958 931 813 489 1959 976 856 446 1960 931 813 444 1961 929 811 485 1962 972 852 489 1963 976 856 442 1964 927 809 442 1965 927 809 489 1966 976 856 444 1967 929 811 485 1968 972 852 440 1969 925 807 481 1970 968 848 440 1971 925 807 485 1972 972 852 442 1973 927 809 477 1974 964 844 481 1975 968 848 438 1976 923 805 440 1977 925 807 438 1978 923 805 481 1979 968 848 438 1980 923 805 434 1981 919 801 477 1982 964 844 477 1983 964 844 434 1984 919 801 469 1985 956 836 476 1986 963 843 473 1987 960 840 436 1988 921 803 476 1989 963 843 436 1990 921 803 433 1991 918 800 433 1992 918 800 437 1993 922 804 480 1994 967 847 480 1995 967 847 476 1996 963 843 433 1997 918 800 437 1998 922 804 439 1999 924 806 484 2000 971 851 484 2001 971 851 480 2002 967 847 437 2003 922 804 439 2004 924 806 441 2005 926 808 488 2006 975 855 439 2007 924 806 488 2008 975 855 484 2009 971 851 441 2010 926 808 492 2011 979 859 488 2012 975 855 492 2013 979 859 441 2014 926 808 443 2015 928 810 492 2016 979 859 445 2017 930 812 496 2018 983 863 445 2019 930 812 492 2020 979 859 443 2021 928 810 496 2022 983 863 447 2023 932 814 500 2024 987 867 447 2025 932 814 496 2026 983 863 445 2027 930 812 504 2028 991 871 500 2029 987 867 449 2030 934 816 449 2031 934 816 500 2032 987 867 447 2033 932 814 504 2034 991 871 451 2035 936 818 508 2036 995 875 451 2037 936 818 504 2038 991 871 449 2039 934 816 451 2040 941 818 453 2041 938 820 512 2042 1003 879 451 2043 941 818 512 2044 1003 879 508 2045 1000 875 516 2046 1007 883 512 2047 1003 879 453 2048 938 820 453 2049 938 820 455 2050 942 822 516 2051 1007 883 520 2052 1011 887 516 2053 1007 883 455 2054 942 822 520 2055 1011 887 455 2056 942 822 457 2057 944 824 524 2058 1015 891 520 2059 1011 887 457 2060 944 824 524 2061 1015 891 457 2062 944 824 459 2063 946 826 528 2064 1019 895 524 2065 1015 891 461 2066 948 828 461 2067 948 828 524 2068 1015 891 459 2069 946 826 528 2070 1019 895 463 2071 950 830 532 2072 1023 899 463 2073 950 830 528 2074 1019 895 461 2075 948 828 536 2076 1027 903 532 2077 1023 899 465 2078 952 832 463 2079 950 830 465 2080 952 832 532 2081 1023 899 465 2082 952 832 467 2083 954 834 536 2084 1027 903 536 2085 1027 903 467 2086 954 834 540 2087 1031 907 540 2088 1031 907 436 2089 921 803 473 2090 960 840 436 2091 921 803 540 2092 1031 907 467 2093 954 834 534 2094 1032 901 471 2095 1034 838 538 2096 1033 905 471 2097 1034 838 534 2098 1032 901 470 2099 1035 837 530 2100 1036 897 470 2101 1035 837 534 2102 1032 901 470 2103 1035 837 530 2104 1036 897 478 2105 1037 845 482 2106 1039 849 530 2107 1036 897 526 2108 1038 893 530 2109 1036 897 482 2110 1039 849 478 2111 1037 845 522 2112 1040 889 482 2113 1039 849 526 2114 1038 893 482 2115 1039 849 522 2116 1040 889 486 2117 1041 853 518 2118 1042 885 486 2119 1041 853 522 2120 1040 889 486 2121 1041 853 518 2122 1042 885 490 2123 1043 857 514 2124 1044 881 490 2125 1043 857 518 2126 1042 885 490 2127 1043 857 514 2128 1044 881 494 2129 1045 861 498 2130 1047 865 514 2131 1044 881 510 2132 1046 877 494 2133 1045 861 514 2134 1044 881 498 2135 1047 865 510 2136 1046 877 502 2137 1049 869 498 2138 1047 865 502 2139 1049 869 510 2140 1046 877 506 2141 1048 873 511 2142 1050 878 503 2143 1052 870 507 2144 1051 874 503 2145 1052 870 511 2146 1050 878 499 2147 1053 866 495 2148 1055 862 511 2149 1050 878 515 2150 1054 882 511 2151 1050 878 495 2152 1055 862 499 2153 1053 866 495 2154 1055 862 515 2155 1054 882 491 2156 1057 858 491 2157 1057 858 515 2158 1054 882 519 2159 1056 886 519 2160 1056 886 487 2161 1059 854 491 2162 1057 858 519 2163 1056 886 483 2164 1061 850 487 2165 1059 854 483 2166 1061 850 519 2167 1056 886 523 2168 1058 890 483 2169 1061 850 523 2170 1058 890 527 2171 1060 894 527 2172 1060 894 479 2173 1063 846 483 2174 1061 850 479 2175 1063 846 527 2176 1060 894 531 2177 1062 898 531 2178 1062 898 475 2179 1065 842 479 2180 1063 846 475 2181 1065 842 531 2182 1062 898 535 2183 1064 902 539 2184 1066 906 475 2185 1065 842 535 2186 1064 902 475 2187 1065 842 539 2188 1066 906 474 2189 1067 841 541 2190 1068 908 544 2191 1071 911 543 2192 1070 910 541 2193 1068 908 543 2194 1070 910 542 2195 1069 909 544 2196 1071 911 546 2197 1073 913 545 2198 1072 912 544 2199 1071 911 545 2200 1072 912 543 2201 1070 910 548 2202 1075 915 545 2203 1072 912 546 2204 1073 913 545 2205 1072 912 548 2206 1075 915 547 2207 1074 914 550 2208 1077 917 547 2209 1074 914 548 2210 1075 915 547 2211 1074 914 550 2212 1077 917 549 2213 1076 916 552 2214 1079 919 549 2215 1076 916 550 2216 1077 917 549 2217 1076 916 552 2218 1079 919 551 2219 1078 918 552 2220 1079 919 554 2221 1081 921 551 2222 1078 918 551 2223 1078 918 554 2224 1081 921 553 2225 1080 920 556 2226 1083 923 553 2227 1080 920 554 2228 1081 921 553 2229 1080 920 556 2230 1083 923 555 2231 1082 922 557 2232 1084 924 555 2233 1082 922 558 2234 1085 925 555 2235 1082 922 556 2236 1083 923 558 2237 1085 925 559 2238 1086 926 557 2239 1084 924 560 2240 1087 927 557 2241 1084 924 558 2242 1085 925 560 2243 1087 927 561 2244 1090 928 559 2245 1089 926 562 2246 1091 929 559 2247 1089 926 560 2248 1088 927 562 2249 1091 929 563 2250 1092 930 561 2251 1090 928 564 2252 1093 931 561 2253 1090 928 562 2254 1091 929 564 2255 1093 931 565 2256 1094 932 563 2257 1092 930 566 2258 1095 933 566 2259 1095 933 563 2260 1092 930 564 2261 1093 931 567 2262 1096 934 565 2263 1094 932 568 2264 1097 935 568 2265 1097 935 565 2266 1094 932 566 2267 1095 933 567 2268 1096 934 570 2269 1099 937 569 2270 1098 936 570 2271 1099 937 567 2272 1096 934 568 2273 1097 935 572 2274 1101 939 571 2275 1100 938 570 2276 1099 937 571 2277 1100 938 569 2278 1098 936 570 2279 1099 937 574 2280 1103 941 573 2281 1102 940 572 2282 1101 939 573 2283 1102 940 571 2284 1100 938 572 2285 1101 939 574 2286 1103 941 576 2287 1105 943 575 2288 1104 942 574 2289 1103 941 575 2290 1104 942 573 2291 1102 940 576 2292 1105 943 541 2293 1068 908 542 2294 1069 909 576 2295 1105 943 542 2296 1069 909 575 2297 1104 942 577 2298 1106 944 580 2299 1109 947 579 2300 1108 946 577 2301 1106 944 579 2302 1108 946 578 2303 1107 945 581 2304 1110 948 583 2305 1112 950 582 2306 1111 949 583 2307 1112 950 581 2308 1110 948 584 2309 1113 951 580 2310 1109 947 586 2311 1115 953 585 2312 1114 952 580 2313 1109 947 585 2314 1114 952 579 2315 1108 946 582 2316 1111 949 588 2317 1117 955 587 2318 1116 954 582 2319 1111 949 587 2320 1116 954 581 2321 1110 948 586 2322 1115 953 589 2323 1118 956 585 2324 1114 952 589 2325 1118 956 586 2326 1115 953 590 2327 1119 957 591 2328 1120 958 587 2329 1116 954 588 2330 1117 955 588 2331 1117 955 592 2332 1121 959 591 2333 1120 958 590 2334 1119 957 593 2335 1122 960 589 2336 1118 956 593 2337 1122 960 590 2338 1119 957 594 2339 1123 961 595 2340 1124 962 591 2341 1120 958 592 2342 1121 959 592 2343 1121 959 596 2344 1125 963 595 2345 1124 962 594 2346 1123 961 597 2347 1126 964 593 2348 1122 960 597 2349 1126 964 594 2350 1123 961 598 2351 1127 965 599 2352 1128 966 595 2353 1124 962 596 2354 1125 963 596 2355 1125 963 600 2356 1129 967 599 2357 1128 966 598 2358 1127 965 601 2359 1130 968 597 2360 1126 964 601 2361 1130 968 598 2362 1127 965 602 2363 1131 969 603 2364 1132 970 599 2365 1128 966 600 2366 1129 967 600 2367 1129 967 604 2368 1133 971 603 2369 1132 970 602 2370 1131 969 605 2371 1134 972 601 2372 1130 968 605 2373 1134 972 602 2374 1131 969 606 2375 1135 973 607 2376 1136 974 603 2377 1132 970 604 2378 1133 971 604 2379 1133 971 608 2380 1137 975 607 2381 1136 974 609 2382 1138 976 605 2383 1134 972 606 2384 1135 973 609 2385 1138 976 606 2386 1135 973 610 2387 1139 977 611 2388 1140 978 607 2389 1136 974 608 2390 1137 975 611 2391 1140 978 608 2392 1137 975 612 2393 1141 979 613 2394 1142 980 609 2395 1138 976 610 2396 1139 977 613 2397 1142 980 610 2398 1139 977 614 2399 1143 981 612 2400 1141 979 615 2401 1144 982 611 2402 1140 978 615 2403 1144 982 612 2404 1141 979 616 2405 1145 983 614 2406 1146 981 617 2407 1148 984 613 2408 1147 980 617 2409 1148 984 614 2410 1146 981 618 2411 1149 985 619 2412 1150 986 615 2413 1153 982 616 2414 1152 983 619 2415 1150 986 616 2416 1152 983 620 2417 1151 987 621 2418 1154 988 617 2419 1148 984 618 2420 1149 985 621 2421 1154 988 618 2422 1149 985 622 2423 1155 989 623 2424 1156 990 619 2425 1150 986 620 2426 1151 987 623 2427 1156 990 620 2428 1151 987 624 2429 1157 991 622 2430 1155 989 626 2431 1159 993 625 2432 1158 992 625 2433 1158 992 621 2434 1154 988 622 2435 1155 989 627 2436 1160 994 623 2437 1156 990 628 2438 1161 995 628 2439 1161 995 623 2440 1156 990 624 2441 1157 991 626 2442 1159 993 630 2443 1163 997 629 2444 1162 996 629 2445 1162 996 625 2446 1158 992 626 2447 1159 993 631 2448 1164 998 628 2449 1161 995 632 2450 1165 999 628 2451 1161 995 631 2452 1164 998 627 2453 1160 994 630 2454 1163 997 634 2455 1167 1001 633 2456 1166 1000 633 2457 1166 1000 629 2458 1162 996 630 2459 1163 997 635 2460 1168 1002 632 2461 1165 999 636 2462 1169 1003 632 2463 1165 999 635 2464 1168 1002 631 2465 1164 998 634 2466 1167 1001 638 2467 1171 1005 637 2468 1170 1004 637 2469 1170 1004 633 2470 1166 1000 634 2471 1167 1001 639 2472 1172 1006 636 2473 1169 1003 640 2474 1173 1007 636 2475 1169 1003 639 2476 1172 1006 635 2477 1168 1002 638 2478 1171 1005 642 2479 1175 1009 641 2480 1174 1008 641 2481 1174 1008 637 2482 1170 1004 638 2483 1171 1005 643 2484 1176 1010 640 2485 1173 1007 644 2486 1177 1011 640 2487 1173 1007 643 2488 1176 1010 639 2489 1172 1006 642 2490 1175 1009 646 2491 1179 1013 645 2492 1178 1012 642 2493 1175 1009 645 2494 1178 1012 641 2495 1174 1008 647 2496 1180 1014 643 2497 1176 1010 648 2498 1181 1015 644 2499 1177 1011 648 2500 1181 1015 643 2501 1176 1010 578 2502 1107 945 646 2503 1179 1013 577 2504 1106 944 646 2505 1179 1013 578 2506 1107 945 645 2507 1178 1012 584 2508 1113 951 647 2509 1180 1014 583 2510 1112 950 648 2511 1181 1015 583 2512 1112 950 647 2513 1180 1014 580 2514 1109 947 577 2515 1106 944 542 2516 1069 909 580 2517 1109 947 542 2518 1069 909 543 2519 1070 910 575 2520 1104 942 542 2521 1069 909 646 2522 1179 1013 577 2523 1106 944 646 2524 1179 1013 542 2525 1069 909 575 2526 1104 942 642 2527 1175 1009 573 2528 1102 940 642 2529 1175 1009 575 2530 1104 942 646 2531 1179 1013 642 2532 1175 1009 638 2533 1171 1005 573 2534 1102 940 571 2535 1100 938 573 2536 1102 940 638 2537 1171 1005 638 2538 1171 1005 634 2539 1167 1001 571 2540 1100 938 571 2541 1100 938 634 2542 1167 1001 569 2543 1098 936 569 2544 1098 936 630 2545 1163 997 567 2546 1096 934 630 2547 1163 997 569 2548 1098 936 634 2549 1167 1001 630 2550 1163 997 626 2551 1159 993 565 2552 1094 932 630 2553 1163 997 565 2554 1094 932 567 2555 1096 934 626 2556 1159 993 622 2557 1155 989 563 2558 1092 930 626 2559 1159 993 563 2560 1092 930 565 2561 1094 932 622 2562 1155 989 618 2563 1149 985 561 2564 1090 928 561 2565 1090 928 563 2566 1092 930 622 2567 1155 989 618 2568 1149 985 559 2569 1089 926 561 2570 1090 928 559 2571 1089 926 618 2572 1149 985 614 2573 1146 981 614 2574 1143 981 610 2575 1139 977 559 2576 1086 926 559 2577 1086 926 610 2578 1139 977 557 2579 1084 924 610 2580 1139 977 606 2581 1135 973 557 2582 1084 924 557 2583 1084 924 606 2584 1135 973 555 2585 1082 922 553 2586 1080 920 555 2587 1082 922 602 2588 1131 969 606 2589 1135 973 602 2590 1131 969 555 2591 1082 922 551 2592 1078 918 553 2593 1080 920 598 2594 1127 965 602 2595 1131 969 598 2596 1127 965 553 2597 1080 920 598 2598 1127 965 594 2599 1123 961 549 2600 1076 916 549 2601 1076 916 551 2602 1078 918 598 2603 1127 965 594 2604 1123 961 547 2605 1074 914 549 2606 1076 916 547 2607 1074 914 594 2608 1123 961 590 2609 1119 957 590 2610 1119 957 545 2611 1072 912 547 2612 1074 914 545 2613 1072 912 590 2614 1119 957 586 2615 1115 953 586 2616 1115 953 543 2617 1070 910 545 2618 1072 912 543 2619 1070 910 586 2620 1115 953 580 2621 1109 947 544 2622 1071 911 541 2623 1068 908 581 2624 1110 948 584 2625 1113 951 581 2626 1110 948 541 2627 1068 908 544 2628 1071 911 587 2629 1116 954 546 2630 1073 913 587 2631 1116 954 544 2632 1071 911 581 2633 1110 948 587 2634 1116 954 591 2635 1120 958 546 2636 1073 913 548 2637 1075 915 546 2638 1073 913 591 2639 1120 958 591 2640 1120 958 595 2641 1124 962 548 2642 1075 915 548 2643 1075 915 595 2644 1124 962 550 2645 1077 917 550 2646 1077 917 599 2647 1128 966 552 2648 1079 919 599 2649 1128 966 550 2650 1077 917 595 2651 1124 962 599 2652 1128 966 603 2653 1132 970 554 2654 1081 921 599 2655 1128 966 554 2656 1081 921 552 2657 1079 919 603 2658 1132 970 607 2659 1136 974 556 2660 1083 923 603 2661 1132 970 556 2662 1083 923 554 2663 1081 921 607 2664 1136 974 611 2665 1140 978 558 2666 1085 925 558 2667 1085 925 556 2668 1083 923 607 2669 1136 974 611 2670 1140 978 560 2671 1087 927 558 2672 1085 925 560 2673 1087 927 611 2674 1140 978 615 2675 1144 982 615 2676 1153 982 619 2677 1150 986 560 2678 1088 927 560 2679 1088 927 619 2680 1150 986 562 2681 1091 929 619 2682 1150 986 623 2683 1156 990 562 2684 1091 929 562 2685 1091 929 623 2686 1156 990 564 2687 1093 931 566 2688 1095 933 564 2689 1093 931 627 2690 1160 994 623 2691 1156 990 627 2692 1160 994 564 2693 1093 931 568 2694 1097 935 566 2695 1095 933 631 2696 1164 998 627 2697 1160 994 631 2698 1164 998 566 2699 1095 933 631 2700 1164 998 635 2701 1168 1002 570 2702 1099 937 570 2703 1099 937 568 2704 1097 935 631 2705 1164 998 635 2706 1168 1002 572 2707 1101 939 570 2708 1099 937 572 2709 1101 939 635 2710 1168 1002 639 2711 1172 1006 639 2712 1172 1006 574 2713 1103 941 572 2714 1101 939 574 2715 1103 941 639 2716 1172 1006 643 2717 1176 1010 643 2718 1176 1010 576 2719 1105 943 574 2720 1103 941 576 2721 1105 943 643 2722 1176 1010 647 2723 1180 1014 647 2724 1180 1014 584 2725 1113 951 541 2726 1068 908 647 2727 1180 1014 541 2728 1068 908 576 2729 1105 943 641 2730 1185 1008 578 2731 1183 945 579 2732 1182 946 578 2733 1183 945 641 2734 1185 1008 645 2735 1184 1012 637 2736 1187 1004 579 2737 1182 946 585 2738 1186 952 579 2739 1182 946 637 2740 1187 1004 641 2741 1185 1008 589 2742 1188 956 637 2743 1187 1004 585 2744 1186 952 637 2745 1187 1004 589 2746 1188 956 633 2747 1189 1000 589 2748 1188 956 629 2749 1191 996 633 2750 1189 1000 629 2751 1191 996 589 2752 1188 956 593 2753 1190 960 597 2754 1192 964 625 2755 1193 992 593 2756 1190 960 629 2757 1191 996 593 2758 1190 960 625 2759 1193 992 597 2760 1192 964 621 2761 1195 988 625 2762 1193 992 621 2763 1195 988 597 2764 1192 964 601 2765 1194 968 621 2766 1195 988 601 2767 1194 968 605 2768 1196 972 621 2769 1195 988 605 2770 1196 972 617 2771 1197 984 609 2772 1198 976 617 2773 1197 984 605 2774 1196 972 617 2775 1197 984 609 2776 1198 976 613 2777 1199 980 620 2778 1203 987 612 2779 1201 979 608 2780 1200 975 612 2781 1201 979 620 2782 1203 987 616 2783 1202 983 620 2784 1203 987 604 2785 1204 971 624 2786 1205 991 604 2787 1204 971 620 2788 1203 987 608 2789 1200 975 628 2790 1207 995 600 2791 1206 967 596 2792 1208 963 624 2793 1205 991 600 2794 1206 967 628 2795 1207 995 600 2796 1206 967 624 2797 1205 991 604 2798 1204 971 628 2799 1207 995 592 2800 1210 959 632 2801 1209 999 592 2802 1210 959 628 2803 1207 995 596 2804 1208 963 632 2805 1209 999 592 2806 1210 959 636 2807 1211 1003 636 2808 1211 1003 592 2809 1210 959 588 2810 1212 955 636 2811 1211 1003 588 2812 1212 955 640 2813 1213 1007 640 2814 1213 1007 582 2815 1214 949 644 2816 1215 1011 582 2817 1214 949 640 2818 1213 1007 588 2819 1212 955 582 2820 1214 949 648 2821 1217 1015 644 2822 1215 1011 648 2823 1217 1015 582 2824 1214 949 583 2825 1216 950 142 2826 688 654 221 2827 691 565 288 2828 690 317 209 2829 502 311 72 2830 1868 225 139 2831 501 310 142 2832 1872 318 288 2833 690 317 74 2834 1871 228 142 2835 688 654 222 2836 692 566 221 2837 691 565 215 2838 674 554 210 2839 673 547 286 2840 672 648 286 2841 323 308 63 2842 161 213 67 2843 162 217 219 2844 683 558 215 2845 674 554 286 2846 672 648 287 2847 682 316 68 2848 1870 218 141 2849 685 313 62 2850 190 210 69 2851 187 219 224 2852 343 324 64 2853 192 214 62 2854 190 210 224 2855 343 324 216 2856 540 555 143 2857 537 570 224 2858 533 568 65 2859 180 215 64 2860 192 214 143 2861 345 326 225 2862 541 314 65 2863 1869 215 143 2864 537 570 143 2865 537 570 217 2866 542 556 225 2867 541 314 223 2868 342 323 75 2869 189 229 70 2870 158 221 223 2871 532 567 140 2872 504 546 207 2873 499 541 50 2874 137 143 19 2875 60 99 15 2876 52 102 50 2877 137 143 15 2878 52 102 14 2879 53 101 158 2880 400 429 159 2881 399 428 194 2882 484 471 159 2883 399 428 163 2884 407 427 194 2885 484 471 167 2886 453 507 181 2887 476 453 174 2888 473 443 182 2889 477 456 198 2890 486 376 169 2891 456 511 189 2892 481 466 184 2893 479 459 162 2894 408 514 163 2895 407 515 190 2896 483 467 191 2897 482 468 45 2898 133 137 50 2899 137 143 18 2900 61 186 19 2901 60 187 49 2902 136 142 46 2903 135 139 22 2904 109 180 33 2905 127 118 30 2906 126 115 26 2907 106 183 55 2908 138 48 39 2909 130 130 23 2910 100 151 37 2911 117 173 31 2912 116 172 27 2913 103 154 34 2914 121 177 38 2915 120 176 13 2916 43 82 12 2917 42 81 51 2918 112 165 12 2919 42 81 16 2920 50 80 51 2921 112 165 195 2922 459 494 160 2923 397 408 156 2924 389 411 195 2925 459 494 156 2926 389 411 157 2927 390 410 177 2928 462 499 180 2929 464 501 166 2930 450 482 168 2931 447 479 196 2932 465 502 183 2933 468 505

+

308 2934 694 675 290 2935 695 657 307 2936 697 674 307 2937 697 674 290 2938 695 657 289 2939 696 656 309 2940 698 676 291 2941 699 658 308 2942 694 675 308 2943 694 675 291 2944 699 658 290 2945 695 657 291 2946 699 658 309 2947 698 676 292 2948 701 659 309 2949 698 676 310 2950 700 677 292 2951 701 659 292 2952 701 659 310 2953 700 677 293 2954 703 660 310 2955 700 677 311 2956 702 678 293 2957 703 660 293 2958 703 660 311 2959 702 678 294 2960 705 661 311 2961 702 678 312 2962 704 679 294 2963 705 661 294 2964 705 661 312 2965 704 679 295 2966 707 662 312 2967 704 679 313 2968 706 680 295 2969 707 662 295 2970 707 662 313 2971 706 680 296 2972 709 663 313 2973 706 680 314 2974 708 681 296 2975 709 663 297 2976 711 664 296 2977 709 663 314 2978 708 681 297 2979 711 664 314 2980 708 681 315 2981 710 682 298 2982 713 665 297 2983 711 664 315 2984 710 682 298 2985 713 665 315 2986 710 682 316 2987 712 683 299 2988 715 666 298 2989 776 665 316 2990 775 683 299 2991 715 666 316 2992 775 683 317 2993 714 684 300 2994 717 667 299 2995 715 666 317 2996 714 684 300 2997 717 667 317 2998 714 684 318 2999 716 685 300 3000 717 667 319 3001 718 686 301 3002 719 668 319 3003 718 686 300 3004 717 667 318 3005 716 685 320 3006 720 687 302 3007 721 669 319 3008 718 686 302 3009 721 669 301 3010 719 668 319 3011 718 686 321 3012 722 688 303 3013 723 670 320 3014 720 687 303 3015 723 670 302 3016 721 669 320 3017 720 687 322 3018 724 689 304 3019 725 671 321 3020 722 688 304 3021 725 671 303 3022 723 670 321 3023 722 688 304 3024 725 671 323 3025 726 690 305 3026 727 672 323 3027 726 690 304 3028 725 671 322 3029 724 689 323 3030 726 690 324 3031 728 691 305 3032 727 672 324 3033 728 691 306 3034 729 673 305 3035 727 672 324 3036 728 691 307 3037 697 674 306 3038 729 673 307 3039 697 674 289 3040 696 656 306 3041 729 673 308 3042 694 675 307 3043 697 674 326 3044 730 693 308 3045 694 675 326 3046 730 693 325 3047 731 692 327 3048 732 694 326 3049 730 693 324 3050 728 691 307 3051 697 674 324 3052 728 691 326 3053 730 693 327 3054 732 694 323 3055 726 690 328 3056 733 695 323 3057 726 690 327 3058 732 694 324 3059 728 691 323 3060 726 690 322 3061 724 689 328 3062 733 695 329 3063 734 696 328 3064 733 695 322 3065 724 689 322 3066 724 689 321 3067 722 688 329 3068 734 696 329 3069 734 696 321 3070 722 688 330 3071 735 697 321 3072 722 688 320 3073 720 687 330 3074 735 697 330 3075 735 697 320 3076 720 687 331 3077 736 698 320 3078 720 687 319 3079 718 686 332 3080 737 699 320 3081 720 687 332 3082 737 699 331 3083 736 698 319 3084 718 686 318 3085 716 685 333 3086 738 700 319 3087 718 686 333 3088 738 700 332 3089 737 699 318 3090 716 685 317 3091 714 684 334 3092 739 701 334 3093 739 701 333 3094 738 700 318 3095 716 685 317 3096 714 684 335 3097 740 702 334 3098 739 701 335 3099 740 702 317 3100 714 684 316 3101 775 683 316 3102 712 683 315 3103 710 682 335 3104 786 702 335 3105 786 702 315 3106 710 682 336 3107 741 703 315 3108 710 682 314 3109 708 681 336 3110 741 703 336 3111 741 703 314 3112 708 681 337 3113 742 704 338 3114 743 705 337 3115 742 704 313 3116 706 680 314 3117 708 681 313 3118 706 680 337 3119 742 704 339 3120 744 706 338 3121 743 705 312 3122 704 679 313 3123 706 680 312 3124 704 679 338 3125 743 705 312 3126 704 679 311 3127 702 678 340 3128 745 707 340 3129 745 707 339 3130 744 706 312 3131 704 679 311 3132 702 678 341 3133 746 708 340 3134 745 707 341 3135 746 708 311 3136 702 678 310 3137 700 677 310 3138 700 677 342 3139 747 709 341 3140 746 708 342 3141 747 709 310 3142 700 677 309 3143 698 676 309 3144 698 676 325 3145 731 692 342 3146 747 709 325 3147 731 692 309 3148 698 676 308 3149 694 675 325 3150 731 692 343 3151 749 710 344 3152 748 711 343 3153 749 710 325 3154 731 692 326 3155 730 693 345 3156 750 712 325 3157 731 692 344 3158 748 711 325 3159 731 692 345 3160 750 712 342 3161 747 709 345 3162 750 712 346 3163 751 713 342 3164 747 709 342 3165 747 709 346 3166 751 713 341 3167 746 708 347 3168 752 714 341 3169 746 708 346 3170 751 713 341 3171 746 708 347 3172 752 714 340 3173 745 707 347 3174 752 714 348 3175 753 715 340 3176 745 707 340 3177 745 707 348 3178 753 715 339 3179 744 706 348 3180 753 715 349 3181 754 716 339 3182 744 706 339 3183 744 706 349 3184 754 716 338 3185 743 705 350 3186 755 717 338 3187 743 705 349 3188 754 716 338 3189 743 705 350 3190 755 717 337 3191 742 704 336 3192 741 703 337 3193 742 704 351 3194 756 718 337 3195 742 704 350 3196 755 717 351 3197 756 718 335 3198 786 702 336 3199 741 703 352 3200 757 719 336 3201 741 703 351 3202 756 718 352 3203 757 719 334 3204 739 701 335 3205 740 702 353 3206 758 720 335 3207 740 702 352 3208 796 719 353 3209 758 720 333 3210 738 700 334 3211 739 701 354 3212 759 721 334 3213 739 701 353 3214 758 720 354 3215 759 721 332 3216 737 699 333 3217 738 700 355 3218 760 722 355 3219 760 722 333 3220 738 700 354 3221 759 721 332 3222 737 699 356 3223 761 723 331 3224 736 698 356 3225 761 723 332 3226 737 699 355 3227 760 722 331 3228 736 698 357 3229 762 724 330 3230 735 697 357 3231 762 724 331 3232 736 698 356 3233 761 723 358 3234 763 725 329 3235 734 696 357 3236 762 724 329 3237 734 696 330 3238 735 697 357 3239 762 724 359 3240 764 726 328 3241 733 695 358 3242 763 725 328 3243 733 695 329 3244 734 696 358 3245 763 725 327 3246 732 694 359 3247 764 726 360 3248 765 727 359 3249 764 726 327 3250 732 694 328 3251 733 695 326 3252 730 693 360 3253 765 727 343 3254 749 710 360 3255 765 727 326 3256 730 693 327 3257 732 694 355 3258 800 722 352 3259 797 719 351 3260 795 718 352 3261 797 719 355 3262 800 722 354 3263 799 721 352 3264 797 719 354 3265 799 721 353 3266 798 720 356 3267 801 723 351 3268 795 718 350 3269 794 717 351 3270 795 718 356 3271 801 723 355 3272 800 722 357 3273 802 724 350 3274 794 717 349 3275 793 716 350 3276 794 717 357 3277 802 724 356 3278 801 723 358 3279 803 725 349 3280 793 716 348 3281 792 715 349 3282 793 716 358 3283 803 725 357 3284 802 724 359 3285 804 726 348 3286 792 715 347 3287 791 714 348 3288 792 715 359 3289 804 726 358 3290 803 725 347 3291 791 714 360 3292 805 727 359 3293 804 726 360 3294 805 727 347 3295 791 714 346 3296 790 713 346 3297 790 713 343 3298 788 710 360 3299 805 727 343 3300 788 710 346 3301 790 713 345 3302 789 712 343 3303 788 710 345 3304 789 712 344 3305 787 711 290 3306 766 657 306 3307 785 673 289 3308 767 656 291 3309 768 658 306 3310 785 673 290 3311 766 657 292 3312 769 659 306 3313 785 673 291 3314 768 658 306 3315 785 673 292 3316 769 659 305 3317 784 672 304 3318 783 671 292 3319 769 659 293 3320 770 660 292 3321 769 659 304 3322 783 671 305 3323 784 672 304 3324 783 671 293 3325 770 660 294 3326 771 661 294 3327 771 661 303 3328 782 670 304 3329 783 671 295 3330 772 662 303 3331 782 670 294 3332 771 661 303 3333 782 670 295 3334 772 662 302 3335 781 669 301 3336 780 668 295 3337 772 662 296 3338 773 663 302 3339 781 669 295 3340 772 662 301 3341 780 668 296 3342 773 663 300 3343 779 667 301 3344 780 668 300 3345 779 667 296 3346 773 663 297 3347 774 664 300 3348 779 667 297 3349 774 664 298 3350 777 665 300 3351 779 667 298 3352 777 665 299 3353 778 666 362 3354 807 729 361 3355 806 728 363 3356 808 730 363 3357 808 730 361 3358 806 728 364 3359 809 731 362 3360 807 729 366 3361 811 733 361 3362 806 728 366 3363 811 733 365 3364 810 732 361 3365 806 728 365 3366 810 732 366 3367 811 733 368 3368 813 735 365 3369 810 732 368 3370 813 735 367 3371 812 734 367 3372 812 734 368 3373 813 735 370 3374 815 737 367 3375 812 734 370 3376 815 737 369 3377 814 736 369 3378 814 736 370 3379 815 737 372 3380 817 739 369 3381 814 736 372 3382 817 739 371 3383 816 738 371 3384 816 738 372 3385 817 739 374 3386 819 741 371 3387 816 738 374 3388 819 741 373 3389 818 740 373 3390 818 740 374 3391 819 741 376 3392 821 743 373 3393 818 740 376 3394 821 743 375 3395 820 742 377 3396 822 744 375 3397 820 742 378 3398 823 745 375 3399 820 742 376 3400 821 743 378 3401 823 745 379 3402 824 746 377 3403 822 744 380 3404 825 747 377 3405 822 744 378 3406 823 745 380 3407 825 747 379 3408 829 746 380 3409 828 747 381 3410 826 748 381 3411 826 748 380 3412 828 747 382 3413 827 749 383 3414 830 750 381 3415 826 748 384 3416 831 751 381 3417 826 748 382 3418 827 749 384 3419 831 751 386 3420 833 753 385 3421 832 752 384 3422 831 751 385 3423 832 752 383 3424 830 750 384 3425 831 751 388 3426 835 755 387 3427 834 754 386 3428 833 753 387 3429 834 754 385 3430 832 752 386 3431 833 753 389 3432 836 756 387 3433 834 754 390 3434 837 757 390 3435 837 757 387 3436 834 754 388 3437 835 755 389 3438 836 756 392 3439 839 759 391 3440 838 758 392 3441 839 759 389 3442 836 756 390 3443 837 757 393 3444 840 760 391 3445 838 758 394 3446 841 761 394 3447 841 761 391 3448 838 758 392 3449 839 759 396 3450 843 763 395 3451 842 762 394 3452 841 761 394 3453 841 761 395 3454 842 762 393 3455 840 760 363 3456 808 730 364 3457 809 731 396 3458 843 763 396 3459 843 763 364 3460 809 731 395 3461 842 762 361 3462 806 728 397 3463 844 764 364 3464 809 731 397 3465 844 764 361 3466 806 728 398 3467 845 765 395 3468 842 762 364 3469 809 731 397 3470 844 764 395 3471 842 762 397 3472 844 764 399 3473 846 766 399 3474 846 766 400 3475 847 767 393 3476 840 760 393 3477 840 760 395 3478 842 762 399 3479 846 766 400 3480 847 767 401 3481 848 768 391 3482 838 758 391 3483 838 758 393 3484 840 760 400 3485 847 767 401 3486 848 768 402 3487 849 769 389 3488 836 756 401 3489 848 768 389 3490 836 756 391 3491 838 758 387 3492 834 754 389 3493 836 756 402 3494 849 769 402 3495 849 769 403 3496 850 770 387 3497 834 754 387 3498 834 754 404 3499 851 771 385 3500 832 752 404 3501 851 771 387 3502 834 754 403 3503 850 770 385 3504 832 752 405 3505 852 772 383 3506 830 750 405 3507 852 772 385 3508 832 752 404 3509 851 771 381 3510 826 748 383 3511 830 750 406 3512 853 773 406 3513 853 773 383 3514 830 750 405 3515 852 772 381 3516 826 748 407 3517 854 774 379 3518 829 746 407 3519 854 774 381 3520 826 748 406 3521 853 773 407 3522 856 774 408 3523 855 775 377 3524 822 744 407 3525 856 774 377 3526 822 744 379 3527 824 746 375 3528 820 742 377 3529 822 744 408 3530 855 775 408 3531 855 775 409 3532 857 776 375 3533 820 742 373 3534 818 740 375 3535 820 742 409 3536 857 776 373 3537 818 740 409 3538 857 776 410 3539 858 777 371 3540 816 738 373 3541 818 740 410 3542 858 777 371 3543 816 738 410 3544 858 777 411 3545 859 778 369 3546 814 736 371 3547 816 738 412 3548 860 779 412 3549 860 779 371 3550 816 738 411 3551 859 778 369 3552 814 736 413 3553 861 780 367 3554 812 734 413 3555 861 780 369 3556 814 736 412 3557 860 779 365 3558 810 732 367 3559 812 734 414 3560 862 781 413 3561 861 780 414 3562 862 781 367 3563 812 734 414 3564 862 781 398 3565 845 765 365 3566 810 732 365 3567 810 732 398 3568 845 765 361 3569 806 728 397 3570 844 764 398 3571 845 765 416 3572 864 783 398 3573 845 765 415 3574 863 782 416 3575 864 783 398 3576 845 765 417 3577 865 784 415 3578 863 782 417 3579 865 784 398 3580 845 765 414 3581 862 781 417 3582 865 784 414 3583 862 781 418 3584 866 785 414 3585 862 781 413 3586 861 780 418 3587 866 785 418 3588 866 785 413 3589 861 780 419 3590 867 786 413 3591 861 780 412 3592 860 779 419 3593 867 786 419 3594 867 786 412 3595 860 779 420 3596 868 787 412 3597 860 779 411 3598 859 778 420 3599 868 787 420 3600 868 787 411 3601 859 778 421 3602 869 788 411 3603 859 778 410 3604 858 777 421 3605 869 788 421 3606 869 788 410 3607 858 777 422 3608 870 789 410 3609 858 777 409 3610 857 776 422 3611 870 789 422 3612 870 789 409 3613 857 776 423 3614 871 790 423 3615 871 790 409 3616 857 776 408 3617 855 775 423 3618 871 790 408 3619 855 775 424 3620 872 791 424 3621 872 791 408 3622 855 775 407 3623 856 774 424 3624 874 791 407 3625 854 774 425 3626 873 792 425 3627 873 792 407 3628 854 774 406 3629 853 773 425 3630 873 792 406 3631 853 773 426 3632 875 793 426 3633 875 793 406 3634 853 773 405 3635 852 772 404 3636 851 771 427 3637 876 794 405 3638 852 772 427 3639 876 794 426 3640 875 793 405 3641 852 772 403 3642 850 770 428 3643 877 795 404 3644 851 771 428 3645 877 795 427 3646 876 794 404 3647 851 771 402 3648 849 769 429 3649 878 796 403 3650 850 770 429 3651 878 796 428 3652 877 795 403 3653 850 770 430 3654 879 797 429 3655 878 796 401 3656 848 768 401 3657 848 768 429 3658 878 796 402 3659 849 769 431 3660 880 798 430 3661 879 797 400 3662 847 767 400 3663 847 767 430 3664 879 797 401 3665 848 768 400 3666 847 767 399 3667 846 766 431 3668 880 798 399 3669 846 766 432 3670 881 799 431 3671 880 798 399 3672 846 766 397 3673 844 764 432 3674 881 799 397 3675 844 764 416 3676 864 783 432 3677 881 799 427 3678 886 794 424 3679 884 791 426 3680 882 793 424 3681 884 791 427 3682 886 794 423 3683 885 790 426 3684 882 793 424 3685 884 791 425 3686 883 792 423 3687 885 790 428 3688 888 795 422 3689 887 789 428 3690 888 795 423 3691 885 790 427 3692 886 794 429 3693 890 796 422 3694 887 789 428 3695 888 795 422 3696 887 789 429 3697 890 796 421 3698 889 788 421 3699 889 788 430 3700 892 797 420 3701 891 787 430 3702 892 797 421 3703 889 788 429 3704 890 796 420 3705 891 787 431 3706 894 798 419 3707 893 786 431 3708 894 798 420 3709 891 787 430 3710 892 797 419 3711 893 786 432 3712 896 799 418 3713 895 785 432 3714 896 799 419 3715 893 786 431 3716 894 798 418 3717 895 785 416 3718 898 783 417 3719 897 784 416 3720 898 783 418 3721 895 785 432 3722 896 799 417 3723 897 784 416 3724 898 783 415 3725 899 782 396 3726 900 763 366 3727 903 733 362 3728 902 729 396 3729 900 763 362 3730 902 729 363 3731 901 730 368 3732 905 735 396 3733 900 763 394 3734 904 761 396 3735 900 763 368 3736 905 735 366 3737 903 733 392 3738 906 759 368 3739 905 735 394 3740 904 761 368 3741 905 735 392 3742 906 759 370 3743 907 737 390 3744 908 757 372 3745 909 739 392 3746 906 759 370 3747 907 737 392 3748 906 759 372 3749 909 739 374 3750 911 741 390 3751 908 757 388 3752 910 755 390 3753 908 757 374 3754 911 741 372 3755 909 739 374 3756 911 741 388 3757 910 755 386 3758 912 753 374 3759 911 741 386 3760 912 753 376 3761 913 743 384 3762 914 751 376 3763 913 743 386 3764 912 753 376 3765 913 743 384 3766 914 751 378 3767 915 745 380 3768 917 747 384 3769 914 751 382 3770 916 749 378 3771 915 745 384 3772 914 751 380 3773 917 747 658 3774 1236 1025 649 3775 1218 1016 659 3776 1237 1026 659 3777 1237 1026 649 3778 1218 1016 650 3779 1220 1017 659 3780 1237 1026 650 3781 1220 1017 660 3782 1238 1027 660 3783 1238 1027 650 3784 1220 1017 651 3785 1222 1018 660 3786 1239 1027 651 3787 1246 1018 661 3788 1240 1028 661 3789 1240 1028 651 3790 1246 1018 652 3791 1224 1019 661 3792 1240 1028 652 3793 1224 1019 662 3794 1241 1029 662 3795 1241 1029 652 3796 1224 1019 653 3797 1226 1020 662 3798 1241 1029 653 3799 1226 1020 663 3800 1242 1030 663 3801 1242 1030 653 3802 1226 1020 654 3803 1228 1021 663 3804 1242 1030 654 3805 1228 1021 664 3806 1243 1031 664 3807 1243 1031 654 3808 1228 1021 655 3809 1230 1022 664 3810 1243 1031 655 3811 1230 1022 665 3812 1244 1032 665 3813 1244 1032 655 3814 1230 1022 656 3815 1232 1023 665 3816 1244 1032 656 3817 1232 1023 666 3818 1245 1033 666 3819 1245 1033 656 3820 1232 1023 657 3821 1234 1024 666 3822 1245 1033 657 3823 1234 1024 658 3824 1236 1025 658 3825 1236 1025 657 3826 1234 1024 649 3827 1218 1016 658 3828 1236 1025 659 3829 1237 1026 668 3830 1248 1035 658 3831 1236 1025 668 3832 1248 1035 667 3833 1247 1034 659 3834 1237 1026 669 3835 1249 1036 668 3836 1248 1035 669 3837 1249 1036 659 3838 1237 1026 660 3839 1238 1027 661 3840 1240 1028 669 3841 1250 1036 660 3842 1239 1027 669 3843 1250 1036 661 3844 1240 1028 670 3845 1251 1037 662 3846 1241 1029 671 3847 1252 1038 670 3848 1251 1037 662 3849 1241 1029 670 3850 1251 1037 661 3851 1240 1028 662 3852 1241 1029 672 3853 1253 1039 671 3854 1252 1038 672 3855 1253 1039 662 3856 1241 1029 663 3857 1242 1030 663 3858 1242 1030 673 3859 1254 1040 672 3860 1253 1039 673 3861 1254 1040 663 3862 1242 1030 664 3863 1243 1031 665 3864 1244 1032 674 3865 1255 1041 673 3866 1254 1040 665 3867 1244 1032 673 3868 1254 1040 664 3869 1243 1031 666 3870 1245 1033 674 3871 1255 1041 665 3872 1244 1032 674 3873 1255 1041 666 3874 1245 1033 675 3875 1256 1042 666 3876 1245 1033 658 3877 1236 1025 675 3878 1256 1042 658 3879 1236 1025 667 3880 1247 1034 675 3881 1256 1042 676 3882 1257 1043 667 3883 1247 1034 677 3884 1258 1044 677 3885 1258 1044 667 3886 1247 1034 668 3887 1248 1035 677 3888 1258 1044 668 3889 1248 1035 678 3890 1259 1045 678 3891 1259 1045 668 3892 1248 1035 669 3893 1249 1036 678 3894 1260 1045 669 3895 1250 1036 679 3896 1261 1046 679 3897 1261 1046 669 3898 1250 1036 670 3899 1251 1037 679 3900 1261 1046 670 3901 1251 1037 680 3902 1262 1047 680 3903 1262 1047 670 3904 1251 1037 671 3905 1252 1038 680 3906 1262 1047 671 3907 1252 1038 681 3908 1263 1048 681 3909 1263 1048 671 3910 1252 1038 672 3911 1253 1039 681 3912 1263 1048 672 3913 1253 1039 682 3914 1264 1049 682 3915 1264 1049 672 3916 1253 1039 673 3917 1254 1040 682 3918 1264 1049 673 3919 1254 1040 683 3920 1265 1050 683 3921 1265 1050 673 3922 1254 1040 674 3923 1255 1041 683 3924 1265 1050 674 3925 1255 1041 684 3926 1266 1051 684 3927 1266 1051 674 3928 1255 1041 675 3929 1256 1042 684 3930 1266 1051 675 3931 1256 1042 676 3932 1257 1043 676 3933 1257 1043 675 3934 1256 1042 667 3935 1247 1034 649 3936 1218 1016 686 3937 1268 1053 650 3938 1220 1017 686 3939 1268 1053 649 3940 1218 1016 685 3941 1267 1052 650 3942 1220 1017 687 3943 1269 1054 651 3944 1222 1018 687 3945 1269 1054 650 3946 1220 1017 686 3947 1268 1053 652 3948 1224 1019 687 3949 1270 1054 688 3950 1271 1055 687 3951 1270 1054 652 3952 1224 1019 651 3953 1246 1018 688 3954 1271 1055 653 3955 1226 1020 652 3956 1224 1019 653 3957 1226 1020 688 3958 1271 1055 689 3959 1272 1056 654 3960 1228 1021 653 3961 1226 1020 690 3962 1273 1057 653 3963 1226 1020 689 3964 1272 1056 690 3965 1273 1057 654 3966 1228 1021 691 3967 1274 1058 655 3968 1230 1022 691 3969 1274 1058 654 3970 1228 1021 690 3971 1273 1057 655 3972 1230 1022 691 3973 1274 1058 656 3974 1232 1023 691 3975 1274 1058 692 3976 1275 1059 656 3977 1232 1023 657 3978 1234 1024 692 3979 1275 1059 693 3980 1276 1060 692 3981 1275 1059 657 3982 1234 1024 656 3983 1232 1023 649 3984 1218 1016 657 3985 1234 1024 693 3986 1276 1060 649 3987 1218 1016 693 3988 1276 1060 685 3989 1267 1052 696 3990 1279 1063 694 3991 1277 1061 695 3992 1278 1062 694 3993 1277 1061 701 3994 1233 1068 702 3995 1286 1069 701 3996 1233 1068 694 3997 1277 1061 696 3998 1279 1063 693 3999 1276 1060 695 4000 1221 1062 685 4001 1267 1052 685 4002 1267 1052 695 4003 1221 1062 694 4004 1219 1061 692 4005 1275 1059 696 4006 1223 1063 693 4007 1276 1060 693 4008 1276 1060 696 4009 1223 1063 695 4010 1221 1062 691 4011 1274 1058 697 4012 1280 1064 692 4013 1275 1059 692 4014 1275 1059 697 4015 1280 1064 696 4016 1223 1063 690 4017 1273 1057 698 4018 1281 1065 691 4019 1274 1058 691 4020 1274 1058 698 4021 1281 1065 697 4022 1280 1064 689 4023 1272 1056 699 4024 1282 1066 690 4025 1273 1057 690 4026 1273 1057 699 4027 1282 1066 698 4028 1281 1065 688 4029 1271 1055 700 4030 1283 1067 689 4031 1272 1056 689 4032 1272 1056 700 4033 1283 1067 699 4034 1282 1066 700 4035 1283 1067 688 4036 1271 1055 687 4037 1270 1054 687 4038 1270 1054 701 4039 1284 1068 700 4040 1283 1067 686 4041 1268 1053 702 4042 1235 1069 687 4043 1269 1054 687 4044 1269 1054 702 4045 1235 1069 701 4046 1285 1068 685 4047 1267 1052 694 4048 1219 1061 686 4049 1268 1053 686 4050 1268 1053 694 4051 1219 1061 702 4052 1235 1069 699 4053 1229 1066 697 4054 1225 1064 698 4055 1227 1065 697 4056 1225 1064 699 4057 1229 1066 700 4058 1231 1067 697 4059 1225 1064 700 4060 1231 1067 701 4061 1233 1068 697 4062 1225 1064 701 4063 1233 1068 696 4064 1279 1063 703 4065 1295 1070 706 4066 1297 1073 704 4067 1298 1071 706 4068 1297 1073 703 4069 1295 1070 705 4070 1296 1072 709 4071 1302 1076 707 4072 1299 1074 710 4073 1301 1077 707 4074 1299 1074 708 4075 1300 1075 710 4076 1301 1077 710 4077 1293 1077 708 4078 1292 1075 706 4079 1289 1073 708 4080 1292 1075 704 4081 1290 1071 706 4082 1289 1073 709 4083 1306 1076 710 4084 1305 1077 705 4085 1303 1072 705 4086 1303 1072 710 4087 1305 1077 706 4088 1304 1073 705 4089 1288 1072 707 4090 1291 1074 709 4091 1294 1076 707 4092 1291 1074 705 4093 1288 1072 703 4094 1287 1070 775 4095 1430 1201 712 4096 1310 1081 711 4097 1308 1079 711 4098 1308 1079 776 4099 1457 1203 775 4100 1430 1201 712 4101 1310 1081 775 4102 1430 1201 713 4103 1312 1083 791 4104 1462 1233 713 4105 1312 1083 775 4106 1430 1201 713 4107 1312 1083 791 4108 1462 1233 715 4109 1315 1086 714 4110 1314 1085 715 4111 1315 1086 791 4112 1462 1233 794 4113 1467 1238 716 4114 1316 1087 714 4115 1314 1085 714 4116 1314 1085 716 4117 1316 1087 715 4118 1315 1086 716 4119 1316 1087 794 4120 1467 1238 796 4121 1469 1240 716 4122 1316 1087 796 4123 1469 1240 717 4124 1318 1089 717 4125 1318 1089 796 4126 1469 1240 719 4127 1320 1091 717 4128 1318 1089 719 4129 1320 1091 718 4130 1319 1090 711 4131 1607 1079 719 4132 1320 1091 776 4133 1432 1203 719 4134 1320 1091 711 4135 1607 1079 718 4136 1319 1090 712 4137 1310 1081 721 4138 1324 1095 720 4139 1322 1093 720 4140 1322 1093 711 4141 1308 1079 712 4142 1310 1081 721 4143 1324 1095 712 4144 1310 1081 722 4145 1326 1097 713 4146 1312 1083 722 4147 1326 1097 712 4148 1310 1081 722 4149 1326 1097 713 4150 1312 1083 723 4151 1328 1099 715 4152 1315 1086 723 4153 1328 1099 713 4154 1312 1083 716 4155 1316 1087 724 4156 1329 1100 715 4157 1315 1086 715 4158 1315 1086 724 4159 1329 1100 723 4160 1328 1099 724 4161 1329 1100 716 4162 1316 1087 717 4163 1318 1089 724 4164 1329 1100 717 4165 1318 1089 725 4166 1331 1102 725 4167 1331 1102 717 4168 1318 1089 718 4169 1319 1090 725 4170 1331 1102 718 4171 1319 1090 726 4172 1332 1103 720 4173 1608 1093 718 4174 1319 1090 711 4175 1607 1079 718 4176 1319 1090 720 4177 1608 1093 726 4178 1332 1103 721 4179 1324 1095 780 4180 1439 1210 781 4181 1441 1212 781 4182 1441 1212 720 4183 1322 1093 721 4184 1324 1095 780 4185 1439 1210 722 4186 1326 1097 779 4187 1437 1208 722 4188 1326 1097 780 4189 1439 1210 721 4190 1324 1095 779 4191 1437 1208 723 4192 1328 1099 778 4193 1435 1206 723 4194 1328 1099 779 4195 1437 1208 722 4196 1326 1097 724 4197 1329 1100 777 4198 1434 1205 723 4199 1328 1099 723 4200 1328 1099 777 4201 1434 1205 778 4202 1435 1206 725 4203 1331 1102 783 4204 1444 1215 724 4205 1329 1100 777 4206 1434 1205 724 4207 1329 1100 783 4208 1444 1215 783 4209 1444 1215 725 4210 1331 1102 782 4211 1443 1214 725 4212 1331 1102 726 4213 1332 1103 782 4214 1443 1214 782 4215 1443 1214 726 4216 1332 1103 781 4217 1617 1212 781 4218 1617 1212 726 4219 1332 1103 720 4220 1608 1093 732 4221 1345 1115 727 4222 1334 1105 734 4223 1348 1119 732 4224 1345 1115 734 4225 1348 1119 733 4226 1346 1117 735 4227 1350 1121 727 4228 1334 1105 728 4229 1336 1107 727 4230 1334 1105 735 4231 1350 1121 734 4232 1348 1119 736 4233 1352 1123 728 4234 1336 1107 729 4235 1338 1109 728 4236 1336 1107 736 4237 1352 1123 735 4238 1350 1121 736 4239 1352 1123 729 4240 1338 1109 730 4241 1340 1111 730 4242 1340 1111 737 4243 1354 1125 736 4244 1352 1123 737 4245 1354 1125 730 4246 1340 1111 731 4247 1342 1113 737 4248 1354 1125 731 4249 1342 1113 738 4250 1356 1127 738 4251 1356 1127 731 4252 1342 1113 732 4253 1344 1115 738 4254 1356 1127 732 4255 1344 1115 733 4256 1610 1117 734 4257 1348 1119 740 4258 1360 1131 733 4259 1346 1117 733 4260 1346 1117 740 4261 1360 1131 739 4262 1358 1129 741 4263 1362 1133 734 4264 1348 1119 735 4265 1350 1121 734 4266 1348 1119 741 4267 1362 1133 740 4268 1360 1131 742 4269 1364 1135 735 4270 1350 1121 736 4271 1352 1123 735 4272 1350 1121 742 4273 1364 1135 741 4274 1362 1133 742 4275 1364 1135 736 4276 1352 1123 737 4277 1354 1125 737 4278 1354 1125 743 4279 1366 1137 742 4280 1364 1135 738 4281 1356 1127 744 4282 1368 1139 743 4283 1366 1137 738 4284 1356 1127 743 4285 1366 1137 737 4286 1354 1125 733 4287 1610 1117 739 4288 1611 1129 744 4289 1368 1139 733 4290 1610 1117 744 4291 1368 1139 738 4292 1356 1127 740 4293 1360 1131 746 4294 1372 1143 739 4295 1358 1129 739 4296 1358 1129 746 4297 1372 1143 745 4298 1370 1141 746 4299 1372 1143 740 4300 1360 1131 741 4301 1362 1133 741 4302 1362 1133 747 4303 1374 1145 746 4304 1372 1143 747 4305 1374 1145 741 4306 1362 1133 742 4307 1364 1135 742 4308 1364 1135 748 4309 1376 1147 747 4310 1374 1145 748 4311 1376 1147 742 4312 1364 1135 743 4313 1366 1137 743 4314 1366 1137 749 4315 1378 1149 748 4316 1376 1147 744 4317 1368 1139 750 4318 1380 1151 743 4319 1366 1137 743 4320 1366 1137 750 4321 1380 1151 749 4322 1378 1149 739 4323 1611 1129 745 4324 1612 1141 744 4325 1368 1139 744 4326 1368 1139 745 4327 1612 1141 750 4328 1380 1151 745 4329 1370 1141 746 4330 1372 1143 751 4331 1382 1153 746 4332 1372 1143 752 4333 1384 1155 751 4334 1382 1153 747 4335 1374 1145 753 4336 1386 1157 752 4337 1384 1155 747 4338 1374 1145 752 4339 1384 1155 746 4340 1372 1143 748 4341 1376 1147 754 4342 1388 1159 753 4343 1386 1157 748 4344 1376 1147 753 4345 1386 1157 747 4346 1374 1145 749 4347 1378 1149 755 4348 1390 1161 748 4349 1376 1147 748 4350 1376 1147 755 4351 1390 1161 754 4352 1388 1159 749 4353 1378 1149 756 4354 1392 1163 755 4355 1390 1161 756 4356 1392 1163 749 4357 1378 1149 750 4358 1380 1151 750 4359 1380 1151 751 4360 1613 1153 756 4361 1392 1163 751 4362 1613 1153 750 4363 1380 1151 745 4364 1612 1141 751 4365 1382 1153 752 4366 1384 1155 757 4367 1394 1165 752 4368 1384 1155 758 4369 1396 1167 757 4370 1394 1165 758 4371 1396 1167 752 4372 1384 1155 759 4373 1398 1169 753 4374 1386 1157 759 4375 1398 1169 752 4376 1384 1155 759 4377 1398 1169 753 4378 1386 1157 760 4379 1400 1171 754 4380 1388 1159 760 4381 1400 1171 753 4382 1386 1157 754 4383 1388 1159 755 4384 1390 1161 761 4385 1402 1173 754 4386 1388 1159 761 4387 1402 1173 760 4388 1400 1171 761 4389 1402 1173 755 4390 1390 1161 756 4391 1392 1163 761 4392 1402 1173 756 4393 1392 1163 762 4394 1404 1175 762 4395 1404 1175 756 4396 1392 1163 751 4397 1613 1153 762 4398 1404 1175 751 4399 1613 1153 757 4400 1614 1165 764 4401 1408 1179 763 4402 1406 1177 757 4403 1394 1165 764 4404 1408 1179 757 4405 1394 1165 758 4406 1396 1167 758 4407 1396 1167 765 4408 1410 1181 764 4409 1408 1179 765 4410 1410 1181 758 4411 1396 1167 759 4412 1398 1169 765 4413 1410 1181 759 4414 1398 1169 766 4415 1412 1183 766 4416 1412 1183 759 4417 1398 1169 760 4418 1400 1171 766 4419 1412 1183 760 4420 1400 1171 761 4421 1402 1173 761 4422 1402 1173 767 4423 1414 1185 766 4424 1412 1183 767 4425 1414 1185 761 4426 1402 1173 762 4427 1404 1175 767 4428 1414 1185 762 4429 1404 1175 768 4430 1416 1187 757 4431 1614 1165 763 4432 1615 1177 768 4433 1416 1187 768 4434 1416 1187 762 4435 1404 1175 757 4436 1614 1165 769 4437 1418 1189 763 4438 1406 1177 770 4439 1420 1191 770 4440 1420 1191 763 4441 1406 1177 764 4442 1408 1179 770 4443 1420 1191 764 4444 1408 1179 771 4445 1422 1193 771 4446 1422 1193 764 4447 1408 1179 765 4448 1410 1181 771 4449 1422 1193 765 4450 1410 1181 772 4451 1424 1195 772 4452 1424 1195 765 4453 1410 1181 766 4454 1412 1183 772 4455 1424 1195 766 4456 1412 1183 767 4457 1414 1185 767 4458 1414 1185 773 4459 1426 1197 772 4460 1424 1195 768 4461 1416 1187 773 4462 1426 1197 767 4463 1414 1185 773 4464 1426 1197 768 4465 1416 1187 774 4466 1428 1199 763 4467 1615 1177 774 4468 1428 1199 768 4469 1416 1187 774 4470 1428 1199 763 4471 1615 1177 769 4472 1616 1189 787 4473 1452 1223 788 4474 1454 1225 780 4475 1439 1210 788 4476 1454 1225 781 4477 1441 1212 780 4478 1439 1210 779 4479 1437 1208 786 4480 1450 1221 787 4481 1452 1223 787 4482 1452 1223 780 4483 1439 1210 779 4484 1437 1208 778 4485 1435 1206 785 4486 1448 1219 786 4487 1450 1221 786 4488 1450 1221 779 4489 1437 1208 778 4490 1435 1206 777 4491 1434 1205 784 4492 1446 1217 778 4493 1435 1206 778 4494 1435 1206 784 4495 1446 1217 785 4496 1448 1219 783 4497 1444 1215 789 4498 1456 1227 784 4499 1446 1217 784 4500 1446 1217 777 4501 1434 1205 783 4502 1444 1215 789 4503 1456 1227 783 4504 1444 1215 782 4505 1443 1214 789 4506 1456 1227 782 4507 1443 1214 788 4508 1618 1225 788 4509 1618 1225 782 4510 1443 1214 781 4511 1617 1212 727 4512 1334 1105 732 4513 1345 1115 787 4514 1452 1223 732 4515 1345 1115 788 4516 1454 1225 787 4517 1452 1223 727 4518 1334 1105 786 4519 1450 1221 728 4520 1336 1107 786 4521 1450 1221 727 4522 1334 1105 787 4523 1452 1223 785 4524 1448 1219 728 4525 1336 1107 786 4526 1450 1221 728 4527 1336 1107 785 4528 1448 1219 729 4529 1338 1109 785 4530 1448 1219 784 4531 1446 1217 730 4532 1340 1111 785 4533 1448 1219 730 4534 1340 1111 729 4535 1338 1109 784 4536 1446 1217 731 4537 1342 1113 730 4538 1340 1111 731 4539 1342 1113 784 4540 1446 1217 789 4541 1456 1227 731 4542 1342 1113 789 4543 1456 1227 732 4544 1344 1115 732 4545 1344 1115 789 4546 1456 1227 788 4547 1618 1225 776 4548 1457 1203 799 4549 1459 1245 775 4550 1430 1201 775 4551 1430 1201 799 4552 1459 1245 790 4553 1458 1229 792 4554 1463 1234 791 4555 1462 1233 775 4556 1430 1201 792 4557 1463 1234 775 4558 1430 1201 790 4559 1458 1229 793 4560 1465 1236 714 4561 1314 1085 791 4562 1462 1233 793 4563 1465 1236 791 4564 1462 1233 792 4565 1463 1234 714 4566 1314 1085 793 4567 1465 1236 795 4568 1468 1239 795 4569 1468 1239 794 4570 1467 1238 714 4571 1314 1085 797 4572 1470 1241 796 4573 1469 1240 795 4574 1468 1239 794 4575 1467 1238 795 4576 1468 1239 796 4577 1469 1240 798 4578 1473 1244 719 4579 1320 1091 797 4580 1470 1241 796 4581 1469 1240 797 4582 1470 1241 719 4583 1320 1091 719 4584 1320 1091 799 4585 1474 1245 776 4586 1432 1203 799 4587 1474 1245 719 4588 1320 1091 798 4589 1473 1244 799 4590 1459 1245 806 4591 1476 1257 790 4592 1458 1229 790 4593 1458 1229 806 4594 1476 1257 800 4595 1475 1246 801 4596 1478 1249 792 4597 1463 1234 790 4598 1458 1229 801 4599 1478 1249 790 4600 1458 1229 800 4601 1475 1246 802 4602 1480 1251 793 4603 1465 1236 792 4604 1463 1234 802 4605 1480 1251 792 4606 1463 1234 801 4607 1478 1249 793 4608 1465 1236 802 4609 1480 1251 803 4610 1482 1253 803 4611 1482 1253 795 4612 1468 1239 793 4613 1465 1236 804 4614 1483 1254 797 4615 1470 1241 803 4616 1482 1253 795 4617 1468 1239 803 4618 1482 1253 797 4619 1470 1241 805 4620 1485 1256 798 4621 1473 1244 804 4622 1483 1254 797 4623 1470 1241 804 4624 1483 1254 798 4625 1473 1244 798 4626 1473 1244 806 4627 1486 1257 799 4628 1474 1245 806 4629 1486 1257 798 4630 1473 1244 805 4631 1485 1256 806 4632 1476 1257 813 4633 1488 1269 800 4634 1475 1246 800 4635 1475 1246 813 4636 1488 1269 807 4637 1487 1258 808 4638 1490 1261 801 4639 1478 1249 807 4640 1487 1258 801 4641 1478 1249 800 4642 1475 1246 807 4643 1487 1258 809 4644 1492 1263 802 4645 1480 1251 808 4646 1490 1261 802 4647 1480 1251 801 4648 1478 1249 808 4649 1490 1261 802 4650 1480 1251 809 4651 1492 1263 810 4652 1494 1265 810 4653 1494 1265 803 4654 1482 1253 802 4655 1480 1251 803 4656 1482 1253 810 4657 1494 1265 811 4658 1495 1266 803 4659 1482 1253 811 4660 1495 1266 804 4661 1483 1254 804 4662 1483 1254 811 4663 1495 1266 812 4664 1497 1268 804 4665 1483 1254 812 4666 1497 1268 805 4667 1485 1256 805 4668 1485 1256 813 4669 1498 1269 806 4670 1486 1257 813 4671 1498 1269 805 4672 1485 1256 812 4673 1497 1268 814 4674 1499 1270 815 4675 1501 1272 816 4676 1503 1274 815 4677 1501 1272 814 4678 1499 1270 827 4679 1502 1293 816 4680 1503 1274 815 4681 1501 1272 817 4682 1506 1277 816 4683 1503 1274 817 4684 1506 1277 818 4685 1507 1278 818 4686 1507 1278 817 4687 1506 1277 819 4688 1510 1281 818 4689 1507 1278 819 4690 1510 1281 820 4691 1511 1282 820 4692 1511 1282 819 4693 1510 1281 821 4694 1513 1284 821 4695 1513 1284 819 4696 1510 1281 822 4697 1514 1285 821 4698 1513 1284 822 4699 1514 1285 824 4700 1517 1288 824 4701 1517 1288 822 4702 1514 1285 823 4703 1516 1287 823 4704 1516 1287 825 4705 1519 1290 824 4706 1517 1288 825 4707 1519 1290 823 4708 1516 1287 826 4709 1520 1291 825 4710 1519 1290 826 4711 1520 1291 814 4712 1623 1270 814 4713 1623 1270 826 4714 1520 1291 827 4715 1522 1293 827 4716 1502 1293 828 4717 1523 1294 815 4718 1501 1272 828 4719 1523 1294 827 4720 1502 1293 834 4721 1524 1305 829 4722 1526 1297 815 4723 1501 1272 828 4724 1523 1294 815 4725 1501 1272 829 4726 1526 1297 817 4727 1506 1277 830 4728 1528 1299 817 4729 1506 1277 829 4730 1526 1297 817 4731 1506 1277 830 4732 1528 1299 819 4733 1510 1281 819 4734 1510 1281 830 4735 1528 1299 822 4736 1514 1285 822 4737 1514 1285 830 4738 1528 1299 831 4739 1530 1301 822 4740 1514 1285 831 4741 1530 1301 823 4742 1516 1287 823 4743 1516 1287 831 4744 1530 1301 832 4745 1531 1302 823 4746 1516 1287 832 4747 1531 1302 826 4748 1520 1291 826 4749 1520 1291 832 4750 1531 1302 833 4751 1533 1304 826 4752 1520 1291 833 4753 1533 1304 827 4754 1522 1293 827 4755 1522 1293 833 4756 1533 1304 834 4757 1534 1305 834 4758 1524 1305 835 4759 1535 1306 828 4760 1523 1294 835 4761 1535 1306 834 4762 1524 1305 841 4763 1536 1317 835 4764 1535 1306 829 4765 1526 1297 828 4766 1523 1294 829 4767 1526 1297 835 4768 1535 1306 836 4769 1538 1309 836 4770 1538 1309 830 4771 1528 1299 829 4772 1526 1297 830 4773 1528 1299 836 4774 1538 1309 837 4775 1540 1311 830 4776 1528 1299 837 4777 1540 1311 831 4778 1530 1301 831 4779 1530 1301 837 4780 1540 1311 838 4781 1542 1313 831 4782 1530 1301 839 4783 1543 1314 832 4784 1531 1302 839 4785 1543 1314 831 4786 1530 1301 838 4787 1542 1313 832 4788 1531 1302 840 4789 1545 1316 833 4790 1533 1304 840 4791 1545 1316 832 4792 1531 1302 839 4793 1543 1314 834 4794 1534 1305 840 4795 1545 1316 841 4796 1546 1317 840 4797 1545 1316 834 4798 1534 1305 833 4799 1533 1304 841 4800 1536 1317 848 4801 1548 1329 835 4802 1535 1306 835 4803 1535 1306 848 4804 1548 1329 842 4805 1547 1318 835 4806 1535 1306 842 4807 1547 1318 836 4808 1538 1309 843 4809 1550 1321 836 4810 1538 1309 842 4811 1547 1318 836 4812 1538 1309 843 4813 1550 1321 837 4814 1540 1311 844 4815 1552 1323 837 4816 1540 1311 843 4817 1550 1321 837 4818 1540 1311 845 4819 1554 1325 838 4820 1542 1313 845 4821 1554 1325 837 4822 1540 1311 844 4823 1552 1323 838 4824 1542 1313 845 4825 1554 1325 846 4826 1555 1326 838 4827 1542 1313 846 4828 1555 1326 839 4829 1543 1314 839 4830 1543 1314 846 4831 1555 1326 847 4832 1557 1328 839 4833 1543 1314 847 4834 1557 1328 840 4835 1545 1316 840 4836 1545 1316 848 4837 1558 1329 841 4838 1546 1317 848 4839 1558 1329 840 4840 1545 1316 847 4841 1557 1328 848 4842 1548 1329 855 4843 1560 1341 842 4844 1547 1318 842 4845 1547 1318 855 4846 1560 1341 849 4847 1559 1330 850 4848 1562 1333 843 4849 1550 1321 842 4850 1547 1318 850 4851 1562 1333 842 4852 1547 1318 849 4853 1559 1330 851 4854 1564 1335 844 4855 1552 1323 843 4856 1550 1321 851 4857 1564 1335 843 4858 1550 1321 850 4859 1562 1333 844 4860 1552 1323 852 4861 1566 1337 845 4862 1554 1325 852 4863 1566 1337 844 4864 1552 1323 851 4865 1564 1335 853 4866 1567 1338 846 4867 1555 1326 852 4868 1566 1337 845 4869 1554 1325 852 4870 1566 1337 846 4871 1555 1326 854 4872 1569 1340 847 4873 1557 1328 853 4874 1567 1338 846 4875 1555 1326 853 4876 1567 1338 847 4877 1557 1328 847 4878 1557 1328 855 4879 1570 1341 848 4880 1558 1329 855 4881 1570 1341 847 4882 1557 1328 854 4883 1569 1340 855 4884 1560 1341 856 4885 1571 1342 849 4886 1559 1330 856 4887 1571 1342 855 4888 1560 1341 862 4889 1572 1353 849 4890 1559 1330 857 4891 1574 1345 850 4892 1562 1333 857 4893 1574 1345 849 4894 1559 1330 856 4895 1571 1342 850 4896 1562 1333 858 4897 1576 1347 851 4898 1564 1335 858 4899 1576 1347 850 4900 1562 1333 857 4901 1574 1345 859 4902 1578 1349 852 4903 1566 1337 858 4904 1576 1347 858 4905 1576 1347 852 4906 1566 1337 851 4907 1564 1335 860 4908 1579 1350 853 4909 1567 1338 859 4910 1578 1349 859 4911 1578 1349 853 4912 1567 1338 852 4913 1566 1337 861 4914 1581 1352 854 4915 1569 1340 860 4916 1579 1350 860 4917 1579 1350 854 4918 1569 1340 853 4919 1567 1338 854 4920 1569 1340 861 4921 1581 1352 855 4922 1570 1341 855 4923 1570 1341 861 4924 1581 1352 862 4925 1582 1353 862 4926 1572 1353 863 4927 1583 1354 856 4928 1571 1342 863 4929 1583 1354 862 4930 1572 1353 870 4931 1584 1365 856 4932 1571 1342 864 4933 1586 1357 857 4934 1574 1345 864 4935 1586 1357 856 4936 1571 1342 863 4937 1583 1354 857 4938 1574 1345 865 4939 1588 1359 858 4940 1576 1347 865 4941 1588 1359 857 4942 1574 1345 864 4943 1586 1357 866 4944 1590 1361 859 4945 1578 1349 865 4946 1588 1359 865 4947 1588 1359 859 4948 1578 1349 858 4949 1576 1347 867 4950 1591 1362 860 4951 1579 1350 866 4952 1590 1361 866 4953 1590 1361 860 4954 1579 1350 859 4955 1578 1349 868 4956 1592 1363 860 4957 1579 1350 867 4958 1591 1362 860 4959 1579 1350 868 4960 1592 1363 861 4961 1581 1352 861 4962 1581 1352 868 4963 1592 1363 869 4964 1593 1364 861 4965 1581 1352 869 4966 1593 1364 862 4967 1582 1353 862 4968 1582 1353 869 4969 1593 1364 870 4970 1594 1365 813 4971 1488 1269 877 4972 1596 1377 807 4973 1487 1258 807 4974 1487 1258 877 4975 1596 1377 871 4976 1595 1366 872 4977 1598 1369 808 4978 1490 1261 871 4979 1595 1366 808 4980 1490 1261 807 4981 1487 1258 871 4982 1595 1366 873 4983 1600 1371 809 4984 1492 1263 872 4985 1598 1369 809 4986 1492 1263 808 4987 1490 1261 872 4988 1598 1369 809 4989 1492 1263 873 4990 1600 1371 874 4991 1602 1373 874 4992 1602 1373 810 4993 1494 1265 809 4994 1492 1263 810 4995 1494 1265 874 4996 1602 1373 875 4997 1603 1374 875 4998 1603 1374 811 4999 1495 1266 810 5000 1494 1265 811 5001 1495 1266 875 5002 1603 1374 876 5003 1605 1376 876 5004 1605 1376 812 5005 1497 1268 811 5006 1495 1266 812 5007 1497 1268 877 5008 1606 1377 813 5009 1498 1269 812 5010 1497 1268 876 5011 1605 1376 877 5012 1606 1377 871 5013 1595 1366 877 5014 1596 1377 814 5015 1499 1270 871 5016 1595 1366 814 5017 1499 1270 816 5018 1503 1274 816 5019 1503 1274 818 5020 1507 1278 872 5021 1598 1369 816 5022 1503 1274 872 5023 1598 1369 871 5024 1595 1366 820 5025 1511 1282 873 5026 1600 1371 818 5027 1507 1278 818 5028 1507 1278 873 5029 1600 1371 872 5030 1598 1369 873 5031 1600 1371 820 5032 1511 1282 821 5033 1513 1284 821 5034 1513 1284 874 5035 1602 1373 873 5036 1600 1371 874 5037 1602 1373 824 5038 1517 1288 875 5039 1603 1374 824 5040 1517 1288 874 5041 1602 1373 821 5042 1513 1284 875 5043 1603 1374 825 5044 1519 1290 876 5045 1605 1376 825 5046 1519 1290 875 5047 1603 1374 824 5048 1517 1288 877 5049 1606 1377 876 5050 1605 1376 814 5051 1623 1270 876 5052 1605 1376 825 5053 1519 1290 814 5054 1623 1270 878 5055 1632 1378 880 5056 1633 1380 879 5057 1635 1379 880 5058 1633 1380 881 5059 1634 1381 879 5060 1635 1379 884 5061 1639 1384 883 5062 1637 1383 885 5063 1638 1385 884 5064 1639 1384 882 5065 1636 1382 883 5066 1637 1383 889 5067 1647 1389 883 5068 1637 1383 882 5069 1636 1382 893 5070 1643 1393 890 5071 1640 1390 892 5072 1642 1392 892 5073 1642 1392 890 5074 1640 1390 891 5075 1641 1391 879 5076 1651 1379 881 5077 1650 1381 885 5078 1654 1385 885 5079 1654 1385 883 5080 1653 1383 879 5081 1651 1379 881 5082 1665 1381 880 5083 1664 1380 884 5084 1667 1384 881 5085 1665 1381 884 5086 1667 1384 885 5087 1666 1385 880 5088 1649 1380 878 5089 1648 1378 884 5090 1655 1384 884 5091 1655 1384 878 5092 1648 1378 882 5093 1652 1382 879 5094 1635 1379 890 5095 1656 1390 886 5096 1645 1386 890 5097 1656 1390 879 5098 1635 1379 887 5099 1644 1387 879 5100 1635 1379 886 5101 1645 1386 878 5102 1632 1378 879 5103 1651 1379 888 5104 1646 1388 887 5105 1660 1387 888 5106 1646 1388 879 5107 1651 1379 883 5108 1653 1383 883 5109 1637 1383 893 5110 1659 1393 888 5111 1662 1388 893 5112 1659 1393 883 5113 1637 1383 889 5114 1647 1389 882 5115 1652 1382 886 5116 1668 1386 889 5117 1669 1389 886 5118 1668 1386 882 5119 1652 1382 878 5120 1648 1378 890 5121 1656 1390 887 5122 1644 1387 891 5123 1657 1391 888 5124 1646 1388 892 5125 1642 1392 887 5126 1660 1387 887 5127 1660 1387 892 5128 1642 1392 891 5129 1641 1391 888 5130 1662 1388 893 5131 1659 1393 892 5132 1658 1392 893 5133 1643 1393 889 5134 1663 1389 886 5135 1661 1386 893 5136 1643 1393 886 5137 1661 1386 890 5138 1640 1390 895 5139 1671 1395 897 5140 1673 1397 896 5141 1672 1396 895 5142 1671 1395 894 5143 1670 1394 897 5144 1673 1397 907 5145 1695 1407 897 5146 1673 1397 894 5147 1670 1394 898 5148 1674 1398 901 5149 1677 1401 899 5150 1675 1399 901 5151 1677 1401 900 5152 1676 1400 899 5153 1675 1399 903 5154 1679 1403 902 5155 1678 1402 904 5156 1680 1404 902 5157 1678 1402 905 5158 1681 1405 904 5159 1680 1404 896 5160 1683 1396 897 5161 1682 1397 900 5162 1684 1400 900 5163 1684 1400 897 5164 1682 1397 899 5165 1685 1399 895 5166 1687 1395 896 5167 1686 1396 901 5168 1688 1401 900 5169 1689 1400 901 5170 1688 1401 896 5171 1686 1396 894 5172 1691 1394 895 5173 1690 1395 901 5174 1693 1401 901 5175 1693 1401 898 5176 1692 1398 894 5177 1691 1394 897 5178 1673 1397 902 5179 1703 1402 906 5180 1694 1406 902 5181 1703 1402 897 5182 1673 1397 907 5183 1695 1407 908 5184 1696 1408 899 5185 1685 1399 897 5186 1682 1397 908 5187 1696 1408 897 5188 1682 1397 906 5189 1697 1406 909 5190 1698 1409 898 5191 1674 1398 899 5192 1675 1399 899 5193 1675 1399 905 5194 1704 1405 909 5195 1698 1409 905 5196 1704 1405 899 5197 1675 1399 908 5198 1699 1408 898 5199 1692 1398 909 5200 1701 1409 894 5201 1691 1394 907 5202 1700 1407 894 5203 1691 1394 909 5204 1701 1409 906 5205 1694 1406 902 5206 1703 1402 903 5207 1702 1403 906 5208 1697 1406 904 5209 1680 1404 908 5210 1696 1408 904 5211 1680 1404 906 5212 1697 1406 903 5213 1679 1403 905 5214 1704 1405 908 5215 1699 1408 904 5216 1705 1404 909 5217 1706 1409 905 5218 1681 1405 907 5219 1707 1407 902 5220 1678 1402 907 5221 1707 1407 905 5222 1681 1405 910 5223 1708 1410 912 5224 1709 1412 913 5225 1710 1413 910 5226 1708 1410 913 5227 1710 1413 911 5228 1711 1411 916 5229 1719 1416 914 5230 1716 1414 917 5231 1718 1417 915 5232 1717 1415 917 5233 1718 1417 914 5234 1716 1414 915 5235 1713 1415 914 5236 1712 1414 910 5237 1708 1410 915 5238 1713 1415 910 5239 1708 1410 911 5240 1711 1411 917 5241 1727 1417 915 5242 1726 1415 911 5243 1725 1411 917 5244 1727 1417 911 5245 1725 1411 913 5246 1724 1413 916 5247 1715 1416 917 5248 1714 1417 913 5249 1710 1413 916 5250 1715 1416 913 5251 1710 1413 912 5252 1709 1412 912 5253 1721 1412 914 5254 1722 1414 916 5255 1723 1416 914 5256 1722 1414 912 5257 1721 1412 910 5258 1720 1410 920 5259 1729 1420 921 5260 1730 1421 918 5261 1728 1418 918 5262 1728 1418 921 5263 1730 1421 919 5264 1731 1419 922 5265 1732 1422 923 5266 1733 1423 925 5267 1734 1425 925 5268 1734 1425 924 5269 1735 1424 922 5270 1732 1422 923 5271 1737 1423 922 5272 1736 1422 918 5273 1728 1418 923 5274 1737 1423 918 5275 1728 1418 919 5276 1731 1419 924 5277 1739 1424 925 5278 1738 1425 921 5279 1730 1421 924 5280 1739 1424 921 5281 1730 1421 920 5282 1729 1420 928 5283 1741 1428 929 5284 1742 1429 926 5285 1740 1426 926 5286 1740 1426 929 5287 1742 1429 927 5288 1743 1427 930 5289 1744 1430 931 5290 1745 1431 933 5291 1746 1433 933 5292 1746 1433 932 5293 1747 1432 930 5294 1744 1430 926 5295 1740 1426 931 5296 1749 1431 930 5297 1748 1430 931 5298 1749 1431 926 5299 1740 1426 927 5300 1743 1427 929 5301 1742 1429 932 5302 1751 1432 933 5303 1750 1433 932 5304 1751 1432 929 5305 1742 1429 928 5306 1741 1428 950 5307 1755 1450 934 5308 1752 1434 936 5309 1754 1436 936 5310 1754 1436 934 5311 1752 1434 935 5312 1753 1435 936 5313 1754 1436 935 5314 1753 1435 938 5315 1757 1438 938 5316 1757 1438 935 5317 1753 1435 937 5318 1756 1437 938 5319 1757 1438 937 5320 1756 1437 940 5321 1759 1440 940 5322 1759 1440 937 5323 1756 1437 939 5324 1758 1439 940 5325 1759 1440 939 5326 1758 1439 942 5327 1761 1442 942 5328 1761 1442 939 5329 1758 1439 941 5330 1760 1441 942 5331 1761 1442 941 5332 1760 1441 944 5333 1763 1444 944 5334 1763 1444 941 5335 1760 1441 943 5336 1762 1443 944 5337 1763 1444 943 5338 1762 1443 946 5339 1765 1446 946 5340 1765 1446 943 5341 1762 1443 945 5342 1764 1445 946 5343 1771 1446 945 5344 1770 1445 948 5345 1767 1448 948 5346 1767 1448 945 5347 1770 1445 947 5348 1766 1447 948 5349 1767 1448 947 5350 1766 1447 951 5351 1769 1451 951 5352 1769 1451 947 5353 1766 1447 949 5354 1768 1449 951 5355 1769 1451 949 5356 1768 1449 950 5357 1755 1450 950 5358 1755 1450 949 5359 1768 1449 934 5360 1752 1434 955 5361 1775 1455 952 5362 1772 1452 954 5363 1774 1454 954 5364 1774 1454 952 5365 1772 1452 953 5366 1773 1453 954 5367 1774 1454 956 5368 1776 1456 957 5369 1777 1457 956 5370 1776 1456 954 5371 1774 1454 953 5372 1773 1453 958 5373 1778 1458 959 5374 1779 1459 957 5375 1777 1457 958 5376 1778 1458 957 5377 1777 1457 956 5378 1776 1456 960 5379 1780 1460 961 5380 1781 1461 959 5381 1779 1459 960 5382 1780 1460 959 5383 1779 1459 958 5384 1778 1458 962 5385 1782 1462 963 5386 1783 1463 960 5387 1780 1460 960 5388 1780 1460 963 5389 1783 1463 961 5390 1781 1461 963 5391 1783 1463 962 5392 1782 1462 964 5393 1784 1464 964 5394 1784 1464 965 5395 1785 1465 963 5396 1783 1463 964 5397 1784 1464 967 5398 1787 1467 965 5399 1785 1465 967 5400 1787 1467 964 5401 1784 1464 966 5402 1786 1466 966 5403 1786 1466 969 5404 1789 1469 967 5405 1787 1467 969 5406 1789 1469 966 5407 1786 1466 968 5408 1788 1468 969 5409 1789 1469 968 5410 1788 1468 955 5411 1791 1455 955 5412 1791 1455 968 5413 1788 1468 952 5414 1790 1452 973 5415 1795 1473 970 5416 1792 1470 972 5417 1794 1472 971 5418 1793 1471 972 5419 1794 1472 970 5420 1792 1470 972 5421 1794 1472 971 5422 1793 1471 975 5423 1797 1475 974 5424 1796 1474 975 5425 1797 1475 971 5426 1793 1471 975 5427 1797 1475 974 5428 1796 1474 977 5429 1799 1477 976 5430 1798 1476 977 5431 1799 1477 974 5432 1796 1474 977 5433 1799 1477 976 5434 1798 1476 979 5435 1801 1479 978 5436 1800 1478 979 5437 1801 1479 976 5438 1798 1476 979 5439 1801 1479 980 5440 1802 1480 981 5441 1803 1481 980 5442 1802 1480 979 5443 1801 1479 978 5444 1800 1478 982 5445 1804 1482 983 5446 1805 1483 981 5447 1803 1481 982 5448 1804 1482 981 5449 1803 1481 980 5450 1802 1480 982 5451 1804 1482 985 5452 1807 1485 983 5453 1805 1483 985 5454 1807 1485 982 5455 1804 1482 984 5456 1806 1484 985 5457 1807 1485 984 5458 1806 1484 986 5459 1808 1486 985 5460 1807 1485 986 5461 1808 1486 987 5462 1809 1487 987 5463 1809 1487 986 5464 1808 1486 973 5465 1811 1473 970 5466 1810 1470 973 5467 1811 1473 986 5468 1808 1486 999 5469 1814 1499 1003 5470 1815 1503 998 5471 1813 1498 998 5472 1813 1498 1003 5473 1815 1503 1002 5474 1812 1502 995 5475 1817 1495 996 5476 1819 1496 994 5477 1816 1494 996 5478 1819 1496 995 5479 1817 1495 997 5480 1818 1497 997 5481 1818 1497 998 5482 1813 1498 996 5483 1819 1496 998 5484 1813 1498 997 5485 1818 1497 999 5486 1814 1499 1004 5487 1820 1504 1005 5488 1821 1505 1010 5489 1822 1510 1010 5490 1822 1510 1011 5491 1823 1511 1004 5492 1820 1504 1018 5493 1827 1518 1019 5494 1824 1519 1013 5495 1826 1513 1019 5496 1824 1519 1012 5497 1825 1512 1013 5498 1826 1513 1016 5499 1829 1516 1017 5500 1830 1517 1015 5501 1828 1515 1015 5502 1828 1515 1017 5503 1830 1517 1014 5504 1831 1514 1006 5505 1833 1506 1007 5506 1834 1507 1008 5507 1835 1508 1008 5508 1835 1508 1009 5509 1832 1509 1006 5510 1833 1506 1017 5511 1830 1517 1018 5512 1827 1518 1014 5513 1831 1514 1014 5514 1831 1514 1018 5515 1827 1518 1013 5516 1826 1513 1005 5517 1821 1505 1006 5518 1833 1506 1009 5519 1832 1509 1009 5520 1832 1509 1010 5521 1822 1510 1005 5522 1821 1505 1000 5523 1836 1500 992 5524 1837 1492 1004 5525 1820 1504 1004 5526 1820 1504 992 5527 1837 1492 1005 5528 1821 1505 992 5529 1837 1492 991 5530 1838 1491 1005 5531 1821 1505 1006 5532 1833 1506 1005 5533 1821 1505 991 5534 1838 1491 991 5535 1838 1491 988 5536 1839 1488 1006 5537 1833 1506 1007 5538 1834 1507 1006 5539 1833 1506 988 5540 1839 1488 994 5541 1846 1494 1008 5542 1863 1508 1007 5543 1862 1507 1007 5544 1862 1507 988 5545 1865 1488 994 5546 1846 1494 1009 5547 1854 1509 1008 5548 1855 1508 994 5549 1816 1494 1009 5550 1854 1509 994 5551 1816 1494 996 5552 1819 1496 1010 5553 1848 1510 1009 5554 1854 1509 996 5555 1819 1496 1010 5556 1848 1510 996 5557 1819 1496 998 5558 1813 1498 998 5559 1813 1498 1011 5560 1849 1511 1010 5561 1848 1510 1011 5562 1849 1511 998 5563 1813 1498 1002 5564 1812 1502 1003 5565 1815 1503 999 5566 1814 1499 1012 5567 1850 1512 1012 5568 1850 1512 999 5569 1814 1499 1013 5570 1851 1513 999 5571 1814 1499 997 5572 1818 1497 1013 5573 1851 1513 1014 5574 1853 1514 1013 5575 1851 1513 997 5576 1818 1497 997 5577 1818 1497 995 5578 1817 1495 1014 5579 1853 1514 1015 5580 1852 1515 1014 5581 1853 1514 995 5582 1817 1495 1015 5583 1860 1515 995 5584 1847 1495 1016 5585 1861 1516 989 5586 1840 1489 1016 5587 1861 1516 995 5588 1847 1495 1017 5589 1830 1517 1016 5590 1829 1516 989 5591 1866 1489 1017 5592 1830 1517 989 5593 1866 1489 990 5594 1841 1490 1018 5595 1827 1518 1017 5596 1830 1517 990 5597 1841 1490 1018 5598 1827 1518 990 5599 1841 1490 993 5600 1842 1493 993 5601 1842 1493 1019 5602 1824 1519 1018 5603 1827 1518 1019 5604 1824 1519 993 5605 1842 1493 1001 5606 1843 1501 1001 5607 1843 1501 992 5608 1837 1492 1000 5609 1836 1500 992 5610 1837 1492 1001 5611 1843 1501 993 5612 1842 1493 993 5613 1842 1493 990 5614 1841 1490 992 5615 1837 1492 992 5616 1837 1492 990 5617 1841 1490 991 5618 1838 1491 990 5619 1841 1490 989 5620 1866 1489 991 5621 1838 1491 991 5622 1838 1491 989 5623 1866 1489 988 5624 1839 1488 988 5625 1865 1488 995 5626 1847 1495 994 5627 1846 1494 995 5628 1847 1495 988 5629 1865 1488 989 5630 1840 1489 1001 5631 1867 1501 1002 5632 1844 1502 1003 5633 1845 1503 1002 5634 1844 1502 1001 5635 1867 1501 1000 5636 1864 1500 1019 5637 1858 1519 1003 5638 1845 1503 1012 5639 1859 1512 1019 5640 1858 1519 1001 5641 1867 1501 1003 5642 1845 1503 1011 5643 1857 1511 1002 5644 1844 1502 1004 5645 1856 1504 1000 5646 1864 1500 1004 5647 1856 1504 1002 5648 1844 1502

+
+
+
+ + + + + + + + + 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 1.0000001.000000 + 30.0000000.0000003.333333 + + + + + +
diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_PalletJackB_01/model.config b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_PalletJackB_01/model.config new file mode 100755 index 0000000..5838110 --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_PalletJackB_01/model.config @@ -0,0 +1,11 @@ + + + aws_robomaker_warehouse_PalletJackB_01 + 1.0 + model.sdf + + + + + + diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_PalletJackB_01/model.sdf b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_PalletJackB_01/model.sdf new file mode 100755 index 0000000..72547b0 --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_PalletJackB_01/model.sdf @@ -0,0 +1,46 @@ + + + + + + 2 + + 0.277 + 0 + 0 + 0.452 + 0 + 0.268 + + + + + + model://aws_robomaker_warehouse_PalletJackB_01/meshes/aws_robomaker_warehouse_PalletJackB_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + model://aws_robomaker_warehouse_PalletJackB_01/meshes/aws_robomaker_warehouse_PalletJackB_01_visual.DAE + + + 1 + + +1 + + diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_RoofB_01/materials/textures/aws_robomaker_warehouse_RoofB_01.png b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_RoofB_01/materials/textures/aws_robomaker_warehouse_RoofB_01.png new file mode 100755 index 0000000..9e4dd9c Binary files /dev/null and b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_RoofB_01/materials/textures/aws_robomaker_warehouse_RoofB_01.png differ diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_RoofB_01/meshes/aws_robomaker_warehouse_RoofB_01_collision.DAE b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_RoofB_01/meshes/aws_robomaker_warehouse_RoofB_01_collision.DAE new file mode 100755 index 0000000..558a316 --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_RoofB_01/meshes/aws_robomaker_warehouse_RoofB_01_collision.DAE @@ -0,0 +1,123 @@ + + + FBX COLLADA exporter2019-06-03T07:07:22Z2019-06-03T07:07:22ZZ_UP + + + + + +-686.312866 -88.698654 -1045.333374 +711.734131 -88.698654 -1045.333374 +-686.312866 21.739517 -1045.333496 +711.734131 21.739517 -1045.333496 +-686.312866 -88.698593 1045.333008 +711.734131 -88.698593 1045.333008 +-686.312866 21.739578 1045.333008 +711.734131 21.739578 1045.333008 + + + + + + + + + + + +0.000000 -0.000001 -1.000000 +0.000000 -0.000001 -1.000000 +0.000000 -0.000001 -1.000000 +0.000000 -0.000001 -1.000000 +0.000000 -0.000001 -1.000000 +0.000000 -0.000001 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 + + + + + + + + + + + +1.000000 0.000000 +0.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 + + + + + + + + + + + +

2 0 2 3 1 3 0 2 0 1 3 1 0 4 0 3 5 3 7 6 7 6 7 6 4 8 4 7 9 7 4 10 4 5 11 5 5 12 11 4 13 10 0 14 8 5 15 11 0 16 8 1 17 9 5 18 14 1 19 12 7 20 15 7 21 15 1 22 12 3 23 13 6 24 19 7 25 18 3 26 16 6 27 19 3 28 16 2 29 17 6 30 22 0 31 21 4 32 23 0 33 21 6 34 22 2 35 20

+
+
+
+ + + 1.000000 0.000000 0.000000 -12.710449 0.000000 -0.000000 -1.000000 0.000000 0.000000 1.000000 -0.000000 990.684692 0.000000 0.000000 0.000000 1.0000001.000000 + 30.0000000.0000003.333333 + + + + + +
diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_RoofB_01/meshes/aws_robomaker_warehouse_RoofB_01_visual.DAE b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_RoofB_01/meshes/aws_robomaker_warehouse_RoofB_01_visual.DAE new file mode 100755 index 0000000..4cab933 --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_RoofB_01/meshes/aws_robomaker_warehouse_RoofB_01_visual.DAE @@ -0,0 +1,6734 @@ + + + FBX COLLADA exporter2019-06-03T07:06:51Z2019-06-03T07:06:51ZZ_UP + + + ../materials/textures/aws_robomaker_warehouse_RoofB_01.png + + + + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + +685.143066 1032.083740 901.985962 +699.023682 1045.333252 901.985962 +699.023682 1045.333252 957.578247 +685.143066 1032.083740 957.578247 +-699.023315 1045.333130 901.985962 +-699.023315 1045.333130 957.578247 +-686.135193 1032.083618 901.985962 +-686.135132 1032.083618 957.578247 +685.143066 -1032.083618 901.985962 +685.143066 -1032.083618 957.578247 +699.023682 -1045.333130 901.985962 +699.023682 -1045.333130 957.578247 +-686.135132 -1032.083618 957.578247 +-686.135132 -1032.083618 901.985962 +-699.023315 -1045.333130 957.578247 +-699.023315 -1045.333130 901.985962 +-0.496077 1032.083740 901.985962 +-0.496077 1045.333252 901.985962 +6.160819 1045.333252 995.633362 +-7.152973 1045.333130 995.633362 +-7.152973 1032.083618 995.633362 +6.160819 1032.083740 995.633362 +6.160905 -1045.333130 995.633362 +-7.152886 -1045.333130 995.633362 +-0.495991 -1045.333130 901.985962 +6.160905 -1032.083618 995.633362 +-7.152886 -1032.083618 995.633362 +-0.495991 -1032.083618 901.985962 +697.140503 321.945190 953.600037 +697.140503 321.945190 901.985962 +697.140503 335.194702 953.600037 +6.811340 321.945190 980.703552 +6.811329 321.945190 913.078613 +6.811329 335.194702 913.078613 +6.811340 335.194702 980.703552 +6.811340 335.194702 991.655212 +687.966919 321.945190 943.338684 +687.966919 321.945190 913.078613 +697.140503 335.194702 901.985962 +687.966919 335.194702 913.078613 +687.966919 335.194702 943.338684 +171.275497 321.945190 913.078613 +341.564392 321.945190 913.078613 +523.502747 321.945190 913.078613 +171.284241 335.194702 971.681396 +341.573151 335.194702 962.340149 +523.493958 335.194702 952.360901 +523.494019 321.945190 952.360840 +353.205109 321.945190 961.702087 +171.284271 321.945190 971.681335 +523.502747 335.194702 913.078613 +341.564392 335.194702 913.078613 +171.275497 335.194702 913.078613 +177.100189 335.194702 982.293396 +517.677979 321.945190 963.569702 +182.924942 321.945190 913.078613 +353.213867 321.945190 913.078613 +511.853302 321.945190 913.078613 +347.389130 335.194702 901.985962 +182.916199 335.194702 971.043335 +353.205109 335.194702 961.702087 +511.862000 335.194702 952.998962 +511.862061 321.945190 952.998901 +341.573151 321.945190 962.340149 +182.916229 321.945190 971.043274 +347.389130 321.945190 901.985962 +511.853302 335.194702 913.078613 +353.213867 335.194702 913.078613 +182.924942 335.194702 913.078613 +517.677979 335.194702 963.569702 +177.100189 321.945190 982.293396 +160.662079 321.945190 913.078613 +176.974945 335.194702 901.986023 +17.425293 335.194702 980.121338 +677.352905 321.945190 943.920898 +517.803345 321.945190 901.986023 +534.116150 335.194702 913.078613 +193.162476 321.945190 913.078613 +501.615784 321.945190 913.078613 +534.116150 321.945190 913.078613 +517.803345 335.194702 901.986023 +331.334473 335.194702 962.901794 +363.443787 335.194702 961.140442 +677.352905 335.194702 943.920898 +363.443787 321.945190 961.140442 +331.334473 321.945190 962.901794 +17.425323 321.945190 980.121338 +176.974945 321.945190 901.986023 +501.615784 335.194702 913.078613 +193.162476 335.194702 913.078613 +160.662079 335.194702 913.078613 +347.389099 335.194702 972.931580 +347.389099 321.945190 972.931580 +6.811340 321.945190 991.655212 +0.000061 335.194702 980.703552 +0.000061 321.945190 980.703552 +0.000061 335.194702 901.985962 +0.000061 321.945190 991.655212 +0.000061 335.194702 902.739136 +0.000061 321.945190 901.985962 +-697.140381 321.945190 901.985962 +-697.140381 321.945190 953.600037 +-687.966797 321.945190 943.338684 +-687.966797 321.945190 913.078613 +-697.140381 335.194702 901.985962 +-697.140381 335.194702 953.600037 +-687.966797 335.194702 913.078613 +-687.966797 335.194702 943.338684 +-6.811218 321.945190 980.703552 +0.000061 321.945190 913.078613 +-6.811207 321.945190 913.078613 +-6.811207 335.194702 913.078613 +0.000061 335.194702 913.078613 +-6.811218 335.194702 980.703552 +-6.811218 321.945190 991.655212 +-176.974823 321.945190 901.986023 +-347.389008 321.945190 901.985962 +-341.564270 321.945190 913.078613 +-193.162354 321.945190 913.078613 +-347.388977 335.194702 972.931580 +-331.334351 335.194702 962.901794 +-182.916077 335.194702 971.043335 +-177.100067 335.194702 982.293396 +-517.803223 321.945190 901.986023 +-347.389008 335.194702 901.985962 +-517.803223 335.194702 901.986023 +-347.388977 321.945190 972.931580 +-363.443665 321.945190 961.140442 +-511.861938 321.945190 952.998901 +-517.677856 321.945190 963.569702 +-353.213745 335.194702 913.078613 +-501.615662 335.194702 913.078613 +-534.116028 321.945190 913.078613 +-501.615662 321.945190 913.078613 +-353.213745 321.945190 913.078613 +-160.661957 321.945190 913.078613 +0.000061 321.945190 902.739136 +-677.352783 335.194702 943.920898 +-523.493835 335.194702 952.360901 +-517.677856 335.194702 963.569702 +-511.861877 335.194702 952.998962 +-363.443665 335.194702 961.140442 +-17.425171 335.194702 980.121338 +-6.811218 335.194702 991.655212 +-171.284119 335.194702 971.681396 +-176.974823 335.194702 901.986023 +-17.425201 321.945190 980.121338 +-171.284149 321.945190 971.681335 +-177.100067 321.945190 982.293396 +-182.916107 321.945190 971.043274 +-331.334351 321.945190 962.901794 +-677.352783 321.945190 943.920898 +-523.493896 321.945190 952.360840 +-160.661957 335.194702 913.078613 +-193.162354 335.194702 913.078613 +-341.564270 335.194702 913.078613 +-534.116028 335.194702 913.078613 +-523.502625 321.945190 913.078613 +-511.853180 321.945190 913.078613 +-182.924820 321.945190 913.078613 +-171.275375 321.945190 913.078613 +-353.204987 335.194702 961.702087 +-341.573029 335.194702 962.340149 +-353.204987 321.945190 961.702087 +-341.573029 321.945190 962.340149 +-182.924820 335.194702 913.078613 +-171.275375 335.194702 913.078613 +-523.502625 335.194702 913.078613 +-511.853180 335.194702 913.078613 +0.000061 335.194702 991.655212 +697.140503 -355.069092 953.600037 +697.140503 -355.069092 901.985962 +697.140503 -341.819580 953.600037 +6.811340 -355.069092 980.703552 +6.811329 -355.069092 913.078613 +6.811329 -341.819580 913.078613 +6.811340 -341.819580 980.703552 +6.811340 -341.819580 991.655212 +687.966919 -355.069092 943.338684 +687.966919 -355.069092 913.078613 +697.140503 -341.819580 901.985962 +687.966919 -341.819580 913.078613 +687.966919 -341.819580 943.338684 +171.275497 -355.069092 913.078613 +341.564392 -355.069092 913.078613 +523.502747 -355.069092 913.078613 +171.284241 -341.819580 971.681396 +341.573151 -341.819580 962.340149 +523.493958 -341.819580 952.360901 +523.494019 -355.069092 952.360840 +353.205109 -355.069092 961.702087 +171.284271 -355.069092 971.681335 +523.502747 -341.819580 913.078613 +341.564392 -341.819580 913.078613 +171.275497 -341.819580 913.078613 +177.100189 -341.819580 982.293396 +517.677979 -355.069092 963.569702 +182.924942 -355.069092 913.078613 +353.213867 -355.069092 913.078613 +511.853302 -355.069092 913.078613 +347.389130 -341.819580 901.985962 +182.916199 -341.819580 971.043335 +353.205109 -341.819580 961.702087 +511.862000 -341.819580 952.998962 +511.862061 -355.069092 952.998901 +341.573151 -355.069092 962.340149 +182.916229 -355.069092 971.043274 +347.389130 -355.069092 901.985962 +511.853302 -341.819580 913.078613 +353.213867 -341.819580 913.078613 +182.924942 -341.819580 913.078613 +517.677979 -341.819580 963.569702 +177.100189 -355.069092 982.293396 +160.662079 -355.069092 913.078613 +176.974945 -341.819580 901.986023 +17.425293 -341.819580 980.121338 +677.352905 -355.069092 943.920898 +517.803345 -355.069092 901.986023 +534.116150 -341.819580 913.078613 +193.162476 -355.069092 913.078613 +501.615784 -355.069092 913.078613 +534.116150 -355.069092 913.078613 +517.803345 -341.819580 901.986023 +331.334473 -341.819580 962.901794 +363.443787 -341.819580 961.140442 +677.352905 -341.819580 943.920898 +363.443787 -355.069092 961.140442 +331.334473 -355.069092 962.901794 +17.425323 -355.069092 980.121338 +176.974945 -355.069092 901.986023 +501.615784 -341.819580 913.078613 +193.162476 -341.819580 913.078613 +160.662079 -341.819580 913.078613 +347.389099 -341.819580 972.931580 +347.389099 -355.069092 972.931580 +6.811340 -355.069092 991.655212 +0.000061 -341.819580 980.703552 +0.000061 -355.069092 980.703552 +0.000061 -341.819580 901.985962 +0.000061 -355.069092 991.655212 +0.000061 -341.819580 902.739136 +0.000061 -355.069092 901.985962 +-697.140381 -355.069092 901.985962 +-697.140381 -355.069092 953.600037 +-687.966797 -355.069092 943.338684 +-687.966797 -355.069092 913.078613 +-697.140381 -341.819580 901.985962 +-697.140381 -341.819580 953.600037 +-687.966797 -341.819580 913.078613 +-687.966797 -341.819580 943.338684 +-6.811218 -355.069092 980.703552 +0.000061 -355.069092 913.078613 +-6.811207 -355.069092 913.078613 +-6.811207 -341.819580 913.078613 +0.000061 -341.819580 913.078613 +-6.811218 -341.819580 980.703552 +-6.811218 -355.069092 991.655212 +-176.974823 -355.069092 901.986023 +-347.389008 -355.069092 901.985962 +-341.564270 -355.069092 913.078613 +-193.162354 -355.069092 913.078613 +-347.388977 -341.819580 972.931580 +-331.334351 -341.819580 962.901794 +-182.916077 -341.819580 971.043335 +-177.100067 -341.819580 982.293396 +-517.803223 -355.069092 901.986023 +-347.389008 -341.819580 901.985962 +-517.803223 -341.819580 901.986023 +-347.388977 -355.069092 972.931580 +-363.443665 -355.069092 961.140442 +-511.861938 -355.069092 952.998901 +-517.677856 -355.069092 963.569702 +-353.213745 -341.819580 913.078613 +-501.615662 -341.819580 913.078613 +-534.116028 -355.069092 913.078613 +-501.615662 -355.069092 913.078613 +-353.213745 -355.069092 913.078613 +-160.661957 -355.069092 913.078613 +0.000061 -355.069092 902.739136 +-677.352783 -341.819580 943.920898 +-523.493835 -341.819580 952.360901 +-517.677856 -341.819580 963.569702 +-511.861877 -341.819580 952.998962 +-363.443665 -341.819580 961.140442 +-17.425171 -341.819580 980.121338 +-6.811218 -341.819580 991.655212 +-171.284119 -341.819580 971.681396 +-176.974823 -341.819580 901.986023 +-17.425201 -355.069092 980.121338 +-171.284149 -355.069092 971.681335 +-177.100067 -355.069092 982.293396 +-182.916107 -355.069092 971.043274 +-331.334351 -355.069092 962.901794 +-677.352783 -355.069092 943.920898 +-523.493896 -355.069092 952.360840 +-160.661957 -341.819580 913.078613 +-193.162354 -341.819580 913.078613 +-341.564270 -341.819580 913.078613 +-534.116028 -341.819580 913.078613 +-523.502625 -355.069092 913.078613 +-511.853180 -355.069092 913.078613 +-182.924820 -355.069092 913.078613 +-171.275375 -355.069092 913.078613 +-353.204987 -341.819580 961.702087 +-341.573029 -341.819580 962.340149 +-353.204987 -355.069092 961.702087 +-341.573029 -355.069092 962.340149 +-182.924820 -341.819580 913.078613 +-171.275375 -341.819580 913.078613 +-523.502625 -341.819580 913.078613 +-511.853180 -341.819580 913.078613 +0.000061 -341.819580 991.655212 +697.140503 -1032.083496 953.600037 +697.140503 -1032.083496 901.985962 +697.140503 -1018.833984 953.600037 +6.811340 -1032.083496 980.703552 +6.811329 -1032.083496 913.078613 +6.811329 -1018.833984 913.078613 +6.811340 -1018.833984 980.703552 +6.811340 -1018.833984 991.655212 +687.966919 -1032.083496 943.338684 +687.966919 -1032.083496 913.078613 +697.140503 -1018.833984 901.985962 +687.966919 -1018.833984 913.078613 +687.966919 -1018.833984 943.338684 +171.275497 -1032.083496 913.078613 +341.564392 -1032.083496 913.078613 +523.502747 -1032.083496 913.078613 +171.284241 -1018.833984 971.681396 +341.573151 -1018.833984 962.340149 +523.493958 -1018.833984 952.360901 +523.494019 -1032.083496 952.360840 +353.205109 -1032.083496 961.702087 +171.284271 -1032.083496 971.681335 +523.502747 -1018.833984 913.078613 +341.564392 -1018.833984 913.078613 +171.275497 -1018.833984 913.078613 +177.100189 -1018.833984 982.293396 +517.677979 -1032.083496 963.569702 +182.924942 -1032.083496 913.078613 +353.213867 -1032.083496 913.078613 +511.853302 -1032.083496 913.078613 +347.389130 -1018.833984 901.985962 +182.916199 -1018.833984 971.043335 +353.205109 -1018.833984 961.702087 +511.862000 -1018.833984 952.998962 +511.862061 -1032.083496 952.998901 +341.573151 -1032.083496 962.340149 +182.916229 -1032.083496 971.043274 +347.389130 -1032.083496 901.985962 +511.853302 -1018.833984 913.078613 +353.213867 -1018.833984 913.078613 +182.924942 -1018.833984 913.078613 +517.677979 -1018.833984 963.569702 +177.100189 -1032.083496 982.293396 +160.662079 -1032.083496 913.078613 +176.974945 -1018.833984 901.986023 +17.425293 -1018.833984 980.121338 +677.352905 -1032.083496 943.920898 +517.803345 -1032.083496 901.986023 +534.116150 -1018.833984 913.078613 +193.162476 -1032.083496 913.078613 +501.615784 -1032.083496 913.078613 +534.116150 -1032.083496 913.078613 +517.803345 -1018.833984 901.986023 +331.334473 -1018.833984 962.901794 +363.443787 -1018.833984 961.140442 +677.352905 -1018.833984 943.920898 +363.443787 -1032.083496 961.140442 +331.334473 -1032.083496 962.901794 +17.425323 -1032.083496 980.121338 +176.974945 -1032.083496 901.986023 +501.615784 -1018.833984 913.078613 +193.162476 -1018.833984 913.078613 +160.662079 -1018.833984 913.078613 +347.389099 -1018.833984 972.931580 +347.389099 -1032.083496 972.931580 +6.811340 -1032.083496 991.655212 +0.000061 -1018.833984 980.703552 +0.000061 -1032.083496 980.703552 +0.000061 -1018.833984 901.985962 +0.000061 -1032.083496 991.655212 +0.000061 -1018.833984 902.739136 +0.000061 -1032.083496 901.985962 +-697.140381 -1032.083496 901.985962 +-697.140381 -1032.083496 953.600037 +-687.966797 -1032.083496 943.338684 +-687.966797 -1032.083496 913.078613 +-697.140381 -1018.833984 901.985962 +-697.140381 -1018.833984 953.600037 +-687.966797 -1018.833984 913.078613 +-687.966797 -1018.833984 943.338684 +-6.811218 -1032.083496 980.703552 +0.000061 -1032.083496 913.078613 +-6.811207 -1032.083496 913.078613 +-6.811207 -1018.833984 913.078613 +0.000061 -1018.833984 913.078613 +-6.811218 -1018.833984 980.703552 +-6.811218 -1032.083496 991.655212 +-176.974823 -1032.083496 901.986023 +-347.389008 -1032.083496 901.985962 +-341.564270 -1032.083496 913.078613 +-193.162354 -1032.083496 913.078613 +-347.388977 -1018.833984 972.931580 +-331.334351 -1018.833984 962.901794 +-182.916077 -1018.833984 971.043335 +-177.100067 -1018.833984 982.293396 +-517.803223 -1032.083496 901.986023 +-347.389008 -1018.833984 901.985962 +-517.803223 -1018.833984 901.986023 +-347.388977 -1032.083496 972.931580 +-363.443665 -1032.083496 961.140442 +-511.861938 -1032.083496 952.998901 +-517.677856 -1032.083496 963.569702 +-353.213745 -1018.833984 913.078613 +-501.615662 -1018.833984 913.078613 +-534.116028 -1032.083496 913.078613 +-501.615662 -1032.083496 913.078613 +-353.213745 -1032.083496 913.078613 +-160.661957 -1032.083496 913.078613 +0.000061 -1032.083496 902.739136 +-677.352783 -1018.833984 943.920898 +-523.493835 -1018.833984 952.360901 +-517.677856 -1018.833984 963.569702 +-511.861877 -1018.833984 952.998962 +-363.443665 -1018.833984 961.140442 +-17.425171 -1018.833984 980.121338 +-6.811218 -1018.833984 991.655212 +-171.284119 -1018.833984 971.681396 +-176.974823 -1018.833984 901.986023 +-17.425201 -1032.083496 980.121338 +-171.284149 -1032.083496 971.681335 +-177.100067 -1032.083496 982.293396 +-182.916107 -1032.083496 971.043274 +-331.334351 -1032.083496 962.901794 +-677.352783 -1032.083496 943.920898 +-523.493896 -1032.083496 952.360840 +-160.661957 -1018.833984 913.078613 +-193.162354 -1018.833984 913.078613 +-341.564270 -1018.833984 913.078613 +-534.116028 -1018.833984 913.078613 +-523.502625 -1032.083496 913.078613 +-511.853180 -1032.083496 913.078613 +-182.924820 -1032.083496 913.078613 +-171.275375 -1032.083496 913.078613 +-353.204987 -1018.833984 961.702087 +-341.573029 -1018.833984 962.340149 +-353.204987 -1032.083496 961.702087 +-341.573029 -1032.083496 962.340149 +-182.924820 -1018.833984 913.078613 +-171.275375 -1018.833984 913.078613 +-523.502625 -1018.833984 913.078613 +-511.853180 -1018.833984 913.078613 +0.000061 -1018.833984 991.655212 +697.140503 1018.834229 953.600037 +697.140503 1018.834229 901.985962 +697.140503 1032.083740 953.600037 +6.811340 1018.834229 980.703552 +6.811329 1018.834229 913.078613 +6.811329 1032.083740 913.078613 +6.811340 1032.083740 980.703552 +6.811340 1032.083740 991.655212 +687.966919 1018.834229 943.338684 +687.966919 1018.834229 913.078613 +697.140503 1032.083740 901.985962 +687.966919 1032.083740 913.078613 +687.966919 1032.083740 943.338684 +171.275497 1018.834229 913.078613 +341.564392 1018.834229 913.078613 +523.502747 1018.834229 913.078613 +171.284241 1032.083740 971.681396 +341.573151 1032.083740 962.340149 +523.493958 1032.083740 952.360901 +523.494019 1018.834229 952.360840 +353.205109 1018.834229 961.702087 +171.284271 1018.834229 971.681335 +523.502747 1032.083740 913.078613 +341.564392 1032.083740 913.078613 +171.275497 1032.083740 913.078613 +177.100189 1032.083740 982.293396 +517.677979 1018.834229 963.569702 +182.924942 1018.834229 913.078613 +353.213867 1018.834229 913.078613 +511.853302 1018.834229 913.078613 +347.389130 1032.083740 901.985962 +182.916199 1032.083740 971.043335 +353.205109 1032.083740 961.702087 +511.862000 1032.083740 952.998962 +511.862061 1018.834229 952.998901 +341.573151 1018.834229 962.340149 +182.916229 1018.834229 971.043274 +347.389130 1018.834229 901.985962 +511.853302 1032.083740 913.078613 +353.213867 1032.083740 913.078613 +182.924942 1032.083740 913.078613 +517.677979 1032.083740 963.569702 +177.100189 1018.834229 982.293396 +160.662079 1018.834229 913.078613 +176.974945 1032.083740 901.986023 +17.425293 1032.083740 980.121338 +677.352905 1018.834229 943.920898 +517.803345 1018.834229 901.986023 +534.116150 1032.083740 913.078613 +193.162476 1018.834229 913.078613 +501.615784 1018.834229 913.078613 +534.116150 1018.834229 913.078613 +517.803345 1032.083740 901.986023 +331.334473 1032.083740 962.901794 +363.443787 1032.083740 961.140442 +677.352905 1032.083740 943.920898 +363.443787 1018.834229 961.140442 +331.334473 1018.834229 962.901794 +17.425323 1018.834229 980.121338 +176.974945 1018.834229 901.986023 +501.615784 1032.083740 913.078613 +193.162476 1032.083740 913.078613 +160.662079 1032.083740 913.078613 +347.389099 1032.083740 972.931580 +347.389099 1018.834229 972.931580 +6.811340 1018.834229 991.655212 +0.000061 1032.083740 980.703552 +0.000061 1018.834229 980.703552 +0.000061 1032.083740 901.985962 +0.000061 1018.834229 991.655212 +0.000061 1032.083740 902.739136 +0.000061 1018.834229 901.985962 +-697.140381 1018.834229 901.985962 +-697.140381 1018.834229 953.600037 +-687.966797 1018.834229 943.338684 +-687.966797 1018.834229 913.078613 +-697.140381 1032.083740 901.985962 +-697.140381 1032.083740 953.600037 +-687.966797 1032.083740 913.078613 +-687.966797 1032.083740 943.338684 +-6.811218 1018.834229 980.703552 +0.000061 1018.834229 913.078613 +-6.811207 1018.834229 913.078613 +-6.811207 1032.083740 913.078613 +0.000061 1032.083740 913.078613 +-6.811218 1032.083740 980.703552 +-6.811218 1018.834229 991.655212 +-176.974823 1018.834229 901.986023 +-347.389008 1018.834229 901.985962 +-341.564270 1018.834229 913.078613 +-193.162354 1018.834229 913.078613 +-347.388977 1032.083740 972.931580 +-331.334351 1032.083740 962.901794 +-182.916077 1032.083740 971.043335 +-177.100067 1032.083740 982.293396 +-517.803223 1018.834229 901.986023 +-347.389008 1032.083740 901.985962 +-517.803223 1032.083740 901.986023 +-347.388977 1018.834229 972.931580 +-363.443665 1018.834229 961.140442 +-511.861938 1018.834229 952.998901 +-517.677856 1018.834229 963.569702 +-353.213745 1032.083740 913.078613 +-501.615662 1032.083740 913.078613 +-534.116028 1018.834229 913.078613 +-501.615662 1018.834229 913.078613 +-353.213745 1018.834229 913.078613 +-160.661957 1018.834229 913.078613 +0.000061 1018.834229 902.739136 +-677.352783 1032.083740 943.920898 +-523.493835 1032.083740 952.360901 +-517.677856 1032.083740 963.569702 +-511.861877 1032.083740 952.998962 +-363.443665 1032.083740 961.140442 +-17.425171 1032.083740 980.121338 +-6.811218 1032.083740 991.655212 +-171.284119 1032.083740 971.681396 +-176.974823 1032.083740 901.986023 +-17.425201 1018.834229 980.121338 +-171.284149 1018.834229 971.681335 +-177.100067 1018.834229 982.293396 +-182.916107 1018.834229 971.043274 +-331.334351 1018.834229 962.901794 +-677.352783 1018.834229 943.920898 +-523.493896 1018.834229 952.360840 +-160.661957 1032.083740 913.078613 +-193.162354 1032.083740 913.078613 +-341.564270 1032.083740 913.078613 +-534.116028 1032.083740 913.078613 +-523.502625 1018.834229 913.078613 +-511.853180 1018.834229 913.078613 +-182.924820 1018.834229 913.078613 +-171.275375 1018.834229 913.078613 +-353.204987 1032.083740 961.702087 +-341.573029 1032.083740 962.340149 +-353.204987 1018.834229 961.702087 +-341.573029 1018.834229 962.340149 +-182.924820 1032.083740 913.078613 +-171.275375 1032.083740 913.078613 +-523.502625 1032.083740 913.078613 +-511.853180 1032.083740 913.078613 +0.000061 1032.083740 991.655212 +699.023682 -1045.333130 974.369080 +699.023682 1045.333130 974.369080 +-0.495991 1045.333130 1012.424255 +-0.495991 -1045.333130 1012.424255 +-699.023315 1045.333130 974.369080 +-699.023315 -1045.333130 974.369080 +699.023682 -1045.333130 953.385437 +699.023682 1045.333130 953.385437 +-0.495991 1045.333130 991.440613 +-0.495991 -1045.333130 991.440613 +-699.023315 1045.333130 953.385437 +-699.023315 -1045.333130 953.385437 +279.078979 518.069458 973.521423 +667.904297 518.069458 951.750305 +279.078979 561.112915 973.521423 +667.904297 561.112915 951.750305 +279.078979 518.069458 983.949829 +667.904297 518.069458 962.178711 +279.078979 561.112915 983.949829 +667.904297 561.112915 962.178711 +279.078979 539.591187 966.960938 +667.904297 539.591187 945.189819 +667.904297 539.591187 962.178711 +279.078979 539.591187 983.949829 +-279.078979 518.069458 973.521423 +-279.078979 539.591187 966.960938 +-667.904358 539.591187 945.189819 +-667.904358 518.069458 951.750305 +-667.904358 518.069458 962.178711 +-279.078979 518.069458 983.949829 +-667.904358 539.591187 962.178711 +-667.904358 561.112915 951.750305 +-279.078979 561.112915 973.521423 +-279.078979 561.112915 983.949829 +-667.904358 561.112915 962.178711 +-279.078979 539.591187 983.949829 +279.078979 -518.069458 973.521423 +279.078979 -539.591187 966.960938 +667.904297 -539.591187 945.189819 +667.904297 -518.069458 951.750305 +667.904297 -518.069458 962.178711 +279.078979 -518.069458 983.949829 +667.904297 -539.591187 962.178711 +667.904297 -561.112915 951.750305 +279.078979 -561.112915 973.521423 +279.078979 -561.112915 983.949829 +667.904297 -561.112915 962.178711 +279.078979 -539.591187 983.949829 +-279.078979 -518.069458 973.521423 +-667.904358 -518.069458 951.750305 +-667.904358 -539.591187 945.189819 +-279.078979 -539.591187 966.960938 +-279.078979 -518.069458 983.949829 +-667.904358 -518.069458 962.178711 +-667.904358 -539.591187 962.178711 +-667.904358 -561.112915 951.750305 +-667.904358 -561.112915 962.178711 +-279.078979 -561.112915 983.949829 +-279.078979 -561.112915 973.521423 +-279.078979 -539.591187 983.949829 +234.788025 1040.947998 975.133057 +261.869507 1040.947998 975.133057 +234.788025 1040.947632 982.615479 +261.869507 1040.947632 982.615479 +234.788025 -1039.386475 975.132690 +261.869507 -1039.386475 975.132690 +234.788025 -1039.387085 982.615112 +261.869507 -1039.387085 982.615112 +-234.788025 1040.947998 975.133057 +-234.788025 1040.947632 982.615479 +-261.869507 1040.947632 982.615479 +-261.869507 1040.947998 975.133057 +-234.788025 -1039.386475 975.132690 +-261.869507 -1039.386475 975.132690 +-261.869507 -1039.387085 982.615112 +-234.788025 -1039.387085 982.615112 + + + + + + + + + + + +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.000004 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.000004 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.000000 1.000000 0.000000 +-0.000005 1.000000 0.000001 +-0.000004 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -1.000000 -0.000000 +0.000004 -1.000000 -0.000000 +0.000005 -1.000000 -0.000001 +1.000000 0.000000 -0.000001 +1.000000 0.000000 -0.000001 +1.000000 0.000000 -0.000001 +1.000000 0.000000 -0.000001 +1.000000 0.000000 -0.000001 +1.000000 0.000000 -0.000001 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000005 1.000000 0.000001 +-0.000000 1.000000 0.000001 +-0.000000 1.000000 0.000001 +-0.000000 1.000000 0.000001 +-0.000005 1.000000 0.000001 +-0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000004 -1.000000 -0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000004 -1.000000 -0.000000 +0.000000 -1.000000 -0.000000 +0.000000 -1.000000 -0.000001 +0.000005 -1.000000 -0.000001 +0.000000 -1.000000 -0.000001 +0.000005 -1.000000 -0.000001 +0.000000 -1.000000 -0.000001 +0.000000 -1.000000 -0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 -0.000001 0.000149 +-1.000000 -0.000001 0.000149 +-1.000000 -0.000001 0.000149 +-1.000000 -0.000001 0.000149 +-1.000000 -0.000001 0.000149 +-1.000000 -0.000001 0.000149 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-1.000000 0.000000 0.000178 +-1.000000 0.000000 0.000178 +-1.000000 0.000000 0.000178 +-1.000000 0.000000 0.000178 +-1.000000 0.000000 0.000178 +-1.000000 0.000000 0.000178 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +1.000000 0.000001 0.000151 +1.000000 0.000001 0.000151 +1.000000 0.000001 0.000151 +1.000000 0.000001 0.000151 +1.000000 0.000001 0.000151 +1.000000 0.000001 0.000151 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 -0.000002 0.000219 +-1.000000 -0.000002 0.000219 +-1.000000 -0.000002 0.000219 +-1.000000 -0.000002 0.000219 +-1.000000 -0.000002 0.000219 +-1.000000 -0.000002 0.000219 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +1.000000 0.000000 0.000180 +1.000000 0.000000 0.000180 +1.000000 0.000000 0.000180 +1.000000 0.000000 0.000180 +1.000000 0.000000 0.000180 +1.000000 0.000000 0.000180 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 0.000002 0.000223 +1.000000 0.000002 0.000223 +1.000000 0.000002 0.000223 +1.000000 0.000002 0.000223 +1.000000 0.000002 0.000223 +1.000000 0.000002 0.000223 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.399484 0.000000 0.916740 +0.399484 0.000000 0.916740 +0.399484 0.000000 0.916740 +0.399484 0.000000 0.916740 +0.399484 0.000000 0.916740 +0.399484 0.000000 0.916740 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.402393 0.000000 -0.915467 +-0.402393 0.000000 -0.915467 +-0.402393 0.000000 -0.915467 +-0.402393 0.000000 -0.915467 +-0.402393 0.000000 -0.915467 +-0.402393 0.000000 -0.915467 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.315026 0.000000 -0.949083 +0.315026 0.000000 -0.949083 +0.315026 0.000000 -0.949083 +0.315026 0.000000 -0.949083 +0.315026 0.000000 -0.949083 +0.315026 0.000000 -0.949083 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.318258 0.000000 0.948004 +-0.318258 0.000000 0.948004 +-0.318258 0.000000 0.948004 +-0.318258 0.000000 0.948004 +-0.318258 0.000000 0.948004 +-0.318258 0.000000 0.948004 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.308093 0.000000 0.951356 +0.308093 0.000000 0.951356 +0.308093 0.000000 0.951356 +0.308093 0.000000 0.951356 +0.308093 0.000000 0.951356 +0.308093 0.000000 0.951356 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.311344 0.000000 -0.950297 +-0.311344 0.000000 -0.950297 +-0.311344 0.000000 -0.950297 +-0.311344 0.000000 -0.950297 +-0.311344 0.000000 -0.950297 +-0.311344 0.000000 -0.950297 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.196559 0.000000 0.980492 +-0.196559 0.000000 0.980492 +-0.196559 0.000000 0.980492 +-0.196559 0.000000 0.980492 +-0.196559 0.000000 0.980492 +-0.196559 0.000000 0.980492 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.192987 0.000000 -0.981201 +0.192987 0.000000 -0.981201 +0.192987 0.000000 -0.981201 +0.192987 0.000000 -0.981201 +0.192987 0.000000 -0.981201 +0.192987 0.000000 -0.981201 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 -0.000001 0.000149 +1.000000 -0.000001 0.000149 +1.000000 -0.000001 0.000149 +1.000000 -0.000001 0.000149 +1.000000 -0.000001 0.000149 +1.000000 -0.000001 0.000149 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +1.000000 0.000000 0.000178 +1.000000 0.000000 0.000178 +1.000000 0.000000 0.000178 +1.000000 0.000000 0.000178 +1.000000 0.000000 0.000178 +1.000000 0.000000 0.000178 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +-1.000000 0.000001 0.000151 +-1.000000 0.000001 0.000151 +-1.000000 0.000001 0.000151 +-1.000000 0.000001 0.000151 +-1.000000 0.000001 0.000151 +-1.000000 0.000001 0.000151 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 -0.000002 0.000219 +1.000000 -0.000002 0.000219 +1.000000 -0.000002 0.000219 +1.000000 -0.000002 0.000219 +1.000000 -0.000002 0.000219 +1.000000 -0.000002 0.000219 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +-1.000000 0.000000 0.000180 +-1.000000 0.000000 0.000180 +-1.000000 0.000000 0.000180 +-1.000000 0.000000 0.000180 +-1.000000 0.000000 0.000180 +-1.000000 0.000000 0.000180 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000002 0.000223 +-1.000000 0.000002 0.000223 +-1.000000 0.000002 0.000223 +-1.000000 0.000002 0.000223 +-1.000000 0.000002 0.000223 +-1.000000 0.000002 0.000223 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.399484 0.000000 0.916740 +-0.399484 0.000000 0.916740 +-0.399484 0.000000 0.916740 +-0.399484 0.000000 0.916740 +-0.399484 0.000000 0.916740 +-0.399484 0.000000 0.916740 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.402393 0.000000 -0.915467 +0.402393 0.000000 -0.915467 +0.402393 0.000000 -0.915467 +0.402393 0.000000 -0.915467 +0.402393 0.000000 -0.915467 +0.402393 0.000000 -0.915467 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.315026 0.000000 -0.949083 +-0.315026 0.000000 -0.949083 +-0.315026 0.000000 -0.949083 +-0.315026 0.000000 -0.949083 +-0.315026 0.000000 -0.949083 +-0.315026 0.000000 -0.949083 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.318258 0.000000 0.948004 +0.318258 0.000000 0.948004 +0.318258 0.000000 0.948004 +0.318258 0.000000 0.948004 +0.318258 0.000000 0.948004 +0.318258 0.000000 0.948004 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.308093 0.000000 0.951356 +-0.308093 0.000000 0.951356 +-0.308093 0.000000 0.951356 +-0.308093 0.000000 0.951356 +-0.308093 0.000000 0.951356 +-0.308093 0.000000 0.951356 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.311344 0.000000 -0.950297 +0.311344 0.000000 -0.950297 +0.311344 0.000000 -0.950297 +0.311344 0.000000 -0.950297 +0.311344 0.000000 -0.950297 +0.311344 0.000000 -0.950297 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.196559 0.000000 0.980492 +0.196559 0.000000 0.980492 +0.196559 0.000000 0.980492 +0.196559 0.000000 0.980492 +0.196559 0.000000 0.980492 +0.196559 0.000000 0.980492 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.192987 0.000000 -0.981201 +-0.192987 0.000000 -0.981201 +-0.192987 0.000000 -0.981201 +-0.192987 0.000000 -0.981201 +-0.192987 0.000000 -0.981201 +-0.192987 0.000000 -0.981201 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 -0.000001 0.000149 +-1.000000 -0.000001 0.000149 +-1.000000 -0.000001 0.000149 +-1.000000 -0.000001 0.000149 +-1.000000 -0.000001 0.000149 +-1.000000 -0.000001 0.000149 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-1.000000 0.000000 0.000178 +-1.000000 0.000000 0.000178 +-1.000000 0.000000 0.000178 +-1.000000 0.000000 0.000178 +-1.000000 0.000000 0.000178 +-1.000000 0.000000 0.000178 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +1.000000 0.000001 0.000151 +1.000000 0.000001 0.000151 +1.000000 0.000001 0.000151 +1.000000 0.000001 0.000151 +1.000000 0.000001 0.000151 +1.000000 0.000001 0.000151 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 -0.000002 0.000219 +-1.000000 -0.000002 0.000219 +-1.000000 -0.000002 0.000219 +-1.000000 -0.000002 0.000219 +-1.000000 -0.000002 0.000219 +-1.000000 -0.000002 0.000219 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +1.000000 0.000000 0.000180 +1.000000 0.000000 0.000180 +1.000000 0.000000 0.000180 +1.000000 0.000000 0.000180 +1.000000 0.000000 0.000180 +1.000000 0.000000 0.000180 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 0.000002 0.000223 +1.000000 0.000002 0.000223 +1.000000 0.000002 0.000223 +1.000000 0.000002 0.000223 +1.000000 0.000002 0.000223 +1.000000 0.000002 0.000223 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.399484 0.000000 0.916740 +0.399484 0.000000 0.916740 +0.399484 0.000000 0.916740 +0.399484 0.000000 0.916740 +0.399484 0.000000 0.916740 +0.399484 0.000000 0.916740 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.402393 0.000000 -0.915467 +-0.402393 0.000000 -0.915467 +-0.402393 0.000000 -0.915467 +-0.402393 0.000000 -0.915467 +-0.402393 0.000000 -0.915467 +-0.402393 0.000000 -0.915467 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.315026 0.000000 -0.949083 +0.315026 0.000000 -0.949083 +0.315026 0.000000 -0.949083 +0.315026 0.000000 -0.949083 +0.315026 0.000000 -0.949083 +0.315026 0.000000 -0.949083 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.318258 0.000000 0.948004 +-0.318258 0.000000 0.948004 +-0.318258 0.000000 0.948004 +-0.318258 0.000000 0.948004 +-0.318258 0.000000 0.948004 +-0.318258 0.000000 0.948004 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.308093 0.000000 0.951356 +0.308093 0.000000 0.951356 +0.308093 0.000000 0.951356 +0.308093 0.000000 0.951356 +0.308093 0.000000 0.951356 +0.308093 0.000000 0.951356 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.311344 0.000000 -0.950297 +-0.311344 0.000000 -0.950297 +-0.311344 0.000000 -0.950297 +-0.311344 0.000000 -0.950297 +-0.311344 0.000000 -0.950297 +-0.311344 0.000000 -0.950297 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.196559 0.000000 0.980492 +-0.196559 0.000000 0.980492 +-0.196559 0.000000 0.980492 +-0.196559 0.000000 0.980492 +-0.196559 0.000000 0.980492 +-0.196559 0.000000 0.980492 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.192987 0.000000 -0.981201 +0.192987 0.000000 -0.981201 +0.192987 0.000000 -0.981201 +0.192987 0.000000 -0.981201 +0.192987 0.000000 -0.981201 +0.192987 0.000000 -0.981201 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 -0.000001 0.000149 +1.000000 -0.000001 0.000149 +1.000000 -0.000001 0.000149 +1.000000 -0.000001 0.000149 +1.000000 -0.000001 0.000149 +1.000000 -0.000001 0.000149 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +1.000000 0.000000 0.000178 +1.000000 0.000000 0.000178 +1.000000 0.000000 0.000178 +1.000000 0.000000 0.000178 +1.000000 0.000000 0.000178 +1.000000 0.000000 0.000178 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +-1.000000 0.000001 0.000151 +-1.000000 0.000001 0.000151 +-1.000000 0.000001 0.000151 +-1.000000 0.000001 0.000151 +-1.000000 0.000001 0.000151 +-1.000000 0.000001 0.000151 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 -0.000002 0.000219 +1.000000 -0.000002 0.000219 +1.000000 -0.000002 0.000219 +1.000000 -0.000002 0.000219 +1.000000 -0.000002 0.000219 +1.000000 -0.000002 0.000219 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +-1.000000 0.000000 0.000180 +-1.000000 0.000000 0.000180 +-1.000000 0.000000 0.000180 +-1.000000 0.000000 0.000180 +-1.000000 0.000000 0.000180 +-1.000000 0.000000 0.000180 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000002 0.000223 +-1.000000 0.000002 0.000223 +-1.000000 0.000002 0.000223 +-1.000000 0.000002 0.000223 +-1.000000 0.000002 0.000223 +-1.000000 0.000002 0.000223 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.399484 0.000000 0.916740 +-0.399484 0.000000 0.916740 +-0.399484 0.000000 0.916740 +-0.399484 0.000000 0.916740 +-0.399484 0.000000 0.916740 +-0.399484 0.000000 0.916740 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.402393 0.000000 -0.915467 +0.402393 0.000000 -0.915467 +0.402393 0.000000 -0.915467 +0.402393 0.000000 -0.915467 +0.402393 0.000000 -0.915467 +0.402393 0.000000 -0.915467 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.315026 0.000000 -0.949083 +-0.315026 0.000000 -0.949083 +-0.315026 0.000000 -0.949083 +-0.315026 0.000000 -0.949083 +-0.315026 0.000000 -0.949083 +-0.315026 0.000000 -0.949083 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.318258 0.000000 0.948004 +0.318258 0.000000 0.948004 +0.318258 0.000000 0.948004 +0.318258 0.000000 0.948004 +0.318258 0.000000 0.948004 +0.318258 0.000000 0.948004 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.308093 0.000000 0.951356 +-0.308093 0.000000 0.951356 +-0.308093 0.000000 0.951356 +-0.308093 0.000000 0.951356 +-0.308093 0.000000 0.951356 +-0.308093 0.000000 0.951356 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.311344 0.000000 -0.950297 +0.311344 0.000000 -0.950297 +0.311344 0.000000 -0.950297 +0.311344 0.000000 -0.950297 +0.311344 0.000000 -0.950297 +0.311344 0.000000 -0.950297 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.196559 0.000000 0.980492 +0.196559 0.000000 0.980492 +0.196559 0.000000 0.980492 +0.196559 0.000000 0.980492 +0.196559 0.000000 0.980492 +0.196559 0.000000 0.980492 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.192987 0.000000 -0.981201 +-0.192987 0.000000 -0.981201 +-0.192987 0.000000 -0.981201 +-0.192987 0.000000 -0.981201 +-0.192987 0.000000 -0.981201 +-0.192987 0.000000 -0.981201 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 -0.000001 0.000149 +-1.000000 -0.000001 0.000149 +-1.000000 -0.000001 0.000149 +-1.000000 -0.000001 0.000149 +-1.000000 -0.000001 0.000149 +-1.000000 -0.000001 0.000149 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-1.000000 0.000000 0.000178 +-1.000000 0.000000 0.000178 +-1.000000 0.000000 0.000178 +-1.000000 0.000000 0.000178 +-1.000000 0.000000 0.000178 +-1.000000 0.000000 0.000178 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +1.000000 0.000001 0.000151 +1.000000 0.000001 0.000151 +1.000000 0.000001 0.000151 +1.000000 0.000001 0.000151 +1.000000 0.000001 0.000151 +1.000000 0.000001 0.000151 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 -0.000002 0.000219 +-1.000000 -0.000002 0.000219 +-1.000000 -0.000002 0.000219 +-1.000000 -0.000002 0.000219 +-1.000000 -0.000002 0.000219 +-1.000000 -0.000002 0.000219 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +1.000000 0.000000 0.000180 +1.000000 0.000000 0.000180 +1.000000 0.000000 0.000180 +1.000000 0.000000 0.000180 +1.000000 0.000000 0.000180 +1.000000 0.000000 0.000180 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 0.000002 0.000223 +1.000000 0.000002 0.000223 +1.000000 0.000002 0.000223 +1.000000 0.000002 0.000223 +1.000000 0.000002 0.000223 +1.000000 0.000002 0.000223 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.399484 0.000000 0.916740 +0.399484 0.000000 0.916740 +0.399484 0.000000 0.916740 +0.399484 0.000000 0.916740 +0.399484 0.000000 0.916740 +0.399484 0.000000 0.916740 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.402393 0.000000 -0.915467 +-0.402393 0.000000 -0.915467 +-0.402393 0.000000 -0.915467 +-0.402393 0.000000 -0.915467 +-0.402393 0.000000 -0.915467 +-0.402393 0.000000 -0.915467 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.315026 0.000000 -0.949083 +0.315026 0.000000 -0.949083 +0.315026 0.000000 -0.949083 +0.315026 0.000000 -0.949083 +0.315026 0.000000 -0.949083 +0.315026 0.000000 -0.949083 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.318258 0.000000 0.948004 +-0.318258 0.000000 0.948004 +-0.318258 0.000000 0.948004 +-0.318258 0.000000 0.948004 +-0.318258 0.000000 0.948004 +-0.318258 0.000000 0.948004 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.308093 0.000000 0.951356 +0.308093 0.000000 0.951356 +0.308093 0.000000 0.951356 +0.308093 0.000000 0.951356 +0.308093 0.000000 0.951356 +0.308093 0.000000 0.951356 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.311344 0.000000 -0.950297 +-0.311344 0.000000 -0.950297 +-0.311344 0.000000 -0.950297 +-0.311344 0.000000 -0.950297 +-0.311344 0.000000 -0.950297 +-0.311344 0.000000 -0.950297 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.196559 0.000000 0.980492 +-0.196559 0.000000 0.980492 +-0.196559 0.000000 0.980492 +-0.196559 0.000000 0.980492 +-0.196559 0.000000 0.980492 +-0.196559 0.000000 0.980492 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.192987 0.000000 -0.981201 +0.192987 0.000000 -0.981201 +0.192987 0.000000 -0.981201 +0.192987 0.000000 -0.981201 +0.192987 0.000000 -0.981201 +0.192987 0.000000 -0.981201 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 -0.000001 0.000149 +1.000000 -0.000001 0.000149 +1.000000 -0.000001 0.000149 +1.000000 -0.000001 0.000149 +1.000000 -0.000001 0.000149 +1.000000 -0.000001 0.000149 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +1.000000 0.000000 0.000178 +1.000000 0.000000 0.000178 +1.000000 0.000000 0.000178 +1.000000 0.000000 0.000178 +1.000000 0.000000 0.000178 +1.000000 0.000000 0.000178 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +-1.000000 0.000001 0.000151 +-1.000000 0.000001 0.000151 +-1.000000 0.000001 0.000151 +-1.000000 0.000001 0.000151 +-1.000000 0.000001 0.000151 +-1.000000 0.000001 0.000151 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 -0.000002 0.000219 +1.000000 -0.000002 0.000219 +1.000000 -0.000002 0.000219 +1.000000 -0.000002 0.000219 +1.000000 -0.000002 0.000219 +1.000000 -0.000002 0.000219 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +-1.000000 0.000000 0.000180 +-1.000000 0.000000 0.000180 +-1.000000 0.000000 0.000180 +-1.000000 0.000000 0.000180 +-1.000000 0.000000 0.000180 +-1.000000 0.000000 0.000180 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000002 0.000223 +-1.000000 0.000002 0.000223 +-1.000000 0.000002 0.000223 +-1.000000 0.000002 0.000223 +-1.000000 0.000002 0.000223 +-1.000000 0.000002 0.000223 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.399484 0.000000 0.916740 +-0.399484 0.000000 0.916740 +-0.399484 0.000000 0.916740 +-0.399484 0.000000 0.916740 +-0.399484 0.000000 0.916740 +-0.399484 0.000000 0.916740 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.402393 0.000000 -0.915467 +0.402393 0.000000 -0.915467 +0.402393 0.000000 -0.915467 +0.402393 0.000000 -0.915467 +0.402393 0.000000 -0.915467 +0.402393 0.000000 -0.915467 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.315026 0.000000 -0.949083 +-0.315026 0.000000 -0.949083 +-0.315026 0.000000 -0.949083 +-0.315026 0.000000 -0.949083 +-0.315026 0.000000 -0.949083 +-0.315026 0.000000 -0.949083 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.318258 0.000000 0.948004 +0.318258 0.000000 0.948004 +0.318258 0.000000 0.948004 +0.318258 0.000000 0.948004 +0.318258 0.000000 0.948004 +0.318258 0.000000 0.948004 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.308093 0.000000 0.951356 +-0.308093 0.000000 0.951356 +-0.308093 0.000000 0.951356 +-0.308093 0.000000 0.951356 +-0.308093 0.000000 0.951356 +-0.308093 0.000000 0.951356 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.311344 0.000000 -0.950297 +0.311344 0.000000 -0.950297 +0.311344 0.000000 -0.950297 +0.311344 0.000000 -0.950297 +0.311344 0.000000 -0.950297 +0.311344 0.000000 -0.950297 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.196559 0.000000 0.980492 +0.196559 0.000000 0.980492 +0.196559 0.000000 0.980492 +0.196559 0.000000 0.980492 +0.196559 0.000000 0.980492 +0.196559 0.000000 0.980492 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.192987 0.000000 -0.981201 +-0.192987 0.000000 -0.981201 +-0.192987 0.000000 -0.981201 +-0.192987 0.000000 -0.981201 +-0.192987 0.000000 -0.981201 +-0.192987 0.000000 -0.981201 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 -0.000001 0.000149 +-1.000000 -0.000001 0.000149 +-1.000000 -0.000001 0.000149 +-1.000000 -0.000001 0.000149 +-1.000000 -0.000001 0.000149 +-1.000000 -0.000001 0.000149 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-1.000000 0.000000 0.000178 +-1.000000 0.000000 0.000178 +-1.000000 0.000000 0.000178 +-1.000000 0.000000 0.000178 +-1.000000 0.000000 0.000178 +-1.000000 0.000000 0.000178 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +1.000000 0.000001 0.000151 +1.000000 0.000001 0.000151 +1.000000 0.000001 0.000151 +1.000000 0.000001 0.000151 +1.000000 0.000001 0.000151 +1.000000 0.000001 0.000151 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 -0.000002 0.000219 +-1.000000 -0.000002 0.000219 +-1.000000 -0.000002 0.000219 +-1.000000 -0.000002 0.000219 +-1.000000 -0.000002 0.000219 +-1.000000 -0.000002 0.000219 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +1.000000 0.000000 0.000180 +1.000000 0.000000 0.000180 +1.000000 0.000000 0.000180 +1.000000 0.000000 0.000180 +1.000000 0.000000 0.000180 +1.000000 0.000000 0.000180 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 0.000002 0.000223 +1.000000 0.000002 0.000223 +1.000000 0.000002 0.000223 +1.000000 0.000002 0.000223 +1.000000 0.000002 0.000223 +1.000000 0.000002 0.000223 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +-0.054773 0.000002 -0.998499 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.399484 0.000000 0.916740 +0.399484 0.000000 0.916740 +0.399484 0.000000 0.916740 +0.399484 0.000000 0.916740 +0.399484 0.000000 0.916740 +0.399484 0.000000 0.916740 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.402393 0.000000 -0.915467 +-0.402393 0.000000 -0.915467 +-0.402393 0.000000 -0.915467 +-0.402393 0.000000 -0.915467 +-0.402393 0.000000 -0.915467 +-0.402393 0.000000 -0.915467 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.315026 0.000000 -0.949083 +0.315026 0.000000 -0.949083 +0.315026 0.000000 -0.949083 +0.315026 0.000000 -0.949083 +0.315026 0.000000 -0.949083 +0.315026 0.000000 -0.949083 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.318258 0.000000 0.948004 +-0.318258 0.000000 0.948004 +-0.318258 0.000000 0.948004 +-0.318258 0.000000 0.948004 +-0.318258 0.000000 0.948004 +-0.318258 0.000000 0.948004 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.308093 0.000000 0.951356 +0.308093 0.000000 0.951356 +0.308093 0.000000 0.951356 +0.308093 0.000000 0.951356 +0.308093 0.000000 0.951356 +0.308093 0.000000 0.951356 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.311344 0.000000 -0.950297 +-0.311344 0.000000 -0.950297 +-0.311344 0.000000 -0.950297 +-0.311344 0.000000 -0.950297 +-0.311344 0.000000 -0.950297 +-0.311344 0.000000 -0.950297 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.196559 0.000000 0.980492 +-0.196559 0.000000 0.980492 +-0.196559 0.000000 0.980492 +-0.196559 0.000000 0.980492 +-0.196559 0.000000 0.980492 +-0.196559 0.000000 0.980492 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.192987 0.000000 -0.981201 +0.192987 0.000000 -0.981201 +0.192987 0.000000 -0.981201 +0.192987 0.000000 -0.981201 +0.192987 0.000000 -0.981201 +0.192987 0.000000 -0.981201 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 -0.000001 0.000149 +1.000000 -0.000001 0.000149 +1.000000 -0.000001 0.000149 +1.000000 -0.000001 0.000149 +1.000000 -0.000001 0.000149 +1.000000 -0.000001 0.000149 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +1.000000 0.000000 0.000178 +1.000000 0.000000 0.000178 +1.000000 0.000000 0.000178 +1.000000 0.000000 0.000178 +1.000000 0.000000 0.000178 +1.000000 0.000000 0.000178 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +-1.000000 0.000001 0.000151 +-1.000000 0.000001 0.000151 +-1.000000 0.000001 0.000151 +-1.000000 0.000001 0.000151 +-1.000000 0.000001 0.000151 +-1.000000 0.000001 0.000151 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 -0.000002 0.000219 +1.000000 -0.000002 0.000219 +1.000000 -0.000002 0.000219 +1.000000 -0.000002 0.000219 +1.000000 -0.000002 0.000219 +1.000000 -0.000002 0.000219 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +-1.000000 0.000000 0.000180 +-1.000000 0.000000 0.000180 +-1.000000 0.000000 0.000180 +-1.000000 0.000000 0.000180 +-1.000000 0.000000 0.000180 +-1.000000 0.000000 0.000180 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000002 0.000223 +-1.000000 0.000002 0.000223 +-1.000000 0.000002 0.000223 +-1.000000 0.000002 0.000223 +-1.000000 0.000002 0.000223 +-1.000000 0.000002 0.000223 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.054773 0.000002 -0.998499 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.399484 0.000000 0.916740 +-0.399484 0.000000 0.916740 +-0.399484 0.000000 0.916740 +-0.399484 0.000000 0.916740 +-0.399484 0.000000 0.916740 +-0.399484 0.000000 0.916740 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.402393 0.000000 -0.915467 +0.402393 0.000000 -0.915467 +0.402393 0.000000 -0.915467 +0.402393 0.000000 -0.915467 +0.402393 0.000000 -0.915467 +0.402393 0.000000 -0.915467 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.315026 0.000000 -0.949083 +-0.315026 0.000000 -0.949083 +-0.315026 0.000000 -0.949083 +-0.315026 0.000000 -0.949083 +-0.315026 0.000000 -0.949083 +-0.315026 0.000000 -0.949083 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.318258 0.000000 0.948004 +0.318258 0.000000 0.948004 +0.318258 0.000000 0.948004 +0.318258 0.000000 0.948004 +0.318258 0.000000 0.948004 +0.318258 0.000000 0.948004 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.308093 0.000000 0.951356 +-0.308093 0.000000 0.951356 +-0.308093 0.000000 0.951356 +-0.308093 0.000000 0.951356 +-0.308093 0.000000 0.951356 +-0.308093 0.000000 0.951356 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.311344 0.000000 -0.950297 +0.311344 0.000000 -0.950297 +0.311344 0.000000 -0.950297 +0.311344 0.000000 -0.950297 +0.311344 0.000000 -0.950297 +0.311344 0.000000 -0.950297 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.196559 0.000000 0.980492 +0.196559 0.000000 0.980492 +0.196559 0.000000 0.980492 +0.196559 0.000000 0.980492 +0.196559 0.000000 0.980492 +0.196559 0.000000 0.980492 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.192987 0.000000 -0.981201 +-0.192987 0.000000 -0.981201 +-0.192987 0.000000 -0.981201 +-0.192987 0.000000 -0.981201 +-0.192987 0.000000 -0.981201 +-0.192987 0.000000 -0.981201 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.000039 0.000000 1.000000 +-0.000039 0.000000 1.000000 +0.054322 0.000000 0.998523 +0.054322 0.000000 0.998523 +-0.000039 0.000000 1.000000 +0.054322 0.000000 0.998523 +-0.054398 0.000000 0.998519 +-0.054398 0.000000 0.998519 +-0.000039 0.000000 1.000000 +-0.000039 0.000000 1.000000 +-0.054398 0.000000 0.998519 +-0.000039 0.000000 1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000039 0.000000 -1.000000 +0.000039 0.000000 -1.000000 +-0.054322 0.000000 -0.998523 +-0.054322 0.000000 -0.998523 +0.000039 0.000000 -1.000000 +-0.054322 0.000000 -0.998523 +0.000039 0.000000 -1.000000 +0.000039 0.000000 -1.000000 +0.054398 0.000000 -0.998519 +0.054398 0.000000 -0.998519 +0.054398 0.000000 -0.998519 +0.000039 0.000000 -1.000000 +-0.053482 -0.291167 -0.955176 +-0.053482 -0.291167 -0.955176 +-0.055904 0.000000 -0.998436 +-0.053482 -0.291167 -0.955176 +-0.055904 0.000000 -0.998436 +-0.055904 0.000000 -0.998436 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.055904 0.000000 -0.998436 +-0.055904 0.000000 -0.998436 +-0.053482 0.291167 -0.955176 +-0.055904 0.000000 -0.998436 +-0.053482 0.291167 -0.955176 +-0.053482 0.291167 -0.955176 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.055904 -0.000000 -0.998436 +0.055904 -0.000000 -0.998436 +0.053482 -0.291167 -0.955176 +0.053482 -0.291167 -0.955176 +0.053482 -0.291167 -0.955176 +0.055904 -0.000000 -0.998436 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.053482 0.291167 -0.955176 +0.053482 0.291167 -0.955176 +0.055904 -0.000000 -0.998436 +0.055904 -0.000000 -0.998436 +0.055904 -0.000000 -0.998436 +0.053482 0.291167 -0.955176 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.055904 0.000000 -0.998436 +-0.053482 0.291167 -0.955176 +-0.055904 0.000000 -0.998436 +-0.053482 0.291167 -0.955176 +-0.055904 0.000000 -0.998436 +-0.053482 0.291167 -0.955176 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.053482 -0.291167 -0.955176 +-0.055904 0.000000 -0.998436 +-0.053482 -0.291167 -0.955176 +-0.055904 0.000000 -0.998436 +-0.053482 -0.291167 -0.955176 +-0.055904 0.000000 -0.998436 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.055904 0.000000 -0.998436 +0.055904 0.000000 -0.998436 +0.053482 0.291167 -0.955176 +0.055904 0.000000 -0.998436 +0.053482 0.291167 -0.955176 +0.053482 0.291167 -0.955176 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.053482 -0.291167 -0.955176 +0.053482 -0.291167 -0.955176 +0.055904 0.000000 -0.998436 +0.053482 -0.291167 -0.955176 +0.055904 0.000000 -0.998436 +0.055904 0.000000 -0.998436 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000049 +0.000000 1.000000 0.000049 +0.000000 1.000000 0.000049 +0.000000 1.000000 0.000049 +0.000000 1.000000 0.000049 +0.000000 1.000000 0.000049 +0.000000 -1.000000 -0.000082 +0.000000 -1.000000 -0.000082 +0.000000 -1.000000 -0.000082 +0.000000 -1.000000 -0.000082 +0.000000 -1.000000 -0.000082 +0.000000 -1.000000 -0.000082 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 1.000000 0.000049 +0.000000 1.000000 0.000049 +0.000000 1.000000 0.000049 +0.000000 1.000000 0.000049 +0.000000 1.000000 0.000049 +0.000000 1.000000 0.000049 +0.000000 -1.000000 -0.000082 +0.000000 -1.000000 -0.000082 +0.000000 -1.000000 -0.000082 +0.000000 -1.000000 -0.000082 +0.000000 -1.000000 -0.000082 +0.000000 -1.000000 -0.000082 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 + + + + + + + + + + + +0.307256 0.287678 +0.309725 0.285091 +0.696866 0.012381 +0.696866 0.022741 +0.685172 0.070052 +0.554812 0.070052 +0.696866 0.303200 +0.307256 0.303200 +0.694397 0.285091 +0.696866 0.287678 +0.307256 0.314271 +0.307256 0.303911 +0.691928 0.303911 +0.691928 0.314271 +0.424636 0.052416 +0.424636 0.042056 +0.694397 0.157317 +0.307256 0.022741 +0.307256 0.012381 +0.694397 0.029544 +0.557398 0.105323 +0.556158 0.087872 +0.558639 0.087872 +0.429625 0.105323 +0.307256 0.292840 +0.696866 0.292840 +0.553756 0.034964 +0.554997 0.052416 +0.696866 0.027142 +0.557398 0.087687 +0.556158 0.070236 +0.558639 0.070236 +0.429625 0.087687 +0.696866 0.157317 +0.556052 0.052600 +0.685172 0.059692 +0.691928 0.314981 +0.691928 0.325341 +0.307256 0.325341 +0.307256 0.314981 +0.307256 0.157317 +0.429625 0.077327 +0.307256 0.027142 +0.553571 0.052600 +0.424636 0.070052 +0.424636 0.059692 +0.685172 0.077327 +0.685172 0.087687 +0.556237 0.034964 +0.685172 0.042056 +0.309725 0.029544 +0.685172 0.052416 +0.429625 0.094963 +0.685172 0.094963 +0.685172 0.105323 +0.309725 0.157317 +0.028294 0.161426 +0.845851 0.072634 +0.028294 0.126921 +0.965740 0.103010 +0.307570 0.173685 +0.412003 0.173685 +0.412003 0.182543 +0.307570 0.182543 +0.965740 0.137515 +0.731259 0.073629 +0.289884 0.082486 +0.731927 0.072634 +0.959607 0.130099 +0.187033 0.082486 +0.731259 0.082486 +0.725300 0.173685 +0.427377 0.203242 +0.114079 0.192395 +0.831314 0.173685 +0.422159 0.193390 +0.119991 0.253147 +0.119991 0.226887 +0.640183 0.192395 +0.870491 0.173685 +0.114079 0.183537 +0.526586 0.203242 +0.725300 0.182543 +0.959607 0.109870 +0.034427 0.133781 +0.631023 0.193390 +0.240187 0.213094 +0.213293 0.203242 +0.731927 0.063777 +0.504246 0.130099 +0.321229 0.110195 +0.640183 0.183537 +0.535750 0.192395 +0.535750 0.183537 +0.422159 0.202247 +0.282479 0.110195 +0.845851 0.063777 +0.034427 0.154011 +0.213293 0.212099 +0.272692 0.213094 +0.631023 0.202247 +0.499693 0.130099 +0.489788 0.108802 +0.204719 0.182543 +0.618003 0.072634 +0.499693 0.084891 +0.622449 0.182543 +0.216930 0.183537 +0.499693 0.072634 +0.494341 0.108802 +0.628408 0.082486 +0.322944 0.202247 +0.739397 0.183537 +0.628408 0.073629 +0.499693 0.063777 +0.504246 0.084891 +0.531809 0.202247 +0.114079 0.212099 +0.216930 0.192395 +0.114079 0.203242 +0.531809 0.193390 +0.622449 0.173685 +0.618003 0.063777 +0.494341 0.154011 +0.739397 0.192395 +0.322944 0.193390 +0.204719 0.173685 +0.731927 0.090087 +0.489788 0.154011 +0.489788 0.101481 +0.494341 0.101481 +0.721194 0.096792 +0.376031 0.161426 +0.965740 0.063777 +0.621974 0.091349 +0.618086 0.083828 +0.845851 0.137515 +0.262107 0.161426 +0.266001 0.154011 +0.731927 0.137515 +0.965740 0.072634 +0.365210 0.154011 +0.262107 0.113998 +0.251375 0.121881 +0.295406 0.073629 +0.237159 0.114136 +0.735821 0.130099 +0.835029 0.130099 +0.237159 0.105279 +0.398258 0.073629 +0.413584 0.173685 +0.152155 0.127323 +0.148267 0.120257 +0.100286 0.173685 +0.203138 0.173685 +0.952512 0.109481 +0.849655 0.103838 +0.516435 0.173685 +0.148183 0.161426 +0.137278 0.154011 +0.159005 0.154011 +0.258213 0.154011 +0.235680 0.213094 +0.114079 0.193390 +0.845767 0.096345 +0.427377 0.193390 +0.530537 0.183537 +0.841879 0.103412 +0.153534 0.072634 +0.153534 0.063777 +0.267459 0.063777 +0.267459 0.072634 +0.386937 0.154011 +0.636242 0.193390 +0.061315 0.073629 +0.494341 0.160923 +0.742659 0.097969 +0.511342 0.085280 +0.277625 0.221951 +0.218512 0.193390 +0.494341 0.161426 +0.398258 0.082486 +0.317726 0.193390 +0.277625 0.213094 +0.516435 0.182543 +0.482692 0.109192 +0.379836 0.114834 +0.829732 0.182543 +0.341323 0.213094 +0.504246 0.077570 +0.061315 0.082486 +0.735456 0.193390 +0.518016 0.173685 +0.614198 0.090922 +0.239987 0.249849 +0.381383 0.072634 +0.381383 0.063777 +0.033645 0.072634 +0.033645 0.063777 +0.065368 0.073629 +0.110576 0.073629 +0.620867 0.173685 +0.137131 0.249849 +0.375948 0.107740 +0.530537 0.192395 +0.526591 0.193390 +0.726881 0.182543 +0.341323 0.221951 +0.618003 0.137515 +0.499693 0.137515 +0.499693 0.137011 +0.413584 0.182543 +0.213294 0.193390 +0.235680 0.221951 +0.295406 0.082486 +0.726881 0.173685 +0.735456 0.202247 +0.526591 0.202247 +0.620867 0.182543 +0.317726 0.202247 +0.213294 0.202247 +0.218512 0.202247 +0.114079 0.202247 +0.427377 0.202247 +0.518016 0.182543 +0.829732 0.173685 +0.636242 0.202247 +0.607097 0.130099 +0.872693 0.173685 +0.905625 0.173685 +0.905625 0.182543 +0.872693 0.182543 +0.628824 0.130099 +0.728033 0.130099 +0.856756 0.130099 +0.735815 0.097594 +0.728039 0.097167 +0.621980 0.130099 +0.614192 0.130099 +0.849661 0.130099 +0.841873 0.130099 +0.499693 0.077570 +0.033645 0.103010 +0.039778 0.109870 +0.039778 0.130099 +0.033645 0.137515 +0.495139 0.130099 +0.495139 0.084891 +0.267459 0.090087 +0.381299 0.083828 +0.377411 0.091349 +0.278191 0.096792 +0.153534 0.137515 +0.164356 0.130099 +0.263565 0.130099 +0.267459 0.137515 +0.153618 0.096345 +0.149730 0.103838 +0.046874 0.109481 +0.256726 0.097969 +0.157506 0.103412 +0.488044 0.085280 +0.385187 0.090922 +0.495139 0.077570 +0.381383 0.137515 +0.392288 0.130099 +0.271352 0.130099 +0.370561 0.130099 +0.142629 0.130099 +0.271347 0.097167 +0.263570 0.097594 +0.377405 0.130099 +0.385193 0.130099 +0.157512 0.130099 +0.149724 0.130099 +0.372060 0.115260 +0.272840 0.120703 +0.041522 0.133392 +0.144379 0.127750 +0.144373 0.154011 +0.152161 0.154011 +0.372054 0.154011 +0.379842 0.154011 +0.258219 0.121505 +0.265995 0.121079 +0.960389 0.161426 +0.954256 0.154011 +0.954256 0.133781 +0.960389 0.126922 +0.498895 0.108802 +0.498895 0.154011 +0.498895 0.101481 +0.612651 0.161426 +0.623473 0.154011 +0.722682 0.154011 +0.726575 0.161426 +0.726575 0.113998 +0.840416 0.120257 +0.836528 0.127323 +0.737308 0.121881 +0.840499 0.161426 +0.851405 0.154011 +0.730469 0.154011 +0.829678 0.154011 +0.601746 0.154011 +0.612735 0.107740 +0.608847 0.114834 +0.505990 0.109192 +0.715843 0.120703 +0.616623 0.115261 +0.947160 0.133392 +0.844304 0.127750 +0.836522 0.154011 +0.844310 0.154011 +0.616629 0.154011 +0.608841 0.154011 +0.730464 0.121505 +0.722687 0.121079 +0.526586 0.212099 +0.427377 0.212099 +0.110576 0.082486 +0.065368 0.082486 +0.061315 0.092338 +0.034628 0.092338 +0.034628 0.083481 +0.061315 0.083481 +0.317721 0.203242 +0.317721 0.212099 +0.218512 0.212099 +0.218512 0.203242 +0.222453 0.183537 +0.321672 0.183537 +0.321672 0.192395 +0.222453 0.192395 +0.282479 0.101338 +0.321229 0.101338 +0.756875 0.086427 +0.736646 0.086427 +0.736646 0.077570 +0.756875 0.077570 +0.631018 0.203242 +0.631018 0.212099 +0.531809 0.212099 +0.531809 0.203242 +0.634970 0.183537 +0.634970 0.192395 +0.272692 0.221951 +0.240187 0.221951 +0.065368 0.092338 +0.065368 0.083481 +0.110576 0.083481 +0.110576 0.092338 +0.322944 0.203242 +0.422153 0.203242 +0.422153 0.212099 +0.322944 0.212099 +0.862883 0.077570 +0.965740 0.077570 +0.965740 0.086427 +0.862883 0.086427 +0.128848 0.226887 +0.128848 0.253147 +0.118996 0.255785 +0.110139 0.255785 +0.110139 0.217035 +0.118996 0.217035 +0.309151 0.182543 +0.309151 0.173685 +0.326885 0.183537 +0.426105 0.183537 +0.426105 0.192395 +0.326885 0.192395 +0.100286 0.217035 +0.109144 0.217035 +0.109144 0.256211 +0.100286 0.256211 +0.310130 0.213094 +0.310130 0.221951 +0.187033 0.073629 +0.289884 0.073629 +0.861307 0.077570 +0.861307 0.086427 +0.758451 0.086427 +0.758451 0.077570 +0.202749 0.221951 +0.202749 0.213094 +0.315063 0.221951 +0.315063 0.213094 +0.203138 0.182543 +0.100286 0.182543 +0.241563 0.243938 +0.241563 0.235081 +0.344420 0.235081 +0.344420 0.243938 +0.034628 0.082486 +0.034628 0.073629 +0.870491 0.182543 +0.831314 0.182543 +0.116098 0.092338 +0.116098 0.083481 +0.218949 0.083481 +0.218949 0.092338 +0.137131 0.240992 +0.239987 0.240992 +0.257388 0.105279 +0.257388 0.114136 +0.431318 0.192395 +0.431318 0.183537 +0.028294 0.161426 +0.845851 0.072634 +0.028294 0.126921 +0.965740 0.103010 +0.307570 0.173685 +0.412003 0.173685 +0.412003 0.182543 +0.307570 0.182543 +0.965740 0.137515 +0.731259 0.073629 +0.289884 0.082486 +0.731927 0.072634 +0.959607 0.130099 +0.187033 0.082486 +0.731259 0.082486 +0.725300 0.173685 +0.427377 0.203242 +0.114079 0.192395 +0.831314 0.173685 +0.422159 0.193390 +0.119991 0.253147 +0.119991 0.226887 +0.640183 0.192395 +0.870491 0.173685 +0.114079 0.183537 +0.526586 0.203242 +0.725300 0.182543 +0.959607 0.109870 +0.034427 0.133781 +0.631023 0.193390 +0.240187 0.213094 +0.213293 0.203242 +0.731927 0.063777 +0.504246 0.130099 +0.321229 0.110195 +0.640183 0.183537 +0.535750 0.192395 +0.535750 0.183537 +0.422159 0.202247 +0.282479 0.110195 +0.845851 0.063777 +0.034427 0.154011 +0.213293 0.212099 +0.272692 0.213094 +0.631023 0.202247 +0.499693 0.130099 +0.489788 0.108802 +0.204719 0.182543 +0.618003 0.072634 +0.499693 0.084891 +0.622449 0.182543 +0.216930 0.183537 +0.499693 0.072634 +0.494341 0.108802 +0.628408 0.082486 +0.322944 0.202247 +0.739397 0.183537 +0.628408 0.073629 +0.499693 0.063777 +0.504246 0.084891 +0.531809 0.202247 +0.114079 0.212099 +0.216930 0.192395 +0.114079 0.203242 +0.531809 0.193390 +0.622449 0.173685 +0.618003 0.063777 +0.494341 0.154011 +0.739397 0.192395 +0.322944 0.193390 +0.204719 0.173685 +0.731927 0.090087 +0.489788 0.154011 +0.489788 0.101481 +0.494341 0.101481 +0.721194 0.096792 +0.376031 0.161426 +0.965740 0.063777 +0.621974 0.091349 +0.618086 0.083828 +0.845851 0.137515 +0.262107 0.161426 +0.266001 0.154011 +0.731927 0.137515 +0.965740 0.072634 +0.365210 0.154011 +0.262107 0.113998 +0.251375 0.121881 +0.295406 0.073629 +0.237159 0.114136 +0.735821 0.130099 +0.835029 0.130099 +0.237159 0.105279 +0.398258 0.073629 +0.413584 0.173685 +0.152155 0.127323 +0.148267 0.120257 +0.100286 0.173685 +0.203138 0.173685 +0.952512 0.109481 +0.849655 0.103838 +0.516435 0.173685 +0.148183 0.161426 +0.137278 0.154011 +0.159005 0.154011 +0.258213 0.154011 +0.235680 0.213094 +0.114079 0.193390 +0.845767 0.096345 +0.427377 0.193390 +0.530537 0.183537 +0.841879 0.103412 +0.153534 0.072634 +0.153534 0.063777 +0.267459 0.063777 +0.267459 0.072634 +0.386937 0.154011 +0.636242 0.193390 +0.061315 0.073629 +0.494341 0.160923 +0.742659 0.097969 +0.511342 0.085280 +0.277625 0.221951 +0.218512 0.193390 +0.494341 0.161426 +0.398258 0.082486 +0.317726 0.193390 +0.277625 0.213094 +0.516435 0.182543 +0.482692 0.109192 +0.379836 0.114834 +0.829732 0.182543 +0.341323 0.213094 +0.504246 0.077570 +0.061315 0.082486 +0.735456 0.193390 +0.518016 0.173685 +0.614198 0.090922 +0.239987 0.249849 +0.381383 0.072634 +0.381383 0.063777 +0.033645 0.072634 +0.033645 0.063777 +0.065368 0.073629 +0.110576 0.073629 +0.620867 0.173685 +0.137131 0.249849 +0.375948 0.107740 +0.530537 0.192395 +0.526591 0.193390 +0.726881 0.182543 +0.341323 0.221951 +0.618003 0.137515 +0.499693 0.137515 +0.499693 0.137011 +0.413584 0.182543 +0.213294 0.193390 +0.235680 0.221951 +0.295406 0.082486 +0.726881 0.173685 +0.735456 0.202247 +0.526591 0.202247 +0.620867 0.182543 +0.317726 0.202247 +0.213294 0.202247 +0.218512 0.202247 +0.114079 0.202247 +0.427377 0.202247 +0.518016 0.182543 +0.829732 0.173685 +0.636242 0.202247 +0.607097 0.130099 +0.872693 0.173685 +0.905625 0.173685 +0.905625 0.182543 +0.872693 0.182543 +0.628824 0.130099 +0.728033 0.130099 +0.856756 0.130099 +0.735815 0.097594 +0.728039 0.097167 +0.621980 0.130099 +0.614192 0.130099 +0.849661 0.130099 +0.841873 0.130099 +0.499693 0.077570 +0.033645 0.103010 +0.039778 0.109870 +0.039778 0.130099 +0.033645 0.137515 +0.495139 0.130099 +0.495139 0.084891 +0.267459 0.090087 +0.381299 0.083828 +0.377411 0.091349 +0.278191 0.096792 +0.153534 0.137515 +0.164356 0.130099 +0.263565 0.130099 +0.267459 0.137515 +0.153618 0.096345 +0.149730 0.103838 +0.046874 0.109481 +0.256726 0.097969 +0.157506 0.103412 +0.488044 0.085280 +0.385187 0.090922 +0.495139 0.077570 +0.381383 0.137515 +0.392288 0.130099 +0.271352 0.130099 +0.370561 0.130099 +0.142629 0.130099 +0.271347 0.097167 +0.263570 0.097594 +0.377405 0.130099 +0.385193 0.130099 +0.157512 0.130099 +0.149724 0.130099 +0.372060 0.115260 +0.272840 0.120703 +0.041522 0.133392 +0.144379 0.127750 +0.144373 0.154011 +0.152161 0.154011 +0.372054 0.154011 +0.379842 0.154011 +0.258219 0.121505 +0.265995 0.121079 +0.960389 0.161426 +0.954256 0.154011 +0.954256 0.133781 +0.960389 0.126922 +0.498895 0.108802 +0.498895 0.154011 +0.498895 0.101481 +0.612651 0.161426 +0.623473 0.154011 +0.722682 0.154011 +0.726575 0.161426 +0.726575 0.113998 +0.840416 0.120257 +0.836528 0.127323 +0.737308 0.121881 +0.840499 0.161426 +0.851405 0.154011 +0.730469 0.154011 +0.829678 0.154011 +0.601746 0.154011 +0.612735 0.107740 +0.608847 0.114834 +0.505990 0.109192 +0.715843 0.120703 +0.616623 0.115261 +0.947160 0.133392 +0.844304 0.127750 +0.836522 0.154011 +0.844310 0.154011 +0.616629 0.154011 +0.608841 0.154011 +0.730464 0.121505 +0.722687 0.121079 +0.526586 0.212099 +0.427377 0.212099 +0.110576 0.082486 +0.065368 0.082486 +0.061315 0.092338 +0.034628 0.092338 +0.034628 0.083481 +0.061315 0.083481 +0.317721 0.203242 +0.317721 0.212099 +0.218512 0.212099 +0.218512 0.203242 +0.222453 0.183537 +0.321672 0.183537 +0.321672 0.192395 +0.222453 0.192395 +0.282479 0.101338 +0.321229 0.101338 +0.756875 0.086427 +0.736646 0.086427 +0.736646 0.077570 +0.756875 0.077570 +0.631018 0.203242 +0.631018 0.212099 +0.531809 0.212099 +0.531809 0.203242 +0.634970 0.183537 +0.634970 0.192395 +0.272692 0.221951 +0.240187 0.221951 +0.065368 0.092338 +0.065368 0.083481 +0.110576 0.083481 +0.110576 0.092338 +0.322944 0.203242 +0.422153 0.203242 +0.422153 0.212099 +0.322944 0.212099 +0.862883 0.077570 +0.965740 0.077570 +0.965740 0.086427 +0.862883 0.086427 +0.128848 0.226887 +0.128848 0.253147 +0.118996 0.255785 +0.110139 0.255785 +0.110139 0.217035 +0.118996 0.217035 +0.309151 0.182543 +0.309151 0.173685 +0.326885 0.183537 +0.426105 0.183537 +0.426105 0.192395 +0.326885 0.192395 +0.100286 0.217035 +0.109144 0.217035 +0.109144 0.256211 +0.100286 0.256211 +0.310130 0.213094 +0.310130 0.221951 +0.187033 0.073629 +0.289884 0.073629 +0.861307 0.077570 +0.861307 0.086427 +0.758451 0.086427 +0.758451 0.077570 +0.202749 0.221951 +0.202749 0.213094 +0.315063 0.221951 +0.315063 0.213094 +0.203138 0.182543 +0.100286 0.182543 +0.241563 0.243938 +0.241563 0.235081 +0.344420 0.235081 +0.344420 0.243938 +0.034628 0.082486 +0.034628 0.073629 +0.870491 0.182543 +0.831314 0.182543 +0.116098 0.092338 +0.116098 0.083481 +0.218949 0.083481 +0.218949 0.092338 +0.137131 0.240992 +0.239987 0.240992 +0.257388 0.105279 +0.257388 0.114136 +0.431318 0.192395 +0.431318 0.183537 +0.028294 0.161426 +0.845851 0.072634 +0.028294 0.126921 +0.965740 0.103010 +0.307570 0.173685 +0.412003 0.173685 +0.412003 0.182543 +0.307570 0.182543 +0.965740 0.137515 +0.731259 0.073629 +0.289884 0.082486 +0.731927 0.072634 +0.959607 0.130099 +0.187033 0.082486 +0.731259 0.082486 +0.725300 0.173685 +0.427377 0.203242 +0.114079 0.192395 +0.831314 0.173685 +0.422159 0.193390 +0.119991 0.253147 +0.119991 0.226887 +0.640183 0.192395 +0.870491 0.173685 +0.114079 0.183537 +0.526586 0.203242 +0.725300 0.182543 +0.959607 0.109870 +0.034427 0.133781 +0.631023 0.193390 +0.240187 0.213094 +0.213293 0.203242 +0.731927 0.063777 +0.504246 0.130099 +0.321229 0.110195 +0.640183 0.183537 +0.535750 0.192395 +0.535750 0.183537 +0.422159 0.202247 +0.282479 0.110195 +0.845851 0.063777 +0.034427 0.154011 +0.213293 0.212099 +0.272692 0.213094 +0.631023 0.202247 +0.499693 0.130099 +0.489788 0.108802 +0.204719 0.182543 +0.618003 0.072634 +0.499693 0.084891 +0.622449 0.182543 +0.216930 0.183537 +0.499693 0.072634 +0.494341 0.108802 +0.628408 0.082486 +0.322944 0.202247 +0.739397 0.183537 +0.628408 0.073629 +0.499693 0.063777 +0.504246 0.084891 +0.531809 0.202247 +0.114079 0.212099 +0.216930 0.192395 +0.114079 0.203242 +0.531809 0.193390 +0.622449 0.173685 +0.618003 0.063777 +0.494341 0.154011 +0.739397 0.192395 +0.322944 0.193390 +0.204719 0.173685 +0.731927 0.090087 +0.489788 0.154011 +0.489788 0.101481 +0.494341 0.101481 +0.721194 0.096792 +0.376031 0.161426 +0.965740 0.063777 +0.621974 0.091349 +0.618086 0.083828 +0.845851 0.137515 +0.262107 0.161426 +0.266001 0.154011 +0.731927 0.137515 +0.965740 0.072634 +0.365210 0.154011 +0.262107 0.113998 +0.251375 0.121881 +0.295406 0.073629 +0.237159 0.114136 +0.735821 0.130099 +0.835029 0.130099 +0.237159 0.105279 +0.398258 0.073629 +0.413584 0.173685 +0.152155 0.127323 +0.148267 0.120257 +0.100286 0.173685 +0.203138 0.173685 +0.952512 0.109481 +0.849655 0.103838 +0.516435 0.173685 +0.148183 0.161426 +0.137278 0.154011 +0.159005 0.154011 +0.258213 0.154011 +0.235680 0.213094 +0.114079 0.193390 +0.845767 0.096345 +0.427377 0.193390 +0.530537 0.183537 +0.841879 0.103412 +0.153534 0.072634 +0.153534 0.063777 +0.267459 0.063777 +0.267459 0.072634 +0.386937 0.154011 +0.636242 0.193390 +0.061315 0.073629 +0.494341 0.160923 +0.742659 0.097969 +0.511342 0.085280 +0.277625 0.221951 +0.218512 0.193390 +0.494341 0.161426 +0.398258 0.082486 +0.317726 0.193390 +0.277625 0.213094 +0.516435 0.182543 +0.482692 0.109192 +0.379836 0.114834 +0.829732 0.182543 +0.341323 0.213094 +0.504246 0.077570 +0.061315 0.082486 +0.735456 0.193390 +0.518016 0.173685 +0.614198 0.090922 +0.239987 0.249849 +0.381383 0.072634 +0.381383 0.063777 +0.033645 0.072634 +0.033645 0.063777 +0.065368 0.073629 +0.110576 0.073629 +0.620867 0.173685 +0.137131 0.249849 +0.375948 0.107740 +0.530537 0.192395 +0.526591 0.193390 +0.726881 0.182543 +0.341323 0.221951 +0.618003 0.137515 +0.499693 0.137515 +0.499693 0.137011 +0.413584 0.182543 +0.213294 0.193390 +0.235680 0.221951 +0.295406 0.082486 +0.726881 0.173685 +0.735456 0.202247 +0.526591 0.202247 +0.620867 0.182543 +0.317726 0.202247 +0.213294 0.202247 +0.218512 0.202247 +0.114079 0.202247 +0.427377 0.202247 +0.518016 0.182543 +0.829732 0.173685 +0.636242 0.202247 +0.607097 0.130099 +0.872693 0.173685 +0.905625 0.173685 +0.905625 0.182543 +0.872693 0.182543 +0.628824 0.130099 +0.728033 0.130099 +0.856756 0.130099 +0.735815 0.097594 +0.728039 0.097167 +0.621980 0.130099 +0.614192 0.130099 +0.849661 0.130099 +0.841873 0.130099 +0.499693 0.077570 +0.033645 0.103010 +0.039778 0.109870 +0.039778 0.130099 +0.033645 0.137515 +0.495139 0.130099 +0.495139 0.084891 +0.267459 0.090087 +0.381299 0.083828 +0.377411 0.091349 +0.278191 0.096792 +0.153534 0.137515 +0.164356 0.130099 +0.263565 0.130099 +0.267459 0.137515 +0.153618 0.096345 +0.149730 0.103838 +0.046874 0.109481 +0.256726 0.097969 +0.157506 0.103412 +0.488044 0.085280 +0.385187 0.090922 +0.495139 0.077570 +0.381383 0.137515 +0.392288 0.130099 +0.271352 0.130099 +0.370561 0.130099 +0.142629 0.130099 +0.271347 0.097167 +0.263570 0.097594 +0.377405 0.130099 +0.385193 0.130099 +0.157512 0.130099 +0.149724 0.130099 +0.372060 0.115260 +0.272840 0.120703 +0.041522 0.133392 +0.144379 0.127750 +0.144373 0.154011 +0.152161 0.154011 +0.372054 0.154011 +0.379842 0.154011 +0.258219 0.121505 +0.265995 0.121079 +0.960389 0.161426 +0.954256 0.154011 +0.954256 0.133781 +0.960389 0.126922 +0.498895 0.108802 +0.498895 0.154011 +0.498895 0.101481 +0.612651 0.161426 +0.623473 0.154011 +0.722682 0.154011 +0.726575 0.161426 +0.726575 0.113998 +0.840416 0.120257 +0.836528 0.127323 +0.737308 0.121881 +0.840499 0.161426 +0.851405 0.154011 +0.730469 0.154011 +0.829678 0.154011 +0.601746 0.154011 +0.612735 0.107740 +0.608847 0.114834 +0.505990 0.109192 +0.715843 0.120703 +0.616623 0.115261 +0.947160 0.133392 +0.844304 0.127750 +0.836522 0.154011 +0.844310 0.154011 +0.616629 0.154011 +0.608841 0.154011 +0.730464 0.121505 +0.722687 0.121079 +0.526586 0.212099 +0.427377 0.212099 +0.110576 0.082486 +0.065368 0.082486 +0.061315 0.092338 +0.034628 0.092338 +0.034628 0.083481 +0.061315 0.083481 +0.317721 0.203242 +0.317721 0.212099 +0.218512 0.212099 +0.218512 0.203242 +0.222453 0.183537 +0.321672 0.183537 +0.321672 0.192395 +0.222453 0.192395 +0.282479 0.101338 +0.321229 0.101338 +0.756875 0.086427 +0.736646 0.086427 +0.736646 0.077570 +0.756875 0.077570 +0.631018 0.203242 +0.631018 0.212099 +0.531809 0.212099 +0.531809 0.203242 +0.634970 0.183537 +0.634970 0.192395 +0.272692 0.221951 +0.240187 0.221951 +0.065368 0.092338 +0.065368 0.083481 +0.110576 0.083481 +0.110576 0.092338 +0.322944 0.203242 +0.422153 0.203242 +0.422153 0.212099 +0.322944 0.212099 +0.862883 0.077570 +0.965740 0.077570 +0.965740 0.086427 +0.862883 0.086427 +0.128848 0.226887 +0.128848 0.253147 +0.118996 0.255785 +0.110139 0.255785 +0.110139 0.217035 +0.118996 0.217035 +0.309151 0.182543 +0.309151 0.173685 +0.326885 0.183537 +0.426105 0.183537 +0.426105 0.192395 +0.326885 0.192395 +0.100286 0.217035 +0.109144 0.217035 +0.109144 0.256211 +0.100286 0.256211 +0.310130 0.213094 +0.310130 0.221951 +0.187033 0.073629 +0.289884 0.073629 +0.861307 0.077570 +0.861307 0.086427 +0.758451 0.086427 +0.758451 0.077570 +0.202749 0.221951 +0.202749 0.213094 +0.315063 0.221951 +0.315063 0.213094 +0.203138 0.182543 +0.100286 0.182543 +0.241563 0.243938 +0.241563 0.235081 +0.344420 0.235081 +0.344420 0.243938 +0.034628 0.082486 +0.034628 0.073629 +0.870491 0.182543 +0.831314 0.182543 +0.116098 0.092338 +0.116098 0.083481 +0.218949 0.083481 +0.218949 0.092338 +0.137131 0.240992 +0.239987 0.240992 +0.257388 0.105279 +0.257388 0.114136 +0.431318 0.192395 +0.431318 0.183537 +0.028294 0.161426 +0.845851 0.072634 +0.028294 0.126921 +0.965740 0.103010 +0.307570 0.173685 +0.412003 0.173685 +0.412003 0.182543 +0.307570 0.182543 +0.965740 0.137515 +0.731259 0.073629 +0.289884 0.082486 +0.731927 0.072634 +0.959607 0.130099 +0.187033 0.082486 +0.731259 0.082486 +0.725300 0.173685 +0.427377 0.203242 +0.114079 0.192395 +0.831314 0.173685 +0.422159 0.193390 +0.119991 0.253147 +0.119991 0.226887 +0.640183 0.192395 +0.870491 0.173685 +0.114079 0.183537 +0.526586 0.203242 +0.725300 0.182543 +0.959607 0.109870 +0.034427 0.133781 +0.631023 0.193390 +0.240187 0.213094 +0.213293 0.203242 +0.731927 0.063777 +0.504246 0.130099 +0.321229 0.110195 +0.640183 0.183537 +0.535750 0.192395 +0.535750 0.183537 +0.422159 0.202247 +0.282479 0.110195 +0.845851 0.063777 +0.034427 0.154011 +0.213293 0.212099 +0.272692 0.213094 +0.631023 0.202247 +0.499693 0.130099 +0.489788 0.108802 +0.204719 0.182543 +0.618003 0.072634 +0.499693 0.084891 +0.622449 0.182543 +0.216930 0.183537 +0.499693 0.072634 +0.494341 0.108802 +0.628408 0.082486 +0.322944 0.202247 +0.739397 0.183537 +0.628408 0.073629 +0.499693 0.063777 +0.504246 0.084891 +0.531809 0.202247 +0.114079 0.212099 +0.216930 0.192395 +0.114079 0.203242 +0.531809 0.193390 +0.622449 0.173685 +0.618003 0.063777 +0.494341 0.154011 +0.739397 0.192395 +0.322944 0.193390 +0.204719 0.173685 +0.731927 0.090087 +0.489788 0.154011 +0.489788 0.101481 +0.494341 0.101481 +0.721194 0.096792 +0.376031 0.161426 +0.965740 0.063777 +0.621974 0.091349 +0.618086 0.083828 +0.845851 0.137515 +0.262107 0.161426 +0.266001 0.154011 +0.731927 0.137515 +0.965740 0.072634 +0.365210 0.154011 +0.262107 0.113998 +0.251375 0.121881 +0.295406 0.073629 +0.237159 0.114136 +0.735821 0.130099 +0.835029 0.130099 +0.237159 0.105279 +0.398258 0.073629 +0.413584 0.173685 +0.152155 0.127323 +0.148267 0.120257 +0.100286 0.173685 +0.203138 0.173685 +0.952512 0.109481 +0.849655 0.103838 +0.516435 0.173685 +0.148183 0.161426 +0.137278 0.154011 +0.159005 0.154011 +0.258213 0.154011 +0.235680 0.213094 +0.114079 0.193390 +0.845767 0.096345 +0.427377 0.193390 +0.530537 0.183537 +0.841879 0.103412 +0.153534 0.072634 +0.153534 0.063777 +0.267459 0.063777 +0.267459 0.072634 +0.386937 0.154011 +0.636242 0.193390 +0.061315 0.073629 +0.494341 0.160923 +0.742659 0.097969 +0.511342 0.085280 +0.277625 0.221951 +0.218512 0.193390 +0.494341 0.161426 +0.398258 0.082486 +0.317726 0.193390 +0.277625 0.213094 +0.516435 0.182543 +0.482692 0.109192 +0.379836 0.114834 +0.829732 0.182543 +0.341323 0.213094 +0.504246 0.077570 +0.061315 0.082486 +0.735456 0.193390 +0.518016 0.173685 +0.614198 0.090922 +0.239987 0.249849 +0.381383 0.072634 +0.381383 0.063777 +0.033645 0.072634 +0.033645 0.063777 +0.065368 0.073629 +0.110576 0.073629 +0.620867 0.173685 +0.137131 0.249849 +0.375948 0.107740 +0.530537 0.192395 +0.526591 0.193390 +0.726881 0.182543 +0.341323 0.221951 +0.618003 0.137515 +0.499693 0.137515 +0.499693 0.137011 +0.413584 0.182543 +0.213294 0.193390 +0.235680 0.221951 +0.295406 0.082486 +0.726881 0.173685 +0.735456 0.202247 +0.526591 0.202247 +0.620867 0.182543 +0.317726 0.202247 +0.213294 0.202247 +0.218512 0.202247 +0.114079 0.202247 +0.427377 0.202247 +0.518016 0.182543 +0.829732 0.173685 +0.636242 0.202247 +0.607097 0.130099 +0.872693 0.173685 +0.905625 0.173685 +0.905625 0.182543 +0.872693 0.182543 +0.628824 0.130099 +0.728033 0.130099 +0.856756 0.130099 +0.735815 0.097594 +0.728039 0.097167 +0.621980 0.130099 +0.614192 0.130099 +0.849661 0.130099 +0.841873 0.130099 +0.499693 0.077570 +0.033645 0.103010 +0.039778 0.109870 +0.039778 0.130099 +0.033645 0.137515 +0.495139 0.130099 +0.495139 0.084891 +0.267459 0.090087 +0.381299 0.083828 +0.377411 0.091349 +0.278191 0.096792 +0.153534 0.137515 +0.164356 0.130099 +0.263565 0.130099 +0.267459 0.137515 +0.153618 0.096345 +0.149730 0.103838 +0.046874 0.109481 +0.256726 0.097969 +0.157506 0.103412 +0.488044 0.085280 +0.385187 0.090922 +0.495139 0.077570 +0.381383 0.137515 +0.392288 0.130099 +0.271352 0.130099 +0.370561 0.130099 +0.142629 0.130099 +0.271347 0.097167 +0.263570 0.097594 +0.377405 0.130099 +0.385193 0.130099 +0.157512 0.130099 +0.149724 0.130099 +0.372060 0.115260 +0.272840 0.120703 +0.041522 0.133392 +0.144379 0.127750 +0.144373 0.154011 +0.152161 0.154011 +0.372054 0.154011 +0.379842 0.154011 +0.258219 0.121505 +0.265995 0.121079 +0.960389 0.161426 +0.954256 0.154011 +0.954256 0.133781 +0.960389 0.126922 +0.498895 0.108802 +0.498895 0.154011 +0.498895 0.101481 +0.612651 0.161426 +0.623473 0.154011 +0.722682 0.154011 +0.726575 0.161426 +0.726575 0.113998 +0.840416 0.120257 +0.836528 0.127323 +0.737308 0.121881 +0.840499 0.161426 +0.851405 0.154011 +0.730469 0.154011 +0.829678 0.154011 +0.601746 0.154011 +0.612735 0.107740 +0.608847 0.114834 +0.505990 0.109192 +0.715843 0.120703 +0.616623 0.115261 +0.947160 0.133392 +0.844304 0.127750 +0.836522 0.154011 +0.844310 0.154011 +0.616629 0.154011 +0.608841 0.154011 +0.730464 0.121505 +0.722687 0.121079 +0.526586 0.212099 +0.427377 0.212099 +0.110576 0.082486 +0.065368 0.082486 +0.061315 0.092338 +0.034628 0.092338 +0.034628 0.083481 +0.061315 0.083481 +0.317721 0.203242 +0.317721 0.212099 +0.218512 0.212099 +0.218512 0.203242 +0.222453 0.183537 +0.321672 0.183537 +0.321672 0.192395 +0.222453 0.192395 +0.282479 0.101338 +0.321229 0.101338 +0.756875 0.086427 +0.736646 0.086427 +0.736646 0.077570 +0.756875 0.077570 +0.631018 0.203242 +0.631018 0.212099 +0.531809 0.212099 +0.531809 0.203242 +0.634970 0.183537 +0.634970 0.192395 +0.272692 0.221951 +0.240187 0.221951 +0.065368 0.092338 +0.065368 0.083481 +0.110576 0.083481 +0.110576 0.092338 +0.322944 0.203242 +0.422153 0.203242 +0.422153 0.212099 +0.322944 0.212099 +0.862883 0.077570 +0.965740 0.077570 +0.965740 0.086427 +0.862883 0.086427 +0.128848 0.226887 +0.128848 0.253147 +0.118996 0.255785 +0.110139 0.255785 +0.110139 0.217035 +0.118996 0.217035 +0.309151 0.182543 +0.309151 0.173685 +0.326885 0.183537 +0.426105 0.183537 +0.426105 0.192395 +0.326885 0.192395 +0.100286 0.217035 +0.109144 0.217035 +0.109144 0.256211 +0.100286 0.256211 +0.310130 0.213094 +0.310130 0.221951 +0.187033 0.073629 +0.289884 0.073629 +0.861307 0.077570 +0.861307 0.086427 +0.758451 0.086427 +0.758451 0.077570 +0.202749 0.221951 +0.202749 0.213094 +0.315063 0.221951 +0.315063 0.213094 +0.203138 0.182543 +0.100286 0.182543 +0.241563 0.243938 +0.241563 0.235081 +0.344420 0.235081 +0.344420 0.243938 +0.034628 0.082486 +0.034628 0.073629 +0.870491 0.182543 +0.831314 0.182543 +0.116098 0.092338 +0.116098 0.083481 +0.218949 0.083481 +0.218949 0.092338 +0.137131 0.240992 +0.239987 0.240992 +0.257388 0.105279 +0.257388 0.114136 +0.431318 0.192395 +0.431318 0.183537 +0.274782 0.709736 +0.361876 0.709736 +0.361876 0.970034 +0.274782 0.970034 +0.187812 0.709736 +0.187812 0.970034 +0.099276 0.706657 +0.186369 0.706657 +0.186369 0.966955 +0.099276 0.966955 +0.012306 0.706657 +0.012306 0.966955 +0.096980 0.974069 +0.096980 0.971456 +0.357278 0.971456 +0.357278 0.974069 +0.013845 0.706190 +0.013845 0.703578 +0.274143 0.703578 +0.274143 0.706190 +0.183194 0.982352 +0.270164 0.977614 +0.270164 0.980227 +0.183194 0.984965 +0.357257 0.982352 +0.357257 0.984965 +0.183194 0.979273 +0.270287 0.974535 +0.270287 0.977148 +0.183194 0.981886 +0.357257 0.979273 +0.357257 0.981886 +0.361876 0.796502 +0.361876 0.883268 +0.183746 0.974069 +0.270512 0.974069 +0.274782 0.796502 +0.274782 0.883268 +0.187812 0.883268 +0.187812 0.796502 +0.100611 0.706190 +0.187377 0.706190 +0.183746 0.971456 +0.270512 0.971456 +0.186369 0.880189 +0.186369 0.793423 +0.100611 0.703578 +0.187377 0.703578 +0.012306 0.793423 +0.012306 0.880189 +0.099276 0.880189 +0.099276 0.793423 +0.947894 0.460818 +0.947894 0.510889 +0.043280 0.510889 +0.043280 0.460818 +0.040852 0.522376 +0.946795 0.534951 +0.945103 0.559154 +0.039160 0.546579 +0.176994 0.590459 +0.126923 0.605722 +0.126923 0.566197 +0.176994 0.566197 +0.043636 0.459622 +0.948250 0.510273 +0.948250 0.534535 +0.043636 0.483883 +0.200504 0.575951 +0.250574 0.560688 +0.250574 0.600213 +0.200504 0.600213 +0.947894 0.560960 +0.300645 0.575951 +0.043280 0.560960 +0.076852 0.590459 +0.076852 0.566197 +0.300645 0.600213 +0.947894 0.460818 +0.947894 0.510889 +0.043280 0.510889 +0.043280 0.460818 +0.040852 0.522376 +0.946795 0.534951 +0.945103 0.559154 +0.039160 0.546579 +0.176994 0.590459 +0.126923 0.605722 +0.126923 0.566197 +0.176994 0.566197 +0.043636 0.459622 +0.948250 0.510273 +0.948250 0.534535 +0.043636 0.483883 +0.200504 0.575951 +0.250574 0.560688 +0.250574 0.600213 +0.200504 0.600213 +0.947894 0.560960 +0.043280 0.560960 +0.076852 0.590459 +0.076852 0.566197 +0.300645 0.575951 +0.300645 0.600213 +0.947894 0.460818 +0.947894 0.510889 +0.043280 0.510889 +0.043280 0.460818 +0.040852 0.522376 +0.946795 0.534951 +0.945103 0.559154 +0.039160 0.546579 +0.176994 0.590459 +0.126923 0.605722 +0.126923 0.566197 +0.176994 0.566197 +0.043636 0.459622 +0.948250 0.510273 +0.948250 0.534535 +0.043636 0.483883 +0.200504 0.575951 +0.250574 0.560688 +0.250574 0.600213 +0.200504 0.600213 +0.947894 0.560960 +0.043280 0.560960 +0.076852 0.590459 +0.076852 0.566197 +0.300645 0.575951 +0.300645 0.600213 +0.947894 0.460818 +0.043280 0.460818 +0.043280 0.510889 +0.947894 0.510889 +0.040852 0.522376 +0.039160 0.546579 +0.945103 0.559154 +0.946795 0.534951 +0.176994 0.590459 +0.176994 0.566197 +0.126923 0.566197 +0.126923 0.605722 +0.043636 0.459622 +0.043636 0.483883 +0.948250 0.534535 +0.948250 0.510273 +0.200504 0.575951 +0.200504 0.600213 +0.250574 0.600213 +0.250574 0.560688 +0.043280 0.560960 +0.947894 0.560960 +0.076852 0.566197 +0.076852 0.590459 +0.300645 0.600213 +0.300645 0.575951 +0.056753 0.146942 +0.056753 0.150229 +0.044853 0.150229 +0.044853 0.146942 +0.044853 0.151136 +0.056753 0.151136 +0.056753 0.154424 +0.044853 0.154424 +0.044853 0.167008 +0.044853 0.155109 +0.958938 0.155109 +0.958938 0.167008 +0.958938 0.183016 +0.958938 0.186304 +0.044853 0.186304 +0.044853 0.183016 +0.958938 0.169371 +0.958938 0.181270 +0.044853 0.181270 +0.044853 0.169371 +0.044853 0.191338 +0.044853 0.188050 +0.958938 0.188050 +0.958938 0.191338 +0.056753 0.146942 +0.056753 0.150229 +0.044853 0.150229 +0.044853 0.146942 +0.044853 0.151136 +0.056753 0.151136 +0.056753 0.154424 +0.044853 0.154424 +0.044853 0.167008 +0.044853 0.155109 +0.958938 0.155109 +0.958938 0.167008 +0.958938 0.183016 +0.958938 0.186304 +0.044853 0.186304 +0.044853 0.183016 +0.958938 0.169371 +0.958938 0.181270 +0.044853 0.181270 +0.044853 0.169371 +0.044853 0.191338 +0.044853 0.188050 +0.958938 0.188050 +0.958938 0.191338 + + + + + + + + + + + +

0 0 8 10 1 0 8 2 1 1 3 9 10 4 0 0 5 8 2 6 3 11 7 17 10 8 18 2 9 3 10 10 18 1 11 2 18 12 34 1 13 4 17 14 5 1 15 4 18 16 34 2 17 35 17 18 5 19 19 43 18 20 34 9 21 13 3 22 10 0 23 11 9 24 13 0 25 11 8 26 12 22 27 26 10 28 14 11 29 15 10 30 14 22 31 26 24 32 27 22 33 26 23 34 48 24 35 27 27 36 20 26 37 21 25 38 22 4 39 24 15 40 25 5 41 7 14 42 6 5 43 7 15 44 25 16 45 29 21 46 30 20 47 31 12 48 38 6 49 36 7 50 37 6 51 36 12 52 38 13 53 39 4 54 28 17 55 33 6 56 19 16 57 16 6 58 19 17 59 33 19 60 43 4 61 44 5 62 45 4 63 44 19 64 43 17 65 5 15 66 51 23 67 48 14 68 49 23 69 48 15 70 51 24 71 27 13 72 50 24 73 40 15 74 42 24 75 40 13 76 50 27 77 55 26 78 21 13 79 23 12 80 52 13 81 23 26 82 21 27 83 20 8 84 54 25 85 22 9 86 53 25 87 22 8 88 54 27 89 20 21 90 30 0 91 32 3 92 41 0 93 32 21 94 30 16 95 29 6 96 47 20 97 31 7 98 46 20 99 31 6 100 47 16 101 29 27 102 55 8 103 1 24 104 40 10 105 0 24 106 40 8 107 1 17 108 33 0 109 8 16 110 16 0 111 8 17 112 33 1 113 9 15 114 42 4 115 28 6 116 19 15 117 42 6 118 19 13 119 50 37 120 97 28 121 58 36 122 84 29 123 56 28 124 58 37 125 97 30 126 59 38 127 64 39 128 68 30 129 59 39 130 68 40 131 83 32 132 128 31 133 102 95 134 109 95 135 109 109 136 123 32 137 128 94 138 105 33 139 89 112 140 101 33 141 89 94 142 105 34 143 115 93 144 129 97 145 130 31 146 102 97 147 130 95 148 109 31 149 102 77 150 141 65 151 137 42 152 138 87 153 132 65 154 137 77 155 141 81 156 131 53 157 135 91 158 127 53 159 135 81 160 131 59 161 134 58 162 88 80 163 96 65 164 67 75 165 57 65 166 67 80 167 96 84 168 143 54 169 152 92 170 142 54 171 152 84 172 143 62 173 151 88 174 147 58 175 139 67 176 146 80 177 136 58 178 139 88 179 147 79 180 159 29 181 56 37 182 97 75 183 158 29 184 56 79 185 159 65 186 137 78 187 160 56 188 161 78 189 160 65 190 137 75 191 158 32 192 128 99 193 180 71 194 172 71 195 172 99 196 180 87 197 132 99 198 180 32 199 128 136 200 175 83 201 155 69 202 164 30 203 59 69 204 164 83 205 155 46 206 156 82 207 176 69 208 164 61 209 167 91 210 127 69 211 164 82 212 176 35 213 189 53 214 135 73 215 177 73 216 177 53 217 135 44 218 193 96 219 114 72 220 122 99 221 108 87 222 104 99 223 108 72 224 122 72 225 122 58 226 88 87 227 104 65 228 67 87 229 104 58 230 88 75 231 57 38 232 133 29 233 140 38 234 133 75 235 57 80 236 96 86 237 185 70 238 203 93 239 129 70 240 203 86 241 185 49 242 186 85 243 276 70 244 203 64 245 275 92 246 142 70 247 203 85 248 276 28 249 58 54 250 152 74 251 277 74 252 277 54 253 152 47 254 278 33 255 89 96 256 209 98 257 210 90 258 227 96 259 209 33 260 89 72 261 208 96 262 209 90 263 227 58 264 139 89 265 232 51 266 233 89 267 232 58 268 139 72 269 208 38 270 64 76 271 234 39 272 68 76 273 234 38 274 64 80 275 136 75 276 158 43 277 279 57 278 280 65 279 137 56 280 161 42 281 138 55 282 281 41 283 282 87 284 132 69 285 164 46 286 156 61 287 167 91 288 127 60 289 235 45 290 236 59 291 134 44 292 193 53 293 135 49 294 186 41 295 282 64 296 275 64 297 275 41 298 282 55 299 281 63 300 284 42 301 138 48 302 283 48 303 283 42 304 138 56 305 161 62 306 151 57 307 280 47 308 278 47 309 278 57 310 280 43 311 279 59 312 134 52 313 238 44 314 193 52 315 238 59 316 134 68 317 237 60 318 235 51 319 233 45 320 236 51 321 233 60 322 235 67 323 146 46 324 156 66 325 240 61 326 167 66 327 240 46 328 156 50 329 239 70 330 203 49 331 186 64 332 275 92 333 142 63 334 284 48 335 283 62 336 151 47 337 278 54 338 152 72 339 208 52 340 238 68 341 237 58 342 139 51 343 233 67 344 146 66 345 240 50 346 239 80 347 136 33 348 320 34 349 321 31 350 199 31 351 199 32 352 200 33 353 320 90 354 62 33 355 366 32 356 367 90 357 62 32 358 367 71 359 61 49 360 79 52 361 397 41 362 74 52 363 397 49 364 79 44 365 396 86 366 390 44 367 392 49 368 393 44 369 392 86 370 390 73 371 391 45 372 230 42 373 228 63 374 229 42 375 228 45 376 230 51 377 231 64 378 331 81 379 333 85 380 330 81 381 333 64 382 331 59 383 332 68 384 334 59 385 335 64 386 90 64 387 90 55 388 95 68 389 334 51 390 318 89 391 319 77 392 72 51 393 318 77 394 72 42 395 81 62 396 323 66 397 325 57 398 322 66 399 325 62 400 323 61 401 324 84 402 92 61 403 344 62 404 345 61 405 344 84 406 92 82 407 93 67 408 346 60 409 347 48 410 86 48 411 86 56 412 99 67 413 346 56 414 329 88 415 327 67 416 328 88 417 327 56 418 329 78 419 326 50 420 360 46 421 361 47 422 76 47 423 76 43 424 77 50 425 360 39 426 378 76 427 379 79 428 66 39 429 378 79 430 66 37 431 69 40 432 338 37 433 336 36 434 337 37 435 336 40 436 338 39 437 339 47 438 357 83 439 359 74 440 356 83 441 359 47 442 357 46 443 358 77 444 141 55 445 281 87 446 132 91 447 127 45 448 236 81 449 131 92 450 142 48 451 283 84 452 143 88 453 147 66 454 240 80 455 136 79 456 159 43 457 279 75 458 158 75 459 158 57 460 280 78 461 160 87 462 132 41 463 282 71 464 172 30 465 59 40 466 83 83 467 155 82 468 176 60 469 235 91 470 127 73 471 177 34 472 115 35 473 189 93 474 129 31 475 102 86 476 185 85 477 276 63 478 284 92 479 142 74 480 277 36 481 84 28 482 58 90 483 227 52 484 238 72 485 208 72 486 208 68 487 237 89 488 232 80 489 136 50 490 239 76 491 234 41 492 282 86 493 185 71 494 172 31 495 102 71 496 172 86 497 185 52 498 82 86 499 121 41 500 71 86 501 121 52 502 82 73 503 106 73 504 177 52 505 238 90 506 227 90 507 227 34 508 115 73 509 177 31 510 103 90 511 60 71 512 63 90 513 60 31 514 103 34 515 126 45 516 236 89 517 232 81 518 131 68 519 237 81 520 131 89 521 232 77 522 111 45 523 75 63 524 94 45 525 75 77 526 111 89 527 125 85 528 276 77 529 141 63 530 284 85 531 276 55 532 281 77 533 141 68 534 116 85 535 85 81 536 100 85 537 85 68 538 116 55 539 120 57 540 280 84 541 143 78 542 160 48 543 283 78 544 160 84 545 143 82 546 117 57 547 87 66 548 98 57 549 87 82 550 117 84 551 119 82 552 176 66 553 240 88 554 147 88 555 147 60 556 235 82 557 176 48 558 112 88 559 78 78 560 91 88 561 78 48 562 112 60 563 124 50 564 239 83 565 155 76 566 234 40 567 83 76 568 234 83 569 155 43 570 80 74 571 107 50 572 73 83 573 118 50 574 73 74 575 107 74 576 277 43 577 279 79 578 159 79 579 159 36 580 84 74 581 277 76 582 70 40 583 110 79 584 65 36 585 113 79 586 65 40 587 110 136 588 175 32 589 128 109 590 123 169 591 241 35 592 189 94 593 105 35 594 189 34 595 115 94 596 105 112 597 101 33 598 89 98 599 210 101 600 288 103 601 286 102 602 287 101 603 288 100 604 285 103 605 286 106 606 244 105 607 242 107 608 243 104 609 245 105 610 242 106 611 244 108 612 289 110 613 290 95 614 109 95 615 109 110 616 290 109 617 123 94 618 105 111 619 246 113 620 247 111 621 246 94 622 105 112 623 101 97 624 130 114 625 291 108 626 289 97 627 130 108 628 289 95 629 109 116 630 295 115 631 292 118 632 293 118 633 293 117 634 294 116 635 295 122 636 249 120 637 251 119 638 248 120 639 251 122 640 249 121 641 250 116 642 171 123 643 168 125 644 169 116 645 171 125 646 169 124 647 170 129 648 297 127 649 299 126 650 296 127 651 299 129 652 297 128 653 298 124 654 255 125 655 252 131 656 253 131 657 253 130 658 254 124 659 255 100 660 285 123 661 300 132 662 301 132 663 301 103 664 286 100 665 285 116 666 295 133 667 303 123 668 300 133 669 303 116 670 295 134 671 302 110 672 290 99 673 180 136 674 175 99 675 180 135 676 304 115 677 292 135 678 304 99 679 180 110 680 290 139 681 256 137 682 258 105 683 242 137 684 258 139 685 256 138 686 257 139 687 256 119 688 248 141 689 259 139 690 256 141 691 259 140 692 260 122 693 249 143 694 263 142 695 261 122 696 249 142 697 261 144 698 262 99 699 108 115 700 195 145 701 196 99 702 108 145 703 196 96 704 114 115 705 195 116 706 171 124 707 170 115 708 195 124 709 170 145 710 196 123 711 168 100 712 197 104 713 198 123 714 168 104 715 198 125 716 169 148 717 305 146 718 307 114 719 291 146 720 307 148 721 305 147 722 306 148 723 305 126 724 296 150 725 308 148 726 305 150 727 308 149 728 309 129 729 297 101 730 288 151 731 310 129 732 297 151 733 310 152 734 311 96 735 209 145 736 264 153 737 265 96 738 209 153 739 265 111 740 246 96 741 209 111 742 246 98 743 210 124 744 255 154 745 267 145 746 264 154 747 267 124 748 255 155 749 266 104 750 245 156 751 268 125 752 252 156 753 268 104 754 245 106 755 244 123 756 300 158 757 312 157 758 313 116 759 295 117 760 294 134 761 302 159 762 314 115 763 292 160 764 315 139 765 256 140 766 260 138 767 257 119 768 248 162 769 269 161 770 270 121 771 250 122 772 249 144 773 262 160 774 315 147 775 306 149 776 309 149 777 309 159 778 314 160 779 315 117 780 294 164 781 317 163 782 316 163 783 316 134 784 302 117 785 294 152 786 311 158 787 312 128 788 298 158 789 312 152 790 311 157 791 313 121 792 250 166 793 272 165 794 271 166 795 272 121 796 250 144 797 262 161 798 270 155 799 266 130 800 254 155 801 266 161 802 270 162 803 269 138 804 257 168 805 273 167 806 274 168 807 273 138 808 257 140 809 260 148 810 305 149 811 309 147 812 306 126 813 296 163 814 316 164 815 317 128 816 298 129 817 297 152 818 311 145 819 264 165 820 271 166 821 272 124 822 255 130 823 254 155 824 266 168 825 273 125 826 252 167 827 274 113 828 349 111 829 350 108 830 348 108 831 348 111 832 350 110 833 351 153 834 389 110 835 154 111 836 388 110 837 154 153 838 389 135 839 153 147 840 375 166 841 373 144 842 374 166 843 373 147 844 375 160 845 372 144 846 402 146 847 194 147 848 202 146 849 194 144 850 402 142 851 403 164 852 385 117 853 162 162 854 384 162 855 384 117 856 162 155 857 213 120 858 204 149 859 407 150 860 166 149 861 407 120 862 204 121 863 406 121 864 363 165 865 364 149 866 362 149 867 362 165 868 364 159 869 365 155 870 342 118 871 340 154 872 341 118 873 340 155 874 342 117 875 343 128 876 395 168 877 190 140 878 394 168 879 190 128 880 395 158 881 174 140 882 370 127 883 368 128 884 369 127 885 368 140 886 370 141 887 371 161 888 183 130 889 376 163 890 178 163 891 178 130 892 376 134 893 377 131 894 355 134 895 353 130 896 354 134 897 353 131 898 355 133 899 352 138 900 207 167 901 386 152 902 188 152 903 188 167 904 386 157 905 387 106 906 400 132 907 398 156 908 399 132 909 398 106 910 400 103 911 401 102 912 405 103 913 145 107 914 404 107 915 404 103 916 145 106 917 148 137 918 381 152 919 383 151 920 380 152 921 383 137 922 381 138 923 382 118 924 293 115 925 292 159 926 314 119 927 248 120 928 251 162 929 269 126 930 296 127 931 299 163 932 316 131 933 253 125 934 252 168 935 273 132 936 301 123 937 300 157 938 313 123 939 300 133 940 303 158 941 312 115 942 292 135 943 304 160 944 315 105 945 242 137 946 258 107 947 243 141 948 259 119 949 248 161 950 270 142 951 261 143 952 263 113 953 247 114 954 291 146 955 307 108 956 289 150 957 308 126 958 296 164 959 317 151 960 310 101 961 288 102 962 287 153 963 265 145 964 264 166 965 272 145 966 264 154 967 267 165 968 271 125 969 252 156 970 268 167 971 274 146 972 307 160 973 315 135 974 304 135 975 304 108 976 289 146 977 307 166 978 224 146 979 201 142 980 218 146 981 201 166 982 224 160 983 192 113 984 247 153 985 265 142 986 261 166 987 272 142 988 261 153 989 265 108 990 184 135 991 211 153 992 150 108 993 184 153 994 150 113 995 157 120 996 251 165 997 271 154 998 267 154 999 267 162 1000 269 120 1001 251 118 1002 220 164 1003 222 162 1004 163 118 1005 220 162 1006 163 154 1007 212 159 1008 314 150 1009 308 118 1010 293 164 1011 317 118 1012 293 150 1013 308 165 1014 217 120 1015 223 150 1016 165 165 1017 217 150 1018 165 159 1019 205 127 1020 299 158 1021 312 133 1022 303 133 1023 303 163 1024 316 127 1025 299 141 1026 216 168 1027 226 158 1028 173 141 1029 216 158 1030 173 127 1031 191 168 1032 273 141 1033 259 131 1034 253 161 1035 270 131 1036 253 141 1037 259 163 1038 219 133 1039 221 131 1040 179 163 1041 219 131 1042 179 161 1043 182 137 1044 258 167 1045 274 156 1046 268 156 1047 268 107 1048 243 137 1049 258 167 1050 187 137 1051 206 151 1052 215 167 1053 187 151 1054 215 157 1055 225 157 1056 313 151 1057 310 132 1058 301 102 1059 287 132 1060 301 151 1061 310 132 1062 144 102 1063 149 107 1064 181 132 1065 144 107 1066 181 156 1067 214 136 1068 175 109 1069 123 110 1070 290 143 1071 263 169 1072 241 94 1073 105 143 1074 263 94 1075 105 113 1076 247 112 1077 101 98 1078 210 111 1079 246 179 1080 449 170 1081 410 178 1082 436 171 1083 408 170 1084 410 179 1085 449 172 1086 411 180 1087 416 181 1088 420 172 1089 411 181 1090 420 182 1091 435 174 1092 480 173 1093 454 237 1094 461 237 1095 461 251 1096 475 174 1097 480 236 1098 457 175 1099 441 254 1100 453 175 1101 441 236 1102 457 176 1103 467 235 1104 481 239 1105 482 173 1106 454 239 1107 482 237 1108 461 173 1109 454 219 1110 493 207 1111 489 184 1112 490 229 1113 484 207 1114 489 219 1115 493 223 1116 483 195 1117 487 233 1118 479 195 1119 487 223 1120 483 201 1121 486 200 1122 440 222 1123 448 207 1124 419 217 1125 409 207 1126 419 222 1127 448 226 1128 495 196 1129 504 234 1130 494 196 1131 504 226 1132 495 204 1133 503 230 1134 499 200 1135 491 209 1136 498 222 1137 488 200 1138 491 230 1139 499 221 1140 511 171 1141 408 179 1142 449 217 1143 510 171 1144 408 221 1145 511 207 1146 489 220 1147 512 198 1148 513 220 1149 512 207 1150 489 217 1151 510 174 1152 480 241 1153 532 213 1154 524 213 1155 524 241 1156 532 229 1157 484 241 1158 532 174 1159 480 278 1160 527 225 1161 507 211 1162 516 172 1163 411 211 1164 516 225 1165 507 188 1166 508 224 1167 528 211 1168 516 203 1169 519 233 1170 479 211 1171 516 224 1172 528 177 1173 541 195 1174 487 215 1175 529 215 1176 529 195 1177 487 186 1178 545 238 1179 466 214 1180 474 241 1181 460 229 1182 456 241 1183 460 214 1184 474 214 1185 474 200 1186 440 229 1187 456 207 1188 419 229 1189 456 200 1190 440 217 1191 409 180 1192 485 171 1193 492 180 1194 485 217 1195 409 222 1196 448 228 1197 537 212 1198 555 235 1199 481 212 1200 555 228 1201 537 191 1202 538 227 1203 628 212 1204 555 206 1205 627 234 1206 494 212 1207 555 227 1208 628 170 1209 410 196 1210 504 216 1211 629 216 1212 629 196 1213 504 189 1214 630 175 1215 441 238 1216 561 240 1217 562 232 1218 579 238 1219 561 175 1220 441 214 1221 560 238 1222 561 232 1223 579 200 1224 491 231 1225 584 193 1226 585 231 1227 584 200 1228 491 214 1229 560 180 1230 416 218 1231 586 181 1232 420 218 1233 586 180 1234 416 222 1235 488 217 1236 510 185 1237 631 199 1238 632 207 1239 489 198 1240 513 184 1241 490 197 1242 633 183 1243 634 229 1244 484 211 1245 516 188 1246 508 203 1247 519 233 1248 479 202 1249 587 187 1250 588 201 1251 486 186 1252 545 195 1253 487 191 1254 538 183 1255 634 206 1256 627 206 1257 627 183 1258 634 197 1259 633 205 1260 636 184 1261 490 190 1262 635 190 1263 635 184 1264 490 198 1265 513 204 1266 503 199 1267 632 189 1268 630 189 1269 630 199 1270 632 185 1271 631 201 1272 486 194 1273 590 186 1274 545 194 1275 590 201 1276 486 210 1277 589 202 1278 587 193 1279 585 187 1280 588 193 1281 585 202 1282 587 209 1283 498 188 1284 508 208 1285 592 203 1286 519 208 1287 592 188 1288 508 192 1289 591 212 1290 555 191 1291 538 206 1292 627 234 1293 494 205 1294 636 190 1295 635 204 1296 503 189 1297 630 196 1298 504 214 1299 560 194 1300 590 210 1301 589 200 1302 491 193 1303 585 209 1304 498 208 1305 592 192 1306 591 222 1307 488 175 1308 672 176 1309 673 173 1310 551 173 1311 551 174 1312 552 175 1313 672 232 1314 414 175 1315 718 174 1316 719 232 1317 414 174 1318 719 213 1319 413 191 1320 431 194 1321 749 183 1322 426 194 1323 749 191 1324 431 186 1325 748 228 1326 742 186 1327 744 191 1328 745 186 1329 744 228 1330 742 215 1331 743 187 1332 582 184 1333 580 205 1334 581 184 1335 580 187 1336 582 193 1337 583 206 1338 683 223 1339 685 227 1340 682 223 1341 685 206 1342 683 201 1343 684 210 1344 686 201 1345 687 206 1346 442 206 1347 442 197 1348 447 210 1349 686 193 1350 670 231 1351 671 219 1352 424 193 1353 670 219 1354 424 184 1355 433 204 1356 675 208 1357 677 199 1358 674 208 1359 677 204 1360 675 203 1361 676 226 1362 444 203 1363 696 204 1364 697 203 1365 696 226 1366 444 224 1367 445 209 1368 698 202 1369 699 190 1370 438 190 1371 438 198 1372 451 209 1373 698 198 1374 681 230 1375 679 209 1376 680 230 1377 679 198 1378 681 220 1379 678 192 1380 712 188 1381 713 189 1382 428 189 1383 428 185 1384 429 192 1385 712 181 1386 730 218 1387 731 221 1388 418 181 1389 730 221 1390 418 179 1391 421 182 1392 690 179 1393 688 178 1394 689 179 1395 688 182 1396 690 181 1397 691 189 1398 709 225 1399 711 216 1400 708 225 1401 711 189 1402 709 188 1403 710 219 1404 493 197 1405 633 229 1406 484 233 1407 479 187 1408 588 223 1409 483 234 1410 494 190 1411 635 226 1412 495 230 1413 499 208 1414 592 222 1415 488 221 1416 511 185 1417 631 217 1418 510 217 1419 510 199 1420 632 220 1421 512 229 1422 484 183 1423 634 213 1424 524 172 1425 411 182 1426 435 225 1427 507 224 1428 528 202 1429 587 233 1430 479 215 1431 529 176 1432 467 177 1433 541 235 1434 481 173 1435 454 228 1436 537 227 1437 628 205 1438 636 234 1439 494 216 1440 629 178 1441 436 170 1442 410 232 1443 579 194 1444 590 214 1445 560 214 1446 560 210 1447 589 231 1448 584 222 1449 488 192 1450 591 218 1451 586 183 1452 634 228 1453 537 213 1454 524 173 1455 454 213 1456 524 228 1457 537 194 1458 434 228 1459 473 183 1460 423 228 1461 473 194 1462 434 215 1463 458 215 1464 529 194 1465 590 232 1466 579 232 1467 579 176 1468 467 215 1469 529 173 1470 455 232 1471 412 213 1472 415 232 1473 412 173 1474 455 176 1475 478 187 1476 588 231 1477 584 223 1478 483 210 1479 589 223 1480 483 231 1481 584 219 1482 463 187 1483 427 205 1484 446 187 1485 427 219 1486 463 231 1487 477 227 1488 628 219 1489 493 205 1490 636 227 1491 628 197 1492 633 219 1493 493 210 1494 468 227 1495 437 223 1496 452 227 1497 437 210 1498 468 197 1499 472 199 1500 632 226 1501 495 220 1502 512 190 1503 635 220 1504 512 226 1505 495 224 1506 469 199 1507 439 208 1508 450 199 1509 439 224 1510 469 226 1511 471 224 1512 528 208 1513 592 230 1514 499 230 1515 499 202 1516 587 224 1517 528 190 1518 464 230 1519 430 220 1520 443 230 1521 430 190 1522 464 202 1523 476 192 1524 591 225 1525 507 218 1526 586 182 1527 435 218 1528 586 225 1529 507 185 1530 432 216 1531 459 192 1532 425 225 1533 470 192 1534 425 216 1535 459 216 1536 629 185 1537 631 221 1538 511 221 1539 511 178 1540 436 216 1541 629 218 1542 422 182 1543 462 221 1544 417 178 1545 465 221 1546 417 182 1547 462 278 1548 527 174 1549 480 251 1550 475 311 1551 593 177 1552 541 236 1553 457 177 1554 541 176 1555 467 236 1556 457 254 1557 453 175 1558 441 240 1559 562 243 1560 640 245 1561 638 244 1562 639 243 1563 640 242 1564 637 245 1565 638 248 1566 596 247 1567 594 249 1568 595 246 1569 597 247 1570 594 248 1571 596 250 1572 641 252 1573 642 237 1574 461 237 1575 461 252 1576 642 251 1577 475 236 1578 457 253 1579 598 255 1580 599 253 1581 598 236 1582 457 254 1583 453 239 1584 482 256 1585 643 250 1586 641 239 1587 482 250 1588 641 237 1589 461 258 1590 647 257 1591 644 260 1592 645 260 1593 645 259 1594 646 258 1595 647 264 1596 601 262 1597 603 261 1598 600 262 1599 603 264 1600 601 263 1601 602 258 1602 523 265 1603 520 267 1604 521 258 1605 523 267 1606 521 266 1607 522 271 1608 649 269 1609 651 268 1610 648 269 1611 651 271 1612 649 270 1613 650 266 1614 607 267 1615 604 273 1616 605 273 1617 605 272 1618 606 266 1619 607 242 1620 637 265 1621 652 274 1622 653 274 1623 653 245 1624 638 242 1625 637 258 1626 647 275 1627 655 265 1628 652 275 1629 655 258 1630 647 276 1631 654 252 1632 642 241 1633 532 278 1634 527 241 1635 532 277 1636 656 257 1637 644 277 1638 656 241 1639 532 252 1640 642 281 1641 608 279 1642 610 247 1643 594 279 1644 610 281 1645 608 280 1646 609 281 1647 608 261 1648 600 283 1649 611 281 1650 608 283 1651 611 282 1652 612 264 1653 601 285 1654 615 284 1655 613 264 1656 601 284 1657 613 286 1658 614 241 1659 460 257 1660 547 287 1661 548 241 1662 460 287 1663 548 238 1664 466 257 1665 547 258 1666 523 266 1667 522 257 1668 547 266 1669 522 287 1670 548 265 1671 520 242 1672 549 246 1673 550 265 1674 520 246 1675 550 267 1676 521 290 1677 657 288 1678 659 256 1679 643 288 1680 659 290 1681 657 289 1682 658 290 1683 657 268 1684 648 292 1685 660 290 1686 657 292 1687 660 291 1688 661 271 1689 649 243 1690 640 293 1691 662 271 1692 649 293 1693 662 294 1694 663 238 1695 561 287 1696 616 295 1697 617 238 1698 561 295 1699 617 253 1700 598 238 1701 561 253 1702 598 240 1703 562 266 1704 607 296 1705 619 287 1706 616 296 1707 619 266 1708 607 297 1709 618 246 1710 597 298 1711 620 267 1712 604 298 1713 620 246 1714 597 248 1715 596 265 1716 652 300 1717 664 299 1718 665 258 1719 647 259 1720 646 276 1721 654 301 1722 666 257 1723 644 302 1724 667 281 1725 608 282 1726 612 280 1727 609 261 1728 600 304 1729 621 303 1730 622 263 1731 602 264 1732 601 286 1733 614 302 1734 667 289 1735 658 291 1736 661 291 1737 661 301 1738 666 302 1739 667 259 1740 646 306 1741 669 305 1742 668 305 1743 668 276 1744 654 259 1745 646 294 1746 663 300 1747 664 270 1748 650 300 1749 664 294 1750 663 299 1751 665 263 1752 602 308 1753 624 307 1754 623 308 1755 624 263 1756 602 286 1757 614 303 1758 622 297 1759 618 272 1760 606 297 1761 618 303 1762 622 304 1763 621 280 1764 609 310 1765 625 309 1766 626 310 1767 625 280 1768 609 282 1769 612 290 1770 657 291 1771 661 289 1772 658 268 1773 648 305 1774 668 306 1775 669 270 1776 650 271 1777 649 294 1778 663 287 1779 616 307 1780 623 308 1781 624 266 1782 607 272 1783 606 297 1784 618 310 1785 625 267 1786 604 309 1787 626 255 1788 701 253 1789 702 250 1790 700 250 1791 700 253 1792 702 252 1793 703 295 1794 741 252 1795 506 253 1796 740 252 1797 506 295 1798 741 277 1799 505 289 1800 727 308 1801 725 286 1802 726 308 1803 725 289 1804 727 302 1805 724 286 1806 754 288 1807 546 289 1808 554 288 1809 546 286 1810 754 284 1811 755 306 1812 737 259 1813 514 304 1814 736 304 1815 736 259 1816 514 297 1817 565 262 1818 556 291 1819 759 292 1820 518 291 1821 759 262 1822 556 263 1823 758 263 1824 715 307 1825 716 291 1826 714 291 1827 714 307 1828 716 301 1829 717 297 1830 694 260 1831 692 296 1832 693 260 1833 692 297 1834 694 259 1835 695 270 1836 747 310 1837 542 282 1838 746 310 1839 542 270 1840 747 300 1841 526 282 1842 722 269 1843 720 270 1844 721 269 1845 720 282 1846 722 283 1847 723 303 1848 535 272 1849 728 305 1850 530 305 1851 530 272 1852 728 276 1853 729 273 1854 707 276 1855 705 272 1856 706 276 1857 705 273 1858 707 275 1859 704 280 1860 559 309 1861 738 294 1862 540 294 1863 540 309 1864 738 299 1865 739 248 1866 752 274 1867 750 298 1868 751 274 1869 750 248 1870 752 245 1871 753 244 1872 757 245 1873 497 249 1874 756 249 1875 756 245 1876 497 248 1877 500 279 1878 733 294 1879 735 293 1880 732 294 1881 735 279 1882 733 280 1883 734 260 1884 645 257 1885 644 301 1886 666 261 1887 600 262 1888 603 304 1889 621 268 1890 648 269 1891 651 305 1892 668 273 1893 605 267 1894 604 310 1895 625 274 1896 653 265 1897 652 299 1898 665 265 1899 652 275 1900 655 300 1901 664 257 1902 644 277 1903 656 302 1904 667 247 1905 594 279 1906 610 249 1907 595 283 1908 611 261 1909 600 303 1910 622 284 1911 613 285 1912 615 255 1913 599 256 1914 643 288 1915 659 250 1916 641 292 1917 660 268 1918 648 306 1919 669 293 1920 662 243 1921 640 244 1922 639 295 1923 617 287 1924 616 308 1925 624 287 1926 616 296 1927 619 307 1928 623 267 1929 604 298 1930 620 309 1931 626 288 1932 659 302 1933 667 277 1934 656 277 1935 656 250 1936 641 288 1937 659 308 1938 576 288 1939 553 284 1940 570 288 1941 553 308 1942 576 302 1943 544 255 1944 599 295 1945 617 284 1946 613 308 1947 624 284 1948 613 295 1949 617 250 1950 536 277 1951 563 295 1952 502 250 1953 536 295 1954 502 255 1955 509 262 1956 603 307 1957 623 296 1958 619 296 1959 619 304 1960 621 262 1961 603 260 1962 572 306 1963 574 304 1964 515 260 1965 572 304 1966 515 296 1967 564 301 1968 666 292 1969 660 260 1970 645 306 1971 669 260 1972 645 292 1973 660 307 1974 569 262 1975 575 292 1976 517 307 1977 569 292 1978 517 301 1979 557 269 1980 651 300 1981 664 275 1982 655 275 1983 655 305 1984 668 269 1985 651 283 1986 568 310 1987 578 300 1988 525 283 1989 568 300 1990 525 269 1991 543 310 1992 625 283 1993 611 273 1994 605 303 1995 622 273 1996 605 283 1997 611 305 1998 571 275 1999 573 273 2000 531 305 2001 571 273 2002 531 303 2003 534 279 2004 610 309 2005 626 298 2006 620 298 2007 620 249 2008 595 279 2009 610 293 2010 567 309 2011 539 279 2012 558 309 2013 539 293 2014 567 299 2015 577 299 2016 665 293 2017 662 274 2018 653 244 2019 639 274 2020 653 293 2021 662 249 2022 533 274 2023 496 244 2024 501 274 2025 496 249 2026 533 298 2027 566 278 2028 527 251 2029 475 252 2030 642 285 2031 615 311 2032 593 236 2033 457 285 2034 615 236 2035 457 255 2036 599 254 2037 453 240 2038 562 253 2039 598 321 2040 801 312 2041 762 320 2042 788 313 2043 760 312 2044 762 321 2045 801 314 2046 763 322 2047 768 323 2048 772 314 2049 763 323 2050 772 324 2051 787 316 2052 832 315 2053 806 379 2054 813 379 2055 813 393 2056 827 316 2057 832 378 2058 809 317 2059 793 396 2060 805 317 2061 793 378 2062 809 318 2063 819 377 2064 833 381 2065 834 315 2066 806 381 2067 834 379 2068 813 315 2069 806 361 2070 845 349 2071 841 326 2072 842 371 2073 836 349 2074 841 361 2075 845 365 2076 835 337 2077 839 375 2078 831 337 2079 839 365 2080 835 343 2081 838 342 2082 792 364 2083 800 349 2084 771 359 2085 761 349 2086 771 364 2087 800 368 2088 847 338 2089 856 376 2090 846 338 2091 856 368 2092 847 346 2093 855 372 2094 851 342 2095 843 351 2096 850 364 2097 840 342 2098 843 372 2099 851 363 2100 863 313 2101 760 321 2102 801 359 2103 862 313 2104 760 363 2105 863 349 2106 841 362 2107 864 340 2108 865 362 2109 864 349 2110 841 359 2111 862 316 2112 832 383 2113 884 355 2114 876 355 2115 876 383 2116 884 371 2117 836 383 2118 884 316 2119 832 420 2120 879 367 2121 859 353 2122 868 314 2123 763 353 2124 868 367 2125 859 330 2126 860 366 2127 880 353 2128 868 345 2129 871 375 2130 831 353 2131 868 366 2132 880 319 2133 893 337 2134 839 357 2135 881 357 2136 881 337 2137 839 328 2138 897 380 2139 818 356 2140 826 383 2141 812 371 2142 808 383 2143 812 356 2144 826 356 2145 826 342 2146 792 371 2147 808 349 2148 771 371 2149 808 342 2150 792 359 2151 761 322 2152 837 313 2153 844 322 2154 837 359 2155 761 364 2156 800 370 2157 889 354 2158 907 377 2159 833 354 2160 907 370 2161 889 333 2162 890 369 2163 980 354 2164 907 348 2165 979 376 2166 846 354 2167 907 369 2168 980 312 2169 762 338 2170 856 358 2171 981 358 2172 981 338 2173 856 331 2174 982 317 2175 793 380 2176 913 382 2177 914 374 2178 931 380 2179 913 317 2180 793 356 2181 912 380 2182 913 374 2183 931 342 2184 843 373 2185 936 335 2186 937 373 2187 936 342 2188 843 356 2189 912 322 2190 768 360 2191 938 323 2192 772 360 2193 938 322 2194 768 364 2195 840 359 2196 862 327 2197 983 341 2198 984 349 2199 841 340 2200 865 326 2201 842 339 2202 985 325 2203 986 371 2204 836 353 2205 868 330 2206 860 345 2207 871 375 2208 831 344 2209 939 329 2210 940 343 2211 838 328 2212 897 337 2213 839 333 2214 890 325 2215 986 348 2216 979 348 2217 979 325 2218 986 339 2219 985 347 2220 988 326 2221 842 332 2222 987 332 2223 987 326 2224 842 340 2225 865 346 2226 855 341 2227 984 331 2228 982 331 2229 982 341 2230 984 327 2231 983 343 2232 838 336 2233 942 328 2234 897 336 2235 942 343 2236 838 352 2237 941 344 2238 939 335 2239 937 329 2240 940 335 2241 937 344 2242 939 351 2243 850 330 2244 860 350 2245 944 345 2246 871 350 2247 944 330 2248 860 334 2249 943 354 2250 907 333 2251 890 348 2252 979 376 2253 846 347 2254 988 332 2255 987 346 2256 855 331 2257 982 338 2258 856 356 2259 912 336 2260 942 352 2261 941 342 2262 843 335 2263 937 351 2264 850 350 2265 944 334 2266 943 364 2267 840 317 2268 1024 318 2269 1025 315 2270 903 315 2271 903 316 2272 904 317 2273 1024 374 2274 766 317 2275 1070 316 2276 1071 374 2277 766 316 2278 1071 355 2279 765 333 2280 783 336 2281 1101 325 2282 778 336 2283 1101 333 2284 783 328 2285 1100 370 2286 1094 328 2287 1096 333 2288 1097 328 2289 1096 370 2290 1094 357 2291 1095 329 2292 934 326 2293 932 347 2294 933 326 2295 932 329 2296 934 335 2297 935 348 2298 1035 365 2299 1037 369 2300 1034 365 2301 1037 348 2302 1035 343 2303 1036 352 2304 1038 343 2305 1039 348 2306 794 348 2307 794 339 2308 799 352 2309 1038 335 2310 1022 373 2311 1023 361 2312 776 335 2313 1022 361 2314 776 326 2315 785 346 2316 1027 350 2317 1029 341 2318 1026 350 2319 1029 346 2320 1027 345 2321 1028 368 2322 796 345 2323 1048 346 2324 1049 345 2325 1048 368 2326 796 366 2327 797 351 2328 1050 344 2329 1051 332 2330 790 332 2331 790 340 2332 803 351 2333 1050 340 2334 1033 372 2335 1031 351 2336 1032 372 2337 1031 340 2338 1033 362 2339 1030 334 2340 1064 330 2341 1065 331 2342 780 331 2343 780 327 2344 781 334 2345 1064 323 2346 1082 360 2347 1083 363 2348 770 323 2349 1082 363 2350 770 321 2351 773 324 2352 1042 321 2353 1040 320 2354 1041 321 2355 1040 324 2356 1042 323 2357 1043 331 2358 1061 367 2359 1063 358 2360 1060 367 2361 1063 331 2362 1061 330 2363 1062 361 2364 845 339 2365 985 371 2366 836 375 2367 831 329 2368 940 365 2369 835 376 2370 846 332 2371 987 368 2372 847 372 2373 851 350 2374 944 364 2375 840 363 2376 863 327 2377 983 359 2378 862 359 2379 862 341 2380 984 362 2381 864 371 2382 836 325 2383 986 355 2384 876 314 2385 763 324 2386 787 367 2387 859 366 2388 880 344 2389 939 375 2390 831 357 2391 881 318 2392 819 319 2393 893 377 2394 833 315 2395 806 370 2396 889 369 2397 980 347 2398 988 376 2399 846 358 2400 981 320 2401 788 312 2402 762 374 2403 931 336 2404 942 356 2405 912 356 2406 912 352 2407 941 373 2408 936 364 2409 840 334 2410 943 360 2411 938 325 2412 986 370 2413 889 355 2414 876 315 2415 806 355 2416 876 370 2417 889 336 2418 786 370 2419 825 325 2420 775 370 2421 825 336 2422 786 357 2423 810 357 2424 881 336 2425 942 374 2426 931 374 2427 931 318 2428 819 357 2429 881 315 2430 807 374 2431 764 355 2432 767 374 2433 764 315 2434 807 318 2435 830 329 2436 940 373 2437 936 365 2438 835 352 2439 941 365 2440 835 373 2441 936 361 2442 815 329 2443 779 347 2444 798 329 2445 779 361 2446 815 373 2447 829 369 2448 980 361 2449 845 347 2450 988 369 2451 980 339 2452 985 361 2453 845 352 2454 820 369 2455 789 365 2456 804 369 2457 789 352 2458 820 339 2459 824 341 2460 984 368 2461 847 362 2462 864 332 2463 987 362 2464 864 368 2465 847 366 2466 821 341 2467 791 350 2468 802 341 2469 791 366 2470 821 368 2471 823 366 2472 880 350 2473 944 372 2474 851 372 2475 851 344 2476 939 366 2477 880 332 2478 816 372 2479 782 362 2480 795 372 2481 782 332 2482 816 344 2483 828 334 2484 943 367 2485 859 360 2486 938 324 2487 787 360 2488 938 367 2489 859 327 2490 784 358 2491 811 334 2492 777 367 2493 822 334 2494 777 358 2495 811 358 2496 981 327 2497 983 363 2498 863 363 2499 863 320 2500 788 358 2501 981 360 2502 774 324 2503 814 363 2504 769 320 2505 817 363 2506 769 324 2507 814 420 2508 879 316 2509 832 393 2510 827 453 2511 945 319 2512 893 378 2513 809 319 2514 893 318 2515 819 378 2516 809 396 2517 805 317 2518 793 382 2519 914 385 2520 992 387 2521 990 386 2522 991 385 2523 992 384 2524 989 387 2525 990 390 2526 948 389 2527 946 391 2528 947 388 2529 949 389 2530 946 390 2531 948 392 2532 993 394 2533 994 379 2534 813 379 2535 813 394 2536 994 393 2537 827 378 2538 809 395 2539 950 397 2540 951 395 2541 950 378 2542 809 396 2543 805 381 2544 834 398 2545 995 392 2546 993 381 2547 834 392 2548 993 379 2549 813 400 2550 999 399 2551 996 402 2552 997 402 2553 997 401 2554 998 400 2555 999 406 2556 953 404 2557 955 403 2558 952 404 2559 955 406 2560 953 405 2561 954 400 2562 875 407 2563 872 409 2564 873 400 2565 875 409 2566 873 408 2567 874 413 2568 1001 411 2569 1003 410 2570 1000 411 2571 1003 413 2572 1001 412 2573 1002 408 2574 959 409 2575 956 415 2576 957 415 2577 957 414 2578 958 408 2579 959 384 2580 989 407 2581 1004 416 2582 1005 416 2583 1005 387 2584 990 384 2585 989 400 2586 999 417 2587 1007 407 2588 1004 417 2589 1007 400 2590 999 418 2591 1006 394 2592 994 383 2593 884 420 2594 879 383 2595 884 419 2596 1008 399 2597 996 419 2598 1008 383 2599 884 394 2600 994 423 2601 960 421 2602 962 389 2603 946 421 2604 962 423 2605 960 422 2606 961 423 2607 960 403 2608 952 425 2609 963 423 2610 960 425 2611 963 424 2612 964 406 2613 953 427 2614 967 426 2615 965 406 2616 953 426 2617 965 428 2618 966 383 2619 812 399 2620 899 429 2621 900 383 2622 812 429 2623 900 380 2624 818 399 2625 899 400 2626 875 408 2627 874 399 2628 899 408 2629 874 429 2630 900 407 2631 872 384 2632 901 388 2633 902 407 2634 872 388 2635 902 409 2636 873 432 2637 1009 430 2638 1011 398 2639 995 430 2640 1011 432 2641 1009 431 2642 1010 432 2643 1009 410 2644 1000 434 2645 1012 432 2646 1009 434 2647 1012 433 2648 1013 413 2649 1001 385 2650 992 435 2651 1014 413 2652 1001 435 2653 1014 436 2654 1015 380 2655 913 429 2656 968 437 2657 969 380 2658 913 437 2659 969 395 2660 950 380 2661 913 395 2662 950 382 2663 914 408 2664 959 438 2665 971 429 2666 968 438 2667 971 408 2668 959 439 2669 970 388 2670 949 440 2671 972 409 2672 956 440 2673 972 388 2674 949 390 2675 948 407 2676 1004 442 2677 1016 441 2678 1017 400 2679 999 401 2680 998 418 2681 1006 443 2682 1018 399 2683 996 444 2684 1019 423 2685 960 424 2686 964 422 2687 961 403 2688 952 446 2689 973 445 2690 974 405 2691 954 406 2692 953 428 2693 966 444 2694 1019 431 2695 1010 433 2696 1013 433 2697 1013 443 2698 1018 444 2699 1019 401 2700 998 448 2701 1021 447 2702 1020 447 2703 1020 418 2704 1006 401 2705 998 436 2706 1015 442 2707 1016 412 2708 1002 442 2709 1016 436 2710 1015 441 2711 1017 405 2712 954 450 2713 976 449 2714 975 450 2715 976 405 2716 954 428 2717 966 445 2718 974 439 2719 970 414 2720 958 439 2721 970 445 2722 974 446 2723 973 422 2724 961 452 2725 977 451 2726 978 452 2727 977 422 2728 961 424 2729 964 432 2730 1009 433 2731 1013 431 2732 1010 410 2733 1000 447 2734 1020 448 2735 1021 412 2736 1002 413 2737 1001 436 2738 1015 429 2739 968 449 2740 975 450 2741 976 408 2742 959 414 2743 958 439 2744 970 452 2745 977 409 2746 956 451 2747 978 395 2748 1054 392 2749 1052 397 2750 1053 392 2751 1052 395 2752 1054 394 2753 1055 437 2754 1093 394 2755 858 395 2756 1092 394 2757 858 437 2758 1093 419 2759 857 431 2760 1079 450 2761 1077 428 2762 1078 450 2763 1077 431 2764 1079 444 2765 1076 428 2766 1106 430 2767 898 431 2768 906 430 2769 898 428 2770 1106 426 2771 1107 448 2772 1089 401 2773 866 446 2774 1088 446 2775 1088 401 2776 866 439 2777 917 404 2778 908 433 2779 1111 434 2780 870 433 2781 1111 404 2782 908 405 2783 1110 405 2784 1067 449 2785 1068 433 2786 1066 433 2787 1066 449 2788 1068 443 2789 1069 439 2790 1046 402 2791 1044 438 2792 1045 402 2793 1044 439 2794 1046 401 2795 1047 412 2796 1099 452 2797 894 424 2798 1098 452 2799 894 412 2800 1099 442 2801 878 424 2802 1074 411 2803 1072 412 2804 1073 411 2805 1072 424 2806 1074 425 2807 1075 414 2808 1080 447 2809 882 445 2810 887 447 2811 882 414 2812 1080 418 2813 1081 415 2814 1059 418 2815 1057 414 2816 1058 418 2817 1057 415 2818 1059 417 2819 1056 422 2820 911 451 2821 1090 436 2822 892 436 2823 892 451 2824 1090 441 2825 1091 390 2826 1104 416 2827 1102 440 2828 1103 416 2829 1102 390 2830 1104 387 2831 1105 386 2832 1109 387 2833 849 391 2834 1108 391 2835 1108 387 2836 849 390 2837 852 421 2838 1085 436 2839 1087 435 2840 1084 436 2841 1087 421 2842 1085 422 2843 1086 402 2844 997 399 2845 996 443 2846 1018 403 2847 952 404 2848 955 446 2849 973 410 2850 1000 411 2851 1003 447 2852 1020 415 2853 957 409 2854 956 452 2855 977 416 2856 1005 407 2857 1004 441 2858 1017 407 2859 1004 417 2860 1007 442 2861 1016 399 2862 996 419 2863 1008 444 2864 1019 389 2865 946 421 2866 962 391 2867 947 425 2868 963 403 2869 952 445 2870 974 426 2871 965 427 2872 967 397 2873 951 398 2874 995 430 2875 1011 392 2876 993 434 2877 1012 410 2878 1000 448 2879 1021 435 2880 1014 385 2881 992 386 2882 991 437 2883 969 429 2884 968 450 2885 976 429 2886 968 438 2887 971 449 2888 975 409 2889 956 440 2890 972 451 2891 978 430 2892 1011 444 2893 1019 419 2894 1008 419 2895 1008 392 2896 993 430 2897 1011 450 2898 928 430 2899 905 426 2900 922 430 2901 905 450 2902 928 444 2903 896 397 2904 951 437 2905 969 426 2906 965 450 2907 976 426 2908 965 437 2909 969 392 2910 888 419 2911 915 437 2912 854 392 2913 888 437 2914 854 397 2915 861 404 2916 955 449 2917 975 438 2918 971 438 2919 971 446 2920 973 404 2921 955 402 2922 924 448 2923 926 446 2924 867 402 2925 924 446 2926 867 438 2927 916 443 2928 1018 434 2929 1012 402 2930 997 448 2931 1021 402 2932 997 434 2933 1012 449 2934 921 404 2935 927 434 2936 869 449 2937 921 434 2938 869 443 2939 909 411 2940 1003 442 2941 1016 417 2942 1007 417 2943 1007 447 2944 1020 411 2945 1003 425 2946 920 452 2947 930 442 2948 877 425 2949 920 442 2950 877 411 2951 895 452 2952 977 425 2953 963 415 2954 957 445 2955 974 415 2956 957 425 2957 963 447 2958 923 417 2959 925 415 2960 883 447 2961 923 415 2962 883 445 2963 886 421 2964 962 451 2965 978 440 2966 972 440 2967 972 391 2968 947 421 2969 962 435 2970 919 451 2971 891 421 2972 910 451 2973 891 435 2974 919 441 2975 929 441 2976 1017 435 2977 1014 416 2978 1005 386 2979 991 416 2980 1005 435 2981 1014 416 2982 848 386 2983 853 391 2984 885 416 2985 848 391 2986 885 440 2987 918 420 2988 879 393 2989 827 394 2990 994 427 2991 967 453 2992 945 378 2993 809 427 2994 967 378 2995 809 397 2996 951 396 2997 805 382 2998 914 395 2999 950 463 3000 1153 454 3001 1114 462 3002 1140 455 3003 1112 454 3004 1114 463 3005 1153 456 3006 1115 464 3007 1120 465 3008 1124 456 3009 1115 465 3010 1124 466 3011 1139 458 3012 1184 457 3013 1158 521 3014 1165 521 3015 1165 535 3016 1179 458 3017 1184 520 3018 1161 459 3019 1145 538 3020 1157 459 3021 1145 520 3022 1161 460 3023 1171 519 3024 1185 523 3025 1186 457 3026 1158 523 3027 1186 521 3028 1165 457 3029 1158 503 3030 1197 491 3031 1193 468 3032 1194 513 3033 1188 491 3034 1193 503 3035 1197 507 3036 1187 479 3037 1191 517 3038 1183 479 3039 1191 507 3040 1187 485 3041 1190 484 3042 1144 506 3043 1152 491 3044 1123 501 3045 1113 491 3046 1123 506 3047 1152 510 3048 1199 480 3049 1208 518 3050 1198 480 3051 1208 510 3052 1199 488 3053 1207 514 3054 1203 484 3055 1195 493 3056 1202 506 3057 1192 484 3058 1195 514 3059 1203 505 3060 1215 455 3061 1112 463 3062 1153 501 3063 1214 455 3064 1112 505 3065 1215 491 3066 1193 504 3067 1216 482 3068 1217 504 3069 1216 491 3070 1193 501 3071 1214 458 3072 1184 525 3073 1236 497 3074 1228 497 3075 1228 525 3076 1236 513 3077 1188 525 3078 1236 458 3079 1184 562 3080 1231 509 3081 1211 495 3082 1220 456 3083 1115 495 3084 1220 509 3085 1211 472 3086 1212 508 3087 1232 495 3088 1220 487 3089 1223 517 3090 1183 495 3091 1220 508 3092 1232 461 3093 1245 479 3094 1191 499 3095 1233 499 3096 1233 479 3097 1191 470 3098 1249 522 3099 1170 498 3100 1178 525 3101 1164 513 3102 1160 525 3103 1164 498 3104 1178 498 3105 1178 484 3106 1144 513 3107 1160 491 3108 1123 513 3109 1160 484 3110 1144 501 3111 1113 464 3112 1189 455 3113 1196 464 3114 1189 501 3115 1113 506 3116 1152 512 3117 1241 496 3118 1259 519 3119 1185 496 3120 1259 512 3121 1241 475 3122 1242 511 3123 1332 496 3124 1259 490 3125 1331 518 3126 1198 496 3127 1259 511 3128 1332 454 3129 1114 480 3130 1208 500 3131 1333 500 3132 1333 480 3133 1208 473 3134 1334 459 3135 1145 522 3136 1265 524 3137 1266 516 3138 1283 522 3139 1265 459 3140 1145 498 3141 1264 522 3142 1265 516 3143 1283 484 3144 1195 515 3145 1288 477 3146 1289 515 3147 1288 484 3148 1195 498 3149 1264 464 3150 1120 502 3151 1290 465 3152 1124 502 3153 1290 464 3154 1120 506 3155 1192 501 3156 1214 469 3157 1335 483 3158 1336 491 3159 1193 482 3160 1217 468 3161 1194 481 3162 1337 467 3163 1338 513 3164 1188 495 3165 1220 472 3166 1212 487 3167 1223 517 3168 1183 486 3169 1291 471 3170 1292 485 3171 1190 470 3172 1249 479 3173 1191 475 3174 1242 467 3175 1338 490 3176 1331 490 3177 1331 467 3178 1338 481 3179 1337 489 3180 1340 468 3181 1194 474 3182 1339 474 3183 1339 468 3184 1194 482 3185 1217 488 3186 1207 483 3187 1336 473 3188 1334 473 3189 1334 483 3190 1336 469 3191 1335 485 3192 1190 478 3193 1294 470 3194 1249 478 3195 1294 485 3196 1190 494 3197 1293 486 3198 1291 477 3199 1289 471 3200 1292 477 3201 1289 486 3202 1291 493 3203 1202 472 3204 1212 492 3205 1296 487 3206 1223 492 3207 1296 472 3208 1212 476 3209 1295 496 3210 1259 475 3211 1242 490 3212 1331 518 3213 1198 489 3214 1340 474 3215 1339 488 3216 1207 473 3217 1334 480 3218 1208 498 3219 1264 478 3220 1294 494 3221 1293 484 3222 1195 477 3223 1289 493 3224 1202 492 3225 1296 476 3226 1295 506 3227 1192 459 3228 1376 460 3229 1377 457 3230 1255 457 3231 1255 458 3232 1256 459 3233 1376 516 3234 1118 459 3235 1422 458 3236 1423 516 3237 1118 458 3238 1423 497 3239 1117 475 3240 1135 478 3241 1453 467 3242 1130 478 3243 1453 475 3244 1135 470 3245 1452 512 3246 1446 470 3247 1448 475 3248 1449 470 3249 1448 512 3250 1446 499 3251 1447 471 3252 1286 468 3253 1284 489 3254 1285 468 3255 1284 471 3256 1286 477 3257 1287 490 3258 1387 507 3259 1389 511 3260 1386 507 3261 1389 490 3262 1387 485 3263 1388 494 3264 1390 485 3265 1391 490 3266 1146 490 3267 1146 481 3268 1151 494 3269 1390 477 3270 1374 515 3271 1375 503 3272 1128 477 3273 1374 503 3274 1128 468 3275 1137 488 3276 1379 492 3277 1381 483 3278 1378 492 3279 1381 488 3280 1379 487 3281 1380 510 3282 1148 487 3283 1400 488 3284 1401 487 3285 1400 510 3286 1148 508 3287 1149 493 3288 1402 486 3289 1403 474 3290 1142 474 3291 1142 482 3292 1155 493 3293 1402 482 3294 1385 514 3295 1383 493 3296 1384 514 3297 1383 482 3298 1385 504 3299 1382 476 3300 1416 472 3301 1417 473 3302 1132 473 3303 1132 469 3304 1133 476 3305 1416 465 3306 1434 502 3307 1435 505 3308 1122 465 3309 1434 505 3310 1122 463 3311 1125 466 3312 1394 463 3313 1392 462 3314 1393 463 3315 1392 466 3316 1394 465 3317 1395 473 3318 1413 509 3319 1415 500 3320 1412 509 3321 1415 473 3322 1413 472 3323 1414 503 3324 1197 481 3325 1337 513 3326 1188 517 3327 1183 471 3328 1292 507 3329 1187 518 3330 1198 474 3331 1339 510 3332 1199 514 3333 1203 492 3334 1296 506 3335 1192 505 3336 1215 469 3337 1335 501 3338 1214 501 3339 1214 483 3340 1336 504 3341 1216 513 3342 1188 467 3343 1338 497 3344 1228 456 3345 1115 466 3346 1139 509 3347 1211 508 3348 1232 486 3349 1291 517 3350 1183 499 3351 1233 460 3352 1171 461 3353 1245 519 3354 1185 457 3355 1158 512 3356 1241 511 3357 1332 489 3358 1340 518 3359 1198 500 3360 1333 462 3361 1140 454 3362 1114 516 3363 1283 478 3364 1294 498 3365 1264 498 3366 1264 494 3367 1293 515 3368 1288 506 3369 1192 476 3370 1295 502 3371 1290 467 3372 1338 512 3373 1241 497 3374 1228 457 3375 1158 497 3376 1228 512 3377 1241 478 3378 1138 512 3379 1177 467 3380 1127 512 3381 1177 478 3382 1138 499 3383 1162 499 3384 1233 478 3385 1294 516 3386 1283 516 3387 1283 460 3388 1171 499 3389 1233 457 3390 1159 516 3391 1116 497 3392 1119 516 3393 1116 457 3394 1159 460 3395 1182 471 3396 1292 515 3397 1288 507 3398 1187 494 3399 1293 507 3400 1187 515 3401 1288 503 3402 1167 471 3403 1131 489 3404 1150 471 3405 1131 503 3406 1167 515 3407 1181 511 3408 1332 503 3409 1197 489 3410 1340 511 3411 1332 481 3412 1337 503 3413 1197 494 3414 1172 511 3415 1141 507 3416 1156 511 3417 1141 494 3418 1172 481 3419 1176 483 3420 1336 510 3421 1199 504 3422 1216 474 3423 1339 504 3424 1216 510 3425 1199 508 3426 1173 483 3427 1143 492 3428 1154 483 3429 1143 508 3430 1173 510 3431 1175 508 3432 1232 492 3433 1296 514 3434 1203 514 3435 1203 486 3436 1291 508 3437 1232 474 3438 1168 514 3439 1134 504 3440 1147 514 3441 1134 474 3442 1168 486 3443 1180 476 3444 1295 509 3445 1211 502 3446 1290 466 3447 1139 502 3448 1290 509 3449 1211 469 3450 1136 500 3451 1163 476 3452 1129 509 3453 1174 476 3454 1129 500 3455 1163 500 3456 1333 469 3457 1335 505 3458 1215 505 3459 1215 462 3460 1140 500 3461 1333 502 3462 1126 466 3463 1166 505 3464 1121 462 3465 1169 505 3466 1121 466 3467 1166 562 3468 1231 458 3469 1184 535 3470 1179 595 3471 1297 461 3472 1245 520 3473 1161 461 3474 1245 460 3475 1171 520 3476 1161 538 3477 1157 459 3478 1145 524 3479 1266 527 3480 1344 529 3481 1342 528 3482 1343 527 3483 1344 526 3484 1341 529 3485 1342 532 3486 1300 531 3487 1298 533 3488 1299 530 3489 1301 531 3490 1298 532 3491 1300 534 3492 1345 536 3493 1346 521 3494 1165 521 3495 1165 536 3496 1346 535 3497 1179 520 3498 1161 537 3499 1302 539 3500 1303 537 3501 1302 520 3502 1161 538 3503 1157 523 3504 1186 540 3505 1347 534 3506 1345 523 3507 1186 534 3508 1345 521 3509 1165 542 3510 1351 541 3511 1348 544 3512 1349 544 3513 1349 543 3514 1350 542 3515 1351 548 3516 1305 546 3517 1307 545 3518 1304 546 3519 1307 548 3520 1305 547 3521 1306 542 3522 1227 549 3523 1224 551 3524 1225 542 3525 1227 551 3526 1225 550 3527 1226 555 3528 1353 553 3529 1355 552 3530 1352 553 3531 1355 555 3532 1353 554 3533 1354 550 3534 1311 551 3535 1308 557 3536 1309 557 3537 1309 556 3538 1310 550 3539 1311 526 3540 1341 549 3541 1356 558 3542 1357 558 3543 1357 529 3544 1342 526 3545 1341 542 3546 1351 559 3547 1359 549 3548 1356 559 3549 1359 542 3550 1351 560 3551 1358 536 3552 1346 525 3553 1236 562 3554 1231 525 3555 1236 561 3556 1360 541 3557 1348 561 3558 1360 525 3559 1236 536 3560 1346 565 3561 1312 563 3562 1314 531 3563 1298 563 3564 1314 565 3565 1312 564 3566 1313 565 3567 1312 545 3568 1304 567 3569 1315 565 3570 1312 567 3571 1315 566 3572 1316 548 3573 1305 569 3574 1319 568 3575 1317 548 3576 1305 568 3577 1317 570 3578 1318 525 3579 1164 541 3580 1251 571 3581 1252 525 3582 1164 571 3583 1252 522 3584 1170 541 3585 1251 542 3586 1227 550 3587 1226 541 3588 1251 550 3589 1226 571 3590 1252 549 3591 1224 526 3592 1253 530 3593 1254 549 3594 1224 530 3595 1254 551 3596 1225 574 3597 1361 572 3598 1363 540 3599 1347 572 3600 1363 574 3601 1361 573 3602 1362 574 3603 1361 552 3604 1352 576 3605 1364 574 3606 1361 576 3607 1364 575 3608 1365 555 3609 1353 527 3610 1344 577 3611 1366 555 3612 1353 577 3613 1366 578 3614 1367 522 3615 1265 571 3616 1320 579 3617 1321 522 3618 1265 579 3619 1321 537 3620 1302 522 3621 1265 537 3622 1302 524 3623 1266 550 3624 1311 580 3625 1323 571 3626 1320 580 3627 1323 550 3628 1311 581 3629 1322 530 3630 1301 582 3631 1324 551 3632 1308 582 3633 1324 530 3634 1301 532 3635 1300 549 3636 1356 584 3637 1368 583 3638 1369 542 3639 1351 543 3640 1350 560 3641 1358 585 3642 1370 541 3643 1348 586 3644 1371 565 3645 1312 566 3646 1316 564 3647 1313 545 3648 1304 588 3649 1325 587 3650 1326 547 3651 1306 548 3652 1305 570 3653 1318 586 3654 1371 573 3655 1362 575 3656 1365 575 3657 1365 585 3658 1370 586 3659 1371 543 3660 1350 590 3661 1373 589 3662 1372 589 3663 1372 560 3664 1358 543 3665 1350 578 3666 1367 584 3667 1368 554 3668 1354 584 3669 1368 578 3670 1367 583 3671 1369 547 3672 1306 592 3673 1328 591 3674 1327 592 3675 1328 547 3676 1306 570 3677 1318 587 3678 1326 581 3679 1322 556 3680 1310 581 3681 1322 587 3682 1326 588 3683 1325 564 3684 1313 594 3685 1329 593 3686 1330 594 3687 1329 564 3688 1313 566 3689 1316 574 3690 1361 575 3691 1365 573 3692 1362 552 3693 1352 589 3694 1372 590 3695 1373 554 3696 1354 555 3697 1353 578 3698 1367 571 3699 1320 591 3700 1327 592 3701 1328 550 3702 1311 556 3703 1310 581 3704 1322 594 3705 1329 551 3706 1308 593 3707 1330 539 3708 1405 537 3709 1406 534 3710 1404 534 3711 1404 537 3712 1406 536 3713 1407 579 3714 1445 536 3715 1210 537 3716 1444 536 3717 1210 579 3718 1445 561 3719 1209 573 3720 1431 592 3721 1429 570 3722 1430 592 3723 1429 573 3724 1431 586 3725 1428 570 3726 1458 572 3727 1250 573 3728 1258 572 3729 1250 570 3730 1458 568 3731 1459 590 3732 1441 543 3733 1218 588 3734 1440 588 3735 1440 543 3736 1218 581 3737 1269 546 3738 1260 575 3739 1463 576 3740 1222 575 3741 1463 546 3742 1260 547 3743 1462 547 3744 1419 591 3745 1420 575 3746 1418 575 3747 1418 591 3748 1420 585 3749 1421 581 3750 1398 544 3751 1396 580 3752 1397 544 3753 1396 581 3754 1398 543 3755 1399 554 3756 1451 594 3757 1246 566 3758 1450 594 3759 1246 554 3760 1451 584 3761 1230 566 3762 1426 553 3763 1424 554 3764 1425 553 3765 1424 566 3766 1426 567 3767 1427 587 3768 1239 556 3769 1432 589 3770 1234 589 3771 1234 556 3772 1432 560 3773 1433 557 3774 1411 560 3775 1409 556 3776 1410 560 3777 1409 557 3778 1411 559 3779 1408 564 3780 1263 593 3781 1442 578 3782 1244 578 3783 1244 593 3784 1442 583 3785 1443 532 3786 1456 558 3787 1454 582 3788 1455 558 3789 1454 532 3790 1456 529 3791 1457 528 3792 1461 529 3793 1201 533 3794 1460 533 3795 1460 529 3796 1201 532 3797 1204 563 3798 1437 578 3799 1439 577 3800 1436 578 3801 1439 563 3802 1437 564 3803 1438 544 3804 1349 541 3805 1348 585 3806 1370 545 3807 1304 546 3808 1307 588 3809 1325 552 3810 1352 553 3811 1355 589 3812 1372 557 3813 1309 551 3814 1308 594 3815 1329 558 3816 1357 549 3817 1356 583 3818 1369 549 3819 1356 559 3820 1359 584 3821 1368 541 3822 1348 561 3823 1360 586 3824 1371 531 3825 1298 563 3826 1314 533 3827 1299 567 3828 1315 545 3829 1304 587 3830 1326 568 3831 1317 569 3832 1319 539 3833 1303 540 3834 1347 572 3835 1363 534 3836 1345 576 3837 1364 552 3838 1352 590 3839 1373 577 3840 1366 527 3841 1344 528 3842 1343 579 3843 1321 571 3844 1320 592 3845 1328 571 3846 1320 580 3847 1323 591 3848 1327 551 3849 1308 582 3850 1324 593 3851 1330 572 3852 1363 586 3853 1371 561 3854 1360 561 3855 1360 534 3856 1345 572 3857 1363 592 3858 1280 572 3859 1257 568 3860 1274 572 3861 1257 592 3862 1280 586 3863 1248 539 3864 1303 579 3865 1321 568 3866 1317 592 3867 1328 568 3868 1317 579 3869 1321 534 3870 1240 561 3871 1267 579 3872 1206 534 3873 1240 579 3874 1206 539 3875 1213 546 3876 1307 591 3877 1327 580 3878 1323 580 3879 1323 588 3880 1325 546 3881 1307 544 3882 1276 590 3883 1278 588 3884 1219 544 3885 1276 588 3886 1219 580 3887 1268 585 3888 1370 576 3889 1364 544 3890 1349 590 3891 1373 544 3892 1349 576 3893 1364 591 3894 1273 546 3895 1279 576 3896 1221 591 3897 1273 576 3898 1221 585 3899 1261 553 3900 1355 584 3901 1368 559 3902 1359 559 3903 1359 589 3904 1372 553 3905 1355 567 3906 1272 594 3907 1282 584 3908 1229 567 3909 1272 584 3910 1229 553 3911 1247 594 3912 1329 567 3913 1315 557 3914 1309 587 3915 1326 557 3916 1309 567 3917 1315 589 3918 1275 559 3919 1277 557 3920 1235 589 3921 1275 557 3922 1235 587 3923 1238 563 3924 1314 593 3925 1330 582 3926 1324 582 3927 1324 533 3928 1299 563 3929 1314 577 3930 1271 593 3931 1243 563 3932 1262 593 3933 1243 577 3934 1271 583 3935 1281 583 3936 1369 577 3937 1366 558 3938 1357 528 3939 1343 558 3940 1357 577 3941 1366 533 3942 1237 558 3943 1200 528 3944 1205 558 3945 1200 533 3946 1237 582 3947 1270 562 3948 1231 535 3949 1179 536 3950 1346 569 3951 1319 595 3952 1297 520 3953 1161 569 3954 1319 520 3955 1161 539 3956 1303 538 3957 1157 524 3958 1266 537 3959 1302 598 3960 1467 599 3961 1464 597 3962 1466 597 3963 1466 599 3964 1464 596 3965 1465 600 3966 1469 601 3967 1468 598 3968 1467 598 3969 1467 601 3970 1468 599 3971 1464 605 3972 1492 602 3973 1493 596 3974 1490 596 3975 1490 599 3976 1491 605 3977 1492 596 3978 1476 603 3979 1478 597 3980 1479 603 3981 1478 596 3982 1476 602 3983 1477 604 3984 1486 600 3985 1484 598 3986 1485 600 3987 1484 604 3988 1486 606 3989 1487 600 3990 1480 607 3991 1482 601 3992 1483 607 3993 1482 600 3994 1480 606 3995 1481 607 3996 1495 605 3997 1492 601 3998 1494 599 3999 1491 601 4000 1494 605 4001 1492 603 4002 1489 604 4003 1486 597 4004 1488 598 4005 1485 597 4006 1488 604 4007 1486 605 4008 1473 604 4009 1470 602 4010 1472 602 4011 1472 604 4012 1470 603 4013 1471 604 4014 1470 605 4015 1473 607 4016 1475 607 4017 1475 606 4018 1474 604 4019 1470 609 4020 1519 608 4021 1516 616 4022 1517 609 4023 1519 616 4024 1517 617 4025 1518 613 4026 1522 612 4027 1523 608 4028 1520 613 4029 1522 608 4030 1520 609 4031 1521 618 4032 1526 609 4033 1524 617 4034 1525 609 4035 1524 618 4036 1526 613 4037 1527 615 4038 1531 610 4039 1529 614 4040 1530 610 4041 1529 615 4042 1531 611 4043 1528 619 4044 1534 610 4045 1532 616 4046 1533 610 4047 1532 619 4048 1534 614 4049 1535 617 4050 1518 616 4051 1517 610 4052 1536 617 4053 1518 610 4054 1536 611 4055 1538 618 4056 1526 611 4057 1539 615 4058 1540 611 4059 1539 618 4060 1526 617 4061 1525 619 4062 1534 608 4063 1537 612 4064 1541 608 4065 1537 619 4066 1534 616 4067 1533 622 4068 1544 621 4069 1543 623 4070 1545 620 4071 1542 623 4072 1545 621 4073 1543 624 4074 1548 620 4075 1546 625 4076 1549 623 4077 1547 620 4078 1546 624 4079 1548 626 4080 1552 623 4081 1550 624 4082 1553 623 4083 1550 626 4084 1552 622 4085 1551 630 4086 1557 628 4087 1555 627 4088 1554 628 4089 1555 630 4090 1557 629 4091 1556 631 4092 1560 628 4093 1558 629 4094 1561 628 4095 1558 631 4096 1560 621 4097 1559 627 4098 1563 628 4099 1562 622 4100 1544 621 4101 1543 622 4102 1544 628 4103 1562 627 4104 1564 626 4105 1552 630 4106 1565 626 4107 1552 627 4108 1564 622 4109 1551 631 4110 1560 625 4111 1567 620 4112 1566 631 4113 1560 620 4114 1566 621 4115 1559 633 4116 1569 635 4117 1571 634 4118 1570 635 4119 1571 633 4120 1569 632 4121 1568 636 4122 1574 632 4123 1572 637 4124 1575 635 4125 1573 632 4126 1572 636 4127 1574 638 4128 1578 635 4129 1576 636 4130 1579 635 4131 1576 638 4132 1578 634 4133 1577 642 4134 1583 640 4135 1581 639 4136 1580 640 4137 1581 642 4138 1583 641 4139 1582 643 4140 1586 640 4141 1584 641 4142 1587 640 4143 1584 643 4144 1586 633 4145 1585 640 4146 1588 634 4147 1570 639 4148 1589 634 4149 1570 640 4150 1588 633 4151 1569 639 4152 1590 638 4153 1578 642 4154 1591 638 4155 1578 639 4156 1590 634 4157 1577 643 4158 1586 637 4159 1593 632 4160 1592 643 4161 1586 632 4162 1592 633 4163 1585 647 4164 1597 646 4165 1596 645 4166 1595 647 4167 1597 645 4168 1595 644 4169 1594 649 4170 1600 648 4171 1599 644 4172 1598 649 4173 1600 644 4174 1598 645 4175 1601 650 4176 1604 645 4177 1602 646 4178 1605 645 4179 1602 650 4180 1604 649 4181 1603 652 4182 1607 654 4183 1609 653 4184 1608 654 4185 1609 652 4186 1607 651 4187 1606 655 4188 1612 654 4189 1610 647 4190 1613 654 4191 1610 655 4192 1612 653 4193 1611 654 4194 1615 651 4195 1614 646 4196 1596 654 4197 1615 646 4198 1596 647 4199 1597 650 4200 1604 651 4201 1617 652 4202 1616 651 4203 1617 650 4204 1604 646 4205 1605 655 4206 1612 644 4207 1619 648 4208 1618 644 4209 1619 655 4210 1612 647 4211 1613 659 4212 1622 656 4213 1620 658 4214 1621 656 4215 1620 659 4216 1622 657 4217 1623 663 4218 1626 662 4219 1627 660 4220 1624 663 4221 1626 660 4222 1624 661 4223 1625 660 4224 1631 656 4225 1628 661 4226 1630 661 4227 1630 656 4228 1628 657 4229 1629 659 4230 1633 661 4231 1635 657 4232 1632 661 4233 1635 659 4234 1633 663 4235 1634 658 4236 1637 662 4237 1638 659 4238 1636 659 4239 1636 662 4240 1638 663 4241 1639 656 4242 1641 660 4243 1642 658 4244 1640 662 4245 1643 658 4246 1640 660 4247 1642 666 4248 1646 665 4249 1645 664 4250 1644 666 4251 1646 664 4252 1644 667 4253 1647 670 4254 1650 668 4255 1648 671 4256 1651 668 4257 1648 670 4258 1650 669 4259 1649 669 4260 1654 664 4261 1652 668 4262 1655 664 4263 1652 669 4264 1654 667 4265 1653 666 4266 1657 669 4267 1659 670 4268 1658 669 4269 1659 666 4270 1657 667 4271 1656 671 4272 1662 665 4273 1661 666 4274 1660 666 4275 1660 670 4276 1663 671 4277 1662 668 4278 1666 665 4279 1664 671 4280 1667 665 4281 1664 668 4282 1666 664 4283 1665

+
+
+
+ + + 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.0000001.000000 + 30.0000000.0000003.333333 + + + + + +
diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_RoofB_01/model.config b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_RoofB_01/model.config new file mode 100755 index 0000000..b49b78b --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_RoofB_01/model.config @@ -0,0 +1,11 @@ + + + aws_robomaker_warehouse_RoofB_01 + 1.0 + model.sdf + + + + + + diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_RoofB_01/model.sdf b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_RoofB_01/model.sdf new file mode 100755 index 0000000..33e4e9c --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_RoofB_01/model.sdf @@ -0,0 +1,56 @@ + + + + + + 1000 + 0 0 0 0 0 0 + + 834024.533 + 0 + 0 + 459441.200 + 0 + 1302083.333 + + + + + + model://aws_robomaker_warehouse_RoofB_01/meshes/aws_robomaker_warehouse_RoofB_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + model://aws_robomaker_warehouse_RoofB_01/meshes/aws_robomaker_warehouse_RoofB_01_visual.DAE + + + 3 + + + 1 + + diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ShelfD_01/materials/textures/aws_robomaker_warehouse_ShelfD_01.png b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ShelfD_01/materials/textures/aws_robomaker_warehouse_ShelfD_01.png new file mode 100755 index 0000000..d33ba54 Binary files /dev/null and b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ShelfD_01/materials/textures/aws_robomaker_warehouse_ShelfD_01.png differ diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ShelfD_01/materials/textures/aws_robomaker_warehouse_ShelfD_02.png b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ShelfD_01/materials/textures/aws_robomaker_warehouse_ShelfD_02.png new file mode 100755 index 0000000..4b7e610 Binary files /dev/null and b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ShelfD_01/materials/textures/aws_robomaker_warehouse_ShelfD_02.png differ diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ShelfD_01/materials/textures/aws_robomaker_warehouse_ShelfD_03.png b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ShelfD_01/materials/textures/aws_robomaker_warehouse_ShelfD_03.png new file mode 100755 index 0000000..b28b289 Binary files /dev/null and b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ShelfD_01/materials/textures/aws_robomaker_warehouse_ShelfD_03.png differ diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ShelfD_01/materials/textures/aws_robomaker_warehouse_ShelfD_04.png b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ShelfD_01/materials/textures/aws_robomaker_warehouse_ShelfD_04.png new file mode 100755 index 0000000..e76fcdd Binary files /dev/null and b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ShelfD_01/materials/textures/aws_robomaker_warehouse_ShelfD_04.png differ diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ShelfD_01/model.config b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ShelfD_01/model.config new file mode 100755 index 0000000..c91fbb1 --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ShelfD_01/model.config @@ -0,0 +1,11 @@ + + + aws_robomaker_warehouse_ShelfD_01 + 1.0 + model.sdf + + + + + + diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ShelfD_01/model.sdf b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ShelfD_01/model.sdf new file mode 100755 index 0000000..17c326e --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ShelfD_01/model.sdf @@ -0,0 +1,46 @@ + + + + + + 30 + + 907.144 + 0 + 0 + 104.950 + 0 + 824.248 + + + + + + model://aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + model://aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_visual.DAE + + + 1 + + +1 + + diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ShelfE_01/materials/textures/aws_robomaker_warehouse_ShelfE_01.png b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ShelfE_01/materials/textures/aws_robomaker_warehouse_ShelfE_01.png new file mode 100755 index 0000000..d33ba54 Binary files /dev/null and b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ShelfE_01/materials/textures/aws_robomaker_warehouse_ShelfE_01.png differ diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ShelfE_01/materials/textures/aws_robomaker_warehouse_ShelfE_02.png b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ShelfE_01/materials/textures/aws_robomaker_warehouse_ShelfE_02.png new file mode 100755 index 0000000..b28b289 Binary files /dev/null and b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ShelfE_01/materials/textures/aws_robomaker_warehouse_ShelfE_02.png differ diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ShelfE_01/materials/textures/aws_robomaker_warehouse_ShelfE_03.png b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ShelfE_01/materials/textures/aws_robomaker_warehouse_ShelfE_03.png new file mode 100755 index 0000000..4b7e610 Binary files /dev/null and b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ShelfE_01/materials/textures/aws_robomaker_warehouse_ShelfE_03.png differ diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ShelfE_01/materials/textures/aws_robomaker_warehouse_ShelfE_04.png b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ShelfE_01/materials/textures/aws_robomaker_warehouse_ShelfE_04.png new file mode 100755 index 0000000..e76fcdd Binary files /dev/null and b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ShelfE_01/materials/textures/aws_robomaker_warehouse_ShelfE_04.png differ diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_collision.DAE b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_collision.DAE new file mode 100755 index 0000000..5922d31 --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_collision.DAE @@ -0,0 +1,327 @@ + + + FBX COLLADA exporter2019-05-15T10:11:35Z2019-05-15T10:11:35ZZ_UP + + + + + +-45.044750 -57.560341 195.803909 +42.866188 -57.560341 195.803955 +-45.044750 133.195770 195.803955 +42.866188 133.195770 195.803986 +-45.044781 -57.560341 -195.804031 +42.866158 -57.560341 -195.804001 +-45.044781 133.195770 -195.803986 +42.866158 133.195770 -195.803970 +-44.361427 -128.142014 1.402283 +42.927315 -128.142014 1.402374 +-44.361427 133.195755 1.402374 +42.927315 133.195755 1.402420 +-44.361412 -128.141998 -4.198639 +42.927338 -128.141998 -4.198563 +-44.361412 133.195786 -4.198517 +42.927338 133.195786 -4.198456 +-44.361458 -128.142029 -190.318237 +42.927284 -128.142029 -190.318130 +42.927284 133.195740 -190.318039 +-44.361458 133.195740 -190.318130 +-44.361443 -128.142014 -195.919159 +-44.361443 133.195770 -195.919022 +42.927307 133.195770 -195.918884 +42.927307 -128.142014 -195.919037 +-44.361401 -128.141998 195.912140 +42.927341 -128.141998 195.912231 +-44.361401 133.195770 195.912231 +42.927341 133.195770 195.912277 +-44.361378 -128.141983 190.311218 +42.927372 -128.141983 190.311295 +-44.361378 133.195801 190.311340 +42.927372 133.195801 190.311401 + + + + + + + + + + + +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +1.000000 -0.000000 0.000004 +1.000000 -0.000000 0.000004 +1.000000 -0.000000 0.000004 +1.000000 -0.000000 0.000004 +1.000000 -0.000000 0.000004 +1.000000 -0.000000 0.000004 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-1.000000 0.000000 -0.000003 +-1.000000 0.000000 -0.000003 +-1.000000 0.000000 -0.000003 +-1.000000 0.000000 -0.000003 +-1.000000 0.000000 -0.000003 +-1.000000 0.000000 -0.000003 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +0.000001 0.000001 -1.000000 +0.000001 0.000001 -1.000000 +0.000001 0.000001 -1.000000 +0.000001 0.000001 -1.000000 +0.000001 0.000001 -1.000000 +0.000001 0.000001 -1.000000 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +1.000000 -0.000000 0.000004 +1.000000 -0.000000 0.000004 +1.000000 -0.000000 0.000004 +1.000000 -0.000000 0.000004 +1.000000 -0.000000 0.000004 +1.000000 -0.000000 0.000004 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-1.000000 0.000000 -0.000003 +-1.000000 0.000000 -0.000003 +-1.000000 0.000000 -0.000003 +-1.000000 0.000000 -0.000003 +-1.000000 0.000000 -0.000003 +-1.000000 0.000000 -0.000003 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +1.000000 -0.000000 0.000005 +1.000000 -0.000000 0.000005 +1.000000 -0.000000 0.000005 +1.000000 -0.000000 0.000005 +1.000000 -0.000000 0.000005 +1.000000 -0.000000 0.000005 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-1.000000 0.000000 -0.000004 +-1.000000 0.000000 -0.000004 +-1.000000 0.000000 -0.000004 +-1.000000 0.000000 -0.000004 +-1.000000 0.000000 -0.000004 +-1.000000 0.000000 -0.000004 + + + + + + + + + + + +1.000000 0.000000 +0.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +1.000000 0.000000 +0.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +1.000000 0.000000 +0.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +1.000000 0.000000 +0.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +1.000000 0.000000 +0.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +1.000000 0.000000 +0.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +1.000000 0.000000 +0.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +1.000000 0.000000 +1.000000 0.000000 +0.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 + + + + + + + + + + + +

2 0 2 0 1 0 3 2 3 3 3 3 0 4 0 1 5 1 7 6 7 5 7 5 4 8 4 4 9 4 6 10 6 7 11 7 5 12 11 1 13 9 0 14 8 0 15 8 4 16 10 5 17 11 7 18 15 3 19 13 1 20 12 1 21 12 5 22 14 7 23 15 2 24 17 7 25 18 6 26 19 7 27 18 2 28 17 3 29 16 0 30 21 6 31 22 4 32 23 6 33 22 0 34 21 2 35 20 10 36 26 8 37 24 11 38 27 11 39 27 8 40 24 9 41 25 15 42 31 13 43 29 12 44 28 12 45 28 14 46 30 15 47 31 12 48 34 9 49 33 8 50 32 9 51 33 12 52 34 13 53 35 13 54 38 11 55 37 9 56 36 11 57 37 13 58 38 15 59 39 15 60 42 14 61 43 11 62 40 10 63 41 11 64 40 14 65 43 14 66 46 12 67 47 10 68 44 8 69 45 10 70 44 12 71 47 19 72 51 16 73 48 18 74 50 18 75 50 16 76 48 17 77 49 22 78 54 23 79 55 20 80 52 20 81 52 21 82 53 22 83 54 20 84 57 17 85 59 16 86 56 17 87 59 20 88 57 23 89 58 23 90 61 18 91 63 17 92 60 18 93 63 23 94 61 22 95 62 22 96 65 21 97 66 18 98 64 19 99 67 18 100 64 21 101 66 21 102 69 20 103 70 19 104 68 16 105 71 19 106 68 20 107 70 26 108 74 24 109 72 27 110 75 27 111 75 24 112 72 25 113 73 31 114 79 29 115 77 28 116 76 28 117 76 30 118 78 31 119 79 28 120 82 25 121 81 24 122 80 25 123 81 28 124 82 29 125 83 29 126 86 27 127 85 25 128 84 27 129 85 29 130 86 31 131 87 31 132 90 30 133 91 27 134 88 26 135 89 27 136 88 30 137 91 30 138 94 28 139 95 26 140 92 24 141 93 26 142 92 28 143 95

+
+
+
+ + + -0.000000 -0.000000 -1.000000 0.000000 -1.000000 0.000000 0.000000 -1.072197 0.000000 1.000000 -0.000000 131.071121 0.000000 0.000000 0.000000 1.0000001.000000 + 30.0000000.0000003.333333 + + + + + +
diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_visual.DAE b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_visual.DAE new file mode 100755 index 0000000..2caad6b --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_visual.DAE @@ -0,0 +1,3689 @@ + + + FBX COLLADA exporter2019-05-27T02:53:28Z2019-05-27T02:53:28ZZ_UP + + + ../materials/textures/aws_robomaker_warehouse_ShelfE_01.png + + + ../materials/textures/aws_robomaker_warehouse_ShelfE_03.png + + + ../materials/textures/aws_robomaker_warehouse_ShelfE_02.png + + + ../materials/textures/aws_robomaker_warehouse_ShelfE_03.png + + + + + + + + + + + + + + + + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + 0.800000 0.800000 0.800000 1.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + +-195.859360 -43.970364 11.286113 +-190.346848 -43.970360 11.286113 +-195.851028 -40.870396 -0.039542 +-195.851028 -43.964931 -0.039542 +-190.355179 -40.870392 -0.039542 +-190.355179 -43.964924 -0.039542 +-195.859344 -40.864964 11.286113 +-190.346863 -40.864960 11.286113 +-195.359573 -41.130783 11.389088 +-195.359573 -43.704540 11.389088 +-190.846634 -41.130779 11.389088 +-190.846634 -43.704540 11.389087 +-195.337234 -41.142639 261.250977 +-195.337234 -43.692688 261.250977 +-190.868851 -41.142639 261.250977 +-190.868851 -43.692688 261.250977 +190.346771 40.164623 11.286113 +195.859314 40.164623 11.286113 +190.355118 43.264595 -0.039542 +190.355118 40.170063 -0.039542 +195.850967 43.264603 -0.039542 +195.850967 40.170067 -0.039542 +190.346802 43.270035 11.286113 +195.859314 43.270039 11.286113 +190.846542 43.004223 11.389088 +190.846558 40.430458 11.389088 +195.359558 43.004227 11.389088 +195.359573 40.430462 11.389087 +190.868851 42.992374 261.250977 +190.868851 40.442318 261.250977 +195.337234 42.992374 261.250977 +195.337219 40.442322 261.250977 +-195.859360 40.164501 11.286113 +-190.346848 40.164501 11.286113 +-195.851028 43.264473 -0.039542 +-195.851028 40.169941 -0.039542 +-190.355179 43.264481 -0.039542 +-190.355179 40.169945 -0.039542 +-195.859344 43.269913 11.286113 +-190.346863 43.269917 11.286113 +-195.359573 43.004101 11.389088 +-195.359573 40.430336 11.389088 +-190.846634 43.004105 11.389088 +-190.846634 40.430340 11.389087 +-195.337234 42.992252 261.250977 +-195.337234 40.442196 261.250977 +-190.868851 42.992252 261.250977 +-190.868851 40.442200 261.250977 +-1.349450 40.164562 11.286113 +4.163049 40.164562 11.286113 +-1.341129 43.264534 -0.039542 +-1.341129 40.170002 -0.039542 +4.154719 43.264542 -0.039542 +4.154719 40.170006 -0.039542 +-1.349450 43.269974 11.286113 +4.163049 43.269978 11.286113 +-0.849689 43.004162 11.389088 +-0.849689 40.430397 11.389088 +3.663298 43.004166 11.389088 +3.663298 40.430401 11.389087 +-0.827415 42.992313 261.250977 +-0.827372 40.442257 261.250977 +3.640989 42.992317 261.250977 +3.641029 40.442265 261.250977 +-1.349419 -43.970303 11.286113 +4.163079 -43.970299 11.286113 +-1.341098 -40.870335 -0.039542 +-1.341098 -43.964870 -0.039542 +4.154749 -40.870331 -0.039542 +4.154749 -43.964863 -0.039542 +-1.349419 -40.864902 11.286113 +4.163079 -40.864899 11.286113 +-0.849659 -41.130722 11.389088 +-0.849659 -43.704479 11.389088 +3.663328 -41.130718 11.389088 +3.663328 -43.704479 11.389087 +-0.827342 -41.142574 261.250977 +-0.827328 -43.692627 261.250977 +3.641059 -41.142570 261.250977 +3.641079 -43.692627 261.250977 +190.346817 -43.970242 11.286113 +195.859329 -43.970238 11.286113 +190.355164 -40.870274 -0.039542 +190.355164 -43.964809 -0.039542 +195.850998 -40.870270 -0.039542 +195.850998 -43.964802 -0.039542 +190.346817 -40.864841 11.286113 +195.859329 -40.864838 11.286113 +190.846588 -41.130661 11.389088 +190.846588 -43.704418 11.389088 +195.359573 -41.130657 11.389088 +195.359573 -43.704418 11.389087 +190.868866 -41.142517 261.250977 +190.868881 -43.692566 261.250977 +195.337250 -41.142517 261.250977 +195.337265 -43.692566 261.250977 +-195.319946 -41.125313 13.878565 +-195.319916 40.434727 66.278061 +-190.886261 -41.125309 13.878560 +-195.319916 40.434727 70.460434 +-190.886246 -41.125320 9.696195 +-190.886246 40.434731 70.460434 +-195.319946 -41.125324 9.696195 +-190.886261 40.434731 66.278061 +-195.319992 -41.186462 144.465973 +-195.320007 40.434692 195.103180 +-195.320007 40.434704 199.280792 +-190.886292 -41.186459 144.465958 +-190.886322 40.434708 199.280792 +-190.886292 -41.186459 141.219635 +-190.886322 40.434696 195.103180 +-195.320007 -41.186462 141.219635 +-195.319946 -41.125320 134.569077 +-195.319916 40.434727 77.097397 +-195.319946 -41.125313 130.386719 +-190.886246 40.434731 77.097397 +-190.886261 40.434731 81.279785 +-190.886261 -41.125309 130.386734 +-190.886246 -41.125313 134.569077 +-195.319916 40.434727 81.279785 +190.824371 -41.125099 13.878565 +190.824371 40.434959 66.278061 +195.258072 -41.125080 13.878560 +190.824371 40.434959 70.460434 +195.258057 40.434978 70.460434 +195.258072 -41.125092 9.696197 +190.824371 -41.125111 9.696197 +195.258057 40.434978 66.278061 +190.824402 -41.186249 144.465973 +190.824356 40.434921 195.103180 +190.824341 40.434937 199.280792 +195.258087 -41.186234 144.465958 +195.258057 40.434948 199.280792 +195.258102 -41.186234 141.219635 +195.258057 40.434937 195.103180 +190.824402 -41.186249 141.219635 +190.824387 -41.125107 134.569061 +190.824402 40.434959 77.097397 +190.824387 -41.125099 130.386719 +195.258072 40.434978 77.097397 +195.258072 40.434978 81.279762 +195.258087 -41.125080 130.386719 +195.258087 -41.125088 134.569061 +190.824402 40.434959 81.279762 +-1.008084 -41.125114 13.878565 +-1.008087 40.434952 66.278061 +3.425621 -41.125095 13.878560 +-1.008087 40.434952 70.460434 +3.425587 40.434975 70.460434 +3.425621 -41.125103 9.696197 +-1.008084 -41.125122 9.696197 +3.425587 40.434975 66.278061 +-1.008060 -41.186264 144.465973 +-1.008118 40.434917 195.103180 +-1.008118 40.434925 199.280792 +3.425625 -41.186237 144.465958 +3.425590 40.434948 199.280792 +3.425625 -41.186237 141.219635 +3.425591 40.434937 195.103180 +-1.008060 -41.186264 141.219635 +-1.008083 -41.125118 134.569061 +-1.008064 40.434952 77.097397 +-1.008083 -41.125114 130.386719 +3.425602 40.434975 77.097397 +3.425602 40.434975 81.279762 +3.425617 -41.125095 130.386719 +3.425617 -41.125099 134.569061 +-1.008064 40.434952 81.279762 +190.734039 -41.267357 256.299133 +190.734024 41.439137 256.299133 +190.734039 -41.267357 259.323669 +190.734024 41.439137 259.323669 +195.278412 -41.267353 256.299133 +195.278397 41.439140 256.299133 +195.278412 -41.267353 259.323669 +195.278397 41.439140 259.323669 +-0.895264 -41.267330 256.299133 +-0.895294 41.439167 256.299133 +-0.895264 -41.267330 259.323669 +-0.895294 41.439167 259.323669 +3.649109 -41.267326 256.299133 +3.649078 41.439171 256.299133 +3.649109 -41.267326 259.323669 +3.649078 41.439171 259.323669 +-195.473846 -41.267296 256.299133 +-195.473846 41.439198 256.299133 +-195.473846 -41.267296 259.323669 +-195.473846 41.439198 259.323669 +-190.929474 -41.267292 256.299133 +-190.929474 41.439201 256.299133 +-190.929474 -41.267292 259.323669 +-190.929474 41.439201 259.323669 +-192.401459 38.361286 242.060989 +193.412613 38.361374 242.060989 +-192.401459 43.984394 236.176102 +-192.401459 38.361290 236.176102 +193.412598 43.984470 236.176102 +193.412613 38.361374 236.176102 +-192.401459 43.984390 242.060989 +193.412628 43.984474 242.060989 +-192.401535 -42.179398 140.859955 +193.412781 -42.179111 140.859970 +-192.401535 41.115921 134.975082 +-192.401505 -42.179394 134.975082 +193.412735 41.116199 134.975098 +193.412781 -42.179108 134.975098 +-192.401535 41.115921 140.859955 +193.412735 41.116199 140.859955 +-192.401535 -42.179398 76.744461 +193.412781 -42.179111 76.744469 +-192.401535 41.115921 70.859589 +-192.401505 -42.179394 70.859589 +193.412735 41.116199 70.859596 +193.412781 -42.179108 70.859596 +-192.401535 41.115921 76.744453 +193.412735 41.116199 76.744476 +-192.401535 41.115921 196.922226 +193.412735 41.116207 196.922226 +-192.401535 -42.179398 196.922226 +-192.401535 -42.179394 202.807083 +193.412781 -42.179111 196.922226 +193.412781 -42.179111 202.807083 +193.412735 41.116207 202.807083 +-192.401535 41.115925 202.807083 +-100.515869 25.034658 96.767853 +-178.499268 25.176374 76.381248 +-178.499268 25.176497 96.767883 +-100.515869 25.034658 76.381271 +-100.603271 -22.747515 76.381271 +-178.586060 -22.605913 76.381248 +-178.586060 -22.605837 96.767883 +-100.603271 -22.747606 96.767868 +-10.756012 25.034658 96.767853 +-88.739410 25.176374 76.381248 +-88.739410 25.176497 96.767883 +-10.756012 25.034658 76.381271 +-10.843414 -22.747515 76.381271 +-88.826202 -22.605913 76.381248 +-88.826202 -22.605837 96.767883 +-10.843414 -22.747606 96.767868 +-136.529434 -37.821102 161.109482 +-136.387711 40.162300 140.722885 +-136.387589 40.162300 161.109512 +-136.529434 -37.821102 140.722916 +-184.311539 -37.733696 140.722916 +-184.169937 40.249088 140.722885 +-184.169937 40.249088 161.109512 +-184.311661 -37.733696 161.109512 +72.596710 29.278488 123.836227 +72.890900 -25.122681 76.618340 +72.596710 29.278488 76.618340 +72.890900 -25.122711 123.836227 +8.309597 -25.279179 76.618340 +8.015530 29.122051 76.618340 +9.438137 29.125500 123.836227 +8.309963 -25.279179 123.836227 +8.016140 29.122051 123.836227 +189.951172 -36.224636 75.382462 +137.447266 39.841038 75.382462 +189.951172 39.841278 75.382446 +137.447266 -36.224880 75.382469 +137.447266 39.841038 82.989067 +189.951172 -36.224636 82.989067 +189.951172 39.841278 82.989052 +137.447266 -36.224880 82.989075 +189.951172 -36.224636 83.132347 +137.447266 39.841038 83.132355 +189.951172 39.841278 83.132332 +137.447266 -36.224880 83.132370 +137.447266 39.841038 90.738976 +189.951172 -36.224636 90.738960 +189.951172 39.841278 90.738960 +137.447266 -36.224880 90.738976 +-112.536499 29.278488 250.422791 +-112.242310 -25.122681 203.204910 +-112.536499 29.278488 203.204910 +-112.242310 -25.122711 250.422791 +-176.823608 -25.279179 203.204910 +-177.117676 29.122051 203.204910 +-175.695068 29.125500 250.422791 +-176.823242 -25.279179 250.422791 +-177.117065 29.122051 250.422791 +95.399185 25.034658 161.436584 +17.415787 25.176378 141.049973 +17.415787 25.176500 161.436615 +95.399185 25.034658 141.049988 +95.311783 -22.747515 141.049988 +17.328995 -22.605909 141.049973 +17.328995 -22.605833 161.436615 +95.311783 -22.747606 161.436584 +95.399185 25.034658 182.055481 +17.415787 25.176382 161.668884 +17.415787 25.176504 182.055511 +95.399185 25.034658 161.668884 +95.311783 -22.747519 161.668884 +17.328995 -22.605909 161.668884 +17.328995 -22.605833 182.055511 +95.311783 -22.747610 182.055481 +82.850586 25.034658 222.664795 +4.867188 25.176378 202.278183 +4.867188 25.176500 222.664825 +82.850586 25.034658 202.278198 +82.763184 -22.747515 202.278198 +4.780396 -22.605909 202.278183 +4.780396 -22.605833 222.664825 +82.763184 -22.747606 222.664795 +-92.589783 -24.403721 203.107849 +-16.469368 28.020813 203.107849 +-16.523869 -24.483076 203.107834 +-92.535278 28.100182 203.107864 +-16.469368 28.020813 210.714432 +-92.589783 -24.403721 210.714432 +-16.523869 -24.483076 210.714462 +-92.535278 28.100182 210.714462 +-92.589783 -24.403721 210.857742 +-16.469368 28.020813 210.857742 +-16.523869 -24.483076 210.857712 +-92.535278 28.100182 210.857758 +-16.469368 28.020813 218.464371 +-92.589783 -24.403721 218.464340 +-16.523869 -24.483076 218.464340 +-92.535278 28.100182 218.464371 +-92.590866 -24.403788 218.585449 +-16.470409 28.020967 218.585449 +-16.524956 -24.483145 218.585449 +-92.536324 28.100309 218.585449 +-16.470409 28.020967 226.192017 +-92.590866 -24.403788 226.192017 +-16.524956 -24.483145 226.192017 +-92.536324 28.100309 226.192017 +162.264526 25.034658 222.664795 +84.281128 25.176378 202.278183 +84.281128 25.176500 222.664825 +162.264526 25.034658 202.278198 +162.177124 -22.747515 202.278198 +84.194336 -22.605909 202.278183 +84.194336 -22.605833 222.664825 +162.177124 -22.747606 222.664795 +162.264526 25.034658 243.283691 +84.281128 25.176382 222.897095 +84.281128 25.176504 243.283722 +162.264526 25.034658 222.897095 +162.177124 -22.747519 222.897095 +84.194336 -22.605909 222.897095 +84.194336 -22.605833 243.283722 +162.177124 -22.747610 243.283691 +66.539444 -9.329350 242.569305 +156.241531 12.946537 242.569305 +137.709412 -36.178265 242.569305 +85.071533 39.795441 242.569305 +156.241531 12.946537 250.175873 +66.539444 -9.329350 250.175873 +137.709412 -36.178265 250.175873 +85.071533 39.795441 250.175873 +-2.835217 29.278488 188.737320 +-2.541027 -25.122681 141.519440 +-2.835217 29.278488 141.519440 +-2.541027 -25.122711 188.737320 +-67.122330 -25.279179 141.519440 +-67.416397 29.122051 141.519440 +-65.993790 29.125500 188.737320 +-67.121964 -25.279179 188.737320 +-67.415787 29.122051 188.737320 +-74.777939 -36.224636 141.372421 +-127.281845 39.841038 141.372421 +-74.777939 39.841278 141.372391 +-127.281845 -36.224880 141.372421 +-127.281845 39.841038 148.979019 +-74.777939 -36.224636 148.979019 +-74.777939 39.841278 148.979004 +-127.281845 -36.224880 148.979019 +-74.777939 -36.224636 149.122299 +-127.281845 39.841038 149.122299 +-74.777939 39.841278 149.122284 +-127.281845 -36.224880 149.122330 +-127.281845 39.841038 156.728928 +-74.777939 -36.224636 156.728912 +-74.777939 39.841278 156.728912 +-127.281845 -36.224880 156.728928 +-74.778671 -36.224316 156.850021 +-127.282822 39.841358 156.850021 +-74.778671 39.841599 156.850021 +-127.282822 -36.224560 156.850021 +-127.282822 39.841358 164.456589 +-74.778671 -36.224316 164.456589 +-74.778671 39.841599 164.456589 +-127.282822 -36.224560 164.456589 +-74.777939 -36.224632 164.726944 +-127.281845 39.841042 164.726944 +-74.777939 39.841278 164.726944 +-127.281845 -36.224876 164.726944 +-127.281845 39.841042 172.333511 +-74.777939 -36.224632 172.333511 +-74.777939 39.841278 172.333511 +-127.281845 -36.224876 172.333542 +130.889359 -36.224636 75.382462 +78.385452 39.841038 75.382462 +130.889359 39.841278 75.382446 +78.385452 -36.224880 75.382469 +78.385452 39.841038 82.989067 +130.889359 -36.224636 82.989067 +130.889359 39.841278 82.989052 +78.385452 -36.224880 82.989075 +130.889359 -36.224636 83.132347 +78.385452 39.841038 83.132355 +130.889359 39.841278 83.132332 +78.385452 -36.224880 83.132370 +78.385452 39.841038 90.738976 +130.889359 -36.224636 90.738960 +130.889359 39.841278 90.738960 +78.385452 -36.224880 90.738976 +130.888626 -36.224316 90.860062 +78.384476 39.841358 90.860062 +130.888626 39.841599 90.860062 +78.384476 -36.224560 90.860062 +78.384476 39.841358 98.466629 +130.888626 -36.224316 98.466629 +130.888626 39.841599 98.466629 +78.384476 -36.224560 98.466629 +130.889359 -36.224632 98.737000 +78.385452 39.841042 98.737000 +130.889359 39.841278 98.737000 +78.385452 -36.224876 98.737000 +78.385452 39.841042 106.343567 +130.889359 -36.224632 106.343567 +130.889359 39.841278 106.343567 +78.385452 -36.224876 106.343582 +169.132980 29.278488 188.737320 +169.427170 -25.122681 141.519440 +169.132980 29.278488 141.519440 +169.427170 -25.122711 188.737320 +104.845879 -25.279179 141.519440 +104.551811 29.122051 141.519440 +105.974419 29.125500 188.737320 +104.846245 -25.279179 188.737320 +104.552422 29.122051 188.737320 + + + + + + + + + + + +0.119405 -0.230384 -0.965746 +-0.119235 -0.230441 -0.965754 +-0.119211 0.230672 -0.965701 +-0.119211 0.230672 -0.965701 +0.119380 0.230616 -0.965694 +0.119405 -0.230384 -0.965746 +-0.956403 -0.263505 0.125933 +-0.956333 0.263761 0.125924 +-0.951498 0.257330 -0.168618 +-0.951498 0.257330 -0.168618 +-0.951559 -0.257087 -0.168648 +-0.956403 -0.263505 0.125933 +0.089169 -0.993226 0.074504 +-0.089036 -0.993235 0.074540 +-0.085984 -0.990457 -0.107708 +-0.085984 -0.990457 -0.107708 +0.086116 -0.990450 -0.107670 +0.089169 -0.993226 0.074504 +0.956359 0.263819 0.125605 +0.956429 -0.263562 0.125613 +0.951558 -0.257089 -0.168647 +0.951558 -0.257089 -0.168647 +0.951499 0.257328 -0.168619 +0.956359 0.263819 0.125605 +-0.089268 0.993198 0.074763 +0.089400 0.993189 0.074727 +0.086342 0.990400 -0.107949 +0.086342 0.990400 -0.107949 +-0.086212 0.990407 -0.107986 +-0.089268 0.993198 0.074763 +-0.059645 -0.051640 0.996883 +-0.059645 0.051639 0.996883 +-0.178122 0.324574 0.928937 +-0.178122 0.324574 0.928937 +-0.178085 -0.324917 0.928824 +-0.059645 -0.051640 0.996883 +0.059645 -0.051639 0.996883 +-0.059645 -0.051640 0.996883 +-0.178085 -0.324917 0.928824 +-0.178085 -0.324917 0.928824 +0.178086 -0.324915 0.928825 +0.059645 -0.051639 0.996883 +0.059645 0.051640 0.996883 +0.059645 -0.051639 0.996883 +0.178086 -0.324915 0.928825 +0.178086 -0.324915 0.928825 +0.178121 0.324575 0.928937 +0.059645 0.051640 0.996883 +-0.059645 0.051639 0.996883 +0.059645 0.051640 0.996883 +0.178121 0.324575 0.928937 +0.178121 0.324575 0.928937 +-0.178122 0.324574 0.928937 +-0.059645 0.051639 0.996883 +-0.956902 -0.286501 -0.047494 +-0.956754 0.286993 -0.047506 +-0.935699 0.302882 0.180917 +-0.935699 0.302882 0.180917 +-0.935847 -0.302400 0.180955 +-0.956902 -0.286501 -0.047494 +0.094684 -0.995181 -0.025483 +-0.094927 -0.995157 -0.025505 +-0.097945 -0.990243 0.099122 +-0.097945 -0.990243 0.099122 +0.097942 -0.990243 0.099126 +0.094684 -0.995181 -0.025483 +0.956974 0.286285 -0.047354 +0.957125 -0.285780 -0.047344 +0.935975 -0.302063 0.180856 +0.935975 -0.302063 0.180856 +0.935830 0.302532 0.180824 +0.956974 0.286285 -0.047354 +-0.095144 0.995135 -0.025563 +0.094891 0.995160 -0.025542 +0.098119 0.990255 0.098831 +0.098119 0.990255 0.098831 +-0.098117 0.990255 0.098834 +-0.095144 0.995135 -0.025563 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.119375 -0.230443 -0.965736 +-0.119330 -0.230456 -0.965738 +-0.119314 0.230833 -0.965650 +-0.119314 0.230833 -0.965650 +0.119359 0.230820 -0.965648 +0.119375 -0.230443 -0.965736 +-0.956450 -0.263645 0.125275 +-0.956341 0.264048 0.125261 +-0.951446 0.257519 -0.168624 +-0.951446 0.257519 -0.168624 +-0.951550 -0.257121 -0.168644 +-0.956450 -0.263645 0.125275 +0.089316 -0.993153 0.075303 +-0.089283 -0.993155 0.075314 +-0.086285 -0.990402 -0.107976 +-0.086285 -0.990402 -0.107976 +0.086320 -0.990400 -0.107968 +0.089316 -0.993153 0.075303 +0.956265 0.264181 0.125560 +0.956375 -0.263778 0.125574 +0.951481 -0.257288 -0.168778 +0.951481 -0.257288 -0.168778 +0.951378 0.257683 -0.168759 +0.956265 0.264181 0.125560 +-0.089247 0.993157 0.075321 +0.089277 0.993155 0.075311 +0.086286 0.990407 -0.107928 +0.086286 0.990407 -0.107928 +-0.086253 0.990409 -0.107936 +-0.089247 0.993157 0.075321 +-0.059706 -0.051712 0.996876 +-0.059706 0.051713 0.996876 +-0.178425 0.325176 0.928668 +-0.178425 0.325176 0.928668 +-0.178431 -0.325180 0.928666 +-0.059706 -0.051712 0.996876 +0.059722 -0.051734 0.996873 +-0.059706 -0.051712 0.996876 +-0.178431 -0.325180 0.928666 +-0.178431 -0.325180 0.928666 +0.178585 -0.325143 0.928649 +0.059722 -0.051734 0.996873 +0.059722 0.051734 0.996874 +0.059722 -0.051734 0.996873 +0.178585 -0.325143 0.928649 +0.178585 -0.325143 0.928649 +0.178656 0.325122 0.928643 +0.059722 0.051734 0.996874 +-0.059706 0.051713 0.996876 +0.059722 0.051734 0.996874 +0.178656 0.325122 0.928643 +0.178656 0.325122 0.928643 +-0.178425 0.325176 0.928668 +-0.059706 0.051713 0.996876 +-0.956803 -0.286841 -0.047442 +-0.956947 0.286356 -0.047456 +-0.935859 0.302824 0.180182 +-0.935859 0.302824 0.180182 +-0.935721 -0.303220 0.180234 +-0.956803 -0.286841 -0.047442 +0.094855 -0.995165 -0.025491 +-0.094809 -0.995169 -0.025488 +-0.097976 -0.990204 0.099478 +-0.097976 -0.990204 0.099478 +0.098011 -0.990200 0.099489 +0.094855 -0.995165 -0.025491 +0.957166 0.285648 -0.047304 +0.957038 -0.286079 -0.047293 +0.935784 -0.303054 0.180183 +0.935784 -0.303054 0.180183 +0.935925 0.302646 0.180138 +0.957166 0.285648 -0.047304 +-0.095272 0.995122 -0.025614 +0.095311 0.995118 -0.025619 +0.098367 0.990224 0.098898 +0.098367 0.990224 0.098898 +-0.098322 0.990228 0.098898 +-0.095272 0.995122 -0.025614 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.119401 -0.230417 -0.965739 +-0.119231 -0.230474 -0.965746 +-0.119216 0.230850 -0.965658 +-0.119216 0.230850 -0.965658 +0.119385 0.230794 -0.965651 +0.119401 -0.230417 -0.965739 +-0.956398 -0.263530 0.125914 +-0.956289 0.263933 0.125901 +-0.951446 0.257519 -0.168624 +-0.951446 0.257519 -0.168624 +-0.951550 -0.257121 -0.168644 +-0.956398 -0.263530 0.125914 +0.089337 -0.993152 0.075283 +-0.089204 -0.993161 0.075319 +-0.086211 -0.990407 -0.107986 +-0.086211 -0.990407 -0.107986 +0.086343 -0.990400 -0.107948 +0.089337 -0.993152 0.075283 +0.956315 0.263991 0.125581 +0.956424 -0.263587 0.125595 +0.951550 -0.257123 -0.168644 +0.951550 -0.257123 -0.168644 +0.951446 0.257518 -0.168624 +0.956315 0.263991 0.125581 +-0.089167 0.993164 0.075327 +0.089299 0.993155 0.075291 +0.086309 0.990407 -0.107909 +0.086309 0.990407 -0.107909 +-0.086179 0.990414 -0.107946 +-0.089167 0.993164 0.075327 +-0.059651 -0.051645 0.996882 +-0.059652 0.051644 0.996882 +-0.178090 0.325226 0.928715 +-0.178090 0.325226 0.928715 +-0.178095 -0.325230 0.928713 +-0.059651 -0.051645 0.996882 +0.059652 -0.051644 0.996882 +-0.059651 -0.051645 0.996882 +-0.178095 -0.325230 0.928713 +-0.178095 -0.325230 0.928713 +0.178095 -0.325229 0.928713 +0.059652 -0.051644 0.996882 +0.059651 0.051645 0.996882 +0.059652 -0.051644 0.996882 +0.178095 -0.325229 0.928713 +0.178095 -0.325229 0.928713 +0.178089 0.325227 0.928715 +0.059651 0.051645 0.996882 +-0.059652 0.051644 0.996882 +0.059651 0.051645 0.996882 +0.178089 0.325227 0.928715 +0.178089 0.325227 0.928715 +-0.178090 0.325226 0.928715 +-0.059652 0.051644 0.996882 +-0.956759 -0.286980 -0.047481 +-0.956880 0.286574 -0.047493 +-0.935838 0.302474 0.180875 +-0.935838 0.302474 0.180875 +-0.935700 -0.302870 0.180926 +-0.956759 -0.286980 -0.047481 +0.094649 -0.995185 -0.025473 +-0.094892 -0.995161 -0.025495 +-0.097976 -0.990204 0.099478 +-0.097976 -0.990204 0.099478 +0.097974 -0.990204 0.099482 +0.094649 -0.995185 -0.025473 +0.957099 0.285866 -0.047341 +0.956983 -0.286258 -0.047331 +0.935829 -0.302532 0.180827 +0.935829 -0.302532 0.180827 +0.935969 0.302125 0.180782 +0.957099 0.285866 -0.047341 +-0.095356 0.995113 -0.025622 +0.095103 0.995138 -0.025600 +0.098324 0.990228 0.098895 +0.098324 0.990228 0.098895 +-0.098322 0.990228 0.098898 +-0.095356 0.995113 -0.025622 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.119406 -0.230420 -0.965737 +-0.119429 -0.230438 -0.965730 +-0.119413 0.230814 -0.965642 +-0.119413 0.230814 -0.965642 +0.119389 0.230797 -0.965649 +0.119406 -0.230420 -0.965737 +-0.956461 -0.263369 0.125776 +-0.956352 0.263771 0.125762 +-0.951515 0.257354 -0.168490 +-0.951515 0.257354 -0.168490 +-0.951619 -0.256956 -0.168510 +-0.956461 -0.263369 0.125776 +0.089354 -0.993150 0.075299 +-0.089353 -0.993150 0.075299 +-0.086359 -0.990397 -0.107966 +-0.086359 -0.990397 -0.107966 +0.086346 -0.990399 -0.107951 +0.089354 -0.993150 0.075299 +0.956215 0.264371 0.125539 +0.956325 -0.263968 0.125553 +0.951413 -0.257453 -0.168912 +0.951413 -0.257453 -0.168912 +0.951309 0.257848 -0.168893 +0.956215 0.264371 0.125539 +-0.089317 0.993152 0.075306 +0.089316 0.993152 0.075307 +0.086312 0.990407 -0.107912 +0.086312 0.990407 -0.107912 +-0.086327 0.990404 -0.107926 +-0.089317 0.993152 0.075306 +-0.059706 -0.051712 0.996876 +-0.059706 0.051711 0.996876 +-0.178271 0.325213 0.928685 +-0.178271 0.325213 0.928685 +-0.178277 -0.325216 0.928683 +-0.059706 -0.051712 0.996876 +0.059652 -0.051644 0.996882 +-0.059706 -0.051712 0.996876 +-0.178277 -0.325216 0.928683 +-0.178277 -0.325216 0.928683 +0.178249 -0.325192 0.928697 +0.059652 -0.051644 0.996882 +0.059651 0.051645 0.996882 +0.059652 -0.051644 0.996882 +0.178249 -0.325192 0.928697 +0.178249 -0.325192 0.928697 +0.178243 0.325190 0.928698 +0.059651 0.051645 0.996882 +-0.059706 0.051711 0.996876 +0.059651 0.051645 0.996882 +0.178243 0.325190 0.928698 +0.178243 0.325190 0.928698 +-0.178271 0.325213 0.928685 +-0.059706 0.051711 0.996876 +-0.956867 -0.286633 -0.047410 +-0.957030 0.286087 -0.047416 +-0.935837 0.303084 0.179859 +-0.935837 0.303084 0.179859 +-0.935699 -0.303480 0.179911 +-0.956867 -0.286633 -0.047410 +0.094767 -0.995173 -0.025490 +-0.094954 -0.995155 -0.025518 +-0.097939 -0.990209 0.099471 +-0.097939 -0.990209 0.099471 +0.098066 -0.990195 0.099485 +0.094767 -0.995173 -0.025490 +0.957021 0.286115 -0.047424 +0.956875 -0.286606 -0.047402 +0.935925 -0.302580 0.180248 +0.935925 -0.302580 0.180248 +0.936065 0.302173 0.180203 +0.957021 0.286115 -0.047424 +-0.095347 0.995114 -0.025629 +0.095227 0.995126 -0.025611 +0.098417 0.990219 0.098898 +0.098417 0.990219 0.098898 +-0.098284 0.990233 0.098891 +-0.095347 0.995114 -0.025629 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.119409 -0.230387 -0.965745 +-0.119432 -0.230405 -0.965738 +-0.119409 0.230636 -0.965686 +-0.119409 0.230636 -0.965686 +0.119385 0.230620 -0.965692 +0.119409 -0.230387 -0.965745 +-0.956465 -0.263343 0.125794 +-0.956396 0.263599 0.125785 +-0.951567 0.257165 -0.168484 +-0.951567 0.257165 -0.168484 +-0.951627 -0.256922 -0.168514 +-0.956465 -0.263343 0.125794 +0.089186 -0.993223 0.074520 +-0.089186 -0.993223 0.074520 +-0.086131 -0.990447 -0.107688 +-0.086131 -0.990447 -0.107688 +0.086118 -0.990449 -0.107673 +0.089186 -0.993223 0.074520 +0.956260 0.264199 0.125562 +0.956330 -0.263943 0.125571 +0.951421 -0.257419 -0.168916 +0.951421 -0.257419 -0.168916 +0.951362 0.257659 -0.168887 +0.956260 0.264199 0.125562 +-0.089418 0.993186 0.074743 +0.089417 0.993186 0.074743 +0.086345 0.990399 -0.107952 +0.086345 0.990399 -0.107952 +-0.086360 0.990397 -0.107965 +-0.089418 0.993186 0.074743 +-0.059699 -0.051708 0.996876 +-0.059699 0.051707 0.996876 +-0.178304 0.324561 0.928907 +-0.178304 0.324561 0.928907 +-0.178267 -0.324903 0.928794 +-0.059699 -0.051708 0.996876 +0.059645 -0.051639 0.996883 +-0.059699 -0.051708 0.996876 +-0.178267 -0.324903 0.928794 +-0.178267 -0.324903 0.928794 +0.178239 -0.324879 0.928808 +0.059645 -0.051639 0.996883 +0.059645 0.051640 0.996883 +0.059645 -0.051639 0.996883 +0.178239 -0.324879 0.928808 +0.178239 -0.324879 0.928808 +0.178275 0.324538 0.928920 +0.059645 0.051640 0.996883 +-0.059699 0.051707 0.996876 +0.059645 0.051640 0.996883 +0.178275 0.324538 0.928920 +0.178275 0.324538 0.928920 +-0.178304 0.324561 0.928907 +-0.059699 0.051707 0.996876 +-0.956902 -0.286501 -0.047494 +-0.956866 0.286632 -0.047435 +-0.935697 0.303492 0.179901 +-0.935697 0.303492 0.179901 +-0.935846 -0.303009 0.179939 +-0.956902 -0.286501 -0.047494 +0.094837 -0.995166 -0.025510 +-0.095030 -0.995147 -0.025535 +-0.097908 -0.990248 0.099115 +-0.097908 -0.990248 0.099115 +0.098035 -0.990234 0.099129 +0.094837 -0.995166 -0.025510 +0.956863 0.286642 -0.047436 +0.957016 -0.286134 -0.047418 +0.936071 -0.302110 0.180277 +0.936071 -0.302110 0.180277 +0.935926 0.302580 0.180245 +0.956863 0.286642 -0.047436 +-0.095136 0.995136 -0.025567 +0.094939 0.995156 -0.025539 +0.098212 0.990246 0.098834 +0.098212 0.990246 0.098834 +-0.098079 0.990259 0.098827 +-0.095136 0.995136 -0.025567 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.119379 -0.230410 -0.965743 +-0.119329 -0.230419 -0.965747 +-0.119305 0.230651 -0.965695 +-0.119305 0.230651 -0.965695 +0.119354 0.230643 -0.965691 +0.119379 -0.230410 -0.965743 +-0.956455 -0.263620 0.125293 +-0.956385 0.263876 0.125285 +-0.951498 0.257330 -0.168618 +-0.951498 0.257330 -0.168618 +-0.951559 -0.257087 -0.168648 +-0.956455 -0.263620 0.125293 +0.089148 -0.993226 0.074524 +-0.089116 -0.993229 0.074535 +-0.086054 -0.990453 -0.107695 +-0.086054 -0.990453 -0.107695 +0.086092 -0.990450 -0.107689 +0.089148 -0.993226 0.074524 +0.956260 0.264199 0.125562 +0.956379 -0.263753 0.125592 +0.951490 -0.257253 -0.168783 +0.951490 -0.257253 -0.168783 +0.951362 0.257659 -0.168887 +0.956260 0.264199 0.125562 +-0.089348 0.993191 0.074758 +0.089378 0.993189 0.074747 +0.086319 0.990400 -0.107968 +0.086319 0.990400 -0.107968 +-0.086283 0.990403 -0.107973 +-0.089348 0.993191 0.074758 +-0.059699 -0.051708 0.996876 +-0.059699 0.051708 0.996876 +-0.178472 0.324536 0.928883 +-0.178472 0.324536 0.928883 +-0.178435 -0.324879 0.928771 +-0.059699 -0.051708 0.996876 +0.059731 -0.051751 0.996872 +-0.059699 -0.051708 0.996876 +-0.178435 -0.324879 0.928771 +-0.178435 -0.324879 0.928771 +0.178666 -0.324823 0.928746 +0.059731 -0.051751 0.996872 +0.059731 0.051751 0.996872 +0.059731 -0.051751 0.996872 +0.178666 -0.324823 0.928746 +0.178666 -0.324823 0.928746 +0.178702 0.324482 0.928858 +0.059731 0.051751 0.996872 +-0.059699 0.051708 0.996876 +0.059731 0.051751 0.996872 +0.178702 0.324482 0.928858 +0.178702 0.324482 0.928858 +-0.178472 0.324536 0.928883 +-0.059699 0.051708 0.996876 +-0.956956 -0.286326 -0.047458 +-0.956757 0.286982 -0.047514 +-0.935719 0.303231 0.180224 +-0.935719 0.303231 0.180224 +-0.935868 -0.302749 0.180262 +-0.956956 -0.286326 -0.047458 +0.094967 -0.995153 -0.025514 +-0.094845 -0.995166 -0.025498 +-0.097945 -0.990243 0.099122 +-0.097945 -0.990243 0.099122 +0.097986 -0.990238 0.099129 +0.094967 -0.995153 -0.025514 +0.957030 0.286102 -0.047321 +0.957180 -0.285601 -0.047306 +0.935931 -0.302584 0.180211 +0.935931 -0.302584 0.180211 +0.935785 0.303054 0.180179 +0.957030 0.286102 -0.047321 +-0.095138 0.995136 -0.025569 +0.095140 0.995136 -0.025563 +0.098162 0.990250 0.098834 +0.098162 0.990250 0.098834 +-0.098117 0.990255 0.098834 +-0.095138 0.995136 -0.025569 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.985978 -0.095115 0.137113 +-0.949755 -0.178415 0.257163 +-0.985878 0.095453 -0.137597 +-0.985878 0.095453 -0.137597 +-0.948297 0.180918 -0.260770 +-0.985978 -0.095115 0.137113 +0.188900 -0.559726 0.806860 +0.117083 -0.566086 0.815989 +-0.117067 -0.566069 0.816003 +-0.117067 -0.566069 0.816003 +-0.188881 -0.559749 0.806849 +0.188900 -0.559726 0.806860 +0.985921 0.095316 -0.137386 +0.949914 -0.178127 0.256776 +0.986163 -0.094499 0.136209 +0.986163 -0.094499 0.136209 +0.948917 0.179845 -0.259252 +0.985921 0.095316 -0.137386 +-0.118970 0.565940 -0.815818 +-0.191917 0.559413 -0.806365 +0.191932 0.559391 -0.806377 +0.191932 0.559391 -0.806377 +0.118984 0.565957 -0.815803 +-0.118970 0.565940 -0.815818 +-0.986292 0.090913 -0.137707 +-0.949902 0.172190 -0.260838 +-0.986592 -0.090992 0.135485 +-0.986592 -0.090992 0.135485 +-0.949886 -0.174273 0.259509 +-0.986292 0.090913 -0.137707 +-0.187114 -0.547656 0.815513 +0.187097 -0.547674 0.815505 +0.127645 -0.552942 0.823384 +0.127645 -0.552942 0.823384 +-0.127399 -0.552974 0.823401 +-0.187114 -0.547656 0.815513 +0.986635 -0.090843 0.135274 +0.950045 0.171961 -0.260470 +0.986295 0.090899 -0.137697 +0.986295 0.090899 -0.137697 +0.949880 -0.174293 0.259518 +0.986635 -0.090843 0.135274 +0.128199 0.546376 -0.827670 +-0.128212 0.546391 -0.827659 +-0.189856 0.540902 -0.819378 +-0.189856 0.540902 -0.819378 +0.190238 0.540878 -0.819305 +0.128199 0.546376 -0.827670 +-0.985580 0.092551 0.141657 +-0.952583 -0.166438 -0.254722 +-0.985690 -0.092197 -0.141119 +-0.985690 -0.092197 -0.141119 +-0.951152 0.168869 0.258442 +-0.985580 0.092551 0.141657 +-0.119608 -0.543026 -0.831154 +0.119633 -0.543044 -0.831139 +0.191447 -0.536835 -0.821679 +0.191447 -0.536835 -0.821679 +-0.191430 -0.536859 -0.821668 +-0.119608 -0.543026 -0.831154 +0.985872 -0.091621 -0.140219 +0.952724 -0.166185 -0.254363 +0.985626 0.092411 0.141429 +0.985626 0.092411 0.141429 +0.951738 0.167865 0.256935 +0.985872 -0.091621 -0.140219 +0.194545 0.536501 0.821169 +-0.194528 0.536525 0.821157 +-0.121214 0.542919 0.830991 +-0.121214 0.542919 0.830991 +0.121217 0.542938 0.830978 +0.194545 0.536501 0.821169 +-0.985980 -0.095111 0.137106 +-0.949749 -0.178426 0.257179 +-0.985878 0.095453 -0.137597 +-0.985878 0.095453 -0.137597 +-0.948300 0.180912 -0.260762 +-0.985980 -0.095111 0.137106 +0.189033 -0.559712 0.806839 +0.117169 -0.566081 0.815981 +-0.116913 -0.566079 0.816018 +-0.116913 -0.566079 0.816018 +-0.188687 -0.559770 0.806880 +0.189033 -0.559712 0.806839 +0.985809 0.095692 -0.137928 +0.949519 -0.178811 0.257762 +0.986075 -0.094797 0.136638 +0.986075 -0.094797 0.136638 +0.948612 0.180368 -0.260006 +0.985809 0.095692 -0.137928 +-0.118817 0.565950 -0.815833 +-0.191627 0.559445 -0.806412 +0.192003 0.559383 -0.806366 +0.192003 0.559383 -0.806366 +0.119011 0.565956 -0.815801 +-0.118817 0.565950 -0.815833 +-0.986322 0.090812 -0.137555 +-0.949604 0.172688 -0.261593 +-0.986517 -0.091247 0.135864 +-0.986517 -0.091247 0.135864 +-0.949961 -0.174146 0.259320 +-0.986322 0.090812 -0.137555 +-0.186852 -0.547684 0.815554 +0.187154 -0.547668 0.815496 +0.127630 -0.552943 0.823386 +0.127630 -0.552943 0.823386 +-0.127234 -0.552986 0.823418 +-0.186852 -0.547684 0.815554 +0.986635 -0.090843 0.135274 +0.950054 0.171945 -0.260445 +0.986295 0.090899 -0.137697 +0.986295 0.090899 -0.137697 +0.949890 -0.174277 0.259494 +0.986635 -0.090843 0.135274 +0.128240 0.546373 -0.827666 +-0.128057 0.546402 -0.827676 +-0.189613 0.540928 -0.819417 +-0.189613 0.540928 -0.819417 +0.190188 0.540884 -0.819313 +0.128240 0.546373 -0.827666 +-0.985558 0.092622 0.141765 +-0.952535 -0.166521 -0.254848 +-0.985679 -0.092233 -0.141174 +-0.985679 -0.092233 -0.141174 +-0.951117 0.168929 0.258533 +-0.985558 0.092622 0.141765 +-0.119490 -0.543033 -0.831166 +0.119703 -0.543039 -0.831132 +0.191647 -0.536814 -0.821646 +0.191647 -0.536814 -0.821646 +-0.191162 -0.536887 -0.821711 +-0.119490 -0.543033 -0.831166 +0.985795 -0.091868 -0.140598 +0.952450 -0.166654 -0.255081 +0.985542 0.092678 0.141836 +0.985542 0.092678 0.141836 +0.951478 0.168306 0.257610 +0.985795 -0.091868 -0.140598 +0.194915 0.536461 0.821107 +-0.194599 0.536518 0.821146 +-0.121183 0.542921 0.830994 +-0.121183 0.542921 0.830994 +0.121481 0.542921 0.830951 +0.194915 0.536461 0.821107 +-0.985980 -0.095111 0.137106 +-0.949680 -0.178545 0.257350 +-0.985856 0.095525 -0.137702 +-0.985856 0.095525 -0.137702 +-0.948300 0.180912 -0.260762 +-0.985980 -0.095111 0.137106 +0.188901 -0.559726 0.806860 +0.117160 -0.566081 0.815982 +-0.116875 -0.566082 0.816022 +-0.116875 -0.566082 0.816022 +-0.188554 -0.559785 0.806901 +0.188901 -0.559726 0.806860 +0.985776 0.095802 -0.138086 +0.949368 -0.179071 0.258136 +0.986032 -0.094942 0.136847 +0.986032 -0.094942 0.136847 +0.948459 0.180629 -0.260382 +0.985776 0.095802 -0.138086 +-0.118740 0.565955 -0.815840 +-0.191581 0.559451 -0.806419 +0.192003 0.559383 -0.806366 +0.192003 0.559383 -0.806366 +0.118945 0.565960 -0.815807 +-0.118740 0.565955 -0.815840 +-0.986344 0.090742 -0.137449 +-0.949604 0.172688 -0.261593 +-0.986509 -0.091273 0.135901 +-0.986509 -0.091273 0.135901 +-0.950036 -0.174020 0.259132 +-0.986344 0.090742 -0.137449 +-0.186917 -0.547677 0.815544 +0.187102 -0.547673 0.815504 +0.127672 -0.552940 0.823381 +0.127672 -0.552940 0.823381 +-0.127197 -0.552989 0.823422 +-0.186917 -0.547677 0.815544 +0.986614 -0.090913 0.135379 +0.949970 0.172086 -0.260659 +0.986252 0.091039 -0.137908 +0.986252 0.091039 -0.137908 +0.949731 -0.174546 0.259895 +0.986614 -0.090913 0.135379 +0.128198 0.546376 -0.827670 +-0.128090 0.546399 -0.827672 +-0.189482 0.540942 -0.819438 +-0.189482 0.540942 -0.819438 +0.190254 0.540877 -0.819302 +0.128198 0.546376 -0.827670 +-0.985535 0.092693 0.141874 +-0.952463 -0.166645 -0.255038 +-0.985657 -0.092303 -0.141281 +-0.985657 -0.092303 -0.141281 +-0.951044 0.169051 0.258720 +-0.985535 0.092693 0.141874 +-0.119451 -0.543036 -0.831170 +0.119781 -0.543034 -0.831124 +0.191581 -0.536821 -0.821657 +0.191581 -0.536821 -0.821657 +-0.191225 -0.536880 -0.821701 +-0.119451 -0.543036 -0.831170 +0.985722 -0.092103 -0.140957 +0.952378 -0.166776 -0.255268 +0.985512 0.092773 0.141981 +0.985512 0.092773 0.141981 +0.951260 0.168674 0.258173 +0.985722 -0.092103 -0.140957 +0.195050 0.536446 0.821085 +-0.194551 0.536523 0.821154 +-0.121223 0.542918 0.830990 +-0.121223 0.542918 0.830990 +0.121467 0.542922 0.830952 +0.195050 0.536446 0.821085 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.167818 0.000000 -0.985818 +-0.167885 0.000000 -0.985807 +-0.167884 0.000000 -0.985807 +-0.167884 0.000000 -0.985807 +0.167809 0.000000 -0.985819 +0.167818 0.000000 -0.985818 +0.167841 0.000000 0.985814 +0.167832 0.000000 0.985816 +-0.167907 0.000000 0.985803 +-0.167907 0.000000 0.985803 +-0.167908 0.000000 0.985803 +0.167841 0.000000 0.985814 +-0.973544 0.000000 0.228500 +-0.973544 0.000000 0.228498 +-0.973536 0.000000 -0.228534 +-0.973536 0.000000 -0.228534 +-0.973535 0.000000 -0.228536 +-0.973544 0.000000 0.228500 +0.005896 -0.999955 0.007463 +-0.005899 -0.999955 0.007463 +-0.005899 -0.999955 -0.007465 +-0.005899 -0.999955 -0.007465 +0.005896 -0.999955 -0.007465 +0.005896 -0.999955 0.007463 +0.973502 0.000001 0.228679 +0.973508 0.000000 0.228655 +0.973493 0.000001 -0.228717 +0.973493 0.000001 -0.228717 +0.973487 0.000000 -0.228740 +0.973502 0.000001 0.228679 +-0.005894 0.999955 0.007457 +0.005901 0.999955 0.007469 +0.005900 0.999955 -0.007472 +0.005900 0.999955 -0.007472 +-0.005894 0.999955 -0.007458 +-0.005894 0.999955 0.007457 +0.119255 -0.230420 -0.965756 +-0.119296 -0.230417 -0.965752 +-0.119294 0.230486 -0.965736 +-0.119294 0.230486 -0.965736 +0.119260 0.230488 -0.965739 +0.119255 -0.230420 -0.965756 +0.119256 -0.230416 0.965757 +0.119256 0.230498 0.965737 +-0.119278 0.230454 0.965745 +-0.119278 0.230454 0.965745 +-0.119277 -0.230394 0.965759 +0.119256 -0.230416 0.965757 +-0.951550 -0.257151 0.168601 +-0.951532 0.257219 0.168599 +-0.951533 0.257221 -0.168588 +-0.951533 0.257221 -0.168588 +-0.951551 -0.257152 -0.168590 +-0.951550 -0.257151 0.168601 +0.086114 -0.990440 0.107763 +-0.086139 -0.990439 0.107754 +-0.086140 -0.990440 -0.107745 +-0.086140 -0.990440 -0.107745 +0.086113 -0.990440 -0.107764 +0.086114 -0.990440 0.107763 +0.951475 0.257352 0.168716 +0.951493 -0.257284 0.168719 +0.951494 -0.257282 -0.168717 +0.951494 -0.257282 -0.168717 +0.951476 0.257351 -0.168714 +0.951475 0.257352 0.168716 +-0.086168 0.990433 0.107786 +0.086136 0.990435 0.107787 +0.086133 0.990435 -0.107791 +0.086133 0.990435 -0.107791 +-0.086168 0.990433 -0.107781 +-0.086168 0.990433 0.107786 +0.119237 -0.230393 -0.965765 +-0.119278 -0.230390 -0.965760 +-0.119276 0.230459 -0.965744 +-0.119276 0.230459 -0.965744 +0.119242 0.230461 -0.965748 +0.119237 -0.230393 -0.965765 +0.119256 -0.230416 0.965757 +0.119256 0.230498 0.965737 +-0.119295 0.230481 0.965737 +-0.119295 0.230481 0.965737 +-0.119295 -0.230422 0.965751 +0.119256 -0.230416 0.965757 +-0.951551 -0.257151 0.168595 +-0.951533 0.257219 0.168593 +-0.951533 0.257221 -0.168588 +-0.951533 0.257221 -0.168588 +-0.951551 -0.257152 -0.168590 +-0.951551 -0.257151 0.168595 +0.086115 -0.990441 0.107752 +-0.086139 -0.990439 0.107750 +-0.086140 -0.990440 -0.107745 +-0.086140 -0.990440 -0.107745 +0.086113 -0.990440 -0.107764 +0.086115 -0.990441 0.107752 +0.951477 0.257354 0.168699 +0.951496 -0.257286 0.168702 +0.951494 -0.257282 -0.168717 +0.951494 -0.257282 -0.168717 +0.951476 0.257351 -0.168714 +0.951477 0.257354 0.168699 +-0.086168 0.990433 0.107782 +0.086137 0.990437 0.107776 +0.086133 0.990435 -0.107791 +0.086133 0.990435 -0.107791 +-0.086168 0.990433 -0.107781 +-0.086168 0.990433 0.107782 +0.119255 -0.230420 -0.965756 +-0.119296 -0.230417 -0.965752 +-0.119294 0.230486 -0.965736 +-0.119294 0.230486 -0.965736 +0.119260 0.230488 -0.965739 +0.119255 -0.230420 -0.965756 +0.119221 -0.230362 0.965774 +0.119222 0.230444 0.965755 +-0.119261 0.230427 0.965754 +-0.119261 0.230427 0.965754 +-0.119260 -0.230367 0.965768 +0.119221 -0.230362 0.965774 +-0.951548 -0.257149 0.168612 +-0.951530 0.257217 0.168610 +-0.951533 0.257221 -0.168588 +-0.951533 0.257221 -0.168588 +-0.951551 -0.257152 -0.168590 +-0.951548 -0.257149 0.168612 +0.086114 -0.990440 0.107763 +-0.086138 -0.990438 0.107762 +-0.086140 -0.990440 -0.107745 +-0.086140 -0.990440 -0.107745 +0.086114 -0.990441 -0.107757 +0.086114 -0.990440 0.107763 +0.951475 0.257352 0.168716 +0.951493 -0.257284 0.168719 +0.951495 -0.257285 -0.168707 +0.951495 -0.257285 -0.168707 +0.951477 0.257353 -0.168704 +0.951475 0.257352 0.168716 +-0.086168 0.990432 0.107794 +0.086136 0.990436 0.107787 +0.086134 0.990436 -0.107784 +0.086134 0.990436 -0.107784 +-0.086168 0.990433 -0.107781 +-0.086168 0.990432 0.107794 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.002423 -0.999997 -0.000001 +0.002423 -0.999997 -0.000001 +0.002423 -0.999997 -0.000001 +0.002423 -0.999997 0.000000 +0.002423 -0.999997 0.000000 +0.002423 -0.999997 0.000000 +-0.999985 -0.005401 0.000013 +-0.999985 -0.005401 0.000013 +-0.999985 -0.005401 0.000013 +-0.999985 -0.005405 0.000008 +-0.999985 -0.005405 0.000008 +-0.999985 -0.005405 0.000008 +-0.002425 0.999997 0.000000 +-0.002425 0.999997 0.000000 +-0.002425 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.002423 -0.999997 -0.000001 +0.002423 -0.999997 -0.000001 +0.002423 -0.999997 -0.000001 +0.002423 -0.999997 0.000000 +0.002423 -0.999997 0.000000 +0.002423 -0.999997 0.000000 +-0.999985 -0.005401 0.000013 +-0.999985 -0.005401 0.000013 +-0.999985 -0.005401 0.000013 +-0.999985 -0.005405 0.000008 +-0.999985 -0.005405 0.000008 +-0.999985 -0.005405 0.000008 +-0.002425 0.999997 0.000000 +-0.002425 0.999997 0.000000 +-0.002425 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.002423 -0.999997 -0.000001 +0.002423 -0.999997 -0.000001 +0.002423 -0.999997 -0.000001 +0.002423 -0.999997 0.000000 +0.002423 -0.999997 0.000000 +0.002423 -0.999997 0.000000 +-0.999985 -0.005401 0.000013 +-0.999985 -0.005401 0.000013 +-0.999985 -0.005401 0.000013 +-0.999985 -0.005405 0.000008 +-0.999985 -0.005405 0.000008 +-0.999985 -0.005405 0.000008 +-0.002425 0.999997 0.000000 +-0.002425 0.999997 0.000000 +-0.002425 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.002423 -0.999997 -0.000001 +0.002423 -0.999997 -0.000001 +0.002423 -0.999997 -0.000001 +0.002423 -0.999997 0.000000 +0.002423 -0.999997 0.000000 +0.002423 -0.999997 0.000000 +-0.999985 -0.005401 0.000013 +-0.999985 -0.005401 0.000013 +-0.999985 -0.005401 0.000013 +-0.999985 -0.005405 0.000008 +-0.999985 -0.005405 0.000008 +-0.999985 -0.005405 0.000008 +-0.002425 0.999997 0.000000 +-0.002425 0.999997 0.000000 +-0.002425 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.001817 0.999998 0.000000 +0.001817 0.999998 0.000000 +0.001817 0.999998 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +-0.001818 -0.999998 -0.000004 +-0.001818 -0.999998 -0.000004 +-0.001818 -0.999998 -0.000004 +-0.001816 -0.999998 0.000004 +-0.001816 -0.999998 0.000004 +-0.001816 -0.999998 0.000004 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.001817 0.999998 0.000000 +0.001817 0.999998 0.000000 +0.001817 0.999998 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +-0.001818 -0.999998 -0.000004 +-0.001818 -0.999998 -0.000004 +-0.001818 -0.999998 -0.000004 +-0.001816 -0.999998 0.000004 +-0.001816 -0.999998 0.000004 +-0.001816 -0.999998 0.000004 +0.999998 -0.001819 -0.000006 +0.999998 -0.001819 -0.000006 +0.999998 -0.001819 -0.000006 +0.999998 -0.001817 0.000000 +0.999998 -0.001817 0.000000 +0.999998 -0.001817 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.001816 0.999998 0.000000 +0.001816 0.999998 0.000000 +0.001816 0.999998 0.000000 +0.001816 0.999998 0.000000 +0.001816 0.999998 0.000000 +0.001816 0.999998 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000001 0.000000 1.000000 +0.000001 0.000000 1.000000 +0.000001 0.000000 1.000000 +-0.001829 -0.999998 0.000000 +-0.001829 -0.999998 0.000000 +-0.001829 -0.999998 0.000000 +-0.001829 -0.999998 0.000000 +-0.001829 -0.999998 0.000000 +-0.001829 -0.999998 0.000000 +-0.999998 0.001817 -0.000006 +-0.999998 0.001817 -0.000006 +-0.999998 0.001817 -0.000006 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.001817 0.999998 0.000000 +0.001817 0.999998 0.000000 +0.001817 0.999998 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +-0.001818 -0.999998 -0.000004 +-0.001818 -0.999998 -0.000004 +-0.001818 -0.999998 -0.000004 +-0.001816 -0.999998 0.000004 +-0.001816 -0.999998 0.000004 +-0.001816 -0.999998 0.000004 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.001817 0.999998 0.000000 +0.001817 0.999998 0.000000 +0.001817 0.999998 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +-0.001816 -0.999998 -0.000004 +-0.001816 -0.999998 -0.000004 +-0.001816 -0.999998 -0.000004 +-0.001818 -0.999998 0.000004 +-0.001818 -0.999998 0.000004 +-0.001818 -0.999998 0.000004 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.001817 0.999998 0.000000 +0.001817 0.999998 0.000000 +0.001817 0.999998 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +-0.001818 -0.999998 -0.000004 +-0.001818 -0.999998 -0.000004 +-0.001818 -0.999998 -0.000004 +-0.001816 -0.999998 0.000004 +-0.001816 -0.999998 0.000004 +-0.001816 -0.999998 0.000004 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.001817 0.999998 0.000000 +0.001817 0.999998 0.000000 +0.001817 0.999998 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +-0.001818 -0.999998 -0.000004 +-0.001818 -0.999998 -0.000004 +-0.001818 -0.999998 -0.000004 +-0.001816 -0.999998 0.000004 +-0.001816 -0.999998 0.000004 +-0.001816 -0.999998 0.000004 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.001817 0.999998 0.000000 +0.001817 0.999998 0.000000 +0.001817 0.999998 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +-0.001816 -0.999998 -0.000004 +-0.001816 -0.999998 -0.000004 +-0.001816 -0.999998 -0.000004 +-0.001818 -0.999998 0.000004 +-0.001818 -0.999998 0.000004 +-0.001818 -0.999998 0.000004 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000001 1.000000 +0.000000 0.000001 1.000000 +0.000000 0.000001 1.000000 +0.000000 -0.000001 1.000000 +0.000000 -0.000001 1.000000 +0.000000 -0.000001 1.000000 +-0.999999 0.001038 0.000000 +-0.999999 0.001038 0.000000 +-0.999999 0.001038 0.000000 +-0.999999 0.001038 0.000000 +-0.999999 0.001038 0.000000 +-0.999999 0.001038 0.000000 +-0.001043 -0.999999 0.000000 +-0.001043 -1.000000 0.000000 +-0.001043 -0.999999 0.000000 +-0.001043 -0.999999 0.000000 +-0.001043 -0.999999 0.000000 +-0.001043 -0.999999 0.000000 +0.999999 -0.001038 0.000000 +1.000000 -0.001038 0.000000 +0.999999 -0.001038 0.000000 +1.000000 -0.001038 0.000000 +1.000000 -0.001038 0.000000 +1.000000 -0.001038 0.000000 +0.001043 0.999999 0.000000 +0.001043 0.999999 0.000000 +0.001043 0.999999 0.000000 +0.001043 0.999999 0.000000 +0.001043 0.999999 0.000000 +0.001043 0.999999 0.000000 +0.000000 0.000001 -1.000000 +0.000000 0.000001 -1.000000 +0.000000 0.000001 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -0.000001 1.000000 +0.000000 -0.000001 1.000000 +0.000000 -0.000001 1.000000 +0.000000 -0.000001 1.000000 +0.000000 -0.000001 1.000000 +0.000000 -0.000001 1.000000 +-0.999999 0.001038 0.000000 +-0.999999 0.001038 0.000000 +-1.000000 0.001038 0.000000 +-1.000000 0.001038 0.000000 +-0.999999 0.001038 0.000000 +-1.000000 0.001038 0.000000 +-0.001043 -0.999999 0.000000 +-0.001043 -0.999999 0.000000 +-0.001043 -0.999999 0.000000 +-0.001043 -0.999999 0.000000 +-0.001043 -0.999999 0.000000 +-0.001043 -0.999999 0.000000 +1.000000 -0.001038 0.000000 +0.999999 -0.001038 0.000000 +0.999999 -0.001038 0.000000 +1.000000 -0.001038 0.000000 +0.999999 -0.001038 0.000000 +0.999999 -0.001038 0.000000 +0.001043 0.999999 0.000000 +0.001043 0.999999 0.000000 +0.001043 0.999999 0.000000 +0.001043 0.999999 0.000000 +0.001043 0.999999 0.000000 +0.001043 0.999999 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999999 0.001039 0.000000 +-0.999999 0.001039 0.000000 +-1.000000 0.001039 0.000000 +-1.000000 0.001039 0.000000 +-0.999999 0.001039 0.000000 +-0.999999 0.001039 0.000000 +-0.001043 -0.999999 0.000000 +-0.001043 -0.999999 0.000000 +-0.001043 -0.999999 0.000000 +-0.001043 -0.999999 0.000000 +-0.001043 -0.999999 0.000000 +-0.001043 -0.999999 0.000000 +0.999999 -0.001039 0.000000 +0.999999 -0.001039 0.000000 +1.000000 -0.001039 0.000000 +1.000000 -0.001039 0.000000 +0.999999 -0.001039 0.000000 +0.999999 -0.001039 0.000000 +0.001043 0.999999 0.000000 +0.001043 0.999999 0.000000 +0.001043 0.999999 0.000000 +0.001043 0.999999 0.000000 +0.001043 0.999999 0.000000 +0.001043 0.999999 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.935637 0.352964 0.000000 +-0.935637 0.352964 0.000000 +-0.935637 0.352964 0.000000 +-0.935637 0.352964 0.000000 +-0.935637 0.352964 0.000000 +-0.935637 0.352964 0.000000 +-0.352969 -0.935635 0.000000 +-0.352969 -0.935635 0.000000 +-0.352969 -0.935635 0.000000 +-0.352969 -0.935635 0.000000 +-0.352969 -0.935635 0.000000 +-0.352969 -0.935635 0.000000 +0.935637 -0.352965 0.000000 +0.935637 -0.352965 0.000000 +0.935637 -0.352965 0.000000 +0.935637 -0.352965 0.000000 +0.935637 -0.352965 0.000000 +0.935637 -0.352965 0.000000 +0.352969 0.935635 0.000000 +0.352969 0.935635 0.000000 +0.352969 0.935635 0.000000 +0.352969 0.935635 0.000000 +0.352969 0.935635 0.000000 +0.352969 0.935635 0.000000 +-0.000001 0.000000 -1.000000 +-0.000001 0.000000 -1.000000 +-0.000001 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000001 0.000000 -1.000000 +-0.000001 0.000000 -1.000000 +-0.000001 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000001 0.000000 1.000000 +0.000001 0.000000 1.000000 +0.000001 0.000000 1.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 + + + + + + + + + + + +0.480507 0.045007 +0.480507 0.412535 +0.108983 0.413764 +0.108319 0.417867 +0.108120 0.417948 +0.108319 0.417867 +0.108120 0.417948 +0.485016 0.418868 +0.485263 0.418876 +0.109020 0.038880 +0.109020 0.042880 +0.108667 0.039200 +0.481756 0.043443 +0.482223 0.042625 +0.485110 0.418890 +0.485263 0.419226 +0.484531 0.420580 +0.484252 0.420580 +0.484252 0.420580 +0.484531 0.420580 +0.482229 0.042758 +0.481756 0.043443 +0.110650 0.039983 +0.110831 0.039988 +0.110760 0.421926 +0.110622 0.421852 +0.110622 0.421852 +0.110760 0.421926 +0.484252 0.420631 +0.109614 0.418992 +0.484531 0.420630 +0.109371 0.419085 +0.484252 0.420631 +0.109614 0.418992 +0.484531 0.420630 +0.109371 0.419085 +0.480507 0.045007 +0.480507 0.412535 +0.108983 0.413764 +0.108319 0.417867 +0.108120 0.417948 +0.108319 0.417867 +0.108120 0.417948 +0.485016 0.418868 +0.485263 0.418876 +0.109020 0.038880 +0.109020 0.042880 +0.108667 0.039200 +0.481756 0.043443 +0.482223 0.042625 +0.485110 0.418890 +0.485263 0.419226 +0.484531 0.420580 +0.484252 0.420580 +0.484252 0.420580 +0.484531 0.420580 +0.482229 0.042758 +0.481756 0.043443 +0.110650 0.039983 +0.110831 0.039988 +0.110760 0.421926 +0.110622 0.421852 +0.110622 0.421852 +0.110760 0.421926 +0.484252 0.420631 +0.109614 0.418992 +0.484531 0.420630 +0.109371 0.419085 +0.484252 0.420631 +0.109614 0.418992 +0.484531 0.420630 +0.109371 0.419085 +0.480507 0.045007 +0.480507 0.412535 +0.108983 0.413764 +0.108319 0.417867 +0.108120 0.417948 +0.108319 0.417867 +0.108120 0.417948 +0.485016 0.418868 +0.485263 0.418876 +0.109020 0.038880 +0.109020 0.042880 +0.108667 0.039200 +0.481756 0.043443 +0.482223 0.042625 +0.485110 0.418890 +0.485263 0.419226 +0.484531 0.420580 +0.484252 0.420580 +0.484252 0.420580 +0.484531 0.420580 +0.482229 0.042758 +0.481756 0.043443 +0.110650 0.039983 +0.110831 0.039988 +0.110760 0.421926 +0.110622 0.421852 +0.110622 0.421852 +0.110760 0.421926 +0.484252 0.420631 +0.109614 0.418992 +0.484531 0.420630 +0.109371 0.419085 +0.484252 0.420631 +0.109614 0.418992 +0.484531 0.420630 +0.109371 0.419085 +0.480507 0.045007 +0.480507 0.412535 +0.108983 0.413764 +0.108319 0.417867 +0.108120 0.417948 +0.108319 0.417867 +0.108120 0.417948 +0.485016 0.418868 +0.485263 0.418876 +0.109020 0.038880 +0.109020 0.042880 +0.108667 0.039200 +0.481756 0.043443 +0.482223 0.042625 +0.485110 0.418890 +0.485263 0.419226 +0.484531 0.420580 +0.484252 0.420580 +0.484252 0.420580 +0.484531 0.420580 +0.482229 0.042758 +0.481756 0.043443 +0.110650 0.039983 +0.110831 0.039988 +0.110760 0.421926 +0.110622 0.421852 +0.110622 0.421852 +0.110760 0.421926 +0.484252 0.420631 +0.109614 0.418992 +0.484531 0.420630 +0.109371 0.419085 +0.484252 0.420631 +0.109614 0.418992 +0.484531 0.420630 +0.109371 0.419085 +0.480507 0.045007 +0.480507 0.412535 +0.108983 0.413764 +0.108319 0.417867 +0.108120 0.417948 +0.108319 0.417867 +0.108120 0.417948 +0.485016 0.418868 +0.485263 0.418876 +0.109020 0.038880 +0.109020 0.042880 +0.108667 0.039200 +0.481756 0.043443 +0.482223 0.042625 +0.485110 0.418890 +0.485263 0.419226 +0.484531 0.420580 +0.484252 0.420580 +0.484252 0.420580 +0.484531 0.420580 +0.482229 0.042758 +0.481756 0.043443 +0.110650 0.039983 +0.110831 0.039988 +0.110760 0.421926 +0.110622 0.421852 +0.110622 0.421852 +0.110760 0.421926 +0.484252 0.420631 +0.109614 0.418992 +0.484531 0.420630 +0.109371 0.419085 +0.484252 0.420631 +0.109614 0.418992 +0.484531 0.420630 +0.109371 0.419085 +0.480507 0.045007 +0.480507 0.412535 +0.108983 0.413764 +0.108319 0.417867 +0.108120 0.417948 +0.108319 0.417867 +0.108120 0.417948 +0.485016 0.418868 +0.485263 0.418876 +0.109020 0.038880 +0.109020 0.042880 +0.108667 0.039200 +0.481756 0.043443 +0.482223 0.042625 +0.485110 0.418890 +0.485263 0.419226 +0.484531 0.420580 +0.484252 0.420580 +0.484252 0.420580 +0.484531 0.420580 +0.482229 0.042758 +0.481756 0.043443 +0.110650 0.039983 +0.110831 0.039988 +0.110760 0.421926 +0.110622 0.421852 +0.110622 0.421852 +0.110760 0.421926 +0.484252 0.420631 +0.109614 0.418992 +0.484531 0.420630 +0.109371 0.419085 +0.484252 0.420631 +0.109614 0.418992 +0.484531 0.420630 +0.109371 0.419085 +0.478224 0.420580 +0.114013 0.420894 +0.478224 0.420580 +0.478853 0.420580 +0.113937 0.420889 +0.478853 0.420580 +0.478224 0.420580 +0.478224 0.420580 +0.114014 0.420907 +0.478853 0.420580 +0.113936 0.420877 +0.478853 0.420580 +0.113979 0.420267 +0.113904 0.420297 +0.113903 0.420285 +0.113980 0.420279 +0.478224 0.420580 +0.478224 0.420580 +0.113977 0.420238 +0.478853 0.420580 +0.113901 0.420246 +0.478853 0.420580 +0.478224 0.420580 +0.113977 0.420226 +0.478224 0.420580 +0.478853 0.420580 +0.113901 0.420258 +0.478854 0.420580 +0.114012 0.420873 +0.113935 0.420856 +0.113935 0.420857 +0.114012 0.420872 +0.478224 0.420580 +0.113979 0.420267 +0.478224 0.420580 +0.478853 0.420580 +0.113904 0.420297 +0.478853 0.420580 +0.478224 0.420580 +0.478224 0.420580 +0.113979 0.420279 +0.478853 0.420580 +0.113903 0.420285 +0.478853 0.420580 +0.114013 0.420894 +0.113936 0.420889 +0.113936 0.420877 +0.114014 0.420907 +0.478224 0.420580 +0.478224 0.420580 +0.114013 0.420894 +0.478853 0.420580 +0.478853 0.420580 +0.113936 0.420889 +0.478224 0.420580 +0.114014 0.420907 +0.478224 0.420580 +0.478853 0.420580 +0.478853 0.420580 +0.113936 0.420877 +0.113979 0.420267 +0.113904 0.420297 +0.113903 0.420285 +0.113980 0.420279 +0.478224 0.420580 +0.478224 0.420580 +0.113977 0.420238 +0.478853 0.420580 +0.113901 0.420246 +0.478853 0.420580 +0.478224 0.420580 +0.113977 0.420226 +0.478224 0.420580 +0.478853 0.420580 +0.113901 0.420258 +0.478854 0.420580 +0.114012 0.420873 +0.113935 0.420856 +0.113935 0.420857 +0.114012 0.420872 +0.478224 0.420580 +0.113979 0.420267 +0.478224 0.420580 +0.478853 0.420580 +0.113904 0.420297 +0.478853 0.420580 +0.478224 0.420580 +0.478224 0.420580 +0.113979 0.420279 +0.478853 0.420580 +0.113903 0.420285 +0.478853 0.420580 +0.114013 0.420894 +0.113936 0.420889 +0.113936 0.420877 +0.114014 0.420907 +0.478224 0.420580 +0.478224 0.420580 +0.114013 0.420894 +0.478853 0.420580 +0.478853 0.420580 +0.113936 0.420889 +0.478224 0.420580 +0.114014 0.420907 +0.478224 0.420580 +0.478853 0.420580 +0.478853 0.420580 +0.113936 0.420877 +0.113979 0.420267 +0.113904 0.420297 +0.113903 0.420285 +0.113980 0.420279 +0.478224 0.420580 +0.478224 0.420580 +0.113977 0.420238 +0.478853 0.420580 +0.113901 0.420246 +0.478853 0.420580 +0.478224 0.420580 +0.113977 0.420226 +0.478224 0.420580 +0.478853 0.420580 +0.113901 0.420258 +0.478854 0.420580 +0.114012 0.420873 +0.113935 0.420856 +0.113935 0.420857 +0.114012 0.420872 +0.478224 0.420580 +0.113979 0.420267 +0.478224 0.420580 +0.478853 0.420580 +0.113904 0.420297 +0.478853 0.420580 +0.478224 0.420580 +0.478224 0.420580 +0.113979 0.420279 +0.478853 0.420580 +0.113903 0.420285 +0.478853 0.420580 +0.114013 0.420894 +0.113936 0.420889 +0.113936 0.420877 +0.114014 0.420907 +0.489049 0.036961 +0.105430 0.036961 +0.489049 0.420580 +0.105430 0.420580 +0.105430 0.036961 +0.489049 0.036961 +0.105430 0.420580 +0.489049 0.420580 +0.105430 0.036961 +0.489049 0.036961 +0.105430 0.420580 +0.489049 0.420580 +0.105430 0.036961 +0.489049 0.036961 +0.105430 0.420580 +0.489049 0.420580 +0.489049 0.036961 +0.105430 0.036961 +0.489049 0.420580 +0.105430 0.420580 +0.105430 0.036961 +0.489049 0.036961 +0.105430 0.420580 +0.489049 0.420580 +0.105430 0.036961 +0.489049 0.036961 +0.105430 0.420580 +0.489049 0.420580 +0.105430 0.036961 +0.489049 0.036961 +0.105430 0.420580 +0.489049 0.420580 +0.489049 0.036961 +0.105430 0.036961 +0.489049 0.420580 +0.105430 0.420580 +0.105430 0.036961 +0.489049 0.036961 +0.105430 0.420580 +0.489049 0.420580 +0.105430 0.036961 +0.489049 0.036961 +0.105430 0.420580 +0.489049 0.420580 +0.105430 0.036961 +0.489049 0.036961 +0.105430 0.420580 +0.489049 0.420580 +0.467426 0.244300 +0.467426 0.037231 +0.472758 0.037231 +0.326355 0.038969 +0.331690 0.038969 +0.331689 0.042629 +0.110811 0.041124 +0.110811 0.037364 +0.331690 0.047687 +0.326355 0.047687 +0.105832 0.246269 +0.472758 0.244300 +0.460786 0.037309 +0.466120 0.037309 +0.326357 0.042629 +0.466120 0.244456 +0.109592 0.246269 +0.318057 0.041124 +0.331690 0.043948 +0.109592 0.039023 +0.318057 0.037364 +0.105832 0.039023 +0.326355 0.043948 +0.460787 0.244456 +0.281892 0.257795 +0.278296 0.257795 +0.278296 0.050602 +0.281892 0.050602 +0.368191 0.050504 +0.364597 0.257639 +0.364599 0.050504 +0.368191 0.257582 +0.283385 0.257786 +0.283384 0.050612 +0.362543 0.050612 +0.362544 0.257786 +0.487685 0.120209 +0.487685 0.199272 +0.474133 0.116347 +0.474135 0.037227 +0.312987 0.338839 +0.105849 0.338894 +0.484093 0.199272 +0.484093 0.120209 +0.477727 0.116290 +0.477727 0.037227 +0.105794 0.259772 +0.312932 0.259717 +0.276913 0.257795 +0.273317 0.257795 +0.273317 0.050602 +0.276913 0.050602 +0.378149 0.050504 +0.374555 0.257639 +0.374557 0.050504 +0.189941 0.050612 +0.189941 0.257786 +0.110783 0.257786 +0.110782 0.050612 +0.477727 0.120209 +0.477727 0.199272 +0.378149 0.257582 +0.484091 0.116347 +0.484093 0.037227 +0.271218 0.050602 +0.271273 0.257740 +0.474135 0.199272 +0.474135 0.120209 +0.487685 0.116290 +0.487685 0.037227 +0.192150 0.257795 +0.192095 0.050658 +0.321285 0.042204 +0.321285 0.045800 +0.114092 0.045800 +0.114092 0.042204 +0.373170 0.050504 +0.369576 0.257639 +0.369578 0.050504 +0.312978 0.420207 +0.105804 0.420207 +0.105804 0.341048 +0.312978 0.341048 +0.482861 0.120209 +0.482861 0.199272 +0.479212 0.199274 +0.479212 0.120207 +0.373170 0.257582 +0.479112 0.116347 +0.479114 0.037227 +0.458811 0.244307 +0.379689 0.244363 +0.482706 0.116290 +0.482706 0.037227 +0.379634 0.037225 +0.458754 0.037227 +0.016244 0.715841 +0.756345 0.522332 +0.756346 0.715841 +0.016243 0.522332 +0.009526 0.061000 +0.749637 0.514493 +0.009526 0.514494 +0.749636 0.060999 +0.969477 0.480355 +0.969577 0.938728 +0.771464 0.938319 +0.771396 0.480706 +0.007192 0.039423 +0.751630 0.039423 +0.007192 0.498972 +0.751630 0.498972 +0.779207 0.499082 +0.779286 0.040707 +0.977371 0.041060 +0.977311 0.498670 +0.016243 0.911620 +0.756344 0.718111 +0.756344 0.911620 +0.016243 0.718111 +0.016244 0.715841 +0.756345 0.522332 +0.756346 0.715841 +0.016243 0.522332 +0.009526 0.061000 +0.749637 0.514493 +0.009526 0.514494 +0.749636 0.060999 +0.969477 0.480355 +0.969577 0.938728 +0.771464 0.938319 +0.771396 0.480706 +0.007192 0.039423 +0.751630 0.039423 +0.007192 0.498972 +0.751630 0.498972 +0.779207 0.499082 +0.779286 0.040707 +0.977371 0.041060 +0.977311 0.498670 +0.016243 0.911620 +0.756344 0.718111 +0.756344 0.911620 +0.016243 0.718111 +0.016244 0.715841 +0.756345 0.522332 +0.756346 0.715841 +0.016243 0.522332 +0.009526 0.061000 +0.749637 0.514493 +0.009526 0.514494 +0.749636 0.060999 +0.969477 0.480355 +0.969577 0.938728 +0.771464 0.938319 +0.771396 0.480706 +0.007192 0.039423 +0.751630 0.039423 +0.007192 0.498972 +0.751630 0.498972 +0.779207 0.499082 +0.779286 0.040707 +0.977371 0.041060 +0.977311 0.498670 +0.016243 0.911620 +0.756344 0.718111 +0.756344 0.911620 +0.016243 0.718111 +0.486957 0.692024 +0.027038 0.424800 +0.486954 0.424800 +0.027038 0.692024 +0.506996 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.966910 0.036168 +0.029544 0.043430 +0.489461 0.415225 +0.029544 0.415224 +0.489461 0.035380 +0.029544 0.035380 +0.037422 0.971548 +0.407335 0.698761 +0.409054 0.971742 +0.039211 0.698717 +0.965462 0.676852 +0.505546 0.676852 +0.505546 0.409621 +0.965459 0.409621 +0.914572 0.962378 +0.922325 0.705031 +0.922325 0.962378 +0.570344 0.705031 +0.570343 0.962377 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.206126 +1.014936 0.691973 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.206126 +0.170286 0.691973 +0.229772 0.173002 +0.933648 0.102615 +0.933648 0.173002 +0.229772 0.102615 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.206126 +1.014936 0.691973 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.206126 +0.170286 0.691973 +0.229772 0.173002 +0.933648 0.102615 +0.933648 0.173002 +0.229772 0.102615 +0.486957 0.692024 +0.027038 0.424800 +0.486954 0.424800 +0.027038 0.692024 +0.506996 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.966910 0.036168 +0.029544 0.043430 +0.489461 0.415225 +0.029544 0.415224 +0.489461 0.035380 +0.029544 0.035380 +0.037422 0.971548 +0.407335 0.698761 +0.409054 0.971742 +0.039211 0.698717 +0.965462 0.676852 +0.505546 0.676852 +0.505546 0.409621 +0.965459 0.409621 +0.914572 0.962378 +0.922325 0.705031 +0.922325 0.962378 +0.570344 0.705031 +0.570343 0.962377 +0.016244 0.715841 +0.756345 0.522332 +0.756346 0.715841 +0.016243 0.522332 +0.009526 0.061000 +0.749637 0.514493 +0.009526 0.514494 +0.749636 0.060999 +0.969477 0.480355 +0.969577 0.938728 +0.771464 0.938319 +0.771396 0.480706 +0.007192 0.039423 +0.751630 0.039423 +0.007192 0.498972 +0.751630 0.498972 +0.779207 0.499082 +0.779286 0.040707 +0.977371 0.041060 +0.977311 0.498670 +0.016243 0.911620 +0.756344 0.718111 +0.756344 0.911620 +0.016243 0.718111 +0.016244 0.715841 +0.756345 0.522332 +0.756346 0.715841 +0.016243 0.522332 +0.009526 0.061000 +0.749637 0.514493 +0.009526 0.514494 +0.749636 0.060999 +0.969477 0.480355 +0.969577 0.938728 +0.771464 0.938319 +0.771396 0.480706 +0.007192 0.039423 +0.751630 0.039423 +0.007192 0.498972 +0.751630 0.498972 +0.779207 0.499082 +0.779286 0.040707 +0.977371 0.041060 +0.977311 0.498670 +0.756344 0.911620 +0.016243 0.718111 +0.756344 0.718111 +0.016243 0.911620 +0.016244 0.715841 +0.756345 0.522332 +0.756346 0.715841 +0.016243 0.522332 +0.009526 0.061000 +0.749637 0.514493 +0.009526 0.514494 +0.749636 0.060999 +0.969477 0.480355 +0.969577 0.938728 +0.771464 0.938319 +0.771396 0.480706 +0.007192 0.039423 +0.751630 0.039423 +0.007192 0.498972 +0.751630 0.498972 +0.779207 0.499082 +0.779286 0.040707 +0.977371 0.041060 +0.977311 0.498670 +0.016243 0.911620 +0.756344 0.718111 +0.756344 0.911620 +0.016243 0.718111 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.206126 +1.014936 0.691973 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.206126 +0.170286 0.691973 +0.229772 0.173002 +0.933648 0.102615 +0.933648 0.173002 +0.229772 0.102615 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.206126 +1.014936 0.691973 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.206126 +0.170286 0.691973 +0.229772 0.173002 +0.933648 0.102615 +0.933648 0.173002 +0.229772 0.102615 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.206126 +1.014936 0.691973 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.691973 +0.170286 0.206126 +0.933648 0.173002 +0.229772 0.173002 +0.229772 0.102615 +0.933648 0.102615 +0.016244 0.715841 +0.756345 0.522332 +0.756346 0.715841 +0.016243 0.522332 +0.009526 0.061000 +0.749637 0.514493 +0.009526 0.514494 +0.749636 0.060999 +0.969477 0.480355 +0.969577 0.938728 +0.771464 0.938319 +0.771396 0.480706 +0.007192 0.039423 +0.751630 0.039423 +0.007192 0.498972 +0.751630 0.498972 +0.779207 0.499082 +0.779286 0.040707 +0.977371 0.041060 +0.977311 0.498670 +0.016243 0.911620 +0.756344 0.718111 +0.756344 0.911620 +0.016243 0.718111 +0.016244 0.715841 +0.756345 0.522332 +0.756346 0.715841 +0.016243 0.522332 +0.009526 0.061000 +0.749637 0.514493 +0.009526 0.514494 +0.749636 0.060999 +0.969477 0.480355 +0.969577 0.938728 +0.771464 0.938319 +0.771396 0.480706 +0.007192 0.039423 +0.751630 0.039423 +0.007192 0.498972 +0.751630 0.498972 +0.779207 0.499082 +0.779286 0.040707 +0.977371 0.041060 +0.977311 0.498670 +0.756344 0.911620 +0.016243 0.718111 +0.756344 0.718111 +0.016243 0.911620 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.206126 +1.014936 0.691973 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.691973 +0.170286 0.206126 +0.933648 0.173002 +0.229772 0.173002 +0.229772 0.102615 +0.933648 0.102615 +0.486957 0.692024 +0.027038 0.424800 +0.486954 0.424800 +0.027038 0.692024 +0.506996 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.966910 0.036168 +0.029544 0.043430 +0.489461 0.415225 +0.029544 0.415224 +0.489461 0.035380 +0.029544 0.035380 +0.037422 0.971548 +0.407335 0.698761 +0.409054 0.971742 +0.039211 0.698717 +0.965462 0.676852 +0.505546 0.676852 +0.505546 0.409621 +0.965459 0.409621 +0.914572 0.962378 +0.922325 0.705031 +0.922325 0.962378 +0.570344 0.705031 +0.570343 0.962377 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.206126 +1.014936 0.691973 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.206126 +0.170286 0.691973 +0.229772 0.173002 +0.933648 0.102615 +0.933648 0.173002 +0.229772 0.102615 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.206126 +1.014936 0.691973 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.206126 +0.170286 0.691973 +0.229772 0.173002 +0.933648 0.102615 +0.933648 0.173002 +0.229772 0.102615 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.206126 +1.014936 0.691973 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.691973 +0.170286 0.206126 +0.933648 0.173002 +0.229772 0.173002 +0.229772 0.102615 +0.933648 0.102615 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.206126 +1.014936 0.691973 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.691973 +0.170286 0.206126 +0.229772 0.173002 +0.933648 0.102615 +0.933648 0.173002 +0.229772 0.102615 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.206126 +1.014936 0.691973 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.206126 +0.170286 0.691973 +0.229772 0.173002 +0.933648 0.102615 +0.933648 0.173002 +0.229772 0.102615 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.206126 +1.014936 0.691973 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.206126 +0.170286 0.691973 +0.229772 0.173002 +0.933648 0.102615 +0.933648 0.173002 +0.229772 0.102615 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.206126 +1.014936 0.691973 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.691973 +0.170286 0.206126 +0.933648 0.173002 +0.229772 0.173002 +0.229772 0.102615 +0.933648 0.102615 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.206126 +1.014936 0.691973 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.691973 +0.170286 0.206126 +0.229772 0.173002 +0.933648 0.102615 +0.933648 0.173002 +0.229772 0.102615 +0.486957 0.692024 +0.027038 0.424800 +0.486954 0.424800 +0.027038 0.692024 +0.506996 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.966910 0.036168 +0.029544 0.043430 +0.489461 0.415225 +0.029544 0.415224 +0.489461 0.035380 +0.029544 0.035380 +0.037422 0.971548 +0.407335 0.698761 +0.409054 0.971742 +0.039211 0.698717 +0.965462 0.676852 +0.505546 0.676852 +0.505546 0.409621 +0.965459 0.409621 +0.914572 0.962378 +0.922325 0.705031 +0.922325 0.962378 +0.570344 0.705031 +0.570343 0.962377 + + + + + + + + + + + +

5 0 2 3 1 10 2 2 0 2 3 0 4 4 1 5 5 2 0 6 7 6 7 3 2 8 9 2 9 9 3 10 12 0 11 7 1 12 8 0 13 4 3 14 22 3 15 22 5 16 13 1 17 8 7 18 15 1 19 5 5 20 23 5 21 23 4 22 21 7 23 15 6 24 14 7 25 6 4 26 11 4 27 11 2 28 20 6 29 14 9 30 17 8 31 24 6 32 3 6 33 3 0 34 7 9 35 17 11 36 19 9 37 25 0 38 4 0 39 4 1 40 8 11 41 19 10 42 18 11 43 27 1 44 5 1 45 5 7 46 15 10 47 18 8 48 16 10 49 26 7 50 6 7 51 6 6 52 14 8 53 16 13 54 28 12 55 29 8 56 24 8 57 24 9 58 17 13 59 28 15 60 30 13 61 31 9 62 25 9 63 25 11 64 19 15 65 30 14 66 32 15 67 33 11 68 27 11 69 27 10 70 18 14 71 32 12 72 34 14 73 35 10 74 26 10 75 26 8 76 16 12 77 34 12 78 34 13 79 28 15 80 30 15 81 30 14 82 32 12 83 34 21 84 38 19 85 46 18 86 36 18 87 36 20 88 37 21 89 38 16 90 43 22 91 39 18 92 45 18 93 45 19 94 48 16 95 43 17 96 44 16 97 40 19 98 58 19 99 58 21 100 49 17 101 44 23 102 51 17 103 41 21 104 59 21 105 59 20 106 57 23 107 51 22 108 50 23 109 42 20 110 47 20 111 47 18 112 56 22 113 50 25 114 53 24 115 60 22 116 39 22 117 39 16 118 43 25 119 53 27 120 55 25 121 61 16 122 40 16 123 40 17 124 44 27 125 55 26 126 54 27 127 63 17 128 41 17 129 41 23 130 51 26 131 54 24 132 52 26 133 62 23 134 42 23 135 42 22 136 50 24 137 52 29 138 64 28 139 65 24 140 60 24 141 60 25 142 53 29 143 64 31 144 66 29 145 67 25 146 61 25 147 61 27 148 55 31 149 66 30 150 68 31 151 69 27 152 63 27 153 63 26 154 54 30 155 68 28 156 70 30 157 71 26 158 62 26 159 62 24 160 52 28 161 70 28 162 70 29 163 64 31 164 66 31 165 66 30 166 68 28 167 70 37 168 74 35 169 82 34 170 72 34 171 72 36 172 73 37 173 74 32 174 79 38 175 75 34 176 81 34 177 81 35 178 84 32 179 79 33 180 80 32 181 76 35 182 94 35 183 94 37 184 85 33 185 80 39 186 87 33 187 77 37 188 95 37 189 95 36 190 93 39 191 87 38 192 86 39 193 78 36 194 83 36 195 83 34 196 92 38 197 86 41 198 89 40 199 96 38 200 75 38 201 75 32 202 79 41 203 89 43 204 91 41 205 97 32 206 76 32 207 76 33 208 80 43 209 91 42 210 90 43 211 99 33 212 77 33 213 77 39 214 87 42 215 90 40 216 88 42 217 98 39 218 78 39 219 78 38 220 86 40 221 88 45 222 100 44 223 101 40 224 96 40 225 96 41 226 89 45 227 100 47 228 102 45 229 103 41 230 97 41 231 97 43 232 91 47 233 102 46 234 104 47 235 105 43 236 99 43 237 99 42 238 90 46 239 104 44 240 106 46 241 107 42 242 98 42 243 98 40 244 88 44 245 106 44 246 106 45 247 100 47 248 102 47 249 102 46 250 104 44 251 106 53 252 110 51 253 118 50 254 108 50 255 108 52 256 109 53 257 110 48 258 115 54 259 111 50 260 117 50 261 117 51 262 120 48 263 115 49 264 116 48 265 112 51 266 130 51 267 130 53 268 121 49 269 116 55 270 123 49 271 113 53 272 131 53 273 131 52 274 129 55 275 123 54 276 122 55 277 114 52 278 119 52 279 119 50 280 128 54 281 122 57 282 125 56 283 132 54 284 111 54 285 111 48 286 115 57 287 125 59 288 127 57 289 133 48 290 112 48 291 112 49 292 116 59 293 127 58 294 126 59 295 135 49 296 113 49 297 113 55 298 123 58 299 126 56 300 124 58 301 134 55 302 114 55 303 114 54 304 122 56 305 124 61 306 136 60 307 137 56 308 132 56 309 132 57 310 125 61 311 136 63 312 138 61 313 139 57 314 133 57 315 133 59 316 127 63 317 138 62 318 140 63 319 141 59 320 135 59 321 135 58 322 126 62 323 140 60 324 142 62 325 143 58 326 134 58 327 134 56 328 124 60 329 142 60 330 142 61 331 136 63 332 138 63 333 138 62 334 140 60 335 142 69 336 146 67 337 154 66 338 144 66 339 144 68 340 145 69 341 146 64 342 151 70 343 147 66 344 153 66 345 153 67 346 156 64 347 151 65 348 152 64 349 148 67 350 166 67 351 166 69 352 157 65 353 152 71 354 159 65 355 149 69 356 167 69 357 167 68 358 165 71 359 159 70 360 158 71 361 150 68 362 155 68 363 155 66 364 164 70 365 158 73 366 161 72 367 168 70 368 147 70 369 147 64 370 151 73 371 161 75 372 163 73 373 169 64 374 148 64 375 148 65 376 152 75 377 163 74 378 162 75 379 171 65 380 149 65 381 149 71 382 159 74 383 162 72 384 160 74 385 170 71 386 150 71 387 150 70 388 158 72 389 160 77 390 172 76 391 173 72 392 168 72 393 168 73 394 161 77 395 172 79 396 174 77 397 175 73 398 169 73 399 169 75 400 163 79 401 174 78 402 176 79 403 177 75 404 171 75 405 171 74 406 162 78 407 176 76 408 178 78 409 179 74 410 170 74 411 170 72 412 160 76 413 178 76 414 178 77 415 172 79 416 174 79 417 174 78 418 176 76 419 178 85 420 182 83 421 190 82 422 180 82 423 180 84 424 181 85 425 182 80 426 187 86 427 183 82 428 189 82 429 189 83 430 192 80 431 187 81 432 188 80 433 184 83 434 202 83 435 202 85 436 193 81 437 188 87 438 195 81 439 185 85 440 203 85 441 203 84 442 201 87 443 195 86 444 194 87 445 186 84 446 191 84 447 191 82 448 200 86 449 194 89 450 197 88 451 204 86 452 183 86 453 183 80 454 187 89 455 197 91 456 199 89 457 205 80 458 184 80 459 184 81 460 188 91 461 199 90 462 198 91 463 207 81 464 185 81 465 185 87 466 195 90 467 198 88 468 196 90 469 206 87 470 186 87 471 186 86 472 194 88 473 196 93 474 208 92 475 209 88 476 204 88 477 204 89 478 197 93 479 208 95 480 210 93 481 211 89 482 205 89 483 205 91 484 199 95 485 210 94 486 212 95 487 213 91 488 207 91 489 207 90 490 198 94 491 212 92 492 214 94 493 215 90 494 206 90 495 206 88 496 196 92 497 214 92 498 214 93 499 208 95 500 210 95 501 210 94 502 212 92 503 214 96 504 216 99 505 218 97 506 217 97 507 217 102 508 228 96 509 216 98 510 219 101 511 221 99 512 220 99 513 220 96 514 229 98 515 219 103 516 222 101 517 224 98 518 231 98 519 231 100 520 223 103 521 222 102 522 225 97 523 227 103 524 226 103 525 226 100 526 230 102 527 225 105 528 234 111 529 244 104 530 232 104 531 232 106 532 233 105 533 234 104 534 245 107 535 237 108 536 235 108 537 235 106 538 236 104 539 245 107 540 247 109 541 240 110 542 238 110 543 238 108 544 239 107 545 247 109 546 246 111 547 243 105 548 241 105 549 241 110 550 242 109 551 246 119 552 260 113 553 250 114 554 248 114 555 248 112 556 249 119 557 260 113 558 261 115 559 253 117 560 251 117 561 251 114 562 252 113 563 261 117 564 256 115 565 263 116 566 254 116 567 254 118 568 255 117 569 256 116 570 262 119 571 259 112 572 257 112 573 257 118 574 258 116 575 262 120 576 264 123 577 265 121 578 266 121 579 266 126 580 276 120 581 264 122 582 267 124 583 268 123 584 269 123 585 269 120 586 277 122 587 267 127 588 270 124 589 271 122 590 279 122 591 279 125 592 272 127 593 270 126 594 273 121 595 274 127 596 275 127 597 275 125 598 278 126 599 273 129 600 282 135 601 292 128 602 280 128 603 280 130 604 281 129 605 282 128 606 293 131 607 285 132 608 283 132 609 283 130 610 284 128 611 293 131 612 295 133 613 288 134 614 286 134 615 286 132 616 287 131 617 295 133 618 294 135 619 291 129 620 289 129 621 289 134 622 290 133 623 294 143 624 308 137 625 298 138 626 296 138 627 296 136 628 297 143 629 308 137 630 309 139 631 301 141 632 299 141 633 299 138 634 300 137 635 309 141 636 304 139 637 311 140 638 302 140 639 302 142 640 303 141 641 304 140 642 310 143 643 307 136 644 305 136 645 305 142 646 306 140 647 310 144 648 312 147 649 313 145 650 314 145 651 314 150 652 324 144 653 312 146 654 315 148 655 316 147 656 317 147 657 317 144 658 325 146 659 315 151 660 318 148 661 319 146 662 327 146 663 327 149 664 320 151 665 318 150 666 321 145 667 322 151 668 323 151 669 323 149 670 326 150 671 321 153 672 330 159 673 340 152 674 328 152 675 328 154 676 329 153 677 330 152 678 341 155 679 333 156 680 331 156 681 331 154 682 332 152 683 341 155 684 343 157 685 336 158 686 334 158 687 334 156 688 335 155 689 343 157 690 342 159 691 339 153 692 337 153 693 337 158 694 338 157 695 342 167 696 356 161 697 346 162 698 344 162 699 344 160 700 345 167 701 356 161 702 357 163 703 349 165 704 347 165 705 347 162 706 348 161 707 357 165 708 352 163 709 359 164 710 350 164 711 350 166 712 351 165 713 352 164 714 358 167 715 355 160 716 353 160 717 353 166 718 354 164 719 358 168 720 360 170 721 362 171 722 363 171 723 363 169 724 361 168 725 360 172 726 364 173 727 365 175 728 367 175 729 367 174 730 366 172 731 364 168 732 368 169 733 369 173 734 371 173 735 371 172 736 370 168 737 368 171 738 372 170 739 373 174 740 375 174 741 375 175 742 374 171 743 372 176 744 376 178 745 378 179 746 379 179 747 379 177 748 377 176 749 376 180 750 380 181 751 381 183 752 383 183 753 383 182 754 382 180 755 380 176 756 384 177 757 385 181 758 387 181 759 387 180 760 386 176 761 384 179 762 388 178 763 389 182 764 391 182 765 391 183 766 390 179 767 388 184 768 392 186 769 394 187 770 395 187 771 395 185 772 393 184 773 392 188 774 396 189 775 397 191 776 399 191 777 399 190 778 398 188 779 396 184 780 400 185 781 401 189 782 403 189 783 403 188 784 402 184 785 400 187 786 404 186 787 405 190 788 407 190 789 407 191 790 406 187 791 404 197 792 410 195 793 419 194 794 408 194 795 408 196 796 409 197 797 410 193 798 423 199 799 431 198 800 420 198 801 420 192 802 421 193 803 423 192 804 413 198 805 422 194 806 411 194 807 411 195 808 412 192 809 413 193 810 415 192 811 428 195 812 425 195 813 425 197 814 414 193 815 415 199 816 416 193 817 417 197 818 430 197 819 430 196 820 426 199 821 416 198 822 418 199 823 429 196 824 427 196 825 427 194 826 424 198 827 418 205 828 442 203 829 443 202 830 440 202 831 440 204 832 441 205 833 442 201 834 449 207 835 454 206 836 455 206 837 455 200 838 448 201 839 449 200 840 450 206 841 451 202 842 444 202 843 444 203 844 445 200 845 450 201 846 433 200 847 434 203 848 435 203 849 435 205 850 432 201 851 433 207 852 446 201 853 447 205 854 453 205 855 453 204 856 452 207 857 446 206 858 437 207 859 438 204 860 436 204 861 436 202 862 439 206 863 437 213 864 465 211 865 466 210 866 463 210 867 463 212 868 464 213 869 465 209 870 473 215 871 478 214 872 479 214 873 479 208 874 472 209 875 473 208 876 474 214 877 475 210 878 467 210 879 467 211 880 468 208 881 474 209 882 457 208 883 458 211 884 459 211 885 459 213 886 456 209 887 457 215 888 470 209 889 471 213 890 477 213 891 477 212 892 476 215 893 470 214 894 461 215 895 462 212 896 460 212 897 460 210 898 469 214 899 461 220 900 489 218 901 490 216 902 487 216 903 487 217 904 488 220 905 489 221 906 498 222 907 499 223 908 502 223 909 502 219 910 503 221 911 498 219 912 493 223 913 494 216 914 491 216 915 491 218 916 492 219 917 493 221 918 481 219 919 482 218 920 483 218 921 483 220 922 480 221 923 481 222 924 496 221 925 497 220 926 501 220 927 501 217 928 500 222 929 496 223 930 485 222 931 486 217 932 484 217 933 484 216 934 495 223 935 485

+

+

248 936 576 249 937 577 250 938 578 249 939 577 248 940 576 251 941 579 252 942 580 250 943 581 249 944 582 250 945 581 252 946 580 253 947 583 254 948 584 251 949 585 248 950 586 251 951 585 254 952 584 255 953 587 256 954 588 255 955 587 254 956 584 255 957 589 249 958 590 251 959 591 249 960 590 255 961 589 252 962 592 255 963 593 256 964 594 253 965 595 255 966 593 253 967 595 252 968 596 254 969 597 253 970 598 256 971 599 253 972 598 254 973 597 250 974 600 254 975 597 248 976 601 250 977 600 273 978 638 274 979 639 275 980 640 274 981 639 273 982 638 276 983 641 277 984 642 275 985 643 274 986 644 275 987 643 277 988 642 278 989 645 279 990 646 276 991 647 273 992 648 276 993 647 279 994 646 280 995 649 281 996 650 280 997 649 279 998 646 280 999 651 274 1000 652 276 1001 653 274 1002 652 280 1003 651 277 1004 654 280 1005 655 281 1006 656 278 1007 657 280 1008 655 278 1009 657 277 1010 658 279 1011 659 278 1012 660 281 1013 661 278 1014 660 279 1015 659 275 1016 662 279 1017 659 273 1018 663 275 1019 662 354 1020 856 355 1021 857 356 1022 858 355 1023 857 354 1024 856 357 1025 859 358 1026 860 356 1027 861 355 1028 862 356 1029 861 358 1030 860 359 1031 863 360 1032 864 357 1033 865 354 1034 866 357 1035 865 360 1036 864 361 1037 867 362 1038 868 361 1039 867 360 1040 864 361 1041 869 355 1042 870 357 1043 871 355 1044 870 361 1045 869 358 1046 872 361 1047 873 362 1048 874 359 1049 875 361 1050 873 359 1051 875 358 1052 876 360 1053 877 359 1054 878 362 1055 879 359 1056 878 360 1057 877 356 1058 880 360 1059 877 354 1060 881 356 1061 880 427 1062 1026 428 1063 1027 429 1064 1028 428 1065 1027 427 1066 1026 430 1067 1029 431 1068 1030 429 1069 1031 428 1070 1032 429 1071 1031 431 1072 1030 432 1073 1033 433 1074 1034 430 1075 1035 427 1076 1036 430 1077 1035 433 1078 1034 434 1079 1037 435 1080 1038 434 1081 1037 433 1082 1034 434 1083 1039 428 1084 1040 430 1085 1041 428 1086 1040 434 1087 1039 431 1088 1042 434 1089 1043 435 1090 1044 432 1091 1045 434 1092 1043 432 1093 1045 431 1094 1046 433 1095 1047 432 1096 1048 435 1097 1049 432 1098 1048 433 1099 1047 429 1100 1050 433 1101 1047 427 1102 1051 429 1103 1050

+

224 1104 504 225 1105 505 226 1106 506 225 1107 505 224 1108 504 227 1109 507 225 1110 508 228 1111 509 229 1112 510 228 1113 509 225 1114 508 227 1115 511 230 1116 512 226 1117 513 225 1118 514 230 1119 512 225 1120 514 229 1121 515 230 1122 516 231 1123 517 226 1124 518 231 1125 517 224 1126 519 226 1127 518 224 1128 520 231 1129 521 228 1130 522 224 1131 520 228 1132 522 227 1133 523 230 1134 524 228 1135 525 231 1136 526 228 1137 525 230 1138 524 229 1139 527 232 1140 528 233 1141 529 234 1142 530 233 1143 529 232 1144 528 235 1145 531 233 1146 532 236 1147 533 237 1148 534 236 1149 533 233 1150 532 235 1151 535 238 1152 536 234 1153 537 233 1154 538 238 1155 536 233 1156 538 237 1157 539 238 1158 540 239 1159 541 234 1160 542 239 1161 541 232 1162 543 234 1163 542 232 1164 544 239 1165 545 236 1166 546 232 1167 544 236 1168 546 235 1169 547 238 1170 548 236 1171 549 239 1172 550 236 1173 549 238 1174 548 237 1175 551 240 1176 552 241 1177 553 242 1178 554 241 1179 553 240 1180 552 243 1181 555 241 1182 556 244 1183 557 245 1184 558 244 1185 557 241 1186 556 243 1187 559 246 1188 560 242 1189 561 241 1190 562 246 1191 560 241 1192 562 245 1193 563 246 1194 564 247 1195 565 242 1196 566 247 1197 565 240 1198 567 242 1199 566 240 1200 568 247 1201 569 244 1202 570 240 1203 568 244 1204 570 243 1205 571 246 1206 572 244 1207 573 247 1208 574 244 1209 573 246 1210 572 245 1211 575 282 1212 664 283 1213 665 284 1214 666 283 1215 665 282 1216 664 285 1217 667 283 1218 668 286 1219 669 287 1220 670 286 1221 669 283 1222 668 285 1223 671 288 1224 672 284 1225 673 283 1226 674 288 1227 672 283 1228 674 287 1229 675 288 1230 676 289 1231 677 284 1232 678 289 1233 677 282 1234 679 284 1235 678 282 1236 680 289 1237 681 286 1238 682 282 1239 680 286 1240 682 285 1241 683 288 1242 684 286 1243 685 289 1244 686 286 1245 685 288 1246 684 287 1247 687 290 1248 688 291 1249 689 292 1250 690 291 1251 689 290 1252 688 293 1253 691 291 1254 692 294 1255 693 295 1256 694 294 1257 693 291 1258 692 293 1259 695 296 1260 696 292 1261 697 291 1262 698 296 1263 696 291 1264 698 295 1265 699 296 1266 700 297 1267 701 292 1268 702 297 1269 701 290 1270 703 292 1271 702 290 1272 704 297 1273 705 294 1274 706 290 1275 704 294 1276 706 293 1277 707 297 1278 708 295 1279 709 294 1280 710 295 1281 709 297 1282 708 296 1283 711 298 1284 712 299 1285 713 300 1286 714 299 1287 713 298 1288 712 301 1289 715 299 1290 716 302 1291 717 303 1292 718 302 1293 717 299 1294 716 301 1295 719 304 1296 720 300 1297 721 299 1298 722 304 1299 720 299 1300 722 303 1301 723 304 1302 724 305 1303 725 300 1304 726 305 1305 725 298 1306 727 300 1307 726 298 1308 728 305 1309 729 302 1310 730 298 1311 728 302 1312 730 301 1313 731 304 1314 732 302 1315 733 305 1316 734 302 1317 733 304 1318 732 303 1319 735 330 1320 790 331 1321 791 332 1322 792 331 1323 791 330 1324 790 333 1325 793 331 1326 794 334 1327 795 335 1328 796 334 1329 795 331 1330 794 333 1331 797 336 1332 798 332 1333 799 331 1334 800 336 1335 798 331 1336 800 335 1337 801 336 1338 802 337 1339 803 332 1340 804 337 1341 803 330 1342 805 332 1343 804 330 1344 806 337 1345 807 334 1346 808 330 1347 806 334 1348 808 333 1349 809 336 1350 810 334 1351 811 337 1352 812 334 1353 811 336 1354 810 335 1355 813 338 1356 814 339 1357 815 340 1358 816 339 1359 815 338 1360 814 341 1361 817 339 1362 818 342 1363 819 343 1364 820 342 1365 819 339 1366 818 341 1367 821 344 1368 822 340 1369 823 339 1370 824 344 1371 822 339 1372 824 343 1373 825 344 1374 826 345 1375 827 340 1376 828 345 1377 827 338 1378 829 340 1379 828 338 1380 830 345 1381 831 342 1382 832 338 1383 830 342 1384 832 341 1385 833 345 1386 834 343 1387 835 342 1388 836 343 1389 835 345 1390 834 344 1391 837

+

257 1392 602 258 1393 603 259 1394 604 258 1395 603 257 1396 602 260 1397 605 261 1398 606 262 1399 607 263 1400 608 262 1401 607 261 1402 606 264 1403 609 262 1404 607 264 1405 609 260 1406 610 262 1407 607 260 1408 610 257 1409 611 263 1410 608 262 1411 607 257 1412 612 263 1413 608 257 1414 612 259 1415 613 263 1416 608 258 1417 614 261 1418 606 258 1419 614 263 1420 608 259 1421 615 261 1422 616 260 1423 617 264 1424 618 260 1425 617 261 1426 616 258 1427 619 265 1428 620 266 1429 621 267 1430 622 266 1431 621 265 1432 620 268 1433 623 269 1434 624 270 1435 625 271 1436 626 270 1437 625 269 1438 624 272 1439 627 270 1440 625 272 1441 627 268 1442 628 270 1443 625 268 1444 628 265 1445 629 271 1446 626 270 1447 625 265 1448 630 271 1449 626 265 1450 630 267 1451 631 271 1452 626 266 1453 632 269 1454 624 266 1455 632 271 1456 626 267 1457 633 269 1458 634 268 1459 635 272 1460 636 268 1461 635 269 1462 634 266 1463 637 306 1464 736 307 1465 737 308 1466 738 307 1467 737 306 1468 736 309 1469 739 310 1470 740 311 1471 741 312 1472 742 311 1473 741 310 1474 740 313 1475 743 311 1476 741 313 1477 743 309 1478 744 311 1479 741 309 1480 744 306 1481 745 312 1482 742 311 1483 741 306 1484 746 312 1485 742 306 1486 746 308 1487 747 312 1488 742 307 1489 748 310 1490 740 307 1491 748 312 1492 742 308 1493 749 310 1494 750 309 1495 751 313 1496 752 309 1497 751 310 1498 750 307 1499 753 314 1500 754 315 1501 755 316 1502 756 315 1503 755 314 1504 754 317 1505 757 318 1506 758 319 1507 759 320 1508 760 319 1509 759 318 1510 758 321 1511 761 319 1512 759 321 1513 761 317 1514 762 319 1515 759 317 1516 762 314 1517 763 320 1518 760 319 1519 759 314 1520 764 320 1521 760 314 1522 764 316 1523 765 320 1524 760 315 1525 766 318 1526 758 315 1527 766 320 1528 760 316 1529 767 318 1530 768 317 1531 769 321 1532 770 317 1533 769 318 1534 768 315 1535 771 322 1536 772 323 1537 773 324 1538 774 323 1539 773 322 1540 772 325 1541 775 326 1542 776 327 1543 777 328 1544 778 327 1545 777 326 1546 776 329 1547 779 327 1548 777 329 1549 779 325 1550 780 327 1551 777 325 1552 780 322 1553 781 328 1554 778 327 1555 777 322 1556 782 328 1557 778 322 1558 782 324 1559 783 326 1560 776 328 1561 778 324 1562 784 326 1563 776 324 1564 784 323 1565 785 329 1566 786 326 1567 787 323 1568 788 329 1569 786 323 1570 788 325 1571 789 346 1572 838 347 1573 839 348 1574 840 347 1575 839 346 1576 838 349 1577 841 350 1578 842 351 1579 843 352 1580 844 351 1581 843 350 1582 842 353 1583 845 351 1584 843 353 1585 845 349 1586 846 351 1587 843 349 1588 846 346 1589 847 352 1590 844 351 1591 843 346 1592 848 352 1593 844 346 1594 848 348 1595 849 350 1596 842 352 1597 844 348 1598 850 350 1599 842 348 1600 850 347 1601 851 353 1602 852 350 1603 853 347 1604 854 353 1605 852 347 1606 854 349 1607 855 363 1608 882 364 1609 883 365 1610 884 364 1611 883 363 1612 882 366 1613 885 367 1614 886 368 1615 887 369 1616 888 368 1617 887 367 1618 886 370 1619 889 368 1620 887 370 1621 889 366 1622 890 368 1623 887 366 1624 890 363 1625 891 369 1626 888 368 1627 887 363 1628 892 369 1629 888 363 1630 892 365 1631 893 369 1632 888 364 1633 894 367 1634 886 364 1635 894 369 1636 888 365 1637 895 367 1638 896 366 1639 897 370 1640 898 366 1641 897 367 1642 896 364 1643 899 371 1644 900 372 1645 901 373 1646 902 372 1647 901 371 1648 900 374 1649 903 375 1650 904 376 1651 905 377 1652 906 376 1653 905 375 1654 904 378 1655 907 376 1656 905 378 1657 907 374 1658 908 376 1659 905 374 1660 908 371 1661 909 377 1662 906 376 1663 905 371 1664 910 377 1665 906 371 1666 910 373 1667 911 377 1668 906 372 1669 912 375 1670 904 372 1671 912 377 1672 906 373 1673 913 375 1674 914 374 1675 915 378 1676 916 374 1677 915 375 1678 914 372 1679 917 379 1680 918 380 1681 919 381 1682 920 380 1683 919 379 1684 918 382 1685 921 383 1686 922 384 1687 923 385 1688 924 384 1689 923 383 1690 922 386 1691 925 384 1692 923 386 1693 925 382 1694 926 384 1695 923 382 1696 926 379 1697 927 385 1698 924 384 1699 923 379 1700 928 385 1701 924 379 1702 928 381 1703 929 383 1704 922 385 1705 924 381 1706 930 383 1707 922 381 1708 930 380 1709 931 386 1710 932 383 1711 933 380 1712 934 386 1713 932 380 1714 934 382 1715 935 387 1716 936 388 1717 937 389 1718 938 388 1719 937 387 1720 936 390 1721 939 391 1722 940 392 1723 941 393 1724 942 392 1725 941 391 1726 940 394 1727 943 392 1728 941 394 1729 943 390 1730 944 392 1731 941 390 1732 944 387 1733 945 393 1734 942 392 1735 941 387 1736 946 393 1737 942 387 1738 946 389 1739 947 391 1740 940 393 1741 942 389 1742 948 391 1743 940 389 1744 948 388 1745 949 391 1746 950 390 1747 951 394 1748 952 390 1749 951 391 1750 950 388 1751 953 395 1752 954 396 1753 955 397 1754 956 396 1755 955 395 1756 954 398 1757 957 399 1758 958 400 1759 959 401 1760 960 400 1761 959 399 1762 958 402 1763 961 400 1764 959 402 1765 961 398 1766 962 400 1767 959 398 1768 962 395 1769 963 401 1770 960 400 1771 959 395 1772 964 401 1773 960 395 1774 964 397 1775 965 401 1776 960 396 1777 966 399 1778 958 396 1779 966 401 1780 960 397 1781 967 399 1782 968 398 1783 969 402 1784 970 398 1785 969 399 1786 968 396 1787 971 403 1788 972 404 1789 973 405 1790 974 404 1791 973 403 1792 972 406 1793 975 407 1794 976 408 1795 977 409 1796 978 408 1797 977 407 1798 976 410 1799 979 408 1800 977 410 1801 979 406 1802 980 408 1803 977 406 1804 980 403 1805 981 409 1806 978 408 1807 977 403 1808 982 409 1809 978 403 1810 982 405 1811 983 409 1812 978 404 1813 984 407 1814 976 404 1815 984 409 1816 978 405 1817 985 407 1818 986 406 1819 987 410 1820 988 406 1821 987 407 1822 986 404 1823 989 411 1824 990 412 1825 991 413 1826 992 412 1827 991 411 1828 990 414 1829 993 415 1830 994 416 1831 995 417 1832 996 416 1833 995 415 1834 994 418 1835 997 416 1836 995 418 1837 997 414 1838 998 416 1839 995 414 1840 998 411 1841 999 417 1842 996 416 1843 995 411 1844 1000 417 1845 996 411 1846 1000 413 1847 1001 415 1848 994 417 1849 996 413 1850 1002 415 1851 994 413 1852 1002 412 1853 1003 418 1854 1004 415 1855 1005 412 1856 1006 418 1857 1004 412 1858 1006 414 1859 1007 419 1860 1008 420 1861 1009 421 1862 1010 420 1863 1009 419 1864 1008 422 1865 1011 423 1866 1012 424 1867 1013 425 1868 1014 424 1869 1013 423 1870 1012 426 1871 1015 424 1872 1013 426 1873 1015 422 1874 1016 424 1875 1013 422 1876 1016 419 1877 1017 425 1878 1014 424 1879 1013 419 1880 1018 425 1881 1014 419 1882 1018 421 1883 1019 423 1884 1012 425 1885 1014 421 1886 1020 423 1887 1012 421 1888 1020 420 1889 1021 423 1890 1022 422 1891 1023 426 1892 1024 422 1893 1023 423 1894 1022 420 1895 1025

+
+
+
+ + + + + + + + + 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 3.020157 0.000000 0.000000 0.000000 1.0000001.000000 + 30.0000000.0000003.333333 + + + + + +
diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ShelfE_01/model.config b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ShelfE_01/model.config new file mode 100755 index 0000000..cddf840 --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ShelfE_01/model.config @@ -0,0 +1,11 @@ + + + aws_robomaker_warehouse_ShelfE_01 + 1.0 + model.sdf + + + + + + diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ShelfE_01/model.sdf b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ShelfE_01/model.sdf new file mode 100755 index 0000000..d615c9e --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ShelfE_01/model.sdf @@ -0,0 +1,46 @@ + + + + + + 30 + + 907.144 + 0 + 0 + 104.950 + 0 + 824.248 + + + + + + model://aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + model://aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_visual.DAE + + + 1 + + +1 + + diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ShelfF_01/materials/textures/aws_robomaker_warehouse_ShelfF_01.png b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ShelfF_01/materials/textures/aws_robomaker_warehouse_ShelfF_01.png new file mode 100755 index 0000000..6a8add8 Binary files /dev/null and b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ShelfF_01/materials/textures/aws_robomaker_warehouse_ShelfF_01.png differ diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ShelfF_01/materials/textures/aws_robomaker_warehouse_ShelfF_02.png b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ShelfF_01/materials/textures/aws_robomaker_warehouse_ShelfF_02.png new file mode 100755 index 0000000..b28b289 Binary files /dev/null and b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ShelfF_01/materials/textures/aws_robomaker_warehouse_ShelfF_02.png differ diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ShelfF_01/materials/textures/aws_robomaker_warehouse_ShelfF_03.png b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ShelfF_01/materials/textures/aws_robomaker_warehouse_ShelfF_03.png new file mode 100755 index 0000000..2738ccc Binary files /dev/null and b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ShelfF_01/materials/textures/aws_robomaker_warehouse_ShelfF_03.png differ diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ShelfF_01/meshes/aws_robomaker_warehouse_ShelfF_01_collision.DAE b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ShelfF_01/meshes/aws_robomaker_warehouse_ShelfF_01_collision.DAE new file mode 100755 index 0000000..cc88e55 --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ShelfF_01/meshes/aws_robomaker_warehouse_ShelfF_01_collision.DAE @@ -0,0 +1,575 @@ + + + FBX COLLADA exporter2019-05-16T06:18:19Z2019-05-16T06:18:19ZZ_UP + + + + + +-109.909821 -899.415955 0.000000 +100.279144 -899.415955 0.000000 +-109.909821 905.263123 0.000000 +100.279144 905.263123 0.000000 +-109.909821 -899.415955 652.940002 +100.279144 -899.415955 652.940002 +-109.909821 905.263123 652.940002 +100.279144 905.263123 652.940002 +-109.909821 -884.415955 0.000000 +-109.909821 -452.497528 0.000000 +-109.909821 -437.497528 0.000000 +-109.909821 -15.096558 0.000000 +-109.909821 -0.096619 0.000000 +100.279144 -0.096558 0.000000 +100.279144 -15.096558 0.000000 +100.279144 -437.497528 0.000000 +100.279144 -452.497528 0.000000 +100.279144 -884.415894 0.000000 +100.279144 -884.415955 652.940002 +100.279144 -452.497528 652.940002 +100.279144 -437.497528 652.940002 +100.279144 -15.096558 652.940002 +100.279144 -0.096619 652.940002 +-109.909821 -0.096558 652.940002 +-109.909821 -15.096558 652.940002 +-109.909821 -437.497528 652.940002 +-109.909821 -452.497528 652.940002 +-109.909821 -884.415894 652.940002 +100.279144 434.116791 0.000000 +-109.909821 434.116760 0.000000 +-109.909821 434.116791 652.940002 +100.279144 434.116760 652.940002 +100.279144 449.116821 0.000000 +-109.909821 449.116821 0.000000 +-109.909821 449.116821 652.940002 +100.279144 449.116821 652.940002 +-109.909813 890.263123 652.940002 +100.279144 890.263123 652.940002 +100.279144 890.263123 0.000000 +-109.909821 890.263123 0.000000 +100.279144 890.263123 164.188065 +100.279144 449.116821 164.188065 +100.279144 434.116791 164.188065 +100.279144 -0.096572 164.188065 +100.279144 -15.096560 164.188065 +100.279144 -437.497528 164.188065 +100.279144 -452.497528 164.188065 +100.279144 -884.415894 164.188065 +100.279144 -899.415955 164.188065 +-109.909821 -899.415955 164.188065 +-109.909821 -884.415894 164.188065 +-109.909821 -452.497528 164.188065 +-109.909821 -437.497528 164.188065 +-109.909821 -15.096558 164.188065 +-109.909821 -0.096604 164.188065 +-109.909821 434.116760 164.188065 +-109.909821 449.116821 164.188065 +-109.909821 890.263123 164.188065 +-109.909821 905.263184 164.188065 +100.279144 905.263184 164.188065 + + + + + + + + + + + +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 -0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.000000 1.000000 -0.000000 +-0.000000 1.000000 -0.000000 +-0.000000 1.000000 -0.000000 +-0.000000 1.000000 -0.000000 +-0.000000 1.000000 -0.000000 +-0.000000 1.000000 -0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 -0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.000000 1.000000 0.000000 +-0.000000 1.000000 0.000000 +-0.000000 1.000000 0.000000 +-0.000000 1.000000 0.000000 +-0.000000 1.000000 0.000000 +-0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 + + + + + + + + + + + +1.000000 0.000000 +0.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +1.000000 0.166667 +1.000000 0.333333 +1.000000 0.500000 +1.000000 0.666667 +1.000000 0.833333 +0.833333 0.000000 +0.666667 0.000000 +0.500000 0.000000 +0.333333 0.000000 +0.166667 0.000000 +0.000000 0.833333 +0.000000 0.666667 +0.000000 0.500000 +0.000000 0.333333 +0.000000 0.166667 +0.833333 0.000000 +0.666667 0.000000 +0.500000 0.000000 +0.333333 0.000000 +0.166667 0.000000 +1.000000 0.166667 +1.000000 0.333333 +1.000000 0.500000 +1.000000 0.666667 +1.000000 0.833333 +0.166667 1.000000 +0.333333 1.000000 +0.500000 1.000000 +0.666667 1.000000 +0.833333 1.000000 +0.000000 0.833333 +0.000000 0.666667 +0.000000 0.500000 +0.000000 0.333333 +0.000000 0.166667 +0.166667 1.000000 +0.333333 1.000000 +0.500000 1.000000 +0.666667 1.000000 +0.833333 1.000000 +0.000000 0.912466 +0.912466 0.000000 +1.000000 0.912466 +0.087534 0.000000 +0.000000 0.912466 +0.087534 1.000000 +1.000000 0.912466 +0.912466 1.000000 +0.000000 0.923029 +0.923029 0.000000 +1.000000 0.923029 +0.076971 0.000000 +0.000000 0.923029 +0.076971 1.000000 +1.000000 0.923029 +0.923029 1.000000 +0.000000 0.977027 +0.022973 1.000000 +1.000000 0.977027 +0.977027 1.000000 +0.000000 0.977027 +0.977027 0.000000 +1.000000 0.977027 +0.022973 0.000000 +0.977027 0.240683 +0.923029 0.240683 +0.912466 0.240683 +0.833333 0.240683 +0.666667 0.240683 +0.500000 0.240683 +0.333333 0.240683 +0.166667 0.240683 +1.000000 0.240683 +0.000000 0.240683 +0.000000 0.240683 +1.000000 0.240683 +0.833333 0.240683 +0.666667 0.240683 +0.500000 0.240683 +0.333333 0.240683 +0.166667 0.240683 +0.087534 0.240683 +0.076971 0.240683 +0.022973 0.240683 +1.000000 0.240683 +0.000000 0.240683 +1.000000 0.240683 +0.000000 0.240683 + + + + + + + + + + + +

16 0 37 9 1 25 10 2 26 16 3 37 10 4 26 15 5 36 26 6 57 20 7 46 25 8 56 20 9 46 26 10 57 19 11 45 49 12 98 1 13 9 48 14 96 1 15 9 49 16 98 0 17 8 46 18 94 15 19 41 45 20 93 15 21 41 46 22 94 16 23 42 59 24 111 2 25 17 58 26 108 2 27 17 59 28 111 3 29 16 14 30 35 11 31 27 12 32 28 14 33 35 12 34 28 13 35 34 8 36 24 1 37 1 0 38 0 1 39 1 8 40 24 17 41 38 30 42 68 23 43 54 31 44 70 31 45 70 23 46 54 22 47 48 22 48 48 23 49 54 24 50 55 22 51 48 24 52 55 21 53 47 25 54 56 21 55 47 24 56 55 21 57 47 25 58 56 20 59 46 18 60 44 27 61 58 4 62 4 18 63 44 4 64 4 5 65 5 26 66 57 27 67 58 19 68 45 19 69 45 27 70 58 18 71 44 43 72 91 14 73 40 13 74 39 14 75 40 43 76 91 44 77 92 18 78 49 48 79 97 47 80 95 48 81 97 18 82 49 5 83 14 19 84 50 47 85 95 46 86 94 47 87 95 19 88 50 18 89 49 49 90 99 8 91 29 0 92 21 8 93 29 49 94 99 50 95 100 52 96 102 9 97 30 51 98 101 9 99 30 52 100 102 10 101 31 23 102 59 55 103 105 54 104 104 55 105 105 23 106 59 30 107 69 24 108 60 54 109 104 53 110 103 54 111 104 24 112 60 23 113 59 28 114 64 29 115 66 33 116 74 28 117 64 33 118 74 32 119 72 35 120 78 34 121 76 30 122 68 35 123 78 30 124 68 31 125 70 42 126 90 32 127 73 41 128 89 32 129 73 42 130 90 28 131 65 30 132 69 56 133 106 55 134 105 56 135 106 30 136 69 34 137 77 36 138 80 35 139 78 37 140 82 35 141 78 36 142 80 34 143 76 34 144 77 36 145 81 56 146 106 36 147 81 57 148 107 56 149 106 38 150 84 39 151 86 2 152 2 38 153 84 2 154 2 3 155 3 36 156 80 7 157 7 6 158 6 7 159 7 36 160 80 37 161 82 40 162 88 3 163 13 59 164 110 3 165 13 40 166 88 38 167 85 57 168 107 36 169 81 6 170 22 6 171 22 58 172 109 57 173 107 4 174 10 49 175 98 5 176 11 5 177 11 49 178 98 48 179 96 46 180 94 20 181 51 19 182 50 20 183 51 46 184 94 45 185 93 7 186 18 59 187 111 6 188 19 6 189 19 59 190 111 58 191 108 24 192 60 53 193 103 25 194 61 25 195 61 53 196 103 52 197 102 22 198 53 43 199 91 31 200 71 31 201 71 43 202 91 42 203 90 21 204 52 44 205 92 22 206 53 22 207 53 44 208 92 43 209 91 20 210 51 44 211 92 21 212 52 44 213 92 20 214 51 45 215 93 48 216 97 1 217 12 47 218 95 47 219 95 1 220 12 17 221 43 27 222 63 50 223 100 4 224 23 4 225 23 50 226 100 49 227 99 26 228 62 51 229 101 27 230 63 27 231 63 51 232 101 50 233 100 25 234 61 52 235 102 26 236 62 26 237 62 52 238 102 51 239 101 54 240 104 12 241 33 53 242 103 53 243 103 12 244 33 11 245 32 31 246 71 42 247 90 35 248 79 35 249 79 42 250 90 41 251 89 56 252 106 33 253 75 55 254 105 55 255 105 33 256 75 29 257 67 35 258 79 41 259 89 37 260 83 37 261 83 41 262 89 40 263 88 37 264 83 40 265 88 7 266 15 7 267 15 40 268 88 59 269 110 58 270 109 2 271 20 57 272 107 57 273 107 2 274 20 39 275 87 47 276 95 17 277 43 50 278 100 50 279 100 17 280 43 8 281 24 46 282 94 51 283 101 9 284 30 46 285 94 9 286 30 16 287 37 50 288 100 51 289 101 47 290 95 47 291 95 51 292 101 46 293 94 53 294 103 14 295 35 44 296 92 14 297 35 53 298 103 11 299 32 52 300 102 44 301 92 45 302 93 44 303 92 52 304 102 53 305 103 52 306 102 45 307 93 15 308 41 52 309 102 15 310 41 10 311 26 43 312 91 13 313 39 54 314 104 54 315 104 13 316 39 12 317 28 54 318 104 55 319 105 43 320 91 43 321 91 55 322 105 42 323 90 42 324 90 55 325 105 29 326 67 42 327 90 29 328 67 28 329 64 41 330 89 32 331 73 56 332 106 56 333 106 32 334 73 33 335 74 56 336 106 57 337 107 41 338 89 41 339 89 57 340 107 40 341 88 40 342 88 57 343 107 39 344 87 40 345 88 39 346 87 38 347 84

+
+
+
+ + + 1.000000 0.000000 0.000000 5.565578 0.000000 1.000000 0.000000 -2.923615 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.0000001.000000 + 30.0000000.0000003.333333 + + + + + +
diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ShelfF_01/meshes/aws_robomaker_warehouse_ShelfF_01_visual.DAE b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ShelfF_01/meshes/aws_robomaker_warehouse_ShelfF_01_visual.DAE new file mode 100755 index 0000000..065be92 --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ShelfF_01/meshes/aws_robomaker_warehouse_ShelfF_01_visual.DAE @@ -0,0 +1,15734 @@ + + + FBX COLLADA exporter2019-05-27T02:54:39Z2019-05-27T02:54:39ZZ_UP + + + ../materials/textures/aws_robomaker_warehouse_ShelfF_01.png + + + ../materials/textures/aws_robomaker_warehouse_ShelfF_02.png + + + ../materials/textures/aws_robomaker_warehouse_ShelfF_03.png + + + + + + + + + + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + +-104.344238 0.000031 887.339539 +-91.344238 0.000031 887.339539 +-104.344238 614.091614 887.339539 +-91.344238 614.091614 887.339539 +-104.344238 0.000031 902.339539 +-91.344238 0.000031 902.339539 +-104.344238 614.091614 902.339539 +-91.344238 614.091614 902.339539 +92.844727 0.000031 887.339539 +92.844727 614.091614 887.339539 +105.844727 614.091614 887.339539 +105.844727 0.000031 887.339539 +92.844727 0.000031 902.339539 +105.844727 0.000031 902.339539 +105.844727 614.091614 902.339539 +92.844727 614.091614 902.339539 +-96.219147 34.111694 887.339539 +99.260559 169.685135 887.339539 +99.260559 156.685135 887.339539 +-96.219147 21.111694 887.339539 +-96.219147 34.111694 902.339539 +-96.219147 21.111694 902.339539 +99.260559 156.685135 902.339539 +99.260559 169.685135 902.339539 +-96.219147 342.438934 887.339539 +99.260559 471.540375 887.339539 +99.260559 458.540375 887.339539 +-96.219147 329.438934 887.339539 +-96.219147 342.438934 902.339539 +-96.219147 329.438934 902.339539 +99.260559 458.540375 902.339539 +99.260559 471.540375 902.339539 +-96.219147 318.660126 887.339539 +99.260559 190.825317 887.339539 +99.260559 177.825317 887.339539 +-96.219147 305.660126 887.339539 +-96.219147 318.660126 902.339539 +-96.219147 305.660126 902.339539 +99.260559 177.825317 902.339539 +99.260559 190.825317 902.339539 +-96.219147 558.273315 887.339539 +99.260559 558.273315 887.339539 +99.260559 545.273315 887.339539 +-96.219147 545.273315 887.339539 +-96.219147 558.273315 902.339539 +-96.219147 545.273315 902.339539 +99.260559 545.273315 902.339539 +99.260559 558.273315 902.339539 +-104.344238 0.000000 440.421143 +-104.344238 614.091614 440.421143 +-91.344238 614.091614 440.421143 +-91.344238 0.000000 440.421143 +-104.344238 0.000000 455.421143 +-91.344238 0.000000 455.421143 +-91.344238 614.091614 455.421143 +-104.344238 614.091614 455.421143 +92.844727 0.000000 440.421143 +92.844727 614.091614 440.421143 +105.844727 614.091614 440.421143 +105.844727 0.000000 440.421143 +92.844727 0.000000 455.421143 +105.844727 0.000000 455.421143 +105.844727 614.091614 455.421143 +92.844727 614.091614 455.421143 +-96.219147 34.111694 440.421143 +99.260559 169.685120 440.421143 +99.260559 156.685120 440.421143 +-96.219147 21.111694 440.421143 +-96.219147 34.111694 455.421143 +-96.219147 21.111694 455.421143 +99.260559 156.685120 455.421143 +99.260559 169.685120 455.421143 +-96.219147 342.438904 440.421143 +99.260559 471.540375 440.421143 +99.260559 458.540375 440.421143 +-96.219147 329.438904 440.421143 +-96.219147 342.438904 455.421143 +-96.219147 329.438904 455.421143 +99.260559 458.540375 455.421143 +99.260559 471.540375 455.421143 +-96.219147 318.660095 440.421143 +99.260559 190.825302 440.421143 +99.260559 177.825287 440.421143 +-96.219147 305.660095 440.421143 +-96.219147 318.660095 455.421143 +-96.219147 305.660095 455.421143 +99.260559 177.825287 455.421143 +99.260559 190.825302 455.421173 +-96.219147 558.273254 440.421143 +99.260559 558.273254 440.421143 +99.260559 545.273254 440.421143 +-96.219147 545.273254 440.421143 +-96.219147 558.273254 455.421143 +-96.219147 545.273254 455.421143 +99.260559 545.273254 455.421143 +99.260559 558.273254 455.421143 +-104.344238 -0.000031 3.020142 +-104.344238 614.091553 3.020142 +-91.344238 614.091553 3.020142 +-91.344238 -0.000031 3.020142 +-104.344238 -0.000031 18.020142 +-91.344238 -0.000031 18.020142 +-91.344238 614.091553 18.020142 +-104.344238 614.091553 18.020142 +92.844727 -0.000031 3.020142 +92.844727 614.091553 3.020142 +105.844727 614.091553 3.020142 +105.844727 -0.000031 3.020142 +92.844727 -0.000031 18.020142 +105.844727 -0.000031 18.020142 +105.844727 614.091553 18.020142 +92.844727 614.091553 18.020142 +-96.219147 34.111694 3.020142 +99.260559 169.685089 3.020142 +99.260559 156.685104 3.020142 +-96.219147 21.111694 3.020142 +-96.219147 34.111694 18.020142 +-96.219147 21.111694 18.020142 +99.260559 156.685089 18.020142 +99.260559 169.685089 18.020142 +-96.219147 342.438904 3.020142 +99.260559 471.540344 3.020142 +99.260559 458.540344 3.020142 +-96.219147 329.438904 3.020142 +-96.219147 342.438904 18.020142 +-96.219147 329.438904 18.020142 +99.260559 458.540344 18.020142 +99.260559 471.540344 18.020142 +-96.219147 318.660095 3.020142 +99.260559 190.825287 3.020142 +99.260559 177.825256 3.020142 +-96.219147 305.660095 3.020142 +-96.219147 318.660095 18.020142 +-96.219147 305.660095 18.020142 +99.260559 177.825256 18.020142 +99.260559 190.825272 18.020203 +-96.219147 558.273254 3.020142 +99.260559 558.273254 3.020142 +99.260559 545.273254 3.020142 +-96.219147 545.273254 3.020142 +-96.219147 558.273254 18.020142 +-96.219147 545.273254 18.020142 +99.260559 545.273254 18.020142 +99.260559 558.273254 18.020142 +-104.344238 -0.000061 -446.193176 +-104.344238 614.091553 -446.193176 +-91.344238 614.091553 -446.193176 +-91.344238 -0.000061 -446.193176 +-104.344238 -0.000061 -431.193176 +-91.344238 -0.000061 -431.193176 +-91.344238 614.091553 -431.193176 +-104.344238 614.091553 -431.193176 +92.844727 -0.000061 -446.193176 +92.844727 614.091553 -446.193176 +105.844727 614.091553 -446.193176 +105.844727 -0.000061 -446.193176 +92.844727 -0.000061 -431.193176 +105.844727 -0.000061 -431.193176 +105.844727 614.091553 -431.193176 +92.844727 614.091553 -431.193176 +-96.219147 34.111664 -446.193176 +99.260559 169.685059 -446.193176 +99.260559 156.685089 -446.193176 +-96.219147 21.111664 -446.193176 +-96.219147 34.111664 -431.193176 +-96.219147 21.111664 -431.193176 +99.260559 156.685059 -431.193176 +99.260559 169.685059 -431.193176 +-96.219147 342.438873 -446.193176 +99.260559 471.540344 -446.193176 +99.260559 458.540344 -446.193176 +-96.219147 329.438873 -446.193176 +-96.219147 342.438873 -431.193176 +-96.219147 329.438873 -431.193176 +99.260559 458.540314 -431.193176 +99.260559 471.540314 -431.193176 +-96.219147 318.660065 -446.193176 +99.260559 190.825272 -446.193176 +99.260559 177.825241 -446.193176 +-96.219147 305.660065 -446.193176 +-96.219147 318.660065 -431.193176 +-96.219147 305.660065 -431.193176 +99.260559 177.825226 -431.193176 +99.260559 190.825256 -431.193176 +-96.219147 558.273254 -446.193176 +99.260559 558.273254 -446.193176 +99.260559 545.273254 -446.193176 +-96.219147 545.273254 -446.193176 +-96.219147 558.273193 -431.193176 +-96.219147 545.273193 -431.193176 +99.260559 545.273193 -431.193176 +99.260559 558.273193 -431.193176 +-104.344238 -0.000092 -902.339539 +-104.344238 614.091492 -902.339539 +-91.344238 614.091492 -902.339539 +-91.344238 -0.000092 -902.339539 +-104.344238 -0.000092 -887.339539 +-91.344238 -0.000092 -887.339539 +-91.344238 614.091492 -887.339539 +-104.344238 614.091492 -887.339539 +92.844727 -0.000092 -902.339539 +92.844727 614.091492 -902.339539 +105.844727 614.091492 -902.339539 +105.844727 -0.000092 -902.339539 +92.844727 -0.000092 -887.339539 +105.844727 -0.000092 -887.339539 +105.844727 614.091492 -887.339539 +92.844727 614.091492 -887.339539 +-96.219147 34.111633 -902.339539 +99.260559 169.685028 -902.339539 +99.260559 156.685074 -902.339539 +-96.219147 21.111633 -902.339539 +-96.219147 34.111633 -887.339539 +-96.219147 21.111633 -887.339539 +99.260559 156.685043 -887.339539 +99.260559 169.685028 -887.339539 +-96.219147 342.438843 -902.339539 +99.260559 471.540314 -902.339539 +99.260559 458.540314 -902.339539 +-96.219147 329.438843 -902.339539 +-96.219147 342.438843 -887.339539 +-96.219147 329.438843 -887.339539 +99.260559 458.540283 -887.339539 +99.260559 471.540283 -887.339539 +-96.219147 318.660034 -902.339539 +99.260559 190.825256 -902.339539 +99.260559 177.825226 -902.339539 +-96.219147 305.660034 -902.339539 +-96.219147 318.660034 -887.339539 +-96.219147 305.660034 -887.339539 +99.260559 177.825211 -887.339539 +99.260559 190.825241 -887.339539 +-96.219147 558.273254 -902.339539 +99.260559 558.273254 -902.339539 +99.260559 545.273254 -902.339539 +-96.219147 545.273254 -902.339539 +-96.219147 558.273193 -887.339539 +-96.219147 545.273193 -887.339539 +99.260559 545.273193 -887.339539 +99.260559 558.273193 -887.339539 +-99.241058 479.273254 -896.629211 +99.260559 479.273254 -896.629211 +99.260559 459.814392 -896.629211 +-99.241058 459.814392 -896.629211 +-99.241058 479.273346 902.339539 +-99.241058 459.814484 902.339539 +99.260559 459.814484 902.339539 +99.260559 479.273346 902.339539 +-99.241058 183.646896 -896.629211 +99.260559 183.646896 -896.629211 +99.260559 164.188019 -896.629211 +-99.241058 164.188019 -896.629211 +-99.241058 183.646973 902.339539 +-99.241058 164.188126 902.339539 +99.260559 164.188126 902.339539 +99.260559 183.646973 902.339539 +-96.219147 329.713470 887.339539 +99.260559 329.713470 887.339539 +99.260559 316.713470 887.339539 +-96.219147 316.713470 887.339539 +-96.219147 329.713470 902.339539 +-96.219147 316.713470 902.339539 +99.260559 316.713470 902.339539 +99.260559 329.713470 902.339539 +-96.219147 329.713440 440.421143 +99.260559 329.713440 440.421143 +99.260559 316.713440 440.421143 +-96.219147 316.713440 440.421143 +-96.219147 329.713440 455.421143 +-96.219147 316.713440 455.421143 +99.260559 316.713440 455.421143 +99.260559 329.713440 455.421143 +-96.219147 329.713440 3.020142 +99.260559 329.713440 3.020142 +99.260559 316.713440 3.020142 +-96.219147 316.713440 3.020142 +-96.219147 329.713409 18.020142 +-96.219147 316.713409 18.020142 +99.260559 316.713409 18.020142 +99.260559 329.713409 18.020142 +-96.219147 329.713440 -446.193176 +99.260559 329.713440 -446.193176 +99.260559 316.713440 -446.193176 +-96.219147 316.713440 -446.193176 +-96.219147 329.713379 -431.193176 +-96.219147 316.713379 -431.193176 +99.260559 316.713379 -431.193176 +99.260559 329.713379 -431.193176 +-96.219147 329.713409 -902.339539 +99.260559 329.713409 -902.339539 +99.260559 316.713409 -902.339539 +-96.219147 316.713409 -902.339539 +-96.219147 329.713379 -887.339539 +-96.219147 316.713379 -887.339539 +99.260559 316.713379 -887.339539 +99.260559 329.713379 -887.339539 +-105.844757 567.987732 -896.629211 +-88.513672 567.987732 -896.629211 +-88.513672 532.745239 -896.629211 +-105.844757 532.745239 -896.629211 +-105.844757 567.987793 902.339539 +-105.844757 532.745422 902.339539 +-88.513672 532.745422 902.339539 +-88.513672 567.987793 902.339539 +-15.810349 184.344681 -723.537659 +-15.810349 220.753220 -723.537659 +58.811157 220.753220 -723.555725 +58.811157 184.344681 -723.555725 +-15.429932 184.344681 -673.737244 +59.191650 184.344681 -673.755188 +59.191650 220.753220 -673.755188 +-15.438255 220.753220 -674.834045 +-15.429932 220.753220 -673.737244 +-15.810432 221.386520 -723.537659 +-15.810432 257.795105 -723.537659 +58.811157 257.795105 -723.555725 +58.811157 221.386520 -723.555725 +-15.430016 221.386520 -673.737366 +59.191650 221.386520 -673.755188 +59.191650 257.795105 -673.755188 +-15.438339 257.795105 -674.834045 +-15.430016 257.795105 -673.737366 +-15.810364 184.344681 -673.767639 +-15.810364 220.753220 -673.767639 +58.811218 220.753220 -673.785583 +58.811218 184.344681 -673.785583 +-15.429863 184.344696 -623.967224 +59.191635 184.344696 -623.985168 +59.191635 220.753220 -623.985291 +-15.438271 220.753220 -625.064148 +-15.429863 220.753220 -623.967224 +-91.014145 184.344681 -723.537659 +-91.014145 220.753220 -723.537659 +-16.392563 220.753220 -723.555603 +-16.392563 184.344681 -723.555603 +-90.633644 184.344681 -673.737244 +-16.012062 184.344681 -673.755188 +-16.012062 220.753220 -673.755310 +-90.642044 220.753220 -674.834045 +-90.633644 220.753220 -673.737244 +-91.014145 221.386520 -723.537659 +-91.014145 257.795105 -723.537659 +-16.392555 257.795105 -723.555725 +-16.392555 221.386520 -723.555725 +-90.633728 221.386520 -673.737244 +-16.012138 221.386520 -673.755310 +-16.012138 257.795105 -673.755310 +-90.642044 257.795105 -674.834167 +-90.633728 257.795105 -673.737244 +-91.014221 258.270355 -723.537659 +-91.014221 294.678894 -723.537659 +-16.392555 294.678894 -723.555725 +-16.392555 258.270355 -723.555725 +-90.633812 258.270355 -673.737244 +-16.012222 258.270355 -673.755310 +-16.012222 294.678894 -673.755310 +-90.642044 294.678894 -674.834167 +-90.633812 294.678894 -673.737244 +-91.014076 184.344681 -673.767639 +-91.014076 220.753220 -673.767639 +-16.392494 220.753220 -673.785706 +-16.392494 184.344681 -673.785706 +-90.633659 184.344696 -623.967224 +-16.012077 184.344696 -623.985168 +-16.012077 220.753220 -623.985291 +-90.641983 220.753220 -625.064026 +-90.633659 220.753220 -623.967224 +-91.014160 221.386520 -673.767639 +-91.014160 257.795105 -673.767639 +-16.392662 257.795105 -673.785706 +-16.392662 221.386520 -673.785706 +-90.633827 221.386520 -623.967346 +-16.012161 221.386520 -623.985168 +-16.012161 257.795105 -623.985291 +-90.642059 257.795105 -625.064148 +-90.633827 257.795105 -623.967346 +-91.014244 258.270355 -673.767639 +-91.014244 294.678894 -673.767639 +-16.392654 294.678894 -673.785706 +-16.392654 258.270355 -673.785706 +-90.633827 258.270355 -623.967346 +-16.012238 258.270355 -623.985291 +-16.012238 294.678894 -623.985413 +-90.642059 294.678894 -625.064148 +-90.633827 294.678894 -623.967346 +-91.014389 295.428833 -723.537659 +-91.014389 331.837433 -723.537659 +-16.392555 331.837433 -723.555847 +-16.392555 295.428833 -723.555847 +-90.633888 295.428833 -673.737366 +-16.012306 295.428833 -673.755432 +-16.012306 331.837433 -673.755432 +-90.642044 331.837433 -674.834290 +-90.633888 331.837433 -673.737366 +50.234726 184.344681 -527.757874 +50.234726 220.753220 -527.757874 +50.252762 220.753220 -453.136414 +50.252762 184.344696 -453.136414 +0.434303 184.344681 -527.377502 +0.452232 184.344696 -452.755920 +0.452332 220.753220 -452.755920 +1.531166 220.753220 -527.385803 +0.434303 220.753220 -527.377502 +50.234741 221.386520 -527.757996 +50.234741 257.795105 -527.757996 +50.252762 257.795105 -453.136414 +50.252762 221.386520 -453.136414 +0.434402 221.386520 -527.377625 +0.452332 221.386520 -452.755920 +0.452332 257.795105 -452.755920 +1.531174 257.795105 -527.385925 +0.434402 257.795105 -527.377625 +0.464661 184.344681 -527.757996 +0.464661 220.753220 -527.757996 +0.482689 220.753220 -453.136292 +0.482689 184.344696 -453.136292 +-49.335667 184.344681 -527.377380 +-49.317738 184.344696 -452.755920 +-49.317638 220.753220 -452.755920 +-48.238800 220.753220 -527.385803 +-49.335667 220.753220 -527.377380 +0.464760 221.386520 -527.757996 +0.464760 257.795105 -527.757996 +0.482788 257.795105 -453.136414 +0.482788 221.386520 -453.136414 +-49.335667 221.386520 -527.377625 +-49.317638 221.386520 -452.756042 +-49.317638 257.795105 -452.756042 +-48.238800 257.795105 -527.385803 +-49.335667 257.795105 -527.377625 +0.464760 258.270355 -527.757996 +0.464760 294.678894 -527.757996 +0.482788 294.678894 -453.136536 +0.482788 258.270355 -453.136536 +-49.335663 258.270355 -527.377747 +-49.317635 258.270355 -452.756165 +-49.317539 294.678894 -452.756165 +-48.238705 294.678894 -527.385925 +-49.335663 294.678894 -527.377747 +50.234772 184.344681 -602.961731 +50.234772 220.753220 -602.961731 +50.252701 220.753220 -528.340149 +50.252701 184.344681 -528.340149 +0.434341 184.344681 -602.581238 +0.452271 184.344681 -527.959656 +0.452370 220.753220 -527.959656 +1.531113 220.753220 -602.589661 +0.434341 220.753220 -602.581238 +50.234772 221.386520 -602.961731 +50.234772 257.795105 -602.961731 +50.252808 257.795105 -528.340149 +50.252808 221.386520 -528.340149 +0.434349 221.386520 -602.581360 +0.452370 221.386520 -527.959656 +0.452370 257.795105 -527.959778 +1.531212 257.795105 -602.589661 +0.434349 257.795105 -602.581360 +0.464699 184.344681 -602.961609 +0.464699 220.753220 -602.961609 +0.482727 220.753220 -528.340027 +0.482727 184.344681 -528.340027 +-49.335728 184.344681 -602.581238 +-49.317699 184.344681 -527.959656 +-49.317600 220.753220 -527.959656 +-48.238861 220.753220 -602.589539 +-49.335728 220.753220 -602.581238 +0.464706 221.386520 -602.961731 +0.464706 257.795105 -602.961731 +0.482735 257.795105 -528.340271 +0.482735 221.386520 -528.340271 +-49.335625 221.386520 -602.581360 +-49.317696 221.386520 -527.959778 +-49.317596 257.795105 -527.959778 +-48.238762 257.795105 -602.589661 +-49.335625 257.795105 -602.581360 +0.464706 258.270355 -602.961853 +0.464706 294.678894 -602.961853 +0.482834 294.678894 -528.340271 +0.482834 258.270355 -528.340271 +-49.335625 258.270355 -602.581360 +-49.317596 258.270355 -527.959778 +-49.317497 294.678894 -527.959778 +-48.238762 294.678894 -602.589661 +-49.335625 294.678894 -602.581360 +0.464760 295.428833 -527.758118 +0.464760 331.837433 -527.758118 +0.482895 331.837433 -453.136658 +0.482895 295.428833 -453.136658 +-49.335560 295.428833 -527.377991 +-49.317539 295.428833 -452.756165 +-49.317539 331.837433 -452.756165 +-48.238602 331.837433 -527.386047 +-49.335560 331.837433 -527.377991 +50.234726 479.563110 -703.469055 +50.234726 515.971619 -703.469055 +50.252762 515.971619 -628.847595 +50.252762 479.563110 -628.847595 +0.434303 479.563110 -703.088684 +0.452232 479.563110 -628.467102 +0.452332 515.971619 -628.467102 +1.531166 515.971619 -703.096985 +0.434303 515.971619 -703.088684 +0.464661 479.563110 -703.469177 +0.464661 515.971619 -703.469177 +0.482689 515.971619 -628.847473 +0.482689 479.563110 -628.847473 +-49.335667 479.563110 -703.088562 +-49.317738 479.563110 -628.467102 +-49.317638 515.971619 -628.467102 +-48.238800 515.971619 -703.096985 +-49.335667 515.971619 -703.088562 +0.464760 516.604919 -703.469177 +0.464760 553.013489 -703.469177 +0.482788 553.013489 -628.847595 +0.482788 516.604919 -628.847595 +-49.335667 516.604919 -703.088806 +-49.317638 516.604919 -628.467224 +-49.317638 553.013489 -628.467224 +-48.238800 553.013489 -703.096985 +-49.335667 553.013489 -703.088806 +50.234772 479.563080 -778.672913 +50.234772 515.971619 -778.672913 +50.252701 515.971619 -704.051331 +50.252701 479.563110 -704.051331 +0.434341 479.563080 -778.292419 +0.452271 479.563110 -703.670837 +0.452370 515.971619 -703.670837 +1.531113 515.971619 -778.300842 +0.434341 515.971619 -778.292419 +50.234772 516.604919 -778.672913 +50.234772 553.013489 -778.672913 +50.252808 553.013489 -704.051331 +50.252808 516.604919 -704.051331 +0.434349 516.604919 -778.292542 +0.452370 516.604919 -703.670837 +0.452370 553.013489 -703.670959 +1.531212 553.013489 -778.300842 +0.434349 553.013489 -778.292542 +50.234772 553.488770 -778.673035 +50.234772 589.897278 -778.673035 +50.252808 589.897278 -704.051331 +50.252808 553.488770 -704.051331 +0.434349 553.488770 -778.292542 +0.452377 553.488770 -703.670959 +0.452377 589.897278 -703.670959 +1.531212 589.897278 -778.300842 +0.434349 589.897278 -778.292542 +0.464699 479.563080 -778.672791 +0.464699 515.971619 -778.672791 +0.482727 515.971619 -704.051208 +0.482727 479.563110 -704.051208 +-49.335728 479.563080 -778.292419 +-49.317699 479.563110 -703.670837 +-49.317600 515.971619 -703.670837 +-48.238861 515.971619 -778.300720 +-49.335728 515.971619 -778.292419 +0.464706 516.604919 -778.672913 +0.464706 553.013489 -778.672913 +0.482735 553.013489 -704.051453 +0.482735 516.604919 -704.051453 +-49.335625 516.604919 -778.292542 +-49.317696 516.604919 -703.670959 +-49.317596 553.013489 -703.670959 +-48.238762 553.013489 -778.300842 +-49.335625 553.013489 -778.292542 +0.464706 553.488770 -778.673035 +0.464706 589.897278 -778.673035 +0.482834 589.897278 -704.051453 +0.482834 553.488770 -704.051453 +-49.335625 553.488770 -778.292542 +-49.317596 553.488770 -703.670959 +-49.317497 589.897278 -703.670959 +-48.238762 589.897278 -778.300842 +-49.335625 589.897278 -778.292542 +0.464806 590.647217 -778.673035 +0.464806 627.055847 -778.673035 +0.482834 627.055847 -704.051575 +0.482834 590.647217 -704.051575 +-49.335526 590.647217 -778.292664 +-49.317497 590.647217 -703.671082 +-49.317497 627.055847 -703.671082 +-48.238663 627.055847 -778.300842 +-49.335526 627.055847 -778.292664 +0.559647 479.789673 -324.522034 +0.559647 516.198181 -324.522034 +75.181152 516.198181 -324.540100 +75.181152 479.789673 -324.540100 +0.940063 479.789673 -274.721619 +75.561646 479.789673 -274.739563 +75.561646 516.198181 -274.739563 +0.931740 516.198181 -275.818420 +0.940063 516.198181 -274.721619 +0.559563 516.831482 -324.522034 +0.559563 553.240112 -324.522034 +75.181152 553.240112 -324.540100 +75.181152 516.831482 -324.540100 +0.939980 516.831482 -274.721741 +75.561646 516.831482 -274.739563 +75.561646 553.240112 -274.739563 +0.931656 553.240112 -275.818420 +0.939980 553.240112 -274.721741 +0.559631 479.789673 -274.752014 +0.559631 516.198181 -274.752014 +75.181213 516.198181 -274.769958 +75.181213 479.789673 -274.769958 +0.940132 479.789673 -224.951599 +75.561630 479.789673 -224.969543 +75.561630 516.198181 -224.969666 +0.931725 516.198181 -226.048523 +0.940132 516.198181 -224.951599 +-74.644150 479.789673 -324.522034 +-74.644150 516.198181 -324.522034 +-0.022568 516.198181 -324.539978 +-0.022568 479.789673 -324.539978 +-74.263649 479.789673 -274.721619 +0.357933 479.789673 -274.739563 +0.357933 516.198181 -274.739685 +-74.272049 516.198181 -275.818420 +-74.263649 516.198181 -274.721619 +-74.644150 516.831482 -324.522034 +-74.644150 553.240112 -324.522034 +-0.022560 553.240112 -324.540100 +-0.022560 516.831482 -324.540100 +-74.263733 516.831482 -274.721619 +0.357857 516.831482 -274.739685 +0.357857 553.240112 -274.739685 +-74.272049 553.240112 -275.818542 +-74.263733 553.240112 -274.721619 +-74.644226 553.715332 -324.522034 +-74.644226 590.123840 -324.522034 +-0.022560 590.123840 -324.540100 +-0.022560 553.715332 -324.540100 +-74.263817 553.715332 -274.721619 +0.357773 553.715332 -274.739685 +0.357773 590.123840 -274.739685 +-74.272049 590.123840 -275.818542 +-74.263817 590.123840 -274.721619 +-74.644081 479.789673 -274.752014 +-74.644081 516.198181 -274.752014 +-0.022499 516.198181 -274.770081 +-0.022499 479.789673 -274.770081 +-74.263664 479.789673 -224.951599 +0.357918 479.789673 -224.969543 +0.357918 516.198181 -224.969666 +-74.271988 516.198181 -226.048401 +-74.263664 516.198181 -224.951599 +-74.644165 516.831482 -274.752014 +-74.644165 553.240112 -274.752014 +-0.022667 553.240112 -274.770081 +-0.022667 516.831482 -274.770081 +-74.263832 516.831482 -224.951721 +0.357834 516.831482 -224.969543 +0.357834 553.240112 -224.969666 +-74.272064 553.240112 -226.048523 +-74.263832 553.240112 -224.951721 +50.234726 184.344711 -212.832336 +50.234726 220.753220 -212.832336 +50.252762 220.753220 -138.210876 +50.252762 184.344711 -138.210876 +0.434303 184.344711 -212.451965 +0.452232 184.344711 -137.830383 +0.452332 220.753220 -137.830383 +1.531166 220.753220 -212.460266 +0.434303 220.753220 -212.451965 +50.234741 221.386520 -212.832458 +50.234741 257.795135 -212.832458 +50.252762 257.795135 -138.210876 +50.252762 221.386520 -138.210876 +0.434402 221.386520 -212.452087 +0.452332 221.386520 -137.830383 +0.452332 257.795135 -137.830383 +1.531174 257.795135 -212.460388 +0.434402 257.795135 -212.452087 +0.464661 184.344711 -212.832458 +0.464661 220.753220 -212.832458 +0.482689 220.753220 -138.210754 +0.482689 184.344711 -138.210754 +-49.335667 184.344711 -212.451843 +-49.317738 184.344711 -137.830383 +-49.317638 220.753220 -137.830383 +-48.238800 220.753220 -212.460266 +-49.335667 220.753220 -212.451843 +0.464760 221.386520 -212.832458 +0.464760 257.795135 -212.832458 +0.482788 257.795135 -138.210876 +0.482788 221.386520 -138.210876 +-49.335667 221.386520 -212.452087 +-49.317638 221.386520 -137.830505 +-49.317638 257.795135 -137.830505 +-48.238800 257.795135 -212.460266 +-49.335667 257.795135 -212.452087 +0.464760 258.270355 -212.832458 +0.464760 294.678894 -212.832458 +0.482788 294.678894 -138.210999 +0.482788 258.270355 -138.210999 +-49.335663 258.270355 -212.452209 +-49.317635 258.270355 -137.830627 +-49.317539 294.678894 -137.830627 +-48.238705 294.678894 -212.460388 +-49.335663 294.678894 -212.452209 +50.234772 184.344696 -288.036194 +50.234772 220.753220 -288.036194 +50.252701 220.753220 -213.414612 +50.252701 184.344711 -213.414612 +0.434341 184.344696 -287.655701 +0.452271 184.344711 -213.034119 +0.452370 220.753220 -213.034119 +1.531113 220.753220 -287.664124 +0.434341 220.753220 -287.655701 +50.234772 221.386520 -288.036194 +50.234772 257.795135 -288.036194 +50.252808 257.795135 -213.414612 +50.252808 221.386520 -213.414612 +0.434349 221.386520 -287.655823 +0.452370 221.386520 -213.034119 +0.452370 257.795135 -213.034241 +1.531212 257.795135 -287.664124 +0.434349 257.795135 -287.655823 +0.464699 184.344696 -288.036072 +0.464699 220.753220 -288.036072 +0.482727 220.753220 -213.414490 +0.482727 184.344711 -213.414490 +-49.335728 184.344696 -287.655701 +-49.317699 184.344711 -213.034119 +-49.317600 220.753220 -213.034119 +-48.238861 220.753220 -287.664001 +-49.335728 220.753220 -287.655701 +-15.810349 184.344711 25.065125 +-15.810349 220.753235 25.065125 +58.811157 220.753235 25.047119 +58.811157 184.344711 25.047119 +-15.429932 184.344727 74.865540 +59.191650 184.344727 74.847656 +59.191650 220.753235 74.847534 +-15.438255 220.753235 73.768677 +-15.429932 220.753235 74.865540 +-15.810364 184.344727 74.835205 +-15.810364 220.753235 74.835205 +58.811218 220.753235 74.817200 +58.811218 184.344727 74.817200 +-15.429863 184.344727 124.635559 +59.191635 184.344727 124.617615 +59.191635 220.753235 124.617493 +-15.438271 220.753235 123.538635 +-15.429863 220.753235 124.635559 +-15.810448 221.386536 74.835083 +-15.810448 257.795135 74.835083 +58.811127 257.795135 74.817078 +58.811127 221.386536 74.817078 +-15.430031 221.386536 124.635559 +59.191559 221.386536 124.617493 +59.191559 257.795135 124.617493 +-15.438271 257.795135 123.538635 +-15.430031 257.795135 124.635559 +-91.014145 184.344711 25.065063 +-91.014145 220.753235 25.065063 +-16.392563 220.753235 25.047180 +-16.392563 184.344711 25.047180 +-90.633644 184.344727 74.865540 +-16.012062 184.344727 74.847595 +-16.012062 220.753235 74.847473 +-90.642044 220.753235 73.768738 +-90.633644 220.753235 74.865540 +-91.014145 221.386536 25.065063 +-91.014145 257.795135 25.065063 +-16.392555 257.795135 25.047058 +-16.392555 221.386536 25.047058 +-90.633728 221.386536 74.865540 +-16.012138 221.386536 74.847473 +-16.012138 257.795135 74.847473 +-90.642044 257.795135 73.768616 +-90.633728 257.795135 74.865540 +-91.014221 258.270386 25.065063 +-91.014221 294.678894 25.065063 +-16.392555 294.678894 25.047058 +-16.392555 258.270386 25.047058 +-90.633812 258.270386 74.865479 +-16.012222 258.270386 74.847473 +-16.012222 294.678894 74.847473 +-90.642044 294.678894 73.768616 +-90.633812 294.678894 74.865479 +-91.014076 184.344727 74.835144 +-91.014076 220.753235 74.835144 +-16.392494 220.753235 74.817139 +-16.392494 184.344727 74.817139 +-90.633659 184.344727 124.635559 +-16.012077 184.344727 124.617554 +-16.012077 220.753235 124.617493 +-90.641983 220.753235 123.538696 +-90.633659 220.753235 124.635559 +-91.014160 221.386536 74.835144 +-91.014160 257.795135 74.835144 +-16.392662 257.795135 74.817139 +-16.392662 221.386536 74.817139 +-90.633827 221.386536 124.635498 +-16.012161 221.386536 124.617554 +-16.012161 257.795135 124.617432 +-90.642059 257.795135 123.538635 +-90.633827 257.795135 124.635498 +-91.014244 258.270386 74.835144 +-91.014244 294.678894 74.835144 +-16.392654 294.678894 74.817017 +-16.392654 258.270386 74.817017 +-90.633827 258.270386 124.635498 +-16.012238 258.270386 124.617432 +-16.012238 294.678894 124.617371 +-90.642059 294.678894 123.538635 +-90.633827 294.678894 124.635498 +-91.014389 295.428864 25.065063 +-91.014389 331.837463 25.065063 +-16.392555 331.837463 25.046936 +-16.392555 295.428864 25.046936 +-90.633888 295.428864 74.865417 +-16.012306 295.428864 74.847412 +-16.012306 331.837463 74.847412 +-90.642044 331.837463 73.768555 +-90.633888 331.837463 74.865417 +50.234726 184.344727 207.836487 +50.234726 220.753265 207.836487 +50.252762 220.753265 282.458008 +50.252762 184.344742 282.458008 +0.434303 184.344727 208.216919 +0.452232 184.344742 282.838501 +0.452332 220.753265 282.838501 +1.531166 220.753265 208.208618 +0.434303 220.753265 208.216919 +50.234741 221.386566 207.836426 +50.234741 257.795166 207.836426 +50.252762 257.795166 282.458008 +50.252762 221.386566 282.458008 +0.434402 221.386566 208.216858 +0.452332 221.386566 282.838501 +0.452332 257.795166 282.838501 +1.531174 257.795166 208.208496 +0.434402 257.795166 208.216858 +0.464661 184.344727 207.836487 +0.464661 220.753265 207.836487 +0.482689 220.753265 282.458069 +0.482689 184.344742 282.458069 +-49.335667 184.344727 208.216980 +-49.317738 184.344742 282.838501 +-49.317638 220.753265 282.838501 +-48.238800 220.753265 208.208557 +-49.335667 220.753265 208.216980 +0.464760 221.386566 207.836426 +0.464760 257.795166 207.836426 +0.482788 257.795166 282.457947 +0.482788 221.386566 282.458008 +-49.335667 221.386566 208.216797 +-49.317638 221.386566 282.838440 +-49.317638 257.795166 282.838379 +-48.238800 257.795166 208.208557 +-49.335667 257.795166 208.216797 +0.464760 258.270386 207.836426 +0.464760 294.678925 207.836426 +0.482788 294.678925 282.457886 +0.482788 258.270386 282.457886 +-49.335663 258.270386 208.216736 +-49.317635 258.270386 282.838318 +-49.317539 294.678925 282.838318 +-48.238705 294.678925 208.208496 +-49.335663 294.678925 208.216736 +50.234772 184.344727 132.632690 +50.234772 220.753265 132.632690 +50.252701 220.753265 207.254272 +50.252701 184.344727 207.254272 +0.434341 184.344727 133.013184 +0.452271 184.344727 207.634766 +0.452370 220.753265 207.634766 +1.531113 220.753265 133.004822 +0.434341 220.753265 133.013184 +50.234772 221.386566 132.632690 +50.234772 257.795166 132.632690 +50.252808 257.795166 207.254272 +50.252808 221.386566 207.254272 +0.434349 221.386566 133.013123 +0.452370 221.386566 207.634705 +0.452370 257.795166 207.634705 +1.531212 257.795166 133.004822 +0.434349 257.795166 133.013123 +50.234772 258.270386 132.632629 +50.234772 294.678925 132.632629 +50.252808 294.678925 207.254272 +50.252808 258.270386 207.254272 +0.434349 258.270386 133.013000 +0.452377 258.270386 207.634644 +0.452377 294.678925 207.634644 +1.531212 294.678925 133.004822 +0.434349 294.678925 133.013000 +0.464699 184.344727 132.632751 +0.464699 220.753265 132.632751 +0.482727 220.753265 207.254333 +0.482727 184.344727 207.254333 +-49.335728 184.344727 133.013184 +-49.317699 184.344727 207.634766 +-49.317600 220.753265 207.634766 +-48.238861 220.753265 133.004883 +-49.335728 220.753265 133.013184 +0.464706 221.386566 132.632690 +0.464706 257.795166 132.632690 +0.482735 257.795166 207.254211 +0.482735 221.386566 207.254211 +-49.335625 221.386566 133.013000 +-49.317696 221.386566 207.634705 +-49.317596 257.795166 207.634705 +-48.238762 257.795166 133.004761 +-49.335625 257.795166 133.013000 +0.464706 258.270386 132.632629 +0.464706 294.678925 132.632629 +0.482834 294.678925 207.254211 +0.482834 258.270386 207.254211 +-49.335625 258.270386 133.013000 +-49.317596 258.270386 207.634583 +-49.317497 294.678925 207.634583 +-48.238762 294.678925 133.004761 +-49.335625 294.678925 133.013000 +0.464806 295.428894 132.632507 +0.464806 331.837494 132.632507 +0.482834 331.837494 207.254028 +0.482834 295.428894 207.254028 +-49.335526 295.428894 133.012939 +-49.317497 295.428894 207.634521 +-49.317497 331.837494 207.634521 +-48.238663 331.837494 133.004700 +-49.335526 331.837494 133.012939 +50.234726 184.108826 364.416748 +50.234726 220.517365 364.416748 +50.252762 220.517365 439.038269 +50.252762 184.108841 439.038269 +0.434303 184.108826 364.797180 +0.452232 184.108841 439.418762 +0.452332 220.517365 439.418762 +1.531166 220.517365 364.788879 +0.434303 220.517365 364.797180 +0.464661 184.108826 364.416748 +0.464661 220.517365 364.416748 +0.482689 220.517365 439.038330 +0.482689 184.108841 439.038330 +-49.335667 184.108826 364.797241 +-49.317738 184.108841 439.418762 +-49.317638 220.517365 439.418762 +-48.238800 220.517365 364.788818 +-49.335667 220.517365 364.797241 +0.464760 221.150665 364.416687 +0.464760 257.559265 364.416687 +0.482788 257.559265 439.038239 +0.482788 221.150665 439.038239 +-49.335667 221.150665 364.797058 +-49.317638 221.150665 439.418671 +-49.317638 257.559265 439.418671 +-48.238800 257.559265 364.788818 +-49.335667 257.559265 364.797058 +50.234772 184.108826 289.212952 +50.234772 220.517365 289.212952 +50.252701 220.517365 363.834534 +50.252701 184.108826 363.834534 +0.434341 184.108826 289.593445 +0.452271 184.108826 364.215027 +0.452370 220.517365 364.215027 +1.531113 220.517365 289.585083 +0.434341 220.517365 289.593445 +50.234772 221.150665 289.212952 +50.234772 257.559265 289.212952 +50.252808 257.559265 363.834534 +50.252808 221.150665 363.834534 +0.434349 221.150665 289.593384 +0.452370 221.150665 364.214966 +0.452370 257.559265 364.214966 +1.531212 257.559265 289.585083 +0.434349 257.559265 289.593384 +0.464699 184.108826 289.213013 +0.464699 220.517365 289.213013 +0.482727 220.517365 363.834595 +0.482727 184.108826 363.834595 +-49.335728 184.108826 289.593445 +-49.317699 184.108826 364.215027 +-49.317600 220.517365 364.215027 +-48.238861 220.517365 289.585144 +-49.335728 220.517365 289.593445 +0.464706 221.150665 289.212952 +0.464706 257.559265 289.212952 +0.482735 257.559265 363.834473 +0.482735 221.150665 363.834473 +-49.335625 221.150665 289.593323 +-49.317696 221.150665 364.214966 +-49.317596 257.559265 364.214966 +-48.238762 257.559265 289.585022 +-49.335625 257.559265 289.593262 +85.526978 480.048401 -90.746643 +85.526978 522.092957 -90.746643 +85.547791 522.092957 -4.573608 +85.547791 480.048431 -4.573608 +28.017448 480.048401 -90.307190 +28.038155 480.048431 -4.134277 +28.038261 522.092957 -4.134277 +29.284103 522.092957 -90.316895 +28.017448 522.092957 -90.307190 +85.526978 523.448792 -90.746643 +85.526978 565.493408 -90.746643 +85.547791 565.493408 -4.573608 +85.547791 523.448792 -4.573608 +28.017448 523.448792 -90.307190 +28.038155 523.448792 -4.134277 +28.038261 565.493408 -4.134338 +29.284103 565.493408 -90.316895 +28.017448 565.493408 -90.307190 +85.526978 567.092346 -90.746643 +85.526978 609.136902 -90.746643 +85.547791 609.136902 -4.573608 +85.547791 567.092407 -4.573608 +28.017448 567.092346 -90.307190 +28.038155 567.092407 -4.134338 +28.038261 609.136902 -4.134338 +29.284103 609.136902 -90.316895 +28.017448 609.136902 -90.307190 +26.951828 480.048401 -90.746582 +26.951828 522.092957 -90.746582 +26.972641 522.092957 -4.573547 +26.972641 480.048431 -4.573547 +-30.557693 480.048401 -90.307190 +-30.536880 480.048431 -4.134277 +-30.536880 522.092957 -4.134277 +-29.291031 522.092957 -90.316895 +-30.557693 522.092957 -90.307190 +26.951828 523.448792 -90.746582 +26.951828 565.493408 -90.746582 +26.972641 565.493408 -4.573608 +26.972641 523.448792 -4.573547 +-30.557693 523.448792 -90.307190 +-30.536880 523.448792 -4.134277 +-30.536880 565.493408 -4.134277 +-29.291031 565.493408 -90.316895 +-30.557693 565.493408 -90.307190 +26.951828 567.092346 -90.746582 +26.951828 609.136902 -90.746582 +26.972641 609.136902 -4.573608 +26.972641 567.092407 -4.573608 +-30.557693 567.092346 -90.307190 +-30.536880 567.092407 -4.134277 +-30.536880 609.136902 -4.134277 +-29.291031 609.136902 -90.316895 +-30.557693 609.136902 -90.307190 +52.878479 610.492737 -90.746521 +52.878479 652.537292 -90.746521 +52.899307 652.537292 -4.573608 +52.899307 610.492737 -4.573608 +-4.631035 610.492737 -90.307190 +-4.610222 610.492737 -4.134338 +-4.610222 652.537292 -4.134338 +-3.364380 652.537292 -90.316833 +-4.631035 652.537292 -90.307190 +-4.233650 480.048401 -208.807556 +-4.233650 522.092957 -208.807556 +81.939331 522.092957 -208.828308 +81.939331 480.048401 -208.828308 +-3.794334 480.048401 -151.297913 +82.378632 480.048401 -151.318787 +82.378632 522.092957 -151.318787 +-3.803947 522.092957 -152.564636 +-3.794334 522.092957 -151.298035 +-4.233582 480.048401 -150.232239 +-4.233582 522.092957 -150.232239 +81.939392 522.092957 -150.253113 +81.939392 480.048401 -150.253113 +-3.794266 480.048401 -92.722778 +82.378723 480.048401 -92.743591 +82.378723 522.092957 -92.743591 +-3.803879 522.092957 -93.989441 +-3.794266 522.092957 -92.722839 +-4.233582 523.448792 -150.232239 +-4.233582 565.493408 -150.232239 +81.939392 565.493408 -150.253113 +81.939392 523.448792 -150.253113 +-3.794266 523.448792 -92.722778 +82.378723 523.448792 -92.743591 +82.378723 565.493408 -92.743591 +-3.803879 565.493408 -93.989441 +-3.794266 565.493408 -92.722839 +-91.382088 480.048401 -208.807556 +-91.382088 522.092957 -208.807556 +-5.209229 522.092957 -208.828308 +-5.209229 480.048401 -208.828308 +-90.942780 480.048401 -151.298035 +-4.769806 480.048401 -151.318787 +-4.769798 522.092957 -151.318787 +-90.952393 522.092957 -152.564636 +-90.942780 522.092957 -151.298035 +-91.382133 480.048401 -150.232361 +-91.382133 522.092957 -150.232361 +-5.209160 522.092957 -150.253113 +-5.209160 480.048401 -150.252991 +-90.942703 480.048401 -92.722778 +-4.769730 480.048401 -92.743530 +-4.769730 522.092957 -92.743591 +-90.952324 522.092957 -93.989380 +-90.942703 522.092957 -92.722778 +-91.382133 523.448792 -150.232361 +-91.382133 565.493408 -150.232361 +-5.209160 565.493408 -150.253113 +-5.209160 523.448792 -150.253113 +-90.942703 523.448792 -92.722778 +-4.769730 523.448792 -92.743530 +-4.769730 565.493408 -92.743591 +-90.952324 565.493408 -93.989380 +-90.942703 565.493408 -92.722778 +-91.382133 567.092346 -150.232361 +-91.382133 609.136902 -150.232361 +-5.209160 609.136902 -150.253113 +-5.209160 567.092346 -150.253113 +-90.942703 567.092346 -92.722778 +-4.769730 567.092346 -92.743530 +-4.769730 609.136902 -92.743591 +-90.952324 609.136902 -93.989380 +-90.942703 609.136902 -92.722778 +-91.382057 610.492737 -134.833191 +-91.382057 652.537292 -134.833191 +-5.209091 652.537292 -134.854004 +-5.209091 610.492737 -134.854004 +-90.942741 610.492737 -77.323669 +-4.769661 610.492737 -77.344360 +-4.769661 652.537292 -77.344482 +-90.952354 652.537292 -78.590271 +-90.942741 652.537292 -77.323669 +-30.522522 480.048401 -90.746521 +-30.522522 522.092957 -90.746521 +-30.501816 522.092957 -4.573608 +-30.501816 480.048431 -4.573608 +-88.032043 480.048401 -90.307190 +-88.011345 480.048431 -4.134216 +-88.011230 522.092957 -4.134216 +-86.765388 522.092957 -90.316772 +-88.032043 522.092957 -90.307190 +-30.522522 523.448792 -90.746521 +-30.522522 565.493408 -90.746521 +-30.501816 565.493408 -4.573608 +-30.501816 523.448792 -4.573608 +-88.032043 523.448792 -90.307190 +-88.011345 523.448792 -4.134216 +-88.011230 565.493408 -4.134216 +-86.765388 565.493408 -90.316833 +-88.032043 565.493408 -90.307190 +-30.522522 567.092346 -90.746521 +-30.522522 609.136902 -90.746521 +-30.501816 609.136902 -4.573608 +-30.501816 567.092407 -4.573608 +-88.032043 567.092346 -90.307190 +-88.011345 567.092407 -4.134216 +-88.011230 609.136902 -4.134216 +-86.765388 609.136902 -90.316833 +-88.032043 609.136902 -90.307190 +91.900269 480.451111 326.717590 +91.900269 522.495667 326.717590 +91.921082 522.495667 412.890625 +91.921082 480.451111 412.890625 +34.390747 480.451111 327.157043 +34.411438 480.451111 413.329926 +34.411560 522.495667 413.329926 +35.657394 522.495667 327.147339 +34.390747 522.495667 327.157043 +33.325119 480.451111 326.717651 +33.325119 522.495667 326.717651 +33.345932 522.495667 412.890656 +33.345932 480.451111 412.890656 +-24.184402 480.451111 327.157043 +-24.163589 480.451111 413.329956 +-24.163589 522.495667 413.329956 +-22.917740 522.495667 327.147339 +-24.184402 522.495667 327.157043 +2.139641 480.451111 208.656738 +2.139641 522.495667 208.656738 +88.312622 522.495667 208.635925 +88.312622 480.451111 208.635925 +2.578957 480.451111 266.166260 +88.751923 480.451111 266.145447 +88.751923 522.495667 266.145447 +2.569344 522.495667 264.899536 +2.578957 522.495667 266.166138 +2.139641 523.851501 208.656738 +2.139641 565.896057 208.656738 +88.312622 565.896057 208.635925 +88.312622 523.851501 208.635925 +2.578957 523.851501 266.166260 +88.751923 523.851501 266.145447 +88.751923 565.896057 266.145447 +2.569344 565.896057 264.899536 +2.578957 565.896057 266.166138 +2.139709 480.451111 267.231934 +2.139709 522.495667 267.231934 +88.312683 522.495667 267.211121 +88.312683 480.451111 267.211121 +2.579025 480.451111 324.741455 +88.752014 480.451111 324.720642 +88.752014 522.495667 324.720642 +2.569412 522.495667 323.474792 +2.579025 522.495667 324.741394 +-85.008797 480.451111 208.656677 +-85.008797 522.495667 208.656677 +1.164063 522.495667 208.635864 +1.164063 480.451111 208.635864 +-84.569489 480.451111 266.166199 +1.603485 480.451111 266.145508 +1.603493 522.495667 266.145386 +-84.579102 522.495667 264.899597 +-84.569489 522.495667 266.166199 +-85.008797 523.851501 208.656677 +-85.008797 565.896057 208.656677 +1.164063 565.896057 208.635864 +1.164063 523.851501 208.635864 +-84.569489 523.851501 266.166199 +1.603485 523.851501 266.145508 +1.603493 565.896057 266.145386 +-84.579102 565.896057 264.899597 +-84.569489 565.896057 266.166199 +-85.008797 567.495056 208.656677 +-85.008797 609.539612 208.656677 +1.164063 609.539612 208.635864 +1.164063 567.495056 208.635864 +-84.569489 567.495056 266.166199 +1.603485 567.495056 266.145508 +1.603493 609.539612 266.145386 +-84.579102 609.539612 264.899597 +-84.569489 609.539612 266.166199 +-85.008842 480.451111 267.231934 +-85.008842 522.495667 267.231873 +1.164131 522.495667 267.211182 +1.164131 480.451111 267.211182 +-84.569412 480.451111 324.741455 +1.603561 480.451111 324.720703 +1.603561 522.495667 324.720642 +-84.579033 522.495667 323.474854 +-84.569412 522.495667 324.741455 +-85.008842 523.851501 267.231873 +-85.008842 565.896057 267.231873 +1.164131 565.896057 267.211182 +1.164131 523.851501 267.211182 +-84.569412 523.851501 324.741455 +1.603561 523.851501 324.720703 +1.603561 565.896057 324.720642 +-84.579033 565.896057 323.474854 +-84.569412 565.896057 324.741455 +-24.149231 480.451111 326.717712 +-24.149231 522.495667 326.717712 +-24.128525 522.495667 412.890625 +-24.128525 480.451111 412.890625 +-81.658752 480.451111 327.157043 +-81.638054 480.451111 413.330048 +-81.637939 522.495667 413.330048 +-80.392097 522.495667 327.147461 +-81.658752 522.495667 327.157043 +-24.149231 523.851501 326.717712 +-24.149231 565.896057 326.717712 +-24.128525 565.896057 412.890625 +-24.128525 523.851501 412.890625 +-81.658752 523.851501 327.157043 +-81.638054 523.851501 413.330048 +-81.637939 565.896057 413.330048 +-80.392097 565.896057 327.147400 +-81.658752 565.896057 327.157043 +2.139641 271.101929 469.782440 +2.139641 313.146515 469.782440 +88.312622 313.146515 469.761597 +88.312622 271.101929 469.761597 +2.578957 271.101959 527.291992 +88.751923 271.101959 527.271179 +88.751923 313.146515 527.271179 +2.569336 313.146515 526.025269 +2.578957 313.146515 527.291870 +91.900269 184.057999 587.843201 +91.900269 226.102570 587.843201 +91.921082 226.102570 674.016235 +91.921082 184.057999 674.016235 +34.390747 184.057999 588.282593 +34.411438 184.057999 674.455566 +34.411560 226.102570 674.455566 +35.657394 226.102570 588.272949 +34.390747 226.102570 588.282593 +33.325119 184.057999 587.843262 +33.325119 226.102570 587.843262 +33.345932 226.102570 674.016296 +33.345932 184.057999 674.016296 +-24.184402 184.057999 588.282654 +-24.163589 184.057999 674.455566 +-24.163589 226.102570 674.455566 +-22.917740 226.102570 588.272949 +-24.184402 226.102570 588.282654 +2.139641 184.057999 469.782349 +2.139641 226.102554 469.782349 +88.312622 226.102554 469.761536 +88.312622 184.057999 469.761536 +2.578957 184.057999 527.291870 +88.751923 184.057999 527.271057 +88.751923 226.102554 527.271057 +2.569344 226.102554 526.025146 +2.578957 226.102554 527.291809 +2.139641 227.458389 469.782349 +2.139641 269.502960 469.782318 +88.312622 269.502960 469.761505 +88.312622 227.458389 469.761536 +2.578957 227.458389 527.291870 +88.751923 227.458389 527.271057 +88.751923 269.502960 527.271057 +2.569344 269.502960 526.025146 +2.578957 269.502960 527.291809 +2.139709 184.057999 528.357544 +2.139709 226.102554 528.357544 +88.312683 226.102554 528.336731 +88.312683 184.057999 528.336731 +2.579025 184.057999 585.867126 +88.752014 184.057999 585.846252 +88.752014 226.102570 585.846252 +2.569412 226.102570 584.600403 +2.579025 226.102570 585.867004 +-85.008797 184.057999 469.782288 +-85.008797 226.102554 469.782288 +1.164063 226.102554 469.761475 +1.164063 184.057999 469.761475 +-84.569489 184.057999 527.291870 +1.603485 184.057999 527.271118 +1.603493 226.102554 527.270996 +-84.579102 226.102554 526.025208 +-84.569489 226.102554 527.291870 +-85.008797 227.458389 469.782288 +-85.008797 269.502960 469.782288 +1.164063 269.502960 469.761475 +1.164063 227.458389 469.761475 +-84.569489 227.458389 527.291870 +1.603485 227.458389 527.271118 +1.603493 269.502960 527.270996 +-84.579102 269.502960 526.025208 +-84.569489 269.502960 527.291870 +-85.008797 271.101929 469.782288 +-85.008797 313.146515 469.782288 +1.164063 313.146515 469.761475 +1.164063 271.101929 469.761475 +-84.569489 271.101959 527.291870 +1.603485 271.101959 527.271118 +1.603493 313.146515 527.270996 +-84.579102 313.146515 526.025208 +-84.569489 313.146515 527.291870 +-85.008842 184.057999 528.357483 +-85.008842 226.102554 528.357483 +1.164131 226.102554 528.336792 +1.164131 184.057999 528.336792 +-84.569412 184.057999 585.867065 +1.603561 184.057999 585.846313 +1.603561 226.102570 585.846252 +-84.579033 226.102570 584.600403 +-84.569412 226.102570 585.867065 +-24.149231 184.057999 587.843323 +-24.149231 226.102570 587.843323 +-24.128525 226.102570 674.016235 +-24.128525 184.057999 674.016235 +-81.658752 184.057999 588.282654 +-81.638054 184.057999 674.455688 +-81.637939 226.102570 674.455688 +-80.392097 226.102570 588.273071 +-81.658752 226.102570 588.282654 +-24.149231 227.458389 587.843323 +-24.149231 269.502960 587.843323 +-24.128525 269.502960 674.016235 +-24.128525 227.458389 674.016235 +-81.658752 227.458389 588.282654 +-81.638054 227.458389 674.455688 +-81.637939 269.502960 674.455688 +-80.392097 269.502960 588.273071 +-81.658752 269.502960 588.282654 +91.900269 184.057999 795.948608 +91.900269 226.102570 795.948608 +91.921082 226.102570 882.121582 +91.921082 184.057999 882.121582 +34.390747 184.057999 796.388000 +34.411438 184.057999 882.560913 +34.411560 226.102570 882.560913 +35.657394 226.102570 796.378296 +34.390747 226.102570 796.388000 +91.900269 227.458389 795.948608 +91.900269 269.502960 795.948547 +91.921082 269.502960 882.121582 +91.921082 227.458389 882.121582 +34.390747 227.458389 796.388000 +34.411438 227.458389 882.560913 +34.411560 269.502960 882.560913 +35.657394 269.502960 796.378296 +34.390747 269.502960 796.388000 +33.325119 184.057999 795.948608 +33.325119 226.102570 795.948608 +33.345932 226.102570 882.121643 +33.345932 184.057999 882.121643 +-24.184402 184.057999 796.388000 +-24.163589 184.057999 882.560913 +-24.163589 226.102570 882.560913 +-22.917740 226.102570 796.378296 +-24.184402 226.102570 796.388000 +33.325119 227.458389 795.948608 +33.325119 269.502960 795.948608 +33.345932 269.502960 882.121582 +33.345932 227.458389 882.121643 +-24.184402 227.458389 796.388000 +-24.163589 227.458389 882.560913 +-24.163589 269.502960 882.560913 +-22.917740 269.502960 796.378296 +-24.184402 269.502960 796.388000 +2.139641 184.057999 677.887695 +2.139641 226.102554 677.887695 +88.312622 226.102554 677.866882 +88.312622 184.057999 677.866882 +2.578957 184.057999 735.397217 +88.751923 184.057999 735.376404 +88.751923 226.102554 735.376404 +2.569344 226.102554 734.130554 +2.578957 226.102554 735.397095 +2.139709 184.057999 736.462891 +2.139709 226.102554 736.462891 +88.312683 226.102554 736.442078 +88.312683 184.057999 736.442078 +2.579025 184.057999 793.972412 +88.752014 184.057999 793.951599 +88.752014 226.102570 793.951599 +2.569412 226.102570 792.705750 +2.579025 226.102570 793.972351 +-85.008797 184.057999 677.887634 +-85.008797 226.102554 677.887634 +1.164063 226.102554 677.866821 +1.164063 184.057999 677.866821 +-84.569489 184.057999 735.397156 +1.603485 184.057999 735.376465 +1.603493 226.102554 735.376343 +-84.579102 226.102554 734.130554 +-84.569489 226.102554 735.397156 +-85.008842 184.057999 736.462830 +-85.008842 226.102554 736.462830 +1.164131 226.102554 736.442139 +1.164131 184.057999 736.442139 +-84.569412 184.057999 793.972412 +1.603561 184.057999 793.951660 +1.603561 226.102570 793.951599 +-84.579033 226.102570 792.705811 +-84.569412 226.102570 793.972412 +-85.008842 227.458389 736.462830 +-85.008842 269.502960 736.462830 +1.164131 269.502960 736.442139 +1.164131 227.458389 736.442139 +-84.569412 227.458389 793.972412 +1.603561 227.458389 793.951660 +1.603561 269.502960 793.951599 +-84.579033 269.502960 792.705811 +-84.569412 269.502960 793.972412 +-24.149231 184.057999 795.948669 +-24.149231 226.102570 795.948669 +-24.128525 226.102570 882.121582 +-24.128525 184.057999 882.121582 +-81.658752 184.057999 796.388000 +-81.638054 184.057999 882.561035 +-81.637939 226.102570 882.561035 +-80.392097 226.102570 796.378357 +-81.658752 226.102570 796.388000 +-24.149231 227.458389 795.948669 +-24.149231 269.502960 795.948669 +-24.128525 269.502960 882.121582 +-24.128525 227.458389 882.121582 +-81.658752 227.458389 796.388000 +-81.638054 227.458389 882.561035 +-81.637939 269.502960 882.560974 +-80.392097 269.502960 796.378357 +-81.658752 269.502960 796.388000 +-24.149231 271.101959 795.948669 +-24.149231 313.146515 795.948669 +-24.128525 313.146515 882.121582 +-24.128525 271.101959 882.121582 +-81.658752 271.101959 796.388000 +-81.638054 271.101959 882.560974 +-81.637939 313.146515 882.560974 +-80.392097 313.146515 796.378357 +-81.658752 313.146515 796.388000 +-77.193710 323.720703 -756.664978 +-33.610245 323.720703 -756.664978 +-77.193710 323.720703 -816.330750 +-33.610245 323.720703 -816.330750 +-77.193710 207.784164 -756.664978 +-33.610245 207.784164 -756.664978 +-77.193710 207.784164 -816.330750 +-33.610245 207.784164 -816.330750 +-75.061211 183.350571 -759.405579 +-35.742756 183.350571 -759.405579 +-75.061211 183.350571 -813.590149 +-35.742756 183.350571 -813.590149 +-75.692474 323.720703 -814.756287 +-75.692474 323.720703 -758.239441 +-35.111488 323.720703 -758.239441 +-35.111488 323.720703 -814.756287 +-73.638229 290.395111 -811.888855 +-73.638229 290.395111 -760.920227 +-37.165726 290.395111 -760.920227 +-37.165726 290.395111 -811.888855 +-73.250549 302.476257 -817.289246 +-29.667084 302.476257 -817.289246 +-73.250549 302.476257 -876.955017 +-29.667084 302.476257 -876.955017 +-73.250549 207.739456 -817.289246 +-29.667084 207.739456 -817.289246 +-73.250549 207.739456 -876.955017 +-29.667084 207.739456 -876.955017 +-71.118050 183.305862 -820.029846 +-31.799591 183.305862 -820.029846 +-71.118050 183.305862 -874.214417 +-31.799591 183.305862 -874.214417 +-71.749313 302.476257 -875.380554 +-71.749313 302.476257 -818.863708 +-31.168327 302.476257 -818.863708 +-31.168327 302.476257 -875.380554 +-69.695068 269.171295 -872.513123 +-69.695068 269.171295 -821.544495 +-33.222565 269.171295 -821.544495 +-33.222565 269.171295 -872.513123 +-26.671051 270.610443 -817.289246 +16.912415 270.610443 -817.289246 +-26.671051 270.610443 -876.955017 +16.912415 270.610443 -876.955017 +-26.671051 207.739456 -817.289246 +16.912415 207.739456 -817.289246 +-26.671051 207.739456 -876.955017 +16.912415 207.739456 -876.955017 +-24.538544 183.305862 -820.029846 +14.779907 183.305862 -820.029846 +-24.538544 183.305862 -874.214417 +14.779907 183.305862 -874.214417 +-25.169815 270.610443 -875.380554 +-25.169815 270.610443 -818.863708 +15.411171 270.610443 -818.863708 +15.411171 270.610443 -875.380554 +-23.115570 237.339645 -872.513123 +-23.115570 237.339661 -821.544495 +13.356934 237.339661 -821.544495 +13.356934 237.339645 -872.513123 +-28.594971 313.097931 -755.184143 +14.988495 313.097931 -755.184143 +-28.594971 313.097931 -814.849915 +14.988495 313.097931 -814.849915 +-28.594971 207.784164 -755.184143 +14.988495 207.784164 -755.184143 +-28.594971 207.784164 -814.849915 +14.988495 207.784164 -814.849915 +-26.462471 183.350571 -757.924744 +12.855988 183.350571 -757.924744 +-26.462471 183.350571 -812.109314 +12.855988 183.350571 -812.109314 +-27.093735 313.097931 -813.275452 +-27.093735 313.097931 -756.758606 +13.487251 313.097931 -756.758606 +13.487251 313.097931 -813.275452 +-25.039490 279.802094 -810.408020 +-25.039490 279.802094 -759.439392 +11.433014 279.802094 -759.439392 +11.433014 279.802094 -810.408020 +-77.193710 621.170898 -499.427917 +-33.610245 621.170898 -499.427917 +-77.193710 621.170898 -559.093689 +-33.610245 621.170898 -559.093689 +-77.193710 505.234375 -499.427917 +-33.610245 505.234375 -499.427917 +-77.193710 505.234375 -559.093689 +-33.610245 505.234375 -559.093689 +-75.061211 480.800781 -502.168518 +-35.742756 480.800781 -502.168518 +-75.061211 480.800781 -556.353088 +-35.742756 480.800781 -556.353088 +-75.692474 621.170898 -557.519226 +-75.692474 621.170898 -501.002380 +-35.111488 621.170898 -501.002380 +-35.111488 621.170898 -557.519226 +-73.638229 587.845337 -554.651794 +-73.638229 587.845337 -503.683167 +-37.165726 587.845337 -503.683167 +-37.165726 587.845337 -554.651794 +-73.250549 599.926453 -560.052185 +-29.667084 599.926453 -560.052185 +-73.250549 599.926453 -619.717957 +-29.667084 599.926453 -619.717957 +-73.250549 505.189667 -560.052185 +-29.667084 505.189667 -560.052185 +-73.250549 505.189667 -619.717957 +-29.667084 505.189667 -619.717957 +-71.118050 480.756073 -562.792786 +-31.799591 480.756073 -562.792786 +-71.118050 480.756073 -616.977356 +-31.799591 480.756073 -616.977356 +-71.749313 599.926453 -618.143494 +-71.749313 599.926453 -561.626648 +-31.168327 599.926453 -561.626648 +-31.168327 599.926453 -618.143494 +-69.695068 566.621460 -615.276062 +-69.695068 566.621460 -564.307434 +-33.222565 566.621460 -564.307434 +-33.222565 566.621460 -615.276062 +-26.671051 568.060669 -560.052185 +16.912415 568.060669 -560.052185 +-26.671051 568.060669 -619.717957 +16.912415 568.060669 -619.717957 +-26.671051 505.189667 -560.052185 +16.912415 505.189667 -560.052185 +-26.671051 505.189667 -619.717957 +16.912415 505.189667 -619.717957 +-24.538544 480.756073 -562.792786 +14.779907 480.756073 -562.792786 +-24.538544 480.756073 -616.977356 +14.779907 480.756073 -616.977356 +-25.169815 568.060669 -618.143494 +-25.169815 568.060669 -561.626648 +15.411171 568.060669 -561.626648 +15.411171 568.060669 -618.143494 +-23.115570 534.789856 -615.276062 +-23.115570 534.789856 -564.307434 +13.356934 534.789856 -564.307434 +13.356934 534.789856 -615.276062 +-28.594971 610.548096 -497.947083 +14.988495 610.548096 -497.947083 +-28.594971 610.548096 -557.612854 +14.988495 610.548096 -557.612854 +-28.594971 505.234375 -497.947083 +14.988495 505.234375 -497.947083 +-28.594971 505.234375 -557.612854 +14.988495 505.234375 -557.612854 +-26.462471 480.800781 -500.687683 +12.855988 480.800781 -500.687683 +-26.462471 480.800781 -554.872253 +12.855988 480.800781 -554.872253 +-27.093735 610.548096 -556.038391 +-27.093735 610.548096 -499.521545 +13.487251 610.548096 -499.521545 +13.487251 610.548096 -556.038391 +-25.039490 577.252319 -553.170959 +-25.039490 577.252319 -502.202332 +11.433014 577.252319 -502.202332 +11.433014 577.252319 -553.170959 +-84.032951 619.746216 -426.448669 +-84.032959 619.746216 -382.865173 +-24.367188 619.746216 -426.448669 +-24.367188 619.746216 -382.865173 +-84.032951 503.809662 -426.448669 +-84.032959 503.809662 -382.865173 +-24.367188 503.809662 -426.448669 +-24.367188 503.809662 -382.865173 +-81.292358 479.376068 -424.316101 +-81.292358 479.376068 -384.997620 +-27.107788 479.376068 -424.316101 +-27.107788 479.376068 -384.997620 +-25.941643 619.746216 -424.947449 +-82.458504 619.746216 -424.947449 +-82.458504 619.746216 -384.366394 +-25.941650 619.746216 -384.366394 +-28.809067 586.420593 -422.893127 +-79.777740 586.420593 -422.893127 +-79.777740 586.420593 -386.420593 +-28.809067 586.420593 -386.420593 +-23.408691 598.501770 -422.505432 +-23.408691 598.501770 -378.922058 +36.257080 598.501770 -422.505432 +36.257080 598.501770 -378.922058 +-23.408691 503.764954 -422.505432 +-23.408691 503.764954 -378.922058 +36.257080 503.764954 -422.505432 +36.257080 503.764954 -378.922058 +-20.668091 479.331360 -420.372986 +-20.668091 479.331360 -381.054504 +33.516479 479.331360 -420.372986 +33.516479 479.331360 -381.054504 +34.682617 598.501770 -421.004211 +-21.834236 598.501770 -421.004211 +-21.834236 598.501770 -380.423279 +34.682617 598.501770 -380.423279 +31.815201 565.196777 -418.950012 +-19.153473 565.196777 -418.950012 +-19.153473 565.196777 -382.477478 +31.815201 565.196777 -382.477478 +-23.408691 566.635925 -375.925964 +-23.408691 566.635925 -332.342468 +36.257080 566.635925 -375.925964 +36.257080 566.635925 -332.342468 +-23.408691 503.764954 -375.925964 +-23.408691 503.764954 -332.342468 +36.257080 503.764954 -375.925964 +36.257080 503.764954 -332.342468 +-20.668091 479.331360 -373.793518 +-20.668091 479.331360 -334.475037 +33.516479 479.331360 -373.793518 +33.516479 479.331360 -334.475037 +34.682617 566.635925 -374.424744 +-21.834236 566.635925 -374.424744 +-21.834236 566.635925 -333.843689 +34.682617 566.635925 -333.843689 +31.815201 533.365173 -372.370544 +-19.153473 533.365173 -372.370544 +-19.153473 533.365173 -335.898010 +31.815201 533.365173 -335.898010 +-85.513794 609.123413 -377.849915 +-85.513802 609.123413 -334.266418 +-25.848022 609.123413 -377.849915 +-25.848022 609.123413 -334.266418 +-85.513794 503.809662 -377.849915 +-85.513802 503.809662 -334.266418 +-25.848022 503.809662 -377.849915 +-25.848022 503.809662 -334.266418 +-82.773193 479.376068 -375.717346 +-82.773193 479.376068 -336.398987 +-28.588623 479.376068 -375.717346 +-28.588623 479.376068 -336.398987 +-27.422485 609.123413 -376.348694 +-83.939339 609.123413 -376.348694 +-83.939339 609.123413 -335.767639 +-27.422485 609.123413 -335.767639 +-30.289902 575.827576 -374.294373 +-81.258575 575.827576 -374.294373 +-81.258575 575.827576 -337.821960 +-30.289909 575.827576 -337.821960 +-77.193710 323.720703 -300.636536 +-33.610245 323.720703 -300.636536 +-77.193710 323.720703 -360.302307 +-33.610245 323.720703 -360.302307 +-77.193710 207.784180 -300.636536 +-33.610245 207.784180 -300.636536 +-77.193710 207.784180 -360.302307 +-33.610245 207.784180 -360.302307 +-75.061211 183.350601 -303.377136 +-35.742756 183.350601 -303.377136 +-75.061211 183.350601 -357.561707 +-35.742756 183.350601 -357.561707 +-75.692474 323.720703 -358.727844 +-75.692474 323.720703 -302.210999 +-35.111488 323.720703 -302.210999 +-35.111488 323.720703 -358.727844 +-73.638229 290.395111 -355.860413 +-73.638229 290.395111 -304.891785 +-37.165726 290.395111 -304.891785 +-37.165726 290.395111 -355.860413 +-73.250549 302.476288 -361.260803 +-29.667084 302.476288 -361.260803 +-73.250549 302.476288 -420.926575 +-29.667084 302.476288 -420.926575 +-73.250549 207.739471 -361.260803 +-29.667084 207.739471 -361.260803 +-73.250549 207.739471 -420.926575 +-29.667084 207.739471 -420.926575 +-71.118050 183.305878 -364.001404 +-31.799591 183.305878 -364.001404 +-71.118050 183.305878 -418.185974 +-31.799591 183.305878 -418.185974 +-71.749313 302.476288 -419.352112 +-71.749313 302.476288 -362.835266 +-31.168327 302.476288 -362.835266 +-31.168327 302.476288 -419.352112 +-69.695068 269.171295 -416.484680 +-69.695068 269.171295 -365.516052 +-33.222565 269.171295 -365.516052 +-33.222565 269.171295 -416.484680 +-26.671051 270.610443 -361.260803 +16.912415 270.610443 -361.260803 +-26.671051 270.610443 -420.926575 +16.912415 270.610443 -420.926575 +-26.671051 207.739471 -361.260803 +16.912415 207.739471 -361.260803 +-26.671051 207.739471 -420.926575 +16.912415 207.739471 -420.926575 +-24.538544 183.305878 -364.001404 +14.779907 183.305878 -364.001404 +-24.538544 183.305878 -418.185974 +14.779907 183.305878 -418.185974 +-25.169815 270.610443 -419.352112 +-25.169815 270.610443 -362.835266 +15.411171 270.610443 -362.835266 +15.411171 270.610443 -419.352112 +-23.115570 237.339661 -416.484680 +-23.115570 237.339676 -365.516052 +13.356934 237.339676 -365.516052 +13.356934 237.339661 -416.484680 +-28.594971 313.097931 -299.155701 +14.988495 313.097931 -299.155701 +-28.594971 313.097931 -358.821472 +14.988495 313.097931 -358.821472 +-28.594971 207.784180 -299.155701 +14.988495 207.784180 -299.155701 +-28.594971 207.784180 -358.821472 +14.988495 207.784180 -358.821472 +-26.462471 183.350601 -301.896301 +12.855988 183.350601 -301.896301 +-26.462471 183.350601 -356.080872 +12.855988 183.350601 -356.080872 +-27.093735 313.097931 -357.247009 +-27.093735 313.097931 -300.730164 +13.487251 313.097931 -300.730164 +13.487251 313.097931 -357.247009 +-25.039490 279.802124 -354.379578 +-25.039490 279.802124 -303.410950 +11.433014 279.802124 -303.410950 +11.433014 279.802124 -354.379578 +-77.193710 323.720734 -8.791321 +-33.610245 323.720734 -8.791321 +-77.193710 323.720734 -68.457092 +-33.610245 323.720734 -68.457092 +-77.193710 207.784195 -8.791321 +-33.610245 207.784195 -8.791321 +-77.193710 207.784195 -68.457092 +-33.610245 207.784195 -68.457092 +-75.061211 183.350616 -11.531921 +-35.742756 183.350616 -11.531921 +-75.061211 183.350616 -65.716492 +-35.742756 183.350616 -65.716492 +-75.692474 323.720734 -66.882629 +-75.692474 323.720734 -10.365784 +-35.111488 323.720734 -10.365784 +-35.111488 323.720734 -66.882629 +-73.638229 290.395142 -64.015198 +-73.638229 290.395142 -13.046570 +-37.165726 290.395142 -13.046570 +-37.165726 290.395142 -64.015198 +-73.250549 302.476288 -69.415588 +-29.667084 302.476288 -69.415588 +-73.250549 302.476288 -129.081360 +-29.667084 302.476288 -129.081360 +-73.250549 207.739487 -69.415588 +-29.667084 207.739487 -69.415588 +-73.250549 207.739471 -129.081360 +-29.667084 207.739471 -129.081360 +-71.118050 183.305893 -72.156189 +-31.799591 183.305893 -72.156189 +-71.118050 183.305893 -126.340759 +-31.799591 183.305893 -126.340759 +-71.749313 302.476288 -127.506897 +-71.749313 302.476288 -70.990051 +-31.168327 302.476288 -70.990051 +-31.168327 302.476288 -127.506897 +-69.695068 269.171295 -124.639465 +-69.695068 269.171295 -73.670837 +-33.222565 269.171295 -73.670837 +-33.222565 269.171295 -124.639465 +-28.594971 313.097931 -7.310486 +14.988495 313.097931 -7.310486 +-28.594971 313.097931 -66.976257 +14.988495 313.097931 -66.976257 +-28.594971 207.784195 -7.310486 +14.988495 207.784195 -7.310486 +-28.594971 207.784195 -66.976257 +14.988495 207.784195 -66.976257 +-26.462471 183.350616 -10.051086 +12.855988 183.350616 -10.051086 +-26.462471 183.350616 -64.235657 +12.855988 183.350616 -64.235657 +-27.093735 313.097931 -65.401794 +-27.093735 313.097931 -8.884949 +13.487251 313.097931 -8.884949 +13.487251 313.097931 -65.401794 +-25.039490 279.802124 -62.534363 +-25.039490 279.802124 -11.565735 +11.433014 279.802124 -11.565735 +11.433014 279.802124 -62.534363 +-84.032951 619.746216 49.376282 +-84.032959 619.746216 92.959778 +-24.367188 619.746216 49.376343 +-24.367188 619.746216 92.959778 +-84.032951 503.809692 49.376343 +-84.032959 503.809692 92.959778 +-24.367188 503.809692 49.376343 +-24.367188 503.809692 92.959778 +-81.292358 479.376099 51.508850 +-81.292358 479.376099 90.827271 +-27.107788 479.376099 51.508850 +-27.107788 479.376099 90.827271 +-25.941643 619.746216 50.877563 +-82.458504 619.746216 50.877563 +-82.458504 619.746216 91.458557 +-25.941650 619.746216 91.458557 +-28.809067 586.420654 52.931824 +-79.777740 586.420654 52.931824 +-79.777740 586.420654 89.404297 +-28.809067 586.420654 89.404297 +-23.408691 598.501770 53.319458 +-23.408691 598.501770 96.902954 +36.257080 598.501770 53.319458 +36.257080 598.501770 96.902954 +-23.408691 503.764984 53.319458 +-23.408691 503.764984 96.902954 +36.257080 503.764984 53.319519 +36.257080 503.764984 96.902954 +-20.668091 479.331390 55.451965 +-20.668091 479.331390 94.770447 +33.516479 479.331390 55.451965 +33.516479 479.331390 94.770447 +34.682617 598.501770 54.820740 +-21.834236 598.501770 54.820740 +-21.834236 598.501770 95.401733 +34.682617 598.501770 95.401733 +31.815201 565.196838 56.874939 +-19.153473 565.196838 56.874939 +-19.153473 565.196838 93.347473 +31.815201 565.196838 93.347473 +-23.408691 566.635986 99.898987 +-23.408691 566.635986 143.482422 +36.257080 566.635986 99.898987 +36.257080 566.635986 143.482483 +-23.408691 503.764984 99.898987 +-23.408691 503.764984 143.482483 +36.257080 503.764984 99.898987 +36.257080 503.764984 143.482483 +-20.668091 479.331390 102.031494 +-20.668091 479.331390 141.349915 +33.516479 479.331390 102.031494 +33.516479 479.331390 141.349976 +34.682617 566.635986 101.400208 +-21.834236 566.635986 101.400208 +-21.834236 566.635986 141.981201 +34.682617 566.635986 141.981201 +31.815201 533.365173 103.454468 +-19.153473 533.365173 103.454468 +-19.153473 533.365173 139.926941 +31.815201 533.365173 139.926941 +-85.513794 609.123474 97.975037 +-85.513802 609.123474 141.558533 +-25.848022 609.123474 97.975037 +-25.848022 609.123474 141.558533 +-85.513794 503.809692 97.975037 +-85.513802 503.809692 141.558533 +-25.848022 503.809692 97.975037 +-25.848022 503.809692 141.558533 +-82.773193 479.376099 100.107544 +-82.773193 479.376099 139.426025 +-28.588623 479.376099 100.107544 +-28.588623 479.376099 139.426025 +-27.422485 609.123474 99.476318 +-83.939339 609.123474 99.476318 +-83.939339 609.123474 140.057312 +-27.422485 609.123474 140.057312 +-30.289902 575.827637 101.530518 +-81.258575 575.827637 101.530518 +-81.258575 575.827637 138.003052 +-30.289909 575.827637 138.003052 +-28.921051 598.501831 657.552368 +-28.921051 598.501831 701.135803 +30.744720 598.501831 657.552368 +30.744720 598.501831 701.135803 +-28.921051 503.765015 657.552368 +-28.921051 503.765015 701.135803 +30.744720 503.765015 657.552368 +30.744720 503.765015 701.135803 +-26.180450 479.331421 659.684875 +-26.180450 479.331421 699.003296 +28.004120 479.331421 659.684875 +28.004120 479.331421 699.003296 +29.170258 598.501831 659.053589 +-27.346596 598.501831 659.053528 +-27.346596 598.501831 699.634521 +29.170258 598.501831 699.634521 +26.302841 565.196838 661.107849 +-24.665833 565.196838 661.107849 +-24.665833 565.196838 697.580322 +26.302841 565.196838 697.580322 +-28.921051 566.635986 704.131836 +-28.921051 566.635986 747.715332 +30.744720 566.635986 704.131836 +30.744720 566.635986 747.715332 +-28.921051 503.765015 704.131836 +-28.921051 503.765015 747.715332 +30.744720 503.765015 704.131836 +30.744720 503.765015 747.715332 +-26.180450 479.331421 706.264343 +-26.180450 479.331421 745.582764 +28.004120 479.331421 706.264343 +28.004120 479.331421 745.582764 +29.170258 566.635986 705.633057 +-27.346596 566.635986 705.633057 +-27.346596 566.635986 746.214050 +29.170258 566.635986 746.214050 +26.302841 533.365234 707.687317 +-24.665833 533.365234 707.687317 +-24.665833 533.365234 744.159851 +26.302841 533.365234 744.159851 +-91.026154 609.123474 702.207886 +-91.026154 609.123474 745.791382 +-31.360382 609.123474 702.207886 +-31.360382 609.123474 745.791382 +-91.026154 503.809723 702.207886 +-91.026154 503.809723 745.791382 +-31.360382 503.809723 702.207886 +-31.360382 503.809723 745.791382 +-88.285553 479.376129 704.340454 +-88.285553 479.376129 743.658875 +-34.100983 479.376129 704.340454 +-34.100983 479.376129 743.658875 +-32.934845 609.123474 703.709167 +-89.451698 609.123474 703.709167 +-89.451698 609.123474 744.290161 +-32.934845 609.123474 744.290161 +-35.802265 575.827637 705.763367 +-86.770935 575.827637 705.763367 +-86.770935 575.827637 742.235901 +-35.802265 575.827637 742.235901 +-77.193710 619.746277 874.443726 +-33.610245 619.746277 874.443726 +-77.193710 619.746277 814.777954 +-33.610245 619.746277 814.777954 +-77.193710 503.809723 874.443726 +-33.610245 503.809723 874.443726 +-77.193710 503.809723 814.777954 +-33.610245 503.809723 814.777954 +-75.061211 479.376129 871.703125 +-35.742756 479.376129 871.703125 +-75.061211 479.376129 817.518555 +-35.742756 479.376129 817.518555 +-75.692474 619.746277 816.352417 +-75.692474 619.746277 872.869263 +-35.111488 619.746277 872.869263 +-35.111488 619.746277 816.352417 +-73.638229 586.420654 819.219849 +-73.638229 586.420654 870.188477 +-37.165726 586.420654 870.188477 +-37.165726 586.420654 819.219849 +-73.250549 598.501831 813.819458 +-29.667084 598.501831 813.819458 +-73.250549 598.501831 754.153687 +-29.667084 598.501831 754.153687 +-73.250549 503.765015 813.819458 +-29.667084 503.765015 813.819458 +-73.250549 503.765015 754.153687 +-29.667084 503.765015 754.153687 +-71.118050 479.331421 811.078857 +-31.799591 479.331421 811.078857 +-71.118050 479.331421 756.894287 +-31.799591 479.331421 756.894287 +-71.749313 598.501831 755.728149 +-71.749313 598.501831 812.244995 +-31.168327 598.501831 812.244995 +-31.168327 598.501831 755.728149 +-69.695068 565.196838 758.595581 +-69.695068 565.196838 809.564270 +-33.222565 565.196838 809.564270 +-33.222565 565.196838 758.595581 +-26.671051 566.635986 813.819458 +16.912415 566.635986 813.819458 +-26.671051 566.635986 754.153687 +16.912415 566.635986 754.153687 +-26.671051 503.765015 813.819458 +16.912415 503.765015 813.819458 +-26.671051 503.765015 754.153687 +16.912415 503.765015 754.153687 +-24.538544 479.331421 811.078857 +14.779907 479.331421 811.078857 +-24.538544 479.331421 756.894287 +14.779907 479.331421 756.894287 +-25.169815 566.635986 755.728149 +-25.169815 566.635986 812.244995 +15.411171 566.635986 812.244995 +15.411171 566.635986 755.728149 +-23.115570 533.365234 758.595581 +-23.115570 533.365234 809.564270 +13.356934 533.365234 809.564270 +13.356934 533.365234 758.595581 +-28.594971 609.123474 875.924561 +14.988495 609.123474 875.924561 +-28.594971 609.123474 816.258789 +14.988495 609.123474 816.258789 +-28.594971 503.809723 875.924561 +14.988495 503.809723 875.924561 +-28.594971 503.809723 816.258789 +14.988495 503.809723 816.258789 +-26.462471 479.376129 873.183960 +12.855988 479.376129 873.183960 +-26.462471 479.376129 818.999390 +12.855988 479.376129 818.999390 +-27.093735 609.123474 817.833252 +-27.093735 609.123474 874.350098 +13.487251 609.123474 874.350098 +13.487251 609.123474 817.833252 +-25.039490 575.827637 820.700684 +-25.039490 575.827637 871.669312 +11.433014 575.827637 871.669312 +11.433014 575.827637 820.700684 + + + + + + + + + + + +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.569896 -0.821717 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.569896 -0.821717 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.569896 0.821717 0.000000 +-0.569896 0.821717 0.000000 +-0.569896 0.821717 0.000000 +-0.569896 0.821717 0.000000 +-0.569896 0.821717 0.000000 +-0.569896 0.821717 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.551094 -0.834443 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.551094 -0.834443 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.551095 0.834443 0.000000 +-0.551094 0.834443 0.000000 +-0.551095 0.834443 0.000000 +-0.551095 0.834443 0.000000 +-0.551095 0.834443 0.000000 +-0.551094 0.834443 0.000000 +0.000000 0.000000 -1.000000 +-0.547313 -0.836928 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.547313 -0.836928 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.547313 0.836928 0.000000 +0.547313 0.836928 0.000000 +0.547313 0.836928 0.000000 +0.547313 0.836928 0.000000 +0.547313 0.836928 0.000000 +0.547313 0.836928 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.569896 -0.821717 0.000000 +0.569896 -0.821717 0.000000 +0.569896 -0.821717 0.000000 +0.569896 -0.821717 0.000000 +0.569896 -0.821717 0.000000 +0.569896 -0.821717 0.000000 +-0.569896 0.821717 0.000000 +-0.569896 0.821717 0.000000 +-0.569896 0.821717 0.000000 +-0.569896 0.821717 0.000000 +-0.569896 0.821717 0.000000 +-0.569896 0.821717 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.551094 -0.834443 0.000000 +0.551094 -0.834443 0.000000 +0.551094 -0.834443 0.000000 +0.551094 -0.834443 0.000000 +0.551094 -0.834443 0.000000 +0.551094 -0.834443 0.000000 +-0.551094 0.834443 0.000000 +-0.551094 0.834443 0.000000 +-0.551094 0.834443 0.000000 +-0.551094 0.834443 0.000000 +-0.551094 0.834443 0.000000 +-0.551094 0.834443 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000001 -0.000001 1.000000 +-0.000001 -0.000001 1.000000 +-0.000001 -0.000001 1.000000 +-0.000001 -0.000001 1.000000 +-0.000001 -0.000001 1.000000 +-0.000001 -0.000001 1.000000 +-0.547313 -0.836928 0.000000 +-0.547313 -0.836928 0.000000 +-0.547313 -0.836928 0.000000 +-0.547313 -0.836928 0.000000 +-0.547313 -0.836928 0.000000 +-0.547313 -0.836928 0.000000 +0.547313 0.836928 0.000000 +0.547313 0.836928 0.000000 +0.547313 0.836928 0.000000 +0.547313 0.836928 0.000000 +0.547313 0.836928 0.000000 +0.547313 0.836928 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.569896 -0.821717 0.000000 +0.569895 -0.821717 0.000000 +0.569895 -0.821717 0.000000 +0.569896 -0.821717 0.000000 +0.569895 -0.821717 0.000000 +0.569896 -0.821717 0.000000 +-0.569895 0.821717 0.000000 +-0.569895 0.821717 0.000000 +-0.569895 0.821717 0.000000 +-0.569895 0.821717 0.000000 +-0.569895 0.821717 0.000000 +-0.569895 0.821717 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.551094 -0.834443 0.000000 +0.551095 -0.834443 0.000000 +0.551094 -0.834443 0.000000 +0.551094 -0.834443 0.000000 +0.551094 -0.834443 0.000000 +0.551094 -0.834443 0.000000 +-0.551094 0.834443 0.000000 +-0.551094 0.834443 0.000000 +-0.551094 0.834443 0.000000 +-0.551094 0.834443 0.000000 +-0.551094 0.834443 0.000000 +-0.551094 0.834443 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000002 -0.000002 1.000000 +-0.000002 -0.000002 1.000000 +-0.000002 -0.000002 1.000000 +-0.000002 -0.000002 1.000000 +-0.000002 -0.000002 1.000000 +-0.000002 -0.000002 1.000000 +-0.547313 -0.836928 0.000000 +-0.547313 -0.836928 0.000000 +-0.547313 -0.836928 0.000000 +-0.547313 -0.836928 0.000000 +-0.547313 -0.836928 0.000000 +-0.547313 -0.836928 0.000000 +0.547313 0.836928 0.000000 +0.547313 0.836928 0.000000 +0.547313 0.836928 0.000000 +0.547313 0.836928 0.000000 +0.547313 0.836928 0.000000 +0.547313 0.836928 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -1.000000 -0.000001 +0.000000 -1.000000 -0.000001 +0.000000 -1.000000 -0.000001 +0.000000 -1.000000 -0.000001 +0.000000 -1.000000 -0.000001 +0.000000 -1.000000 -0.000001 +0.000000 1.000000 0.000001 +0.000000 1.000000 0.000001 +0.000000 1.000000 0.000001 +0.000000 1.000000 0.000001 +0.000000 1.000000 0.000001 +0.000000 1.000000 0.000001 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.569895 -0.821717 -0.000001 +0.569895 -0.821717 -0.000001 +0.569895 -0.821717 -0.000001 +0.569895 -0.821717 -0.000001 +0.569895 -0.821717 -0.000001 +0.569895 -0.821717 -0.000001 +-0.569895 0.821717 0.000000 +-0.569895 0.821717 0.000000 +-0.569895 0.821717 0.000000 +-0.569895 0.821717 0.000000 +-0.569895 0.821717 0.000000 +-0.569895 0.821717 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.551094 -0.834443 0.000000 +0.551094 -0.834443 0.000000 +0.551094 -0.834443 0.000000 +0.551094 -0.834443 0.000000 +0.551094 -0.834443 0.000000 +0.551094 -0.834443 0.000000 +-0.551094 0.834443 0.000000 +-0.551094 0.834443 0.000000 +-0.551094 0.834443 0.000000 +-0.551094 0.834443 0.000000 +-0.551094 0.834443 0.000000 +-0.551094 0.834443 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.547313 -0.836928 0.000000 +-0.547313 -0.836928 0.000000 +-0.547313 -0.836928 0.000000 +-0.547313 -0.836928 0.000000 +-0.547313 -0.836928 0.000000 +-0.547313 -0.836928 0.000000 +0.547313 0.836928 0.000000 +0.547313 0.836928 0.000000 +0.547313 0.836928 0.000000 +0.547313 0.836928 0.000000 +0.547313 0.836928 0.000000 +0.547313 0.836928 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -1.000000 -0.000002 +0.000000 -1.000000 -0.000002 +0.000000 -1.000000 -0.000002 +0.000000 -1.000000 -0.000002 +0.000000 -1.000000 -0.000002 +0.000000 -1.000000 -0.000002 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.569896 -0.821717 -0.000001 +0.569896 -0.821717 -0.000001 +0.569896 -0.821717 -0.000001 +0.569896 -0.821717 -0.000001 +0.569896 -0.821717 -0.000001 +0.569896 -0.821717 -0.000001 +-0.569895 0.821717 0.000000 +-0.569895 0.821717 0.000000 +-0.569895 0.821717 0.000000 +-0.569895 0.821717 0.000000 +-0.569895 0.821717 0.000000 +-0.569895 0.821717 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.551094 -0.834443 0.000000 +0.551095 -0.834443 0.000000 +0.551094 -0.834443 0.000000 +0.551094 -0.834443 0.000000 +0.551094 -0.834443 0.000000 +0.551094 -0.834443 0.000000 +-0.551095 0.834443 0.000001 +-0.551095 0.834443 0.000001 +-0.551095 0.834443 0.000001 +-0.551095 0.834443 0.000001 +-0.551095 0.834443 0.000001 +-0.551095 0.834443 0.000001 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.547313 -0.836928 0.000000 +-0.547313 -0.836928 0.000000 +-0.547313 -0.836928 0.000000 +-0.547313 -0.836928 0.000000 +-0.547313 -0.836928 0.000000 +-0.547313 -0.836928 0.000000 +0.547313 0.836928 0.000000 +0.547313 0.836928 0.000000 +0.547313 0.836928 0.000000 +0.547313 0.836928 0.000000 +0.547313 0.836928 0.000000 +0.547313 0.836928 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -1.000000 -0.000002 +0.000000 -1.000000 -0.000002 +0.000000 -1.000000 -0.000002 +0.000000 -1.000000 -0.000002 +0.000000 -1.000000 -0.000002 +0.000000 -1.000000 -0.000002 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -1.000000 -0.000002 +0.000000 -1.000000 -0.000002 +0.000000 -1.000000 -0.000002 +0.000000 -1.000000 -0.000002 +0.000000 -1.000000 -0.000002 +0.000000 -1.000000 -0.000002 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -1.000000 -0.000002 +0.000000 -1.000000 -0.000002 +0.000000 -1.000000 -0.000002 +0.000000 -1.000000 -0.000002 +0.000000 -1.000000 -0.000002 +0.000000 -1.000000 -0.000002 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -1.000000 -0.000002 +0.000000 -1.000000 -0.000002 +0.000000 -1.000000 -0.000002 +0.000000 -1.000000 -0.000002 +0.000000 -1.000000 -0.000002 +0.000000 -1.000000 -0.000002 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999971 0.000000 0.007589 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.000240 0.000000 1.000000 +0.000240 0.000000 1.000000 +0.000240 0.000000 1.000000 +-0.999971 0.000001 0.007639 +-0.999971 0.000001 0.007639 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999971 0.000000 0.007590 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.000239 0.000000 1.000000 +0.000239 0.000000 1.000000 +0.000239 0.000000 1.000000 +-0.999971 0.000001 0.007639 +-0.999971 0.000001 0.007639 +-0.999971 0.000000 0.007640 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999971 0.000000 0.007664 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 -0.000001 0.007640 +-0.999971 -0.000001 0.007640 +-0.999971 0.000000 0.007640 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999971 0.000000 0.007658 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 -0.000001 0.007640 +-0.999971 -0.000001 0.007640 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999971 0.000000 0.007581 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000002 0.007639 +-0.999971 0.000002 0.007639 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999972 0.000000 0.007505 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007637 +0.999971 0.000000 -0.007637 +0.999971 0.000000 -0.007637 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000004 0.007638 +-0.999971 0.000004 0.007638 +-0.999971 0.000000 0.007641 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999971 0.000000 0.007589 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000001 0.007639 +-0.999971 0.000001 0.007639 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999972 0.000000 0.007505 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.000240 0.000000 1.000000 +0.000240 0.000000 1.000000 +0.000240 0.000000 1.000000 +-0.999971 0.000004 0.007637 +-0.999971 0.000004 0.007637 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999972 0.000000 0.007505 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000004 0.007639 +-0.999971 0.000004 0.007639 +-0.999971 0.000000 0.007642 +-0.000244 0.000000 -1.000000 +-0.000244 0.000000 -1.000000 +-0.000244 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999972 0.000000 0.007435 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007635 +0.999971 0.000000 -0.007635 +0.999971 0.000000 -0.007635 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000006 0.007640 +-0.999971 0.000006 0.007640 +-0.999971 0.000000 0.007645 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007638 0.000002 -0.999971 +-0.007638 0.000002 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000241 +1.000000 0.000000 -0.000241 +1.000000 0.000000 -0.000241 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000000 0.000240 +-1.000000 0.000000 0.000240 +-1.000000 0.000000 0.000240 +-0.007638 0.000002 -0.999971 +-0.007638 0.000002 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007679 0.000000 -0.999970 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007643 -0.000001 -0.999971 +-0.007643 -0.000001 -0.999971 +-0.007642 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007456 0.000000 -0.999972 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007638 0.000005 -0.999971 +-0.007638 0.000005 -0.999971 +-0.007642 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007456 0.000000 -0.999972 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000000 0.000243 +-1.000000 0.000000 0.000243 +-1.000000 0.000000 0.000243 +-0.007635 0.000005 -0.999971 +-0.007635 0.000005 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007679 0.000000 -0.999970 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007640 -0.000001 -0.999971 +-0.007640 -0.000001 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007640 0.000003 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000000 0.000241 +-1.000000 0.000000 0.000241 +-1.000000 0.000000 0.000241 +-0.007638 0.000002 -0.999971 +-0.007638 0.000002 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000000 0.000243 +-1.000000 0.000000 0.000243 +-1.000000 0.000000 0.000243 +-0.007638 0.000002 -0.999971 +-0.007638 0.000002 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007638 0.000002 -0.999971 +-0.007638 0.000002 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000243 +1.000000 0.000000 -0.000243 +1.000000 0.000000 -0.000243 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000000 0.000243 +-1.000000 0.000000 0.000243 +-1.000000 0.000000 0.000243 +-0.007640 0.000002 -0.999971 +-0.007640 0.000002 -0.999971 +-0.007642 0.000000 -0.999971 +1.000000 0.000000 -0.000243 +1.000000 0.000000 -0.000243 +1.000000 0.000000 -0.000243 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007344 0.000000 -0.999973 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000000 0.000241 +-1.000000 0.000000 0.000241 +-1.000000 0.000000 0.000241 +-0.007633 0.000009 -0.999971 +-0.007633 0.000009 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007638 0.000002 -0.999971 +-0.007638 0.000002 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007679 0.000000 -0.999970 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007643 -0.000001 -0.999971 +-0.007643 -0.000001 -0.999971 +-0.007642 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007456 0.000000 -0.999972 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007638 0.000005 -0.999971 +-0.007638 0.000005 -0.999971 +-0.007642 0.000000 -0.999971 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007679 0.000000 -0.999970 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007640 -0.000001 -0.999971 +-0.007640 -0.000001 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007640 0.000003 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000000 0.000241 +-1.000000 0.000000 0.000241 +-1.000000 0.000000 0.000241 +-0.007638 0.000002 -0.999971 +-0.007638 0.000002 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007640 0.000002 -0.999971 +-0.007640 0.000002 -0.999971 +-0.007642 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000000 0.000243 +-1.000000 0.000000 0.000243 +-1.000000 0.000000 0.000243 +-0.007638 0.000002 -0.999971 +-0.007638 0.000002 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007638 0.000002 -0.999971 +-0.007638 0.000002 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000243 +1.000000 0.000000 -0.000243 +1.000000 0.000000 -0.000243 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000000 0.000243 +-1.000000 0.000000 0.000243 +-1.000000 0.000000 0.000243 +-0.007640 0.000002 -0.999971 +-0.007640 0.000002 -0.999971 +-0.007642 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007456 0.000000 -0.999972 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007638 0.000005 -0.999971 +-0.007638 0.000005 -0.999971 +-0.007642 0.000000 -0.999971 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999971 0.000000 0.007589 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.000240 0.000000 1.000000 +0.000240 0.000000 1.000000 +0.000240 0.000000 1.000000 +-0.999971 0.000001 0.007639 +-0.999971 0.000001 0.007639 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999971 0.000000 0.007590 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.000239 0.000000 1.000000 +0.000239 0.000000 1.000000 +0.000239 0.000000 1.000000 +-0.999971 0.000001 0.007639 +-0.999971 0.000001 0.007639 +-0.999971 0.000000 0.007640 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999971 0.000000 0.007664 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 -0.000001 0.007640 +-0.999971 -0.000001 0.007640 +-0.999971 0.000000 0.007640 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999971 0.000000 0.007658 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 -0.000001 0.007640 +-0.999971 -0.000001 0.007640 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999971 0.000000 0.007581 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000002 0.007639 +-0.999971 0.000002 0.007639 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999972 0.000000 0.007505 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007637 +0.999971 0.000000 -0.007637 +0.999971 0.000000 -0.007637 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000004 0.007638 +-0.999971 0.000004 0.007638 +-0.999971 0.000000 0.007641 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999971 0.000000 0.007589 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000001 0.007639 +-0.999971 0.000001 0.007639 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999972 0.000000 0.007505 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.000240 0.000000 1.000000 +0.000240 0.000000 1.000000 +0.000240 0.000000 1.000000 +-0.999971 0.000004 0.007637 +-0.999971 0.000004 0.007637 +-0.999971 0.000000 0.007640 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007638 0.000002 -0.999971 +-0.007638 0.000002 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000241 +1.000000 0.000000 -0.000241 +1.000000 0.000000 -0.000241 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000000 0.000240 +-1.000000 0.000000 0.000240 +-1.000000 0.000000 0.000240 +-0.007638 0.000002 -0.999971 +-0.007638 0.000002 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007679 0.000000 -0.999970 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007643 -0.000001 -0.999971 +-0.007643 -0.000001 -0.999971 +-0.007642 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007456 0.000000 -0.999972 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007638 0.000005 -0.999971 +-0.007638 0.000005 -0.999971 +-0.007642 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007456 0.000000 -0.999972 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000000 0.000243 +-1.000000 0.000000 0.000243 +-1.000000 0.000000 0.000243 +-0.007635 0.000005 -0.999971 +-0.007635 0.000005 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007679 0.000000 -0.999970 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007640 -0.000001 -0.999971 +-0.007640 -0.000001 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007640 0.000003 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000000 0.000241 +-1.000000 0.000000 0.000241 +-1.000000 0.000000 0.000241 +-0.007638 0.000002 -0.999971 +-0.007638 0.000002 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000000 0.000243 +-1.000000 0.000000 0.000243 +-1.000000 0.000000 0.000243 +-0.007638 0.000002 -0.999971 +-0.007638 0.000002 -0.999971 +-0.007639 0.000000 -0.999971 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999971 0.000000 0.007588 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.000241 0.000000 1.000000 +0.000241 0.000000 1.000000 +0.000241 0.000000 1.000000 +-0.999971 0.000002 0.007639 +-0.999971 0.000002 0.007639 +-0.999971 0.000000 0.007640 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999971 0.000000 0.007664 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 -0.000001 0.007640 +-0.999971 -0.000001 0.007640 +-0.999971 0.000000 0.007640 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999972 0.000000 0.007511 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000004 0.007639 +-0.999971 0.000004 0.007639 +-0.999971 0.000000 0.007641 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999971 0.000000 0.007658 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 -0.000001 0.007640 +-0.999971 -0.000001 0.007640 +-0.999971 0.000000 0.007640 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999971 0.000000 0.007581 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000002 0.007639 +-0.999971 0.000002 0.007639 +-0.999971 0.000000 0.007640 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999972 0.000000 0.007505 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007637 +0.999971 0.000000 -0.007637 +0.999971 0.000000 -0.007637 +0.000241 0.000000 1.000000 +0.000241 0.000000 1.000000 +0.000241 0.000000 1.000000 +-0.999971 0.000004 0.007638 +-0.999971 0.000004 0.007638 +-0.999971 0.000000 0.007641 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999971 0.000000 0.007588 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000002 0.007639 +-0.999971 0.000002 0.007639 +-0.999971 0.000000 0.007640 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999972 0.000000 0.007505 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000004 0.007637 +-0.999971 0.000004 0.007637 +-0.999971 0.000000 0.007640 +-0.000243 0.000000 -1.000000 +-0.000243 0.000000 -1.000000 +-0.000243 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999972 0.000000 0.007505 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000243 0.000000 1.000000 +0.000243 0.000000 1.000000 +0.000243 0.000000 1.000000 +-0.999971 0.000004 0.007639 +-0.999971 0.000004 0.007639 +-0.999971 0.000000 0.007642 +-0.000243 0.000000 -1.000000 +-0.000243 0.000000 -1.000000 +-0.000243 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999972 0.000000 0.007435 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007635 +0.999971 0.000000 -0.007635 +0.999971 0.000000 -0.007635 +0.000241 0.000000 1.000000 +0.000241 0.000000 1.000000 +0.000241 0.000000 1.000000 +-0.999971 0.000006 0.007640 +-0.999971 0.000006 0.007640 +-0.999971 0.000000 0.007645 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007639 0.000002 -0.999971 +-0.007639 0.000002 -0.999971 +-0.007641 0.000000 -0.999971 +1.000000 0.000000 -0.000241 +1.000000 0.000000 -0.000241 +1.000000 0.000000 -0.000241 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007624 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000000 0.000240 +-1.000000 0.000000 0.000240 +-1.000000 0.000000 0.000240 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007679 0.000000 -0.999970 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007640 -0.000001 -0.999971 +-0.007640 -0.000001 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007512 0.000000 -0.999972 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000002 0.999971 +0.007639 0.000002 0.999971 +0.007639 0.000002 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007638 0.000004 -0.999971 +-0.007638 0.000004 -0.999971 +-0.007641 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007511 0.000000 -0.999972 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +-1.000000 0.000000 0.000243 +-1.000000 0.000000 0.000243 +-1.000000 0.000000 0.000243 +-0.007636 0.000004 -0.999971 +-0.007636 0.000004 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007624 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007640 0.000000 -0.999971 +-0.007640 0.000000 -0.999971 +-0.007641 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +-1.000000 0.000000 0.000241 +-1.000000 0.000000 0.000241 +-1.000000 0.000000 0.000241 +-0.007639 0.000002 -0.999971 +-0.007639 0.000002 -0.999971 +-0.007641 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007456 0.000000 -0.999972 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007638 0.000005 -0.999971 +-0.007638 0.000005 -0.999971 +-0.007642 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +-1.000000 0.000000 0.000243 +-1.000000 0.000000 0.000243 +-1.000000 0.000000 0.000243 +-0.007639 0.000002 -0.999971 +-0.007639 0.000002 -0.999971 +-0.007641 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007512 0.000000 -0.999972 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007636 0.000004 -0.999971 +-0.007636 0.000004 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000243 +1.000000 0.000000 -0.000243 +1.000000 0.000000 -0.000243 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007512 0.000000 -0.999972 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000000 0.000243 +-1.000000 0.000000 0.000243 +-1.000000 0.000000 0.000243 +-0.007638 0.000004 -0.999971 +-0.007638 0.000004 -0.999971 +-0.007641 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007512 0.000000 -0.999972 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007639 0.000004 -0.999971 +-0.007639 0.000004 -0.999971 +-0.007642 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007639 0.000002 -0.999971 +-0.007639 0.000002 -0.999971 +-0.007641 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007679 0.000000 -0.999970 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007640 -0.000001 -0.999971 +-0.007640 -0.000001 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007512 0.000000 -0.999972 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007638 0.000004 -0.999971 +-0.007638 0.000004 -0.999971 +-0.007641 0.000000 -0.999971 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007624 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007640 0.000000 -0.999971 +-0.007640 0.000000 -0.999971 +-0.007641 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +-1.000000 0.000000 0.000241 +-1.000000 0.000000 0.000241 +-1.000000 0.000000 0.000241 +-0.007639 0.000002 -0.999971 +-0.007639 0.000002 -0.999971 +-0.007641 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +-1.000000 0.000000 0.000243 +-1.000000 0.000000 0.000243 +-1.000000 0.000000 0.000243 +-0.007639 0.000002 -0.999971 +-0.007639 0.000002 -0.999971 +-0.007641 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007512 -0.000002 -0.999972 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007638 0.000002 -0.999971 +-0.007638 0.000002 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007661 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007641 -0.000001 -0.999971 +-0.007641 -0.000001 -0.999971 +-0.007641 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007661 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007639 0.000001 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007641 -0.000001 -0.999971 +-0.007641 -0.000001 -0.999971 +-0.007641 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007661 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007641 -0.000001 -0.999971 +-0.007641 -0.000001 -0.999971 +-0.007641 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007661 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007640 -0.000001 -0.999971 +-0.007640 -0.000001 -0.999971 +-0.007640 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007661 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000001 0.999971 +0.007638 0.000000 0.999971 +0.007639 0.000001 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007640 -0.000001 -0.999971 +-0.007640 -0.000001 -0.999971 +-0.007640 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007661 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007640 -0.000001 -0.999971 +-0.007640 -0.000001 -0.999971 +-0.007640 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007613 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007639 0.000001 -0.999971 +-0.007639 0.000001 -0.999971 +-0.007640 0.000000 -0.999971 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000241 0.000003 1.000000 +0.000241 0.000003 1.000000 +0.000241 0.000003 1.000000 +-0.999971 0.000002 0.007639 +-0.999971 0.000002 0.007639 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000241 0.000001 1.000000 +0.000241 0.000001 1.000000 +0.000241 0.000001 1.000000 +-0.999971 0.000001 0.007639 +-0.999971 0.000001 0.007639 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000241 0.000001 1.000000 +0.000241 0.000001 1.000000 +0.000241 0.000001 1.000000 +-0.999971 0.000001 0.007639 +-0.999971 0.000001 0.007639 +-0.999971 0.000000 0.007640 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.000241 0.000000 1.000000 +0.000241 0.000000 1.000000 +0.000241 0.000000 1.000000 +-0.999971 0.000001 0.007639 +-0.999971 0.000001 0.007639 +-0.999971 0.000000 0.007640 +-0.000241 0.000000 -1.000000 +-0.000239 -0.000003 -1.000000 +-0.000241 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000001 0.007641 +-0.999971 0.000001 0.007641 +-0.999971 0.000000 0.007642 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000001 0.007641 +-0.999971 0.000001 0.007641 +-0.999971 0.000000 0.007642 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000001 0.007641 +-0.999971 0.000001 0.007641 +-0.999971 0.000000 0.007642 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000001 0.007639 +-0.999971 0.000001 0.007639 +-0.999971 0.000000 0.007640 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007565 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007639 0.000002 -0.999971 +-0.007639 0.000002 -0.999971 +-0.007641 0.000000 -0.999971 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007613 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007639 0.000001 -0.999971 +-0.007639 0.000001 -0.999971 +-0.007640 0.000000 -0.999971 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007613 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007639 0.000001 -0.999971 +-0.007639 0.000001 -0.999971 +-0.007640 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007661 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007641 -0.000001 -0.999971 +-0.007641 -0.000001 -0.999971 +-0.007641 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007661 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007640 -0.000001 -0.999971 +-0.007640 -0.000001 -0.999971 +-0.007640 0.000000 -0.999971 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000240 0.000003 1.000000 +0.000240 0.000003 1.000000 +0.000240 0.000003 1.000000 +-0.999971 0.000002 0.007639 +-0.999971 0.000002 0.007639 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000240 0.000003 1.000000 +0.000240 0.000003 1.000000 +0.000240 0.000003 1.000000 +-0.999971 0.000002 0.007639 +-0.999971 0.000002 0.007639 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000241 0.000001 1.000000 +0.000241 0.000001 1.000000 +0.000241 0.000001 1.000000 +-0.999971 0.000001 0.007639 +-0.999971 0.000001 0.007639 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000001 0.007639 +-0.999971 0.000001 0.007639 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000001 0.007639 +-0.999971 0.000001 0.007639 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000001 0.007639 +-0.999971 0.000001 0.007639 +-0.999971 0.000000 0.007640 +-0.000240 -0.000001 -1.000000 +-0.000241 0.000000 -1.000000 +-0.000240 -0.000001 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000001 0.007641 +-0.999971 0.000001 0.007641 +-0.999971 0.000000 0.007642 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000001 0.007641 +-0.999971 0.000001 0.007641 +-0.999971 0.000000 0.007642 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007565 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007641 0.000000 0.999971 +0.007641 0.000000 0.999971 +0.007641 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007639 0.000002 -0.999971 +-0.007639 0.000002 -0.999971 +-0.007641 0.000000 -0.999971 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007613 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007641 0.000000 0.999971 +0.007641 0.000000 0.999971 +0.007641 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007639 0.000001 -0.999971 +-0.007639 0.000001 -0.999971 +-0.007640 0.000000 -0.999971 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000240 0.000002 1.000000 +0.000240 0.000002 1.000000 +0.000240 0.000002 1.000000 +-0.999971 0.000001 0.007639 +-0.999971 0.000001 0.007639 +-0.999971 0.000000 0.007640 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007661 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007640 -0.000001 -0.999971 +-0.007640 -0.000001 -0.999971 +-0.007640 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007661 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007640 -0.000001 -0.999971 +-0.007640 -0.000001 -0.999971 +-0.007640 0.000000 -0.999971 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000240 0.000002 1.000000 +0.000240 0.000002 1.000000 +0.000240 0.000002 1.000000 +-0.999971 0.000002 0.007639 +-0.999971 0.000002 0.007639 +-0.999971 0.000000 0.007640 +-0.000242 -0.000001 -1.000000 +-0.000242 -0.000001 -1.000000 +-0.000242 -0.000001 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000240 0.000002 1.000000 +0.000240 0.000002 1.000000 +0.000240 0.000002 1.000000 +-0.999971 0.000002 0.007639 +-0.999971 0.000002 0.007639 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000241 0.000002 1.000000 +0.000241 0.000002 1.000000 +0.000241 0.000002 1.000000 +-0.999971 0.000002 0.007639 +-0.999971 0.000002 0.007639 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000001 0.007639 +-0.999971 0.000001 0.007639 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000001 0.007639 +-0.999971 0.000001 0.007639 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000001 0.007639 +-0.999971 0.000001 0.007639 +-0.999971 0.000000 0.007640 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000001 0.007641 +-0.999971 0.000001 0.007641 +-0.999971 0.000000 0.007642 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007589 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007639 0.000001 -0.999971 +-0.007639 0.000001 -0.999971 +-0.007640 0.000000 -0.999971 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007589 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007641 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007641 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007639 0.000001 -0.999971 +-0.007639 0.000001 -0.999971 +-0.007640 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007661 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007640 -0.000001 -0.999971 +-0.007640 -0.000001 -0.999971 +-0.007640 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007661 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007640 -0.000001 -0.999971 +-0.007640 -0.000001 -0.999971 +-0.007640 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007661 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007640 -0.000001 -0.999971 +-0.007640 -0.000001 -0.999971 +-0.007640 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007661 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007640 -0.000001 -0.999971 +-0.007640 -0.000001 -0.999971 +-0.007640 0.000000 -0.999971 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000241 0.000002 1.000000 +0.000241 0.000002 1.000000 +0.000241 0.000002 1.000000 +-0.999971 0.000002 0.007639 +-0.999971 0.000002 0.007639 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000240 0.000002 1.000000 +0.000240 0.000002 1.000000 +0.000240 0.000002 1.000000 +-0.999971 0.000002 0.007639 +-0.999971 0.000002 0.007639 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000001 0.007639 +-0.999971 0.000001 0.007639 +-0.999971 0.000000 0.007640 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000001 0.007641 +-0.999971 0.000001 0.007641 +-0.999971 0.000000 0.007642 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000001 0.007641 +-0.999971 0.000001 0.007641 +-0.999971 0.000000 0.007642 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007589 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007639 0.000001 -0.999971 +-0.007639 0.000001 -0.999971 +-0.007640 0.000000 -0.999971 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007589 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007639 0.000001 -0.999971 +-0.007639 0.000001 -0.999971 +-0.007640 0.000000 -0.999971 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007583 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007639 0.000001 -0.999971 +-0.007639 0.000001 -0.999971 +-0.007640 0.000000 -0.999971 +-0.999972 0.000000 0.007505 +-0.999972 0.000000 0.007505 +-0.999972 0.000000 0.007505 +-0.999972 0.000000 0.007505 +-0.999972 0.000000 0.007505 +-0.999972 0.000000 0.007505 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007613 0.000000 -0.999971 +-0.007613 0.000000 -0.999971 +-0.007613 0.000000 -0.999971 +-0.007661 0.000000 -0.999971 +-0.007661 0.000000 -0.999971 +-0.007661 0.000000 -0.999971 +-0.007661 0.000000 -0.999971 +-0.007661 0.000000 -0.999971 +-0.007661 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007613 0.000000 -0.999971 +-0.007613 0.000000 -0.999971 +-0.007613 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007613 0.000000 -0.999971 +-0.007613 0.000000 -0.999971 +-0.007613 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007565 0.000000 -0.999971 +-0.007565 0.000000 -0.999971 +-0.007565 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007565 0.000000 -0.999971 +-0.007565 0.000000 -0.999971 +-0.007565 0.000000 -0.999971 +-0.007661 0.000000 -0.999971 +-0.007661 0.000000 -0.999971 +-0.007661 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007512 0.000000 -0.999972 +-0.007512 0.000000 -0.999972 +-0.007512 0.000000 -0.999972 +-0.007679 0.000000 -0.999971 +-0.007679 0.000000 -0.999970 +-0.007679 0.000000 -0.999970 +-0.999972 0.000000 0.007435 +-0.999972 0.000000 0.007435 +-0.999972 0.000000 0.007435 +-0.999972 0.000000 0.007505 +-0.999972 0.000000 0.007505 +-0.999972 0.000000 0.007505 +-0.999971 0.000000 0.007581 +-0.999971 0.000000 0.007581 +-0.999971 0.000000 0.007581 +-0.999971 0.000000 0.007658 +-0.999971 0.000000 0.007658 +-0.999971 0.000000 0.007658 +-0.999971 0.000000 0.007588 +-0.999971 0.000000 0.007588 +-0.999971 0.000000 0.007588 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +-0.999972 0.000000 0.007511 +-0.999972 0.000000 0.007511 +-0.999972 0.000000 0.007511 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +-0.007641 0.000002 -0.999971 +-0.007641 0.000002 -0.999971 +-0.007641 0.000002 -0.999971 +-0.007661 0.000000 -0.999971 +-0.007661 0.000000 -0.999971 +-0.007661 0.000000 -0.999971 +-0.007613 0.000000 -0.999971 +-0.007613 0.000000 -0.999971 +-0.007613 0.000000 -0.999971 +-0.007640 0.000001 -0.999971 +-0.007640 0.000001 -0.999971 +-0.007640 0.000001 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000240 0.000000 1.000000 +0.000240 0.000000 1.000000 +0.000240 0.000000 1.000000 +-0.000241 -0.000001 -1.000000 +-0.000241 -0.000001 -1.000000 +-0.000241 -0.000001 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007661 0.000000 -0.999971 +-0.007661 0.000000 -0.999971 +-0.007661 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007613 0.000000 -0.999971 +-0.007613 0.000000 -0.999971 +-0.007613 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007565 0.000000 -0.999971 +-0.007565 0.000000 -0.999971 +-0.007565 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.007661 0.000000 -0.999971 +-0.007661 0.000000 -0.999971 +-0.007661 0.000000 -0.999971 +-0.007641 -0.000001 -0.999971 +-0.007641 -0.000001 -0.999971 +-0.007641 -0.000001 -0.999971 +-0.007661 0.000000 -0.999971 +-0.007661 0.000000 -0.999971 +-0.007661 0.000000 -0.999971 +-0.007661 0.000000 -0.999971 +-0.007661 0.000000 -0.999971 +-0.007661 0.000000 -0.999971 +-0.007640 -0.000001 -0.999971 +-0.007640 -0.000001 -0.999971 +-0.007640 -0.000001 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999971 0.000000 0.007595 +-0.999971 0.000000 0.007595 +-0.999971 0.000000 0.007595 +-0.007565 0.000000 -0.999971 +-0.007565 0.000000 -0.999971 +-0.007565 0.000000 -0.999971 +-0.007641 0.000002 -0.999971 +-0.007641 0.000002 -0.999971 +-0.007641 0.000002 -0.999971 +-0.007661 0.000000 -0.999971 +-0.007661 0.000000 -0.999971 +-0.007661 0.000000 -0.999971 +-0.007641 -0.000001 -0.999971 +-0.007641 -0.000001 -0.999971 +-0.007641 -0.000001 -0.999971 +-0.007661 0.000000 -0.999971 +-0.007661 0.000000 -0.999971 +-0.007661 0.000000 -0.999971 +-0.007640 -0.000001 -0.999971 +-0.007640 -0.000001 -0.999971 +-0.007640 -0.000001 -0.999971 +-0.999971 0.000000 0.007595 +-0.999971 0.000000 0.007595 +-0.999971 0.000000 0.007595 +0.000241 0.000001 1.000000 +0.000241 0.000001 1.000000 +0.000241 0.000001 1.000000 +-0.014447 0.030105 0.999442 +-0.014447 0.030105 0.999442 +-0.014447 0.030105 0.999442 +0.000241 0.000001 1.000000 +0.000241 0.000001 1.000000 +0.000241 0.000001 1.000000 +-0.007613 0.000000 -0.999971 +-0.007613 0.000000 -0.999971 +-0.007613 0.000000 -0.999971 +-0.007640 0.000000 -0.999971 +-0.007640 0.000000 -0.999971 +-0.007640 0.000000 -0.999971 +-0.999971 0.000000 0.007664 +-0.999971 0.000000 0.007664 +-0.999971 0.000000 0.007664 +0.000240 0.000003 1.000000 +0.000240 0.000003 1.000000 +0.000240 0.000003 1.000000 +-0.999971 0.000000 0.007589 +-0.999971 0.000000 0.007589 +-0.999971 0.000000 0.007589 +0.000240 0.000003 1.000000 +0.000240 0.000003 1.000000 +0.000240 0.000003 1.000000 +-0.999972 0.000000 0.007505 +-0.999972 0.000000 0.007505 +-0.999972 0.000000 0.007505 +0.000239 0.000003 1.000000 +0.000239 0.000003 1.000000 +0.000239 0.000003 1.000000 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-0.007641 0.000000 -0.999971 +-0.007641 0.000000 -0.999971 +-0.007641 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000001 0.999971 +0.007639 0.000001 0.999971 +0.007639 0.000001 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007640 0.000000 -0.999971 +-0.007640 0.000000 -0.999971 +-0.007640 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +-0.007661 0.000000 -0.999971 +-0.007661 0.000000 -0.999971 +-0.007661 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.007613 0.000000 -0.999971 +-0.007613 0.000000 -0.999971 +-0.007613 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007640 0.000000 -0.999971 +-0.007640 0.000000 -0.999971 +-0.007640 0.000000 -0.999971 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999971 0.000000 0.007589 +-0.999971 0.000000 0.007589 +-0.999971 0.000000 0.007589 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999971 0.000000 0.007589 +-0.999971 0.000000 0.007589 +-0.999971 0.000000 0.007589 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999971 0.000000 0.007589 +-0.999971 0.000000 0.007589 +-0.999971 0.000000 0.007589 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.000241 0.000000 1.000000 +0.000241 0.000000 1.000000 +0.000241 0.000000 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.000239 -0.000003 -1.000000 +-0.000239 -0.000003 -1.000000 +-0.000239 -0.000003 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.000241 0.000001 1.000000 +0.000241 0.000001 1.000000 +0.000241 0.000001 1.000000 +-0.999971 0.000000 0.007642 +-0.999971 0.000000 0.007642 +-0.999971 0.000000 0.007642 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +-0.999971 0.000000 0.007642 +-0.999971 0.000000 0.007642 +-0.999971 0.000000 0.007642 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +-0.999971 0.000000 0.007642 +-0.999971 0.000000 0.007642 +-0.999971 0.000000 0.007642 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999971 0.000000 0.007589 +-0.999971 0.000000 0.007589 +-0.999971 0.000000 0.007589 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.000240 0.000003 1.000000 +0.000240 0.000003 1.000000 +0.000240 0.000003 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +-0.007613 0.000000 -0.999971 +-0.007613 0.000000 -0.999971 +-0.007613 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-0.007640 0.000000 -0.999971 +-0.007640 0.000000 -0.999971 +-0.007640 0.000000 -0.999971 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.999971 0.000000 0.007588 +-0.999971 0.000000 0.007588 +-0.999971 0.000000 0.007588 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.000240 0.000000 1.000000 +0.000240 0.000000 1.000000 +0.000240 0.000000 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.999971 0.000000 0.007590 +-0.999971 0.000000 0.007590 +-0.999971 0.000000 0.007590 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.000239 0.000000 1.000000 +0.000239 0.000000 1.000000 +0.000239 0.000000 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +-0.999971 0.000000 0.007658 +-0.999971 0.000000 0.007658 +-0.999971 0.000000 0.007658 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.000240 0.000003 1.000000 +0.000240 0.000003 1.000000 +0.000240 0.000003 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.999971 0.000000 0.007581 +-0.999971 0.000000 0.007581 +-0.999971 0.000000 0.007581 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.999972 0.000000 0.007505 +-0.999972 0.000000 0.007505 +-0.999972 0.000000 0.007505 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007637 +0.999971 0.000000 -0.007637 +0.999971 0.000000 -0.007637 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000000 0.007641 +-0.999971 0.000000 0.007641 +-0.999971 0.000000 0.007641 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +-0.007679 0.000000 -0.999971 +-0.007679 0.000000 -0.999970 +-0.007679 0.000000 -0.999971 +-0.007642 0.000000 -0.999971 +-0.007642 0.000000 -0.999971 +-0.007642 0.000000 -0.999971 +-0.007456 0.000000 -0.999972 +-0.007456 0.000000 -0.999972 +-0.007456 0.000000 -0.999972 +-0.007642 0.000000 -0.999971 +-0.007642 0.000000 -0.999971 +-0.007642 0.000000 -0.999971 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +-0.007679 0.000000 -0.999970 +-0.007679 0.000000 -0.999970 +-0.007679 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000003 0.999971 +0.007640 0.000003 0.999971 +0.007640 0.000003 0.999971 +-1.000000 0.000000 0.000241 +-1.000000 0.000000 0.000241 +-1.000000 0.000000 0.000241 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007642 0.000000 -0.999971 +-0.007642 0.000000 -0.999971 +-0.007642 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000003 0.000242 +-1.000000 0.000003 0.000242 +-1.000000 0.000003 0.000242 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000243 +1.000000 0.000000 -0.000243 +1.000000 0.000000 -0.000243 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000003 0.000242 +-1.000000 0.000003 0.000242 +-1.000000 0.000003 0.000242 +-0.007642 0.000000 -0.999971 +-0.007642 0.000000 -0.999971 +-0.007642 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-0.007642 0.000006 -0.999971 +-0.007642 0.000006 -0.999971 +-0.007642 0.000006 -0.999971 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.999971 0.000000 0.007589 +-0.999971 0.000000 0.007589 +-0.999971 0.000000 0.007589 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.000240 0.000000 1.000000 +0.000240 0.000000 1.000000 +0.000240 0.000000 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.999971 0.000000 0.007590 +-0.999971 0.000000 0.007590 +-0.999971 0.000000 0.007590 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.000239 0.000000 1.000000 +0.000239 0.000000 1.000000 +0.000239 0.000000 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +-0.999971 0.000000 0.007664 +-0.999971 0.000000 0.007664 +-0.999971 0.000000 0.007664 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000240 0.000003 1.000000 +0.000240 0.000003 1.000000 +0.000240 0.000003 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +-0.999971 0.000000 0.007658 +-0.999971 0.000000 0.007658 +-0.999971 0.000000 0.007658 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.000240 0.000003 1.000000 +0.000240 0.000003 1.000000 +0.000240 0.000003 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.999971 0.000000 0.007581 +-0.999971 0.000000 0.007581 +-0.999971 0.000000 0.007581 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.999972 0.000000 0.007505 +-0.999972 0.000000 0.007505 +-0.999972 0.000000 0.007505 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007637 +0.999971 0.000000 -0.007637 +0.999971 0.000000 -0.007637 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000000 0.007641 +-0.999971 0.000000 0.007641 +-0.999971 0.000000 0.007641 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.999971 0.000000 0.007589 +-0.999971 0.000000 0.007589 +-0.999971 0.000000 0.007589 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000240 0.000003 1.000000 +0.000240 0.000003 1.000000 +0.000240 0.000003 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.999972 0.000000 0.007505 +-0.999972 0.000000 0.007505 +-0.999972 0.000000 0.007505 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.000239 0.000003 1.000000 +0.000239 0.000003 1.000000 +0.000239 0.000003 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.999972 0.000000 0.007505 +-0.999972 0.000000 0.007505 +-0.999972 0.000000 0.007505 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000240 0.000003 1.000000 +0.000240 0.000003 1.000000 +0.000240 0.000003 1.000000 +-0.999971 0.000000 0.007642 +-0.999971 0.000000 0.007642 +-0.999971 0.000000 0.007642 +-0.000244 0.000000 -1.000000 +-0.000244 0.000000 -1.000000 +-0.000244 0.000000 -1.000000 +-0.999972 0.000000 0.007435 +-0.999972 0.000000 0.007435 +-0.999972 0.000000 0.007435 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007635 +0.999971 0.000000 -0.007635 +0.999971 0.000000 -0.007635 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000000 0.007645 +-0.999971 0.000000 0.007645 +-0.999971 0.000000 0.007645 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000241 +1.000000 0.000000 -0.000241 +1.000000 0.000000 -0.000241 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000000 0.000240 +-1.000000 0.000000 0.000240 +-1.000000 0.000000 0.000240 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +-0.007679 0.000000 -0.999971 +-0.007679 0.000000 -0.999970 +-0.007679 0.000000 -0.999970 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-0.007642 0.000000 -0.999971 +-0.007642 0.000000 -0.999971 +-0.007642 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +-0.007456 0.000000 -0.999972 +-0.007456 0.000000 -0.999972 +-0.007456 0.000000 -0.999972 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007642 0.000000 -0.999971 +-0.007642 0.000000 -0.999971 +-0.007642 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +-0.007456 0.000000 -0.999972 +-0.007456 0.000000 -0.999972 +-0.007456 0.000000 -0.999972 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000003 0.000242 +-1.000000 0.000003 0.000242 +-1.000000 0.000003 0.000242 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +-0.007679 0.000000 -0.999970 +-0.007679 0.000000 -0.999970 +-0.007679 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000003 0.999971 +0.007640 0.000003 0.999971 +0.007640 0.000003 0.999971 +-1.000000 0.000000 0.000241 +-1.000000 0.000000 0.000241 +-1.000000 0.000000 0.000241 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000003 0.000242 +-1.000000 0.000003 0.000242 +-1.000000 0.000003 0.000242 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000243 +1.000000 0.000000 -0.000243 +1.000000 0.000000 -0.000243 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000003 0.000242 +-1.000000 0.000003 0.000242 +-1.000000 0.000003 0.000242 +-0.007642 0.000000 -0.999971 +-0.007642 0.000000 -0.999971 +-0.007642 0.000000 -0.999971 +1.000000 0.000000 -0.000243 +1.000000 0.000000 -0.000243 +1.000000 0.000000 -0.000243 +-0.007344 0.000000 -0.999973 +-0.007344 0.000000 -0.999973 +-0.007344 0.000000 -0.999973 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000000 0.000241 +-1.000000 0.000000 0.000241 +-1.000000 0.000000 0.000241 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000241 +1.000000 0.000000 -0.000241 +1.000000 0.000000 -0.000241 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000000 0.000240 +-1.000000 0.000000 0.000240 +-1.000000 0.000000 0.000240 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +-0.007679 0.000000 -0.999971 +-0.007679 0.000000 -0.999970 +-0.007679 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-0.007642 0.000000 -0.999971 +-0.007642 0.000000 -0.999971 +-0.007642 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +-0.007456 0.000000 -0.999972 +-0.007456 0.000000 -0.999972 +-0.007456 0.000000 -0.999972 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007642 0.000000 -0.999971 +-0.007642 0.000000 -0.999971 +-0.007642 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +-0.007456 0.000000 -0.999972 +-0.007456 0.000000 -0.999972 +-0.007456 0.000000 -0.999972 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000003 0.000242 +-1.000000 0.000003 0.000242 +-1.000000 0.000003 0.000242 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +-0.007679 0.000000 -0.999971 +-0.007679 0.000000 -0.999970 +-0.007679 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000003 0.999971 +0.007640 0.000003 0.999971 +0.007640 0.000003 0.999971 +-1.000000 0.000000 0.000241 +-1.000000 0.000000 0.000241 +-1.000000 0.000000 0.000241 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000003 0.000242 +-1.000000 0.000003 0.000242 +-1.000000 0.000003 0.000242 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.000240 0.000003 1.000000 +0.000240 0.000003 1.000000 +0.000240 0.000003 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +-0.999971 0.000000 0.007664 +-0.999971 0.000000 0.007664 +-0.999971 0.000000 0.007664 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000240 0.000003 1.000000 +0.000240 0.000003 1.000000 +0.000240 0.000003 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000000 0.007641 +-0.999971 0.000000 0.007641 +-0.999971 0.000000 0.007641 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.000240 0.000003 1.000000 +0.000240 0.000003 1.000000 +0.000240 0.000003 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007637 +0.999971 0.000000 -0.007637 +0.999971 0.000000 -0.007637 +0.000241 0.000000 1.000000 +0.000241 0.000000 1.000000 +0.000241 0.000000 1.000000 +-0.999971 0.000000 0.007641 +-0.999971 0.000000 0.007641 +-0.999971 0.000000 0.007641 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +-0.999971 0.000000 0.007588 +-0.999971 0.000000 0.007588 +-0.999971 0.000000 0.007588 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000241 0.000002 1.000000 +0.000241 0.000002 1.000000 +0.000241 0.000002 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +-0.000241 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.999971 0.000000 -0.007640 +0.000240 0.000003 1.000000 +0.000240 0.000003 1.000000 +0.000240 0.000003 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.000243 0.000000 -1.000000 +-0.000243 0.000000 -1.000000 +-0.000243 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000242 0.000002 1.000000 +0.000242 0.000002 1.000000 +0.000242 0.000002 1.000000 +-0.999971 0.000000 0.007642 +-0.999971 0.000000 0.007642 +-0.999971 0.000000 0.007642 +-0.000243 0.000000 -1.000000 +-0.000243 0.000000 -1.000000 +-0.000243 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007635 +0.999971 0.000000 -0.007635 +0.999971 0.000000 -0.007635 +0.000241 0.000000 1.000000 +0.000241 0.000000 1.000000 +0.000241 0.000000 1.000000 +-0.999971 0.000000 0.007645 +-0.999971 0.000000 0.007645 +-0.999971 0.000000 0.007645 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-0.007641 0.000000 -0.999971 +-0.007641 0.000000 -0.999971 +-0.007641 0.000000 -0.999971 +1.000000 0.000000 -0.000241 +1.000000 0.000000 -0.000241 +1.000000 0.000000 -0.000241 +-0.007624 0.000000 -0.999971 +-0.007624 0.000000 -0.999971 +-0.007624 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000000 0.000240 +-1.000000 0.000000 0.000240 +-1.000000 0.000000 0.000240 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +-0.007679 0.000000 -0.999971 +-0.007679 0.000000 -0.999970 +-0.007679 0.000000 -0.999970 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +-0.007512 0.000000 -0.999972 +-0.007512 0.000000 -0.999972 +-0.007512 0.000000 -0.999972 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000002 0.999971 +0.007639 0.000002 0.999971 +0.007639 0.000002 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007641 0.000000 -0.999971 +-0.007641 0.000000 -0.999971 +-0.007641 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +-0.007511 0.000000 -0.999972 +-0.007511 0.000000 -0.999972 +-0.007511 0.000000 -0.999972 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +-1.000000 0.000003 0.000242 +-1.000000 0.000003 0.000242 +-1.000000 0.000003 0.000242 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +-0.007624 0.000000 -0.999971 +-0.007624 0.000000 -0.999971 +-0.007624 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-0.007641 0.000000 -0.999971 +-0.007641 0.000000 -0.999971 +-0.007641 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +-1.000000 0.000000 0.000241 +-1.000000 0.000000 0.000241 +-1.000000 0.000000 0.000241 +-0.007641 0.000000 -0.999971 +-0.007641 0.000000 -0.999971 +-0.007641 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +-0.007456 0.000000 -0.999972 +-0.007456 0.000000 -0.999972 +-0.007456 0.000000 -0.999972 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007642 0.000000 -0.999971 +-0.007642 0.000000 -0.999971 +-0.007642 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +-1.000000 0.000003 0.000242 +-1.000000 0.000003 0.000242 +-1.000000 0.000003 0.000242 +-0.007641 0.000000 -0.999971 +-0.007641 0.000000 -0.999971 +-0.007641 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +-0.007512 0.000000 -0.999972 +-0.007512 0.000000 -0.999972 +-0.007512 0.000000 -0.999972 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000243 +1.000000 0.000000 -0.000243 +1.000000 0.000000 -0.000243 +-0.007512 0.000000 -0.999972 +-0.007512 0.000000 -0.999972 +-0.007512 0.000000 -0.999972 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000003 0.000242 +-1.000000 0.000003 0.000242 +-1.000000 0.000003 0.000242 +-0.007641 0.000000 -0.999971 +-0.007641 0.000000 -0.999971 +-0.007641 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +-0.007512 0.000000 -0.999972 +-0.007512 0.000000 -0.999972 +-0.007512 0.000000 -0.999972 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007642 0.000000 -0.999971 +-0.007642 0.000000 -0.999971 +-0.007642 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-0.007641 0.000000 -0.999971 +-0.007641 0.000000 -0.999971 +-0.007641 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007641 0.000000 -0.999971 +-0.007641 0.000000 -0.999971 +-0.007641 0.000000 -0.999971 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +-0.007624 0.000000 -0.999971 +-0.007624 0.000000 -0.999971 +-0.007624 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-0.007641 0.000000 -0.999971 +-0.007641 0.000000 -0.999971 +-0.007641 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +-1.000000 0.000000 0.000241 +-1.000000 0.000000 0.000241 +-1.000000 0.000000 0.000241 +-0.007641 0.000000 -0.999971 +-0.007641 0.000000 -0.999971 +-0.007641 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +-0.007568 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +-1.000000 0.000003 0.000242 +-1.000000 0.000003 0.000242 +-1.000000 0.000003 0.000242 +-0.007641 0.000000 -0.999971 +-0.007641 0.000000 -0.999971 +-0.007641 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +-0.007512 -0.000002 -0.999972 +-0.007512 -0.000002 -0.999972 +-0.007512 -0.000002 -0.999972 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +-0.007639 0.000000 -0.999971 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-0.007641 0.000000 -0.999971 +-0.007641 0.000000 -0.999971 +-0.007641 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007640 0.000000 -0.999971 +-0.007640 0.000000 -0.999971 +-0.007640 0.000000 -0.999971 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.000242 -0.000001 -1.000000 +-0.000242 -0.000001 -1.000000 +-0.000242 -0.000001 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.000241 0.000003 1.000000 +0.000241 0.000003 1.000000 +0.000241 0.000003 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.000241 0.000003 1.000000 +0.000241 0.000003 1.000000 +0.000241 0.000003 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.000241 0.000003 1.000000 +0.000241 0.000003 1.000000 +0.000241 0.000003 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.000241 0.000001 1.000000 +0.000241 0.000001 1.000000 +0.000241 0.000001 1.000000 +-0.999971 0.000000 0.007642 +-0.999971 0.000000 0.007642 +-0.999971 0.000000 0.007642 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007641 0.000000 0.999971 +0.007641 0.000000 0.999971 +0.007641 0.000000 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007641 0.000000 0.999971 +0.007641 0.000000 0.999971 +0.007641 0.000000 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-0.007641 0.000000 -0.999971 +-0.007641 0.000000 -0.999971 +-0.007641 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-0.007640 0.000000 -0.999971 +-0.007640 0.000000 -0.999971 +-0.007640 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-0.007641 -0.000001 -0.999971 +-0.007641 -0.000001 -0.999971 +-0.007641 -0.000001 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +-0.007661 0.000000 -0.999971 +-0.007661 0.000000 -0.999971 +-0.007661 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007640 0.000000 -0.999971 +-0.007640 0.000000 -0.999971 +-0.007640 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007640 0.000000 -0.999971 +-0.007640 0.000000 -0.999971 +-0.007640 0.000000 -0.999971 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.000240 0.000003 1.000000 +0.000240 0.000003 1.000000 +0.000240 0.000003 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.000241 0.000001 1.000000 +0.000241 0.000001 1.000000 +0.000241 0.000001 1.000000 +-0.999971 0.000000 0.007642 +-0.999971 0.000000 0.007642 +-0.999971 0.000000 0.007642 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.000241 0.000001 1.000000 +0.000241 0.000001 1.000000 +0.000241 0.000001 1.000000 +-0.999971 0.000000 0.007642 +-0.999971 0.000000 0.007642 +-0.999971 0.000000 0.007642 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007641 0.000000 0.999971 +0.007641 0.000000 0.999971 +0.007641 0.000000 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-0.007640 0.000000 -0.999971 +-0.007640 0.000000 -0.999971 +-0.007640 0.000000 -0.999971 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007641 0.000001 0.999971 +0.007641 0.000001 0.999971 +0.007641 0.000001 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-0.007640 0.000000 -0.999971 +-0.007640 0.000000 -0.999971 +-0.007640 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +0.007640 0.000000 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +0.007638 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007456 0.000000 -0.999972 +-0.007456 0.000000 -0.999972 +-0.007456 0.000000 -0.999972 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-0.007641 0.000000 -0.999971 +-0.007641 0.000000 -0.999971 +-0.007641 0.000000 -0.999971 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +1.000000 0.000000 -0.000242 +-0.007661 0.000000 -0.999971 +-0.007661 0.000000 -0.999971 +-0.007661 0.000000 -0.999971 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +0.007639 0.000000 0.999971 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-1.000000 0.000000 0.000242 +-0.007640 0.000000 -0.999971 +-0.007640 0.000000 -0.999971 +-0.007640 0.000000 -0.999971 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999971 0.000000 0.007589 +-0.999971 0.000000 0.007589 +-0.999971 0.000000 0.007589 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999971 0.000000 0.007589 +-0.999971 0.000000 0.007589 +-0.999971 0.000000 0.007589 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.999971 0.000000 -0.007639 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +0.000242 0.000000 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.000240 0.000003 1.000000 +0.000240 0.000003 1.000000 +0.000240 0.000003 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +-0.000242 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.000240 0.000003 1.000000 +0.000240 0.000003 1.000000 +0.000240 0.000003 1.000000 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +-0.999971 0.000000 0.007640 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.000241 0.000001 1.000000 +0.000241 0.000001 1.000000 +0.000241 0.000001 1.000000 +-0.999971 0.000000 0.007642 +-0.999971 0.000000 0.007642 +-0.999971 0.000000 0.007642 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +-0.000240 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.999971 0.000000 -0.007641 +0.000241 0.000001 1.000000 +0.000241 0.000001 1.000000 +0.000241 0.000001 1.000000 +-0.999971 0.000000 0.007642 +-0.999971 0.000000 0.007642 +-0.999971 0.000000 0.007642 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007641 0.000000 0.999971 +0.007641 0.000000 0.999971 +0.007641 0.000000 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-0.007641 0.000000 -0.999971 +-0.007641 0.000000 -0.999971 +-0.007641 0.000000 -0.999971 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +1.000000 0.000000 -0.000240 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.007641 0.000000 0.999971 +0.007641 0.000000 0.999971 +0.007641 0.000000 0.999971 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-1.000000 0.000003 0.000240 +-0.007640 0.000000 -0.999971 +-0.007640 0.000000 -0.999971 +-0.007640 0.000000 -0.999971 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998106 0.061525 0.000000 +0.998106 0.061525 0.000000 +0.998106 0.061525 0.000000 +0.000000 0.080183 -0.996780 +0.000000 0.080183 -0.996780 +0.000000 0.080183 -0.996780 +-0.998106 0.061525 0.000000 +-0.998106 0.061525 0.000000 +-0.998106 0.061525 0.000000 +0.000000 0.085726 0.996319 +0.000000 0.085726 0.996319 +0.000000 0.085726 0.996319 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998103 0.061563 0.000000 +0.998103 0.061563 0.000000 +0.998103 0.061563 0.000000 +0.000000 0.080233 -0.996776 +0.000000 0.080233 -0.996776 +0.000000 0.080233 -0.996776 +-0.998103 0.061563 0.000000 +-0.998103 0.061563 0.000000 +-0.998103 0.061563 0.000000 +0.000000 0.085779 0.996314 +0.000000 0.085779 0.996314 +0.000000 0.085779 0.996314 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998099 0.061626 0.000000 +0.998099 0.061626 0.000000 +0.998099 0.061626 0.000000 +0.000000 0.080315 -0.996770 +0.000000 0.080314 -0.996770 +0.000000 0.080314 -0.996770 +-0.998099 0.061626 0.000000 +-0.998099 0.061626 0.000000 +-0.998099 0.061626 0.000000 +0.000000 0.085866 0.996307 +0.000000 0.085866 0.996307 +0.000000 0.085866 0.996307 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998102 0.061580 0.000000 +0.998102 0.061580 0.000000 +0.998102 0.061580 0.000000 +0.000000 0.080254 -0.996774 +0.000000 0.080254 -0.996774 +0.000000 0.080254 -0.996774 +-0.998102 0.061579 0.000000 +-0.998102 0.061579 0.000000 +-0.998102 0.061579 0.000000 +0.000000 0.085802 0.996312 +0.000000 0.085802 0.996312 +0.000000 0.085802 0.996312 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998106 0.061525 0.000000 +0.998106 0.061525 0.000000 +0.998106 0.061525 0.000000 +0.000000 0.080183 -0.996780 +0.000000 0.080183 -0.996780 +0.000000 0.080183 -0.996780 +-0.998106 0.061525 0.000000 +-0.998106 0.061525 0.000000 +-0.998106 0.061525 0.000000 +0.000000 0.085726 0.996319 +0.000000 0.085726 0.996319 +0.000000 0.085726 0.996319 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998103 0.061563 0.000000 +0.998103 0.061563 0.000000 +0.998103 0.061563 0.000000 +0.000000 0.080233 -0.996776 +0.000000 0.080233 -0.996776 +0.000000 0.080233 -0.996776 +-0.998103 0.061563 0.000000 +-0.998103 0.061563 0.000000 +-0.998103 0.061563 0.000000 +0.000000 0.085779 0.996314 +0.000000 0.085779 0.996314 +0.000000 0.085779 0.996314 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998099 0.061626 0.000000 +0.998099 0.061626 0.000000 +0.998099 0.061626 0.000000 +0.000000 0.080314 -0.996770 +0.000000 0.080314 -0.996770 +0.000000 0.080314 -0.996770 +-0.998099 0.061626 0.000000 +-0.998099 0.061626 0.000000 +-0.998099 0.061626 0.000000 +0.000000 0.085866 0.996307 +0.000000 0.085866 0.996307 +0.000000 0.085866 0.996307 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998102 0.061580 0.000000 +0.998102 0.061580 0.000000 +0.998102 0.061580 0.000000 +0.000000 0.080255 -0.996774 +0.000000 0.080255 -0.996774 +0.000000 0.080255 -0.996774 +-0.998102 0.061579 0.000000 +-0.998102 0.061579 0.000000 +-0.998102 0.061579 0.000000 +0.000000 0.085802 0.996312 +0.000000 0.085802 0.996312 +0.000000 0.085802 0.996312 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -0.086950 -0.996213 +0.000000 -0.086950 -0.996213 +0.000000 -0.086950 -0.996213 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.000000 -0.086945 0.996213 +0.000000 -0.086945 0.996213 +0.000000 -0.086945 0.996213 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.061527 0.998105 +0.000000 0.061527 0.998105 +0.000000 0.061527 0.998105 +0.996780 0.080182 0.000000 +0.996780 0.080183 0.000000 +0.996780 0.080182 0.000000 +0.000000 0.061523 -0.998106 +0.000000 0.061523 -0.998106 +0.000000 0.061523 -0.998106 +-0.996319 0.085726 0.000000 +-0.996319 0.085726 0.000000 +-0.996319 0.085726 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -0.086945 -0.996213 +0.000000 -0.086945 -0.996213 +0.000000 -0.086945 -0.996213 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.000000 -0.086945 0.996213 +0.000000 -0.086945 0.996213 +0.000000 -0.086945 0.996213 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.061561 0.998103 +0.000000 0.061561 0.998103 +0.000000 0.061561 0.998103 +0.996776 0.080232 0.000000 +0.996776 0.080232 0.000000 +0.996776 0.080232 0.000000 +0.000000 0.061561 -0.998103 +0.000000 0.061561 -0.998103 +0.000000 0.061561 -0.998103 +-0.996314 0.085778 0.000000 +-0.996314 0.085778 0.000000 +-0.996314 0.085778 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -0.086945 -0.996213 +0.000000 -0.086945 -0.996213 +0.000000 -0.086945 -0.996213 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.000000 -0.086950 0.996213 +0.000000 -0.086950 0.996213 +0.000000 -0.086950 0.996213 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.061625 0.998099 +0.000000 0.061625 0.998099 +0.000000 0.061625 0.998099 +0.996770 0.080314 0.000000 +0.996770 0.080314 0.000000 +0.996770 0.080314 0.000000 +0.000000 0.061628 -0.998099 +0.000000 0.061628 -0.998099 +0.000000 0.061628 -0.998099 +-0.996307 0.085866 0.000000 +-0.996307 0.085866 0.000000 +-0.996307 0.085866 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -0.086950 -0.996213 +0.000000 -0.086950 -0.996213 +0.000000 -0.086950 -0.996213 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.000000 -0.086950 0.996213 +0.000000 -0.086950 0.996213 +0.000000 -0.086950 0.996213 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.061582 0.998102 +0.000000 0.061582 0.998102 +0.000000 0.061582 0.998102 +0.996774 0.080254 0.000000 +0.996774 0.080254 0.000000 +0.996774 0.080254 0.000000 +0.000000 0.061582 -0.998102 +0.000000 0.061582 -0.998102 +0.000000 0.061582 -0.998102 +-0.996312 0.085802 0.000000 +-0.996312 0.085802 0.000000 +-0.996312 0.085802 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998106 0.061525 0.000000 +0.998106 0.061525 0.000000 +0.998106 0.061525 0.000000 +0.000000 0.080183 -0.996780 +0.000000 0.080183 -0.996780 +0.000000 0.080183 -0.996780 +-0.998106 0.061525 0.000000 +-0.998106 0.061525 0.000000 +-0.998106 0.061525 0.000000 +0.000000 0.085726 0.996319 +0.000000 0.085726 0.996319 +0.000000 0.085726 0.996319 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998103 0.061563 0.000000 +0.998103 0.061563 0.000000 +0.998103 0.061563 0.000000 +0.000000 0.080233 -0.996776 +0.000000 0.080233 -0.996776 +0.000000 0.080233 -0.996776 +-0.998103 0.061563 0.000000 +-0.998103 0.061563 0.000000 +-0.998103 0.061563 0.000000 +0.000000 0.085779 0.996314 +0.000000 0.085779 0.996314 +0.000000 0.085779 0.996314 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998099 0.061626 0.000000 +0.998099 0.061626 0.000000 +0.998099 0.061626 0.000000 +0.000000 0.080315 -0.996770 +0.000000 0.080314 -0.996770 +0.000000 0.080314 -0.996770 +-0.998099 0.061626 0.000000 +-0.998099 0.061626 0.000000 +-0.998099 0.061626 0.000000 +0.000000 0.085866 0.996307 +0.000000 0.085866 0.996307 +0.000000 0.085866 0.996307 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998102 0.061580 0.000000 +0.998102 0.061580 0.000000 +0.998102 0.061580 0.000000 +0.000000 0.080254 -0.996774 +0.000000 0.080254 -0.996774 +0.000000 0.080254 -0.996774 +-0.998102 0.061579 0.000000 +-0.998102 0.061579 0.000000 +-0.998102 0.061579 0.000000 +0.000000 0.085802 0.996312 +0.000000 0.085802 0.996312 +0.000000 0.085802 0.996312 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998106 0.061525 0.000000 +0.998106 0.061525 0.000000 +0.998106 0.061525 0.000000 +0.000000 0.080183 -0.996780 +0.000000 0.080183 -0.996780 +0.000000 0.080183 -0.996780 +-0.998106 0.061525 0.000000 +-0.998106 0.061525 0.000000 +-0.998106 0.061525 0.000000 +0.000000 0.085726 0.996319 +0.000000 0.085726 0.996319 +0.000000 0.085726 0.996319 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998103 0.061563 0.000000 +0.998103 0.061563 0.000000 +0.998103 0.061563 0.000000 +0.000000 0.080233 -0.996776 +0.000000 0.080233 -0.996776 +0.000000 0.080233 -0.996776 +-0.998103 0.061563 0.000000 +-0.998103 0.061563 0.000000 +-0.998103 0.061563 0.000000 +0.000000 0.085779 0.996314 +0.000000 0.085779 0.996314 +0.000000 0.085779 0.996314 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998102 0.061580 0.000000 +0.998102 0.061580 0.000000 +0.998102 0.061580 0.000000 +0.000000 0.080254 -0.996774 +0.000000 0.080254 -0.996774 +0.000000 0.080254 -0.996774 +-0.998102 0.061579 0.000000 +-0.998102 0.061579 0.000000 +-0.998102 0.061579 0.000000 +0.000000 0.085802 0.996312 +0.000000 0.085802 0.996312 +0.000000 0.085802 0.996312 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000000 -0.000001 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -0.086947 -0.996213 +0.000000 -0.086947 -0.996213 +0.000000 -0.086947 -0.996213 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.000000 -0.086947 0.996213 +0.000000 -0.086947 0.996213 +0.000000 -0.086947 0.996213 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.061525 0.998106 +0.000000 0.061525 0.998106 +0.000000 0.061525 0.998106 +0.996780 0.080183 0.000000 +0.996780 0.080183 0.000000 +0.996780 0.080183 0.000000 +0.000000 0.061525 -0.998106 +0.000000 0.061525 -0.998105 +0.000000 0.061525 -0.998105 +-0.996319 0.085726 0.000000 +-0.996319 0.085726 0.000000 +-0.996319 0.085726 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -0.000001 -1.000000 +0.000000 -0.000001 -1.000000 +0.000001 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000001 -0.086945 -0.996213 +0.000001 -0.086945 -0.996213 +0.000001 -0.086945 -0.996213 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.000000 -0.086947 0.996213 +0.000000 -0.086947 0.996213 +0.000000 -0.086947 0.996213 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.061561 0.998103 +0.000000 0.061561 0.998103 +0.000000 0.061561 0.998103 +0.996776 0.080232 0.000000 +0.996776 0.080232 0.000000 +0.996776 0.080232 0.000000 +0.000000 0.061563 -0.998103 +0.000000 0.061563 -0.998103 +0.000000 0.061563 -0.998103 +-0.996314 0.085778 0.000000 +-0.996314 0.085778 0.000000 +-0.996314 0.085778 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.000001 0.000001 1.000000 +0.000000 0.000000 1.000000 +-0.000001 0.000001 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -0.086947 -0.996213 +0.000000 -0.086947 -0.996213 +0.000000 -0.086947 -0.996213 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.000000 -0.086950 0.996213 +-0.000001 -0.086947 0.996213 +0.000000 -0.086950 0.996213 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.061626 0.998099 +0.000000 0.061626 0.998099 +0.000000 0.061626 0.998099 +0.996770 0.080314 0.000000 +0.996770 0.080314 0.000000 +0.996770 0.080314 0.000000 +0.000000 0.061626 -0.998099 +0.000000 0.061626 -0.998099 +0.000000 0.061626 -0.998099 +-0.996307 0.085866 0.000000 +-0.996307 0.085866 0.000000 +-0.996307 0.085866 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -0.086947 -0.996213 +0.000000 -0.086947 -0.996213 +0.000000 -0.086947 -0.996213 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.000000 -0.086947 0.996213 +0.000000 -0.086947 0.996213 +0.000000 -0.086947 0.996213 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.061578 0.998102 +0.000000 0.061578 0.998102 +0.000000 0.061578 0.998102 +0.996774 0.080254 0.000000 +0.996774 0.080254 0.000000 +0.996774 0.080254 0.000000 +0.000000 0.061580 -0.998102 +0.000000 0.061580 -0.998102 +0.000000 0.061580 -0.998102 +-0.996312 0.085802 0.000000 +-0.996312 0.085802 0.000000 +-0.996312 0.085802 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -0.086947 -0.996213 +0.000000 -0.086947 -0.996213 +0.000000 -0.086947 -0.996213 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.000000 -0.086947 0.996213 +0.000000 -0.086947 0.996213 +0.000000 -0.086947 0.996213 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.061563 0.998103 +0.000000 0.061563 0.998103 +0.000000 0.061563 0.998103 +0.996776 0.080232 0.000000 +0.996776 0.080232 0.000000 +0.996776 0.080232 0.000000 +0.000000 0.061562 -0.998103 +0.000000 0.061562 -0.998103 +0.000000 0.061562 -0.998103 +-0.996314 0.085778 0.000000 +-0.996314 0.085778 0.000000 +-0.996314 0.085778 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -0.086947 -0.996213 +0.000000 -0.086947 -0.996213 +0.000000 -0.086947 -0.996213 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.000000 -0.086947 0.996213 +0.000000 -0.086947 0.996213 +0.000000 -0.086947 0.996213 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.061626 0.998099 +0.000000 0.061626 0.998099 +0.000000 0.061626 0.998099 +0.996770 0.080314 0.000000 +0.996770 0.080314 0.000000 +0.996770 0.080314 0.000000 +0.000000 0.061625 -0.998099 +0.000000 0.061625 -0.998099 +0.000000 0.061625 -0.998099 +-0.996307 0.085866 0.000000 +-0.996307 0.085866 0.000000 +-0.996307 0.085866 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -0.086947 -0.996213 +0.000000 -0.086947 -0.996213 +0.000000 -0.086947 -0.996213 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.000000 -0.086947 0.996213 +0.000000 -0.086947 0.996213 +0.000000 -0.086947 0.996213 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.061580 0.998102 +0.000000 0.061580 0.998102 +0.000000 0.061580 0.998102 +0.996774 0.080254 0.000000 +0.996774 0.080254 0.000000 +0.996775 0.080254 0.000000 +0.000000 0.061579 -0.998102 +0.000000 0.061579 -0.998102 +0.000000 0.061579 -0.998102 +-0.996312 0.085802 0.000000 +-0.996312 0.085802 0.000000 +-0.996312 0.085802 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998105 0.061525 0.000000 +0.998106 0.061525 0.000000 +0.998106 0.061525 0.000000 +0.000000 0.080182 -0.996780 +0.000000 0.080182 -0.996780 +0.000000 0.080182 -0.996780 +-0.998106 0.061525 0.000000 +-0.998106 0.061525 0.000000 +-0.998106 0.061525 0.000000 +0.000000 0.085726 0.996319 +0.000000 0.085726 0.996319 +0.000000 0.085726 0.996319 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998103 0.061563 0.000000 +0.998103 0.061563 0.000000 +0.998103 0.061563 0.000000 +0.000000 0.080232 -0.996776 +0.000000 0.080232 -0.996776 +0.000000 0.080232 -0.996776 +-0.998103 0.061563 0.000000 +-0.998103 0.061563 0.000000 +-0.998103 0.061563 0.000000 +0.000000 0.085778 0.996314 +0.000000 0.085778 0.996314 +0.000000 0.085778 0.996314 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998099 0.061626 0.000000 +0.998099 0.061626 0.000000 +0.998099 0.061626 0.000000 +0.000000 0.080314 -0.996770 +0.000000 0.080314 -0.996770 +0.000000 0.080314 -0.996770 +-0.998099 0.061626 0.000000 +-0.998099 0.061626 0.000000 +-0.998099 0.061626 0.000000 +0.000000 0.085866 0.996307 +0.000000 0.085866 0.996307 +0.000000 0.085866 0.996307 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998102 0.061580 0.000000 +0.998102 0.061580 0.000000 +0.998102 0.061580 0.000000 +0.000000 0.080254 -0.996774 +0.000000 0.080254 -0.996774 +0.000000 0.080254 -0.996774 +-0.998102 0.061579 0.000000 +-0.998102 0.061579 0.000000 +-0.998102 0.061579 0.000000 +0.000000 0.085802 0.996312 +0.000000 0.085802 0.996312 +0.000000 0.085802 0.996312 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -0.086950 -0.996213 +0.000000 -0.086950 -0.996213 +0.000000 -0.086950 -0.996213 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.000000 -0.086945 0.996213 +0.000000 -0.086945 0.996213 +0.000000 -0.086945 0.996213 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.061527 0.998105 +0.000000 0.061527 0.998105 +0.000000 0.061527 0.998105 +0.996780 0.080183 0.000000 +0.996780 0.080183 0.000000 +0.996780 0.080183 0.000000 +0.000000 0.061523 -0.998106 +0.000000 0.061523 -0.998106 +0.000000 0.061523 -0.998106 +-0.996319 0.085726 0.000000 +-0.996319 0.085726 0.000000 +-0.996319 0.085726 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -0.086945 -0.996213 +0.000000 -0.086945 -0.996213 +0.000000 -0.086945 -0.996213 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.000000 -0.086945 0.996213 +0.000000 -0.086945 0.996213 +0.000000 -0.086945 0.996213 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.061561 0.998103 +0.000000 0.061561 0.998103 +0.000000 0.061561 0.998103 +0.996776 0.080232 0.000000 +0.996776 0.080232 0.000000 +0.996776 0.080232 0.000000 +0.000000 0.061561 -0.998103 +0.000000 0.061561 -0.998103 +0.000000 0.061561 -0.998103 +-0.996314 0.085778 0.000000 +-0.996314 0.085778 0.000000 +-0.996314 0.085778 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -0.086945 -0.996213 +0.000000 -0.086945 -0.996213 +0.000000 -0.086945 -0.996213 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.000000 -0.086950 0.996213 +0.000000 -0.086950 0.996213 +0.000000 -0.086950 0.996213 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.061625 0.998099 +0.000000 0.061625 0.998099 +0.000000 0.061625 0.998099 +0.996770 0.080314 0.000000 +0.996770 0.080314 0.000000 +0.996770 0.080314 0.000000 +0.000000 0.061628 -0.998099 +0.000000 0.061628 -0.998099 +0.000000 0.061628 -0.998099 +-0.996307 0.085866 0.000000 +-0.996307 0.085866 0.000000 +-0.996307 0.085866 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -0.086950 -0.996213 +0.000000 -0.086950 -0.996213 +0.000000 -0.086950 -0.996213 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.000000 -0.086950 0.996213 +0.000000 -0.086950 0.996213 +0.000000 -0.086950 0.996213 +-0.993768 -0.111467 0.000000 +-0.993768 -0.111467 0.000000 +-0.993768 -0.111467 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.061582 0.998102 +0.000000 0.061582 0.998102 +0.000000 0.061582 0.998102 +0.996774 0.080254 0.000000 +0.996774 0.080254 0.000000 +0.996774 0.080254 0.000000 +0.000000 0.061582 -0.998102 +0.000000 0.061582 -0.998102 +0.000000 0.061582 -0.998102 +-0.996312 0.085802 0.000000 +-0.996312 0.085802 0.000000 +-0.996312 0.085802 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998106 0.061525 0.000000 +0.998106 0.061525 0.000000 +0.998106 0.061525 0.000000 +0.000000 0.080183 -0.996780 +0.000000 0.080183 -0.996780 +0.000000 0.080183 -0.996780 +-0.998106 0.061525 0.000000 +-0.998106 0.061525 0.000000 +-0.998106 0.061525 0.000000 +0.000000 0.085726 0.996319 +0.000000 0.085726 0.996319 +0.000000 0.085726 0.996319 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.080233 -0.996776 +0.000000 0.080233 -0.996776 +0.000000 0.080233 -0.996776 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.080315 -0.996769 +0.000000 0.080315 -0.996770 +0.000000 0.080315 -0.996770 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998102 0.061580 0.000000 +0.998102 0.061580 0.000000 +0.998102 0.061580 0.000000 +0.000000 0.080255 -0.996774 +0.000000 0.080255 -0.996774 +0.000000 0.080255 -0.996774 +-0.998102 0.061579 0.000000 +-0.998102 0.061579 0.000000 +-0.998102 0.061579 0.000000 +0.000000 0.085802 0.996312 +0.000000 0.085802 0.996312 +0.000000 0.085802 0.996312 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.085779 0.996314 +0.000000 0.085779 0.996314 +0.000000 0.085779 0.996314 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998103 0.061563 0.000000 +0.998103 0.061563 0.000000 +0.998103 0.061563 0.000000 +-0.998103 0.061563 0.000000 +-0.998103 0.061563 0.000000 +-0.998103 0.061563 0.000000 +0.000000 0.085779 0.996314 +0.000000 0.085779 0.996314 +0.000000 0.085779 0.996314 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998099 0.061626 0.000000 +0.998099 0.061626 0.000000 +0.998099 0.061626 0.000000 +-0.998099 0.061626 0.000000 +-0.998099 0.061626 0.000000 +-0.998099 0.061626 0.000000 +0.000000 0.085866 0.996307 +0.000000 0.085866 0.996307 +0.000000 0.085866 0.996307 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998106 0.061525 0.000000 +0.998106 0.061525 0.000000 +0.998106 0.061525 0.000000 +0.000000 0.080183 -0.996780 +0.000000 0.080183 -0.996780 +0.000000 0.080183 -0.996780 +-0.998106 0.061525 0.000000 +-0.998106 0.061525 0.000000 +-0.998106 0.061525 0.000000 +0.000000 0.085726 0.996319 +0.000000 0.085726 0.996319 +0.000000 0.085726 0.996319 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998103 0.061563 0.000000 +0.998103 0.061563 0.000000 +0.998103 0.061563 0.000000 +0.000000 0.080233 -0.996776 +0.000000 0.080233 -0.996776 +0.000000 0.080233 -0.996776 +-0.998103 0.061563 0.000000 +-0.998103 0.061563 0.000000 +-0.998103 0.061563 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998102 0.061580 0.000000 +0.998102 0.061580 0.000000 +0.998102 0.061580 0.000000 +0.000000 0.080255 -0.996774 +0.000000 0.080255 -0.996774 +0.000000 0.080255 -0.996774 +-0.998102 0.061579 0.000000 +-0.998102 0.061579 0.000000 +-0.998102 0.061579 0.000000 +0.000000 0.085802 0.996312 +0.000000 0.085802 0.996312 +0.000000 0.085802 0.996312 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998106 0.061525 0.000000 +0.998106 0.061525 0.000000 +0.998106 0.061525 0.000000 +0.000000 0.080183 -0.996780 +0.000000 0.080183 -0.996780 +0.000000 0.080183 -0.996780 +-0.998106 0.061525 0.000000 +-0.998106 0.061525 0.000000 +-0.998106 0.061525 0.000000 +0.000000 0.085726 0.996319 +0.000000 0.085726 0.996319 +0.000000 0.085726 0.996319 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998103 0.061563 0.000000 +0.998103 0.061563 0.000000 +0.998103 0.061563 0.000000 +0.000000 0.080233 -0.996776 +0.000000 0.080233 -0.996776 +0.000000 0.080233 -0.996776 +-0.998103 0.061563 0.000000 +-0.998103 0.061563 0.000000 +-0.998103 0.061563 0.000000 +0.000000 0.085779 0.996314 +0.000000 0.085779 0.996314 +0.000000 0.085779 0.996314 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998099 0.061626 0.000000 +0.998099 0.061626 0.000000 +0.998099 0.061626 0.000000 +0.000000 0.080314 -0.996770 +0.000000 0.080314 -0.996770 +0.000000 0.080314 -0.996770 +-0.998099 0.061626 0.000000 +-0.998099 0.061626 0.000000 +-0.998099 0.061626 0.000000 +0.000000 0.085866 0.996307 +0.000000 0.085866 0.996307 +0.000000 0.085866 0.996307 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998102 0.061580 0.000000 +0.998102 0.061580 0.000000 +0.998102 0.061580 0.000000 +0.000000 0.080254 -0.996774 +0.000000 0.080254 -0.996774 +0.000000 0.080254 -0.996774 +-0.998102 0.061579 0.000000 +-0.998102 0.061579 0.000000 +-0.998102 0.061579 0.000000 +0.000000 0.085802 0.996312 +0.000000 0.085802 0.996312 +0.000000 0.085802 0.996312 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998105 0.061525 0.000000 +0.998106 0.061525 0.000000 +0.998105 0.061525 0.000000 +0.000000 0.080183 -0.996780 +0.000000 0.080183 -0.996780 +0.000000 0.080183 -0.996780 +-0.998105 0.061525 0.000000 +-0.998106 0.061525 0.000000 +-0.998105 0.061525 0.000000 +0.000000 0.085726 0.996319 +0.000000 0.085726 0.996319 +0.000000 0.085726 0.996319 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998103 0.061563 0.000000 +0.998103 0.061563 0.000000 +0.998103 0.061563 0.000000 +0.000000 0.080233 -0.996776 +0.000000 0.080233 -0.996776 +0.000000 0.080233 -0.996776 +-0.998103 0.061563 0.000000 +-0.998103 0.061563 0.000000 +-0.998103 0.061563 0.000000 +0.000000 0.085779 0.996314 +0.000000 0.085779 0.996314 +0.000000 0.085779 0.996314 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998099 0.061626 0.000000 +0.998099 0.061626 0.000000 +0.998099 0.061626 0.000000 +0.000000 0.080314 -0.996770 +0.000000 0.080314 -0.996770 +0.000000 0.080314 -0.996770 +-0.998099 0.061626 0.000000 +-0.998099 0.061626 0.000000 +-0.998099 0.061626 0.000000 +0.000000 0.085866 0.996307 +0.000000 0.085866 0.996307 +0.000000 0.085866 0.996307 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998102 0.061580 0.000000 +0.998102 0.061580 0.000000 +0.998102 0.061580 0.000000 +0.000000 0.080255 -0.996774 +0.000000 0.080255 -0.996774 +0.000000 0.080255 -0.996774 +-0.998102 0.061580 0.000000 +-0.998102 0.061580 0.000000 +-0.998102 0.061580 0.000000 +0.000000 0.085802 0.996312 +0.000000 0.085802 0.996312 +0.000000 0.085802 0.996312 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -0.000001 -1.000000 +0.000000 -0.000001 -1.000000 +0.000000 -0.000001 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -0.086947 -0.996213 +0.000000 -0.086947 -0.996213 +0.000000 -0.086947 -0.996213 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.000000 -0.086947 0.996213 +0.000000 -0.086947 0.996213 +0.000000 -0.086947 0.996213 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.061525 0.998106 +0.000000 0.061525 0.998105 +0.000000 0.061525 0.998106 +0.996780 0.080183 0.000000 +0.996780 0.080183 0.000000 +0.996780 0.080183 0.000000 +0.000000 0.061525 -0.998106 +0.000000 0.061525 -0.998105 +0.000000 0.061525 -0.998106 +-0.996319 0.085726 0.000000 +-0.996319 0.085726 0.000000 +-0.996319 0.085726 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -0.086947 -0.996213 +0.000000 -0.086947 -0.996213 +0.000000 -0.086947 -0.996213 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.000000 -0.086947 0.996213 +0.000000 -0.086947 0.996213 +0.000000 -0.086947 0.996213 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.061562 0.998103 +0.000000 0.061562 0.998103 +0.000000 0.061562 0.998103 +0.996776 0.080232 0.000000 +0.996776 0.080232 0.000000 +0.996776 0.080232 0.000000 +0.000000 0.061563 -0.998103 +0.000000 0.061563 -0.998103 +0.000000 0.061563 -0.998103 +-0.996314 0.085779 0.000000 +-0.996314 0.085779 0.000000 +-0.996314 0.085779 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -0.086947 -0.996213 +0.000000 -0.086947 -0.996213 +0.000000 -0.086947 -0.996213 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +-0.000001 -0.086947 0.996213 +-0.000001 -0.086947 0.996213 +-0.000001 -0.086947 0.996213 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.061626 0.998099 +0.000000 0.061626 0.998099 +0.000000 0.061626 0.998099 +0.996770 0.080314 0.000000 +0.996770 0.080314 0.000000 +0.996770 0.080314 0.000000 +0.000000 0.061626 -0.998099 +0.000000 0.061626 -0.998099 +0.000000 0.061626 -0.998099 +-0.996307 0.085866 0.000000 +-0.996307 0.085866 0.000000 +-0.996307 0.085866 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -0.086947 -0.996213 +0.000000 -0.086947 -0.996213 +0.000000 -0.086947 -0.996213 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.000000 -0.086947 0.996213 +0.000000 -0.086947 0.996213 +0.000000 -0.086947 0.996213 +-0.993768 -0.111467 0.000000 +-0.993768 -0.111467 0.000000 +-0.993768 -0.111467 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.061578 0.998102 +0.000000 0.061578 0.998102 +0.000000 0.061578 0.998102 +0.996774 0.080254 0.000000 +0.996774 0.080254 0.000000 +0.996775 0.080254 0.000000 +0.000000 0.061580 -0.998102 +0.000000 0.061580 -0.998102 +0.000000 0.061580 -0.998102 +-0.996312 0.085802 0.000000 +-0.996312 0.085802 0.000000 +-0.996312 0.085802 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -0.086947 -0.996213 +0.000000 -0.086947 -0.996213 +0.000000 -0.086947 -0.996213 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.000000 -0.086947 0.996213 +0.000000 -0.086947 0.996213 +0.000000 -0.086947 0.996213 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.061565 0.998103 +0.000000 0.061565 0.998103 +0.000000 0.061565 0.998103 +0.996776 0.080232 0.000000 +0.996776 0.080232 0.000000 +0.996776 0.080232 0.000000 +0.000000 0.061561 -0.998103 +0.000000 0.061561 -0.998103 +0.000000 0.061561 -0.998103 +-0.996314 0.085778 0.000000 +-0.996314 0.085778 0.000000 +-0.996314 0.085778 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -0.086947 -0.996213 +0.000000 -0.086947 -0.996213 +0.000000 -0.086947 -0.996213 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.000000 -0.086950 0.996213 +0.000000 -0.086950 0.996213 +0.000000 -0.086950 0.996213 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.061626 0.998099 +0.000000 0.061626 0.998099 +0.000000 0.061626 0.998099 +0.996770 0.080314 0.000000 +0.996770 0.080314 0.000000 +0.996770 0.080314 0.000000 +0.000000 0.061625 -0.998099 +0.000000 0.061625 -0.998099 +0.000000 0.061625 -0.998099 +-0.996307 0.085866 0.000000 +-0.996307 0.085866 0.000000 +-0.996307 0.085866 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -0.086950 -0.996213 +0.000000 -0.086950 -0.996213 +0.000000 -0.086950 -0.996213 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.993768 -0.111466 0.000000 +0.000000 -0.086947 0.996213 +0.000000 -0.086947 0.996213 +0.000000 -0.086947 0.996213 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +-0.993768 -0.111466 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.061578 0.998102 +0.000000 0.061578 0.998102 +0.000000 0.061578 0.998102 +0.996774 0.080254 0.000000 +0.996774 0.080254 0.000000 +0.996775 0.080254 0.000000 +0.000000 0.061580 -0.998102 +0.000000 0.061580 -0.998102 +0.000000 0.061580 -0.998102 +-0.996312 0.085802 0.000000 +-0.996312 0.085802 0.000000 +-0.996312 0.085802 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998106 0.061525 0.000000 +0.998106 0.061525 0.000000 +0.998106 0.061525 0.000000 +0.000000 0.080183 -0.996780 +0.000000 0.080183 -0.996780 +0.000000 0.080183 -0.996780 +-0.998106 0.061525 0.000000 +-0.998106 0.061525 0.000000 +-0.998106 0.061525 0.000000 +0.000000 0.085726 0.996319 +0.000000 0.085726 0.996319 +0.000000 0.085726 0.996319 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998103 0.061563 0.000000 +0.998103 0.061563 0.000000 +0.998103 0.061563 0.000000 +0.000000 0.080231 -0.996776 +0.000000 0.080231 -0.996776 +0.000000 0.080231 -0.996776 +-0.998103 0.061563 0.000000 +-0.998103 0.061563 0.000000 +-0.998103 0.061563 0.000000 +0.000000 0.085779 0.996314 +0.000000 0.085779 0.996314 +0.000000 0.085779 0.996314 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998099 0.061626 0.000000 +0.998099 0.061626 0.000000 +0.998099 0.061626 0.000000 +0.000000 0.080313 -0.996770 +0.000000 0.080313 -0.996770 +0.000000 0.080313 -0.996770 +-0.998099 0.061626 0.000000 +-0.998099 0.061626 0.000000 +-0.998099 0.061626 0.000000 +0.000000 0.085866 0.996307 +0.000000 0.085866 0.996307 +0.000000 0.085866 0.996307 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +-0.996213 -0.086947 0.000000 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.000000 -0.111466 -0.993768 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.996213 -0.086947 0.000000 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 -0.111466 0.993768 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.998102 0.061580 0.000000 +0.998102 0.061580 0.000000 +0.998102 0.061580 0.000000 +0.000000 0.080254 -0.996774 +0.000000 0.080254 -0.996774 +0.000000 0.080254 -0.996774 +-0.998102 0.061579 0.000000 +-0.998102 0.061579 0.000000 +-0.998102 0.061579 0.000000 +0.000000 0.085802 0.996312 +0.000000 0.085802 0.996312 +0.000000 0.085802 0.996312 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 + + + + + + + + + + + +0.359897 0.758714 +0.625139 0.758714 +0.625139 0.764329 +0.359897 0.764329 +0.625139 0.758240 +0.625139 0.763855 +0.359897 0.763855 +0.359897 0.758240 +0.902056 0.885447 +0.636815 0.885447 +0.636815 0.878968 +0.902056 0.878968 +0.536490 0.826242 +0.536490 0.831857 +0.530011 0.831857 +0.530011 0.826242 +0.902056 0.864356 +0.636815 0.864356 +0.636815 0.857877 +0.902056 0.857877 +0.631329 0.718832 +0.896570 0.718832 +0.896570 0.724447 +0.631329 0.724447 +0.622396 0.718832 +0.622396 0.724447 +0.357154 0.724447 +0.357154 0.718832 +0.902056 0.737814 +0.636815 0.737814 +0.636815 0.731335 +0.902056 0.731335 +0.230680 0.731335 +0.230680 0.736950 +0.224201 0.736950 +0.224201 0.731335 +0.902056 0.727269 +0.636815 0.727269 +0.636815 0.720790 +0.902056 0.720790 +0.229084 0.723487 +0.126341 0.724820 +0.129481 0.720165 +0.634912 0.803989 +0.610953 0.707254 +0.614854 0.703215 +0.216620 0.931142 +0.132187 0.931142 +0.132187 0.924664 +0.216620 0.924664 +0.216620 0.888962 +0.132187 0.888962 +0.132187 0.882483 +0.216620 0.882483 +0.231827 0.739749 +0.130647 0.738764 +0.133787 0.734109 +0.570346 0.707254 +0.596246 0.801979 +0.592346 0.806018 +0.216620 0.825691 +0.132187 0.825691 +0.132187 0.819212 +0.216620 0.819212 +0.807150 0.938173 +0.722717 0.938173 +0.722717 0.931694 +0.807150 0.931694 +0.517625 0.703215 +0.540005 0.801585 +0.513725 0.707254 +0.350964 0.724528 +0.347824 0.729183 +0.250090 0.723089 +0.216620 0.853811 +0.132187 0.853811 +0.132187 0.847332 +0.216620 0.847332 +0.216620 0.920597 +0.132187 0.920597 +0.132187 0.914118 +0.216620 0.914118 +0.519687 0.781430 +0.435254 0.781430 +0.435254 0.775815 +0.519687 0.775815 +0.614593 0.775815 +0.614593 0.781430 +0.530161 0.781430 +0.530161 0.775815 +0.216620 0.748359 +0.132187 0.748359 +0.132187 0.741880 +0.216620 0.741880 +0.216620 0.787025 +0.132187 0.787025 +0.132187 0.780546 +0.216620 0.780546 +0.359897 0.723089 +0.625139 0.723089 +0.625139 0.728704 +0.359897 0.728704 +0.899313 0.723089 +0.899313 0.728704 +0.634072 0.728704 +0.634072 0.723089 +0.902056 0.801085 +0.636815 0.801085 +0.636815 0.794606 +0.902056 0.794606 +0.230680 0.843817 +0.230680 0.849432 +0.224201 0.849432 +0.224201 0.843817 +0.902056 0.811630 +0.636815 0.811630 +0.636815 0.805152 +0.902056 0.805152 +0.634072 0.758240 +0.899313 0.758240 +0.899313 0.763855 +0.634072 0.763855 +0.625139 0.740664 +0.625139 0.746279 +0.359897 0.746279 +0.359897 0.740664 +0.902056 0.832721 +0.636815 0.832721 +0.636815 0.826242 +0.902056 0.826242 +0.511885 0.808667 +0.511885 0.814282 +0.505406 0.814282 +0.505406 0.808667 +0.902056 0.843266 +0.636815 0.843266 +0.636815 0.836787 +0.902056 0.836787 +0.345081 0.723487 +0.242338 0.724820 +0.245478 0.720164 +0.348221 0.718832 +0.607438 0.721314 +0.611338 0.717275 +0.631397 0.818050 +0.627496 0.822089 +0.902056 0.948718 +0.817624 0.948718 +0.817624 0.942239 +0.902056 0.942239 +0.504855 0.706179 +0.420422 0.706179 +0.420422 0.699700 +0.504855 0.699700 +0.347824 0.859261 +0.246644 0.858276 +0.249784 0.853621 +0.350964 0.854606 +0.563315 0.707254 +0.567216 0.703215 +0.589216 0.801979 +0.585315 0.806018 +0.216620 0.765935 +0.132187 0.765935 +0.132187 0.759456 +0.216620 0.759456 +0.216620 0.836236 +0.132187 0.836236 +0.132187 0.829757 +0.216620 0.829757 +0.524655 0.703215 +0.547035 0.801585 +0.543135 0.805624 +0.520755 0.707254 +0.238482 0.706952 +0.235342 0.711607 +0.134469 0.710169 +0.137608 0.705514 +0.216620 0.941688 +0.132187 0.941688 +0.132187 0.935209 +0.216620 0.935209 +0.216620 0.910052 +0.132187 0.910052 +0.132187 0.903573 +0.216620 0.903573 +0.238482 0.728704 +0.154049 0.728704 +0.154049 0.723089 +0.238482 0.723089 +0.216620 0.864908 +0.216620 0.870522 +0.132187 0.870522 +0.132187 0.864908 +0.518915 0.737814 +0.434482 0.737814 +0.434482 0.731335 +0.518915 0.731335 +0.529460 0.790540 +0.445027 0.790540 +0.445027 0.784061 +0.529460 0.784061 +0.634072 0.740664 +0.899313 0.740664 +0.899313 0.746279 +0.634072 0.746279 +0.625139 0.705514 +0.625139 0.711129 +0.359897 0.711129 +0.359897 0.705514 +0.902056 0.853811 +0.636815 0.853811 +0.636815 0.847332 +0.902056 0.847332 +0.230680 0.752426 +0.230680 0.758041 +0.224201 0.758041 +0.224201 0.752426 +0.902056 0.822176 +0.636815 0.822176 +0.636815 0.815697 +0.902056 0.815697 +0.634072 0.705514 +0.899313 0.705514 +0.899313 0.711129 +0.634072 0.711129 +0.625139 0.687938 +0.625139 0.693553 +0.359897 0.693553 +0.359897 0.687938 +0.902056 0.790540 +0.636815 0.790540 +0.636815 0.784061 +0.902056 0.784061 +0.230680 0.907088 +0.230680 0.912703 +0.224201 0.912703 +0.224201 0.907088 +0.902056 0.779995 +0.636815 0.779995 +0.636815 0.773516 +0.902056 0.773516 +0.347824 0.738764 +0.245081 0.740096 +0.248221 0.735441 +0.350964 0.734109 +0.600408 0.717799 +0.604308 0.713760 +0.624367 0.814534 +0.620466 0.818574 +0.902056 0.895992 +0.817624 0.895992 +0.817624 0.889513 +0.902056 0.889513 +0.902056 0.906537 +0.817624 0.906537 +0.817624 0.900058 +0.902056 0.900058 +0.347824 0.764354 +0.246644 0.763369 +0.249784 0.758714 +0.350964 0.759699 +0.603276 0.801979 +0.599376 0.806018 +0.577376 0.707254 +0.581276 0.703215 +0.420493 0.727269 +0.336061 0.727269 +0.336061 0.720790 +0.420493 0.720790 +0.216620 0.776480 +0.132187 0.776480 +0.132187 0.770001 +0.216620 0.770001 +0.564225 0.805624 +0.541845 0.707254 +0.545746 0.703215 +0.568126 0.801585 +0.350964 0.706952 +0.347824 0.711607 +0.246950 0.710169 +0.250090 0.705514 +0.431038 0.787025 +0.346606 0.787025 +0.346606 0.780546 +0.431038 0.780546 +0.216620 0.899507 +0.132187 0.899507 +0.132187 0.893028 +0.216620 0.893028 +0.350964 0.763855 +0.266531 0.763855 +0.266531 0.758240 +0.350964 0.758240 +0.804407 0.775815 +0.804407 0.781430 +0.719974 0.781430 +0.719974 0.775815 +0.216620 0.737814 +0.132187 0.737814 +0.132187 0.731335 +0.216620 0.731335 +0.353707 0.695633 +0.269274 0.695633 +0.269274 0.689155 +0.353707 0.689155 +0.634072 0.687938 +0.899313 0.687938 +0.899313 0.693553 +0.634072 0.693553 +0.625139 0.853621 +0.625139 0.859236 +0.359897 0.859236 +0.359897 0.853621 +0.902056 0.769450 +0.636815 0.769450 +0.636815 0.762971 +0.902056 0.762971 +0.230680 0.921149 +0.230680 0.926764 +0.224201 0.926764 +0.224201 0.921149 +0.902056 0.758905 +0.636815 0.758905 +0.636815 0.752426 +0.902056 0.752426 +0.634072 0.853621 +0.899313 0.853621 +0.899313 0.859236 +0.634072 0.859236 +0.899313 0.758714 +0.899313 0.764329 +0.634072 0.764329 +0.634072 0.758714 +0.902056 0.748359 +0.636815 0.748359 +0.636815 0.741880 +0.902056 0.741880 +0.592731 0.826242 +0.592731 0.831857 +0.586252 0.831857 +0.586252 0.826242 +0.902056 0.874901 +0.636815 0.874901 +0.636815 0.868423 +0.902056 0.868423 +0.347824 0.714158 +0.245081 0.715491 +0.248221 0.710836 +0.350964 0.709503 +0.593378 0.714284 +0.597278 0.710245 +0.617336 0.811019 +0.613436 0.815059 +0.807150 0.895992 +0.722717 0.895992 +0.722717 0.889513 +0.807150 0.889513 +0.902056 0.938173 +0.817624 0.938173 +0.817624 0.931694 +0.902056 0.931694 +0.235342 0.859261 +0.134163 0.858276 +0.137302 0.853621 +0.238482 0.854606 +0.556285 0.707254 +0.560186 0.703215 +0.582186 0.801979 +0.578285 0.806018 +0.807150 0.906537 +0.722717 0.906537 +0.722717 0.900058 +0.807150 0.900058 +0.424008 0.737814 +0.339576 0.737814 +0.339576 0.731335 +0.424008 0.731335 +0.557195 0.805624 +0.534815 0.707254 +0.538715 0.703215 +0.561096 0.801585 +0.238482 0.689377 +0.235342 0.694032 +0.134469 0.692593 +0.137608 0.687938 +0.427523 0.765935 +0.343091 0.765935 +0.343091 0.759456 +0.427523 0.759456 +0.431038 0.776480 +0.346606 0.776480 +0.346606 0.770001 +0.431038 0.770001 +0.234967 0.781430 +0.150534 0.781430 +0.150534 0.775815 +0.234967 0.775815 +0.216620 0.857877 +0.216620 0.863492 +0.132187 0.863492 +0.132187 0.857877 +0.902056 0.927627 +0.817624 0.927627 +0.817624 0.921149 +0.902056 0.921149 +0.902056 0.917082 +0.817624 0.917082 +0.817624 0.910603 +0.902056 0.910603 +0.359897 0.734109 +0.625139 0.734109 +0.625139 0.739724 +0.359897 0.739724 +0.625139 0.709503 +0.625139 0.715118 +0.359897 0.715118 +0.359897 0.709503 +0.902056 0.716724 +0.636815 0.716724 +0.636815 0.710245 +0.902056 0.710245 +0.230680 0.703215 +0.230680 0.708830 +0.224201 0.708830 +0.224201 0.703215 +0.627882 0.695633 +0.362640 0.695633 +0.362640 0.689155 +0.627882 0.689155 +0.634072 0.734109 +0.899313 0.734109 +0.899313 0.739724 +0.634072 0.739724 +0.899313 0.709503 +0.899313 0.715118 +0.634072 0.715118 +0.634072 0.709503 +0.902056 0.706179 +0.636815 0.706179 +0.636815 0.699700 +0.902056 0.699700 +0.230680 0.745395 +0.230680 0.751011 +0.224201 0.751011 +0.224201 0.745395 +0.902056 0.695633 +0.636815 0.695633 +0.636815 0.689155 +0.902056 0.689155 +0.231827 0.714158 +0.129084 0.715491 +0.132224 0.710836 +0.234967 0.709503 +0.586348 0.710769 +0.590248 0.706730 +0.610306 0.807504 +0.606406 0.811544 +0.216620 0.815145 +0.132187 0.815145 +0.132187 0.808667 +0.216620 0.808667 +0.216620 0.804600 +0.132187 0.804600 +0.132187 0.798121 +0.216620 0.798121 +0.235342 0.764354 +0.134163 0.763369 +0.137302 0.758714 +0.238482 0.759699 +0.549255 0.707254 +0.553156 0.703215 +0.575156 0.801979 +0.571255 0.806018 +0.525945 0.769450 +0.441512 0.769450 +0.441512 0.762971 +0.525945 0.762971 +0.525945 0.779995 +0.441512 0.779995 +0.441512 0.773516 +0.525945 0.773516 +0.550165 0.805624 +0.527785 0.707254 +0.531685 0.703215 +0.554065 0.801585 +0.350964 0.689377 +0.347824 0.694032 +0.246950 0.692593 +0.250090 0.687938 +0.216620 0.878417 +0.132187 0.878417 +0.132187 0.871938 +0.216620 0.871938 +0.434553 0.797570 +0.350121 0.797570 +0.350121 0.791091 +0.434553 0.791091 +0.613821 0.824827 +0.529389 0.824827 +0.529389 0.819212 +0.613821 0.819212 +0.216620 0.752426 +0.216620 0.758041 +0.132187 0.758041 +0.132187 0.752426 +0.515400 0.727269 +0.430967 0.727269 +0.430967 0.720790 +0.515400 0.720790 +0.511885 0.716724 +0.427452 0.716724 +0.427452 0.710245 +0.511885 0.710245 +0.148913 0.282482 +0.045497 0.282481 +0.045497 0.272344 +0.148913 0.272344 +0.148913 0.259624 +0.148913 0.269762 +0.045497 0.269762 +0.045497 0.259624 +0.964980 0.177286 +0.964980 0.187424 +0.027754 0.187424 +0.027754 0.177286 +0.967071 0.173044 +0.967071 0.276459 +0.029845 0.276459 +0.029845 0.173044 +0.964980 0.198485 +0.964980 0.208623 +0.027754 0.208623 +0.027754 0.198485 +0.028022 0.134227 +0.028022 0.030812 +0.965247 0.030812 +0.965247 0.134227 +0.161816 0.257043 +0.058401 0.257043 +0.058401 0.246905 +0.161816 0.246905 +0.161816 0.234186 +0.161816 0.244323 +0.058401 0.244323 +0.058401 0.234186 +0.968082 0.155196 +0.968082 0.165334 +0.030856 0.165334 +0.030856 0.155196 +0.967071 0.166099 +0.967071 0.269514 +0.029845 0.269514 +0.029845 0.166099 +0.968082 0.218793 +0.968082 0.228931 +0.030856 0.228931 +0.030856 0.218793 +0.962770 0.030978 +0.962770 0.134393 +0.025544 0.134393 +0.025544 0.030978 +0.216620 0.796706 +0.132187 0.796706 +0.132187 0.791091 +0.216620 0.791091 +0.899313 0.775815 +0.899313 0.781430 +0.814881 0.781430 +0.814881 0.775815 +0.522430 0.758905 +0.437997 0.758905 +0.437997 0.752426 +0.522430 0.752426 +0.518915 0.748359 +0.434482 0.748359 +0.434482 0.741880 +0.518915 0.741880 +0.424008 0.747496 +0.339576 0.747496 +0.339576 0.741880 +0.424008 0.741880 +0.350964 0.740664 +0.350964 0.746279 +0.266531 0.746279 +0.266531 0.740664 +0.599761 0.815145 +0.515329 0.815145 +0.515329 0.808667 +0.599761 0.808667 +0.529460 0.801085 +0.445027 0.801085 +0.445027 0.794606 +0.529460 0.794606 +0.424780 0.781430 +0.340348 0.781430 +0.340348 0.775815 +0.424780 0.775815 +0.256057 0.740664 +0.256057 0.746279 +0.171625 0.746279 +0.171625 0.740664 +0.807150 0.927627 +0.722717 0.927627 +0.722717 0.921149 +0.807150 0.921149 +0.807150 0.917082 +0.722717 0.917082 +0.722717 0.910603 +0.807150 0.910603 +0.709500 0.781430 +0.625067 0.781430 +0.625067 0.775815 +0.709500 0.775815 +0.329873 0.775815 +0.329873 0.781430 +0.245441 0.781430 +0.245441 0.775815 +0.416978 0.716724 +0.332545 0.716724 +0.332545 0.710245 +0.416978 0.710245 +0.409948 0.706179 +0.325515 0.706179 +0.325515 0.699700 +0.409948 0.699700 +0.256057 0.763855 +0.171625 0.763855 +0.171625 0.758240 +0.256057 0.758240 +0.216620 0.840302 +0.216620 0.845917 +0.132187 0.845917 +0.132187 0.840302 +0.807150 0.948718 +0.722717 0.948718 +0.722717 0.942239 +0.807150 0.942239 +0.424008 0.755389 +0.339576 0.755389 +0.339576 0.748911 +0.424008 0.748911 +0.634912 0.703215 +0.634912 0.710701 +0.619690 0.710701 +0.619690 0.703215 +0.634912 0.720790 +0.634912 0.736012 +0.627426 0.736012 +0.627426 0.720790 +0.899313 0.716533 +0.899313 0.731756 +0.122294 0.731755 +0.122294 0.716533 +0.899313 0.712544 +0.899313 0.720030 +0.122294 0.720029 +0.122294 0.712544 +0.899313 0.741139 +0.899313 0.756361 +0.122294 0.756361 +0.122294 0.741139 +0.899313 0.694968 +0.899313 0.702454 +0.122294 0.702454 +0.122294 0.694968 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.503250 0.182172 +0.260475 0.182172 +0.266882 0.176062 +0.496844 0.176062 +0.202726 0.996046 +0.670755 0.996046 +0.004123 0.996046 +0.472024 0.996046 +0.677249 0.192456 +0.251604 0.192456 +0.429384 0.192456 +0.854111 0.192456 +0.765823 0.004091 +0.765823 0.182429 +0.516603 0.182429 +0.516603 0.004091 +0.670755 0.468044 +0.004123 0.468044 +0.670755 0.356586 +0.004123 0.356586 +0.202726 0.468044 +0.472024 0.468044 +0.202726 0.356586 +0.472024 0.356586 +0.260475 0.004834 +0.266882 0.010943 +0.503250 0.004834 +0.496844 0.010943 +0.004105 0.192456 +0.251604 0.345840 +0.004105 0.345840 +0.677249 0.345840 +0.429384 0.345840 +0.854111 0.345840 +0.941696 0.996046 +0.941696 0.468044 +0.941696 0.356586 +0.503250 0.182172 +0.260475 0.182172 +0.266882 0.176063 +0.496844 0.176063 +0.202726 0.899077 +0.670755 0.899077 +0.004123 0.899077 +0.472024 0.899077 +0.251893 0.192456 +0.677115 0.192456 +0.854111 0.192456 +0.429617 0.192456 +0.765823 0.004091 +0.765823 0.182429 +0.516603 0.182429 +0.516603 0.004091 +0.670755 0.468044 +0.004123 0.468044 +0.670755 0.356586 +0.004123 0.356586 +0.202726 0.468044 +0.472024 0.468044 +0.202726 0.356586 +0.472024 0.356586 +0.004105 0.192456 +0.004105 0.345840 +0.677115 0.345840 +0.260475 0.004834 +0.266882 0.010943 +0.503250 0.004834 +0.496844 0.010943 +0.429617 0.345840 +0.251893 0.345840 +0.854111 0.345840 +0.941696 0.899077 +0.941696 0.468044 +0.941696 0.356586 +0.503250 0.182172 +0.260475 0.182172 +0.266878 0.176066 +0.496844 0.176066 +0.670755 0.754753 +0.202726 0.754753 +0.472024 0.754753 +0.941696 0.754753 +0.251803 0.192456 +0.676793 0.192456 +0.854111 0.192456 +0.429464 0.192456 +0.765823 0.004091 +0.765823 0.182429 +0.516603 0.182429 +0.516603 0.004091 +0.202726 0.468044 +0.472024 0.468044 +0.202726 0.356586 +0.472024 0.356586 +0.670755 0.468044 +0.941696 0.468044 +0.670755 0.356586 +0.941696 0.356586 +0.004123 0.754753 +0.004123 0.468044 +0.004123 0.356586 +0.260475 0.004834 +0.266878 0.010943 +0.503250 0.004834 +0.496844 0.010943 +0.676793 0.345840 +0.429464 0.345840 +0.251803 0.345840 +0.854111 0.345840 +0.004105 0.192456 +0.004105 0.345840 +0.503250 0.182172 +0.260475 0.182172 +0.266884 0.176061 +0.496844 0.176061 +0.670755 0.949681 +0.202726 0.949681 +0.472024 0.949681 +0.941696 0.949681 +0.251692 0.192456 +0.677407 0.192456 +0.854111 0.192456 +0.429511 0.192456 +0.765823 0.004091 +0.765823 0.182429 +0.516603 0.182429 +0.516603 0.004091 +0.202726 0.468044 +0.472024 0.468044 +0.202726 0.356586 +0.472024 0.356586 +0.670755 0.468044 +0.941696 0.468044 +0.670755 0.356586 +0.941696 0.356586 +0.260475 0.004834 +0.266884 0.010943 +0.503250 0.004834 +0.496844 0.010943 +0.677407 0.345840 +0.429511 0.345840 +0.004105 0.192456 +0.251692 0.345840 +0.004105 0.345840 +0.854111 0.345840 +0.004123 0.949681 +0.004123 0.468044 +0.004123 0.356586 +0.503250 0.182172 +0.260475 0.182172 +0.266882 0.176062 +0.496844 0.176062 +0.202726 0.996046 +0.670755 0.996046 +0.004123 0.996046 +0.472024 0.996046 +0.677249 0.192456 +0.251604 0.192456 +0.429384 0.192456 +0.854111 0.192456 +0.765823 0.004091 +0.765823 0.182429 +0.516603 0.182429 +0.516603 0.004091 +0.670755 0.468044 +0.004123 0.468044 +0.670755 0.356586 +0.004123 0.356586 +0.202726 0.468044 +0.472024 0.468044 +0.202726 0.356586 +0.472024 0.356586 +0.260475 0.004834 +0.266882 0.010943 +0.503250 0.004834 +0.496844 0.010943 +0.004105 0.192456 +0.251604 0.345840 +0.004105 0.345840 +0.677249 0.345840 +0.429384 0.345840 +0.854111 0.345840 +0.941696 0.996046 +0.941696 0.468044 +0.941696 0.356586 +0.503250 0.182172 +0.260475 0.182172 +0.266882 0.176063 +0.496844 0.176063 +0.202726 0.899077 +0.670755 0.899077 +0.004123 0.899077 +0.472024 0.899077 +0.251893 0.192456 +0.677115 0.192456 +0.854111 0.192456 +0.429617 0.192456 +0.765823 0.004091 +0.765823 0.182429 +0.516603 0.182429 +0.516603 0.004091 +0.670755 0.468044 +0.004123 0.468044 +0.670755 0.356586 +0.004123 0.356586 +0.202726 0.468044 +0.472024 0.468044 +0.202726 0.356586 +0.472024 0.356586 +0.004105 0.192456 +0.004105 0.345840 +0.677115 0.345840 +0.260475 0.004834 +0.266882 0.010943 +0.503250 0.004834 +0.496844 0.010943 +0.429617 0.345840 +0.251893 0.345840 +0.854111 0.345840 +0.941696 0.899077 +0.941696 0.468044 +0.941696 0.356586 +0.503250 0.182172 +0.260475 0.182172 +0.266878 0.176066 +0.496844 0.176066 +0.670755 0.754753 +0.202726 0.754753 +0.472024 0.754753 +0.941696 0.754753 +0.251803 0.192456 +0.676793 0.192456 +0.854111 0.192456 +0.429464 0.192456 +0.765823 0.004091 +0.765823 0.182429 +0.516603 0.182429 +0.516603 0.004091 +0.202726 0.468044 +0.472024 0.468044 +0.202726 0.356586 +0.472024 0.356586 +0.670755 0.468044 +0.941696 0.468044 +0.670755 0.356586 +0.941696 0.356586 +0.004123 0.754753 +0.004123 0.468044 +0.004123 0.356586 +0.260475 0.004834 +0.266878 0.010943 +0.503250 0.004834 +0.496844 0.010943 +0.676793 0.345840 +0.429464 0.345840 +0.251803 0.345840 +0.854111 0.345840 +0.004105 0.192456 +0.004105 0.345840 +0.503250 0.182172 +0.260475 0.182172 +0.266884 0.176061 +0.496844 0.176061 +0.670755 0.949681 +0.202726 0.949681 +0.472024 0.949681 +0.941696 0.949681 +0.251692 0.192456 +0.677407 0.192456 +0.854111 0.192456 +0.429511 0.192456 +0.765823 0.004091 +0.765823 0.182429 +0.516603 0.182429 +0.516603 0.004091 +0.202726 0.468044 +0.472024 0.468044 +0.202726 0.356586 +0.472024 0.356586 +0.670755 0.468044 +0.941696 0.468044 +0.670755 0.356586 +0.941696 0.356586 +0.260475 0.004834 +0.266884 0.010943 +0.503250 0.004834 +0.496844 0.010943 +0.677407 0.345840 +0.429511 0.345840 +0.004105 0.192456 +0.251692 0.345840 +0.004105 0.345840 +0.854111 0.345840 +0.004123 0.949681 +0.004123 0.468044 +0.004123 0.356586 +0.503250 0.182172 +0.260475 0.182172 +0.266882 0.176062 +0.496844 0.176062 +0.202726 0.996046 +0.670755 0.996046 +0.004123 0.996046 +0.472024 0.996046 +0.677249 0.192456 +0.251604 0.192456 +0.429384 0.192456 +0.854111 0.192456 +0.765823 0.004091 +0.765823 0.182429 +0.516603 0.182429 +0.516603 0.004091 +0.670755 0.468044 +0.004123 0.468044 +0.670755 0.356586 +0.004123 0.356586 +0.202726 0.468044 +0.472024 0.468044 +0.202726 0.356586 +0.472024 0.356586 +0.260475 0.004834 +0.266882 0.010943 +0.503250 0.004834 +0.496844 0.010943 +0.004105 0.192456 +0.251604 0.345840 +0.004105 0.345840 +0.677249 0.345840 +0.429384 0.345840 +0.854111 0.345840 +0.941696 0.996046 +0.941696 0.468044 +0.941696 0.356586 +0.503250 0.182172 +0.260475 0.182172 +0.266882 0.176063 +0.496844 0.176063 +0.202726 0.899077 +0.670755 0.899077 +0.004123 0.899077 +0.472024 0.899077 +0.251893 0.192456 +0.677115 0.192456 +0.854111 0.192456 +0.429617 0.192456 +0.765823 0.004091 +0.765823 0.182429 +0.516603 0.182429 +0.516603 0.004091 +0.670755 0.468044 +0.004123 0.468044 +0.670755 0.356586 +0.004123 0.356586 +0.202726 0.468044 +0.472024 0.468044 +0.202726 0.356586 +0.472024 0.356586 +0.004105 0.192456 +0.004105 0.345840 +0.677115 0.345840 +0.260475 0.004834 +0.266882 0.010943 +0.503250 0.004834 +0.496844 0.010943 +0.429617 0.345840 +0.251893 0.345840 +0.854111 0.345840 +0.941696 0.899077 +0.941696 0.468044 +0.941696 0.356586 +0.503250 0.182172 +0.260475 0.182172 +0.266878 0.176066 +0.496844 0.176066 +0.670755 0.754753 +0.202726 0.754753 +0.472024 0.754753 +0.941696 0.754753 +0.251803 0.192456 +0.676793 0.192456 +0.854111 0.192456 +0.429464 0.192456 +0.765823 0.004091 +0.765823 0.182429 +0.516603 0.182429 +0.516603 0.004091 +0.202726 0.468044 +0.472024 0.468044 +0.202726 0.356586 +0.472024 0.356586 +0.670755 0.468044 +0.941696 0.468044 +0.670755 0.356586 +0.941696 0.356586 +0.004123 0.754753 +0.004123 0.468044 +0.004123 0.356586 +0.260475 0.004834 +0.266878 0.010943 +0.503250 0.004834 +0.496844 0.010943 +0.676793 0.345840 +0.429464 0.345840 +0.251803 0.345840 +0.854111 0.345840 +0.004105 0.192456 +0.004105 0.345840 +0.503250 0.182172 +0.260475 0.182172 +0.266884 0.176061 +0.496844 0.176061 +0.670755 0.949681 +0.202726 0.949681 +0.472024 0.949681 +0.941696 0.949681 +0.251692 0.192456 +0.677407 0.192456 +0.854111 0.192456 +0.429511 0.192456 +0.765823 0.004091 +0.765823 0.182429 +0.516603 0.182429 +0.516603 0.004091 +0.202726 0.468044 +0.472024 0.468044 +0.202726 0.356586 +0.472024 0.356586 +0.670755 0.468044 +0.941696 0.468044 +0.670755 0.356586 +0.941696 0.356586 +0.260475 0.004834 +0.266884 0.010943 +0.503250 0.004834 +0.496844 0.010943 +0.677407 0.345840 +0.429511 0.345840 +0.004105 0.192456 +0.251692 0.345840 +0.004105 0.345840 +0.854111 0.345840 +0.004123 0.949681 +0.004123 0.468044 +0.004123 0.356586 +0.503250 0.182172 +0.260475 0.182172 +0.266882 0.176062 +0.496844 0.176062 +0.202726 0.996046 +0.670755 0.996046 +0.004123 0.996046 +0.472024 0.996046 +0.677249 0.192456 +0.251604 0.192456 +0.429384 0.192456 +0.854111 0.192456 +0.765823 0.004091 +0.765823 0.182429 +0.516603 0.182429 +0.516603 0.004091 +0.670755 0.468044 +0.004123 0.468044 +0.670755 0.356586 +0.004123 0.356586 +0.202726 0.468044 +0.472024 0.468044 +0.202726 0.356586 +0.472024 0.356586 +0.260475 0.004834 +0.266882 0.010943 +0.503250 0.004834 +0.496844 0.010943 +0.004105 0.192456 +0.251604 0.345840 +0.004105 0.345840 +0.677249 0.345840 +0.429384 0.345840 +0.854111 0.345840 +0.941696 0.996046 +0.941696 0.468044 +0.941696 0.356586 +0.503250 0.182172 +0.260475 0.182172 +0.266882 0.176063 +0.496844 0.176063 +0.202726 0.899077 +0.670755 0.899077 +0.004123 0.899077 +0.472024 0.899077 +0.251893 0.192456 +0.677115 0.192456 +0.854111 0.192456 +0.429617 0.192456 +0.765823 0.004091 +0.765823 0.182429 +0.516603 0.182429 +0.516603 0.004091 +0.670755 0.468044 +0.004123 0.468044 +0.670755 0.356586 +0.004123 0.356586 +0.202726 0.468044 +0.472024 0.468044 +0.202726 0.356586 +0.472024 0.356586 +0.004105 0.192456 +0.004105 0.345840 +0.677115 0.345840 +0.260475 0.004834 +0.266882 0.010943 +0.503250 0.004834 +0.496844 0.010943 +0.429617 0.345840 +0.251893 0.345840 +0.854111 0.345840 +0.941696 0.899077 +0.941696 0.468044 +0.941696 0.356586 +0.503250 0.182172 +0.260475 0.182172 +0.266878 0.176066 +0.496844 0.176066 +0.670755 0.754753 +0.202726 0.754753 +0.472024 0.754753 +0.941696 0.754753 +0.251803 0.192456 +0.676793 0.192456 +0.854111 0.192456 +0.429464 0.192456 +0.765823 0.004091 +0.765823 0.182429 +0.516603 0.182429 +0.516603 0.004091 +0.202726 0.468044 +0.472024 0.468044 +0.202726 0.356586 +0.472024 0.356586 +0.670755 0.468044 +0.941696 0.468044 +0.670755 0.356586 +0.941696 0.356586 +0.004123 0.754753 +0.004123 0.468044 +0.004123 0.356586 +0.260475 0.004834 +0.266878 0.010943 +0.503250 0.004834 +0.496844 0.010943 +0.676793 0.345840 +0.429464 0.345840 +0.251803 0.345840 +0.854111 0.345840 +0.004105 0.192456 +0.004105 0.345840 +0.503250 0.182172 +0.260475 0.182172 +0.266884 0.176061 +0.496844 0.176061 +0.670755 0.949681 +0.202726 0.949681 +0.472024 0.949681 +0.941696 0.949681 +0.251692 0.192456 +0.677407 0.192456 +0.854111 0.192456 +0.429511 0.192456 +0.765823 0.004091 +0.765823 0.182429 +0.516603 0.182429 +0.516603 0.004091 +0.202726 0.468044 +0.472024 0.468044 +0.202726 0.356586 +0.472024 0.356586 +0.670755 0.468044 +0.941696 0.468044 +0.670755 0.356586 +0.941696 0.356586 +0.260475 0.004834 +0.266884 0.010943 +0.503250 0.004834 +0.496844 0.010943 +0.677407 0.345840 +0.429511 0.345840 +0.004105 0.192456 +0.251692 0.345840 +0.004105 0.345840 +0.854111 0.345840 +0.004123 0.949681 +0.004123 0.468044 +0.004123 0.356586 +0.503250 0.182172 +0.260475 0.182172 +0.266882 0.176062 +0.496844 0.176062 +0.202726 0.996046 +0.670755 0.996046 +0.004123 0.996046 +0.472024 0.996046 +0.677249 0.192456 +0.251604 0.192456 +0.429384 0.192456 +0.854111 0.192456 +0.765823 0.004091 +0.765823 0.182429 +0.516603 0.182429 +0.516603 0.004091 +0.670755 0.468044 +0.004123 0.468044 +0.670755 0.356586 +0.004123 0.356586 +0.202726 0.468044 +0.472024 0.468044 +0.202726 0.356586 +0.472024 0.356586 +0.260475 0.004834 +0.266882 0.010943 +0.503250 0.004834 +0.496844 0.010943 +0.004105 0.192456 +0.251604 0.345840 +0.004105 0.345840 +0.677249 0.345840 +0.429384 0.345840 +0.854111 0.345840 +0.941696 0.996046 +0.941696 0.468044 +0.941696 0.356586 +0.503250 0.182172 +0.260475 0.182172 +0.266882 0.176063 +0.496844 0.176063 +0.202726 0.899077 +0.670755 0.899077 +0.004123 0.899077 +0.472024 0.899077 +0.251893 0.192456 +0.677115 0.192456 +0.854111 0.192456 +0.429617 0.192456 +0.765823 0.004091 +0.765823 0.182429 +0.516603 0.182429 +0.516603 0.004091 +0.670755 0.468044 +0.004123 0.468044 +0.670755 0.356586 +0.004123 0.356586 +0.202726 0.468044 +0.472024 0.468044 +0.202726 0.356586 +0.472024 0.356586 +0.004105 0.192456 +0.004105 0.345840 +0.677115 0.345840 +0.260475 0.004834 +0.266882 0.010943 +0.503250 0.004834 +0.496844 0.010943 +0.429617 0.345840 +0.251893 0.345840 +0.854111 0.345840 +0.941696 0.899077 +0.941696 0.468044 +0.941696 0.356586 +0.503250 0.182172 +0.260475 0.182172 +0.266884 0.176061 +0.496844 0.176061 +0.670755 0.949681 +0.202726 0.949681 +0.472024 0.949681 +0.941696 0.949681 +0.251692 0.192456 +0.677407 0.192456 +0.854111 0.192456 +0.429511 0.192456 +0.765823 0.004091 +0.765823 0.182429 +0.516603 0.182429 +0.516603 0.004091 +0.202726 0.468044 +0.472024 0.468044 +0.202726 0.356586 +0.472024 0.356586 +0.670755 0.468044 +0.941696 0.468044 +0.670755 0.356586 +0.941696 0.356586 +0.260475 0.004834 +0.266884 0.010943 +0.503250 0.004834 +0.496844 0.010943 +0.677407 0.345840 +0.429511 0.345840 +0.004105 0.192456 +0.251692 0.345840 +0.004105 0.345840 +0.854111 0.345840 +0.004123 0.949681 +0.004123 0.468044 +0.004123 0.356586 +0.503250 0.182172 +0.260475 0.182172 +0.266882 0.176062 +0.496844 0.176062 +0.202726 0.996046 +0.670755 0.996046 +0.004123 0.996046 +0.472024 0.996046 +0.677249 0.192456 +0.251604 0.192456 +0.429384 0.192456 +0.854111 0.192456 +0.765823 0.004091 +0.765823 0.182429 +0.516603 0.182429 +0.516603 0.004091 +0.670755 0.468044 +0.004123 0.468044 +0.670755 0.356586 +0.004123 0.356586 +0.202726 0.468044 +0.472024 0.468044 +0.202726 0.356586 +0.472024 0.356586 +0.260475 0.004834 +0.266882 0.010943 +0.503250 0.004834 +0.496844 0.010943 +0.004105 0.192456 +0.251604 0.345840 +0.004105 0.345840 +0.677249 0.345840 +0.429384 0.345840 +0.854111 0.345840 +0.941696 0.996046 +0.941696 0.468044 +0.941696 0.356586 +0.503250 0.182172 +0.260475 0.182172 +0.266882 0.176063 +0.496844 0.176063 +0.202726 0.899077 +0.670755 0.899077 +0.004123 0.899077 +0.472024 0.899077 +0.251893 0.192456 +0.677115 0.192456 +0.854111 0.192456 +0.429617 0.192456 +0.765823 0.004091 +0.765823 0.182429 +0.516603 0.182429 +0.516603 0.004091 +0.670755 0.468044 +0.004123 0.468044 +0.670755 0.356586 +0.004123 0.356586 +0.202726 0.468044 +0.472024 0.468044 +0.202726 0.356586 +0.472024 0.356586 +0.004105 0.192456 +0.004105 0.345840 +0.677115 0.345840 +0.260475 0.004834 +0.266882 0.010943 +0.503250 0.004834 +0.496844 0.010943 +0.429617 0.345840 +0.251893 0.345840 +0.854111 0.345840 +0.941696 0.899077 +0.941696 0.468044 +0.941696 0.356586 +0.503250 0.182172 +0.260475 0.182172 +0.266878 0.176066 +0.496844 0.176066 +0.670755 0.754753 +0.202726 0.754753 +0.472024 0.754753 +0.941696 0.754753 +0.251803 0.192456 +0.676793 0.192456 +0.854111 0.192456 +0.429464 0.192456 +0.765823 0.004091 +0.765823 0.182429 +0.516603 0.182429 +0.516603 0.004091 +0.202726 0.468044 +0.472024 0.468044 +0.202726 0.356586 +0.472024 0.356586 +0.670755 0.468044 +0.941696 0.468044 +0.670755 0.356586 +0.941696 0.356586 +0.004123 0.754753 +0.004123 0.468044 +0.004123 0.356586 +0.260475 0.004834 +0.266878 0.010943 +0.503250 0.004834 +0.496844 0.010943 +0.676793 0.345840 +0.429464 0.345840 +0.251803 0.345840 +0.854111 0.345840 +0.004105 0.192456 +0.004105 0.345840 +0.503250 0.182172 +0.260475 0.182172 +0.266884 0.176061 +0.496844 0.176061 +0.670755 0.949681 +0.202726 0.949681 +0.472024 0.949681 +0.941696 0.949681 +0.251692 0.192456 +0.677407 0.192456 +0.854111 0.192456 +0.429511 0.192456 +0.765823 0.004091 +0.765823 0.182429 +0.516603 0.182429 +0.516603 0.004091 +0.202726 0.468044 +0.472024 0.468044 +0.202726 0.356586 +0.472024 0.356586 +0.670755 0.468044 +0.941696 0.468044 +0.670755 0.356586 +0.941696 0.356586 +0.260475 0.004834 +0.266884 0.010943 +0.503250 0.004834 +0.496844 0.010943 +0.677407 0.345840 +0.429511 0.345840 +0.004105 0.192456 +0.251692 0.345840 +0.004105 0.345840 +0.854111 0.345840 +0.004123 0.949681 +0.004123 0.468044 +0.004123 0.356586 +0.503250 0.182172 +0.260475 0.182172 +0.266882 0.176063 +0.496844 0.176063 +0.202726 0.899077 +0.670755 0.899077 +0.004123 0.899077 +0.472024 0.899077 +0.251893 0.192456 +0.677115 0.192456 +0.854111 0.192456 +0.429617 0.192456 +0.765823 0.004091 +0.765823 0.182429 +0.516603 0.182429 +0.516603 0.004091 +0.670755 0.468044 +0.004123 0.468044 +0.670755 0.356586 +0.004123 0.356586 +0.202726 0.468044 +0.472024 0.468044 +0.202726 0.356586 +0.472024 0.356586 +0.004105 0.192456 +0.004105 0.345840 +0.677115 0.345840 +0.260475 0.004834 +0.266882 0.010943 +0.503250 0.004834 +0.496844 0.010943 +0.429617 0.345840 +0.251893 0.345840 +0.854111 0.345840 +0.941696 0.899077 +0.941696 0.468044 +0.941696 0.356586 +0.503250 0.182172 +0.260475 0.182172 +0.266878 0.176066 +0.496844 0.176066 +0.670755 0.754753 +0.202726 0.754753 +0.472024 0.754753 +0.941696 0.754753 +0.251803 0.192456 +0.676793 0.192456 +0.854111 0.192456 +0.429464 0.192456 +0.765823 0.004091 +0.765823 0.182429 +0.516603 0.182429 +0.516603 0.004091 +0.202726 0.468044 +0.472024 0.468044 +0.202726 0.356586 +0.472024 0.356586 +0.670755 0.468044 +0.941696 0.468044 +0.670755 0.356586 +0.941696 0.356586 +0.004123 0.754753 +0.004123 0.468044 +0.004123 0.356586 +0.260475 0.004834 +0.266878 0.010943 +0.503250 0.004834 +0.496844 0.010943 +0.676793 0.345840 +0.429464 0.345840 +0.251803 0.345840 +0.854111 0.345840 +0.004105 0.192456 +0.004105 0.345840 +0.503250 0.182172 +0.260475 0.182172 +0.266884 0.176061 +0.496844 0.176061 +0.670755 0.949681 +0.202726 0.949681 +0.472024 0.949681 +0.941696 0.949681 +0.251692 0.192456 +0.677407 0.192456 +0.854111 0.192456 +0.429511 0.192456 +0.765823 0.004091 +0.765823 0.182429 +0.516603 0.182429 +0.516603 0.004091 +0.202726 0.468044 +0.472024 0.468044 +0.202726 0.356586 +0.472024 0.356586 +0.670755 0.468044 +0.941696 0.468044 +0.670755 0.356586 +0.941696 0.356586 +0.260475 0.004834 +0.266884 0.010943 +0.503250 0.004834 +0.496844 0.010943 +0.677407 0.345840 +0.429511 0.345840 +0.004105 0.192456 +0.251692 0.345840 +0.004105 0.345840 +0.854111 0.345840 +0.004123 0.949681 +0.004123 0.468044 +0.004123 0.356586 +0.503250 0.182172 +0.260475 0.182172 +0.266882 0.176062 +0.496844 0.176062 +0.202726 0.996046 +0.670755 0.996046 +0.004123 0.996046 +0.472024 0.996046 +0.677249 0.192456 +0.251604 0.192456 +0.429384 0.192456 +0.854111 0.192456 +0.765823 0.004091 +0.765823 0.182429 +0.516603 0.182429 +0.516603 0.004091 +0.670755 0.468044 +0.004123 0.468044 +0.670755 0.356586 +0.004123 0.356586 +0.202726 0.468044 +0.472024 0.468044 +0.202726 0.356586 +0.472024 0.356586 +0.260475 0.004834 +0.266882 0.010943 +0.503250 0.004834 +0.496844 0.010943 +0.004105 0.192456 +0.251604 0.345840 +0.004105 0.345840 +0.677249 0.345840 +0.429384 0.345840 +0.854111 0.345840 +0.941696 0.996046 +0.941696 0.468044 +0.941696 0.356586 +0.503250 0.182172 +0.260475 0.182172 +0.266882 0.176063 +0.496844 0.176063 +0.202726 0.899077 +0.670755 0.899077 +0.004123 0.899077 +0.472024 0.899077 +0.251893 0.192456 +0.677115 0.192456 +0.854111 0.192456 +0.429617 0.192456 +0.765823 0.004091 +0.765823 0.182429 +0.516603 0.182429 +0.516603 0.004091 +0.670755 0.468044 +0.004123 0.468044 +0.670755 0.356586 +0.004123 0.356586 +0.202726 0.468044 +0.472024 0.468044 +0.202726 0.356586 +0.472024 0.356586 +0.004105 0.192456 +0.004105 0.345840 +0.677115 0.345840 +0.260475 0.004834 +0.266882 0.010943 +0.503250 0.004834 +0.496844 0.010943 +0.429617 0.345840 +0.251893 0.345840 +0.854111 0.345840 +0.941696 0.899077 +0.941696 0.468044 +0.941696 0.356586 +0.503250 0.182172 +0.260475 0.182172 +0.266878 0.176066 +0.496844 0.176066 +0.670755 0.754753 +0.202726 0.754753 +0.472024 0.754753 +0.941696 0.754753 +0.251803 0.192456 +0.676793 0.192456 +0.854111 0.192456 +0.429464 0.192456 +0.765823 0.004091 +0.765823 0.182429 +0.516603 0.182429 +0.516603 0.004091 +0.202726 0.468044 +0.472024 0.468044 +0.202726 0.356586 +0.472024 0.356586 +0.670755 0.468044 +0.941696 0.468044 +0.670755 0.356586 +0.941696 0.356586 +0.004123 0.754753 +0.004123 0.468044 +0.004123 0.356586 +0.260475 0.004834 +0.266878 0.010943 +0.503250 0.004834 +0.496844 0.010943 +0.676793 0.345840 +0.429464 0.345840 +0.251803 0.345840 +0.854111 0.345840 +0.004105 0.192456 +0.004105 0.345840 +0.503250 0.182172 +0.260475 0.182172 +0.266884 0.176061 +0.496844 0.176061 +0.670755 0.949681 +0.202726 0.949681 +0.472024 0.949681 +0.941696 0.949681 +0.251692 0.192456 +0.677407 0.192456 +0.854111 0.192456 +0.429511 0.192456 +0.765823 0.004091 +0.765823 0.182429 +0.516603 0.182429 +0.516603 0.004091 +0.202726 0.468044 +0.472024 0.468044 +0.202726 0.356586 +0.472024 0.356586 +0.670755 0.468044 +0.941696 0.468044 +0.670755 0.356586 +0.941696 0.356586 +0.260475 0.004834 +0.266884 0.010943 +0.503250 0.004834 +0.496844 0.010943 +0.677407 0.345840 +0.429511 0.345840 +0.004105 0.192456 +0.251692 0.345840 +0.004105 0.345840 +0.854111 0.345840 +0.004123 0.949681 +0.004123 0.468044 +0.004123 0.356586 +0.213991 0.931142 +0.213990 0.924664 +0.214038 0.825691 +0.214038 0.819212 +0.134759 0.853811 +0.134759 0.847332 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035379 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035379 +0.029544 0.035379 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035379 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035379 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035379 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 + + + + + + + + + + + +

0 0 0 3 1 2 1 2 3 3 3 2 0 4 0 2 5 1 6 6 7 4 7 4 7 8 6 7 9 6 4 10 4 5 11 5 7 12 10 5 13 11 1 14 8 7 15 10 1 16 8 3 17 9 7 18 15 3 19 12 6 20 14 6 21 14 3 22 12 2 23 13 4 24 18 6 25 19 2 26 16 4 27 18 2 28 16 0 29 17 8 30 20 10 31 22 11 32 23 10 33 22 8 34 20 9 35 21 15 36 27 12 37 24 14 38 26 14 39 26 12 40 24 13 41 25 14 42 30 13 43 31 11 44 28 14 45 30 11 46 28 10 47 29 14 48 35 10 49 32 15 50 34 15 51 34 10 52 32 9 53 33 12 54 38 15 55 39 9 56 36 12 57 38 9 58 36 8 59 37 18 60 42 16 61 40 17 62 41 18 63 47 21 64 49 19 65 46 18 66 47 19 67 46 16 68 4530 21 69 49 22 70 48 20 71 4531 22 72 48 21 73 49 18 74 47 23 75 45 20 76 43 22 77 44 20 78 52 23 79 53 17 80 50 20 81 52 17 82 50 16 83 51 26 84 56 24 85 54 25 86 55 26 87 61 29 88 63 27 89 60 26 90 61 27 91 60 24 92 4532 29 93 63 30 94 62 28 95 4533 30 96 62 29 97 63 26 98 61 31 99 59 28 100 57 30 101 58 28 102 66 31 103 67 25 104 64 28 105 66 25 106 64 24 107 65 33 108 4534 37 109 77 35 110 74 33 111 69 35 112 70 32 113 68 38 114 76 37 115 77 34 116 75 37 117 72 39 118 73 36 119 71 36 120 80 39 121 81 33 122 78 36 123 80 33 124 78 32 125 79 40 126 82 42 127 84 43 128 85 42 129 84 40 130 82 41 131 83 44 132 86 46 133 88 47 134 89 46 135 88 44 136 86 45 137 87 43 138 90 42 139 91 45 140 93 46 141 92 45 142 93 42 143 91 44 144 96 47 145 97 41 146 94 44 147 96 41 148 94 40 149 95 48 150 98 50 151 100 51 152 101 50 153 100 48 154 98 49 155 99 55 156 105 52 157 102 54 158 104 54 159 104 52 160 102 53 161 103 51 162 106 54 163 108 53 164 109 54 165 108 51 166 106 50 167 107 54 168 113 50 169 110 55 170 112 55 171 112 50 172 110 49 173 111 49 174 114 52 175 116 55 176 117 52 177 116 49 178 114 48 179 115 56 180 118 58 181 120 59 182 121 58 183 120 56 184 118 57 185 119 63 186 125 60 187 122 62 188 124 62 189 124 60 190 122 61 191 123 59 192 126 62 193 128 61 194 129 62 195 128 59 196 126 58 197 127 62 198 133 58 199 130 63 200 132 63 201 132 58 202 130 57 203 131 57 204 134 60 205 136 63 206 137 60 207 136 57 208 134 56 209 135 64 210 138 65 211 139 66 212 140 66 213 140 67 214 141 64 215 138 71 216 145 68 217 142 70 218 144 69 219 143 70 220 144 68 221 142 70 222 148 69 223 149 67 224 146 70 225 148 67 226 146 66 227 147 68 228 152 71 229 153 65 230 150 68 231 152 65 232 150 64 233 151 72 234 154 73 235 155 74 236 156 74 237 156 75 238 157 72 239 154 79 240 161 76 241 158 78 242 160 77 243 159 78 244 160 76 245 158 78 246 164 77 247 165 75 248 162 78 249 164 75 250 162 74 251 163 76 252 168 79 253 169 73 254 166 76 255 168 73 256 166 72 257 167 80 258 170 81 259 171 83 260 173 82 261 172 83 262 173 81 263 171 85 264 175 86 265 176 87 266 177 87 267 177 84 268 174 85 269 175 86 270 180 85 271 181 83 272 178 86 273 180 83 274 178 82 275 179 84 276 184 87 277 185 81 278 182 84 279 184 81 280 182 80 281 183 88 282 186 90 283 188 91 284 189 90 285 188 88 286 186 89 287 187 92 288 190 94 289 192 95 290 193 94 291 192 92 292 190 93 293 191 94 294 196 93 295 197 91 296 194 94 297 196 91 298 194 90 299 195 92 300 200 95 301 201 89 302 198 92 303 200 89 304 198 88 305 199 96 306 202 98 307 204 99 308 205 98 309 204 96 310 202 97 311 203 103 312 209 100 313 206 102 314 208 102 315 208 100 316 206 101 317 207 102 318 212 101 319 213 99 320 210 102 321 212 99 322 210 98 323 211 98 324 214 103 325 216 102 326 217 103 327 216 98 328 214 97 329 215 100 330 220 103 331 221 97 332 218 100 333 220 97 334 218 96 335 219 104 336 222 106 337 224 107 338 225 106 339 224 104 340 222 105 341 223 111 342 229 108 343 226 110 344 228 110 345 228 108 346 226 109 347 227 110 348 232 109 349 233 107 350 230 110 351 232 107 352 230 106 353 231 110 354 237 106 355 234 111 356 236 111 357 236 106 358 234 105 359 235 108 360 240 111 361 241 105 362 238 108 363 240 105 364 238 104 365 239 112 366 242 113 367 243 114 368 244 114 369 244 115 370 245 112 371 242 119 372 249 116 373 246 118 374 248 117 375 247 118 376 248 116 377 246 118 378 252 117 379 253 115 380 250 118 381 252 115 382 250 114 383 251 116 384 256 119 385 257 113 386 254 116 387 256 113 388 254 112 389 255 120 390 258 121 391 259 122 392 260 122 393 260 123 394 261 120 395 258 127 396 265 124 397 262 126 398 264 125 399 263 126 400 264 124 401 262 126 402 268 125 403 269 123 404 266 126 405 268 123 406 266 122 407 267 124 408 272 127 409 273 121 410 270 124 411 272 121 412 270 120 413 271 128 414 274 129 415 275 131 416 277 130 417 276 131 418 277 129 419 275 133 420 279 134 421 280 135 422 281 135 423 281 132 424 278 133 425 279 134 426 284 133 427 285 131 428 282 134 429 284 131 430 282 130 431 283 132 432 288 135 433 289 129 434 286 132 435 288 129 436 286 128 437 287 136 438 290 138 439 292 139 440 293 138 441 292 136 442 290 137 443 291 140 444 294 142 445 296 143 446 297 142 447 296 140 448 294 141 449 295 142 450 300 141 451 301 139 452 298 142 453 300 139 454 298 138 455 299 140 456 304 143 457 305 137 458 302 140 459 304 137 460 302 136 461 303 144 462 306 146 463 308 147 464 309 146 465 308 144 466 306 145 467 307 151 468 313 148 469 310 150 470 312 150 471 312 148 472 310 149 473 311 150 474 316 149 475 317 147 476 314 150 477 316 147 478 314 146 479 315 150 480 321 146 481 318 151 482 320 151 483 320 146 484 318 145 485 319 148 486 324 151 487 325 145 488 322 148 489 324 145 490 322 144 491 323 152 492 326 154 493 328 155 494 329 154 495 328 152 496 326 153 497 327 159 498 333 156 499 330 158 500 332 158 501 332 156 502 330 157 503 331 158 504 336 157 505 337 155 506 334 158 507 336 155 508 334 154 509 335 158 510 341 154 511 338 159 512 340 159 513 340 154 514 338 153 515 339 156 516 344 159 517 345 153 518 342 156 519 344 153 520 342 152 521 343 160 522 346 161 523 347 162 524 348 162 525 348 163 526 349 160 527 346 167 528 353 164 529 350 166 530 352 165 531 351 166 532 352 164 533 350 166 534 356 165 535 357 163 536 354 166 537 356 163 538 354 162 539 355 164 540 360 167 541 361 161 542 358 164 543 360 161 544 358 160 545 359 168 546 362 169 547 363 170 548 364 170 549 364 171 550 365 168 551 362 175 552 369 172 553 366 174 554 368 173 555 367 174 556 368 172 557 366 174 558 372 173 559 373 171 560 370 174 561 372 171 562 370 170 563 371 172 564 376 175 565 377 169 566 374 172 567 376 169 568 374 168 569 375 176 570 378 177 571 379 179 572 381 178 573 380 179 574 381 177 575 379 181 576 383 182 577 384 183 578 385 183 579 385 180 580 382 181 581 383 182 582 388 181 583 389 179 584 386 182 585 388 179 586 386 178 587 387 180 588 392 183 589 393 177 590 390 180 591 392 177 592 390 176 593 391 184 594 394 186 595 396 187 596 397 186 597 396 184 598 394 185 599 395 188 600 398 190 601 400 191 602 401 190 603 400 188 604 398 189 605 399 190 606 404 189 607 405 187 608 402 190 609 404 187 610 402 186 611 403 188 612 408 191 613 409 185 614 406 188 615 408 185 616 406 184 617 407 192 618 410 194 619 412 195 620 413 194 621 412 192 622 410 193 623 411 199 624 417 196 625 414 198 626 416 198 627 416 196 628 414 197 629 415 195 630 418 198 631 420 197 632 421 198 633 420 195 634 418 194 635 419 198 636 425 194 637 422 199 638 424 199 639 424 194 640 422 193 641 423 193 642 426 196 643 428 199 644 429 196 645 428 193 646 426 192 647 427 200 648 430 202 649 432 203 650 433 202 651 432 200 652 430 201 653 431 207 654 437 204 655 434 206 656 436 206 657 436 204 658 434 205 659 435 203 660 438 206 661 440 205 662 441 206 663 440 203 664 438 202 665 439 206 666 445 202 667 442 207 668 444 207 669 444 202 670 442 201 671 443 201 672 446 204 673 448 207 674 449 204 675 448 201 676 446 200 677 447 208 678 450 209 679 451 210 680 452 210 681 452 211 682 453 208 683 450 215 684 457 212 685 454 214 686 456 213 687 455 214 688 456 212 689 454 214 690 460 213 691 461 211 692 458 214 693 460 211 694 458 210 695 459 212 696 464 215 697 465 209 698 462 212 699 464 209 700 462 208 701 463 216 702 466 217 703 467 218 704 468 218 705 468 219 706 469 216 707 466 223 708 473 220 709 470 222 710 472 221 711 471 222 712 472 220 713 470 222 714 476 221 715 477 219 716 474 222 717 476 219 718 474 218 719 475 220 720 480 223 721 481 217 722 478 220 723 480 217 724 478 216 725 479 224 726 482 225 727 483 227 728 485 226 729 484 227 730 485 225 731 483 229 732 487 230 733 488 231 734 489 231 735 489 228 736 486 229 737 487 230 738 492 229 739 493 227 740 490 230 741 492 227 742 490 226 743 491 228 744 496 231 745 497 225 746 494 228 747 496 225 748 494 224 749 495 232 750 498 234 751 500 235 752 501 234 753 500 232 754 498 233 755 499 236 756 502 238 757 504 239 758 505 238 759 504 236 760 502 237 761 503 238 762 508 237 763 509 235 764 506 238 765 508 235 766 506 234 767 507 236 768 512 239 769 513 233 770 510 236 771 512 233 772 510 232 773 511 242 774 516 243 775 517 240 776 514 242 777 516 240 778 514 241 779 515 244 780 518 246 781 520 247 782 521 246 783 520 244 784 518 245 785 519 244 786 525 240 787 522 245 788 524 245 789 524 240 790 522 243 791 523 242 792 527 246 793 528 245 794 529 245 795 529 243 796 526 242 797 527 241 798 531 247 799 532 246 800 533 246 801 533 242 802 530 241 803 531 247 804 537 241 805 534 244 806 536 244 807 536 241 808 534 240 809 535 250 810 540 251 811 541 248 812 538 250 813 540 248 814 538 249 815 539 252 816 542 254 817 544 255 818 545 254 819 544 252 820 542 253 821 543 252 822 549 248 823 546 253 824 548 253 825 548 248 826 546 251 827 547 253 828 553 251 829 550 254 830 552 254 831 552 251 832 550 250 833 551 249 834 555 255 835 556 254 836 557 254 837 557 250 838 554 249 839 555 255 840 561 249 841 558 252 842 560 252 843 560 249 844 558 248 845 559 256 846 562 258 847 564 259 848 565 258 849 564 256 850 562 257 851 563 260 852 566 262 853 568 263 854 569 262 855 568 260 856 566 261 857 567 259 858 570 258 859 571 261 860 573 262 861 572 261 862 573 258 863 571 260 864 576 263 865 577 257 866 574 260 867 576 257 868 574 256 869 575 264 870 578 266 871 580 267 872 581 266 873 580 264 874 578 265 875 579 268 876 582 270 877 584 271 878 585 270 879 584 268 880 582 269 881 583 270 882 588 269 883 589 267 884 586 270 885 588 267 886 586 266 887 587 268 888 592 271 889 593 265 890 590 268 891 592 265 892 590 264 893 591 272 894 594 274 895 596 275 896 597 274 897 596 272 898 594 273 899 595 276 900 598 278 901 600 279 902 601 278 903 600 276 904 598 277 905 599 278 906 604 277 907 605 275 908 602 278 909 604 275 910 602 274 911 603 276 912 608 279 913 609 273 914 606 276 915 608 273 916 606 272 917 607 280 918 610 282 919 612 283 920 613 282 921 612 280 922 610 281 923 611 284 924 614 286 925 616 287 926 617 286 927 616 284 928 614 285 929 615 286 930 620 285 931 621 283 932 618 286 933 620 283 934 618 282 935 619 284 936 624 287 937 625 281 938 622 284 939 624 281 940 622 280 941 623 288 942 626 290 943 628 291 944 629 290 945 628 288 946 626 289 947 627 292 948 630 294 949 632 295 950 633 294 951 632 292 952 630 293 953 631 294 954 636 293 955 637 291 956 634 294 957 636 291 958 634 290 959 635 292 960 640 295 961 641 289 962 638 292 963 640 289 964 638 288 965 639 299 966 645 296 967 642 298 968 644 298 969 644 296 970 642 297 971 643 300 972 646 302 973 648 303 974 649 302 975 648 300 976 646 301 977 647 300 978 653 296 979 650 301 980 652 301 981 652 296 982 650 299 983 651 301 984 657 299 985 654 302 986 656 302 987 656 299 988 654 298 989 655 297 990 659 303 991 660 302 992 661 302 993 661 298 994 658 297 995 659 303 996 665 297 997 662 300 998 664 300 999 664 297 1000 662 296 1001 663

+

306 1002 668 304 1003 666 305 1004 667 310 1005 670 311 1006 673 312 1007 674 306 1008 671 311 1009 673 310 1010 670 310 1011 677 307 1012 675 306 1013 676 310 1014 681 312 1015 682 308 1016 679 308 1017 686 311 1018 683 304 1019 685 315 1020 689 313 1021 687 314 1022 688 319 1023 691 320 1024 694 321 1025 695 315 1026 692 320 1027 694 319 1028 691 319 1029 698 316 1030 696 315 1031 697 319 1032 702 321 1033 703 317 1034 700 317 1035 707 320 1036 704 313 1037 706 324 1038 710 322 1039 708 323 1040 709 328 1041 712 329 1042 715 330 1043 716 324 1044 713 329 1045 715 328 1046 712 328 1047 719 325 1048 717 324 1049 718 328 1050 723 330 1051 724 326 1052 721 326 1053 728 329 1054 725 322 1055 727 333 1056 731 331 1057 729 332 1058 730 337 1059 733 338 1060 736 339 1061 737 333 1062 734 338 1063 736 337 1064 733 337 1065 740 334 1066 738 333 1067 739 337 1068 744 339 1069 745 335 1070 742 335 1071 749 338 1072 746 331 1073 748 342 1074 752 340 1075 750 341 1076 751 346 1077 754 347 1078 757 348 1079 758 342 1080 755 347 1081 757 346 1082 754 346 1083 761 343 1084 759 342 1085 760 346 1086 765 348 1087 766 344 1088 763 344 1089 770 347 1090 767 340 1091 769 351 1092 773 349 1093 771 350 1094 772 355 1095 775 356 1096 778 357 1097 779 351 1098 776 356 1099 778 355 1100 775 355 1101 782 352 1102 780 351 1103 781 355 1104 786 357 1105 787 353 1106 784 353 1107 791 356 1108 788 349 1109 790 360 1110 794 358 1111 792 359 1112 793 364 1113 796 365 1114 799 366 1115 800 360 1116 797 365 1117 799 364 1118 796 364 1119 803 361 1120 801 360 1121 802 364 1122 807 366 1123 808 362 1124 805 362 1125 812 365 1126 809 358 1127 811 369 1128 815 367 1129 813 368 1130 814 373 1131 817 374 1132 820 375 1133 821 369 1134 818 374 1135 820 373 1136 817 373 1137 824 370 1138 822 369 1139 823 373 1140 828 375 1141 829 371 1142 826 371 1143 833 374 1144 830 367 1145 832 378 1146 836 376 1147 834 377 1148 835 382 1149 838 383 1150 841 384 1151 842 378 1152 839 383 1153 841 382 1154 838 382 1155 845 379 1156 843 378 1157 844 382 1158 849 384 1159 850 380 1160 847 380 1161 854 383 1162 851 376 1163 853 387 1164 857 385 1165 855 386 1166 856 391 1167 859 392 1168 862 393 1169 863 387 1170 860 392 1171 862 391 1172 859 391 1173 866 388 1174 864 387 1175 865 391 1176 870 393 1177 871 389 1178 868 389 1179 875 392 1180 872 385 1181 874 396 1182 878 394 1183 876 395 1184 877 400 1185 880 401 1186 883 402 1187 884 396 1188 881 401 1189 883 400 1190 880 400 1191 887 397 1192 885 396 1193 886 400 1194 891 402 1195 892 398 1196 889 398 1197 896 401 1198 893 394 1199 895 405 1200 899 403 1201 897 404 1202 898 409 1203 901 410 1204 904 411 1205 905 405 1206 902 410 1207 904 409 1208 901 409 1209 908 406 1210 906 405 1211 907 409 1212 912 411 1213 913 407 1214 910 407 1215 917 410 1216 914 403 1217 916 414 1218 920 412 1219 918 413 1220 919 418 1221 922 419 1222 925 420 1223 926 414 1224 923 419 1225 925 418 1226 922 418 1227 929 415 1228 927 414 1229 928 418 1230 933 420 1231 934 416 1232 931 416 1233 938 419 1234 935 412 1235 937 423 1236 941 421 1237 939 422 1238 940 427 1239 943 428 1240 946 429 1241 947 423 1242 944 428 1243 946 427 1244 943 427 1245 950 424 1246 948 423 1247 949 427 1248 954 429 1249 955 425 1250 952 425 1251 959 428 1252 956 421 1253 958 432 1254 962 430 1255 960 431 1256 961 436 1257 964 437 1258 967 438 1259 968 432 1260 965 437 1261 967 436 1262 964 436 1263 971 433 1264 969 432 1265 970 436 1266 975 438 1267 976 434 1268 973 434 1269 980 437 1270 977 430 1271 979 441 1272 983 439 1273 981 440 1274 982 445 1275 985 446 1276 988 447 1277 989 441 1278 986 446 1279 988 445 1280 985 445 1281 992 442 1282 990 441 1283 991 445 1284 996 447 1285 997 443 1286 994 443 1287 1001 446 1288 998 439 1289 1000 450 1290 1004 448 1291 1002 449 1292 1003 454 1293 1006 455 1294 1009 456 1295 1010 450 1296 1007 455 1297 1009 454 1298 1006 454 1299 1013 451 1300 1011 450 1301 1012 454 1302 1017 456 1303 1018 452 1304 1015 452 1305 1022 455 1306 1019 448 1307 1021 459 1308 1025 457 1309 1023 458 1310 1024 463 1311 1027 464 1312 1030 465 1313 1031 459 1314 1028 464 1315 1030 463 1316 1027 463 1317 1034 460 1318 1032 459 1319 1033 463 1320 1038 465 1321 1039 461 1322 1036 461 1323 1043 464 1324 1040 457 1325 1042 468 1326 1046 466 1327 1044 467 1328 1045 472 1329 1048 473 1330 1051 474 1331 1052 468 1332 1049 473 1333 1051 472 1334 1048 472 1335 1055 469 1336 1053 468 1337 1054 472 1338 1059 474 1339 1060 470 1340 1057 470 1341 1064 473 1342 1061 466 1343 1063 477 1344 1067 475 1345 1065 476 1346 1066 481 1347 1069 482 1348 1072 483 1349 1073 477 1350 1070 482 1351 1072 481 1352 1069 481 1353 1076 478 1354 1074 477 1355 1075 481 1356 1080 483 1357 1081 479 1358 1078 479 1359 1085 482 1360 1082 475 1361 1084 486 1362 1088 484 1363 1086 485 1364 1087 490 1365 1090 491 1366 1093 492 1367 1094 486 1368 1091 491 1369 1093 490 1370 1090 490 1371 1097 487 1372 1095 486 1373 1096 490 1374 1101 492 1375 1102 488 1376 1099 488 1377 1106 491 1378 1103 484 1379 1105 495 1380 1109 493 1381 1107 494 1382 1108 499 1383 1111 500 1384 1114 501 1385 1115 495 1386 1112 500 1387 1114 499 1388 1111 499 1389 1118 496 1390 1116 495 1391 1117 499 1392 1122 501 1393 1123 497 1394 1120 497 1395 1127 500 1396 1124 493 1397 1126 504 1398 1130 502 1399 1128 503 1400 1129 508 1401 1132 509 1402 1135 510 1403 1136 504 1404 1133 509 1405 1135 508 1406 1132 508 1407 1139 505 1408 1137 504 1409 1138 508 1410 1143 510 1411 1144 506 1412 1141 506 1413 1148 509 1414 1145 502 1415 1147 513 1416 1151 511 1417 1149 512 1418 1150 517 1419 1153 518 1420 1156 519 1421 1157 513 1422 1154 518 1423 1156 517 1424 1153 517 1425 1160 514 1426 1158 513 1427 1159 517 1428 1164 519 1429 1165 515 1430 1162 515 1431 1169 518 1432 1166 511 1433 1168 522 1434 1172 520 1435 1170 521 1436 1171 526 1437 1174 527 1438 1177 528 1439 1178 522 1440 1175 527 1441 1177 526 1442 1174 526 1443 1181 523 1444 1179 522 1445 1180 526 1446 1185 528 1447 1186 524 1448 1183 524 1449 1190 527 1450 1187 520 1451 1189 531 1452 1193 529 1453 1191 530 1454 1192 535 1455 1195 536 1456 1198 537 1457 1199 531 1458 1196 536 1459 1198 535 1460 1195 535 1461 1202 532 1462 1200 531 1463 1201 535 1464 1206 537 1465 1207 533 1466 1204 533 1467 1211 536 1468 1208 529 1469 1210 540 1470 1214 538 1471 1212 539 1472 1213 544 1473 1216 545 1474 1219 546 1475 1220 540 1476 1217 545 1477 1219 544 1478 1216 544 1479 1223 541 1480 1221 540 1481 1222 544 1482 1227 546 1483 1228 542 1484 1225 542 1485 1232 545 1486 1229 538 1487 1231 549 1488 1235 547 1489 1233 548 1490 1234 553 1491 1237 554 1492 1240 555 1493 1241 549 1494 1238 554 1495 1240 553 1496 1237 553 1497 1244 550 1498 1242 549 1499 1243 553 1500 1248 555 1501 1249 551 1502 1246 551 1503 1253 554 1504 1250 547 1505 1252 558 1506 1256 556 1507 1254 557 1508 1255 562 1509 1258 563 1510 1261 564 1511 1262 558 1512 1259 563 1513 1261 562 1514 1258 562 1515 1265 559 1516 1263 558 1517 1264 562 1518 1269 564 1519 1270 560 1520 1267 560 1521 1274 563 1522 1271 556 1523 1273 567 1524 1277 565 1525 1275 566 1526 1276 571 1527 1279 572 1528 1282 573 1529 1283 567 1530 1280 572 1531 1282 571 1532 1279 571 1533 1286 568 1534 1284 567 1535 1285 571 1536 1290 573 1537 1291 569 1538 1288 569 1539 1295 572 1540 1292 565 1541 1294 576 1542 1298 574 1543 1296 575 1544 1297 580 1545 1300 581 1546 1303 582 1547 1304 576 1548 1301 581 1549 1303 580 1550 1300 580 1551 1307 579 1552 1308 576 1553 1306 580 1554 1311 582 1555 1312 578 1556 1309 578 1557 1316 575 1558 1314 574 1559 1315 585 1560 1319 583 1561 1317 584 1562 1318 589 1563 1321 590 1564 1324 591 1565 1325 585 1566 1322 590 1567 1324 589 1568 1321 589 1569 1328 586 1570 1326 585 1571 1327 589 1572 1332 591 1573 1333 587 1574 1330 587 1575 1337 590 1576 1334 583 1577 1336 594 1578 1340 592 1579 1338 593 1580 1339 598 1581 1342 599 1582 1345 600 1583 1346 594 1584 1343 599 1585 1345 598 1586 1342 598 1587 1349 595 1588 1347 594 1589 1348 598 1590 1353 600 1591 1354 596 1592 1351 596 1593 1358 599 1594 1355 592 1595 1357 603 1596 1361 601 1597 1359 602 1598 1360 607 1599 1363 608 1600 1366 609 1601 1367 603 1602 1364 608 1603 1366 607 1604 1363 607 1605 1370 604 1606 1368 603 1607 1369 607 1608 1374 609 1609 1375 605 1610 1372 605 1611 1379 608 1612 1376 601 1613 1378 612 1614 1382 610 1615 1380 611 1616 1381 616 1617 1384 617 1618 1387 618 1619 1388 612 1620 1385 617 1621 1387 616 1622 1384 616 1623 1391 613 1624 1389 612 1625 1390 616 1626 1395 618 1627 1396 614 1628 1393 614 1629 1400 617 1630 1397 610 1631 1399 621 1632 1403 619 1633 1401 620 1634 1402 625 1635 1405 626 1636 1408 627 1637 1409 621 1638 1406 626 1639 1408 625 1640 1405 625 1641 1412 622 1642 1410 621 1643 1411 625 1644 1416 627 1645 1417 623 1646 1414 623 1647 1421 626 1648 1418 619 1649 1420 630 1650 1424 628 1651 1422 629 1652 1423 634 1653 1426 635 1654 1429 636 1655 1430 630 1656 1427 635 1657 1429 634 1658 1426 634 1659 1433 631 1660 1431 630 1661 1432 634 1662 1437 636 1663 1438 632 1664 1435 632 1665 1442 635 1666 1439 628 1667 1441 639 1668 1445 637 1669 1443 638 1670 1444 643 1671 1447 644 1672 1450 645 1673 1451 639 1674 1448 644 1675 1450 643 1676 1447 643 1677 1454 640 1678 1452 639 1679 1453 643 1680 1458 645 1681 1459 641 1682 1456 641 1683 1463 644 1684 1460 637 1685 1462 648 1686 1466 646 1687 1464 647 1688 1465 652 1689 1468 653 1690 1471 654 1691 1472 648 1692 1469 653 1693 1471 652 1694 1468 652 1695 1475 649 1696 1473 648 1697 1474 652 1698 1479 654 1699 1480 650 1700 1477 650 1701 1484 653 1702 1481 646 1703 1483 657 1704 1487 655 1705 1485 656 1706 1486 661 1707 1489 662 1708 1492 663 1709 1493 657 1710 1490 662 1711 1492 661 1712 1489 661 1713 1496 658 1714 1494 657 1715 1495 661 1716 1500 663 1717 1501 659 1718 1498 659 1719 1505 662 1720 1502 655 1721 1504 666 1722 1508 664 1723 1506 665 1724 1507 667 1725 1512 668 1726 1510 664 1727 1511 670 1728 1514 671 1729 1517 672 1730 1518 666 1731 1515 671 1732 1517 670 1733 1514 670 1734 1521 667 1735 1519 666 1736 1520 670 1737 1525 672 1738 1526 668 1739 1523 668 1740 1530 671 1741 1527 664 1742 1529 675 1743 1533 673 1744 1531 674 1745 1532 679 1746 1535 680 1747 1538 681 1748 1539 675 1749 1536 680 1750 1538 679 1751 1535 679 1752 1542 676 1753 1540 675 1754 1541 679 1755 1546 681 1756 1547 677 1757 1544 677 1758 1551 680 1759 1548 673 1760 1550 684 1761 1554 682 1762 1552 683 1763 1553 688 1764 1556 689 1765 1559 690 1766 1560 684 1767 1557 689 1768 1559 688 1769 1556 688 1770 1563 685 1771 1561 684 1772 1562 688 1773 1567 690 1774 1568 686 1775 1565 686 1776 1572 689 1777 1569 682 1778 1571 693 1779 1575 691 1780 1573 692 1781 1574 697 1782 1577 698 1783 1580 699 1784 1581 693 1785 1578 698 1786 1580 697 1787 1577 697 1788 1584 694 1789 1582 693 1790 1583 697 1791 1588 699 1792 1589 695 1793 1586 695 1794 1593 698 1795 1590 691 1796 1592 702 1797 1596 700 1798 1594 701 1799 1595 706 1800 1598 707 1801 1601 708 1802 1602 702 1803 1599 707 1804 1601 706 1805 1598 706 1806 1605 703 1807 1603 702 1808 1604 706 1809 1609 708 1810 1610 704 1811 1607 704 1812 1614 707 1813 1611 700 1814 1613 711 1815 1617 709 1816 1615 710 1817 1616 712 1818 1621 713 1819 1619 709 1820 1620 715 1821 1623 716 1822 1626 717 1823 1627 711 1824 1624 716 1825 1626 715 1826 1623 715 1827 1630 712 1828 1628 711 1829 1629 715 1830 1634 717 1831 1635 713 1832 1632 713 1833 1639 716 1834 1636 709 1835 1638 720 1836 1642 718 1837 1640 719 1838 1641 724 1839 1644 725 1840 1647 726 1841 1648 720 1842 1645 725 1843 1647 724 1844 1644 724 1845 1651 721 1846 1649 720 1847 1650 724 1848 1655 726 1849 1656 722 1850 1653 722 1851 1660 725 1852 1657 718 1853 1659 729 1854 1663 727 1855 1661 728 1856 1662 733 1857 1665 734 1858 1668 735 1859 1669 729 1860 1666 734 1861 1668 733 1862 1665 733 1863 1672 730 1864 1670 729 1865 1671 733 1866 1676 735 1867 1677 731 1868 1674 731 1869 1681 734 1870 1678 727 1871 1680 738 1872 1684 736 1873 1682 737 1874 1683 742 1875 1686 743 1876 1689 744 1877 1690 738 1878 1687 743 1879 1689 742 1880 1686 742 1881 1693 739 1882 1691 738 1883 1692 742 1884 1697 744 1885 1698 740 1886 1695 740 1887 1702 743 1888 1699 736 1889 1701 747 1890 1705 745 1891 1703 746 1892 1704 751 1893 1707 752 1894 1710 753 1895 1711 747 1896 1708 752 1897 1710 751 1898 1707 751 1899 1714 748 1900 1712 747 1901 1713 751 1902 1718 753 1903 1719 749 1904 1716 749 1905 1723 752 1906 1720 745 1907 1722 756 1908 1726 754 1909 1724 755 1910 1725 760 1911 1728 761 1912 1731 762 1913 1732 756 1914 1729 761 1915 1731 760 1916 1728 760 1917 1735 757 1918 1733 756 1919 1734 760 1920 1739 762 1921 1740 758 1922 1737 758 1923 1744 761 1924 1741 754 1925 1743 765 1926 1747 763 1927 1745 764 1928 1746 766 1929 1751 767 1930 1749 763 1931 1750 769 1932 1753 770 1933 1756 771 1934 1757 765 1935 1754 770 1936 1756 769 1937 1753 769 1938 1760 766 1939 1758 765 1940 1759 769 1941 1764 771 1942 1765 767 1943 1762 767 1944 1769 770 1945 1766 763 1946 1768 774 1947 1772 772 1948 1770 773 1949 1771 778 1950 1774 779 1951 1777 780 1952 1778 774 1953 1775 779 1954 1777 778 1955 1774 778 1956 1781 775 1957 1779 774 1958 1780 778 1959 1785 780 1960 1786 776 1961 1783 776 1962 1790 779 1963 1787 772 1964 1789 783 1965 1793 781 1966 1791 782 1967 1792 787 1968 1795 788 1969 1798 789 1970 1799 783 1971 1796 788 1972 1798 787 1973 1795 787 1974 1802 784 1975 1800 783 1976 1801 787 1977 1806 789 1978 1807 785 1979 1804 785 1980 1811 788 1981 1808 781 1982 1810 792 1983 1814 790 1984 1812 791 1985 1813 796 1986 1816 797 1987 1819 798 1988 1820 792 1989 1817 797 1990 1819 796 1991 1816 796 1992 1823 793 1993 1821 792 1994 1822 796 1995 1827 798 1996 1828 794 1997 1825 794 1998 1832 797 1999 1829 790 2000 1831 801 2001 1835 799 2002 1833 800 2003 1834 805 2004 1837 806 2005 1840 807 2006 1841 801 2007 1838 806 2008 1840 805 2009 1837 805 2010 1844 802 2011 1842 801 2012 1843 805 2013 1848 807 2014 1849 803 2015 1846 803 2016 1853 806 2017 1850 799 2018 1852 810 2019 1856 808 2020 1854 809 2021 1855 814 2022 1858 815 2023 1861 816 2024 1862 810 2025 1859 815 2026 1861 814 2027 1858 814 2028 1865 811 2029 1863 810 2030 1864 814 2031 1869 816 2032 1870 812 2033 1867 812 2034 1874 815 2035 1871 808 2036 1873 819 2037 1877 817 2038 1875 818 2039 1876 823 2040 1879 824 2041 1882 825 2042 1883 819 2043 1880 824 2044 1882 823 2045 1879 823 2046 1886 820 2047 1884 819 2048 1885 823 2049 1890 825 2050 1891 821 2051 1888 821 2052 1895 824 2053 1892 817 2054 1894 828 2055 1898 826 2056 1896 827 2057 1897 832 2058 1900 833 2059 1903 834 2060 1904 828 2061 1901 833 2062 1903 832 2063 1900 832 2064 1907 829 2065 1905 828 2066 1906 832 2067 1911 834 2068 1912 830 2069 1909 830 2070 1916 833 2071 1913 826 2072 1915 837 2073 1919 835 2074 1917 836 2075 1918 841 2076 1921 842 2077 1924 843 2078 1925 837 2079 1922 842 2080 1924 841 2081 1921 841 2082 1928 838 2083 1926 837 2084 1927 841 2085 1932 843 2086 1933 839 2087 1930 839 2088 1937 842 2089 1934 835 2090 1936 846 2091 1940 844 2092 1938 845 2093 1939 850 2094 1942 851 2095 1945 852 2096 1946 846 2097 1943 851 2098 1945 850 2099 1942 850 2100 1949 847 2101 1947 846 2102 1948 850 2103 1953 852 2104 1954 848 2105 1951 848 2106 1958 851 2107 1955 844 2108 1957 855 2109 1961 853 2110 1959 854 2111 1960 859 2112 1963 860 2113 1966 861 2114 1967 855 2115 1964 860 2116 1966 859 2117 1963 859 2118 1970 856 2119 1968 855 2120 1969 859 2121 1974 861 2122 1975 857 2123 1972 857 2124 1979 860 2125 1976 853 2126 1978 864 2127 1982 862 2128 1980 863 2129 1981 868 2130 1984 869 2131 1987 870 2132 1988 864 2133 1985 869 2134 1987 868 2135 1984 868 2136 1991 865 2137 1989 864 2138 1990 868 2139 1995 870 2140 1996 866 2141 1993 866 2142 2000 869 2143 1997 862 2144 1999 873 2145 2003 871 2146 2001 872 2147 2002 877 2148 2005 878 2149 2008 879 2150 2009 873 2151 2006 878 2152 2008 877 2153 2005 877 2154 2012 874 2155 2010 873 2156 2011 877 2157 2016 879 2158 2017 875 2159 2014 875 2160 2021 878 2161 2018 871 2162 2020 882 2163 2024 880 2164 2022 881 2165 2023 886 2166 2026 887 2167 2029 888 2168 2030 882 2169 2027 887 2170 2029 886 2171 2026 886 2172 2033 883 2173 2031 882 2174 2032 886 2175 2037 888 2176 2038 884 2177 2035 884 2178 2042 887 2179 2039 880 2180 2041 891 2181 2045 889 2182 2043 890 2183 2044 895 2184 2047 896 2185 2050 897 2186 2051 891 2187 2048 896 2188 2050 895 2189 2047 895 2190 2054 892 2191 2052 891 2192 2053 895 2193 2058 897 2194 2059 893 2195 2056 893 2196 2063 896 2197 2060 889 2198 2062 900 2199 2066 898 2200 2064 899 2201 2065 904 2202 2068 905 2203 2071 906 2204 2072 900 2205 2069 905 2206 2071 904 2207 2068 904 2208 2075 901 2209 2073 900 2210 2074 904 2211 2079 906 2212 2080 902 2213 2077 902 2214 2084 905 2215 2081 898 2216 2083 909 2217 2087 907 2218 2085 908 2219 2086 913 2220 2089 914 2221 2092 915 2222 2093 909 2223 2090 914 2224 2092 913 2225 2089 913 2226 2096 910 2227 2094 909 2228 2095 913 2229 2100 915 2230 2101 911 2231 2098 911 2232 2105 914 2233 2102 907 2234 2104 918 2235 2108 916 2236 2106 917 2237 2107 922 2238 2110 923 2239 2113 924 2240 2114 918 2241 2111 923 2242 2113 922 2243 2110 922 2244 2117 919 2245 2115 918 2246 2116 922 2247 2121 924 2248 2122 920 2249 2119 920 2250 2126 923 2251 2123 916 2252 2125 927 2253 2129 925 2254 2127 926 2255 2128 931 2256 2131 932 2257 2134 933 2258 2135 927 2259 2132 932 2260 2134 931 2261 2131 931 2262 2138 928 2263 2136 927 2264 2137 931 2265 2142 933 2266 2143 929 2267 2140 929 2268 2147 932 2269 2144 925 2270 2146 936 2271 2150 934 2272 2148 935 2273 2149 940 2274 2152 941 2275 2155 942 2276 2156 936 2277 2153 941 2278 2155 940 2279 2152 940 2280 2159 937 2281 2157 936 2282 2158 940 2283 2163 942 2284 2164 938 2285 2161 938 2286 2168 941 2287 2165 934 2288 2167 945 2289 2171 943 2290 2169 944 2291 2170 949 2292 2173 950 2293 2176 951 2294 2177 945 2295 2174 950 2296 2176 949 2297 2173 949 2298 2180 946 2299 2178 945 2300 2179 949 2301 2184 951 2302 2185 947 2303 2182 947 2304 2189 950 2305 2186 943 2306 2188 954 2307 2192 952 2308 2190 953 2309 2191 958 2310 2194 959 2311 2197 960 2312 2198 954 2313 2195 959 2314 2197 958 2315 2194 958 2316 2201 955 2317 2199 954 2318 2200 958 2319 2205 960 2320 2206 956 2321 2203 956 2322 2210 959 2323 2207 952 2324 2209 963 2325 2213 961 2326 2211 962 2327 2212 967 2328 2215 968 2329 2218 969 2330 2219 963 2331 2216 968 2332 2218 967 2333 2215 967 2334 2222 964 2335 2220 963 2336 2221 967 2337 2226 969 2338 2227 965 2339 2224 965 2340 2231 968 2341 2228 961 2342 2230 972 2343 2234 970 2344 2232 971 2345 2233 976 2346 2236 977 2347 2239 978 2348 2240 972 2349 2237 977 2350 2239 976 2351 2236 976 2352 2243 973 2353 2241 972 2354 2242 976 2355 2247 978 2356 2248 974 2357 2245 974 2358 2252 977 2359 2249 970 2360 2251 981 2361 2255 979 2362 2253 980 2363 2254 985 2364 2257 986 2365 2260 987 2366 2261 981 2367 2258 986 2368 2260 985 2369 2257 985 2370 2264 982 2371 2262 981 2372 2263 985 2373 2268 987 2374 2269 983 2375 2266 983 2376 2273 986 2377 2270 979 2378 2272 990 2379 2276 988 2380 2274 989 2381 2275 994 2382 2278 995 2383 2281 996 2384 2282 990 2385 2279 995 2386 2281 994 2387 2278 994 2388 2285 991 2389 2283 990 2390 2284 994 2391 2289 996 2392 2290 992 2393 2287 992 2394 2294 995 2395 2291 988 2396 2293 999 2397 2297 997 2398 2295 998 2399 2296 1003 2400 2299 1004 2401 2302 1005 2402 2303 999 2403 2300 1004 2404 2302 1003 2405 2299 1003 2406 2306 1000 2407 2304 999 2408 2305 1003 2409 2310 1005 2410 2311 1001 2411 2308 1001 2412 2315 998 2413 2313 997 2414 2314 1008 2415 2318 1006 2416 2316 1007 2417 2317 1012 2418 2320 1013 2419 2323 1014 2420 2324 1008 2421 2321 1013 2422 2323 1012 2423 2320 1012 2424 2327 1009 2425 2325 1008 2426 2326 1012 2427 2331 1014 2428 2332 1010 2429 2329 1010 2430 2336 1007 2431 2334 1006 2432 2335 1017 2433 2339 1015 2434 2337 1016 2435 2338 1021 2436 2341 1022 2437 2344 1023 2438 2345 1017 2439 2342 1022 2440 2344 1021 2441 2341 1021 2442 2348 1018 2443 2346 1017 2444 2347 1021 2445 2352 1023 2446 2353 1019 2447 2350 1019 2448 2357 1022 2449 2354 1015 2450 2356 1026 2451 2360 1024 2452 2358 1025 2453 2359 1030 2454 2362 1031 2455 2365 1032 2456 2366 1026 2457 2363 1031 2458 2365 1030 2459 2362 1030 2460 2369 1027 2461 2367 1026 2462 2368 1030 2463 2373 1032 2464 2374 1028 2465 2371 1028 2466 2378 1025 2467 2376 1024 2468 2377 1035 2469 2381 1033 2470 2379 1034 2471 2380 1039 2472 2383 1040 2473 2386 1041 2474 2387 1035 2475 2384 1040 2476 2386 1039 2477 2383 1039 2478 2390 1036 2479 2388 1035 2480 2389 1039 2481 2394 1041 2482 2395 1037 2483 2392 1037 2484 2399 1034 2485 2397 1033 2486 2398 1044 2487 2402 1042 2488 2400 1043 2489 2401 1045 2490 2406 1046 2491 2404 1042 2492 2405 1048 2493 2408 1049 2494 2411 1050 2495 2412 1044 2496 2409 1049 2497 2411 1048 2498 2408 1048 2499 2415 1045 2500 2413 1044 2501 2414 1048 2502 2419 1050 2503 2420 1046 2504 2417 1046 2505 2424 1049 2506 2421 1042 2507 2423 1053 2508 2427 1051 2509 2425 1052 2510 2426 1058 2511 2432 1053 2512 2430 1052 2513 2431 1059 2514 2433 1057 2515 2429 1058 2516 2432 1057 2517 2436 1054 2518 2434 1053 2519 2435 1057 2520 2440 1059 2521 2441 1055 2522 2438 1055 2523 2445 1058 2524 2442 1051 2525 2444 1062 2526 2448 1060 2527 2446 1061 2528 2447 1067 2529 2453 1062 2530 2451 1061 2531 2452 1068 2532 2454 1066 2533 2450 1067 2534 2453 1066 2535 2457 1063 2536 2455 1062 2537 2456 1066 2538 2461 1068 2539 2462 1064 2540 2459 1064 2541 2466 1067 2542 2463 1060 2543 2465 1071 2544 2469 1069 2545 2467 1070 2546 2468 1076 2547 2474 1071 2548 2472 1070 2549 2473 1077 2550 2475 1076 2551 2474 1073 2552 4621 1075 2553 2478 1072 2554 2476 1071 2555 2477 1075 2556 2482 1077 2557 2483 1073 2558 2480 1073 2559 2487 1076 2560 2484 1069 2561 2486 1080 2562 2490 1078 2563 2488 1079 2564 2489 1085 2565 2495 1080 2566 2493 1079 2567 2494 1086 2568 2496 1084 2569 2492 1085 2570 2495 1084 2571 2499 1081 2572 2497 1080 2573 2498 1084 2574 2503 1086 2575 2504 1082 2576 2501 1082 2577 2508 1085 2578 2505 1078 2579 2507 1089 2580 2511 1087 2581 2509 1088 2582 2510 1094 2583 2516 1089 2584 2514 1088 2585 2515 1095 2586 2517 1093 2587 2513 1094 2588 2516 1093 2589 2520 1090 2590 2518 1089 2591 2519 1093 2592 2524 1095 2593 2525 1091 2594 2522 1091 2595 2529 1094 2596 2526 1087 2597 2528 1098 2598 2532 1096 2599 2530 1097 2600 2531 1103 2601 2537 1098 2602 2535 1097 2603 2536 1104 2604 2538 1102 2605 2534 1103 2606 2537 1102 2607 2541 1099 2608 2539 1098 2609 2540 1102 2610 2545 1104 2611 2546 1100 2612 2543 1100 2613 2550 1103 2614 2547 1096 2615 2549 1107 2616 2553 1105 2617 2551 1106 2618 2552 1112 2619 2558 1107 2620 2556 1106 2621 2557 1113 2622 2559 1111 2623 2555 1109 2624 4625 1111 2625 2562 1108 2626 2560 1107 2627 2561 1111 2628 2566 1113 2629 2567 1109 2630 2564 1109 2631 2571 1112 2632 2568 1105 2633 2570 1116 2634 2574 1114 2635 2572 1115 2636 2573 1117 2637 2578 1118 2638 2576 1114 2639 2577 1121 2640 2583 1116 2641 2581 1115 2642 2582 1122 2643 2584 1120 2644 2580 1121 2645 2583 1120 2646 2587 1117 2647 2585 1116 2648 2586 1120 2649 2591 1122 2650 2592 1118 2651 2589 1118 2652 2596 1121 2653 2593 1114 2654 2595 1125 2655 2599 1123 2656 2597 1124 2657 2598 1129 2658 2601 1130 2659 2604 1131 2660 2605 1125 2661 2602 1130 2662 2604 1129 2663 2601 1129 2664 2608 1126 2665 2606 1125 2666 2607 1129 2667 2612 1131 2668 2613 1127 2669 2610 1127 2670 2617 1124 2671 2615 1123 2672 2616 1134 2673 2620 1132 2674 2618 1133 2675 2619 1138 2676 2622 1139 2677 2625 1140 2678 2626 1134 2679 2623 1139 2680 2625 1138 2681 2622 1138 2682 2629 1135 2683 2627 1134 2684 2628 1138 2685 2633 1140 2686 2634 1136 2687 2631 1136 2688 2638 1139 2689 2635 1132 2690 2637 1143 2691 2641 1141 2692 2639 1142 2693 2640 1147 2694 2643 1148 2695 2646 1149 2696 2647 1143 2697 2644 1148 2698 2646 1147 2699 2643 1147 2700 2650 1144 2701 2648 1143 2702 2649 1147 2703 2654 1149 2704 2655 1145 2705 2652 1145 2706 2659 1148 2707 2656 1141 2708 2658 1152 2709 2662 1150 2710 2660 1151 2711 2661 1156 2712 2664 1157 2713 2667 1158 2714 2668 1152 2715 2665 1157 2716 2667 1156 2717 2664 1156 2718 2671 1153 2719 2669 1152 2720 2670 1156 2721 2675 1158 2722 2676 1154 2723 2673 1154 2724 2680 1157 2725 2677 1150 2726 2679 1161 2727 2683 1159 2728 2681 1160 2729 2682 1165 2730 2685 1166 2731 2688 1167 2732 2689 1161 2733 2686 1166 2734 2688 1165 2735 2685 1165 2736 2692 1162 2737 2690 1161 2738 2691 1165 2739 2696 1167 2740 2697 1163 2741 2694 1163 2742 2701 1166 2743 2698 1159 2744 2700 1170 2745 2704 1168 2746 2702 1169 2747 2703 1175 2748 2709 1170 2749 2707 1169 2750 2708 1176 2751 2710 1174 2752 2706 1175 2753 2709 1174 2754 2713 1171 2755 2711 1170 2756 2712 1174 2757 2717 1176 2758 2718 1172 2759 2715 1172 2760 2722 1175 2761 2719 1168 2762 2721 1179 2763 2725 1177 2764 2723 1178 2765 2724 1180 2766 2729 1181 2767 2727 1177 2768 2728 1184 2769 2734 1179 2770 2732 1178 2771 2733 1185 2772 2735 1183 2773 2731 1184 2774 2734 1183 2775 2738 1180 2776 2736 1179 2777 2737 1183 2778 2742 1185 2779 2743 1181 2780 2740 1181 2781 2747 1184 2782 2744 1177 2783 2746 1188 2784 2750 1186 2785 2748 1187 2786 2749 1193 2787 2755 1188 2788 2753 1187 2789 2754 1194 2790 2756 1193 2791 2755 1190 2792 4634 1192 2793 2759 1189 2794 2757 1188 2795 2758 1192 2796 2763 1194 2797 2764 1190 2798 2761 1190 2799 2768 1193 2800 2765 1186 2801 2767 1197 2802 2771 1195 2803 2769 1196 2804 2770 1202 2805 2776 1197 2806 2774 1196 2807 2775 1203 2808 2777 1202 2809 2776 1199 2810 4635 1201 2811 2780 1198 2812 2778 1197 2813 2779 1201 2814 2784 1203 2815 2785 1200 2816 2783 1199 2817 2789 1202 2818 2786 1195 2819 2788 1206 2820 2792 1204 2821 2790 1205 2822 2791 1211 2823 2797 1206 2824 2795 1205 2825 2796 1212 2826 2798 1211 2827 2797 1208 2828 4636 1210 2829 2801 1207 2830 2799 1206 2831 2800 1210 2832 2805 1212 2833 2806 1208 2834 2803 1208 2835 2810 1211 2836 2807 1204 2837 2809 1215 2838 2813 1213 2839 2811 1214 2840 2812 1220 2841 2818 1215 2842 2816 1214 2843 2817 1221 2844 2819 1220 2845 2818 1217 2846 4637 1219 2847 2822 1216 2848 2820 1215 2849 2821 1219 2850 2826 1221 2851 2827 1217 2852 2824 1217 2853 2831 1220 2854 2828 1213 2855 2830 1224 2856 2834 1225 2857 2835 1223 2858 2833 1229 2859 2839 1224 2860 2837 1223 2861 2838 1230 2862 2840 1229 2863 2839 1226 2864 4638 1228 2865 2843 1225 2866 2841 1224 2867 2842 1228 2868 2847 1230 2869 2848 1226 2870 2845 1226 2871 2852 1229 2872 2849 1222 2873 2851 1233 2874 2855 1231 2875 2853 1232 2876 2854 1238 2877 2860 1233 2878 2858 1232 2879 2859 1239 2880 2861 1238 2881 2860 1235 2882 4639 1237 2883 2864 1234 2884 2862 1233 2885 2863 1237 2886 2868 1239 2887 2869 1235 2888 2866 1235 2889 2873 1238 2890 2870 1231 2891 2872 1242 2892 2876 1240 2893 2874 1241 2894 2875 1246 2895 2878 1247 2896 2881 1248 2897 2882 1242 2898 2879 1247 2899 2881 1246 2900 2878 1246 2901 2885 1243 2902 2883 1242 2903 2884 1246 2904 2889 1248 2905 2890 1244 2906 2887 1244 2907 2894 1247 2908 2891 1240 2909 2893 1251 2910 2897 1249 2911 2895 1250 2912 2896 1255 2913 2899 1256 2914 2902 1257 2915 2903 1251 2916 2900 1256 2917 2902 1255 2918 2899 1255 2919 2906 1252 2920 2904 1251 2921 2905 1255 2922 2910 1257 2923 2911 1253 2924 2908 1253 2925 2915 1256 2926 2912 1249 2927 2914 1260 2928 2918 1258 2929 2916 1259 2930 2917 1265 2931 2923 1260 2932 2921 1259 2933 2922 1266 2934 2924 1265 2935 2923 1262 2936 4642 1264 2937 2927 1261 2938 2925 1260 2939 2926 1264 2940 2931 1266 2941 2932 1262 2942 2929 1262 2943 2936 1265 2944 2933 1258 2945 2935 1269 2946 2939 1267 2947 2937 1268 2948 2938 1273 2949 2941 1274 2950 2944 1275 2951 2945 1269 2952 2942 1274 2953 2944 1273 2954 2941 1273 2955 2948 1270 2956 2946 1269 2957 2947 1273 2958 2952 1275 2959 2953 1271 2960 2950 1271 2961 2957 1274 2962 2954 1267 2963 2956 1278 2964 2960 1276 2965 2958 1277 2966 2959 1282 2967 2962 1283 2968 2965 1284 2969 2966 1278 2970 2963 1283 2971 2965 1282 2972 2962 1282 2973 2969 1279 2974 2967 1278 2975 2968 1282 2976 2973 1284 2977 2974 1280 2978 2971 1280 2979 2978 1283 2980 2975 1276 2981 2977 1287 2982 2981 1285 2983 2979 1286 2984 2980 1292 2985 2986 1287 2986 2984 1286 2987 2985 1293 2988 2987 1292 2989 2986 1289 2990 4645 1291 2991 2990 1288 2992 2988 1287 2993 2989 1291 2994 2994 1293 2995 2995 1289 2996 2992 1289 2997 2999 1292 2998 2996 1285 2999 2998 1296 3000 3002 1294 3001 3000 1295 3002 3001 1301 3003 3007 1296 3004 3005 1295 3005 3006 1302 3006 3008 1301 3007 3007 1298 3008 4646 1300 3009 3011 1297 3010 3009 1296 3011 3010 1300 3012 3015 1302 3013 3016 1298 3014 3013 1298 3015 3020 1301 3016 3017 1294 3017 3019 1305 3018 3023 1303 3019 3021 1304 3020 3022 1310 3021 3028 1305 3022 3026 1304 3023 3027 1311 3024 3029 1310 3025 3028 1307 3026 4647 1309 3027 3032 1306 3028 3030 1305 3029 3031 1309 3030 3036 1311 3031 3037 1307 3032 3034 1307 3033 3041 1310 3034 3038 1303 3035 3040 1314 3036 3044 1312 3037 3042 1313 3038 3043 1319 3039 3049 1314 3040 3047 1313 3041 3048 1320 3042 3050 1319 3043 3049 1316 3044 4648 1318 3045 3053 1315 3046 3051 1314 3047 3052 1318 3048 3057 1320 3049 3058 1316 3050 3055 1316 3051 3062 1319 3052 3059 1312 3053 3061 1323 3054 3065 1321 3055 3063 1322 3056 3064 1328 3057 3070 1323 3058 3068 1322 3059 3069 1329 3060 3071 1328 3061 3070 1325 3062 4649 1327 3063 3074 1324 3064 3072 1323 3065 3073 1327 3066 3078 1329 3067 3079 1325 3068 3076 1325 3069 3083 1328 3070 3080 1321 3071 3082 1332 3072 3086 1333 3073 3087 1331 3074 3085 1337 3075 3091 1332 3076 3089 1331 3077 3090 1338 3078 3092 1337 3079 3091 1334 3080 4650 1336 3081 3095 1333 3082 3093 1332 3083 3094 1336 3084 3099 1338 3085 3100 1334 3086 3097 1334 3087 3104 1337 3088 3101 1330 3089 3103 1341 3090 3107 1339 3091 3105 1340 3092 3106 1346 3093 3112 1341 3094 3110 1340 3095 3111 1347 3096 3113 1346 3097 3112 1343 3098 4651 1345 3099 3116 1342 3100 3114 1341 3101 3115 1345 3102 3120 1347 3103 3121 1343 3104 3118 1343 3105 3125 1346 3106 3122 1339 3107 3124 1350 3108 3128 1348 3109 3126 1349 3110 3127 1354 3111 3130 1355 3112 3133 1356 3113 3134 1350 3114 3131 1355 3115 3133 1354 3116 3130 1354 3117 3137 1351 3118 3135 1350 3119 3136 1354 3120 3141 1356 3121 3142 1352 3122 3139 1352 3123 3146 1349 3124 3144 1348 3125 3145 1359 3126 3149 1357 3127 3147 1358 3128 3148 1363 3129 3151 1364 3130 3154 1365 3131 3155 1359 3132 3152 1364 3133 3154 1363 3134 3151 1363 3135 3158 1360 3136 3156 1359 3137 3157 1363 3138 3162 1365 3139 3163 1361 3140 3160 1361 3141 3167 1364 3142 3164 1357 3143 3166 1368 3144 3170 1366 3145 3168 1367 3146 3169 1372 3147 3172 1373 3148 3175 1374 3149 3176 1368 3150 3173 1373 3151 3175 1372 3152 3172 1372 3153 3179 1369 3154 3177 1368 3155 3178 1372 3156 3183 1374 3157 3184 1370 3158 3181 1370 3159 3188 1373 3160 3185 1366 3161 3187 1377 3162 3191 1375 3163 3189 1376 3164 3190 1381 3165 3193 1382 3166 3196 1383 3167 3197 1377 3168 3194 1382 3169 3196 1381 3170 3193 1381 3171 3200 1378 3172 3198 1377 3173 3199 1381 3174 3204 1383 3175 3205 1379 3176 3202 1379 3177 3209 1382 3178 3206 1375 3179 3208 1386 3180 3212 1384 3181 3210 1385 3182 3211 1390 3183 3214 1391 3184 3217 1392 3185 3218 1386 3186 3215 1391 3187 3217 1390 3188 3214 1390 3189 3221 1387 3190 3219 1386 3191 3220 1390 3192 3225 1392 3193 3226 1388 3194 3223 1388 3195 3230 1391 3196 3227 1384 3197 3229 1395 3198 3233 1393 3199 3231 1394 3200 3232 1399 3201 3235 1400 3202 3238 1401 3203 3239 1395 3204 3236 1400 3205 3238 1399 3206 3235 1399 3207 3242 1396 3208 3240 1395 3209 3241 1399 3210 3246 1401 3211 3247 1397 3212 3244 1397 3213 3251 1400 3214 3248 1393 3215 3250 1404 3216 3254 1402 3217 3252 1403 3218 3253 1409 3219 3259 1404 3220 3257 1403 3221 3258 1410 3222 3260 1409 3223 3259 1406 3224 4658 1408 3225 3263 1405 3226 3261 1404 3227 3262 1408 3228 3267 1410 3229 3268 1406 3230 3265 1406 3231 3272 1409 3232 3269 1402 3233 3271 1413 3234 3275 1411 3235 3273 1412 3236 3274 1418 3237 3280 1413 3238 3278 1412 3239 3279 1419 3240 3281 1418 3241 3280 1415 3242 4659 1417 3243 3284 1414 3244 3282 1413 3245 3283 1417 3246 3288 1419 3247 3289 1415 3248 3286 1415 3249 3293 1418 3250 3290 1411 3251 3292 1422 3252 3296 1420 3253 3294 1421 3254 3295 1427 3255 3301 1422 3256 3299 1421 3257 3300 1428 3258 3302 1427 3259 3301 1424 3260 4660 1426 3261 3305 1423 3262 3303 1422 3263 3304 1426 3264 3309 1428 3265 3310 1424 3266 3307 1424 3267 3314 1427 3268 3311 1420 3269 3313 1431 3270 3317 1429 3271 3315 1430 3272 3316 1436 3273 3322 1435 3274 3319 1430 3275 3321 1437 3276 3323 1436 3277 3322 1433 3278 4661 1435 3279 3326 1432 3280 3324 1431 3281 3325 1435 3282 3330 1437 3283 3331 1433 3284 3328 1433 3285 3335 1436 3286 3332 1429 3287 3334 1440 3288 3338 1438 3289 3336 1439 3290 3337 1445 3291 3343 1440 3292 3341 1439 3293 3342 1446 3294 3344 1445 3295 3343 1442 3296 4662 1444 3297 3347 1441 3298 3345 1440 3299 3346 1444 3300 3351 1446 3301 3352 1442 3302 3349 1442 3303 3356 1445 3304 3353 1438 3305 3355 1449 3306 3359 1447 3307 3357 1448 3308 3358 1453 3309 3361 1454 3310 3364 1455 3311 3365 1449 3312 3362 1454 3313 3364 1453 3314 3361 1453 3315 3368 1450 3316 3366 1449 3317 3367 1453 3318 3372 1455 3319 3373 1451 3320 3370 1451 3321 3377 1454 3322 3374 1447 3323 3376 1458 3324 3380 1456 3325 3378 1457 3326 3379 1462 3327 3382 1463 3328 3385 1464 3329 3386 1458 3330 3383 1463 3331 3385 1462 3332 3382 1462 3333 3389 1459 3334 3387 1458 3335 3388 1462 3336 3393 1464 3337 3394 1460 3338 3391 1460 3339 3398 1457 3340 3396 1456 3341 3397 1467 3342 3401 1465 3343 3399 1466 3344 3400 1471 3345 3403 1472 3346 3406 1473 3347 3407 1467 3348 3404 1472 3349 3406 1471 3350 3403 1471 3351 3410 1468 3352 3408 1467 3353 3409 1471 3354 3414 1473 3355 3415 1469 3356 3412 1469 3357 3419 1472 3358 3416 1465 3359 3418 806 3360 1840 803 3361 4591 807 3362 1841 797 3363 1819 794 3364 4590 798 3365 1820 1446 3366 3344 1444 3367 3340 1445 3368 3343 1437 3369 3323 1435 3370 3319 1436 3371 3322 1463 3372 3385 1460 3373 4664 1464 3374 3386 1382 3375 3196 1379 3376 4655 1383 3377 3197 1373 3378 3175 1370 3379 4654 1374 3380 3176 1419 3381 3281 1417 3382 3277 1418 3383 3280 1472 3384 3406 1469 3385 4665 1473 3386 3407 1428 3387 3302 1426 3388 3298 1427 3389 3301 1435 3390 3319 1431 3391 3320 1430 3392 3321 1410 3393 3260 1408 3394 3256 1409 3395 3259 1274 3396 2944 1271 3397 4643 1275 3398 2945 1311 3399 3029 1309 3400 3025 1310 3401 3028 1364 3402 3154 1361 3403 4653 1365 3404 3155 1347 3405 3113 1345 3406 3109 1346 3407 3112 1355 3408 3133 1352 3409 4652 1356 3410 3134 1283 3411 2965 1280 3412 4644 1284 3413 2966 1320 3414 3050 1318 3415 3046 1319 3416 3049 1329 3417 3071 1327 3418 3067 1328 3419 3070 1293 3420 2987 1291 3421 2983 1292 3422 2986 1302 3423 3008 1300 3424 3004 1301 3425 3007 1338 3426 3092 1336 3427 3088 1337 3428 3091 1266 3429 2924 1264 3430 2920 1265 3431 2923 950 3432 2176 947 3433 4607 951 3434 2177 941 3435 2155 938 3436 4606 942 3437 2156 815 3438 1861 812 3439 4592 816 3440 1862 779 3441 1777 776 3442 4588 780 3443 1778 770 3444 1756 767 3445 4587 771 3446 1757 761 3447 1731 758 3448 4586 762 3449 1732 734 3450 1668 731 3451 4583 735 3452 1669 878 3453 2008 875 3454 4599 879 3455 2009 752 3456 1710 749 3457 4585 753 3458 1711 932 3459 2134 929 3460 4605 933 3461 2135 1352 3462 3146 1355 3463 3143 1349 3464 3144 1400 3465 3238 1397 3466 4657 1401 3467 3239 1454 3468 3364 1451 3469 4663 1455 3470 3365 1460 3471 3398 1463 3472 3395 1457 3473 3396 1212 3474 2798 1210 3475 2794 1211 3476 2797 1203 3477 2777 1201 3478 2773 1202 3479 2776 1203 3480 2785 1199 3481 2782 1200 3482 2783 1225 3483 2835 1222 3484 2832 1223 3485 2833 1221 3486 2819 1219 3487 2815 1220 3488 2818 1157 3489 2667 1154 3490 4630 1158 3491 2668 1239 3492 2861 1237 3493 2857 1238 3494 2860 1256 3495 2902 1253 3496 4641 1257 3497 2903 1230 3498 2840 1228 3499 2836 1229 3500 2839 1247 3501 2881 1244 3502 4640 1248 3503 2882 1194 3504 2756 1192 3505 2752 1193 3506 2755 995 3507 2281 992 3508 4612 996 3509 2282 1001 3510 2315 1004 3511 2312 998 3512 2313 1004 3513 2302 1001 3514 4613 1005 3515 2303 1022 3516 2344 1019 3517 4615 1023 3518 2345 1028 3519 2378 1031 3520 2375 1025 3521 2376 1077 3522 2475 1075 3523 2471 1076 3524 2474 1094 3525 2516 1091 3526 4623 1095 3527 2517 1130 3528 2604 1127 3529 4627 1131 3530 2605 1127 3531 2617 1130 3532 2614 1124 3533 2615 1013 3534 2323 1010 3535 4614 1014 3536 2324 1010 3537 2336 1013 3538 2333 1007 3539 2334 1031 3540 2365 1028 3541 4616 1032 3542 2366 1037 3543 2399 1040 3544 2396 1034 3545 2397 1103 3546 2537 1100 3547 4624 1104 3548 2538 1100 3549 2543 1101 3550 2544 1102 3551 2545 1111 3552 2555 1112 3553 2558 1109 3554 4625 1109 3555 2564 1110 3556 2565 1111 3557 2566 1139 3558 2625 1136 3559 4628 1140 3560 2626 1139 3561 2635 1133 3562 2636 1132 3563 2637 608 3564 1366 605 3565 4569 609 3566 1367 605 3567 1372 606 3568 1373 607 3569 1374 644 3570 1450 641 3571 4573 645 3572 1451 641 3573 1456 642 3574 1457 643 3575 1458 653 3576 1471 650 3577 4574 654 3578 1472 650 3579 1477 651 3580 1478 652 3581 1479 990 3582 2276 991 3583 2277 988 3584 2274 990 3585 2279 989 3586 2280 995 3587 2281 994 3588 2285 993 3589 2286 991 3590 2283 992 3591 2287 993 3592 2288 994 3593 2289 995 3594 2291 989 3595 2292 988 3596 2293 999 3597 2297 1000 3598 2298 997 3599 2295 999 3600 2300 998 3601 2301 1004 3602 2302 1003 3603 2306 1002 3604 2307 1000 3605 2304 1001 3606 2308 1002 3607 2309 1003 3608 2310 1008 3609 2318 1009 3610 2319 1006 3611 2316 1008 3612 2321 1007 3613 2322 1013 3614 2323 1012 3615 2327 1011 3616 2328 1009 3617 2325 1010 3618 2329 1011 3619 2330 1012 3620 2331 1017 3621 2339 1018 3622 2340 1015 3623 2337 1017 3624 2342 1016 3625 2343 1022 3626 2344 1021 3627 2348 1020 3628 2349 1018 3629 2346 1019 3630 2350 1020 3631 2351 1021 3632 2352 1022 3633 2354 1016 3634 2355 1015 3635 2356 1026 3636 2360 1027 3637 2361 1024 3638 2358 1026 3639 2363 1025 3640 2364 1031 3641 2365 1030 3642 2369 1029 3643 2370 1027 3644 2367 1028 3645 2371 1029 3646 2372 1030 3647 2373 1035 3648 2381 1036 3649 2382 1033 3650 2379 1040 3651 2386 1037 3652 4617 1041 3653 2387 1035 3654 2384 1034 3655 2385 1040 3656 2386 1039 3657 2390 1038 3658 2391 1036 3659 2388 1037 3660 2392 1038 3661 2393 1039 3662 2394 1044 3663 2402 1045 3664 2403 1042 3665 2400 1045 3666 2406 1047 3667 2407 1046 3668 2404 1049 3669 2411 1046 3670 4618 1050 3671 2412 1044 3672 2409 1043 3673 2410 1049 3674 2411 1048 3675 2415 1047 3676 2416 1045 3677 2413 1046 3678 2417 1047 3679 2418 1048 3680 2419 1049 3681 2421 1043 3682 2422 1042 3683 2423 1053 3684 2427 1054 3685 2428 1051 3686 2425 1058 3687 2432 1057 3688 2429 1053 3689 2430 1058 3690 2432 1055 3691 4619 1059 3692 2433 1057 3693 2436 1056 3694 2437 1054 3695 2434 1055 3696 2438 1056 3697 2439 1057 3698 2440 1058 3699 2442 1052 3700 2443 1051 3701 2444 1062 3702 2448 1063 3703 2449 1060 3704 2446 1067 3705 2453 1066 3706 2450 1062 3707 2451 1067 3708 2453 1064 3709 4620 1068 3710 2454 1066 3711 2457 1065 3712 2458 1063 3713 2455 1064 3714 2459 1065 3715 2460 1066 3716 2461 1067 3717 2463 1061 3718 2464 1060 3719 2465 1071 3720 2469 1072 3721 2470 1069 3722 2467 1076 3723 2474 1075 3724 2471 1071 3725 2472 1075 3726 2478 1074 3727 2479 1072 3728 2476 1073 3729 2480 1074 3730 2481 1075 3731 2482 1076 3732 2484 1070 3733 2485 1069 3734 2486 1080 3735 2490 1081 3736 2491 1078 3737 2488 1085 3738 2495 1084 3739 2492 1080 3740 2493 1085 3741 2495 1082 3742 4622 1086 3743 2496 1084 3744 2499 1083 3745 2500 1081 3746 2497 1082 3747 2501 1083 3748 2502 1084 3749 2503 1085 3750 2505 1079 3751 2506 1078 3752 2507 1089 3753 2511 1090 3754 2512 1087 3755 2509 1094 3756 2516 1093 3757 2513 1089 3758 2514 1093 3759 2520 1092 3760 2521 1090 3761 2518 1091 3762 2522 1092 3763 2523 1093 3764 2524 1094 3765 2526 1088 3766 2527 1087 3767 2528 1098 3768 2532 1099 3769 2533 1096 3770 2530 1103 3771 2537 1102 3772 2534 1098 3773 2535 1102 3774 2541 1101 3775 2542 1099 3776 2539 1103 3777 2547 1097 3778 2548 1096 3779 2549 1107 3780 2553 1108 3781 2554 1105 3782 2551 1112 3783 2558 1111 3784 2555 1107 3785 2556 1111 3786 2562 1110 3787 2563 1108 3788 2560 1112 3789 2568 1106 3790 2569 1105 3791 2570 1116 3792 2574 1117 3793 2575 1114 3794 2572 1117 3795 2578 1119 3796 2579 1118 3797 2576 1121 3798 2583 1120 3799 2580 1116 3800 2581 1121 3801 2583 1118 3802 4626 1122 3803 2584 1120 3804 2587 1119 3805 2588 1117 3806 2585 1118 3807 2589 1119 3808 2590 1120 3809 2591 1121 3810 2593 1115 3811 2594 1114 3812 2595 1125 3813 2599 1126 3814 2600 1123 3815 2597 1125 3816 2602 1124 3817 2603 1130 3818 2604 1129 3819 2608 1128 3820 2609 1126 3821 2606 1127 3822 2610 1128 3823 2611 1129 3824 2612 1134 3825 2620 1135 3826 2621 1132 3827 2618 1134 3828 2623 1133 3829 2624 1139 3830 2625 1138 3831 2629 1137 3832 2630 1135 3833 2627 1136 3834 2631 1137 3835 2632 1138 3836 2633 1143 3837 2641 1144 3838 2642 1141 3839 2639 1148 3840 2646 1145 3841 4629 1149 3842 2647 1143 3843 2644 1142 3844 2645 1148 3845 2646 1147 3846 2650 1146 3847 2651 1144 3848 2648 1145 3849 2652 1146 3850 2653 1147 3851 2654 1148 3852 2656 1142 3853 2657 1141 3854 2658 585 3855 1319 586 3856 1320 583 3857 1317 590 3858 1324 587 3859 4567 591 3860 1325 585 3861 1322 584 3862 1323 590 3863 1324 589 3864 1328 588 3865 1329 586 3866 1326 587 3867 1330 588 3868 1331 589 3869 1332 590 3870 1334 584 3871 1335 583 3872 1336 594 3873 1340 595 3874 1341 592 3875 1338 599 3876 1345 596 3877 4568 600 3878 1346 594 3879 1343 593 3880 1344 599 3881 1345 598 3882 1349 597 3883 1350 595 3884 1347 596 3885 1351 597 3886 1352 598 3887 1353 599 3888 1355 593 3889 1356 592 3890 1357 603 3891 1361 604 3892 1362 601 3893 1359 603 3894 1364 602 3895 1365 608 3896 1366 607 3897 1370 606 3898 1371 604 3899 1368 608 3900 1376 602 3901 1377 601 3902 1378 612 3903 1382 613 3904 1383 610 3905 1380 617 3906 1387 614 3907 4570 618 3908 1388 612 3909 1385 611 3910 1386 617 3911 1387 616 3912 1391 615 3913 1392 613 3914 1389 614 3915 1393 615 3916 1394 616 3917 1395 617 3918 1397 611 3919 1398 610 3920 1399 621 3921 1403 622 3922 1404 619 3923 1401 626 3924 1408 623 3925 4571 627 3926 1409 621 3927 1406 620 3928 1407 626 3929 1408 625 3930 1412 624 3931 1413 622 3932 1410 623 3933 1414 624 3934 1415 625 3935 1416 626 3936 1418 620 3937 1419 619 3938 1420 630 3939 1424 631 3940 1425 628 3941 1422 635 3942 1429 632 3943 4572 636 3944 1430 630 3945 1427 629 3946 1428 635 3947 1429 634 3948 1433 633 3949 1434 631 3950 1431 632 3951 1435 633 3952 1436 634 3953 1437 635 3954 1439 629 3955 1440 628 3956 1441 639 3957 1445 640 3958 1446 637 3959 1443 639 3960 1448 638 3961 1449 644 3962 1450 643 3963 1454 642 3964 1455 640 3965 1452 644 3966 1460 638 3967 1461 637 3968 1462 648 3969 1466 649 3970 1467 646 3971 1464 648 3972 1469 647 3973 1470 653 3974 1471 652 3975 1475 651 3976 1476 649 3977 1473 653 3978 1481 647 3979 1482 646 3980 1483 500 3981 1114 497 3982 4557 501 3983 1115 500 3984 1124 494 3985 1125 493 3986 1126 509 3987 1135 506 3988 4558 510 3989 1136 509 3990 1145 503 3991 1146 502 3992 1147 518 3993 1156 515 3994 4559 519 3995 1157 518 3996 1166 512 3997 1167 511 3998 1168 522 3999 1172 523 4000 1173 520 4001 1170 527 4002 1177 524 4003 4560 528 4004 1178 522 4005 1175 521 4006 1176 527 4007 1177 526 4008 1181 525 4009 1182 523 4010 1179 524 4011 1183 525 4012 1184 526 4013 1185 527 4014 1187 521 4015 1188 520 4016 1189 531 4017 1193 532 4018 1194 529 4019 1191 536 4020 1198 533 4021 4561 537 4022 1199 531 4023 1196 530 4024 1197 536 4025 1198 535 4026 1202 534 4027 1203 532 4028 1200 533 4029 1204 534 4030 1205 535 4031 1206 536 4032 1208 530 4033 1209 529 4034 1210 540 4035 1214 541 4036 1215 538 4037 1212 545 4038 1219 542 4039 4562 546 4040 1220 540 4041 1217 539 4042 1218 545 4043 1219 544 4044 1223 543 4045 1224 541 4046 1221 542 4047 1225 543 4048 1226 544 4049 1227 545 4050 1229 539 4051 1230 538 4052 1231 549 4053 1235 550 4054 1236 547 4055 1233 554 4056 1240 551 4057 4563 555 4058 1241 549 4059 1238 548 4060 1239 554 4061 1240 553 4062 1244 552 4063 1245 550 4064 1242 551 4065 1246 552 4066 1247 553 4067 1248 554 4068 1250 548 4069 1251 547 4070 1252 558 4071 1256 559 4072 1257 556 4073 1254 563 4074 1261 560 4075 4564 564 4076 1262 558 4077 1259 557 4078 1260 563 4079 1261 562 4080 1265 561 4081 1266 559 4082 1263 560 4083 1267 561 4084 1268 562 4085 1269 563 4086 1271 557 4087 1272 556 4088 1273 567 4089 1277 568 4090 1278 565 4091 1275 572 4092 1282 569 4093 4565 573 4094 1283 567 4095 1280 566 4096 1281 572 4097 1282 571 4098 1286 570 4099 1287 568 4100 1284 569 4101 1288 570 4102 1289 571 4103 1290 572 4104 1292 566 4105 1293 565 4106 1294 576 4107 1298 577 4108 1299 574 4109 1296 579 4110 1308 577 4111 1305 576 4112 1306 578 4113 1316 581 4114 1313 575 4115 1314 306 4116 668 307 4117 669 304 4118 666 311 4119 673 308 4120 4536 312 4121 674 306 4122 671 305 4123 672 311 4124 673 310 4125 677 309 4126 678 307 4127 675 308 4128 679 309 4129 680 310 4130 681 311 4131 683 305 4132 684 304 4133 685 315 4134 689 316 4135 690 313 4136 687 320 4137 694 317 4138 4537 321 4139 695 315 4140 692 314 4141 693 320 4142 694 319 4143 698 318 4144 699 316 4145 696 317 4146 700 318 4147 701 319 4148 702 320 4149 704 314 4150 705 313 4151 706 324 4152 710 325 4153 711 322 4154 708 329 4155 715 326 4156 4538 330 4157 716 324 4158 713 323 4159 714 329 4160 715 328 4161 719 327 4162 720 325 4163 717 326 4164 721 327 4165 722 328 4166 723 329 4167 725 323 4168 726 322 4169 727 333 4170 731 334 4171 732 331 4172 729 338 4173 736 335 4174 4539 339 4175 737 333 4176 734 332 4177 735 338 4178 736 337 4179 740 336 4180 741 334 4181 738 335 4182 742 336 4183 743 337 4184 744 338 4185 746 332 4186 747 331 4187 748 342 4188 752 343 4189 753 340 4190 750 347 4191 757 344 4192 4540 348 4193 758 342 4194 755 341 4195 756 347 4196 757 346 4197 761 345 4198 762 343 4199 759 344 4200 763 345 4201 764 346 4202 765 347 4203 767 341 4204 768 340 4205 769 351 4206 773 352 4207 774 349 4208 771 356 4209 778 353 4210 4541 357 4211 779 351 4212 776 350 4213 777 356 4214 778 355 4215 782 354 4216 783 352 4217 780 353 4218 784 354 4219 785 355 4220 786 356 4221 788 350 4222 789 349 4223 790 360 4224 794 361 4225 795 358 4226 792 365 4227 799 362 4228 4542 366 4229 800 360 4230 797 359 4231 798 365 4232 799 364 4233 803 363 4234 804 361 4235 801 362 4236 805 363 4237 806 364 4238 807 365 4239 809 359 4240 810 358 4241 811 369 4242 815 370 4243 816 367 4244 813 374 4245 820 371 4246 4543 375 4247 821 369 4248 818 368 4249 819 374 4250 820 373 4251 824 372 4252 825 370 4253 822 371 4254 826 372 4255 827 373 4256 828 374 4257 830 368 4258 831 367 4259 832 378 4260 836 379 4261 837 376 4262 834 383 4263 841 380 4264 4544 384 4265 842 378 4266 839 377 4267 840 383 4268 841 382 4269 845 381 4270 846 379 4271 843 380 4272 847 381 4273 848 382 4274 849 383 4275 851 377 4276 852 376 4277 853 387 4278 857 388 4279 858 385 4280 855 392 4281 862 389 4282 4545 393 4283 863 387 4284 860 386 4285 861 392 4286 862 391 4287 866 390 4288 867 388 4289 864 389 4290 868 390 4291 869 391 4292 870 392 4293 872 386 4294 873 385 4295 874 396 4296 878 397 4297 879 394 4298 876 401 4299 883 398 4300 4546 402 4301 884 396 4302 881 395 4303 882 401 4304 883 400 4305 887 399 4306 888 397 4307 885 398 4308 889 399 4309 890 400 4310 891 401 4311 893 395 4312 894 394 4313 895 405 4314 899 406 4315 900 403 4316 897 410 4317 904 407 4318 4547 411 4319 905 405 4320 902 404 4321 903 410 4322 904 409 4323 908 408 4324 909 406 4325 906 407 4326 910 408 4327 911 409 4328 912 410 4329 914 404 4330 915 403 4331 916 414 4332 920 415 4333 921 412 4334 918 419 4335 925 416 4336 4548 420 4337 926 414 4338 923 413 4339 924 419 4340 925 418 4341 929 417 4342 930 415 4343 927 416 4344 931 417 4345 932 418 4346 933 419 4347 935 413 4348 936 412 4349 937 423 4350 941 424 4351 942 421 4352 939 428 4353 946 425 4354 4549 429 4355 947 423 4356 944 422 4357 945 428 4358 946 427 4359 950 426 4360 951 424 4361 948 425 4362 952 426 4363 953 427 4364 954 428 4365 956 422 4366 957 421 4367 958 432 4368 962 433 4369 963 430 4370 960 437 4371 967 434 4372 4550 438 4373 968 432 4374 965 431 4375 966 437 4376 967 436 4377 971 435 4378 972 433 4379 969 434 4380 973 435 4381 974 436 4382 975 437 4383 977 431 4384 978 430 4385 979 441 4386 983 442 4387 984 439 4388 981 446 4389 988 443 4390 4551 447 4391 989 441 4392 986 440 4393 987 446 4394 988 445 4395 992 444 4396 993 442 4397 990 443 4398 994 444 4399 995 445 4400 996 446 4401 998 440 4402 999 439 4403 1000 450 4404 1004 451 4405 1005 448 4406 1002 455 4407 1009 452 4408 4552 456 4409 1010 450 4410 1007 449 4411 1008 455 4412 1009 454 4413 1013 453 4414 1014 451 4415 1011 452 4416 1015 453 4417 1016 454 4418 1017 455 4419 1019 449 4420 1020 448 4421 1021 459 4422 1025 460 4423 1026 457 4424 1023 464 4425 1030 461 4426 4553 465 4427 1031 459 4428 1028 458 4429 1029 464 4430 1030 463 4431 1034 462 4432 1035 460 4433 1032 461 4434 1036 462 4435 1037 463 4436 1038 464 4437 1040 458 4438 1041 457 4439 1042 468 4440 1046 469 4441 1047 466 4442 1044 473 4443 1051 470 4444 4554 474 4445 1052 468 4446 1049 467 4447 1050 473 4448 1051 472 4449 1055 471 4450 1056 469 4451 1053 470 4452 1057 471 4453 1058 472 4454 1059 473 4455 1061 467 4456 1062 466 4457 1063 477 4458 1067 478 4459 1068 475 4460 1065 482 4461 1072 479 4462 4555 483 4463 1073 477 4464 1070 476 4465 1071 482 4466 1072 481 4467 1076 480 4468 1077 478 4469 1074 479 4470 1078 480 4471 1079 481 4472 1080 482 4473 1082 476 4474 1083 475 4475 1084 486 4476 1088 487 4477 1089 484 4478 1086 491 4479 1093 488 4480 4556 492 4481 1094 486 4482 1091 485 4483 1092 491 4484 1093 490 4485 1097 489 4486 1098 487 4487 1095 488 4488 1099 489 4489 1100 490 4490 1101 491 4491 1103 485 4492 1104 484 4493 1105 657 4494 1487 658 4495 1488 655 4496 1485 662 4497 1492 659 4498 4575 663 4499 1493 657 4500 1490 656 4501 1491 662 4502 1492 661 4503 1496 660 4504 1497 658 4505 1494 659 4506 1498 660 4507 1499 661 4508 1500 662 4509 1502 656 4510 1503 655 4511 1504 666 4512 1508 667 4513 1509 664 4514 1506 667 4515 1512 669 4516 1513 668 4517 1510 671 4518 1517 668 4519 4576 672 4520 1518 666 4521 1515 665 4522 1516 671 4523 1517 670 4524 1521 669 4525 1522 667 4526 1519 668 4527 1523 669 4528 1524 670 4529 1525 671 4530 1527 665 4531 1528 664 4532 1529 675 4533 1533 676 4534 1534 673 4535 1531 680 4536 1538 677 4537 4577 681 4538 1539 675 4539 1536 674 4540 1537 680 4541 1538 679 4542 1542 678 4543 1543 676 4544 1540 677 4545 1544 678 4546 1545 679 4547 1546 680 4548 1548 674 4549 1549 673 4550 1550 684 4551 1554 685 4552 1555 682 4553 1552 689 4554 1559 686 4555 4578 690 4556 1560 684 4557 1557 683 4558 1558 689 4559 1559 688 4560 1563 687 4561 1564 685 4562 1561 686 4563 1565 687 4564 1566 688 4565 1567 689 4566 1569 683 4567 1570 682 4568 1571 693 4569 1575 694 4570 1576 691 4571 1573 698 4572 1580 695 4573 4579 699 4574 1581 693 4575 1578 692 4576 1579 698 4577 1580 697 4578 1584 696 4579 1585 694 4580 1582 695 4581 1586 696 4582 1587 697 4583 1588 698 4584 1590 692 4585 1591 691 4586 1592 702 4587 1596 703 4588 1597 700 4589 1594 707 4590 1601 704 4591 4580 708 4592 1602 702 4593 1599 701 4594 1600 707 4595 1601 706 4596 1605 705 4597 1606 703 4598 1603 704 4599 1607 705 4600 1608 706 4601 1609 707 4602 1611 701 4603 1612 700 4604 1613 711 4605 1617 712 4606 1618 709 4607 1615 712 4608 1621 714 4609 1622 713 4610 1619 716 4611 1626 713 4612 4581 717 4613 1627 711 4614 1624 710 4615 1625 716 4616 1626 715 4617 1630 714 4618 1631 712 4619 1628 713 4620 1632 714 4621 1633 715 4622 1634 716 4623 1636 710 4624 1637 709 4625 1638 720 4626 1642 721 4627 1643 718 4628 1640 725 4629 1647 722 4630 4582 726 4631 1648 720 4632 1645 719 4633 1646 725 4634 1647 724 4635 1651 723 4636 1652 721 4637 1649 722 4638 1653 723 4639 1654 724 4640 1655 725 4641 1657 719 4642 1658 718 4643 1659 729 4644 1663 730 4645 1664 727 4646 1661 729 4647 1666 728 4648 1667 734 4649 1668 733 4650 1672 732 4651 1673 730 4652 1670 731 4653 1674 732 4654 1675 733 4655 1676 734 4656 1678 728 4657 1679 727 4658 1680 738 4659 1684 739 4660 1685 736 4661 1682 743 4662 1689 740 4663 4584 744 4664 1690 738 4665 1687 737 4666 1688 743 4667 1689 742 4668 1693 741 4669 1694 739 4670 1691 740 4671 1695 741 4672 1696 742 4673 1697 743 4674 1699 737 4675 1700 736 4676 1701 747 4677 1705 748 4678 1706 745 4679 1703 747 4680 1708 746 4681 1709 752 4682 1710 751 4683 1714 750 4684 1715 748 4685 1712 749 4686 1716 750 4687 1717 751 4688 1718 752 4689 1720 746 4690 1721 745 4691 1722 756 4692 1726 757 4693 1727 754 4694 1724 756 4695 1729 755 4696 1730 761 4697 1731 760 4698 1735 759 4699 1736 757 4700 1733 758 4701 1737 759 4702 1738 760 4703 1739 761 4704 1741 755 4705 1742 754 4706 1743 765 4707 1747 766 4708 1748 763 4709 1745 766 4710 1751 768 4711 1752 767 4712 1749 765 4713 1754 764 4714 1755 770 4715 1756 769 4716 1760 768 4717 1761 766 4718 1758 767 4719 1762 768 4720 1763 769 4721 1764 770 4722 1766 764 4723 1767 763 4724 1768 774 4725 1772 775 4726 1773 772 4727 1770 774 4728 1775 773 4729 1776 779 4730 1777 778 4731 1781 777 4732 1782 775 4733 1779 776 4734 1783 777 4735 1784 778 4736 1785 779 4737 1787 773 4738 1788 772 4739 1789 783 4740 1793 784 4741 1794 781 4742 1791 788 4743 1798 785 4744 4589 789 4745 1799 783 4746 1796 782 4747 1797 788 4748 1798 787 4749 1802 786 4750 1803 784 4751 1800 785 4752 1804 786 4753 1805 787 4754 1806 788 4755 1808 782 4756 1809 781 4757 1810 792 4758 1814 793 4759 1815 790 4760 1812 792 4761 1817 791 4762 1818 797 4763 1819 796 4764 1823 795 4765 1824 793 4766 1821 794 4767 1825 795 4768 1826 796 4769 1827 797 4770 1829 791 4771 1830 790 4772 1831 801 4773 1835 802 4774 1836 799 4775 1833 801 4776 1838 800 4777 1839 806 4778 1840 805 4779 1844 804 4780 1845 802 4781 1842 803 4782 1846 804 4783 1847 805 4784 1848 806 4785 1850 800 4786 1851 799 4787 1852 810 4788 1856 811 4789 1857 808 4790 1854 810 4791 1859 809 4792 1860 815 4793 1861 814 4794 1865 813 4795 1866 811 4796 1863 812 4797 1867 813 4798 1868 814 4799 1869 815 4800 1871 809 4801 1872 808 4802 1873 819 4803 1877 820 4804 1878 817 4805 1875 824 4806 1882 821 4807 4593 825 4808 1883 819 4809 1880 818 4810 1881 824 4811 1882 823 4812 1886 822 4813 1887 820 4814 1884 821 4815 1888 822 4816 1889 823 4817 1890 824 4818 1892 818 4819 1893 817 4820 1894 828 4821 1898 829 4822 1899 826 4823 1896 833 4824 1903 830 4825 4594 834 4826 1904 828 4827 1901 827 4828 1902 833 4829 1903 832 4830 1907 831 4831 1908 829 4832 1905 830 4833 1909 831 4834 1910 832 4835 1911 833 4836 1913 827 4837 1914 826 4838 1915 837 4839 1919 838 4840 1920 835 4841 1917 842 4842 1924 839 4843 4595 843 4844 1925 837 4845 1922 836 4846 1923 842 4847 1924 841 4848 1928 840 4849 1929 838 4850 1926 839 4851 1930 840 4852 1931 841 4853 1932 842 4854 1934 836 4855 1935 835 4856 1936 846 4857 1940 847 4858 1941 844 4859 1938 851 4860 1945 848 4861 4596 852 4862 1946 846 4863 1943 845 4864 1944 851 4865 1945 850 4866 1949 849 4867 1950 847 4868 1947 848 4869 1951 849 4870 1952 850 4871 1953 851 4872 1955 845 4873 1956 844 4874 1957 855 4875 1961 856 4876 1962 853 4877 1959 860 4878 1966 857 4879 4597 861 4880 1967 855 4881 1964 854 4882 1965 860 4883 1966 859 4884 1970 858 4885 1971 856 4886 1968 857 4887 1972 858 4888 1973 859 4889 1974 860 4890 1976 854 4891 1977 853 4892 1978 864 4893 1982 865 4894 1983 862 4895 1980 869 4896 1987 866 4897 4598 870 4898 1988 864 4899 1985 863 4900 1986 869 4901 1987 868 4902 1991 867 4903 1992 865 4904 1989 866 4905 1993 867 4906 1994 868 4907 1995 869 4908 1997 863 4909 1998 862 4910 1999 873 4911 2003 874 4912 2004 871 4913 2001 873 4914 2006 872 4915 2007 878 4916 2008 877 4917 2012 876 4918 2013 874 4919 2010 875 4920 2014 876 4921 2015 877 4922 2016 878 4923 2018 872 4924 2019 871 4925 2020 882 4926 2024 883 4927 2025 880 4928 2022 887 4929 2029 884 4930 4600 888 4931 2030 882 4932 2027 881 4933 2028 887 4934 2029 886 4935 2033 885 4936 2034 883 4937 2031 884 4938 2035 885 4939 2036 886 4940 2037 887 4941 2039 881 4942 2040 880 4943 2041 891 4944 2045 892 4945 2046 889 4946 2043 896 4947 2050 893 4948 4601 897 4949 2051 891 4950 2048 890 4951 2049 896 4952 2050 895 4953 2054 894 4954 2055 892 4955 2052 893 4956 2056 894 4957 2057 895 4958 2058 896 4959 2060 890 4960 2061 889 4961 2062 900 4962 2066 901 4963 2067 898 4964 2064 905 4965 2071 902 4966 4602 906 4967 2072 900 4968 2069 899 4969 2070 905 4970 2071 904 4971 2075 903 4972 2076 901 4973 2073 902 4974 2077 903 4975 2078 904 4976 2079 905 4977 2081 899 4978 2082 898 4979 2083 909 4980 2087 910 4981 2088 907 4982 2085 914 4983 2092 911 4984 4603 915 4985 2093 909 4986 2090 908 4987 2091 914 4988 2092 913 4989 2096 912 4990 2097 910 4991 2094 911 4992 2098 912 4993 2099 913 4994 2100 914 4995 2102 908 4996 2103 907 4997 2104 918 4998 2108 919 4999 2109 916 5000 2106 923 5001 2113 920 5002 4604 924 5003 2114 918 5004 2111 917 5005 2112 923 5006 2113 922 5007 2117 921 5008 2118 919 5009 2115 920 5010 2119 921 5011 2120 922 5012 2121 923 5013 2123 917 5014 2124 916 5015 2125 927 5016 2129 928 5017 2130 925 5018 2127 927 5019 2132 926 5020 2133 932 5021 2134 931 5022 2138 930 5023 2139 928 5024 2136 929 5025 2140 930 5026 2141 931 5027 2142 932 5028 2144 926 5029 2145 925 5030 2146 936 5031 2150 937 5032 2151 934 5033 2148 936 5034 2153 935 5035 2154 941 5036 2155 940 5037 2159 939 5038 2160 937 5039 2157 938 5040 2161 939 5041 2162 940 5042 2163 941 5043 2165 935 5044 2166 934 5045 2167 945 5046 2171 946 5047 2172 943 5048 2169 945 5049 2174 944 5050 2175 950 5051 2176 949 5052 2180 948 5053 2181 946 5054 2178 947 5055 2182 948 5056 2183 949 5057 2184 950 5058 2186 944 5059 2187 943 5060 2188 954 5061 2192 955 5062 2193 952 5063 2190 959 5064 2197 956 5065 4608 960 5066 2198 954 5067 2195 953 5068 2196 959 5069 2197 958 5070 2201 957 5071 2202 955 5072 2199 956 5073 2203 957 5074 2204 958 5075 2205 959 5076 2207 953 5077 2208 952 5078 2209 963 5079 2213 964 5080 2214 961 5081 2211 968 5082 2218 965 5083 4609 969 5084 2219 963 5085 2216 962 5086 2217 968 5087 2218 967 5088 2222 966 5089 2223 964 5090 2220 965 5091 2224 966 5092 2225 967 5093 2226 968 5094 2228 962 5095 2229 961 5096 2230 972 5097 2234 973 5098 2235 970 5099 2232 977 5100 2239 974 5101 4610 978 5102 2240 972 5103 2237 971 5104 2238 977 5105 2239 976 5106 2243 975 5107 2244 973 5108 2241 974 5109 2245 975 5110 2246 976 5111 2247 977 5112 2249 971 5113 2250 970 5114 2251 981 5115 2255 982 5116 2256 979 5117 2253 986 5118 2260 983 5119 4611 987 5120 2261 981 5121 2258 980 5122 2259 986 5123 2260 985 5124 2264 984 5125 2265 982 5126 2262 983 5127 2266 984 5128 2267 985 5129 2268 986 5130 2270 980 5131 2271 979 5132 2272 1314 5133 3044 1315 5134 3045 1312 5135 3042 1323 5136 3065 1324 5137 3066 1321 5138 3063 1333 5139 3087 1330 5140 3084 1331 5141 3085 1260 5142 2918 1261 5143 2919 1258 5144 2916 1265 5145 2923 1264 5146 2920 1260 5147 2921 1264 5148 2927 1263 5149 2928 1261 5150 2925 1262 5151 2929 1263 5152 2930 1264 5153 2931 1265 5154 2933 1259 5155 2934 1258 5156 2935 1269 5157 2939 1270 5158 2940 1267 5159 2937 1269 5160 2942 1268 5161 2943 1274 5162 2944 1273 5163 2948 1272 5164 2949 1270 5165 2946 1271 5166 2950 1272 5167 2951 1273 5168 2952 1274 5169 2954 1268 5170 2955 1267 5171 2956 1278 5172 2960 1279 5173 2961 1276 5174 2958 1278 5175 2963 1277 5176 2964 1283 5177 2965 1282 5178 2969 1281 5179 2970 1279 5180 2967 1280 5181 2971 1281 5182 2972 1282 5183 2973 1283 5184 2975 1277 5185 2976 1276 5186 2977 1287 5187 2981 1288 5188 2982 1285 5189 2979 1292 5190 2986 1291 5191 2983 1287 5192 2984 1291 5193 2990 1290 5194 2991 1288 5195 2988 1289 5196 2992 1290 5197 2993 1291 5198 2994 1292 5199 2996 1286 5200 2997 1285 5201 2998 1296 5202 3002 1297 5203 3003 1294 5204 3000 1301 5205 3007 1300 5206 3004 1296 5207 3005 1300 5208 3011 1299 5209 3012 1297 5210 3009 1298 5211 3013 1299 5212 3014 1300 5213 3015 1301 5214 3017 1295 5215 3018 1294 5216 3019 1305 5217 3023 1306 5218 3024 1303 5219 3021 1310 5220 3028 1309 5221 3025 1305 5222 3026 1309 5223 3032 1308 5224 3033 1306 5225 3030 1307 5226 3034 1308 5227 3035 1309 5228 3036 1310 5229 3038 1304 5230 3039 1303 5231 3040 1319 5232 3049 1318 5233 3046 1314 5234 3047 1318 5235 3053 1317 5236 3054 1315 5237 3051 1316 5238 3055 1317 5239 3056 1318 5240 3057 1319 5241 3059 1313 5242 3060 1312 5243 3061 1328 5244 3070 1327 5245 3067 1323 5246 3068 1327 5247 3074 1326 5248 3075 1324 5249 3072 1325 5250 3076 1326 5251 3077 1327 5252 3078 1328 5253 3080 1322 5254 3081 1321 5255 3082 1337 5256 3091 1336 5257 3088 1332 5258 3089 1336 5259 3095 1335 5260 3096 1333 5261 3093 1334 5262 3097 1335 5263 3098 1336 5264 3099 1337 5265 3101 1331 5266 3102 1330 5267 3103 1341 5268 3107 1342 5269 3108 1339 5270 3105 1346 5271 3112 1345 5272 3109 1341 5273 3110 1345 5274 3116 1344 5275 3117 1342 5276 3114 1343 5277 3118 1344 5278 3119 1345 5279 3120 1346 5280 3122 1340 5281 3123 1339 5282 3124 1350 5283 3128 1351 5284 3129 1348 5285 3126 1350 5286 3131 1349 5287 3132 1355 5288 3133 1354 5289 3137 1353 5290 3138 1351 5291 3135 1352 5292 3139 1353 5293 3140 1354 5294 3141 1359 5295 3149 1360 5296 3150 1357 5297 3147 1359 5298 3152 1358 5299 3153 1364 5300 3154 1363 5301 3158 1362 5302 3159 1360 5303 3156 1361 5304 3160 1362 5305 3161 1363 5306 3162 1364 5307 3164 1358 5308 3165 1357 5309 3166 1368 5310 3170 1369 5311 3171 1366 5312 3168 1368 5313 3173 1367 5314 3174 1373 5315 3175 1372 5316 3179 1371 5317 3180 1369 5318 3177 1370 5319 3181 1371 5320 3182 1372 5321 3183 1373 5322 3185 1367 5323 3186 1366 5324 3187 1377 5325 3191 1378 5326 3192 1375 5327 3189 1377 5328 3194 1376 5329 3195 1382 5330 3196 1381 5331 3200 1380 5332 3201 1378 5333 3198 1379 5334 3202 1380 5335 3203 1381 5336 3204 1382 5337 3206 1376 5338 3207 1375 5339 3208 1386 5340 3212 1387 5341 3213 1384 5342 3210 1391 5343 3217 1388 5344 4656 1392 5345 3218 1386 5346 3215 1385 5347 3216 1391 5348 3217 1390 5349 3221 1389 5350 3222 1387 5351 3219 1388 5352 3223 1389 5353 3224 1390 5354 3225 1391 5355 3227 1385 5356 3228 1384 5357 3229 1395 5358 3233 1396 5359 3234 1393 5360 3231 1395 5361 3236 1394 5362 3237 1400 5363 3238 1399 5364 3242 1398 5365 3243 1396 5366 3240 1397 5367 3244 1398 5368 3245 1399 5369 3246 1400 5370 3248 1394 5371 3249 1393 5372 3250 1404 5373 3254 1405 5374 3255 1402 5375 3252 1409 5376 3259 1408 5377 3256 1404 5378 3257 1408 5379 3263 1407 5380 3264 1405 5381 3261 1406 5382 3265 1407 5383 3266 1408 5384 3267 1409 5385 3269 1403 5386 3270 1402 5387 3271 1413 5388 3275 1414 5389 3276 1411 5390 3273 1418 5391 3280 1417 5392 3277 1413 5393 3278 1417 5394 3284 1416 5395 3285 1414 5396 3282 1415 5397 3286 1416 5398 3287 1417 5399 3288 1418 5400 3290 1412 5401 3291 1411 5402 3292 1422 5403 3296 1423 5404 3297 1420 5405 3294 1427 5406 3301 1426 5407 3298 1422 5408 3299 1426 5409 3305 1425 5410 3306 1423 5411 3303 1424 5412 3307 1425 5413 3308 1426 5414 3309 1427 5415 3311 1421 5416 3312 1420 5417 3313 1431 5418 3317 1432 5419 3318 1429 5420 3315 1435 5421 3326 1434 5422 3327 1432 5423 3324 1433 5424 3328 1434 5425 3329 1435 5426 3330 1436 5427 3332 1430 5428 3333 1429 5429 3334 1440 5430 3338 1441 5431 3339 1438 5432 3336 1445 5433 3343 1444 5434 3340 1440 5435 3341 1444 5436 3347 1443 5437 3348 1441 5438 3345 1442 5439 3349 1443 5440 3350 1444 5441 3351 1445 5442 3353 1439 5443 3354 1438 5444 3355 1449 5445 3359 1450 5446 3360 1447 5447 3357 1449 5448 3362 1448 5449 3363 1454 5450 3364 1453 5451 3368 1452 5452 3369 1450 5453 3366 1451 5454 3370 1452 5455 3371 1453 5456 3372 1454 5457 3374 1448 5458 3375 1447 5459 3376 1458 5460 3380 1459 5461 3381 1456 5462 3378 1458 5463 3383 1457 5464 3384 1463 5465 3385 1462 5466 3389 1461 5467 3390 1459 5468 3387 1460 5469 3391 1461 5470 3392 1462 5471 3393 1467 5472 3401 1468 5473 3402 1465 5474 3399 1467 5475 3404 1466 5476 3405 1472 5477 3406 1471 5478 3410 1470 5479 3411 1468 5480 3408 1469 5481 3412 1470 5482 3413 1471 5483 3414 1472 5484 3416 1466 5485 3417 1465 5486 3418 495 5487 1109 496 5488 1110 493 5489 1107 495 5490 1112 494 5491 1113 500 5492 1114 499 5493 1118 498 5494 1119 496 5495 1116 497 5496 1120 498 5497 1121 499 5498 1122 504 5499 1130 505 5500 1131 502 5501 1128 504 5502 1133 503 5503 1134 509 5504 1135 508 5505 1139 507 5506 1140 505 5507 1137 506 5508 1141 507 5509 1142 508 5510 1143 513 5511 1151 514 5512 1152 511 5513 1149 513 5514 1154 512 5515 1155 518 5516 1156 517 5517 1160 516 5518 1161 514 5519 1158 515 5520 1162 516 5521 1163 517 5522 1164 581 5523 1303 578 5524 4566 582 5525 1304 576 5526 1301 575 5527 1302 581 5528 1303 578 5529 1309 579 5530 1310 580 5531 1311 1152 5532 2662 1153 5533 2663 1150 5534 2660 1152 5535 2665 1151 5536 2666 1157 5537 2667 1156 5538 2671 1155 5539 2672 1153 5540 2669 1154 5541 2673 1155 5542 2674 1156 5543 2675 1157 5544 2677 1151 5545 2678 1150 5546 2679 1161 5547 2683 1162 5548 2684 1159 5549 2681 1166 5550 2688 1163 5551 4631 1167 5552 2689 1161 5553 2686 1160 5554 2687 1166 5555 2688 1165 5556 2692 1164 5557 2693 1162 5558 2690 1163 5559 2694 1164 5560 2695 1165 5561 2696 1166 5562 2698 1160 5563 2699 1159 5564 2700 1170 5565 2704 1171 5566 2705 1168 5567 2702 1175 5568 2709 1174 5569 2706 1170 5570 2707 1175 5571 2709 1172 5572 4632 1176 5573 2710 1174 5574 2713 1173 5575 2714 1171 5576 2711 1172 5577 2715 1173 5578 2716 1174 5579 2717 1175 5580 2719 1169 5581 2720 1168 5582 2721 1179 5583 2725 1180 5584 2726 1177 5585 2723 1180 5586 2729 1182 5587 2730 1181 5588 2727 1184 5589 2734 1183 5590 2731 1179 5591 2732 1184 5592 2734 1181 5593 4633 1185 5594 2735 1183 5595 2738 1182 5596 2739 1180 5597 2736 1181 5598 2740 1182 5599 2741 1183 5600 2742 1184 5601 2744 1178 5602 2745 1177 5603 2746 1188 5604 2750 1189 5605 2751 1186 5606 2748 1193 5607 2755 1192 5608 2752 1188 5609 2753 1192 5610 2759 1191 5611 2760 1189 5612 2757 1190 5613 2761 1191 5614 2762 1192 5615 2763 1193 5616 2765 1187 5617 2766 1186 5618 2767 1197 5619 2771 1198 5620 2772 1195 5621 2769 1202 5622 2776 1201 5623 2773 1197 5624 2774 1201 5625 2780 1200 5626 2781 1198 5627 2778 1202 5628 2786 1196 5629 2787 1195 5630 2788 1206 5631 2792 1207 5632 2793 1204 5633 2790 1211 5634 2797 1210 5635 2794 1206 5636 2795 1210 5637 2801 1209 5638 2802 1207 5639 2799 1208 5640 2803 1209 5641 2804 1210 5642 2805 1211 5643 2807 1205 5644 2808 1204 5645 2809 1215 5646 2813 1216 5647 2814 1213 5648 2811 1220 5649 2818 1219 5650 2815 1215 5651 2816 1219 5652 2822 1218 5653 2823 1216 5654 2820 1217 5655 2824 1218 5656 2825 1219 5657 2826 1220 5658 2828 1214 5659 2829 1213 5660 2830 1229 5661 2839 1228 5662 2836 1224 5663 2837 1228 5664 2843 1227 5665 2844 1225 5666 2841 1226 5667 2845 1227 5668 2846 1228 5669 2847 1229 5670 2849 1223 5671 2850 1222 5672 2851 1233 5673 2855 1234 5674 2856 1231 5675 2853 1238 5676 2860 1237 5677 2857 1233 5678 2858 1237 5679 2864 1236 5680 2865 1234 5681 2862 1235 5682 2866 1236 5683 2867 1237 5684 2868 1238 5685 2870 1232 5686 2871 1231 5687 2872 1242 5688 2876 1243 5689 2877 1240 5690 2874 1242 5691 2879 1241 5692 2880 1247 5693 2881 1246 5694 2885 1245 5695 2886 1243 5696 2883 1244 5697 2887 1245 5698 2888 1246 5699 2889 1247 5700 2891 1241 5701 2892 1240 5702 2893 1251 5703 2897 1252 5704 2898 1249 5705 2895 1251 5706 2900 1250 5707 2901 1256 5708 2902 1255 5709 2906 1254 5710 2907 1252 5711 2904 1253 5712 2908 1254 5713 2909 1255 5714 2910 1256 5715 2912 1250 5716 2913 1249 5717 2914

+

1476 5718 3424 1480 5719 3440 1474 5720 3427 1477 5721 3426 1481 5722 3437 1476 5723 3424 1475 5724 3425 1479 5725 3436 1477 5726 3454 1474 5727 3427 1478 5728 3441 1475 5729 3425 1484 5730 3442 1478 5731 3441 1480 5732 3440 1481 5733 3437 1485 5734 3439 1480 5735 3440 1481 5736 3455 1479 5737 3436 1483 5738 3438 1478 5739 3441 1482 5740 3443 1479 5741 3436 1474 5742 3421 1486 5743 3423 1476 5744 3420 1474 5745 3421 1475 5746 3444 1488 5747 3445 1475 5748 3444 1477 5749 3446 1489 5750 3447 1486 5751 3423 1477 5752 3446 1476 5753 3420 1487 5754 3429 1490 5755 3450 1486 5756 3448 1488 5757 3430 1491 5758 3449 1487 5759 3429 1489 5760 3428 1493 5761 3451 1488 5762 3430 1486 5763 3431 1490 5764 3453 1489 5765 3428 1490 5766 3435 1492 5767 3433 1493 5768 3434 1496 5769 3461 1500 5770 3477 1494 5771 3464 1497 5772 3463 1501 5773 3474 1496 5774 3461 1495 5775 3462 1499 5776 3473 1497 5777 3491 1494 5778 3464 1498 5779 3478 1495 5780 3462 1498 5781 3478 1500 5782 3477 1504 5783 3479 1501 5784 3474 1505 5785 3476 1500 5786 3477 1503 5787 3475 1501 5788 3492 1499 5789 3473 1498 5790 3478 1502 5791 3480 1499 5792 3473 1494 5793 3458 1506 5794 3460 1496 5795 3457 1494 5796 3458 1495 5797 3484 1508 5798 3485 1495 5799 3484 1497 5800 3486 1509 5801 3487 1497 5802 3486 1496 5803 3457 1506 5804 3460 1507 5805 3466 1510 5806 3488 1506 5807 3468 1508 5808 3467 1511 5809 3483 1507 5810 3466 1509 5811 3465 1513 5812 3489 1508 5813 3481 1506 5814 3468 1510 5815 3488 1509 5816 3465 1510 5817 3472 1512 5818 3470 1513 5819 3471 1520 5820 3514 1514 5821 3501 1516 5822 3498 1517 5823 3500 1521 5824 3511 1516 5825 3498 1519 5826 3510 1517 5827 3500 1515 5828 3499 1514 5829 3518 1518 5830 3519 1515 5831 3499 1518 5832 3515 1520 5833 3514 1524 5834 3516 1521 5835 3511 1525 5836 3513 1520 5837 3514 1523 5838 3512 1521 5839 3511 1519 5840 3510 1518 5841 3519 1522 5842 3520 1519 5843 3510 1514 5844 3495 1526 5845 3497 1516 5846 3494 1514 5847 3495 1515 5848 3521 1528 5849 3522 1515 5850 3521 1517 5851 3523 1529 5852 3524 1516 5853 3494 1529 5854 3524 1517 5855 3523 1527 5856 3503 1530 5857 3526 1526 5858 3505 1528 5859 3504 1531 5860 3525 1527 5861 3503 1529 5862 3502 1533 5863 3527 1528 5864 3529 1526 5865 3505 1530 5866 3526 1529 5867 3502 1530 5868 3509 1532 5869 3507 1533 5870 3508 1536 5871 3535 1540 5872 3551 1534 5873 3538 1537 5874 3537 1541 5875 3548 1536 5876 3535 1535 5877 3536 1539 5878 3547 1537 5879 3537 1534 5880 3565 1538 5881 3566 1535 5882 3536 1544 5883 3553 1538 5884 3552 1540 5885 3551 1541 5886 3548 1545 5887 3550 1540 5888 3551 1541 5889 3548 1539 5890 3547 1543 5891 3549 1538 5892 3566 1542 5893 3567 1539 5894 3547 1534 5895 3532 1546 5896 3534 1536 5897 3531 1534 5898 3532 1535 5899 3555 1548 5900 3556 1535 5901 3555 1537 5902 3557 1549 5903 3558 1536 5904 3531 1549 5905 3558 1537 5906 3557 1547 5907 3540 1550 5908 3560 1546 5909 3542 1548 5910 3541 1551 5911 3559 1547 5912 3540 1549 5913 3539 1553 5914 3562 1548 5915 3561 1546 5916 3542 1550 5917 3560 1549 5918 3539 1550 5919 3546 1552 5920 3544 1553 5921 3545 1556 5922 3572 1560 5923 3588 1554 5924 3575 1557 5925 3574 1561 5926 3585 1556 5927 3572 1555 5928 3573 1559 5929 3584 1557 5930 3602 1554 5931 3575 1558 5932 3589 1555 5933 3573 1564 5934 3590 1558 5935 3589 1560 5936 3588 1561 5937 3585 1565 5938 3587 1560 5939 3588 1561 5940 3603 1559 5941 3584 1563 5942 3586 1558 5943 3589 1562 5944 3591 1559 5945 3584 1554 5946 3569 1566 5947 3571 1556 5948 3568 1554 5949 3569 1555 5950 3592 1568 5951 3593 1555 5952 3592 1557 5953 3594 1569 5954 3595 1566 5955 3571 1557 5956 3594 1556 5957 3568 1567 5958 3577 1570 5959 3598 1566 5960 3596 1568 5961 3578 1571 5962 3597 1567 5963 3577 1569 5964 3576 1573 5965 3599 1568 5966 3578 1566 5967 3579 1570 5968 3601 1569 5969 3576 1570 5970 3583 1572 5971 3581 1573 5972 3582 1576 5973 3609 1580 5974 3625 1574 5975 3612 1577 5976 3611 1581 5977 3622 1576 5978 3609 1575 5979 3610 1579 5980 3621 1577 5981 3639 1574 5982 3612 1578 5983 3626 1575 5984 3610 1578 5985 3626 1580 5986 3625 1584 5987 3627 1581 5988 3622 1585 5989 3624 1580 5990 3625 1583 5991 3623 1581 5992 3640 1579 5993 3621 1578 5994 3626 1582 5995 3628 1579 5996 3621 1574 5997 3606 1586 5998 3608 1576 5999 3605 1574 6000 3606 1575 6001 3632 1588 6002 3633 1575 6003 3632 1577 6004 3634 1589 6005 3635 1577 6006 3634 1576 6007 3605 1586 6008 3608 1587 6009 3614 1590 6010 3636 1586 6011 3616 1588 6012 3615 1591 6013 3631 1587 6014 3614 1589 6015 3613 1593 6016 3637 1588 6017 3629 1586 6018 3616 1590 6019 3636 1589 6020 3613 1590 6021 3620 1592 6022 3618 1593 6023 3619 1600 6024 3662 1594 6025 3649 1596 6026 3646 1597 6027 3648 1601 6028 3659 1596 6029 3646 1599 6030 3658 1597 6031 3648 1595 6032 3647 1594 6033 3666 1598 6034 3667 1595 6035 3647 1598 6036 3663 1600 6037 3662 1604 6038 3664 1601 6039 3659 1605 6040 3661 1600 6041 3662 1603 6042 3660 1601 6043 3659 1599 6044 3658 1598 6045 3667 1602 6046 3668 1599 6047 3658 1594 6048 3643 1606 6049 3645 1596 6050 3642 1594 6051 3643 1595 6052 3669 1608 6053 3670 1595 6054 3669 1597 6055 3671 1609 6056 3672 1596 6057 3642 1609 6058 3672 1597 6059 3671 1607 6060 3651 1610 6061 3674 1606 6062 3653 1608 6063 3652 1611 6064 3673 1607 6065 3651 1609 6066 3650 1613 6067 3675 1608 6068 3677 1606 6069 3653 1610 6070 3674 1609 6071 3650 1610 6072 3657 1612 6073 3655 1613 6074 3656 1616 6075 3683 1620 6076 3699 1614 6077 3686 1617 6078 3685 1621 6079 3696 1616 6080 3683 1615 6081 3684 1619 6082 3695 1617 6083 3685 1614 6084 3713 1618 6085 3714 1615 6086 3684 1624 6087 3701 1618 6088 3700 1620 6089 3699 1621 6090 3696 1625 6091 3698 1620 6092 3699 1621 6093 3696 1619 6094 3695 1623 6095 3697 1618 6096 3714 1622 6097 3715 1619 6098 3695 1614 6099 3680 1626 6100 3682 1616 6101 3679 1614 6102 3680 1615 6103 3703 1628 6104 3704 1615 6105 3703 1617 6106 3705 1629 6107 3706 1616 6108 3679 1629 6109 3706 1617 6110 3705 1627 6111 3688 1630 6112 3708 1626 6113 3690 1628 6114 3689 1631 6115 3707 1627 6116 3688 1629 6117 3687 1633 6118 3710 1628 6119 3709 1626 6120 3690 1630 6121 3708 1629 6122 3687 1630 6123 3694 1632 6124 3692 1633 6125 3693 1636 6126 3720 1640 6127 3736 1634 6128 3723 1637 6129 3722 1641 6130 3733 1636 6131 3720 1635 6132 3721 1639 6133 3732 1637 6134 3750 1634 6135 3723 1638 6136 3737 1635 6137 3721 1644 6138 3738 1638 6139 3737 1640 6140 3736 1641 6141 3733 1645 6142 3735 1640 6143 3736 1641 6144 3751 1639 6145 3732 1643 6146 3734 1638 6147 3737 1642 6148 3739 1639 6149 3732 1634 6150 3717 1646 6151 3719 1636 6152 3716 1634 6153 3717 1635 6154 3740 1648 6155 3741 1635 6156 3740 1637 6157 3742 1649 6158 3743 1646 6159 3719 1637 6160 3742 1636 6161 3716 1647 6162 3725 1650 6163 3746 1646 6164 3744 1648 6165 3726 1651 6166 3745 1647 6167 3725 1649 6168 3724 1653 6169 3747 1648 6170 3726 1646 6171 3727 1650 6172 3749 1649 6173 3724 1650 6174 3731 1652 6175 3729 1653 6176 3730 1656 6177 3757 1660 6178 3773 1654 6179 3760 1657 6180 3759 1661 6181 3770 1656 6182 3757 1655 6183 3758 1659 6184 3769 1657 6185 3787 1654 6186 3760 1658 6187 3774 1655 6188 3758 1658 6189 3774 1660 6190 3773 1664 6191 3775 1661 6192 3770 1665 6193 3772 1660 6194 3773 1663 6195 3771 1661 6196 3788 1659 6197 3769 1658 6198 3774 1662 6199 3776 1659 6200 3769 1654 6201 3754 1666 6202 3756 1656 6203 3753 1654 6204 3754 1655 6205 3780 1668 6206 3781 1655 6207 3780 1657 6208 3782 1669 6209 3783 1657 6210 3782 1656 6211 3753 1666 6212 3756 1667 6213 3762 1670 6214 3784 1666 6215 3764 1668 6216 3763 1671 6217 3779 1667 6218 3762 1669 6219 3761 1673 6220 3785 1668 6221 3777 1666 6222 3764 1670 6223 3784 1669 6224 3761 1670 6225 3768 1672 6226 3766 1673 6227 3767 1680 6228 3810 1674 6229 3797 1676 6230 3794 1677 6231 3796 1681 6232 3807 1676 6233 3794 1679 6234 3806 1677 6235 3796 1675 6236 3795 1674 6237 3814 1678 6238 3815 1675 6239 3795 1678 6240 3811 1680 6241 3810 1684 6242 3812 1681 6243 3807 1685 6244 3809 1680 6245 3810 1683 6246 3808 1681 6247 3807 1679 6248 3806 1678 6249 3815 1682 6250 3816 1679 6251 3806 1674 6252 3791 1686 6253 3793 1676 6254 3790 1674 6255 3791 1675 6256 3817 1688 6257 3818 1675 6258 3817 1677 6259 3819 1689 6260 3820 1676 6261 3790 1689 6262 3820 1677 6263 3819 1687 6264 3799 1690 6265 3822 1686 6266 3801 1688 6267 3800 1691 6268 3821 1687 6269 3799 1689 6270 3798 1693 6271 3823 1688 6272 3825 1686 6273 3801 1690 6274 3822 1689 6275 3798 1690 6276 3805 1692 6277 3803 1693 6278 3804 1696 6279 3831 1700 6280 3847 1694 6281 3834 1697 6282 3833 1701 6283 3844 1696 6284 3831 1695 6285 3832 1699 6286 3843 1697 6287 3833 1694 6288 3861 1698 6289 3862 1695 6290 3832 1704 6291 3849 1698 6292 3848 1700 6293 3847 1701 6294 3844 1705 6295 3846 1700 6296 3847 1701 6297 3844 1699 6298 3843 1703 6299 3845 1698 6300 3862 1702 6301 3863 1699 6302 3843 1694 6303 3828 1706 6304 3830 1696 6305 3827 1694 6306 3828 1695 6307 3851 1708 6308 3852 1695 6309 3851 1697 6310 3853 1709 6311 3854 1696 6312 3827 1709 6313 3854 1697 6314 3853 1707 6315 3836 1710 6316 3856 1706 6317 3838 1708 6318 3837 1711 6319 3855 1707 6320 3836 1709 6321 3835 1713 6322 3858 1708 6323 3857 1706 6324 3838 1710 6325 3856 1709 6326 3835 1710 6327 3842 1712 6328 3840 1713 6329 3841 1716 6330 3868 1720 6331 3884 1714 6332 3871 1717 6333 3870 1721 6334 3881 1716 6335 3868 1715 6336 3869 1719 6337 3880 1717 6338 3898 1714 6339 3871 1718 6340 3885 1715 6341 3869 1724 6342 3886 1718 6343 3885 1720 6344 3884 1721 6345 3881 1725 6346 3883 1720 6347 3884 1721 6348 3899 1719 6349 3880 1723 6350 3882 1718 6351 3885 1722 6352 3887 1719 6353 3880 1714 6354 3865 1726 6355 3867 1716 6356 3864 1714 6357 3865 1715 6358 3888 1728 6359 3889 1715 6360 3888 1717 6361 3890 1729 6362 3891 1726 6363 3867 1717 6364 3890 1716 6365 3864 1727 6366 3873 1730 6367 3894 1726 6368 3892 1728 6369 3874 1731 6370 3893 1727 6371 3873 1729 6372 3872 1733 6373 3895 1728 6374 3874 1726 6375 3875 1730 6376 3897 1729 6377 3872 1730 6378 3879 1732 6379 3877 1733 6380 3878 1736 6381 3905 1740 6382 3921 1734 6383 3908 1737 6384 3907 1741 6385 3918 1736 6386 3905 1735 6387 3906 1739 6388 3917 1737 6389 3935 1734 6390 3908 1738 6391 3922 1735 6392 3906 1738 6393 3922 1740 6394 3921 1744 6395 3923 1741 6396 3918 1745 6397 3920 1740 6398 3921 1743 6399 3919 1741 6400 3936 1739 6401 3917 1738 6402 3922 1742 6403 3924 1739 6404 3917 1734 6405 3902 1746 6406 3904 1736 6407 3901 1734 6408 3902 1735 6409 3928 1748 6410 3929 1735 6411 3928 1737 6412 3930 1749 6413 3931 1737 6414 3930 1736 6415 3901 1746 6416 3904 1747 6417 3910 1750 6418 3932 1746 6419 3912 1748 6420 3911 1751 6421 3927 1747 6422 3910 1749 6423 3909 1753 6424 3933 1748 6425 3925 1746 6426 3912 1750 6427 3932 1749 6428 3909 1750 6429 3916 1752 6430 3914 1753 6431 3915 1760 6432 3958 1754 6433 3945 1756 6434 3942 1757 6435 3944 1761 6436 3955 1756 6437 3942 1759 6438 3954 1757 6439 3944 1755 6440 3943 1754 6441 3962 1758 6442 3963 1755 6443 3943 1758 6444 3959 1760 6445 3958 1764 6446 3960 1761 6447 3955 1765 6448 3957 1760 6449 3958 1763 6450 3956 1761 6451 3955 1759 6452 3954 1758 6453 3963 1762 6454 3964 1759 6455 3954 1754 6456 3939 1766 6457 3941 1756 6458 3938 1754 6459 3939 1755 6460 3965 1768 6461 3966 1755 6462 3965 1757 6463 3967 1769 6464 3968 1756 6465 3938 1769 6466 3968 1757 6467 3967 1767 6468 3947 1770 6469 3970 1766 6470 3949 1768 6471 3948 1771 6472 3969 1767 6473 3947 1769 6474 3946 1773 6475 3971 1768 6476 3973 1766 6477 3949 1770 6478 3970 1769 6479 3946 1770 6480 3953 1772 6481 3951 1773 6482 3952 1776 6483 3979 1780 6484 3995 1774 6485 3982 1777 6486 3981 1781 6487 3992 1776 6488 3979 1775 6489 3980 1779 6490 3991 1777 6491 3981 1774 6492 4009 1778 6493 4010 1775 6494 3980 1784 6495 3997 1778 6496 3996 1780 6497 3995 1781 6498 3992 1785 6499 3994 1780 6500 3995 1781 6501 3992 1779 6502 3991 1783 6503 3993 1778 6504 4010 1782 6505 4011 1779 6506 3991 1774 6507 3976 1786 6508 3978 1776 6509 3975 1774 6510 3976 1775 6511 3999 1788 6512 4000 1775 6513 3999 1777 6514 4001 1789 6515 4002 1776 6516 3975 1789 6517 4002 1777 6518 4001 1787 6519 3984 1790 6520 4004 1786 6521 3986 1788 6522 3985 1791 6523 4003 1787 6524 3984 1789 6525 3983 1793 6526 4006 1788 6527 4005 1786 6528 3986 1790 6529 4004 1789 6530 3983 1790 6531 3990 1792 6532 3988 1793 6533 3989 1796 6534 4016 1800 6535 4032 1794 6536 4019 1797 6537 4018 1801 6538 4029 1796 6539 4016 1795 6540 4017 1799 6541 4028 1797 6542 4046 1794 6543 4019 1798 6544 4033 1795 6545 4017 1804 6546 4034 1798 6547 4033 1800 6548 4032 1801 6549 4029 1805 6550 4031 1800 6551 4032 1801 6552 4047 1799 6553 4028 1803 6554 4030 1798 6555 4033 1802 6556 4035 1799 6557 4028 1794 6558 4013 1806 6559 4015 1796 6560 4012 1794 6561 4013 1795 6562 4036 1808 6563 4037 1795 6564 4036 1797 6565 4038 1809 6566 4039 1806 6567 4015 1797 6568 4038 1796 6569 4012 1807 6570 4021 1810 6571 4042 1806 6572 4040 1808 6573 4022 1811 6574 4041 1807 6575 4021 1809 6576 4020 1813 6577 4043 1808 6578 4022 1806 6579 4023 1810 6580 4045 1809 6581 4020 1810 6582 4027 1812 6583 4025 1813 6584 4026 1816 6585 4053 1820 6586 4069 1814 6587 4056 1817 6588 4055 1821 6589 4066 1816 6590 4053 1815 6591 4054 1819 6592 4065 1817 6593 4083 1814 6594 4056 1818 6595 4070 1815 6596 4054 1818 6597 4070 1820 6598 4069 1824 6599 4071 1821 6600 4066 1825 6601 4068 1820 6602 4069 1823 6603 4067 1821 6604 4084 1819 6605 4065 1818 6606 4070 1822 6607 4072 1819 6608 4065 1814 6609 4050 1826 6610 4052 1816 6611 4049 1814 6612 4050 1815 6613 4076 1828 6614 4077 1815 6615 4076 1817 6616 4078 1829 6617 4079 1817 6618 4078 1816 6619 4049 1826 6620 4052 1827 6621 4058 1830 6622 4080 1826 6623 4060 1828 6624 4059 1831 6625 4075 1827 6626 4058 1829 6627 4057 1833 6628 4081 1828 6629 4073 1826 6630 4060 1830 6631 4080 1829 6632 4057 1830 6633 4064 1832 6634 4062 1833 6635 4063 1836 6636 4090 1840 6637 4106 1834 6638 4093 1837 6639 4092 1841 6640 4103 1836 6641 4090 1835 6642 4091 1839 6643 4102 1837 6644 4092 1834 6645 4120 1838 6646 4121 1835 6647 4091 1844 6648 4108 1838 6649 4107 1840 6650 4106 1841 6651 4103 1845 6652 4105 1840 6653 4106 1841 6654 4103 1839 6655 4102 1843 6656 4104 1838 6657 4121 1842 6658 4122 1839 6659 4102 1834 6660 4087 1846 6661 4089 1836 6662 4086 1834 6663 4087 1835 6664 4110 1848 6665 4111 1835 6666 4110 1837 6667 4112 1849 6668 4113 1836 6669 4086 1849 6670 4113 1837 6671 4112 1847 6672 4095 1850 6673 4115 1846 6674 4097 1848 6675 4096 1851 6676 4114 1847 6677 4095 1849 6678 4094 1853 6679 4117 1848 6680 4116 1846 6681 4097 1850 6682 4115 1849 6683 4094 1850 6684 4101 1852 6685 4099 1853 6686 4100 1856 6687 4127 1860 6688 4143 1854 6689 4130 1857 6690 4129 1861 6691 4140 1856 6692 4127 1855 6693 4128 1859 6694 4139 1857 6695 4157 1854 6696 4130 1858 6697 4144 1855 6698 4128 1864 6699 4145 1858 6700 4144 1860 6701 4143 1861 6702 4140 1865 6703 4142 1860 6704 4143 1861 6705 4158 1859 6706 4139 1863 6707 4141 1858 6708 4144 1862 6709 4146 1859 6710 4139 1854 6711 4124 1866 6712 4126 1856 6713 4123 1854 6714 4124 1855 6715 4147 1868 6716 4148 1855 6717 4147 1857 6718 4149 1869 6719 4150 1866 6720 4126 1857 6721 4149 1856 6722 4123 1867 6723 4132 1870 6724 4153 1866 6725 4151 1868 6726 4133 1871 6727 4152 1867 6728 4132 1869 6729 4131 1873 6730 4154 1868 6731 4133 1866 6732 4134 1870 6733 4156 1869 6734 4131 1870 6735 4138 1872 6736 4136 1873 6737 4137 1876 6738 4164 1880 6739 4180 1874 6740 4167 1877 6741 4166 1881 6742 4177 1876 6743 4164 1875 6744 4165 1879 6745 4176 1877 6746 4194 1874 6747 4167 1878 6748 4181 1875 6749 4165 1878 6750 4181 1880 6751 4180 1884 6752 4182 1881 6753 4177 1885 6754 4179 1880 6755 4180 1883 6756 4178 1881 6757 4195 1879 6758 4176 1878 6759 4181 1882 6760 4183 1879 6761 4176 1874 6762 4161 1886 6763 4163 1876 6764 4160 1874 6765 4161 1875 6766 4187 1888 6767 4188 1875 6768 4187 1877 6769 4189 1889 6770 4190 1877 6771 4189 1876 6772 4160 1886 6773 4163 1887 6774 4169 1890 6775 4191 1886 6776 4171 1888 6777 4170 1891 6778 4186 1887 6779 4169 1889 6780 4168 1893 6781 4192 1888 6782 4184 1886 6783 4171 1890 6784 4191 1889 6785 4168 1890 6786 4175 1892 6787 4173 1893 6788 4174 1900 6789 4217 1894 6790 4204 1896 6791 4201 1897 6792 4203 1901 6793 4214 1896 6794 4201 1899 6795 4213 1897 6796 4203 1895 6797 4202 1894 6798 4221 1898 6799 4222 1895 6800 4202 1898 6801 4218 1900 6802 4217 1904 6803 4219 1901 6804 4214 1905 6805 4216 1900 6806 4217 1903 6807 4215 1901 6808 4214 1899 6809 4213 1898 6810 4222 1902 6811 4223 1899 6812 4213 1894 6813 4198 1906 6814 4200 1896 6815 4197 1894 6816 4198 1895 6817 4224 1908 6818 4225 1895 6819 4224 1897 6820 4226 1909 6821 4227 1896 6822 4197 1909 6823 4227 1897 6824 4226 1907 6825 4206 1910 6826 4229 1906 6827 4208 1908 6828 4207 1911 6829 4228 1907 6830 4206 1909 6831 4205 1913 6832 4230 1908 6833 4232 1906 6834 4208 1910 6835 4229 1909 6836 4205 1910 6837 4212 1912 6838 4210 1913 6839 4211 1916 6840 4238 1920 6841 4254 1914 6842 4241 1917 6843 4240 1921 6844 4251 1916 6845 4238 1915 6846 4239 1919 6847 4250 1917 6848 4240 1914 6849 4268 1918 6850 4269 1915 6851 4239 1924 6852 4256 1918 6853 4255 1920 6854 4254 1921 6855 4251 1925 6856 4253 1920 6857 4254 1921 6858 4251 1919 6859 4250 1923 6860 4252 1918 6861 4269 1922 6862 4270 1919 6863 4250 1914 6864 4235 1926 6865 4237 1916 6866 4234 1914 6867 4235 1915 6868 4258 1928 6869 4259 1915 6870 4258 1917 6871 4260 1929 6872 4261 1916 6873 4234 1929 6874 4261 1917 6875 4260 1927 6876 4243 1930 6877 4263 1926 6878 4245 1928 6879 4244 1931 6880 4262 1927 6881 4243 1929 6882 4242 1933 6883 4265 1928 6884 4264 1926 6885 4245 1930 6886 4263 1929 6887 4242 1930 6888 4249 1932 6889 4247 1933 6890 4248 1936 6891 4275 1940 6892 4291 1934 6893 4278 1937 6894 4277 1941 6895 4288 1936 6896 4275 1935 6897 4276 1939 6898 4287 1937 6899 4305 1934 6900 4278 1938 6901 4292 1935 6902 4276 1938 6903 4292 1940 6904 4291 1944 6905 4293 1941 6906 4288 1945 6907 4290 1940 6908 4291 1943 6909 4289 1941 6910 4306 1939 6911 4287 1938 6912 4292 1942 6913 4294 1939 6914 4287 1934 6915 4272 1946 6916 4274 1936 6917 4271 1934 6918 4272 1935 6919 4298 1948 6920 4299 1935 6921 4298 1937 6922 4300 1949 6923 4301 1937 6924 4300 1936 6925 4271 1946 6926 4274 1947 6927 4280 1950 6928 4302 1946 6929 4282 1948 6930 4281 1951 6931 4297 1947 6932 4280 1949 6933 4279 1953 6934 4303 1948 6935 4295 1946 6936 4282 1950 6937 4302 1949 6938 4279 1950 6939 4286 1952 6940 4284 1953 6941 4285 1960 6942 4328 1954 6943 4315 1956 6944 4312 1957 6945 4314 1961 6946 4325 1956 6947 4312 1959 6948 4324 1957 6949 4314 1955 6950 4313 1954 6951 4332 1958 6952 4333 1955 6953 4313 1958 6954 4329 1960 6955 4328 1964 6956 4330 1961 6957 4325 1965 6958 4327 1960 6959 4328 1963 6960 4326 1961 6961 4325 1959 6962 4324 1958 6963 4333 1962 6964 4334 1959 6965 4324 1954 6966 4309 1966 6967 4311 1956 6968 4308 1954 6969 4309 1955 6970 4335 1968 6971 4336 1955 6972 4335 1957 6973 4337 1969 6974 4338 1956 6975 4308 1969 6976 4338 1957 6977 4337 1967 6978 4317 1970 6979 4340 1966 6980 4319 1968 6981 4318 1971 6982 4339 1967 6983 4317 1969 6984 4316 1973 6985 4341 1968 6986 4343 1966 6987 4319 1970 6988 4340 1969 6989 4316 1970 6990 4323 1972 6991 4321 1973 6992 4322 1976 6993 4349 1980 6994 4365 1974 6995 4352 1977 6996 4351 1981 6997 4362 1976 6998 4349 1975 6999 4350 1979 7000 4361 1977 7001 4351 1974 7002 4379 1978 7003 4380 1975 7004 4350 1984 7005 4367 1978 7006 4366 1980 7007 4365 1981 7008 4362 1985 7009 4364 1980 7010 4365 1981 7011 4362 1979 7012 4361 1983 7013 4363 1978 7014 4380 1982 7015 4381 1979 7016 4361 1974 7017 4346 1986 7018 4348 1976 7019 4345 1974 7020 4346 1975 7021 4369 1988 7022 4370 1975 7023 4369 1977 7024 4371 1989 7025 4372 1976 7026 4345 1989 7027 4372 1977 7028 4371 1987 7029 4354 1990 7030 4374 1986 7031 4356 1988 7032 4355 1991 7033 4373 1987 7034 4354 1989 7035 4353 1993 7036 4376 1988 7037 4375 1986 7038 4356 1990 7039 4374 1989 7040 4353 1990 7041 4360 1992 7042 4358 1993 7043 4359 1996 7044 4386 2000 7045 4402 1994 7046 4389 1997 7047 4388 2001 7048 4399 1996 7049 4386 1995 7050 4387 1999 7051 4398 1997 7052 4416 1994 7053 4389 1998 7054 4403 1995 7055 4387 2004 7056 4404 1998 7057 4403 2000 7058 4402 2001 7059 4399 2005 7060 4401 2000 7061 4402 2001 7062 4417 1999 7063 4398 2003 7064 4400 1998 7065 4403 2002 7066 4405 1999 7067 4398 1994 7068 4383 2006 7069 4385 1996 7070 4382 1994 7071 4383 1995 7072 4406 2008 7073 4407 1995 7074 4406 1997 7075 4408 2009 7076 4409 2006 7077 4385 1997 7078 4408 1996 7079 4382 2007 7080 4391 2010 7081 4412 2006 7082 4410 2008 7083 4392 2011 7084 4411 2007 7085 4391 2009 7086 4390 2013 7087 4413 2008 7088 4392 2006 7089 4393 2010 7090 4415 2009 7091 4390 2010 7092 4397 2012 7093 4395 2013 7094 4396 2016 7095 4423 2020 7096 4439 2014 7097 4426 2017 7098 4425 2021 7099 4436 2016 7100 4423 2015 7101 4424 2019 7102 4435 2017 7103 4453 2014 7104 4426 2018 7105 4440 2015 7106 4424 2018 7107 4440 2020 7108 4439 2024 7109 4441 2021 7110 4436 2025 7111 4438 2020 7112 4439 2023 7113 4437 2021 7114 4454 2019 7115 4435 2018 7116 4440 2022 7117 4442 2019 7118 4435 2014 7119 4420 2026 7120 4422 2016 7121 4419 2014 7122 4420 2015 7123 4446 2028 7124 4447 2015 7125 4446 2017 7126 4448 2029 7127 4449 2017 7128 4448 2016 7129 4419 2026 7130 4422 2027 7131 4428 2030 7132 4450 2026 7133 4430 2028 7134 4429 2031 7135 4445 2027 7136 4428 2029 7137 4427 2033 7138 4451 2028 7139 4443 2026 7140 4430 2030 7141 4450 2029 7142 4427 2030 7143 4434 2032 7144 4432 2033 7145 4433 2040 7146 4476 2034 7147 4463 2036 7148 4460 2037 7149 4462 2041 7150 4473 2036 7151 4460 2039 7152 4472 2037 7153 4462 2035 7154 4461 2034 7155 4480 2038 7156 4481 2035 7157 4461 2038 7158 4477 2040 7159 4476 2044 7160 4478 2041 7161 4473 2045 7162 4475 2040 7163 4476 2043 7164 4474 2041 7165 4473 2039 7166 4472 2038 7167 4481 2042 7168 4482 2039 7169 4472 2034 7170 4457 2046 7171 4459 2036 7172 4456 2034 7173 4457 2035 7174 4483 2048 7175 4484 2035 7176 4483 2037 7177 4485 2049 7178 4486 2036 7179 4456 2049 7180 4486 2037 7181 4485 2047 7182 4465 2050 7183 4488 2046 7184 4467 2048 7185 4466 2051 7186 4487 2047 7187 4465 2049 7188 4464 2053 7189 4489 2048 7190 4491 2046 7191 4467 2050 7192 4488 2049 7193 4464 2050 7194 4471 2052 7195 4469 2053 7196 4470 2056 7197 4497 2060 7198 4513 2054 7199 4500 2057 7200 4499 2061 7201 4510 2056 7202 4497 2055 7203 4498 2059 7204 4509 2057 7205 4499 2054 7206 4527 2058 7207 4528 2055 7208 4498 2064 7209 4515 2058 7210 4514 2060 7211 4513 2061 7212 4510 2065 7213 4512 2060 7214 4513 2061 7215 4510 2059 7216 4509 2063 7217 4511 2058 7218 4528 2062 7219 4529 2059 7220 4509 2054 7221 4494 2066 7222 4496 2056 7223 4493 2054 7224 4494 2055 7225 4517 2068 7226 4518 2055 7227 4517 2057 7228 4519 2069 7229 4520 2056 7230 4493 2069 7231 4520 2057 7232 4519 2067 7233 4502 2070 7234 4522 2066 7235 4504 2068 7236 4503 2071 7237 4521 2067 7238 4502 2069 7239 4501 2073 7240 4524 2068 7241 4523 2066 7242 4504 2070 7243 4522 2069 7244 4501 2070 7245 4508 2072 7246 4506 2073 7247 4507 1640 7248 3736 1638 7249 3737 1634 7250 3723 1641 7251 3733 1640 7252 3736 1636 7253 3720 1639 7254 3732 1641 7255 3751 1637 7256 3750 1638 7257 3737 1639 7258 3732 1635 7259 3721 1644 7260 3738 1642 7261 3739 1638 7262 3737 1645 7263 3735 1644 7264 3738 1640 7265 3736 1643 7266 3734 1645 7267 3752 1641 7268 3751 1642 7269 3739 1643 7270 3734 1639 7271 3732 1634 7272 3717 1647 7273 3718 1646 7274 3719 1648 7275 3741 1647 7276 3718 1634 7277 3717 1649 7278 3743 1648 7279 3741 1635 7280 3740 1646 7281 3719 1649 7282 3743 1637 7283 3742 1647 7284 3725 1651 7285 3745 1650 7286 3746 1648 7287 3726 1652 7288 3748 1651 7289 3745 1653 7290 3747 1652 7291 3748 1648 7292 3726 1650 7293 3749 1653 7294 3747 1649 7295 3724 1650 7296 3731 1651 7297 3728 1652 7298 3729 1660 7299 3773 1658 7300 3774 1654 7301 3760 1661 7302 3770 1660 7303 3773 1656 7304 3757 1659 7305 3769 1661 7306 3788 1657 7307 3787 1658 7308 3774 1659 7309 3769 1655 7310 3758 1664 7311 3775 1662 7312 3776 1658 7313 3774 1665 7314 3772 1664 7315 3775 1660 7316 3773 1663 7317 3771 1665 7318 3789 1661 7319 3788 1662 7320 3776 1663 7321 3771 1659 7322 3769 1654 7323 3754 1667 7324 3755 1666 7325 3756 1668 7326 3781 1667 7327 3755 1654 7328 3754 1669 7329 3783 1668 7330 3781 1655 7331 3780 1666 7332 3756 1669 7333 3783 1657 7334 3782 1667 7335 3762 1671 7336 3779 1670 7337 3784 1668 7338 3763 1672 7339 3786 1671 7340 3779 1673 7341 3785 1672 7342 3778 1668 7343 3777 1670 7344 3784 1673 7345 3785 1669 7346 3761 1670 7347 3768 1671 7348 3765 1672 7349 3766 1680 7350 3810 1678 7351 3811 1674 7352 3797 1681 7353 3807 1680 7354 3810 1676 7355 3794 1679 7356 3806 1681 7357 3807 1677 7358 3796 1678 7359 3815 1679 7360 3806 1675 7361 3795 1684 7362 3812 1682 7363 3813 1678 7364 3811 1685 7365 3809 1684 7366 3812 1680 7367 3810 1683 7368 3808 1685 7369 3809 1681 7370 3807 1682 7371 3816 1683 7372 3808 1679 7373 3806 1674 7374 3791 1687 7375 3792 1686 7376 3793 1688 7377 3818 1687 7378 3792 1674 7379 3791 1689 7380 3820 1688 7381 3818 1675 7382 3817 1676 7383 3790 1686 7384 3793 1689 7385 3820 1687 7386 3799 1691 7387 3821 1690 7388 3822 1688 7389 3800 1692 7390 3824 1691 7391 3821 1693 7392 3823 1692 7393 3826 1688 7394 3825 1690 7395 3822 1693 7396 3823 1689 7397 3798 1690 7398 3805 1691 7399 3802 1692 7400 3803 1700 7401 3847 1698 7402 3848 1694 7403 3834 1701 7404 3844 1700 7405 3847 1696 7406 3831 1699 7407 3843 1701 7408 3844 1697 7409 3833 1698 7410 3862 1699 7411 3843 1695 7412 3832 1704 7413 3849 1702 7414 3850 1698 7415 3848 1705 7416 3846 1704 7417 3849 1700 7418 3847 1703 7419 3845 1705 7420 3846 1701 7421 3844 1702 7422 3863 1703 7423 3845 1699 7424 3843 1694 7425 3828 1707 7426 3829 1706 7427 3830 1708 7428 3852 1707 7429 3829 1694 7430 3828 1709 7431 3854 1708 7432 3852 1695 7433 3851 1696 7434 3827 1706 7435 3830 1709 7436 3854 1707 7437 3836 1711 7438 3855 1710 7439 3856 1708 7440 3837 1712 7441 3860 1711 7442 3855 1713 7443 3858 1712 7444 3859 1708 7445 3857 1710 7446 3856 1713 7447 3858 1709 7448 3835 1710 7449 3842 1711 7450 3839 1712 7451 3840 1720 7452 3884 1718 7453 3885 1714 7454 3871 1721 7455 3881 1720 7456 3884 1716 7457 3868 1719 7458 3880 1721 7459 3899 1717 7460 3898 1718 7461 3885 1719 7462 3880 1715 7463 3869 1724 7464 3886 1722 7465 3887 1718 7466 3885 1725 7467 3883 1724 7468 3886 1720 7469 3884 1723 7470 3882 1725 7471 3900 1721 7472 3899 1722 7473 3887 1723 7474 3882 1719 7475 3880 1714 7476 3865 1727 7477 3866 1726 7478 3867 1728 7479 3889 1727 7480 3866 1714 7481 3865 1729 7482 3891 1728 7483 3889 1715 7484 3888 1726 7485 3867 1729 7486 3891 1717 7487 3890 1727 7488 3873 1731 7489 3893 1730 7490 3894 1728 7491 3874 1732 7492 3896 1731 7493 3893 1733 7494 3895 1732 7495 3896 1728 7496 3874 1730 7497 3897 1733 7498 3895 1729 7499 3872 1730 7500 3879 1731 7501 3876 1732 7502 3877 1738 7503 3922 1739 7504 3917 1735 7505 3906 1742 7506 3924 1743 7507 3919 1739 7508 3917 1748 7509 3929 1747 7510 3903 1734 7511 3902 1748 7512 3911 1752 7513 3934 1751 7514 3927 1758 7515 3963 1759 7516 3954 1755 7517 3943 1762 7518 3964 1763 7519 3956 1759 7520 3954 1768 7521 3966 1767 7522 3940 1754 7523 3939 1768 7524 3948 1772 7525 3972 1771 7526 3969 1780 7527 3995 1778 7528 3996 1774 7529 3982 1781 7530 3992 1780 7531 3995 1776 7532 3979 1779 7533 3991 1781 7534 3992 1777 7535 3981 1778 7536 4010 1779 7537 3991 1775 7538 3980 1784 7539 3997 1782 7540 3998 1778 7541 3996 1785 7542 3994 1784 7543 3997 1780 7544 3995 1783 7545 3993 1785 7546 3994 1781 7547 3992 1782 7548 4011 1783 7549 3993 1779 7550 3991 1774 7551 3976 1787 7552 3977 1786 7553 3978 1788 7554 4000 1787 7555 3977 1774 7556 3976 1789 7557 4002 1788 7558 4000 1775 7559 3999 1776 7560 3975 1786 7561 3978 1789 7562 4002 1787 7563 3984 1791 7564 4003 1790 7565 4004 1788 7566 3985 1792 7567 4008 1791 7568 4003 1793 7569 4006 1792 7570 4007 1788 7571 4005 1790 7572 4004 1793 7573 4006 1789 7574 3983 1790 7575 3990 1791 7576 3987 1792 7577 3988 1821 7578 4066 1820 7579 4069 1816 7580 4053 1825 7581 4068 1824 7582 4071 1820 7583 4069 1826 7584 4052 1829 7585 4079 1817 7586 4078 1830 7587 4080 1833 7588 4081 1829 7589 4057 1740 7590 3921 1738 7591 3922 1734 7592 3908 1741 7593 3918 1740 7594 3921 1736 7595 3905 1739 7596 3917 1741 7597 3936 1737 7598 3935 1744 7599 3923 1742 7600 3924 1738 7601 3922 1745 7602 3920 1744 7603 3923 1740 7604 3921 1743 7605 3919 1745 7606 3937 1741 7607 3936 1734 7608 3902 1747 7609 3903 1746 7610 3904 1749 7611 3931 1748 7612 3929 1735 7613 3928 1746 7614 3904 1749 7615 3931 1737 7616 3930 1747 7617 3910 1751 7618 3927 1750 7619 3932 1753 7620 3933 1752 7621 3926 1748 7622 3925 1750 7623 3932 1753 7624 3933 1749 7625 3909 1750 7626 3916 1751 7627 3913 1752 7628 3914 1760 7629 3958 1758 7630 3959 1754 7631 3945 1761 7632 3955 1760 7633 3958 1756 7634 3942 1759 7635 3954 1761 7636 3955 1757 7637 3944 1764 7638 3960 1762 7639 3961 1758 7640 3959 1765 7641 3957 1764 7642 3960 1760 7643 3958 1763 7644 3956 1765 7645 3957 1761 7646 3955 1754 7647 3939 1767 7648 3940 1766 7649 3941 1769 7650 3968 1768 7651 3966 1755 7652 3965 1756 7653 3938 1766 7654 3941 1769 7655 3968 1767 7656 3947 1771 7657 3969 1770 7658 3970 1773 7659 3971 1772 7660 3974 1768 7661 3973 1770 7662 3970 1773 7663 3971 1769 7664 3946 1770 7665 3953 1771 7666 3950 1772 7667 3951 1800 7668 4032 1798 7669 4033 1794 7670 4019 1801 7671 4029 1800 7672 4032 1796 7673 4016 1799 7674 4028 1801 7675 4047 1797 7676 4046 1798 7677 4033 1799 7678 4028 1795 7679 4017 1804 7680 4034 1802 7681 4035 1798 7682 4033 1805 7683 4031 1804 7684 4034 1800 7685 4032 1803 7686 4030 1805 7687 4048 1801 7688 4047 1802 7689 4035 1803 7690 4030 1799 7691 4028 1794 7692 4013 1807 7693 4014 1806 7694 4015 1808 7695 4037 1807 7696 4014 1794 7697 4013 1809 7698 4039 1808 7699 4037 1795 7700 4036 1806 7701 4015 1809 7702 4039 1797 7703 4038 1807 7704 4021 1811 7705 4041 1810 7706 4042 1808 7707 4022 1812 7708 4044 1811 7709 4041 1813 7710 4043 1812 7711 4044 1808 7712 4022 1810 7713 4045 1813 7714 4043 1809 7715 4020 1810 7716 4027 1811 7717 4024 1812 7718 4025 1820 7719 4069 1818 7720 4070 1814 7721 4056 1819 7722 4065 1821 7723 4084 1817 7724 4083 1818 7725 4070 1819 7726 4065 1815 7727 4054 1824 7728 4071 1822 7729 4072 1818 7730 4070 1823 7731 4067 1825 7732 4085 1821 7733 4084 1822 7734 4072 1823 7735 4067 1819 7736 4065 1814 7737 4050 1827 7738 4051 1826 7739 4052 1828 7740 4077 1827 7741 4051 1814 7742 4050 1829 7743 4079 1828 7744 4077 1815 7745 4076 1827 7746 4058 1831 7747 4075 1830 7748 4080 1828 7749 4059 1832 7750 4082 1831 7751 4075 1833 7752 4081 1832 7753 4074 1828 7754 4073 1830 7755 4064 1831 7756 4061 1832 7757 4062 1840 7758 4106 1838 7759 4107 1834 7760 4093 1841 7761 4103 1840 7762 4106 1836 7763 4090 1839 7764 4102 1841 7765 4103 1837 7766 4092 1838 7767 4121 1839 7768 4102 1835 7769 4091 1844 7770 4108 1842 7771 4109 1838 7772 4107 1845 7773 4105 1844 7774 4108 1840 7775 4106 1843 7776 4104 1845 7777 4105 1841 7778 4103 1842 7779 4122 1843 7780 4104 1839 7781 4102 1834 7782 4087 1847 7783 4088 1846 7784 4089 1848 7785 4111 1847 7786 4088 1834 7787 4087 1849 7788 4113 1848 7789 4111 1835 7790 4110 1836 7791 4086 1846 7792 4089 1849 7793 4113 1847 7794 4095 1851 7795 4114 1850 7796 4115 1848 7797 4096 1852 7798 4119 1851 7799 4114 1853 7800 4117 1852 7801 4118 1848 7802 4116 1850 7803 4115 1853 7804 4117 1849 7805 4094 1850 7806 4101 1851 7807 4098 1852 7808 4099 1480 7809 3440 1478 7810 3441 1474 7811 3427 1481 7812 3437 1480 7813 3440 1476 7814 3424 1479 7815 3436 1481 7816 3455 1477 7817 3454 1478 7818 3441 1479 7819 3436 1475 7820 3425 1484 7821 3442 1482 7822 3443 1478 7823 3441 1485 7824 3439 1484 7825 3442 1480 7826 3440 1483 7827 3438 1485 7828 3456 1481 7829 3455 1482 7830 3443 1483 7831 3438 1479 7832 3436 1474 7833 3421 1487 7834 3422 1486 7835 3423 1488 7836 3445 1487 7837 3422 1474 7838 3421 1489 7839 3447 1488 7840 3445 1475 7841 3444 1486 7842 3423 1489 7843 3447 1477 7844 3446 1487 7845 3429 1491 7846 3449 1490 7847 3450 1488 7848 3430 1492 7849 3452 1491 7850 3449 1493 7851 3451 1492 7852 3452 1488 7853 3430 1490 7854 3453 1493 7855 3451 1489 7856 3428 1490 7857 3435 1491 7858 3432 1492 7859 3433 1500 7860 3477 1498 7861 3478 1494 7862 3464 1501 7863 3474 1500 7864 3477 1496 7865 3461 1499 7866 3473 1501 7867 3492 1497 7868 3491 1498 7869 3478 1499 7870 3473 1495 7871 3462 1504 7872 3479 1502 7873 3480 1498 7874 3478 1505 7875 3476 1504 7876 3479 1500 7877 3477 1503 7878 3475 1505 7879 3493 1501 7880 3492 1502 7881 3480 1503 7882 3475 1499 7883 3473 1494 7884 3458 1507 7885 3459 1506 7886 3460 1508 7887 3485 1507 7888 3459 1494 7889 3458 1509 7890 3487 1508 7891 3485 1495 7892 3484 1506 7893 3460 1509 7894 3487 1497 7895 3486 1507 7896 3466 1511 7897 3483 1510 7898 3488 1508 7899 3467 1512 7900 3490 1511 7901 3483 1513 7902 3489 1512 7903 3482 1508 7904 3481 1510 7905 3488 1513 7906 3489 1509 7907 3465 1510 7908 3472 1511 7909 3469 1512 7910 3470 1520 7911 3514 1518 7912 3515 1514 7913 3501 1521 7914 3511 1520 7915 3514 1516 7916 3498 1519 7917 3510 1521 7918 3511 1517 7919 3500 1518 7920 3519 1519 7921 3510 1515 7922 3499 1524 7923 3516 1522 7924 3517 1518 7925 3515 1525 7926 3513 1524 7927 3516 1520 7928 3514 1523 7929 3512 1525 7930 3513 1521 7931 3511 1522 7932 3520 1523 7933 3512 1519 7934 3510 1514 7935 3495 1527 7936 3496 1526 7937 3497 1528 7938 3522 1527 7939 3496 1514 7940 3495 1529 7941 3524 1528 7942 3522 1515 7943 3521 1516 7944 3494 1526 7945 3497 1529 7946 3524 1527 7947 3503 1531 7948 3525 1530 7949 3526 1528 7950 3504 1532 7951 3528 1531 7952 3525 1533 7953 3527 1532 7954 3530 1528 7955 3529 1530 7956 3526 1533 7957 3527 1529 7958 3502 1530 7959 3509 1531 7960 3506 1532 7961 3507 1540 7962 3551 1538 7963 3552 1534 7964 3538 1541 7965 3548 1540 7966 3551 1536 7967 3535 1539 7968 3547 1541 7969 3548 1537 7970 3537 1538 7971 3566 1539 7972 3547 1535 7973 3536 1544 7974 3553 1542 7975 3554 1538 7976 3552 1545 7977 3550 1544 7978 3553 1540 7979 3551 1543 7980 3549 1545 7981 3550 1541 7982 3548 1542 7983 3567 1543 7984 3549 1539 7985 3547 1534 7986 3532 1547 7987 3533 1546 7988 3534 1548 7989 3556 1547 7990 3533 1534 7991 3532 1549 7992 3558 1548 7993 3556 1535 7994 3555 1536 7995 3531 1546 7996 3534 1549 7997 3558 1547 7998 3540 1551 7999 3559 1550 8000 3560 1548 8001 3541 1552 8002 3564 1551 8003 3559 1553 8004 3562 1552 8005 3563 1548 8006 3561 1550 8007 3560 1553 8008 3562 1549 8009 3539 1550 8010 3546 1551 8011 3543 1552 8012 3544 1560 8013 3588 1558 8014 3589 1554 8015 3575 1561 8016 3585 1560 8017 3588 1556 8018 3572 1559 8019 3584 1561 8020 3603 1557 8021 3602 1558 8022 3589 1559 8023 3584 1555 8024 3573 1564 8025 3590 1562 8026 3591 1558 8027 3589 1565 8028 3587 1564 8029 3590 1560 8030 3588 1563 8031 3586 1565 8032 3604 1561 8033 3603 1562 8034 3591 1563 8035 3586 1559 8036 3584 1554 8037 3569 1567 8038 3570 1566 8039 3571 1568 8040 3593 1567 8041 3570 1554 8042 3569 1569 8043 3595 1568 8044 3593 1555 8045 3592 1566 8046 3571 1569 8047 3595 1557 8048 3594 1567 8049 3577 1571 8050 3597 1570 8051 3598 1568 8052 3578 1572 8053 3600 1571 8054 3597 1573 8055 3599 1572 8056 3600 1568 8057 3578 1570 8058 3601 1573 8059 3599 1569 8060 3576 1570 8061 3583 1571 8062 3580 1572 8063 3581 1580 8064 3625 1578 8065 3626 1574 8066 3612 1581 8067 3622 1580 8068 3625 1576 8069 3609 1579 8070 3621 1581 8071 3640 1577 8072 3639 1578 8073 3626 1579 8074 3621 1575 8075 3610 1584 8076 3627 1582 8077 3628 1578 8078 3626 1585 8079 3624 1584 8080 3627 1580 8081 3625 1583 8082 3623 1585 8083 3641 1581 8084 3640 1582 8085 3628 1583 8086 3623 1579 8087 3621 1574 8088 3606 1587 8089 3607 1586 8090 3608 1588 8091 3633 1587 8092 3607 1574 8093 3606 1589 8094 3635 1588 8095 3633 1575 8096 3632 1586 8097 3608 1589 8098 3635 1577 8099 3634 1587 8100 3614 1591 8101 3631 1590 8102 3636 1588 8103 3615 1592 8104 3638 1591 8105 3631 1593 8106 3637 1592 8107 3630 1588 8108 3629 1590 8109 3636 1593 8110 3637 1589 8111 3613 1590 8112 3620 1591 8113 3617 1592 8114 3618 1600 8115 3662 1598 8116 3663 1594 8117 3649 1601 8118 3659 1600 8119 3662 1596 8120 3646 1599 8121 3658 1601 8122 3659 1597 8123 3648 1598 8124 3667 1599 8125 3658 1595 8126 3647 1604 8127 3664 1602 8128 3665 1598 8129 3663 1605 8130 3661 1604 8131 3664 1600 8132 3662 1603 8133 3660 1605 8134 3661 1601 8135 3659 1602 8136 3668 1603 8137 3660 1599 8138 3658 1594 8139 3643 1607 8140 3644 1606 8141 3645 1608 8142 3670 1607 8143 3644 1594 8144 3643 1609 8145 3672 1608 8146 3670 1595 8147 3669 1596 8148 3642 1606 8149 3645 1609 8150 3672 1607 8151 3651 1611 8152 3673 1610 8153 3674 1608 8154 3652 1612 8155 3676 1611 8156 3673 1613 8157 3675 1612 8158 3678 1608 8159 3677 1610 8160 3674 1613 8161 3675 1609 8162 3650 1610 8163 3657 1611 8164 3654 1612 8165 3655 1620 8166 3699 1618 8167 3700 1614 8168 3686 1621 8169 3696 1620 8170 3699 1616 8171 3683 1619 8172 3695 1621 8173 3696 1617 8174 3685 1618 8175 3714 1619 8176 3695 1615 8177 3684 1624 8178 3701 1622 8179 3702 1618 8180 3700 1625 8181 3698 1624 8182 3701 1620 8183 3699 1623 8184 3697 1625 8185 3698 1621 8186 3696 1622 8187 3715 1623 8188 3697 1619 8189 3695 1614 8190 3680 1627 8191 3681 1626 8192 3682 1628 8193 3704 1627 8194 3681 1614 8195 3680 1629 8196 3706 1628 8197 3704 1615 8198 3703 1616 8199 3679 1626 8200 3682 1629 8201 3706 1627 8202 3688 1631 8203 3707 1630 8204 3708 1628 8205 3689 1632 8206 3712 1631 8207 3707 1633 8208 3710 1632 8209 3711 1628 8210 3709 1630 8211 3708 1633 8212 3710 1629 8213 3687 1630 8214 3694 1631 8215 3691 1632 8216 3692 1860 8217 4143 1858 8218 4144 1854 8219 4130 1861 8220 4140 1860 8221 4143 1856 8222 4127 1859 8223 4139 1861 8224 4158 1857 8225 4157 1858 8226 4144 1859 8227 4139 1855 8228 4128 1864 8229 4145 1862 8230 4146 1858 8231 4144 1865 8232 4142 1864 8233 4145 1860 8234 4143 1863 8235 4141 1865 8236 4159 1861 8237 4158 1862 8238 4146 1863 8239 4141 1859 8240 4139 1854 8241 4124 1867 8242 4125 1866 8243 4126 1868 8244 4148 1867 8245 4125 1854 8246 4124 1869 8247 4150 1868 8248 4148 1855 8249 4147 1866 8250 4126 1869 8251 4150 1857 8252 4149 1867 8253 4132 1871 8254 4152 1870 8255 4153 1868 8256 4133 1872 8257 4155 1871 8258 4152 1873 8259 4154 1872 8260 4155 1868 8261 4133 1870 8262 4156 1873 8263 4154 1869 8264 4131 1870 8265 4138 1871 8266 4135 1872 8267 4136 1880 8268 4180 1878 8269 4181 1874 8270 4167 1881 8271 4177 1880 8272 4180 1876 8273 4164 1879 8274 4176 1881 8275 4195 1877 8276 4194 1878 8277 4181 1879 8278 4176 1875 8279 4165 1884 8280 4182 1882 8281 4183 1878 8282 4181 1885 8283 4179 1884 8284 4182 1880 8285 4180 1883 8286 4178 1885 8287 4196 1881 8288 4195 1882 8289 4183 1883 8290 4178 1879 8291 4176 1874 8292 4161 1887 8293 4162 1886 8294 4163 1888 8295 4188 1887 8296 4162 1874 8297 4161 1889 8298 4190 1888 8299 4188 1875 8300 4187 1886 8301 4163 1889 8302 4190 1877 8303 4189 1887 8304 4169 1891 8305 4186 1890 8306 4191 1888 8307 4170 1892 8308 4193 1891 8309 4186 1893 8310 4192 1892 8311 4185 1888 8312 4184 1890 8313 4191 1893 8314 4192 1889 8315 4168 1890 8316 4175 1891 8317 4172 1892 8318 4173 1900 8319 4217 1898 8320 4218 1894 8321 4204 1901 8322 4214 1900 8323 4217 1896 8324 4201 1899 8325 4213 1901 8326 4214 1897 8327 4203 1898 8328 4222 1899 8329 4213 1895 8330 4202 1904 8331 4219 1902 8332 4220 1898 8333 4218 1905 8334 4216 1904 8335 4219 1900 8336 4217 1903 8337 4215 1905 8338 4216 1901 8339 4214 1902 8340 4223 1903 8341 4215 1899 8342 4213 1894 8343 4198 1907 8344 4199 1906 8345 4200 1908 8346 4225 1907 8347 4199 1894 8348 4198 1909 8349 4227 1908 8350 4225 1895 8351 4224 1896 8352 4197 1906 8353 4200 1909 8354 4227 1907 8355 4206 1911 8356 4228 1910 8357 4229 1908 8358 4207 1912 8359 4231 1911 8360 4228 1913 8361 4230 1912 8362 4233 1908 8363 4232 1910 8364 4229 1913 8365 4230 1909 8366 4205 1910 8367 4212 1911 8368 4209 1912 8369 4210 1920 8370 4254 1918 8371 4255 1914 8372 4241 1921 8373 4251 1920 8374 4254 1916 8375 4238 1919 8376 4250 1921 8377 4251 1917 8378 4240 1918 8379 4269 1919 8380 4250 1915 8381 4239 1924 8382 4256 1922 8383 4257 1918 8384 4255 1925 8385 4253 1924 8386 4256 1920 8387 4254 1923 8388 4252 1925 8389 4253 1921 8390 4251 1922 8391 4270 1923 8392 4252 1919 8393 4250 1914 8394 4235 1927 8395 4236 1926 8396 4237 1928 8397 4259 1927 8398 4236 1914 8399 4235 1929 8400 4261 1928 8401 4259 1915 8402 4258 1916 8403 4234 1926 8404 4237 1929 8405 4261 1927 8406 4243 1931 8407 4262 1930 8408 4263 1928 8409 4244 1932 8410 4267 1931 8411 4262 1933 8412 4265 1932 8413 4266 1928 8414 4264 1930 8415 4263 1933 8416 4265 1929 8417 4242 1930 8418 4249 1931 8419 4246 1932 8420 4247 1940 8421 4291 1938 8422 4292 1934 8423 4278 1941 8424 4288 1940 8425 4291 1936 8426 4275 1939 8427 4287 1941 8428 4306 1937 8429 4305 1938 8430 4292 1939 8431 4287 1935 8432 4276 1944 8433 4293 1942 8434 4294 1938 8435 4292 1945 8436 4290 1944 8437 4293 1940 8438 4291 1943 8439 4289 1945 8440 4307 1941 8441 4306 1942 8442 4294 1943 8443 4289 1939 8444 4287 1934 8445 4272 1947 8446 4273 1946 8447 4274 1948 8448 4299 1947 8449 4273 1934 8450 4272 1949 8451 4301 1948 8452 4299 1935 8453 4298 1946 8454 4274 1949 8455 4301 1937 8456 4300 1947 8457 4280 1951 8458 4297 1950 8459 4302 1948 8460 4281 1952 8461 4304 1951 8462 4297 1953 8463 4303 1952 8464 4296 1948 8465 4295 1950 8466 4302 1953 8467 4303 1949 8468 4279 1950 8469 4286 1951 8470 4283 1952 8471 4284 1960 8472 4328 1958 8473 4329 1954 8474 4315 1961 8475 4325 1960 8476 4328 1956 8477 4312 1959 8478 4324 1961 8479 4325 1957 8480 4314 1958 8481 4333 1959 8482 4324 1955 8483 4313 1964 8484 4330 1962 8485 4331 1958 8486 4329 1965 8487 4327 1964 8488 4330 1960 8489 4328 1963 8490 4326 1965 8491 4327 1961 8492 4325 1962 8493 4334 1963 8494 4326 1959 8495 4324 1954 8496 4309 1967 8497 4310 1966 8498 4311 1968 8499 4336 1967 8500 4310 1954 8501 4309 1969 8502 4338 1968 8503 4336 1955 8504 4335 1956 8505 4308 1966 8506 4311 1969 8507 4338 1967 8508 4317 1971 8509 4339 1970 8510 4340 1968 8511 4318 1972 8512 4342 1971 8513 4339 1973 8514 4341 1972 8515 4344 1968 8516 4343 1970 8517 4340 1973 8518 4341 1969 8519 4316 1970 8520 4323 1971 8521 4320 1972 8522 4321 1980 8523 4365 1978 8524 4366 1974 8525 4352 1981 8526 4362 1980 8527 4365 1976 8528 4349 1979 8529 4361 1981 8530 4362 1977 8531 4351 1978 8532 4380 1979 8533 4361 1975 8534 4350 1984 8535 4367 1982 8536 4368 1978 8537 4366 1985 8538 4364 1984 8539 4367 1980 8540 4365 1983 8541 4363 1985 8542 4364 1981 8543 4362 1982 8544 4381 1983 8545 4363 1979 8546 4361 1974 8547 4346 1987 8548 4347 1986 8549 4348 1988 8550 4370 1987 8551 4347 1974 8552 4346 1989 8553 4372 1988 8554 4370 1975 8555 4369 1976 8556 4345 1986 8557 4348 1989 8558 4372 1987 8559 4354 1991 8560 4373 1990 8561 4374 1988 8562 4355 1992 8563 4378 1991 8564 4373 1993 8565 4376 1992 8566 4377 1988 8567 4375 1990 8568 4374 1993 8569 4376 1989 8570 4353 1990 8571 4360 1991 8572 4357 1992 8573 4358 2000 8574 4402 1998 8575 4403 1994 8576 4389 2001 8577 4399 2000 8578 4402 1996 8579 4386 1999 8580 4398 2001 8581 4417 1997 8582 4416 1998 8583 4403 1999 8584 4398 1995 8585 4387 2004 8586 4404 2002 8587 4405 1998 8588 4403 2005 8589 4401 2004 8590 4404 2000 8591 4402 2003 8592 4400 2005 8593 4418 2001 8594 4417 2002 8595 4405 2003 8596 4400 1999 8597 4398 1994 8598 4383 2007 8599 4384 2006 8600 4385 2008 8601 4407 2007 8602 4384 1994 8603 4383 2009 8604 4409 2008 8605 4407 1995 8606 4406 2006 8607 4385 2009 8608 4409 1997 8609 4408 2007 8610 4391 2011 8611 4411 2010 8612 4412 2008 8613 4392 2012 8614 4414 2011 8615 4411 2013 8616 4413 2012 8617 4414 2008 8618 4392 2010 8619 4415 2013 8620 4413 2009 8621 4390 2010 8622 4397 2011 8623 4394 2012 8624 4395 2020 8625 4439 2018 8626 4440 2014 8627 4426 2021 8628 4436 2020 8629 4439 2016 8630 4423 2019 8631 4435 2021 8632 4454 2017 8633 4453 2018 8634 4440 2019 8635 4435 2015 8636 4424 2024 8637 4441 2022 8638 4442 2018 8639 4440 2025 8640 4438 2024 8641 4441 2020 8642 4439 2023 8643 4437 2025 8644 4455 2021 8645 4454 2022 8646 4442 2023 8647 4437 2019 8648 4435 2014 8649 4420 2027 8650 4421 2026 8651 4422 2028 8652 4447 2027 8653 4421 2014 8654 4420 2029 8655 4449 2028 8656 4447 2015 8657 4446 2026 8658 4422 2029 8659 4449 2017 8660 4448 2027 8661 4428 2031 8662 4445 2030 8663 4450 2028 8664 4429 2032 8665 4452 2031 8666 4445 2033 8667 4451 2032 8668 4444 2028 8669 4443 2030 8670 4450 2033 8671 4451 2029 8672 4427 2030 8673 4434 2031 8674 4431 2032 8675 4432 2040 8676 4476 2038 8677 4477 2034 8678 4463 2041 8679 4473 2040 8680 4476 2036 8681 4460 2039 8682 4472 2041 8683 4473 2037 8684 4462 2038 8685 4481 2039 8686 4472 2035 8687 4461 2044 8688 4478 2042 8689 4479 2038 8690 4477 2045 8691 4475 2044 8692 4478 2040 8693 4476 2043 8694 4474 2045 8695 4475 2041 8696 4473 2042 8697 4482 2043 8698 4474 2039 8699 4472 2034 8700 4457 2047 8701 4458 2046 8702 4459 2048 8703 4484 2047 8704 4458 2034 8705 4457 2049 8706 4486 2048 8707 4484 2035 8708 4483 2036 8709 4456 2046 8710 4459 2049 8711 4486 2047 8712 4465 2051 8713 4487 2050 8714 4488 2048 8715 4466 2052 8716 4490 2051 8717 4487 2053 8718 4489 2052 8719 4492 2048 8720 4491 2050 8721 4488 2053 8722 4489 2049 8723 4464 2050 8724 4471 2051 8725 4468 2052 8726 4469 2060 8727 4513 2058 8728 4514 2054 8729 4500 2061 8730 4510 2060 8731 4513 2056 8732 4497 2059 8733 4509 2061 8734 4510 2057 8735 4499 2058 8736 4528 2059 8737 4509 2055 8738 4498 2064 8739 4515 2062 8740 4516 2058 8741 4514 2065 8742 4512 2064 8743 4515 2060 8744 4513 2063 8745 4511 2065 8746 4512 2061 8747 4510 2062 8748 4529 2063 8749 4511 2059 8750 4509 2054 8751 4494 2067 8752 4495 2066 8753 4496 2068 8754 4518 2067 8755 4495 2054 8756 4494 2069 8757 4520 2068 8758 4518 2055 8759 4517 2056 8760 4493 2066 8761 4496 2069 8762 4520 2067 8763 4502 2071 8764 4521 2070 8765 4522 2068 8766 4503 2072 8767 4526 2071 8768 4521 2073 8769 4524 2072 8770 4525 2068 8771 4523 2070 8772 4522 2073 8773 4524 2069 8774 4501 2070 8775 4508 2071 8776 4505 2072 8777 4506

+
+
+
+ + + + + + + + + 1.000000 0.000000 0.000000 0.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1.0000001.000000 + 30.0000000.0000003.333333 + + + + + +
diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ShelfF_01/model.config b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ShelfF_01/model.config new file mode 100755 index 0000000..adb8edd --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ShelfF_01/model.config @@ -0,0 +1,11 @@ + + + aws_robomaker_warehouse_ShelfF_01 + 1.0 + model.sdf + + + + + + diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ShelfF_01/model.sdf b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ShelfF_01/model.sdf new file mode 100755 index 0000000..bcc9aef --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_ShelfF_01/model.sdf @@ -0,0 +1,46 @@ + + + + + + 30 + + 907.144 + 0 + 0 + 104.950 + 0 + 824.248 + + + + + + model://aws_robomaker_warehouse_ShelfF_01/meshes/aws_robomaker_warehouse_ShelfF_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + model://aws_robomaker_warehouse_ShelfF_01/meshes/aws_robomaker_warehouse_ShelfF_01_visual.DAE + + + 1 + + +1 + + diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_TrashCanC_01/materials/textures/aws_robomaker_warehouse_TrashCanC_01.png b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_TrashCanC_01/materials/textures/aws_robomaker_warehouse_TrashCanC_01.png new file mode 100755 index 0000000..252756a Binary files /dev/null and b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_TrashCanC_01/materials/textures/aws_robomaker_warehouse_TrashCanC_01.png differ diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_TrashCanC_01/meshes/aws_robomaker_warehouse_TrashCanC_01_collision.DAE b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_TrashCanC_01/meshes/aws_robomaker_warehouse_TrashCanC_01_collision.DAE new file mode 100755 index 0000000..2bce352 --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_TrashCanC_01/meshes/aws_robomaker_warehouse_TrashCanC_01_collision.DAE @@ -0,0 +1,724 @@ + + + FBX COLLADA exporter2019-03-21T05:48:15Z2019-03-21T05:48:15ZZ_UP + + + + + +73.948090 -45.443611 130.823112 +73.948112 -45.443619 110.171623 +63.734142 -35.842438 23.716797 +67.833038 -39.073685 100.779701 +39.877193 -45.443611 130.823112 +39.877193 -45.443619 110.171623 +39.877193 -35.842438 23.716797 +39.877193 -39.073685 100.779701 +73.948090 -23.254808 130.823112 +73.948112 -23.254808 110.171623 +63.734142 -23.254808 23.716797 +67.833038 -23.254808 100.779701 +39.877193 -23.254808 130.823112 +39.877193 -23.254808 23.716797 +62.144539 -23.254814 3.300064 +62.144539 -35.842449 3.300064 +39.877197 -35.842445 3.300079 +39.877197 -23.254810 3.300079 +-73.948090 -45.443611 130.823112 +-39.877193 -45.443611 130.823112 +-39.877193 -45.443619 110.171623 +-73.948112 -45.443619 110.171623 +-39.877193 -39.073685 100.779701 +-67.833038 -39.073685 100.779701 +-63.734142 -35.842438 23.716797 +-63.734142 -23.254808 23.716797 +-67.833038 -23.254808 100.779701 +-73.948090 -23.254808 130.823112 +-39.877193 -23.254808 130.823112 +-39.877193 -35.842438 23.716797 +-73.948112 -23.254808 110.171623 +-39.877193 -23.254808 23.716797 +-62.144539 -23.254814 3.300064 +-62.144539 -35.842449 3.300064 +-39.877197 -35.842445 3.300079 +-39.877197 -23.254810 3.300079 +73.948090 45.443619 130.823112 +39.877193 45.443619 130.823112 +39.877193 45.443623 110.171623 +73.948112 45.443623 110.171623 +39.877193 39.073692 100.779701 +67.833038 39.073692 100.779701 +63.734142 35.842445 23.716797 +63.734142 23.254814 23.716797 +67.833038 23.254814 100.779701 +73.948090 23.254814 130.823112 +39.877193 23.254814 130.823112 +39.877193 35.842445 23.716797 +73.948112 23.254814 110.171623 +39.877193 23.254814 23.716797 +62.144539 23.254820 3.300064 +62.144539 35.842453 3.300064 +39.877197 35.842453 3.300079 +39.877197 23.254818 3.300079 +-73.948090 45.443619 130.823112 +-73.948112 45.443623 110.171623 +-39.877193 45.443623 110.171623 +-39.877193 45.443619 130.823112 +-67.833038 39.073692 100.779701 +-39.877193 39.073692 100.779701 +-67.833038 23.254814 100.779701 +-63.734142 23.254814 23.716797 +-63.734142 35.842445 23.716797 +-39.877193 23.254814 130.823112 +-73.948090 23.254814 130.823112 +-39.877193 35.842445 23.716797 +-73.948112 23.254814 110.171623 +-39.877193 23.254814 23.716797 +-62.144539 23.254820 3.300064 +-39.877197 23.254818 3.300079 +-39.877197 35.842453 3.300079 +-62.144539 35.842453 3.300064 + + + + + + + + + + + +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -0.827605 -0.561311 +0.000000 -0.827605 -0.561311 +0.000000 -0.827605 -0.561311 +0.000000 -0.827605 -0.561311 +0.000000 -0.827605 -0.561311 +0.000000 -0.827605 -0.561311 +0.998588 0.000000 -0.053114 +0.998588 0.000000 -0.053114 +0.998589 0.000000 -0.053114 +0.998589 0.000000 -0.053114 +0.998588 0.000000 -0.053114 +0.998589 0.000000 -0.053114 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -0.999122 -0.041893 +0.000000 -0.999122 -0.041893 +0.000000 -0.999122 -0.041893 +0.000000 -0.999122 -0.041893 +0.000000 -0.999122 -0.041893 +0.000000 -0.999122 -0.041893 +1.000000 0.000000 0.000001 +1.000000 0.000000 0.000001 +1.000000 0.000000 0.000001 +1.000000 0.000000 0.000001 +1.000000 0.000000 0.000001 +1.000000 0.000000 0.000001 +0.838022 0.000000 -0.545636 +0.838022 0.000000 -0.545636 +0.838022 0.000000 -0.545636 +0.838022 0.000000 -0.545636 +0.838022 0.000000 -0.545636 +0.838022 0.000000 -0.545636 +-0.000001 0.000000 -1.000000 +-0.000001 0.000000 -1.000000 +-0.000001 0.000000 -1.000000 +-0.000001 0.000000 -1.000000 +-0.000001 0.000000 -1.000000 +-0.000001 0.000000 -1.000000 +0.996983 0.000000 -0.077623 +0.996983 0.000000 -0.077623 +0.996983 0.000000 -0.077623 +0.996983 0.000000 -0.077623 +0.996983 0.000000 -0.077623 +0.996983 0.000000 -0.077623 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-0.000000 -1.000000 0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -0.827605 -0.561311 +0.000000 -0.827605 -0.561311 +0.000000 -0.827605 -0.561311 +0.000000 -0.827605 -0.561311 +0.000000 -0.827605 -0.561311 +0.000000 -0.827605 -0.561311 +-0.998588 0.000000 -0.053114 +-0.998588 0.000000 -0.053114 +-0.998589 0.000000 -0.053114 +-0.998589 0.000000 -0.053114 +-0.998589 0.000000 -0.053114 +-0.998588 0.000000 -0.053114 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -0.827605 -0.561311 +0.000000 -0.827605 -0.561311 +0.000000 -0.827605 -0.561311 +0.000000 -0.827605 -0.561311 +0.000000 -0.827605 -0.561311 +0.000000 -0.827605 -0.561311 +0.000000 -0.999122 -0.041893 +0.000000 -0.999122 -0.041893 +0.000000 -0.999122 -0.041893 +0.000000 -0.999122 -0.041893 +0.000000 -0.999122 -0.041893 +0.000000 -0.999122 -0.041893 +-1.000000 0.000000 0.000001 +-1.000000 0.000000 0.000001 +-1.000000 0.000000 0.000001 +-1.000000 0.000000 0.000001 +-1.000000 0.000000 0.000001 +-1.000000 0.000000 0.000001 +-0.838022 0.000000 -0.545636 +-0.838022 0.000000 -0.545636 +-0.838022 0.000000 -0.545636 +-0.838022 0.000000 -0.545636 +-0.838022 0.000000 -0.545636 +-0.838022 0.000000 -0.545636 +-0.998589 0.000000 -0.053114 +-0.998589 0.000000 -0.053114 +-0.998589 0.000000 -0.053114 +-0.998589 0.000000 -0.053114 +-0.998589 0.000000 -0.053114 +-0.998589 0.000000 -0.053114 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +-0.996983 0.000000 -0.077623 +-0.996983 0.000000 -0.077623 +-0.996983 0.000000 -0.077623 +-0.996983 0.000000 -0.077623 +-0.996983 0.000000 -0.077623 +-0.996983 0.000000 -0.077623 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +-0.000000 1.000000 -0.000000 +-0.000000 1.000000 -0.000000 +-0.000000 1.000000 -0.000000 +-0.000000 1.000000 -0.000000 +-0.000000 1.000000 -0.000000 +-0.000000 1.000000 -0.000000 +0.000000 -0.999122 -0.041893 +0.000000 -0.999122 -0.041893 +0.000000 -0.999122 -0.041893 +0.000000 -0.999122 -0.041893 +0.000000 -0.999122 -0.041893 +0.000000 -0.999122 -0.041893 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.838022 0.000000 -0.545636 +0.838022 0.000000 -0.545636 +0.838022 0.000000 -0.545636 +0.838022 0.000000 -0.545636 +0.838022 0.000000 -0.545636 +0.838022 0.000000 -0.545636 +-1.000000 0.000000 0.000001 +-1.000000 0.000000 0.000001 +-1.000000 0.000000 0.000001 +-1.000000 0.000000 0.000001 +-1.000000 0.000000 0.000001 +-1.000000 0.000000 0.000001 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.827605 -0.561311 +0.000000 0.827605 -0.561311 +0.000000 0.827605 -0.561311 +0.000000 0.827605 -0.561311 +0.000000 0.827605 -0.561311 +0.000000 0.827605 -0.561311 +0.998588 0.000000 -0.053114 +0.998588 0.000000 -0.053114 +0.998589 0.000000 -0.053114 +0.998589 0.000000 -0.053114 +0.998589 0.000000 -0.053114 +0.998588 0.000000 -0.053114 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.999122 -0.041893 +0.000000 0.999122 -0.041893 +0.000000 0.999122 -0.041893 +0.000000 0.999122 -0.041893 +0.000000 0.999122 -0.041893 +0.000000 0.999122 -0.041893 +1.000000 0.000000 0.000001 +1.000000 0.000000 0.000001 +1.000000 0.000000 0.000001 +1.000000 0.000000 0.000001 +1.000000 0.000000 0.000001 +1.000000 0.000000 0.000001 +0.838022 0.000000 -0.545636 +0.838022 0.000000 -0.545636 +0.838022 0.000000 -0.545636 +0.838022 0.000000 -0.545636 +0.838022 0.000000 -0.545636 +0.838022 0.000000 -0.545636 +0.998589 0.000000 -0.053114 +0.998589 0.000000 -0.053114 +0.998589 0.000000 -0.053114 +0.998589 0.000000 -0.053114 +0.998589 0.000000 -0.053114 +0.998589 0.000000 -0.053114 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.000001 0.000000 -1.000000 +-0.000001 0.000000 -1.000000 +-0.000001 0.000000 -1.000000 +-0.000001 0.000000 -1.000000 +-0.000001 0.000000 -1.000000 +-0.000001 0.000000 -1.000000 +0.996983 0.000000 -0.077623 +0.996983 0.000000 -0.077623 +0.996983 0.000000 -0.077623 +0.996983 0.000000 -0.077623 +0.996983 0.000000 -0.077623 +0.996983 0.000000 -0.077623 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +0.000000 -1.000000 -0.000000 +0.000000 -1.000000 -0.000000 +0.000000 -1.000000 -0.000000 +0.000000 -1.000000 -0.000000 +0.000000 -1.000000 -0.000000 +0.000000 -1.000000 -0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.999122 -0.041893 +0.000000 0.999122 -0.041893 +0.000000 0.999122 -0.041893 +0.000000 0.999122 -0.041893 +0.000000 0.999122 -0.041893 +0.000000 0.999122 -0.041893 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.827605 -0.561311 +0.000000 0.827605 -0.561311 +0.000000 0.827605 -0.561311 +0.000000 0.827605 -0.561311 +0.000000 0.827605 -0.561311 +0.000000 0.827605 -0.561311 +-0.998588 0.000000 -0.053114 +-0.998588 0.000000 -0.053114 +-0.998589 0.000000 -0.053114 +-0.998589 0.000000 -0.053114 +-0.998588 0.000000 -0.053114 +-0.998589 0.000000 -0.053114 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.827605 -0.561311 +0.000000 0.827605 -0.561311 +0.000000 0.827605 -0.561311 +0.000000 0.827605 -0.561311 +0.000000 0.827605 -0.561311 +0.000000 0.827605 -0.561311 +0.000000 0.999122 -0.041893 +0.000000 0.999122 -0.041893 +0.000000 0.999122 -0.041893 +0.000000 0.999122 -0.041893 +0.000000 0.999122 -0.041893 +0.000000 0.999122 -0.041893 +-1.000000 0.000000 0.000001 +-1.000000 0.000000 0.000001 +-1.000000 0.000000 0.000001 +-1.000000 0.000000 0.000001 +-1.000000 0.000000 0.000001 +-1.000000 0.000000 0.000001 +-0.838022 0.000000 -0.545636 +-0.838022 0.000000 -0.545636 +-0.838022 0.000000 -0.545636 +-0.838022 0.000000 -0.545636 +-0.838022 0.000000 -0.545636 +-0.838022 0.000000 -0.545636 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +-0.996983 0.000000 -0.077623 +-0.996983 0.000000 -0.077623 +-0.996983 0.000000 -0.077623 +-0.996983 0.000000 -0.077623 +-0.996983 0.000000 -0.077623 +-0.996983 0.000000 -0.077623 +-0.000000 1.000000 0.000000 +-0.000000 1.000000 0.000000 +-0.000000 1.000000 0.000000 +-0.000000 1.000000 0.000000 +-0.000000 1.000000 0.000000 +-0.000000 1.000000 0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 -0.000000 +-0.000000 -1.000000 -0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000001 +1.000000 0.000000 0.000001 +1.000000 0.000000 0.000001 +1.000000 0.000000 0.000001 +1.000000 0.000000 0.000001 +1.000000 0.000000 0.000001 +-0.838022 0.000000 -0.545636 +-0.838022 0.000000 -0.545636 +-0.838022 0.000000 -0.545636 +-0.838022 0.000000 -0.545636 +-0.838022 0.000000 -0.545636 +-0.838022 0.000000 -0.545636 + + + + + + + + + + + +1.000000 0.000000 +1.000000 0.000000 +1.000000 0.000000 +1.000000 0.000000 +0.500000 0.000000 +0.500000 0.000000 +0.500000 0.000000 +0.500000 0.000000 +1.000000 0.500000 +1.000000 0.500000 +1.000000 0.500000 +1.000000 0.500000 +0.500000 0.500000 +0.500000 0.500000 +1.000000 0.500000 +1.000000 0.000000 +0.500000 0.000000 +0.500000 0.500000 +0.500000 0.750000 +1.000000 0.758827 +1.000000 0.750000 +0.250000 0.000000 +0.250000 0.000000 +0.244569 0.500000 +0.244569 0.750000 +0.244569 0.000000 +0.246922 0.000000 +0.263138 0.000000 +0.263138 0.000000 +0.263138 0.500000 +0.239137 0.500000 +0.239137 0.750000 +0.250000 0.000000 +1.000000 0.000000 +0.500000 0.000000 +0.500000 0.000000 +1.000000 0.000000 +1.000000 0.750000 +0.500000 0.000000 +1.000000 0.000000 +1.000000 0.000000 +1.000000 0.500000 +1.000000 0.500000 +1.000000 0.500000 +0.500000 0.500000 +0.263138 0.000000 +0.263138 0.000000 +0.250000 0.000000 +0.250000 0.000000 +0.500000 0.000000 +1.000000 0.750000 +0.500000 0.758827 +1.000000 0.500000 +0.500000 0.500000 +0.244569 0.000000 +0.250000 0.500000 +1.000000 0.500000 +1.000000 0.000000 +0.500000 0.000000 +0.500000 0.500000 +0.244569 0.758827 +0.239137 0.000000 +0.244569 0.500000 +0.239137 0.750000 +0.246922 0.000000 +0.263138 0.500000 +0.500000 0.758827 +1.000000 0.729501 +1.000000 0.729501 +0.500000 0.729501 +1.000000 0.767654 +1.000000 0.756892 +1.000000 0.750000 +0.244569 0.761770 +0.239137 0.767654 +0.239137 0.767654 +1.000000 0.750000 +1.000000 0.753446 +1.000000 0.758827 +0.500000 0.767654 +1.000000 0.729501 +0.500000 0.729501 +1.000000 0.729500 +0.250000 0.767654 +0.263138 0.729501 +0.263138 0.729501 +1.000000 0.000000 +0.500000 0.000000 +0.500000 0.000000 +1.000000 0.000000 +0.500000 0.000000 +1.000000 0.000000 +1.000000 0.000000 +1.000000 0.500000 +1.000000 0.500000 +1.000000 0.500000 +0.500000 0.500000 +0.263138 0.000000 +0.263138 0.000000 +0.250000 0.000000 +0.248461 0.000000 +0.500000 0.000000 +1.000000 0.500000 +1.000000 0.750000 +1.000000 0.750000 +0.500000 0.500000 +0.244569 0.000000 +0.250000 0.500000 +1.000000 0.729501 +0.500000 0.729501 +1.000000 0.500000 +1.000000 0.000000 +0.500000 0.000000 +0.500000 0.500000 +0.500000 0.758827 +0.250000 0.750000 +1.000000 0.758827 +1.000000 0.756892 +0.239137 0.000000 +0.244569 0.500000 +0.239137 0.750000 +0.246922 0.000000 +0.263138 0.500000 +0.263138 0.729501 +1.000000 0.000000 +1.000000 0.000000 +0.500000 0.000000 +0.500000 0.000000 +1.000000 0.000000 +0.500000 0.000000 +1.000000 0.500000 +1.000000 0.500000 +1.000000 0.000000 +0.500000 0.500000 +1.000000 0.500000 +0.263138 0.000000 +0.263138 0.000000 +0.250000 0.000000 +0.250000 0.000000 +0.500000 0.000000 +1.000000 0.500000 +1.000000 0.753446 +1.000000 0.758827 +0.500000 0.500000 +0.244569 0.500000 +0.250000 0.000000 +0.500000 0.729501 +1.000000 0.729501 +1.000000 0.500000 +0.500000 0.500000 +0.500000 0.000000 +1.000000 0.000000 +0.500000 0.750000 +0.250000 0.750000 +1.000000 0.756892 +1.000000 0.767654 +0.239137 0.500000 +0.244569 0.000000 +0.239137 0.750000 +0.248461 0.000000 +0.263138 0.500000 +0.263138 0.729501 +1.000000 0.750000 +0.500000 0.767654 +1.000000 0.729501 +0.244569 0.758827 +0.239137 0.767654 +1.000000 0.750000 +0.500000 0.758827 +1.000000 0.729500 +0.244569 0.758827 +0.239137 0.767654 +-0.010863 0.500000 +-0.009854 0.727779 +-0.008555 0.757142 +-0.008555 1.015969 +0.500000 1.017654 + + + + + + + + + + + +

0 0 0 5 1 5 1 2 1 5 3 5 0 4 0 4 5 4 7 6 7 3 7 3 5 8 5 1 9 1 5 10 5 3 11 3 3 12 3 2 13 2 11 14 11 11 15 11 2 16 2 10 17 10 12 18 12 0 19 0 8 20 8 0 21 0 12 22 12 4 23 4 7 24 7 2 25 2 3 26 3 2 27 2 7 28 7 6 29 6 8 30 8 0 31 0 9 32 9 0 33 0 1 34 1 9 35 9 3 36 3 9 37 9 1 38 1 9 39 9 3 40 3 11 41 11 16 42 16 14 43 14 15 44 15 14 45 14 16 46 16 17 47 17 2 48 2 14 49 14 10 50 10 14 51 14 2 52 2 15 53 15 6 54 6 15 55 15 2 56 2 15 57 15 6 58 6 16 59 16 13 60 13 17 61 17 6 62 6 6 63 6 17 64 17 16 65 16 10 66 10 14 67 14 13 68 13 13 69 13 14 70 14 17 71 17 28 72 44 4 73 4 12 74 12 4 75 4 28 76 44 19 77 34 18 78 33 20 79 35 19 80 34 20 81 35 18 82 33 21 83 36 20 84 35 21 85 36 23 86 39 20 87 35 23 88 39 22 89 38 24 90 40 23 91 39 26 92 42 26 93 42 25 94 41 24 95 40 27 96 43 18 97 33 28 98 44 28 99 44 18 100 33 19 101 34 4 102 4 19 103 34 20 104 35 4 105 4 20 106 35 5 107 5 22 108 38 5 109 5 20 110 35 5 111 5 22 112 38 7 113 7 23 114 39 24 115 40 22 116 38 22 117 38 24 118 40 29 119 49 18 120 33 27 121 43 30 122 52 18 123 33 30 124 52 21 125 36 21 126 36 30 127 52 23 128 39 30 129 52 26 130 42 23 131 39 60 132 130 25 133 41 26 134 42 25 135 41 60 136 130 61 137 131 6 138 6 29 139 49 31 140 53 6 141 6 31 142 53 13 143 13 34 144 58 32 145 56 35 146 59 32 147 56 34 148 58 33 149 57 24 150 40 32 151 56 33 152 57 32 153 56 24 154 40 25 155 41 29 156 49 33 157 57 34 158 58 33 159 57 29 160 49 24 161 40 31 162 53 29 163 49 35 164 59 29 165 49 34 166 58 35 167 59 25 168 41 31 169 53 32 170 56 31 171 53 35 172 59 32 173 56 22 174 38 6 175 6 7 176 7 6 177 6 22 178 38 29 179 49 63 180 133 28 181 44 46 182 96 46 183 96 28 184 44 12 185 12 9 186 9 44 187 94 48 188 102 44 189 94 9 190 9 11 191 11 64 192 134 30 193 52 27 194 43 30 195 52 64 196 134 66 197 140 36 198 86 38 199 88 37 200 87 38 201 88 36 202 86 39 203 89 38 204 88 39 205 89 41 206 91 38 207 88 41 208 91 40 209 90 42 210 92 41 211 91 44 212 94 44 213 94 43 214 93 42 215 92 36 216 86 37 217 87 46 218 96 36 219 86 46 220 96 45 221 95 41 222 91 42 223 92 40 224 90 40 225 90 42 226 92 47 227 101 36 228 86 45 229 95 48 230 102 36 231 86 48 232 102 39 233 89 39 234 89 48 235 102 41 236 91 48 237 102 44 238 94 41 239 91 11 240 11 43 241 93 44 242 94 43 243 93 11 244 11 10 245 10 45 246 95 46 247 96 8 248 8 46 249 96 12 250 12 8 251 8 52 252 112 50 253 110 53 254 113 50 255 110 52 256 112 51 257 111 42 258 92 50 259 110 51 260 111 50 261 110 42 262 92 43 263 93 47 264 101 51 265 111 52 266 112 51 267 111 47 268 101 42 269 92 49 270 105 47 271 101 53 272 113 47 273 101 52 274 112 53 275 113 43 276 93 49 277 105 50 278 110 49 279 105 53 280 113 50 281 110 31 282 172 67 283 175 13 284 13 13 285 13 67 286 175 49 287 176 43 288 93 10 289 10 13 290 13 13 291 13 49 292 105 43 293 93 40 294 90 65 295 139 59 296 129 65 297 139 40 298 90 47 299 101 37 300 87 57 301 127 63 302 133 37 303 87 63 304 133 46 305 96 54 306 124 56 307 126 55 308 125 56 309 126 54 310 124 57 311 127 59 312 129 58 313 128 56 314 126 55 315 125 56 316 126 58 317 128 58 318 128 62 319 132 60 320 130 60 321 130 62 322 132 61 323 131 57 324 127 54 325 124 63 326 133 54 327 124 64 328 134 63 329 133 38 330 88 56 331 126 37 332 87 57 333 127 37 334 87 56 335 126 40 336 90 59 337 129 38 338 88 56 339 126 38 340 88 59 341 129 59 342 129 62 343 132 58 344 128 62 345 132 59 346 129 65 347 139 64 348 134 54 349 124 66 350 140 54 351 124 55 352 125 66 353 140 58 354 128 66 355 140 55 356 125 66 357 140 58 358 128 60 359 130 49 360 105 67 361 143 65 362 139 49 363 105 65 364 139 47 365 101 63 366 133 64 367 134 28 368 44 64 369 134 27 370 43 28 371 44 68 372 148 70 373 150 69 374 149 70 375 150 68 376 148 71 377 151 62 378 132 68 379 148 61 380 131 68 381 148 62 382 132 71 383 151 65 384 139 71 385 151 62 386 132 71 387 151 65 388 139 70 389 150 67 390 143 69 391 149 65 392 139 65 393 139 69 394 149 70 395 150 61 396 131 68 397 148 67 398 143 67 399 143 68 400 148 69 401 149 25 402 41 67 403 143 31 404 53 67 405 143 25 406 41 61 407 131 45 408 95 8 409 8 9 410 9 45 411 95 9 412 9 48 413 102 60 414 130 26 415 42 66 416 140 30 417 52 66 418 140 26 419 42

+
+
+
+ + + 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.0000001.000000 + 30.0000000.0000003.333333 + + + + + +
diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_TrashCanC_01/meshes/aws_robomaker_warehouse_TrashCanC_01_visual.DAE b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_TrashCanC_01/meshes/aws_robomaker_warehouse_TrashCanC_01_visual.DAE new file mode 100755 index 0000000..4a1b714 --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_TrashCanC_01/meshes/aws_robomaker_warehouse_TrashCanC_01_visual.DAE @@ -0,0 +1,5186 @@ + + + FBX COLLADA exporter2019-05-24T10:41:56Z2019-05-24T10:41:56ZZ_UP + + + ../materials/textures/aws_robomaker_warehouse_TrashCanC_01.png + + + + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + +71.401909 -39.300514 124.688263 +71.401924 41.480721 124.688271 +71.401909 -39.300526 119.246025 +65.696968 44.532944 119.246033 +65.795555 -20.014954 124.688263 +65.795555 -20.014954 129.204849 +71.364082 -33.759178 129.204865 +71.364090 41.486977 129.204865 +71.364082 -33.759178 130.572052 +65.795578 44.484856 124.688271 +65.795578 44.484856 129.204880 +65.088181 -42.352749 124.688263 +71.401924 41.480721 119.246033 +59.481823 -31.953896 124.688263 +59.481823 -31.953896 129.204865 +65.050354 -36.811394 129.204865 +71.364090 41.486965 130.572052 +69.823471 -41.589695 124.688263 +70.000336 43.757866 124.688271 +69.823471 -41.589695 119.246025 +69.975677 43.769882 119.246033 +62.286385 -26.238655 124.688263 +62.286385 -26.238655 129.204849 +69.785652 -36.048340 129.204865 +69.971970 43.762566 129.204865 +69.785652 -36.048340 130.572052 +69.806374 43.776142 130.572052 +38.155067 44.532944 119.246033 +28.887484 44.532944 119.246033 +28.887484 44.484856 124.688271 +38.155067 44.484856 124.688271 +28.887484 44.484856 129.204880 +38.155067 44.484856 129.204880 +65.133194 44.539200 130.572052 +65.088181 -42.352749 119.246025 +65.050354 -36.811394 130.572052 +0.000000 44.532944 119.246033 +0.000000 44.539200 130.572052 +38.155064 38.942123 119.246033 +28.887480 38.942123 119.246033 +28.887480 38.894035 124.688271 +38.155064 38.894035 124.688271 +28.887480 38.894035 129.204880 +38.155064 38.894035 129.204880 +-71.401909 -39.300526 119.246025 +-71.401924 41.480721 119.246033 +-71.401924 41.480721 124.688271 +-71.401909 -39.300514 124.688263 +-28.887484 44.532944 119.246033 +-28.887484 44.484856 124.688271 +-70.000336 43.757866 124.688271 +-65.795578 44.484856 124.688271 +-65.795555 -20.014954 124.688263 +-65.795555 -20.014954 129.204849 +-28.887484 44.484856 129.204880 +-65.795578 44.484856 129.204880 +-69.971970 43.762566 129.204865 +-71.364090 41.486977 129.204865 +-71.364082 -33.759178 129.204865 +-71.364090 41.486965 130.572052 +-71.364082 -33.759178 130.572052 +-65.696968 44.532944 119.246033 +-59.481823 -31.953896 124.688263 +-65.088181 -42.352749 124.688263 +-59.481823 -31.953896 129.204865 +-65.050354 -36.811394 129.204865 +-65.133194 44.539200 130.572052 +-65.088181 -42.352749 119.246025 +-69.823471 -41.589695 119.246025 +-69.823471 -41.589695 124.688263 +-69.975677 43.769882 119.246033 +-62.286385 -26.238655 124.688263 +-62.286385 -26.238655 129.204849 +-69.785652 -36.048340 129.204865 +-69.785652 -36.048340 130.572052 +-65.050354 -36.811394 130.572052 +-69.806374 43.776142 130.572052 +-38.155067 44.484856 124.688271 +-38.155067 44.532944 119.246033 +-38.155067 44.484856 129.204880 +-38.155064 38.894035 129.204880 +-28.887480 38.894035 129.204880 +-28.887480 38.894035 124.688271 +-28.887480 38.942123 119.246033 +-38.155064 38.942123 119.246033 +-38.155064 38.894035 124.688271 +-58.682518 -35.234798 24.205990 +58.682518 -35.234798 24.205990 +-63.082516 30.834759 24.205990 +63.082516 30.834759 24.205990 +-62.344437 -37.280159 114.311317 +66.744438 -32.880165 114.311317 +-66.744438 32.880127 114.311317 +62.344437 37.280117 114.311317 +-67.875870 -44.578415 111.675568 +72.275864 -40.178425 111.675568 +-72.275864 40.178383 111.675568 +67.875870 44.578373 111.675568 +-67.875854 -44.578407 119.486084 +72.275856 -40.178406 119.486084 +-72.275856 40.178371 119.486084 +67.875854 44.578373 119.486084 +-61.537354 -25.933434 119.486061 +57.137352 -30.333424 119.486061 +-57.137352 30.333387 119.486061 +61.537354 25.933397 119.486061 +-63.082516 -30.834793 24.205990 +63.082516 -30.834793 24.205990 +-58.682518 35.234760 24.205990 +58.682518 35.234760 24.205990 +-66.744438 -32.880165 114.311317 +62.344437 -37.280159 114.311317 +-62.344437 37.280117 114.311317 +66.744438 32.880127 114.311317 +-72.275864 -40.178425 111.675568 +67.875870 -44.578415 111.675568 +-67.875870 44.578373 111.675568 +72.275864 40.178383 111.675568 +-72.275856 -40.178406 119.486084 +67.875854 -44.578407 119.486084 +-67.875854 44.578373 119.486084 +72.275856 40.178371 119.486084 +-57.137352 -30.333424 119.486061 +61.537354 -25.933434 119.486061 +-61.537354 25.933397 119.486061 +57.137352 30.333387 119.486061 +-61.982513 -34.134792 24.205990 +61.982513 -34.134792 24.205990 +-61.982513 34.134758 24.205990 +61.982513 34.134758 24.205990 +-65.644440 -36.180161 114.311317 +65.644440 -36.180161 114.311317 +-65.644440 36.180126 114.311317 +65.644440 36.180126 114.311317 +-71.175873 -43.478416 111.675568 +71.175873 -43.478416 111.675568 +-71.175873 43.478382 111.675568 +71.175873 43.478382 111.675568 +-71.175858 -43.478405 119.486084 +71.175858 -43.478405 119.486084 +-71.175858 43.478371 119.486084 +71.175858 43.478371 119.486084 +-60.437359 -29.233433 119.486061 +60.437359 -29.233433 119.486061 +-60.437359 29.233397 119.486061 +60.437359 29.233397 119.486061 +50.893700 36.303509 98.584373 +52.939297 36.303509 98.584373 +50.893700 36.303509 114.288940 +52.939297 36.303509 114.288940 +50.893700 43.803059 114.288940 +52.939297 43.803059 114.288940 +37.914577 36.303509 98.584373 +39.960175 36.303509 98.584373 +37.914577 36.303509 114.288940 +39.960175 36.303509 114.288940 +37.914577 43.803059 114.288940 +39.960175 43.803059 114.288940 +24.935450 36.303509 98.584373 +26.981047 36.303509 98.584373 +24.935450 36.303509 114.288940 +26.981047 36.303509 114.288940 +24.935450 43.803059 114.288940 +26.981047 43.803059 114.288940 +11.956321 36.303509 98.584373 +14.001920 36.303509 98.584373 +11.956321 36.303509 114.288940 +14.001920 36.303509 114.288940 +11.956321 43.803059 114.288940 +14.001920 43.803059 114.288940 +1.022792 36.303509 98.584373 +1.022792 36.303509 114.288940 +1.022792 43.803059 114.288940 +-52.939301 36.303509 98.584373 +-52.939301 43.803059 114.288940 +-52.939301 36.303509 114.288940 +-50.893707 36.303509 98.584373 +-50.893707 43.803059 114.288940 +-50.893707 36.303509 114.288940 +-39.960190 36.303509 98.584373 +-39.960190 43.803059 114.288940 +-39.960190 36.303509 114.288940 +-37.914589 36.303509 98.584373 +-37.914589 43.803059 114.288940 +-37.914589 36.303509 114.288940 +-26.981058 36.303509 98.584373 +-26.981058 43.803059 114.288940 +-26.981058 36.303509 114.288940 +-24.935457 36.303509 98.584373 +-24.935457 43.803059 114.288940 +-24.935457 36.303509 114.288940 +-14.001928 36.303509 98.584373 +-14.001928 43.803059 114.288940 +-14.001928 36.303509 114.288940 +-11.956332 36.303509 98.584373 +-11.956332 43.803059 114.288940 +-11.956332 36.303509 114.288940 +-1.022804 36.303509 114.288940 +-0.511402 36.303509 98.584373 +-1.022804 43.803059 114.288940 +52.939297 -36.303551 98.584373 +52.939297 -43.803101 114.288940 +52.939297 -36.303551 114.288940 +50.893700 -36.303551 98.584373 +50.893700 -43.803101 114.288940 +50.893700 -36.303551 114.288940 +39.960175 -36.303551 98.584373 +39.960175 -43.803101 114.288940 +39.960175 -36.303551 114.288940 +37.914577 -36.303551 98.584373 +37.914577 -43.803101 114.288940 +37.914577 -36.303551 114.288940 +26.981047 -36.303551 98.584373 +26.981047 -43.803101 114.288940 +26.981047 -36.303551 114.288940 +24.935450 -36.303551 98.584373 +24.935450 -43.803101 114.288940 +24.935450 -36.303551 114.288940 +14.001920 -36.303551 98.584373 +14.001920 -43.803101 114.288940 +14.001920 -36.303551 114.288940 +11.956321 -36.303551 98.584373 +11.956321 -43.803101 114.288940 +11.956321 -36.303551 114.288940 +1.022792 -36.303551 98.584373 +1.022792 -43.803101 114.288940 +1.022792 -36.303551 114.288940 +-1.022804 -43.803101 114.288940 +-52.939301 -36.303551 98.584373 +-52.939301 -36.303551 114.288940 +-52.939301 -43.803101 114.288940 +-50.893707 -43.803101 114.288940 +-50.893707 -36.303551 98.584373 +-50.893707 -36.303551 114.288940 +-39.960190 -36.303551 98.584373 +-39.960190 -36.303551 114.288940 +-39.960190 -43.803101 114.288940 +-37.914589 -43.803101 114.288940 +-37.914589 -36.303551 98.584373 +-37.914589 -36.303551 114.288940 +-26.981058 -36.303551 98.584373 +-26.981058 -36.303551 114.288940 +-26.981058 -43.803101 114.288940 +-24.935457 -43.803101 114.288940 +-24.935457 -36.303551 98.584373 +-24.935457 -36.303551 114.288940 +-14.001928 -36.303551 98.584373 +-14.001928 -36.303551 114.288940 +-14.001928 -43.803101 114.288940 +-11.956332 -43.803101 114.288940 +-11.956332 -36.303551 98.584373 +-11.956332 -36.303551 114.288940 +-0.511402 -36.303551 98.584373 +-1.022804 -36.303551 114.288940 +-64.623444 14.001894 98.584373 +-72.122993 14.001894 114.288940 +-64.623444 14.001894 114.288940 +-64.623444 11.956286 98.584373 +-72.122993 11.956286 114.288940 +-64.623444 11.956286 114.288940 +-64.623444 1.022792 98.584373 +-72.122993 1.022792 114.288940 +-64.623444 1.022792 114.288940 +-64.623444 -1.022828 98.584373 +-72.122993 -1.022828 114.288940 +-64.623444 -1.022828 114.288940 +-64.623444 -11.956358 98.584373 +-72.122993 -11.956358 114.288940 +-64.623444 -11.956358 114.288940 +-64.623444 -14.001966 98.584373 +-72.122993 -14.001966 114.288940 +-64.623444 -14.001966 114.288940 +64.623444 14.001894 98.584373 +72.122993 14.001894 114.288940 +64.623444 14.001894 114.288940 +64.623444 11.956286 98.584373 +72.122993 11.956286 114.288940 +64.623444 11.956286 114.288940 +64.623444 1.022792 98.584373 +72.122993 1.022792 114.288940 +64.623444 1.022792 114.288940 +64.623444 -1.022828 98.584373 +72.122993 -1.022828 114.288940 +64.623444 -1.022828 114.288940 +64.623444 -11.956358 98.584373 +72.122993 -11.956358 114.288940 +64.623444 -11.956358 114.288940 +64.623444 -14.001966 98.584373 +72.122993 -14.001966 114.288940 +64.623444 -14.001966 114.288940 +60.347473 -30.725693 13.085787 +59.774971 -30.725693 9.838970 +58.126526 -30.725693 6.983769 +55.600948 -30.725693 4.864561 +52.502869 -30.725693 3.736954 +49.205967 -30.725693 3.736954 +46.107891 -30.725693 4.864562 +43.582321 -30.725693 6.983769 +41.933868 -30.725693 9.838970 +41.361366 -30.725693 13.085785 +41.933868 -30.725693 16.332600 +43.582317 -30.725693 19.187801 +46.107891 -30.725693 21.307009 +49.205963 -30.725693 22.434618 +52.502865 -30.725693 22.434618 +55.600948 -30.725693 21.307014 +58.126514 -30.725693 19.187807 +59.774971 -30.725693 16.332607 +60.347473 -25.927771 13.085786 +59.774971 -25.927771 9.838970 +58.126526 -25.927771 6.983769 +55.600948 -25.927771 4.864561 +52.502869 -25.927771 3.736954 +49.205967 -25.927771 3.736954 +46.107891 -25.927771 4.864562 +43.582321 -25.927771 6.983769 +41.933868 -25.927771 9.838970 +41.361366 -25.927771 13.085784 +41.933868 -25.927771 16.332600 +43.582317 -25.927771 19.187801 +46.107891 -25.927771 21.307009 +49.205963 -25.927771 22.434618 +52.502865 -25.927771 22.434618 +55.600948 -25.927771 21.307014 +58.126514 -25.927771 19.187807 +59.774971 -25.927771 16.332607 +-60.347462 -30.725693 13.085787 +-59.774979 -30.725693 9.838970 +-59.774979 -25.927771 9.838970 +-60.347462 -25.927771 13.085786 +-58.126534 -30.725693 6.983769 +-58.126534 -25.927771 6.983769 +-55.600937 -30.725693 4.864561 +-55.600937 -25.927771 4.864561 +-52.502869 -30.725693 3.736954 +-52.502869 -25.927771 3.736954 +-49.205963 -30.725693 3.736954 +-49.205963 -25.927771 3.736954 +-46.107899 -30.725693 4.864562 +-46.107899 -25.927771 4.864562 +-43.582314 -30.725693 6.983769 +-43.582314 -25.927771 6.983769 +-41.933857 -30.725693 9.838970 +-41.933857 -25.927771 9.838970 +-41.361366 -30.725693 13.085785 +-41.361366 -25.927771 13.085784 +-41.933857 -30.725693 16.332600 +-41.933857 -25.927771 16.332600 +-43.582314 -30.725693 19.187801 +-43.582314 -25.927771 19.187801 +-46.107887 -30.725693 21.307009 +-46.107887 -25.927771 21.307009 +-49.205963 -30.725693 22.434618 +-49.205963 -25.927771 22.434618 +-52.502865 -30.725693 22.434618 +-52.502865 -25.927771 22.434618 +-55.600937 -30.725693 21.307014 +-55.600937 -25.927771 21.307014 +-58.126514 -30.725693 19.187807 +-58.126514 -25.927771 19.187807 +-59.774979 -30.725693 16.332607 +-59.774979 -25.927771 16.332607 +60.347473 30.725647 13.085784 +59.774971 30.725647 9.838969 +59.774971 25.927723 9.838969 +60.347473 25.927723 13.085784 +58.126526 30.725647 6.983766 +58.126526 25.927723 6.983767 +55.600948 30.725647 4.864559 +55.600948 25.927723 4.864559 +52.502869 30.725647 3.736951 +52.502869 25.927723 3.736951 +49.205967 30.725647 3.736951 +49.205967 25.927723 3.736951 +46.107895 30.725647 4.864560 +46.107895 25.927723 4.864560 +43.582317 30.725647 6.983766 +43.582317 25.927723 6.983767 +41.933868 30.725647 9.838967 +41.933868 25.927723 9.838967 +41.361366 30.725647 13.085782 +41.361366 25.927723 13.085783 +41.933868 30.725647 16.332598 +41.933868 25.927723 16.332598 +43.582317 30.725647 19.187798 +43.582317 25.927723 19.187798 +46.107891 30.725647 21.307007 +46.107891 25.927723 21.307007 +49.205967 30.725647 22.434614 +49.205967 25.927723 22.434614 +52.502865 30.725647 22.434616 +52.502865 25.927723 22.434616 +55.600948 30.725647 21.307011 +55.600948 25.927723 21.307011 +58.126514 30.725647 19.187803 +58.126514 25.927723 19.187805 +59.774971 30.725647 16.332605 +59.774971 25.927723 16.332605 +-60.347462 30.725647 13.085784 +-60.347462 25.927723 13.085784 +-59.774979 25.927723 9.838969 +-59.774979 30.725647 9.838969 +-58.126534 25.927723 6.983767 +-58.126534 30.725647 6.983766 +-55.600937 25.927723 4.864559 +-55.600937 30.725647 4.864559 +-52.502869 25.927723 3.736951 +-52.502869 30.725647 3.736951 +-49.205963 25.927723 3.736951 +-49.205963 30.725647 3.736951 +-46.107899 25.927723 4.864560 +-46.107899 30.725647 4.864560 +-43.582314 25.927723 6.983767 +-43.582314 30.725647 6.983766 +-41.933857 25.927723 9.838967 +-41.933857 30.725647 9.838967 +-41.361366 25.927723 13.085783 +-41.361366 30.725647 13.085782 +-41.933857 25.927723 16.332598 +-41.933857 30.725647 16.332598 +-43.582314 25.927723 19.187798 +-43.582314 30.725647 19.187798 +-46.107887 25.927723 21.307007 +-46.107887 30.725647 21.307007 +-49.205963 25.927723 22.434614 +-49.205963 30.725647 22.434614 +-52.502865 25.927723 22.434616 +-52.502865 30.725647 22.434616 +-55.600937 25.927723 21.307011 +-55.600937 30.725647 21.307011 +-58.126514 25.927723 19.187805 +-58.126514 30.725647 19.187803 +-59.774979 25.927723 16.332605 +-59.774979 30.725647 16.332605 +49.165504 -31.833576 12.980597 +52.524448 -31.833576 12.980596 +49.165504 -24.726522 12.980600 +52.524448 -24.726522 12.980596 +51.956390 -31.833576 24.916767 +55.315327 -31.833576 24.916767 +51.956390 -24.726522 24.916767 +55.315327 -24.726522 24.916767 +49.725330 -24.726522 12.641880 +50.285149 -24.726522 12.438480 +50.844975 -24.726522 12.370875 +51.404797 -24.726522 12.438569 +51.964622 -24.726522 12.641838 +51.964622 -31.833576 12.641846 +51.404797 -31.833576 12.438583 +50.844975 -31.833576 12.370832 +50.285149 -31.833576 12.438583 +49.725330 -31.833576 12.641846 +49.165504 -31.549501 12.980596 +52.524448 -31.549501 12.980596 +49.165504 -25.010597 12.980596 +52.524448 -25.010597 12.980596 +51.956390 -31.549501 24.916767 +55.315327 -31.549501 24.916767 +51.956390 -25.010597 24.916767 +55.315327 -25.010597 24.916767 +49.725330 -25.010586 12.641838 +50.285149 -25.010597 12.438583 +50.844975 -25.010597 12.370832 +51.404797 -25.010597 12.438583 +51.964622 -25.010597 12.641838 +51.964622 -31.549501 12.641838 +51.404797 -31.549501 12.438583 +50.844975 -31.549501 12.370832 +50.285149 -31.549501 12.438583 +49.725330 -31.549501 12.641838 +52.037685 -31.619381 13.955422 +50.604675 -31.619381 13.433851 +50.303543 -31.619381 13.955422 +51.933098 -31.619381 14.548533 +52.037685 -24.876726 13.955422 +51.736553 -24.876726 13.433851 +51.170616 -24.876726 13.227865 +50.604675 -24.876726 13.433851 +50.303543 -24.876726 13.955422 +50.408127 -24.876726 14.548532 +50.869488 -24.876726 14.935658 +51.471745 -24.876726 14.935658 +51.933098 -24.876726 14.548533 +51.736553 -31.619381 13.433851 +51.170616 -31.619381 13.227865 +50.408127 -31.619381 14.548532 +50.869488 -31.619381 14.935658 +51.471745 -31.619381 14.935658 +-52.524448 -31.833576 12.980596 +-55.315334 -31.833576 24.916767 +-51.956390 -31.833576 24.916767 +-49.165504 -31.833576 12.980597 +-52.524448 -24.726522 12.980596 +-49.165504 -24.726522 12.980600 +-51.956390 -24.726522 24.916767 +-55.315334 -24.726522 24.916767 +-49.725327 -31.833576 12.641846 +-51.964615 -31.833576 12.641846 +-50.285156 -31.833576 12.438583 +-51.404785 -31.833576 12.438583 +-50.844975 -31.833576 12.370832 +-51.964615 -24.726522 12.641838 +-49.725327 -24.726522 12.641880 +-51.404785 -24.726522 12.438569 +-50.285156 -24.726522 12.438480 +-50.844975 -24.726522 12.370875 +-51.956390 -31.549501 24.916767 +-55.315334 -31.549501 24.916767 +-52.524448 -31.549501 12.980596 +-49.165504 -31.549501 12.980596 +-51.956390 -25.010597 24.916767 +-49.165504 -25.010597 12.980596 +-52.524448 -25.010597 12.980596 +-55.315334 -25.010597 24.916767 +-51.964615 -31.549501 12.641838 +-49.725327 -31.549501 12.641838 +-51.404785 -31.549501 12.438583 +-50.285156 -31.549501 12.438583 +-50.844975 -31.549501 12.370832 +-49.725327 -25.010586 12.641838 +-51.964615 -25.010597 12.641838 +-50.285156 -25.010597 12.438583 +-51.404785 -25.010597 12.438583 +-50.844975 -25.010597 12.370832 +-52.037682 -31.619381 13.955422 +-51.736553 -31.619381 13.433851 +-51.736553 -24.876726 13.433851 +-52.037682 -24.876726 13.955422 +-51.170612 -31.619381 13.227865 +-51.170612 -24.876726 13.227865 +-50.604675 -31.619381 13.433851 +-50.604675 -24.876726 13.433851 +-50.303535 -31.619381 13.955422 +-50.303535 -24.876726 13.955422 +-50.408127 -31.619381 14.548532 +-50.408127 -24.876726 14.548532 +-50.869488 -31.619381 14.935658 +-50.869488 -24.876726 14.935658 +-51.471741 -31.619381 14.935658 +-51.471741 -24.876726 14.935658 +-51.933090 -31.619381 14.548533 +-51.933090 -24.876726 14.548533 +52.524441 31.833542 12.980596 +55.315327 31.833542 24.916767 +51.956390 31.833542 24.916767 +49.165504 31.833542 12.980597 +52.524441 24.726486 12.980596 +49.165504 24.726486 12.980600 +51.956390 24.726486 24.916767 +55.315327 24.726486 24.916767 +49.725327 31.833542 12.641846 +51.964622 31.833542 12.641846 +50.285156 31.833542 12.438583 +51.404793 31.833542 12.438583 +50.844975 31.833542 12.370832 +51.964622 24.726486 12.641838 +49.725327 24.726486 12.641880 +51.404793 24.726486 12.438569 +50.285156 24.726486 12.438480 +50.844975 24.726486 12.370875 +51.956390 31.549465 24.916767 +55.315327 31.549465 24.916767 +52.524441 31.549465 12.980596 +49.165504 31.549465 12.980596 +51.956390 25.010550 24.916767 +49.165504 25.010550 12.980596 +52.524441 25.010550 12.980596 +55.315327 25.010550 24.916767 +51.964622 31.549465 12.641838 +49.725327 31.549465 12.641838 +51.404793 31.549465 12.438583 +50.285156 31.549465 12.438583 +50.844975 31.549465 12.370832 +49.725327 25.010550 12.641838 +51.964622 25.010550 12.641838 +50.285156 25.010550 12.438583 +51.404793 25.010550 12.438583 +50.844975 25.010550 12.370832 +52.037682 31.619347 13.955422 +51.736557 31.619347 13.433851 +51.736557 24.876690 13.433851 +52.037682 24.876690 13.955422 +51.170616 31.619347 13.227865 +51.170616 24.876690 13.227865 +50.604675 31.619347 13.433851 +50.604675 24.876690 13.433851 +50.303543 31.619347 13.955422 +50.303543 24.876690 13.955422 +50.408127 31.619347 14.548532 +50.408127 24.876690 14.548532 +50.869488 31.619347 14.935658 +50.869488 24.876690 14.935658 +51.471745 31.619347 14.935658 +51.471745 24.876690 14.935658 +51.933098 31.619347 14.548533 +51.933098 24.876690 14.548533 +-52.524448 31.833542 12.980596 +-49.165504 31.833542 12.980597 +-51.956390 31.833542 24.916767 +-55.315334 31.833542 24.916767 +-52.524448 24.726486 12.980596 +-55.315334 24.726486 24.916767 +-51.956390 24.726486 24.916767 +-49.165504 24.726486 12.980600 +-49.725327 31.833542 12.641846 +-51.964615 31.833542 12.641846 +-50.285156 31.833542 12.438583 +-51.404785 31.833542 12.438583 +-50.844975 31.833542 12.370832 +-51.964615 24.726486 12.641838 +-49.725327 24.726486 12.641880 +-51.404785 24.726486 12.438569 +-50.285156 24.726486 12.438480 +-50.844975 24.726486 12.370875 +-51.956390 31.549465 24.916767 +-49.165504 31.549465 12.980596 +-52.524448 31.549465 12.980596 +-55.315334 31.549465 24.916767 +-51.956390 25.010550 24.916767 +-55.315334 25.010550 24.916767 +-52.524448 25.010550 12.980596 +-49.165504 25.010550 12.980596 +-49.725327 31.549465 12.641838 +-51.964615 31.549465 12.641838 +-50.285156 31.549465 12.438583 +-51.404785 31.549465 12.438583 +-50.844975 31.549465 12.370832 +-51.964615 25.010550 12.641838 +-49.725327 25.010550 12.641838 +-51.404785 25.010550 12.438583 +-50.285156 25.010550 12.438583 +-50.844975 25.010550 12.370832 +-52.037682 31.619347 13.955422 +-52.037682 24.876690 13.955422 +-51.736553 24.876690 13.433851 +-51.736553 31.619347 13.433851 +-51.170612 24.876690 13.227865 +-51.170612 31.619347 13.227865 +-50.604675 24.876690 13.433851 +-50.604675 31.619347 13.433851 +-50.303535 24.876690 13.955422 +-50.303535 31.619347 13.955422 +-50.408127 24.876690 14.548532 +-50.408127 31.619347 14.548532 +-50.869488 24.876690 14.935658 +-50.869488 31.619347 14.935658 +-51.471741 24.876690 14.935658 +-51.471741 31.619347 14.935658 +-51.933090 24.876690 14.548533 +-51.933090 31.619347 14.548533 +38.765221 41.980946 126.364548 +38.765221 43.170593 125.871796 +38.765221 43.663345 124.682159 +38.765221 43.170593 123.492523 +38.765221 41.980946 122.999756 +38.765221 40.791309 123.492523 +38.765221 40.298557 124.682159 +38.765221 40.791309 125.871796 +28.410164 41.980946 126.364548 +28.410164 43.170593 125.871796 +28.410164 43.663345 124.682159 +28.410164 43.170593 123.492523 +28.410164 41.980946 122.999756 +28.410164 40.791309 123.492523 +28.410164 40.298557 124.682159 +28.410164 40.791309 125.871796 +34.847843 41.980946 123.997856 +35.122620 42.644310 123.997856 +35.785976 42.919075 123.997856 +36.449337 42.644310 123.997856 +36.724110 41.980946 123.997856 +36.449337 41.317593 123.997856 +35.785976 41.042816 123.997856 +35.122620 41.317593 123.997856 +34.847843 41.980946 118.223709 +35.122620 42.644310 118.223709 +35.785976 42.919075 118.223709 +36.449337 42.644310 118.223709 +36.724110 41.980946 118.223709 +36.449337 41.317593 118.223709 +35.785976 41.042816 118.223709 +35.122620 41.317593 118.223709 +30.455627 41.980946 123.997856 +30.730400 42.644310 123.997856 +31.393763 42.919075 123.997856 +32.057121 42.644310 123.997856 +32.331894 41.980946 123.997856 +32.057121 41.317593 123.997856 +31.393763 41.042816 123.997856 +30.730402 41.317593 123.997856 +30.455627 41.980946 118.223709 +30.730402 42.644310 118.223709 +31.393763 42.919075 118.223709 +32.057121 42.644310 118.223709 +32.331894 41.980946 118.223709 +32.057121 41.317593 118.223709 +31.393763 41.042816 118.223709 +30.730402 41.317593 118.223709 +-28.410160 43.170593 125.871780 +-28.410160 41.980946 126.364548 +-38.765217 41.980946 126.364548 +-38.765217 43.170593 125.871780 +-28.410160 43.663345 124.682159 +-38.765217 43.663345 124.682159 +-28.410160 43.170593 123.492523 +-38.765217 43.170593 123.492523 +-28.410160 41.980946 122.999756 +-38.765217 41.980946 122.999756 +-28.410160 40.791309 123.492523 +-38.765217 40.791309 123.492523 +-28.410160 40.298557 124.682159 +-38.765217 40.298557 124.682159 +-28.410160 40.791309 125.871780 +-38.765217 40.791309 125.871780 +-34.847836 41.980946 123.997849 +-35.122620 42.644310 123.997849 +-35.122620 42.644310 118.223709 +-34.847836 41.980946 118.223709 +-35.785969 42.919075 123.997849 +-35.785969 42.919075 118.223709 +-36.449329 42.644310 123.997849 +-36.449329 42.644310 118.223709 +-36.724102 41.980946 123.997849 +-36.724102 41.980946 118.223709 +-36.449329 41.317593 123.997849 +-36.449329 41.317593 118.223709 +-35.785969 41.042816 123.997849 +-35.785969 41.042816 118.223709 +-35.122620 41.317593 123.997849 +-35.122620 41.317593 118.223709 +-30.455622 41.980946 123.997849 +-30.730396 42.644310 123.997849 +-30.730396 42.644310 118.223709 +-30.455622 41.980946 118.223709 +-31.393757 42.919075 123.997849 +-31.393757 42.919075 118.223709 +-32.057114 42.644310 123.997849 +-32.057114 42.644310 118.223709 +-32.331894 41.980946 123.997849 +-32.331894 41.980946 118.223709 +-32.057114 41.317593 123.997849 +-32.057114 41.317593 118.223709 +-31.393757 41.042816 123.997849 +-31.393757 41.042816 118.223709 +-30.730396 41.317593 123.997849 +-30.730396 41.317593 118.223709 + + + + + + + + + + + +0.954794 -0.297269 0.000001 +0.961660 0.274243 -0.000988 +0.962188 0.272384 0.000000 +0.962188 0.272384 0.000000 +0.954794 -0.297267 0.000000 +0.954794 -0.297269 0.000001 +-0.000000 1.000000 0.000561 +-0.000000 0.999999 -0.001678 +0.001038 0.999992 0.003826 +0.001038 0.999992 0.003826 +0.000000 0.999961 0.008836 +-0.000000 1.000000 0.000561 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +0.967232 -0.253893 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +1.000000 -0.000000 0.000000 +0.967232 -0.253893 0.000000 +0.967232 -0.253893 0.000000 +0.000646 0.999660 -0.026085 +0.001038 0.999992 0.003826 +-0.000000 0.999999 -0.001678 +-0.000003 -0.000000 -1.000000 +-0.000004 -0.000002 -1.000000 +-0.000003 -0.000000 -1.000000 +0.000002 -0.000000 -1.000000 +-0.000003 -0.000000 -1.000000 +-0.000003 -0.000000 -1.000000 +0.000002 -0.000000 -1.000000 +-0.000003 -0.000000 -1.000000 +0.000001 -0.000001 -1.000000 +0.954794 -0.297268 -0.000000 +0.957663 0.287503 0.014966 +0.955706 0.294323 0.000002 +0.955706 0.294323 0.000002 +0.954794 -0.297268 0.000000 +0.954794 -0.297268 -0.000000 +0.060145 0.998104 -0.013067 +0.000646 0.999660 -0.026085 +-0.000000 0.999999 -0.001678 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.534109 -0.845416 0.000000 +0.079799 -0.996811 0.000000 +0.079799 -0.996811 0.000000 +0.079799 -0.996811 0.000000 +0.534108 -0.845416 0.000000 +0.534109 -0.845416 0.000000 +0.561036 0.827791 0.000337 +0.962188 0.272384 0.000000 +0.961660 0.274243 -0.000988 +0.961660 0.274243 -0.000988 +0.558547 0.829473 0.000612 +0.561036 0.827791 0.000337 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.884768 -0.466031 0.000000 +0.897736 -0.440534 0.000000 +0.897736 -0.440534 0.000000 +0.897736 -0.440534 0.000000 +0.884768 -0.466031 0.000000 +0.884768 -0.466031 0.000000 +0.000000 -0.000001 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 -0.000001 -1.000000 +-0.000000 -0.000001 -1.000000 +0.000000 -0.000001 -1.000000 +0.000000 -0.000001 -1.000000 +0.534108 -0.845416 0.000000 +0.079799 -0.996811 0.000000 +0.079799 -0.996811 0.000000 +0.079799 -0.996811 0.000000 +0.534108 -0.845416 0.000000 +0.534108 -0.845416 0.000000 +0.527538 0.848563 0.040552 +0.955706 0.294323 0.000002 +0.957663 0.287503 0.014966 +0.957663 0.287503 0.014966 +0.579778 0.812153 0.065308 +0.527538 0.848563 0.040552 +0.954794 -0.297267 0.000000 +0.534109 -0.845416 0.000000 +0.534108 -0.845416 0.000000 +0.534108 -0.845416 0.000000 +0.954794 -0.297269 0.000001 +0.954794 -0.297267 0.000000 +0.058423 0.998284 0.003992 +0.561036 0.827791 0.000337 +0.558547 0.829473 0.000612 +0.558547 0.829473 0.000612 +0.087074 0.996176 0.007225 +0.058423 0.998284 0.003992 +-0.000000 -0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +0.967232 -0.253893 0.000000 +0.884768 -0.466031 0.000000 +0.884768 -0.466031 0.000000 +0.884768 -0.466031 0.000000 +0.967232 -0.253893 0.000000 +0.967232 -0.253893 0.000000 +0.000001 -0.000001 -1.000000 +0.000000 -0.000001 -1.000000 +0.000000 -0.000001 -1.000000 +0.000000 -0.000001 -1.000000 +0.000002 -0.000000 -1.000000 +0.000001 -0.000001 -1.000000 +0.954794 -0.297268 0.000000 +0.534108 -0.845416 0.000000 +0.534108 -0.845416 0.000000 +0.534108 -0.845416 0.000000 +0.954794 -0.297268 -0.000000 +0.954794 -0.297268 0.000000 +0.060145 0.998104 -0.013067 +0.527538 0.848563 0.040552 +0.579778 0.812153 0.065308 +0.579778 0.812153 0.065308 +0.073338 0.997265 0.009197 +0.060145 0.998104 -0.013067 +0.058423 0.998284 0.003992 +0.087074 0.996176 0.007225 +0.000000 0.999961 0.008836 +0.000000 0.999961 0.008836 +0.000000 0.999990 0.004418 +0.058423 0.998284 0.003992 +0.073338 0.997265 0.009197 +0.058423 0.998284 0.003992 +0.000000 0.999990 0.004418 +0.000000 0.999990 0.004418 +0.000000 0.999649 -0.026483 +0.073338 0.997265 0.009197 +0.060145 0.998104 -0.013067 +0.073338 0.997265 0.009197 +0.000000 0.999649 -0.026483 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.999649 -0.026483 +0.000646 0.999660 -0.026085 +0.060145 0.998104 -0.013067 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 -0.000001 -0.000000 +1.000000 -0.000001 -0.000000 +1.000000 -0.000001 -0.000000 +1.000000 -0.000001 -0.000000 +1.000000 -0.000001 -0.000000 +1.000000 -0.000001 -0.000000 +1.000000 -0.000001 -0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 0.000000 +1.000000 -0.000001 -0.000000 +1.000000 -0.000001 -0.000000 +-1.000000 0.000001 0.000000 +-1.000000 0.000001 0.000000 +-1.000000 0.000001 0.000000 +-1.000000 0.000001 0.000000 +-1.000000 0.000001 0.000000 +-1.000000 0.000001 0.000000 +-1.000000 0.000001 0.000000 +-1.000000 0.000001 0.000000 +-1.000000 0.000001 0.000000 +-1.000000 0.000001 0.000000 +-1.000000 0.000001 0.000000 +-1.000000 0.000001 0.000000 +0.000000 0.999961 0.008836 +0.000000 0.999961 0.008836 +0.000000 0.999990 0.004418 +0.000000 0.999990 0.004418 +0.000000 0.999990 0.004418 +0.000000 0.999961 0.008836 +0.000000 0.999990 0.004418 +0.000000 0.999990 0.004418 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.999990 0.004418 +-0.954794 -0.297269 0.000001 +-0.954794 -0.297267 0.000000 +-0.962188 0.272384 0.000000 +-0.962188 0.272384 0.000000 +-0.961660 0.274243 -0.000988 +-0.954794 -0.297269 0.000001 +-0.000000 1.000000 0.000561 +0.000000 0.999961 0.008836 +-0.001038 0.999992 0.003826 +-0.001038 0.999992 0.003826 +-0.000000 0.999999 -0.001678 +-0.000000 1.000000 0.000561 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +-0.967232 -0.253893 0.000000 +-0.967232 -0.253893 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-0.967232 -0.253893 0.000000 +-0.000000 0.999999 -0.001678 +-0.001038 0.999992 0.003826 +-0.000646 0.999660 -0.026085 +-0.000002 -0.000000 -1.000000 +-0.000001 -0.000001 -1.000000 +0.000003 -0.000000 -1.000000 +0.000003 -0.000000 -1.000000 +0.000004 -0.000002 -1.000000 +0.000003 -0.000000 -1.000000 +-0.000002 -0.000000 -1.000000 +0.000003 -0.000000 -1.000000 +0.000003 -0.000000 -1.000000 +-0.954794 -0.297268 -0.000000 +-0.954794 -0.297268 0.000000 +-0.955706 0.294323 0.000002 +-0.955706 0.294323 0.000002 +-0.957663 0.287503 0.014966 +-0.954794 -0.297268 -0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -0.000001 -1.000000 +0.000000 -0.000001 -1.000000 +-0.000000 -0.000001 -1.000000 +0.000000 0.000000 -1.000000 +0.079799 -0.996811 0.000000 +-0.079799 -0.996811 0.000000 +-0.079799 -0.996811 0.000000 +-0.079799 -0.996811 0.000000 +0.079799 -0.996811 0.000000 +0.079799 -0.996811 0.000000 +-0.534109 -0.845416 0.000000 +-0.534108 -0.845416 0.000000 +-0.079799 -0.996811 0.000000 +-0.079799 -0.996811 0.000000 +-0.079799 -0.996811 0.000000 +-0.534109 -0.845416 0.000000 +-0.561036 0.827791 0.000337 +-0.558547 0.829473 0.000612 +-0.961660 0.274243 -0.000988 +-0.961660 0.274243 -0.000988 +-0.962188 0.272384 0.000000 +-0.561036 0.827791 0.000337 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.884768 -0.466031 0.000000 +-0.884768 -0.466031 0.000000 +-0.897736 -0.440534 0.000000 +-0.897736 -0.440534 0.000000 +-0.897736 -0.440534 0.000000 +-0.884768 -0.466031 0.000000 +-0.000000 -0.000001 -1.000000 +-0.000000 -0.000001 -1.000000 +0.000000 -0.000001 -1.000000 +0.000000 -0.000001 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 -0.000001 -1.000000 +-0.534108 -0.845416 0.000000 +-0.534108 -0.845416 0.000000 +-0.079799 -0.996811 0.000000 +-0.079799 -0.996811 0.000000 +-0.079799 -0.996811 0.000000 +-0.534108 -0.845416 0.000000 +-0.527538 0.848563 0.040552 +-0.579778 0.812153 0.065307 +-0.957663 0.287503 0.014966 +-0.957663 0.287503 0.014966 +-0.955706 0.294323 0.000002 +-0.527538 0.848563 0.040552 +-0.954794 -0.297267 0.000000 +-0.954794 -0.297269 0.000001 +-0.534108 -0.845416 0.000000 +-0.534108 -0.845416 0.000000 +-0.534109 -0.845416 0.000000 +-0.954794 -0.297267 0.000000 +-0.058423 0.998284 0.003992 +-0.087074 0.996176 0.007225 +-0.558547 0.829473 0.000612 +-0.558547 0.829473 0.000612 +-0.561036 0.827791 0.000337 +-0.058423 0.998284 0.003992 +0.000000 -0.000000 1.000000 +0.000000 -0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -0.000000 1.000000 +-0.967232 -0.253893 0.000000 +-0.967232 -0.253893 0.000000 +-0.884768 -0.466031 0.000000 +-0.884768 -0.466031 0.000000 +-0.884768 -0.466031 0.000000 +-0.967232 -0.253893 0.000000 +-0.000001 -0.000001 -1.000000 +-0.000002 -0.000000 -1.000000 +-0.000000 -0.000001 -1.000000 +-0.000000 -0.000001 -1.000000 +-0.000000 -0.000001 -1.000000 +-0.000001 -0.000001 -1.000000 +-0.954794 -0.297268 0.000000 +-0.954794 -0.297268 -0.000000 +-0.534108 -0.845416 0.000000 +-0.534108 -0.845416 0.000000 +-0.534108 -0.845416 0.000000 +-0.954794 -0.297268 0.000000 +-0.060145 0.998104 -0.013067 +-0.073338 0.997265 0.009197 +-0.579778 0.812153 0.065307 +-0.579778 0.812153 0.065307 +-0.527538 0.848563 0.040552 +-0.060145 0.998104 -0.013067 +-0.058423 0.998284 0.003992 +0.000000 0.999990 0.004418 +0.000000 0.999961 0.008836 +0.000000 0.999961 0.008836 +-0.087074 0.996176 0.007225 +-0.058423 0.998284 0.003992 +-0.073338 0.997265 0.009197 +0.000000 0.999649 -0.026483 +0.000000 0.999990 0.004418 +0.000000 0.999990 0.004418 +-0.058423 0.998284 0.003992 +-0.073338 0.997265 0.009197 +0.000000 0.999649 -0.026483 +-0.073338 0.997265 0.009197 +-0.060145 0.998104 -0.013067 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.000000 0.999999 -0.001678 +-0.000646 0.999660 -0.026085 +0.000000 0.999649 -0.026483 +0.000000 0.999649 -0.026483 +-0.060145 0.998104 -0.013067 +-0.000000 0.999999 -0.001678 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.079799 -0.996811 0.000000 +0.079799 -0.996811 0.000000 +0.079799 -0.996811 0.000000 +0.079799 -0.996811 0.000000 +-0.079799 -0.996811 0.000000 +-0.079799 -0.996811 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-1.000000 -0.000001 -0.000000 +-1.000000 -0.000001 -0.000000 +-1.000000 -0.000001 -0.000000 +-1.000000 -0.000001 -0.000000 +-1.000000 -0.000001 -0.000000 +-1.000000 -0.000001 -0.000000 +-1.000000 -0.000001 -0.000000 +-1.000000 -0.000001 -0.000000 +-1.000000 -0.000001 0.000000 +-1.000000 -0.000001 0.000000 +-1.000000 -0.000001 0.000000 +-1.000000 -0.000001 -0.000000 +1.000000 0.000001 0.000000 +1.000000 0.000001 0.000000 +1.000000 0.000001 0.000000 +1.000000 0.000001 0.000000 +1.000000 0.000001 0.000000 +1.000000 0.000001 0.000000 +1.000000 0.000001 0.000000 +1.000000 0.000001 0.000000 +1.000000 0.000001 0.000000 +1.000000 0.000001 0.000000 +1.000000 0.000001 0.000000 +1.000000 0.000001 0.000000 +0.000000 0.999961 0.008836 +0.000000 0.999990 0.004418 +0.000000 0.999990 0.004418 +0.000000 0.999990 0.004418 +0.000000 0.999961 0.008836 +0.000000 0.999961 0.008836 +0.000000 0.999990 0.004418 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.999990 0.004418 +0.000000 0.999990 0.004418 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.156433 -0.987270 -0.028768 +0.156433 -0.987270 -0.028768 +0.163765 -0.986072 -0.029039 +0.163765 -0.986072 -0.029039 +-0.163765 -0.986072 -0.029039 +-0.156433 -0.987270 -0.028768 +0.986405 -0.158422 -0.043684 +0.986405 0.158422 -0.043684 +0.985884 0.161615 -0.043735 +0.985884 0.161615 -0.043735 +0.985884 -0.161615 -0.043735 +0.986405 -0.158422 -0.043684 +0.156432 0.987270 -0.028768 +-0.156432 0.987270 -0.028768 +-0.163764 0.986072 -0.029039 +-0.163764 0.986072 -0.029039 +0.163764 0.986072 -0.029039 +0.156432 0.987270 -0.028768 +-0.986405 0.158422 -0.043684 +-0.986405 -0.158422 -0.043684 +-0.985884 -0.161615 -0.043735 +-0.985884 -0.161615 -0.043735 +-0.985884 0.161615 -0.043735 +-0.986405 0.158422 -0.043684 +0.033583 0.316870 -0.947874 +-0.033583 0.316870 -0.947874 +-0.061187 0.297691 -0.952699 +-0.061187 0.297691 -0.952699 +0.061187 0.297691 -0.952699 +0.033583 0.316870 -0.947874 +-0.397146 0.030264 -0.917256 +-0.397146 -0.030264 -0.917256 +-0.342229 -0.078768 -0.936309 +-0.342229 -0.078768 -0.936309 +-0.342228 0.078768 -0.936310 +-0.397146 0.030264 -0.917256 +-0.033583 -0.316870 -0.947874 +0.033583 -0.316870 -0.947874 +0.061186 -0.297691 -0.952699 +0.061186 -0.297691 -0.952699 +-0.061186 -0.297691 -0.952699 +-0.033583 -0.316870 -0.947874 +0.397146 -0.030264 -0.917256 +0.397146 0.030264 -0.917256 +0.342228 0.078768 -0.936309 +0.342228 0.078768 -0.936309 +0.342228 -0.078768 -0.936309 +0.397146 -0.030264 -0.917256 +-0.160182 -0.987087 0.000001 +0.160182 -0.987087 0.000001 +0.160182 -0.987087 0.000001 +0.160182 -0.987087 0.000001 +-0.160182 -0.987087 0.000001 +-0.160182 -0.987087 0.000001 +0.987088 -0.160182 0.000001 +0.987088 0.160181 0.000002 +0.987087 0.160182 0.000001 +0.987087 0.160182 0.000001 +0.987088 -0.160182 0.000002 +0.987088 -0.160182 0.000001 +0.160181 0.987088 0.000000 +-0.160181 0.987088 0.000001 +-0.160182 0.987087 0.000000 +-0.160182 0.987087 0.000000 +0.160182 0.987087 0.000001 +0.160181 0.987088 0.000000 +-0.987088 0.160181 0.000001 +-0.987087 -0.160182 0.000002 +-0.987088 -0.160182 0.000001 +-0.987088 -0.160182 0.000001 +-0.987088 0.160182 0.000002 +-0.987088 0.160181 0.000001 +0.000000 0.000001 1.000000 +-0.000000 0.000001 1.000000 +-0.000000 0.000001 1.000000 +-0.000000 0.000001 1.000000 +0.000000 0.000001 1.000000 +0.000000 0.000001 1.000000 +-0.000002 0.000000 1.000000 +-0.000002 -0.000000 1.000000 +-0.000002 -0.000000 1.000000 +-0.000002 -0.000000 1.000000 +-0.000002 0.000000 1.000000 +-0.000002 0.000000 1.000000 +-0.000000 -0.000001 1.000000 +0.000000 -0.000001 1.000000 +0.000000 -0.000001 1.000000 +0.000000 -0.000001 1.000000 +-0.000000 -0.000001 1.000000 +-0.000000 -0.000001 1.000000 +0.000002 -0.000000 1.000000 +0.000002 0.000000 1.000000 +0.000002 0.000000 1.000000 +0.000002 0.000000 1.000000 +0.000002 -0.000000 1.000000 +0.000002 -0.000000 1.000000 +0.708894 -0.703891 -0.044788 +0.163765 -0.986072 -0.029039 +0.156433 -0.987270 -0.028768 +0.156433 -0.987270 -0.028768 +0.703799 -0.708992 -0.044697 +0.708894 -0.703891 -0.044788 +-0.703799 -0.708992 -0.044697 +-0.156433 -0.987270 -0.028768 +-0.163765 -0.986072 -0.029039 +-0.163765 -0.986072 -0.029039 +-0.708894 -0.703891 -0.044788 +-0.703799 -0.708992 -0.044697 +0.708894 0.703892 -0.044788 +0.985884 0.161615 -0.043735 +0.986405 0.158422 -0.043684 +0.986405 0.158422 -0.043684 +0.703798 0.708992 -0.044697 +0.708894 0.703892 -0.044788 +-0.708894 0.703892 -0.044788 +-0.163764 0.986072 -0.029039 +-0.156432 0.987270 -0.028768 +-0.156432 0.987270 -0.028768 +-0.703798 0.708992 -0.044697 +-0.708894 0.703892 -0.044788 +0.191333 0.201883 -0.960539 +0.342228 0.078768 -0.936309 +0.397146 0.030264 -0.917256 +0.397146 0.030264 -0.917256 +0.211413 0.186282 -0.959481 +0.191333 0.201883 -0.960539 +-0.191333 0.201883 -0.960539 +-0.061187 0.297691 -0.952699 +-0.033583 0.316870 -0.947874 +-0.033583 0.316870 -0.947874 +-0.211413 0.186282 -0.959481 +-0.191333 0.201883 -0.960539 +0.191333 -0.201883 -0.960539 +0.061186 -0.297691 -0.952699 +0.033583 -0.316870 -0.947874 +0.033583 -0.316870 -0.947874 +0.211413 -0.186282 -0.959481 +0.191333 -0.201883 -0.960539 +-0.191333 -0.201884 -0.960539 +-0.342229 -0.078768 -0.936309 +-0.397146 -0.030264 -0.917256 +-0.397146 -0.030264 -0.917256 +-0.211413 -0.186282 -0.959481 +-0.191333 -0.201884 -0.960539 +-0.707107 -0.707106 0.000002 +-0.987088 -0.160182 0.000001 +-0.987087 -0.160182 0.000002 +-0.987087 -0.160182 0.000002 +-0.707107 -0.707106 0.000002 +-0.707107 -0.707106 0.000002 +0.707107 -0.707107 0.000002 +0.160182 -0.987087 0.000001 +0.160182 -0.987087 0.000001 +0.160182 -0.987087 0.000001 +0.707107 -0.707107 0.000002 +0.707107 -0.707107 0.000002 +-0.707107 0.707107 0.000002 +-0.160182 0.987087 0.000000 +-0.160181 0.987088 0.000001 +-0.160181 0.987088 0.000001 +-0.707107 0.707107 0.000002 +-0.707107 0.707107 0.000002 +0.707107 0.707106 0.000002 +0.987087 0.160182 0.000001 +0.987088 0.160181 0.000002 +0.987088 0.160181 0.000002 +0.707107 0.707107 0.000002 +0.707107 0.707106 0.000002 +0.000001 0.000001 1.000000 +0.000002 0.000000 1.000000 +0.000002 0.000000 1.000000 +0.000002 0.000000 1.000000 +0.000001 0.000001 1.000000 +0.000001 0.000001 1.000000 +-0.000001 0.000001 1.000000 +-0.000000 0.000001 1.000000 +-0.000000 0.000001 1.000000 +-0.000000 0.000001 1.000000 +-0.000001 0.000001 1.000000 +-0.000001 0.000001 1.000000 +0.000001 -0.000001 1.000000 +0.000000 -0.000001 1.000000 +0.000000 -0.000001 1.000000 +0.000000 -0.000001 1.000000 +0.000001 -0.000001 1.000000 +0.000001 -0.000001 1.000000 +-0.000001 -0.000001 1.000000 +-0.000002 -0.000000 1.000000 +-0.000002 -0.000000 1.000000 +-0.000002 -0.000000 1.000000 +-0.000001 -0.000001 1.000000 +-0.000001 -0.000001 1.000000 +0.985884 -0.161615 -0.043735 +0.708894 -0.703891 -0.044788 +0.703799 -0.708992 -0.044697 +0.703799 -0.708992 -0.044697 +0.986405 -0.158422 -0.043684 +0.985884 -0.161615 -0.043735 +-0.986405 -0.158422 -0.043684 +-0.703799 -0.708992 -0.044697 +-0.708894 -0.703891 -0.044788 +-0.708894 -0.703891 -0.044788 +-0.985884 -0.161615 -0.043735 +-0.986405 -0.158422 -0.043684 +0.163764 0.986072 -0.029039 +0.708894 0.703892 -0.044788 +0.703798 0.708992 -0.044697 +0.703798 0.708992 -0.044697 +0.156432 0.987270 -0.028768 +0.163764 0.986072 -0.029039 +-0.985884 0.161615 -0.043735 +-0.708894 0.703892 -0.044788 +-0.703798 0.708992 -0.044697 +-0.703798 0.708992 -0.044697 +-0.986405 0.158422 -0.043684 +-0.985884 0.161615 -0.043735 +0.061187 0.297691 -0.952699 +0.191333 0.201883 -0.960539 +0.211413 0.186282 -0.959481 +0.211413 0.186282 -0.959481 +0.033583 0.316870 -0.947874 +0.061187 0.297691 -0.952699 +-0.342228 0.078768 -0.936310 +-0.191333 0.201883 -0.960539 +-0.211413 0.186282 -0.959481 +-0.211413 0.186282 -0.959481 +-0.397146 0.030264 -0.917256 +-0.342228 0.078768 -0.936310 +0.342228 -0.078768 -0.936309 +0.191333 -0.201883 -0.960539 +0.211413 -0.186282 -0.959481 +0.211413 -0.186282 -0.959481 +0.397146 -0.030264 -0.917256 +0.342228 -0.078768 -0.936309 +-0.061186 -0.297691 -0.952699 +-0.191333 -0.201884 -0.960539 +-0.211413 -0.186282 -0.959481 +-0.211413 -0.186282 -0.959481 +-0.033583 -0.316870 -0.947874 +-0.061186 -0.297691 -0.952699 +-0.160182 -0.987087 0.000001 +-0.707107 -0.707106 0.000002 +-0.707107 -0.707106 0.000002 +-0.707107 -0.707106 0.000002 +-0.160182 -0.987087 0.000001 +-0.160182 -0.987087 0.000001 +0.987088 -0.160182 0.000002 +0.707107 -0.707107 0.000002 +0.707107 -0.707107 0.000002 +0.707107 -0.707107 0.000002 +0.987088 -0.160182 0.000001 +0.987088 -0.160182 0.000002 +-0.987088 0.160182 0.000002 +-0.707107 0.707107 0.000002 +-0.707107 0.707107 0.000002 +-0.707107 0.707107 0.000002 +-0.987088 0.160181 0.000001 +-0.987088 0.160182 0.000002 +0.160182 0.987087 0.000001 +0.707107 0.707106 0.000002 +0.707107 0.707107 0.000002 +0.707107 0.707107 0.000002 +0.160181 0.987088 0.000000 +0.160182 0.987087 0.000001 +0.000000 0.000001 1.000000 +0.000001 0.000001 1.000000 +0.000001 0.000001 1.000000 +0.000001 0.000001 1.000000 +0.000000 0.000001 1.000000 +0.000000 0.000001 1.000000 +-0.000002 0.000000 1.000000 +-0.000001 0.000001 1.000000 +-0.000001 0.000001 1.000000 +-0.000001 0.000001 1.000000 +-0.000002 0.000000 1.000000 +-0.000002 0.000000 1.000000 +0.000002 -0.000000 1.000000 +0.000001 -0.000001 1.000000 +0.000001 -0.000001 1.000000 +0.000001 -0.000001 1.000000 +0.000002 -0.000000 1.000000 +0.000002 -0.000000 1.000000 +-0.000000 -0.000001 1.000000 +-0.000001 -0.000001 1.000000 +-0.000001 -0.000001 1.000000 +-0.000001 -0.000001 1.000000 +-0.000000 -0.000001 1.000000 +-0.000000 -0.000001 1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.902388 -0.430926 +0.000000 0.902387 -0.430926 +0.000000 0.902388 -0.430926 +0.000000 0.902388 -0.430926 +0.000000 0.902387 -0.430926 +0.000000 0.902388 -0.430926 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.902388 -0.430926 +0.000000 0.902387 -0.430926 +0.000000 0.902388 -0.430926 +0.000000 0.902388 -0.430926 +0.000000 0.902387 -0.430926 +0.000000 0.902388 -0.430926 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +0.000000 0.902387 -0.430926 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.999470 0.000000 -0.032547 +-0.999470 0.000000 -0.032547 +-0.999470 0.000000 -0.032547 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 -0.902388 -0.430926 +0.000000 -0.902387 -0.430926 +0.000000 -0.902388 -0.430926 +0.000000 -0.902388 -0.430926 +0.000000 -0.902387 -0.430926 +0.000000 -0.902388 -0.430926 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -0.902388 -0.430926 +0.000000 -0.902387 -0.430926 +0.000000 -0.902388 -0.430926 +0.000000 -0.902388 -0.430926 +0.000000 -0.902387 -0.430926 +0.000000 -0.902388 -0.430926 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +0.000000 -0.902387 -0.430926 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.999470 0.000000 -0.032547 +-0.999470 0.000000 -0.032547 +-0.999470 0.000000 -0.032547 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.902387 0.000000 -0.430926 +-0.902387 0.000000 -0.430926 +-0.902387 0.000000 -0.430926 +-0.902387 0.000000 -0.430926 +-0.902387 0.000000 -0.430926 +-0.902387 0.000000 -0.430926 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.902387 0.000000 -0.430926 +-0.902387 0.000000 -0.430926 +-0.902387 0.000000 -0.430926 +-0.902387 0.000000 -0.430926 +-0.902387 0.000000 -0.430926 +-0.902387 0.000000 -0.430926 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.902387 0.000000 -0.430926 +-0.902387 0.000000 -0.430926 +-0.902387 0.000000 -0.430926 +-0.902387 0.000000 -0.430926 +-0.902387 0.000000 -0.430926 +-0.902387 0.000000 -0.430926 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.902387 0.000000 -0.430926 +0.902387 0.000000 -0.430926 +0.902387 0.000000 -0.430926 +0.902387 0.000000 -0.430926 +0.902387 0.000000 -0.430926 +0.902387 0.000000 -0.430926 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.902387 0.000000 -0.430926 +0.902387 0.000000 -0.430926 +0.902387 0.000000 -0.430926 +0.902387 0.000000 -0.430926 +0.902387 0.000000 -0.430926 +0.902387 0.000000 -0.430926 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.902387 0.000000 -0.430926 +0.902387 0.000000 -0.430926 +0.902387 0.000000 -0.430926 +0.902387 0.000000 -0.430926 +0.902387 0.000000 -0.430926 +0.902387 0.000000 -0.430926 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 -0.000000 +0.939693 0.000000 -0.342019 +0.939693 -0.000000 -0.342020 +0.939693 -0.000000 -0.342020 +1.000000 -0.000000 -0.000000 +1.000000 0.000000 -0.000000 +0.939693 0.000000 -0.342019 +0.766045 0.000000 -0.642787 +0.766045 0.000000 -0.642787 +0.766045 0.000000 -0.642787 +0.939693 -0.000000 -0.342020 +0.939693 0.000000 -0.342019 +0.766045 0.000000 -0.642787 +0.499999 0.000000 -0.866026 +0.499999 0.000000 -0.866026 +0.499999 0.000000 -0.866026 +0.766045 0.000000 -0.642787 +0.766045 0.000000 -0.642787 +0.499999 0.000000 -0.866026 +0.173648 0.000000 -0.984808 +0.173648 0.000000 -0.984808 +0.173648 0.000000 -0.984808 +0.499999 0.000000 -0.866026 +0.499999 0.000000 -0.866026 +0.173648 0.000000 -0.984808 +-0.173648 0.000000 -0.984808 +-0.173648 0.000000 -0.984808 +-0.173648 0.000000 -0.984808 +0.173648 0.000000 -0.984808 +0.173648 0.000000 -0.984808 +-0.173648 0.000000 -0.984808 +-0.500000 0.000000 -0.866025 +-0.500000 0.000000 -0.866025 +-0.500000 0.000000 -0.866025 +-0.173648 0.000000 -0.984808 +-0.173648 0.000000 -0.984808 +-0.500000 0.000000 -0.866025 +-0.766044 0.000000 -0.642788 +-0.766044 0.000000 -0.642788 +-0.766044 0.000000 -0.642788 +-0.500000 0.000000 -0.866025 +-0.500000 0.000000 -0.866025 +-0.766044 0.000000 -0.642788 +-0.939692 -0.000000 -0.342020 +-0.939692 0.000000 -0.342021 +-0.939692 0.000000 -0.342021 +-0.766044 0.000000 -0.642788 +-0.766044 0.000000 -0.642788 +-0.939692 -0.000000 -0.342020 +-1.000000 -0.000000 0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-0.939692 0.000000 -0.342021 +-0.939692 -0.000000 -0.342020 +-1.000000 -0.000000 0.000000 +-0.939693 0.000000 0.342020 +-0.939693 0.000000 0.342020 +-0.939693 0.000000 0.342020 +-1.000000 0.000000 -0.000000 +-1.000000 -0.000000 0.000000 +-0.939693 0.000000 0.342020 +-0.766045 0.000000 0.642787 +-0.766045 0.000000 0.642787 +-0.766045 0.000000 0.642787 +-0.939693 0.000000 0.342020 +-0.939693 0.000000 0.342020 +-0.766045 0.000000 0.642787 +-0.500000 0.000000 0.866025 +-0.500000 0.000000 0.866025 +-0.500000 0.000000 0.866025 +-0.766045 0.000000 0.642787 +-0.766045 0.000000 0.642787 +-0.500000 0.000000 0.866025 +-0.173649 0.000000 0.984808 +-0.173649 0.000000 0.984808 +-0.173649 0.000000 0.984808 +-0.500000 0.000000 0.866025 +-0.500000 0.000000 0.866025 +-0.173649 0.000000 0.984808 +0.173647 0.000000 0.984808 +0.173647 0.000000 0.984808 +0.173647 0.000000 0.984808 +-0.173649 0.000000 0.984808 +-0.173649 0.000000 0.984808 +0.173647 0.000000 0.984808 +0.500000 0.000000 0.866026 +0.500000 0.000000 0.866026 +0.500000 0.000000 0.866026 +0.173647 0.000000 0.984808 +0.173647 0.000000 0.984808 +0.500000 0.000000 0.866026 +0.766044 0.000000 0.642788 +0.766044 0.000000 0.642788 +0.766044 0.000000 0.642788 +0.500000 0.000000 0.866026 +0.500000 0.000000 0.866026 +0.766044 0.000000 0.642788 +0.939692 0.000000 0.342021 +0.939692 0.000000 0.342021 +0.939692 0.000000 0.342021 +0.766044 0.000000 0.642788 +0.766044 0.000000 0.642788 +0.939692 0.000000 0.342021 +1.000000 0.000000 -0.000000 +1.000000 -0.000000 -0.000000 +1.000000 -0.000000 -0.000000 +0.939692 0.000000 0.342021 +0.939692 0.000000 0.342021 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-0.939694 -0.000000 -0.342017 +-0.939694 -0.000000 -0.342017 +-0.939694 0.000000 -0.342017 +-1.000000 0.000000 -0.000000 +-0.939694 0.000000 -0.342017 +-0.939694 -0.000000 -0.342017 +-0.766044 0.000000 -0.642789 +-0.766044 0.000000 -0.642789 +-0.766043 0.000000 -0.642789 +-0.939694 0.000000 -0.342017 +-0.766043 0.000000 -0.642789 +-0.766044 0.000000 -0.642789 +-0.499998 0.000000 -0.866026 +-0.499998 0.000000 -0.866026 +-0.499998 0.000000 -0.866026 +-0.766043 0.000000 -0.642789 +-0.499998 0.000000 -0.866026 +-0.499998 0.000000 -0.866026 +-0.173649 0.000000 -0.984808 +-0.173649 0.000000 -0.984808 +-0.173649 0.000000 -0.984808 +-0.499998 0.000000 -0.866026 +-0.173649 0.000000 -0.984808 +-0.173649 0.000000 -0.984808 +0.173649 0.000000 -0.984808 +0.173649 0.000000 -0.984808 +0.173649 0.000000 -0.984808 +-0.173649 0.000000 -0.984808 +0.173649 0.000000 -0.984808 +0.173649 0.000000 -0.984808 +0.499999 0.000000 -0.866026 +0.499999 0.000000 -0.866026 +0.499999 0.000000 -0.866026 +0.173649 0.000000 -0.984808 +0.499999 0.000000 -0.866026 +0.499999 0.000000 -0.866026 +0.766043 0.000000 -0.642789 +0.766043 0.000000 -0.642789 +0.766043 0.000000 -0.642789 +0.499999 0.000000 -0.866026 +0.766043 0.000000 -0.642789 +0.766043 0.000000 -0.642789 +0.939693 0.000000 -0.342019 +0.939693 0.000000 -0.342019 +0.939693 -0.000000 -0.342019 +0.766043 0.000000 -0.642789 +0.939693 -0.000000 -0.342019 +0.939693 0.000000 -0.342019 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 -0.000000 0.000000 +0.939693 -0.000000 -0.342019 +1.000000 -0.000000 0.000000 +1.000000 0.000000 -0.000000 +0.939693 0.000000 0.342019 +0.939693 0.000000 0.342019 +0.939693 0.000000 0.342019 +1.000000 -0.000000 0.000000 +0.939693 0.000000 0.342019 +0.939693 0.000000 0.342019 +0.766044 0.000000 0.642788 +0.766044 0.000000 0.642788 +0.766044 0.000000 0.642788 +0.939693 0.000000 0.342019 +0.766044 0.000000 0.642788 +0.766044 0.000000 0.642788 +0.500000 0.000000 0.866025 +0.500000 0.000000 0.866025 +0.500000 0.000000 0.866025 +0.766044 0.000000 0.642788 +0.500000 0.000000 0.866025 +0.500000 0.000000 0.866025 +0.173648 0.000000 0.984808 +0.173648 0.000000 0.984808 +0.173648 0.000000 0.984808 +0.500000 0.000000 0.866025 +0.173648 0.000000 0.984808 +0.173648 0.000000 0.984808 +-0.173648 0.000000 0.984808 +-0.173648 0.000000 0.984808 +-0.173648 0.000000 0.984808 +0.173648 0.000000 0.984808 +-0.173648 0.000000 0.984808 +-0.173648 0.000000 0.984808 +-0.499999 0.000000 0.866026 +-0.499999 0.000000 0.866026 +-0.499999 0.000000 0.866026 +-0.173648 0.000000 0.984808 +-0.499999 0.000000 0.866026 +-0.499999 0.000000 0.866026 +-0.766043 0.000000 0.642789 +-0.766043 0.000000 0.642789 +-0.766043 0.000000 0.642789 +-0.499999 0.000000 0.866026 +-0.766043 0.000000 0.642789 +-0.766043 0.000000 0.642789 +-0.939693 0.000000 0.342019 +-0.939693 0.000000 0.342019 +-0.939693 0.000000 0.342019 +-0.766043 0.000000 0.642789 +-0.939693 0.000000 0.342019 +-0.939693 0.000000 0.342019 +-1.000000 -0.000000 -0.000000 +-1.000000 -0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-0.939693 0.000000 0.342019 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +0.939693 0.000000 -0.342020 +0.939693 0.000000 -0.342020 +0.939693 -0.000000 -0.342019 +1.000000 0.000000 -0.000000 +0.939693 -0.000000 -0.342019 +0.939693 0.000000 -0.342020 +0.766045 -0.000000 -0.642787 +0.766045 -0.000000 -0.642787 +0.766045 -0.000000 -0.642787 +0.939693 -0.000000 -0.342019 +0.766045 -0.000000 -0.642787 +0.766045 -0.000000 -0.642787 +0.500000 -0.000000 -0.866026 +0.500000 -0.000000 -0.866026 +0.500000 0.000000 -0.866026 +0.766045 -0.000000 -0.642787 +0.500000 0.000000 -0.866026 +0.500000 -0.000000 -0.866026 +0.173648 0.000000 -0.984808 +0.173648 0.000000 -0.984808 +0.173648 0.000000 -0.984808 +0.500000 0.000000 -0.866026 +0.173648 0.000000 -0.984808 +0.173648 0.000000 -0.984808 +-0.173649 0.000000 -0.984808 +-0.173649 0.000000 -0.984808 +-0.173649 0.000000 -0.984808 +0.173648 0.000000 -0.984808 +-0.173649 0.000000 -0.984808 +-0.173649 0.000000 -0.984808 +-0.500000 0.000000 -0.866025 +-0.500000 0.000000 -0.866025 +-0.500000 -0.000000 -0.866025 +-0.173649 0.000000 -0.984808 +-0.500000 -0.000000 -0.866025 +-0.500000 0.000000 -0.866025 +-0.766044 -0.000000 -0.642788 +-0.766044 -0.000000 -0.642788 +-0.766044 -0.000000 -0.642788 +-0.500000 -0.000000 -0.866025 +-0.766044 -0.000000 -0.642788 +-0.766044 -0.000000 -0.642788 +-0.939693 -0.000000 -0.342020 +-0.939693 -0.000000 -0.342020 +-0.939693 -0.000000 -0.342020 +-0.766044 -0.000000 -0.642788 +-0.939693 -0.000000 -0.342020 +-0.939693 -0.000000 -0.342020 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 -0.000000 -0.000000 +-0.939693 -0.000000 -0.342020 +-1.000000 -0.000000 -0.000000 +-1.000000 0.000000 0.000000 +-0.939693 0.000000 0.342020 +-0.939693 0.000000 0.342020 +-0.939693 0.000000 0.342020 +-1.000000 -0.000000 -0.000000 +-0.939693 0.000000 0.342020 +-0.939693 0.000000 0.342020 +-0.766045 0.000000 0.642787 +-0.766045 0.000000 0.642787 +-0.766045 0.000000 0.642787 +-0.939693 0.000000 0.342020 +-0.766045 0.000000 0.642787 +-0.766045 0.000000 0.642787 +-0.500000 0.000000 0.866025 +-0.500000 0.000000 0.866025 +-0.500000 0.000000 0.866025 +-0.766045 0.000000 0.642787 +-0.500000 0.000000 0.866025 +-0.500000 0.000000 0.866025 +-0.173648 0.000000 0.984808 +-0.173648 0.000000 0.984808 +-0.173648 0.000000 0.984808 +-0.500000 0.000000 0.866025 +-0.173648 0.000000 0.984808 +-0.173648 0.000000 0.984808 +0.173647 0.000000 0.984808 +0.173647 0.000000 0.984808 +0.173647 0.000000 0.984808 +-0.173648 0.000000 0.984808 +0.173647 0.000000 0.984808 +0.173647 0.000000 0.984808 +0.500000 0.000000 0.866026 +0.500000 0.000000 0.866026 +0.500000 0.000000 0.866026 +0.173647 0.000000 0.984808 +0.500000 0.000000 0.866026 +0.500000 0.000000 0.866026 +0.766044 0.000000 0.642788 +0.766044 0.000000 0.642788 +0.766044 0.000000 0.642788 +0.500000 0.000000 0.866026 +0.766044 0.000000 0.642788 +0.766044 0.000000 0.642788 +0.939692 0.000000 0.342021 +0.939692 0.000000 0.342021 +0.939692 0.000000 0.342021 +0.766044 0.000000 0.642788 +0.939692 0.000000 0.342021 +0.939692 0.000000 0.342021 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +0.939692 0.000000 0.342021 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 -0.000000 +-0.939694 -0.000000 -0.342017 +-0.939694 0.000000 -0.342017 +-0.939694 0.000000 -0.342017 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-0.939694 -0.000000 -0.342017 +-0.766044 -0.000000 -0.642789 +-0.766044 -0.000000 -0.642789 +-0.766044 -0.000000 -0.642789 +-0.939694 0.000000 -0.342017 +-0.939694 -0.000000 -0.342017 +-0.766044 -0.000000 -0.642789 +-0.499998 0.000000 -0.866026 +-0.499998 -0.000000 -0.866026 +-0.499998 -0.000000 -0.866026 +-0.766044 -0.000000 -0.642789 +-0.766044 -0.000000 -0.642789 +-0.499998 0.000000 -0.866026 +-0.173649 0.000000 -0.984808 +-0.173649 0.000000 -0.984808 +-0.173649 0.000000 -0.984808 +-0.499998 -0.000000 -0.866026 +-0.499998 0.000000 -0.866026 +-0.173649 0.000000 -0.984808 +0.173649 0.000000 -0.984808 +0.173649 0.000000 -0.984808 +0.173649 0.000000 -0.984808 +-0.173649 0.000000 -0.984808 +-0.173649 0.000000 -0.984808 +0.173649 0.000000 -0.984808 +0.500000 -0.000000 -0.866026 +0.500000 0.000000 -0.866026 +0.500000 0.000000 -0.866026 +0.173649 0.000000 -0.984808 +0.173649 0.000000 -0.984808 +0.500000 -0.000000 -0.866026 +0.766043 -0.000000 -0.642789 +0.766043 -0.000000 -0.642789 +0.766043 -0.000000 -0.642789 +0.500000 0.000000 -0.866026 +0.500000 -0.000000 -0.866026 +0.766043 -0.000000 -0.642789 +0.939693 -0.000000 -0.342019 +0.939693 -0.000000 -0.342019 +0.939693 -0.000000 -0.342019 +0.766043 -0.000000 -0.642789 +0.766043 -0.000000 -0.642789 +0.939693 -0.000000 -0.342019 +1.000000 -0.000000 -0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.939693 -0.000000 -0.342019 +0.939693 -0.000000 -0.342019 +1.000000 -0.000000 -0.000000 +0.939693 0.000000 0.342019 +0.939693 0.000000 0.342019 +0.939693 0.000000 0.342019 +1.000000 0.000000 0.000000 +1.000000 -0.000000 -0.000000 +0.939693 0.000000 0.342019 +0.766044 0.000000 0.642788 +0.766044 0.000000 0.642788 +0.766044 0.000000 0.642788 +0.939693 0.000000 0.342019 +0.939693 0.000000 0.342019 +0.766044 0.000000 0.642788 +0.500000 0.000000 0.866025 +0.500000 0.000000 0.866025 +0.500000 0.000000 0.866025 +0.766044 0.000000 0.642788 +0.766044 0.000000 0.642788 +0.500000 0.000000 0.866025 +0.173648 0.000000 0.984808 +0.173648 0.000000 0.984808 +0.173648 0.000000 0.984808 +0.500000 0.000000 0.866025 +0.500000 0.000000 0.866025 +0.173648 0.000000 0.984808 +-0.173648 0.000000 0.984808 +-0.173648 0.000000 0.984808 +-0.173648 0.000000 0.984808 +0.173648 0.000000 0.984808 +0.173648 0.000000 0.984808 +-0.173648 0.000000 0.984808 +-0.499999 0.000000 0.866026 +-0.499999 0.000000 0.866026 +-0.499999 0.000000 0.866026 +-0.173648 0.000000 0.984808 +-0.173648 0.000000 0.984808 +-0.499999 0.000000 0.866026 +-0.766043 0.000000 0.642789 +-0.766043 0.000000 0.642789 +-0.766043 0.000000 0.642789 +-0.499999 0.000000 0.866026 +-0.499999 0.000000 0.866026 +-0.766043 0.000000 0.642789 +-0.939693 0.000000 0.342019 +-0.939693 0.000000 0.342019 +-0.939693 0.000000 0.342019 +-0.766043 0.000000 0.642789 +-0.766043 0.000000 0.642789 +-0.939693 0.000000 0.342019 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-1.000000 0.000000 -0.000000 +-0.939693 0.000000 0.342019 +-0.939693 0.000000 0.342019 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.000001 -1.000000 -0.000009 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.000001 -1.000000 -0.000000 +0.000000 -1.000000 0.000000 +-0.000001 -1.000000 -0.000009 +-0.000001 -1.000000 -0.000009 +-0.000005 -1.000000 -0.000032 +-0.000001 -1.000000 -0.000000 +-0.000005 -1.000000 0.000015 +-0.000001 -1.000000 -0.000000 +-0.000005 -1.000000 -0.000032 +-0.000005 -1.000000 -0.000032 +0.000000 -1.000000 0.000054 +-0.000005 -1.000000 0.000015 +0.000000 -1.000000 0.000054 +0.000000 -1.000000 0.000000 +-0.000005 -1.000000 0.000015 +0.809111 0.000000 -0.587656 +0.973737 0.000000 -0.227676 +0.973737 0.000000 -0.227676 +0.973737 0.000000 -0.227676 +0.809110 -0.000003 -0.587657 +0.809111 0.000000 -0.587656 +-0.973737 0.000000 0.227677 +-0.973737 0.000000 0.227677 +-0.973737 0.000000 0.227677 +-0.973737 0.000000 0.227677 +-0.973737 0.000000 0.227677 +-0.973737 0.000000 0.227677 +-0.973737 -0.000003 0.227677 +-0.973737 0.000000 0.227677 +-0.973737 -0.000000 0.227677 +-0.973737 -0.000000 0.227677 +-0.973737 -0.000003 0.227677 +-0.973737 -0.000003 0.227677 +0.973737 0.000000 -0.227676 +0.809111 0.000000 -0.587656 +0.809111 0.000000 -0.587656 +0.809111 0.000000 -0.587656 +0.973737 0.000000 -0.227676 +0.973737 0.000000 -0.227676 +0.431554 -0.000021 -0.902087 +0.809111 0.000000 -0.587656 +0.809110 -0.000003 -0.587657 +0.809110 -0.000003 -0.587657 +0.431556 -0.000021 -0.902086 +0.431554 -0.000021 -0.902087 +-0.517703 -0.000008 -0.855561 +-0.431563 -0.000021 -0.902083 +-0.431565 -0.000022 -0.902082 +-0.431565 -0.000022 -0.902082 +-0.517701 -0.000003 -0.855562 +-0.517703 -0.000008 -0.855561 +0.232218 -0.000004 -0.972664 +0.431554 -0.000021 -0.902087 +0.431556 -0.000021 -0.902086 +0.431556 -0.000021 -0.902086 +0.232219 0.000000 -0.972663 +0.232218 -0.000004 -0.972664 +-0.431563 -0.000021 -0.902083 +-0.232215 0.000000 -0.972664 +-0.232217 -0.000004 -0.972664 +-0.232217 -0.000004 -0.972664 +-0.431565 -0.000022 -0.902082 +-0.431563 -0.000021 -0.902083 +-0.232215 0.000000 -0.972664 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.232217 -0.000004 -0.972664 +-0.232215 0.000000 -0.972664 +0.000000 0.000000 -1.000000 +0.232218 -0.000004 -0.972664 +0.232219 0.000000 -0.972663 +0.232219 0.000000 -0.972663 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.431540 0.000119 -0.902094 +-0.517708 0.000014 -0.855557 +-0.517697 0.000044 -0.855564 +-0.517697 0.000044 -0.855564 +-0.431571 0.000065 -0.902079 +-0.431540 0.000119 -0.902094 +0.809111 0.000000 -0.587656 +0.431565 -0.000007 -0.902082 +0.431568 0.000000 -0.902080 +0.431568 0.000000 -0.902080 +0.809111 0.000000 -0.587656 +0.809111 0.000000 -0.587656 +-0.232300 -0.000284 -0.972644 +-0.431540 0.000119 -0.902094 +-0.431571 0.000065 -0.902079 +-0.431571 0.000065 -0.902079 +-0.232283 -0.000276 -0.972648 +-0.232300 -0.000284 -0.972644 +0.431565 -0.000007 -0.902082 +0.232180 -0.000019 -0.972673 +0.232167 -0.000042 -0.972676 +0.232167 -0.000042 -0.972676 +0.431568 0.000000 -0.902080 +0.431565 -0.000007 -0.902082 +0.232180 -0.000019 -0.972673 +0.000091 0.000075 -1.000000 +0.000114 0.000121 -1.000000 +0.000114 0.000121 -1.000000 +0.232167 -0.000042 -0.972676 +0.232180 -0.000019 -0.972673 +0.000091 0.000075 -1.000000 +-0.232300 -0.000284 -0.972644 +-0.232283 -0.000276 -0.972648 +-0.232283 -0.000276 -0.972648 +0.000114 0.000121 -1.000000 +0.000091 0.000075 -1.000000 +0.984808 0.000000 -0.173645 +0.642787 0.000000 -0.766045 +0.642787 0.000000 -0.766045 +0.642787 0.000000 -0.766045 +0.984808 0.000000 -0.173645 +0.984808 0.000000 -0.173645 +0.642787 0.000000 -0.766045 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.642787 0.000000 -0.766045 +0.642787 0.000000 -0.766045 +0.000001 0.000000 -1.000000 +-0.642786 0.000000 -0.766046 +-0.642786 0.000000 -0.766046 +-0.642786 0.000000 -0.766046 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +-0.642786 0.000000 -0.766046 +-0.984808 0.000000 -0.173648 +-0.984808 0.000000 -0.173648 +-0.984808 0.000000 -0.173648 +-0.642786 0.000000 -0.766046 +-0.642786 0.000000 -0.766046 +-0.984808 0.000000 -0.173648 +-0.866024 0.000000 0.500002 +-0.866024 0.000000 0.500002 +-0.866024 0.000000 0.500002 +-0.984808 0.000000 -0.173648 +-0.984808 0.000000 -0.173648 +-0.866024 0.000000 0.500002 +-0.342020 0.000000 0.939693 +-0.342020 0.000000 0.939693 +-0.342020 0.000000 0.939693 +-0.866024 0.000000 0.500002 +-0.866024 0.000000 0.500002 +-0.342020 0.000000 0.939693 +0.342022 0.000000 0.939692 +0.342022 0.000000 0.939692 +0.342022 0.000000 0.939692 +-0.342020 0.000000 0.939693 +-0.342020 0.000000 0.939693 +0.342022 0.000000 0.939692 +0.866024 0.000000 0.500002 +0.866024 0.000000 0.500002 +0.866024 0.000000 0.500002 +0.342022 0.000000 0.939692 +0.342022 0.000000 0.939692 +0.866024 0.000000 0.500002 +0.984808 0.000000 -0.173645 +0.984808 0.000000 -0.173645 +0.984808 0.000000 -0.173645 +0.866024 0.000000 0.500002 +0.866024 0.000000 0.500002 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000001 -1.000000 -0.000009 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000001 -1.000000 -0.000000 +0.000005 -1.000000 -0.000032 +0.000001 -1.000000 -0.000009 +0.000001 -1.000000 -0.000009 +0.000000 -1.000000 0.000000 +0.000001 -1.000000 -0.000000 +0.000005 -1.000000 0.000015 +0.000000 -1.000000 0.000054 +0.000005 -1.000000 -0.000032 +0.000005 -1.000000 -0.000032 +0.000001 -1.000000 -0.000000 +0.000005 -1.000000 0.000015 +0.000000 -1.000000 0.000054 +0.000005 -1.000000 0.000015 +0.000000 -1.000000 0.000000 +-0.809109 0.000000 -0.587658 +-0.809108 -0.000003 -0.587659 +-0.973737 0.000000 -0.227677 +-0.973737 0.000000 -0.227677 +-0.973737 0.000000 -0.227677 +-0.809109 0.000000 -0.587658 +0.973737 0.000000 0.227677 +0.973737 0.000000 0.227677 +0.973737 0.000001 0.227677 +0.973737 0.000001 0.227677 +0.973737 0.000001 0.227677 +0.973737 0.000000 0.227677 +0.973737 -0.000004 0.227677 +0.973737 -0.000004 0.227677 +0.973737 -0.000000 0.227677 +0.973737 -0.000000 0.227677 +0.973737 0.000000 0.227677 +0.973737 -0.000004 0.227677 +-0.973737 0.000000 -0.227677 +-0.973737 0.000000 -0.227677 +-0.809109 0.000000 -0.587658 +-0.809109 0.000000 -0.587658 +-0.809109 0.000000 -0.587658 +-0.973737 0.000000 -0.227677 +-0.431551 -0.000021 -0.902089 +-0.431552 -0.000021 -0.902088 +-0.809108 -0.000003 -0.587659 +-0.809108 -0.000003 -0.587659 +-0.809109 0.000000 -0.587658 +-0.431551 -0.000021 -0.902089 +0.517705 -0.000008 -0.855559 +0.517703 -0.000003 -0.855560 +0.431564 -0.000022 -0.902083 +0.431564 -0.000022 -0.902083 +0.431562 -0.000021 -0.902083 +0.517705 -0.000008 -0.855559 +-0.232218 -0.000004 -0.972664 +-0.232219 0.000000 -0.972663 +-0.431552 -0.000021 -0.902088 +-0.431552 -0.000021 -0.902088 +-0.431551 -0.000021 -0.902089 +-0.232218 -0.000004 -0.972664 +0.431562 -0.000021 -0.902083 +0.431564 -0.000022 -0.902083 +0.232214 -0.000004 -0.972665 +0.232214 -0.000004 -0.972665 +0.232213 0.000000 -0.972665 +0.431562 -0.000021 -0.902083 +0.232213 0.000000 -0.972665 +0.232214 -0.000004 -0.972665 +-0.000001 0.000000 -1.000000 +-0.000001 0.000000 -1.000000 +-0.000001 0.000000 -1.000000 +0.232213 0.000000 -0.972665 +-0.000001 0.000000 -1.000000 +-0.000001 0.000000 -1.000000 +-0.232219 0.000000 -0.972663 +-0.232219 0.000000 -0.972663 +-0.232218 -0.000004 -0.972664 +-0.000001 0.000000 -1.000000 +0.431539 0.000119 -0.902094 +0.431569 0.000065 -0.902080 +0.517700 0.000044 -0.855562 +0.517700 0.000044 -0.855562 +0.517711 0.000014 -0.855556 +0.431539 0.000119 -0.902094 +-0.809109 0.000000 -0.587658 +-0.809109 0.000000 -0.587658 +-0.431565 0.000000 -0.902082 +-0.431565 0.000000 -0.902082 +-0.431562 -0.000007 -0.902083 +-0.809109 0.000000 -0.587658 +0.232298 -0.000284 -0.972645 +0.232281 -0.000276 -0.972649 +0.431569 0.000065 -0.902080 +0.431569 0.000065 -0.902080 +0.431539 0.000119 -0.902094 +0.232298 -0.000284 -0.972645 +-0.431562 -0.000007 -0.902083 +-0.431565 0.000000 -0.902082 +-0.232167 -0.000042 -0.972676 +-0.232167 -0.000042 -0.972676 +-0.232180 -0.000019 -0.972673 +-0.431562 -0.000007 -0.902083 +-0.232180 -0.000019 -0.972673 +-0.232167 -0.000042 -0.972676 +-0.000114 0.000121 -1.000000 +-0.000114 0.000121 -1.000000 +-0.000091 0.000075 -1.000000 +-0.232180 -0.000019 -0.972673 +-0.000091 0.000075 -1.000000 +-0.000114 0.000121 -1.000000 +0.232281 -0.000276 -0.972649 +0.232281 -0.000276 -0.972649 +0.232298 -0.000284 -0.972645 +-0.000091 0.000075 -1.000000 +-0.984809 0.000000 -0.173640 +-0.984809 0.000000 -0.173640 +-0.642788 0.000000 -0.766044 +-0.642788 0.000000 -0.766044 +-0.642788 0.000000 -0.766044 +-0.984809 0.000000 -0.173640 +-0.642788 0.000000 -0.766044 +-0.642788 0.000000 -0.766044 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +-0.642788 0.000000 -0.766044 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.642783 0.000000 -0.766048 +0.642783 0.000000 -0.766048 +0.642783 0.000000 -0.766048 +0.000001 0.000000 -1.000000 +0.642783 0.000000 -0.766048 +0.642783 0.000000 -0.766048 +0.984808 0.000000 -0.173648 +0.984808 0.000000 -0.173648 +0.984808 0.000000 -0.173647 +0.642783 0.000000 -0.766048 +0.984808 0.000000 -0.173647 +0.984808 0.000000 -0.173648 +0.866021 0.000000 0.500008 +0.866021 0.000000 0.500008 +0.866021 0.000000 0.500008 +0.984808 0.000000 -0.173647 +0.866021 0.000000 0.500008 +0.866021 0.000000 0.500008 +0.342020 0.000000 0.939693 +0.342020 0.000000 0.939693 +0.342020 0.000000 0.939693 +0.866021 0.000000 0.500008 +0.342020 0.000000 0.939693 +0.342020 0.000000 0.939693 +-0.342024 0.000000 0.939691 +-0.342024 0.000000 0.939691 +-0.342024 0.000000 0.939691 +0.342020 0.000000 0.939693 +-0.342024 0.000000 0.939691 +-0.342024 0.000000 0.939691 +-0.866024 0.000000 0.500003 +-0.866024 0.000000 0.500003 +-0.866024 0.000000 0.500003 +-0.342024 0.000000 0.939691 +-0.866024 0.000000 0.500003 +-0.866024 0.000000 0.500003 +-0.984809 0.000000 -0.173640 +-0.984809 0.000000 -0.173640 +-0.984809 0.000000 -0.173640 +-0.866024 0.000000 0.500003 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.809113 0.000000 -0.587653 +0.809112 0.000003 -0.587655 +0.973737 0.000000 -0.227677 +0.973737 0.000000 -0.227677 +0.973737 0.000000 -0.227677 +0.809113 0.000000 -0.587653 +-0.973737 -0.000000 0.227677 +-0.973737 0.000000 0.227677 +-0.973737 -0.000001 0.227677 +-0.973737 -0.000001 0.227677 +-0.973737 -0.000001 0.227677 +-0.973737 -0.000000 0.227677 +-0.973737 0.000004 0.227677 +-0.973737 0.000004 0.227677 +-0.973737 0.000000 0.227677 +-0.973737 0.000000 0.227677 +-0.973737 0.000000 0.227677 +-0.973737 0.000004 0.227677 +0.973737 0.000000 -0.227677 +0.973737 0.000000 -0.227677 +0.809113 0.000000 -0.587653 +0.809113 0.000000 -0.587653 +0.809113 0.000000 -0.587653 +0.973737 0.000000 -0.227677 +0.431556 0.000021 -0.902086 +0.431558 0.000021 -0.902085 +0.809112 0.000003 -0.587655 +0.809112 0.000003 -0.587655 +0.809113 0.000000 -0.587653 +0.431556 0.000021 -0.902086 +-0.517705 0.000008 -0.855559 +-0.517703 0.000003 -0.855560 +-0.431564 0.000022 -0.902083 +-0.431564 0.000022 -0.902083 +-0.431562 0.000021 -0.902083 +-0.517705 0.000008 -0.855559 +0.232217 0.000004 -0.972664 +0.232219 0.000000 -0.972664 +0.431558 0.000021 -0.902085 +0.431558 0.000021 -0.902085 +0.431556 0.000021 -0.902086 +0.232217 0.000004 -0.972664 +-0.431562 0.000021 -0.902083 +-0.431564 0.000022 -0.902083 +-0.232214 0.000004 -0.972665 +-0.232214 0.000004 -0.972665 +-0.232213 0.000000 -0.972665 +-0.431562 0.000021 -0.902083 +-0.232213 0.000000 -0.972665 +-0.232214 0.000004 -0.972665 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +-0.232213 0.000000 -0.972665 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.232219 0.000000 -0.972664 +0.232219 0.000000 -0.972664 +0.232217 0.000004 -0.972664 +-0.000000 0.000000 -1.000000 +-0.431539 -0.000119 -0.902094 +-0.431569 -0.000065 -0.902080 +-0.517700 -0.000044 -0.855562 +-0.517700 -0.000044 -0.855562 +-0.517711 -0.000014 -0.855556 +-0.431539 -0.000119 -0.902094 +0.809113 0.000000 -0.587653 +0.809113 0.000000 -0.587653 +0.431570 0.000000 -0.902079 +0.431570 0.000000 -0.902079 +0.431567 0.000007 -0.902081 +0.809113 0.000000 -0.587653 +-0.232298 0.000284 -0.972645 +-0.232281 0.000276 -0.972649 +-0.431569 -0.000065 -0.902080 +-0.431569 -0.000065 -0.902080 +-0.431539 -0.000119 -0.902094 +-0.232298 0.000284 -0.972645 +0.431567 0.000007 -0.902081 +0.431570 0.000000 -0.902079 +0.232166 0.000042 -0.972676 +0.232166 0.000042 -0.972676 +0.232179 0.000019 -0.972673 +0.431567 0.000007 -0.902081 +0.232179 0.000019 -0.972673 +0.232166 0.000042 -0.972676 +0.000113 -0.000121 -1.000000 +0.000113 -0.000121 -1.000000 +0.000090 -0.000075 -1.000000 +0.232179 0.000019 -0.972673 +0.000090 -0.000075 -1.000000 +0.000113 -0.000121 -1.000000 +-0.232281 0.000276 -0.972649 +-0.232281 0.000276 -0.972649 +-0.232298 0.000284 -0.972645 +0.000090 -0.000075 -1.000000 +0.984809 0.000000 -0.173643 +0.984809 0.000000 -0.173643 +0.642790 0.000000 -0.766042 +0.642790 0.000000 -0.766042 +0.642790 0.000000 -0.766042 +0.984809 0.000000 -0.173643 +0.642790 0.000000 -0.766042 +0.642790 0.000000 -0.766042 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000000 0.000000 -1.000000 +0.642790 0.000000 -0.766042 +-0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.642786 0.000000 -0.766046 +-0.642786 0.000000 -0.766046 +-0.642786 0.000000 -0.766046 +-0.000000 0.000000 -1.000000 +-0.642786 0.000000 -0.766046 +-0.642786 0.000000 -0.766046 +-0.984808 0.000000 -0.173648 +-0.984808 0.000000 -0.173648 +-0.984808 0.000000 -0.173648 +-0.642786 0.000000 -0.766046 +-0.984808 0.000000 -0.173648 +-0.984808 0.000000 -0.173648 +-0.866024 0.000000 0.500002 +-0.866024 0.000000 0.500002 +-0.866024 0.000000 0.500002 +-0.984808 0.000000 -0.173648 +-0.866024 0.000000 0.500002 +-0.866024 0.000000 0.500002 +-0.342020 0.000000 0.939693 +-0.342020 0.000000 0.939693 +-0.342020 0.000000 0.939693 +-0.866024 0.000000 0.500002 +-0.342020 0.000000 0.939693 +-0.342020 0.000000 0.939693 +0.342022 0.000000 0.939692 +0.342022 0.000000 0.939692 +0.342022 0.000000 0.939692 +-0.342020 0.000000 0.939693 +0.342022 0.000000 0.939692 +0.342022 0.000000 0.939692 +0.866026 0.000000 0.500000 +0.866026 0.000000 0.500000 +0.866026 0.000000 0.500000 +0.342022 0.000000 0.939692 +0.866026 0.000000 0.500000 +0.866026 0.000000 0.500000 +0.984809 0.000000 -0.173643 +0.984809 0.000000 -0.173643 +0.984809 0.000000 -0.173643 +0.866026 0.000000 0.500000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.809109 0.000000 -0.587658 +-0.973737 0.000000 -0.227677 +-0.973737 0.000000 -0.227677 +-0.973737 0.000000 -0.227677 +-0.809108 0.000003 -0.587659 +-0.809109 0.000000 -0.587658 +0.973737 0.000000 0.227677 +0.973737 0.000000 0.227677 +0.973737 0.000000 0.227677 +0.973737 0.000000 0.227677 +0.973737 0.000000 0.227677 +0.973737 0.000000 0.227677 +0.973737 0.000003 0.227677 +0.973737 0.000000 0.227677 +0.973737 0.000000 0.227677 +0.973737 0.000000 0.227677 +0.973737 0.000003 0.227677 +0.973737 0.000003 0.227677 +-0.973737 0.000000 -0.227677 +-0.809109 0.000000 -0.587658 +-0.809109 0.000000 -0.587658 +-0.809109 0.000000 -0.587658 +-0.973737 0.000000 -0.227677 +-0.973737 0.000000 -0.227677 +-0.431551 0.000021 -0.902089 +-0.809109 0.000000 -0.587658 +-0.809108 0.000003 -0.587659 +-0.809108 0.000003 -0.587659 +-0.431552 0.000021 -0.902088 +-0.431551 0.000021 -0.902089 +0.517705 0.000008 -0.855559 +0.431562 0.000021 -0.902083 +0.431564 0.000022 -0.902083 +0.431564 0.000022 -0.902083 +0.517703 0.000003 -0.855560 +0.517705 0.000008 -0.855559 +-0.232218 0.000004 -0.972664 +-0.431551 0.000021 -0.902089 +-0.431552 0.000021 -0.902088 +-0.431552 0.000021 -0.902088 +-0.232219 0.000000 -0.972663 +-0.232218 0.000004 -0.972664 +0.431562 0.000021 -0.902083 +0.232213 0.000000 -0.972665 +0.232214 0.000004 -0.972665 +0.232214 0.000004 -0.972665 +0.431564 0.000022 -0.902083 +0.431562 0.000021 -0.902083 +0.232213 0.000000 -0.972665 +-0.000001 0.000000 -1.000000 +-0.000001 0.000000 -1.000000 +-0.000001 0.000000 -1.000000 +0.232214 0.000004 -0.972665 +0.232213 0.000000 -0.972665 +-0.000001 0.000000 -1.000000 +-0.232218 0.000004 -0.972664 +-0.232219 0.000000 -0.972663 +-0.232219 0.000000 -0.972663 +-0.000001 0.000000 -1.000000 +-0.000001 0.000000 -1.000000 +0.431539 -0.000119 -0.902094 +0.517711 -0.000014 -0.855556 +0.517700 -0.000044 -0.855562 +0.517700 -0.000044 -0.855562 +0.431569 -0.000065 -0.902080 +0.431539 -0.000119 -0.902094 +-0.809109 0.000000 -0.587658 +-0.431562 0.000007 -0.902083 +-0.431565 0.000000 -0.902082 +-0.431565 0.000000 -0.902082 +-0.809109 0.000000 -0.587658 +-0.809109 0.000000 -0.587658 +0.232298 0.000284 -0.972645 +0.431539 -0.000119 -0.902094 +0.431569 -0.000065 -0.902080 +0.431569 -0.000065 -0.902080 +0.232281 0.000276 -0.972649 +0.232298 0.000284 -0.972645 +-0.431562 0.000007 -0.902083 +-0.232180 0.000019 -0.972673 +-0.232167 0.000042 -0.972676 +-0.232167 0.000042 -0.972676 +-0.431565 0.000000 -0.902082 +-0.431562 0.000007 -0.902083 +-0.232180 0.000019 -0.972673 +-0.000091 -0.000075 -1.000000 +-0.000114 -0.000121 -1.000000 +-0.000114 -0.000121 -1.000000 +-0.232167 0.000042 -0.972676 +-0.232180 0.000019 -0.972673 +-0.000091 -0.000075 -1.000000 +0.232298 0.000284 -0.972645 +0.232281 0.000276 -0.972649 +0.232281 0.000276 -0.972649 +-0.000114 -0.000121 -1.000000 +-0.000091 -0.000075 -1.000000 +-0.984809 0.000000 -0.173640 +-0.642788 0.000000 -0.766044 +-0.642788 0.000000 -0.766044 +-0.642788 0.000000 -0.766044 +-0.984809 0.000000 -0.173640 +-0.984809 0.000000 -0.173640 +-0.642788 0.000000 -0.766044 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +-0.642788 0.000000 -0.766044 +-0.642788 0.000000 -0.766044 +0.000001 0.000000 -1.000000 +0.642783 0.000000 -0.766048 +0.642783 0.000000 -0.766048 +0.642783 0.000000 -0.766048 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.642783 0.000000 -0.766048 +0.984808 0.000000 -0.173647 +0.984808 0.000000 -0.173648 +0.984808 0.000000 -0.173648 +0.642783 0.000000 -0.766048 +0.642783 0.000000 -0.766048 +0.984808 0.000000 -0.173647 +0.866021 0.000000 0.500008 +0.866021 0.000000 0.500008 +0.866021 0.000000 0.500008 +0.984808 0.000000 -0.173648 +0.984808 0.000000 -0.173647 +0.866021 0.000000 0.500008 +0.342020 0.000000 0.939693 +0.342020 0.000000 0.939693 +0.342020 0.000000 0.939693 +0.866021 0.000000 0.500008 +0.866021 0.000000 0.500008 +0.342020 0.000000 0.939693 +-0.342024 0.000000 0.939691 +-0.342024 0.000000 0.939691 +-0.342024 0.000000 0.939691 +0.342020 0.000000 0.939693 +0.342020 0.000000 0.939693 +-0.342024 0.000000 0.939691 +-0.866024 0.000000 0.500003 +-0.866024 0.000000 0.500003 +-0.866024 0.000000 0.500003 +-0.342024 0.000000 0.939691 +-0.342024 0.000000 0.939691 +-0.866024 0.000000 0.500003 +-0.984809 0.000000 -0.173640 +-0.984809 0.000000 -0.173640 +-0.984809 0.000000 -0.173640 +-0.866024 0.000000 0.500003 +-0.866024 0.000000 0.500003 +0.000000 0.707106 0.707108 +0.000000 -0.000002 1.000000 +0.000000 -0.000002 1.000000 +0.000000 -0.000002 1.000000 +0.000000 0.707106 0.707108 +0.000000 0.707106 0.707108 +0.000000 1.000000 0.000000 +0.000000 0.707106 0.707108 +0.000000 0.707106 0.707108 +0.000000 0.707106 0.707108 +0.000000 1.000000 -0.000000 +0.000000 1.000000 0.000000 +0.000000 0.707109 -0.707104 +0.000000 1.000000 0.000000 +0.000000 1.000000 -0.000000 +0.000000 1.000000 -0.000000 +0.000000 0.707109 -0.707104 +0.000000 0.707109 -0.707104 +0.000000 -0.000002 -1.000000 +0.000000 0.707109 -0.707104 +0.000000 0.707109 -0.707104 +0.000000 0.707109 -0.707104 +0.000000 -0.000002 -1.000000 +0.000000 -0.000002 -1.000000 +0.000000 -0.707111 -0.707103 +0.000000 -0.000002 -1.000000 +0.000000 -0.000002 -1.000000 +0.000000 -0.000002 -1.000000 +0.000000 -0.707111 -0.707103 +0.000000 -0.707111 -0.707103 +0.000000 -1.000000 -0.000000 +0.000000 -0.707111 -0.707103 +0.000000 -0.707111 -0.707103 +0.000000 -0.707111 -0.707103 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 -0.000000 +0.000000 -0.707107 0.707107 +0.000000 -1.000000 -0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.000002 1.000000 +0.000000 -0.000002 1.000000 +0.000000 -0.000002 1.000000 +0.000000 -0.707107 0.707107 +-1.000000 -0.000003 0.000000 +-0.707103 0.707111 0.000000 +-0.707103 0.707110 0.000000 +-0.707103 0.707110 0.000000 +-1.000000 -0.000003 0.000000 +-1.000000 -0.000003 0.000000 +-0.707103 0.707111 0.000000 +-0.000001 1.000000 0.000000 +-0.000001 1.000000 0.000000 +-0.000001 1.000000 0.000000 +-0.707103 0.707110 0.000000 +-0.707103 0.707111 0.000000 +-0.000001 1.000000 0.000000 +0.707104 0.707110 0.000000 +0.707104 0.707110 0.000000 +0.707104 0.707110 0.000000 +-0.000001 1.000000 0.000000 +-0.000001 1.000000 0.000000 +0.707104 0.707110 0.000000 +1.000000 -0.000003 0.000000 +1.000000 -0.000003 0.000000 +1.000000 -0.000003 0.000000 +0.707104 0.707110 0.000000 +0.707104 0.707110 0.000000 +1.000000 -0.000003 0.000000 +0.707107 -0.707106 0.000000 +0.707107 -0.707106 0.000000 +0.707107 -0.707106 0.000000 +1.000000 -0.000003 0.000000 +1.000000 -0.000003 0.000000 +0.707107 -0.707106 0.000000 +-0.000001 -1.000000 0.000000 +-0.000001 -1.000000 0.000000 +-0.000001 -1.000000 0.000000 +0.707107 -0.707106 0.000000 +0.707107 -0.707106 0.000000 +-0.000001 -1.000000 0.000000 +-0.707106 -0.707108 0.000000 +-0.707106 -0.707107 0.000000 +-0.707106 -0.707107 0.000000 +-0.000001 -1.000000 0.000000 +-0.000001 -1.000000 0.000000 +-0.707106 -0.707108 0.000000 +-1.000000 -0.000003 0.000000 +-1.000000 -0.000003 0.000000 +-1.000000 -0.000003 0.000000 +-0.707106 -0.707107 0.000000 +-0.707106 -0.707108 0.000000 +-1.000000 -0.000004 -0.000000 +-0.707104 0.707110 -0.000000 +-0.707103 0.707110 -0.000000 +-0.707103 0.707110 -0.000000 +-1.000000 -0.000003 0.000000 +-1.000000 -0.000004 -0.000000 +-0.707104 0.707110 -0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 -0.000000 +0.000001 1.000000 -0.000000 +-0.707103 0.707110 -0.000000 +-0.707104 0.707110 -0.000000 +0.000001 1.000000 0.000000 +0.707104 0.707109 0.000000 +0.707104 0.707109 0.000000 +0.707104 0.707109 0.000000 +0.000001 1.000000 -0.000000 +0.000001 1.000000 0.000000 +0.707104 0.707109 0.000000 +1.000000 -0.000003 0.000000 +1.000000 -0.000003 0.000000 +1.000000 -0.000003 0.000000 +0.707104 0.707109 0.000000 +0.707104 0.707109 0.000000 +1.000000 -0.000003 0.000000 +0.707107 -0.707106 0.000000 +0.707107 -0.707106 0.000000 +0.707107 -0.707106 0.000000 +1.000000 -0.000003 0.000000 +1.000000 -0.000003 0.000000 +0.707107 -0.707106 0.000000 +0.000000 -1.000000 0.000000 +0.000001 -1.000000 0.000000 +0.000001 -1.000000 0.000000 +0.707107 -0.707106 0.000000 +0.707107 -0.707106 0.000000 +0.000000 -1.000000 0.000000 +-0.707106 -0.707107 0.000000 +-0.707106 -0.707107 0.000000 +-0.707106 -0.707107 0.000000 +0.000001 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.707106 -0.707107 0.000000 +-1.000000 -0.000004 -0.000000 +-1.000000 -0.000003 0.000000 +-1.000000 -0.000003 0.000000 +-0.707106 -0.707107 0.000000 +-0.707106 -0.707107 0.000000 +0.000000 0.707108 0.707106 +0.000000 0.707108 0.707106 +0.000000 -0.000002 1.000000 +0.000000 -0.000002 1.000000 +0.000000 -0.000002 1.000000 +0.000000 0.707108 0.707106 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +0.000000 0.707108 0.707106 +0.000000 0.707108 0.707106 +0.000000 0.707108 0.707106 +0.000000 1.000000 0.000002 +0.000000 0.707109 -0.707104 +0.000000 0.707109 -0.707104 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +0.000000 1.000000 0.000002 +0.000000 0.707109 -0.707104 +0.000000 -0.000002 -1.000000 +0.000000 -0.000002 -1.000000 +0.000000 0.707109 -0.707104 +0.000000 0.707109 -0.707104 +0.000000 0.707109 -0.707104 +0.000000 -0.000002 -1.000000 +0.000000 -0.707111 -0.707103 +0.000000 -0.707111 -0.707103 +0.000000 -0.000002 -1.000000 +0.000000 -0.000002 -1.000000 +0.000000 -0.000002 -1.000000 +0.000000 -0.707111 -0.707103 +0.000000 -1.000000 0.000002 +0.000000 -1.000000 0.000002 +0.000000 -0.707111 -0.707103 +0.000000 -0.707111 -0.707103 +0.000000 -0.707111 -0.707103 +0.000000 -1.000000 0.000002 +0.000000 -0.707109 0.707104 +0.000000 -0.707109 0.707105 +0.000000 -1.000000 0.000002 +0.000000 -1.000000 0.000002 +0.000000 -1.000000 0.000002 +0.000000 -0.707109 0.707104 +0.000000 -0.707109 0.707104 +0.000000 -0.000002 1.000000 +0.000000 -0.000002 1.000000 +0.000000 -0.000002 1.000000 +0.000000 -0.707109 0.707105 +0.000000 -0.707109 0.707104 +1.000000 -0.000003 0.000000 +1.000000 -0.000003 0.000000 +0.707101 0.707112 0.000000 +0.707101 0.707112 0.000000 +0.707101 0.707113 0.000000 +1.000000 -0.000003 0.000000 +0.707101 0.707113 0.000000 +0.707101 0.707112 0.000000 +0.000003 1.000000 0.000000 +0.000003 1.000000 0.000000 +0.000003 1.000000 0.000000 +0.707101 0.707113 0.000000 +0.000003 1.000000 0.000000 +0.000003 1.000000 0.000000 +-0.707104 0.707110 0.000000 +-0.707104 0.707110 0.000000 +-0.707104 0.707109 0.000000 +0.000003 1.000000 0.000000 +-0.707104 0.707109 0.000000 +-0.707104 0.707110 0.000000 +-1.000000 -0.000003 0.000000 +-1.000000 -0.000003 0.000000 +-1.000000 -0.000003 0.000000 +-0.707104 0.707109 0.000000 +-1.000000 -0.000003 0.000000 +-1.000000 -0.000003 0.000000 +-0.707107 -0.707106 0.000000 +-0.707107 -0.707106 0.000000 +-0.707107 -0.707106 0.000000 +-1.000000 -0.000003 0.000000 +-0.707107 -0.707106 0.000000 +-0.707107 -0.707106 0.000000 +0.000003 -1.000000 0.000000 +0.000003 -1.000000 0.000000 +0.000003 -1.000000 0.000000 +-0.707107 -0.707106 0.000000 +0.000003 -1.000000 0.000000 +0.000003 -1.000000 0.000000 +0.707104 -0.707110 0.000000 +0.707104 -0.707110 0.000000 +0.707104 -0.707110 0.000000 +0.000003 -1.000000 0.000000 +0.707104 -0.707110 0.000000 +0.707104 -0.707110 0.000000 +1.000000 -0.000003 0.000000 +1.000000 -0.000003 0.000000 +1.000000 -0.000003 0.000000 +0.707104 -0.707110 0.000000 +1.000000 -0.000003 0.000000 +1.000000 -0.000003 0.000000 +0.707103 0.707110 0.000000 +0.707103 0.707110 0.000000 +0.707103 0.707110 0.000000 +1.000000 -0.000003 0.000000 +0.707103 0.707110 0.000000 +0.707103 0.707110 0.000000 +-0.000001 1.000000 0.000000 +-0.000001 1.000000 0.000000 +-0.000001 1.000000 0.000000 +0.707103 0.707110 0.000000 +-0.000001 1.000000 0.000000 +-0.000001 1.000000 0.000000 +-0.707101 0.707112 0.000000 +-0.707101 0.707112 0.000000 +-0.707101 0.707112 0.000000 +-0.000001 1.000000 0.000000 +-0.707101 0.707112 0.000000 +-0.707101 0.707112 0.000000 +-1.000000 -0.000003 0.000000 +-1.000000 -0.000003 0.000000 +-1.000000 -0.000003 0.000000 +-0.707101 0.707112 0.000000 +-1.000000 -0.000003 0.000000 +-1.000000 -0.000003 0.000000 +-0.707104 -0.707109 0.000000 +-0.707104 -0.707109 0.000000 +-0.707104 -0.707109 0.000000 +-1.000000 -0.000003 0.000000 +-0.707104 -0.707109 0.000000 +-0.707104 -0.707109 0.000000 +-0.000001 -1.000000 0.000000 +-0.000001 -1.000000 0.000000 +-0.000001 -1.000000 0.000000 +-0.707104 -0.707109 0.000000 +-0.000001 -1.000000 0.000000 +-0.000001 -1.000000 0.000000 +0.707106 -0.707107 0.000000 +0.707106 -0.707107 0.000000 +0.707106 -0.707107 0.000000 +-0.000001 -1.000000 0.000000 +0.707106 -0.707107 0.000000 +0.707106 -0.707107 0.000000 +1.000000 -0.000003 0.000000 +1.000000 -0.000003 0.000000 +1.000000 -0.000003 0.000000 +0.707106 -0.707107 0.000000 + + + + + + + + + + + +0.962718 0.097492 +0.785926 0.097711 +0.785912 0.085800 +0.962703 0.085582 +0.533273 0.064974 +0.469898 0.065137 +0.469869 0.053197 +0.533243 0.053034 +0.780060 0.085807 +0.395865 0.350816 +0.613251 0.051819 +0.982278 0.145638 +0.841133 0.135570 +0.982291 0.135754 +0.533217 0.043125 +0.216895 0.351441 +0.076535 0.085205 +0.082372 0.085196 +0.247059 0.084938 +0.082367 0.082204 +0.247054 0.081946 +0.533200 0.040136 +0.159767 0.042734 +0.613208 0.063579 +0.192131 0.351658 +0.065963 0.081731 +0.013274 0.351410 +0.312722 0.009084 +0.312722 0.020994 +0.302225 0.020994 +0.780024 0.097718 +0.302919 0.096387 +0.288985 0.096387 +0.302919 0.106273 +0.288985 0.106272 +0.312566 0.040069 +0.302078 0.040031 +0.312556 0.043058 +0.076309 0.082201 +0.553539 0.052685 +0.553710 0.064443 +0.553397 0.042928 +0.159785 0.009079 +0.006628 0.136336 +0.026910 0.136284 +0.026885 0.126400 +0.026855 0.114489 +0.006573 0.114540 +0.006603 0.126451 +0.805329 0.115639 +0.805336 0.103728 +0.982127 0.103838 +0.982120 0.115748 +0.406516 0.065280 +0.406489 0.053339 +0.650881 0.014828 +0.200058 0.350984 +0.324980 0.052508 +0.987979 0.103842 +0.650882 0.024713 +0.509723 0.024723 +0.406467 0.043429 +0.085032 0.031363 +0.249725 0.032637 +0.255559 0.032681 +0.264814 0.032317 +0.085055 0.028370 +0.249748 0.029646 +0.325045 0.064512 +0.208742 0.350678 +0.095582 0.096380 +0.096565 0.020988 +0.095582 0.106264 +0.096531 0.039809 +0.005129 0.350608 +0.266143 0.029272 +0.017334 0.009083 +0.006837 0.020996 +0.006836 0.009084 +0.988022 0.115752 +0.014700 0.096387 +0.014701 0.106271 +0.006836 0.040069 +0.017348 0.043030 +0.006845 0.043063 +0.255803 0.029680 +0.385933 0.053281 +0.385781 0.065283 +0.386059 0.043320 +0.679412 0.039084 +0.659130 0.039084 +0.679412 0.060880 +0.679412 0.048969 +0.659130 0.048969 +0.659130 0.060880 +0.036229 0.566111 +0.277315 0.361151 +0.020460 0.361020 +0.600077 0.566528 +0.704641 0.062956 +0.977524 0.062956 +0.245847 0.121733 +0.372218 0.123456 +0.380255 0.319669 +0.232327 0.320416 +0.339240 0.086644 +0.612122 0.087465 +0.043215 0.121936 +0.169503 0.124203 +0.176784 0.320404 +0.028847 0.320467 +0.692888 0.040720 +0.989983 0.040720 +0.394534 0.333952 +0.217982 0.333981 +0.692888 0.019963 +0.989983 0.019963 +0.191072 0.334728 +0.014443 0.333964 +0.697932 0.131753 +0.400850 0.130459 +0.984710 0.183163 +0.808851 0.182199 +0.399403 0.125514 +0.696501 0.126805 +0.812907 0.174608 +0.988769 0.175780 +0.674296 0.162825 +0.424215 0.161736 +0.953406 0.206493 +0.839897 0.205871 +0.423040 0.094441 +0.673134 0.095528 +0.844239 0.151315 +0.957750 0.152071 +0.238531 0.121292 +0.224710 0.319119 +0.184505 0.319322 +0.176726 0.123984 +0.379442 0.123209 +0.387976 0.318567 +0.035904 0.121464 +0.021238 0.319137 +0.198376 0.333650 +0.210649 0.332829 +0.007119 0.332778 +0.401884 0.332938 +0.805506 0.167317 +0.705143 0.134191 +0.392191 0.123075 +0.991919 0.185611 +0.837994 0.145667 +0.681508 0.165264 +0.415828 0.092002 +0.960614 0.208940 +0.798235 0.165186 +0.797788 0.126875 +0.812769 0.133815 +0.793732 0.165239 +0.793285 0.126928 +0.778470 0.134216 +0.709693 0.212066 +0.709246 0.173754 +0.724227 0.180694 +0.705190 0.212118 +0.704742 0.173807 +0.689928 0.181095 +0.209812 0.202408 +0.209532 0.164095 +0.224482 0.171100 +0.205309 0.202441 +0.205028 0.164128 +0.190182 0.171351 +0.785520 0.211657 +0.785072 0.173345 +0.800053 0.180286 +0.781016 0.211710 +0.780569 0.173398 +0.765754 0.180686 +0.206917 0.160879 +0.206670 0.122566 +0.221614 0.129585 +0.203539 0.160901 +0.202166 0.122595 +0.741013 0.211981 +0.725751 0.180958 +0.740566 0.173670 +0.745069 0.173617 +0.745517 0.211929 +0.760050 0.180558 +0.202547 0.326199 +0.187420 0.295110 +0.202267 0.287886 +0.206770 0.287853 +0.207051 0.326166 +0.221721 0.294859 +0.205500 0.243982 +0.190374 0.212892 +0.205220 0.205669 +0.209723 0.205636 +0.210004 0.243949 +0.224674 0.212641 +0.205128 0.284751 +0.190001 0.253662 +0.204848 0.246438 +0.209351 0.246406 +0.209631 0.284719 +0.224302 0.253411 +0.187530 0.130236 +0.941787 0.247187 +0.926888 0.215988 +0.941787 0.208873 +0.946290 0.208873 +0.946291 0.247187 +0.961189 0.215987 +0.905656 0.247188 +0.890756 0.215989 +0.905655 0.208874 +0.910159 0.208874 +0.910159 0.247188 +0.925058 0.215988 +0.978855 0.247188 +0.963956 0.215989 +0.978855 0.208874 +0.983358 0.208874 +0.983359 0.247188 +0.998257 0.215988 +0.869514 0.247187 +0.854615 0.215987 +0.869513 0.208873 +0.874017 0.208873 +0.874017 0.247187 +0.888916 0.215987 +0.761604 0.179225 +0.746144 0.148300 +0.760912 0.140917 +0.765415 0.140836 +0.764981 0.179164 +0.836423 0.248501 +0.836422 0.210187 +0.851321 0.217301 +0.831919 0.248501 +0.831919 0.210187 +0.817020 0.217302 +0.765215 0.244214 +0.765214 0.205900 +0.780113 0.213015 +0.760711 0.244214 +0.760711 0.205900 +0.745812 0.213015 +0.727478 0.245819 +0.727478 0.207505 +0.742377 0.214620 +0.722974 0.245819 +0.722974 0.207505 +0.708075 0.214620 +0.798727 0.249138 +0.798726 0.210824 +0.813625 0.217939 +0.794223 0.249138 +0.794223 0.210824 +0.779324 0.217939 +0.780234 0.148116 +0.765162 0.139848 +0.765583 0.101536 +0.780403 0.108814 +0.760659 0.139798 +0.761080 0.101486 +0.746104 0.108437 +0.707895 0.280630 +0.708380 0.242319 +0.723188 0.249621 +0.703392 0.280573 +0.703877 0.242262 +0.688889 0.249187 +0.734623 0.164070 +0.734148 0.125758 +0.749134 0.132688 +0.730120 0.164126 +0.729645 0.125814 +0.714836 0.133113 +0.729753 0.124028 +0.714679 0.092913 +0.729538 0.085715 +0.734042 0.085690 +0.734256 0.124003 +0.748980 0.092721 +0.722946 0.315807 +0.708564 0.284366 +0.723579 0.277499 +0.728082 0.277573 +0.727449 0.315882 +0.742861 0.284933 +0.742406 0.279084 +0.728025 0.247643 +0.743039 0.240775 +0.747542 0.240850 +0.746909 0.279158 +0.762321 0.248210 +0.744231 0.678025 +0.725296 0.678025 +0.725296 0.650471 +0.744231 0.650471 +0.706360 0.678025 +0.706360 0.650471 +0.687424 0.678025 +0.687424 0.650471 +0.668488 0.678025 +0.668488 0.650471 +0.649551 0.678025 +0.649551 0.650471 +0.971420 0.678025 +0.971420 0.650471 +0.952487 0.678025 +0.952487 0.650471 +0.933556 0.678025 +0.933556 0.650471 +0.914624 0.678025 +0.914624 0.650471 +0.895692 0.678025 +0.895692 0.650471 +0.876761 0.678025 +0.876761 0.650471 +0.857829 0.678025 +0.857829 0.650471 +0.838898 0.678025 +0.838898 0.650471 +0.819952 0.678025 +0.819952 0.650471 +0.801033 0.678025 +0.801033 0.650471 +0.782100 0.678025 +0.782100 0.650471 +0.763166 0.678025 +0.763166 0.650471 +0.725958 0.683942 +0.725958 0.711495 +0.707019 0.711495 +0.707019 0.683942 +0.688080 0.711495 +0.688080 0.683942 +0.669141 0.711495 +0.669141 0.683942 +0.650201 0.711495 +0.650201 0.683942 +0.972069 0.711495 +0.972069 0.683942 +0.953142 0.711495 +0.953142 0.683942 +0.934215 0.711495 +0.934215 0.683942 +0.915287 0.711495 +0.915287 0.683942 +0.896359 0.711495 +0.896359 0.683942 +0.877429 0.711495 +0.877429 0.683942 +0.858499 0.711495 +0.858499 0.683942 +0.839567 0.711495 +0.839567 0.683942 +0.820615 0.711495 +0.820615 0.683942 +0.801702 0.711495 +0.801702 0.683942 +0.782768 0.711495 +0.782768 0.683942 +0.763832 0.711495 +0.763832 0.683942 +0.744895 0.711495 +0.744895 0.683942 +0.745805 0.716864 +0.745805 0.744417 +0.726878 0.744417 +0.726878 0.716864 +0.707951 0.744417 +0.707951 0.716864 +0.689025 0.744417 +0.689025 0.716864 +0.670099 0.744417 +0.670099 0.716864 +0.651172 0.744417 +0.651172 0.716864 +0.973028 0.744417 +0.973028 0.716864 +0.954086 0.744417 +0.954086 0.716864 +0.935145 0.744417 +0.935145 0.716864 +0.916206 0.744417 +0.916206 0.716864 +0.897267 0.744417 +0.897267 0.716864 +0.878330 0.744417 +0.878330 0.716864 +0.859394 0.744417 +0.859394 0.716864 +0.840459 0.744417 +0.840459 0.716864 +0.821525 0.744417 +0.821525 0.716864 +0.802593 0.744417 +0.802593 0.716864 +0.783663 0.744417 +0.783663 0.716864 +0.764733 0.744417 +0.764733 0.716864 +0.725776 0.645703 +0.706838 0.645703 +0.706838 0.618147 +0.725776 0.618147 +0.687901 0.645703 +0.687901 0.618147 +0.668963 0.645703 +0.668963 0.618147 +0.650025 0.645703 +0.650025 0.618147 +0.971923 0.645703 +0.971923 0.618147 +0.952992 0.645703 +0.952992 0.618147 +0.934061 0.645703 +0.934061 0.618147 +0.915129 0.645703 +0.915129 0.618147 +0.896197 0.645703 +0.896197 0.618147 +0.877264 0.645703 +0.877264 0.618147 +0.858330 0.645703 +0.858330 0.618147 +0.839396 0.645703 +0.839396 0.618147 +0.820461 0.645703 +0.820461 0.618147 +0.801525 0.645703 +0.801525 0.618147 +0.782589 0.645703 +0.782589 0.618147 +0.763652 0.645703 +0.763652 0.618147 +0.744714 0.645703 +0.744714 0.618147 +0.929712 0.897583 +0.930427 0.998107 +0.903560 0.992027 +0.902845 0.891502 +0.961986 0.792536 +0.988828 0.786346 +0.988521 0.886874 +0.961679 0.893063 +0.907936 0.889806 +0.925848 0.893860 +0.912782 0.889194 +0.921738 0.891220 +0.917384 0.889665 +0.965835 0.788797 +0.983730 0.784671 +0.969934 0.786142 +0.978880 0.784077 +0.974282 0.784568 +0.896920 0.884571 +0.870153 0.891075 +0.869282 0.790551 +0.896050 0.784047 +0.811491 0.992036 +0.811320 0.891508 +0.838153 0.897734 +0.838325 0.998262 +0.873088 0.786767 +0.890933 0.782431 +0.877156 0.784064 +0.886078 0.781896 +0.881485 0.782439 +0.816420 0.889840 +0.834309 0.893990 +0.821269 0.889253 +0.830214 0.891329 +0.825867 0.889750 +0.688145 0.825747 +0.682005 0.825747 +0.682005 0.788648 +0.688145 0.788648 +0.677858 0.825747 +0.677858 0.788648 +0.673712 0.825747 +0.673712 0.788648 +0.667571 0.825747 +0.667571 0.788648 +0.660875 0.825747 +0.660875 0.788648 +0.655700 0.825747 +0.655700 0.788648 +0.652039 0.825747 +0.652039 0.788648 +0.694841 0.825747 +0.694841 0.788648 +0.841662 0.897576 +0.868434 0.891093 +0.869227 0.991617 +0.842454 0.998100 +0.710152 0.898309 +0.711302 0.998830 +0.684409 0.992865 +0.683259 0.892345 +0.863319 0.889473 +0.845469 0.893795 +0.858465 0.888934 +0.849540 0.891095 +0.853871 0.889475 +0.706271 0.894603 +0.688342 0.890627 +0.702150 0.891981 +0.693186 0.889993 +0.697789 0.890446 +0.779887 0.991303 +0.779715 0.890775 +0.806548 0.897001 +0.806722 0.997528 +0.862394 0.885521 +0.835534 0.891631 +0.836139 0.791106 +0.863000 0.784996 +0.784815 0.889106 +0.802704 0.893257 +0.789665 0.888520 +0.798609 0.890595 +0.794263 0.889016 +0.840000 0.787379 +0.857908 0.783305 +0.844107 0.784735 +0.853061 0.782699 +0.848461 0.783175 +0.739616 0.788214 +0.739616 0.825320 +0.733474 0.825320 +0.733474 0.788214 +0.729326 0.825320 +0.729326 0.788214 +0.725179 0.825320 +0.725179 0.788214 +0.719037 0.825320 +0.719037 0.788214 +0.712339 0.825320 +0.712340 0.788214 +0.707163 0.825320 +0.707163 0.788214 +0.751490 0.825320 +0.751490 0.788214 +0.746312 0.825320 +0.746312 0.788214 +0.969708 0.898199 +0.996510 0.891839 +0.996843 0.992366 +0.970041 0.998726 +0.963770 0.898540 +0.964374 0.999066 +0.937514 0.992955 +0.936910 0.892430 +0.991401 0.890196 +0.973533 0.894436 +0.986548 0.889634 +0.977615 0.891755 +0.981954 0.890154 +0.959909 0.894813 +0.942003 0.890739 +0.955802 0.892169 +0.946850 0.890132 +0.951449 0.890609 +0.906181 0.883206 +0.907427 0.782686 +0.934171 0.789290 +0.932923 0.889811 +0.678776 0.992433 +0.651882 0.998389 +0.653067 0.897868 +0.679962 0.891913 +0.912551 0.781090 +0.930379 0.785492 +0.917407 0.780572 +0.926321 0.782774 +0.921997 0.781134 +0.656948 0.894163 +0.674879 0.890193 +0.661070 0.891543 +0.670036 0.889558 +0.665432 0.890008 +0.665386 0.786241 +0.665386 0.749135 +0.671527 0.749135 +0.671527 0.786241 +0.675674 0.749135 +0.675674 0.786241 +0.679822 0.749135 +0.679822 0.786241 +0.685964 0.749135 +0.685964 0.786241 +0.692661 0.749135 +0.692661 0.786241 +0.697838 0.749135 +0.697838 0.786241 +0.701499 0.749135 +0.701499 0.786241 +0.658689 0.749135 +0.658689 0.786241 +0.741987 0.897511 +0.742843 0.998036 +0.715967 0.991993 +0.715111 0.891468 +0.872759 0.897623 +0.899532 0.891140 +0.900325 0.991665 +0.873552 0.998148 +0.720200 0.889766 +0.738117 0.893794 +0.725046 0.889145 +0.734004 0.891161 +0.729648 0.889611 +0.876568 0.893843 +0.894416 0.889521 +0.880638 0.891142 +0.889561 0.888980 +0.884968 0.889522 +0.830122 0.884867 +0.803262 0.890977 +0.803868 0.790451 +0.830728 0.784342 +0.748488 0.992323 +0.748315 0.891795 +0.775149 0.898021 +0.775321 0.998548 +0.807729 0.786724 +0.825636 0.782651 +0.811836 0.784081 +0.820789 0.782044 +0.816189 0.782520 +0.753415 0.890127 +0.771305 0.894277 +0.758265 0.889540 +0.767210 0.891615 +0.762863 0.890037 +0.738349 0.786207 +0.732207 0.786207 +0.732207 0.749101 +0.738349 0.749101 +0.728060 0.786207 +0.728060 0.749101 +0.723912 0.786207 +0.723912 0.749101 +0.717770 0.786207 +0.717770 0.749101 +0.711073 0.786207 +0.711073 0.749101 +0.705896 0.786207 +0.705896 0.749101 +0.750222 0.786207 +0.750222 0.749101 +0.745045 0.786207 +0.745045 0.749101 +0.626234 0.061351 +0.623284 0.061351 +0.623284 0.039693 +0.626234 0.039693 +0.630928 0.061351 +0.630928 0.039693 +0.635622 0.061351 +0.635622 0.039693 +0.638572 0.061352 +0.638572 0.039693 +0.641522 0.061352 +0.641522 0.039693 +0.646216 0.061352 +0.646216 0.039693 +0.650910 0.061352 +0.650910 0.039693 +0.696806 0.090865 +0.696820 0.092437 +0.684184 0.092551 +0.684170 0.090980 +0.696835 0.094008 +0.684198 0.094123 +0.696735 0.083009 +0.684099 0.083123 +0.696749 0.084580 +0.684113 0.084695 +0.696764 0.086152 +0.684127 0.086266 +0.696778 0.087723 +0.684141 0.087838 +0.696792 0.089294 +0.684156 0.089409 +0.689627 0.076494 +0.689613 0.078065 +0.676977 0.077951 +0.676991 0.076380 +0.689599 0.079637 +0.676962 0.079522 +0.689698 0.068637 +0.677061 0.068523 +0.689684 0.070209 +0.677047 0.070095 +0.689670 0.071780 +0.677033 0.071666 +0.689655 0.073351 +0.677019 0.073237 +0.689641 0.074923 +0.677005 0.074809 +0.645476 0.067196 +0.645476 0.088854 +0.642526 0.088854 +0.642526 0.067196 +0.650170 0.067196 +0.650170 0.088854 +0.654864 0.067196 +0.654864 0.088854 +0.657814 0.067196 +0.657814 0.088854 +0.660764 0.067196 +0.660765 0.088854 +0.665458 0.067196 +0.665458 0.088854 +0.670152 0.067196 +0.670152 0.088854 +0.635789 0.088435 +0.632534 0.088427 +0.632548 0.088000 +0.635802 0.088060 +0.632561 0.087587 +0.635815 0.087666 +0.632677 0.090618 +0.635907 0.090221 +0.632621 0.090194 +0.635857 0.089850 +0.632574 0.089757 +0.635818 0.089493 +0.632543 0.089311 +0.635793 0.089145 +0.632531 0.088866 +0.635784 0.088795 +0.636294 0.080370 +0.633039 0.080362 +0.633052 0.079935 +0.636306 0.079995 +0.633065 0.079523 +0.636319 0.079601 +0.633181 0.082553 +0.636412 0.082156 +0.633125 0.082129 +0.636362 0.081785 +0.633078 0.081692 +0.636322 0.081429 +0.633047 0.081247 +0.636297 0.081080 +0.633035 0.080801 +0.636289 0.080730 +0.420844 0.326712 +0.420558 0.172494 +0.677403 0.172019 +0.677689 0.326237 +0.687378 0.316368 +0.687124 0.181632 +0.410869 0.182364 +0.411122 0.317100 +0.684906 0.323816 +0.413617 0.324318 +0.684629 0.174413 +0.413341 0.174915 +0.863789 0.435271 +0.860755 0.416581 +0.889682 0.416006 +0.886531 0.434678 +0.851512 0.400055 +0.899028 0.399539 +0.837173 0.387688 +0.913442 0.387261 +0.819470 0.380971 +0.931187 0.380653 +0.990353 0.678025 +0.800537 0.380713 +0.990353 0.650471 +0.950122 0.380514 +0.782658 0.386946 +0.967962 0.386858 +0.767988 0.398919 +0.982556 0.398922 +0.758299 0.415187 +0.992144 0.415250 +0.754757 0.433788 +0.995570 0.433873 +0.757791 0.452479 +0.992420 0.452544 +0.767035 0.469004 +0.983073 0.469012 +0.781373 0.481371 +0.968659 0.481290 +0.799077 0.488089 +0.950914 0.487897 +0.818010 0.488346 +0.931980 0.488037 +0.835889 0.482112 +0.914139 0.481692 +0.850558 0.470140 +0.899545 0.469628 +0.860248 0.453872 +0.889957 0.453300 +0.738093 0.553041 +0.861094 0.553253 +0.857800 0.534607 +0.734555 0.571642 +0.848328 0.518212 +0.724868 0.587911 +0.833819 0.506045 +0.710156 0.599911 +0.990994 0.711495 +0.816024 0.499575 +0.990994 0.683942 +0.692323 0.606123 +0.797089 0.499581 +0.673390 0.605868 +0.779298 0.506063 +0.655686 0.599154 +0.764796 0.518239 +0.641345 0.586789 +0.755334 0.534640 +0.632099 0.570265 +0.752052 0.553288 +0.629062 0.551575 +0.755346 0.571935 +0.632599 0.532974 +0.764819 0.588330 +0.642286 0.516704 +0.779329 0.600496 +0.656999 0.504703 +0.797124 0.606967 +0.674832 0.498492 +0.816059 0.606960 +0.693765 0.498747 +0.833849 0.600478 +0.711469 0.505461 +0.848351 0.588302 +0.725810 0.517826 +0.857812 0.571901 +0.735056 0.534350 +0.740236 0.432191 +0.994925 0.316443 +0.991606 0.297802 +0.736907 0.450831 +0.982112 0.281419 +0.727403 0.467208 +0.967587 0.269272 +0.712871 0.479347 +0.949784 0.262825 +0.695064 0.485784 +0.991971 0.744417 +0.930849 0.262856 +0.991971 0.716864 +0.676129 0.485743 +0.913066 0.269361 +0.658351 0.479227 +0.898581 0.281556 +0.643872 0.467024 +0.889141 0.297969 +0.634441 0.450605 +0.885883 0.316623 +0.631194 0.431951 +0.889202 0.335264 +0.634523 0.413310 +0.898696 0.351647 +0.644027 0.396933 +0.913221 0.363794 +0.658558 0.384793 +0.931025 0.370241 +0.676366 0.378357 +0.949960 0.370210 +0.695301 0.378398 +0.967742 0.363705 +0.713079 0.384914 +0.982227 0.351510 +0.727558 0.397117 +0.991668 0.335096 +0.736989 0.413536 +0.756574 0.316863 +0.759677 0.335541 +0.991761 0.573912 +0.995178 0.555288 +0.768982 0.352033 +0.982179 0.590244 +0.783366 0.364346 +0.967590 0.602314 +0.990852 0.645703 +0.801094 0.370998 +0.990852 0.618147 +0.949752 0.608666 +0.820029 0.371185 +0.930818 0.608535 +0.837885 0.364885 +0.913071 0.601935 +0.852510 0.352858 +0.898651 0.589663 +0.862139 0.336554 +0.889297 0.573200 +0.865611 0.317940 +0.886139 0.554531 +0.862507 0.299262 +0.889556 0.535907 +0.853202 0.282771 +0.899138 0.519575 +0.838818 0.270457 +0.913728 0.507505 +0.821090 0.263805 +0.931565 0.501153 +0.802156 0.263618 +0.950499 0.501284 +0.784301 0.269918 +0.968247 0.507883 +0.769676 0.281945 +0.982667 0.520155 +0.760046 0.298249 +0.992020 0.536619 +0.617349 0.999539 +0.018316 0.999095 +0.285228 0.558402 +0.012346 0.558264 +0.616788 0.566386 +0.634060 0.999396 +0.001606 0.998928 +0.019518 0.565944 +0.012847 0.360946 +0.004733 0.558189 +0.284927 0.361084 +0.292841 0.558336 +0.692536 0.045974 +0.989630 0.045974 +0.327186 0.069626 +0.624279 0.070519 +0.697381 0.065247 +0.984784 0.065247 +0.619375 0.089778 +0.331973 0.088914 +0.996890 0.048265 +0.685276 0.048265 +0.319919 0.071895 +0.631532 0.072833 +0.692888 0.023627 +0.989983 0.023627 +0.692888 0.002869 +0.989983 0.002870 +0.997596 0.040720 +0.685276 0.040720 +0.685276 0.019963 +0.997596 0.019963 +0.997596 0.023627 +0.685276 0.023627 +0.685276 0.002870 +0.997596 0.002870 +0.323245 0.020775 +0.464390 0.022671 +0.403506 0.350094 +0.324948 0.011657 +0.329968 0.008678 +0.494631 0.010890 +0.617003 0.546204 +0.617003 0.381527 +0.524043 0.552884 +0.460822 0.374847 +0.770722 0.085824 +0.708838 0.092493 +0.714997 0.079998 +0.692466 0.070998 +0.702831 0.069347 +0.613548 0.376517 +0.613594 0.551214 +0.554999 0.355201 +0.841120 0.145455 +0.585161 0.367184 +0.420487 0.368300 +0.415486 0.365288 +0.413844 0.356158 +0.304641 0.381527 +0.304641 0.546204 +0.397601 0.552884 +0.908389 0.080257 +0.908398 0.069626 +0.997318 0.103853 +0.318277 0.552884 +0.981488 0.092812 +0.997914 0.071348 +0.318458 0.374847 +0.308095 0.376517 +0.308050 0.551214 +0.253144 0.084929 +0.253140 0.081937 +0.078944 0.031316 +0.078967 0.028323 +0.477907 0.030534 +0.499594 0.014411 +0.568568 0.347429 +0.590147 0.363695 +0.067275 0.084786 +0.613110 0.042062 +0.770512 0.097735 +0.509723 0.014839 +0.325106 0.042547 +0.997534 0.115763 +0.326605 0.039549 +0.983284 0.117268 +0.806675 0.117071 +0.988433 0.120449 +0.393617 0.132834 +0.990008 0.129654 +0.848858 0.129412 +0.312455 0.053169 +0.302092 0.051499 +0.295960 0.086764 +0.289823 0.074256 +0.612905 0.331331 +0.436135 0.330853 +0.570677 0.343510 +0.801617 0.184566 +0.429535 0.343210 +0.431145 0.334012 +0.096426 0.074255 +0.096426 0.051497 +0.006836 0.053169 +0.023332 0.086765 +0.799250 0.103725 +0.799243 0.115635 +0.666518 0.014827 +0.666519 0.024712 +0.617907 0.334796 +0.584280 0.351218 +0.968803 0.097485 +0.968789 0.085574 +0.997915 0.145659 +0.997928 0.135774 +0.801660 0.120516 +0.835225 0.137068 +0.382560 0.118727 +0.370650 0.118665 +0.360766 0.118702 +0.330599 0.118813 +0.318688 0.118962 +0.340484 0.118777 +0.340438 0.106541 +0.360721 0.106467 +0.370605 0.106431 +0.382516 0.106492 +0.318643 0.106727 +0.330554 0.106578 +0.402948 0.089996 +0.391037 0.090030 +0.381152 0.089971 +0.350986 0.089792 +0.339077 0.089616 +0.360870 0.089851 +0.381080 0.102207 +0.360798 0.102086 +0.402875 0.102232 +0.390964 0.102266 +0.350913 0.102028 +0.339004 0.101852 +0.653860 0.061352 +0.653860 0.039693 +0.696721 0.081438 +0.684084 0.081552 +0.689712 0.067066 +0.677076 0.066952 +0.673102 0.088854 +0.673102 0.067196 +0.632732 0.091027 +0.635961 0.090612 +0.633237 0.082962 +0.636465 0.082547 +0.891075 0.756619 +0.991731 0.756619 +0.761135 0.756619 +0.861326 0.756619 +0.861402 0.771773 +0.891173 0.771773 +0.991731 0.771773 +0.761135 0.771773 +0.866686 0.756619 +0.885702 0.756619 +0.871562 0.756619 +0.880810 0.756619 +0.876184 0.756619 +0.866759 0.771773 +0.885802 0.771773 +0.871650 0.771773 +0.880903 0.771773 +0.876489 0.771773 +0.761135 0.754289 +0.991731 0.754289 +0.891075 0.754289 +0.861326 0.754289 +0.991731 0.769412 +0.891173 0.769412 +0.861402 0.769412 +0.761135 0.769412 +0.885702 0.754289 +0.866686 0.754289 +0.880810 0.754289 +0.871562 0.754289 +0.876184 0.754289 +0.885802 0.769412 +0.866759 0.769412 +0.880903 0.769412 +0.871650 0.769412 +0.876489 0.769412 +0.861216 0.749698 +0.890962 0.749698 +0.991731 0.749698 +0.761135 0.749698 +0.890445 0.753429 +0.991731 0.753429 +0.761135 0.753429 +0.860744 0.753429 +0.885598 0.749698 +0.866577 0.749698 +0.880715 0.749698 +0.871461 0.749698 +0.876288 0.749698 +0.885049 0.753429 +0.866072 0.753429 +0.880150 0.753429 +0.870924 0.753429 +0.875527 0.753429 +0.991731 0.747373 +0.890962 0.747373 +0.861216 0.747373 +0.761135 0.747373 +0.761135 0.751102 +0.991731 0.751102 +0.890445 0.751102 +0.860744 0.751102 +0.885598 0.747373 +0.866577 0.747373 +0.880715 0.747373 +0.871461 0.747373 +0.876288 0.747373 +0.885049 0.751102 +0.866072 0.751102 +0.880150 0.751102 +0.870924 0.751102 +0.875527 0.751102 +0.890771 0.761641 +0.861097 0.761641 +0.761135 0.761641 +0.991731 0.761641 +0.891116 0.767610 +0.991731 0.767610 +0.761135 0.767610 +0.861394 0.767610 +0.866438 0.761641 +0.885403 0.761641 +0.871304 0.761641 +0.880525 0.761641 +0.875913 0.761641 +0.885741 0.767610 +0.866744 0.767610 +0.880853 0.767610 +0.871615 0.767610 +0.876229 0.767610 +0.761135 0.763965 +0.861097 0.763965 +0.890771 0.763965 +0.991731 0.763965 +0.761135 0.765281 +0.991731 0.765281 +0.891116 0.765281 +0.861394 0.765281 +0.866438 0.763965 +0.885403 0.763965 +0.871304 0.763965 +0.880525 0.763965 +0.875913 0.763965 +0.885741 0.765281 +0.866744 0.765281 +0.880853 0.765281 +0.871615 0.765281 +0.876229 0.765281 +0.862726 0.773917 +0.761135 0.773917 +0.991731 0.773917 +0.892385 0.773917 +0.861499 0.760471 +0.891160 0.760471 +0.991731 0.760471 +0.761135 0.760471 +0.887061 0.773917 +0.868117 0.773917 +0.882215 0.773917 +0.873007 0.773917 +0.877618 0.773917 +0.866857 0.760471 +0.885814 0.760471 +0.871730 0.760471 +0.880949 0.760471 +0.876342 0.760471 +0.991731 0.776242 +0.761135 0.776242 +0.862726 0.776242 +0.892385 0.776242 +0.991731 0.758148 +0.891160 0.758148 +0.861499 0.758148 +0.761135 0.758148 +0.868117 0.776242 +0.887061 0.776242 +0.873007 0.776242 +0.882215 0.776242 +0.877618 0.776242 +0.885814 0.758148 +0.866857 0.758148 +0.880949 0.758148 +0.871730 0.758148 +0.876342 0.758148 +0.700017 0.825747 +0.700017 0.788648 +0.755151 0.825320 +0.755151 0.788214 +0.653511 0.749135 +0.653511 0.786241 +0.753884 0.786207 +0.753884 0.749101 +0.995494 0.178374 +0.703734 0.124428 +0.416982 0.164112 +0.832661 0.208239 +0.965736 0.153101 +0.680366 0.093152 + + + + + + + + + + + +

2 0 0 12 1 1 1 2 2 1 3 2 0 4 3 2 5 0 36 6 5 37 7 6 29 8 7 29 9 7 28 10 4 36 11 5 0 12 1006 1 13 1005 18 14 1007 0 15 1006 18 16 1007 9 17 1009 0 18 1006 9 19 1009 4 20 1010 4 21 11 9 22 973 10 23 12 10 24 12 5 25 13 4 26 11 31 27 14 29 28 7 37 29 6 10 30 955 24 31 958 7 32 959 5 33 956 10 34 955 7 35 959 5 36 956 7 37 959 6 38 960 6 39 18 7 40 17 16 41 19 16 42 19 8 43 20 6 44 18 33 45 21 31 46 14 37 47 6 35 48 964 33 49 963 37 50 980 17 51 28 11 52 29 34 53 42 34 54 42 19 55 27 17 56 28 18 57 8 1 58 2 12 59 1 12 60 1 20 61 30 18 62 8 21 63 1013 13 64 1014 11 65 1012 11 66 1012 17 67 1011 21 68 1013 22 69 33 14 70 34 13 71 32 13 72 32 21 73 31 22 74 33 23 75 968 15 76 969 14 77 967 14 78 967 22 79 966 23 80 968 25 81 37 35 82 22 15 83 36 15 84 36 23 85 35 25 86 37 26 87 38 16 88 19 7 89 17 7 90 17 24 91 16 26 92 38 0 93 3 17 94 1032 19 95 1031 19 96 1031 2 97 0 0 98 3 9 99 965 18 100 8 20 101 30 20 102 30 3 103 1000 9 104 965 4 105 1010 21 106 1036 17 107 1035 17 108 1035 0 109 1006 4 110 1010 5 111 13 22 112 1034 21 113 1033 21 114 1033 4 115 11 5 116 13 6 117 960 23 118 995 22 119 994 22 120 994 5 121 956 6 122 960 8 123 20 25 124 991 23 125 990 23 126 990 6 127 18 8 128 20 33 129 25 26 130 38 24 131 16 24 132 16 10 133 998 33 134 25 9 135 10 3 136 23 27 137 40 27 138 40 30 139 39 9 140 10 10 141 999 9 142 10 30 143 39 30 144 39 32 145 41 10 146 999 33 147 21 10 148 999 32 149 41 25 150 970 8 151 962 16 152 961 25 153 970 16 154 961 26 155 971 25 156 970 26 157 971 33 158 963 35 159 964 25 160 970 33 161 963 32 162 41 31 163 14 33 164 21 31 165 1039 32 166 1042 43 167 1043 43 168 1043 42 169 1044 31 170 1039 28 171 1037 29 172 1038 40 173 1045 40 174 1045 39 175 1046 28 176 1037 29 177 1038 31 178 1039 42 179 1044 42 180 1044 40 181 1045 29 182 1038 30 183 1040 27 184 1041 38 185 1047 38 186 1047 41 187 1048 30 188 1040 32 189 1042 30 190 1040 41 191 1048 41 192 1048 43 193 1043 32 194 1042 38 195 47 39 196 46 40 197 45 40 198 45 41 199 48 38 200 47 41 201 48 40 202 45 42 203 44 42 204 44 43 205 43 41 206 48 44 207 49 47 208 50 46 209 51 46 210 51 45 211 52 44 212 49 36 213 5 48 214 53 49 215 54 49 216 54 37 217 6 36 218 5 47 219 1015 52 220 1017 51 221 1019 47 222 1015 51 223 1019 50 224 1020 47 225 1015 50 226 1020 46 227 1016 52 228 55 53 229 59 55 230 60 55 231 60 51 232 1001 52 233 55 37 234 6 49 235 54 54 236 61 53 237 972 58 238 974 57 239 975 57 240 975 56 241 976 55 242 977 53 243 972 57 244 975 55 245 977 58 246 62 60 247 66 59 248 67 59 249 67 57 250 63 58 251 62 75 252 987 35 253 964 37 254 980 13 255 1014 62 256 1021 63 257 1022 63 258 1022 11 259 1012 13 260 1014 14 261 34 64 262 72 62 263 70 62 264 70 13 265 32 14 266 34 15 267 969 65 268 982 64 269 981 64 270 981 14 271 967 15 272 969 35 273 22 75 274 83 65 275 73 65 276 73 15 277 36 35 278 22 69 279 77 68 280 78 67 281 76 67 282 76 63 283 71 69 284 77 50 285 58 70 286 79 45 287 52 45 288 52 46 289 51 50 290 58 71 291 1024 69 292 1023 63 293 1022 63 294 1022 62 295 1021 71 296 1024 72 297 81 71 298 80 62 299 70 62 300 70 64 301 72 72 302 81 73 303 986 72 304 985 64 305 981 64 306 981 65 307 982 73 308 986 74 309 84 73 310 82 65 311 73 65 312 73 75 313 83 74 314 84 76 315 85 56 316 64 57 317 63 57 318 63 59 319 67 76 320 85 47 321 50 44 322 49 68 323 1026 68 324 1026 69 325 1025 47 326 50 51 327 983 61 328 1003 70 329 79 70 330 79 50 331 58 51 332 983 52 333 1017 47 334 1015 69 335 1029 69 336 1029 71 337 1030 52 338 1017 53 339 59 52 340 55 71 341 1027 71 342 1027 72 343 1028 53 344 59 58 345 974 53 346 972 72 347 996 72 348 996 73 349 997 58 350 974 60 351 66 58 352 62 73 353 992 73 354 992 74 355 993 60 356 66 66 357 75 55 358 65 56 359 64 56 360 64 76 361 85 66 362 75 51 363 57 77 364 86 78 365 87 78 366 87 61 367 68 51 368 57 55 369 1002 79 370 88 77 371 86 77 372 86 51 373 57 55 374 1002 79 375 88 55 376 1002 66 377 1004 59 378 979 60 379 978 74 380 988 76 381 989 59 382 979 74 383 988 66 384 984 76 385 989 74 386 988 66 387 984 74 388 988 75 389 987 37 390 6 54 391 61 79 392 88 79 393 88 66 394 1004 37 395 6 37 396 980 66 397 984 75 398 987 67 399 76 34 400 42 11 401 29 11 402 29 63 403 71 67 404 76 54 405 1051 81 406 1055 80 407 1056 80 408 1056 79 409 1054 54 410 1051 48 411 1049 83 412 1057 82 413 1058 82 414 1058 49 415 1050 48 416 1049 49 417 1050 82 418 1058 81 419 1055 81 420 1055 54 421 1051 49 422 1050 77 423 1052 85 424 1059 84 425 1060 84 426 1060 78 427 1053 77 428 1052 79 429 1054 80 430 1056 85 431 1059 85 432 1059 77 433 1052 79 434 1054 84 435 94 85 436 93 82 437 92 82 438 92 83 439 91 84 440 94 85 441 93 80 442 90 81 443 89 81 444 89 82 445 92 85 446 93 108 447 756 109 448 757 87 449 758 87 450 758 86 451 755 108 452 756 86 453 95 87 454 98 111 455 919 111 456 919 90 457 920 86 458 95 107 459 101 89 460 102 113 461 103 113 462 103 91 463 104 107 464 101 109 465 97 108 466 96 112 467 921 112 468 921 93 469 922 109 470 97 88 471 107 106 472 108 110 473 109 110 474 109 92 475 110 88 476 107 90 477 100 111 478 99 115 479 931 115 480 931 94 481 932 90 482 100 91 483 104 113 484 103 117 485 113 117 486 113 95 487 114 91 488 104 93 489 106 112 490 105 116 491 933 116 492 933 97 493 934 93 494 106 92 495 110 110 496 109 114 497 117 114 498 117 96 499 118 92 500 110 94 501 112 115 502 111 119 503 943 119 504 943 98 505 944 94 506 112 95 507 114 117 508 113 121 509 9 121 510 9 99 511 15 95 512 114 97 513 116 116 514 115 120 515 945 120 516 945 101 517 946 97 518 116 96 519 118 114 520 117 118 521 24 118 522 24 100 523 26 96 524 118 98 525 120 119 526 119 103 527 127 103 528 127 122 529 128 98 530 120 99 531 122 121 532 121 105 533 129 105 534 129 123 535 130 99 536 122 101 537 124 120 538 123 104 539 131 104 540 131 125 541 132 101 542 124 100 543 126 118 544 125 102 545 133 102 546 133 124 547 134 100 548 126 131 549 924 111 550 919 87 551 98 87 552 98 127 553 923 131 554 924 126 555 926 86 556 95 90 557 920 90 558 920 130 559 925 126 560 926 133 561 140 113 562 103 89 563 102 89 564 102 129 565 139 133 566 140 132 567 930 112 568 921 108 569 96 108 570 96 128 571 929 132 572 930 134 573 143 114 574 117 110 575 109 110 576 109 130 577 137 134 578 143 135 579 940 115 580 931 111 581 99 111 582 99 131 583 935 135 584 940 136 585 941 116 586 933 112 587 105 112 588 105 132 589 938 136 590 941 137 591 146 117 592 113 113 593 103 113 594 103 133 595 140 137 596 146 138 597 56 118 598 24 114 599 117 114 600 117 134 601 143 138 602 56 139 603 952 119 604 943 115 605 111 115 606 111 135 607 948 139 608 952 140 609 953 120 610 945 116 611 115 116 612 115 136 613 949 140 614 953 141 615 957 121 616 9 117 617 113 117 618 113 137 619 146 141 620 957 142 621 151 102 622 133 118 623 125 118 624 125 138 625 147 142 626 151 143 627 152 103 628 127 119 629 119 119 630 119 139 631 148 143 632 152 144 633 153 104 634 131 120 635 123 120 636 123 140 637 149 144 638 153 145 639 154 105 640 129 121 641 121 121 642 121 141 643 150 145 644 154 91 645 104 131 646 136 127 647 135 127 648 135 107 649 101 91 650 104 106 651 108 126 652 138 130 653 137 130 654 137 110 655 109 106 656 108 93 657 922 133 658 928 129 659 927 129 660 927 109 661 97 93 662 922 92 663 110 132 664 142 128 665 141 128 666 141 88 667 107 92 668 110 94 669 932 134 670 939 130 671 936 130 672 936 90 673 100 94 674 932 95 675 114 135 676 144 131 677 136 131 678 136 91 679 104 95 680 114 96 681 118 136 682 145 132 683 142 132 684 142 92 685 110 96 686 118 97 687 934 137 688 942 133 689 937 133 690 937 93 691 106 97 692 934 98 693 944 138 694 951 134 695 947 134 696 947 94 697 112 98 698 944 99 699 15 139 700 69 135 701 144 135 702 144 95 703 114 99 704 15 100 705 26 140 706 74 136 707 145 136 708 145 96 709 118 100 710 26 101 711 946 141 712 954 137 713 950 137 714 950 97 715 116 101 716 946 122 717 128 142 718 1227 138 719 1008 138 720 1008 98 721 120 122 722 128 123 723 130 143 724 1228 139 725 1018 139 726 1018 99 727 122 123 728 130 124 729 134 144 730 1229 140 731 1225 140 732 1225 100 733 126 124 734 134 125 735 132 145 736 1230 141 737 1226 141 738 1226 101 739 124 125 740 132 126 741 764 128 742 766 108 743 756 108 744 756 86 745 755 126 746 764 106 747 762 88 748 761 128 749 766 128 750 766 126 751 764 106 752 762 129 753 765 127 754 763 87 755 758 87 756 758 109 757 757 129 758 765 89 759 760 107 760 759 127 761 763 127 762 763 129 763 765 89 764 760 147 765 155 151 766 156 149 767 157 147 768 155 146 769 158 150 770 159 150 771 159 151 772 156 147 773 155 146 774 158 148 775 160 150 776 159 153 777 161 157 778 162 155 779 163 153 780 161 152 781 164 156 782 165 156 783 165 157 784 162 153 785 161 152 786 164 154 787 166 156 788 165 159 789 167 163 790 168 161 791 169 159 792 167 158 793 170 162 794 171 162 795 171 163 796 168 159 797 167 158 798 170 160 799 172 162 800 171 165 801 173 169 802 174 167 803 175 165 804 173 164 805 176 168 806 177 168 807 177 169 808 174 165 809 173 164 810 176 166 811 178 168 812 177 170 813 179 172 814 180 171 815 181 198 816 182 199 817 183 172 818 180 172 819 180 170 820 179 198 821 182 173 822 184 175 823 185 174 824 186 173 825 184 174 826 186 177 827 187 177 828 187 176 829 188 173 830 184 176 831 188 177 832 187 178 833 189 179 834 190 181 835 191 180 836 192 179 837 190 180 838 192 183 839 193 183 840 193 182 841 194 179 842 190 182 843 194 183 844 193 184 845 195 185 846 196 187 847 197 186 848 198 185 849 196 186 850 198 189 851 199 189 852 199 188 853 200 185 854 196 188 855 200 189 856 199 190 857 201 191 858 202 193 859 203 192 860 204 191 861 202 192 862 204 195 863 205 195 864 205 194 865 206 191 866 202 194 867 206 195 868 205 196 869 207 198 870 182 197 871 208 199 872 183 200 873 209 202 874 210 201 875 211 200 876 209 201 877 211 204 878 212 204 879 212 203 880 213 200 881 209 203 882 213 204 883 212 205 884 214 206 885 215 208 886 216 207 887 217 206 888 215 207 889 217 210 890 218 210 891 218 209 892 219 206 893 215 209 894 219 210 895 218 211 896 220 212 897 221 214 898 222 213 899 223 212 900 221 213 901 223 216 902 224 216 903 224 215 904 225 212 905 221 215 906 225 216 907 224 217 908 226 218 909 227 220 910 228 219 911 229 218 912 227 219 913 229 222 914 230 222 915 230 221 916 231 218 917 227 221 918 231 222 919 230 223 920 232 224 921 233 226 922 234 225 923 235 252 924 237 224 925 233 225 926 235 225 927 235 227 928 236 252 929 237 228 930 238 230 931 239 229 932 240 228 933 238 232 934 241 231 935 242 231 936 242 230 937 239 228 938 238 232 939 241 233 940 243 231 941 242 234 942 244 236 943 245 235 944 246 234 945 244 238 946 247 237 947 248 237 948 248 236 949 245 234 950 244 238 951 247 239 952 249 237 953 248 240 954 250 242 955 251 241 956 252 240 957 250 244 958 253 243 959 254 243 960 254 242 961 251 240 962 250 244 963 253 245 964 255 243 965 254 246 966 256 248 967 257 247 968 258 246 969 256 250 970 259 249 971 260 249 972 260 248 973 257 246 974 256 250 975 259 251 976 261 249 977 260 252 978 237 227 979 236 253 980 262 254 981 263 255 982 264 256 983 265 254 984 263 257 985 266 258 986 267 258 987 267 255 988 264 254 989 263 257 990 266 259 991 268 258 992 267 260 993 269 261 994 270 262 995 271 260 996 269 263 997 272 264 998 273 264 999 273 261 1000 270 260 1001 269 263 1002 272 265 1003 274 264 1004 273 266 1005 275 267 1006 276 268 1007 277 266 1008 275 269 1009 278 270 1010 279 270 1011 279 267 1012 276 266 1013 275 269 1014 278 271 1015 280 270 1016 279 272 1017 281 274 1018 282 273 1019 283 272 1020 281 273 1021 283 276 1022 284 276 1023 284 275 1024 285 272 1025 281 275 1026 285 276 1027 284 277 1028 286 278 1029 287 280 1030 288 279 1031 289 278 1032 287 279 1033 289 282 1034 290 282 1035 290 281 1036 291 278 1037 287 281 1038 291 282 1039 290 283 1040 292 284 1041 293 286 1042 294 285 1043 295 284 1044 293 285 1045 295 288 1046 296 288 1047 296 287 1048 297 284 1049 293 287 1050 297 288 1051 296 289 1052 298 290 1053 299 291 1054 300 309 1055 301 309 1056 301 308 1057 302 290 1058 299 291 1059 300 292 1060 303 310 1061 304 310 1062 304 309 1063 301 291 1064 300 292 1065 303 293 1066 305 311 1067 306 311 1068 306 310 1069 304 292 1070 303 293 1071 305 294 1072 307 312 1073 308 312 1074 308 311 1075 306 293 1076 305 294 1077 307 295 1078 309 313 1079 310 313 1080 310 312 1081 308 294 1082 307 295 1083 777 296 1084 311 314 1085 312 314 1086 312 313 1087 779 295 1088 777 296 1089 311 297 1090 313 315 1091 314 315 1092 314 314 1093 312 296 1094 311 297 1095 313 298 1096 315 316 1097 316 316 1098 316 315 1099 314 297 1100 313 298 1101 315 299 1102 317 317 1103 318 317 1104 318 316 1105 316 298 1106 315 299 1107 317 300 1108 319 318 1109 320 318 1110 320 317 1111 318 299 1112 317 300 1113 319 301 1114 321 319 1115 322 319 1116 322 318 1117 320 300 1118 319 301 1119 321 302 1120 323 320 1121 324 320 1122 324 319 1123 322 301 1124 321 302 1125 323 303 1126 325 321 1127 326 321 1128 326 320 1129 324 302 1130 323 303 1131 325 304 1132 327 322 1133 328 322 1134 328 321 1135 326 303 1136 325 304 1137 327 305 1138 329 323 1139 330 323 1140 330 322 1141 328 304 1142 327 305 1143 329 306 1144 331 324 1145 332 324 1146 332 323 1147 330 305 1148 329 306 1149 331 307 1150 333 325 1151 334 325 1152 334 324 1153 332 306 1154 331 307 1155 333 290 1156 299 308 1157 302 308 1158 302 325 1159 334 307 1160 333 321 1161 796 322 1162 798 323 1163 800 323 1164 800 320 1165 794 321 1166 796 320 1167 794 323 1168 800 324 1169 802 324 1170 802 319 1171 792 320 1172 794 319 1173 792 324 1174 802 325 1175 804 325 1176 804 318 1177 790 319 1178 792 318 1179 790 325 1180 804 308 1181 770 308 1182 770 317 1183 788 318 1184 790 317 1185 788 308 1186 770 309 1187 769 309 1188 769 316 1189 786 317 1190 788 316 1191 786 309 1192 769 310 1193 772 310 1194 772 315 1195 784 316 1196 786 315 1197 784 310 1198 772 311 1199 774 311 1200 774 314 1201 782 315 1202 784 314 1203 782 311 1204 774 312 1205 776 312 1206 776 313 1207 780 314 1208 782 295 1209 778 294 1210 775 293 1211 773 293 1212 773 296 1213 781 295 1214 778 296 1215 781 293 1216 773 292 1217 771 292 1218 771 297 1219 783 296 1220 781 297 1221 783 292 1222 771 291 1223 768 291 1224 768 298 1225 785 297 1226 783 298 1227 785 291 1228 768 290 1229 767 290 1230 767 299 1231 787 298 1232 785 299 1233 787 290 1234 767 307 1235 803 307 1236 803 300 1237 789 299 1238 787 300 1239 789 307 1240 803 306 1241 801 306 1242 801 301 1243 791 300 1244 789 301 1245 791 306 1246 801 305 1247 799 305 1248 799 302 1249 793 301 1250 791 302 1251 793 305 1252 799 304 1253 797 304 1254 797 303 1255 795 302 1256 793 326 1257 335 329 1258 336 328 1259 337 328 1260 337 327 1261 338 326 1262 335 327 1263 338 328 1264 337 331 1265 339 331 1266 339 330 1267 340 327 1268 338 330 1269 340 331 1270 339 333 1271 341 333 1272 341 332 1273 342 330 1274 340 332 1275 342 333 1276 341 335 1277 343 335 1278 343 334 1279 344 332 1280 342 334 1281 815 335 1282 813 337 1283 345 337 1284 345 336 1285 346 334 1286 815 336 1287 346 337 1288 345 339 1289 347 339 1290 347 338 1291 348 336 1292 346 338 1293 348 339 1294 347 341 1295 349 341 1296 349 340 1297 350 338 1298 348 340 1299 350 341 1300 349 343 1301 351 343 1302 351 342 1303 352 340 1304 350 342 1305 352 343 1306 351 345 1307 353 345 1308 353 344 1309 354 342 1310 352 344 1311 354 345 1312 353 347 1313 355 347 1314 355 346 1315 356 344 1316 354 346 1317 356 347 1318 355 349 1319 357 349 1320 357 348 1321 358 346 1322 356 348 1323 358 349 1324 357 351 1325 359 351 1326 359 350 1327 360 348 1328 358 350 1329 360 351 1330 359 353 1331 361 353 1332 361 352 1333 362 350 1334 360 352 1335 362 353 1336 361 355 1337 363 355 1338 363 354 1339 364 352 1340 362 354 1341 364 355 1342 363 357 1343 365 357 1344 365 356 1345 366 354 1346 364 356 1347 366 357 1348 365 359 1349 367 359 1350 367 358 1351 368 356 1352 366 358 1353 368 359 1354 367 361 1355 369 361 1356 369 360 1357 370 358 1358 368 360 1359 370 361 1360 369 329 1361 336 329 1362 336 326 1363 335 360 1364 370 353 1365 833 351 1366 831 357 1367 837 357 1368 837 355 1369 835 353 1370 833 351 1371 831 349 1372 829 359 1373 839 359 1374 839 357 1375 837 351 1376 831 349 1377 829 347 1378 827 361 1379 841 361 1380 841 359 1381 839 349 1382 829 347 1383 827 345 1384 825 329 1385 806 329 1386 806 361 1387 841 347 1388 827 345 1389 825 343 1390 823 328 1391 807 328 1392 807 329 1393 806 345 1394 825 343 1395 823 341 1396 821 331 1397 809 331 1398 809 328 1399 807 343 1400 823 341 1401 821 339 1402 819 333 1403 811 333 1404 811 331 1405 809 341 1406 821 339 1407 819 337 1408 817 335 1409 814 335 1410 814 333 1411 811 339 1412 819 336 1413 818 338 1414 820 332 1415 812 332 1416 812 334 1417 816 336 1418 818 338 1419 820 340 1420 822 330 1421 810 330 1422 810 332 1423 812 338 1424 820 340 1425 822 342 1426 824 327 1427 808 327 1428 808 330 1429 810 340 1430 822 342 1431 824 344 1432 826 326 1433 805 326 1434 805 327 1435 808 342 1436 824 344 1437 826 346 1438 828 360 1439 842 360 1440 842 326 1441 805 344 1442 826 346 1443 828 348 1444 830 358 1445 840 358 1446 840 360 1447 842 346 1448 828 348 1449 830 350 1450 832 356 1451 838 356 1452 838 358 1453 840 348 1454 830 350 1455 832 352 1456 834 354 1457 836 354 1458 836 356 1459 838 350 1460 832 362 1461 371 365 1462 372 364 1463 373 364 1464 373 363 1465 374 362 1466 371 363 1467 374 364 1468 373 367 1469 375 367 1470 375 366 1471 376 363 1472 374 366 1473 376 367 1474 375 369 1475 377 369 1476 377 368 1477 378 366 1478 376 368 1479 378 369 1480 377 371 1481 379 371 1482 379 370 1483 380 368 1484 378 370 1485 380 371 1486 379 373 1487 381 373 1488 381 372 1489 382 370 1490 380 372 1491 855 373 1492 853 375 1493 383 375 1494 383 374 1495 384 372 1496 855 374 1497 384 375 1498 383 377 1499 385 377 1500 385 376 1501 386 374 1502 384 376 1503 386 377 1504 385 379 1505 387 379 1506 387 378 1507 388 376 1508 386 378 1509 388 379 1510 387 381 1511 389 381 1512 389 380 1513 390 378 1514 388 380 1515 390 381 1516 389 383 1517 391 383 1518 391 382 1519 392 380 1520 390 382 1521 392 383 1522 391 385 1523 393 385 1524 393 384 1525 394 382 1526 392 384 1527 394 385 1528 393 387 1529 395 387 1530 395 386 1531 396 384 1532 394 386 1533 396 387 1534 395 389 1535 397 389 1536 397 388 1537 398 386 1538 396 388 1539 398 389 1540 397 391 1541 399 391 1542 399 390 1543 400 388 1544 398 390 1545 400 391 1546 399 393 1547 401 393 1548 401 392 1549 402 390 1550 400 392 1551 402 393 1552 401 395 1553 403 395 1554 403 394 1555 404 392 1556 402 394 1557 404 395 1558 403 397 1559 405 397 1560 405 396 1561 406 394 1562 404 396 1563 406 397 1564 405 365 1565 372 365 1566 372 362 1567 371 396 1568 406 389 1569 871 387 1570 869 393 1571 875 393 1572 875 391 1573 873 389 1574 871 387 1575 869 385 1576 867 395 1577 877 395 1578 877 393 1579 875 387 1580 869 385 1581 867 383 1582 865 397 1583 879 397 1584 879 395 1585 877 385 1586 867 383 1587 865 381 1588 863 365 1589 844 365 1590 844 397 1591 879 383 1592 865 381 1593 863 379 1594 861 364 1595 845 364 1596 845 365 1597 844 381 1598 863 379 1599 861 377 1600 859 367 1601 847 367 1602 847 364 1603 845 379 1604 861 377 1605 859 375 1606 857 369 1607 849 369 1608 849 367 1609 847 377 1610 859 375 1611 857 373 1612 854 371 1613 851 371 1614 851 369 1615 849 375 1616 857 372 1617 856 374 1618 858 368 1619 850 368 1620 850 370 1621 852 372 1622 856 374 1623 858 376 1624 860 366 1625 848 366 1626 848 368 1627 850 374 1628 858 376 1629 860 378 1630 862 363 1631 846 363 1632 846 366 1633 848 376 1634 860 378 1635 862 380 1636 864 362 1637 843 362 1638 843 363 1639 846 378 1640 862 380 1641 864 382 1642 866 396 1643 880 396 1644 880 362 1645 843 380 1646 864 382 1647 866 384 1648 868 394 1649 878 394 1650 878 396 1651 880 382 1652 866 384 1653 868 386 1654 870 392 1655 876 392 1656 876 394 1657 878 384 1658 868 386 1659 870 388 1660 872 390 1661 874 390 1662 874 392 1663 876 386 1664 870 398 1665 407 401 1666 408 400 1667 409 400 1668 409 399 1669 410 398 1670 407 401 1671 408 403 1672 411 402 1673 412 402 1674 412 400 1675 409 401 1676 408 403 1677 411 405 1678 413 404 1679 414 404 1680 414 402 1681 412 403 1682 411 405 1683 413 407 1684 415 406 1685 416 406 1686 416 404 1687 414 405 1688 413 407 1689 889 409 1690 417 408 1691 418 408 1692 418 406 1693 891 407 1694 889 409 1695 417 411 1696 419 410 1697 420 410 1698 420 408 1699 418 409 1700 417 411 1701 419 413 1702 421 412 1703 422 412 1704 422 410 1705 420 411 1706 419 413 1707 421 415 1708 423 414 1709 424 414 1710 424 412 1711 422 413 1712 421 415 1713 423 417 1714 425 416 1715 426 416 1716 426 414 1717 424 415 1718 423 417 1719 425 419 1720 427 418 1721 428 418 1722 428 416 1723 426 417 1724 425 419 1725 427 421 1726 429 420 1727 430 420 1728 430 418 1729 428 419 1730 427 421 1731 429 423 1732 431 422 1733 432 422 1734 432 420 1735 430 421 1736 429 423 1737 431 425 1738 433 424 1739 434 424 1740 434 422 1741 432 423 1742 431 425 1743 433 427 1744 435 426 1745 436 426 1746 436 424 1747 434 425 1748 433 427 1749 435 429 1750 437 428 1751 438 428 1752 438 426 1753 436 427 1754 435 429 1755 437 431 1756 439 430 1757 440 430 1758 440 428 1759 438 429 1760 437 431 1761 439 433 1762 441 432 1763 442 432 1764 442 430 1765 440 431 1766 439 433 1767 441 398 1768 407 399 1769 410 399 1770 410 432 1771 442 433 1772 441 424 1773 910 426 1774 912 428 1775 914 428 1776 914 422 1777 908 424 1778 910 422 1779 908 428 1780 914 430 1781 916 430 1782 916 420 1783 906 422 1784 908 420 1785 906 430 1786 916 432 1787 918 432 1788 918 418 1789 904 420 1790 906 418 1791 904 432 1792 918 399 1793 884 399 1794 884 416 1795 902 418 1796 904 416 1797 902 399 1798 884 400 1799 883 400 1800 883 414 1801 900 416 1802 902 414 1803 900 400 1804 883 402 1805 886 402 1806 886 412 1807 898 414 1808 900 412 1809 898 402 1810 886 404 1811 888 404 1812 888 410 1813 896 412 1814 898 410 1815 896 404 1816 888 406 1817 892 406 1818 892 408 1819 894 410 1820 896 409 1821 893 407 1822 890 405 1823 887 405 1824 887 411 1825 895 409 1826 893 411 1827 895 405 1828 887 403 1829 885 403 1830 885 413 1831 897 411 1832 895 413 1833 897 403 1834 885 401 1835 882 401 1836 882 415 1837 899 413 1838 897 415 1839 899 401 1840 882 398 1841 881 398 1842 881 417 1843 901 415 1844 899 417 1845 901 398 1846 881 433 1847 917 433 1848 917 419 1849 903 417 1850 901 419 1851 903 433 1852 917 431 1853 915 431 1854 915 421 1855 905 419 1856 903 421 1857 905 431 1858 915 429 1859 913 429 1860 913 423 1861 907 421 1862 905 423 1863 907 429 1864 913 427 1865 911 427 1866 911 425 1867 909 423 1868 907 438 1869 445 434 1870 446 435 1871 443 435 1872 443 439 1873 444 438 1874 445 440 1875 449 441 1876 450 437 1877 447 437 1878 447 436 1879 448 440 1880 449 435 1881 443 434 1882 446 451 1883 451 451 1884 451 447 1885 452 435 1886 443 447 1887 452 451 1888 451 450 1889 453 450 1890 453 448 1891 454 447 1892 452 450 1893 453 449 1894 455 448 1895 454 436 1896 448 437 1897 447 446 1898 456 446 1899 456 442 1900 457 436 1901 448 442 1902 457 446 1903 456 445 1904 458 445 1905 458 443 1906 459 442 1907 457 445 1908 458 444 1909 460 443 1910 459 453 1911 463 452 1912 464 456 1913 461 456 1914 461 457 1915 462 453 1916 463 455 1917 467 459 1918 468 458 1919 465 458 1920 465 454 1921 466 455 1922 467 469 1923 470 452 1924 464 453 1925 463 453 1926 463 465 1927 469 469 1928 470 468 1929 472 469 1930 470 465 1931 469 465 1932 469 466 1933 471 468 1934 472 466 1935 471 467 1936 473 468 1937 472 464 1938 475 455 1939 467 454 1940 466 454 1941 466 460 1942 474 464 1943 475 463 1944 477 464 1945 475 460 1946 474 460 1947 474 461 1948 476 463 1949 477 461 1950 476 462 1951 478 463 1952 477 453 1953 1093 457 1954 1092 439 1955 1074 439 1956 1074 435 1957 1073 453 1958 1093 456 1959 1091 452 1960 1094 434 1961 1076 434 1962 1076 438 1963 1075 456 1964 1091 454 1965 1096 458 1966 1095 440 1967 1079 440 1968 1079 436 1969 1078 454 1970 1096 459 1971 1098 455 1972 1097 437 1973 1077 437 1974 1077 441 1975 1080 459 1976 1098 465 1977 1099 453 1978 1093 435 1979 1073 435 1980 1073 447 1981 1082 465 1982 1099 452 1983 1094 469 1984 1100 451 1985 1081 451 1986 1081 434 1987 1076 452 1988 1094 466 1989 1101 465 1990 1099 447 1991 1082 447 1992 1082 448 1993 1084 466 1994 1101 469 1995 1100 468 1996 1102 450 1997 1083 450 1998 1083 451 1999 1081 469 2000 1100 468 2001 1102 467 2002 1103 449 2003 1085 449 2004 1085 450 2005 1083 468 2006 1102 467 2007 1103 466 2008 1101 448 2009 1084 448 2010 1084 449 2011 1085 467 2012 1103 460 2013 1104 454 2014 1096 436 2015 1078 436 2016 1078 442 2017 1087 460 2018 1104 455 2019 1097 464 2020 1105 446 2021 1086 446 2022 1086 437 2023 1077 455 2024 1097 461 2025 1106 460 2026 1104 442 2027 1087 442 2028 1087 443 2029 1089 461 2030 1106 464 2031 1105 463 2032 1107 445 2033 1088 445 2034 1088 446 2035 1086 464 2036 1105 463 2037 1107 462 2038 1108 444 2039 1090 444 2040 1090 445 2041 1088 463 2042 1107 462 2043 1108 461 2044 1106 443 2045 1089 443 2046 1089 444 2047 1090 462 2048 1108 470 2049 479 483 2050 480 475 2051 481 475 2052 481 474 2053 482 470 2054 479 483 2055 480 484 2056 483 476 2057 484 476 2058 484 475 2059 481 483 2060 480 484 2061 483 471 2062 485 477 2063 486 477 2064 486 476 2065 484 484 2066 483 471 2067 485 472 2068 487 478 2069 488 478 2070 488 477 2071 486 471 2072 485 472 2073 487 485 2074 489 479 2075 490 479 2076 490 478 2077 488 472 2078 487 485 2079 489 486 2080 491 480 2081 492 480 2082 492 479 2083 490 485 2084 489 486 2085 491 487 2086 493 481 2087 494 481 2088 494 480 2089 492 486 2090 491 487 2091 1217 473 2092 495 482 2093 496 482 2094 496 481 2095 1218 487 2096 1217 473 2097 495 470 2098 479 474 2099 482 474 2100 482 482 2101 496 473 2102 495 490 2103 499 489 2104 500 488 2105 497 488 2106 497 491 2107 498 490 2108 499 494 2109 503 493 2110 504 492 2111 501 492 2112 501 495 2113 502 494 2114 503 488 2115 497 497 2116 506 496 2117 505 496 2118 505 491 2119 498 488 2120 497 497 2121 506 499 2122 508 498 2123 507 498 2124 507 496 2125 505 497 2126 506 498 2127 507 499 2128 508 500 2129 509 493 2130 504 502 2131 511 501 2132 510 501 2133 510 492 2134 501 493 2135 504 502 2136 511 504 2137 513 503 2138 512 503 2139 512 501 2140 510 502 2141 511 503 2142 512 504 2143 513 505 2144 514 508 2145 517 507 2146 518 506 2147 515 506 2148 515 509 2149 516 508 2150 517 512 2151 521 511 2152 522 510 2153 519 510 2154 519 513 2155 520 512 2156 521 515 2157 523 514 2158 524 508 2159 517 508 2160 517 509 2161 516 515 2162 523 517 2163 525 516 2164 526 514 2165 524 514 2166 524 515 2167 523 517 2168 525 516 2169 526 517 2170 525 518 2171 527 520 2172 528 519 2173 529 511 2174 522 511 2175 522 512 2176 521 520 2177 528 522 2178 530 521 2179 531 519 2180 529 519 2181 529 520 2182 528 522 2183 530 521 2184 531 522 2185 530 523 2186 532 508 2187 1129 488 2188 1109 489 2189 1112 489 2190 1112 507 2191 1130 508 2192 1129 506 2193 1127 490 2194 1111 491 2195 1110 491 2196 1110 509 2197 1128 506 2198 1127 511 2199 1134 493 2200 1116 494 2201 1115 494 2202 1115 510 2203 1131 511 2204 1134 513 2205 1132 495 2206 1114 492 2207 1113 492 2208 1113 512 2209 1133 513 2210 1132 514 2211 1136 497 2212 1118 488 2213 1109 488 2214 1109 508 2215 1129 514 2216 1136 509 2217 1128 491 2218 1110 496 2219 1117 496 2220 1117 515 2221 1135 509 2222 1128 516 2223 1138 499 2224 1120 497 2225 1118 497 2226 1118 514 2227 1136 516 2228 1138 515 2229 1135 496 2230 1117 498 2231 1119 498 2232 1119 517 2233 1137 515 2234 1135 517 2235 1137 498 2236 1119 500 2237 1121 500 2238 1121 518 2239 1139 517 2240 1137 518 2241 1139 500 2242 1121 499 2243 1120 499 2244 1120 516 2245 1138 518 2246 1139 519 2247 1141 502 2248 1123 493 2249 1116 493 2250 1116 511 2251 1134 519 2252 1141 512 2253 1133 492 2254 1113 501 2255 1122 501 2256 1122 520 2257 1140 512 2258 1133 521 2259 1143 504 2260 1125 502 2261 1123 502 2262 1123 519 2263 1141 521 2264 1143 520 2265 1140 501 2266 1122 503 2267 1124 503 2268 1124 522 2269 1142 520 2270 1140 522 2271 1142 503 2272 1124 505 2273 1126 505 2274 1126 523 2275 1144 522 2276 1142 523 2277 1144 505 2278 1126 504 2279 1125 504 2280 1125 521 2281 1143 523 2282 1144 524 2283 533 527 2284 534 526 2285 535 526 2286 535 525 2287 536 524 2288 533 525 2289 536 526 2290 535 529 2291 537 529 2292 537 528 2293 538 525 2294 536 528 2295 538 529 2296 537 531 2297 539 531 2298 539 530 2299 540 528 2300 538 530 2301 540 531 2302 539 533 2303 541 533 2304 541 532 2305 542 530 2306 540 532 2307 542 533 2308 541 535 2309 543 535 2310 543 534 2311 544 532 2312 542 534 2313 544 535 2314 543 537 2315 545 537 2316 545 536 2317 546 534 2318 544 536 2319 1220 537 2320 1219 539 2321 547 539 2322 547 538 2323 548 536 2324 1220 538 2325 548 539 2326 547 541 2327 549 541 2328 549 540 2329 550 538 2330 548 540 2331 550 541 2332 549 527 2333 534 527 2334 534 524 2335 533 540 2336 550 544 2337 553 543 2338 554 542 2339 551 542 2340 551 545 2341 552 544 2342 553 548 2343 557 547 2344 558 546 2345 555 546 2346 555 549 2347 556 548 2348 557 542 2349 551 551 2350 560 550 2351 559 550 2352 559 545 2353 552 542 2354 551 551 2355 560 553 2356 562 552 2357 561 552 2358 561 550 2359 559 551 2360 560 552 2361 561 553 2362 562 554 2363 563 547 2364 558 556 2365 565 555 2366 564 555 2367 564 546 2368 555 547 2369 558 556 2370 565 558 2371 567 557 2372 566 557 2373 566 555 2374 564 556 2375 565 557 2376 566 558 2377 567 559 2378 568 562 2379 571 561 2380 572 560 2381 569 560 2382 569 563 2383 570 562 2384 571 566 2385 575 565 2386 576 564 2387 573 564 2388 573 567 2389 574 566 2390 575 569 2391 577 568 2392 578 562 2393 571 562 2394 571 563 2395 570 569 2396 577 571 2397 579 570 2398 580 568 2399 578 568 2400 578 569 2401 577 571 2402 579 570 2403 580 571 2404 579 572 2405 581 574 2406 582 573 2407 583 565 2408 576 565 2409 576 566 2410 575 574 2411 582 576 2412 584 575 2413 585 573 2414 583 573 2415 583 574 2416 582 576 2417 584 575 2418 585 576 2419 584 577 2420 586 562 2421 1165 542 2422 1145 543 2423 1148 543 2424 1148 561 2425 1166 562 2426 1165 560 2427 1163 544 2428 1147 545 2429 1146 545 2430 1146 563 2431 1164 560 2432 1163 565 2433 1170 547 2434 1152 548 2435 1151 548 2436 1151 564 2437 1167 565 2438 1170 567 2439 1168 549 2440 1150 546 2441 1149 546 2442 1149 566 2443 1169 567 2444 1168 568 2445 1172 551 2446 1154 542 2447 1145 542 2448 1145 562 2449 1165 568 2450 1172 563 2451 1164 545 2452 1146 550 2453 1153 550 2454 1153 569 2455 1171 563 2456 1164 570 2457 1174 553 2458 1156 551 2459 1154 551 2460 1154 568 2461 1172 570 2462 1174 569 2463 1171 550 2464 1153 552 2465 1155 552 2466 1155 571 2467 1173 569 2468 1171 571 2469 1173 552 2470 1155 554 2471 1157 554 2472 1157 572 2473 1175 571 2474 1173 572 2475 1175 554 2476 1157 553 2477 1156 553 2478 1156 570 2479 1174 572 2480 1175 573 2481 1177 556 2482 1159 547 2483 1152 547 2484 1152 565 2485 1170 573 2486 1177 566 2487 1169 546 2488 1149 555 2489 1158 555 2490 1158 574 2491 1176 566 2492 1169 575 2493 1179 558 2494 1161 556 2495 1159 556 2496 1159 573 2497 1177 575 2498 1179 574 2499 1176 555 2500 1158 557 2501 1160 557 2502 1160 576 2503 1178 574 2504 1176 576 2505 1178 557 2506 1160 559 2507 1162 559 2508 1162 577 2509 1180 576 2510 1178 577 2511 1180 559 2512 1162 558 2513 1161 558 2514 1161 575 2515 1179 577 2516 1180 578 2517 587 581 2518 588 580 2519 589 580 2520 589 579 2521 590 578 2522 587 579 2523 590 580 2524 589 583 2525 591 583 2526 591 582 2527 592 579 2528 590 582 2529 592 583 2530 591 585 2531 593 585 2532 593 584 2533 594 582 2534 592 584 2535 594 585 2536 593 587 2537 595 587 2538 595 586 2539 596 584 2540 594 586 2541 596 587 2542 595 589 2543 597 589 2544 597 588 2545 598 586 2546 596 588 2547 598 589 2548 597 591 2549 599 591 2550 599 590 2551 600 588 2552 598 590 2553 600 591 2554 599 593 2555 601 593 2556 601 592 2557 602 590 2558 600 592 2559 1222 593 2560 1221 595 2561 603 595 2562 603 594 2563 604 592 2564 1222 594 2565 604 595 2566 603 581 2567 588 581 2568 588 578 2569 587 594 2570 604 598 2571 607 597 2572 608 596 2573 605 596 2574 605 599 2575 606 598 2576 607 602 2577 611 601 2578 612 600 2579 609 600 2580 609 603 2581 610 602 2582 611 596 2583 605 597 2584 608 604 2585 613 604 2586 613 605 2587 614 596 2588 605 605 2589 614 604 2590 613 606 2591 615 606 2592 615 607 2593 616 605 2594 614 606 2595 615 608 2596 617 607 2597 616 603 2598 610 600 2599 609 609 2600 618 609 2601 618 610 2602 619 603 2603 610 610 2604 619 609 2605 618 611 2606 620 611 2607 620 612 2608 621 610 2609 619 611 2610 620 613 2611 622 612 2612 621 616 2613 625 615 2614 626 614 2615 623 614 2616 623 617 2617 624 616 2618 625 620 2619 629 619 2620 630 618 2621 627 618 2622 627 621 2623 628 620 2624 629 622 2625 632 615 2626 626 616 2627 625 616 2628 625 623 2629 631 622 2630 632 624 2631 634 622 2632 632 623 2633 631 623 2634 631 625 2635 633 624 2636 634 625 2637 633 626 2638 635 624 2639 634 627 2640 637 620 2641 629 621 2642 628 621 2643 628 628 2644 636 627 2645 637 629 2646 639 627 2647 637 628 2648 636 628 2649 636 630 2650 638 629 2651 639 630 2652 638 631 2653 640 629 2654 639 616 2655 1201 617 2656 1200 599 2657 1182 599 2658 1182 596 2659 1181 616 2660 1201 614 2661 1199 615 2662 1202 597 2663 1184 597 2664 1184 598 2665 1183 614 2666 1199 621 2667 1204 618 2668 1203 602 2669 1187 602 2670 1187 603 2671 1186 621 2672 1204 619 2673 1206 620 2674 1205 600 2675 1185 600 2676 1185 601 2677 1188 619 2678 1206 623 2679 1207 616 2680 1201 596 2681 1181 596 2682 1181 605 2683 1190 623 2684 1207 615 2685 1202 622 2686 1208 604 2687 1189 604 2688 1189 597 2689 1184 615 2690 1202 625 2691 1209 623 2692 1207 605 2693 1190 605 2694 1190 607 2695 1192 625 2696 1209 622 2697 1208 624 2698 1210 606 2699 1191 606 2700 1191 604 2701 1189 622 2702 1208 624 2703 1210 626 2704 1211 608 2705 1193 608 2706 1193 606 2707 1191 624 2708 1210 626 2709 1211 625 2710 1209 607 2711 1192 607 2712 1192 608 2713 1193 626 2714 1211 628 2715 1212 621 2716 1204 603 2717 1186 603 2718 1186 610 2719 1195 628 2720 1212 620 2721 1205 627 2722 1213 609 2723 1194 609 2724 1194 600 2725 1185 620 2726 1205 630 2727 1214 628 2728 1212 610 2729 1195 610 2730 1195 612 2731 1197 630 2732 1214 627 2733 1213 629 2734 1215 611 2735 1196 611 2736 1196 609 2737 1194 627 2738 1213 629 2739 1215 631 2740 1216 613 2741 1198 613 2742 1198 611 2743 1196 629 2744 1215 631 2745 1216 630 2746 1214 612 2747 1197 612 2748 1197 613 2749 1198 631 2750 1216 632 2751 641 635 2752 642 634 2753 643 634 2754 643 633 2755 644 632 2756 641 635 2757 642 637 2758 645 636 2759 646 636 2760 646 634 2761 643 635 2762 642 637 2763 645 639 2764 647 638 2765 648 638 2766 648 636 2767 646 637 2768 645 639 2769 647 641 2770 649 640 2771 650 640 2772 650 638 2773 648 639 2774 647 641 2775 649 643 2776 651 642 2777 652 642 2778 652 640 2779 650 641 2780 649 643 2781 651 645 2782 653 644 2783 654 644 2784 654 642 2785 652 643 2786 651 645 2787 1223 647 2788 655 646 2789 656 646 2790 656 644 2791 1224 645 2792 1223 647 2793 655 649 2794 657 648 2795 658 648 2796 658 646 2797 656 647 2798 655 649 2799 657 632 2800 641 633 2801 644 633 2802 644 648 2803 658 649 2804 657 659 2805 659 658 2806 660 650 2807 661 650 2808 661 651 2809 662 659 2810 659 660 2811 663 659 2812 659 651 2813 662 651 2814 662 652 2815 664 660 2816 663 661 2817 665 660 2818 663 652 2819 664 652 2820 664 653 2821 666 661 2822 665 662 2823 667 661 2824 665 653 2825 666 653 2826 666 654 2827 668 662 2828 667 663 2829 669 662 2830 667 654 2831 668 654 2832 668 655 2833 670 663 2834 669 664 2835 671 663 2836 669 655 2837 670 655 2838 670 656 2839 672 664 2840 671 665 2841 673 664 2842 671 656 2843 672 656 2844 672 657 2845 674 665 2846 673 665 2847 673 657 2848 674 650 2849 1062 650 2850 1062 658 2851 1061 665 2852 673 666 2853 675 667 2854 676 675 2855 677 675 2856 677 674 2857 678 666 2858 675 667 2859 676 668 2860 679 676 2861 680 676 2862 680 675 2863 677 667 2864 676 668 2865 1063 669 2866 681 677 2867 682 677 2868 682 676 2869 1064 668 2870 1063 669 2871 681 670 2872 683 678 2873 684 678 2874 684 677 2875 682 669 2876 681 670 2877 683 671 2878 685 679 2879 686 679 2880 686 678 2881 684 670 2882 683 671 2883 685 672 2884 687 680 2885 688 680 2886 688 679 2887 686 671 2888 685 672 2889 687 673 2890 689 681 2891 690 681 2892 690 680 2893 688 672 2894 687 673 2895 689 666 2896 675 674 2897 678 674 2898 678 681 2899 690 673 2900 689 682 2901 691 683 2902 692 691 2903 693 691 2904 693 690 2905 694 682 2906 691 683 2907 692 684 2908 695 692 2909 696 692 2910 696 691 2911 693 683 2912 692 684 2913 1065 685 2914 697 693 2915 698 693 2916 698 692 2917 1066 684 2918 1065 685 2919 697 686 2920 699 694 2921 700 694 2922 700 693 2923 698 685 2924 697 686 2925 699 687 2926 701 695 2927 702 695 2928 702 694 2929 700 686 2930 699 687 2931 701 688 2932 703 696 2933 704 696 2934 704 695 2935 702 687 2936 701 688 2937 703 689 2938 705 697 2939 706 697 2940 706 696 2941 704 688 2942 703 689 2943 705 682 2944 691 690 2945 694 690 2946 694 697 2947 706 689 2948 705 698 2949 707 701 2950 708 700 2951 709 700 2952 709 699 2953 710 698 2954 707 702 2955 711 703 2956 712 701 2957 708 701 2958 708 698 2959 707 702 2960 711 704 2961 713 705 2962 714 703 2963 712 703 2964 712 702 2965 711 704 2966 713 706 2967 715 707 2968 716 705 2969 714 705 2970 714 704 2971 713 706 2972 715 708 2973 717 709 2974 718 707 2975 716 707 2976 716 706 2977 715 708 2978 717 710 2979 719 711 2980 720 709 2981 718 709 2982 718 708 2983 717 710 2984 719 712 2985 721 713 2986 722 711 2987 720 711 2988 720 710 2989 719 712 2990 721 712 2991 721 699 2992 1068 700 2993 1067 700 2994 1067 713 2995 722 712 2996 721 714 2997 723 717 2998 724 716 2999 725 716 3000 725 715 3001 726 714 3002 723 715 3003 726 716 3004 725 719 3005 727 719 3006 727 718 3007 728 715 3008 726 718 3009 1070 719 3010 1069 721 3011 729 721 3012 729 720 3013 730 718 3014 1070 720 3015 730 721 3016 729 723 3017 731 723 3018 731 722 3019 732 720 3020 730 722 3021 732 723 3022 731 725 3023 733 725 3024 733 724 3025 734 722 3026 732 724 3027 734 725 3028 733 727 3029 735 727 3030 735 726 3031 736 724 3032 734 726 3033 736 727 3034 735 729 3035 737 729 3036 737 728 3037 738 726 3038 736 728 3039 738 729 3040 737 717 3041 724 717 3042 724 714 3043 723 728 3044 738 730 3045 739 733 3046 740 732 3047 741 732 3048 741 731 3049 742 730 3050 739 731 3051 742 732 3052 741 735 3053 743 735 3054 743 734 3055 744 731 3056 742 734 3057 1072 735 3058 1071 737 3059 745 737 3060 745 736 3061 746 734 3062 1072 736 3063 746 737 3064 745 739 3065 747 739 3066 747 738 3067 748 736 3068 746 738 3069 748 739 3070 747 741 3071 749 741 3072 749 740 3073 750 738 3074 748 740 3075 750 741 3076 749 743 3077 751 743 3078 751 742 3079 752 740 3080 750 742 3081 752 743 3082 751 745 3083 753 745 3084 753 744 3085 754 742 3086 752 744 3087 754 745 3088 753 733 3089 740 733 3090 740 730 3091 739 744 3092 754

+
+
+
+ + + + + + + + + 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.0000001.000000 + 30.0000000.0000003.333333 + + + + + +
diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_TrashCanC_01/model.config b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_TrashCanC_01/model.config new file mode 100755 index 0000000..28251bb --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_TrashCanC_01/model.config @@ -0,0 +1,11 @@ + + + aws_robomaker_warehouse_TrashCanC_01 + 1.0 + model.sdf + + + + + + diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_TrashCanC_01/model.sdf b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_TrashCanC_01/model.sdf new file mode 100755 index 0000000..483c066 --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_TrashCanC_01/model.sdf @@ -0,0 +1,46 @@ + + + + + + 1 + + 0.200 + 0 + 0 + 0.308 + 0 + 0.240 + + + + + + model://aws_robomaker_warehouse_TrashCanC_01/meshes/aws_robomaker_warehouse_TrashCanC_01_collision.DAE + 1 1 1 + + + + + + 0.4 + 0.4 + 0 0 0 + 0 + 0 + + + + + + + + model://aws_robomaker_warehouse_TrashCanC_01/meshes/aws_robomaker_warehouse_TrashCanC_01_visual.DAE + + + 1 + + +1 + + diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_WallB_01/materials/textures/aws_robomaker_warehouse_WallB_01.png b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_WallB_01/materials/textures/aws_robomaker_warehouse_WallB_01.png new file mode 100755 index 0000000..f635537 Binary files /dev/null and b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_WallB_01/materials/textures/aws_robomaker_warehouse_WallB_01.png differ diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_WallB_01/meshes/aws_robomaker_warehouse_WallB_01_collision.DAE b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_WallB_01/meshes/aws_robomaker_warehouse_WallB_01_collision.DAE new file mode 100755 index 0000000..eb18cdd --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_WallB_01/meshes/aws_robomaker_warehouse_WallB_01_collision.DAE @@ -0,0 +1,343 @@ + + + FBX COLLADA exporter2019-05-15T08:14:39Z2019-05-15T08:14:39ZZ_UP + + + + + +699.023682 1032.083740 0.000000 +699.023682 1045.333252 0.000000 +-699.023315 1032.083618 0.000000 +-699.023315 1045.333130 0.000000 +699.023682 1032.083740 901.986084 +699.023682 1045.333252 901.986084 +-699.023315 1032.083618 901.986084 +-699.023315 1045.333130 901.986084 +685.143066 1032.083740 0.000000 +685.143066 1045.333252 0.000000 +685.143066 1045.333252 901.986084 +685.143066 1032.083740 901.986084 +699.023682 -1045.333130 0.000000 +699.023682 -1045.333130 901.986084 +685.143066 -1045.333130 0.000000 +685.143066 -1045.333130 901.986084 +685.143066 -1032.083618 901.986084 +699.023682 -1032.083618 901.986084 +699.023682 -1032.083618 0.000000 +685.143066 -1032.083618 0.000000 +-699.023315 -1045.333130 0.000000 +-699.023315 -1045.333130 901.986084 +-699.023315 -1032.083618 901.986084 +-699.023315 -1032.083618 0.000000 +-686.135132 -1032.083618 901.986084 +-686.135132 -1045.333130 901.986084 +-686.135132 -1045.333130 0.000000 +-686.135132 -1032.083618 0.000000 +-686.135132 1032.083618 901.986084 +-686.135193 1045.333130 901.986084 +-686.135132 1045.333130 0.000000 +-686.135193 1032.083618 0.000000 + + + + + + + + + + + +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +-0.000000 1.000000 -0.000000 +-0.000000 1.000000 -0.000000 +-0.000000 1.000000 -0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.000000 1.000000 -0.000000 +-0.000000 1.000000 -0.000000 +-0.000000 1.000000 -0.000000 +-0.000000 1.000000 -0.000000 +-0.000000 1.000000 -0.000000 +-0.000000 1.000000 -0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -1.000000 -0.000000 +0.000000 -1.000000 -0.000000 +0.000000 -1.000000 -0.000000 +0.000000 -1.000000 -0.000000 +0.000000 -1.000000 -0.000000 +0.000000 -1.000000 -0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.000000 1.000000 -0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.000000 1.000000 -0.000000 +-0.000000 1.000000 -0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 + + + + + + + + + + + +1.000000 0.000000 +0.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +1.000000 0.009929 +0.990071 0.000000 +0.000000 0.009929 +0.009929 0.000000 +1.000000 0.009929 +0.009929 1.000000 +0.000000 0.009929 +0.990071 1.000000 +1.000000 0.000000 +1.000000 0.009929 +0.000000 1.000000 +0.000000 0.000000 +0.000000 0.009929 +0.000000 0.000000 +0.990071 0.000000 +0.000000 0.009929 +0.990071 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 0.000000 +0.990071 0.000000 +1.000000 0.009929 +0.000000 0.009929 +0.990071 0.000000 +0.000000 0.009929 +1.000000 0.009929 +1.000000 0.009929 +0.990071 0.000000 +0.000000 0.009929 +0.990071 1.000000 +0.000000 0.009929 +1.000000 0.009929 +0.990071 0.000000 +0.990071 0.000000 +1.000000 0.009929 +0.000000 0.989764 +0.010236 1.000000 +1.000000 0.989764 +0.989764 1.000000 +0.000000 0.989764 +0.989764 0.000000 +1.000000 0.989764 +0.010236 0.000000 + + + + + + + + + + + +

0 0 0 8 1 20 1 2 1 8 3 20 9 4 22 1 5 1 10 6 24 11 7 26 5 8 5 5 9 5 11 10 26 4 11 4 4 12 10 0 13 8 5 14 11 5 15 11 0 16 8 1 17 9 5 18 14 9 19 23 10 20 25 9 21 23 5 22 14 1 23 12 7 24 18 3 25 16 6 26 19 6 27 19 3 28 16 2 29 17 30 30 60 8 31 20 31 32 62 8 33 20 30 34 60 9 35 22 28 36 56 10 37 24 29 38 58 10 39 24 28 40 56 11 41 26 10 42 25 30 43 61 29 44 59 30 45 61 10 46 25 9 47 23 19 48 42 0 49 0 18 50 39 0 51 0 19 52 42 8 53 20 4 54 10 17 55 37 18 56 40 4 57 10 18 58 40 0 59 8 17 60 38 4 61 4 11 62 26 11 63 26 16 64 35 17 65 38 16 66 36 11 67 27 8 68 21 16 69 36 8 70 21 19 71 41 15 72 32 14 73 34 13 74 30 13 75 30 14 76 34 12 77 28 14 78 29 19 79 42 12 80 28 12 81 28 19 82 42 18 83 39 18 84 40 17 85 37 13 86 30 13 87 30 12 88 31 18 89 40 17 90 38 16 91 35 15 92 32 17 93 38 15 94 32 13 95 33 26 96 53 15 97 32 25 98 51 15 99 32 26 100 53 14 101 34 25 102 51 16 103 35 24 104 49 16 105 35 25 106 51 15 107 32 14 108 29 26 109 52 27 110 55 14 111 29 27 112 55 19 113 42 24 114 50 16 115 36 19 116 41 24 117 50 19 118 41 27 119 54 20 120 46 21 121 43 22 122 45 22 123 45 23 124 48 20 125 46 26 126 53 25 127 51 21 128 43 21 129 43 20 130 44 26 131 53 24 132 49 22 133 45 25 134 51 22 135 45 21 136 43 25 137 51 26 138 52 20 139 46 27 140 55 20 141 46 23 142 47 27 143 55 28 144 57 8 145 21 11 146 27 8 147 21 28 148 57 31 149 63 31 150 62 3 151 3 30 152 60 3 153 3 31 154 62 2 155 2 29 156 58 6 157 6 28 158 56 6 159 6 29 160 58 7 161 7 29 162 59 3 163 13 7 164 15 3 165 13 29 166 59 30 167 61 6 168 6 22 169 45 28 170 56 28 171 56 22 172 45 24 173 49 2 174 17 23 175 48 6 176 19 22 177 45 6 178 19 23 179 48 23 180 47 31 181 62 27 182 55 31 183 62 23 184 47 2 185 2 24 186 50 31 187 63 28 188 57 31 189 63 24 190 50 27 191 54

+
+
+
+ + + 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.0000001.000000 + 30.0000000.0000003.333333 + + + + + +
diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_WallB_01/meshes/aws_robomaker_warehouse_WallB_01_visual.DAE b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_WallB_01/meshes/aws_robomaker_warehouse_WallB_01_visual.DAE new file mode 100755 index 0000000..9356888 --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_WallB_01/meshes/aws_robomaker_warehouse_WallB_01_visual.DAE @@ -0,0 +1,289 @@ + + + FBX COLLADA exporter2019-05-24T10:55:29Z2019-05-24T10:55:29ZZ_UP + + + ../materials/textures/aws_robomaker_warehouse_WallB_01.png + + + + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + +699.023682 1045.333252 0.000000 +-699.023315 1045.333130 0.000000 +699.023682 1045.333252 901.986084 +-699.023315 1045.333130 901.986084 +685.143066 1032.083740 0.000000 +685.143066 1045.333252 901.986084 +685.143066 1032.083740 901.986084 +699.023682 -1045.333130 0.000000 +699.023682 -1045.333130 901.986084 +685.143066 -1032.083618 901.986084 +699.023682 -1032.083618 901.986084 +685.143066 -1032.083618 0.000000 +-699.023315 -1045.333130 0.000000 +-699.023315 -1045.333130 901.986084 +-686.135132 -1032.083618 901.986084 +-686.135132 -1045.333130 901.986084 +-686.135132 -1032.083618 0.000000 +-686.135132 1032.083618 901.986084 +-686.135193 1032.083618 0.000000 + + + + + + + + + + + +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 -0.000000 +0.000000 -1.000000 -0.000000 +0.000000 -1.000000 -0.000000 +-0.000000 1.000000 -0.000000 +-0.000000 1.000000 -0.000000 +-0.000000 1.000000 -0.000000 +-0.000000 1.000000 -0.000000 +-0.000000 1.000000 -0.000000 +-0.000000 1.000000 -0.000000 +-0.000000 1.000000 -0.000000 +-0.000000 1.000000 -0.000000 +-0.000000 1.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 + + + + + + + + + + + +1.423979 0.041268 +1.432463 0.041268 +1.432463 0.050156 +1.423979 0.050156 +0.657583 2.277837 +0.657583 2.286321 +0.080013 2.286321 +0.080013 2.277837 +0.133948 0.068165 +0.142837 0.068165 +0.142837 0.645734 +0.133948 0.645734 +1.439517 0.041268 +1.448001 0.041268 +1.448001 0.618837 +1.439517 0.618837 +0.080013 2.898408 +1.020908 0.068165 +1.432463 0.928227 +1.020908 0.645734 +1.423979 0.928227 +0.080013 2.320839 +0.080014 0.956087 +0.657583 0.956087 +0.102230 0.050156 +0.102230 0.041268 +1.538820 1.910483 +0.093746 0.050156 +1.401763 2.320839 +0.080014 0.947603 +0.093746 0.041268 +0.657583 0.947603 +1.401763 2.898408 +0.102230 0.928227 +0.961250 1.910483 +0.093746 0.928227 +2.778234 0.618837 +0.102230 0.936480 +2.154409 1.980973 +0.093746 0.936480 +0.961250 1.901595 +1.576840 1.980973 +1.432463 0.936480 +1.576841 0.659224 +1.423979 0.936480 +1.029160 0.068165 +1.029160 0.645734 +2.154409 0.659224 +1.538820 1.901595 +0.961250 1.023523 +1.538820 1.023523 +0.961250 1.015271 +1.538820 1.015271 +2.769750 0.618837 +2.769750 0.041268 +2.778234 0.041268 +2.181874 2.869334 +1.604305 2.869334 +1.604305 1.991262 +2.181875 1.991262 +2.167332 1.537295 +2.167332 0.659224 +2.744901 0.659224 +2.744901 1.537295 + + + + + + + + + + + +

6 0 3 2 1 1 5 2 2 5 3 2 17 4 20 6 5 3 2 6 1 6 7 3 10 8 25 10 9 22 0 10 5 2 11 6 7 12 31 10 13 22 8 14 29 10 15 22 7 16 31 0 17 5 13 18 36 3 19 15 1 20 12 13 21 36 1 22 12 12 23 55 17 24 20 5 25 2 3 26 42 10 27 25 9 28 24 8 29 30 10 30 25 6 31 3 9 32 24 9 33 32 6 34 16 4 35 21 9 36 32 4 37 21 11 38 28 15 39 49 7 40 26 8 41 34 12 42 52 15 43 49 13 44 51 15 45 49 12 46 52 7 47 26 9 48 24 14 49 33 15 50 35 15 51 35 14 52 33 13 53 39 14 54 59 9 55 56 11 56 57 14 57 59 11 58 57 16 59 58 17 60 63 4 61 61 6 62 62 4 63 61 17 64 63 18 65 60 5 66 10 1 67 45 3 68 46 0 69 8 5 70 10 2 71 11 5 72 10 0 73 8 1 74 45 14 75 43 18 76 38 17 77 41 18 78 38 14 79 43 16 80 47 9 81 24 15 82 35 8 83 30 3 84 42 13 85 39 17 86 20 17 87 20 13 88 39 14 89 33

+
+
+
+ + + + + + + + + 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.0000001.000000 + 30.0000000.0000003.333333 + + + + + +
diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_WallB_01/model.config b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_WallB_01/model.config new file mode 100755 index 0000000..ba404b6 --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_WallB_01/model.config @@ -0,0 +1,11 @@ + + + aws_robomaker_warehouse_WallB_01 + 1.0 + model.sdf + + + + + + diff --git a/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_WallB_01/model.sdf b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_WallB_01/model.sdf new file mode 100755 index 0000000..66af32f --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/models/aws_robomaker_warehouse_WallB_01/model.sdf @@ -0,0 +1,46 @@ + + + + + + 1000 + + 840083.33 + 0 + 0 + 475500.0 + 0 + 1302083.33 + + + + + + model://aws_robomaker_warehouse_WallB_01/meshes/aws_robomaker_warehouse_WallB_01_collision.DAE + 1 1 1 + + + + + + 0.5 + 0.5 + 0 0 0 + 0 + 0 + + + + + + + + model://aws_robomaker_warehouse_WallB_01/meshes/aws_robomaker_warehouse_WallB_01_visual.DAE + + + 2 + + +1 + + diff --git a/simulators/dynamic_logistics_warehouse_h/models/meshes/001.stl b/simulators/dynamic_logistics_warehouse_h/models/meshes/001.stl new file mode 100755 index 0000000..629534c Binary files /dev/null and b/simulators/dynamic_logistics_warehouse_h/models/meshes/001.stl differ diff --git a/simulators/dynamic_logistics_warehouse_h/models/meshes/001_sldprt.stl b/simulators/dynamic_logistics_warehouse_h/models/meshes/001_sldprt.stl new file mode 100755 index 0000000..1386822 Binary files /dev/null and b/simulators/dynamic_logistics_warehouse_h/models/meshes/001_sldprt.stl differ diff --git a/simulators/dynamic_logistics_warehouse_h/models/meshes/3_do_sldprt.stl b/simulators/dynamic_logistics_warehouse_h/models/meshes/3_do_sldprt.stl new file mode 100755 index 0000000..b889ca6 Binary files /dev/null and b/simulators/dynamic_logistics_warehouse_h/models/meshes/3_do_sldprt.stl differ diff --git a/simulators/dynamic_logistics_warehouse_h/models/meshes/Part33.stl b/simulators/dynamic_logistics_warehouse_h/models/meshes/Part33.stl new file mode 100755 index 0000000..581bd03 Binary files /dev/null and b/simulators/dynamic_logistics_warehouse_h/models/meshes/Part33.stl differ diff --git a/simulators/dynamic_logistics_warehouse_h/models/samp/model.config b/simulators/dynamic_logistics_warehouse_h/models/samp/model.config new file mode 100755 index 0000000..166fe54 --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/models/samp/model.config @@ -0,0 +1,11 @@ + + + samp + 1.0 + model.sdf + + + + + + diff --git a/simulators/dynamic_logistics_warehouse_h/models/samp/model.sdf b/simulators/dynamic_logistics_warehouse_h/models/samp/model.sdf new file mode 100755 index 0000000..5caa4ce --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/models/samp/model.sdf @@ -0,0 +1,107 @@ + + + + + + 1 + + 0.166667 + 0 + 0 + 0.166667 + 0 + 0.166667 + + 0 0 0 0 -0 0 + + 0 0 0 1.5708 -0 0 + 1 + 0 + 1 + 0 + + 0 0 0 0 -0 0 + + + /home/robotics/AGV/amr_100_ws/src/amr_100/simulators/dynamic_logistics_warehouse_h/models/meshes/3_do_sldprt.stl + 1 1 1 + + + + 1 + + + __default__ + + 0.3 0.3 0.3 1 + 0.7 0.7 0.7 1 + 0.01 0.01 0.01 1 + 0 0 0 1 + + 0 + 1 + + + 0 + 10 + 0 0 0 0 -0 0 + + + /home/robotics/AGV/amr_100_ws/src/amr_100/simulators/dynamic_logistics_warehouse_h/models/meshes/3_do_sldprt.stl + 1 1 1 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 0 + 1 + + diff --git a/simulators/dynamic_logistics_warehouse_h/models/samp_1/model.config b/simulators/dynamic_logistics_warehouse_h/models/samp_1/model.config new file mode 100755 index 0000000..48a03c2 --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/models/samp_1/model.config @@ -0,0 +1,11 @@ + + + samp_1 + 1.0 + model.sdf + + + + + + diff --git a/simulators/dynamic_logistics_warehouse_h/models/samp_1/model.sdf b/simulators/dynamic_logistics_warehouse_h/models/samp_1/model.sdf new file mode 100755 index 0000000..77c2293 --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/models/samp_1/model.sdf @@ -0,0 +1,107 @@ + + + + + + 1 + + 0.166667 + 0 + 0 + 0.166667 + 0 + 0.166667 + + 0 0 0 0 -0 0 + + 0 -0 0 1.5708 -0 0 + 1 + 0 + 1 + 0 + + 0 0 0 0 -0 0 + + + /home/robotics/AGV/amr_100_ws/src/amr_100/simulators/dynamic_logistics_warehouse_h/models/meshes/3_do_sldprt.stl + 1 1 1 + + + + 1 + + + __default__ + + 0.3 0.3 0.3 1 + 0.7 0.7 0.7 1 + 0.01 0.01 0.01 1 + 0 0 0 1 + + 0 + 1 + + + 0.2 + 10 + 0 0 0 0 -0 0 + + + /home/robotics/AGV/amr_100_ws/src/amr_100/simulators/dynamic_logistics_warehouse_h/models/meshes/3_do_sldprt.stl + 1 1 1 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 0 + 1 + + diff --git a/simulators/dynamic_logistics_warehouse_h/models/samp_4_do/model.config b/simulators/dynamic_logistics_warehouse_h/models/samp_4_do/model.config new file mode 100755 index 0000000..0f75779 --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/models/samp_4_do/model.config @@ -0,0 +1,11 @@ + + + samp_4_do + 1.0 + model.sdf + + + + + + diff --git a/simulators/dynamic_logistics_warehouse_h/models/samp_4_do/model.sdf b/simulators/dynamic_logistics_warehouse_h/models/samp_4_do/model.sdf new file mode 100755 index 0000000..853717f --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/models/samp_4_do/model.sdf @@ -0,0 +1,107 @@ + + + + + + 1 + + 0.166667 + 0 + 0 + 0.166667 + 0 + 0.166667 + + 0 0 0 0 -0 0 + + -0 0 0 1.5708 -0 0 + 1 + 0 + 1 + 0 + + 0 0 0 0 -0 0 + + + /home/robotics/AGV/amr_100_ws/src/amr_100/simulators/dynamic_logistics_warehouse_h/models/meshes/001_sldprt.stl + 1 1 1 + + + + 1 + + + __default__ + + 0.3 0.3 0.3 1 + 0.7 0.7 0.7 1 + 0.01 0.01 0.01 1 + 0 0 0 1 + + 0 + 1 + + + 0 + 10 + 0 0 0 0 -0 0 + + + /home/robotics/AGV/amr_100_ws/src/amr_100/simulators/dynamic_logistics_warehouse_h/models/meshes/001_sldprt.stl + 1 1 1 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 0 + 1 + + diff --git a/simulators/dynamic_logistics_warehouse_h/models/samp_6_do/model.config b/simulators/dynamic_logistics_warehouse_h/models/samp_6_do/model.config new file mode 100755 index 0000000..ebfde25 --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/models/samp_6_do/model.config @@ -0,0 +1,11 @@ + + + samp_6_do + 1.0 + model.sdf + + + + + + diff --git a/simulators/dynamic_logistics_warehouse_h/models/samp_6_do/model.sdf b/simulators/dynamic_logistics_warehouse_h/models/samp_6_do/model.sdf new file mode 100755 index 0000000..ab89d81 --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/models/samp_6_do/model.sdf @@ -0,0 +1,107 @@ + + + + + + 1 + + 0.166667 + 0 + 0 + 0.166667 + 0 + 0.166667 + + 0 0 0 0 -0 0 + + -0 0 0 1.5708 -0 0 + 1 + 0 + 1 + 0 + + 0 0 0 0 -0 0 + + + /home/robotics/AGV/amr_100_ws/src/amr_100/simulators/dynamic_logistics_warehouse_h/models/meshes/001.stl + 1 1 1 + + + + 1 + + + __default__ + + 0.3 0.3 0.3 1 + 0.7 0.7 0.7 1 + 0.01 0.01 0.01 1 + 0 0 0 1 + + 0 + 1 + + + 0 + 10 + 0 0 0 0 -0 0 + + + /home/robotics/AGV/amr_100_ws/src/amr_100/simulators/dynamic_logistics_warehouse_h/models/meshes/001.stl + 1 1 1 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 0 + 1 + + diff --git a/simulators/dynamic_logistics_warehouse_h/models/walls/model.config b/simulators/dynamic_logistics_warehouse_h/models/walls/model.config new file mode 100755 index 0000000..799a5e8 --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/models/walls/model.config @@ -0,0 +1,11 @@ + + + walls + 1.0 + model.sdf + + + + + + diff --git a/simulators/dynamic_logistics_warehouse_h/models/walls/model.sdf b/simulators/dynamic_logistics_warehouse_h/models/walls/model.sdf new file mode 100755 index 0000000..91c982d --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/models/walls/model.sdf @@ -0,0 +1,123 @@ + + + + 14 20.85 0 0 -0 0 + + + + + 42.15 0.15 2.5 + + + 0 0 1.25 0 -0 0 + + + 0 0 1.25 0 -0 0 + + + 42.15 0.15 2.5 + + + + + 1 1 1 1 + + + 0 + + + -0 -31.35 0 0 -0 0 + + + + + + 62.85 0.15 2.5 + + + 0 0 1.25 0 -0 0 + + + 0 0 1.25 0 -0 0 + + + 62.85 0.15 2.5 + + + + + 1 1 1 1 + + + 0 + + + -21 1e-06 0 0 -0 1.5708 + + + + + + 62.85 0.15 2.5 + + + 0 0 1.25 0 -0 0 + + + 0 0 1.25 0 -0 0 + + + 62.85 0.15 2.5 + + + + + 1 1 1 1 + + + 0 + + + 21 1e-06 0 0 -0 1.5708 + + + + + + 42.15 0.15 2.5 + + + 0 0 1.25 0 -0 0 + + + 0 0 1.25 0 -0 0 + + + 42.15 0.15 2.5 + + + + + 1 1 1 1 + + + 0 + + + -0 31.35 0 0 -0 0 + + 1 + + diff --git a/simulators/dynamic_logistics_warehouse_h/package.xml b/simulators/dynamic_logistics_warehouse_h/package.xml new file mode 100755 index 0000000..429c5d0 --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/package.xml @@ -0,0 +1,18 @@ + + + dynamic_logistics_warehouse + 1.0.0 + + LARGE INDUTRIAL WAREHOUSE + + Apache 2.0 + + + catkin + gazebo_ros + gazebo + gazebo_plugins + + + + diff --git a/simulators/dynamic_logistics_warehouse_h/rviz/basic_data.rviz b/simulators/dynamic_logistics_warehouse_h/rviz/basic_data.rviz new file mode 100755 index 0000000..63a035d --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/rviz/basic_data.rviz @@ -0,0 +1,314 @@ +Panels: + - Class: rviz/Displays + Help Height: 78 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /Odometry1/Shape1 + Splitter Ratio: 0.5 + Tree Height: 747 + - Class: rviz/Selection + Name: Selection + - Class: rviz/Tool Properties + Expanded: + - /2D Pose Estimate1 + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.588679016 + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: LaserScan + - Class: rviz/Tool Properties + Expanded: + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5 + - Class: rviz/Tool Properties + Expanded: ~ + Name: Tool Properties + Splitter Ratio: 0.5 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.0299999993 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Alpha: 0.699999988 + Class: rviz/Map + Color Scheme: map + Draw Behind: false + Enabled: true + Name: Map + Topic: /map + Unreliable: false + Use Timestamp: false + Value: true + - Angle Tolerance: 0.100000001 + Class: rviz/Odometry + Covariance: + Orientation: + Alpha: 0.5 + Color: 255; 255; 127 + Color Style: Unique + Frame: Local + Offset: 1 + Scale: 1 + Value: true + Position: + Alpha: 0.300000012 + Color: 204; 51; 204 + Scale: 1 + Value: true + Value: true + Enabled: false + Keep: 3 + Name: Odometry + Position Tolerance: 0.100000001 + Shape: + Alpha: 1 + Axes Length: 1 + Axes Radius: 0.100000001 + Color: 85; 0; 255 + Head Length: 0.300000012 + Head Radius: 0.100000001 + Shaft Length: 1 + Shaft Radius: 0.100000001 + Value: Arrow + Topic: /boxer_velocity_controller/odom + Unreliable: false + Value: false + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/LaserScan + Color: 255; 0; 0 + Color Transformer: FlatColor + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 6640 + Min Color: 0; 0; 0 + Min Intensity: 104 + Name: LaserScan + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.100000001 + Style: Flat Squares + Topic: /front/scan + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true + - Alpha: 1 + Axes Length: 1 + Axes Radius: 0.100000001 + Class: rviz/PoseWithCovariance + Color: 255; 25; 0 + Covariance: + Orientation: + Alpha: 0.5 + Color: 255; 255; 127 + Color Style: Unique + Frame: Local + Offset: 1 + Scale: 1 + Value: true + Position: + Alpha: 0.300000012 + Color: 204; 51; 204 + Scale: 1 + Value: true + Value: true + Enabled: true + Head Length: 0.100000001 + Head Radius: 0.0500000007 + Name: PoseWithCovariance + Shaft Length: 0.5 + Shaft Radius: 0.0500000007 + Shape: Arrow + Topic: /amcl_pose + Unreliable: false + Value: true + - Alpha: 1 + Buffer Length: 1 + Class: rviz/Path + Color: 25; 255; 0 + Enabled: true + Head Diameter: 0.300000012 + Head Length: 0.200000003 + Length: 0.300000012 + Line Style: Lines + Line Width: 0.0299999993 + Name: Path + Offset: + X: 0 + Y: 0 + Z: 0 + Pose Color: 255; 85; 255 + Pose Style: None + Radius: 0.0299999993 + Shaft Diameter: 0.100000001 + Shaft Length: 0.100000001 + Topic: /move_base/TrajectoryPlannerROS/global_plan + Unreliable: false + Value: true + - Alpha: 0.699999988 + Class: rviz/Map + Color Scheme: costmap + Draw Behind: false + Enabled: true + Name: Map + Topic: /move_base/local_costmap/costmap + Unreliable: false + Use Timestamp: false + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/PointCloud + Color: 255; 255; 255 + Color Transformer: Intensity + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 4096 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: PointCloud + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.100000001 + Style: Flat Squares + Topic: /obstacle_pc + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/LaserScan + Color: 85; 0; 255 + Color Transformer: FlatColor + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 999999 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: LaserScan + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.100000001 + Style: Flat Squares + Topic: /scan + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Default Light: true + Fixed Frame: map + Frame Rate: 30 + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + - Class: rviz/FocusCamera + - Class: rviz/Measure + - Class: rviz/SetInitialPose + Topic: /initialpose + - Class: rviz/SetGoal + Topic: /move_base_simple/goal + - Class: rviz/PublishPoint + Single click: true + Topic: /clicked_point + Value: true + Views: + Current: + Angle: 0 + Class: rviz/TopDownOrtho + Enable Stereo Rendering: + Stereo Eye Separation: 0.0599999987 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.00999999978 + Scale: 19.5390034 + Target Frame: + Value: TopDownOrtho (rviz) + X: 0 + Y: 0 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 1028 + Hide Left Dock: false + Hide Right Dock: false + QMainWindow State: 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 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 928 + X: 992 + Y: 24 diff --git a/simulators/dynamic_logistics_warehouse_h/worlds/warehouse.world b/simulators/dynamic_logistics_warehouse_h/worlds/warehouse.world new file mode 100755 index 0000000..18869d5 --- /dev/null +++ b/simulators/dynamic_logistics_warehouse_h/worlds/warehouse.world @@ -0,0 +1,11509 @@ + + + 0 0 -9.8 + + 0.001 + 1 + 1000 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://aws_robomaker_warehouse_ShelfF_01/meshes/aws_robomaker_warehouse_ShelfF_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ShelfF_01/meshes/aws_robomaker_warehouse_ShelfF_01_visual.DAE + + + + 1 + + + 0 0 0 0 -0 0 + 0 + 0 + 0 + + 1 + -5.79514 -0.956635 0 0 -0 0 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_visual.DAE + + + + 1 + + + 0 0 0 0 -0 0 + 0 + 0 + 0 + + 1 + 4.73156 0.57943 0 0 -0 0 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_visual.DAE + + + + 1 + + + 0 0 0 0 -0 0 + 0 + 0 + 0 + + 1 + 4.73156 -4.82705 0 0 -0 0 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_visual.DAE + + + + 1 + + + 0 0 0 0 -0 0 + 0 + 0 + 0 + + 1 + 4.73156 -8.6651 0 0 -0 0 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_visual.DAE + + + + 1 + + + 0 0 0 0 -0 0 + 0 + 0 + 0 + + 1 + 4.73156 -1.24267 0 0 -0 0 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_visual.DAE + + + + 1 + + + 0 0 0 0 -0 0 + 0 + 0 + 0 + + 1 + 4.73156 -3.03855 0 0 -0 0 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_visual.DAE + + + + 1 + + + 0 0 0 0 -0 0 + 0 + 0 + 0 + + 1 + 4.73156 -6.75054 0 0 -0 0 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://aws_robomaker_warehouse_Lamp_01/meshes/aws_robomaker_warehouse_Lamp_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_Lamp_01/meshes/aws_robomaker_warehouse_Lamp_01_visual.DAE + + + + 1 + + + 0 0 0 0 -0 0 + 0 + 0 + 0 + + 1 + 0 0 -4 0 -0 0 + + + + + 2 + 0 0 0 0 -0 0 + + 0.57 + 0 + 0 + 0.474 + 0 + 0.391 + + + 0 0 0 0 -0 0 + 0 + 0 + 1 + + + + model://aws_robomaker_warehouse_Bucket_01/meshes/aws_robomaker_warehouse_Bucket_01_visual.DAE + + + + 1 + + + + 0 + 10 + 0 0 0 0 -0 0 + + + model://aws_robomaker_warehouse_Bucket_01/meshes/aws_robomaker_warehouse_Bucket_01_collision.DAE + 1 1 1 + + + + + + 0.4 + 0.4 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + + 0 + + 1 + 0.433449 9.63171 0 0 0 -1.56316 + + + + + 2 + 0 0 0 0 -0 0 + + 0.57 + 0 + 0 + 0.474 + 0 + 0.391 + + + 0 0 0 0 -0 0 + 0 + 0 + 1 + + + + model://aws_robomaker_warehouse_Bucket_01/meshes/aws_robomaker_warehouse_Bucket_01_visual.DAE + + + + 1 + + + + 0 + 10 + 0 0 0 0 -0 0 + + + model://aws_robomaker_warehouse_Bucket_01/meshes/aws_robomaker_warehouse_Bucket_01_collision.DAE + 1 1 1 + + + + + + 0.4 + 0.4 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + + 0 + + 1 + -1.8321 -6.3752 0 0 0 -1.56316 + + + + + 2 + 0 0 0 0 -0 0 + + 0.57 + 0 + 0 + 0.474 + 0 + 0.391 + + + 0 0 0 0 -0 0 + 0 + 0 + 1 + + + + model://aws_robomaker_warehouse_Bucket_01/meshes/aws_robomaker_warehouse_Bucket_01_visual.DAE + + + + 1 + + + + 0 + 10 + 0 0 0 0 -0 0 + + + model://aws_robomaker_warehouse_Bucket_01/meshes/aws_robomaker_warehouse_Bucket_01_collision.DAE + 1 1 1 + + + + + + 0.4 + 0.4 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + + 0 + + 1 + 0.433449 8.59 0 0 0 -1.56316 + + + + + 2 + + 0.841 + 0 + 0 + 0.954 + 0 + 1.422 + + + + + + model://aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_visual.DAE + + + + 1 + + + 0 0 0 0 -0 0 + 0 + 0 + 0 + + 1 + 5.70814 8.61684 -0.017477 0 -0 0 + + + + + 2 + + 0.841 + 0 + 0 + 0.954 + 0 + 1.422 + + + + + + model://aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_visual.DAE + + + + 1 + + + 0 0 0 0 -0 0 + 0 + 0 + 0 + + 1 + 3.40864 8.61684 -0.017477 0 -0 0 + + + + + 2 + + 0.841 + 0 + 0 + 0.954 + 0 + 1.422 + + + + + + model://aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_visual.DAE + + + + 1 + + + 0 0 0 0 -0 0 + 0 + 0 + 0 + + 1 + -1.49129 5.22243 -0.017477 0 0 -1.58319 + + + + + 1 + + 1.558 + 0 + 0 + 1.821 + 0 + 1.892 + + + + + + model://aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_visual.DAE + + + + 1 + + + 0 0 0 0 -0 0 + 0 + 0 + 0 + + 1 + 3.32496 3.82245 -0.012064 0 -0 1.56387 + + + + + 1 + + 1.558 + 0 + 0 + 1.821 + 0 + 1.892 + + + + + + model://aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_visual.DAE + + + + 1 + + + 0 0 0 0 -0 0 + 0 + 0 + 0 + + 1 + 5.54171 3.81648 -0.015663 0 0 -1.58319 + + + + + 1 + + 1.558 + 0 + 0 + 1.821 + 0 + 1.892 + + + + + + model://aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_visual.DAE + + + + 1 + + + 0 0 0 0 -0 0 + 0 + 0 + 0 + + 1 + 5.38424 6.13715 0 0 -0 -3.13319 + + + + + 1 + + 1.558 + 0 + 0 + 1.821 + 0 + 1.892 + + + + + + model://aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_visual.DAE + + + + 1 + + + 0 0 0 0 -0 0 + 0 + 0 + 0 + + 1 + 3.236 6.13715 0 0 -0 -3.13319 + + + + + 1 + + 1.558 + 0 + 0 + 1.821 + 0 + 1.892 + + + + + + model://aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_visual.DAE + + + + 1 + + + 0 0 0 0 -0 0 + 0 + 0 + 0 + + 1 + -1.57368 2.30199 -0.015663 0 0 -3.13319 + + + + + 1 + + 1.558 + 0 + 0 + 1.821 + 0 + 1.892 + + + + + + model://aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_visual.DAE + + + + 1 + + + 0 0 0 0 -0 0 + 0 + 0 + 0 + + 1 + -1.2196 9.407 -0.015663 0 -0 1.56387 + + + + + 1 + + 1.558 + 0 + 0 + 1.821 + 0 + 1.892 + + + + + + model://aws_robomaker_warehouse_ClutteringD_01/meshes/aws_robomaker_warehouse_ClutteringD_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ClutteringD_01/meshes/aws_robomaker_warehouse_ClutteringD_01_visual.DAE + + + + 1 + + + 0 0 0 0 -0 0 + 0 + 0 + 0 + + 1 + -1.63468 -7.81181 -0.319559 0 -0 0 + + + + + 1 + + 0.2 + 0 + 0 + 0.308 + 0 + 0.24 + + + + + + model://aws_robomaker_warehouse_TrashCanC_01/meshes/aws_robomaker_warehouse_TrashCanC_01_collision.DAE + 1 1 1 + + + + + + 0.4 + 0.4 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_TrashCanC_01/meshes/aws_robomaker_warehouse_TrashCanC_01_visual.DAE + + + + 1 + + + 0 0 0 0 -0 0 + 0 + 0 + 0 + + 1 + -1.59244 7.71542 0 0 -0 0 + + + + + 2 + + 0.277 + 0 + 0 + 0.452 + 0 + 0.268 + + + + + + model://aws_robomaker_warehouse_PalletJackB_01/meshes/aws_robomaker_warehouse_PalletJackB_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_PalletJackB_01/meshes/aws_robomaker_warehouse_PalletJackB_01_visual.DAE + + + + 1 + + + 0 0 0 0 -0 0 + 0 + 0 + 0 + + 1 + -0.276098 -9.48194 0.023266 0 -0 0 + + + + 17.8694 22.9388 19.5315 0 1.0538 -1.61028 + orbit + perspective + + + 6e-06 2.3e-05 -4.2e-05 + + + 0.4 0.4 0.4 1 + 0.7 0.7 0.7 1 + 1 + + + + + EARTH_WGS84 + 0 + 0 + 0 + 0 + + + + + + 2 + 0 0 0 0 -0 0 + + 0.57 + 0 + 0 + 0.474 + 0 + 0.391 + + + 0 0 0 0 -0 0 + 0 + 0 + 1 + + + + model://aws_robomaker_warehouse_Bucket_01/meshes/aws_robomaker_warehouse_Bucket_01_visual.DAE + + + + 1 + + + + 0 + 10 + 0 0 0 0 -0 0 + + + model://aws_robomaker_warehouse_Bucket_01/meshes/aws_robomaker_warehouse_Bucket_01_collision.DAE + 1 1 1 + + + + + + 0.4 + 0.4 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + + 0 + + 1 + 0.141914 -1.40115 0 0 -0 0 + + + + + 1 + + 0.608 + 0 + 0 + 0.476 + 0 + 0.542 + + + + + + model://aws_robomaker_warehouse_DeskC_01/meshes/aws_robomaker_warehouse_DeskC_01_collision.DAE + 1 1 1 + + + + + + 0.3 + 0.3 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_DeskC_01/meshes/aws_robomaker_warehouse_DeskC_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + -0.141916 1.40114 0 0 -0 0 + + 0 + 1 + -1.60315 -2.32122 0 0 -0 0 + + + + + 2 + 0 0 0 0 -0 0 + + 0.57 + 0 + 0 + 0.474 + 0 + 0.391 + + + 0 0 0 0 -0 0 + 0 + 0 + 1 + + + + model://aws_robomaker_warehouse_Bucket_01/meshes/aws_robomaker_warehouse_Bucket_01_visual.DAE + + + + 1 + + + + 0 + 10 + 0 0 0 0 -0 0 + + + model://aws_robomaker_warehouse_Bucket_01/meshes/aws_robomaker_warehouse_Bucket_01_collision.DAE + 1 1 1 + + + + + + 0.4 + 0.4 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + + 0 + + 1 + 5.70576 16.4215 0 0 -0 0 + + + 3569 568000000 + 100 323637658 + 1691663550 366892984 + 100223 + + -1.60315 -2.32122 0 0 -0 0 + 1 1 1 + + -1.46124 -3.72237 0 0 -0 0 + 1 1 1 + + -1.46124 -3.72237 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -1.74507 -0.92008 0 0 -0 0 + 1 1 1 + + -1.74507 -0.92008 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + + 5.70576 16.4215 0 0 -0 0 + 1 1 1 + + 5.70576 16.4215 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 0.433449 9.63171 0 0 0 -1.56316 + 1 1 1 + + 0.433449 9.63171 0 0 0 -1.56316 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -1.8321 -6.3752 0 0 0 -1.56316 + 1 1 1 + + -1.8321 -6.3752 0 0 0 -1.56316 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 0.433449 8.59 0 0 0 -1.56316 + 1 1 1 + + 0.433449 8.59 0 0 0 -1.56316 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 5.32193 26.8473 0 0 -0 0 + 1 1 1 + + 5.32193 26.8473 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 19.569 42.6346 0 0 -0 0 + 1 1 1 + + 19.569 42.6346 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 18.3234 42.7208 0 0 -0 0 + 1 1 1 + + 18.3234 42.7208 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 17.0635 42.7283 0 0 -0 0 + 1 1 1 + + 17.0635 42.7283 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 19.5577 40.8293 0 0 -0 0 + 1 1 1 + + 19.5577 40.8293 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 18.2734 41.1462 0 0 -0 0 + 1 1 1 + + 18.2734 41.1462 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 16.7737 40.5695 0 0 -0 0 + 1 1 1 + + 16.7737 40.5695 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 18.7804 39.1318 0 0 -0 0 + 1 1 1 + + 18.7804 39.1318 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 16.9145 38.7931 0 0 -0 0 + 1 1 1 + + 16.9145 38.7931 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 19.0987 37.4201 0 0 -0 0 + 1 1 1 + + 19.0987 37.4201 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 25.9577 41.0196 0 0 -0 0 + 1 1 1 + + 25.9577 41.0196 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 5.63979 34.8748 0 0 -0 0 + 1 1 1 + + 5.63979 34.8748 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 25.5015 -7.22065 0 0 -0 0 + 1 1 1 + + 25.5015 -7.22065 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 27.3318 -8.09227 0 0 -0 0 + 1 1 1 + + 27.3318 -8.09227 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 3.6268 20.5877 0 0 -0 0 + 1 1 1 + + 3.6268 20.5877 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -1.09618 20.7984 0 0 -0 0 + 1 1 1 + + -1.09618 20.7984 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -2.13817 19.5115 0 0 -0 0 + 1 1 1 + + -2.13817 19.5115 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 0.423469 19.756 0 0 -0 0 + 1 1 1 + + 0.423469 19.756 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 12.6001 25.9609 0 0 -0 0 + 1 1 1 + + 12.6001 25.9609 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 13.1244 23.3177 0 0 -0 0 + 1 1 1 + + 13.1244 23.3177 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 12.1236 33.8765 0 0 -0 0 + 1 1 1 + + 12.1236 33.8765 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 4.53165 39.3479 0 0 -0 0 + 1 1 1 + + 4.53165 39.3479 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 3.62899 18.3956 0 0 -0 0 + 1 1 1 + + 3.62899 18.3956 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 5.70814 8.61684 -0.017477 0 -0 0 + 1 1 1 + + 5.70814 8.61684 -0.017477 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 3.40864 8.61684 -0.017477 0 -0 0 + 1 1 1 + + 3.40864 8.61684 -0.017477 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -1.49129 5.22243 -0.017477 0 0 -1.58319 + 1 1 1 + + -1.49129 5.22243 -0.017477 0 0 -1.58319 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 6.03172 14.3582 0 0 -0 0 + 1 1 1 + + 6.03172 14.3582 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 19.0653 45.7064 0 0 -0 0 + 1 1 1 + + 19.0653 45.7064 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 18.4398 26.9463 0 0 -0 0 + 1 1 1 + + 18.4398 26.9463 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 17.3599 -0.413513 0 0 -0 0 + 1 1 1 + + 17.3599 -0.413513 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 19.2928 -2.39539 0 0 -0 0 + 1 1 1 + + 19.2928 -2.39539 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 19.577 -5.73383 0 0 -0 0 + 1 1 1 + + 19.577 -5.73383 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 18.2768 -8.48817 0 0 -0 0 + 1 1 1 + + 18.2768 -8.48817 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 26.735 50.9817 0 0 -0 0 + 1 1 1 + + 26.735 50.9817 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 26.7207 48.4951 0 0 -0 0 + 1 1 1 + + 26.7207 48.4951 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 26.2657 43.5389 0 0 -0 0 + 1 1 1 + + 26.2657 43.5389 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 27.0194 26.9829 0 0 -0 0 + 1 1 1 + + 27.0194 26.9829 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -0.622283 34.3027 0 0 -0 0 + 1 1 1 + + -0.622283 34.3027 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 26.7292 22.9634 0 0 -0 0 + 1 1 1 + + 26.7292 22.9634 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 27.4595 29.2376 0 0 -0 0 + 1 1 1 + + 27.4595 29.2376 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 0.27204 46.622 0 0 -0 0 + 1 1 1 + + 0.27204 46.622 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 12.9705 27.7007 0 0 -0 0 + 1 1 1 + + 12.9705 27.7007 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 13.3751 40.2692 0 0 -0 0 + 1 1 1 + + 13.3751 40.2692 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 13.158 43.7439 0 0 -0 0 + 1 1 1 + + 13.158 43.7439 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 13.3077 9.45373 0 0 -0 0 + 1 1 1 + + 13.3077 9.45373 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 12.86 7.00015 0 0 -0 0 + 1 1 1 + + 12.86 7.00015 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 19.3513 48.1497 0 0 -0 0 + 1 1 1 + + 19.3513 48.1497 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -0.697852 37.4519 0 0 -0 0 + 1 1 1 + + -0.697852 37.4519 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 13.052 14.2242 0 0 -0 0 + 1 1 1 + + 13.052 14.2242 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 3.32496 3.82245 -0.012064 0 -0 1.56387 + 1 1 1 + + 3.32496 3.82245 -0.012064 0 -0 1.56387 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 5.54171 3.81648 -0.015663 0 0 -1.58319 + 1 1 1 + + 5.54171 3.81648 -0.015663 0 0 -1.58319 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 5.38424 6.13715 0 0 0 -3.13319 + 1 1 1 + + 5.38424 6.13715 0 0 -0 -3.13319 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 3.236 6.13715 0 0 0 -3.13319 + 1 1 1 + + 3.236 6.13715 0 0 -0 -3.13319 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -1.57368 2.30199 -0.015663 0 0 -3.13319 + 1 1 1 + + -1.57368 2.30199 -0.015663 0 0 -3.13319 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -1.2196 9.407 -0.015663 0 -0 1.56387 + 1 1 1 + + -1.2196 9.407 -0.015663 0 -0 1.56387 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 11.2817 40.8663 0 0 -0 0 + 1 1 1 + + 11.2817 40.8663 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 12.5185 51.2298 0 0 -0 0 + 1 1 1 + + 12.5185 51.2298 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 12.5381 4.26885 0 0 -0 0 + 1 1 1 + + 12.5381 4.26885 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 18.897 33.6641 0 0 -0 0 + 1 1 1 + + 18.897 33.6641 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 19.0494 29.9725 0 0 -0 0 + 1 1 1 + + 19.0494 29.9725 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 16.6865 4.92219 0 0 -0 0 + 1 1 1 + + 16.6865 4.92219 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 26.2755 17.983 0 0 -0 0 + 1 1 1 + + 26.2755 17.983 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 27.3097 13.3744 0 0 -0 0 + 1 1 1 + + 27.3097 13.3744 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 26.2078 -3.17715 0 0 -0 0 + 1 1 1 + + 26.2078 -3.17715 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -1.63468 -7.81181 -0.319559 0 -0 0 + 1 1 1 + + -1.63468 -7.81181 -0.319559 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 3.75927 15.6402 -0.319559 0 -0 0 + 1 1 1 + + 3.75927 15.6402 -0.319559 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 3.79574 13.9378 -0.319559 0 -0 0 + 1 1 1 + + 3.79574 13.9378 -0.319559 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 19.5791 1.04522 -0.319559 0 -0 0 + 1 1 1 + + 19.5791 1.04522 -0.319559 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 25.7986 14.976 -0.319559 0 -0 0 + 1 1 1 + + 25.7986 14.976 -0.319559 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 25.7484 12.7941 -0.319559 0 -0 0 + 1 1 1 + + 25.7484 12.7941 -0.319559 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 26.4124 46.52 -0.319559 0 -0 0 + 1 1 1 + + 26.4124 46.52 -0.319559 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 19.5668 -0.476464 -0.319559 0 -0 0 + 1 1 1 + + 19.5668 -0.476464 -0.319559 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 27.0966 31.0093 -0.319559 0 -0 0 + 1 1 1 + + 27.0966 31.0093 -0.319559 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 17.1951 25.1471 -0.319559 0 -0 0 + 1 1 1 + + 17.1951 25.1471 -0.319559 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 17.4881 29.6484 -0.319559 0 -0 0 + 1 1 1 + + 17.4881 29.6484 -0.319559 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -0.754194 41.4319 -0.319559 0 -0 0 + 1 1 1 + + -0.754194 41.4319 -0.319559 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -0.699945 44.5929 -0.319559 0 -0 0 + 1 1 1 + + -0.699945 44.5929 -0.319559 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 12.8719 2.10478 -0.319559 0 -0 0 + 1 1 1 + + 12.8719 2.10478 -0.319559 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 26.6012 20.1146 -0.319559 0 -0 0 + 1 1 1 + + 26.6012 20.1146 -0.319559 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 19.3018 25.0601 -0.5 0 -0 0 + 1 1 1 + + 19.3018 25.0601 -0.5 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 27.6843 -1.91409 -1.0 0 -0 0 + 1 1 1 + + 27.6843 -1.91409 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 7.57654 16.6993 0 0 -0 0 + 1 1 1 + + 7.57654 16.6993 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -0.629272 22.9652 0 0 -0 0 + 1 1 1 + + -0.629272 22.9652 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 13.3154 34.0588 0 0 -0 0 + 1 1 1 + + 13.3154 34.0588 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 18.3806 21.858 0 0 -0 0 + 1 1 1 + + 18.3806 21.858 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 25.0656 47.2669 0 0 -0 0 + 1 1 1 + + 25.0656 47.2669 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -0.10816 13.7255 0 0 -0 0 + 1 1 1 + + -0.10816 13.7255 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -1.97191 27.2819 0 0 -0 0 + 1 1 1 + + -1.97191 27.2819 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 0 0 -4 0 -0 0 + 1 1 1 + + 0 0 -4 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -2.63654 37.6155 0 0 -0 0 + 1 1 1 + + -2.63654 37.6155 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -2.35812 47.5506 0 0 -0 0 + 1 1 1 + + -2.35812 47.5506 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 4.55034 48.6475 0 0 -0 0 + 1 1 1 + + 4.55034 48.6475 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 6.94607 11.6812 0 0 -0 0 + 1 1 1 + + 6.94607 11.6812 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -0.276098 -9.48194 0.023266 0 -0 0 + 1 1 1 + + -0.276098 -9.48194 0.023266 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -0.781544 26.6893 0 0 -0 0 + 1 1 1 + + -0.781544 26.6893 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 5.19718 24.5925 0 0 -0 0 + 1 1 1 + + 5.19718 24.5925 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 12.2168 35.1041 0 0 -0 0 + 1 1 1 + + 12.2168 35.1041 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 26.4178 34.8553 0 0 -0 0 + 1 1 1 + + 26.4178 34.8553 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 27.0644 41.9414 0 0 -0 0 + 1 1 1 + + 27.0644 41.9414 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 26.5796 -1.00381 0 0 -0 0 + 1 1 1 + + 26.5796 -1.00381 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 27.3554 -6.53711 0 0 -0 0 + 1 1 1 + + 27.3554 -6.53711 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 5.90008 47.6153 0 0 -0 0 + 1 1 1 + + 5.90008 47.6153 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 5.05335 29.9841 0 0 -0 0 + 1 1 1 + + 5.05335 29.9841 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 4.73156 -1.24267 0 0 -0 0 + 1 1 1 + + 4.73156 -1.24267 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 4.73156 -3.03855 0 0 -0 0 + 1 1 1 + + 4.73156 -3.03855 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 4.73156 -6.75054 0 0 -0 0 + 1 1 1 + + 4.73156 -6.75054 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -0.851524 18.3394 0 0 -0 0 + 1 1 1 + + -0.851524 18.3394 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 12.1503 19.8895 0 0 -0 0 + 1 1 1 + + 12.1503 19.8895 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 12.2899 46.6706 0 0 -0 0 + 1 1 1 + + 12.2899 46.6706 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 13.3327 -1.35228 0 0 -0 0 + 1 1 1 + + 13.3327 -1.35228 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 17.841 20.5995 0 0 -0 0 + 1 1 1 + + 17.841 20.5995 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 18.1484 14.8286 0 0 -0 0 + 1 1 1 + + 18.1484 14.8286 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 25.7775 38.6928 0 0 -0 0 + 1 1 1 + + 25.7775 38.6928 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 26.2435 36.7034 0 0 -0 0 + 1 1 1 + + 26.2435 36.7034 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 27.2806 1.0311 0 0 -0 0 + 1 1 1 + + 27.2806 1.0311 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 5.46812 37.9706 0 0 -0 0 + 1 1 1 + + 5.46812 37.9706 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -0.818404 14.1026 0 0 -0 0 + 1 1 1 + + -0.818404 14.1026 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 4.73156 0.57943 0 0 -0 0 + 1 1 1 + + 4.73156 0.57943 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 4.73156 -4.82705 0 0 -0 0 + 1 1 1 + + 4.73156 -4.82705 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 4.73156 -8.6651 0 0 -0 0 + 1 1 1 + + 4.73156 -8.6651 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 4.68679 22.0652 0 0 -0 0 + 1 1 1 + + 4.68679 22.0652 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 27.1086 5.51766 0.033086 0 -0 0 + 1 1 1 + + 27.1086 5.51766 0.033086 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 26.8034 4.14144 0 0 -0 0 + 1 1 1 + + 26.8034 4.14144 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 5.10444 44.4736 0 0 -0 0 + 1 1 1 + + 5.10444 44.4736 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -0.827656 49.4129 0 0 -0 0 + 1 1 1 + + -0.827656 49.4129 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 12.0536 18.5206 0 0 -0 0 + 1 1 1 + + 12.0536 18.5206 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 12.18 20.3383 0 0 -0 0 + 1 1 1 + + 12.18 20.3383 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 13.2287 -4.69103 0 0 -0 0 + 1 1 1 + + 13.2287 -4.69103 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 17.4838 18.1535 0 0 -0 0 + 1 1 1 + + 17.4838 18.1535 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 26.0327 34.3649 0 0 -0 0 + 1 1 1 + + 26.0327 34.3649 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 26.6188 9.9624 0 0 -0 0 + 1 1 1 + + 26.6188 9.9624 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -5.8506 19.9859 0 0 -0 0 + 1 1 1 + + -5.8506 19.9859 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -5.53864 41.5726 0 0 -0 0 + 1 1 1 + + -5.53864 41.5726 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -5.79514 -0.956635 0 0 -0 0 + 1 1 1 + + -5.79514 -0.956635 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 33.4849 42.901 0 0 -0 0 + 1 1 1 + + 33.4849 42.901 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 32.8705 23.2354 0 0 -0 0 + 1 1 1 + + 32.8705 23.2354 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 32.9964 1.12153 0 0 -0 0 + 1 1 1 + + 32.9964 1.12153 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 6.07509 20.3238 0 0 -0 0 + 1 1 1 + + 6.07509 20.3238 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 12.5113 48.2728 0 0 -0 0 + 1 1 1 + + 12.5113 48.2728 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -1.59244 7.71542 0 0 -0 0 + 1 1 1 + + -1.59244 7.71542 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -0.940084 16.4807 0 0 -0 0 + 1 1 1 + + -0.940084 16.4807 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -0.259089 25.3092 0 0 -0 0 + 1 1 1 + + -0.259089 25.3092 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -0.727374 39.1622 0 0 -0 0 + 1 1 1 + + -0.727374 39.1622 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 12.3802 37.7552 0 0 -0 0 + 1 1 1 + + 12.3802 37.7552 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 17.2123 36.4518 0 0 -0 0 + 1 1 1 + + 17.2123 36.4518 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 17.9551 8.90379 0 0 -0 0 + 1 1 1 + + 17.9551 8.90379 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 27.7469 40.8969 0 0 -0 0 + 1 1 1 + + 27.7469 40.8969 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 26.6799 2.02665 0 0 -0 0 + 1 1 1 + + 26.6799 2.02665 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 4.53166 20.7695 0 0 -0 0 + 1 1 1 + + 4.53166 20.7695 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 21.6259 5.20915 4e-05 0 -1.2e-05 0 + 1 1 1 + + 21.6259 5.20915 4e-05 1.57081 -0 -1.5708 + -0 -0 1e-06 -0 -0 -0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 14 20.85 0 0 -0 0 + 1 1 1 + + 14 -10.5 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + -7 20.85 0 0 -0 1.5708 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + 35 20.85 0 0 -0 1.5708 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + 14 52.2 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 10.387 20.7515 10 0 -0 0 + + + + + + 2 + 0 0 0 0 -0 0 + + 0.57 + 0 + 0 + 0.474 + 0 + 0.391 + + + 0 0 0 0 -0 0 + 0 + 0 + 1 + + + + model://aws_robomaker_warehouse_Bucket_01/meshes/aws_robomaker_warehouse_Bucket_01_visual.DAE + + + + 1 + + + + 0 + 10 + 0 0 0 0 -0 0 + + + model://aws_robomaker_warehouse_Bucket_01/meshes/aws_robomaker_warehouse_Bucket_01_collision.DAE + 1 1 1 + + + + + + 0.4 + 0.4 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + + 0 + + 1 + 5.32193 26.8473 0 0 -0 0 + + + + + 2 + 0 0 0 0 -0 0 + + 0.57 + 0 + 0 + 0.474 + 0 + 0.391 + + + 0 0 0 0 -0 0 + 0 + 0 + 1 + + + + model://aws_robomaker_warehouse_Bucket_01/meshes/aws_robomaker_warehouse_Bucket_01_visual.DAE + + + + 1 + + + + 0 + 10 + 0 0 0 0 -0 0 + + + model://aws_robomaker_warehouse_Bucket_01/meshes/aws_robomaker_warehouse_Bucket_01_collision.DAE + 1 1 1 + + + + + + 0.4 + 0.4 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + + 0 + + 1 + 5.63979 34.8748 0 0 -0 0 + + + + + 2 + + 0.841 + 0 + 0 + 0.954 + 0 + 1.422 + + + + + + model://aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 4.53165 39.3479 0 0 -0 0 + + + + + 2 + + 0.277 + 0 + 0 + 0.452 + 0 + 0.268 + + + + + + model://aws_robomaker_warehouse_PalletJackB_01/meshes/aws_robomaker_warehouse_PalletJackB_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_PalletJackB_01/meshes/aws_robomaker_warehouse_PalletJackB_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 4.55034 48.6475 0 0 -0 0 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 5.90008 47.6153 0 0 -0 0 + + + + + 1 + + 0.2 + 0 + 0 + 0.308 + 0 + 0.24 + + + + + + model://aws_robomaker_warehouse_TrashCanC_01/meshes/aws_robomaker_warehouse_TrashCanC_01_collision.DAE + 1 1 1 + + + + + + 0.4 + 0.4 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_TrashCanC_01/meshes/aws_robomaker_warehouse_TrashCanC_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 6.07509 20.3238 0 0 -0 0 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 5.05335 29.9841 0 0 -0 0 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 5.46812 37.9706 0 0 -0 0 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://aws_robomaker_warehouse_ShelfF_01/meshes/aws_robomaker_warehouse_ShelfF_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ShelfF_01/meshes/aws_robomaker_warehouse_ShelfF_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + -5.8506 19.9859 0 0 -0 0 + + + + + 1 + + 0.2 + 0 + 0 + 0.308 + 0 + 0.24 + + + + + + model://aws_robomaker_warehouse_TrashCanC_01/meshes/aws_robomaker_warehouse_TrashCanC_01_collision.DAE + 1 1 1 + + + + + + 0.4 + 0.4 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_TrashCanC_01/meshes/aws_robomaker_warehouse_TrashCanC_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 12.5113 48.2728 0 0 -0 0 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://aws_robomaker_warehouse_ShelfF_01/meshes/aws_robomaker_warehouse_ShelfF_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ShelfF_01/meshes/aws_robomaker_warehouse_ShelfF_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + -5.53864 41.5726 0 0 -0 0 + + + + + 2 + + 0.841 + 0 + 0 + 0.954 + 0 + 1.422 + + + + + + model://aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 3.62899 18.3956 0 0 -0 0 + + + + + 1 + + 0.608 + 0 + 0 + 0.476 + 0 + 0.542 + + + + + + model://aws_robomaker_warehouse_DeskC_01/meshes/aws_robomaker_warehouse_DeskC_01_collision.DAE + 1 1 1 + + + + + + 0.3 + 0.3 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_DeskC_01/meshes/aws_robomaker_warehouse_DeskC_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 7.57654 16.6993 0 0 -0 0 + + + + + 2 + + 0.841 + 0 + 0 + 0.954 + 0 + 1.422 + + + + + + model://aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 6.03172 14.3582 0 0 -0 0 + + + + + 2 + 0 0 0 0 -0 0 + + 0.57 + 0 + 0 + 0.474 + 0 + 0.391 + + + 0 0 0 0 -0 0 + 0 + 0 + 1 + + + + model://aws_robomaker_warehouse_Bucket_01/meshes/aws_robomaker_warehouse_Bucket_01_visual.DAE + + + + 1 + + + + 0 + 10 + 0 0 0 0 -0 0 + + + model://aws_robomaker_warehouse_Bucket_01/meshes/aws_robomaker_warehouse_Bucket_01_collision.DAE + 1 1 1 + + + + + + 0.4 + 0.4 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + + 0 + + 1 + 3.6268 20.5877 0 0 -0 0 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + -0.818404 14.1026 0 0 -0 0 + + + + + 2 + + 0.277 + 0 + 0 + 0.452 + 0 + 0.268 + + + + + + model://aws_robomaker_warehouse_PalletJackB_01/meshes/aws_robomaker_warehouse_PalletJackB_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_PalletJackB_01/meshes/aws_robomaker_warehouse_PalletJackB_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 6.94607 11.6812 0 0 -0 0 + + + + + 1 + + 0.2 + 0 + 0 + 0.308 + 0 + 0.24 + + + + + + model://aws_robomaker_warehouse_TrashCanC_01/meshes/aws_robomaker_warehouse_TrashCanC_01_collision.DAE + 1 1 1 + + + + + + 0.4 + 0.4 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_TrashCanC_01/meshes/aws_robomaker_warehouse_TrashCanC_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + -0.940084 16.4807 0 0 -0 0 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + -0.851524 18.3394 0 0 -0 0 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 4.68679 22.0652 0 0 -0 0 + + + + + 2 + 0 0 0 0 -0 0 + + 0.57 + 0 + 0 + 0.474 + 0 + 0.391 + + + 0 0 0 0 -0 0 + 0 + 0 + 1 + + + + model://aws_robomaker_warehouse_Bucket_01/meshes/aws_robomaker_warehouse_Bucket_01_visual.DAE + + + + 1 + + + + 0 + 10 + 0 0 0 0 -0 0 + + + model://aws_robomaker_warehouse_Bucket_01/meshes/aws_robomaker_warehouse_Bucket_01_collision.DAE + 1 1 1 + + + + + + 0.4 + 0.4 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + + 0 + + 1 + -1.09618 20.7984 0 0 -0 0 + + + + + 2 + 0 0 0 0 -0 0 + + 0.57 + 0 + 0 + 0.474 + 0 + 0.391 + + + 0 0 0 0 -0 0 + 0 + 0 + 1 + + + + model://aws_robomaker_warehouse_Bucket_01/meshes/aws_robomaker_warehouse_Bucket_01_visual.DAE + + + + 1 + + + + 0 + 10 + 0 0 0 0 -0 0 + + + model://aws_robomaker_warehouse_Bucket_01/meshes/aws_robomaker_warehouse_Bucket_01_collision.DAE + 1 1 1 + + + + + + 0.4 + 0.4 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + + 0 + + 1 + -2.13817 19.5115 0 0 -0 0 + + + + + 2 + 0 0 0 0 -0 0 + + 0.57 + 0 + 0 + 0.474 + 0 + 0.391 + + + 0 0 0 0 -0 0 + 0 + 0 + 1 + + + + model://aws_robomaker_warehouse_Bucket_01/meshes/aws_robomaker_warehouse_Bucket_01_visual.DAE + + + + 1 + + + + 0 + 10 + 0 0 0 0 -0 0 + + + model://aws_robomaker_warehouse_Bucket_01/meshes/aws_robomaker_warehouse_Bucket_01_collision.DAE + 1 1 1 + + + + + + 0.4 + 0.4 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + + 0 + + 1 + 0.423469 19.756 0 0 -0 0 + + + + + 1 + + 0.608 + 0 + 0 + 0.476 + 0 + 0.542 + + + + + + model://aws_robomaker_warehouse_DeskC_01/meshes/aws_robomaker_warehouse_DeskC_01_collision.DAE + 1 1 1 + + + + + + 0.3 + 0.3 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_DeskC_01/meshes/aws_robomaker_warehouse_DeskC_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + -0.629272 22.9652 0 0 -0 0 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://aws_robomaker_warehouse_Lamp_01/meshes/aws_robomaker_warehouse_Lamp_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_Lamp_01/meshes/aws_robomaker_warehouse_Lamp_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + -0.10816 13.7255 0 0 -0 0 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://aws_robomaker_warehouse_Lamp_01/meshes/aws_robomaker_warehouse_Lamp_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_Lamp_01/meshes/aws_robomaker_warehouse_Lamp_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + -1.97191 27.2819 0 0 -0 0 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://aws_robomaker_warehouse_Lamp_01/meshes/aws_robomaker_warehouse_Lamp_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_Lamp_01/meshes/aws_robomaker_warehouse_Lamp_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + -2.63654 37.6155 0 0 -0 0 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://aws_robomaker_warehouse_Lamp_01/meshes/aws_robomaker_warehouse_Lamp_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_Lamp_01/meshes/aws_robomaker_warehouse_Lamp_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + -2.35812 47.5506 0 0 -0 0 + + + + + 1 + + 0.2 + 0 + 0 + 0.308 + 0 + 0.24 + + + + + + model://aws_robomaker_warehouse_TrashCanC_01/meshes/aws_robomaker_warehouse_TrashCanC_01_collision.DAE + 1 1 1 + + + + + + 0.4 + 0.4 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_TrashCanC_01/meshes/aws_robomaker_warehouse_TrashCanC_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + -0.259089 25.3092 0 0 -0 0 + + + + + 2 + + 0.277 + 0 + 0 + 0.452 + 0 + 0.268 + + + + + + model://aws_robomaker_warehouse_PalletJackB_01/meshes/aws_robomaker_warehouse_PalletJackB_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_PalletJackB_01/meshes/aws_robomaker_warehouse_PalletJackB_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + -0.781544 26.6893 0 0 -0 0 + + + + + 2 + + 0.841 + 0 + 0 + 0.954 + 0 + 1.422 + + + + + + model://aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + -0.622283 34.3027 0 0 -0 0 + + + + + 1 + + 1.558 + 0 + 0 + 1.821 + 0 + 1.892 + + + + + + model://aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + -0.697852 37.4519 0 0 -0 0 + + + + + 2 + + 0.841 + 0 + 0 + 0.954 + 0 + 1.422 + + + + + + model://aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 0.27204 46.622 0 0 -0 0 + + + + + 1 + + 0.2 + 0 + 0 + 0.308 + 0 + 0.24 + + + + + + model://aws_robomaker_warehouse_TrashCanC_01/meshes/aws_robomaker_warehouse_TrashCanC_01_collision.DAE + 1 1 1 + + + + + + 0.4 + 0.4 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_TrashCanC_01/meshes/aws_robomaker_warehouse_TrashCanC_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + -0.727374 39.1622 0 0 -0 0 + + + + + 2 + + 0.277 + 0 + 0 + 0.452 + 0 + 0.268 + + + + + + model://aws_robomaker_warehouse_PalletJackB_01/meshes/aws_robomaker_warehouse_PalletJackB_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_PalletJackB_01/meshes/aws_robomaker_warehouse_PalletJackB_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 5.19718 24.5925 0 0 -0 0 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 5.10444 44.4736 0 0 -0 0 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + -0.827656 49.4129 0 0 -0 0 + + + + + 2 + 0 0 0 0 -0 0 + + 0.57 + 0 + 0 + 0.474 + 0 + 0.391 + + + 0 0 0 0 -0 0 + 0 + 0 + 1 + + + + model://aws_robomaker_warehouse_Bucket_01/meshes/aws_robomaker_warehouse_Bucket_01_visual.DAE + + + + 1 + + + + 0 + 10 + 0 0 0 0 -0 0 + + + model://aws_robomaker_warehouse_Bucket_01/meshes/aws_robomaker_warehouse_Bucket_01_collision.DAE + 1 1 1 + + + + + + 0.4 + 0.4 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + + 0 + + 1 + 12.6001 25.9609 0 0 -0 0 + + + + + 2 + + 0.841 + 0 + 0 + 0.954 + 0 + 1.422 + + + + + + model://aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 12.9705 27.7007 0 0 -0 0 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 12.1503 19.8895 0 0 -0 0 + + + + + 1 + + 1.558 + 0 + 0 + 1.821 + 0 + 1.892 + + + + + + model://aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 13.052 14.2242 0 0 -0 0 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 12.845 17.1513 0 0 -0 0 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 12.7191 21.3646 0 0 -0 0 + + + + + 2 + 0 0 0 0 -0 0 + + 0.57 + 0 + 0 + 0.474 + 0 + 0.391 + + + 0 0 0 0 -0 0 + 0 + 0 + 1 + + + + model://aws_robomaker_warehouse_Bucket_01/meshes/aws_robomaker_warehouse_Bucket_01_visual.DAE + + + + 1 + + + + 0 + 10 + 0 0 0 0 -0 0 + + + model://aws_robomaker_warehouse_Bucket_01/meshes/aws_robomaker_warehouse_Bucket_01_collision.DAE + 1 1 1 + + + + + + 0.4 + 0.4 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + + 0 + + 1 + 13.1244 23.3177 0 0 -0 0 + + + + + 1 + + 0.608 + 0 + 0 + 0.476 + 0 + 0.542 + + + + + + model://aws_robomaker_warehouse_DeskC_01/meshes/aws_robomaker_warehouse_DeskC_01_collision.DAE + 1 1 1 + + + + + + 0.3 + 0.3 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_DeskC_01/meshes/aws_robomaker_warehouse_DeskC_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 13.3154 34.0588 0 0 -0 0 + + + + + 1 + + 0.2 + 0 + 0 + 0.308 + 0 + 0.24 + + + + + + model://aws_robomaker_warehouse_TrashCanC_01/meshes/aws_robomaker_warehouse_TrashCanC_01_collision.DAE + 1 1 1 + + + + + + 0.4 + 0.4 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_TrashCanC_01/meshes/aws_robomaker_warehouse_TrashCanC_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 12.3802 37.7552 0 0 -0 0 + + + + + 2 + + 0.277 + 0 + 0 + 0.452 + 0 + 0.268 + + + + + + model://aws_robomaker_warehouse_PalletJackB_01/meshes/aws_robomaker_warehouse_PalletJackB_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_PalletJackB_01/meshes/aws_robomaker_warehouse_PalletJackB_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 12.2168 35.1041 0 0 -0 0 + + + + + 2 + + 0.841 + 0 + 0 + 0.954 + 0 + 1.422 + + + + + + model://aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 13.3751 40.2692 0 0 -0 0 + + + + + 2 + + 0.841 + 0 + 0 + 0.954 + 0 + 1.422 + + + + + + model://aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 13.158 43.7439 0 0 -0 0 + + + + + 1 + + 1.558 + 0 + 0 + 1.821 + 0 + 1.892 + + + + + + model://aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 11.2817 40.8663 0 0 -0 0 + + + + + 1 + + 1.558 + 0 + 0 + 1.821 + 0 + 1.892 + + + + + + model://aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 12.5185 51.2298 0 0 -0 0 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 12.2899 46.6706 0 0 -0 0 + + + + + 2 + 0 0 0 0 -0 0 + + 0.57 + 0 + 0 + 0.474 + 0 + 0.391 + + + 0 0 0 0 -0 0 + 0 + 0 + 1 + + + + model://aws_robomaker_warehouse_Bucket_01/meshes/aws_robomaker_warehouse_Bucket_01_visual.DAE + + + + 1 + + + + 0 + 10 + 0 0 0 0 -0 0 + + + model://aws_robomaker_warehouse_Bucket_01/meshes/aws_robomaker_warehouse_Bucket_01_collision.DAE + 1 1 1 + + + + + + 0.4 + 0.4 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + + 0 + + 1 + 10.9157 33.2489 0 0 -0 0 + + + + + 2 + + 0.841 + 0 + 0 + 0.954 + 0 + 1.422 + + + + + + model://aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 13.3077 9.45373 0 0 -0 0 + + + + + 2 + + 0.841 + 0 + 0 + 0.954 + 0 + 1.422 + + + + + + model://aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 12.86 7.00015 0 0 -0 0 + + + + + 1 + + 1.558 + 0 + 0 + 1.821 + 0 + 1.892 + + + + + + model://aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 12.5381 4.26885 0 0 -0 0 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 13.3327 -1.35228 0 0 -0 0 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 13.2287 -4.69103 0 0 -0 0 + + + + + 2 + + 0.841 + 0 + 0 + 0.954 + 0 + 1.422 + + + + + + model://aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 19.3513 48.1497 0 0 -0 0 + + + + + 2 + + 0.841 + 0 + 0 + 0.954 + 0 + 1.422 + + + + + + model://aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 19.0653 45.7064 0 0 -0 0 + + + + + 2 + 0 0 0 0 -0 0 + + 0.57 + 0 + 0 + 0.474 + 0 + 0.391 + + + 0 0 0 0 -0 0 + 0 + 0 + 1 + + + + model://aws_robomaker_warehouse_Bucket_01/meshes/aws_robomaker_warehouse_Bucket_01_visual.DAE + + + + 1 + + + + 0 + 10 + 0 0 0 0 -0 0 + + + model://aws_robomaker_warehouse_Bucket_01/meshes/aws_robomaker_warehouse_Bucket_01_collision.DAE + 1 1 1 + + + + + + 0.4 + 0.4 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + + 0 + + 1 + 19.569 42.6346 0 0 -0 0 + + + + + 2 + 0 0 0 0 -0 0 + + 0.57 + 0 + 0 + 0.474 + 0 + 0.391 + + + 0 0 0 0 -0 0 + 0 + 0 + 1 + + + + model://aws_robomaker_warehouse_Bucket_01/meshes/aws_robomaker_warehouse_Bucket_01_visual.DAE + + + + 1 + + + + 0 + 10 + 0 0 0 0 -0 0 + + + model://aws_robomaker_warehouse_Bucket_01/meshes/aws_robomaker_warehouse_Bucket_01_collision.DAE + 1 1 1 + + + + + + 0.4 + 0.4 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + + 0 + + 1 + 18.3234 42.7208 0 0 -0 0 + + + + + 2 + 0 0 0 0 -0 0 + + 0.57 + 0 + 0 + 0.474 + 0 + 0.391 + + + 0 0 0 0 -0 0 + 0 + 0 + 1 + + + + model://aws_robomaker_warehouse_Bucket_01/meshes/aws_robomaker_warehouse_Bucket_01_visual.DAE + + + + 1 + + + + 0 + 10 + 0 0 0 0 -0 0 + + + model://aws_robomaker_warehouse_Bucket_01/meshes/aws_robomaker_warehouse_Bucket_01_collision.DAE + 1 1 1 + + + + + + 0.4 + 0.4 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + + 0 + + 1 + 17.0635 42.7283 0 0 -0 0 + + + + + 2 + 0 0 0 0 -0 0 + + 0.57 + 0 + 0 + 0.474 + 0 + 0.391 + + + 0 0 0 0 -0 0 + 0 + 0 + 1 + + + + model://aws_robomaker_warehouse_Bucket_01/meshes/aws_robomaker_warehouse_Bucket_01_visual.DAE + + + + 1 + + + + 0 + 10 + 0 0 0 0 -0 0 + + + model://aws_robomaker_warehouse_Bucket_01/meshes/aws_robomaker_warehouse_Bucket_01_collision.DAE + 1 1 1 + + + + + + 0.4 + 0.4 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + + 0 + + 1 + 19.5577 40.8293 0 0 -0 0 + + + + + 2 + 0 0 0 0 -0 0 + + 0.57 + 0 + 0 + 0.474 + 0 + 0.391 + + + 0 0 0 0 -0 0 + 0 + 0 + 1 + + + + model://aws_robomaker_warehouse_Bucket_01/meshes/aws_robomaker_warehouse_Bucket_01_visual.DAE + + + + 1 + + + + 0 + 10 + 0 0 0 0 -0 0 + + + model://aws_robomaker_warehouse_Bucket_01/meshes/aws_robomaker_warehouse_Bucket_01_collision.DAE + 1 1 1 + + + + + + 0.4 + 0.4 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + + 0 + + 1 + 18.2734 41.1462 0 0 -0 0 + + + + + 2 + 0 0 0 0 -0 0 + + 0.57 + 0 + 0 + 0.474 + 0 + 0.391 + + + 0 0 0 0 -0 0 + 0 + 0 + 1 + + + + model://aws_robomaker_warehouse_Bucket_01/meshes/aws_robomaker_warehouse_Bucket_01_visual.DAE + + + + 1 + + + + 0 + 10 + 0 0 0 0 -0 0 + + + model://aws_robomaker_warehouse_Bucket_01/meshes/aws_robomaker_warehouse_Bucket_01_collision.DAE + 1 1 1 + + + + + + 0.4 + 0.4 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + + 0 + + 1 + 16.7737 40.5695 0 0 -0 0 + + + + + 2 + 0 0 0 0 -0 0 + + 0.57 + 0 + 0 + 0.474 + 0 + 0.391 + + + 0 0 0 0 -0 0 + 0 + 0 + 1 + + + + model://aws_robomaker_warehouse_Bucket_01/meshes/aws_robomaker_warehouse_Bucket_01_visual.DAE + + + + 1 + + + + 0 + 10 + 0 0 0 0 -0 0 + + + model://aws_robomaker_warehouse_Bucket_01/meshes/aws_robomaker_warehouse_Bucket_01_collision.DAE + 1 1 1 + + + + + + 0.4 + 0.4 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + + 0 + + 1 + 18.7804 39.1318 0 0 -0 0 + + + + + 2 + 0 0 0 0 -0 0 + + 0.57 + 0 + 0 + 0.474 + 0 + 0.391 + + + 0 0 0 0 -0 0 + 0 + 0 + 1 + + + + model://aws_robomaker_warehouse_Bucket_01/meshes/aws_robomaker_warehouse_Bucket_01_visual.DAE + + + + 1 + + + + 0 + 10 + 0 0 0 0 -0 0 + + + model://aws_robomaker_warehouse_Bucket_01/meshes/aws_robomaker_warehouse_Bucket_01_collision.DAE + 1 1 1 + + + + + + 0.4 + 0.4 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + + 0 + + 1 + 16.9145 38.7931 0 0 -0 0 + + + + + 2 + 0 0 0 0 -0 0 + + 0.57 + 0 + 0 + 0.474 + 0 + 0.391 + + + 0 0 0 0 -0 0 + 0 + 0 + 1 + + + + model://aws_robomaker_warehouse_Bucket_01/meshes/aws_robomaker_warehouse_Bucket_01_visual.DAE + + + + 1 + + + + 0 + 10 + 0 0 0 0 -0 0 + + + model://aws_robomaker_warehouse_Bucket_01/meshes/aws_robomaker_warehouse_Bucket_01_collision.DAE + 1 1 1 + + + + + + 0.4 + 0.4 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + + 0 + + 1 + 19.0987 37.4201 0 0 -0 0 + + + + + 1 + + 0.2 + 0 + 0 + 0.308 + 0 + 0.24 + + + + + + model://aws_robomaker_warehouse_TrashCanC_01/meshes/aws_robomaker_warehouse_TrashCanC_01_collision.DAE + 1 1 1 + + + + + + 0.4 + 0.4 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_TrashCanC_01/meshes/aws_robomaker_warehouse_TrashCanC_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 17.2123 36.4518 0 0 -0 0 + + + + + 1 + + 1.558 + 0 + 0 + 1.821 + 0 + 1.892 + + + + + + model://aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 18.897 33.6641 0 0 -0 0 + + + + + 1 + + 1.558 + 0 + 0 + 1.821 + 0 + 1.892 + + + + + + model://aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 19.0494 29.9725 0 0 -0 0 + + + + + 2 + + 0.841 + 0 + 0 + 0.954 + 0 + 1.422 + + + + + + model://aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 18.4398 26.9463 0 0 -0 0 + + + + + 1 + + 1.558 + 0 + 0 + 1.821 + 0 + 1.892 + + + + + + model://aws_robomaker_warehouse_ClutteringD_01/meshes/aws_robomaker_warehouse_ClutteringD_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ClutteringD_01/meshes/aws_robomaker_warehouse_ClutteringD_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 19.3018 25.0601 0 0 -0 0 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 17.841 20.5995 0 0 -0 0 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 17.4838 18.1535 0 0 -0 0 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 18.1484 14.8286 0 0 -0 0 + + + + + 1 + + 0.2 + 0 + 0 + 0.308 + 0 + 0.24 + + + + + + model://aws_robomaker_warehouse_TrashCanC_01/meshes/aws_robomaker_warehouse_TrashCanC_01_collision.DAE + 1 1 1 + + + + + + 0.4 + 0.4 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_TrashCanC_01/meshes/aws_robomaker_warehouse_TrashCanC_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 17.9551 8.90379 0 0 -0 0 + + + + + 1 + + 0.608 + 0 + 0 + 0.476 + 0 + 0.542 + + + + + + model://aws_robomaker_warehouse_DeskC_01/meshes/aws_robomaker_warehouse_DeskC_01_collision.DAE + 1 1 1 + + + + + + 0.3 + 0.3 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_DeskC_01/meshes/aws_robomaker_warehouse_DeskC_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 18.3806 21.858 0 0 -0 0 + + + + + 1 + + 1.558 + 0 + 0 + 1.821 + 0 + 1.892 + + + + + + model://aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 16.6865 4.92219 0 0 -0 0 + + + + + 2 + + 0.841 + 0 + 0 + 0.954 + 0 + 1.422 + + + + + + model://aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 17.3599 -0.413513 0 0 -0 0 + + + + + 2 + + 0.841 + 0 + 0 + 0.954 + 0 + 1.422 + + + + + + model://aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 19.2928 -2.39539 0 0 -0 0 + + + + + 2 + + 0.841 + 0 + 0 + 0.954 + 0 + 1.422 + + + + + + model://aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 19.577 -5.73383 0 0 -0 0 + + + + + 2 + + 0.841 + 0 + 0 + 0.954 + 0 + 1.422 + + + + + + model://aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 18.2768 -8.48817 0 0 -0 0 + + + + + 2 + + 0.841 + 0 + 0 + 0.954 + 0 + 1.422 + + + + + + model://aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 26.735 50.9817 0 0 -0 0 + + + + + 2 + + 0.841 + 0 + 0 + 0.954 + 0 + 1.422 + + + + + + model://aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 26.7207 48.4951 0 0 -0 0 + + + + + 2 + + 0.841 + 0 + 0 + 0.954 + 0 + 1.422 + + + + + + model://aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 26.2657 43.5389 0 0 -0 0 + + + + + 1 + + 0.608 + 0 + 0 + 0.476 + 0 + 0.542 + + + + + + model://aws_robomaker_warehouse_DeskC_01/meshes/aws_robomaker_warehouse_DeskC_01_collision.DAE + 1 1 1 + + + + + + 0.3 + 0.3 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_DeskC_01/meshes/aws_robomaker_warehouse_DeskC_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 25.0656 47.2669 0 0 -0 0 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://aws_robomaker_warehouse_ShelfF_01/meshes/aws_robomaker_warehouse_ShelfF_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ShelfF_01/meshes/aws_robomaker_warehouse_ShelfF_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 33.4849 42.901 0 0 -0 0 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://aws_robomaker_warehouse_ShelfF_01/meshes/aws_robomaker_warehouse_ShelfF_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ShelfF_01/meshes/aws_robomaker_warehouse_ShelfF_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 32.8705 23.2354 0 0 -0 0 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://aws_robomaker_warehouse_ShelfF_01/meshes/aws_robomaker_warehouse_ShelfF_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ShelfF_01/meshes/aws_robomaker_warehouse_ShelfF_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 32.9964 1.12153 0 0 -0 0 + + + + + 2 + 0 0 0 0 -0 0 + + 0.57 + 0 + 0 + 0.474 + 0 + 0.391 + + + 0 0 0 0 -0 0 + 0 + 0 + 1 + + + + model://aws_robomaker_warehouse_Bucket_01/meshes/aws_robomaker_warehouse_Bucket_01_visual.DAE + + + + 1 + + + + 0 + 10 + 0 0 0 0 -0 0 + + + model://aws_robomaker_warehouse_Bucket_01/meshes/aws_robomaker_warehouse_Bucket_01_collision.DAE + 1 1 1 + + + + + + 0.4 + 0.4 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + + 0 + + 1 + 25.9577 41.0196 0 0 -0 0 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 25.7775 38.6928 0 0 -0 0 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 26.2435 36.7034 0 0 -0 0 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 26.0327 34.3649 0 0 -0 0 + + + + + 2 + + 0.277 + 0 + 0 + 0.452 + 0 + 0.268 + + + + + + model://aws_robomaker_warehouse_PalletJackB_01/meshes/aws_robomaker_warehouse_PalletJackB_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_PalletJackB_01/meshes/aws_robomaker_warehouse_PalletJackB_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 26.4178 34.8553 0 0 -0 0 + + + + + 2 + + 0.277 + 0 + 0 + 0.452 + 0 + 0.268 + + + + + + model://aws_robomaker_warehouse_PalletJackB_01/meshes/aws_robomaker_warehouse_PalletJackB_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_PalletJackB_01/meshes/aws_robomaker_warehouse_PalletJackB_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 27.0644 41.9414 0 0 -0 0 + + + + + 1 + + 0.2 + 0 + 0 + 0.308 + 0 + 0.24 + + + + + + model://aws_robomaker_warehouse_TrashCanC_01/meshes/aws_robomaker_warehouse_TrashCanC_01_collision.DAE + 1 1 1 + + + + + + 0.4 + 0.4 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_TrashCanC_01/meshes/aws_robomaker_warehouse_TrashCanC_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 27.7469 40.8969 0 0 -0 0 + + + + + 2 + + 0.841 + 0 + 0 + 0.954 + 0 + 1.422 + + + + + + model://aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 27.0194 26.9829 0 0 -0 0 + + + + + 2 + + 0.841 + 0 + 0 + 0.954 + 0 + 1.422 + + + + + + model://aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 26.7292 22.9634 0 0 -0 0 + + + + + 1 + + 1.558 + 0 + 0 + 1.821 + 0 + 1.892 + + + + + + model://aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 26.2755 17.983 0 0 -0 0 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 26.6188 9.9624 0 0 -0 0 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 26.8635 6.91241 0 0 -0 0 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 27.1658 4.11766 0 0 -0 0 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 26.9771 1.18415 0 0 -0 0 + + + + + 1 + + 1.558 + 0 + 0 + 1.821 + 0 + 1.892 + + + + + + model://aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 26.8949 7.00748 0 0 -0 0 + + + + + 1 + + 1.558 + 0 + 0 + 1.821 + 0 + 1.892 + + + + + + model://aws_robomaker_warehouse_ClutteringD_01/meshes/aws_robomaker_warehouse_ClutteringD_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ClutteringD_01/meshes/aws_robomaker_warehouse_ClutteringD_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 27.6843 -1.91409 0 0 -0 0 + + + + + 1 + + 1.558 + 0 + 0 + 1.821 + 0 + 1.892 + + + + + + model://aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 26.2078 -3.17715 0 0 -0 0 + + + + + 1 + + 0.2 + 0 + 0 + 0.308 + 0 + 0.24 + + + + + + model://aws_robomaker_warehouse_TrashCanC_01/meshes/aws_robomaker_warehouse_TrashCanC_01_collision.DAE + 1 1 1 + + + + + + 0.4 + 0.4 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_TrashCanC_01/meshes/aws_robomaker_warehouse_TrashCanC_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 26.6799 2.02665 0 0 -0 0 + + + + + 2 + + 0.277 + 0 + 0 + 0.452 + 0 + 0.268 + + + + + + model://aws_robomaker_warehouse_PalletJackB_01/meshes/aws_robomaker_warehouse_PalletJackB_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_PalletJackB_01/meshes/aws_robomaker_warehouse_PalletJackB_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 26.5796 -1.00381 0 0 -0 0 + + + + + 2 + + 0.277 + 0 + 0 + 0.452 + 0 + 0.268 + + + + + + model://aws_robomaker_warehouse_PalletJackB_01/meshes/aws_robomaker_warehouse_PalletJackB_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_PalletJackB_01/meshes/aws_robomaker_warehouse_PalletJackB_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 27.3554 -6.53711 0 0 -0 0 + + + + + 2 + 0 0 0 0 -0 0 + + 0.57 + 0 + 0 + 0.474 + 0 + 0.391 + + + 0 0 0 0 -0 0 + 0 + 0 + 1 + + + + model://aws_robomaker_warehouse_Bucket_01/meshes/aws_robomaker_warehouse_Bucket_01_visual.DAE + + + + 1 + + + + 0 + 10 + 0 0 0 0 -0 0 + + + model://aws_robomaker_warehouse_Bucket_01/meshes/aws_robomaker_warehouse_Bucket_01_collision.DAE + 1 1 1 + + + + + + 0.4 + 0.4 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + + 0 + + 1 + 25.5015 -7.22065 0 0 -0 0 + + + + + 2 + 0 0 0 0 -0 0 + + 0.57 + 0 + 0 + 0.474 + 0 + 0.391 + + + 0 0 0 0 -0 0 + 0 + 0 + 1 + + + + model://aws_robomaker_warehouse_Bucket_01/meshes/aws_robomaker_warehouse_Bucket_01_visual.DAE + + + + 1 + + + + 0 + 10 + 0 0 0 0 -0 0 + + + model://aws_robomaker_warehouse_Bucket_01/meshes/aws_robomaker_warehouse_Bucket_01_collision.DAE + 1 1 1 + + + + + + 0.4 + 0.4 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + + 0 + + 1 + 27.3318 -8.09227 0 0 -0 0 + + + + + 2 + + 0.841 + 0 + 0 + 0.954 + 0 + 1.422 + + + + + + model://aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 27.4595 29.2376 0 0 -0 0 + + + 14 20.85 0 0 -0 0 + + + + + 42.15 0.15 2.5 + + + 0 0 1.25 0 -0 0 + 10 + + + + + + + + + + + + + + + 0 0 1.25 0 -0 0 + + + 42.15 0.15 2.5 + + + + + 1 1 1 1 + + + 0 + + + -0 -31.35 0 0 -0 0 + 0 + 0 + 0 + + + + + + 62.85 0.15 2.5 + + + 0 0 1.25 0 -0 0 + 10 + + + + + + + + + + + + + + + 0 0 1.25 0 -0 0 + + + 62.85 0.15 2.5 + + + + + 1 1 1 1 + + + 0 + + + -21 1e-06 0 0 -0 1.5708 + 0 + 0 + 0 + + + + + + 62.85 0.15 2.5 + + + 0 0 1.25 0 -0 0 + 10 + + + + + + + + + + + + + + + 0 0 1.25 0 -0 0 + + + 62.85 0.15 2.5 + + + + + 1 1 1 1 + + + 0 + + + 21 1e-06 0 0 -0 1.5708 + 0 + 0 + 0 + + + + + + 42.15 0.15 2.5 + + + 0 0 1.25 0 -0 0 + 10 + + + + + + + + + + + + + + + 0 0 1.25 0 -0 0 + + + 42.15 0.15 2.5 + + + + + 1 1 1 1 + + + 0 + + + -0 31.35 0 0 -0 0 + 0 + 0 + 0 + + 1 + + + 1 + + + + + 0 0 1 + 100 100 + + + + + 65535 + + + + + 100 + 50 + + + + + + + + 10 + + + 0 + + + 0 0 1 + 100 100 + + + + + + + 0 + 0 + 0 + + 4.53166 20.7695 0 0 -0 0 + + + 1 + 10.387 20.7515 10 0 -0 0 + 0.8 0.8 0.8 1 + 0.2 0.2 0.2 1 + + 1000 + 0.9 + 0.01 + 0.001 + + -0.5 0.1 -0.9 + + 0 + 0 + 0 + + + + + + 1 + + 1.558 + 0 + 0 + 1.821 + 0 + 1.892 + + + + + + model://aws_robomaker_warehouse_ClutteringD_01/meshes/aws_robomaker_warehouse_ClutteringD_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ClutteringD_01/meshes/aws_robomaker_warehouse_ClutteringD_01_visual.DAE + + + + 1 + + + 0 0 0 0 -0 0 + 0 + 0 + 0 + + 1 + 3.75927 15.6402 -0.319559 0 -0 0 + + + + + 1 + + 1.558 + 0 + 0 + 1.821 + 0 + 1.892 + + + + + + model://aws_robomaker_warehouse_ClutteringD_01/meshes/aws_robomaker_warehouse_ClutteringD_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ClutteringD_01/meshes/aws_robomaker_warehouse_ClutteringD_01_visual.DAE + + + + 1 + + + 0 0 0 0 -0 0 + 0 + 0 + 0 + + 1 + 3.79574 13.9378 -0.319559 0 -0 0 + + + + + 1 + + 1.558 + 0 + 0 + 1.821 + 0 + 1.892 + + + + + + model://aws_robomaker_warehouse_ClutteringD_01/meshes/aws_robomaker_warehouse_ClutteringD_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ClutteringD_01/meshes/aws_robomaker_warehouse_ClutteringD_01_visual.DAE + + + + 1 + + + 0 0 0 0 -0 0 + 0 + 0 + 0 + + 1 + 19.5791 1.04522 -0.319559 0 -0 0 + + + + + 1 + + 1.558 + 0 + 0 + 1.821 + 0 + 1.892 + + + + + + model://aws_robomaker_warehouse_ClutteringD_01/meshes/aws_robomaker_warehouse_ClutteringD_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ClutteringD_01/meshes/aws_robomaker_warehouse_ClutteringD_01_visual.DAE + + + + 1 + + + 0 0 0 0 -0 0 + 0 + 0 + 0 + + 1 + 19.5668 -0.476464 -0.319559 0 -0 0 + + + + + 1 + + 1.558 + 0 + 0 + 1.821 + 0 + 1.892 + + + + + + model://aws_robomaker_warehouse_ClutteringD_01/meshes/aws_robomaker_warehouse_ClutteringD_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ClutteringD_01/meshes/aws_robomaker_warehouse_ClutteringD_01_visual.DAE + + + + 1 + + + 0 0 0 0 -0 0 + 0 + 0 + 0 + + 1 + 27.0966 31.0093 -0.319559 0 -0 0 + + + + + 1 + + 1.558 + 0 + 0 + 1.821 + 0 + 1.892 + + + + + + model://aws_robomaker_warehouse_ClutteringD_01/meshes/aws_robomaker_warehouse_ClutteringD_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ClutteringD_01/meshes/aws_robomaker_warehouse_ClutteringD_01_visual.DAE + + + + 1 + + + 0 0 0 0 -0 0 + 0 + 0 + 0 + + 1 + 17.1951 25.1471 -0.319559 0 -0 0 + + + + + 1 + + 1.558 + 0 + 0 + 1.821 + 0 + 1.892 + + + + + + model://aws_robomaker_warehouse_ClutteringD_01/meshes/aws_robomaker_warehouse_ClutteringD_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ClutteringD_01/meshes/aws_robomaker_warehouse_ClutteringD_01_visual.DAE + + + + 1 + + + 0 0 0 0 -0 0 + 0 + 0 + 0 + + 1 + 17.4881 29.6484 -0.319559 0 -0 0 + + + + + 1 + + 1.558 + 0 + 0 + 1.821 + 0 + 1.892 + + + + + + model://aws_robomaker_warehouse_ClutteringD_01/meshes/aws_robomaker_warehouse_ClutteringD_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ClutteringD_01/meshes/aws_robomaker_warehouse_ClutteringD_01_visual.DAE + + + + 1 + + + 0 0 0 0 -0 0 + 0 + 0 + 0 + + 1 + -0.754194 41.4319 -0.319559 0 -0 0 + + + + + 1 + + 1.558 + 0 + 0 + 1.821 + 0 + 1.892 + + + + + + model://aws_robomaker_warehouse_ClutteringD_01/meshes/aws_robomaker_warehouse_ClutteringD_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ClutteringD_01/meshes/aws_robomaker_warehouse_ClutteringD_01_visual.DAE + + + + 1 + + + 0 0 0 0 -0 0 + 0 + 0 + 0 + + 1 + -0.699945 44.5929 -0.319559 0 -0 0 + + + + + 1 + + 1.558 + 0 + 0 + 1.821 + 0 + 1.892 + + + + + + model://aws_robomaker_warehouse_ClutteringD_01/meshes/aws_robomaker_warehouse_ClutteringD_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ClutteringD_01/meshes/aws_robomaker_warehouse_ClutteringD_01_visual.DAE + + + + 1 + + + 0 0 0 0 -0 0 + 0 + 0 + 0 + + 1 + 12.8719 2.10478 -0.319559 0 -0 0 + + + + + 1 + + 1.558 + 0 + 0 + 1.821 + 0 + 1.892 + + + + + + model://aws_robomaker_warehouse_ClutteringD_01/meshes/aws_robomaker_warehouse_ClutteringD_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ClutteringD_01/meshes/aws_robomaker_warehouse_ClutteringD_01_visual.DAE + + + + 1 + + + 0 0 0 0 -0 0 + 0 + 0 + 0 + + 1 + 26.6012 20.1146 -0.319559 0 -0 0 + + + + + 1 + + 1.558 + 0 + 0 + 1.821 + 0 + 1.892 + + + + + + model://aws_robomaker_warehouse_ClutteringD_01/meshes/aws_robomaker_warehouse_ClutteringD_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ClutteringD_01/meshes/aws_robomaker_warehouse_ClutteringD_01_visual.DAE + + + + 1 + + + 0 0 0 0 -0 0 + 0 + 0 + 0 + + 1 + 25.7986 14.976 -0.319559 0 -0 0 + + + + + 1 + + 1.558 + 0 + 0 + 1.821 + 0 + 1.892 + + + + + + model://aws_robomaker_warehouse_ClutteringD_01/meshes/aws_robomaker_warehouse_ClutteringD_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ClutteringD_01/meshes/aws_robomaker_warehouse_ClutteringD_01_visual.DAE + + + + 1 + + + 0 0 0 0 -0 0 + 0 + 0 + 0 + + 1 + 25.7484 12.7941 -0.319559 0 -0 0 + + + + + 1 + + 1.558 + 0 + 0 + 1.821 + 0 + 1.892 + + + + + + model://aws_robomaker_warehouse_ClutteringD_01/meshes/aws_robomaker_warehouse_ClutteringD_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://aws_robomaker_warehouse_ClutteringD_01/meshes/aws_robomaker_warehouse_ClutteringD_01_visual.DAE + + + + 1 + + + 0 0 0 0 -0 0 + 0 + 0 + 0 + + 1 + 26.4124 46.52 -0.319559 0 -0 0 + + + 8.5 27 1 0 0 0 + + walk.dae + 1.0 + + + walk.dae + 1.0 + true + + + LHipJoint_LeftUpLeg_collision + LeftUpLeg_LeftLeg_collision + LeftLeg_LeftFoot_collision + LeftFoot_LeftToeBase_collision + RHipJoint_RightUpLeg_collision + RightUpLeg_RightLeg_collision + RightLeg_RightFoot_collision + RightFoot_RightToeBase_collision + Spine_Spine1_collision + Neck_Neck1_collision + Neck1_Head_collision + LeftShoulder_LeftArm_collision + LeftArm_LeftForeArm_collision + LeftForeArm_LeftHand_collision + LeftFingerBase_LeftHandIndex1_collision + RightShoulder_RightArm_collision + RightArm_RightForeArm_collision + RightForeArm_RightHand_collision + RightFingerBase_RightHandIndex1_collision + LowerBack_Spine_collision + 1.0 + 0.4 + True + 5.1 + 6.0 + 2.0 + 20.0 + 15 + 3.0 + 2.0 + 1.0 + + ground_plane + + + 8.5 27 1 0 0 0 + 8.3 21 1 0 0 0 + + + + 5 + + + + 13.5 28.0 1 0 0 0 + + walk.dae + 1.0 + + + walk.dae + 1.0 + true + + + LHipJoint_LeftUpLeg_collision + LeftUpLeg_LeftLeg_collision + LeftLeg_LeftFoot_collision + LeftFoot_LeftToeBase_collision + RHipJoint_RightUpLeg_collision + RightUpLeg_RightLeg_collision + RightLeg_RightFoot_collision + RightFoot_RightToeBase_collision + Spine_Spine1_collision + Neck_Neck1_collision + Neck1_Head_collision + LeftShoulder_LeftArm_collision + LeftArm_LeftForeArm_collision + LeftForeArm_LeftHand_collision + LeftFingerBase_LeftHandIndex1_collision + RightShoulder_RightArm_collision + RightArm_RightForeArm_collision + RightForeArm_RightHand_collision + RightFingerBase_RightHandIndex1_collision + LowerBack_Spine_collision + 1.2 + 0.4 + True + 5.1 + 6.0 + 2.0 + 20.0 + 15 + 3.0 + 2.0 + 1.0 + + ground_plane + + + 10.5 28.0 1 0 0 0 + 16.5 29.5 1 0 0 0 + + + + + 10.5 25.0 1 0 0 0 + + walk.dae + 1.0 + + + walk.dae + 1.0 + true + + + LHipJoint_LeftUpLeg_collision + LeftUpLeg_LeftLeg_collision + LeftLeg_LeftFoot_collision + LeftFoot_LeftToeBase_collision + RHipJoint_RightUpLeg_collision + RightUpLeg_RightLeg_collision + RightLeg_RightFoot_collision + RightFoot_RightToeBase_collision + Spine_Spine1_collision + Neck_Neck1_collision + Neck1_Head_collision + LeftShoulder_LeftArm_collision + LeftArm_LeftForeArm_collision + LeftForeArm_LeftHand_collision + LeftFingerBase_LeftHandIndex1_collision + RightShoulder_RightArm_collision + RightArm_RightForeArm_collision + RightForeArm_RightHand_collision + RightFingerBase_RightHandIndex1_collision + LowerBack_Spine_collision + 1.2 + 0.4 + True + 5.1 + 6.0 + 2.0 + 20.0 + 15 + 3.0 + 2.0 + 1.0 + + ground_plane + + + 10.5 25.0 1 0 0 0 + 10.5 28.5 1 0 0 0 + + + + + diff --git a/simulators/sim_env/CMakeLists.txt b/simulators/sim_env/CMakeLists.txt new file mode 100755 index 0000000..c854a20 --- /dev/null +++ b/simulators/sim_env/CMakeLists.txt @@ -0,0 +1,15 @@ +cmake_minimum_required(VERSION 3.0.2) +project(sim_env) +find_package(catkin REQUIRED COMPONENTS + roscpp + rospy + std_msgs + message_generation + controller_manager + gazebo_ros + rviz +) + +catkin_package( + CATKIN_DEPENDS urdf xacro +) \ No newline at end of file diff --git a/simulators/sim_env/config/amcl_params.yaml b/simulators/sim_env/config/amcl_params.yaml new file mode 100755 index 0000000..65e20d4 --- /dev/null +++ b/simulators/sim_env/config/amcl_params.yaml @@ -0,0 +1,25 @@ +min_particles: 500 +max_particles: 3000 +kld_err: 0.02 +update_min_d: 0.20 +update_min_a: 0.20 +resample_interval: 1 +transform_tolerance: 0.5 +recovery_alpha_slow: 0.00 +recovery_alpha_fast: 0.00 +gui_publish_rate: 50.0 +laser_max_range: 3.5 +laser_max_beams: 180 +laser_z_hit: 0.5 +laser_z_short: 0.05 +laser_z_max: 0.05 +laser_z_rand: 0.5 +laser_sigma_hit: 0.2 +laser_lambda_short: 0.1 +laser_likelihood_max_dist: 2.0 +laser_model_type: "likelihood_field" +odom_model_type: "diff" +odom_alpha1: 0.1 +odom_alpha2: 0.1 +odom_alpha3: 0.1 +odom_alpha4: 0.1 \ No newline at end of file diff --git a/simulators/sim_env/config/costmap/global_costmap_params.yaml b/simulators/sim_env/config/costmap/global_costmap_params.yaml new file mode 100755 index 0000000..344317b --- /dev/null +++ b/simulators/sim_env/config/costmap/global_costmap_params.yaml @@ -0,0 +1,15 @@ +global_costmap: + global_frame: map + robot_base_frame: $(arg prefix)base_footprint + + update_frequency: 1.0 + publish_frequency: 1.0 + transform_tolerance: 0.5 + + static_map: true + # plugins: + # - {name: static_map, type: "costmap_2d::StaticLayer"} + # # - {name: voxel_layer, type: "costmap_2d::VoxelLayer"} + # - {name: obstacle_layer, type: "costmap_2d::ObstacleLayer"} + # - {name: voronoi_layer, type: "costmap_2d::VoronoiLayer"} + # - {name: inflation_layer, type: "costmap_2d::InflationLayer"} \ No newline at end of file diff --git a/simulators/sim_env/config/costmap/local_costmap_params.yaml b/simulators/sim_env/config/costmap/local_costmap_params.yaml new file mode 100755 index 0000000..ff18013 --- /dev/null +++ b/simulators/sim_env/config/costmap/local_costmap_params.yaml @@ -0,0 +1,17 @@ +local_costmap: + global_frame: odom + robot_base_frame: $(arg prefix)base_footprint + + update_frequency: 10.0 + publish_frequency: 10.0 + transform_tolerance: 0.5 + + static_map: false + rolling_window: true + width: 3 + height: 3 + resolution: 0.05 + + # plugins: + # - {name: obstacle_layer, type: "costmap_2d::ObstacleLayer"} + # - {name: inflation_layer, type: "costmap_2d::InflationLayer"} \ No newline at end of file diff --git a/simulators/sim_env/config/move_base_params.yaml b/simulators/sim_env/config/move_base_params.yaml new file mode 100755 index 0000000..be41f8c --- /dev/null +++ b/simulators/sim_env/config/move_base_params.yaml @@ -0,0 +1,12 @@ +shutdown_costmaps: false + +planner_frequency: 2.0 +planner_patience: 5.0 + +controller_frequency: 10.0 +controller_patience: 15.0 + +oscillation_timeout: 10.0 +oscillation_distance: 0.2 + +conservative_reset_dist: 3.0 diff --git a/simulators/sim_env/config/planner/dwa_planner_params.yaml b/simulators/sim_env/config/planner/dwa_planner_params.yaml new file mode 100755 index 0000000..6873061 --- /dev/null +++ b/simulators/sim_env/config/planner/dwa_planner_params.yaml @@ -0,0 +1,47 @@ +DWAPlanner: + +# Robot Configuration Parameters + max_vel_x: 0.46 + min_vel_x: 0.00 + + max_vel_y: 0.0 + min_vel_y: 0.0 + +# The velocity when robot is moving in a straight line + max_vel_trans: 0.26 + min_vel_trans: 0.13 + + max_vel_theta: 1.82 + min_vel_theta: 0.9 + + acc_lim_x: 2.5 + acc_lim_y: 0.0 + acc_lim_theta: 3.2 + +# Goal Tolerance Parameters + xy_goal_tolerance: 0.05 + yaw_goal_tolerance: 0.17 + latch_xy_goal_tolerance: false + +# Forward Simulation Parameters + sim_time: 2.0 + vx_samples: 20 + vy_samples: 0 + vth_samples: 40 + controller_frequency: 10.0 + +# Trajectory Scoring Parameters + path_distance_bias: 32.0 + goal_distance_bias: 20.0 + occdist_scale: 0.02 + forward_point_distance: 0.325 + stop_time_buffer: 0.2 + scaling_speed: 0.25 + max_scaling_factor: 0.2 + +# Oscillation Prevention Parameters + oscillation_reset_dist: 0.05 + +# Debugging + publish_traj_pc : true + publish_cost_grid_pc: true diff --git a/simulators/sim_env/config/planner/evolutionary_planner_params.yaml b/simulators/sim_env/config/planner/evolutionary_planner_params.yaml new file mode 100755 index 0000000..bc61caa --- /dev/null +++ b/simulators/sim_env/config/planner/evolutionary_planner_params.yaml @@ -0,0 +1,23 @@ +EvolutionaryPlanner: + # offset of transform from world(x,y) to grid map(x,y) + convert_offset: 0.0 + # error tolerance + default_tolerance: 0.0 + # whether outline the map or not + outline_map: true + # obstacle inflation factor + obstacle_factor: 0.5 + + ## Ant Colony Optimization(ACO) planner + # number of ants + n_ants: 50 + # pheromone weight coefficient + alpha: 1.0 + # heuristic factor weight coefficient + beta: 8.0 + # evaporation coefficient + rho: 0.1 + # pheromone gain + Q: 1.0 + # maximum iterations + max_iter: 30 \ No newline at end of file diff --git a/simulators/sim_env/config/planner/graph_planner_params.yaml b/simulators/sim_env/config/planner/graph_planner_params.yaml new file mode 100755 index 0000000..4ec5a8e --- /dev/null +++ b/simulators/sim_env/config/planner/graph_planner_params.yaml @@ -0,0 +1,11 @@ +GraphPlanner: + # offset of transform from world(x,y) to grid map(x,y) + convert_offset: 0.0 + # error tolerance + default_tolerance: 0.0 + # whether outline the map or not + outline_map: true + # obstacle inflation factor + obstacle_factor: 0.5 + # whether publish expand zone or not + expand_zone: true \ No newline at end of file diff --git a/simulators/sim_env/config/planner/pid_planner_params.yaml b/simulators/sim_env/config/planner/pid_planner_params.yaml new file mode 100755 index 0000000..79c4402 --- /dev/null +++ b/simulators/sim_env/config/planner/pid_planner_params.yaml @@ -0,0 +1,29 @@ +PIDPlanner: + # next point distance/turning angle + p_window: 0.2 + o_window: 1.0 + + # goal reached tolerance + p_precision: 0.2 + o_precision: 0.5 + + # linear velocity + max_v: 0.5 + min_v: 0.0 + max_v_inc: 0.5 + + # angular velocity + max_w: 1.57 + min_w: 0.0 + max_w_inc: 1.57 + + # pid controller params + k_v_p: 1.00 + k_v_i: 0.10 + k_v_d: 0.10 + + k_w_p: 1.00 + k_w_i: 0.10 + k_w_d: 0.10 + + k_theta: 0.3 diff --git a/simulators/sim_env/config/planner/sample_planner_params.yaml b/simulators/sim_env/config/planner/sample_planner_params.yaml new file mode 100755 index 0000000..a0a9538 --- /dev/null +++ b/simulators/sim_env/config/planner/sample_planner_params.yaml @@ -0,0 +1,17 @@ +SamplePlanner: + # random sample points + sample_points: 2000 #1000 for informed RRT*, 3000 for others + # max distance between sample points + sample_max_d: 10.0 + # optimization radius + optimization_r: 20.0 + # offset of transform from world(x,y) to grid map(x,y) + convert_offset: 0.0 + # error tolerance + default_tolerance: 0.0 + # whether outline the map or not + outline_map: true + # obstacle inflation factor + obstacle_factor: 0.5 + # whether publish expand zone or not + expand_zone: true \ No newline at end of file diff --git a/simulators/sim_env/config/turtlebot3_burger/costmap_common_params_turtlebot3_burger.yaml b/simulators/sim_env/config/turtlebot3_burger/costmap_common_params_turtlebot3_burger.yaml new file mode 100755 index 0000000..bffd785 --- /dev/null +++ b/simulators/sim_env/config/turtlebot3_burger/costmap_common_params_turtlebot3_burger.yaml @@ -0,0 +1,12 @@ +obstacle_range: 3.0 +raytrace_range: 3.5 + +footprint: [[-0.105, -0.105], [-0.105, 0.105], [0.041, 0.105], [0.041, -0.105]] +#robot_radius: 0.105 + +inflation_radius: 3.0 +cost_scaling_factor: 3.0 + +map_type: costmap +observation_sources: scan +scan: {sensor_frame: base_scan, data_type: LaserScan, topic: scan, marking: true, clearing: true} \ No newline at end of file diff --git a/simulators/sim_env/config/turtlebot3_waffle/costmap_common_params_turtlebot3_waffle.yaml b/simulators/sim_env/config/turtlebot3_waffle/costmap_common_params_turtlebot3_waffle.yaml new file mode 100755 index 0000000..13d5d14 --- /dev/null +++ b/simulators/sim_env/config/turtlebot3_waffle/costmap_common_params_turtlebot3_waffle.yaml @@ -0,0 +1,12 @@ +obstacle_range: 3.0 +raytrace_range: 3.5 + +footprint: [[-0.205, -0.155], [-0.205, 0.155], [0.077, 0.155], [0.077, -0.155]] +#robot_radius: 0.17 + +inflation_radius: 1.0 +cost_scaling_factor: 3.0 + +map_type: costmap +observation_sources: scan +scan: {sensor_frame: base_scan, data_type: LaserScan, topic: scan, marking: true, clearing: true, inf_is_valid: true} diff --git a/simulators/sim_env/config/turtlebot3_waffle_pi/costmap_common_params_turtlebot3_waffle_pi.yaml b/simulators/sim_env/config/turtlebot3_waffle_pi/costmap_common_params_turtlebot3_waffle_pi.yaml new file mode 100755 index 0000000..3d5a6d7 --- /dev/null +++ b/simulators/sim_env/config/turtlebot3_waffle_pi/costmap_common_params_turtlebot3_waffle_pi.yaml @@ -0,0 +1,12 @@ +obstacle_range: 3.0 +raytrace_range: 3.5 + +footprint: [[-0.205, -0.155], [-0.205, 0.155], [0.077, 0.155], [0.077, -0.155]] +#robot_radius: 0.17 + +inflation_radius: 1.0 +cost_scaling_factor: 3.0 + +map_type: costmap +observation_sources: scan +scan: {sensor_frame: base_scan, data_type: LaserScan, topic: scan, marking: true, clearing: true} diff --git a/simulators/sim_env/launch/app/environment_single.launch.xml b/simulators/sim_env/launch/app/environment_single.launch.xml new file mode 100755 index 0000000..e1e6928 --- /dev/null +++ b/simulators/sim_env/launch/app/environment_single.launch.xml @@ -0,0 +1,87 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/simulators/sim_env/launch/config.launch b/simulators/sim_env/launch/config.launch new file mode 100755 index 0000000..09806a3 --- /dev/null +++ b/simulators/sim_env/launch/config.launch @@ -0,0 +1,51 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/simulators/sim_env/launch/include/location_methods/amcl.launch.xml b/simulators/sim_env/launch/include/location_methods/amcl.launch.xml new file mode 100755 index 0000000..1125ac3 --- /dev/null +++ b/simulators/sim_env/launch/include/location_methods/amcl.launch.xml @@ -0,0 +1,35 @@ + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/simulators/sim_env/launch/include/navigation/move_base.launch.xml b/simulators/sim_env/launch/include/navigation/move_base.launch.xml new file mode 100755 index 0000000..f82e479 --- /dev/null +++ b/simulators/sim_env/launch/include/navigation/move_base.launch.xml @@ -0,0 +1,130 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/simulators/sim_env/launch/include/robots/start_robots.launch.xml b/simulators/sim_env/launch/include/robots/start_robots.launch.xml new file mode 100755 index 0000000..931798d --- /dev/null +++ b/simulators/sim_env/launch/include/robots/start_robots.launch.xml @@ -0,0 +1,25 @@ + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/simulators/sim_env/launch/main.launch b/simulators/sim_env/launch/main.launch new file mode 100755 index 0000000..b124157 --- /dev/null +++ b/simulators/sim_env/launch/main.launch @@ -0,0 +1,11 @@ + + + + + + + + + + + diff --git a/simulators/sim_env/launch/realworld/(untested)qbot_navigaition.launch b/simulators/sim_env/launch/realworld/(untested)qbot_navigaition.launch new file mode 100755 index 0000000..35779a1 --- /dev/null +++ b/simulators/sim_env/launch/realworld/(untested)qbot_navigaition.launch @@ -0,0 +1,103 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/simulators/sim_env/maps/warehouse/warehouse.pgm b/simulators/sim_env/maps/warehouse/warehouse.pgm new file mode 100755 index 0000000..88ec4c3 --- /dev/null +++ b/simulators/sim_env/maps/warehouse/warehouse.pgm @@ -0,0 +1,7 @@ +P5 +# Created by GIMP version 2.10.30 PNM plug-in +480 480 +255 +     +  ,Z}bb~~U  p͜  +  \ No newline at end of file diff --git a/simulators/sim_env/maps/warehouse/warehouse.yaml b/simulators/sim_env/maps/warehouse/warehouse.yaml new file mode 100755 index 0000000..681e554 --- /dev/null +++ b/simulators/sim_env/maps/warehouse/warehouse.yaml @@ -0,0 +1,7 @@ +image: ./warehouse.pgm +resolution: 0.050000 +origin: [-12.000000, -12.000000, 0.000000] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 + diff --git a/simulators/sim_env/meshes/turtlebot3/bases/burger_base.stl b/simulators/sim_env/meshes/turtlebot3/bases/burger_base.stl new file mode 100755 index 0000000..270a12c Binary files /dev/null and b/simulators/sim_env/meshes/turtlebot3/bases/burger_base.stl differ diff --git a/simulators/sim_env/meshes/turtlebot3/bases/waffle_base.stl b/simulators/sim_env/meshes/turtlebot3/bases/waffle_base.stl new file mode 100755 index 0000000..e8b4cbc Binary files /dev/null and b/simulators/sim_env/meshes/turtlebot3/bases/waffle_base.stl differ diff --git a/simulators/sim_env/meshes/turtlebot3/bases/waffle_base_for_open_manipulator.stl b/simulators/sim_env/meshes/turtlebot3/bases/waffle_base_for_open_manipulator.stl new file mode 100755 index 0000000..a164dbe Binary files /dev/null and b/simulators/sim_env/meshes/turtlebot3/bases/waffle_base_for_open_manipulator.stl differ diff --git a/simulators/sim_env/meshes/turtlebot3/bases/waffle_pi_base.stl b/simulators/sim_env/meshes/turtlebot3/bases/waffle_pi_base.stl new file mode 100755 index 0000000..8e2bf43 Binary files /dev/null and b/simulators/sim_env/meshes/turtlebot3/bases/waffle_pi_base.stl differ diff --git a/simulators/sim_env/meshes/turtlebot3/bases/waffle_pi_base_for_open_manipulator.stl b/simulators/sim_env/meshes/turtlebot3/bases/waffle_pi_base_for_open_manipulator.stl new file mode 100755 index 0000000..8d167ed Binary files /dev/null and b/simulators/sim_env/meshes/turtlebot3/bases/waffle_pi_base_for_open_manipulator.stl differ diff --git a/simulators/sim_env/meshes/turtlebot3/sensors/astra.dae b/simulators/sim_env/meshes/turtlebot3/sensors/astra.dae new file mode 100755 index 0000000..eb1ea6b --- /dev/null +++ b/simulators/sim_env/meshes/turtlebot3/sensors/astra.dae @@ -0,0 +1,256759 @@ + + + FBX COLLADA exporter2016-03-24T15:23:32Z2016-03-24T15:23:32ZY_UP + + astra.jpg + + + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.156863 0.156863 0.156863 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.684000 0.684000 0.684000 1.000000 + + + 45.254833 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + +7.500000 0.000000 1.500000 +7.500000 0.000000 0.000000 +-7.469662 0.673908 0.000000 +-7.500000 0.000000 0.000000 +-7.500000 0.000000 1.500000 +-7.469662 0.673908 1.500000 +-7.374790 1.364723 0.000000 +-7.374790 1.364723 1.500000 +-7.210492 2.063687 0.000000 +-7.210492 2.063687 1.500000 +-6.973412 2.760710 0.000000 +-6.973412 2.760710 1.500000 +-6.662130 3.444710 0.000000 +-6.662130 3.444710 1.500000 +-6.277466 4.104073 0.000000 +-6.277466 4.104073 1.500000 +-5.822649 4.727236 0.000000 +-5.822649 4.727236 1.500000 +-5.303301 5.303301 0.000000 +-5.303301 5.303301 1.500000 +-4.727236 5.822649 0.000000 +-4.727236 5.822649 1.500000 +-4.104073 6.277466 0.000000 +-4.104073 6.277466 1.500000 +-3.444710 6.662130 0.000000 +-3.444710 6.662130 1.500000 +-2.760710 6.973412 0.000000 +-2.760710 6.973412 1.500000 +-2.063687 7.210492 0.000000 +-2.063687 7.210492 1.500000 +-1.364723 7.374790 0.000000 +-1.364723 7.374790 1.500000 +-0.673908 7.469662 0.000000 +-0.673908 7.469662 1.500000 +0.000000 7.500000 0.000000 +0.000000 7.500000 1.500000 +0.673908 7.469662 0.000000 +0.673908 7.469662 1.500000 +1.364723 7.374790 0.000000 +1.364723 7.374790 1.500000 +2.063687 7.210492 0.000000 +2.063687 7.210492 1.500000 +2.760710 6.973412 0.000000 +2.760710 6.973412 1.500000 +3.444710 6.662130 0.000000 +3.444710 6.662130 1.500000 +4.104073 6.277466 0.000000 +4.104073 6.277466 1.500000 +4.727236 5.822649 0.000000 +4.727236 5.822649 1.500000 +5.303301 5.303301 0.000000 +5.303301 5.303301 1.500000 +5.822649 4.727236 0.000000 +5.822649 4.727236 1.500000 +6.277466 4.104073 0.000000 +6.277466 4.104073 1.500000 +6.662130 3.444710 0.000000 +6.662130 3.444710 1.500000 +6.973412 2.760710 0.000000 +6.973412 2.760710 1.500000 +7.210492 2.063687 0.000000 +7.210492 2.063687 1.500000 +7.374790 1.364723 0.000000 +7.374790 1.364723 1.500000 +7.469662 0.673908 0.000000 +7.469662 0.673908 1.500000 +7.500000 0.000000 0.000000 +7.500000 0.000000 1.500000 +-7.500000 0.000000 1.500000 +-7.500000 0.000000 0.000000 +-7.469662 -0.673908 1.500000 +-7.469662 -0.673908 0.000000 +-7.374790 -1.364723 1.500000 +-7.374790 -1.364723 0.000000 +-7.210492 -2.063687 1.500000 +-7.210492 -2.063687 0.000000 +-6.973412 -2.760710 1.500000 +-6.973412 -2.760710 0.000000 +-6.662130 -3.444710 1.500000 +-6.662130 -3.444710 0.000000 +-6.277466 -4.104073 1.500000 +-6.277466 -4.104073 0.000000 +-5.822649 -4.727236 1.500000 +-5.822649 -4.727236 0.000000 +-5.303301 -5.303301 1.500000 +-5.303301 -5.303301 0.000000 +-4.727236 -5.822649 1.500000 +-4.727236 -5.822649 0.000000 +-4.104073 -6.277466 1.500000 +-4.104073 -6.277466 0.000000 +-3.444710 -6.662130 1.500000 +-3.444710 -6.662130 0.000000 +-2.760710 -6.973412 1.500000 +-2.760710 -6.973412 0.000000 +-2.063687 -7.210492 1.500000 +-2.063687 -7.210492 0.000000 +-1.364723 -7.374790 1.500000 +-1.364723 -7.374790 0.000000 +-0.673908 -7.469662 1.500000 +-0.673908 -7.469662 0.000000 +0.000000 -7.500000 1.500000 +0.000000 -7.500000 0.000000 +0.673908 -7.469662 1.500000 +0.673908 -7.469662 0.000000 +1.364723 -7.374790 1.500000 +1.364723 -7.374790 0.000000 +2.063687 -7.210492 1.500000 +2.063687 -7.210492 0.000000 +2.760710 -6.973412 1.500000 +2.760710 -6.973412 0.000000 +3.444710 -6.662130 1.500000 +3.444710 -6.662130 0.000000 +4.104073 -6.277466 1.500000 +4.104073 -6.277466 0.000000 +4.727236 -5.822649 1.500000 +4.727236 -5.822649 0.000000 +5.303301 -5.303301 1.500000 +5.303301 -5.303301 0.000000 +5.822649 -4.727236 1.500000 +5.822649 -4.727236 0.000000 +6.277466 -4.104073 1.500000 +6.277466 -4.104073 0.000000 +6.662130 -3.444710 1.500000 +6.662130 -3.444710 0.000000 +6.973412 -2.760710 1.500000 +6.973412 -2.760710 0.000000 +7.210492 -2.063687 1.500000 +7.210492 -2.063687 0.000000 +7.374790 -1.364723 1.500000 +7.374790 -1.364723 0.000000 +7.469662 -0.673908 1.500000 +7.469662 -0.673908 0.000000 +2.063687 7.210492 1.500000 +1.364723 7.374790 1.500000 +0.673908 7.469662 1.500000 +-0.673908 7.469662 1.500000 +-1.364723 7.374790 1.500000 +-2.063687 7.210492 1.500000 +-2.760710 6.973412 1.500000 +-3.444710 6.662130 1.500000 +-4.104073 6.277466 1.500000 +-4.727236 5.822649 1.500000 +-5.303301 5.303301 1.500000 +-5.822649 4.727236 1.500000 +-6.277466 4.104073 1.500000 +-6.662130 3.444710 1.500000 +-6.973412 2.760710 1.500000 +-7.210492 2.063687 1.500000 +-7.374790 1.364723 1.500000 +-7.469662 0.673908 1.500000 +-7.500000 0.000000 1.500000 +-7.469662 -0.673908 1.500000 +-7.374790 -1.364723 1.500000 +-7.210492 -2.063687 1.500000 +-6.973412 -2.760710 1.500000 +-6.662130 -3.444710 1.500000 +-6.277466 -4.104073 1.500000 +-5.822649 -4.727236 1.500000 +-5.303301 -5.303301 1.500000 +-4.727236 -5.822649 1.500000 +-4.104073 -6.277466 1.500000 +-3.444710 -6.662130 1.500000 +-2.760710 -6.973412 1.500000 +-2.063687 -7.210492 1.500000 +-1.364723 -7.374790 1.500000 +-0.673908 -7.469662 1.500000 +0.673908 -7.469662 1.500000 +1.364723 -7.374790 1.500000 +2.063687 -7.210492 1.500000 +2.760710 -6.973412 1.500000 +3.444710 -6.662130 1.500000 +4.104073 -6.277466 1.500000 +4.727236 -5.822649 1.500000 +5.303301 -5.303301 1.500000 +5.822649 -4.727236 1.500000 +6.277466 -4.104073 1.500000 +6.662130 -3.444710 1.500000 +6.973412 -2.760710 1.500000 +7.210492 -2.063687 1.500000 +7.374790 -1.364723 1.500000 +7.469662 -0.673908 1.500000 +7.500000 0.000000 1.500000 +7.469662 0.673908 1.500000 +7.374790 1.364723 1.500000 +7.210492 2.063687 1.500000 +6.973412 2.760710 1.500000 +6.662130 3.444710 1.500000 +6.277466 4.104073 1.500000 +5.822649 4.727236 1.500000 +5.303301 5.303301 1.500000 +4.727236 5.822649 1.500000 +4.104073 6.277466 1.500000 +3.444710 6.662130 1.500000 +2.760710 6.973412 1.500000 +2.063687 -7.210492 0.000000 +1.364723 -7.374790 0.000000 +0.673908 -7.469662 0.000000 +-0.673908 -7.469662 0.000000 +-1.364723 -7.374790 0.000000 +-2.063687 -7.210492 0.000000 +-2.760710 -6.973412 0.000000 +-3.444710 -6.662130 0.000000 +-4.104073 -6.277466 0.000000 +-4.727236 -5.822649 0.000000 +-5.303301 -5.303301 0.000000 +-5.822649 -4.727236 0.000000 +-6.277466 -4.104073 0.000000 +-6.662130 -3.444710 0.000000 +-6.973412 -2.760710 0.000000 +-7.210492 -2.063687 0.000000 +-7.374790 -1.364723 0.000000 +-7.469662 -0.673908 0.000000 +-7.500000 0.000000 0.000000 +-7.469662 0.673908 0.000000 +-7.374790 1.364723 0.000000 +-7.210492 2.063687 0.000000 +-6.973412 2.760710 0.000000 +-6.662130 3.444710 0.000000 +-6.277466 4.104073 0.000000 +-5.822649 4.727236 0.000000 +-5.303301 5.303301 0.000000 +-4.727236 5.822649 0.000000 +-4.104073 6.277466 0.000000 +-3.444710 6.662130 0.000000 +-2.760710 6.973412 0.000000 +-2.063687 7.210492 0.000000 +-1.364723 7.374790 0.000000 +-0.673908 7.469662 0.000000 +0.673908 7.469662 0.000000 +1.364723 7.374790 0.000000 +2.063687 7.210492 0.000000 +2.760710 6.973412 0.000000 +3.444710 6.662130 0.000000 +4.104073 6.277466 0.000000 +4.727236 5.822649 0.000000 +5.303301 5.303301 0.000000 +5.822649 4.727236 0.000000 +6.277466 4.104073 0.000000 +6.662130 3.444710 0.000000 +6.973412 2.760710 0.000000 +7.210492 2.063687 0.000000 +7.374790 1.364723 0.000000 +7.469662 0.673908 0.000000 +7.500000 0.000000 0.000000 +7.469662 -0.673908 0.000000 +7.374790 -1.364723 0.000000 +7.210492 -2.063687 0.000000 +6.973412 -2.760710 0.000000 +6.662130 -3.444710 0.000000 +6.277466 -4.104073 0.000000 +5.822649 -4.727236 0.000000 +5.303301 -5.303301 0.000000 +4.727236 -5.822649 0.000000 +4.104073 -6.277466 0.000000 +3.444710 -6.662130 0.000000 +2.760710 -6.973412 0.000000 + + + + + + + + + + + +0.995955 0.089854 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.995955 0.089854 0.000000 +-1.000000 0.000000 0.000000 +-0.995955 0.089854 0.000000 +-0.995955 0.089854 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.995955 0.089854 0.000000 +-0.995955 0.089854 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.995955 0.089854 0.000000 +-0.961399 0.275158 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.961399 0.275158 0.000000 +-0.961399 0.275158 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.961399 0.275158 0.000000 +-0.961399 0.275158 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.961399 0.275158 0.000000 +-0.888284 0.459295 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.888284 0.459295 0.000000 +-0.888284 0.459295 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.888284 0.459295 0.000000 +-0.888284 0.459295 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.888284 0.459295 0.000000 +-0.776353 0.630298 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.776353 0.630298 0.000000 +-0.776353 0.630298 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.776353 0.630298 0.000000 +-0.776353 0.630298 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.776353 0.630298 0.000000 +-0.630298 0.776353 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.630298 0.776353 0.000000 +-0.630298 0.776353 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.630298 0.776353 0.000000 +-0.630298 0.776353 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.630298 0.776353 0.000000 +-0.459295 0.888284 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.459295 0.888284 0.000000 +-0.459295 0.888284 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.459295 0.888284 0.000000 +-0.459295 0.888284 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.459295 0.888284 0.000000 +-0.275158 0.961399 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.275158 0.961399 0.000000 +-0.275158 0.961399 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.275158 0.961399 0.000000 +-0.275158 0.961399 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.275158 0.961399 0.000000 +-0.089854 0.995955 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.089854 0.995955 0.000000 +-0.089854 0.995955 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.089854 0.995955 0.000000 +-0.089854 0.995955 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.089854 0.995955 0.000000 +0.089854 0.995955 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.089854 0.995955 0.000000 +0.089854 0.995955 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.089854 0.995955 0.000000 +0.089854 0.995955 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.089854 0.995955 0.000000 +0.275158 0.961399 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.275158 0.961399 0.000000 +0.275158 0.961399 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.275158 0.961399 0.000000 +0.275158 0.961399 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.275158 0.961399 0.000000 +0.459295 0.888284 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.459295 0.888284 0.000000 +0.459295 0.888284 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.459295 0.888284 0.000000 +0.459295 0.888284 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.459295 0.888284 0.000000 +0.630298 0.776353 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.630298 0.776353 0.000000 +0.630298 0.776353 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.630298 0.776353 0.000000 +0.630298 0.776353 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.630298 0.776353 0.000000 +0.776353 0.630298 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.776353 0.630298 0.000000 +0.776353 0.630298 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.776353 0.630298 0.000000 +0.776353 0.630298 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.776353 0.630298 0.000000 +0.888284 0.459295 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.888284 0.459295 0.000000 +0.888284 0.459295 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.888284 0.459295 0.000000 +0.888284 0.459295 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.888284 0.459295 0.000000 +0.961399 0.275158 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.961399 0.275158 0.000000 +0.961399 0.275158 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.961399 0.275158 0.000000 +0.961399 0.275158 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.961399 0.275158 0.000000 +0.995955 0.089854 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.995955 0.089854 0.000000 +0.995955 0.089854 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.995955 0.089854 0.000000 +0.995955 0.089854 0.000000 +0.995955 -0.089854 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.995955 -0.089854 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.995955 -0.089854 0.000000 +-0.995955 -0.089854 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.995955 -0.089854 0.000000 +-0.995955 -0.089854 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.995955 -0.089854 0.000000 +-0.961399 -0.275158 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.961399 -0.275158 0.000000 +-0.961399 -0.275158 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.961399 -0.275158 0.000000 +-0.961399 -0.275158 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.961399 -0.275158 0.000000 +-0.888284 -0.459295 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.888284 -0.459295 0.000000 +-0.888284 -0.459295 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.888284 -0.459295 0.000000 +-0.888284 -0.459295 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.888284 -0.459295 0.000000 +-0.776353 -0.630298 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.776353 -0.630298 0.000000 +-0.776353 -0.630298 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.776353 -0.630298 0.000000 +-0.776353 -0.630298 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.776353 -0.630298 0.000000 +-0.630298 -0.776353 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.630298 -0.776353 0.000000 +-0.630298 -0.776353 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.630298 -0.776353 0.000000 +-0.630298 -0.776353 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.630298 -0.776353 0.000000 +-0.459295 -0.888284 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.459295 -0.888284 0.000000 +-0.459295 -0.888284 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.459295 -0.888284 0.000000 +-0.459295 -0.888284 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.459295 -0.888284 0.000000 +-0.275158 -0.961399 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.275158 -0.961399 0.000000 +-0.275158 -0.961399 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.275158 -0.961399 0.000000 +-0.275158 -0.961399 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.275158 -0.961399 0.000000 +-0.089854 -0.995955 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.089854 -0.995955 0.000000 +-0.089854 -0.995955 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +-0.089854 -0.995955 0.000000 +-0.089854 -0.995955 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.089854 -0.995955 0.000000 +0.089854 -0.995955 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.089854 -0.995955 0.000000 +0.089854 -0.995955 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.089854 -0.995955 0.000000 +0.089854 -0.995955 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.089854 -0.995955 0.000000 +0.275158 -0.961399 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.275158 -0.961399 0.000000 +0.275158 -0.961399 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.275158 -0.961399 0.000000 +0.275158 -0.961399 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.275158 -0.961399 0.000000 +0.459295 -0.888284 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.459295 -0.888284 0.000000 +0.459295 -0.888284 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.459295 -0.888284 0.000000 +0.459295 -0.888284 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.459295 -0.888284 0.000000 +0.630298 -0.776353 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.630298 -0.776353 0.000000 +0.630298 -0.776353 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.630298 -0.776353 0.000000 +0.630298 -0.776353 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.630298 -0.776353 0.000000 +0.776353 -0.630298 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.776353 -0.630298 0.000000 +0.776353 -0.630298 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.776353 -0.630298 0.000000 +0.776353 -0.630298 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.776353 -0.630298 0.000000 +0.888284 -0.459295 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.888284 -0.459295 0.000000 +0.888284 -0.459295 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.888284 -0.459295 0.000000 +0.888284 -0.459295 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.888284 -0.459295 0.000000 +0.961399 -0.275158 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.961399 -0.275158 0.000000 +0.961399 -0.275158 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.961399 -0.275158 0.000000 +0.961399 -0.275158 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.961399 -0.275158 0.000000 +0.995955 -0.089854 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.995955 -0.089854 0.000000 +0.995955 -0.089854 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.995955 -0.089854 0.000000 +0.995955 -0.089854 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 + + + + + + + + + + + +0.488202 0.824117 +0.488202 0.824066 +0.423825 0.850074 +0.422662 0.847156 +0.422662 0.847208 +0.423825 0.850125 +0.425296 0.852966 +0.425296 0.853018 +0.427083 0.855788 +0.427083 0.855839 +0.429185 0.858488 +0.429185 0.858540 +0.431591 0.861018 +0.431591 0.861069 +0.434280 0.863326 +0.434280 0.863377 +0.437220 0.865366 +0.437220 0.865418 +0.440370 0.867100 +0.440370 0.867152 +0.443681 0.868498 +0.443681 0.868549 +0.447100 0.869539 +0.447100 0.869590 +0.450569 0.870216 +0.450569 0.870267 +0.454033 0.870532 +0.454033 0.870583 +0.457442 0.870502 +0.457442 0.870553 +0.460747 0.870149 +0.460747 0.870200 +0.463910 0.869502 +0.463910 0.869554 +0.466901 0.868598 +0.466901 0.868650 +0.469799 0.867428 +0.469799 0.867479 +0.472673 0.865947 +0.472673 0.865998 +0.475475 0.864148 +0.475475 0.864200 +0.478158 0.862033 +0.478158 0.862084 +0.480671 0.859610 +0.480671 0.859662 +0.482964 0.856904 +0.482964 0.856955 +0.484991 0.853944 +0.484991 0.853995 +0.486714 0.850773 +0.486714 0.850824 +0.488102 0.847440 +0.488102 0.847491 +0.489136 0.843999 +0.489136 0.844050 +0.489809 0.840506 +0.489809 0.840558 +0.490123 0.837019 +0.490123 0.837070 +0.490093 0.833588 +0.490093 0.833639 +0.489742 0.830261 +0.489742 0.830312 +0.489100 0.827076 +0.489100 0.827128 +0.488202 0.824066 +0.488202 0.824117 +0.422662 0.847208 +0.422662 0.847156 +0.421764 0.844197 +0.421764 0.844146 +0.421122 0.841013 +0.421122 0.840961 +0.420771 0.837685 +0.420771 0.837634 +0.420741 0.834255 +0.420741 0.834203 +0.421055 0.830767 +0.421055 0.830716 +0.421728 0.827275 +0.421728 0.827223 +0.422762 0.823834 +0.422762 0.823783 +0.424150 0.820501 +0.424150 0.820449 +0.425873 0.817330 +0.425873 0.817278 +0.427900 0.814370 +0.427900 0.814319 +0.430193 0.811663 +0.430193 0.811612 +0.432705 0.809241 +0.432705 0.809190 +0.435388 0.807125 +0.435388 0.807074 +0.438191 0.805327 +0.438191 0.805275 +0.441064 0.803846 +0.441064 0.803795 +0.443963 0.802675 +0.443963 0.802624 +0.446954 0.801771 +0.446954 0.801720 +0.450117 0.801125 +0.450117 0.801074 +0.453422 0.800772 +0.453422 0.800720 +0.456830 0.800741 +0.456830 0.800690 +0.460295 0.801058 +0.460295 0.801006 +0.463764 0.801734 +0.463764 0.801683 +0.467183 0.802776 +0.467183 0.802724 +0.470494 0.804173 +0.470494 0.804122 +0.473644 0.805907 +0.473644 0.805856 +0.476584 0.807948 +0.476584 0.807897 +0.479273 0.810256 +0.479273 0.810205 +0.481679 0.812785 +0.481679 0.812734 +0.483781 0.815486 +0.483781 0.815435 +0.485568 0.818307 +0.485568 0.818256 +0.487039 0.821200 +0.487039 0.821148 +0.475475 0.864200 +0.472673 0.865998 +0.469799 0.867479 +0.463910 0.869554 +0.460747 0.870200 +0.457442 0.870553 +0.454033 0.870583 +0.450569 0.870267 +0.447100 0.869590 +0.443681 0.868549 +0.440370 0.867152 +0.437220 0.865418 +0.434280 0.863377 +0.431591 0.861069 +0.429185 0.858540 +0.427083 0.855839 +0.425296 0.853018 +0.423825 0.850125 +0.422662 0.847208 +0.421764 0.844197 +0.421122 0.841013 +0.420771 0.837685 +0.420741 0.834255 +0.421055 0.830767 +0.421728 0.827275 +0.422762 0.823834 +0.424150 0.820501 +0.425873 0.817330 +0.427900 0.814370 +0.430193 0.811663 +0.432705 0.809241 +0.435388 0.807125 +0.438191 0.805327 +0.441064 0.803846 +0.446954 0.801771 +0.450117 0.801125 +0.453422 0.800772 +0.456830 0.800741 +0.460295 0.801058 +0.463764 0.801734 +0.467183 0.802776 +0.470494 0.804173 +0.473644 0.805907 +0.476584 0.807948 +0.479273 0.810256 +0.481679 0.812785 +0.483781 0.815486 +0.485568 0.818307 +0.487039 0.821200 +0.488202 0.824117 +0.489100 0.827128 +0.489742 0.830312 +0.490093 0.833639 +0.490123 0.837070 +0.489809 0.840558 +0.489136 0.844050 +0.488102 0.847491 +0.486714 0.850824 +0.484991 0.853995 +0.482964 0.856955 +0.480671 0.859662 +0.478158 0.862084 +0.453422 0.800720 +0.450117 0.801074 +0.446954 0.801720 +0.441064 0.803795 +0.438191 0.805275 +0.435388 0.807074 +0.432705 0.809190 +0.430193 0.811612 +0.427900 0.814319 +0.425873 0.817278 +0.424150 0.820449 +0.422762 0.823783 +0.421728 0.827223 +0.421055 0.830716 +0.420741 0.834203 +0.420771 0.837634 +0.421122 0.840961 +0.421764 0.844146 +0.422662 0.847156 +0.423825 0.850074 +0.425296 0.852966 +0.427083 0.855788 +0.429185 0.858488 +0.431591 0.861018 +0.434280 0.863326 +0.437220 0.865366 +0.440370 0.867100 +0.443681 0.868498 +0.447100 0.869539 +0.450569 0.870216 +0.454033 0.870532 +0.457442 0.870502 +0.460747 0.870149 +0.463910 0.869502 +0.469799 0.867428 +0.472673 0.865947 +0.475475 0.864148 +0.478158 0.862033 +0.480671 0.859610 +0.482964 0.856904 +0.484991 0.853944 +0.486714 0.850773 +0.488102 0.847440 +0.489136 0.843999 +0.489809 0.840506 +0.490123 0.837019 +0.490093 0.833588 +0.489742 0.830261 +0.489100 0.827076 +0.488202 0.824066 +0.487039 0.821148 +0.485568 0.818256 +0.483781 0.815435 +0.481679 0.812734 +0.479273 0.810205 +0.476584 0.807897 +0.473644 0.805856 +0.470494 0.804122 +0.467183 0.802724 +0.463764 0.801683 +0.460295 0.801006 +0.456830 0.800690 + + + + + + + + + + + +

64 0 64 0 1 0 1 2 1 4 3 4 2 4 2 3 5 3 5 6 5 2 7 2 4 8 4 7 9 7 2 10 2 5 11 5 7 12 7 6 13 6 2 14 2 9 15 9 6 16 6 7 17 7 9 18 9 8 19 8 6 20 6 11 21 11 8 22 8 9 23 9 11 24 11 10 25 10 8 26 8 13 27 13 10 28 10 11 29 11 13 30 13 12 31 12 10 32 10 15 33 15 12 34 12 13 35 13 15 36 15 14 37 14 12 38 12 17 39 17 14 40 14 15 41 15 17 42 17 16 43 16 14 44 14 19 45 19 16 46 16 17 47 17 19 48 19 18 49 18 16 50 16 21 51 21 18 52 18 19 53 19 21 54 21 20 55 20 18 56 18 23 57 23 20 58 20 21 59 21 23 60 23 22 61 22 20 62 20 25 63 25 22 64 22 23 65 23 25 66 25 24 67 24 22 68 22 27 69 27 24 70 24 25 71 25 27 72 27 26 73 26 24 74 24 29 75 29 26 76 26 27 77 27 29 78 29 28 79 28 26 80 26 31 81 31 28 82 28 29 83 29 31 84 31 30 85 30 28 86 28 33 87 33 30 88 30 31 89 31 33 90 33 32 91 32 30 92 30 35 93 35 32 94 32 33 95 33 35 96 35 34 97 34 32 98 32 37 99 37 34 100 34 35 101 35 37 102 37 36 103 36 34 104 34 39 105 39 36 106 36 37 107 37 39 108 39 38 109 38 36 110 36 41 111 41 38 112 38 39 113 39 41 114 41 40 115 40 38 116 38 43 117 43 40 118 40 41 119 41 43 120 43 42 121 42 40 122 40 45 123 45 42 124 42 43 125 43 45 126 45 44 127 44 42 128 42 47 129 47 44 130 44 45 131 45 47 132 47 46 133 46 44 134 44 49 135 49 46 136 46 47 137 47 49 138 49 48 139 48 46 140 46 51 141 51 48 142 48 49 143 49 51 144 51 50 145 50 48 146 48 53 147 53 50 148 50 51 149 51 53 150 53 52 151 52 50 152 50 55 153 55 52 154 52 53 155 53 55 156 55 54 157 54 52 158 52 57 159 57 54 160 54 55 161 55 57 162 57 56 163 56 54 164 54 59 165 59 56 166 56 57 167 57 59 168 59 58 169 58 56 170 56 61 171 61 58 172 58 59 173 59 61 174 61 60 175 60 58 176 58 63 177 63 60 178 60 61 179 61 63 180 63 62 181 62 60 182 60 65 183 65 62 184 62 63 185 63 65 186 65 64 187 64 62 188 62 0 189 0 64 190 64 65 191 65 130 192 130 66 193 66 67 194 67 71 195 71 68 196 68 69 197 69 71 198 71 70 199 70 68 200 68 73 201 73 70 202 70 71 203 71 73 204 73 72 205 72 70 206 70 75 207 75 72 208 72 73 209 73 75 210 75 74 211 74 72 212 72 77 213 77 74 214 74 75 215 75 77 216 77 76 217 76 74 218 74 79 219 79 76 220 76 77 221 77 79 222 79 78 223 78 76 224 76 81 225 81 78 226 78 79 227 79 81 228 81 80 229 80 78 230 78 83 231 83 80 232 80 81 233 81 83 234 83 82 235 82 80 236 80 85 237 85 82 238 82 83 239 83 85 240 85 84 241 84 82 242 82 87 243 87 84 244 84 85 245 85 87 246 87 86 247 86 84 248 84 89 249 89 86 250 86 87 251 87 89 252 89 88 253 88 86 254 86 91 255 91 88 256 88 89 257 89 91 258 91 90 259 90 88 260 88 93 261 93 90 262 90 91 263 91 93 264 93 92 265 92 90 266 90 95 267 95 92 268 92 93 269 93 95 270 95 94 271 94 92 272 92 97 273 97 94 274 94 95 275 95 97 276 97 96 277 96 94 278 94 99 279 99 96 280 96 97 281 97 99 282 99 98 283 98 96 284 96 101 285 101 98 286 98 99 287 99 101 288 101 100 289 100 98 290 98 103 291 103 100 292 100 101 293 101 103 294 103 102 295 102 100 296 100 105 297 105 102 298 102 103 299 103 105 300 105 104 301 104 102 302 102 107 303 107 104 304 104 105 305 105 107 306 107 106 307 106 104 308 104 109 309 109 106 310 106 107 311 107 109 312 109 108 313 108 106 314 106 111 315 111 108 316 108 109 317 109 111 318 111 110 319 110 108 320 108 113 321 113 110 322 110 111 323 111 113 324 113 112 325 112 110 326 110 115 327 115 112 328 112 113 329 113 115 330 115 114 331 114 112 332 112 117 333 117 114 334 114 115 335 115 117 336 117 116 337 116 114 338 114 119 339 119 116 340 116 117 341 117 119 342 119 118 343 118 116 344 116 121 345 121 118 346 118 119 347 119 121 348 121 120 349 120 118 350 118 123 351 123 120 352 120 121 353 121 123 354 123 122 355 122 120 356 120 125 357 125 122 358 122 123 359 123 125 360 125 124 361 124 122 362 122 127 363 127 124 364 124 125 365 125 127 366 127 126 367 126 124 368 124 129 369 129 126 370 126 127 371 127 129 372 129 128 373 128 126 374 126 131 375 131 128 376 128 129 377 129 131 378 131 130 379 130 128 380 128 66 381 66 130 382 130 131 383 131 134 384 134 132 385 132 133 386 133 136 387 136 134 388 134 135 389 135 137 390 137 134 391 134 136 392 136 138 393 138 134 394 134 137 395 137 139 396 139 134 397 134 138 398 138 140 399 140 134 400 134 139 401 139 141 402 141 134 403 134 140 404 140 142 405 142 134 406 134 141 407 141 143 408 143 134 409 134 142 410 142 144 411 144 134 412 134 143 413 143 145 414 145 134 415 134 144 416 144 146 417 146 134 418 134 145 419 145 147 420 147 134 421 134 146 422 146 148 423 148 134 424 134 147 425 147 149 426 149 134 427 134 148 428 148 150 429 150 134 430 134 149 431 149 151 432 151 134 433 134 150 434 150 152 435 152 134 436 134 151 437 151 153 438 153 134 439 134 152 440 152 154 441 154 134 442 134 153 443 153 155 444 155 134 445 134 154 446 154 156 447 156 134 448 134 155 449 155 157 450 157 134 451 134 156 452 156 158 453 158 134 454 134 157 455 157 159 456 159 134 457 134 158 458 158 160 459 160 134 460 134 159 461 159 161 462 161 134 463 134 160 464 160 162 465 162 134 466 134 161 467 161 163 468 163 134 469 134 162 470 162 164 471 164 134 472 134 163 473 163 165 474 165 134 475 134 164 476 164 166 477 166 134 478 134 165 479 165 167 480 167 134 481 134 166 482 166 168 483 168 134 484 134 167 485 167 169 486 169 134 487 134 168 488 168 170 489 170 134 490 134 169 491 169 171 492 171 134 493 134 170 494 170 172 495 172 134 496 134 171 497 171 173 498 173 134 499 134 172 500 172 174 501 174 134 502 134 173 503 173 175 504 175 134 505 134 174 506 174 176 507 176 134 508 134 175 509 175 177 510 177 134 511 134 176 512 176 178 513 178 134 514 134 177 515 177 179 516 179 134 517 134 178 518 178 180 519 180 134 520 134 179 521 179 181 522 181 134 523 134 180 524 180 182 525 182 134 526 134 181 527 181 183 528 183 134 529 134 182 530 182 184 531 184 134 532 134 183 533 183 185 534 185 134 535 134 184 536 184 186 537 186 134 538 134 185 539 185 187 540 187 134 541 134 186 542 186 188 543 188 134 544 134 187 545 187 189 546 189 134 547 134 188 548 188 190 549 190 134 550 134 189 551 189 191 552 191 134 553 134 190 554 190 192 555 192 134 556 134 191 557 191 193 558 193 134 559 134 192 560 192 132 561 132 134 562 134 193 563 193 196 564 196 194 565 194 195 566 195 198 567 198 196 568 196 197 569 197 199 570 199 196 571 196 198 572 198 200 573 200 196 574 196 199 575 199 201 576 201 196 577 196 200 578 200 202 579 202 196 580 196 201 581 201 203 582 203 196 583 196 202 584 202 204 585 204 196 586 196 203 587 203 205 588 205 196 589 196 204 590 204 206 591 206 196 592 196 205 593 205 207 594 207 196 595 196 206 596 206 208 597 208 196 598 196 207 599 207 209 600 209 196 601 196 208 602 208 210 603 210 196 604 196 209 605 209 211 606 211 196 607 196 210 608 210 212 609 212 196 610 196 211 611 211 213 612 213 196 613 196 212 614 212 214 615 214 196 616 196 213 617 213 215 618 215 196 619 196 214 620 214 216 621 216 196 622 196 215 623 215 217 624 217 196 625 196 216 626 216 218 627 218 196 628 196 217 629 217 219 630 219 196 631 196 218 632 218 220 633 220 196 634 196 219 635 219 221 636 221 196 637 196 220 638 220 222 639 222 196 640 196 221 641 221 223 642 223 196 643 196 222 644 222 224 645 224 196 646 196 223 647 223 225 648 225 196 649 196 224 650 224 226 651 226 196 652 196 225 653 225 227 654 227 196 655 196 226 656 226 228 657 228 196 658 196 227 659 227 229 660 229 196 661 196 228 662 228 230 663 230 196 664 196 229 665 229 231 666 231 196 667 196 230 668 230 232 669 232 196 670 196 231 671 231 233 672 233 196 673 196 232 674 232 234 675 234 196 676 196 233 677 233 235 678 235 196 679 196 234 680 234 236 681 236 196 682 196 235 683 235 237 684 237 196 685 196 236 686 236 238 687 238 196 688 196 237 689 237 239 690 239 196 691 196 238 692 238 240 693 240 196 694 196 239 695 239 241 696 241 196 697 196 240 698 240 242 699 242 196 700 196 241 701 241 243 702 243 196 703 196 242 704 242 244 705 244 196 706 196 243 707 243 245 708 245 196 709 196 244 710 244 246 711 246 196 712 196 245 713 245 247 714 247 196 715 196 246 716 246 248 717 248 196 718 196 247 719 247 249 720 249 196 721 196 248 722 248 250 723 250 196 724 196 249 725 249 251 726 251 196 727 196 250 728 250 252 729 252 196 730 196 251 731 251 253 732 253 196 733 196 252 734 252 254 735 254 196 736 196 253 737 253 255 738 255 196 739 196 254 740 254 194 741 194 196 742 196 255 743 255

+
+
+ + + + +37.750000 0.000000 3.800000 +37.549999 0.000000 3.600000 +22.450001 0.000000 3.600000 +22.250000 0.000000 3.800000 +22.576044 -1.373821 3.600000 +22.980099 -2.779115 3.600000 +22.379383 -1.410214 3.800000 +22.794140 -2.852734 3.800000 +23.680683 -4.131433 3.600000 +23.513285 -4.240876 3.800000 +24.661345 -5.338656 3.600000 +24.519922 -5.480078 3.800000 +25.868567 -6.319316 3.600000 +25.759125 -6.486715 3.800000 +27.220884 -7.019902 3.600000 +27.147266 -7.205859 3.800000 +28.626179 -7.423955 3.600000 +28.589787 -7.620616 3.800000 +30.000000 -7.550000 3.600000 +30.000000 -7.750000 3.800000 +31.373821 -7.423955 3.600000 +31.410213 -7.620616 3.800000 +32.779114 -7.019902 3.600000 +32.852734 -7.205859 3.800000 +34.131435 -6.319316 3.600000 +34.240875 -6.486715 3.800000 +35.338657 -5.338656 3.600000 +35.480076 -5.480078 3.800000 +36.319317 -4.131433 3.600000 +36.486713 -4.240876 3.800000 +37.019901 -2.779115 3.600000 +37.205860 -2.852734 3.800000 +37.423954 -1.373821 3.600000 +37.620617 -1.410214 3.800000 +62.750000 0.000000 3.800000 +62.549999 0.000000 3.600000 +47.450001 0.000000 3.600000 +47.250000 0.000000 3.800000 +47.576046 -1.373821 3.600000 +47.379383 -1.410214 3.800000 +47.980099 -2.779115 3.600000 +47.794140 -2.852734 3.800000 +48.680683 -4.131433 3.600000 +48.513287 -4.240876 3.800000 +49.661343 -5.338656 3.600000 +49.519924 -5.480078 3.800000 +50.868565 -6.319316 3.600000 +52.220886 -7.019902 3.600000 +50.759125 -6.486715 3.800000 +52.147266 -7.205859 3.800000 +53.626179 -7.423955 3.600000 +53.589787 -7.620616 3.800000 +55.000000 -7.550000 3.600000 +55.000000 -7.750000 3.800000 +56.373821 -7.423955 3.600000 +56.410213 -7.620616 3.800000 +57.779114 -7.019902 3.600000 +57.852734 -7.205859 3.800000 +59.131435 -6.319316 3.600000 +59.240875 -6.486715 3.800000 +60.338657 -5.338656 3.600000 +60.480076 -5.480078 3.800000 +61.319317 -4.131433 3.600000 +61.486713 -4.240876 3.800000 +62.019901 -2.779115 3.600000 +62.205860 -2.852734 3.800000 +62.423954 -1.373821 3.600000 +62.620617 -1.410214 3.800000 +112.750000 0.000000 3.800000 +112.550003 0.000000 3.600000 +97.449997 0.000000 3.600000 +97.250000 0.000000 3.800000 +97.576042 -1.373821 3.600000 +97.379387 -1.410214 3.800000 +97.980095 -2.779115 3.600000 +97.794144 -2.852734 3.800000 +98.680687 -4.131433 3.600000 +98.513283 -4.240876 3.800000 +99.661346 -5.338656 3.600000 +99.519920 -5.480078 3.800000 +100.868568 -6.319316 3.600000 +102.220886 -7.019902 3.600000 +100.759125 -6.486715 3.800000 +102.147263 -7.205859 3.800000 +103.626183 -7.423955 3.600000 +103.589783 -7.620616 3.800000 +105.000000 -7.550000 3.600000 +105.000000 -7.750000 3.800000 +106.373817 -7.423955 3.600000 +106.410217 -7.620616 3.800000 +107.779114 -7.019902 3.600000 +107.852737 -7.205859 3.800000 +109.131432 -6.319316 3.600000 +109.240875 -6.486715 3.800000 +110.338654 -5.338656 3.600000 +110.480080 -5.480078 3.800000 +111.319313 -4.131433 3.600000 +111.486717 -4.240876 3.800000 +112.019905 -2.779115 3.600000 +112.205856 -2.852734 3.800000 +112.423958 -1.373821 3.600000 +112.620613 -1.410214 3.800000 +94.449997 -4.800000 3.800000 +94.250000 -4.800000 3.600000 +89.192574 -5.264006 3.600000 +89.150002 -4.800000 3.600000 +88.949997 -4.800000 3.800000 +88.995911 -5.300398 3.800000 +89.329041 -5.738642 3.600000 +89.143082 -5.812261 3.800000 +89.565659 -6.195385 3.600000 +89.398262 -6.304827 3.800000 +89.896881 -6.603122 3.600000 +89.755455 -6.744544 3.800000 +90.304619 -6.934339 3.600000 +90.195175 -7.101737 3.800000 +90.761360 -7.170960 3.600000 +90.687737 -7.356918 3.800000 +91.235992 -7.307429 3.600000 +91.199600 -7.504090 3.800000 +91.699997 -7.350000 3.600000 +91.699997 -7.550000 3.800000 +92.164009 -7.307429 3.600000 +92.200401 -7.504090 3.800000 +92.638641 -7.170960 3.600000 +92.712257 -7.356918 3.800000 +93.095383 -6.934339 3.600000 +93.204826 -7.101737 3.800000 +93.503120 -6.603122 3.600000 +93.644547 -6.744544 3.800000 +93.834335 -6.195385 3.600000 +94.001740 -6.304827 3.800000 +94.070961 -5.738642 3.600000 +94.256920 -5.812261 3.800000 +94.207428 -5.264006 3.600000 +94.404091 -5.300398 3.800000 +91.699997 7.000000 6.100000 +89.340065 5.236712 5.900000 +89.300003 4.800000 5.900000 +89.500000 4.800000 6.100000 +89.468506 5.683427 5.900000 +89.536728 5.200319 6.100000 +89.691208 6.113303 5.900000 +89.654465 5.609808 6.100000 +90.002945 6.497056 5.900000 +89.858612 6.003861 6.100000 +90.386696 6.808789 5.900000 +90.144363 6.355635 6.100000 +90.816574 7.031492 5.900000 +90.496140 6.641390 6.100000 +91.263290 7.159933 5.900000 +90.890190 6.845534 6.100000 +91.699997 7.200000 5.900000 +91.299683 6.963272 6.100000 +93.863274 5.200319 6.100000 +93.900002 4.800000 6.100000 +94.099998 4.800000 5.900000 +94.059937 5.236712 5.900000 +93.745537 5.609808 6.100000 +93.931496 5.683427 5.900000 +93.541389 6.003861 6.100000 +93.708786 6.113303 5.900000 +93.255638 6.355635 6.100000 +93.397057 6.497056 5.900000 +92.903862 6.641390 6.100000 +93.013306 6.808789 5.900000 +92.509811 6.845534 6.100000 +92.583427 7.031492 5.900000 +92.100319 6.963272 6.100000 +92.136711 7.159933 5.900000 +93.535782 4.800000 6.100000 +93.334023 4.800000 5.898239 +90.065979 4.800000 5.898239 +89.864220 4.800000 6.100000 +90.093262 4.502669 5.898239 +89.894867 4.465956 6.100000 +90.180710 4.198526 5.898239 +89.993111 4.124259 6.100000 +90.332336 3.905849 5.898239 +90.163460 3.795443 6.100000 +90.544571 3.644574 5.898239 +90.401909 3.501907 6.100000 +90.805847 3.432333 5.898239 +90.695442 3.263460 6.100000 +91.098526 3.280708 5.898239 +91.024261 3.093113 6.100000 +91.402672 3.193260 5.898239 +91.365959 2.994868 6.100000 +91.699997 3.165981 5.898239 +91.699997 2.964220 6.100000 +91.997330 3.193260 5.898239 +92.034042 2.994868 6.100000 +92.301476 3.280708 5.898239 +92.375740 3.093113 6.100000 +92.594154 3.432333 5.898239 +92.704559 3.263460 6.100000 +92.855423 3.644574 5.898239 +92.998093 3.501907 6.100000 +93.067665 3.905849 5.898239 +93.236542 3.795443 6.100000 +93.219292 4.198526 5.898239 +93.406883 4.124259 6.100000 +93.306740 4.502669 5.898239 +93.505135 4.465956 6.100000 +93.568283 4.454270 2.000000 +93.302597 4.800000 2.297405 +93.599998 4.800000 2.000000 +93.275841 4.508387 2.297405 +89.831718 4.454270 2.000000 +89.800003 4.800000 2.000000 +90.097404 4.800000 2.297405 +90.124161 4.508387 2.297405 +89.933403 4.100620 2.000000 +90.209923 4.210093 2.297405 +90.109711 3.760301 2.000000 +90.358635 3.923044 2.297405 +90.356499 3.456497 2.000000 +90.566795 3.666794 2.297405 +90.660301 3.209708 2.000000 +90.823044 3.458635 2.297405 +91.000618 3.033402 2.000000 +91.110092 3.309926 2.297405 +91.354271 2.931720 2.000000 +91.408386 3.224159 2.297405 +91.699997 2.900000 2.000000 +91.699997 3.197405 2.297405 +92.045731 2.931720 2.000000 +91.991615 3.224159 2.297405 +92.399384 3.033402 2.000000 +92.289909 3.309926 2.297405 +92.739700 3.209708 2.000000 +92.576958 3.458635 2.297405 +93.043503 3.456497 2.000000 +92.833206 3.666794 2.297405 +93.290291 3.760301 2.000000 +93.041367 3.923044 2.297405 +93.466599 4.100620 2.000000 +93.190071 4.210093 2.297405 +89.831718 -5.145730 2.000000 +89.800003 -4.800000 2.000000 +93.270691 -5.090660 2.302641 +93.297356 -4.800000 2.302641 +93.599998 -4.800000 2.000000 +93.185204 -5.387980 2.302641 +93.568283 -5.145730 2.000000 +93.036980 -5.674090 2.302641 +93.466599 -5.499380 2.000000 +92.829506 -5.929503 2.302641 +93.290291 -5.839698 2.000000 +92.574089 -6.136982 2.302641 +93.043503 -6.143503 2.000000 +92.287979 -6.285206 2.302641 +92.739700 -6.390292 2.000000 +91.990662 -6.370692 2.302641 +92.399384 -6.566598 2.000000 +92.045731 -6.668280 2.000000 +91.699997 -6.397359 2.302641 +91.409340 -6.370692 2.302641 +91.699997 -6.700000 2.000000 +91.112022 -6.285206 2.302641 +91.354271 -6.668280 2.000000 +90.825912 -6.136982 2.302641 +91.000618 -6.566598 2.000000 +90.660301 -6.390292 2.000000 +90.570496 -5.929503 2.302641 +90.356499 -6.143503 2.000000 +90.363014 -5.674090 2.302641 +90.214798 -5.387980 2.302641 +90.109711 -5.839698 2.000000 +90.129311 -5.090660 2.302641 +89.933403 -5.499380 2.000000 +90.102638 -4.800000 2.302641 +97.900002 0.000000 2.000000 +98.404404 0.000000 2.504402 +111.595596 0.000000 2.504402 +112.099998 0.000000 2.000000 +111.485489 -1.200155 2.504402 +111.132507 -2.427805 2.504402 +111.981468 -1.291938 2.000000 +111.601494 -2.613472 2.000000 +110.520485 -3.609176 2.504402 +110.942665 -3.885189 2.000000 +109.663795 -4.663792 2.504402 +108.609177 -5.520486 2.504402 +110.020454 -5.020458 2.000000 +108.885193 -5.942668 2.000000 +107.427803 -6.132510 2.504402 +107.613472 -6.601497 2.000000 +106.200157 -6.485487 2.504402 +106.291939 -6.981468 2.000000 +105.000000 -6.595598 2.504402 +105.000000 -7.100000 2.000000 +103.799843 -6.485487 2.504402 +103.708061 -6.981468 2.000000 +102.572197 -6.132510 2.504402 +102.386528 -6.601497 2.000000 +101.390823 -5.520486 2.504402 +101.114807 -5.942668 2.000000 +100.336205 -4.663792 2.504402 +99.979546 -5.020458 2.000000 +99.479515 -3.609176 2.504402 +99.057335 -3.885189 2.000000 +98.867493 -2.427805 2.504402 +98.398506 -2.613472 2.000000 +98.514511 -1.200155 2.504402 +98.018532 -1.291938 2.000000 +47.900002 0.000000 2.000000 +48.404404 0.000000 2.504402 +61.595596 0.000000 2.504402 +62.099998 0.000000 2.000000 +61.485489 -1.200155 2.504402 +61.132511 -2.427805 2.504402 +61.981468 -1.291938 2.000000 +61.601498 -2.613472 2.000000 +60.520485 -3.609176 2.504402 +60.942669 -3.885189 2.000000 +59.663792 -4.663792 2.504402 +60.020458 -5.020458 2.000000 +58.609177 -5.520486 2.504402 +58.885189 -5.942668 2.000000 +57.427803 -6.132510 2.504402 +57.613472 -6.601497 2.000000 +56.200153 -6.485487 2.504402 +56.291939 -6.981468 2.000000 +55.000000 -6.595598 2.504402 +55.000000 -7.100000 2.000000 +53.799847 -6.485487 2.504402 +53.708061 -6.981468 2.000000 +52.572197 -6.132510 2.504402 +52.386528 -6.601497 2.000000 +51.390823 -5.520486 2.504402 +51.114811 -5.942668 2.000000 +50.336208 -4.663792 2.504402 +49.979542 -5.020458 2.000000 +49.479515 -3.609176 2.504402 +49.057331 -3.885189 2.000000 +48.867489 -2.427805 2.504402 +48.398502 -2.613472 2.000000 +48.514511 -1.200155 2.504402 +48.018532 -1.291938 2.000000 +22.900000 0.000000 2.000000 +23.404402 0.000000 2.504402 +36.595596 0.000000 2.504402 +37.099998 0.000000 2.000000 +36.485489 -1.200155 2.504402 +36.132511 -2.427805 2.504402 +36.981468 -1.291938 2.000000 +36.601498 -2.613472 2.000000 +35.520485 -3.609176 2.504402 +35.942669 -3.885189 2.000000 +34.663792 -4.663792 2.504402 +35.020458 -5.020458 2.000000 +33.609177 -5.520486 2.504402 +33.885189 -5.942668 2.000000 +32.427803 -6.132510 2.504402 +32.613472 -6.601497 2.000000 +31.200155 -6.485487 2.504402 +31.291937 -6.981468 2.000000 +30.000000 -6.595598 2.504402 +30.000000 -7.100000 2.000000 +28.799845 -6.485487 2.504402 +28.708063 -6.981468 2.000000 +27.572195 -6.132510 2.504402 +27.386528 -6.601497 2.000000 +26.390825 -5.520486 2.504402 +26.114811 -5.942668 2.000000 +25.336208 -4.663792 2.504402 +24.979542 -5.020458 2.000000 +24.479513 -3.609176 2.504402 +24.057331 -3.885189 2.000000 +23.867491 -2.427805 2.504402 +23.398502 -2.613472 2.000000 +23.514513 -1.200155 2.504402 +23.018532 -1.291938 2.000000 +94.099998 4.800000 5.900000 +94.099998 4.800000 3.800000 +89.340065 5.236712 3.800000 +89.300003 4.800000 3.800000 +89.300003 4.800000 5.900000 +89.340065 5.236712 5.900000 +89.468506 5.683427 3.800000 +89.691208 6.113303 3.800000 +89.468506 5.683427 5.900000 +90.002945 6.497056 3.800000 +89.691208 6.113303 5.900000 +90.002945 6.497056 5.900000 +90.386696 6.808789 3.800000 +90.816574 7.031492 3.800000 +90.386696 6.808789 5.900000 +91.263290 7.159933 3.800000 +90.816574 7.031492 5.900000 +91.263290 7.159933 5.900000 +91.699997 7.200000 3.800000 +91.699997 7.200000 5.900000 +92.136711 7.159933 3.800000 +92.136711 7.159933 5.900000 +92.583427 7.031492 3.800000 +92.583427 7.031492 5.900000 +93.013306 6.808789 3.800000 +93.013306 6.808789 5.900000 +93.397057 6.497056 3.800000 +93.397057 6.497056 5.900000 +93.708786 6.113303 3.800000 +93.708786 6.113303 5.900000 +93.931496 5.683427 3.800000 +93.931496 5.683427 5.900000 +94.059937 5.236712 3.800000 +94.059937 5.236712 5.900000 +58.599697 -7.229767 4.861010 +58.576794 -7.114806 4.750000 +58.576794 -7.114806 3.800000 +58.579338 -7.153796 4.785039 +58.577660 -7.137560 3.800000 +58.587017 -7.192451 4.822354 +58.616989 -7.264806 3.800000 +58.616989 -7.264806 4.900000 +58.606358 -7.244668 3.800000 +58.587017 -7.192451 3.800000 +58.726795 6.854998 3.800000 +58.726795 6.854998 4.600000 +58.576794 7.114806 4.750000 +58.576794 7.114806 3.800000 +58.579208 7.076820 4.718311 +58.586666 7.038483 4.688838 +58.579556 7.074208 3.800000 +58.599300 7.000798 4.662520 +58.592773 7.018209 3.800000 +58.616989 6.964806 4.640193 +58.639317 6.931494 4.622507 +58.616989 6.964806 3.800000 +58.665634 6.901708 4.609871 +58.651127 6.917133 3.800000 +58.695107 6.876082 4.602415 +58.693016 6.877687 3.800000 +7.005025 0.494975 2.000000 +6.993918 0.506082 3.800000 +7.106427 0.771769 3.800000 +7.106474 0.777817 3.800000 +7.122182 0.777817 2.000000 +7.122133 0.771522 2.000000 +7.098054 0.697815 3.800000 +7.113419 0.694544 2.000000 +7.077222 0.630755 3.800000 +7.091734 0.624744 2.000000 +7.044535 0.568607 3.800000 +7.057711 0.560055 2.000000 +6.998161 0.510393 3.800000 +7.009442 0.499462 2.000000 +127.922775 0.924879 3.800000 +127.893524 0.777817 3.800000 +127.877815 0.777817 2.000000 +127.900177 0.849008 3.800000 +128.560654 1.060660 2.000000 +128.549545 1.049553 3.800000 +128.503372 1.108162 2.000000 +128.494507 1.095189 3.800000 +128.430893 1.147369 2.000000 +128.424881 1.132857 3.800000 +128.351913 1.170894 2.000000 +128.271515 1.177768 2.000000 +128.349014 1.155457 3.800000 +128.194550 1.169053 2.000000 +128.271774 1.162061 3.800000 +128.124741 1.147369 2.000000 +128.197815 1.153689 3.800000 +128.060059 1.113346 2.000000 +128.130753 1.132857 3.800000 +128.068604 1.100170 3.800000 +127.999458 1.065077 2.000000 +127.947472 1.003367 2.000000 +128.010391 1.053796 3.800000 +127.908264 0.930891 2.000000 +127.960449 0.994510 3.800000 +127.884743 0.851918 2.000000 +123.733521 -2.462444 3.800000 +123.075127 -0.818834 3.800000 +123.000000 0.000000 3.800000 +122.877777 0.000000 7.300000 +122.954941 -0.841074 7.300000 +123.315956 -1.656426 3.800000 +132.122223 0.000000 7.300000 +132.000000 0.000000 3.800000 +132.045059 -0.841074 7.300000 +131.924881 -0.818834 3.800000 +131.797684 -1.701416 7.300000 +131.684052 -1.656426 3.800000 +131.368774 -2.529325 7.300000 +131.266479 -2.462444 3.800000 +130.768402 -3.268405 7.300000 +130.681976 -3.181981 3.800000 +130.029327 -3.868780 7.300000 +129.962448 -3.766480 3.800000 +129.201416 -4.297688 7.300000 +129.156433 -4.184047 3.800000 +128.341080 -4.545056 7.300000 +128.318832 -4.424874 3.800000 +127.500000 -4.622223 7.300000 +127.500000 -4.500000 3.800000 +126.658928 -4.545056 7.300000 +126.681168 -4.424874 3.800000 +125.798584 -4.297688 7.300000 +124.970673 -3.868780 7.300000 +125.843575 -4.184047 3.800000 +125.037560 -3.766480 3.800000 +124.231598 -3.268405 7.300000 +124.318016 -3.181981 3.800000 +123.631218 -2.529325 7.300000 +123.202309 -1.701416 7.300000 +141.024994 0.000000 7.300000 +141.024994 0.000000 3.300000 +138.975006 0.000000 3.300000 +138.975006 0.000000 7.300000 +138.992111 -0.186512 3.300000 +138.992111 -0.186512 7.300000 +139.046967 -0.377297 3.300000 +139.046967 -0.377297 7.300000 +139.142075 -0.560890 3.300000 +139.142075 -0.560890 7.300000 +139.275223 -0.724784 3.300000 +139.275223 -0.724784 7.300000 +139.439117 -0.857920 3.300000 +139.439117 -0.857920 7.300000 +139.622696 -0.953033 3.300000 +139.622696 -0.953033 7.300000 +139.813492 -1.007888 3.300000 +139.813492 -1.007888 7.300000 +140.000000 -1.025000 3.300000 +140.000000 -1.025000 7.300000 +140.186508 -1.007888 3.300000 +140.186508 -1.007888 7.300000 +140.377304 -0.953033 3.300000 +140.377304 -0.953033 7.300000 +140.560883 -0.857920 3.300000 +140.560883 -0.857920 7.300000 +140.724777 -0.724784 3.300000 +140.724777 -0.724784 7.300000 +140.857925 -0.560890 3.300000 +140.857925 -0.560890 7.300000 +140.953033 -0.377297 3.300000 +140.953033 -0.377297 7.300000 +141.007889 -0.186512 3.300000 +141.007889 -0.186512 7.300000 +141.024994 0.000000 3.300000 +140.000000 0.000000 2.684118 +138.975006 0.000000 3.300000 +138.992111 -0.186512 3.300000 +139.046967 -0.377297 3.300000 +139.142075 -0.560890 3.300000 +139.275223 -0.724784 3.300000 +139.439117 -0.857920 3.300000 +139.622696 -0.953033 3.300000 +139.813492 -1.007888 3.300000 +140.000000 -1.025000 3.300000 +140.186508 -1.007888 3.300000 +140.377304 -0.953033 3.300000 +140.560883 -0.857920 3.300000 +140.724777 -0.724784 3.300000 +140.857925 -0.560890 3.300000 +140.953033 -0.377297 3.300000 +141.007889 -0.186512 3.300000 +140.000000 0.000000 2.684118 +140.000000 0.000000 2.684118 +140.000000 0.000000 2.684118 +140.000000 0.000000 2.684118 +140.000000 0.000000 2.684118 +140.000000 0.000000 2.684118 +140.000000 0.000000 2.684118 +140.000000 0.000000 2.684118 +140.000000 0.000000 2.684118 +140.000000 0.000000 2.684118 +140.000000 0.000000 2.684118 +140.000000 0.000000 2.684118 +140.000000 0.000000 2.684118 +140.000000 0.000000 2.684118 +140.000000 0.000000 2.684118 +140.000000 0.000000 2.684118 +12.122223 0.000000 7.300000 +12.000000 0.000000 3.800000 +3.000000 0.000000 3.800000 +2.877777 0.000000 7.300000 +3.075126 -0.818834 3.800000 +3.315953 -1.656426 3.800000 +2.954944 -0.841074 7.300000 +3.202312 -1.701416 7.300000 +3.733520 -2.462444 3.800000 +3.631220 -2.529325 7.300000 +4.318019 -3.181981 3.800000 +5.037556 -3.766480 3.800000 +4.231595 -3.268405 7.300000 +4.970675 -3.868780 7.300000 +5.843574 -4.184047 3.800000 +5.798584 -4.297688 7.300000 +6.681166 -4.424874 3.800000 +6.658926 -4.545056 7.300000 +7.500000 -4.500000 3.800000 +7.500000 -4.622223 7.300000 +8.318833 -4.424874 3.800000 +8.341074 -4.545056 7.300000 +9.156426 -4.184047 3.800000 +9.962444 -3.766480 3.800000 +9.201416 -4.297688 7.300000 +10.029325 -3.868780 7.300000 +10.681980 -3.181981 3.800000 +10.768405 -3.268405 7.300000 +11.266479 -2.462444 3.800000 +11.368779 -2.529325 7.300000 +11.684048 -1.656426 3.800000 +11.797688 -1.701416 7.300000 +11.924874 -0.818834 3.800000 +12.045056 -0.841074 7.300000 +12.800000 0.000000 7.300000 +12.830544 0.000000 3.800000 +7.930544 5.313128 3.800000 +7.900000 5.284884 7.300000 +8.788663 5.172431 3.800000 +8.781279 5.142794 7.300000 +9.800528 4.808562 3.800000 +9.787346 4.781009 7.300000 +10.684292 4.274925 3.800000 +11.409000 3.624143 3.800000 +10.666046 4.250430 7.300000 +12.003209 2.852334 3.800000 +11.386611 3.603367 7.300000 +12.468576 1.930791 3.800000 +11.977406 2.835990 7.300000 +12.440106 1.919727 7.300000 +12.754985 0.894335 3.800000 +12.724874 0.889210 7.300000 +-3.975000 0.000000 7.300000 +-3.975000 0.000000 3.300000 +-6.025000 0.000000 3.300000 +-6.025000 0.000000 7.300000 +-6.007888 -0.186512 3.300000 +-6.007888 -0.186512 7.300000 +-5.953033 -0.377297 3.300000 +-5.953033 -0.377297 7.300000 +-5.857920 -0.560890 3.300000 +-5.857920 -0.560890 7.300000 +-5.724784 -0.724784 3.300000 +-5.724784 -0.724784 7.300000 +-5.560890 -0.857920 3.300000 +-5.560890 -0.857920 7.300000 +-5.377297 -0.953033 3.300000 +-5.377297 -0.953033 7.300000 +-5.186512 -1.007888 3.300000 +-5.186512 -1.007888 7.300000 +-5.000000 -1.025000 3.300000 +-5.000000 -1.025000 7.300000 +-4.813488 -1.007888 3.300000 +-4.813488 -1.007888 7.300000 +-4.622703 -0.953033 3.300000 +-4.622703 -0.953033 7.300000 +-4.439110 -0.857920 3.300000 +-4.439110 -0.857920 7.300000 +-4.275216 -0.724784 3.300000 +-4.275216 -0.724784 7.300000 +-4.142080 -0.560890 3.300000 +-4.142080 -0.560890 7.300000 +-4.046967 -0.377297 3.300000 +-4.046967 -0.377297 7.300000 +-3.992112 -0.186512 3.300000 +-3.992112 -0.186512 7.300000 +-3.975000 0.000000 3.300000 +-5.000000 0.000000 2.684118 +-6.025000 0.000000 3.300000 +-6.007888 -0.186512 3.300000 +-5.953033 -0.377297 3.300000 +-5.857920 -0.560890 3.300000 +-5.724784 -0.724784 3.300000 +-5.560890 -0.857920 3.300000 +-5.377297 -0.953033 3.300000 +-5.186512 -1.007888 3.300000 +-5.000000 -1.025000 3.300000 +-4.813488 -1.007888 3.300000 +-4.622703 -0.953033 3.300000 +-4.439110 -0.857920 3.300000 +-4.275216 -0.724784 3.300000 +-4.142080 -0.560890 3.300000 +-4.046967 -0.377297 3.300000 +-3.992112 -0.186512 3.300000 +-5.000000 0.000000 2.684118 +-5.000000 0.000000 2.684118 +-5.000000 0.000000 2.684118 +-5.000000 0.000000 2.684118 +-5.000000 0.000000 2.684118 +-5.000000 0.000000 2.684118 +-5.000000 0.000000 2.684118 +-5.000000 0.000000 2.684118 +-5.000000 0.000000 2.684118 +-5.000000 0.000000 2.684118 +-5.000000 0.000000 2.684118 +-5.000000 0.000000 2.684118 +-5.000000 0.000000 2.684118 +-5.000000 0.000000 2.684118 +-5.000000 0.000000 2.684118 +-5.000000 0.000000 2.684118 +99.776794 -8.127241 5.800000 +99.776794 -8.127241 3.800000 +99.893013 -8.364360 3.800000 +99.926796 -8.387049 3.800000 +99.926796 -8.387049 5.800000 +99.893013 -8.364360 5.800000 +99.851128 -8.324914 3.800000 +99.851128 -8.324914 5.800000 +99.816986 -8.277242 3.800000 +99.816986 -8.277242 5.800000 +99.792770 -8.223838 3.800000 +99.792770 -8.223838 5.800000 +99.779556 -8.167839 3.800000 +99.779556 -8.167839 5.800000 +99.776794 8.127241 5.800000 +99.776794 8.127241 3.800000 +99.816986 7.977242 3.800000 +99.816986 7.977242 5.800000 +99.806358 7.997379 3.800000 +99.806358 7.997379 5.800000 +99.787018 8.049596 3.800000 +99.787018 8.049596 5.800000 +99.777657 8.104487 3.800000 +99.777657 8.104487 5.800000 +33.576794 -7.114806 4.750000 +33.576794 -7.114806 3.800000 +33.616989 -7.264806 3.800000 +33.616989 -7.264806 4.900000 +33.606358 -7.244668 3.800000 +33.587017 -7.192451 3.800000 +33.599697 -7.229767 4.861010 +33.587017 -7.192451 4.822354 +33.577660 -7.137560 3.800000 +33.579338 -7.153796 4.785039 +33.726795 6.854998 3.800000 +33.726795 6.854998 4.600000 +33.576794 7.114806 4.750000 +33.576794 7.114806 3.800000 +33.579208 7.076820 4.718311 +33.586666 7.038483 4.688838 +33.580013 7.070971 3.800000 +33.599300 7.000798 4.662520 +33.594028 7.014585 3.800000 +33.616989 6.964806 4.640193 +33.639317 6.931494 4.622507 +33.616989 6.964806 3.800000 +33.665634 6.901708 4.609871 +33.648621 6.920034 3.800000 +33.695107 6.876082 4.602415 +33.690441 6.879704 3.800000 +39.400002 0.000000 6.300000 +39.400002 0.000000 5.300000 +38.599998 0.000000 5.300000 +38.599998 0.000000 6.300000 +38.606678 -0.072785 5.300000 +38.606678 -0.072785 6.300000 +38.628086 -0.147238 5.300000 +38.665203 -0.218884 5.300000 +38.628086 -0.147238 6.300000 +38.665203 -0.218884 6.300000 +38.717155 -0.282843 5.300000 +38.717155 -0.282843 6.300000 +38.781116 -0.334798 5.300000 +38.781116 -0.334798 6.300000 +38.852760 -0.371915 5.300000 +38.852760 -0.371915 6.300000 +38.927216 -0.393322 5.300000 +38.927216 -0.393322 6.300000 +39.000000 -0.400000 5.300000 +39.000000 -0.400000 6.300000 +39.072784 -0.393322 5.300000 +39.072784 -0.393322 6.300000 +39.147240 -0.371915 5.300000 +39.147240 -0.371915 6.300000 +39.218884 -0.334798 5.300000 +39.218884 -0.334798 6.300000 +39.282845 -0.282843 5.300000 +39.282845 -0.282843 6.300000 +39.334797 -0.218884 5.300000 +39.334797 -0.218884 6.300000 +39.371914 -0.147238 5.300000 +39.371914 -0.147238 6.300000 +39.393322 -0.072785 5.300000 +39.393322 -0.072785 6.300000 +21.852762 -6.871915 6.300000 +21.606678 -6.572785 5.300000 +21.600000 -6.500000 5.300000 +21.600000 -6.500000 6.300000 +21.628084 -6.647238 5.300000 +21.606678 -6.572785 6.300000 +21.665201 -6.718884 5.300000 +21.628084 -6.647238 6.300000 +21.665201 -6.718884 6.300000 +21.717157 -6.782843 5.300000 +21.781116 -6.834798 5.300000 +21.717157 -6.782843 6.300000 +21.781116 -6.834798 6.300000 +21.852762 -6.871915 5.300000 +22.400000 -6.500000 6.300000 +22.400000 -6.500000 5.300000 +22.393322 -6.572785 6.300000 +22.393322 -6.572785 5.300000 +22.371916 -6.647238 6.300000 +22.371916 -6.647238 5.300000 +22.334799 -6.718884 6.300000 +22.334799 -6.718884 5.300000 +22.282843 -6.782843 6.300000 +22.282843 -6.782843 5.300000 +22.218884 -6.834798 6.300000 +22.218884 -6.834798 5.300000 +22.147238 -6.871915 6.300000 +22.147238 -6.871915 5.300000 +22.072784 -6.893322 6.300000 +22.072784 -6.893322 5.300000 +22.000000 -6.900000 6.300000 +22.000000 -6.900000 5.300000 +21.927216 -6.893322 6.300000 +21.927216 -6.893322 5.300000 +21.628084 6.352762 6.300000 +21.600000 6.500000 5.300000 +21.600000 6.500000 6.300000 +21.606678 6.427215 5.300000 +21.628084 6.352762 5.300000 +21.606678 6.427215 6.300000 +22.393322 6.427215 6.300000 +22.400000 6.500000 6.300000 +22.400000 6.500000 5.300000 +22.393322 6.427215 5.300000 +22.371916 6.352762 6.300000 +22.371916 6.352762 5.300000 +22.334799 6.281116 6.300000 +22.334799 6.281116 5.300000 +22.282843 6.217157 6.300000 +22.282843 6.217157 5.300000 +22.218884 6.165202 6.300000 +22.218884 6.165202 5.300000 +22.147238 6.128085 6.300000 +22.147238 6.128085 5.300000 +22.072784 6.106678 6.300000 +22.072784 6.106678 5.300000 +22.000000 6.100000 6.300000 +22.000000 6.100000 5.300000 +21.927216 6.106678 6.300000 +21.927216 6.106678 5.300000 +21.852762 6.128085 6.300000 +21.852762 6.128085 5.300000 +21.781116 6.165202 6.300000 +21.781116 6.165202 5.300000 +21.717157 6.217157 6.300000 +21.717157 6.217157 5.300000 +21.665201 6.281116 6.300000 +21.665201 6.281116 5.300000 +63.400002 -6.500000 6.300000 +63.400002 -6.500000 5.300000 +62.606678 -6.572785 5.300000 +62.599998 -6.500000 5.300000 +62.599998 -6.500000 6.300000 +62.606678 -6.572785 6.300000 +62.628086 -6.647238 5.300000 +62.628086 -6.647238 6.300000 +62.665203 -6.718884 5.300000 +62.665203 -6.718884 6.300000 +62.717155 -6.782843 5.300000 +62.717155 -6.782843 6.300000 +62.781116 -6.834798 5.300000 +62.781116 -6.834798 6.300000 +62.852760 -6.871915 5.300000 +62.852760 -6.871915 6.300000 +62.927216 -6.893322 5.300000 +62.927216 -6.893322 6.300000 +63.000000 -6.900000 5.300000 +63.000000 -6.900000 6.300000 +63.072784 -6.893322 5.300000 +63.072784 -6.893322 6.300000 +63.147240 -6.871915 5.300000 +63.147240 -6.871915 6.300000 +63.218884 -6.834798 5.300000 +63.218884 -6.834798 6.300000 +63.282845 -6.782843 5.300000 +63.282845 -6.782843 6.300000 +63.334797 -6.718884 5.300000 +63.334797 -6.718884 6.300000 +63.371914 -6.647238 5.300000 +63.371914 -6.647238 6.300000 +63.393322 -6.572785 5.300000 +63.393322 -6.572785 6.300000 +62.628086 6.352762 6.300000 +62.606678 6.427215 5.300000 +62.599998 6.500000 5.300000 +62.599998 6.500000 6.300000 +62.628086 6.352762 5.300000 +62.606678 6.427215 6.300000 +63.400002 6.500000 6.300000 +63.400002 6.500000 5.300000 +63.393322 6.427215 6.300000 +63.393322 6.427215 5.300000 +63.371914 6.352762 6.300000 +63.334797 6.281116 6.300000 +63.371914 6.352762 5.300000 +63.282845 6.217157 6.300000 +63.334797 6.281116 5.300000 +63.282845 6.217157 5.300000 +63.218884 6.165202 6.300000 +63.147240 6.128085 6.300000 +63.218884 6.165202 5.300000 +63.147240 6.128085 5.300000 +63.072784 6.106678 6.300000 +63.072784 6.106678 5.300000 +63.000000 6.100000 6.300000 +63.000000 6.100000 5.300000 +62.927216 6.106678 6.300000 +62.927216 6.106678 5.300000 +62.852760 6.128085 6.300000 +62.852760 6.128085 5.300000 +62.781116 6.165202 6.300000 +62.781116 6.165202 5.300000 +62.717155 6.217157 6.300000 +62.717155 6.217157 5.300000 +62.665203 6.281116 6.300000 +62.665203 6.281116 5.300000 +84.106674 -6.572785 6.300000 +84.106674 -6.572785 5.300000 +84.099998 -6.500000 5.300000 +84.099998 -6.500000 6.300000 +84.893326 -6.572785 6.300000 +84.900002 -6.500000 6.300000 +84.900002 -6.500000 5.300000 +84.893326 -6.572785 5.300000 +84.871918 -6.647238 6.300000 +84.871918 -6.647238 5.300000 +84.834801 -6.718884 6.300000 +84.834801 -6.718884 5.300000 +84.782845 -6.782843 6.300000 +84.782845 -6.782843 5.300000 +84.718887 -6.834798 6.300000 +84.647240 -6.871915 6.300000 +84.718887 -6.834798 5.300000 +84.647240 -6.871915 5.300000 +84.572784 -6.893322 6.300000 +84.572784 -6.893322 5.300000 +84.500000 -6.900000 6.300000 +84.500000 -6.900000 5.300000 +84.427216 -6.893322 6.300000 +84.427216 -6.893322 5.300000 +84.352760 -6.871915 6.300000 +84.352760 -6.871915 5.300000 +84.281113 -6.834798 6.300000 +84.281113 -6.834798 5.300000 +84.217155 -6.782843 6.300000 +84.165199 -6.718884 6.300000 +84.217155 -6.782843 5.300000 +84.165199 -6.718884 5.300000 +84.128082 -6.647238 6.300000 +84.128082 -6.647238 5.300000 +84.128082 6.352762 5.300000 +84.099998 6.500000 5.300000 +84.099998 6.500000 6.300000 +84.106674 6.427215 5.300000 +84.900002 6.500000 6.300000 +84.900002 6.500000 5.300000 +84.893326 6.427215 6.300000 +84.893326 6.427215 5.300000 +84.871918 6.352762 6.300000 +84.871918 6.352762 5.300000 +84.834801 6.281116 6.300000 +84.834801 6.281116 5.300000 +84.782845 6.217157 6.300000 +84.782845 6.217157 5.300000 +84.718887 6.165202 6.300000 +84.718887 6.165202 5.300000 +84.647240 6.128085 6.300000 +84.647240 6.128085 5.300000 +84.572784 6.106678 6.300000 +84.572784 6.106678 5.300000 +84.500000 6.100000 6.300000 +84.500000 6.100000 5.300000 +84.427216 6.106678 6.300000 +84.427216 6.106678 5.300000 +84.352760 6.128085 6.300000 +84.352760 6.128085 5.300000 +84.281113 6.165202 6.300000 +84.281113 6.165202 5.300000 +84.217155 6.217157 6.300000 +84.217155 6.217157 5.300000 +84.165199 6.281116 6.300000 +84.165199 6.281116 5.300000 +84.128082 6.352762 6.300000 +84.106674 6.427215 6.300000 +112.781113 -6.834798 6.300000 +112.606674 -6.572785 5.300000 +112.599998 -6.500000 5.300000 +112.599998 -6.500000 6.300000 +112.628082 -6.647238 5.300000 +112.606674 -6.572785 6.300000 +112.628082 -6.647238 6.300000 +112.665199 -6.718884 5.300000 +112.717155 -6.782843 5.300000 +112.665199 -6.718884 6.300000 +112.717155 -6.782843 6.300000 +112.781113 -6.834798 5.300000 +113.400002 -6.500000 6.300000 +113.400002 -6.500000 5.300000 +113.393326 -6.572785 6.300000 +113.393326 -6.572785 5.300000 +113.371918 -6.647238 6.300000 +113.371918 -6.647238 5.300000 +113.334801 -6.718884 6.300000 +113.282845 -6.782843 6.300000 +113.334801 -6.718884 5.300000 +113.218887 -6.834798 6.300000 +113.282845 -6.782843 5.300000 +113.218887 -6.834798 5.300000 +113.147240 -6.871915 6.300000 +113.147240 -6.871915 5.300000 +113.072784 -6.893322 6.300000 +113.072784 -6.893322 5.300000 +113.000000 -6.900000 6.300000 +113.000000 -6.900000 5.300000 +112.927216 -6.893322 6.300000 +112.927216 -6.893322 5.300000 +112.852760 -6.871915 6.300000 +112.852760 -6.871915 5.300000 +112.628082 6.352762 6.300000 +112.599998 6.500000 5.300000 +112.599998 6.500000 6.300000 +112.606674 6.427215 5.300000 +112.628082 6.352762 5.300000 +112.606674 6.427215 6.300000 +113.400002 6.500000 6.300000 +113.400002 6.500000 5.300000 +113.393326 6.427215 6.300000 +113.393326 6.427215 5.300000 +113.371918 6.352762 6.300000 +113.371918 6.352762 5.300000 +113.334801 6.281116 6.300000 +113.334801 6.281116 5.300000 +113.282845 6.217157 6.300000 +113.282845 6.217157 5.300000 +113.218887 6.165202 6.300000 +113.147240 6.128085 6.300000 +113.218887 6.165202 5.300000 +113.147240 6.128085 5.300000 +113.072784 6.106678 6.300000 +113.072784 6.106678 5.300000 +113.000000 6.100000 6.300000 +113.000000 6.100000 5.300000 +112.927216 6.106678 6.300000 +112.927216 6.106678 5.300000 +112.852760 6.128085 6.300000 +112.852760 6.128085 5.300000 +112.781113 6.165202 6.300000 +112.781113 6.165202 5.300000 +112.717155 6.217157 6.300000 +112.717155 6.217157 5.300000 +112.665199 6.281116 6.300000 +112.665199 6.281116 5.300000 +40.000000 0.000000 6.300000 +40.000000 0.000000 3.800000 +38.016693 0.181963 3.800000 +38.000000 0.000000 3.800000 +38.000000 0.000000 6.300000 +38.016693 0.181963 6.300000 +38.070213 0.368095 3.800000 +38.070213 0.368095 6.300000 +38.163006 0.547210 3.800000 +38.163006 0.547210 6.300000 +38.292892 0.707107 3.800000 +38.292892 0.707107 6.300000 +38.452789 0.836995 3.800000 +38.452789 0.836995 6.300000 +38.631905 0.929788 3.800000 +38.631905 0.929788 6.300000 +38.818035 0.983305 3.800000 +38.818035 0.983305 6.300000 +39.000000 1.000000 3.800000 +39.000000 1.000000 6.300000 +39.181965 0.983305 3.800000 +39.181965 0.983305 6.300000 +39.368095 0.929788 3.800000 +39.368095 0.929788 6.300000 +39.547211 0.836995 3.800000 +39.547211 0.836995 6.300000 +39.707108 0.707107 3.800000 +39.707108 0.707107 6.300000 +39.836994 0.547210 3.800000 +39.836994 0.547210 6.300000 +39.929787 0.368095 3.800000 +39.929787 0.368095 6.300000 +39.983307 0.181963 3.800000 +39.983307 0.181963 6.300000 +22.983305 -6.318037 3.800000 +22.983305 -6.318037 6.300000 +23.000000 -6.500000 6.300000 +23.000000 -6.500000 3.800000 +21.000000 -6.500000 3.800000 +21.000000 -6.500000 6.300000 +21.016695 -6.318037 3.800000 +21.016695 -6.318037 6.300000 +21.070211 -6.131905 3.800000 +21.070211 -6.131905 6.300000 +21.163004 -5.952790 3.800000 +21.163004 -5.952790 6.300000 +21.292892 -5.792893 3.800000 +21.292892 -5.792893 6.300000 +21.452789 -5.663004 3.800000 +21.631905 -5.570212 3.800000 +21.452789 -5.663004 6.300000 +21.631905 -5.570212 6.300000 +21.818037 -5.516695 3.800000 +22.000000 -5.500000 3.800000 +21.818037 -5.516695 6.300000 +22.000000 -5.500000 6.300000 +22.181963 -5.516695 3.800000 +22.181963 -5.516695 6.300000 +22.368095 -5.570212 3.800000 +22.368095 -5.570212 6.300000 +22.547211 -5.663004 3.800000 +22.547211 -5.663004 6.300000 +22.707108 -5.792893 3.800000 +22.707108 -5.792893 6.300000 +22.836996 -5.952790 3.800000 +22.836996 -5.952790 6.300000 +22.929789 -6.131905 3.800000 +22.929789 -6.131905 6.300000 +62.000000 -6.500000 3.800000 +62.000000 -6.500000 6.300000 +63.983307 -6.318037 6.300000 +64.000000 -6.500000 6.300000 +64.000000 -6.500000 3.800000 +63.983307 -6.318037 3.800000 +63.929787 -6.131905 6.300000 +63.929787 -6.131905 3.800000 +63.836994 -5.952790 6.300000 +63.836994 -5.952790 3.800000 +63.707108 -5.792893 6.300000 +63.707108 -5.792893 3.800000 +63.547211 -5.663004 6.300000 +63.368095 -5.570212 6.300000 +63.547211 -5.663004 3.800000 +63.368095 -5.570212 3.800000 +63.181965 -5.516695 6.300000 +63.181965 -5.516695 3.800000 +63.000000 -5.500000 6.300000 +63.000000 -5.500000 3.800000 +62.818035 -5.516695 6.300000 +62.818035 -5.516695 3.800000 +62.631905 -5.570212 6.300000 +62.631905 -5.570212 3.800000 +62.452789 -5.663004 6.300000 +62.452789 -5.663004 3.800000 +62.292892 -5.792893 6.300000 +62.292892 -5.792893 3.800000 +62.163006 -5.952790 6.300000 +62.163006 -5.952790 3.800000 +62.070213 -6.131905 6.300000 +62.070213 -6.131905 3.800000 +62.016693 -6.318037 6.300000 +62.016693 -6.318037 3.800000 +62.016693 6.681963 6.300000 +62.016693 6.681963 3.800000 +62.000000 6.500000 3.800000 +62.000000 6.500000 6.300000 +64.000000 6.500000 6.300000 +64.000000 6.500000 3.800000 +63.983307 6.681963 6.300000 +63.983307 6.681963 3.800000 +63.929787 6.868095 6.300000 +63.929787 6.868095 3.800000 +63.836994 7.047210 6.300000 +63.836994 7.047210 3.800000 +63.707108 7.207107 6.300000 +63.707108 7.207107 3.800000 +63.547211 7.336996 6.300000 +63.368095 7.429788 6.300000 +63.547211 7.336996 3.800000 +63.181965 7.483305 6.300000 +63.368095 7.429788 3.800000 +63.181965 7.483305 3.800000 +63.000000 7.500000 6.300000 +63.000000 7.500000 3.800000 +62.818035 7.483305 6.300000 +62.631905 7.429788 6.300000 +62.818035 7.483305 3.800000 +62.631905 7.429788 3.800000 +62.452789 7.336996 6.300000 +62.452789 7.336996 3.800000 +62.292892 7.207107 6.300000 +62.292892 7.207107 3.800000 +62.163006 7.047210 6.300000 +62.163006 7.047210 3.800000 +62.070213 6.868095 6.300000 +62.070213 6.868095 3.800000 +21.000000 6.500000 3.800000 +21.000000 6.500000 6.300000 +22.983305 6.681963 6.300000 +23.000000 6.500000 6.300000 +23.000000 6.500000 3.800000 +22.983305 6.681963 3.800000 +22.929789 6.868095 6.300000 +22.929789 6.868095 3.800000 +22.836996 7.047210 6.300000 +22.707108 7.207107 6.300000 +22.836996 7.047210 3.800000 +22.707108 7.207107 3.800000 +22.547211 7.336996 6.300000 +22.547211 7.336996 3.800000 +22.368095 7.429788 6.300000 +22.181963 7.483305 6.300000 +22.368095 7.429788 3.800000 +22.000000 7.500000 6.300000 +22.181963 7.483305 3.800000 +22.000000 7.500000 3.800000 +21.818037 7.483305 6.300000 +21.818037 7.483305 3.800000 +21.631905 7.429788 6.300000 +21.631905 7.429788 3.800000 +21.452789 7.336996 6.300000 +21.292892 7.207107 6.300000 +21.452789 7.336996 3.800000 +21.292892 7.207107 3.800000 +21.163004 7.047210 6.300000 +21.163004 7.047210 3.800000 +21.070211 6.868095 6.300000 +21.070211 6.868095 3.800000 +21.016695 6.681963 6.300000 +21.016695 6.681963 3.800000 +85.483307 -6.318037 3.800000 +85.483307 -6.318037 6.300000 +85.500000 -6.500000 6.300000 +85.500000 -6.500000 3.800000 +83.500000 -6.500000 3.800000 +83.500000 -6.500000 6.300000 +83.516693 -6.318037 3.800000 +83.516693 -6.318037 6.300000 +83.570213 -6.131905 3.800000 +83.570213 -6.131905 6.300000 +83.663002 -5.952790 3.800000 +83.663002 -5.952790 6.300000 +83.792892 -5.792893 3.800000 +83.792892 -5.792893 6.300000 +83.952789 -5.663004 3.800000 +84.131905 -5.570212 3.800000 +83.952789 -5.663004 6.300000 +84.131905 -5.570212 6.300000 +84.318039 -5.516695 3.800000 +84.318039 -5.516695 6.300000 +84.500000 -5.500000 3.800000 +84.500000 -5.500000 6.300000 +84.681961 -5.516695 3.800000 +84.681961 -5.516695 6.300000 +84.868095 -5.570212 3.800000 +85.047211 -5.663004 3.800000 +84.868095 -5.570212 6.300000 +85.047211 -5.663004 6.300000 +85.207108 -5.792893 3.800000 +85.207108 -5.792893 6.300000 +85.336998 -5.952790 3.800000 +85.336998 -5.952790 6.300000 +85.429787 -6.131905 3.800000 +85.429787 -6.131905 6.300000 +113.983307 -6.318037 3.800000 +114.000000 -6.500000 6.300000 +114.000000 -6.500000 3.800000 +113.983307 -6.318037 6.300000 +112.000000 -6.500000 3.800000 +112.000000 -6.500000 6.300000 +112.016693 -6.318037 3.800000 +112.016693 -6.318037 6.300000 +112.070213 -6.131905 3.800000 +112.070213 -6.131905 6.300000 +112.163002 -5.952790 3.800000 +112.163002 -5.952790 6.300000 +112.292892 -5.792893 3.800000 +112.292892 -5.792893 6.300000 +112.452789 -5.663004 3.800000 +112.452789 -5.663004 6.300000 +112.631905 -5.570212 3.800000 +112.631905 -5.570212 6.300000 +112.818039 -5.516695 3.800000 +112.818039 -5.516695 6.300000 +113.000000 -5.500000 3.800000 +113.000000 -5.500000 6.300000 +113.181961 -5.516695 3.800000 +113.368095 -5.570212 3.800000 +113.181961 -5.516695 6.300000 +113.368095 -5.570212 6.300000 +113.547211 -5.663004 3.800000 +113.547211 -5.663004 6.300000 +113.707108 -5.792893 3.800000 +113.707108 -5.792893 6.300000 +113.836998 -5.952790 3.800000 +113.836998 -5.952790 6.300000 +113.929787 -6.131905 3.800000 +113.929787 -6.131905 6.300000 +114.000000 6.500000 6.300000 +114.000000 6.500000 3.800000 +112.016693 6.681963 3.800000 +112.000000 6.500000 3.800000 +112.000000 6.500000 6.300000 +112.016693 6.681963 6.300000 +112.070213 6.868095 3.800000 +112.070213 6.868095 6.300000 +112.163002 7.047210 3.800000 +112.163002 7.047210 6.300000 +112.292892 7.207107 3.800000 +112.292892 7.207107 6.300000 +112.452789 7.336996 3.800000 +112.452789 7.336996 6.300000 +112.631905 7.429788 3.800000 +112.631905 7.429788 6.300000 +112.818039 7.483305 3.800000 +112.818039 7.483305 6.300000 +113.000000 7.500000 3.800000 +113.000000 7.500000 6.300000 +113.181961 7.483305 3.800000 +113.181961 7.483305 6.300000 +113.368095 7.429788 3.800000 +113.368095 7.429788 6.300000 +113.547211 7.336996 3.800000 +113.547211 7.336996 6.300000 +113.707108 7.207107 3.800000 +113.707108 7.207107 6.300000 +113.836998 7.047210 3.800000 +113.836998 7.047210 6.300000 +113.929787 6.868095 3.800000 +113.929787 6.868095 6.300000 +113.983307 6.681963 3.800000 +113.983307 6.681963 6.300000 +83.500000 6.500000 3.800000 +83.500000 6.500000 6.300000 +85.483307 6.681963 6.300000 +85.500000 6.500000 6.300000 +85.500000 6.500000 3.800000 +85.483307 6.681963 3.800000 +85.429787 6.868095 6.300000 +85.429787 6.868095 3.800000 +85.336998 7.047210 6.300000 +85.336998 7.047210 3.800000 +85.207108 7.207107 6.300000 +85.207108 7.207107 3.800000 +85.047211 7.336996 6.300000 +85.047211 7.336996 3.800000 +84.868095 7.429788 6.300000 +84.868095 7.429788 3.800000 +84.681961 7.483305 6.300000 +84.681961 7.483305 3.800000 +84.500000 7.500000 6.300000 +84.500000 7.500000 3.800000 +84.318039 7.483305 6.300000 +84.131905 7.429788 6.300000 +84.318039 7.483305 3.800000 +84.131905 7.429788 3.800000 +83.952789 7.336996 6.300000 +83.952789 7.336996 3.800000 +83.792892 7.207107 6.300000 +83.792892 7.207107 3.800000 +83.663002 7.047210 6.300000 +83.663002 7.047210 3.800000 +83.570213 6.868095 6.300000 +83.570213 6.868095 3.800000 +83.516693 6.681963 6.300000 +83.516693 6.681963 3.800000 +94.250000 -4.800000 3.600000 +94.250000 -4.800000 2.700000 +89.150002 -4.800000 2.700000 +89.150002 -4.800000 3.600000 +89.192574 -5.264006 2.700000 +89.192574 -5.264006 3.600000 +89.329041 -5.738642 2.700000 +89.329041 -5.738642 3.600000 +89.565659 -6.195385 2.700000 +89.896881 -6.603122 2.700000 +89.565659 -6.195385 3.600000 +89.896881 -6.603122 3.600000 +90.304619 -6.934339 2.700000 +90.304619 -6.934339 3.600000 +90.761360 -7.170960 2.700000 +90.761360 -7.170960 3.600000 +91.235992 -7.307429 2.700000 +91.235992 -7.307429 3.600000 +91.699997 -7.350000 2.700000 +91.699997 -7.350000 3.600000 +92.164009 -7.307429 2.700000 +92.164009 -7.307429 3.600000 +92.638641 -7.170960 2.700000 +92.638641 -7.170960 3.600000 +93.095383 -6.934339 2.700000 +93.095383 -6.934339 3.600000 +93.503120 -6.603122 2.700000 +93.503120 -6.603122 3.600000 +93.834335 -6.195385 2.700000 +93.834335 -6.195385 3.600000 +94.070961 -5.738642 2.700000 +94.070961 -5.738642 3.600000 +94.207428 -5.264006 2.700000 +94.207428 -5.264006 3.600000 +90.065979 4.800000 5.898239 +90.097404 4.800000 2.297405 +93.302597 4.800000 2.297405 +93.334023 4.800000 5.898239 +93.275841 5.091613 2.297405 +93.306740 5.097331 5.898239 +93.190071 5.389907 2.297405 +93.219292 5.401474 5.898239 +93.041367 5.676956 2.297405 +93.067665 5.694151 5.898239 +92.833206 5.933206 2.297405 +92.855423 5.955426 5.898239 +92.576958 6.141365 2.297405 +92.594154 6.167667 5.898239 +92.289909 6.290074 2.297405 +92.301476 6.319292 5.898239 +91.991615 6.375841 2.297405 +91.997330 6.406740 5.898239 +91.699997 6.402596 2.297405 +91.699997 6.434020 5.898239 +91.408386 6.375841 2.297405 +91.402672 6.406740 5.898239 +91.110092 6.290074 2.297405 +91.098526 6.319292 5.898239 +90.823044 6.141365 2.297405 +90.805847 6.167667 5.898239 +90.566795 5.933206 2.297405 +90.544571 5.955426 5.898239 +90.358635 5.676956 2.297405 +90.332336 5.694151 5.898239 +90.209923 5.389907 2.297405 +90.180710 5.401474 5.898239 +90.124161 5.091613 2.297405 +90.093262 5.097331 5.898239 +112.550003 0.000000 3.600000 +112.550003 0.000000 2.700000 +97.449997 0.000000 2.700000 +97.449997 0.000000 3.600000 +97.576042 -1.373821 2.700000 +97.576042 -1.373821 3.600000 +97.980095 -2.779115 2.700000 +97.980095 -2.779115 3.600000 +98.680687 -4.131433 2.700000 +98.680687 -4.131433 3.600000 +99.661346 -5.338656 2.700000 +99.661346 -5.338656 3.600000 +100.868568 -6.319316 2.700000 +100.868568 -6.319316 3.600000 +102.220886 -7.019902 2.700000 +102.220886 -7.019902 3.600000 +103.626183 -7.423955 2.700000 +103.626183 -7.423955 3.600000 +105.000000 -7.550000 2.700000 +105.000000 -7.550000 3.600000 +106.373817 -7.423955 2.700000 +106.373817 -7.423955 3.600000 +107.779114 -7.019902 2.700000 +107.779114 -7.019902 3.600000 +109.131432 -6.319316 2.700000 +109.131432 -6.319316 3.600000 +110.338654 -5.338656 2.700000 +110.338654 -5.338656 3.600000 +111.319313 -4.131433 2.700000 +111.319313 -4.131433 3.600000 +112.019905 -2.779115 2.700000 +112.019905 -2.779115 3.600000 +112.423958 -1.373821 2.700000 +112.423958 -1.373821 3.600000 +62.549999 0.000000 3.600000 +62.549999 0.000000 2.700000 +47.450001 0.000000 2.700000 +47.450001 0.000000 3.600000 +47.576046 -1.373821 2.700000 +47.576046 -1.373821 3.600000 +47.980099 -2.779115 2.700000 +47.980099 -2.779115 3.600000 +48.680683 -4.131433 2.700000 +48.680683 -4.131433 3.600000 +49.661343 -5.338656 2.700000 +49.661343 -5.338656 3.600000 +50.868565 -6.319316 2.700000 +50.868565 -6.319316 3.600000 +52.220886 -7.019902 2.700000 +52.220886 -7.019902 3.600000 +53.626179 -7.423955 2.700000 +53.626179 -7.423955 3.600000 +55.000000 -7.550000 2.700000 +55.000000 -7.550000 3.600000 +56.373821 -7.423955 2.700000 +56.373821 -7.423955 3.600000 +57.779114 -7.019902 2.700000 +57.779114 -7.019902 3.600000 +59.131435 -6.319316 2.700000 +59.131435 -6.319316 3.600000 +60.338657 -5.338656 2.700000 +60.338657 -5.338656 3.600000 +61.319317 -4.131433 2.700000 +61.319317 -4.131433 3.600000 +62.019901 -2.779115 2.700000 +62.019901 -2.779115 3.600000 +62.423954 -1.373821 2.700000 +62.423954 -1.373821 3.600000 +37.549999 0.000000 3.600000 +37.549999 0.000000 2.700000 +22.450001 0.000000 2.700000 +22.450001 0.000000 3.600000 +22.576044 -1.373821 2.700000 +22.576044 -1.373821 3.600000 +22.980099 -2.779115 2.700000 +22.980099 -2.779115 3.600000 +23.680683 -4.131433 2.700000 +23.680683 -4.131433 3.600000 +24.661345 -5.338656 2.700000 +24.661345 -5.338656 3.600000 +25.868567 -6.319316 2.700000 +25.868567 -6.319316 3.600000 +27.220884 -7.019902 2.700000 +27.220884 -7.019902 3.600000 +28.626179 -7.423955 2.700000 +28.626179 -7.423955 3.600000 +30.000000 -7.550000 2.700000 +30.000000 -7.550000 3.600000 +31.373821 -7.423955 2.700000 +31.373821 -7.423955 3.600000 +32.779114 -7.019902 2.700000 +32.779114 -7.019902 3.600000 +34.131435 -6.319316 2.700000 +34.131435 -6.319316 3.600000 +35.338657 -5.338656 2.700000 +35.338657 -5.338656 3.600000 +36.319317 -4.131433 2.700000 +36.319317 -4.131433 3.600000 +37.019901 -2.779115 2.700000 +37.019901 -2.779115 3.600000 +37.423954 -1.373821 2.700000 +37.423954 -1.373821 3.600000 +137.424271 -13.100425 0.000000 +135.000000 -13.322845 0.000000 +145.343231 -8.397364 0.000000 +146.151169 -7.290390 0.000000 +147.387421 -4.904068 0.000000 +148.100418 -2.424265 0.000000 +144.420670 -9.420673 0.000000 +143.397369 -10.343233 0.000000 +142.290390 -11.151161 0.000000 +139.904068 -12.387425 0.000000 +148.249481 0.000000 0.005412 +148.322845 0.000000 0.000000 +148.156189 0.000000 0.028591 +148.067474 0.000000 0.070137 +147.988541 0.000000 0.128186 +147.923569 0.000000 0.199028 +147.883743 0.000000 0.260870 +147.668640 -2.344364 0.260870 +146.979141 -4.742435 0.260870 +145.783630 -7.050106 0.260870 +145.002335 -8.120595 0.260870 +144.110184 -9.110177 0.260870 +143.120590 -10.002330 0.260870 +142.050110 -10.783629 0.260870 +139.742432 -11.979147 0.260870 +137.344360 -12.668647 0.260870 +135.000000 -12.923576 0.199028 +135.000000 -12.883736 0.260870 +135.000000 -12.988548 0.128186 +135.000000 -13.067468 0.070137 +135.000000 -13.156192 0.028591 +135.000000 -13.249480 0.005412 +145.912338 -7.504298 0.006315 +144.364655 -9.364659 0.006315 +147.154236 -5.260069 0.006315 +147.962616 -2.713745 0.006315 +142.504303 -10.912342 0.006315 +140.260071 -12.154233 0.006315 +137.713745 -12.962611 0.006315 +147.870926 -2.694549 0.030844 +147.790192 -2.677648 0.070137 +147.717804 -2.662494 0.123782 +147.652863 -2.648899 0.194321 +146.863800 -5.134378 0.194321 +145.651581 -7.324980 0.194321 +144.140884 -9.140888 0.194321 +142.324982 -10.651588 0.194321 +140.134384 -11.863803 0.194321 +137.648895 -12.652865 0.194321 +137.662491 -12.717802 0.123782 +137.677643 -12.790188 0.070137 +137.694550 -12.870921 0.030844 +140.160736 -11.924690 0.123782 +140.190109 -11.992562 0.070137 +140.222870 -12.068260 0.030844 +142.362579 -10.706254 0.123782 +142.404480 -10.767191 0.070137 +144.187805 -9.187800 0.123782 +144.240097 -9.240095 0.070137 +142.451218 -10.835155 0.030844 +144.298416 -9.298419 0.030844 +145.706253 -7.362573 0.123782 +145.767197 -7.404479 0.070137 +146.924683 -5.160728 0.123782 +146.992569 -5.190102 0.070137 +145.835159 -7.451217 0.030844 +147.068268 -5.222862 0.030844 +137.072708 -11.200635 1.197855 +135.000000 -11.390800 1.197855 +143.843277 -7.179600 1.197855 +144.534042 -6.233157 1.197855 +145.591034 -4.192894 1.197855 +146.200638 -2.072705 1.197855 +146.344849 0.000000 1.202234 +146.390808 0.000000 1.197855 +143.054520 -8.054512 1.197855 +142.179596 -8.843285 1.197855 +141.233154 -9.534049 1.197855 +139.192886 -10.591033 1.197855 +146.254272 0.000000 1.223865 +146.169281 0.000000 1.261917 +146.130188 0.000000 1.286452 +145.944366 -2.025282 1.286452 +145.348709 -4.096961 1.286452 +144.315918 -6.090544 1.286452 +143.640945 -7.015333 1.286452 +142.870224 -7.870227 1.286452 +142.015335 -8.640953 1.286452 +141.090546 -9.315913 1.286452 +139.096954 -10.348714 1.286452 +137.025284 -10.944368 1.286452 +135.000000 -11.169284 1.261917 +135.000000 -11.130182 1.286452 +135.000000 -11.254274 1.223865 +135.000000 -11.344848 1.202234 +144.346359 -6.427393 1.202485 +143.020782 -8.020783 1.202485 +145.410034 -4.505223 1.202485 +146.102417 -2.324309 1.202485 +141.427399 -9.346366 1.202485 +139.505219 -10.410039 1.202485 +137.324310 -11.102411 1.202485 +146.015472 -2.306108 1.223865 +145.933792 -2.289007 1.261052 +145.251938 -4.436797 1.261052 +144.204407 -6.329773 1.261052 +142.898956 -7.898963 1.261052 +141.329773 -9.204412 1.261052 +139.436798 -10.251930 1.261052 +137.289001 -10.933786 1.261052 +137.306107 -11.015470 1.223865 +139.469940 -10.328519 1.223865 +141.377060 -9.273175 1.223865 +142.957977 -7.957974 1.223865 +144.273178 -6.377061 1.223865 +145.328522 -4.469943 1.223865 +136.610367 8.702252 2.000000 +135.000000 8.850000 2.000000 +141.870728 5.578138 2.000000 +142.407410 4.842806 2.000000 +143.228622 3.257638 2.000000 +143.702255 1.610373 2.000000 +141.257889 6.257895 2.000000 +140.578140 6.870726 2.000000 +139.842804 7.407410 2.000000 +138.257645 8.228626 2.000000 +144.330032 0.000000 1.971092 +143.850006 0.000000 2.000000 +145.044617 0.000000 1.817447 +145.719299 0.000000 1.536341 +146.130188 0.000000 1.286452 +145.944366 2.025282 1.286452 +145.348709 4.096961 1.286452 +144.315918 6.090544 1.286452 +143.640945 7.015333 1.286452 +142.870224 7.870227 1.286452 +142.015335 8.640953 1.286452 +141.090546 9.315913 1.286452 +139.096954 10.348714 1.286452 +137.025284 10.944368 1.286452 +135.000000 10.719302 1.536341 +135.000000 11.130182 1.286452 +135.000000 10.044611 1.817447 +135.000000 9.330033 1.971092 +141.597336 6.597330 1.971092 +142.687653 5.286719 1.971092 +143.562561 3.705678 1.971092 +144.132065 1.911812 1.971092 +140.286713 7.687660 1.971092 +138.705673 8.562562 1.971092 +136.911819 9.132058 1.971092 +144.831467 2.058236 1.817447 +145.491852 2.196486 1.536341 +144.837555 4.257464 1.536341 +143.832382 6.073927 1.536341 +142.579697 7.579691 1.536341 +141.073929 8.832375 1.536341 +139.257462 9.837552 1.536341 +137.196487 10.491848 1.536341 +137.058243 9.831473 1.817447 +144.218353 3.989492 1.817447 +143.276443 5.691624 1.817447 +142.102615 7.102612 1.817447 +140.691620 8.276450 1.817447 +138.989487 9.218360 1.817447 +143.054520 8.054512 1.197855 +143.843277 7.179600 1.197855 +144.534042 6.233157 1.197855 +145.591034 4.192894 1.197855 +146.200638 2.072705 1.197855 +146.631424 0.000000 1.169774 +146.390808 0.000000 1.197855 +146.966415 0.000000 1.073265 +147.259811 0.000000 0.924604 +147.521255 0.000000 0.725038 +147.753815 0.000000 0.465344 +147.883743 0.000000 0.260870 +147.668640 2.344364 0.260870 +146.979141 4.742435 0.260870 +145.783630 7.050106 0.260870 +145.002335 8.120595 0.260870 +144.110184 9.110177 0.260870 +143.120590 10.002330 0.260870 +142.050110 10.783629 0.260870 +139.742432 11.979147 0.260870 +137.344360 12.668647 0.260870 +135.000000 12.753820 0.465344 +135.000000 12.883736 0.260870 +135.000000 12.521252 0.725038 +135.000000 12.259805 0.924604 +135.000000 11.966409 1.073265 +135.000000 11.631423 1.169774 +135.000000 11.390800 1.197855 +137.072708 11.200635 1.197855 +139.192886 10.591033 1.197855 +141.233154 9.534049 1.197855 +142.179596 8.843285 1.197855 +143.224655 8.224658 1.169774 +144.583939 6.590766 1.169774 +145.674637 4.619738 1.169774 +146.384613 2.383389 1.169774 +146.712494 2.452030 1.073265 +146.999664 2.512150 0.924604 +147.255569 2.565723 0.725038 +147.483200 2.613379 0.465344 +146.704712 5.065528 0.465344 +145.508759 7.226756 0.465344 +144.018311 9.018312 0.465344 +142.226761 10.508755 0.465344 +140.065521 11.704715 0.465344 +137.613373 12.483196 0.465344 +137.565720 12.255563 0.725038 +137.512146 11.999662 0.924604 +137.452026 11.712492 1.073265 +137.383392 11.384615 1.169774 +139.619736 10.674644 1.169774 +141.590759 9.583935 1.169774 +146.491272 4.973157 0.725038 +146.251343 4.869317 0.924604 +145.982071 4.752786 1.073265 +145.317123 7.094974 0.725038 +145.101700 6.946829 0.924604 +143.853867 8.853862 0.725038 +143.668991 8.668991 0.924604 +144.859955 6.780581 1.073265 +143.461533 8.461529 1.073265 +142.094971 10.317125 0.725038 +141.946823 10.101702 0.924604 +139.973160 11.491277 0.725038 +139.869324 11.251336 0.924604 +141.780579 9.859952 1.073265 +139.752792 10.982074 1.073265 +148.585403 2.844129 2.300000 +148.869080 0.548516 2.300000 +135.000000 13.900000 0.000000 +135.000000 13.879929 2.300000 +137.848236 13.605055 0.000000 +137.844131 13.585409 2.300000 +140.520767 12.756612 0.000000 +148.880966 0.000000 2.180967 +148.899994 0.000000 0.000000 +148.870224 0.548516 2.170219 +140.512787 12.738192 2.300000 +142.876221 11.453172 0.000000 +144.828781 9.828784 0.000000 +142.864853 11.436633 2.300000 +144.814713 9.814466 2.300000 +146.453171 7.876221 0.000000 +147.756607 5.520766 0.000000 +146.436630 7.864847 2.300000 +147.738190 5.512793 2.300000 +148.605057 2.848242 0.000000 +23.404402 0.000000 2.504402 +23.406109 0.000000 2.700000 +36.593891 0.000000 2.700000 +36.595596 0.000000 2.504402 +36.483810 -1.199845 2.700000 +36.485489 -1.200155 2.504402 +36.130924 -2.427176 2.700000 +36.132511 -2.427805 2.504402 +35.519058 -3.608242 2.700000 +35.520485 -3.609176 2.504402 +34.662586 -4.662585 2.700000 +34.663792 -4.663792 2.504402 +33.608242 -5.519057 2.700000 +32.427177 -6.130923 2.700000 +33.609177 -5.520486 2.504402 +32.427803 -6.132510 2.504402 +31.199844 -6.483809 2.700000 +31.200155 -6.485487 2.504402 +30.000000 -6.593891 2.700000 +30.000000 -6.595598 2.504402 +28.800156 -6.483809 2.700000 +28.799845 -6.485487 2.504402 +27.572824 -6.130923 2.700000 +26.391758 -5.519057 2.700000 +27.572195 -6.132510 2.504402 +26.390825 -5.520486 2.504402 +25.337416 -4.662585 2.700000 +25.336208 -4.663792 2.504402 +24.480942 -3.608242 2.700000 +24.479513 -3.609176 2.504402 +23.869078 -2.427176 2.700000 +23.867491 -2.427805 2.504402 +23.516191 -1.199845 2.700000 +23.514513 -1.200155 2.504402 +48.404404 0.000000 2.504402 +48.406109 0.000000 2.700000 +61.593891 0.000000 2.700000 +61.595596 0.000000 2.504402 +61.483810 -1.199845 2.700000 +61.130924 -2.427176 2.700000 +61.485489 -1.200155 2.504402 +61.132511 -2.427805 2.504402 +60.519058 -3.608242 2.700000 +60.520485 -3.609176 2.504402 +59.662586 -4.662585 2.700000 +58.608242 -5.519057 2.700000 +59.663792 -4.663792 2.504402 +58.609177 -5.520486 2.504402 +57.427177 -6.130923 2.700000 +57.427803 -6.132510 2.504402 +56.199844 -6.483809 2.700000 +56.200153 -6.485487 2.504402 +55.000000 -6.593891 2.700000 +55.000000 -6.595598 2.504402 +53.800156 -6.483809 2.700000 +53.799847 -6.485487 2.504402 +52.572823 -6.130923 2.700000 +52.572197 -6.132510 2.504402 +51.391758 -5.519057 2.700000 +51.390823 -5.520486 2.504402 +50.337414 -4.662585 2.700000 +50.336208 -4.663792 2.504402 +49.480942 -3.608242 2.700000 +49.479515 -3.609176 2.504402 +48.869076 -2.427176 2.700000 +48.867489 -2.427805 2.504402 +48.516190 -1.199845 2.700000 +48.514511 -1.200155 2.504402 +98.404404 0.000000 2.504402 +98.406105 0.000000 2.700000 +111.593895 0.000000 2.700000 +111.595596 0.000000 2.504402 +111.483810 -1.199845 2.700000 +111.485489 -1.200155 2.504402 +111.130920 -2.427176 2.700000 +110.519058 -3.608242 2.700000 +111.132507 -2.427805 2.504402 +110.520485 -3.609176 2.504402 +109.662582 -4.662585 2.700000 +108.608238 -5.519057 2.700000 +109.663795 -4.663792 2.504402 +108.609177 -5.520486 2.504402 +107.427177 -6.130923 2.700000 +107.427803 -6.132510 2.504402 +106.199844 -6.483809 2.700000 +106.200157 -6.485487 2.504402 +105.000000 -6.593891 2.700000 +105.000000 -6.595598 2.504402 +103.800156 -6.483809 2.700000 +103.799843 -6.485487 2.504402 +102.572823 -6.130923 2.700000 +102.572197 -6.132510 2.504402 +101.391762 -5.519057 2.700000 +101.390823 -5.520486 2.504402 +100.337418 -4.662585 2.700000 +100.336205 -4.663792 2.504402 +99.480942 -3.608242 2.700000 +99.479515 -3.609176 2.504402 +98.869080 -2.427176 2.700000 +98.867493 -2.427805 2.504402 +98.516190 -1.199845 2.700000 +98.514511 -1.200155 2.504402 +92.572189 -6.134080 2.700000 +93.293892 -4.800000 2.700000 +93.297356 -4.800000 2.302641 +93.267281 -5.090029 2.700000 +93.270691 -5.090660 2.302641 +93.181984 -5.386703 2.700000 +93.185204 -5.387980 2.302641 +93.034081 -5.672193 2.700000 +93.036980 -5.674090 2.302641 +92.827049 -5.927051 2.700000 +90.129311 -5.090660 2.302641 +90.102638 -4.800000 2.302641 +90.106110 -4.800000 2.700000 +90.214798 -5.387980 2.302641 +90.132721 -5.090029 2.700000 +90.218018 -5.386703 2.700000 +90.363014 -5.674090 2.302641 +90.365921 -5.672193 2.700000 +90.570496 -5.929503 2.302641 +90.572952 -5.927051 2.700000 +90.825912 -6.136982 2.302641 +90.827805 -6.134080 2.700000 +91.112022 -6.285206 2.302641 +91.113297 -6.281981 2.700000 +91.409340 -6.370692 2.302641 +91.409973 -6.367282 2.700000 +91.699997 -6.397359 2.302641 +91.699997 -6.393891 2.700000 +91.990662 -6.370692 2.302641 +92.287979 -6.285206 2.302641 +91.990028 -6.367282 2.700000 +92.574089 -6.136982 2.302641 +92.286705 -6.281981 2.700000 +92.829506 -5.929503 2.302641 +146.158096 2.335968 3.350000 +146.391724 0.434471 3.350000 +137.335968 11.158103 7.750000 +135.000000 11.400000 7.750000 +135.000000 11.400000 3.350000 +137.335968 11.158103 3.350000 +139.527817 10.462257 7.750000 +141.459641 9.393249 7.750000 +139.527817 10.462257 3.350000 +141.459641 9.393249 3.350000 +143.061020 8.061017 7.750000 +143.061523 8.060518 3.350000 +144.393250 6.459635 7.750000 +145.462250 4.527822 7.750000 +144.393250 6.459634 3.350000 +145.462265 4.527822 3.350000 +146.158096 2.335968 7.750000 +146.399994 0.000000 7.300000 +146.399994 0.000000 7.750000 +146.392975 0.400000 7.300000 +135.000000 12.700000 7.750000 +135.000000 12.700000 2.300000 +130.750000 12.700000 2.300000 +130.750000 12.700000 7.750000 +129.649994 12.700000 7.750000 +129.649994 12.700000 2.300000 +109.849998 12.700000 2.300000 +109.849998 12.700000 7.750000 +101.449997 12.700000 3.350000 +101.949997 12.700000 7.750000 +108.750000 12.700000 7.750000 +101.949997 12.700000 3.850000 +101.941650 12.700000 3.759018 +97.250000 12.700000 5.800000 +100.449997 12.700000 5.800000 +97.250000 12.700000 3.850000 +88.949997 12.700000 7.750000 +95.750000 12.700000 7.750000 +88.949997 12.700000 2.300000 +95.750000 12.700000 3.850000 +95.758347 12.700000 3.759018 +101.914894 12.700000 3.665953 +100.449997 12.700000 3.850000 +97.241653 12.700000 3.759018 +100.458344 12.700000 3.759018 +97.214897 12.700000 3.665953 +101.868500 12.700000 3.576395 +95.785103 12.700000 3.665953 +100.485107 12.700000 3.665953 +97.168495 12.700000 3.576395 +95.831505 12.700000 3.576395 +101.803551 12.700000 3.496447 +100.531502 12.700000 3.576395 +97.103554 12.700000 3.496447 +101.723602 12.700000 3.431502 +95.896446 12.700000 3.496447 +100.596443 12.700000 3.496447 +97.023605 12.700000 3.431502 +95.976395 12.700000 3.431502 +101.634048 12.700000 3.385106 +100.676392 12.700000 3.431502 +96.934044 12.700000 3.385106 +101.540985 12.700000 3.358347 +96.065956 12.700000 3.385106 +100.765953 12.700000 3.385106 +96.840981 12.700000 3.358347 +96.159019 12.700000 3.358347 +108.750000 12.700000 2.300000 +96.250000 12.700000 3.350000 +96.750000 12.700000 3.350000 +100.859016 12.700000 3.358347 +100.949997 12.700000 3.350000 +80.550003 12.700000 3.350000 +81.050003 12.700000 7.750000 +87.849998 12.700000 7.750000 +81.050003 12.700000 3.850000 +81.041656 12.700000 3.759018 +76.349998 12.700000 5.800000 +79.550003 12.700000 5.800000 +76.349998 12.700000 3.850000 +68.050003 12.700000 7.750000 +74.849998 12.700000 7.750000 +68.050003 12.700000 2.300000 +74.849998 12.700000 3.850000 +74.858345 12.700000 3.759018 +81.014893 12.700000 3.665953 +79.550003 12.700000 3.850000 +76.341652 12.700000 3.759018 +79.558350 12.700000 3.759018 +76.314896 12.700000 3.665953 +80.968498 12.700000 3.576395 +74.885109 12.700000 3.665953 +79.585106 12.700000 3.665953 +76.268501 12.700000 3.576395 +74.931503 12.700000 3.576395 +80.903557 12.700000 3.496447 +79.631500 12.700000 3.576395 +76.203552 12.700000 3.496447 +80.823608 12.700000 3.431502 +74.996445 12.700000 3.496447 +79.696449 12.700000 3.496447 +76.123604 12.700000 3.431502 +75.076393 12.700000 3.431502 +80.734047 12.700000 3.385106 +79.776398 12.700000 3.431502 +76.034050 12.700000 3.385106 +80.640984 12.700000 3.358347 +75.165955 12.700000 3.385106 +79.865952 12.700000 3.385106 +75.940979 12.700000 3.358347 +75.259018 12.700000 3.358347 +87.849998 12.700000 2.300000 +75.349998 12.700000 3.350000 +75.849998 12.700000 3.350000 +79.959015 12.700000 3.358347 +80.050003 12.700000 3.350000 +59.650002 12.700000 3.350000 +60.150002 12.700000 7.750000 +66.949997 12.700000 7.750000 +60.150002 12.700000 3.850000 +60.141651 12.700000 3.759018 +55.450001 12.700000 5.800000 +58.650002 12.700000 5.800000 +55.450001 12.700000 3.850000 +47.150002 12.700000 7.750000 +53.950001 12.700000 7.750000 +47.150002 12.700000 2.300000 +53.950001 12.700000 3.850000 +53.958347 12.700000 3.759018 +60.114895 12.700000 3.665953 +58.650002 12.700000 3.850000 +55.441654 12.700000 3.759018 +58.658348 12.700000 3.759018 +55.414894 12.700000 3.665953 +60.068497 12.700000 3.576395 +53.985107 12.700000 3.665953 +58.685104 12.700000 3.665953 +55.368496 12.700000 3.576395 +54.031502 12.700000 3.576395 +60.003555 12.700000 3.496447 +58.731503 12.700000 3.576395 +55.303555 12.700000 3.496447 +59.923603 12.700000 3.431502 +54.096447 12.700000 3.496447 +58.796448 12.700000 3.496447 +55.223606 12.700000 3.431502 +54.176395 12.700000 3.431502 +59.834049 12.700000 3.385106 +58.876396 12.700000 3.431502 +55.134048 12.700000 3.385106 +59.740982 12.700000 3.358347 +54.265953 12.700000 3.385106 +58.965954 12.700000 3.385106 +55.040981 12.700000 3.358347 +54.359020 12.700000 3.358347 +66.949997 12.700000 2.300000 +54.450001 12.700000 3.350000 +54.950001 12.700000 3.350000 +59.059017 12.700000 3.358347 +59.150002 12.700000 3.350000 +33.459019 12.700000 3.358347 +34.549999 12.700000 3.850000 +34.549999 12.700000 5.800000 +37.750000 12.700000 5.800000 +26.250000 12.700000 7.750000 +33.049999 12.700000 7.750000 +26.250000 12.700000 2.300000 +33.049999 12.700000 3.850000 +39.250000 12.700000 7.750000 +46.049999 12.700000 7.750000 +39.250000 12.700000 3.850000 +39.241653 12.700000 3.759018 +39.214893 12.700000 3.665953 +33.058346 12.700000 3.759018 +37.750000 12.700000 3.850000 +34.541653 12.700000 3.759018 +37.758347 12.700000 3.759018 +34.514893 12.700000 3.665953 +33.085106 12.700000 3.665953 +39.168499 12.700000 3.576395 +37.785107 12.700000 3.665953 +34.468498 12.700000 3.576395 +39.103554 12.700000 3.496447 +33.131504 12.700000 3.576395 +37.831501 12.700000 3.576395 +34.403553 12.700000 3.496447 +33.196445 12.700000 3.496447 +39.023605 12.700000 3.431502 +37.896446 12.700000 3.496447 +34.323605 12.700000 3.431502 +38.934048 12.700000 3.385106 +33.276394 12.700000 3.431502 +37.976395 12.700000 3.431502 +34.234047 12.700000 3.385106 +33.365952 12.700000 3.385106 +38.840981 12.700000 3.358347 +38.065952 12.700000 3.385106 +34.140980 12.700000 3.358347 +38.750000 12.700000 3.350000 +46.049999 12.700000 2.300000 +38.250000 12.700000 3.350000 +38.159019 12.700000 3.358347 +34.049999 12.700000 3.350000 +33.549999 12.700000 3.350000 +25.150000 12.700000 2.300000 +5.350000 12.700000 2.300000 +5.350000 12.700000 7.750000 +25.150000 12.700000 7.750000 +4.250000 12.700000 2.300000 +0.000000 12.700000 2.300000 +0.000000 12.700000 7.750000 +4.250000 12.700000 7.750000 +55.650002 -11.400000 7.750000 +79.349998 -11.400000 7.750000 +79.849998 -11.400000 3.350000 +55.150002 -11.400000 3.350000 +79.759018 -11.400000 3.358347 +55.240982 -11.400000 3.358347 +79.665955 -11.400000 3.385106 +55.334049 -11.400000 3.385106 +79.576393 -11.400000 3.431502 +55.423603 -11.400000 3.431502 +79.496445 -11.400000 3.496447 +55.503555 -11.400000 3.496447 +79.431503 -11.400000 3.576395 +55.568497 -11.400000 3.576395 +79.385109 -11.400000 3.665953 +55.614895 -11.400000 3.665953 +79.358345 -11.400000 3.759018 +55.641651 -11.400000 3.759018 +79.349998 -11.400000 3.850000 +55.650002 -11.400000 3.850000 +85.140984 -12.700000 3.358347 +79.349998 -12.700000 3.850000 +79.349998 -12.700000 7.750000 +77.050003 -12.700000 7.750000 +79.358345 -12.700000 3.759018 +79.385109 -12.700000 3.665953 +79.431503 -12.700000 3.576395 +84.050003 -12.700000 5.800000 +80.849998 -12.700000 5.800000 +84.050003 -12.700000 3.850000 +87.849998 -12.700000 7.750000 +85.550003 -12.700000 7.750000 +87.849998 -12.700000 2.300000 +85.550003 -12.700000 3.850000 +85.541656 -12.700000 3.759018 +85.514893 -12.700000 3.665953 +80.849998 -12.700000 3.850000 +84.058350 -12.700000 3.759018 +85.468498 -12.700000 3.576395 +79.496445 -12.700000 3.496447 +80.841652 -12.700000 3.759018 +84.085106 -12.700000 3.665953 +79.576393 -12.700000 3.431502 +85.403557 -12.700000 3.496447 +80.814896 -12.700000 3.665953 +84.131500 -12.700000 3.576395 +85.323608 -12.700000 3.431502 +79.665955 -12.700000 3.385106 +80.768501 -12.700000 3.576395 +84.196449 -12.700000 3.496447 +80.703552 -12.700000 3.496447 +84.276398 -12.700000 3.431502 +79.759018 -12.700000 3.358347 +77.050003 -12.700000 2.300000 +79.849998 -12.700000 3.350000 +80.349998 -12.700000 3.350000 +80.440979 -12.700000 3.358347 +80.534050 -12.700000 3.385106 +80.623604 -12.700000 3.431502 +85.234047 -12.700000 3.385106 +84.365952 -12.700000 3.385106 +84.459015 -12.700000 3.358347 +84.550003 -12.700000 3.350000 +85.050003 -12.700000 3.350000 +100.250000 -11.400000 7.750000 +100.750000 -11.400000 3.350000 +85.050003 -11.400000 3.350000 +100.659019 -11.400000 3.358347 +85.140984 -11.400000 3.358347 +100.565956 -11.400000 3.385106 +85.234047 -11.400000 3.385106 +100.476395 -11.400000 3.431502 +85.323608 -11.400000 3.431502 +100.396446 -11.400000 3.496447 +85.403557 -11.400000 3.496447 +100.331505 -11.400000 3.576395 +85.468498 -11.400000 3.576395 +100.285103 -11.400000 3.665953 +85.514893 -11.400000 3.665953 +100.258347 -11.400000 3.759018 +85.541656 -11.400000 3.759018 +100.250000 -11.400000 3.850000 +85.550003 -11.400000 3.850000 +85.550003 -11.400000 7.750000 +95.750000 11.400000 7.750000 +81.050003 11.400000 7.750000 +80.550003 11.400000 3.350000 +96.250000 11.400000 3.350000 +80.640984 11.400000 3.358347 +96.159019 11.400000 3.358347 +80.734047 11.400000 3.385106 +96.065956 11.400000 3.385106 +80.823608 11.400000 3.431502 +95.976395 11.400000 3.431502 +80.903557 11.400000 3.496447 +95.896446 11.400000 3.496447 +80.968498 11.400000 3.576395 +95.831505 11.400000 3.576395 +81.014893 11.400000 3.665953 +95.785103 11.400000 3.665953 +81.041656 11.400000 3.759018 +95.758347 11.400000 3.759018 +81.050003 11.400000 3.850000 +95.750000 11.400000 3.850000 +60.150002 11.400000 7.750000 +59.650002 11.400000 3.350000 +75.349998 11.400000 3.350000 +59.740982 11.400000 3.358347 +75.259018 11.400000 3.358347 +59.834049 11.400000 3.385106 +75.165955 11.400000 3.385106 +59.923603 11.400000 3.431502 +75.076393 11.400000 3.431502 +60.003555 11.400000 3.496447 +74.996445 11.400000 3.496447 +60.068497 11.400000 3.576395 +74.931503 11.400000 3.576395 +60.114895 11.400000 3.665953 +74.885109 11.400000 3.665953 +60.141651 11.400000 3.759018 +74.858345 11.400000 3.759018 +60.150002 11.400000 3.850000 +74.849998 11.400000 3.850000 +74.849998 11.400000 7.750000 +106.040985 -12.700000 3.358347 +100.250000 -12.700000 3.850000 +100.250000 -12.700000 7.750000 +97.949997 -12.700000 7.750000 +100.258347 -12.700000 3.759018 +100.285103 -12.700000 3.665953 +100.331505 -12.700000 3.576395 +104.949997 -12.700000 3.850000 +104.949997 -12.700000 5.800000 +101.750000 -12.700000 5.800000 +108.750000 -12.700000 7.750000 +106.449997 -12.700000 7.750000 +108.750000 -12.700000 2.300000 +106.449997 -12.700000 3.850000 +106.441650 -12.700000 3.759018 +106.414894 -12.700000 3.665953 +101.750000 -12.700000 3.850000 +104.958344 -12.700000 3.759018 +106.368500 -12.700000 3.576395 +100.396446 -12.700000 3.496447 +101.741653 -12.700000 3.759018 +104.985107 -12.700000 3.665953 +100.476395 -12.700000 3.431502 +106.303551 -12.700000 3.496447 +101.714897 -12.700000 3.665953 +105.031502 -12.700000 3.576395 +106.223602 -12.700000 3.431502 +100.565956 -12.700000 3.385106 +101.668495 -12.700000 3.576395 +105.096443 -12.700000 3.496447 +101.603554 -12.700000 3.496447 +105.176392 -12.700000 3.431502 +100.659019 -12.700000 3.358347 +97.949997 -12.700000 2.300000 +100.750000 -12.700000 3.350000 +101.250000 -12.700000 3.350000 +101.340981 -12.700000 3.358347 +101.434044 -12.700000 3.385106 +101.523605 -12.700000 3.431502 +106.134048 -12.700000 3.385106 +105.265953 -12.700000 3.385106 +105.359016 -12.700000 3.358347 +105.449997 -12.700000 3.350000 +105.949997 -12.700000 3.350000 +135.000000 -11.400000 3.350000 +128.034470 -11.400000 3.350000 +126.965530 -11.400000 3.350000 +105.949997 -11.400000 3.350000 +106.040985 -11.400000 3.358347 +106.134048 -11.400000 3.385106 +106.223602 -11.400000 3.431502 +106.303551 -11.400000 3.496447 +106.368500 -11.400000 3.576395 +106.414894 -11.400000 3.665953 +106.441650 -11.400000 3.759018 +127.000000 -11.400000 7.300000 +106.449997 -11.400000 3.850000 +106.449997 -11.400000 7.750000 +128.000000 -11.400000 7.300000 +135.000000 -11.400000 7.750000 +127.900002 11.400000 7.300000 +127.934471 11.400000 3.350000 +101.540985 11.400000 3.358347 +101.449997 11.400000 3.350000 +101.634048 11.400000 3.385106 +101.723602 11.400000 3.431502 +101.803551 11.400000 3.496447 +101.868500 11.400000 3.576395 +101.914894 11.400000 3.665953 +101.941650 11.400000 3.759018 +101.949997 11.400000 3.850000 +127.065529 11.400000 3.350000 +101.949997 11.400000 7.750000 +135.000000 11.400000 7.750000 +127.099998 11.400000 7.300000 +135.000000 11.400000 3.350000 +55.240982 -12.700000 3.358347 +54.150002 -12.700000 5.800000 +50.950001 -12.700000 5.800000 +54.150002 -12.700000 3.850000 +49.450001 -12.700000 7.750000 +47.150002 -12.700000 7.750000 +49.450001 -12.700000 3.850000 +49.458347 -12.700000 3.759018 +49.485107 -12.700000 3.665953 +49.531502 -12.700000 3.576395 +57.950001 -12.700000 7.750000 +55.650002 -12.700000 7.750000 +57.950001 -12.700000 2.300000 +55.650002 -12.700000 3.850000 +55.641651 -12.700000 3.759018 +55.614895 -12.700000 3.665953 +50.950001 -12.700000 3.850000 +54.158348 -12.700000 3.759018 +55.568497 -12.700000 3.576395 +49.596447 -12.700000 3.496447 +50.941654 -12.700000 3.759018 +54.185104 -12.700000 3.665953 +49.676395 -12.700000 3.431502 +55.503555 -12.700000 3.496447 +50.914894 -12.700000 3.665953 +54.231503 -12.700000 3.576395 +55.423603 -12.700000 3.431502 +49.765953 -12.700000 3.385106 +50.868496 -12.700000 3.576395 +54.296448 -12.700000 3.496447 +50.803555 -12.700000 3.496447 +54.376396 -12.700000 3.431502 +49.859020 -12.700000 3.358347 +47.150002 -12.700000 2.300000 +49.950001 -12.700000 3.350000 +50.450001 -12.700000 3.350000 +50.540981 -12.700000 3.358347 +50.634048 -12.700000 3.385106 +50.723606 -12.700000 3.431502 +55.334049 -12.700000 3.385106 +54.465954 -12.700000 3.385106 +54.559017 -12.700000 3.358347 +54.650002 -12.700000 3.350000 +55.150002 -12.700000 3.350000 +34.750000 -11.400000 7.750000 +49.450001 -11.400000 7.750000 +49.950001 -11.400000 3.350000 +34.250000 -11.400000 3.350000 +49.859020 -11.400000 3.358347 +34.340981 -11.400000 3.358347 +49.765953 -11.400000 3.385106 +34.434048 -11.400000 3.385106 +49.676395 -11.400000 3.431502 +34.523605 -11.400000 3.431502 +49.596447 -11.400000 3.496447 +34.603554 -11.400000 3.496447 +49.531502 -11.400000 3.576395 +34.668499 -11.400000 3.576395 +49.485107 -11.400000 3.665953 +34.714893 -11.400000 3.665953 +49.458347 -11.400000 3.759018 +34.741653 -11.400000 3.759018 +49.450001 -11.400000 3.850000 +34.750000 -11.400000 3.850000 +34.340981 -12.700000 3.358347 +28.549999 -12.700000 7.750000 +26.250000 -12.700000 7.750000 +28.549999 -12.700000 3.850000 +28.558348 -12.700000 3.759018 +28.585106 -12.700000 3.665953 +28.631502 -12.700000 3.576395 +33.250000 -12.700000 5.800000 +30.049999 -12.700000 5.800000 +33.250000 -12.700000 3.850000 +37.049999 -12.700000 7.750000 +34.750000 -12.700000 7.750000 +37.049999 -12.700000 2.300000 +34.750000 -12.700000 3.850000 +34.741653 -12.700000 3.759018 +34.714893 -12.700000 3.665953 +30.049999 -12.700000 3.850000 +33.258347 -12.700000 3.759018 +34.668499 -12.700000 3.576395 +28.696447 -12.700000 3.496447 +30.041653 -12.700000 3.759018 +33.285107 -12.700000 3.665953 +28.776396 -12.700000 3.431502 +34.603554 -12.700000 3.496447 +30.014894 -12.700000 3.665953 +33.331501 -12.700000 3.576395 +34.523605 -12.700000 3.431502 +28.865953 -12.700000 3.385106 +29.968498 -12.700000 3.576395 +33.396446 -12.700000 3.496447 +29.903553 -12.700000 3.496447 +33.476395 -12.700000 3.431502 +28.959019 -12.700000 3.358347 +26.250000 -12.700000 2.300000 +29.049999 -12.700000 3.350000 +29.549999 -12.700000 3.350000 +29.640982 -12.700000 3.358347 +29.734047 -12.700000 3.385106 +29.823605 -12.700000 3.431502 +34.434048 -12.700000 3.385106 +33.565952 -12.700000 3.385106 +33.659019 -12.700000 3.358347 +33.750000 -12.700000 3.350000 +34.250000 -12.700000 3.350000 +7.000000 -11.400000 7.300000 +6.965529 -11.400000 3.350000 +28.959019 -11.400000 3.358347 +29.049999 -11.400000 3.350000 +28.865953 -11.400000 3.385106 +28.776396 -11.400000 3.431502 +28.696447 -11.400000 3.496447 +28.631502 -11.400000 3.576395 +28.585106 -11.400000 3.665953 +28.558348 -11.400000 3.759018 +28.549999 -11.400000 3.850000 +8.034472 -11.400000 3.350000 +28.549999 -11.400000 7.750000 +0.000000 -11.400000 7.750000 +8.000000 -11.400000 7.300000 +0.000000 -11.400000 3.350000 +53.950001 11.400000 7.750000 +39.250000 11.400000 7.750000 +38.750000 11.400000 3.350000 +54.450001 11.400000 3.350000 +38.840981 11.400000 3.358347 +54.359020 11.400000 3.358347 +38.934048 11.400000 3.385106 +54.265953 11.400000 3.385106 +39.023605 11.400000 3.431502 +54.176395 11.400000 3.431502 +39.103554 11.400000 3.496447 +54.096447 11.400000 3.496447 +39.168499 11.400000 3.576395 +54.031502 11.400000 3.576395 +39.214893 11.400000 3.665953 +53.985107 11.400000 3.665953 +39.241653 11.400000 3.759018 +53.958347 11.400000 3.759018 +39.250000 11.400000 3.850000 +53.950001 11.400000 3.850000 +143.788177 9.168318 7.750000 +147.372650 2.864868 7.750000 +147.688614 0.537489 7.750000 +147.688614 0.537489 2.300000 +147.688156 0.548516 2.300000 +147.372650 2.864868 2.300000 +146.545944 5.289716 7.750000 +145.309753 7.416134 7.750000 +146.545944 5.289716 2.300000 +135.000000 12.700000 2.300000 +135.000000 12.700000 7.750000 +137.338669 12.482814 2.300000 +139.796326 11.759474 2.300000 +137.338669 12.482814 7.750000 +141.973160 10.614379 2.300000 +139.796326 11.759474 7.750000 +141.973160 10.614379 7.750000 +143.788177 9.168318 2.300000 +145.309753 7.416134 2.300000 +147.687531 -0.562527 2.300000 +147.687531 -0.562527 2.300000 +135.000000 -12.700000 7.750000 +135.000000 -12.700000 2.300000 +137.326355 -12.485115 7.750000 +137.326355 -12.485115 2.300000 +139.784729 -11.764200 7.750000 +141.962677 -10.621254 7.750000 +139.784729 -11.764200 2.300000 +141.962677 -10.621254 2.300000 +143.779114 -9.176985 7.750000 +143.779114 -9.176985 2.300000 +145.302429 -7.426303 7.750000 +145.302429 -7.426303 2.300000 +146.540726 -5.301105 7.750000 +147.369827 -2.877075 7.750000 +146.540726 -5.301105 2.300000 +147.687531 -0.562527 7.750000 +147.369827 -2.877075 2.300000 +-6.973160 10.614379 7.750000 +0.000000 12.700000 7.750000 +0.000000 12.700000 2.300000 +-2.338666 12.482814 7.750000 +-4.796329 11.759474 7.750000 +-2.338666 12.482814 2.300000 +-12.688622 0.537489 2.300000 +-12.688622 0.537489 7.750000 +-12.688149 0.548516 2.300000 +-12.372652 2.864868 2.300000 +-11.545947 5.289716 2.300000 +-12.372652 2.864868 7.750000 +-11.545947 5.289716 7.750000 +-10.309751 7.416134 2.300000 +-10.309751 7.416134 7.750000 +-8.788172 9.168318 2.300000 +-8.788171 9.168318 7.750000 +-6.973160 10.614379 2.300000 +-4.796329 11.759474 2.300000 +88.949997 -12.700000 2.300000 +96.849998 -12.700000 2.300000 +96.849998 -12.700000 7.750000 +88.949997 -12.700000 7.750000 +68.050003 -12.700000 2.300000 +75.949997 -12.700000 2.300000 +75.949997 -12.700000 7.750000 +68.050003 -12.700000 7.750000 +109.849998 -12.700000 7.750000 +109.849998 -12.700000 2.300000 +129.649994 -12.700000 2.300000 +129.649994 -12.700000 7.750000 +59.049999 -12.700000 2.300000 +66.949997 -12.700000 2.300000 +66.949997 -12.700000 7.750000 +59.049999 -12.700000 7.750000 +38.150002 -12.700000 2.300000 +46.049999 -12.700000 2.300000 +46.049999 -12.700000 7.750000 +38.150002 -12.700000 7.750000 +5.350000 -12.700000 7.750000 +5.350000 -12.700000 2.300000 +25.150000 -12.700000 2.300000 +25.150000 -12.700000 7.750000 +0.000000 -12.700000 7.750000 +0.000000 -12.700000 2.300000 +4.250000 -12.700000 2.300000 +4.250000 -12.700000 7.750000 +0.000000 11.400000 3.350000 +7.065529 11.400000 3.350000 +7.934471 11.400000 3.350000 +33.549999 11.400000 3.350000 +33.459019 11.400000 3.358347 +33.365952 11.400000 3.385106 +33.276394 11.400000 3.431502 +33.196445 11.400000 3.496447 +33.131504 11.400000 3.576395 +33.085106 11.400000 3.665953 +33.058346 11.400000 3.759018 +7.900000 11.400000 7.300000 +33.049999 11.400000 3.850000 +33.049999 11.400000 7.750000 +7.100000 11.400000 7.300000 +0.000000 11.400000 7.750000 +146.392975 -0.400000 7.300000 +146.391724 -0.434471 3.350000 +137.335968 -11.158103 3.350000 +135.000000 -11.400000 3.350000 +135.000000 -11.400000 7.750000 +139.527817 -10.462257 3.350000 +137.335968 -11.158103 7.750000 +141.459641 -9.393249 3.350000 +139.527817 -10.462257 7.750000 +143.061523 -8.060518 3.350000 +141.459641 -9.393249 7.750000 +143.061020 -8.061017 7.750000 +144.393250 -6.459634 3.350000 +144.393250 -6.459635 7.750000 +145.462265 -4.527822 3.350000 +146.158096 -2.335968 3.350000 +145.462250 -4.527822 7.750000 +146.399994 0.000000 7.750000 +146.399994 0.000000 7.300000 +146.158096 -2.335968 7.750000 +-2.074379 11.209682 3.350000 +0.000000 11.400000 3.350000 +0.000000 -11.400000 7.750000 +0.000000 -11.400000 3.350000 +-2.074379 -11.209682 7.750000 +-2.074379 -11.209682 3.350000 +-4.196280 -10.599586 7.750000 +-6.238191 -9.541749 7.750000 +-4.196280 -10.599586 3.350000 +-6.238191 -9.541749 3.350000 +-8.061017 -8.061017 7.750000 +-8.061017 -8.061017 3.350000 +-9.541749 -6.238191 7.750000 +-9.541749 -6.238191 3.350000 +-10.599586 -4.196280 7.750000 +-10.599586 -4.196280 3.350000 +-11.209682 -2.074379 7.750000 +-11.209682 -2.074379 3.350000 +-11.391718 -0.434471 3.350000 +-11.400000 0.000000 7.750000 +-11.392981 -0.400000 7.300000 +-11.400000 0.000000 7.300000 +-11.209682 2.074379 7.750000 +-11.392981 0.400000 7.300000 +-11.391718 0.434471 3.350000 +-11.209682 2.074379 3.350000 +-10.599586 4.196280 7.750000 +-10.599586 4.196280 3.350000 +-9.541749 6.238191 7.750000 +-8.061017 8.061017 7.750000 +-9.541749 6.238191 3.350000 +-6.238191 9.541749 7.750000 +-8.061017 8.061017 3.350000 +-6.238191 9.541749 3.350000 +-4.196280 10.599586 7.750000 +-2.074379 11.209682 7.750000 +-4.196280 10.599586 3.350000 +0.000000 11.400000 7.750000 +130.750000 -12.700000 2.300000 +135.000000 -12.700000 2.300000 +135.000000 -12.700000 7.750000 +130.750000 -12.700000 7.750000 +-8.779120 -9.176985 2.300000 +-12.687535 -0.562527 7.750000 +-12.687535 -0.562527 2.300000 +-12.369820 -2.877075 7.750000 +-12.687337 -0.566984 2.300000 +-11.540723 -5.301105 7.750000 +-12.369820 -2.877075 2.300000 +-10.302428 -7.426303 7.750000 +-11.540723 -5.301105 2.300000 +-8.779120 -9.176985 7.750000 +-10.302428 -7.426303 2.300000 +-2.326349 -12.485115 2.300000 +0.000000 -12.700000 2.300000 +0.000000 -12.700000 7.750000 +-4.784724 -11.764200 2.300000 +-2.326349 -12.485115 7.750000 +-6.962684 -10.621254 2.300000 +-4.784724 -11.764200 7.750000 +-6.962684 -10.621254 7.750000 +4.250000 -12.421063 1.239572 +4.250000 -12.405008 1.295411 +4.250000 -12.400000 7.750000 +4.250000 -12.700000 7.750000 +4.250000 -12.400000 1.350000 +4.250000 -13.450000 1.700000 +4.250000 -13.450000 1.050000 +4.250000 -12.700000 2.300000 +4.250000 -13.879929 2.300000 +4.250000 -13.881399 2.131400 +4.250000 -12.700000 1.050000 +4.250000 -12.645411 1.055008 +4.250000 -12.589572 1.071064 +4.250000 -12.535837 1.098901 +4.250000 -12.487868 1.137868 +4.250000 -12.448901 1.185837 +5.350000 -12.400000 1.350000 +5.350000 -12.400000 7.750000 +4.250000 -12.400000 7.750000 +4.250000 -12.400000 1.350000 +5.350000 -12.589572 1.071064 +5.350000 -12.645411 1.055008 +5.350000 -12.700000 2.300000 +5.350000 -12.700000 7.750000 +5.350000 -12.400000 7.750000 +5.350000 -13.881399 2.131400 +5.350000 -13.879929 2.300000 +5.350000 -13.450000 1.700000 +5.350000 -13.450000 1.050000 +5.350000 -12.700000 1.050000 +5.350000 -12.400000 1.350000 +5.350000 -12.405008 1.295411 +5.350000 -12.421063 1.239572 +5.350000 -12.448901 1.185837 +5.350000 -12.487868 1.137868 +5.350000 -12.535837 1.098901 +25.150000 -12.421063 1.239572 +25.150000 -12.405008 1.295411 +25.150000 -12.400000 7.750000 +25.150000 -12.700000 7.750000 +25.150000 -12.400000 1.350000 +25.150000 -12.700000 2.300000 +25.150000 -13.879929 2.300000 +25.150000 -13.881399 2.131400 +25.150000 -13.450000 1.700000 +25.150000 -13.450000 1.050000 +25.150000 -12.700000 1.050000 +25.150000 -12.645411 1.055008 +25.150000 -12.589572 1.071064 +25.150000 -12.535837 1.098901 +25.150000 -12.487868 1.137868 +25.150000 -12.448901 1.185837 +26.250000 -12.400000 1.350000 +26.250000 -12.400000 7.750000 +25.150000 -12.400000 7.750000 +25.150000 -12.400000 1.350000 +26.250000 -12.589572 1.071064 +26.250000 -12.645411 1.055008 +26.250000 -12.700000 1.050000 +26.250000 -13.450000 1.050000 +26.250000 -12.700000 2.300000 +26.250000 -12.700000 7.750000 +26.250000 -12.400000 7.750000 +26.250000 -13.881399 2.131400 +26.250000 -13.879929 2.300000 +26.250000 -13.450000 1.700000 +26.250000 -12.400000 1.350000 +26.250000 -12.405008 1.295411 +26.250000 -12.421063 1.239572 +26.250000 -12.448901 1.185837 +26.250000 -12.487868 1.137868 +26.250000 -12.535837 1.098901 +46.049999 -12.421063 1.239572 +46.049999 -12.405008 1.295411 +46.049999 -12.400000 7.750000 +46.049999 -12.700000 7.750000 +46.049999 -12.400000 1.350000 +46.049999 -13.450000 1.700000 +46.049999 -13.450000 1.050000 +46.049999 -12.700000 2.300000 +46.049999 -13.879929 2.300000 +46.049999 -13.881399 2.131400 +46.049999 -12.700000 1.050000 +46.049999 -12.645411 1.055008 +46.049999 -12.589572 1.071064 +46.049999 -12.535837 1.098901 +46.049999 -12.487868 1.137868 +46.049999 -12.448901 1.185837 +47.150002 -12.400000 1.350000 +47.150002 -12.400000 7.750000 +46.049999 -12.400000 7.750000 +46.049999 -12.400000 1.350000 +47.150002 -12.589572 1.071064 +47.150002 -12.645411 1.055008 +47.150002 -12.700000 1.050000 +47.150002 -13.450000 1.050000 +47.150002 -12.700000 2.300000 +47.150002 -12.700000 7.750000 +47.150002 -12.400000 7.750000 +47.150002 -13.881399 2.131400 +47.150002 -13.879929 2.300000 +47.150002 -13.450000 1.700000 +47.150002 -12.400000 1.350000 +47.150002 -12.405008 1.295411 +47.150002 -12.421063 1.239572 +47.150002 -12.448901 1.185837 +47.150002 -12.487868 1.137868 +47.150002 -12.535837 1.098901 +66.949997 -12.421063 1.239572 +66.949997 -12.405008 1.295411 +66.949997 -12.400000 7.750000 +66.949997 -12.700000 7.750000 +66.949997 -12.400000 1.350000 +66.949997 -12.700000 2.300000 +66.949997 -13.879929 2.300000 +66.949997 -13.881399 2.131400 +66.949997 -13.450000 1.700000 +66.949997 -13.450000 1.050000 +66.949997 -12.700000 1.050000 +66.949997 -12.645411 1.055008 +66.949997 -12.589572 1.071064 +66.949997 -12.535837 1.098901 +66.949997 -12.487868 1.137868 +66.949997 -12.448901 1.185837 +66.949997 -12.400000 1.350000 +68.050003 -12.400000 1.350000 +68.050003 -12.400000 7.750000 +66.949997 -12.400000 7.750000 +68.050003 -12.589572 1.071064 +68.050003 -12.645411 1.055008 +68.050003 -12.700000 2.300000 +68.050003 -12.700000 7.750000 +68.050003 -12.400000 7.750000 +68.050003 -13.881399 2.131400 +68.050003 -13.879929 2.300000 +68.050003 -13.450000 1.700000 +68.050003 -13.450000 1.050000 +68.050003 -12.700000 1.050000 +68.050003 -12.400000 1.350000 +68.050003 -12.405008 1.295411 +68.050003 -12.421063 1.239572 +68.050003 -12.448901 1.185837 +68.050003 -12.487868 1.137868 +68.050003 -12.535837 1.098901 +87.849998 -12.421063 1.239572 +87.849998 -12.405008 1.295411 +87.849998 -12.400000 7.750000 +87.849998 -12.700000 7.750000 +87.849998 -12.400000 1.350000 +87.849998 -12.700000 2.300000 +87.849998 -13.879929 2.300000 +87.849998 -13.881399 2.131400 +87.849998 -13.450000 1.700000 +87.849998 -13.450000 1.050000 +87.849998 -12.700000 1.050000 +87.849998 -12.645411 1.055008 +87.849998 -12.589572 1.071064 +87.849998 -12.535837 1.098901 +87.849998 -12.487868 1.137868 +87.849998 -12.448901 1.185837 +87.849998 -12.400000 1.350000 +88.949997 -12.400000 1.350000 +88.949997 -12.400000 7.750000 +87.849998 -12.400000 7.750000 +88.949997 -12.589572 1.071064 +88.949997 -12.645411 1.055008 +88.949997 -12.700000 1.050000 +88.949997 -13.450000 1.050000 +88.949997 -12.700000 2.300000 +88.949997 -12.700000 7.750000 +88.949997 -12.400000 7.750000 +88.949997 -13.881399 2.131400 +88.949997 -13.879929 2.300000 +88.949997 -13.450000 1.700000 +88.949997 -12.400000 1.350000 +88.949997 -12.405008 1.295411 +88.949997 -12.421063 1.239572 +88.949997 -12.448901 1.185837 +88.949997 -12.487868 1.137868 +88.949997 -12.535837 1.098901 +108.750000 -12.421063 1.239572 +108.750000 -12.405008 1.295411 +108.750000 -12.400000 7.750000 +108.750000 -12.700000 7.750000 +108.750000 -12.400000 1.350000 +108.750000 -13.450000 1.700000 +108.750000 -13.450000 1.050000 +108.750000 -12.700000 2.300000 +108.750000 -13.879929 2.300000 +108.750000 -13.881399 2.131400 +108.750000 -12.700000 1.050000 +108.750000 -12.645411 1.055008 +108.750000 -12.589572 1.071064 +108.750000 -12.535837 1.098901 +108.750000 -12.487868 1.137868 +108.750000 -12.448901 1.185837 +108.750000 -12.400000 1.350000 +109.849998 -12.400000 1.350000 +109.849998 -12.400000 7.750000 +108.750000 -12.400000 7.750000 +109.849998 -12.589572 1.071064 +109.849998 -12.645411 1.055008 +109.849998 -12.700000 1.050000 +109.849998 -13.450000 1.050000 +109.849998 -12.700000 2.300000 +109.849998 -12.700000 7.750000 +109.849998 -12.400000 7.750000 +109.849998 -13.881399 2.131400 +109.849998 -13.879929 2.300000 +109.849998 -13.450000 1.700000 +109.849998 -12.400000 1.350000 +109.849998 -12.405008 1.295411 +109.849998 -12.421063 1.239572 +109.849998 -12.448901 1.185837 +109.849998 -12.487868 1.137868 +109.849998 -12.535837 1.098901 +129.649994 -12.421063 1.239572 +129.649994 -12.405008 1.295411 +129.649994 -12.400000 7.750000 +129.649994 -12.700000 7.750000 +129.649994 -12.400000 1.350000 +129.649994 -13.450000 1.700000 +129.649994 -13.450000 1.050000 +129.649994 -12.700000 2.300000 +129.649994 -13.879929 2.300000 +129.649994 -13.881399 2.131400 +129.649994 -12.700000 1.050000 +129.649994 -12.645411 1.055008 +129.649994 -12.589572 1.071064 +129.649994 -12.535837 1.098901 +129.649994 -12.487868 1.137868 +129.649994 -12.448901 1.185837 +130.750000 -12.400000 1.350000 +130.750000 -12.400000 7.750000 +129.649994 -12.400000 7.750000 +129.649994 -12.400000 1.350000 +130.750000 -12.589572 1.071064 +130.750000 -12.645411 1.055008 +130.750000 -12.700000 1.050000 +130.750000 -13.450000 1.050000 +130.750000 -12.700000 2.300000 +130.750000 -12.700000 7.750000 +130.750000 -12.400000 7.750000 +130.750000 -13.881399 2.131400 +130.750000 -13.879929 2.300000 +130.750000 -13.450000 1.700000 +130.750000 -12.400000 1.350000 +130.750000 -12.405008 1.295411 +130.750000 -12.421063 1.239572 +130.750000 -12.448901 1.185837 +130.750000 -12.487868 1.137868 +130.750000 -12.535837 1.098901 +57.950001 -12.421063 1.239572 +57.950001 -12.405008 1.295411 +57.950001 -12.400000 7.750000 +57.950001 -12.700000 7.750000 +57.950001 -12.400000 1.350000 +57.950001 -12.700000 2.300000 +57.950001 -13.879929 2.300000 +57.950001 -13.881399 2.131400 +57.950001 -13.450000 1.700000 +57.950001 -13.450000 1.050000 +57.950001 -12.700000 1.050000 +57.950001 -12.645411 1.055008 +57.950001 -12.589572 1.071064 +57.950001 -12.535837 1.098901 +57.950001 -12.487868 1.137868 +57.950001 -12.448901 1.185837 +59.049999 -12.400000 1.350000 +59.049999 -12.400000 7.750000 +57.950001 -12.400000 7.750000 +57.950001 -12.400000 1.350000 +59.049999 -12.589572 1.071064 +59.049999 -12.645411 1.055008 +59.049999 -12.700000 2.300000 +59.049999 -12.700000 7.750000 +59.049999 -12.400000 7.750000 +59.049999 -13.881399 2.131400 +59.049999 -13.879929 2.300000 +59.049999 -13.450000 1.700000 +59.049999 -13.450000 1.050000 +59.049999 -12.700000 1.050000 +59.049999 -12.400000 1.350000 +59.049999 -12.405008 1.295411 +59.049999 -12.421063 1.239572 +59.049999 -12.448901 1.185837 +59.049999 -12.487868 1.137868 +59.049999 -12.535837 1.098901 +75.949997 -12.421063 1.239572 +75.949997 -12.405008 1.295411 +75.949997 -12.400000 7.750000 +75.949997 -12.700000 7.750000 +75.949997 -12.400000 1.350000 +75.949997 -13.450000 1.700000 +75.949997 -13.450000 1.050000 +75.949997 -12.700000 2.300000 +75.949997 -13.879929 2.300000 +75.949997 -13.881399 2.131400 +75.949997 -12.700000 1.050000 +75.949997 -12.645411 1.055008 +75.949997 -12.589572 1.071064 +75.949997 -12.535837 1.098901 +75.949997 -12.487868 1.137868 +75.949997 -12.448901 1.185837 +77.050003 -12.400000 1.350000 +77.050003 -12.400000 7.750000 +75.949997 -12.400000 7.750000 +75.949997 -12.400000 1.350000 +77.050003 -12.589572 1.071064 +77.050003 -12.645411 1.055008 +77.050003 -12.700000 2.300000 +77.050003 -12.700000 7.750000 +77.050003 -12.400000 7.750000 +77.050003 -13.881399 2.131400 +77.050003 -13.879929 2.300000 +77.050003 -13.450000 1.700000 +77.050003 -13.450000 1.050000 +77.050003 -12.700000 1.050000 +77.050003 -12.400000 1.350000 +77.050003 -12.405008 1.295411 +77.050003 -12.421063 1.239572 +77.050003 -12.448901 1.185837 +77.050003 -12.487868 1.137868 +77.050003 -12.535837 1.098901 +96.849998 -12.421063 1.239572 +96.849998 -12.405008 1.295411 +96.849998 -12.400000 7.750000 +96.849998 -12.700000 7.750000 +96.849998 -12.400000 1.350000 +96.849998 -13.450000 1.700000 +96.849998 -13.450000 1.050000 +96.849998 -12.700000 2.300000 +96.849998 -13.879929 2.300000 +96.849998 -13.881399 2.131400 +96.849998 -12.700000 1.050000 +96.849998 -12.645411 1.055008 +96.849998 -12.589572 1.071064 +96.849998 -12.535837 1.098901 +96.849998 -12.487868 1.137868 +96.849998 -12.448901 1.185837 +97.949997 -12.400000 1.350000 +97.949997 -12.400000 7.750000 +96.849998 -12.400000 7.750000 +96.849998 -12.400000 1.350000 +97.949997 -12.589572 1.071064 +97.949997 -12.645411 1.055008 +97.949997 -12.700000 1.050000 +97.949997 -13.450000 1.050000 +97.949997 -12.700000 2.300000 +97.949997 -12.700000 7.750000 +97.949997 -12.400000 7.750000 +97.949997 -13.881399 2.131400 +97.949997 -13.879929 2.300000 +97.949997 -13.450000 1.700000 +97.949997 -12.400000 1.350000 +97.949997 -12.405008 1.295411 +97.949997 -12.421063 1.239572 +97.949997 -12.448901 1.185837 +97.949997 -12.487868 1.137868 +97.949997 -12.535837 1.098901 +37.049999 -12.421063 1.239572 +37.049999 -12.405008 1.295411 +37.049999 -12.400000 7.750000 +37.049999 -12.700000 7.750000 +37.049999 -12.400000 1.350000 +37.049999 -13.450000 1.700000 +37.049999 -13.450000 1.050000 +37.049999 -12.700000 2.300000 +37.049999 -13.879929 2.300000 +37.049999 -13.881399 2.131400 +37.049999 -12.700000 1.050000 +37.049999 -12.645411 1.055008 +37.049999 -12.589572 1.071064 +37.049999 -12.535837 1.098901 +37.049999 -12.487868 1.137868 +37.049999 -12.448901 1.185837 +38.150002 -12.400000 1.350000 +38.150002 -12.400000 7.750000 +37.049999 -12.400000 7.750000 +37.049999 -12.400000 1.350000 +38.150002 -12.589572 1.071064 +38.150002 -12.645411 1.055008 +38.150002 -12.700000 2.300000 +38.150002 -12.700000 7.750000 +38.150002 -12.400000 7.750000 +38.150002 -13.881399 2.131400 +38.150002 -13.879929 2.300000 +38.150002 -13.450000 1.700000 +38.150002 -13.450000 1.050000 +38.150002 -12.700000 1.050000 +38.150002 -12.400000 1.350000 +38.150002 -12.405008 1.295411 +38.150002 -12.421063 1.239572 +38.150002 -12.448901 1.185837 +38.150002 -12.487868 1.137868 +38.150002 -12.535837 1.098901 +-12.688622 0.537489 7.750000 +-12.688622 0.537489 2.300000 +-12.400000 0.533016 2.300000 +-12.400000 0.533016 7.750000 +-12.400000 0.533016 2.300000 +-12.400000 0.548516 2.300000 +-12.400000 -0.566984 2.300000 +-12.400000 -0.566984 7.750000 +-12.400000 0.533016 7.750000 +-12.400000 -0.566984 1.350000 +-12.400000 0.548516 1.350000 +-12.400000 -0.566984 2.300000 +-12.687535 -0.562527 2.300000 +-12.687535 -0.562527 7.750000 +-12.400000 -0.566984 7.750000 +147.399994 0.533016 2.300000 +147.688614 0.537489 2.300000 +147.688614 0.537489 7.750000 +147.399994 0.533016 7.750000 +147.399994 -0.566984 2.300000 +147.399994 0.533016 7.750000 +147.399994 -0.566984 7.750000 +147.399994 0.533016 2.300000 +147.399994 0.548516 1.350000 +147.399994 0.548516 2.300000 +147.399994 -0.566984 1.350000 +147.687531 -0.562527 7.750000 +147.687531 -0.562527 2.300000 +147.399994 -0.566984 2.300000 +147.399994 -0.566984 7.750000 +39.250000 12.700000 3.850000 +39.250000 11.400000 3.850000 +39.250000 11.400000 7.750000 +39.250000 12.700000 7.750000 +33.049999 12.700000 3.850000 +33.049999 12.700000 7.750000 +33.049999 11.400000 7.750000 +33.049999 11.400000 3.850000 +28.549999 -12.700000 3.850000 +28.549999 -11.400000 3.850000 +28.549999 -11.400000 7.750000 +28.549999 -12.700000 7.750000 +34.750000 -11.400000 3.850000 +34.750000 -12.700000 3.850000 +34.750000 -12.700000 7.750000 +34.750000 -11.400000 7.750000 +60.150002 12.700000 3.850000 +60.150002 11.400000 3.850000 +60.150002 11.400000 7.750000 +60.150002 12.700000 7.750000 +53.950001 12.700000 3.850000 +53.950001 12.700000 7.750000 +53.950001 11.400000 7.750000 +53.950001 11.400000 3.850000 +49.450001 -12.700000 3.850000 +49.450001 -11.400000 3.850000 +49.450001 -11.400000 7.750000 +49.450001 -12.700000 7.750000 +55.650002 -11.400000 3.850000 +55.650002 -12.700000 3.850000 +55.650002 -12.700000 7.750000 +55.650002 -11.400000 7.750000 +95.750000 12.700000 3.850000 +95.750000 12.700000 7.750000 +95.750000 11.400000 7.750000 +95.750000 11.400000 3.850000 +101.949997 11.400000 7.750000 +101.949997 12.700000 7.750000 +101.949997 12.700000 3.850000 +101.949997 11.400000 3.850000 +106.449997 -12.700000 3.850000 +106.449997 -12.700000 7.750000 +106.449997 -11.400000 7.750000 +106.449997 -11.400000 3.850000 +100.250000 -11.400000 3.850000 +100.250000 -11.400000 7.750000 +100.250000 -12.700000 7.750000 +100.250000 -12.700000 3.850000 +74.849998 12.700000 3.850000 +74.849998 12.700000 7.750000 +74.849998 11.400000 7.750000 +74.849998 11.400000 3.850000 +81.050003 11.400000 7.750000 +81.050003 12.700000 7.750000 +81.050003 12.700000 3.850000 +81.050003 11.400000 3.850000 +85.550003 -12.700000 3.850000 +85.550003 -12.700000 7.750000 +85.550003 -11.400000 7.750000 +85.550003 -11.400000 3.850000 +79.349998 -11.400000 7.750000 +79.349998 -12.700000 7.750000 +79.349998 -12.700000 3.850000 +79.349998 -11.400000 3.850000 +4.250000 12.400000 1.350000 +4.250000 12.400000 7.750000 +5.350000 12.400000 7.750000 +5.350000 12.400000 1.350000 +5.350000 12.421063 1.239572 +5.350000 12.405008 1.295411 +5.350000 12.400000 7.750000 +5.350000 12.700000 7.750000 +5.350000 12.400000 1.350000 +5.350000 13.450000 1.700000 +5.350000 13.450000 1.050000 +5.350000 12.700000 2.300000 +5.350000 13.879929 2.300000 +5.350000 13.881399 2.131400 +5.350000 12.700000 1.050000 +5.350000 12.645411 1.055008 +5.350000 12.589572 1.071064 +5.350000 12.535837 1.098901 +5.350000 12.487868 1.137868 +5.350000 12.448901 1.185837 +4.250000 12.589572 1.071064 +4.250000 12.645411 1.055008 +4.250000 12.700000 2.300000 +4.250000 12.700000 7.750000 +4.250000 12.400000 7.750000 +4.250000 13.881399 2.131400 +4.250000 13.879929 2.300000 +4.250000 13.450000 1.700000 +4.250000 13.450000 1.050000 +4.250000 12.700000 1.050000 +4.250000 12.400000 1.350000 +4.250000 12.405008 1.295411 +4.250000 12.421063 1.239572 +4.250000 12.448901 1.185837 +4.250000 12.487868 1.137868 +4.250000 12.535837 1.098901 +25.150000 12.400000 7.750000 +26.250000 12.400000 7.750000 +26.250000 12.400000 1.350000 +25.150000 12.400000 1.350000 +26.250000 12.421063 1.239572 +26.250000 12.405008 1.295411 +26.250000 12.400000 7.750000 +26.250000 12.700000 7.750000 +26.250000 12.400000 1.350000 +26.250000 12.700000 2.300000 +26.250000 13.879929 2.300000 +26.250000 13.881399 2.131400 +26.250000 13.450000 1.700000 +26.250000 13.450000 1.050000 +26.250000 12.700000 1.050000 +26.250000 12.645411 1.055008 +26.250000 12.589572 1.071064 +26.250000 12.535837 1.098901 +26.250000 12.487868 1.137868 +26.250000 12.448901 1.185837 +25.150000 12.589572 1.071064 +25.150000 12.645411 1.055008 +25.150000 12.700000 2.300000 +25.150000 12.700000 7.750000 +25.150000 12.400000 7.750000 +25.150000 13.881399 2.131400 +25.150000 13.879929 2.300000 +25.150000 13.450000 1.700000 +25.150000 13.450000 1.050000 +25.150000 12.700000 1.050000 +25.150000 12.400000 1.350000 +25.150000 12.405008 1.295411 +25.150000 12.421063 1.239572 +25.150000 12.448901 1.185837 +25.150000 12.487868 1.137868 +25.150000 12.535837 1.098901 +46.049999 12.400000 7.750000 +47.150002 12.400000 7.750000 +47.150002 12.400000 1.350000 +46.049999 12.400000 1.350000 +47.150002 12.421063 1.239572 +47.150002 12.405008 1.295411 +47.150002 12.400000 7.750000 +47.150002 12.700000 7.750000 +47.150002 12.400000 1.350000 +47.150002 12.700000 2.300000 +47.150002 13.879929 2.300000 +47.150002 13.881399 2.131400 +47.150002 13.450000 1.700000 +47.150002 13.450000 1.050000 +47.150002 12.700000 1.050000 +47.150002 12.645411 1.055008 +47.150002 12.589572 1.071064 +47.150002 12.535837 1.098901 +47.150002 12.487868 1.137868 +47.150002 12.448901 1.185837 +46.049999 12.589572 1.071064 +46.049999 12.645411 1.055008 +46.049999 12.700000 2.300000 +46.049999 12.700000 7.750000 +46.049999 12.400000 7.750000 +46.049999 13.881399 2.131400 +46.049999 13.879929 2.300000 +46.049999 13.450000 1.700000 +46.049999 13.450000 1.050000 +46.049999 12.700000 1.050000 +46.049999 12.400000 1.350000 +46.049999 12.405008 1.295411 +46.049999 12.421063 1.239572 +46.049999 12.448901 1.185837 +46.049999 12.487868 1.137868 +46.049999 12.535837 1.098901 +66.949997 12.400000 1.350000 +66.949997 12.400000 7.750000 +68.050003 12.400000 7.750000 +68.050003 12.400000 1.350000 +68.050003 12.421063 1.239572 +68.050003 12.405008 1.295411 +68.050003 12.400000 7.750000 +68.050003 12.700000 7.750000 +68.050003 12.400000 1.350000 +68.050003 12.700000 2.300000 +68.050003 13.879929 2.300000 +68.050003 13.881399 2.131400 +68.050003 13.450000 1.700000 +68.050003 13.450000 1.050000 +68.050003 12.700000 1.050000 +68.050003 12.645411 1.055008 +68.050003 12.589572 1.071064 +68.050003 12.535837 1.098901 +68.050003 12.487868 1.137868 +68.050003 12.448901 1.185837 +66.949997 12.589572 1.071064 +66.949997 12.645411 1.055008 +66.949997 12.700000 2.300000 +66.949997 12.700000 7.750000 +66.949997 12.400000 7.750000 +66.949997 13.881399 2.131400 +66.949997 13.879929 2.300000 +66.949997 13.450000 1.700000 +66.949997 13.450000 1.050000 +66.949997 12.700000 1.050000 +66.949997 12.400000 1.350000 +66.949997 12.405008 1.295411 +66.949997 12.421063 1.239572 +66.949997 12.448901 1.185837 +66.949997 12.487868 1.137868 +66.949997 12.535837 1.098901 +87.849998 12.400000 1.350000 +87.849998 12.400000 7.750000 +88.949997 12.400000 7.750000 +88.949997 12.400000 1.350000 +88.949997 12.421063 1.239572 +88.949997 12.405008 1.295411 +88.949997 12.400000 7.750000 +88.949997 12.700000 7.750000 +88.949997 12.400000 1.350000 +88.949997 13.450000 1.700000 +88.949997 13.450000 1.050000 +88.949997 12.700000 2.300000 +88.949997 13.879929 2.300000 +88.949997 13.881399 2.131400 +88.949997 12.700000 1.050000 +88.949997 12.645411 1.055008 +88.949997 12.589572 1.071064 +88.949997 12.535837 1.098901 +88.949997 12.487868 1.137868 +88.949997 12.448901 1.185837 +87.849998 12.589572 1.071064 +87.849998 12.645411 1.055008 +87.849998 12.700000 2.300000 +87.849998 12.700000 7.750000 +87.849998 12.400000 7.750000 +87.849998 12.700000 1.050000 +87.849998 13.450000 1.050000 +87.849998 13.881399 2.131400 +87.849998 13.879929 2.300000 +87.849998 13.450000 1.700000 +87.849998 12.400000 1.350000 +87.849998 12.405008 1.295411 +87.849998 12.421063 1.239572 +87.849998 12.448901 1.185837 +87.849998 12.487868 1.137868 +87.849998 12.535837 1.098901 +108.750000 12.400000 1.350000 +108.750000 12.400000 7.750000 +109.849998 12.400000 7.750000 +109.849998 12.400000 1.350000 +109.849998 12.421063 1.239572 +109.849998 12.405008 1.295411 +109.849998 12.400000 7.750000 +109.849998 12.700000 7.750000 +109.849998 12.400000 1.350000 +109.849998 12.700000 2.300000 +109.849998 13.879929 2.300000 +109.849998 13.881399 2.131400 +109.849998 13.450000 1.700000 +109.849998 13.450000 1.050000 +109.849998 12.700000 1.050000 +109.849998 12.645411 1.055008 +109.849998 12.589572 1.071064 +109.849998 12.535837 1.098901 +109.849998 12.487868 1.137868 +109.849998 12.448901 1.185837 +108.750000 12.589572 1.071064 +108.750000 12.645411 1.055008 +108.750000 12.700000 2.300000 +108.750000 12.700000 7.750000 +108.750000 12.400000 7.750000 +108.750000 12.700000 1.050000 +108.750000 13.450000 1.050000 +108.750000 13.881399 2.131400 +108.750000 13.879929 2.300000 +108.750000 13.450000 1.700000 +108.750000 12.400000 1.350000 +108.750000 12.405008 1.295411 +108.750000 12.421063 1.239572 +108.750000 12.448901 1.185837 +108.750000 12.487868 1.137868 +108.750000 12.535837 1.098901 +129.649994 12.400000 7.750000 +130.750000 12.400000 7.750000 +130.750000 12.400000 1.350000 +129.649994 12.400000 1.350000 +130.750000 12.421063 1.239572 +130.750000 12.405008 1.295411 +130.750000 12.400000 7.750000 +130.750000 12.700000 7.750000 +130.750000 12.400000 1.350000 +130.750000 12.700000 2.300000 +130.750000 13.879929 2.300000 +130.750000 13.881399 2.131400 +130.750000 13.450000 1.700000 +130.750000 13.450000 1.050000 +130.750000 12.700000 1.050000 +130.750000 12.645411 1.055008 +130.750000 12.589572 1.071064 +130.750000 12.535837 1.098901 +130.750000 12.487868 1.137868 +130.750000 12.448901 1.185837 +129.649994 12.589572 1.071064 +129.649994 12.645411 1.055008 +129.649994 12.700000 2.300000 +129.649994 12.700000 7.750000 +129.649994 12.400000 7.750000 +129.649994 13.881399 2.131400 +129.649994 13.879929 2.300000 +129.649994 13.450000 1.700000 +129.649994 13.450000 1.050000 +129.649994 12.700000 1.050000 +129.649994 12.400000 1.350000 +129.649994 12.405008 1.295411 +129.649994 12.421063 1.239572 +129.649994 12.448901 1.185837 +129.649994 12.487868 1.137868 +129.649994 12.535837 1.098901 +109.849998 12.700000 2.300000 +129.649994 12.700000 2.300000 +129.649994 13.879929 2.300000 +109.849998 13.879929 2.300000 +135.000000 13.879929 2.300000 +130.750000 13.879929 2.300000 +147.688156 0.548516 2.300000 +148.869080 0.548516 2.300000 +147.388702 2.794616 2.300000 +148.549744 3.009495 2.300000 +146.644119 5.069977 2.300000 +147.741745 5.504558 2.300000 +145.432297 7.242727 2.300000 +146.420242 7.888638 2.300000 +143.784180 9.172136 2.300000 +144.618713 10.006642 2.300000 +141.785400 10.735382 2.300000 +142.431168 11.723063 2.300000 +139.562332 11.852220 2.300000 +139.996719 12.949331 2.300000 +137.256943 12.497849 2.300000 +137.471680 13.658083 2.300000 +135.000000 12.700000 2.300000 +130.750000 12.700000 2.300000 +130.750000 13.881399 2.131400 +130.750000 13.879929 2.300000 +26.250000 13.881399 2.131400 +26.250000 13.879929 2.300000 +46.049999 13.879929 2.300000 +5.350000 13.879929 2.300000 +25.150000 13.879929 2.300000 +5.350000 13.881399 2.131400 +0.000000 13.900000 0.000000 +0.000000 13.879929 2.300000 +4.250000 13.879929 2.300000 +135.000000 13.900000 0.000000 +4.250000 13.881399 2.131400 +25.150000 13.881399 2.131400 +46.049999 13.881399 2.131400 +109.849998 13.881399 2.131400 +109.849998 13.879929 2.300000 +129.649994 13.879929 2.300000 +88.949997 13.879929 2.300000 +108.750000 13.879929 2.300000 +88.949997 13.881399 2.131400 +68.050003 13.879929 2.300000 +87.849998 13.879929 2.300000 +68.050003 13.881399 2.131400 +47.150002 13.879929 2.300000 +66.949997 13.879929 2.300000 +47.150002 13.881399 2.131400 +66.949997 13.881399 2.131400 +87.849998 13.881399 2.131400 +108.750000 13.881399 2.131400 +129.649994 13.881399 2.131400 +135.000000 13.879929 2.300000 +129.649994 13.450000 1.050000 +130.750000 13.450000 1.050000 +130.750000 13.450000 1.700000 +129.649994 13.450000 1.700000 +88.949997 12.700000 2.300000 +108.750000 12.700000 2.300000 +108.750000 13.879929 2.300000 +88.949997 13.879929 2.300000 +108.750000 13.450000 1.050000 +109.849998 13.450000 1.050000 +109.849998 13.450000 1.700000 +108.750000 13.450000 1.700000 +68.050003 12.700000 2.300000 +87.849998 12.700000 2.300000 +87.849998 13.879929 2.300000 +68.050003 13.879929 2.300000 +87.849998 13.450000 1.050000 +88.949997 13.450000 1.050000 +88.949997 13.450000 1.700000 +87.849998 13.450000 1.700000 +47.150002 12.700000 2.300000 +66.949997 12.700000 2.300000 +66.949997 13.879929 2.300000 +47.150002 13.879929 2.300000 +66.949997 13.450000 1.050000 +68.050003 13.450000 1.050000 +68.050003 13.450000 1.700000 +66.949997 13.450000 1.700000 +26.250000 13.879929 2.300000 +26.250000 12.700000 2.300000 +46.049999 12.700000 2.300000 +46.049999 13.879929 2.300000 +46.049999 13.450000 1.050000 +47.150002 13.450000 1.050000 +47.150002 13.450000 1.700000 +46.049999 13.450000 1.700000 +5.350000 12.700000 2.300000 +25.150000 12.700000 2.300000 +25.150000 13.879929 2.300000 +5.350000 13.879929 2.300000 +25.150000 13.450000 1.700000 +25.150000 13.450000 1.050000 +26.250000 13.450000 1.050000 +26.250000 13.450000 1.700000 +0.000000 12.700000 2.300000 +4.250000 12.700000 2.300000 +-13.549736 3.009495 2.300000 +-13.869085 0.548516 2.300000 +-12.688149 0.548516 2.300000 +-12.741753 5.504558 2.300000 +-12.388709 2.794616 2.300000 +-11.420237 7.888638 2.300000 +-11.644112 5.069977 2.300000 +-9.618707 10.006642 2.300000 +-10.432302 7.242727 2.300000 +-7.431163 11.723063 2.300000 +-8.784186 9.172136 2.300000 +-4.996721 12.949331 2.300000 +-6.785395 10.735382 2.300000 +-2.471677 13.658083 2.300000 +-4.562334 11.852220 2.300000 +0.000000 13.879929 2.300000 +-2.256937 12.497849 2.300000 +4.250000 13.879929 2.300000 +4.250000 13.450000 1.700000 +4.250000 13.450000 1.050000 +5.350000 13.450000 1.050000 +5.350000 13.450000 1.700000 +80.849998 -11.400000 7.000000 +84.050003 -11.400000 7.000000 +84.550003 -11.400000 3.350000 +80.349998 -11.400000 3.350000 +84.459015 -11.400000 3.358347 +80.440979 -11.400000 3.358347 +84.365952 -11.400000 3.385106 +80.534050 -11.400000 3.385106 +84.276398 -11.400000 3.431502 +80.623604 -11.400000 3.431502 +84.196449 -11.400000 3.496447 +80.703552 -11.400000 3.496447 +84.131500 -11.400000 3.576395 +80.768501 -11.400000 3.576395 +84.085106 -11.400000 3.665953 +80.814896 -11.400000 3.665953 +84.058350 -11.400000 3.759018 +80.841652 -11.400000 3.759018 +84.050003 -11.400000 3.850000 +80.849998 -11.400000 3.850000 +79.550003 11.400000 7.000000 +76.349998 11.400000 7.000000 +75.849998 11.400000 3.350000 +80.050003 11.400000 3.350000 +75.940979 11.400000 3.358347 +79.959015 11.400000 3.358347 +76.034050 11.400000 3.385106 +79.865952 11.400000 3.385106 +76.123604 11.400000 3.431502 +79.776398 11.400000 3.431502 +76.203552 11.400000 3.496447 +79.696449 11.400000 3.496447 +76.268501 11.400000 3.576395 +79.631500 11.400000 3.576395 +76.314896 11.400000 3.665953 +79.585106 11.400000 3.665953 +76.341652 11.400000 3.759018 +79.558350 11.400000 3.759018 +76.349998 11.400000 3.850000 +79.550003 11.400000 3.850000 +101.750000 -11.400000 7.000000 +104.949997 -11.400000 7.000000 +105.449997 -11.400000 3.350000 +101.250000 -11.400000 3.350000 +105.359016 -11.400000 3.358347 +101.340981 -11.400000 3.358347 +105.265953 -11.400000 3.385106 +101.434044 -11.400000 3.385106 +105.176392 -11.400000 3.431502 +101.523605 -11.400000 3.431502 +105.096443 -11.400000 3.496447 +101.603554 -11.400000 3.496447 +105.031502 -11.400000 3.576395 +101.668495 -11.400000 3.576395 +104.985107 -11.400000 3.665953 +101.714897 -11.400000 3.665953 +104.958344 -11.400000 3.759018 +101.741653 -11.400000 3.759018 +104.949997 -11.400000 3.850000 +101.750000 -11.400000 3.850000 +100.449997 11.400000 3.850000 +96.750000 11.400000 3.350000 +100.949997 11.400000 3.350000 +96.840981 11.400000 3.358347 +100.859016 11.400000 3.358347 +96.934044 11.400000 3.385106 +100.765953 11.400000 3.385106 +97.023605 11.400000 3.431502 +100.676392 11.400000 3.431502 +97.103554 11.400000 3.496447 +100.596443 11.400000 3.496447 +97.168495 11.400000 3.576395 +100.531502 11.400000 3.576395 +97.214897 11.400000 3.665953 +100.485107 11.400000 3.665953 +97.241653 11.400000 3.759018 +100.458344 11.400000 3.759018 +97.250000 11.400000 3.850000 +100.449997 11.400000 7.000000 +97.250000 11.400000 7.000000 +50.950001 -11.400000 7.000000 +54.150002 -11.400000 7.000000 +54.650002 -11.400000 3.350000 +50.450001 -11.400000 3.350000 +54.559017 -11.400000 3.358347 +50.540981 -11.400000 3.358347 +54.465954 -11.400000 3.385106 +50.634048 -11.400000 3.385106 +54.376396 -11.400000 3.431502 +50.723606 -11.400000 3.431502 +54.296448 -11.400000 3.496447 +50.803555 -11.400000 3.496447 +54.231503 -11.400000 3.576395 +50.868496 -11.400000 3.576395 +54.185104 -11.400000 3.665953 +50.914894 -11.400000 3.665953 +54.158348 -11.400000 3.759018 +50.941654 -11.400000 3.759018 +54.150002 -11.400000 3.850000 +50.950001 -11.400000 3.850000 +58.650002 11.400000 7.000000 +55.450001 11.400000 7.000000 +54.950001 11.400000 3.350000 +59.150002 11.400000 3.350000 +55.040981 11.400000 3.358347 +59.059017 11.400000 3.358347 +55.134048 11.400000 3.385106 +58.965954 11.400000 3.385106 +55.223606 11.400000 3.431502 +58.876396 11.400000 3.431502 +55.303555 11.400000 3.496447 +58.796448 11.400000 3.496447 +55.368496 11.400000 3.576395 +58.731503 11.400000 3.576395 +55.414894 11.400000 3.665953 +58.685104 11.400000 3.665953 +55.441654 11.400000 3.759018 +58.658348 11.400000 3.759018 +55.450001 11.400000 3.850000 +58.650002 11.400000 3.850000 +30.049999 -11.400000 3.850000 +33.750000 -11.400000 3.350000 +29.549999 -11.400000 3.350000 +33.659019 -11.400000 3.358347 +29.640982 -11.400000 3.358347 +33.565952 -11.400000 3.385106 +29.734047 -11.400000 3.385106 +33.476395 -11.400000 3.431502 +29.823605 -11.400000 3.431502 +33.396446 -11.400000 3.496447 +29.903553 -11.400000 3.496447 +33.331501 -11.400000 3.576395 +29.968498 -11.400000 3.576395 +33.285107 -11.400000 3.665953 +30.014894 -11.400000 3.665953 +33.258347 -11.400000 3.759018 +30.041653 -11.400000 3.759018 +33.250000 -11.400000 3.850000 +30.049999 -11.400000 7.000000 +33.250000 -11.400000 7.000000 +37.750000 11.400000 7.000000 +34.549999 11.400000 7.000000 +34.049999 11.400000 3.350000 +38.250000 11.400000 3.350000 +34.140980 11.400000 3.358347 +38.159019 11.400000 3.358347 +34.234047 11.400000 3.385106 +38.065952 11.400000 3.385106 +34.323605 11.400000 3.431502 +37.976395 11.400000 3.431502 +34.403553 11.400000 3.496447 +37.896446 11.400000 3.496447 +34.468498 11.400000 3.576395 +37.831501 11.400000 3.576395 +34.514893 11.400000 3.665953 +37.785107 11.400000 3.665953 +34.541653 11.400000 3.759018 +37.758347 11.400000 3.759018 +34.549999 11.400000 3.850000 +37.750000 11.400000 3.850000 +-12.385041 -2.810829 2.300000 +-12.687337 -0.566984 2.300000 +-13.400000 -0.551484 2.300000 +-13.868968 -0.551484 2.300000 +-13.400000 -0.566984 2.300000 +0.000000 -13.879929 2.300000 +4.250000 -13.879929 2.300000 +4.250000 -12.700000 2.300000 +-2.471383 -13.658135 2.300000 +0.000000 -12.700000 2.300000 +-4.996109 -12.949568 2.300000 +-2.255104 -12.498180 2.300000 +-7.430270 -11.723630 2.300000 +-4.558522 -11.853686 2.300000 +-9.617636 -10.007671 2.300000 +-6.779826 -10.738899 2.300000 +-11.419149 -7.890211 2.300000 +-8.777508 -9.178527 2.300000 +-12.740834 -5.506682 2.300000 +-10.425510 -7.252498 2.300000 +-13.549156 -3.012103 2.300000 +-11.638355 -5.083178 2.300000 +88.949997 -12.700000 2.300000 +88.949997 -13.879929 2.300000 +96.849998 -13.879929 2.300000 +96.849998 -12.700000 2.300000 +97.949997 -13.450000 1.700000 +97.949997 -13.450000 1.050000 +96.849998 -13.450000 1.050000 +96.849998 -13.450000 1.700000 +68.050003 -12.700000 2.300000 +68.050003 -13.879929 2.300000 +75.949997 -13.879929 2.300000 +75.949997 -12.700000 2.300000 +75.949997 -13.450000 1.700000 +77.050003 -13.450000 1.700000 +77.050003 -13.450000 1.050000 +75.949997 -13.450000 1.050000 +47.150002 -12.700000 2.300000 +47.150002 -13.879929 2.300000 +57.950001 -13.879929 2.300000 +57.950001 -12.700000 2.300000 +59.049999 -13.450000 1.700000 +59.049999 -13.450000 1.050000 +57.950001 -13.450000 1.050000 +57.950001 -13.450000 1.700000 +26.250000 -12.700000 2.300000 +26.250000 -13.879929 2.300000 +37.049999 -13.879929 2.300000 +37.049999 -12.700000 2.300000 +37.049999 -13.450000 1.700000 +38.150002 -13.450000 1.700000 +38.150002 -13.450000 1.050000 +37.049999 -13.450000 1.050000 +148.399994 -0.566984 2.300000 +147.687332 -0.566984 2.300000 +148.548218 -3.016350 2.300000 +148.868774 -0.556318 2.300000 +148.399994 -0.556318 2.300000 +130.750000 -12.700000 2.300000 +130.750000 -13.879929 2.300000 +135.000000 -12.700000 2.300000 +135.000000 -13.879929 2.300000 +137.255096 -12.498180 2.300000 +137.470901 -13.658222 2.300000 +139.558517 -11.853686 2.300000 +139.995117 -12.949952 2.300000 +141.779831 -10.738899 2.300000 +142.428818 -11.724552 2.300000 +143.777512 -9.178527 2.300000 +144.615891 -10.009347 2.300000 +145.425507 -7.252498 2.300000 +146.417374 -7.892773 2.300000 +146.638351 -5.083178 2.300000 +147.739334 -5.510142 2.300000 +147.385040 -2.810829 2.300000 +109.849998 -12.700000 2.300000 +109.849998 -13.879929 2.300000 +129.649994 -13.879929 2.300000 +129.649994 -12.700000 2.300000 +130.750000 -13.450000 1.700000 +130.750000 -13.450000 1.050000 +129.649994 -13.450000 1.050000 +129.649994 -13.450000 1.700000 +108.750000 -12.700000 2.300000 +97.949997 -12.700000 2.300000 +97.949997 -13.879929 2.300000 +108.750000 -13.879929 2.300000 +109.849998 -13.450000 1.700000 +109.849998 -13.450000 1.050000 +108.750000 -13.450000 1.050000 +108.750000 -13.450000 1.700000 +87.849998 -12.700000 2.300000 +77.050003 -12.700000 2.300000 +77.050003 -13.879929 2.300000 +87.849998 -13.879929 2.300000 +88.949997 -13.450000 1.700000 +88.949997 -13.450000 1.050000 +87.849998 -13.450000 1.050000 +87.849998 -13.450000 1.700000 +66.949997 -13.879929 2.300000 +66.949997 -12.700000 2.300000 +59.049999 -12.700000 2.300000 +59.049999 -13.879929 2.300000 +68.050003 -13.450000 1.700000 +68.050003 -13.450000 1.050000 +66.949997 -13.450000 1.050000 +66.949997 -13.450000 1.700000 +46.049999 -13.879929 2.300000 +46.049999 -12.700000 2.300000 +38.150002 -12.700000 2.300000 +38.150002 -13.879929 2.300000 +47.150002 -13.450000 1.700000 +47.150002 -13.450000 1.050000 +46.049999 -13.450000 1.050000 +46.049999 -13.450000 1.700000 +5.350000 -12.700000 2.300000 +5.350000 -13.879929 2.300000 +25.150000 -13.879929 2.300000 +25.150000 -12.700000 2.300000 +26.250000 -13.450000 1.700000 +26.250000 -13.450000 1.050000 +25.150000 -13.450000 1.050000 +25.150000 -13.450000 1.700000 +4.250000 -13.450000 1.700000 +5.350000 -13.450000 1.700000 +5.350000 -13.450000 1.050000 +4.250000 -13.450000 1.050000 +34.620628 -8.624022 3.800000 +22.200001 0.200000 3.800000 +47.200001 0.200000 3.800000 +112.800003 -0.200000 3.800000 +112.620613 1.410214 3.800000 +112.800003 0.200000 3.800000 +47.250000 0.000000 3.800000 +47.194992 0.254589 3.800000 +22.379383 -1.410214 3.800000 +22.200001 -0.200000 3.800000 +47.379383 -1.410214 3.800000 +47.200001 -0.200000 3.800000 +22.250000 0.000000 3.800000 +22.194992 0.254589 3.800000 +112.750000 0.000000 3.800000 +112.805008 -0.254589 3.800000 +112.821060 -0.310428 3.800000 +22.178936 0.310428 3.800000 +47.194992 -0.254589 3.800000 +22.194992 -0.254589 3.800000 +47.178936 0.310428 3.800000 +112.805008 0.254589 3.800000 +112.821060 0.310428 3.800000 +47.151100 0.364163 3.800000 +22.178936 -0.310428 3.800000 +47.178936 -0.310428 3.800000 +22.151098 0.364163 3.800000 +112.848900 -0.364163 3.800000 +112.887871 -0.412132 3.800000 +22.112131 0.412132 3.800000 +47.151100 -0.364163 3.800000 +22.151098 -0.364163 3.800000 +47.112133 0.412132 3.800000 +112.848900 0.364163 3.800000 +22.112131 -0.412132 3.800000 +47.112133 -0.412132 3.800000 +47.064163 0.451099 3.800000 +22.064163 0.451099 3.800000 +112.887871 0.412132 3.800000 +112.935837 -0.451099 3.800000 +24.519922 -5.480078 3.800000 +22.836996 -5.952790 3.800000 +22.707108 -5.792893 3.800000 +61.486713 -4.240876 3.800000 +62.070213 -6.131905 3.800000 +62.163006 -5.952790 3.800000 +60.480076 5.480078 3.800000 +62.163006 5.952790 3.800000 +62.292892 5.792893 3.800000 +23.513285 4.240876 3.800000 +22.929789 6.131905 3.800000 +22.836996 5.952790 3.800000 +110.480080 5.480078 3.800000 +112.163002 5.952790 3.800000 +112.292892 5.792893 3.800000 +111.486717 -4.240876 3.800000 +112.070213 -6.131905 3.800000 +112.163002 -5.952790 3.800000 +112.292892 -5.792893 3.800000 +112.452789 5.663004 3.800000 +22.707108 5.792893 3.800000 +62.452789 5.663004 3.800000 +22.547211 -5.663004 3.800000 +62.292892 -5.792893 3.800000 +22.064163 -0.451099 3.800000 +47.064163 -0.451099 3.800000 +47.010429 0.478936 3.800000 +22.010427 0.478936 3.800000 +112.935837 0.451099 3.800000 +112.989571 -0.478936 3.800000 +122.241386 -0.872740 3.800000 +114.800003 0.200000 3.800000 +45.200001 -0.200000 3.800000 +20.200001 -0.200000 3.800000 +97.794144 -2.852734 3.800000 +94.001740 -3.295173 3.800000 +94.256920 -3.787740 3.800000 +94.059937 4.363289 3.800000 +97.379387 1.410214 3.800000 +93.931496 3.916573 3.800000 +114.794991 0.254589 3.800000 +85.429787 -6.131905 3.800000 +89.143082 -5.812261 3.800000 +89.340065 5.236712 3.800000 +85.483307 6.318037 3.800000 +114.800003 -0.200000 3.800000 +85.483307 -6.318037 3.800000 +34.179371 -6.618025 3.800000 +40.000000 0.000000 3.800000 +59.179371 -6.618025 3.800000 +59.239826 6.615266 3.800000 +39.983307 0.181963 3.800000 +34.239826 6.615266 3.800000 +12.749272 0.927276 3.800000 +20.200001 0.200000 3.800000 +100.820633 6.618025 3.800000 +85.500000 6.500000 3.800000 +100.760178 -6.615266 3.800000 +12.830544 0.000000 3.800000 +20.205008 -0.254589 3.800000 +98.513283 -4.240876 3.800000 +94.404091 -4.299602 3.800000 +22.010427 -0.478936 3.800000 +37.750000 0.000000 3.800000 +38.016693 -0.181963 3.800000 +38.070213 -0.368095 3.800000 +38.163006 -0.547210 3.800000 +38.292892 -0.707107 3.800000 +38.452789 -0.836995 3.800000 +45.205009 -0.254589 3.800000 +47.010429 -0.478936 3.800000 +46.954590 0.494992 3.800000 +45.200001 0.200000 3.800000 +38.000000 0.000000 3.800000 +37.620617 1.410214 3.800000 +38.016693 0.181963 3.800000 +38.070213 0.368095 3.800000 +38.163006 0.547210 3.800000 +38.292892 0.707107 3.800000 +21.954590 0.494992 3.800000 +112.989571 0.478936 3.800000 +97.794144 2.852734 3.800000 +94.099998 4.800000 3.800000 +113.045410 -0.494992 3.800000 +22.368095 -5.570212 3.800000 +22.929789 -6.131905 3.800000 +62.016693 -6.318037 3.800000 +62.452789 -5.663004 3.800000 +62.631905 5.570212 3.800000 +62.070213 6.131905 3.800000 +22.983305 6.318037 3.800000 +22.547211 5.663004 3.800000 +112.631905 5.570212 3.800000 +112.070213 6.131905 3.800000 +112.016693 -6.318037 3.800000 +112.452789 -5.663004 3.800000 +89.300003 4.800000 3.800000 +88.995911 -5.300398 3.800000 +85.336998 -5.952790 3.800000 +34.239826 -6.615266 3.800000 +59.239826 -6.615266 3.800000 +59.300850 6.625028 3.800000 +34.300850 6.625028 3.800000 +100.760178 6.615266 3.800000 +85.429787 6.131905 3.800000 +100.699150 -6.625028 3.800000 +7.930544 8.850000 3.800000 +7.930544 5.313128 3.800000 +126.156731 5.158520 3.800000 +127.069458 5.313128 3.800000 +93.708786 3.486696 3.800000 +93.644547 -2.855456 3.800000 +20.205008 0.254589 3.800000 +114.778938 0.310428 3.800000 +126.969460 -8.850000 3.800000 +126.969460 -5.304076 3.800000 +8.935244 -5.133690 3.800000 +8.030544 -5.304076 3.800000 +20.221064 -0.310428 3.800000 +114.794991 -0.254589 3.800000 +94.059937 5.236712 3.800000 +94.449997 -4.800000 3.800000 +35.480076 -5.480078 3.800000 +34.300850 -6.625028 3.800000 +34.358582 -6.647087 3.800000 +34.409557 -6.679704 3.800000 +39.983307 -0.181963 3.800000 +45.221062 -0.310428 3.800000 +60.480076 -5.480078 3.800000 +59.300850 -6.625028 3.800000 +59.358582 -6.647087 3.800000 +59.409557 -6.679704 3.800000 +59.451382 -6.720035 3.800000 +59.483013 -6.764806 3.800000 +62.000000 -6.500000 3.800000 +62.016693 -6.681963 3.800000 +62.070213 -6.868095 3.800000 +62.163006 -7.047210 3.800000 +60.183014 -7.977242 3.800000 +60.205971 -8.027020 3.800000 +62.292892 -7.207107 3.800000 +34.451382 -6.720035 3.800000 +59.240875 6.486715 3.800000 +59.358582 6.647087 3.800000 +59.409557 6.679704 3.800000 +59.451382 6.720035 3.800000 +59.483013 6.764806 3.800000 +60.183014 7.977242 3.800000 +62.016693 6.318037 3.800000 +62.000000 6.500000 3.800000 +62.016693 6.681963 3.800000 +62.070213 6.868095 3.800000 +60.205971 8.027020 3.800000 +62.163006 7.047210 3.800000 +60.219986 8.083406 3.800000 +39.929787 0.368095 3.800000 +45.205009 0.254589 3.800000 +34.240875 6.486715 3.800000 +34.358582 6.647087 3.800000 +34.409557 6.679704 3.800000 +34.451382 6.720035 3.800000 +34.483013 6.764806 3.800000 +99.519920 5.480078 3.800000 +100.699150 6.625028 3.800000 +100.641418 6.647087 3.800000 +100.590446 6.679704 3.800000 +100.548622 6.720035 3.800000 +89.468506 5.683427 3.800000 +85.483307 6.681963 3.800000 +97.379387 -1.410214 3.800000 +93.204826 -2.498262 3.800000 +85.500000 -6.500000 3.800000 +89.398262 -6.304827 3.800000 +100.759125 -6.486715 3.800000 +100.641418 -6.647087 3.800000 +100.590446 -6.679704 3.800000 +100.548622 -6.720035 3.800000 +100.516991 -6.764806 3.800000 +97.250000 0.000000 3.800000 +93.397057 3.102944 3.800000 +92.712257 -2.243082 3.800000 +93.013306 2.791211 3.800000 +92.200401 -2.095910 3.800000 +92.583427 2.568508 3.800000 +91.699997 -2.050000 3.800000 +92.136711 2.440067 3.800000 +91.699997 2.400000 3.800000 +91.199600 -2.095910 3.800000 +91.263290 2.440067 3.800000 +90.687737 -2.243082 3.800000 +122.488243 -1.815759 3.800000 +114.778938 -0.310428 3.800000 +21.954590 -0.494992 3.800000 +46.954590 -0.494992 3.800000 +46.900002 0.500000 3.800000 +21.900000 0.500000 3.800000 +113.045410 0.494992 3.800000 +113.099998 -0.500000 3.800000 +12.751048 -0.917166 3.800000 +20.248901 -0.364163 3.800000 +60.219986 -8.083406 3.800000 +60.222744 8.143861 3.800000 +12.490518 1.873348 3.800000 +20.221064 0.310428 3.800000 +122.258759 0.971635 3.800000 +114.751099 0.364163 3.800000 +23.513285 -4.240876 3.800000 +22.181963 -5.516695 3.800000 +22.000000 -5.500000 3.800000 +62.205860 -2.852734 3.800000 +62.631905 -5.570212 3.800000 +62.818035 -5.516695 3.800000 +61.486713 4.240876 3.800000 +62.818035 5.516695 3.800000 +63.000000 5.500000 3.800000 +22.794140 2.852734 3.800000 +22.368095 5.570212 3.800000 +22.181963 5.516695 3.800000 +111.486717 4.240876 3.800000 +112.818039 5.516695 3.800000 +113.000000 5.500000 3.800000 +89.340065 4.363289 3.800000 +85.336998 5.952790 3.800000 +21.818037 -5.516695 3.800000 +63.000000 -5.500000 3.800000 +63.181965 5.516695 3.800000 +22.000000 5.500000 3.800000 +113.181961 5.516695 3.800000 +85.207108 -5.792893 3.800000 +88.949997 -4.800000 3.800000 +85.483307 -6.681963 3.800000 +112.205856 -2.852734 3.800000 +112.631905 -5.570212 3.800000 +112.818039 -5.516695 3.800000 +113.000000 -5.500000 3.800000 +25.759125 -6.486715 3.800000 +22.983305 -6.318037 3.800000 +23.000000 -6.500000 3.800000 +22.983305 -6.681963 3.800000 +34.483013 -6.764806 3.800000 +35.183014 7.977242 3.800000 +24.519922 5.480078 3.800000 +23.000000 6.500000 3.800000 +22.983305 6.681963 3.800000 +22.929789 6.868095 3.800000 +109.240875 6.486715 3.800000 +112.016693 6.318037 3.800000 +112.000000 6.500000 3.800000 +112.016693 6.681963 3.800000 +100.516991 6.764806 3.800000 +99.816986 -7.977242 3.800000 +110.480080 -5.480078 3.800000 +112.000000 -6.500000 3.800000 +112.016693 -6.681963 3.800000 +112.070213 -6.868095 3.800000 +85.429787 6.868095 3.800000 +99.519920 -5.480078 3.800000 +94.404091 -5.300398 3.800000 +99.787018 -8.049596 3.800000 +94.256920 -5.812261 3.800000 +99.776794 -8.127241 3.800000 +94.001740 -6.304827 3.800000 +99.786667 -8.203564 3.800000 +90.816574 2.568508 3.800000 +90.195175 -2.498262 3.800000 +45.248901 -0.364163 3.800000 +62.452789 -7.336996 3.800000 +62.292892 7.207107 3.800000 +45.221062 0.310428 3.800000 +98.513283 4.240876 3.800000 +93.931496 5.683427 3.800000 +99.816986 7.977242 3.800000 +93.708786 6.113303 3.800000 +99.787018 8.049596 3.800000 +93.397057 6.497056 3.800000 +99.776794 8.127241 3.800000 +21.900000 -0.500000 3.800000 +46.900002 -0.500000 3.800000 +39.929787 -0.368095 3.800000 +45.500000 0.500000 3.800000 +39.836994 0.547210 3.800000 +20.500000 0.500000 3.800000 +114.712135 0.412132 3.800000 +113.099998 0.500000 3.800000 +114.500000 -0.500000 3.800000 +38.631905 -0.929788 3.800000 +60.222744 -8.143861 3.800000 +60.212982 8.204887 3.800000 +38.452789 0.836995 3.800000 +20.248901 0.364163 3.800000 +114.751099 -0.364163 3.800000 +20.287868 -0.412132 3.800000 +89.691208 6.113303 3.800000 +85.047211 -5.663004 3.800000 +85.207108 5.792893 3.800000 +89.755455 -6.744544 3.800000 +85.429787 -6.868095 3.800000 +89.468506 3.916573 3.800000 +85.336998 7.047210 3.800000 +8.848227 5.157227 3.800000 +125.239807 4.827653 3.800000 +126.059807 -5.132304 3.800000 +9.840670 -4.789151 3.800000 +22.929789 -6.868095 3.800000 +22.836996 7.047210 3.800000 +112.070213 6.868095 3.800000 +93.013306 6.808789 3.800000 +99.786667 8.203564 3.800000 +88.995911 -4.299602 3.800000 +99.816986 -8.277242 3.800000 +112.163002 -7.047210 3.800000 +122.920944 -2.728914 3.800000 +114.712135 -0.412132 3.800000 +21.631905 -5.570212 3.800000 +63.181965 -5.516695 3.800000 +63.368095 5.570212 3.800000 +21.818037 5.516695 3.800000 +12.043793 2.787230 3.800000 +20.287868 0.412132 3.800000 +113.368095 5.570212 3.800000 +93.644547 -6.744544 3.800000 +113.181961 -5.516695 3.800000 +12.498336 -1.852388 3.800000 +20.335836 -0.451099 3.800000 +45.287868 -0.412132 3.800000 +45.248901 0.364163 3.800000 +122.523331 1.909837 3.800000 +114.664162 0.451099 3.800000 +90.386696 2.791211 3.800000 +89.755455 -2.855456 3.800000 +84.868095 -5.570212 3.800000 +34.122986 -6.632041 3.800000 +34.240875 -6.486715 3.800000 +34.073204 -6.654998 3.800000 +33.726795 -6.854998 3.800000 +33.665634 -6.901708 3.800000 +33.616989 -6.964806 3.800000 +33.586666 -7.038483 3.800000 +33.576794 -7.114806 3.800000 +33.587017 -7.192451 3.800000 +33.616989 -7.264806 3.800000 +34.316986 -8.477242 3.800000 +32.852734 -7.205859 3.800000 +59.122986 -6.632041 3.800000 +59.240875 -6.486715 3.800000 +59.073204 -6.654998 3.800000 +58.726795 -6.854998 3.800000 +58.665634 -6.901708 3.800000 +58.616989 -6.964806 3.800000 +58.586666 -7.038483 3.800000 +58.576794 -7.114806 3.800000 +58.587017 -7.192451 3.800000 +58.616989 -7.264806 3.800000 +59.316986 -8.477242 3.800000 +57.852734 -7.205859 3.800000 +59.179371 6.618025 3.800000 +57.852734 7.205859 3.800000 +59.122986 6.632041 3.800000 +59.073204 6.654998 3.800000 +58.726795 6.854998 3.800000 +58.665634 6.901708 3.800000 +58.616989 6.964806 3.800000 +58.586666 7.038483 3.800000 +58.576794 7.114806 3.800000 +58.587017 7.192451 3.800000 +58.616989 7.264806 3.800000 +56.410213 7.620616 3.800000 +34.179371 6.618025 3.800000 +32.852734 7.205859 3.800000 +34.122986 6.632041 3.800000 +34.073204 6.654998 3.800000 +33.726795 6.854998 3.800000 +33.665634 6.901708 3.800000 +33.616989 6.964806 3.800000 +33.586666 7.038483 3.800000 +33.576794 7.114806 3.800000 +33.587017 7.192451 3.800000 +33.616989 7.264806 3.800000 +31.410213 7.620616 3.800000 +100.877014 6.632041 3.800000 +100.759125 6.486715 3.800000 +100.926796 6.654998 3.800000 +101.273209 6.854998 3.800000 +101.317978 6.886630 3.800000 +101.358307 6.928454 3.800000 +101.390923 6.979429 3.800000 +101.412979 7.037160 3.800000 +101.422745 7.098186 3.800000 +101.419983 7.158640 3.800000 +101.405968 7.215026 3.800000 +101.383011 7.264806 3.800000 +100.683014 8.477242 3.800000 +102.147263 7.205859 3.800000 +100.820633 -6.618025 3.800000 +102.147263 -7.205859 3.800000 +100.877014 -6.632041 3.800000 +100.926796 -6.654998 3.800000 +101.273209 -6.854998 3.800000 +101.317978 -6.886630 3.800000 +101.358307 -6.928454 3.800000 +101.390923 -6.979429 3.800000 +101.412979 -7.037160 3.800000 +101.422745 -7.098186 3.800000 +101.419983 -7.158640 3.800000 +101.405968 -7.215026 3.800000 +101.383011 -7.264806 3.800000 +103.589783 -7.620616 3.800000 +39.836994 -0.547210 3.800000 +39.707108 0.707107 3.800000 +22.794140 -2.852734 3.800000 +21.452789 -5.663004 3.800000 +20.500000 -0.500000 3.800000 +20.445412 -0.494992 3.800000 +21.292892 -5.792893 3.800000 +20.389572 -0.478936 3.800000 +21.163004 -5.952790 3.800000 +21.070211 -6.131905 3.800000 +21.016695 -6.318037 3.800000 +12.062460 -2.756567 3.800000 +21.000000 -6.500000 3.800000 +21.016695 -6.681963 3.800000 +11.452391 -3.576773 3.800000 +21.070211 -6.868095 3.800000 +37.620617 -1.410214 3.800000 +38.818035 -0.983305 3.800000 +39.000000 -1.000000 3.800000 +47.794140 -2.852734 3.800000 +62.631905 -7.429788 3.800000 +60.212982 -8.204887 3.800000 +62.452789 7.336996 3.800000 +60.190922 8.262618 3.800000 +47.379383 1.410214 3.800000 +37.205860 2.852734 3.800000 +38.631905 0.929788 3.800000 +38.818035 0.983305 3.800000 +22.379383 1.410214 3.800000 +21.631905 5.570212 3.800000 +20.445412 0.494992 3.800000 +20.389572 0.478936 3.800000 +21.452789 5.663004 3.800000 +20.335836 0.451099 3.800000 +21.292892 5.792893 3.800000 +21.163004 5.952790 3.800000 +21.070211 6.131905 3.800000 +11.418529 3.613839 3.800000 +21.016695 6.318037 3.800000 +21.000000 6.500000 3.800000 +10.645123 4.303824 3.800000 +21.016695 6.681963 3.800000 +21.070211 6.868095 3.800000 +112.205856 2.852734 3.800000 +113.547211 5.663004 3.800000 +114.500000 0.500000 3.800000 +114.554588 0.494992 3.800000 +113.707108 5.792893 3.800000 +114.610428 0.478936 3.800000 +113.836998 5.952790 3.800000 +113.929787 6.131905 3.800000 +113.983307 6.318037 3.800000 +122.973160 2.814679 3.800000 +114.000000 6.500000 3.800000 +113.983307 6.681963 3.800000 +123.598534 3.632252 3.800000 +113.929787 6.868095 3.800000 +113.836998 7.047210 3.800000 +85.047211 5.663004 3.800000 +112.620613 -1.410214 3.800000 +113.368095 -5.570212 3.800000 +114.554588 -0.494992 3.800000 +114.610428 -0.478936 3.800000 +113.547211 -5.663004 3.800000 +114.664162 -0.451099 3.800000 +113.707108 -5.792893 3.800000 +113.836998 -5.952790 3.800000 +113.929787 -6.131905 3.800000 +123.530807 -3.558121 3.800000 +113.983307 -6.318037 3.800000 +114.000000 -6.500000 3.800000 +124.288673 -4.254654 3.800000 +113.983307 -6.681963 3.800000 +113.929787 -6.868095 3.800000 +21.163004 -7.047210 3.800000 +10.696977 -4.265447 3.800000 +21.292892 -7.207107 3.800000 +21.452789 -7.336996 3.800000 +125.149277 -4.784225 3.800000 +113.836998 -7.047210 3.800000 +113.707108 -7.207107 3.800000 +85.336998 -7.047210 3.800000 +124.369385 4.314387 3.800000 +113.707108 7.207107 3.800000 +113.547211 7.336996 3.800000 +9.770308 4.822904 3.800000 +21.163004 7.047210 3.800000 +21.292892 7.207107 3.800000 +90.002945 6.497056 3.800000 +85.207108 7.207107 3.800000 +90.195175 -7.101737 3.800000 +45.335838 -0.451099 3.800000 +45.287868 0.412132 3.800000 +89.691208 3.486696 3.800000 +99.865631 -8.340340 3.800000 +90.002945 3.102944 3.800000 +84.868095 5.570212 3.800000 +89.398262 -3.295173 3.800000 +84.681961 5.516695 3.800000 +89.143082 -3.787740 3.800000 +84.681961 -5.516695 3.800000 +84.500000 -5.500000 3.800000 +84.500000 5.500000 3.800000 +84.318039 -5.516695 3.800000 +84.318039 5.516695 3.800000 +84.131905 -5.570212 3.800000 +84.131905 5.570212 3.800000 +83.952789 -5.663004 3.800000 +83.952789 5.663004 3.800000 +83.792892 -5.792893 3.800000 +22.836996 -7.047210 3.800000 +39.181965 -0.983305 3.800000 +45.500000 -0.500000 3.800000 +45.445412 0.494992 3.800000 +39.000000 1.000000 3.800000 +27.147266 -7.205859 3.800000 +22.707108 7.207107 3.800000 +25.759125 6.486715 3.800000 +112.163002 7.047210 3.800000 +107.852737 7.205859 3.800000 +99.816986 8.277242 3.800000 +112.292892 -7.207107 3.800000 +109.240875 -6.486715 3.800000 +63.368095 -5.570212 3.800000 +62.620617 -1.410214 3.800000 +62.205860 2.852734 3.800000 +63.547211 5.663004 3.800000 +22.707108 -7.207107 3.800000 +22.547211 7.336996 3.800000 +112.292892 7.207107 3.800000 +92.583427 7.031492 3.800000 +83.792892 5.792893 3.800000 +83.663002 -5.952790 3.800000 +112.452789 -7.336996 3.800000 +34.348618 -8.522013 3.800000 +59.348618 -8.522013 3.800000 +60.190922 -8.262618 3.800000 +63.547211 -5.663004 3.800000 +63.707108 5.792893 3.800000 +60.158306 8.313593 3.800000 +59.316986 8.477242 3.800000 +34.316986 8.477242 3.800000 +100.651382 8.522013 3.800000 +100.683014 -8.477242 3.800000 +85.207108 -7.207107 3.800000 +93.204826 -7.101737 3.800000 +39.707108 -0.707107 3.800000 +39.547211 0.836995 3.800000 +62.818035 -7.483305 3.800000 +62.631905 7.429788 3.800000 +85.047211 7.336996 3.800000 +90.386696 6.808789 3.800000 +21.452789 7.336996 3.800000 +113.368095 7.429788 3.800000 +113.547211 -7.336996 3.800000 +21.631905 -7.429788 3.800000 +36.486713 -4.240876 3.800000 +35.183014 -7.977242 3.800000 +35.480076 5.480078 3.800000 +35.205971 8.027020 3.800000 +35.205971 -8.027020 3.800000 +35.219986 8.083406 3.800000 +45.389572 -0.478936 3.800000 +45.335838 0.451099 3.800000 +90.687737 -7.356918 3.800000 +45.445412 -0.494992 3.800000 +48.513287 -4.240876 3.800000 +39.547211 -0.836995 3.800000 +39.368095 -0.929788 3.800000 +37.205860 -2.852734 3.800000 +35.219986 -8.083406 3.800000 +49.519924 -5.480078 3.800000 +35.222744 -8.143861 3.800000 +35.212982 -8.204887 3.800000 +50.759125 -6.486715 3.800000 +35.190922 -8.262618 3.800000 +35.158306 -8.313593 3.800000 +52.147266 -7.205859 3.800000 +35.117977 -8.355417 3.800000 +45.389572 0.478936 3.800000 +47.794140 2.852734 3.800000 +39.368095 0.929788 3.800000 +39.181965 0.983305 3.800000 +36.486713 4.240876 3.800000 +35.222744 8.143861 3.800000 +48.513287 4.240876 3.800000 +35.212982 8.204887 3.800000 +35.190922 8.262618 3.800000 +49.519924 5.480078 3.800000 +35.158306 8.313593 3.800000 +35.117977 8.355417 3.800000 +50.759125 6.486715 3.800000 +35.073204 8.387049 3.800000 +99.926796 -8.387049 3.800000 +60.158306 -8.313593 3.800000 +60.117977 8.355417 3.800000 +99.865631 8.340340 3.800000 +83.663002 5.952790 3.800000 +83.570213 -6.131905 3.800000 +85.047211 -7.336996 3.800000 +34.390442 -8.562344 3.800000 +35.073204 -8.387049 3.800000 +59.390442 -8.562344 3.800000 +59.348618 8.522013 3.800000 +34.726795 8.587049 3.800000 +34.348618 8.522013 3.800000 +100.609558 8.562344 3.800000 +92.136711 7.159933 3.800000 +100.651382 -8.522013 3.800000 +22.547211 -7.336996 3.800000 +63.707108 -5.792893 3.800000 +63.836994 5.952790 3.800000 +22.368095 7.429788 3.800000 +112.452789 7.336996 3.800000 +112.631905 -7.429788 3.800000 +84.868095 7.429788 3.800000 +92.712257 -7.356918 3.800000 +100.273209 -8.587049 3.800000 +63.000000 -7.500000 3.800000 +62.818035 7.483305 3.800000 +31.410213 -7.620616 3.800000 +56.410213 -7.620616 3.800000 +55.000000 7.750000 3.800000 +30.000000 7.750000 3.800000 +103.589783 7.620616 3.800000 +105.000000 -7.750000 3.800000 +113.368095 -7.429788 3.800000 +34.441418 -8.594960 3.800000 +59.441418 -8.594960 3.800000 +59.390442 8.562344 3.800000 +34.390442 8.562344 3.800000 +100.558578 8.594960 3.800000 +100.609558 -8.562344 3.800000 +21.818037 -7.483305 3.800000 +21.631905 7.429788 3.800000 +113.181961 7.483305 3.800000 +99.926796 8.387049 3.800000 +34.726795 -8.587049 3.800000 +53.589787 -7.620616 3.800000 +62.750000 0.000000 3.800000 +62.620617 1.410214 3.800000 +63.836994 -5.952790 3.800000 +63.929787 6.131905 3.800000 +52.147266 7.205859 3.800000 +34.677017 8.610006 3.800000 +90.816574 7.031492 3.800000 +28.589787 -7.620616 3.800000 +60.117977 -8.355417 3.800000 +60.073204 8.387049 3.800000 +27.147266 7.205859 3.800000 +106.410217 7.620616 3.800000 +107.852737 -7.205859 3.800000 +112.818039 -7.483305 3.800000 +112.631905 7.429788 3.800000 +22.181963 7.483305 3.800000 +22.368095 -7.429788 3.800000 +100.322983 -8.610006 3.800000 +63.929787 -6.131905 3.800000 +83.570213 6.131905 3.800000 +91.199600 -7.504090 3.800000 +63.983307 6.318037 3.800000 +83.516693 -6.318037 3.800000 +84.868095 -7.429788 3.800000 +91.699997 7.200000 3.800000 +100.273209 8.587049 3.800000 +60.073204 -8.387049 3.800000 +63.181965 -7.483305 3.800000 +59.726795 8.587049 3.800000 +63.000000 7.500000 3.800000 +84.681961 7.483305 3.800000 +92.200401 -7.504090 3.800000 +34.499149 -8.617019 3.800000 +34.677017 -8.610006 3.800000 +59.499149 -8.617019 3.800000 +59.441418 8.594960 3.800000 +34.620628 8.624022 3.800000 +34.441418 8.594960 3.800000 +21.818037 7.483305 3.800000 +113.000000 7.500000 3.800000 +100.500854 8.617019 3.800000 +100.558578 -8.594960 3.800000 +113.181961 -7.483305 3.800000 +22.000000 -7.500000 3.800000 +55.000000 -7.750000 3.800000 +59.560177 -8.626781 3.800000 +53.589787 7.620616 3.800000 +59.499149 8.617019 3.800000 +91.263290 7.159933 3.800000 +100.322983 8.610006 3.800000 +84.500000 7.500000 3.800000 +59.726795 -8.587049 3.800000 +59.677017 8.610006 3.800000 +22.181963 -7.483305 3.800000 +22.000000 7.500000 3.800000 +112.818039 7.483305 3.800000 +28.589787 7.620616 3.800000 +34.499149 8.617019 3.800000 +127.069458 8.850000 3.800000 +34.560177 8.626781 3.800000 +59.560177 8.626781 3.800000 +59.620628 8.624022 3.800000 +105.000000 7.750000 3.800000 +100.439827 8.626781 3.800000 +100.379372 8.624022 3.800000 +84.318039 7.483305 3.800000 +63.181965 7.483305 3.800000 +84.131905 7.429788 3.800000 +63.368095 7.429788 3.800000 +83.952789 7.336996 3.800000 +63.547211 7.336996 3.800000 +83.792892 7.207107 3.800000 +63.707108 7.207107 3.800000 +83.663002 7.047210 3.800000 +63.836994 7.047210 3.800000 +83.570213 6.868095 3.800000 +63.929787 6.868095 3.800000 +83.516693 6.681963 3.800000 +63.983307 6.681963 3.800000 +83.500000 6.500000 3.800000 +64.000000 6.500000 3.800000 +83.516693 6.318037 3.800000 +63.983307 -6.318037 3.800000 +83.500000 -6.500000 3.800000 +64.000000 -6.500000 3.800000 +83.516693 -6.681963 3.800000 +63.983307 -6.681963 3.800000 +83.570213 -6.868095 3.800000 +63.929787 -6.868095 3.800000 +83.663002 -7.047210 3.800000 +63.836994 -7.047210 3.800000 +83.792892 -7.207107 3.800000 +63.707108 -7.207107 3.800000 +83.952789 -7.336996 3.800000 +63.547211 -7.336996 3.800000 +84.131905 -7.429788 3.800000 +63.368095 -7.429788 3.800000 +84.318039 -7.483305 3.800000 +59.677017 -8.610006 3.800000 +84.500000 -7.500000 3.800000 +100.379372 -8.624022 3.800000 +113.000000 -7.500000 3.800000 +106.410217 -7.620616 3.800000 +100.500854 -8.617019 3.800000 +8.030544 -8.850000 3.800000 +100.439827 -8.626781 3.800000 +30.000000 -7.750000 3.800000 +34.560177 -8.626781 3.800000 +84.681961 -7.483305 3.800000 +91.699997 -7.550000 3.800000 +59.620628 -8.624022 3.800000 +56.291939 6.981468 2.000000 +128.504471 -1.107405 2.000000 +93.568283 -4.454270 2.000000 +98.018532 -1.291938 2.000000 +93.466599 -4.100620 2.000000 +98.398506 2.613472 2.000000 +93.290291 3.760301 2.000000 +93.466599 4.100620 2.000000 +6.531325 1.129348 2.000000 +23.018532 1.291938 2.000000 +7.114645 0.700531 2.000000 +111.981468 -1.291938 2.000000 +127.886307 -0.695854 2.000000 +127.877815 -0.777817 2.000000 +37.099998 0.000000 2.000000 +48.018532 1.291938 2.000000 +47.900002 0.000000 2.000000 +36.981468 -1.291938 2.000000 +98.398506 -2.613472 2.000000 +93.599998 -4.800000 2.000000 +99.057335 3.885189 2.000000 +93.568283 4.454270 2.000000 +7.122182 0.777817 2.000000 +22.900000 0.000000 2.000000 +112.099998 0.000000 2.000000 +7.091734 0.624744 2.000000 +127.910721 -0.618946 2.000000 +128.560654 -1.060660 2.000000 +6.439340 1.060660 2.000000 +93.290291 -3.760301 2.000000 +93.043503 3.456497 2.000000 +128.436691 -1.144914 2.000000 +93.568283 -5.145730 2.000000 +93.599998 4.800000 2.000000 +36.981468 1.291938 2.000000 +48.398502 2.613472 2.000000 +48.018532 -1.291938 2.000000 +36.601498 -2.613472 2.000000 +127.886307 -0.859781 2.000000 +111.601494 -2.613472 2.000000 +23.398502 2.613472 2.000000 +97.900002 0.000000 2.000000 +93.043503 -3.456497 2.000000 +98.018532 1.291938 2.000000 +92.739700 3.209708 2.000000 +92.739700 -3.209708 2.000000 +92.399384 3.033402 2.000000 +92.399384 -3.033402 2.000000 +92.045731 2.931720 2.000000 +92.045731 -2.931720 2.000000 +91.699997 2.900000 2.000000 +91.699997 -2.900000 2.000000 +91.354271 2.931720 2.000000 +91.354271 -2.931720 2.000000 +91.000618 3.033402 2.000000 +7.105709 0.891430 2.000000 +6.644146 1.170132 2.000000 +7.054345 0.554954 2.000000 +23.018532 -1.291938 2.000000 +111.981468 1.291938 2.000000 +127.948227 -0.551164 2.000000 +128.735947 -0.849952 2.000000 +6.264046 0.849952 2.000000 +128.359787 -1.169330 2.000000 +127.910721 -0.936688 2.000000 +99.057335 -3.885189 2.000000 +93.466599 -5.499380 2.000000 +99.979546 5.020458 2.000000 +93.568283 5.145730 2.000000 +91.000618 -3.033402 2.000000 +90.660301 3.209708 2.000000 +36.601498 2.613472 2.000000 +49.057331 3.885189 2.000000 +48.398502 -2.613472 2.000000 +35.942669 -3.885189 2.000000 +127.994972 -0.494975 2.000000 +7.005025 0.494975 2.000000 +6.923222 0.396644 2.000000 +6.857581 0.278024 2.000000 +6.814853 0.143437 2.000000 +6.800000 0.000000 2.000000 +6.814853 -0.143437 2.000000 +6.857581 -0.278024 2.000000 +6.923222 -0.396644 2.000000 +7.005025 -0.494975 2.000000 +7.051770 -0.551164 2.000000 +7.089279 -0.618946 2.000000 +7.113695 -0.695854 2.000000 +7.122182 -0.777817 2.000000 +7.113695 -0.859781 2.000000 +7.089279 -0.936688 2.000000 +7.051770 -1.004471 2.000000 +128.076782 -0.396644 2.000000 +128.142426 -0.278024 2.000000 +128.185150 -0.143437 2.000000 +128.199997 0.000000 2.000000 +128.185150 0.143437 2.000000 +128.142426 0.278024 2.000000 +128.076782 0.396644 2.000000 +127.994972 0.494975 2.000000 +127.945656 0.554954 2.000000 +127.908264 0.624744 2.000000 +127.885353 0.700531 2.000000 +127.877815 0.777817 2.000000 +127.894295 0.891430 2.000000 +127.945229 1.000046 2.000000 +93.290291 -5.839698 2.000000 +93.466599 5.499380 2.000000 +136.610367 -8.702252 2.000000 +138.257645 -8.228626 2.000000 +128.876617 -0.595766 2.000000 +139.842804 -7.407410 2.000000 +141.257889 -6.257895 2.000000 +142.407410 -4.842806 2.000000 +143.228622 -3.257638 2.000000 +143.702255 -1.610373 2.000000 +128.968170 -0.307364 2.000000 +143.850006 0.000000 2.000000 +143.702255 1.610373 2.000000 +143.228622 3.257638 2.000000 +142.407410 4.842806 2.000000 +141.257889 6.257895 2.000000 +139.842804 7.407410 2.000000 +129.000000 0.000000 2.000000 +138.257645 8.228626 2.000000 +136.610367 8.702252 2.000000 +135.000000 8.850000 2.000000 +128.968170 0.307364 2.000000 +128.876617 0.595766 2.000000 +128.735947 0.849952 2.000000 +128.560654 1.060660 2.000000 +128.468674 1.129348 2.000000 +-1.610373 8.702252 2.000000 +-3.257638 8.228626 2.000000 +6.123387 0.595766 2.000000 +-4.842806 7.407410 2.000000 +-6.257895 6.257895 2.000000 +-7.407410 4.842806 2.000000 +-8.228626 3.257638 2.000000 +-8.702252 1.610373 2.000000 +6.031828 0.307364 2.000000 +-8.850000 0.000000 2.000000 +-8.702252 -1.610373 2.000000 +-8.228626 -3.257638 2.000000 +-7.407410 -4.842806 2.000000 +-6.257895 -6.257895 2.000000 +-4.842806 -7.407410 2.000000 +6.000000 0.000000 2.000000 +-3.257638 -8.228626 2.000000 +-1.610373 -8.702252 2.000000 +0.000000 -8.850000 2.000000 +6.031828 -0.307364 2.000000 +6.123387 -0.595766 2.000000 +6.264046 -0.849952 2.000000 +6.439340 -1.060660 2.000000 +6.495529 -1.107405 2.000000 +6.563312 -1.144914 2.000000 +111.601494 2.613472 2.000000 +128.026077 1.088672 2.000000 +24.057331 3.885189 2.000000 +7.054770 1.000046 2.000000 +23.398502 -2.613472 2.000000 +7.005025 -1.060660 2.000000 +110.942665 -3.885189 2.000000 +127.948227 -1.004471 2.000000 +6.640219 -1.169330 2.000000 +128.277817 -1.177817 2.000000 +128.355850 1.170132 2.000000 +6.763987 1.175627 2.000000 +90.660301 -3.209708 2.000000 +90.356499 3.456497 2.000000 +35.942669 3.885189 2.000000 +49.979542 5.020458 2.000000 +49.057331 -3.885189 2.000000 +35.020458 -5.020458 2.000000 +6.948836 -1.107405 2.000000 +127.994972 -1.060660 2.000000 +99.979546 -5.020458 2.000000 +93.043503 -6.143503 2.000000 +101.114807 5.942668 2.000000 +93.290291 5.839698 2.000000 +6.722183 -1.177817 2.000000 +128.195847 -1.169330 2.000000 +110.942665 3.885189 2.000000 +128.124741 1.147369 2.000000 +24.979542 5.020458 2.000000 +6.973916 1.088672 2.000000 +24.057331 -3.885189 2.000000 +110.020454 -5.020458 2.000000 +6.881053 -1.144914 2.000000 +128.051163 -1.107405 2.000000 +90.356499 -3.456497 2.000000 +90.109711 3.760301 2.000000 +35.020458 5.020458 2.000000 +51.114811 5.942668 2.000000 +49.979542 -5.020458 2.000000 +33.885189 -5.942668 2.000000 +92.739700 -6.390292 2.000000 +93.043503 6.143503 2.000000 +128.236008 1.175627 2.000000 +110.020454 5.020458 2.000000 +6.875256 1.147369 2.000000 +26.114811 5.942668 2.000000 +27.386528 6.601497 2.000000 +108.885193 5.942668 2.000000 +101.114807 -5.942668 2.000000 +102.386528 6.601497 2.000000 +6.804146 -1.169330 2.000000 +24.979542 -5.020458 2.000000 +26.114811 -5.942668 2.000000 +128.118942 -1.144914 2.000000 +108.885193 -5.942668 2.000000 +107.613472 -6.601497 2.000000 +92.739700 6.390292 2.000000 +92.399384 -6.566598 2.000000 +90.109711 -3.760301 2.000000 +89.933403 4.100620 2.000000 +33.885189 5.942668 2.000000 +52.386528 6.601497 2.000000 +51.114811 -5.942668 2.000000 +32.613472 -6.601497 2.000000 +107.613472 6.601497 2.000000 +28.708063 6.981468 2.000000 +27.386528 -6.601497 2.000000 +106.291939 -6.981468 2.000000 +92.045731 -6.668280 2.000000 +89.933403 -4.100620 2.000000 +102.386528 -6.601497 2.000000 +89.831718 4.454270 2.000000 +92.399384 6.566598 2.000000 +103.708061 6.981468 2.000000 +32.613472 6.601497 2.000000 +53.708061 6.981468 2.000000 +52.386528 -6.601497 2.000000 +31.291937 -6.981468 2.000000 +106.291939 6.981468 2.000000 +0.000000 8.850000 2.000000 +105.000000 7.100000 2.000000 +30.000000 7.100000 2.000000 +28.708063 -6.981468 2.000000 +135.000000 -8.850000 2.000000 +30.000000 -7.100000 2.000000 +105.000000 -7.100000 2.000000 +91.699997 -6.700000 2.000000 +92.045731 6.668280 2.000000 +91.699997 6.700000 2.000000 +91.354271 6.668280 2.000000 +91.000618 6.566598 2.000000 +90.660301 6.390292 2.000000 +89.831718 -4.454270 2.000000 +31.291937 6.981468 2.000000 +53.708061 -6.981468 2.000000 +55.000000 -7.100000 2.000000 +103.708061 -6.981468 2.000000 +91.354271 -6.668280 2.000000 +56.291939 -6.981468 2.000000 +91.000618 -6.566598 2.000000 +57.613472 -6.601497 2.000000 +90.660301 -6.390292 2.000000 +90.356499 -6.143503 2.000000 +58.885189 -5.942668 2.000000 +90.109711 -5.839698 2.000000 +60.020458 -5.020458 2.000000 +89.933403 -5.499380 2.000000 +60.942669 -3.885189 2.000000 +89.831718 -5.145730 2.000000 +61.601498 -2.613472 2.000000 +89.800003 -4.800000 2.000000 +61.981468 -1.291938 2.000000 +62.099998 0.000000 2.000000 +89.800003 4.800000 2.000000 +61.981468 1.291938 2.000000 +89.831718 5.145730 2.000000 +89.933403 5.499380 2.000000 +61.601498 2.613472 2.000000 +90.109711 5.839698 2.000000 +60.942669 3.885189 2.000000 +90.356499 6.143503 2.000000 +60.020458 5.020458 2.000000 +58.885189 5.942668 2.000000 +57.613472 6.601497 2.000000 +55.000000 7.100000 2.000000 +6.964030 1.076464 3.800000 +5.037556 3.766480 3.800000 +6.450447 1.049553 3.800000 +4.318019 3.181981 3.800000 +6.276989 0.841051 3.800000 +3.733520 2.462444 3.800000 +6.137804 0.589527 3.800000 +3.315953 1.656426 3.800000 +6.047204 0.304145 3.800000 +3.075126 0.818834 3.800000 +6.015708 0.000000 3.800000 +3.000000 0.000000 3.800000 +6.047204 -0.304145 3.800000 +3.075126 -0.818834 3.800000 +6.137804 -0.589527 3.800000 +3.315953 -1.656426 3.800000 +6.276989 -0.841051 3.800000 +3.733520 -2.462444 3.800000 +6.450447 -1.049553 3.800000 +4.318019 -3.181981 3.800000 +6.504430 -1.094462 3.800000 +5.843574 4.184047 3.800000 +6.538820 1.115543 3.800000 +5.037556 -3.766480 3.800000 +6.569551 -1.130498 3.800000 +6.643437 -1.153955 3.800000 +5.843574 -4.184047 3.800000 +6.722183 -1.162109 3.800000 +6.681166 4.424874 3.800000 +6.647211 1.154725 3.800000 +7.500000 4.500000 3.800000 +6.762345 1.160005 3.800000 +6.681166 -4.424874 3.800000 +6.800928 -1.153955 3.800000 +6.874815 -1.130498 3.800000 +7.500000 -4.500000 3.800000 +6.939936 -1.094462 3.800000 +8.318833 4.424874 3.800000 +6.869245 1.132857 3.800000 +9.156426 4.184047 3.800000 +8.318833 -4.424874 3.800000 +6.993918 -1.049553 3.800000 +9.156426 -4.184047 3.800000 +7.038827 -0.995570 3.800000 +9.962444 -3.766480 3.800000 +7.074863 -0.930449 3.800000 +10.681980 -3.181981 3.800000 +7.098320 -0.856562 3.800000 +11.266479 -2.462444 3.800000 +7.106474 -0.777817 3.800000 +11.684048 -1.656426 3.800000 +11.924874 -0.818834 3.800000 +7.098320 -0.699072 3.800000 +12.000000 0.000000 3.800000 +7.074863 -0.625186 3.800000 +11.924874 0.818834 3.800000 +11.684048 1.656426 3.800000 +7.038827 -0.560065 3.800000 +11.266479 2.462444 3.800000 +6.993918 -0.506082 3.800000 +10.681980 3.181981 3.800000 +6.910278 -0.405545 3.800000 +6.843164 -0.284263 3.800000 +6.799479 -0.146655 3.800000 +6.784292 0.000000 3.800000 +6.799479 0.146655 3.800000 +6.843164 0.284263 3.800000 +6.910278 0.405545 3.800000 +6.993918 0.506082 3.800000 +7.041301 0.563706 3.800000 +7.077222 0.630755 3.800000 +7.099233 0.703566 3.800000 +7.106474 0.777817 3.800000 +7.090647 0.886968 3.800000 +7.041709 0.991318 3.800000 +9.962444 3.766480 3.800000 +132.451462 -1.974254 3.800000 +143.623398 -1.989825 3.800000 +143.839523 -0.430544 3.800000 +143.252167 -0.430544 3.800000 +143.128296 -0.987778 3.800000 +128.030548 -5.304076 3.800000 +128.030548 -8.850000 3.800000 +128.918549 -5.138328 3.800000 +129.806793 -4.805559 3.800000 +130.648560 -4.301307 3.800000 +131.395462 -3.638686 3.800000 +142.895493 -1.542108 3.800000 +143.099091 -3.567523 3.800000 +142.551514 -2.061970 3.800000 +136.795990 -0.704506 3.800000 +136.722382 -0.138438 3.800000 +132.827896 -0.168183 3.800000 +136.978378 -1.277409 3.800000 +142.106445 -2.514932 3.800000 +142.251953 -5.072635 3.800000 +141.582428 -2.873655 3.800000 +141.103775 -6.408308 3.800000 +141.010284 -3.121104 3.800000 +140.423721 -3.253065 3.800000 +139.713821 -7.490149 3.800000 +132.005692 -2.848403 3.800000 +137.274551 -1.825908 3.800000 +138.169281 -8.263058 3.800000 +139.287506 -3.202238 3.800000 +136.567947 -8.709996 3.800000 +138.715057 -3.018428 3.800000 +135.000000 -8.850000 3.800000 +138.167297 -2.720882 3.800000 +137.677414 -2.316802 3.800000 +122.553871 -1.904159 7.300000 +126.584976 5.220416 7.300000 +127.099998 5.284884 7.300000 +127.069458 5.313128 3.800000 +126.969460 -5.304076 3.800000 +127.000000 -5.276362 7.300000 +126.480453 -5.232134 3.800000 +126.486298 -5.202154 7.300000 +125.491020 -4.937479 3.800000 +125.502533 -4.909187 7.300000 +124.540962 -4.433825 3.800000 +123.695221 -3.733409 3.800000 +124.557922 -4.408419 7.300000 +123.717018 -3.712016 7.300000 +123.010941 -2.874554 3.800000 +123.036667 -2.858083 7.300000 +122.525368 -1.915133 3.800000 +125.595840 4.946127 7.300000 +126.579704 5.250501 3.800000 +124.641914 4.463336 7.300000 +125.584869 4.974632 3.800000 +123.787987 3.782979 7.300000 +124.625443 4.489058 3.800000 +123.766594 3.804781 3.800000 +123.091583 2.942081 7.300000 +123.066177 2.959036 3.800000 +122.590813 1.997470 7.300000 +122.562523 2.008981 3.800000 +122.297844 1.013702 7.300000 +122.200241 0.050179 7.300000 +122.267868 1.019544 3.800000 +122.169693 0.050468 3.800000 +122.279587 -0.915020 7.300000 +122.249496 -0.920293 3.800000 +131.373734 -3.617210 7.300000 +132.827896 -0.168183 3.800000 +132.798203 -0.137865 7.300000 +132.722992 -1.065413 3.800000 +132.721664 -0.907845 7.300000 +132.451462 -1.974254 3.800000 +132.433228 -1.937339 7.300000 +132.005692 -2.848403 3.800000 +131.395462 -3.638686 3.800000 +131.967255 -2.851946 7.300000 +128.762924 -5.147332 7.300000 +128.000000 -5.276362 7.300000 +128.030548 -5.304076 3.800000 +129.770279 -4.789139 7.300000 +128.918549 -5.138328 3.800000 +130.650864 -4.261698 7.300000 +129.806793 -4.805559 3.800000 +130.648560 -4.301307 3.800000 +105.449997 -11.400000 3.350000 +105.449997 -12.700000 3.350000 +54.650002 -11.400000 3.350000 +54.650002 -12.700000 3.350000 +55.150002 -12.700000 3.350000 +49.950001 -11.400000 3.350000 +49.950001 -12.700000 3.350000 +50.450001 -12.700000 3.350000 +126.965530 -11.100000 3.350000 +8.034472 -11.100000 3.350000 +8.034472 -11.400000 3.350000 +100.750000 -11.400000 3.350000 +100.750000 -12.700000 3.350000 +101.250000 -12.700000 3.350000 +84.550003 -12.700000 3.350000 +85.050003 -12.700000 3.350000 +84.550003 -11.400000 3.350000 +79.849998 -12.700000 3.350000 +80.349998 -12.700000 3.350000 +79.849998 -11.400000 3.350000 +33.750000 -12.700000 3.350000 +34.250000 -12.700000 3.350000 +33.750000 -11.400000 3.350000 +29.049999 -12.700000 3.350000 +29.549999 -12.700000 3.350000 +29.049999 -11.400000 3.350000 +29.549999 -11.400000 3.350000 +34.250000 -11.400000 3.350000 +50.450001 -11.400000 3.350000 +55.150002 -11.400000 3.350000 +80.349998 -11.400000 3.350000 +85.050003 -11.400000 3.350000 +101.250000 -11.400000 3.350000 +105.949997 -11.400000 3.350000 +126.965530 -11.400000 3.350000 +105.949997 -12.700000 3.350000 +128.034470 -11.400000 3.350000 +146.131927 -2.457691 3.350000 +146.391724 -0.434471 3.350000 +146.091492 -0.434471 3.350000 +145.470139 -4.509571 3.350000 +145.836761 -2.403063 3.350000 +144.385651 -6.470667 3.350000 +145.191071 -4.399086 3.350000 +142.905914 -8.213190 3.350000 +144.134476 -6.306450 3.350000 +141.108261 -9.625441 3.350000 +142.693741 -8.001019 3.350000 +139.107269 -10.634397 3.350000 +140.944077 -9.374322 3.350000 +137.031647 -11.217504 3.350000 +138.996826 -10.355454 3.350000 +135.000000 -11.400000 3.350000 +136.977051 -10.922511 3.350000 +135.000000 -11.100000 3.350000 +128.034470 -11.100000 3.350000 +8.034508 -11.100000 3.345793 +126.965492 -11.100000 3.345793 +126.969460 -8.850000 3.800000 +8.030544 -8.850000 3.800000 +126.968452 -9.997694 3.685314 +8.031545 -9.997694 3.685314 +135.000000 -9.997694 3.685314 +128.034515 -11.100000 3.345793 +135.000000 -11.100000 3.345793 +128.031540 -9.997694 3.685314 +135.000000 -11.016247 3.380277 +135.000000 -8.850000 3.800000 +128.030548 -8.850000 3.800000 +135.000000 -8.940572 3.799293 +8.034472 -11.100000 3.350000 +8.034472 -11.100000 3.350000 +126.965530 -11.100000 3.350000 +126.965530 -11.100000 3.350000 +135.000000 -11.100000 3.345793 +135.000000 -11.100000 3.345793 +128.034515 -11.100000 3.345793 +128.034515 -11.100000 3.345793 +137.220291 1.742168 3.800000 +143.252167 0.430544 3.800000 +143.839523 0.430544 3.800000 +142.926056 1.483298 3.800000 +142.616745 1.978530 3.800000 +143.623398 1.989825 3.800000 +142.217499 2.417580 3.800000 +141.745667 2.777518 3.800000 +143.099091 3.567523 3.800000 +141.225632 3.042994 3.800000 +135.000000 8.850000 3.800000 +127.930542 8.850000 3.800000 +127.930542 5.313128 3.800000 +129.628021 4.887351 3.800000 +130.440491 4.446146 3.800000 +131.174942 3.861284 3.800000 +140.148682 3.277173 3.800000 +142.251953 5.072635 3.800000 +132.276199 2.366971 3.800000 +132.785355 0.692605 3.800000 +136.800186 0.723270 3.800000 +141.103775 6.408308 3.800000 +139.054962 3.141476 3.800000 +139.713821 7.490149 3.800000 +138.513016 2.924183 3.800000 +138.169281 8.263058 3.800000 +138.010544 2.608449 3.800000 +136.567947 8.709996 3.800000 +137.573166 2.207357 3.800000 +131.795380 3.156636 3.800000 +34.049999 12.700000 3.350000 +33.549999 12.700000 3.350000 +38.750000 12.700000 3.350000 +38.250000 12.700000 3.350000 +38.750000 11.400000 3.350000 +59.650002 11.400000 3.350000 +59.650002 12.700000 3.350000 +59.150002 12.700000 3.350000 +75.849998 12.700000 3.350000 +75.349998 12.700000 3.350000 +75.849998 11.400000 3.350000 +96.750000 12.700000 3.350000 +96.250000 12.700000 3.350000 +96.750000 11.400000 3.350000 +7.934471 11.100000 3.350000 +127.065529 11.100000 3.350000 +127.065529 11.400000 3.350000 +54.950001 12.700000 3.350000 +54.450001 12.700000 3.350000 +54.950001 11.400000 3.350000 +80.550003 12.700000 3.350000 +80.050003 12.700000 3.350000 +80.550003 11.400000 3.350000 +101.449997 12.700000 3.350000 +100.949997 12.700000 3.350000 +101.449997 11.400000 3.350000 +100.949997 11.400000 3.350000 +96.250000 11.400000 3.350000 +80.050003 11.400000 3.350000 +75.349998 11.400000 3.350000 +59.150002 11.400000 3.350000 +54.450001 11.400000 3.350000 +38.250000 11.400000 3.350000 +33.549999 11.400000 3.350000 +7.934471 11.400000 3.350000 +34.049999 11.400000 3.350000 +135.000000 11.400000 3.350000 +146.091492 0.434471 3.350000 +146.391724 0.434471 3.350000 +145.836761 2.403063 3.350000 +146.131927 2.457691 3.350000 +145.191071 4.399086 3.350000 +145.470139 4.509571 3.350000 +144.134476 6.306450 3.350000 +144.385651 6.470667 3.350000 +142.693741 8.001019 3.350000 +142.905914 8.213190 3.350000 +140.944077 9.374322 3.350000 +141.108261 9.625441 3.350000 +138.996826 10.355454 3.350000 +139.107269 10.634397 3.350000 +136.977051 10.922511 3.350000 +137.031647 11.217504 3.350000 +135.000000 11.100000 3.350000 +127.934471 11.400000 3.350000 +127.934471 11.100000 3.350000 +127.065491 11.100000 3.345793 +7.934508 11.100000 3.345793 +7.930544 8.850000 3.800000 +127.069458 8.850000 3.800000 +7.931545 9.997694 3.685314 +127.068459 9.997694 3.685314 +135.000000 11.016247 3.380277 +135.000000 11.100000 3.345793 +127.931541 9.997694 3.685314 +127.930542 8.850000 3.800000 +135.000000 8.850000 3.800000 +135.000000 8.940572 3.799293 +127.934509 11.100000 3.345793 +135.000000 9.997694 3.685314 +127.065491 11.100000 3.345793 +7.934508 11.100000 3.345793 +7.934508 11.100000 3.345793 +127.065491 11.100000 3.345793 +127.934471 11.100000 3.350000 +135.000000 11.100000 3.350000 +135.000000 11.100000 3.350000 +127.934471 11.100000 3.350000 +132.688705 1.221477 3.800000 +132.658981 1.214478 7.300000 +132.758514 0.661855 7.300000 +132.785355 0.692605 3.800000 +127.930542 5.313128 3.800000 +127.900002 5.284884 7.300000 +128.462402 5.242945 3.800000 +128.456894 5.212903 7.300000 +129.495056 4.943119 3.800000 +129.483627 4.914795 7.300000 +130.410492 4.465840 3.800000 +131.174515 3.861682 3.800000 +130.393814 4.440251 7.300000 +131.815857 3.128586 3.800000 +131.153473 3.839555 7.300000 +132.337997 2.237975 3.800000 +131.791138 3.110659 7.300000 +132.310272 2.225151 7.300000 +144.987808 0.431544 3.685430 +146.091492 0.434508 3.345793 +144.134460 6.306470 3.345793 +145.191071 4.399112 3.345793 +145.836746 2.403095 3.345793 +143.839523 0.430544 3.800000 +143.623398 1.989825 3.800000 +143.099091 3.567523 3.800000 +142.251953 5.072635 3.800000 +141.103775 6.408308 3.800000 +139.713821 7.490149 3.800000 +138.169281 8.263058 3.800000 +136.567947 8.709996 3.800000 +142.693726 8.001032 3.345793 +140.944061 9.374329 3.345793 +138.996811 10.355457 3.345793 +135.000000 8.940572 3.799293 +135.000000 8.850000 3.800000 +136.977051 10.922512 3.345793 +135.000000 11.100000 3.345793 +135.000000 11.016247 3.380277 +135.000000 9.997694 3.685314 +136.660690 8.788490 3.799238 +143.950287 6.417131 3.381562 +142.633194 7.938622 3.381562 +145.019409 4.571501 3.381562 +145.733032 2.467636 3.381562 +144.743500 2.240130 3.685314 +143.716614 2.004038 3.799238 +143.137054 3.712648 3.799238 +142.268784 5.211537 3.799238 +141.199127 6.447184 3.799238 +139.922485 7.467564 3.799238 +138.390701 8.276384 3.799238 +141.061218 9.195047 3.381562 +139.175079 10.190974 3.381562 +137.044861 10.821546 3.381562 +136.856323 9.823845 3.685314 +144.095673 4.150028 3.685314 +143.125107 5.825499 3.685314 +141.929443 7.206715 3.685314 +140.502396 8.347303 3.685314 +138.790161 9.251410 3.685314 +136.567947 -8.709996 3.800000 +145.836746 -2.403095 3.345793 +146.091492 -0.434508 3.345793 +140.944061 -9.374329 3.345793 +138.996811 -10.355457 3.345793 +136.977051 -10.922512 3.345793 +142.693726 -8.001032 3.345793 +144.134460 -6.306470 3.345793 +145.191071 -4.399112 3.345793 +144.988190 -0.431545 3.685352 +143.839523 -0.430544 3.800000 +143.623398 -1.989825 3.800000 +143.099091 -3.567523 3.800000 +142.251953 -5.072635 3.800000 +141.103775 -6.408308 3.800000 +139.713821 -7.490149 3.800000 +138.169281 -8.263058 3.800000 +135.000000 -9.997694 3.685314 +135.000000 -11.100000 3.345793 +135.000000 -8.850000 3.800000 +136.660690 -8.788490 3.799238 +142.633194 -7.938622 3.381562 +141.061218 -9.195048 3.381562 +139.175079 -10.190974 3.381562 +137.044846 -10.821547 3.381562 +143.950287 -6.417132 3.381562 +145.019409 -4.571502 3.381562 +145.733032 -2.467636 3.381562 +144.743500 -2.240131 3.685314 +143.716614 -2.004039 3.799238 +143.137054 -3.712649 3.799238 +142.268784 -5.211538 3.799238 +141.199127 -6.447185 3.799238 +139.922485 -7.467564 3.799238 +138.390701 -8.276384 3.799238 +136.856323 -9.823845 3.685314 +138.790161 -9.251410 3.685314 +140.502396 -8.347303 3.685314 +141.929443 -7.206715 3.685314 +143.125107 -5.825499 3.685314 +144.095673 -4.150029 3.685314 +137.061386 10.906909 3.350000 +135.000000 11.100000 3.345793 +146.091492 0.434508 3.345793 +146.091492 0.434508 3.345793 +145.817871 2.486726 3.345793 +145.098679 4.607229 3.345793 +145.817871 2.486726 3.350000 +144.021194 6.467469 3.345793 +145.098679 4.607229 3.350000 +144.021194 6.467469 3.350000 +142.693741 8.001019 3.345793 +141.109406 9.267423 3.345793 +142.693741 8.001019 3.350000 +141.109406 9.267423 3.350000 +139.208420 10.271280 3.345793 +137.061386 10.906909 3.345793 +139.208420 10.271280 3.350000 +135.000000 11.100000 3.345793 +142.693741 -8.001019 3.350000 +145.817871 -2.486726 3.350000 +146.091492 -0.434471 3.350000 +146.091492 -0.434471 3.350000 +145.098679 -4.607229 3.350000 +145.817871 -2.486726 3.345793 +144.021194 -6.467469 3.350000 +145.098679 -4.607229 3.345793 +135.000000 -11.100000 3.350000 +135.000000 -11.100000 3.350000 +137.061386 -10.906909 3.345793 +137.061386 -10.906909 3.350000 +139.208420 -10.271280 3.345793 +139.208420 -10.271280 3.350000 +141.109406 -9.267423 3.345793 +141.109406 -9.267423 3.350000 +142.693741 -8.001019 3.345793 +144.021194 -6.467469 3.345793 +2.994303 -2.848403 3.800000 +-8.252169 -0.430544 3.800000 +-8.839521 -0.430544 3.800000 +-8.128301 -0.987778 3.800000 +-7.895492 -1.542108 3.800000 +0.000000 -8.850000 3.800000 +6.969456 -8.850000 3.800000 +6.969456 -5.304076 3.800000 +6.081450 -5.138328 3.800000 +5.193205 -4.805559 3.800000 +4.351435 -4.301307 3.800000 +-7.551519 -2.061970 3.800000 +-8.623405 -1.989825 3.800000 +-7.106439 -2.514932 3.800000 +2.172110 -0.168183 3.800000 +-1.722378 -0.138438 3.800000 +2.548533 -1.974254 3.800000 +-1.795996 -0.704506 3.800000 +-6.582427 -2.873655 3.800000 +-8.099092 -3.567523 3.800000 +-6.010288 -3.121104 3.800000 +-7.251956 -5.072635 3.800000 +-5.423715 -3.253065 3.800000 +-4.287510 -3.202238 3.800000 +-6.103777 -6.408308 3.800000 +3.604533 -3.638686 3.800000 +-1.978379 -1.277409 3.800000 +-4.713828 -7.490149 3.800000 +-3.715063 -3.018428 3.800000 +-3.169286 -8.263058 3.800000 +-3.167305 -2.720882 3.800000 +-1.567948 -8.709996 3.800000 +-2.677416 -2.316802 3.800000 +-2.274559 -1.825908 3.800000 +0.000000 -11.400000 3.350000 +6.965529 -11.400000 3.350000 +-11.091494 -0.434471 3.350000 +-11.391718 -0.434471 3.350000 +-10.836757 -2.403063 3.350000 +-11.131925 -2.457691 3.350000 +-10.191076 -4.399086 3.350000 +-10.470137 -4.509571 3.350000 +-9.134478 -6.306450 3.350000 +-9.385653 -6.470667 3.350000 +-7.693743 -8.001019 3.350000 +-7.905916 -8.213190 3.350000 +-5.944080 -9.374322 3.350000 +-6.108265 -9.625441 3.350000 +-3.996820 -10.355454 3.350000 +-4.107263 -10.634397 3.350000 +-1.977054 -10.922511 3.350000 +-2.031651 -11.217504 3.350000 +0.000000 -11.100000 3.350000 +6.965529 -11.100000 3.350000 +0.000000 -11.013051 3.381562 +0.000000 -11.100000 3.345793 +6.969456 -8.850000 3.800000 +0.000000 -8.850000 3.800000 +6.968455 -9.997694 3.685314 +0.000000 -8.944016 3.799238 +0.000000 -9.997694 3.685314 +6.965492 -11.100000 3.345793 +6.965492 -11.100000 3.345793 +0.000000 -11.100000 3.345793 +0.000000 -11.100000 3.350000 +6.965529 -11.100000 3.350000 +2.248239 -0.913077 3.800000 +2.278332 -0.907845 7.300000 +2.201793 -0.137865 7.300000 +2.172110 -0.168183 3.800000 +6.969456 -5.304076 3.800000 +7.000000 -5.276362 7.300000 +6.229799 -5.176996 3.800000 +5.216642 -4.816739 3.800000 +6.237077 -5.147332 7.300000 +5.229726 -4.789139 7.300000 +4.330979 -4.286258 3.800000 +4.349138 -4.261698 7.300000 +3.603945 -3.638056 3.800000 +3.006996 -2.868382 3.800000 +3.626269 -3.617210 7.300000 +3.032741 -2.851946 7.300000 +2.538344 -1.948504 3.800000 +2.566774 -1.937339 7.300000 +-2.573162 2.207357 3.800000 +-8.623405 1.989825 3.800000 +-8.839521 0.430544 3.800000 +-8.252169 0.430544 3.800000 +-7.926055 1.483298 3.800000 +-8.099092 3.567523 3.800000 +-7.616751 1.978530 3.800000 +-7.217493 2.417580 3.800000 +-7.251956 5.072635 3.800000 +-6.745670 2.777518 3.800000 +7.069456 5.313128 3.800000 +7.069456 8.850000 3.800000 +5.371973 4.887351 3.800000 +4.559510 4.446146 3.800000 +3.825059 3.861284 3.800000 +3.204613 3.156636 3.800000 +-6.225626 3.042994 3.800000 +-6.103777 6.408308 3.800000 +-1.800180 0.723270 3.800000 +2.214643 0.692605 3.800000 +-2.220284 1.742168 3.800000 +-4.713828 7.490149 3.800000 +-5.148685 3.277173 3.800000 +-3.169286 8.263058 3.800000 +-4.054963 3.141476 3.800000 +-1.567948 8.709996 3.800000 +-3.513015 2.924183 3.800000 +0.000000 8.850000 3.800000 +-3.010537 2.608449 3.800000 +2.723794 2.366971 3.800000 +0.000000 11.100000 3.350000 +7.065529 11.100000 3.350000 +-11.131925 2.457691 3.350000 +-11.391718 0.434471 3.350000 +-11.091494 0.434471 3.350000 +-10.470137 4.509571 3.350000 +-10.836757 2.403063 3.350000 +-9.385653 6.470667 3.350000 +-10.191076 4.399086 3.350000 +-7.905916 8.213190 3.350000 +-9.134478 6.306450 3.350000 +-6.108265 9.625441 3.350000 +-7.693743 8.001019 3.350000 +-4.107263 10.634397 3.350000 +-5.944080 9.374322 3.350000 +-2.031651 11.217504 3.350000 +-3.996820 10.355454 3.350000 +0.000000 11.400000 3.350000 +-1.977054 10.922511 3.350000 +7.065529 11.400000 3.350000 +0.000000 9.997694 3.685314 +7.065492 11.100000 3.345793 +0.000000 11.100000 3.345793 +7.068455 9.997694 3.685314 +0.000000 11.013051 3.381562 +0.000000 8.850000 3.800000 +7.069456 8.850000 3.800000 +0.000000 8.944016 3.799238 +7.065492 11.100000 3.345793 +7.065529 11.100000 3.350000 +0.000000 11.100000 3.350000 +0.000000 11.100000 3.345793 +3.825478 3.861682 3.800000 +6.543107 5.212903 7.300000 +7.100000 5.284884 7.300000 +7.069456 5.313128 3.800000 +2.214643 0.692605 3.800000 +2.241488 0.661855 7.300000 +2.311292 1.221477 3.800000 +2.341023 1.214478 7.300000 +2.662008 2.237975 3.800000 +2.689730 2.225151 7.300000 +3.184139 3.128586 3.800000 +6.537592 5.242945 3.800000 +5.516369 4.914795 7.300000 +5.504937 4.943119 3.800000 +4.606184 4.440251 7.300000 +4.589507 4.465840 3.800000 +3.846533 3.839555 7.300000 +3.208869 3.110659 7.300000 +2.201793 -0.137865 7.300000 +-1.751784 -0.107668 7.300000 +-1.722378 -0.138438 3.800000 +2.172110 -0.168183 3.800000 +2.214643 0.692605 3.800000 +-1.800180 0.723270 3.800000 +-1.824725 0.692912 7.300000 +2.241488 0.661855 7.300000 +-10.836749 2.403095 3.345793 +-11.091493 0.434508 3.345793 +-8.051521 3.673623 3.800000 +-7.192382 5.156756 3.800000 +-6.134018 6.379367 3.800000 +-4.870748 7.389068 3.800000 +-3.355065 8.189386 3.800000 +-1.643227 8.696109 3.800000 +0.000000 8.850000 3.800000 +0.000000 9.997694 3.685314 +0.000000 11.100000 3.345793 +-1.977050 10.922512 3.345793 +-3.996813 10.355457 3.345793 +-5.944069 9.374329 3.345793 +-7.693730 8.001032 3.345793 +-9.134464 6.306470 3.345793 +-10.191065 4.399112 3.345793 +-9.988190 0.431545 3.685352 +-8.839521 0.430544 3.800000 +-8.624982 1.982973 3.800000 +-8.716608 2.004039 3.799238 +-8.137055 3.712649 3.799238 +-7.268789 5.211538 3.799238 +-6.199132 6.447185 3.799238 +-4.922491 7.467564 3.799238 +-3.390706 8.276384 3.799238 +-1.660684 8.788490 3.799238 +-1.856326 9.823845 3.685314 +-2.044852 10.821547 3.381562 +-4.175084 10.190974 3.381562 +-6.061219 9.195048 3.381562 +-7.633188 7.938622 3.381562 +-8.950291 6.417132 3.381562 +-10.019414 4.571502 3.381562 +-10.733036 2.467636 3.381562 +-9.743495 2.240131 3.685314 +-3.790159 9.251410 3.685314 +-5.502400 8.347303 3.685314 +-6.929440 7.206715 3.685314 +-8.125112 5.825499 3.685314 +-9.095666 4.150029 3.685314 +-7.693743 8.001019 3.345793 +-10.817864 2.486726 3.350000 +-11.091494 0.434471 3.350000 +-11.091493 0.434508 3.345793 +-10.098685 4.607229 3.350000 +-10.817864 2.486726 3.345793 +-10.098685 4.607229 3.345793 +-9.021189 6.467469 3.350000 +-7.693743 8.001019 3.350000 +-9.021189 6.467469 3.345793 +0.000000 11.100000 3.345793 +0.000000 11.100000 3.350000 +-2.061393 10.906909 3.345793 +-2.061393 10.906909 3.350000 +-4.208419 10.271280 3.345793 +-6.109409 9.267423 3.345793 +-4.208419 10.271280 3.350000 +-6.109409 9.267423 3.350000 +90.132721 -4.509971 2.700000 +90.106110 -4.800000 2.700000 +93.270691 -4.509340 2.302641 +93.297356 -4.800000 2.302641 +93.293892 -4.800000 2.700000 +93.185204 -4.212021 2.302641 +93.267281 -4.509971 2.700000 +93.036980 -3.925910 2.302641 +93.181984 -4.213297 2.700000 +93.034081 -3.927807 2.700000 +92.829506 -3.670497 2.302641 +92.827049 -3.672949 2.700000 +92.574089 -3.463018 2.302641 +92.572189 -3.465920 2.700000 +92.287979 -3.314794 2.302641 +91.990662 -3.229308 2.302641 +92.286705 -3.318019 2.700000 +91.990028 -3.232718 2.700000 +91.699997 -3.202641 2.302641 +91.699997 -3.206109 2.700000 +91.409340 -3.229308 2.302641 +91.409973 -3.232718 2.700000 +91.112022 -3.314794 2.302641 +90.825912 -3.463018 2.302641 +91.113297 -3.318019 2.700000 +90.827805 -3.465920 2.700000 +90.570496 -3.670497 2.302641 +90.363014 -3.925910 2.302641 +90.572952 -3.672949 2.700000 +90.214798 -4.212021 2.302641 +90.365921 -3.927807 2.700000 +90.218018 -4.213297 2.700000 +90.129311 -4.509340 2.302641 +90.102638 -4.800000 2.302641 +111.485489 1.200155 2.504402 +111.595596 0.000000 2.504402 +98.516190 1.199845 2.700000 +98.406105 0.000000 2.700000 +98.404404 0.000000 2.504402 +98.514511 1.200155 2.504402 +98.869080 2.427176 2.700000 +98.867493 2.427805 2.504402 +99.480942 3.608242 2.700000 +99.479515 3.609176 2.504402 +100.337418 4.662585 2.700000 +100.336205 4.663792 2.504402 +101.391762 5.519057 2.700000 +101.390823 5.520486 2.504402 +102.572823 6.130923 2.700000 +102.572197 6.132510 2.504402 +103.800156 6.483809 2.700000 +103.799843 6.485487 2.504402 +105.000000 6.593891 2.700000 +105.000000 6.595598 2.504402 +106.199844 6.483809 2.700000 +106.200157 6.485487 2.504402 +107.427177 6.130923 2.700000 +107.427803 6.132510 2.504402 +108.608238 5.519057 2.700000 +109.662582 4.662585 2.700000 +108.609177 5.520486 2.504402 +109.663795 4.663792 2.504402 +110.519058 3.608242 2.700000 +110.520485 3.609176 2.504402 +111.130920 2.427176 2.700000 +111.132507 2.427805 2.504402 +111.483810 1.199845 2.700000 +111.593895 0.000000 2.700000 +61.595596 0.000000 2.504402 +61.593891 0.000000 2.700000 +48.516190 1.199845 2.700000 +48.406109 0.000000 2.700000 +48.404404 0.000000 2.504402 +48.514511 1.200155 2.504402 +48.869076 2.427176 2.700000 +48.867489 2.427805 2.504402 +49.480942 3.608242 2.700000 +49.479515 3.609176 2.504402 +50.337414 4.662585 2.700000 +51.391758 5.519057 2.700000 +50.336208 4.663792 2.504402 +52.572823 6.130923 2.700000 +51.390823 5.520486 2.504402 +52.572197 6.132510 2.504402 +53.800156 6.483809 2.700000 +53.799847 6.485487 2.504402 +55.000000 6.593891 2.700000 +56.199844 6.483809 2.700000 +55.000000 6.595598 2.504402 +56.200153 6.485487 2.504402 +57.427177 6.130923 2.700000 +57.427803 6.132510 2.504402 +58.608242 5.519057 2.700000 +58.609177 5.520486 2.504402 +59.662586 4.662585 2.700000 +59.663792 4.663792 2.504402 +60.519058 3.608242 2.700000 +60.520485 3.609176 2.504402 +61.130924 2.427176 2.700000 +61.132511 2.427805 2.504402 +61.483810 1.199845 2.700000 +61.485489 1.200155 2.504402 +36.595596 0.000000 2.504402 +36.593891 0.000000 2.700000 +23.516191 1.199845 2.700000 +23.406109 0.000000 2.700000 +23.404402 0.000000 2.504402 +23.514513 1.200155 2.504402 +23.869078 2.427176 2.700000 +23.867491 2.427805 2.504402 +24.480942 3.608242 2.700000 +24.479513 3.609176 2.504402 +25.337416 4.662585 2.700000 +25.336208 4.663792 2.504402 +26.391758 5.519057 2.700000 +26.390825 5.520486 2.504402 +27.572824 6.130923 2.700000 +27.572195 6.132510 2.504402 +28.800156 6.483809 2.700000 +28.799845 6.485487 2.504402 +30.000000 6.593891 2.700000 +30.000000 6.595598 2.504402 +31.199844 6.483809 2.700000 +31.200155 6.485487 2.504402 +32.427177 6.130923 2.700000 +32.427803 6.132510 2.504402 +33.608242 5.519057 2.700000 +34.662586 4.662585 2.700000 +33.609177 5.520486 2.504402 +34.663792 4.663792 2.504402 +35.519058 3.608242 2.700000 +35.520485 3.609176 2.504402 +36.130924 2.427176 2.700000 +36.132511 2.427805 2.504402 +36.483810 1.199845 2.700000 +36.485489 1.200155 2.504402 +-13.870219 0.548516 2.170219 +-13.869085 0.548516 2.300000 +0.000000 -13.900000 0.000000 +0.000000 -13.879929 2.300000 +-2.529286 -13.667945 0.000000 +-2.525634 -13.648208 2.300000 +-5.116517 -12.924057 0.000000 +-5.109128 -12.905395 2.300000 +-7.606215 -11.634237 0.000000 +-7.595232 -11.617437 2.300000 +-9.828784 -9.828784 0.000000 +-9.814591 -9.814591 2.300000 +-11.634237 -7.606215 0.000000 +-11.617437 -7.595232 2.300000 +-12.924057 -5.116517 0.000000 +-12.905395 -5.109128 2.300000 +-13.667945 -2.529286 0.000000 +-13.900000 0.000000 0.000000 +-13.648208 -2.525634 2.300000 +-13.868968 -0.551484 2.300000 +-13.870103 -0.551484 2.170102 +-13.667945 2.529286 0.000000 +0.000000 13.879929 2.300000 +0.000000 13.900000 0.000000 +-2.525634 13.648208 2.300000 +-5.109128 12.905395 2.300000 +-2.529286 13.667945 0.000000 +-5.116517 12.924057 0.000000 +-7.595232 11.617437 2.300000 +-7.606215 11.634237 0.000000 +-9.814591 9.814591 2.300000 +-9.828784 9.828784 0.000000 +-11.617437 7.595232 2.300000 +-12.905395 5.109128 2.300000 +-11.634237 7.606215 0.000000 +-12.924057 5.116517 0.000000 +-13.648208 2.525634 2.300000 +5.350000 -13.881399 2.131400 +25.150000 -13.881399 2.131400 +25.150000 -13.879929 2.300000 +5.350000 -13.879929 2.300000 +37.049999 -13.879929 2.300000 +26.250000 -13.879929 2.300000 +37.049999 -13.881399 2.131400 +57.950001 -13.881399 2.131400 +57.950001 -13.879929 2.300000 +47.150002 -13.879929 2.300000 +66.949997 -13.879929 2.300000 +59.049999 -13.879929 2.300000 +66.949997 -13.881399 2.131400 +108.750000 -13.879929 2.300000 +97.949997 -13.879929 2.300000 +108.750000 -13.881399 2.131400 +129.649994 -13.879929 2.300000 +109.849998 -13.879929 2.300000 +129.649994 -13.881399 2.131400 +135.000000 -13.879929 2.300000 +130.750000 -13.879929 2.300000 +135.000000 -13.900000 0.000000 +0.000000 -13.900000 0.000000 +130.750000 -13.881399 2.131400 +109.849998 -13.881399 2.131400 +97.949997 -13.881399 2.131400 +4.250000 -13.879929 2.300000 +0.000000 -13.879929 2.300000 +4.250000 -13.881399 2.131400 +46.049999 -13.879929 2.300000 +38.150002 -13.879929 2.300000 +46.049999 -13.881399 2.131400 +75.949997 -13.879929 2.300000 +68.050003 -13.879929 2.300000 +75.949997 -13.881399 2.131400 +87.849998 -13.879929 2.300000 +77.050003 -13.879929 2.300000 +87.849998 -13.881399 2.131400 +96.849998 -13.879929 2.300000 +88.949997 -13.879929 2.300000 +96.849998 -13.881399 2.131400 +88.949997 -13.881399 2.131400 +77.050003 -13.881399 2.131400 +68.050003 -13.881399 2.131400 +59.049999 -13.881399 2.131400 +47.150002 -13.881399 2.131400 +38.150002 -13.881399 2.131400 +26.250000 -13.881399 2.131400 +148.869904 -0.556318 2.169911 +148.868774 -0.556318 2.300000 +135.000000 -13.879929 2.300000 +135.000000 -13.900000 0.000000 +137.844131 -13.585409 2.300000 +137.848236 -13.605055 0.000000 +140.512787 -12.738192 2.300000 +142.864853 -11.436633 2.300000 +140.520767 -12.756612 0.000000 +144.814713 -9.814471 2.300000 +142.876221 -11.453172 0.000000 +144.828781 -9.828784 0.000000 +146.436630 -7.864847 2.300000 +146.453171 -7.876221 0.000000 +147.738190 -5.512793 2.300000 +148.585403 -2.844129 2.300000 +147.756607 -5.520766 0.000000 +148.605057 -2.848242 0.000000 +148.899994 0.000000 0.000000 +148.880966 0.000000 2.180967 +135.000000 13.322845 0.000000 +146.634232 7.606215 0.000000 +147.387421 4.904068 0.000000 +144.828781 9.828784 0.000000 +146.151169 7.290390 0.000000 +142.606216 11.634237 0.000000 +144.420670 9.420673 0.000000 +140.116516 12.924057 0.000000 +142.290390 11.151161 0.000000 +137.529282 13.667945 0.000000 +139.904068 12.387425 0.000000 +135.000000 13.900000 0.000000 +137.424271 13.100425 0.000000 +147.924057 5.116517 0.000000 +148.100418 2.424265 0.000000 +148.667938 2.529286 0.000000 +148.322845 0.000000 0.000000 +148.899994 0.000000 0.000000 +148.100418 -2.424265 0.000000 +148.667938 -2.529286 0.000000 +147.387421 -4.904068 0.000000 +147.924057 -5.116517 0.000000 +146.151169 -7.290390 0.000000 +146.634232 -7.606215 0.000000 +144.420670 -9.420673 0.000000 +144.828781 -9.828784 0.000000 +142.290390 -11.151161 0.000000 +142.606216 -11.634237 0.000000 +139.904068 -12.387425 0.000000 +140.116516 -12.924057 0.000000 +137.424271 -13.100425 0.000000 +137.529282 -13.667945 0.000000 +135.000000 -13.322845 0.000000 +135.000000 -13.900000 0.000000 +0.000000 -13.322845 0.000000 +0.000000 -13.900000 0.000000 +-2.424265 -13.100425 0.000000 +-2.529286 -13.667945 0.000000 +-4.904068 -12.387425 0.000000 +-5.116517 -12.924057 0.000000 +-7.290390 -11.151161 0.000000 +-7.606215 -11.634237 0.000000 +-9.420673 -9.420673 0.000000 +-9.828784 -9.828784 0.000000 +-11.151161 -7.290390 0.000000 +-11.634237 -7.606215 0.000000 +-12.387425 -4.904068 0.000000 +-12.924057 -5.116517 0.000000 +-13.100425 -2.424265 0.000000 +-13.667945 -2.529286 0.000000 +-13.322845 0.000000 0.000000 +-13.900000 0.000000 0.000000 +-13.100425 2.424265 0.000000 +-13.667945 2.529286 0.000000 +-12.387425 4.904068 0.000000 +-12.924057 5.116517 0.000000 +-11.151161 7.290390 0.000000 +-11.634237 7.606215 0.000000 +-9.420673 9.420673 0.000000 +-9.828784 9.828784 0.000000 +-7.290390 11.151161 0.000000 +-7.606215 11.634237 0.000000 +-4.904068 12.387425 0.000000 +-5.116517 12.924057 0.000000 +-2.424265 13.100425 0.000000 +-2.529286 13.667945 0.000000 +0.000000 13.322845 0.000000 +0.000000 13.900000 0.000000 +0.000000 12.521252 0.725038 +135.000000 11.390800 1.197855 +0.000000 11.390800 1.197855 +135.000000 11.631423 1.169774 +0.000000 11.631423 1.169774 +135.000000 11.966409 1.073265 +0.000000 11.966409 1.073265 +135.000000 12.259805 0.924604 +135.000000 12.521252 0.725038 +0.000000 12.259805 0.924604 +0.000000 12.753820 0.465344 +0.000000 12.883736 0.260870 +135.000000 12.883736 0.260870 +135.000000 12.753820 0.465344 +143.054520 -8.054512 1.197855 +142.179596 -8.843285 1.197855 +141.233154 -9.534049 1.197855 +139.192886 -10.591033 1.197855 +137.072708 -11.200635 1.197855 +135.000000 -11.631423 1.169774 +135.000000 -11.390800 1.197855 +135.000000 -11.966409 1.073265 +135.000000 -12.259805 0.924604 +135.000000 -12.521252 0.725038 +135.000000 -12.753820 0.465344 +135.000000 -12.883736 0.260870 +137.344360 -12.668647 0.260870 +139.742432 -11.979147 0.260870 +142.050110 -10.783629 0.260870 +143.120590 -10.002330 0.260870 +144.110184 -9.110177 0.260870 +145.002335 -8.120595 0.260870 +145.783630 -7.050106 0.260870 +146.979141 -4.742435 0.260870 +147.668640 -2.344364 0.260870 +147.753815 0.000000 0.465344 +147.883743 0.000000 0.260870 +147.521255 0.000000 0.725038 +147.259811 0.000000 0.924604 +146.966415 0.000000 1.073265 +146.631424 0.000000 1.169774 +146.390808 0.000000 1.197855 +146.200638 -2.072705 1.197855 +145.591034 -4.192894 1.197855 +144.534042 -6.233157 1.197855 +143.843277 -7.179600 1.197855 +143.224655 -8.224658 1.169774 +141.590759 -9.583935 1.169774 +139.619736 -10.674644 1.169774 +137.383392 -11.384615 1.169774 +137.452026 -11.712492 1.073265 +137.512146 -11.999662 0.924604 +137.565720 -12.255563 0.725038 +137.613373 -12.483196 0.465344 +140.065521 -11.704715 0.465344 +142.226761 -10.508755 0.465344 +144.018311 -9.018312 0.465344 +145.508759 -7.226756 0.465344 +146.704712 -5.065528 0.465344 +147.483200 -2.613379 0.465344 +147.255569 -2.565723 0.725038 +146.999664 -2.512150 0.924604 +146.712494 -2.452030 1.073265 +146.384613 -2.383389 1.169774 +145.674637 -4.619738 1.169774 +144.583939 -6.590766 1.169774 +139.973160 -11.491277 0.725038 +139.869324 -11.251336 0.924604 +139.752792 -10.982074 1.073265 +142.094971 -10.317125 0.725038 +141.946823 -10.101702 0.924604 +143.853867 -8.853862 0.725038 +143.668991 -8.668991 0.924604 +141.780579 -9.859952 1.073265 +143.461533 -8.461529 1.073265 +145.317123 -7.094974 0.725038 +145.101700 -6.946829 0.924604 +146.491272 -4.973157 0.725038 +146.251343 -4.869317 0.924604 +144.859955 -6.780581 1.073265 +145.982071 -4.752786 1.073265 +-4.742435 11.979147 0.260870 +-7.050106 10.783629 0.260870 +-2.072705 -11.200635 1.197855 +0.000000 -11.390800 1.197855 +-2.344364 12.668647 0.260870 +0.000000 12.883736 0.260870 +0.000000 12.753820 0.465344 +0.000000 12.521252 0.725038 +0.000000 12.259805 0.924604 +0.000000 11.966409 1.073265 +0.000000 11.631423 1.169774 +0.000000 11.390800 1.197855 +-2.072705 11.200635 1.197855 +-4.192894 10.591033 1.197855 +-6.233157 9.534049 1.197855 +-8.054512 8.054512 1.197855 +-9.534049 6.233157 1.197855 +-10.591033 4.192894 1.197855 +-11.200635 2.072705 1.197855 +-11.390800 0.000000 1.197855 +-11.200635 -2.072705 1.197855 +-10.591033 -4.192894 1.197855 +-9.534049 -6.233157 1.197855 +-8.054512 -8.054512 1.197855 +-6.233157 -9.534049 1.197855 +-4.192894 -10.591033 1.197855 +0.000000 -11.631423 1.169774 +0.000000 -11.966409 1.073265 +0.000000 -12.259805 0.924604 +0.000000 -12.521252 0.725038 +0.000000 -12.753820 0.465344 +0.000000 -12.883736 0.260870 +-2.344364 -12.668647 0.260870 +-4.742435 -11.979147 0.260870 +-7.050106 -10.783629 0.260870 +-9.110177 -9.110177 0.260870 +-10.783629 -7.050106 0.260870 +-11.979147 -4.742435 0.260870 +-12.668647 -2.344364 0.260870 +-12.883736 0.000000 0.260870 +-12.668647 2.344364 0.260870 +-11.979147 4.742435 0.260870 +-10.783629 7.050106 0.260870 +-9.110177 9.110177 0.260870 +-9.018312 9.018312 0.465344 +-6.979015 10.674891 0.465344 +-4.694614 11.858353 0.465344 +-2.320724 12.540900 0.465344 +-2.278405 12.312214 0.725038 +-2.230831 12.055132 0.924604 +-2.177444 11.766634 1.073265 +-2.116489 11.437241 1.169774 +-4.281465 10.814761 1.169774 +-6.364828 9.735449 1.169774 +-8.224658 8.224658 1.169774 +-9.735449 6.364828 1.169774 +-10.814761 4.281465 1.169774 +-11.437241 2.116489 1.169774 +-11.631423 0.000000 1.169774 +-11.437241 -2.116489 1.169774 +-10.814761 -4.281465 1.169774 +-9.735449 -6.364828 1.169774 +-8.224658 -8.224658 1.169774 +-6.364828 -9.735449 1.169774 +-4.281465 -10.814761 1.169774 +-2.116489 -11.437241 1.169774 +-2.177444 -11.766634 1.073265 +-2.230831 -12.055132 0.924604 +-2.278405 -12.312214 0.725038 +-2.320724 -12.540900 0.465344 +-4.694614 -11.858353 0.465344 +-6.979015 -10.674891 0.465344 +-9.018312 -9.018312 0.465344 +-10.674891 -6.979015 0.465344 +-11.858353 -4.694614 0.465344 +-12.540900 -2.320724 0.465344 +-12.753820 0.000000 0.465344 +-12.540900 2.320724 0.465344 +-11.858353 4.694614 0.465344 +-10.674891 6.979015 0.465344 +-4.609006 11.642114 0.725038 +-4.512769 11.399023 0.924604 +-4.404772 11.126226 1.073265 +-6.851751 10.480231 0.725038 +-6.708684 10.261401 0.924604 +-8.853862 8.853862 0.725038 +-8.668991 8.668991 0.924604 +-6.548135 10.015830 1.073265 +-8.461529 8.461529 1.073265 +-10.480231 6.851751 0.725038 +-10.261401 6.708684 0.924604 +-11.642114 4.609006 0.725038 +-11.399023 4.512769 0.924604 +-10.015830 6.548135 1.073265 +-11.126226 4.404772 1.073265 +-12.312214 2.278405 0.725038 +-12.055132 2.230831 0.924604 +-12.521252 0.000000 0.725038 +-12.259805 0.000000 0.924604 +-11.766634 2.177444 1.073265 +-11.966409 0.000000 1.073265 +-12.312214 -2.278405 0.725038 +-12.055132 -2.230831 0.924604 +-11.642114 -4.609006 0.725038 +-11.399023 -4.512769 0.924604 +-11.766634 -2.177444 1.073265 +-11.126226 -4.404772 1.073265 +-10.480231 -6.851751 0.725038 +-10.261401 -6.708684 0.924604 +-8.853862 -8.853862 0.725038 +-8.668991 -8.668991 0.924604 +-10.015830 -6.548135 1.073265 +-8.461529 -8.461529 1.073265 +-6.851751 -10.480231 0.725038 +-6.708684 -10.261401 0.924604 +-4.609006 -11.642114 0.725038 +-4.512769 -11.399023 0.924604 +-6.548135 -10.015830 1.073265 +-4.404772 -11.126226 1.073265 +0.000000 -11.631423 1.169774 +0.000000 -11.390800 1.197855 +135.000000 -12.753820 0.465344 +135.000000 -12.883736 0.260870 +0.000000 -12.883736 0.260870 +0.000000 -12.753820 0.465344 +135.000000 -12.521252 0.725038 +135.000000 -12.259805 0.924604 +0.000000 -12.521252 0.725038 +0.000000 -12.259805 0.924604 +135.000000 -11.966409 1.073265 +0.000000 -11.966409 1.073265 +135.000000 -11.631423 1.169774 +135.000000 -11.390800 1.197855 +0.000000 -9.330033 1.971092 +0.000000 -8.850000 2.000000 +135.000000 -10.719302 1.536341 +135.000000 -11.130182 1.286452 +0.000000 -11.130182 1.286452 +0.000000 -10.719302 1.536341 +135.000000 -10.044611 1.817447 +135.000000 -9.330033 1.971092 +0.000000 -10.044611 1.817447 +135.000000 -8.850000 2.000000 +-7.407410 -4.842806 2.000000 +0.000000 -10.719302 1.536341 +0.000000 -11.130182 1.286452 +-6.257895 -6.257895 2.000000 +-4.842806 -7.407410 2.000000 +-3.257638 -8.228626 2.000000 +-1.610373 -8.702252 2.000000 +0.000000 -8.850000 2.000000 +0.000000 -9.330033 1.971092 +0.000000 -10.044611 1.817447 +-2.025282 -10.944368 1.286452 +-4.096961 -10.348714 1.286452 +-6.090544 -9.315913 1.286452 +-7.870227 -7.870227 1.286452 +-9.315913 -6.090544 1.286452 +-10.348714 -4.096961 1.286452 +-10.944368 -2.025282 1.286452 +-11.130182 0.000000 1.286452 +-10.944368 2.025282 1.286452 +-10.348714 4.096961 1.286452 +-9.315913 6.090544 1.286452 +-7.870227 7.870227 1.286452 +-6.090544 9.315913 1.286452 +-4.096961 10.348714 1.286452 +-2.025282 10.944368 1.286452 +0.000000 11.130182 1.286452 +0.000000 10.719302 1.536341 +0.000000 10.044611 1.817447 +0.000000 9.330033 1.971092 +0.000000 8.850000 2.000000 +-1.610373 8.702252 2.000000 +-3.257638 8.228626 2.000000 +-4.842806 7.407410 2.000000 +-6.257895 6.257895 2.000000 +-7.407410 4.842806 2.000000 +-8.228626 3.257638 2.000000 +-8.702252 1.610373 2.000000 +-8.850000 0.000000 2.000000 +-8.702252 -1.610373 2.000000 +-8.228626 -3.257638 2.000000 +-8.674955 -3.434336 1.971092 +-7.809196 -5.105485 1.971092 +-6.597330 -6.597330 1.971092 +-5.105485 -7.809196 1.971092 +-3.434336 -8.674955 1.971092 +-1.697721 -9.174272 1.971092 +-1.827748 -9.876920 1.817447 +-1.950517 -10.540347 1.536341 +-3.945718 -9.966681 1.536341 +-5.865706 -8.972008 1.536341 +-7.579691 -7.579691 1.536341 +-8.972008 -5.865706 1.536341 +-9.966681 -3.945718 1.536341 +-10.540347 -1.950517 1.536341 +-10.719302 0.000000 1.536341 +-10.540347 1.950517 1.536341 +-9.966681 3.945718 1.536341 +-8.972008 5.865706 1.536341 +-7.579691 7.579691 1.536341 +-5.865706 8.972008 1.536341 +-3.945718 9.966681 1.536341 +-1.950517 10.540347 1.536341 +-1.827748 9.876920 1.817447 +-1.697721 9.174272 1.971092 +-3.434336 8.674955 1.971092 +-5.105485 7.809196 1.971092 +-6.597330 6.597330 1.971092 +-7.809196 5.105485 1.971092 +-8.674955 3.434336 1.971092 +-9.174272 1.697721 1.971092 +-9.330033 0.000000 1.971092 +-9.174272 -1.697721 1.971092 +-3.697368 9.339362 1.817447 +-5.496509 8.407294 1.817447 +-7.102612 7.102612 1.817447 +-8.407294 5.496509 1.817447 +-9.339362 3.697368 1.817447 +-9.876920 1.827748 1.817447 +-10.044611 0.000000 1.817447 +-9.876920 -1.827748 1.817447 +-9.339362 -3.697368 1.817447 +-8.407294 -5.496509 1.817447 +-7.102612 -7.102612 1.817447 +-5.496509 -8.407294 1.817447 +-3.697368 -9.339362 1.817447 +143.702255 -1.610373 2.000000 +143.850006 0.000000 2.000000 +140.578140 -6.870726 2.000000 +139.842804 -7.407410 2.000000 +138.257645 -8.228626 2.000000 +136.610367 -8.702252 2.000000 +141.257889 -6.257895 2.000000 +141.870728 -5.578138 2.000000 +142.407410 -4.842806 2.000000 +143.228622 -3.257638 2.000000 +135.000000 -9.330033 1.971092 +135.000000 -8.850000 2.000000 +135.000000 -10.044611 1.817447 +135.000000 -10.719302 1.536341 +135.000000 -11.130182 1.286452 +137.025284 -10.944368 1.286452 +139.096954 -10.348714 1.286452 +141.090546 -9.315913 1.286452 +142.015335 -8.640953 1.286452 +142.870224 -7.870227 1.286452 +143.640945 -7.015333 1.286452 +144.315918 -6.090544 1.286452 +145.348709 -4.096961 1.286452 +145.944366 -2.025282 1.286452 +145.719299 0.000000 1.536341 +146.130188 0.000000 1.286452 +145.044617 0.000000 1.817447 +144.330032 0.000000 1.971092 +141.597336 -6.597330 1.971092 +140.286713 -7.687660 1.971092 +138.705673 -8.562562 1.971092 +136.911819 -9.132058 1.971092 +142.687653 -5.286719 1.971092 +143.562561 -3.705678 1.971092 +144.132065 -1.911812 1.971092 +137.058243 -9.831473 1.817447 +137.196487 -10.491848 1.536341 +139.257462 -9.837552 1.536341 +141.073929 -8.832375 1.536341 +142.579697 -7.579691 1.536341 +143.832382 -6.073927 1.536341 +144.837555 -4.257464 1.536341 +145.491852 -2.196486 1.536341 +144.831467 -2.058236 1.817447 +138.989487 -9.218360 1.817447 +140.691620 -8.276450 1.817447 +142.102615 -7.102612 1.817447 +143.276443 -5.691624 1.817447 +144.218353 -3.989492 1.817447 +0.000000 8.850000 2.000000 +0.000000 10.719302 1.536341 +0.000000 11.130182 1.286452 +135.000000 11.130182 1.286452 +135.000000 10.719302 1.536341 +0.000000 10.044611 1.817447 +135.000000 10.044611 1.817447 +0.000000 9.330033 1.971092 +135.000000 9.330033 1.971092 +135.000000 8.850000 2.000000 +135.000000 11.130182 1.286452 +0.000000 11.130182 1.286452 +0.000000 11.390800 1.197855 +135.000000 11.390800 1.197855 +0.000000 11.344848 1.202234 +135.000000 11.344848 1.202234 +0.000000 11.254274 1.223865 +135.000000 11.254274 1.223865 +0.000000 11.169284 1.261917 +135.000000 11.169284 1.261917 +143.054520 8.054512 1.197855 +142.179596 8.843285 1.197855 +141.233154 9.534049 1.197855 +139.192886 10.591033 1.197855 +137.072708 11.200635 1.197855 +135.000000 11.344848 1.202234 +135.000000 11.390800 1.197855 +135.000000 11.254274 1.223865 +135.000000 11.169284 1.261917 +135.000000 11.130182 1.286452 +137.025284 10.944368 1.286452 +139.096954 10.348714 1.286452 +141.090546 9.315913 1.286452 +142.015335 8.640953 1.286452 +142.870224 7.870227 1.286452 +143.640945 7.015333 1.286452 +144.315918 6.090544 1.286452 +145.348709 4.096961 1.286452 +145.944366 2.025282 1.286452 +146.169281 0.000000 1.261917 +146.130188 0.000000 1.286452 +146.254272 0.000000 1.223865 +146.344849 0.000000 1.202234 +146.390808 0.000000 1.197855 +146.200638 2.072705 1.197855 +145.591034 4.192894 1.197855 +144.534042 6.233157 1.197855 +143.843277 7.179600 1.197855 +143.020782 8.020783 1.202485 +141.427399 9.346366 1.202485 +139.505219 10.410039 1.202485 +137.324310 11.102411 1.202485 +137.306107 11.015470 1.223865 +137.289001 10.933786 1.261052 +139.436798 10.251930 1.261052 +141.329773 9.204412 1.261052 +142.898956 7.898963 1.261052 +144.204407 6.329773 1.261052 +145.251938 4.436797 1.261052 +145.933792 2.289007 1.261052 +146.015472 2.306108 1.223865 +146.102417 2.324309 1.202485 +145.410034 4.505223 1.202485 +144.346359 6.427393 1.202485 +145.328522 4.469943 1.223865 +144.273178 6.377061 1.223865 +142.957977 7.957974 1.223865 +141.377060 9.273175 1.223865 +139.469940 10.328519 1.223865 +-2.072705 11.200635 1.197855 +0.000000 11.390800 1.197855 +-4.192894 10.591033 1.197855 +-6.233157 9.534049 1.197855 +-8.054512 8.054512 1.197855 +-9.534049 6.233157 1.197855 +-10.591033 4.192894 1.197855 +-11.200635 2.072705 1.197855 +-11.390800 0.000000 1.197855 +-11.200635 -2.072705 1.197855 +-10.591033 -4.192894 1.197855 +-9.534049 -6.233157 1.197855 +-8.054512 -8.054512 1.197855 +-6.233157 -9.534049 1.197855 +-4.192894 -10.591033 1.197855 +-2.072705 -11.200635 1.197855 +0.000000 -11.390800 1.197855 +0.000000 -11.344848 1.202234 +0.000000 -11.254274 1.223865 +0.000000 -11.169284 1.261917 +0.000000 -11.130182 1.286452 +-2.025282 -10.944368 1.286452 +-4.096961 -10.348714 1.286452 +-6.090544 -9.315913 1.286452 +-7.870227 -7.870227 1.286452 +-9.315913 -6.090544 1.286452 +-10.348714 -4.096961 1.286452 +-10.944368 -2.025282 1.286452 +-11.130182 0.000000 1.286452 +-10.944368 2.025282 1.286452 +-10.348714 4.096961 1.286452 +-9.315913 6.090544 1.286452 +-7.870227 7.870227 1.286452 +-6.090544 9.315913 1.286452 +-4.096961 10.348714 1.286452 +-2.025282 10.944368 1.286452 +0.000000 11.130182 1.286452 +0.000000 11.169284 1.261917 +0.000000 11.254274 1.223865 +0.000000 11.344848 1.202234 +-4.175335 10.546683 1.202485 +-2.064025 11.153732 1.202485 +-6.207056 9.494124 1.202485 +-8.020783 8.020783 1.202485 +-9.494124 6.207056 1.202485 +-10.546683 4.175335 1.202485 +-11.153732 2.064025 1.202485 +-11.343102 0.000000 1.202485 +-11.153732 -2.064025 1.202485 +-10.546683 -4.175335 1.202485 +-9.494124 -6.207056 1.202485 +-8.020783 -8.020783 1.202485 +-6.207056 -9.494124 1.202485 +-4.175335 -10.546683 1.202485 +-2.064025 -11.153732 1.202485 +-2.047862 -11.066388 1.223865 +-2.032677 -10.984328 1.261052 +-4.111920 -10.386498 1.261052 +-6.112782 -9.349927 1.261052 +-7.898963 -7.898963 1.261052 +-9.349927 -6.112782 1.261052 +-10.386498 -4.111920 1.261052 +-10.984328 -2.032677 1.261052 +-11.170821 0.000000 1.261052 +-10.984328 2.032677 1.261052 +-10.386498 4.111920 1.261052 +-9.349927 6.112782 1.261052 +-7.898963 7.898963 1.261052 +-6.112782 9.349927 1.261052 +-4.111920 10.386498 1.261052 +-2.032677 10.984328 1.261052 +-2.047862 11.066388 1.223865 +-4.142639 10.464093 1.223865 +-6.158449 9.419777 1.223865 +-7.957974 7.957974 1.223865 +-9.419777 6.158449 1.223865 +-10.464093 4.142639 1.223865 +-11.066388 2.047862 1.223865 +-11.254274 0.000000 1.223865 +-11.066388 -2.047862 1.223865 +-10.464093 -4.142639 1.223865 +-9.419777 -6.158449 1.223865 +-7.957974 -7.957974 1.223865 +-6.158449 -9.419777 1.223865 +-4.142639 -10.464093 1.223865 +0.000000 -11.130182 1.286452 +135.000000 -11.130182 1.286452 +135.000000 -11.344848 1.202234 +135.000000 -11.390800 1.197855 +0.000000 -11.390800 1.197855 +0.000000 -11.344848 1.202234 +135.000000 -11.254274 1.223865 +0.000000 -11.254274 1.223865 +135.000000 -11.169284 1.261917 +0.000000 -11.169284 1.261917 +0.000000 13.249480 0.005412 +0.000000 13.322845 0.000000 +135.000000 12.923576 0.199028 +135.000000 12.883736 0.260870 +0.000000 12.883736 0.260870 +135.000000 12.988548 0.128186 +0.000000 12.923576 0.199028 +135.000000 13.067468 0.070137 +0.000000 12.988548 0.128186 +135.000000 13.156192 0.028591 +0.000000 13.067468 0.070137 +135.000000 13.249480 0.005412 +0.000000 13.156192 0.028591 +135.000000 13.322845 0.000000 +148.100418 2.424265 0.000000 +148.322845 0.000000 0.000000 +143.397369 10.343233 0.000000 +142.290390 11.151161 0.000000 +139.904068 12.387425 0.000000 +137.424271 13.100425 0.000000 +144.420670 9.420673 0.000000 +145.343231 8.397364 0.000000 +146.151169 7.290390 0.000000 +147.387421 4.904068 0.000000 +135.000000 13.249480 0.005412 +135.000000 13.322845 0.000000 +135.000000 13.156192 0.028591 +135.000000 13.067468 0.070137 +135.000000 12.988548 0.128186 +135.000000 12.923576 0.199028 +135.000000 12.883736 0.260870 +137.344360 12.668647 0.260870 +139.742432 11.979147 0.260870 +142.050110 10.783629 0.260870 +143.120590 10.002330 0.260870 +144.110184 9.110177 0.260870 +145.002335 8.120595 0.260870 +145.783630 7.050106 0.260870 +146.979141 4.742435 0.260870 +147.668640 2.344364 0.260870 +147.923569 0.000000 0.199028 +147.883743 0.000000 0.260870 +147.988541 0.000000 0.128186 +148.067474 0.000000 0.070137 +148.156189 0.000000 0.028591 +148.249481 0.000000 0.005412 +144.364655 9.364659 0.006315 +142.504303 10.912342 0.006315 +140.260071 12.154233 0.006315 +137.713745 12.962611 0.006315 +145.912338 7.504298 0.006315 +147.154236 5.260069 0.006315 +147.962616 2.713745 0.006315 +137.694550 12.870921 0.030844 +137.677643 12.790188 0.070137 +137.662491 12.717802 0.123782 +137.648895 12.652865 0.194321 +140.134384 11.863803 0.194321 +142.324982 10.651588 0.194321 +144.140884 9.140888 0.194321 +145.651581 7.324980 0.194321 +146.863800 5.134378 0.194321 +147.652863 2.648899 0.194321 +147.717804 2.662494 0.123782 +147.790192 2.677648 0.070137 +147.870926 2.694549 0.030844 +146.924683 5.160728 0.123782 +146.992569 5.190102 0.070137 +147.068268 5.222862 0.030844 +145.706253 7.362573 0.123782 +145.767197 7.404479 0.070137 +144.187805 9.187800 0.123782 +144.240097 9.240095 0.070137 +145.835159 7.451217 0.030844 +144.298416 9.298419 0.030844 +142.362579 10.706254 0.123782 +142.404480 10.767191 0.070137 +140.160736 11.924690 0.123782 +140.190109 11.992562 0.070137 +142.451218 10.835155 0.030844 +140.222870 12.068260 0.030844 +-11.151161 7.290390 0.000000 +-2.344364 -12.668647 0.260870 +0.000000 -12.883736 0.260870 +-12.387425 4.904068 0.000000 +-13.100425 2.424265 0.000000 +-13.322845 0.000000 0.000000 +-13.100425 -2.424265 0.000000 +-12.387425 -4.904068 0.000000 +-11.151161 -7.290390 0.000000 +-9.420673 -9.420673 0.000000 +-7.290390 -11.151161 0.000000 +-4.904068 -12.387425 0.000000 +-2.424265 -13.100425 0.000000 +0.000000 -13.322845 0.000000 +0.000000 -13.243629 0.006315 +0.000000 -13.149950 0.030844 +0.000000 -13.067468 0.070137 +0.000000 -12.993512 0.123782 +0.000000 -12.927168 0.194321 +-4.742435 -11.979147 0.260870 +-7.050106 -10.783629 0.260870 +-9.110177 -9.110177 0.260870 +-10.783629 -7.050106 0.260870 +-11.979147 -4.742435 0.260870 +-12.668647 -2.344364 0.260870 +-12.883736 0.000000 0.260870 +-12.668647 2.344364 0.260870 +-11.979147 4.742435 0.260870 +-10.783629 7.050106 0.260870 +-9.110177 9.110177 0.260870 +-7.050106 10.783629 0.260870 +-4.742435 11.979147 0.260870 +-2.344364 12.668647 0.260870 +0.000000 12.883736 0.260870 +0.000000 12.927168 0.194321 +0.000000 12.993512 0.123782 +0.000000 13.067468 0.070137 +0.000000 13.149950 0.030844 +0.000000 13.243629 0.006315 +0.000000 13.322845 0.000000 +-2.424265 13.100425 0.000000 +-4.904068 12.387425 0.000000 +-7.290390 11.151161 0.000000 +-9.420673 9.420673 0.000000 +-11.084858 7.247043 0.006315 +-12.313771 4.874910 0.006315 +-13.022532 2.409851 0.006315 +-13.243629 0.000000 0.006315 +-13.022532 -2.409851 0.006315 +-12.313771 -4.874910 0.006315 +-11.084858 -7.247043 0.006315 +-9.364659 -9.364659 0.006315 +-7.247043 -11.084858 0.006315 +-4.874910 -12.313771 0.006315 +-2.409851 -13.022532 0.006315 +-2.392805 -12.930417 0.030844 +-2.377796 -12.849311 0.070137 +-2.364339 -12.776590 0.123782 +-2.352267 -12.711353 0.194321 +-4.758422 -12.019529 0.194321 +-7.073872 -10.819982 0.194321 +-9.140888 -9.140888 0.194321 +-10.819982 -7.073872 0.194321 +-12.019529 -4.758422 0.194321 +-12.711353 -2.352267 0.194321 +-12.927168 0.000000 0.194321 +-12.711353 2.352267 0.194321 +-12.019529 4.758422 0.194321 +-10.819982 7.073872 0.194321 +-9.140888 9.140888 0.194321 +-7.073872 10.819982 0.194321 +-4.758422 12.019529 0.194321 +-2.352267 12.711353 0.194321 +-2.364339 12.776590 0.123782 +-2.377796 12.849311 0.070137 +-2.392805 12.930417 0.030844 +-2.409851 13.022532 0.006315 +-4.874910 12.313771 0.006315 +-7.247043 11.084858 0.006315 +-9.364659 9.364659 0.006315 +-4.782843 12.081215 0.123782 +-4.810066 12.149979 0.070137 +-4.840427 12.226670 0.030844 +-7.110177 10.875511 0.123782 +-7.150646 10.937412 0.070137 +-7.195781 11.006450 0.030844 +-9.187800 9.187800 0.123782 +-9.240095 9.240095 0.070137 +-9.298419 9.298419 0.030844 +-10.875511 7.110177 0.123782 +-10.937412 7.150646 0.070137 +-11.006450 7.195781 0.030844 +-12.081215 4.782843 0.123782 +-12.149979 4.810066 0.070137 +-12.226670 4.840427 0.030844 +-12.776590 2.364339 0.123782 +-12.849311 2.377796 0.070137 +-12.993512 0.000000 0.123782 +-13.067468 0.000000 0.070137 +-12.930417 2.392805 0.030844 +-13.149950 0.000000 0.030844 +-12.776590 -2.364339 0.123782 +-12.849311 -2.377796 0.070137 +-12.081215 -4.782843 0.123782 +-12.149979 -4.810066 0.070137 +-12.930417 -2.392805 0.030844 +-12.226670 -4.840427 0.030844 +-10.875511 -7.110177 0.123782 +-10.937412 -7.150646 0.070137 +-11.006450 -7.195781 0.030844 +-9.187800 -9.187800 0.123782 +-9.240095 -9.240095 0.070137 +-9.298419 -9.298419 0.030844 +-7.110177 -10.875511 0.123782 +-7.150646 -10.937412 0.070137 +-7.195781 -11.006450 0.030844 +-4.782843 -12.081215 0.123782 +-4.810066 -12.149979 0.070137 +-4.840427 -12.226670 0.030844 +0.000000 -12.923576 0.199028 +0.000000 -12.883736 0.260870 +135.000000 -13.322845 0.000000 +0.000000 -13.322845 0.000000 +135.000000 -13.249480 0.005412 +135.000000 -13.156192 0.028591 +0.000000 -13.249480 0.005412 +135.000000 -13.067468 0.070137 +0.000000 -13.156192 0.028591 +135.000000 -12.988548 0.128186 +0.000000 -13.067468 0.070137 +135.000000 -12.923576 0.199028 +0.000000 -12.988548 0.128186 +135.000000 -12.883736 0.260870 +-4.208049 -10.271432 3.345793 +-9.990095 -0.431548 3.684967 +-11.091493 -0.434508 3.345793 +-6.109075 -9.267643 3.345793 +-7.693455 -8.001297 3.345793 +-9.020956 -6.467794 3.345793 +-10.098519 -4.607593 3.345793 +-10.817775 -2.487116 3.345793 +-8.839521 -0.430544 3.800000 +-8.624983 -1.982971 3.800000 +-8.051522 -3.673621 3.800000 +-7.192384 -5.156754 3.800000 +-6.134010 -6.379375 3.800000 +-4.870749 -7.389067 3.800000 +-3.355066 -8.189385 3.800000 +-1.643229 -8.696108 3.800000 +0.000000 -8.850000 3.800000 +0.000000 -8.944016 3.799238 +0.000000 -9.997694 3.685314 +0.000000 -11.013051 3.381562 +0.000000 -11.100000 3.345793 +-2.060999 -10.906983 3.345793 +-4.175086 -10.190973 3.381562 +-6.061221 -9.195046 3.381562 +-7.633190 -7.938621 3.381562 +-8.950292 -6.417130 3.381562 +-10.019415 -4.571500 3.381562 +-10.733036 -2.467634 3.381562 +-9.743496 -2.240129 3.685314 +-8.716609 -2.004037 3.799238 +-8.137056 -3.712647 3.799238 +-7.268791 -5.211536 3.799238 +-6.199134 -6.447183 3.799238 +-4.922493 -7.467563 3.799238 +-3.390708 -8.276383 3.799238 +-1.660686 -8.788489 3.799238 +-1.856328 -9.823845 3.685314 +-2.044855 -10.821546 3.381562 +-9.095667 -4.150027 3.685314 +-8.125113 -5.825498 3.685314 +-6.929442 -7.206713 3.685314 +-5.502402 -8.347302 3.685314 +-3.790161 -9.251409 3.685314 +-2.061393 -10.906909 3.350000 +0.000000 -11.100000 3.350000 +-11.091493 -0.434508 3.345793 +-11.091494 -0.434471 3.350000 +-10.817864 -2.486726 3.345793 +-10.817864 -2.486726 3.350000 +-10.098685 -4.607229 3.345793 +-9.021189 -6.467469 3.345793 +-10.098685 -4.607229 3.350000 +-9.021189 -6.467469 3.350000 +-7.693743 -8.001019 3.345793 +-7.693743 -8.001019 3.350000 +-6.109409 -9.267423 3.345793 +-6.109409 -9.267423 3.350000 +-4.208419 -10.271280 3.345793 +-4.208419 -10.271280 3.350000 +-2.061393 -10.906909 3.345793 +0.000000 -11.100000 3.345793 +36.130924 -2.427176 2.700000 +35.338657 -5.338656 2.700000 +35.519058 -3.608242 2.700000 +34.131435 -6.319316 2.700000 +34.662586 -4.662585 2.700000 +32.779114 -7.019902 2.700000 +33.608242 -5.519057 2.700000 +31.373821 -7.423955 2.700000 +32.427177 -6.130923 2.700000 +30.000000 -7.550000 2.700000 +31.199844 -6.483809 2.700000 +28.626179 -7.423955 2.700000 +30.000000 -6.593891 2.700000 +27.220884 -7.019902 2.700000 +28.800156 -6.483809 2.700000 +25.868567 -6.319316 2.700000 +27.572824 -6.130923 2.700000 +24.661345 -5.338656 2.700000 +26.391758 -5.519057 2.700000 +23.680683 -4.131433 2.700000 +25.337416 -4.662585 2.700000 +22.980099 -2.779115 2.700000 +24.480942 -3.608242 2.700000 +22.576044 -1.373821 2.700000 +23.869078 -2.427176 2.700000 +22.450001 0.000000 2.700000 +23.516191 -1.199845 2.700000 +22.576044 1.373821 2.700000 +23.406109 0.000000 2.700000 +22.980099 2.779115 2.700000 +23.516191 1.199845 2.700000 +23.680683 4.131433 2.700000 +23.869078 2.427176 2.700000 +24.661345 5.338656 2.700000 +24.480942 3.608242 2.700000 +25.868567 6.319316 2.700000 +25.337416 4.662585 2.700000 +27.220884 7.019902 2.700000 +26.391758 5.519057 2.700000 +28.626179 7.423955 2.700000 +27.572824 6.130923 2.700000 +30.000000 7.550000 2.700000 +28.800156 6.483809 2.700000 +31.373821 7.423955 2.700000 +30.000000 6.593891 2.700000 +32.779114 7.019902 2.700000 +31.199844 6.483809 2.700000 +34.131435 6.319316 2.700000 +32.427177 6.130923 2.700000 +35.338657 5.338656 2.700000 +33.608242 5.519057 2.700000 +36.319317 4.131433 2.700000 +34.662586 4.662585 2.700000 +37.019901 2.779115 2.700000 +35.519058 3.608242 2.700000 +37.423954 1.373821 2.700000 +36.130924 2.427176 2.700000 +37.549999 0.000000 2.700000 +36.483810 1.199845 2.700000 +37.423954 -1.373821 2.700000 +36.593891 0.000000 2.700000 +37.019901 -2.779115 2.700000 +36.483810 -1.199845 2.700000 +36.319317 -4.131433 2.700000 +22.450001 0.000000 3.600000 +22.450001 0.000000 2.700000 +37.423954 1.373821 2.700000 +37.549999 0.000000 2.700000 +37.549999 0.000000 3.600000 +37.423954 1.373821 3.600000 +37.019901 2.779115 2.700000 +37.019901 2.779115 3.600000 +36.319317 4.131433 2.700000 +36.319317 4.131433 3.600000 +35.338657 5.338656 2.700000 +35.338657 5.338656 3.600000 +34.131435 6.319316 2.700000 +32.779114 7.019902 2.700000 +34.131435 6.319316 3.600000 +32.779114 7.019902 3.600000 +31.373821 7.423955 2.700000 +31.373821 7.423955 3.600000 +30.000000 7.550000 2.700000 +30.000000 7.550000 3.600000 +28.626179 7.423955 2.700000 +28.626179 7.423955 3.600000 +27.220884 7.019902 2.700000 +27.220884 7.019902 3.600000 +25.868567 6.319316 2.700000 +25.868567 6.319316 3.600000 +24.661345 5.338656 2.700000 +24.661345 5.338656 3.600000 +23.680683 4.131433 2.700000 +23.680683 4.131433 3.600000 +22.980099 2.779115 2.700000 +22.980099 2.779115 3.600000 +22.576044 1.373821 2.700000 +22.576044 1.373821 3.600000 +48.869076 2.427176 2.700000 +49.661343 5.338656 2.700000 +49.480942 3.608242 2.700000 +50.868565 6.319316 2.700000 +50.337414 4.662585 2.700000 +52.220886 7.019902 2.700000 +51.391758 5.519057 2.700000 +53.626179 7.423955 2.700000 +52.572823 6.130923 2.700000 +55.000000 7.550000 2.700000 +53.800156 6.483809 2.700000 +56.373821 7.423955 2.700000 +55.000000 6.593891 2.700000 +57.779114 7.019902 2.700000 +56.199844 6.483809 2.700000 +59.131435 6.319316 2.700000 +57.427177 6.130923 2.700000 +60.338657 5.338656 2.700000 +58.608242 5.519057 2.700000 +61.319317 4.131433 2.700000 +59.662586 4.662585 2.700000 +62.019901 2.779115 2.700000 +60.519058 3.608242 2.700000 +62.423954 1.373821 2.700000 +61.130924 2.427176 2.700000 +62.549999 0.000000 2.700000 +61.483810 1.199845 2.700000 +62.423954 -1.373821 2.700000 +61.593891 0.000000 2.700000 +62.019901 -2.779115 2.700000 +61.483810 -1.199845 2.700000 +61.319317 -4.131433 2.700000 +61.130924 -2.427176 2.700000 +60.338657 -5.338656 2.700000 +60.519058 -3.608242 2.700000 +59.131435 -6.319316 2.700000 +59.662586 -4.662585 2.700000 +57.779114 -7.019902 2.700000 +58.608242 -5.519057 2.700000 +56.373821 -7.423955 2.700000 +57.427177 -6.130923 2.700000 +55.000000 -7.550000 2.700000 +56.199844 -6.483809 2.700000 +53.626179 -7.423955 2.700000 +55.000000 -6.593891 2.700000 +52.220886 -7.019902 2.700000 +53.800156 -6.483809 2.700000 +50.868565 -6.319316 2.700000 +52.572823 -6.130923 2.700000 +49.661343 -5.338656 2.700000 +51.391758 -5.519057 2.700000 +48.680683 -4.131433 2.700000 +50.337414 -4.662585 2.700000 +47.980099 -2.779115 2.700000 +49.480942 -3.608242 2.700000 +47.576046 -1.373821 2.700000 +48.869076 -2.427176 2.700000 +47.450001 0.000000 2.700000 +48.516190 -1.199845 2.700000 +47.576046 1.373821 2.700000 +48.406109 0.000000 2.700000 +47.980099 2.779115 2.700000 +48.516190 1.199845 2.700000 +48.680683 4.131433 2.700000 +47.450001 0.000000 3.600000 +47.450001 0.000000 2.700000 +62.423954 1.373821 2.700000 +62.549999 0.000000 2.700000 +62.549999 0.000000 3.600000 +62.423954 1.373821 3.600000 +62.019901 2.779115 2.700000 +62.019901 2.779115 3.600000 +61.319317 4.131433 2.700000 +61.319317 4.131433 3.600000 +60.338657 5.338656 2.700000 +60.338657 5.338656 3.600000 +59.131435 6.319316 2.700000 +59.131435 6.319316 3.600000 +57.779114 7.019902 2.700000 +57.779114 7.019902 3.600000 +56.373821 7.423955 2.700000 +56.373821 7.423955 3.600000 +55.000000 7.550000 2.700000 +55.000000 7.550000 3.600000 +53.626179 7.423955 2.700000 +53.626179 7.423955 3.600000 +52.220886 7.019902 2.700000 +52.220886 7.019902 3.600000 +50.868565 6.319316 2.700000 +50.868565 6.319316 3.600000 +49.661343 5.338656 2.700000 +49.661343 5.338656 3.600000 +48.680683 4.131433 2.700000 +48.680683 4.131433 3.600000 +47.980099 2.779115 2.700000 +47.980099 2.779115 3.600000 +47.576046 1.373821 2.700000 +47.576046 1.373821 3.600000 +98.406105 0.000000 2.700000 +97.980095 2.779115 2.700000 +98.516190 1.199845 2.700000 +98.680687 4.131433 2.700000 +98.869080 2.427176 2.700000 +99.661346 5.338656 2.700000 +99.480942 3.608242 2.700000 +100.868568 6.319316 2.700000 +100.337418 4.662585 2.700000 +102.220886 7.019902 2.700000 +101.391762 5.519057 2.700000 +103.626183 7.423955 2.700000 +102.572823 6.130923 2.700000 +105.000000 7.550000 2.700000 +103.800156 6.483809 2.700000 +106.373817 7.423955 2.700000 +105.000000 6.593891 2.700000 +107.779114 7.019902 2.700000 +106.199844 6.483809 2.700000 +109.131432 6.319316 2.700000 +107.427177 6.130923 2.700000 +110.338654 5.338656 2.700000 +108.608238 5.519057 2.700000 +111.319313 4.131433 2.700000 +109.662582 4.662585 2.700000 +112.019905 2.779115 2.700000 +110.519058 3.608242 2.700000 +112.423958 1.373821 2.700000 +111.130920 2.427176 2.700000 +112.550003 0.000000 2.700000 +111.483810 1.199845 2.700000 +112.423958 -1.373821 2.700000 +111.593895 0.000000 2.700000 +112.019905 -2.779115 2.700000 +111.483810 -1.199845 2.700000 +111.319313 -4.131433 2.700000 +111.130920 -2.427176 2.700000 +110.338654 -5.338656 2.700000 +110.519058 -3.608242 2.700000 +109.131432 -6.319316 2.700000 +109.662582 -4.662585 2.700000 +107.779114 -7.019902 2.700000 +108.608238 -5.519057 2.700000 +106.373817 -7.423955 2.700000 +107.427177 -6.130923 2.700000 +105.000000 -7.550000 2.700000 +106.199844 -6.483809 2.700000 +103.626183 -7.423955 2.700000 +105.000000 -6.593891 2.700000 +102.220886 -7.019902 2.700000 +103.800156 -6.483809 2.700000 +100.868568 -6.319316 2.700000 +102.572823 -6.130923 2.700000 +99.661346 -5.338656 2.700000 +101.391762 -5.519057 2.700000 +98.680687 -4.131433 2.700000 +100.337418 -4.662585 2.700000 +97.980095 -2.779115 2.700000 +99.480942 -3.608242 2.700000 +97.576042 -1.373821 2.700000 +98.869080 -2.427176 2.700000 +97.449997 0.000000 2.700000 +98.516190 -1.199845 2.700000 +97.576042 1.373821 2.700000 +97.449997 0.000000 3.600000 +97.449997 0.000000 2.700000 +112.423958 1.373821 2.700000 +112.550003 0.000000 2.700000 +112.550003 0.000000 3.600000 +112.019905 2.779115 2.700000 +112.423958 1.373821 3.600000 +111.319313 4.131433 2.700000 +112.019905 2.779115 3.600000 +110.338654 5.338656 2.700000 +111.319313 4.131433 3.600000 +110.338654 5.338656 3.600000 +109.131432 6.319316 2.700000 +109.131432 6.319316 3.600000 +107.779114 7.019902 2.700000 +107.779114 7.019902 3.600000 +106.373817 7.423955 2.700000 +106.373817 7.423955 3.600000 +105.000000 7.550000 2.700000 +105.000000 7.550000 3.600000 +103.626183 7.423955 2.700000 +103.626183 7.423955 3.600000 +102.220886 7.019902 2.700000 +102.220886 7.019902 3.600000 +100.868568 6.319316 2.700000 +100.868568 6.319316 3.600000 +99.661346 5.338656 2.700000 +99.661346 5.338656 3.600000 +98.680687 4.131433 2.700000 +98.680687 4.131433 3.600000 +97.980095 2.779115 2.700000 +97.980095 2.779115 3.600000 +97.576042 1.373821 2.700000 +97.576042 1.373821 3.600000 +93.306740 4.502669 5.898239 +93.334023 4.800000 5.898239 +90.124161 4.508387 2.297405 +90.097404 4.800000 2.297405 +90.065979 4.800000 5.898239 +90.209923 4.210093 2.297405 +90.093262 4.502669 5.898239 +90.358635 3.923044 2.297405 +90.180710 4.198526 5.898239 +90.566795 3.666794 2.297405 +90.332336 3.905849 5.898239 +90.823044 3.458635 2.297405 +90.544571 3.644574 5.898239 +91.110092 3.309926 2.297405 +90.805847 3.432333 5.898239 +91.408386 3.224159 2.297405 +91.098526 3.280708 5.898239 +91.699997 3.197405 2.297405 +91.402672 3.193260 5.898239 +91.991615 3.224159 2.297405 +91.699997 3.165981 5.898239 +92.289909 3.309926 2.297405 +91.997330 3.193260 5.898239 +92.576958 3.458635 2.297405 +92.301476 3.280708 5.898239 +92.833206 3.666794 2.297405 +92.594154 3.432333 5.898239 +93.041367 3.923044 2.297405 +92.855423 3.644574 5.898239 +93.190071 4.210093 2.297405 +93.067665 3.905849 5.898239 +93.275841 4.508387 2.297405 +93.219292 4.198526 5.898239 +93.302597 4.800000 2.297405 +93.293892 -4.800000 2.700000 +94.070961 -5.738642 2.700000 +93.267281 -5.090029 2.700000 +93.834335 -6.195385 2.700000 +93.181984 -5.386703 2.700000 +93.503120 -6.603122 2.700000 +93.034081 -5.672193 2.700000 +93.095383 -6.934339 2.700000 +92.827049 -5.927051 2.700000 +92.638641 -7.170960 2.700000 +92.572189 -6.134080 2.700000 +92.164009 -7.307429 2.700000 +92.286705 -6.281981 2.700000 +91.699997 -7.350000 2.700000 +91.990028 -6.367282 2.700000 +91.235992 -7.307429 2.700000 +91.699997 -6.393891 2.700000 +90.761360 -7.170960 2.700000 +91.409973 -6.367282 2.700000 +90.304619 -6.934339 2.700000 +91.113297 -6.281981 2.700000 +89.896881 -6.603122 2.700000 +90.827805 -6.134080 2.700000 +89.565659 -6.195385 2.700000 +90.572952 -5.927051 2.700000 +89.329041 -5.738642 2.700000 +90.365921 -5.672193 2.700000 +89.192574 -5.264006 2.700000 +90.218018 -5.386703 2.700000 +89.150002 -4.800000 2.700000 +90.132721 -5.090029 2.700000 +89.192574 -4.335994 2.700000 +90.106110 -4.800000 2.700000 +89.329041 -3.861358 2.700000 +90.132721 -4.509971 2.700000 +89.565659 -3.404615 2.700000 +90.218018 -4.213297 2.700000 +89.896881 -2.996878 2.700000 +90.365921 -3.927807 2.700000 +90.304619 -2.665661 2.700000 +90.572952 -3.672949 2.700000 +90.761360 -2.429040 2.700000 +90.827805 -3.465920 2.700000 +91.235992 -2.292571 2.700000 +91.113297 -3.318019 2.700000 +91.699997 -2.250000 2.700000 +91.409973 -3.232718 2.700000 +92.164009 -2.292571 2.700000 +91.699997 -3.206109 2.700000 +92.638641 -2.429040 2.700000 +91.990028 -3.232718 2.700000 +93.095383 -2.665661 2.700000 +92.286705 -3.318019 2.700000 +93.503120 -2.996878 2.700000 +92.572189 -3.465920 2.700000 +93.834335 -3.404615 2.700000 +92.827049 -3.672949 2.700000 +94.070961 -3.861358 2.700000 +93.034081 -3.927807 2.700000 +94.207428 -4.335994 2.700000 +93.181984 -4.213297 2.700000 +94.250000 -4.800000 2.700000 +93.267281 -4.509971 2.700000 +94.207428 -5.264006 2.700000 +94.250000 -4.800000 2.700000 +94.250000 -4.800000 3.600000 +89.150002 -4.800000 3.600000 +89.150002 -4.800000 2.700000 +89.192574 -4.335994 3.600000 +89.192574 -4.335994 2.700000 +89.329041 -3.861358 3.600000 +89.329041 -3.861358 2.700000 +89.565659 -3.404615 3.600000 +89.565659 -3.404615 2.700000 +89.896881 -2.996878 3.600000 +89.896881 -2.996878 2.700000 +90.304619 -2.665661 3.600000 +90.304619 -2.665661 2.700000 +90.761360 -2.429040 3.600000 +90.761360 -2.429040 2.700000 +91.235992 -2.292571 3.600000 +91.235992 -2.292571 2.700000 +91.699997 -2.250000 3.600000 +91.699997 -2.250000 2.700000 +92.164009 -2.292571 3.600000 +92.164009 -2.292571 2.700000 +92.638641 -2.429040 3.600000 +92.638641 -2.429040 2.700000 +93.095383 -2.665661 3.600000 +93.095383 -2.665661 2.700000 +93.503120 -2.996878 3.600000 +93.503120 -2.996878 2.700000 +93.834335 -3.404615 3.600000 +93.834335 -3.404615 2.700000 +94.070961 -3.861358 3.600000 +94.070961 -3.861358 2.700000 +94.207428 -4.335994 3.600000 +94.207428 -4.335994 2.700000 +83.516693 6.318037 3.800000 +83.516693 6.318037 6.300000 +83.500000 6.500000 6.300000 +83.500000 6.500000 3.800000 +85.500000 6.500000 3.800000 +85.500000 6.500000 6.300000 +85.483307 6.318037 3.800000 +85.483307 6.318037 6.300000 +85.429787 6.131905 3.800000 +85.429787 6.131905 6.300000 +85.336998 5.952790 3.800000 +85.336998 5.952790 6.300000 +85.207108 5.792893 3.800000 +85.207108 5.792893 6.300000 +85.047211 5.663004 3.800000 +85.047211 5.663004 6.300000 +84.868095 5.570212 3.800000 +84.868095 5.570212 6.300000 +84.681961 5.516695 3.800000 +84.681961 5.516695 6.300000 +84.500000 5.500000 3.800000 +84.500000 5.500000 6.300000 +84.318039 5.516695 3.800000 +84.318039 5.516695 6.300000 +84.131905 5.570212 3.800000 +84.131905 5.570212 6.300000 +83.952789 5.663004 3.800000 +83.952789 5.663004 6.300000 +83.792892 5.792893 3.800000 +83.792892 5.792893 6.300000 +83.663002 5.952790 3.800000 +83.663002 5.952790 6.300000 +83.570213 6.131905 3.800000 +83.570213 6.131905 6.300000 +84.099998 6.500000 6.300000 +83.570213 6.868095 6.300000 +84.106674 6.572785 6.300000 +83.663002 7.047210 6.300000 +84.128082 6.647238 6.300000 +83.792892 7.207107 6.300000 +84.165199 6.718884 6.300000 +83.952789 7.336996 6.300000 +84.217155 6.782843 6.300000 +84.131905 7.429788 6.300000 +84.281113 6.834798 6.300000 +84.318039 7.483305 6.300000 +84.352760 6.871915 6.300000 +84.500000 7.500000 6.300000 +84.427216 6.893322 6.300000 +84.681961 7.483305 6.300000 +84.500000 6.900000 6.300000 +84.868095 7.429788 6.300000 +84.572784 6.893322 6.300000 +85.047211 7.336996 6.300000 +84.647240 6.871915 6.300000 +85.207108 7.207107 6.300000 +84.718887 6.834798 6.300000 +85.336998 7.047210 6.300000 +84.782845 6.782843 6.300000 +85.429787 6.868095 6.300000 +84.834801 6.718884 6.300000 +85.483307 6.681963 6.300000 +84.871918 6.647238 6.300000 +85.500000 6.500000 6.300000 +84.893326 6.572785 6.300000 +85.483307 6.318037 6.300000 +84.900002 6.500000 6.300000 +85.429787 6.131905 6.300000 +84.893326 6.427215 6.300000 +85.336998 5.952790 6.300000 +84.871918 6.352762 6.300000 +85.207108 5.792893 6.300000 +84.834801 6.281116 6.300000 +85.047211 5.663004 6.300000 +84.782845 6.217157 6.300000 +84.868095 5.570212 6.300000 +84.718887 6.165202 6.300000 +84.681961 5.516695 6.300000 +84.647240 6.128085 6.300000 +84.500000 5.500000 6.300000 +84.572784 6.106678 6.300000 +84.318039 5.516695 6.300000 +84.500000 6.100000 6.300000 +84.131905 5.570212 6.300000 +84.427216 6.106678 6.300000 +83.952789 5.663004 6.300000 +84.352760 6.128085 6.300000 +83.792892 5.792893 6.300000 +84.281113 6.165202 6.300000 +83.663002 5.952790 6.300000 +84.217155 6.217157 6.300000 +83.570213 6.131905 6.300000 +84.165199 6.281116 6.300000 +83.516693 6.318037 6.300000 +84.128082 6.352762 6.300000 +83.500000 6.500000 6.300000 +84.106674 6.427215 6.300000 +83.516693 6.681963 6.300000 +112.016693 6.318037 3.800000 +112.016693 6.318037 6.300000 +112.000000 6.500000 6.300000 +112.000000 6.500000 3.800000 +114.000000 6.500000 3.800000 +114.000000 6.500000 6.300000 +113.983307 6.318037 3.800000 +113.983307 6.318037 6.300000 +113.929787 6.131905 3.800000 +113.929787 6.131905 6.300000 +113.836998 5.952790 3.800000 +113.836998 5.952790 6.300000 +113.707108 5.792893 3.800000 +113.707108 5.792893 6.300000 +113.547211 5.663004 3.800000 +113.547211 5.663004 6.300000 +113.368095 5.570212 3.800000 +113.368095 5.570212 6.300000 +113.181961 5.516695 3.800000 +113.181961 5.516695 6.300000 +113.000000 5.500000 3.800000 +113.000000 5.500000 6.300000 +112.818039 5.516695 3.800000 +112.818039 5.516695 6.300000 +112.631905 5.570212 3.800000 +112.631905 5.570212 6.300000 +112.452789 5.663004 3.800000 +112.452789 5.663004 6.300000 +112.292892 5.792893 3.800000 +112.292892 5.792893 6.300000 +112.163002 5.952790 3.800000 +112.163002 5.952790 6.300000 +112.070213 6.131905 3.800000 +112.070213 6.131905 6.300000 +113.282845 6.782843 6.300000 +113.929787 6.868095 6.300000 +113.334801 6.718884 6.300000 +113.983307 6.681963 6.300000 +113.371918 6.647238 6.300000 +114.000000 6.500000 6.300000 +113.393326 6.572785 6.300000 +113.983307 6.318037 6.300000 +113.400002 6.500000 6.300000 +113.929787 6.131905 6.300000 +113.393326 6.427215 6.300000 +113.836998 5.952790 6.300000 +113.371918 6.352762 6.300000 +113.707108 5.792893 6.300000 +113.334801 6.281116 6.300000 +113.547211 5.663004 6.300000 +113.282845 6.217157 6.300000 +113.368095 5.570212 6.300000 +113.218887 6.165202 6.300000 +113.181961 5.516695 6.300000 +113.147240 6.128085 6.300000 +113.000000 5.500000 6.300000 +113.072784 6.106678 6.300000 +112.818039 5.516695 6.300000 +113.000000 6.100000 6.300000 +112.631905 5.570212 6.300000 +112.927216 6.106678 6.300000 +112.452789 5.663004 6.300000 +112.852760 6.128085 6.300000 +112.292892 5.792893 6.300000 +112.781113 6.165202 6.300000 +112.163002 5.952790 6.300000 +112.717155 6.217157 6.300000 +112.070213 6.131905 6.300000 +112.665199 6.281116 6.300000 +112.016693 6.318037 6.300000 +112.628082 6.352762 6.300000 +112.000000 6.500000 6.300000 +112.606674 6.427215 6.300000 +112.016693 6.681963 6.300000 +112.599998 6.500000 6.300000 +112.070213 6.868095 6.300000 +112.606674 6.572785 6.300000 +112.163002 7.047210 6.300000 +112.628082 6.647238 6.300000 +112.292892 7.207107 6.300000 +112.665199 6.718884 6.300000 +112.452789 7.336996 6.300000 +112.717155 6.782843 6.300000 +112.631905 7.429788 6.300000 +112.781113 6.834798 6.300000 +112.818039 7.483305 6.300000 +112.852760 6.871915 6.300000 +113.000000 7.500000 6.300000 +112.927216 6.893322 6.300000 +113.181961 7.483305 6.300000 +113.000000 6.900000 6.300000 +113.368095 7.429788 6.300000 +113.072784 6.893322 6.300000 +113.547211 7.336996 6.300000 +113.147240 6.871915 6.300000 +113.707108 7.207107 6.300000 +113.218887 6.834798 6.300000 +113.836998 7.047210 6.300000 +114.000000 -6.500000 3.800000 +114.000000 -6.500000 6.300000 +112.000000 -6.500000 6.300000 +112.000000 -6.500000 3.800000 +112.016693 -6.681963 6.300000 +112.016693 -6.681963 3.800000 +112.070213 -6.868095 6.300000 +112.070213 -6.868095 3.800000 +112.163002 -7.047210 6.300000 +112.163002 -7.047210 3.800000 +112.292892 -7.207107 6.300000 +112.292892 -7.207107 3.800000 +112.452789 -7.336996 6.300000 +112.452789 -7.336996 3.800000 +112.631905 -7.429788 6.300000 +112.631905 -7.429788 3.800000 +112.818039 -7.483305 6.300000 +112.818039 -7.483305 3.800000 +113.000000 -7.500000 6.300000 +113.000000 -7.500000 3.800000 +113.181961 -7.483305 6.300000 +113.181961 -7.483305 3.800000 +113.368095 -7.429788 6.300000 +113.368095 -7.429788 3.800000 +113.547211 -7.336996 6.300000 +113.547211 -7.336996 3.800000 +113.707108 -7.207107 6.300000 +113.707108 -7.207107 3.800000 +113.836998 -7.047210 6.300000 +113.836998 -7.047210 3.800000 +113.929787 -6.868095 6.300000 +113.929787 -6.868095 3.800000 +113.983307 -6.681963 6.300000 +113.983307 -6.681963 3.800000 +112.628082 -6.647238 6.300000 +112.000000 -6.500000 6.300000 +112.606674 -6.572785 6.300000 +112.016693 -6.318037 6.300000 +112.599998 -6.500000 6.300000 +112.070213 -6.131905 6.300000 +112.606674 -6.427215 6.300000 +112.163002 -5.952790 6.300000 +112.628082 -6.352762 6.300000 +112.292892 -5.792893 6.300000 +112.665199 -6.281116 6.300000 +112.452789 -5.663004 6.300000 +112.717155 -6.217157 6.300000 +112.631905 -5.570212 6.300000 +112.781113 -6.165202 6.300000 +112.818039 -5.516695 6.300000 +112.852760 -6.128085 6.300000 +113.000000 -5.500000 6.300000 +112.927216 -6.106678 6.300000 +113.181961 -5.516695 6.300000 +113.000000 -6.100000 6.300000 +113.368095 -5.570212 6.300000 +113.072784 -6.106678 6.300000 +113.547211 -5.663004 6.300000 +113.147240 -6.128085 6.300000 +113.707108 -5.792893 6.300000 +113.218887 -6.165202 6.300000 +113.836998 -5.952790 6.300000 +113.282845 -6.217157 6.300000 +113.929787 -6.131905 6.300000 +113.334801 -6.281116 6.300000 +113.983307 -6.318037 6.300000 +113.371918 -6.352762 6.300000 +114.000000 -6.500000 6.300000 +113.393326 -6.427215 6.300000 +113.983307 -6.681963 6.300000 +113.400002 -6.500000 6.300000 +113.929787 -6.868095 6.300000 +113.393326 -6.572785 6.300000 +113.836998 -7.047210 6.300000 +113.371918 -6.647238 6.300000 +113.707108 -7.207107 6.300000 +113.334801 -6.718884 6.300000 +113.547211 -7.336996 6.300000 +113.282845 -6.782843 6.300000 +113.368095 -7.429788 6.300000 +113.218887 -6.834798 6.300000 +113.181961 -7.483305 6.300000 +113.147240 -6.871915 6.300000 +113.000000 -7.500000 6.300000 +113.072784 -6.893322 6.300000 +112.818039 -7.483305 6.300000 +113.000000 -6.900000 6.300000 +112.631905 -7.429788 6.300000 +112.927216 -6.893322 6.300000 +112.452789 -7.336996 6.300000 +112.852760 -6.871915 6.300000 +112.292892 -7.207107 6.300000 +112.781113 -6.834798 6.300000 +112.163002 -7.047210 6.300000 +112.717155 -6.782843 6.300000 +112.070213 -6.868095 6.300000 +112.665199 -6.718884 6.300000 +112.016693 -6.681963 6.300000 +83.516693 -6.681963 3.800000 +83.500000 -6.500000 6.300000 +83.500000 -6.500000 3.800000 +83.516693 -6.681963 6.300000 +85.500000 -6.500000 3.800000 +85.500000 -6.500000 6.300000 +85.483307 -6.681963 3.800000 +85.483307 -6.681963 6.300000 +85.429787 -6.868095 3.800000 +85.336998 -7.047210 3.800000 +85.429787 -6.868095 6.300000 +85.336998 -7.047210 6.300000 +85.207108 -7.207107 3.800000 +85.207108 -7.207107 6.300000 +85.047211 -7.336996 3.800000 +84.868095 -7.429788 3.800000 +85.047211 -7.336996 6.300000 +84.868095 -7.429788 6.300000 +84.681961 -7.483305 3.800000 +84.681961 -7.483305 6.300000 +84.500000 -7.500000 3.800000 +84.500000 -7.500000 6.300000 +84.318039 -7.483305 3.800000 +84.318039 -7.483305 6.300000 +84.131905 -7.429788 3.800000 +84.131905 -7.429788 6.300000 +83.952789 -7.336996 3.800000 +83.952789 -7.336996 6.300000 +83.792892 -7.207107 3.800000 +83.792892 -7.207107 6.300000 +83.663002 -7.047210 3.800000 +83.663002 -7.047210 6.300000 +83.570213 -6.868095 3.800000 +83.570213 -6.868095 6.300000 +84.106674 -6.572785 6.300000 +83.516693 -6.318037 6.300000 +84.099998 -6.500000 6.300000 +83.570213 -6.131905 6.300000 +84.106674 -6.427215 6.300000 +83.663002 -5.952790 6.300000 +84.128082 -6.352762 6.300000 +83.792892 -5.792893 6.300000 +84.165199 -6.281116 6.300000 +83.952789 -5.663004 6.300000 +84.217155 -6.217157 6.300000 +84.131905 -5.570212 6.300000 +84.281113 -6.165202 6.300000 +84.318039 -5.516695 6.300000 +84.352760 -6.128085 6.300000 +84.500000 -5.500000 6.300000 +84.427216 -6.106678 6.300000 +84.681961 -5.516695 6.300000 +84.500000 -6.100000 6.300000 +84.868095 -5.570212 6.300000 +84.572784 -6.106678 6.300000 +85.047211 -5.663004 6.300000 +84.647240 -6.128085 6.300000 +85.207108 -5.792893 6.300000 +84.718887 -6.165202 6.300000 +85.336998 -5.952790 6.300000 +84.782845 -6.217157 6.300000 +85.429787 -6.131905 6.300000 +84.834801 -6.281116 6.300000 +85.483307 -6.318037 6.300000 +84.871918 -6.352762 6.300000 +85.500000 -6.500000 6.300000 +84.893326 -6.427215 6.300000 +85.483307 -6.681963 6.300000 +84.900002 -6.500000 6.300000 +85.429787 -6.868095 6.300000 +84.893326 -6.572785 6.300000 +85.336998 -7.047210 6.300000 +84.871918 -6.647238 6.300000 +85.207108 -7.207107 6.300000 +84.834801 -6.718884 6.300000 +85.047211 -7.336996 6.300000 +84.782845 -6.782843 6.300000 +84.868095 -7.429788 6.300000 +84.718887 -6.834798 6.300000 +84.681961 -7.483305 6.300000 +84.647240 -6.871915 6.300000 +84.500000 -7.500000 6.300000 +84.572784 -6.893322 6.300000 +84.318039 -7.483305 6.300000 +84.500000 -6.900000 6.300000 +84.131905 -7.429788 6.300000 +84.427216 -6.893322 6.300000 +83.952789 -7.336996 6.300000 +84.352760 -6.871915 6.300000 +83.792892 -7.207107 6.300000 +84.281113 -6.834798 6.300000 +83.663002 -7.047210 6.300000 +84.217155 -6.782843 6.300000 +83.570213 -6.868095 6.300000 +84.165199 -6.718884 6.300000 +83.516693 -6.681963 6.300000 +84.128082 -6.647238 6.300000 +83.500000 -6.500000 6.300000 +21.000000 6.500000 6.300000 +21.000000 6.500000 3.800000 +22.983305 6.318037 3.800000 +23.000000 6.500000 3.800000 +23.000000 6.500000 6.300000 +22.983305 6.318037 6.300000 +22.929789 6.131905 3.800000 +22.836996 5.952790 3.800000 +22.929789 6.131905 6.300000 +22.707108 5.792893 3.800000 +22.836996 5.952790 6.300000 +22.707108 5.792893 6.300000 +22.547211 5.663004 3.800000 +22.547211 5.663004 6.300000 +22.368095 5.570212 3.800000 +22.368095 5.570212 6.300000 +22.181963 5.516695 3.800000 +22.181963 5.516695 6.300000 +22.000000 5.500000 3.800000 +22.000000 5.500000 6.300000 +21.818037 5.516695 3.800000 +21.818037 5.516695 6.300000 +21.631905 5.570212 3.800000 +21.631905 5.570212 6.300000 +21.452789 5.663004 3.800000 +21.452789 5.663004 6.300000 +21.292892 5.792893 3.800000 +21.292892 5.792893 6.300000 +21.163004 5.952790 3.800000 +21.163004 5.952790 6.300000 +21.070211 6.131905 3.800000 +21.070211 6.131905 6.300000 +21.016695 6.318037 3.800000 +21.016695 6.318037 6.300000 +21.665201 6.281116 6.300000 +21.016695 6.318037 6.300000 +21.628084 6.352762 6.300000 +21.000000 6.500000 6.300000 +21.606678 6.427215 6.300000 +21.016695 6.681963 6.300000 +21.600000 6.500000 6.300000 +21.070211 6.868095 6.300000 +21.606678 6.572785 6.300000 +21.163004 7.047210 6.300000 +21.628084 6.647238 6.300000 +21.292892 7.207107 6.300000 +21.665201 6.718884 6.300000 +21.452789 7.336996 6.300000 +21.717157 6.782843 6.300000 +21.631905 7.429788 6.300000 +21.781116 6.834798 6.300000 +21.818037 7.483305 6.300000 +21.852762 6.871915 6.300000 +22.000000 7.500000 6.300000 +21.927216 6.893322 6.300000 +22.181963 7.483305 6.300000 +22.000000 6.900000 6.300000 +22.368095 7.429788 6.300000 +22.072784 6.893322 6.300000 +22.547211 7.336996 6.300000 +22.147238 6.871915 6.300000 +22.707108 7.207107 6.300000 +22.218884 6.834798 6.300000 +22.836996 7.047210 6.300000 +22.282843 6.782843 6.300000 +22.929789 6.868095 6.300000 +22.334799 6.718884 6.300000 +22.983305 6.681963 6.300000 +22.371916 6.647238 6.300000 +23.000000 6.500000 6.300000 +22.393322 6.572785 6.300000 +22.983305 6.318037 6.300000 +22.400000 6.500000 6.300000 +22.929789 6.131905 6.300000 +22.393322 6.427215 6.300000 +22.836996 5.952790 6.300000 +22.371916 6.352762 6.300000 +22.707108 5.792893 6.300000 +22.334799 6.281116 6.300000 +22.547211 5.663004 6.300000 +22.282843 6.217157 6.300000 +22.368095 5.570212 6.300000 +22.218884 6.165202 6.300000 +22.181963 5.516695 6.300000 +22.147238 6.128085 6.300000 +22.000000 5.500000 6.300000 +22.072784 6.106678 6.300000 +21.818037 5.516695 6.300000 +22.000000 6.100000 6.300000 +21.631905 5.570212 6.300000 +21.927216 6.106678 6.300000 +21.452789 5.663004 6.300000 +21.852762 6.128085 6.300000 +21.292892 5.792893 6.300000 +21.781116 6.165202 6.300000 +21.163004 5.952790 6.300000 +21.717157 6.217157 6.300000 +21.070211 6.131905 6.300000 +64.000000 6.500000 3.800000 +64.000000 6.500000 6.300000 +62.000000 6.500000 6.300000 +62.000000 6.500000 3.800000 +62.016693 6.318037 6.300000 +62.016693 6.318037 3.800000 +62.070213 6.131905 6.300000 +62.070213 6.131905 3.800000 +62.163006 5.952790 6.300000 +62.163006 5.952790 3.800000 +62.292892 5.792893 6.300000 +62.292892 5.792893 3.800000 +62.452789 5.663004 6.300000 +62.452789 5.663004 3.800000 +62.631905 5.570212 6.300000 +62.631905 5.570212 3.800000 +62.818035 5.516695 6.300000 +62.818035 5.516695 3.800000 +63.000000 5.500000 6.300000 +63.000000 5.500000 3.800000 +63.181965 5.516695 6.300000 +63.181965 5.516695 3.800000 +63.368095 5.570212 6.300000 +63.368095 5.570212 3.800000 +63.547211 5.663004 6.300000 +63.547211 5.663004 3.800000 +63.707108 5.792893 6.300000 +63.707108 5.792893 3.800000 +63.836994 5.952790 6.300000 +63.836994 5.952790 3.800000 +63.929787 6.131905 6.300000 +63.929787 6.131905 3.800000 +63.983307 6.318037 6.300000 +63.983307 6.318037 3.800000 +62.599998 6.500000 6.300000 +62.070213 6.868095 6.300000 +62.606678 6.572785 6.300000 +62.163006 7.047210 6.300000 +62.628086 6.647238 6.300000 +62.292892 7.207107 6.300000 +62.665203 6.718884 6.300000 +62.452789 7.336996 6.300000 +62.717155 6.782843 6.300000 +62.631905 7.429788 6.300000 +62.781116 6.834798 6.300000 +62.818035 7.483305 6.300000 +62.852760 6.871915 6.300000 +63.000000 7.500000 6.300000 +62.927216 6.893322 6.300000 +63.181965 7.483305 6.300000 +63.000000 6.900000 6.300000 +63.368095 7.429788 6.300000 +63.072784 6.893322 6.300000 +63.547211 7.336996 6.300000 +63.147240 6.871915 6.300000 +63.707108 7.207107 6.300000 +63.218884 6.834798 6.300000 +63.836994 7.047210 6.300000 +63.282845 6.782843 6.300000 +63.929787 6.868095 6.300000 +63.334797 6.718884 6.300000 +63.983307 6.681963 6.300000 +63.371914 6.647238 6.300000 +64.000000 6.500000 6.300000 +63.393322 6.572785 6.300000 +63.983307 6.318037 6.300000 +63.400002 6.500000 6.300000 +63.929787 6.131905 6.300000 +63.393322 6.427215 6.300000 +63.836994 5.952790 6.300000 +63.371914 6.352762 6.300000 +63.707108 5.792893 6.300000 +63.334797 6.281116 6.300000 +63.547211 5.663004 6.300000 +63.282845 6.217157 6.300000 +63.368095 5.570212 6.300000 +63.218884 6.165202 6.300000 +63.181965 5.516695 6.300000 +63.147240 6.128085 6.300000 +63.000000 5.500000 6.300000 +63.072784 6.106678 6.300000 +62.818035 5.516695 6.300000 +63.000000 6.100000 6.300000 +62.631905 5.570212 6.300000 +62.927216 6.106678 6.300000 +62.452789 5.663004 6.300000 +62.852760 6.128085 6.300000 +62.292892 5.792893 6.300000 +62.781116 6.165202 6.300000 +62.163006 5.952790 6.300000 +62.717155 6.217157 6.300000 +62.070213 6.131905 6.300000 +62.665203 6.281116 6.300000 +62.016693 6.318037 6.300000 +62.628086 6.352762 6.300000 +62.000000 6.500000 6.300000 +62.606678 6.427215 6.300000 +62.016693 6.681963 6.300000 +64.000000 -6.500000 3.800000 +64.000000 -6.500000 6.300000 +62.000000 -6.500000 6.300000 +62.000000 -6.500000 3.800000 +62.016693 -6.681963 6.300000 +62.016693 -6.681963 3.800000 +62.070213 -6.868095 6.300000 +62.070213 -6.868095 3.800000 +62.163006 -7.047210 6.300000 +62.163006 -7.047210 3.800000 +62.292892 -7.207107 6.300000 +62.292892 -7.207107 3.800000 +62.452789 -7.336996 6.300000 +62.452789 -7.336996 3.800000 +62.631905 -7.429788 6.300000 +62.631905 -7.429788 3.800000 +62.818035 -7.483305 6.300000 +62.818035 -7.483305 3.800000 +63.000000 -7.500000 6.300000 +63.000000 -7.500000 3.800000 +63.181965 -7.483305 6.300000 +63.181965 -7.483305 3.800000 +63.368095 -7.429788 6.300000 +63.368095 -7.429788 3.800000 +63.547211 -7.336996 6.300000 +63.547211 -7.336996 3.800000 +63.707108 -7.207107 6.300000 +63.707108 -7.207107 3.800000 +63.836994 -7.047210 6.300000 +63.836994 -7.047210 3.800000 +63.929787 -6.868095 6.300000 +63.929787 -6.868095 3.800000 +63.983307 -6.681963 6.300000 +63.983307 -6.681963 3.800000 +63.282845 -6.782843 6.300000 +63.368095 -7.429788 6.300000 +63.218884 -6.834798 6.300000 +63.181965 -7.483305 6.300000 +63.147240 -6.871915 6.300000 +63.000000 -7.500000 6.300000 +63.072784 -6.893322 6.300000 +62.818035 -7.483305 6.300000 +63.000000 -6.900000 6.300000 +62.631905 -7.429788 6.300000 +62.927216 -6.893322 6.300000 +62.452789 -7.336996 6.300000 +62.852760 -6.871915 6.300000 +62.292892 -7.207107 6.300000 +62.781116 -6.834798 6.300000 +62.163006 -7.047210 6.300000 +62.717155 -6.782843 6.300000 +62.070213 -6.868095 6.300000 +62.665203 -6.718884 6.300000 +62.016693 -6.681963 6.300000 +62.628086 -6.647238 6.300000 +62.000000 -6.500000 6.300000 +62.606678 -6.572785 6.300000 +62.016693 -6.318037 6.300000 +62.599998 -6.500000 6.300000 +62.070213 -6.131905 6.300000 +62.606678 -6.427215 6.300000 +62.163006 -5.952790 6.300000 +62.628086 -6.352762 6.300000 +62.292892 -5.792893 6.300000 +62.665203 -6.281116 6.300000 +62.452789 -5.663004 6.300000 +62.717155 -6.217157 6.300000 +62.631905 -5.570212 6.300000 +62.781116 -6.165202 6.300000 +62.818035 -5.516695 6.300000 +62.852760 -6.128085 6.300000 +63.000000 -5.500000 6.300000 +62.927216 -6.106678 6.300000 +63.181965 -5.516695 6.300000 +63.000000 -6.100000 6.300000 +63.368095 -5.570212 6.300000 +63.072784 -6.106678 6.300000 +63.547211 -5.663004 6.300000 +63.147240 -6.128085 6.300000 +63.707108 -5.792893 6.300000 +63.218884 -6.165202 6.300000 +63.836994 -5.952790 6.300000 +63.282845 -6.217157 6.300000 +63.929787 -6.131905 6.300000 +63.334797 -6.281116 6.300000 +63.983307 -6.318037 6.300000 +63.371914 -6.352762 6.300000 +64.000000 -6.500000 6.300000 +63.393322 -6.427215 6.300000 +63.983307 -6.681963 6.300000 +63.400002 -6.500000 6.300000 +63.929787 -6.868095 6.300000 +63.393322 -6.572785 6.300000 +63.836994 -7.047210 6.300000 +63.371914 -6.647238 6.300000 +63.707108 -7.207107 6.300000 +63.334797 -6.718884 6.300000 +63.547211 -7.336996 6.300000 +21.000000 -6.500000 6.300000 +21.000000 -6.500000 3.800000 +22.983305 -6.681963 3.800000 +23.000000 -6.500000 3.800000 +23.000000 -6.500000 6.300000 +22.929789 -6.868095 3.800000 +22.983305 -6.681963 6.300000 +22.929789 -6.868095 6.300000 +22.836996 -7.047210 3.800000 +22.836996 -7.047210 6.300000 +22.707108 -7.207107 3.800000 +22.547211 -7.336996 3.800000 +22.707108 -7.207107 6.300000 +22.547211 -7.336996 6.300000 +22.368095 -7.429788 3.800000 +22.368095 -7.429788 6.300000 +22.181963 -7.483305 3.800000 +22.181963 -7.483305 6.300000 +22.000000 -7.500000 3.800000 +22.000000 -7.500000 6.300000 +21.818037 -7.483305 3.800000 +21.818037 -7.483305 6.300000 +21.631905 -7.429788 3.800000 +21.631905 -7.429788 6.300000 +21.452789 -7.336996 3.800000 +21.452789 -7.336996 6.300000 +21.292892 -7.207107 3.800000 +21.292892 -7.207107 6.300000 +21.163004 -7.047210 3.800000 +21.163004 -7.047210 6.300000 +21.070211 -6.868095 3.800000 +21.070211 -6.868095 6.300000 +21.016695 -6.681963 3.800000 +21.016695 -6.681963 6.300000 +21.665201 -6.718884 6.300000 +21.016695 -6.681963 6.300000 +21.628084 -6.647238 6.300000 +21.000000 -6.500000 6.300000 +21.606678 -6.572785 6.300000 +21.016695 -6.318037 6.300000 +21.600000 -6.500000 6.300000 +21.070211 -6.131905 6.300000 +21.606678 -6.427215 6.300000 +21.163004 -5.952790 6.300000 +21.628084 -6.352762 6.300000 +21.292892 -5.792893 6.300000 +21.665201 -6.281116 6.300000 +21.452789 -5.663004 6.300000 +21.717157 -6.217157 6.300000 +21.631905 -5.570212 6.300000 +21.781116 -6.165202 6.300000 +21.818037 -5.516695 6.300000 +21.852762 -6.128085 6.300000 +22.000000 -5.500000 6.300000 +21.927216 -6.106678 6.300000 +22.181963 -5.516695 6.300000 +22.000000 -6.100000 6.300000 +22.368095 -5.570212 6.300000 +22.072784 -6.106678 6.300000 +22.547211 -5.663004 6.300000 +22.147238 -6.128085 6.300000 +22.707108 -5.792893 6.300000 +22.218884 -6.165202 6.300000 +22.836996 -5.952790 6.300000 +22.282843 -6.217157 6.300000 +22.929789 -6.131905 6.300000 +22.334799 -6.281116 6.300000 +22.983305 -6.318037 6.300000 +22.371916 -6.352762 6.300000 +23.000000 -6.500000 6.300000 +22.393322 -6.427215 6.300000 +22.983305 -6.681963 6.300000 +22.400000 -6.500000 6.300000 +22.929789 -6.868095 6.300000 +22.393322 -6.572785 6.300000 +22.836996 -7.047210 6.300000 +22.371916 -6.647238 6.300000 +22.707108 -7.207107 6.300000 +22.334799 -6.718884 6.300000 +22.547211 -7.336996 6.300000 +22.282843 -6.782843 6.300000 +22.368095 -7.429788 6.300000 +22.218884 -6.834798 6.300000 +22.181963 -7.483305 6.300000 +22.147238 -6.871915 6.300000 +22.000000 -7.500000 6.300000 +22.072784 -6.893322 6.300000 +21.818037 -7.483305 6.300000 +22.000000 -6.900000 6.300000 +21.631905 -7.429788 6.300000 +21.927216 -6.893322 6.300000 +21.452789 -7.336996 6.300000 +21.852762 -6.871915 6.300000 +21.292892 -7.207107 6.300000 +21.781116 -6.834798 6.300000 +21.163004 -7.047210 6.300000 +21.717157 -6.782843 6.300000 +21.070211 -6.868095 6.300000 +40.000000 0.000000 3.800000 +40.000000 0.000000 6.300000 +38.000000 0.000000 6.300000 +38.000000 0.000000 3.800000 +38.016693 -0.181963 6.300000 +38.016693 -0.181963 3.800000 +38.070213 -0.368095 6.300000 +38.070213 -0.368095 3.800000 +38.163006 -0.547210 6.300000 +38.163006 -0.547210 3.800000 +38.292892 -0.707107 6.300000 +38.292892 -0.707107 3.800000 +38.452789 -0.836995 6.300000 +38.452789 -0.836995 3.800000 +38.631905 -0.929788 6.300000 +38.631905 -0.929788 3.800000 +38.818035 -0.983305 6.300000 +38.818035 -0.983305 3.800000 +39.000000 -1.000000 6.300000 +39.000000 -1.000000 3.800000 +39.181965 -0.983305 6.300000 +39.181965 -0.983305 3.800000 +39.368095 -0.929788 6.300000 +39.368095 -0.929788 3.800000 +39.547211 -0.836995 6.300000 +39.547211 -0.836995 3.800000 +39.707108 -0.707107 6.300000 +39.707108 -0.707107 3.800000 +39.836994 -0.547210 6.300000 +39.836994 -0.547210 3.800000 +39.929787 -0.368095 6.300000 +39.929787 -0.368095 3.800000 +39.983307 -0.181963 6.300000 +39.983307 -0.181963 3.800000 +39.400002 0.000000 6.300000 +39.929787 -0.368095 6.300000 +39.393322 -0.072785 6.300000 +39.836994 -0.547210 6.300000 +39.371914 -0.147238 6.300000 +39.707108 -0.707107 6.300000 +39.334797 -0.218884 6.300000 +39.547211 -0.836995 6.300000 +39.282845 -0.282843 6.300000 +39.368095 -0.929788 6.300000 +39.218884 -0.334798 6.300000 +39.181965 -0.983305 6.300000 +39.147240 -0.371915 6.300000 +39.000000 -1.000000 6.300000 +39.072784 -0.393322 6.300000 +38.818035 -0.983305 6.300000 +39.000000 -0.400000 6.300000 +38.631905 -0.929788 6.300000 +38.927216 -0.393322 6.300000 +38.452789 -0.836995 6.300000 +38.852760 -0.371915 6.300000 +38.292892 -0.707107 6.300000 +38.781116 -0.334798 6.300000 +38.163006 -0.547210 6.300000 +38.717155 -0.282843 6.300000 +38.070213 -0.368095 6.300000 +38.665203 -0.218884 6.300000 +38.016693 -0.181963 6.300000 +38.628086 -0.147238 6.300000 +38.000000 0.000000 6.300000 +38.606678 -0.072785 6.300000 +38.016693 0.181963 6.300000 +38.599998 0.000000 6.300000 +38.070213 0.368095 6.300000 +38.606678 0.072785 6.300000 +38.163006 0.547210 6.300000 +38.628086 0.147238 6.300000 +38.292892 0.707107 6.300000 +38.665203 0.218884 6.300000 +38.452789 0.836995 6.300000 +38.717155 0.282843 6.300000 +38.631905 0.929788 6.300000 +38.781116 0.334798 6.300000 +38.818035 0.983305 6.300000 +38.852760 0.371915 6.300000 +39.000000 1.000000 6.300000 +38.927216 0.393322 6.300000 +39.181965 0.983305 6.300000 +39.000000 0.400000 6.300000 +39.368095 0.929788 6.300000 +39.072784 0.393322 6.300000 +39.547211 0.836995 6.300000 +39.147240 0.371915 6.300000 +39.707108 0.707107 6.300000 +39.218884 0.334798 6.300000 +39.836994 0.547210 6.300000 +39.282845 0.282843 6.300000 +39.929787 0.368095 6.300000 +39.334797 0.218884 6.300000 +39.983307 0.181963 6.300000 +39.371914 0.147238 6.300000 +40.000000 0.000000 6.300000 +39.393322 0.072785 6.300000 +39.983307 -0.181963 6.300000 +112.606674 6.572785 6.300000 +112.599998 6.500000 6.300000 +113.393326 6.572785 5.300000 +113.400002 6.500000 5.300000 +113.400002 6.500000 6.300000 +113.393326 6.572785 6.300000 +113.371918 6.647238 5.300000 +113.371918 6.647238 6.300000 +113.334801 6.718884 5.300000 +113.334801 6.718884 6.300000 +113.282845 6.782843 5.300000 +113.282845 6.782843 6.300000 +113.218887 6.834798 5.300000 +113.147240 6.871915 5.300000 +113.218887 6.834798 6.300000 +113.072784 6.893322 5.300000 +113.147240 6.871915 6.300000 +113.072784 6.893322 6.300000 +113.000000 6.900000 5.300000 +112.927216 6.893322 5.300000 +113.000000 6.900000 6.300000 +112.852760 6.871915 5.300000 +112.927216 6.893322 6.300000 +112.852760 6.871915 6.300000 +112.781113 6.834798 5.300000 +112.781113 6.834798 6.300000 +112.717155 6.782843 5.300000 +112.717155 6.782843 6.300000 +112.665199 6.718884 5.300000 +112.628082 6.647238 5.300000 +112.665199 6.718884 6.300000 +112.628082 6.647238 6.300000 +112.606674 6.572785 5.300000 +112.599998 6.500000 5.300000 +112.852760 6.128085 5.300000 +112.927216 6.106678 5.300000 +113.334801 6.281116 5.300000 +113.371918 6.352762 5.300000 +113.282845 6.217157 5.300000 +113.218887 6.165202 5.300000 +113.393326 6.427215 5.300000 +113.147240 6.128085 5.300000 +113.400002 6.500000 5.300000 +113.072784 6.106678 5.300000 +113.393326 6.572785 5.300000 +113.371918 6.647238 5.300000 +113.334801 6.718884 5.300000 +113.282845 6.782843 5.300000 +113.218887 6.834798 5.300000 +113.147240 6.871915 5.300000 +113.072784 6.893322 5.300000 +113.000000 6.100000 5.300000 +113.000000 6.900000 5.300000 +112.927216 6.893322 5.300000 +112.852760 6.871915 5.300000 +112.781113 6.834798 5.300000 +112.717155 6.782843 5.300000 +112.665199 6.718884 5.300000 +112.628082 6.647238 5.300000 +112.606674 6.572785 5.300000 +112.599998 6.500000 5.300000 +112.606674 6.427215 5.300000 +112.628082 6.352762 5.300000 +112.665199 6.281116 5.300000 +112.717155 6.217157 5.300000 +112.781113 6.165202 5.300000 +112.665199 -6.281116 5.300000 +112.606674 -6.427215 6.300000 +112.599998 -6.500000 6.300000 +112.599998 -6.500000 5.300000 +112.606674 -6.427215 5.300000 +112.628082 -6.352762 6.300000 +112.665199 -6.281116 6.300000 +112.628082 -6.352762 5.300000 +113.400002 -6.500000 5.300000 +113.400002 -6.500000 6.300000 +113.393326 -6.427215 5.300000 +113.393326 -6.427215 6.300000 +113.371918 -6.352762 5.300000 +113.371918 -6.352762 6.300000 +113.334801 -6.281116 5.300000 +113.334801 -6.281116 6.300000 +113.282845 -6.217157 5.300000 +113.282845 -6.217157 6.300000 +113.218887 -6.165202 5.300000 +113.218887 -6.165202 6.300000 +113.147240 -6.128085 5.300000 +113.147240 -6.128085 6.300000 +113.072784 -6.106678 5.300000 +113.000000 -6.100000 5.300000 +113.072784 -6.106678 6.300000 +113.000000 -6.100000 6.300000 +112.927216 -6.106678 5.300000 +112.927216 -6.106678 6.300000 +112.852760 -6.128085 5.300000 +112.781113 -6.165202 5.300000 +112.852760 -6.128085 6.300000 +112.781113 -6.165202 6.300000 +112.717155 -6.217157 5.300000 +112.717155 -6.217157 6.300000 +113.000000 -6.900000 5.300000 +113.072784 -6.893322 5.300000 +113.334801 -6.718884 5.300000 +113.371918 -6.647238 5.300000 +113.282845 -6.782843 5.300000 +113.218887 -6.834798 5.300000 +113.393326 -6.572785 5.300000 +113.147240 -6.871915 5.300000 +113.400002 -6.500000 5.300000 +113.393326 -6.427215 5.300000 +113.371918 -6.352762 5.300000 +113.334801 -6.281116 5.300000 +113.282845 -6.217157 5.300000 +113.218887 -6.165202 5.300000 +113.147240 -6.128085 5.300000 +113.072784 -6.106678 5.300000 +113.000000 -6.100000 5.300000 +112.927216 -6.106678 5.300000 +112.852760 -6.128085 5.300000 +112.781113 -6.165202 5.300000 +112.717155 -6.217157 5.300000 +112.665199 -6.281116 5.300000 +112.628082 -6.352762 5.300000 +112.606674 -6.427215 5.300000 +112.599998 -6.500000 5.300000 +112.606674 -6.572785 5.300000 +112.628082 -6.647238 5.300000 +112.665199 -6.718884 5.300000 +112.717155 -6.782843 5.300000 +112.781113 -6.834798 5.300000 +112.852760 -6.871915 5.300000 +112.927216 -6.893322 5.300000 +84.782845 6.782843 6.300000 +84.893326 6.572785 5.300000 +84.900002 6.500000 5.300000 +84.900002 6.500000 6.300000 +84.893326 6.572785 6.300000 +84.871918 6.647238 5.300000 +84.834801 6.718884 5.300000 +84.871918 6.647238 6.300000 +84.834801 6.718884 6.300000 +84.782845 6.782843 5.300000 +84.099998 6.500000 6.300000 +84.099998 6.500000 5.300000 +84.106674 6.572785 6.300000 +84.128082 6.647238 6.300000 +84.106674 6.572785 5.300000 +84.128082 6.647238 5.300000 +84.165199 6.718884 6.300000 +84.165199 6.718884 5.300000 +84.217155 6.782843 6.300000 +84.217155 6.782843 5.300000 +84.281113 6.834798 6.300000 +84.352760 6.871915 6.300000 +84.281113 6.834798 5.300000 +84.427216 6.893322 6.300000 +84.352760 6.871915 5.300000 +84.500000 6.900000 6.300000 +84.427216 6.893322 5.300000 +84.572784 6.893322 6.300000 +84.500000 6.900000 5.300000 +84.647240 6.871915 6.300000 +84.572784 6.893322 5.300000 +84.718887 6.834798 6.300000 +84.647240 6.871915 5.300000 +84.718887 6.834798 5.300000 +84.500000 6.100000 5.300000 +84.572784 6.106678 5.300000 +84.834801 6.281116 5.300000 +84.871918 6.352762 5.300000 +84.782845 6.217157 5.300000 +84.718887 6.165202 5.300000 +84.893326 6.427215 5.300000 +84.647240 6.128085 5.300000 +84.900002 6.500000 5.300000 +84.893326 6.572785 5.300000 +84.871918 6.647238 5.300000 +84.834801 6.718884 5.300000 +84.782845 6.782843 5.300000 +84.718887 6.834798 5.300000 +84.647240 6.871915 5.300000 +84.572784 6.893322 5.300000 +84.500000 6.900000 5.300000 +84.427216 6.893322 5.300000 +84.352760 6.871915 5.300000 +84.281113 6.834798 5.300000 +84.217155 6.782843 5.300000 +84.165199 6.718884 5.300000 +84.128082 6.647238 5.300000 +84.106674 6.572785 5.300000 +84.099998 6.500000 5.300000 +84.106674 6.427215 5.300000 +84.128082 6.352762 5.300000 +84.165199 6.281116 5.300000 +84.217155 6.217157 5.300000 +84.281113 6.165202 5.300000 +84.352760 6.128085 5.300000 +84.427216 6.106678 5.300000 +84.099998 -6.500000 6.300000 +84.099998 -6.500000 5.300000 +84.900002 -6.500000 5.300000 +84.900002 -6.500000 6.300000 +84.893326 -6.427215 5.300000 +84.871918 -6.352762 5.300000 +84.893326 -6.427215 6.300000 +84.871918 -6.352762 6.300000 +84.834801 -6.281116 5.300000 +84.834801 -6.281116 6.300000 +84.782845 -6.217157 5.300000 +84.718887 -6.165202 5.300000 +84.782845 -6.217157 6.300000 +84.718887 -6.165202 6.300000 +84.647240 -6.128085 5.300000 +84.647240 -6.128085 6.300000 +84.572784 -6.106678 5.300000 +84.500000 -6.100000 5.300000 +84.572784 -6.106678 6.300000 +84.500000 -6.100000 6.300000 +84.427216 -6.106678 5.300000 +84.427216 -6.106678 6.300000 +84.352760 -6.128085 5.300000 +84.352760 -6.128085 6.300000 +84.281113 -6.165202 5.300000 +84.217155 -6.217157 5.300000 +84.281113 -6.165202 6.300000 +84.165199 -6.281116 5.300000 +84.217155 -6.217157 6.300000 +84.165199 -6.281116 6.300000 +84.128082 -6.352762 5.300000 +84.106674 -6.427215 5.300000 +84.128082 -6.352762 6.300000 +84.106674 -6.427215 6.300000 +84.427216 -6.893322 5.300000 +84.500000 -6.900000 5.300000 +84.834801 -6.718884 5.300000 +84.871918 -6.647238 5.300000 +84.782845 -6.782843 5.300000 +84.718887 -6.834798 5.300000 +84.893326 -6.572785 5.300000 +84.647240 -6.871915 5.300000 +84.900002 -6.500000 5.300000 +84.572784 -6.893322 5.300000 +84.893326 -6.427215 5.300000 +84.871918 -6.352762 5.300000 +84.834801 -6.281116 5.300000 +84.782845 -6.217157 5.300000 +84.718887 -6.165202 5.300000 +84.647240 -6.128085 5.300000 +84.572784 -6.106678 5.300000 +84.500000 -6.100000 5.300000 +84.427216 -6.106678 5.300000 +84.352760 -6.128085 5.300000 +84.281113 -6.165202 5.300000 +84.217155 -6.217157 5.300000 +84.165199 -6.281116 5.300000 +84.128082 -6.352762 5.300000 +84.106674 -6.427215 5.300000 +84.099998 -6.500000 5.300000 +84.106674 -6.572785 5.300000 +84.128082 -6.647238 5.300000 +84.165199 -6.718884 5.300000 +84.217155 -6.782843 5.300000 +84.281113 -6.834798 5.300000 +84.352760 -6.871915 5.300000 +62.781116 6.834798 6.300000 +62.606678 6.572785 6.300000 +62.599998 6.500000 6.300000 +62.599998 6.500000 5.300000 +62.628086 6.647238 6.300000 +62.606678 6.572785 5.300000 +62.665203 6.718884 6.300000 +62.628086 6.647238 5.300000 +62.717155 6.782843 6.300000 +62.665203 6.718884 5.300000 +63.400002 6.500000 5.300000 +63.400002 6.500000 6.300000 +63.393322 6.572785 5.300000 +63.393322 6.572785 6.300000 +63.371914 6.647238 5.300000 +63.371914 6.647238 6.300000 +63.334797 6.718884 5.300000 +63.282845 6.782843 5.300000 +63.334797 6.718884 6.300000 +63.218884 6.834798 5.300000 +63.282845 6.782843 6.300000 +63.218884 6.834798 6.300000 +63.147240 6.871915 5.300000 +63.072784 6.893322 5.300000 +63.147240 6.871915 6.300000 +63.000000 6.900000 5.300000 +63.072784 6.893322 6.300000 +62.927216 6.893322 5.300000 +63.000000 6.900000 6.300000 +62.852760 6.871915 5.300000 +62.927216 6.893322 6.300000 +62.781116 6.834798 5.300000 +62.852760 6.871915 6.300000 +62.717155 6.782843 5.300000 +62.852760 6.128085 5.300000 +62.927216 6.106678 5.300000 +63.334797 6.281116 5.300000 +63.371914 6.352762 5.300000 +63.282845 6.217157 5.300000 +63.218884 6.165202 5.300000 +63.393322 6.427215 5.300000 +63.147240 6.128085 5.300000 +63.400002 6.500000 5.300000 +63.072784 6.106678 5.300000 +63.393322 6.572785 5.300000 +63.371914 6.647238 5.300000 +63.334797 6.718884 5.300000 +63.282845 6.782843 5.300000 +63.218884 6.834798 5.300000 +63.147240 6.871915 5.300000 +63.072784 6.893322 5.300000 +63.000000 6.900000 5.300000 +62.927216 6.893322 5.300000 +62.852760 6.871915 5.300000 +62.781116 6.834798 5.300000 +62.717155 6.782843 5.300000 +62.665203 6.718884 5.300000 +62.628086 6.647238 5.300000 +62.606678 6.572785 5.300000 +63.000000 6.100000 5.300000 +62.599998 6.500000 5.300000 +62.606678 6.427215 5.300000 +62.628086 6.352762 5.300000 +62.665203 6.281116 5.300000 +62.717155 6.217157 5.300000 +62.781116 6.165202 5.300000 +62.599998 -6.500000 6.300000 +62.599998 -6.500000 5.300000 +63.393322 -6.427215 5.300000 +63.400002 -6.500000 5.300000 +63.400002 -6.500000 6.300000 +63.393322 -6.427215 6.300000 +63.371914 -6.352762 5.300000 +63.334797 -6.281116 5.300000 +63.371914 -6.352762 6.300000 +63.334797 -6.281116 6.300000 +63.282845 -6.217157 5.300000 +63.218884 -6.165202 5.300000 +63.282845 -6.217157 6.300000 +63.147240 -6.128085 5.300000 +63.218884 -6.165202 6.300000 +63.072784 -6.106678 5.300000 +63.147240 -6.128085 6.300000 +63.000000 -6.100000 5.300000 +63.072784 -6.106678 6.300000 +63.000000 -6.100000 6.300000 +62.927216 -6.106678 5.300000 +62.852760 -6.128085 5.300000 +62.927216 -6.106678 6.300000 +62.781116 -6.165202 5.300000 +62.852760 -6.128085 6.300000 +62.781116 -6.165202 6.300000 +62.717155 -6.217157 5.300000 +62.717155 -6.217157 6.300000 +62.665203 -6.281116 5.300000 +62.665203 -6.281116 6.300000 +62.628086 -6.352762 5.300000 +62.628086 -6.352762 6.300000 +62.606678 -6.427215 5.300000 +62.606678 -6.427215 6.300000 +62.927216 -6.893322 5.300000 +63.000000 -6.900000 5.300000 +63.334797 -6.718884 5.300000 +63.371914 -6.647238 5.300000 +63.282845 -6.782843 5.300000 +63.218884 -6.834798 5.300000 +63.393322 -6.572785 5.300000 +63.147240 -6.871915 5.300000 +63.400002 -6.500000 5.300000 +63.072784 -6.893322 5.300000 +63.393322 -6.427215 5.300000 +63.371914 -6.352762 5.300000 +63.334797 -6.281116 5.300000 +63.282845 -6.217157 5.300000 +63.218884 -6.165202 5.300000 +63.147240 -6.128085 5.300000 +63.072784 -6.106678 5.300000 +63.000000 -6.100000 5.300000 +62.927216 -6.106678 5.300000 +62.852760 -6.128085 5.300000 +62.781116 -6.165202 5.300000 +62.717155 -6.217157 5.300000 +62.665203 -6.281116 5.300000 +62.628086 -6.352762 5.300000 +62.606678 -6.427215 5.300000 +62.599998 -6.500000 5.300000 +62.606678 -6.572785 5.300000 +62.628086 -6.647238 5.300000 +62.665203 -6.718884 5.300000 +62.717155 -6.782843 5.300000 +62.781116 -6.834798 5.300000 +62.852760 -6.871915 5.300000 +22.000000 6.900000 6.300000 +21.606678 6.572785 6.300000 +21.600000 6.500000 6.300000 +21.600000 6.500000 5.300000 +21.628084 6.647238 6.300000 +21.606678 6.572785 5.300000 +21.628084 6.647238 5.300000 +21.665201 6.718884 6.300000 +21.665201 6.718884 5.300000 +21.717157 6.782843 6.300000 +21.781116 6.834798 6.300000 +21.717157 6.782843 5.300000 +21.852762 6.871915 6.300000 +21.781116 6.834798 5.300000 +21.927216 6.893322 6.300000 +21.852762 6.871915 5.300000 +22.400000 6.500000 5.300000 +22.400000 6.500000 6.300000 +22.393322 6.572785 5.300000 +22.393322 6.572785 6.300000 +22.371916 6.647238 5.300000 +22.371916 6.647238 6.300000 +22.334799 6.718884 5.300000 +22.334799 6.718884 6.300000 +22.282843 6.782843 5.300000 +22.282843 6.782843 6.300000 +22.218884 6.834798 5.300000 +22.218884 6.834798 6.300000 +22.147238 6.871915 5.300000 +22.147238 6.871915 6.300000 +22.072784 6.893322 5.300000 +22.072784 6.893322 6.300000 +22.000000 6.900000 5.300000 +21.927216 6.893322 5.300000 +22.000000 6.100000 5.300000 +22.072784 6.106678 5.300000 +22.334799 6.281116 5.300000 +22.371916 6.352762 5.300000 +22.282843 6.217157 5.300000 +22.218884 6.165202 5.300000 +22.393322 6.427215 5.300000 +22.147238 6.128085 5.300000 +22.400000 6.500000 5.300000 +22.393322 6.572785 5.300000 +22.371916 6.647238 5.300000 +22.334799 6.718884 5.300000 +22.282843 6.782843 5.300000 +22.218884 6.834798 5.300000 +22.147238 6.871915 5.300000 +22.072784 6.893322 5.300000 +22.000000 6.900000 5.300000 +21.927216 6.893322 5.300000 +21.852762 6.871915 5.300000 +21.781116 6.834798 5.300000 +21.717157 6.782843 5.300000 +21.665201 6.718884 5.300000 +21.628084 6.647238 5.300000 +21.606678 6.572785 5.300000 +21.600000 6.500000 5.300000 +21.606678 6.427215 5.300000 +21.628084 6.352762 5.300000 +21.665201 6.281116 5.300000 +21.717157 6.217157 5.300000 +21.781116 6.165202 5.300000 +21.852762 6.128085 5.300000 +21.927216 6.106678 5.300000 +21.600000 -6.500000 6.300000 +21.600000 -6.500000 5.300000 +22.393322 -6.427215 5.300000 +22.400000 -6.500000 5.300000 +22.400000 -6.500000 6.300000 +22.393322 -6.427215 6.300000 +22.371916 -6.352762 5.300000 +22.371916 -6.352762 6.300000 +22.334799 -6.281116 5.300000 +22.334799 -6.281116 6.300000 +22.282843 -6.217157 5.300000 +22.282843 -6.217157 6.300000 +22.218884 -6.165202 5.300000 +22.218884 -6.165202 6.300000 +22.147238 -6.128085 5.300000 +22.147238 -6.128085 6.300000 +22.072784 -6.106678 5.300000 +22.072784 -6.106678 6.300000 +22.000000 -6.100000 5.300000 +22.000000 -6.100000 6.300000 +21.927216 -6.106678 5.300000 +21.927216 -6.106678 6.300000 +21.852762 -6.128085 5.300000 +21.852762 -6.128085 6.300000 +21.781116 -6.165202 5.300000 +21.717157 -6.217157 5.300000 +21.781116 -6.165202 6.300000 +21.717157 -6.217157 6.300000 +21.665201 -6.281116 5.300000 +21.665201 -6.281116 6.300000 +21.628084 -6.352762 5.300000 +21.628084 -6.352762 6.300000 +21.606678 -6.427215 5.300000 +21.606678 -6.427215 6.300000 +21.852762 -6.871915 5.300000 +21.927216 -6.893322 5.300000 +22.334799 -6.718884 5.300000 +22.371916 -6.647238 5.300000 +22.282843 -6.782843 5.300000 +22.218884 -6.834798 5.300000 +22.393322 -6.572785 5.300000 +22.147238 -6.871915 5.300000 +22.400000 -6.500000 5.300000 +22.072784 -6.893322 5.300000 +22.393322 -6.427215 5.300000 +22.371916 -6.352762 5.300000 +22.334799 -6.281116 5.300000 +22.282843 -6.217157 5.300000 +22.218884 -6.165202 5.300000 +22.147238 -6.128085 5.300000 +22.072784 -6.106678 5.300000 +22.000000 -6.900000 5.300000 +22.000000 -6.100000 5.300000 +21.927216 -6.106678 5.300000 +21.852762 -6.128085 5.300000 +21.781116 -6.165202 5.300000 +21.717157 -6.217157 5.300000 +21.665201 -6.281116 5.300000 +21.628084 -6.352762 5.300000 +21.606678 -6.427215 5.300000 +21.600000 -6.500000 5.300000 +21.606678 -6.572785 5.300000 +21.628084 -6.647238 5.300000 +21.665201 -6.718884 5.300000 +21.717157 -6.782843 5.300000 +21.781116 -6.834798 5.300000 +38.599998 0.000000 6.300000 +38.599998 0.000000 5.300000 +39.393322 0.072785 5.300000 +39.400002 0.000000 5.300000 +39.400002 0.000000 6.300000 +39.393322 0.072785 6.300000 +39.371914 0.147238 5.300000 +39.371914 0.147238 6.300000 +39.334797 0.218884 5.300000 +39.334797 0.218884 6.300000 +39.282845 0.282843 5.300000 +39.218884 0.334798 5.300000 +39.282845 0.282843 6.300000 +39.218884 0.334798 6.300000 +39.147240 0.371915 5.300000 +39.147240 0.371915 6.300000 +39.072784 0.393322 5.300000 +39.072784 0.393322 6.300000 +39.000000 0.400000 5.300000 +39.000000 0.400000 6.300000 +38.927216 0.393322 5.300000 +38.927216 0.393322 6.300000 +38.852760 0.371915 5.300000 +38.852760 0.371915 6.300000 +38.781116 0.334798 5.300000 +38.781116 0.334798 6.300000 +38.717155 0.282843 5.300000 +38.717155 0.282843 6.300000 +38.665203 0.218884 5.300000 +38.665203 0.218884 6.300000 +38.628086 0.147238 5.300000 +38.628086 0.147238 6.300000 +38.606678 0.072785 5.300000 +38.606678 0.072785 6.300000 +38.927216 -0.393322 5.300000 +39.000000 -0.400000 5.300000 +39.334797 -0.218884 5.300000 +39.371914 -0.147238 5.300000 +39.282845 -0.282843 5.300000 +39.218884 -0.334798 5.300000 +39.393322 -0.072785 5.300000 +39.147240 -0.371915 5.300000 +39.400002 0.000000 5.300000 +39.393322 0.072785 5.300000 +39.371914 0.147238 5.300000 +39.334797 0.218884 5.300000 +39.282845 0.282843 5.300000 +39.218884 0.334798 5.300000 +39.147240 0.371915 5.300000 +39.072784 0.393322 5.300000 +39.000000 0.400000 5.300000 +39.072784 -0.393322 5.300000 +38.927216 0.393322 5.300000 +38.852760 0.371915 5.300000 +38.781116 0.334798 5.300000 +38.717155 0.282843 5.300000 +38.665203 0.218884 5.300000 +38.628086 0.147238 5.300000 +38.606678 0.072785 5.300000 +38.599998 0.000000 5.300000 +38.606678 -0.072785 5.300000 +38.628086 -0.147238 5.300000 +38.665203 -0.218884 5.300000 +38.717155 -0.282843 5.300000 +38.781116 -0.334798 5.300000 +38.852760 -0.371915 5.300000 +20.500000 0.500000 5.800000 +21.000000 0.500000 5.800000 +21.900000 0.500000 3.800000 +20.500000 0.500000 3.800000 +21.900000 0.500000 4.900000 +20.200001 0.200000 3.800000 +20.200001 -0.200000 3.800000 +20.200001 -0.200000 5.800000 +20.200001 0.200000 5.800000 +21.900000 -0.500000 4.900000 +21.000000 -0.500000 5.800000 +20.500000 -0.500000 5.800000 +20.500000 -0.500000 3.800000 +21.900000 -0.500000 3.800000 +22.200001 0.200000 4.600000 +22.200001 -0.200000 4.600000 +22.200001 -0.200000 3.800000 +22.200001 0.200000 3.800000 +20.389572 -0.478936 5.800000 +20.445412 -0.494992 5.800000 +21.000000 -0.500000 5.800000 +21.000000 0.500000 5.800000 +20.500000 -0.500000 5.800000 +20.500000 0.500000 5.800000 +20.445412 0.494992 5.800000 +20.389572 0.478936 5.800000 +20.335836 0.451099 5.800000 +20.287868 0.412132 5.800000 +20.248901 0.364163 5.800000 +20.221064 0.310428 5.800000 +20.205008 0.254589 5.800000 +20.200001 0.200000 5.800000 +20.200001 -0.200000 5.800000 +20.205008 -0.254589 5.800000 +20.221064 -0.310428 5.800000 +20.248901 -0.364163 5.800000 +20.287868 -0.412132 5.800000 +20.335836 -0.451099 5.800000 +22.200001 0.200000 4.600000 +22.194992 0.254589 4.605009 +21.900000 0.500000 4.900000 +21.000000 0.500000 5.800000 +21.000000 -0.500000 5.800000 +21.900000 -0.500000 4.900000 +22.010427 0.478936 4.789572 +22.010427 -0.478936 4.789572 +22.112131 -0.412132 4.687868 +22.151098 -0.364163 4.648901 +22.178936 -0.310428 4.621064 +22.194992 -0.254589 4.605009 +22.200001 -0.200000 4.600000 +22.064163 0.451099 4.735837 +22.112131 0.412132 4.687868 +22.151098 0.364163 4.648901 +22.178936 0.310428 4.621064 +22.194992 0.254589 4.605009 +22.200001 0.200000 4.600000 +21.900000 0.500000 3.800000 +21.900000 0.500000 4.900000 +21.961473 0.493634 3.800000 +21.954590 0.494992 4.845411 +22.019154 0.475323 3.800000 +22.010427 0.478936 4.789572 +22.069990 0.447191 3.800000 +22.064163 0.451099 4.735837 +22.112131 0.412132 3.800000 +22.089090 0.432906 4.710911 +22.112131 0.412132 4.687868 +22.147190 0.369990 3.800000 +22.132906 0.389089 4.667094 +22.175323 0.319153 3.800000 +22.151098 0.364163 4.648901 +22.193634 0.261473 3.800000 +22.178936 0.310428 4.621064 +22.200001 0.200000 3.800000 +22.200001 -0.200000 3.800000 +22.200001 -0.200000 4.600000 +21.900000 -0.500000 4.900000 +21.900000 -0.500000 3.800000 +21.954590 -0.494992 4.845411 +22.010427 -0.478936 4.789572 +21.961473 -0.493634 3.800000 +22.064163 -0.451099 4.735837 +22.019154 -0.475323 3.800000 +22.089090 -0.432906 4.710911 +22.069990 -0.447191 3.800000 +22.112131 -0.412132 4.687868 +22.132906 -0.389089 4.667094 +22.112131 -0.412132 3.800000 +22.151098 -0.364163 4.648901 +22.147190 -0.369990 3.800000 +22.178936 -0.310428 4.621064 +22.175323 -0.319153 3.800000 +22.194992 -0.254589 4.605009 +22.193634 -0.261473 3.800000 +20.500000 0.500000 5.800000 +20.500000 0.500000 3.800000 +20.206366 0.261473 3.800000 +20.200001 0.200000 3.800000 +20.200001 0.200000 5.800000 +20.206366 0.261473 5.800000 +20.224678 0.319153 3.800000 +20.224678 0.319153 5.800000 +20.252810 0.369990 3.800000 +20.252810 0.369990 5.800000 +20.287868 0.412132 3.800000 +20.287868 0.412132 5.800000 +20.330009 0.447191 3.800000 +20.380846 0.475323 3.800000 +20.330009 0.447191 5.800000 +20.438528 0.493634 3.800000 +20.380846 0.475323 5.800000 +20.438528 0.493634 5.800000 +20.500000 -0.500000 3.800000 +20.500000 -0.500000 5.800000 +20.206366 -0.261473 5.800000 +20.200001 -0.200000 5.800000 +20.200001 -0.200000 3.800000 +20.206366 -0.261473 3.800000 +20.224678 -0.319153 5.800000 +20.224678 -0.319153 3.800000 +20.252810 -0.369990 5.800000 +20.252810 -0.369990 3.800000 +20.287868 -0.412132 5.800000 +20.330009 -0.447191 5.800000 +20.287868 -0.412132 3.800000 +20.380846 -0.475323 5.800000 +20.330009 -0.447191 3.800000 +20.380846 -0.475323 3.800000 +20.438528 -0.493634 5.800000 +20.438528 -0.493634 3.800000 +35.183014 7.977242 5.800000 +34.933014 7.544229 5.800000 +34.483013 6.764806 4.900000 +34.483013 6.764806 3.800000 +35.183014 7.977242 3.800000 +35.073204 8.387049 3.800000 +34.726795 8.587049 3.800000 +34.726795 8.587049 5.800000 +35.073204 8.387049 5.800000 +33.616989 7.264806 4.900000 +34.066986 8.044229 5.800000 +34.316986 8.477242 3.800000 +33.616989 7.264806 3.800000 +34.316986 8.477242 5.800000 +34.073204 6.654998 3.800000 +34.073204 6.654998 4.600000 +33.726795 6.854998 4.600000 +33.726795 6.854998 3.800000 +34.390442 8.562344 5.800000 +34.348618 8.522013 5.800000 +34.066986 8.044229 5.800000 +34.933014 7.544229 5.800000 +34.316986 8.477242 5.800000 +35.183014 7.977242 5.800000 +35.205971 8.027020 5.800000 +35.219986 8.083406 5.800000 +35.222744 8.143861 5.800000 +35.212982 8.204887 5.800000 +35.190922 8.262618 5.800000 +35.158306 8.313593 5.800000 +35.117977 8.355417 5.800000 +35.073204 8.387049 5.800000 +34.726795 8.587049 5.800000 +34.677017 8.610006 5.800000 +34.620628 8.624022 5.800000 +34.560177 8.626781 5.800000 +34.499149 8.617019 5.800000 +34.441418 8.594960 5.800000 +34.316986 -8.477242 5.800000 +34.066986 -8.044229 5.800000 +33.616989 -7.264806 4.900000 +33.616989 -7.264806 3.800000 +34.316986 -8.477242 3.800000 +34.726795 -8.587049 5.800000 +34.726795 -8.587049 3.800000 +35.073204 -8.387049 3.800000 +35.073204 -8.387049 5.800000 +35.183014 -7.977242 3.800000 +34.483013 -6.764806 3.800000 +34.933014 -7.544229 5.800000 +35.183014 -7.977242 5.800000 +34.483013 -6.764806 4.900000 +33.726795 -6.854998 3.800000 +33.726795 -6.854998 4.600000 +34.073204 -6.654998 4.600000 +34.073204 -6.654998 3.800000 +35.219986 -8.083406 5.800000 +35.205971 -8.027020 5.800000 +35.183014 -7.977242 5.800000 +34.933014 -7.544229 5.800000 +34.066986 -8.044229 5.800000 +34.316986 -8.477242 5.800000 +34.348618 -8.522013 5.800000 +34.390442 -8.562344 5.800000 +34.441418 -8.594960 5.800000 +34.499149 -8.617019 5.800000 +34.560177 -8.626781 5.800000 +34.620628 -8.624022 5.800000 +34.677017 -8.610006 5.800000 +34.726795 -8.587049 5.800000 +35.073204 -8.387049 5.800000 +35.117977 -8.355417 5.800000 +35.158306 -8.313593 5.800000 +35.190922 -8.262618 5.800000 +35.212982 -8.204887 5.800000 +35.222744 -8.143861 5.800000 +34.073204 6.654998 4.600000 +34.122986 6.632041 4.605009 +34.483013 6.764806 4.900000 +34.933014 7.544229 5.800000 +34.066986 8.044229 5.800000 +34.409557 6.679704 4.789572 +33.616989 7.264806 4.900000 +33.587017 7.192451 4.822354 +33.576794 7.114806 4.750000 +33.586666 7.038483 4.688838 +33.616989 6.964806 4.640193 +33.665634 6.901708 4.609871 +33.695107 6.876082 4.602415 +33.726795 6.854998 4.600000 +34.358582 6.647087 4.735837 +34.300850 6.625028 4.687868 +34.239826 6.615266 4.648901 +34.179371 6.618025 4.621064 +33.726795 -6.854998 4.600000 +33.695107 -6.876082 4.602415 +34.066986 -8.044229 5.800000 +34.933014 -7.544229 5.800000 +33.616989 -7.264806 4.900000 +34.483013 -6.764806 4.900000 +34.409557 -6.679704 4.789572 +33.587017 -7.192451 4.822354 +34.300850 -6.625028 4.687868 +34.239826 -6.615266 4.648901 +34.179371 -6.618025 4.621064 +34.122986 -6.632041 4.605009 +34.073204 -6.654998 4.600000 +33.576794 -7.114806 4.750000 +33.586666 -7.038483 4.688838 +33.616989 -6.964806 4.640193 +33.665634 -6.901708 4.609871 +34.122986 6.632041 4.605009 +34.073204 6.654998 4.600000 +34.483013 6.764806 3.800000 +34.483013 6.764806 4.900000 +34.446762 6.714752 3.800000 +34.451382 6.720035 4.845411 +34.402065 6.673955 3.800000 +34.409557 6.679704 4.789572 +34.352283 6.643994 3.800000 +34.358582 6.647087 4.735837 +34.300850 6.625028 3.800000 +34.330364 6.634596 4.710911 +34.300850 6.625028 4.687868 +34.246826 6.615737 3.800000 +34.270508 6.618558 4.667094 +34.188732 6.616793 3.800000 +34.239826 6.615266 4.648901 +34.129623 6.629775 3.800000 +34.179371 6.618025 4.621064 +34.073204 6.654998 3.800000 +33.577660 7.137560 3.800000 +33.576794 7.114806 3.800000 +33.616989 7.264806 4.900000 +33.616989 7.264806 3.800000 +33.599697 7.229767 4.861010 +33.606358 7.244668 3.800000 +33.587017 7.192451 4.822354 +33.579338 7.153796 4.785039 +33.587017 7.192451 3.800000 +33.576794 7.114806 4.750000 +35.073204 8.387049 3.800000 +35.073204 8.387049 5.800000 +35.208237 8.033661 5.800000 +35.183014 7.977242 5.800000 +35.183014 7.977242 3.800000 +35.221218 8.092770 5.800000 +35.208237 8.033661 3.800000 +35.221218 8.092770 3.800000 +35.222275 8.150862 5.800000 +35.212982 8.204887 5.800000 +35.222275 8.150862 3.800000 +35.212982 8.204887 3.800000 +35.194016 8.256320 5.800000 +35.164055 8.306101 5.800000 +35.194016 8.256320 3.800000 +35.123260 8.350800 5.800000 +35.164055 8.306101 3.800000 +35.123260 8.350800 3.800000 +34.670376 8.612272 5.800000 +34.726795 8.587049 5.800000 +34.316986 8.477242 3.800000 +34.316986 8.477242 5.800000 +34.353237 8.527295 3.800000 +34.353237 8.527295 5.800000 +34.397934 8.568092 3.800000 +34.447716 8.598053 3.800000 +34.397934 8.568092 5.800000 +34.499149 8.617019 3.800000 +34.447716 8.598053 5.800000 +34.553173 8.626310 3.800000 +34.499149 8.617019 5.800000 +34.611267 8.625255 3.800000 +34.553173 8.626310 5.800000 +34.670376 8.612272 3.800000 +34.611267 8.625255 5.800000 +34.726795 8.587049 3.800000 +33.599300 -7.000798 4.662520 +33.726795 -6.854998 4.600000 +33.726795 -6.854998 3.800000 +33.695107 -6.876082 4.602415 +33.665634 -6.901708 4.609871 +33.690441 -6.879704 3.800000 +33.639317 -6.931494 4.622507 +33.648621 -6.920034 3.800000 +33.616989 -6.964806 4.640193 +33.576794 -7.114806 3.800000 +33.576794 -7.114806 4.750000 +33.580013 -7.070971 3.800000 +33.579208 -7.076820 4.718311 +33.594028 -7.014585 3.800000 +33.586666 -7.038483 4.688838 +33.616989 -6.964806 3.800000 +34.073204 -6.654998 3.800000 +34.073204 -6.654998 4.600000 +34.483013 -6.764806 4.900000 +34.483013 -6.764806 3.800000 +34.451382 -6.720035 4.845411 +34.409557 -6.679704 4.789572 +34.446762 -6.714752 3.800000 +34.358582 -6.647087 4.735837 +34.402065 -6.673955 3.800000 +34.330364 -6.634596 4.710911 +34.352283 -6.643994 3.800000 +34.300850 -6.625028 4.687868 +34.270508 -6.618558 4.667094 +34.300850 -6.625028 3.800000 +34.239826 -6.615266 4.648901 +34.246826 -6.615737 3.800000 +34.179371 -6.618025 4.621064 +34.188732 -6.616793 3.800000 +34.122986 -6.632041 4.605009 +34.129623 -6.629775 3.800000 +34.316986 -8.477242 5.800000 +34.316986 -8.477242 3.800000 +34.670376 -8.612272 3.800000 +34.726795 -8.587049 3.800000 +34.726795 -8.587049 5.800000 +34.670376 -8.612272 5.800000 +34.611267 -8.625255 3.800000 +34.553173 -8.626310 3.800000 +34.611267 -8.625255 5.800000 +34.499149 -8.617019 3.800000 +34.553173 -8.626310 5.800000 +34.499149 -8.617019 5.800000 +34.447716 -8.598053 3.800000 +34.447716 -8.598053 5.800000 +34.397934 -8.568092 3.800000 +34.397934 -8.568092 5.800000 +34.353237 -8.527295 3.800000 +34.353237 -8.527295 5.800000 +35.073204 -8.387049 5.800000 +35.073204 -8.387049 3.800000 +35.208237 -8.033661 3.800000 +35.183014 -7.977242 3.800000 +35.183014 -7.977242 5.800000 +35.208237 -8.033661 5.800000 +35.221218 -8.092770 3.800000 +35.222275 -8.150862 3.800000 +35.221218 -8.092770 5.800000 +35.222275 -8.150862 5.800000 +35.212982 -8.204887 3.800000 +35.212982 -8.204887 5.800000 +35.194016 -8.256320 3.800000 +35.164055 -8.306101 3.800000 +35.194016 -8.256320 5.800000 +35.164055 -8.306101 5.800000 +35.123260 -8.350800 3.800000 +35.123260 -8.350800 5.800000 +114.500000 0.500000 3.800000 +113.099998 0.500000 3.800000 +114.000000 0.500000 5.800000 +114.500000 0.500000 5.800000 +113.099998 0.500000 4.900000 +112.800003 -0.200000 3.800000 +112.800003 -0.200000 4.600000 +112.800003 0.200000 4.600000 +112.800003 0.200000 3.800000 +113.099998 -0.500000 4.900000 +113.099998 -0.500000 3.800000 +114.500000 -0.500000 3.800000 +114.500000 -0.500000 5.800000 +114.000000 -0.500000 5.800000 +114.800003 0.200000 5.800000 +114.800003 -0.200000 5.800000 +114.800003 -0.200000 3.800000 +114.800003 0.200000 3.800000 +114.610428 0.478936 5.800000 +114.554588 0.494992 5.800000 +114.000000 0.500000 5.800000 +114.000000 -0.500000 5.800000 +114.500000 0.500000 5.800000 +114.500000 -0.500000 5.800000 +114.554588 -0.494992 5.800000 +114.610428 -0.478936 5.800000 +114.664162 -0.451099 5.800000 +114.712135 -0.412132 5.800000 +114.751099 -0.364163 5.800000 +114.778938 -0.310428 5.800000 +114.794991 -0.254589 5.800000 +114.800003 -0.200000 5.800000 +114.800003 0.200000 5.800000 +114.794991 0.254589 5.800000 +114.778938 0.310428 5.800000 +114.751099 0.364163 5.800000 +114.712135 0.412132 5.800000 +114.664162 0.451099 5.800000 +99.816986 7.977242 3.800000 +100.516991 6.764806 3.800000 +100.066986 7.544229 5.800000 +99.816986 7.977242 5.800000 +100.516991 6.764806 4.900000 +100.926796 6.654998 3.800000 +101.273209 6.854998 3.800000 +101.273209 6.854998 4.600000 +100.926796 6.654998 4.600000 +100.683014 8.477242 5.800000 +100.933014 8.044229 5.800000 +101.383011 7.264806 4.900000 +101.383011 7.264806 3.800000 +100.683014 8.477242 3.800000 +99.926796 8.387049 5.800000 +100.273209 8.587049 5.800000 +100.273209 8.587049 3.800000 +99.926796 8.387049 3.800000 +100.379372 8.624022 5.800000 +100.322983 8.610006 5.800000 +100.066986 7.544229 5.800000 +100.933014 8.044229 5.800000 +99.816986 7.977242 5.800000 +99.787018 8.049596 5.800000 +99.776794 8.127241 5.800000 +99.786667 8.203564 5.800000 +99.816986 8.277242 5.800000 +99.865631 8.340340 5.800000 +99.926796 8.387049 5.800000 +100.273209 8.587049 5.800000 +100.683014 8.477242 5.800000 +100.651382 8.522013 5.800000 +100.609558 8.562344 5.800000 +100.558578 8.594960 5.800000 +100.500854 8.617019 5.800000 +100.439827 8.626781 5.800000 +100.683014 -8.477242 3.800000 +101.383011 -7.264806 3.800000 +100.933014 -8.044229 5.800000 +100.683014 -8.477242 5.800000 +101.383011 -7.264806 4.900000 +100.926796 -6.654998 3.800000 +100.926796 -6.654998 4.600000 +101.273209 -6.854998 4.600000 +101.273209 -6.854998 3.800000 +100.516991 -6.764806 4.900000 +100.516991 -6.764806 3.800000 +99.816986 -7.977242 3.800000 +99.816986 -7.977242 5.800000 +100.066986 -7.544229 5.800000 +99.926796 -8.387049 5.800000 +99.926796 -8.387049 3.800000 +100.273209 -8.587049 3.800000 +100.273209 -8.587049 5.800000 +100.609558 -8.562344 5.800000 +100.651382 -8.522013 5.800000 +100.933014 -8.044229 5.800000 +100.066986 -7.544229 5.800000 +100.683014 -8.477242 5.800000 +99.816986 -7.977242 5.800000 +99.787018 -8.049596 5.800000 +99.776794 -8.127241 5.800000 +99.786667 -8.203564 5.800000 +99.816986 -8.277242 5.800000 +99.865631 -8.340340 5.800000 +99.926796 -8.387049 5.800000 +100.273209 -8.587049 5.800000 +100.322983 -8.610006 5.800000 +100.379372 -8.624022 5.800000 +100.439827 -8.626781 5.800000 +100.500854 -8.617019 5.800000 +100.558578 -8.594960 5.800000 +112.800003 -0.200000 4.600000 +112.805008 -0.254589 4.605009 +114.000000 -0.500000 5.800000 +114.000000 0.500000 5.800000 +113.099998 -0.500000 4.900000 +113.099998 0.500000 4.900000 +112.989571 -0.478936 4.789572 +112.989571 0.478936 4.789572 +112.887871 0.412132 4.687868 +112.848900 0.364163 4.648901 +112.821060 0.310428 4.621064 +112.805008 0.254589 4.605009 +112.800003 0.200000 4.600000 +112.935837 -0.451099 4.735837 +112.887871 -0.412132 4.687868 +112.848900 -0.364163 4.648901 +112.821060 -0.310428 4.621064 +101.273209 6.854998 4.600000 +101.317978 6.886630 4.605009 +101.383011 7.264806 4.900000 +100.933014 8.044229 5.800000 +100.066986 7.544229 5.800000 +100.516991 6.764806 4.900000 +101.419983 7.158640 4.789572 +100.590446 6.679704 4.789572 +100.699150 6.625028 4.687868 +100.760178 6.615266 4.648901 +100.820633 6.618025 4.621064 +100.877014 6.632041 4.605009 +100.926796 6.654998 4.600000 +101.422745 7.098186 4.735837 +101.412979 7.037160 4.687868 +101.390923 6.979429 4.648901 +101.358307 6.928454 4.621064 +100.926796 -6.654998 4.600000 +100.877014 -6.632041 4.605009 +100.516991 -6.764806 4.900000 +100.066986 -7.544229 5.800000 +100.933014 -8.044229 5.800000 +101.383011 -7.264806 4.900000 +100.590446 -6.679704 4.789572 +101.419983 -7.158640 4.789572 +101.412979 -7.037160 4.687868 +101.390923 -6.979429 4.648901 +101.358307 -6.928454 4.621064 +101.317978 -6.886630 4.605009 +101.273209 -6.854998 4.600000 +100.641418 -6.647087 4.735837 +100.699150 -6.625028 4.687868 +100.760178 -6.615266 4.648901 +100.820633 -6.618025 4.621064 +112.800003 0.200000 3.800000 +112.800003 0.200000 4.600000 +113.099998 0.500000 4.900000 +113.099998 0.500000 3.800000 +113.045410 0.494992 4.845411 +112.989571 0.478936 4.789572 +113.045410 0.494992 3.800000 +112.935837 0.451099 4.735837 +112.989571 0.478936 3.800000 +112.910912 0.432906 4.710911 +112.935837 0.451099 3.800000 +112.887871 0.412132 4.687868 +112.867096 0.389089 4.667094 +112.887871 0.412132 3.800000 +112.848900 0.364163 4.648901 +112.848900 0.364163 3.800000 +112.821060 0.310428 4.621064 +112.821060 0.310428 3.800000 +112.805008 0.254589 4.605009 +112.805008 0.254589 3.800000 +112.910912 -0.432906 4.710911 +112.800003 -0.200000 4.600000 +112.800003 -0.200000 3.800000 +112.805008 -0.254589 4.605009 +112.821060 -0.310428 4.621064 +112.805008 -0.254589 3.800000 +112.848900 -0.364163 4.648901 +112.821060 -0.310428 3.800000 +112.867096 -0.389089 4.667094 +112.848900 -0.364163 3.800000 +112.887871 -0.412132 4.687868 +113.099998 -0.500000 3.800000 +113.099998 -0.500000 4.900000 +113.045410 -0.494992 3.800000 +113.045410 -0.494992 4.845411 +112.989571 -0.478936 3.800000 +112.989571 -0.478936 4.789572 +112.935837 -0.451099 3.800000 +112.935837 -0.451099 4.735837 +112.887871 -0.412132 3.800000 +114.800003 0.200000 5.800000 +114.800003 0.200000 3.800000 +114.554588 0.494992 3.800000 +114.500000 0.500000 3.800000 +114.500000 0.500000 5.800000 +114.554588 0.494992 5.800000 +114.610428 0.478936 3.800000 +114.664162 0.451099 3.800000 +114.610428 0.478936 5.800000 +114.664162 0.451099 5.800000 +114.712135 0.412132 3.800000 +114.712135 0.412132 5.800000 +114.751099 0.364163 3.800000 +114.751099 0.364163 5.800000 +114.778938 0.310428 3.800000 +114.778938 0.310428 5.800000 +114.794991 0.254589 3.800000 +114.794991 0.254589 5.800000 +114.500000 -0.500000 5.800000 +114.500000 -0.500000 3.800000 +114.800003 -0.200000 3.800000 +114.800003 -0.200000 5.800000 +114.794991 -0.254589 3.800000 +114.794991 -0.254589 5.800000 +114.778938 -0.310428 3.800000 +114.778938 -0.310428 5.800000 +114.751099 -0.364163 3.800000 +114.751099 -0.364163 5.800000 +114.712135 -0.412132 3.800000 +114.712135 -0.412132 5.800000 +114.664162 -0.451099 3.800000 +114.664162 -0.451099 5.800000 +114.610428 -0.478936 3.800000 +114.610428 -0.478936 5.800000 +114.554588 -0.494992 3.800000 +114.554588 -0.494992 5.800000 +100.926796 6.654998 3.800000 +100.926796 6.654998 4.600000 +100.548622 6.720035 4.845411 +100.516991 6.764806 4.900000 +100.516991 6.764806 3.800000 +100.590446 6.679704 4.789572 +100.548622 6.720035 3.800000 +100.641418 6.647087 4.735837 +100.590446 6.679704 3.800000 +100.669640 6.634596 4.710911 +100.641418 6.647087 3.800000 +100.699150 6.625028 4.687868 +100.729492 6.618558 4.667094 +100.699150 6.625028 3.800000 +100.760178 6.615266 4.648901 +100.760178 6.615266 3.800000 +100.820633 6.618025 4.621064 +100.820633 6.618025 3.800000 +100.877014 6.632041 4.605009 +100.877014 6.632041 3.800000 +101.317978 6.886630 4.605009 +101.273209 6.854998 4.600000 +101.383011 7.264806 3.800000 +101.383011 7.264806 4.900000 +101.405968 7.215026 3.800000 +101.405968 7.215026 4.845411 +101.419983 7.158640 3.800000 +101.419983 7.158640 4.789572 +101.422745 7.098186 3.800000 +101.422745 7.098186 4.735837 +101.412979 7.037160 3.800000 +101.419449 7.067502 4.710911 +101.412979 7.037160 4.687868 +101.390923 6.979429 3.800000 +101.403412 7.007648 4.667094 +101.358307 6.928454 3.800000 +101.390923 6.979429 4.648901 +101.317978 6.886630 3.800000 +101.358307 6.928454 4.621064 +101.273209 6.854998 3.800000 +99.851128 8.324914 5.800000 +99.893013 8.364360 5.800000 +99.926796 8.387049 5.800000 +99.926796 8.387049 3.800000 +99.776794 8.127241 3.800000 +99.776794 8.127241 5.800000 +99.779556 8.167839 3.800000 +99.779556 8.167839 5.800000 +99.792770 8.223838 3.800000 +99.816986 8.277242 3.800000 +99.792770 8.223838 5.800000 +99.816986 8.277242 5.800000 +99.851128 8.324914 3.800000 +99.893013 8.364360 3.800000 +100.651382 8.522013 5.800000 +100.683014 8.477242 5.800000 +100.322983 8.610006 3.800000 +100.273209 8.587049 3.800000 +100.273209 8.587049 5.800000 +100.322983 8.610006 5.800000 +100.379372 8.624022 3.800000 +100.379372 8.624022 5.800000 +100.439827 8.626781 3.800000 +100.439827 8.626781 5.800000 +100.500854 8.617019 3.800000 +100.500854 8.617019 5.800000 +100.558578 8.594960 3.800000 +100.609558 8.562344 3.800000 +100.558578 8.594960 5.800000 +100.609558 8.562344 5.800000 +100.651382 8.522013 3.800000 +100.683014 8.477242 3.800000 +101.273209 -6.854998 3.800000 +101.273209 -6.854998 4.600000 +101.383011 -7.264806 4.900000 +101.383011 -7.264806 3.800000 +101.405968 -7.215026 4.845411 +101.419983 -7.158640 4.789572 +101.405968 -7.215026 3.800000 +101.422745 -7.098186 4.735837 +101.419983 -7.158640 3.800000 +101.419449 -7.067502 4.710911 +101.422745 -7.098186 3.800000 +101.412979 -7.037160 4.687868 +101.403412 -7.007648 4.667094 +101.412979 -7.037160 3.800000 +101.390923 -6.979429 4.648901 +101.390923 -6.979429 3.800000 +101.358307 -6.928454 4.621064 +101.358307 -6.928454 3.800000 +101.317978 -6.886630 4.605009 +101.317978 -6.886630 3.800000 +100.669640 -6.634596 4.710911 +100.926796 -6.654998 4.600000 +100.926796 -6.654998 3.800000 +100.877014 -6.632041 4.605009 +100.820633 -6.618025 4.621064 +100.877014 -6.632041 3.800000 +100.760178 -6.615266 4.648901 +100.820633 -6.618025 3.800000 +100.729492 -6.618558 4.667094 +100.760178 -6.615266 3.800000 +100.699150 -6.625028 4.687868 +100.516991 -6.764806 3.800000 +100.516991 -6.764806 4.900000 +100.548622 -6.720035 3.800000 +100.548622 -6.720035 4.845411 +100.590446 -6.679704 3.800000 +100.590446 -6.679704 4.789572 +100.641418 -6.647087 3.800000 +100.641418 -6.647087 4.735837 +100.699150 -6.625028 3.800000 +100.273209 -8.587049 5.800000 +100.273209 -8.587049 3.800000 +100.651382 -8.522013 3.800000 +100.683014 -8.477242 3.800000 +100.683014 -8.477242 5.800000 +100.651382 -8.522013 5.800000 +100.609558 -8.562344 3.800000 +100.609558 -8.562344 5.800000 +100.558578 -8.594960 3.800000 +100.558578 -8.594960 5.800000 +100.500854 -8.617019 3.800000 +100.500854 -8.617019 5.800000 +100.439827 -8.626781 3.800000 +100.439827 -8.626781 5.800000 +100.379372 -8.624022 3.800000 +100.379372 -8.624022 5.800000 +100.322983 -8.610006 3.800000 +100.322983 -8.610006 5.800000 +99.806358 -7.997379 3.800000 +99.816986 -7.977242 5.800000 +99.816986 -7.977242 3.800000 +99.806358 -7.997379 5.800000 +99.777657 -8.104487 3.800000 +99.776794 -8.127241 3.800000 +99.776794 -8.127241 5.800000 +99.787018 -8.049596 3.800000 +99.777657 -8.104487 5.800000 +99.787018 -8.049596 5.800000 +-7.964773 -1.331398 7.300000 +-8.165813 -0.734931 7.300000 +-8.225290 -0.400000 7.300000 +-8.252169 -0.430544 3.800000 +-1.722378 -0.138438 3.800000 +-1.751784 -0.107668 7.300000 +-1.750580 -0.450822 3.800000 +-1.780835 -0.446625 7.300000 +-1.898423 -1.068733 3.800000 +-1.927301 -1.058782 7.300000 +-2.176019 -1.669461 3.800000 +-2.202312 -1.653917 7.300000 +-2.578030 -2.212697 3.800000 +-2.600580 -2.192095 7.300000 +-3.082824 -2.662030 3.800000 +-3.100674 -2.637245 7.300000 +-3.656090 -2.992637 3.800000 +-4.258162 -3.195566 3.800000 +-3.668602 -2.964773 7.300000 +-4.265069 -3.165814 7.300000 +-4.852021 -3.277205 3.800000 +-4.853399 -3.246692 7.300000 +-5.450822 -3.249420 3.800000 +-6.068733 -3.101577 3.800000 +-5.446625 -3.219166 7.300000 +-6.058783 -3.072699 7.300000 +-6.669461 -2.823981 3.800000 +-6.653917 -2.797688 7.300000 +-7.212697 -2.421970 3.800000 +-7.192095 -2.399420 7.300000 +-7.662030 -1.917176 3.800000 +-7.637245 -1.899326 7.300000 +-7.992637 -1.343911 3.800000 +-8.195566 -0.741838 3.800000 +-1.804883 0.743770 3.800000 +-8.252169 0.430544 3.800000 +-8.225290 0.400000 7.300000 +-1.834631 0.736845 7.300000 +-1.824725 0.692912 7.300000 +-1.800180 0.723270 3.800000 +-8.249692 0.448858 3.800000 +-8.219435 0.444679 7.300000 +-8.102222 1.066858 3.800000 +-8.073339 1.056925 7.300000 +-7.824989 1.667754 3.800000 +-7.798687 1.652226 7.300000 +-7.423307 2.211233 3.800000 +-6.918785 2.660871 3.800000 +-7.400745 2.190645 7.300000 +-6.900919 2.636097 7.300000 +-6.345719 2.991824 3.800000 +-6.333189 2.963968 7.300000 +-5.743770 3.195117 3.800000 +-5.149960 3.277115 3.800000 +-5.736845 3.165369 7.300000 +-5.148563 3.246603 7.300000 +-4.551142 3.249692 3.800000 +-3.933142 3.102222 3.800000 +-4.555321 3.219435 7.300000 +-3.943075 3.073339 7.300000 +-3.332246 2.824990 3.800000 +-3.347774 2.798687 7.300000 +-2.788767 2.423307 3.800000 +-2.809355 2.400745 7.300000 +-2.339129 1.918784 3.800000 +-2.008176 1.345719 3.800000 +-2.363903 1.900919 7.300000 +-2.036032 1.333189 7.300000 +-3.992112 0.186512 7.300000 +-2.289157 -1.792715 7.300000 +-4.046967 -0.377297 7.300000 +-1.997538 -1.244075 7.300000 +-3.992112 -0.186512 7.300000 +-1.820215 -0.671911 7.300000 +-3.975000 0.000000 7.300000 +-2.688164 -2.284276 7.300000 +-4.142080 -0.560890 7.300000 +-3.174904 -2.689149 7.300000 +-4.275216 -0.724784 7.300000 +-3.720007 -2.987326 7.300000 +-4.439110 -0.857920 7.300000 +-4.290003 -3.171499 7.300000 +-4.622703 -0.953033 7.300000 +-4.853385 -3.246691 7.300000 +-4.813488 -1.007888 7.300000 +-5.421252 -3.222584 7.300000 +-5.000000 -1.025000 7.300000 +-6.005527 -3.090536 7.300000 +-5.186512 -1.007888 7.300000 +-6.575288 -2.842705 7.300000 +12.800000 0.000000 7.300000 +12.045056 0.841074 7.300000 +12.718694 0.924787 7.300000 +11.797688 1.701416 7.300000 +12.459718 1.868474 7.300000 +11.368779 2.529325 7.300000 +12.012488 2.779830 7.300000 +10.768405 3.268405 7.300000 +11.386516 3.603471 7.300000 +10.029325 3.868780 7.300000 +10.612467 4.289820 7.300000 +9.201416 4.297688 7.300000 +9.737464 4.804556 7.300000 +8.341074 4.545056 7.300000 +8.816013 5.134015 7.300000 +7.500000 4.622223 7.300000 +-5.377297 -0.953033 7.300000 +-7.096539 -2.483350 7.300000 +-5.560890 -0.857920 7.300000 +-7.538228 -2.029754 7.300000 +12.720471 -0.914699 7.300000 +12.122223 0.000000 7.300000 +12.467550 -1.847552 7.300000 +12.045056 -0.841074 7.300000 +12.031198 -2.749227 7.300000 +11.797688 -1.701416 7.300000 +11.420459 -3.566511 7.300000 +11.368779 -2.529325 7.300000 +10.664437 -4.251627 7.300000 +10.768405 -3.268405 7.300000 +9.807949 -4.771098 7.300000 +10.029325 -3.868780 7.300000 +8.903117 -5.110897 7.300000 +9.201416 -4.297688 7.300000 +8.000000 -5.276362 7.300000 +8.341074 -4.545056 7.300000 +-5.724784 -0.724784 7.300000 +-7.878109 -1.509631 7.300000 +-5.857920 -0.560890 7.300000 +-8.106282 -0.955779 7.300000 +-8.225290 -0.400000 7.300000 +-5.953033 -0.377297 7.300000 +7.000000 -11.400000 7.300000 +8.000000 -11.400000 7.300000 +7.000000 -5.276362 7.300000 +7.500000 -4.622223 7.300000 +6.110551 -5.114629 7.300000 +6.658926 -4.545056 7.300000 +5.219826 -4.784434 7.300000 +5.798584 -4.297688 7.300000 +4.375292 -4.280911 7.300000 +4.970675 -3.868780 7.300000 +3.626263 -3.617203 7.300000 +4.231595 -3.268405 7.300000 +3.015352 -2.824524 7.300000 +3.631220 -2.529325 7.300000 +2.570785 -1.947522 7.300000 +2.302299 -1.036294 7.300000 +3.202312 -1.701416 7.300000 +2.201793 -0.137865 7.300000 +2.954944 -0.841074 7.300000 +-11.392981 0.400000 7.300000 +-11.392981 -0.400000 7.300000 +-8.225290 0.400000 7.300000 +-6.007888 -0.186512 7.300000 +-7.908245 1.450728 7.300000 +-6.025000 0.000000 7.300000 +-6.007888 0.186512 7.300000 +-7.602960 1.946048 7.300000 +-5.953033 0.377297 7.300000 +-7.207154 2.385576 7.300000 +-5.857920 0.560890 7.300000 +-6.738245 2.746089 7.300000 +-5.724784 0.724784 7.300000 +-6.220734 3.012027 7.300000 +-5.560890 0.857920 7.300000 +-5.148576 3.246602 7.300000 +-5.377297 0.953033 7.300000 +-5.186512 1.007888 7.300000 +-4.059474 3.110934 7.300000 +-5.000000 1.025000 7.300000 +-4.813488 1.007888 7.300000 +-3.519837 2.893375 7.300000 +-4.622703 0.953033 7.300000 +-3.019960 2.577196 7.300000 +-2.585664 2.175657 7.300000 +-4.439110 0.857920 7.300000 +-2.236415 1.710291 7.300000 +-4.275216 0.724784 7.300000 +-1.824725 0.692912 7.300000 +-4.142080 0.560890 7.300000 +-4.046967 0.377297 7.300000 +7.900000 5.284884 7.300000 +7.900000 11.400000 7.300000 +7.100000 11.400000 7.300000 +6.658926 4.545056 7.300000 +7.100000 5.284884 7.300000 +5.798584 4.297688 7.300000 +4.970675 3.868780 7.300000 +5.398512 4.865568 7.300000 +4.583273 4.425235 7.300000 +4.231595 3.268405 7.300000 +3.846538 3.839559 7.300000 +3.631220 2.529325 7.300000 +3.225011 3.132806 7.300000 +3.202312 1.701416 7.300000 +2.744752 2.340430 7.300000 +2.954944 0.841074 7.300000 +2.877777 0.000000 7.300000 +2.241488 0.661855 7.300000 +-1.751784 -0.107668 7.300000 +-11.091494 0.434471 3.350000 +-9.988190 0.431545 3.685352 +-11.091493 0.434508 3.345793 +-11.392981 0.400000 7.300000 +-8.225290 0.400000 7.300000 +-8.252169 0.430544 3.800000 +-8.839521 0.430544 3.800000 +-11.391718 0.434471 3.350000 +-8.839521 -0.430544 3.800000 +-8.252169 -0.430544 3.800000 +-11.091494 -0.434471 3.350000 +-11.091493 -0.434508 3.345793 +-8.225290 -0.400000 7.300000 +-11.392981 -0.400000 7.300000 +-11.391718 -0.434471 3.350000 +-9.990095 -0.431548 3.684967 +-6.025000 0.000000 3.300000 +-5.000000 0.000000 2.684118 +-3.975000 0.000000 3.300000 +-3.992112 0.186512 3.300000 +-4.046967 0.377297 3.300000 +-4.142080 0.560890 3.300000 +-4.275216 0.724784 3.300000 +-4.439110 0.857920 3.300000 +-4.622703 0.953033 3.300000 +-4.813488 1.007888 3.300000 +-5.000000 1.025000 3.300000 +-5.186512 1.007888 3.300000 +-5.377297 0.953033 3.300000 +-5.560890 0.857920 3.300000 +-5.724784 0.724784 3.300000 +-5.857920 0.560890 3.300000 +-5.953033 0.377297 3.300000 +-6.007888 0.186512 3.300000 +-5.000000 0.000000 2.684118 +-5.000000 0.000000 2.684118 +-5.000000 0.000000 2.684118 +-5.000000 0.000000 2.684118 +-5.000000 0.000000 2.684118 +-5.000000 0.000000 2.684118 +-5.000000 0.000000 2.684118 +-5.000000 0.000000 2.684118 +-5.000000 0.000000 2.684118 +-5.000000 0.000000 2.684118 +-5.000000 0.000000 2.684118 +-5.000000 0.000000 2.684118 +-5.000000 0.000000 2.684118 +-5.000000 0.000000 2.684118 +-5.000000 0.000000 2.684118 +-5.000000 0.000000 2.684118 +-6.025000 0.000000 7.300000 +-6.025000 0.000000 3.300000 +-3.992112 0.186512 3.300000 +-3.975000 0.000000 3.300000 +-3.975000 0.000000 7.300000 +-4.046967 0.377297 3.300000 +-3.992112 0.186512 7.300000 +-4.142080 0.560890 3.300000 +-4.046967 0.377297 7.300000 +-4.142080 0.560890 7.300000 +-4.275216 0.724784 3.300000 +-4.275216 0.724784 7.300000 +-4.439110 0.857920 3.300000 +-4.439110 0.857920 7.300000 +-4.622703 0.953033 3.300000 +-4.813488 1.007888 3.300000 +-4.622703 0.953033 7.300000 +-5.000000 1.025000 3.300000 +-4.813488 1.007888 7.300000 +-5.186512 1.007888 3.300000 +-5.000000 1.025000 7.300000 +-5.186512 1.007888 7.300000 +-5.377297 0.953033 3.300000 +-5.377297 0.953033 7.300000 +-5.560890 0.857920 3.300000 +-5.560890 0.857920 7.300000 +-5.724784 0.724784 3.300000 +-5.724784 0.724784 7.300000 +-5.857920 0.560890 3.300000 +-5.857920 0.560890 7.300000 +-5.953033 0.377297 3.300000 +-5.953033 0.377297 7.300000 +-6.007888 0.186512 3.300000 +-6.007888 0.186512 7.300000 +10.724623 -4.244586 3.800000 +8.829911 -5.130432 7.300000 +8.000000 -5.276362 7.300000 +8.030544 -5.304076 3.800000 +8.837576 -5.159999 3.800000 +9.832508 -4.759139 7.300000 +9.845950 -4.786566 3.800000 +10.706146 -4.220264 7.300000 +12.763217 -0.844542 3.800000 +12.830544 0.000000 3.800000 +12.800000 0.000000 7.300000 +12.733058 -0.839703 7.300000 +12.486633 -1.883663 3.800000 +12.458060 -1.872870 7.300000 +12.030012 -2.809572 3.800000 +12.004055 -2.793473 7.300000 +11.443138 -3.586971 3.800000 +11.420552 -3.566408 7.300000 +12.000000 0.000000 3.800000 +12.122223 0.000000 7.300000 +2.954944 0.841074 7.300000 +2.877777 0.000000 7.300000 +3.000000 0.000000 3.800000 +3.075126 0.818834 3.800000 +3.202312 1.701416 7.300000 +3.315953 1.656426 3.800000 +3.631220 2.529325 7.300000 +3.733520 2.462444 3.800000 +4.231595 3.268405 7.300000 +4.318019 3.181981 3.800000 +4.970675 3.868780 7.300000 +5.037556 3.766480 3.800000 +5.798584 4.297688 7.300000 +5.843574 4.184047 3.800000 +6.658926 4.545056 7.300000 +6.681166 4.424874 3.800000 +7.500000 4.622223 7.300000 +7.500000 4.500000 3.800000 +8.341074 4.545056 7.300000 +8.318833 4.424874 3.800000 +9.201416 4.297688 7.300000 +9.156426 4.184047 3.800000 +10.029325 3.868780 7.300000 +9.962444 3.766480 3.800000 +10.768405 3.268405 7.300000 +10.681980 3.181981 3.800000 +11.368779 2.529325 7.300000 +11.266479 2.462444 3.800000 +11.797688 1.701416 7.300000 +11.684048 1.656426 3.800000 +12.045056 0.841074 7.300000 +11.924874 0.818834 3.800000 +7.065529 11.400000 3.350000 +7.065529 11.100000 3.350000 +7.065492 11.100000 3.345793 +7.069456 5.313128 3.800000 +7.100000 5.284884 7.300000 +7.069456 8.850000 3.800000 +7.068455 9.997694 3.685314 +7.100000 11.400000 7.300000 +7.934471 11.100000 3.350000 +7.931545 9.997694 3.685314 +7.934508 11.100000 3.345793 +7.900000 11.400000 7.300000 +7.900000 5.284884 7.300000 +7.930544 5.313128 3.800000 +7.930544 8.850000 3.800000 +7.934471 11.400000 3.350000 +6.965529 -11.100000 3.350000 +6.968455 -9.997694 3.685314 +6.965492 -11.100000 3.345793 +7.000000 -11.400000 7.300000 +7.000000 -5.276362 7.300000 +6.969456 -5.304076 3.800000 +6.969456 -8.850000 3.800000 +6.965529 -11.400000 3.350000 +8.034472 -11.400000 3.350000 +8.034472 -11.100000 3.350000 +8.034508 -11.100000 3.345793 +8.030544 -5.304076 3.800000 +8.000000 -5.276362 7.300000 +8.030544 -8.850000 3.800000 +8.031545 -9.997694 3.685314 +8.000000 -11.400000 7.300000 +137.008179 1.345719 3.800000 +143.219437 0.444679 7.300000 +143.225296 0.400000 7.300000 +136.800186 0.723270 3.800000 +136.824722 0.692912 7.300000 +136.804886 0.743770 3.800000 +143.252167 0.430544 3.800000 +143.249695 0.448858 3.800000 +143.073334 1.056925 7.300000 +142.798691 1.652226 7.300000 +143.102219 1.066858 3.800000 +142.824997 1.667754 3.800000 +142.400742 2.190645 7.300000 +142.423309 2.211233 3.800000 +141.900925 2.636097 7.300000 +141.918777 2.660871 3.800000 +141.333191 2.963968 7.300000 +140.736847 3.165369 7.300000 +141.345718 2.991824 3.800000 +140.743774 3.195117 3.800000 +140.148560 3.246603 7.300000 +139.555328 3.219435 7.300000 +140.149963 3.277115 3.800000 +139.551147 3.249692 3.800000 +138.943069 3.073339 7.300000 +138.933136 3.102222 3.800000 +138.347778 2.798687 7.300000 +138.332245 2.824990 3.800000 +137.809357 2.400745 7.300000 +137.788773 2.423307 3.800000 +137.363907 1.900919 7.300000 +137.036026 1.333189 7.300000 +137.339127 1.918784 3.800000 +136.834625 0.736845 7.300000 +136.927307 -1.058782 7.300000 +143.252167 -0.430544 3.800000 +143.225296 -0.400000 7.300000 +143.195572 -0.741838 3.800000 +136.780838 -0.446625 7.300000 +136.751785 -0.107668 7.300000 +136.722382 -0.138438 3.800000 +142.992630 -1.343911 3.800000 +143.165817 -0.734931 7.300000 +142.964767 -1.331398 7.300000 +142.662033 -1.917176 3.800000 +142.637238 -1.899326 7.300000 +142.212692 -2.421970 3.800000 +141.669464 -2.823981 3.800000 +142.192093 -2.399420 7.300000 +141.653915 -2.797688 7.300000 +141.068726 -3.101577 3.800000 +140.450821 -3.249420 3.800000 +141.058777 -3.072699 7.300000 +140.446625 -3.219166 7.300000 +139.852020 -3.277205 3.800000 +139.853394 -3.246692 7.300000 +139.258163 -3.195566 3.800000 +138.656082 -2.992637 3.800000 +139.265076 -3.165814 7.300000 +138.668610 -2.964773 7.300000 +138.082825 -2.662030 3.800000 +138.100677 -2.637245 7.300000 +137.578033 -2.212697 3.800000 +137.600586 -2.192095 7.300000 +137.176025 -1.669461 3.800000 +137.202316 -1.653917 7.300000 +136.898422 -1.068733 3.800000 +136.750580 -0.450822 3.800000 +136.722382 -0.138438 3.800000 +136.751785 -0.107668 7.300000 +132.798203 -0.137865 7.300000 +132.827896 -0.168183 3.800000 +136.824722 0.692912 7.300000 +136.800186 0.723270 3.800000 +132.785355 0.692605 3.800000 +132.758514 0.661855 7.300000 +146.392975 -0.400000 7.300000 +146.399994 0.000000 7.300000 +131.984650 -2.824524 7.300000 +131.797684 -1.701416 7.300000 +131.373734 -3.617203 7.300000 +131.368774 -2.529325 7.300000 +130.624710 -4.280911 7.300000 +130.768402 -3.268405 7.300000 +129.780167 -4.784434 7.300000 +130.029327 -3.868780 7.300000 +128.889450 -5.114629 7.300000 +129.201416 -4.297688 7.300000 +128.000000 -5.276362 7.300000 +128.341080 -4.545056 7.300000 +137.289154 -1.792715 7.300000 +139.275223 -0.724784 7.300000 +137.688171 -2.284276 7.300000 +139.439117 -0.857920 7.300000 +138.174896 -2.689149 7.300000 +139.622696 -0.953033 7.300000 +138.720001 -2.987326 7.300000 +139.813492 -1.007888 7.300000 +139.290009 -3.171499 7.300000 +140.000000 -1.025000 7.300000 +139.853378 -3.246691 7.300000 +140.186508 -1.007888 7.300000 +140.421249 -3.222584 7.300000 +140.377304 -0.953033 7.300000 +141.005524 -3.090536 7.300000 +136.997543 -1.244075 7.300000 +139.142075 -0.560890 7.300000 +136.820221 -0.671911 7.300000 +139.046967 -0.377297 7.300000 +136.751785 -0.107668 7.300000 +138.992111 -0.186512 7.300000 +140.560883 -0.857920 7.300000 +141.575287 -2.842705 7.300000 +140.724777 -0.724784 7.300000 +142.096542 -2.483350 7.300000 +132.429214 -1.947522 7.300000 +132.045059 -0.841074 7.300000 +132.697708 -1.036294 7.300000 +132.122223 0.000000 7.300000 +140.857925 -0.560890 7.300000 +142.538223 -2.029754 7.300000 +142.878113 -1.509631 7.300000 +140.953033 -0.377297 7.300000 +143.106277 -0.955779 7.300000 +141.007889 -0.186512 7.300000 +127.000000 -5.276362 7.300000 +127.000000 -11.400000 7.300000 +128.000000 -11.400000 7.300000 +127.500000 -4.622223 7.300000 +126.091934 -5.109536 7.300000 +126.658928 -4.545056 7.300000 +125.181992 -4.766219 7.300000 +125.798584 -4.297688 7.300000 +124.321190 -4.240891 7.300000 +124.970673 -3.868780 7.300000 +123.562698 -3.547911 7.300000 +124.231598 -3.268405 7.300000 +122.952164 -2.721612 7.300000 +123.631218 -2.529325 7.300000 +122.518990 -1.810946 7.300000 +123.202309 -1.701416 7.300000 +122.271942 -0.870290 7.300000 +122.954941 -0.841074 7.300000 +122.289360 0.969130 7.300000 +122.877777 0.000000 7.300000 +122.554176 1.904939 7.300000 +122.954941 0.841074 7.300000 +123.004509 2.807239 7.300000 +123.202309 1.701416 7.300000 +123.630585 3.621830 7.300000 +123.631218 2.529325 7.300000 +124.402061 4.300323 7.300000 +124.231598 3.268405 7.300000 +125.272659 4.809257 7.300000 +124.970673 3.868780 7.300000 +126.188942 5.135283 7.300000 +125.798584 4.297688 7.300000 +127.099998 5.284884 7.300000 +126.658928 4.545056 7.300000 +127.900002 5.284884 7.300000 +127.900002 11.400000 7.300000 +127.099998 11.400000 7.300000 +127.500000 4.622223 7.300000 +129.601486 4.865568 7.300000 +128.341080 4.545056 7.300000 +129.201416 4.297688 7.300000 +130.416733 4.425235 7.300000 +131.153458 3.839559 7.300000 +130.029327 3.868780 7.300000 +131.774994 3.132806 7.300000 +130.768402 3.268405 7.300000 +132.255249 2.340430 7.300000 +131.368774 2.529325 7.300000 +132.758514 0.661855 7.300000 +131.797684 1.701416 7.300000 +132.045059 0.841074 7.300000 +136.824722 0.692912 7.300000 +132.798203 -0.137865 7.300000 +138.975006 0.000000 7.300000 +137.236420 1.710291 7.300000 +138.992111 0.186512 7.300000 +139.046967 0.377297 7.300000 +137.585663 2.175657 7.300000 +139.142075 0.560890 7.300000 +138.019958 2.577196 7.300000 +139.275223 0.724784 7.300000 +138.519836 2.893375 7.300000 +139.439117 0.857920 7.300000 +139.059479 3.110934 7.300000 +140.148575 3.246602 7.300000 +139.622696 0.953033 7.300000 +139.813492 1.007888 7.300000 +141.220734 3.012027 7.300000 +140.000000 1.025000 7.300000 +140.186508 1.007888 7.300000 +141.738251 2.746089 7.300000 +140.377304 0.953033 7.300000 +142.207153 2.385576 7.300000 +140.560883 0.857920 7.300000 +142.602966 1.946048 7.300000 +140.724777 0.724784 7.300000 +142.908249 1.450728 7.300000 +143.225296 0.400000 7.300000 +140.857925 0.560890 7.300000 +140.953033 0.377297 7.300000 +141.007889 0.186512 7.300000 +141.024994 0.000000 7.300000 +143.225296 -0.400000 7.300000 +146.392975 0.400000 7.300000 +143.839523 0.430544 3.800000 +143.252167 0.430544 3.800000 +146.091492 0.434508 3.345793 +146.091492 0.434508 3.345793 +143.225296 0.400000 7.300000 +146.392975 0.400000 7.300000 +146.391724 0.434471 3.350000 +144.987808 0.431544 3.685430 +143.225296 -0.400000 7.300000 +143.252167 -0.430544 3.800000 +146.391724 -0.434471 3.350000 +146.392975 -0.400000 7.300000 +146.091492 -0.434508 3.345793 +144.988190 -0.431545 3.685352 +143.839523 -0.430544 3.800000 +138.975006 0.000000 3.300000 +140.000000 0.000000 2.684118 +141.024994 0.000000 3.300000 +141.007889 0.186512 3.300000 +140.953033 0.377297 3.300000 +140.857925 0.560890 3.300000 +140.724777 0.724784 3.300000 +140.560883 0.857920 3.300000 +140.377304 0.953033 3.300000 +140.186508 1.007888 3.300000 +140.000000 1.025000 3.300000 +139.813492 1.007888 3.300000 +139.622696 0.953033 3.300000 +139.439117 0.857920 3.300000 +139.275223 0.724784 3.300000 +139.142075 0.560890 3.300000 +139.046967 0.377297 3.300000 +138.992111 0.186512 3.300000 +140.000000 0.000000 2.684118 +140.000000 0.000000 2.684118 +140.000000 0.000000 2.684118 +140.000000 0.000000 2.684118 +140.000000 0.000000 2.684118 +140.000000 0.000000 2.684118 +140.000000 0.000000 2.684118 +140.000000 0.000000 2.684118 +140.000000 0.000000 2.684118 +140.000000 0.000000 2.684118 +140.000000 0.000000 2.684118 +140.000000 0.000000 2.684118 +140.000000 0.000000 2.684118 +140.000000 0.000000 2.684118 +140.000000 0.000000 2.684118 +140.000000 0.000000 2.684118 +138.975006 0.000000 7.300000 +138.975006 0.000000 3.300000 +141.007889 0.186512 3.300000 +141.024994 0.000000 3.300000 +141.024994 0.000000 7.300000 +141.007889 0.186512 7.300000 +140.953033 0.377297 3.300000 +140.857925 0.560890 3.300000 +140.953033 0.377297 7.300000 +140.857925 0.560890 7.300000 +140.724777 0.724784 3.300000 +140.560883 0.857920 3.300000 +140.724777 0.724784 7.300000 +140.377304 0.953033 3.300000 +140.560883 0.857920 7.300000 +140.377304 0.953033 7.300000 +140.186508 1.007888 3.300000 +140.186508 1.007888 7.300000 +140.000000 1.025000 3.300000 +140.000000 1.025000 7.300000 +139.813492 1.007888 3.300000 +139.813492 1.007888 7.300000 +139.622696 0.953033 3.300000 +139.622696 0.953033 7.300000 +139.439117 0.857920 3.300000 +139.439117 0.857920 7.300000 +139.275223 0.724784 3.300000 +139.275223 0.724784 7.300000 +139.142075 0.560890 3.300000 +139.142075 0.560890 7.300000 +139.046967 0.377297 3.300000 +139.046967 0.377297 7.300000 +138.992111 0.186512 3.300000 +138.992111 0.186512 7.300000 +131.368774 2.529325 7.300000 +131.924881 0.818834 3.800000 +132.000000 0.000000 3.800000 +132.122223 0.000000 7.300000 +131.684052 1.656426 3.800000 +132.045059 0.841074 7.300000 +131.797684 1.701416 7.300000 +131.266479 2.462444 3.800000 +122.877777 0.000000 7.300000 +123.000000 0.000000 3.800000 +122.954941 0.841074 7.300000 +123.075127 0.818834 3.800000 +123.202309 1.701416 7.300000 +123.315956 1.656426 3.800000 +123.631218 2.529325 7.300000 +123.733521 2.462444 3.800000 +124.231598 3.268405 7.300000 +124.318016 3.181981 3.800000 +124.970673 3.868780 7.300000 +125.037560 3.766480 3.800000 +125.798584 4.297688 7.300000 +125.843575 4.184047 3.800000 +126.658928 4.545056 7.300000 +126.681168 4.424874 3.800000 +127.500000 4.622223 7.300000 +127.500000 4.500000 3.800000 +128.341080 4.545056 7.300000 +129.201416 4.297688 7.300000 +128.318832 4.424874 3.800000 +129.156433 4.184047 3.800000 +130.029327 3.868780 7.300000 +130.768402 3.268405 7.300000 +129.962448 3.766480 3.800000 +130.681976 3.181981 3.800000 +127.958290 0.991318 3.800000 +131.266479 2.462444 3.800000 +128.549545 1.049553 3.800000 +131.684052 1.656426 3.800000 +128.723007 0.841051 3.800000 +130.681976 3.181981 3.800000 +128.461182 1.115543 3.800000 +131.924881 0.818834 3.800000 +128.862198 0.589527 3.800000 +132.000000 0.000000 3.800000 +128.952789 0.304145 3.800000 +131.924881 -0.818834 3.800000 +128.984299 0.000000 3.800000 +131.684052 -1.656426 3.800000 +128.952789 -0.304145 3.800000 +131.266479 -2.462444 3.800000 +128.862198 -0.589527 3.800000 +130.681976 -3.181981 3.800000 +128.723007 -0.841051 3.800000 +129.962448 -3.766480 3.800000 +128.549545 -1.049553 3.800000 +129.962448 3.766480 3.800000 +128.352783 1.154725 3.800000 +129.156433 -4.184047 3.800000 +128.495575 -1.094462 3.800000 +128.430450 -1.130498 3.800000 +128.318832 -4.424874 3.800000 +128.356567 -1.153955 3.800000 +129.156433 4.184047 3.800000 +128.237656 1.160005 3.800000 +128.318832 4.424874 3.800000 +128.130753 1.132857 3.800000 +127.500000 -4.500000 3.800000 +128.277817 -1.162109 3.800000 +128.199066 -1.153955 3.800000 +126.681168 -4.424874 3.800000 +128.125183 -1.130498 3.800000 +127.500000 4.500000 3.800000 +128.035965 1.076464 3.800000 +126.681168 4.424874 3.800000 +125.843575 -4.184047 3.800000 +128.060059 -1.094462 3.800000 +125.037560 -3.766480 3.800000 +128.006088 -1.049553 3.800000 +124.318016 -3.181981 3.800000 +127.961174 -0.995570 3.800000 +123.733521 -2.462444 3.800000 +127.925140 -0.930449 3.800000 +123.315956 -1.656426 3.800000 +127.901680 -0.856562 3.800000 +123.075127 -0.818834 3.800000 +123.000000 0.000000 3.800000 +127.893524 -0.777817 3.800000 +123.075127 0.818834 3.800000 +127.901680 -0.699072 3.800000 +123.315956 1.656426 3.800000 +123.733521 2.462444 3.800000 +127.925140 -0.625186 3.800000 +124.318016 3.181981 3.800000 +127.961174 -0.560065 3.800000 +128.006088 -0.506082 3.800000 +128.089722 -0.405545 3.800000 +128.156830 -0.284263 3.800000 +128.200516 -0.146655 3.800000 +128.215714 0.000000 3.800000 +128.200516 0.146655 3.800000 +128.156830 0.284263 3.800000 +128.089722 0.405545 3.800000 +128.006088 0.506082 3.800000 +127.958702 0.563706 3.800000 +127.922775 0.630755 3.800000 +127.900764 0.703566 3.800000 +127.893524 0.777817 3.800000 +125.037560 3.766480 3.800000 +127.909355 0.886968 3.800000 +125.843575 4.184047 3.800000 +127.065529 11.400000 3.350000 +127.065529 11.100000 3.350000 +127.065529 11.100000 3.350000 +127.069458 5.313128 3.800000 +127.099998 5.284884 7.300000 +127.069458 8.850000 3.800000 +127.068459 9.997694 3.685314 +127.099998 11.400000 7.300000 +127.934471 11.100000 3.350000 +127.931541 9.997694 3.685314 +127.934471 11.100000 3.350000 +127.900002 11.400000 7.300000 +127.900002 5.284884 7.300000 +127.930542 5.313128 3.800000 +127.930542 8.850000 3.800000 +127.934471 11.400000 3.350000 +127.000000 -5.276362 7.300000 +126.969460 -5.304076 3.800000 +126.968452 -9.997694 3.685314 +126.965492 -11.100000 3.345793 +126.965530 -11.400000 3.350000 +127.000000 -11.400000 7.300000 +126.965492 -11.100000 3.345793 +126.969460 -8.850000 3.800000 +128.034470 -11.400000 3.350000 +128.034515 -11.100000 3.345793 +128.034515 -11.100000 3.345793 +128.030548 -5.304076 3.800000 +128.000000 -5.276362 7.300000 +128.030548 -8.850000 3.800000 +128.031540 -9.997694 3.685314 +128.000000 -11.400000 7.300000 +127.901680 -0.856562 3.800000 +127.948227 -0.551164 2.000000 +127.994972 -0.494975 2.000000 +128.006088 -0.506082 3.800000 +127.910721 -0.618946 2.000000 +127.961174 -0.560065 3.800000 +127.886307 -0.695854 2.000000 +127.925140 -0.625186 3.800000 +127.877815 -0.777817 2.000000 +127.901680 -0.699072 3.800000 +127.886307 -0.859781 2.000000 +127.893524 -0.777817 3.800000 +128.549545 -1.049553 3.800000 +128.560654 -1.060660 2.000000 +128.495575 -1.094462 3.800000 +128.504471 -1.107405 2.000000 +128.430450 -1.130498 3.800000 +128.356567 -1.153955 3.800000 +128.436691 -1.144914 2.000000 +128.359787 -1.169330 2.000000 +128.277817 -1.162109 3.800000 +128.277817 -1.177817 2.000000 +128.199066 -1.153955 3.800000 +128.125183 -1.130498 3.800000 +128.195847 -1.169330 2.000000 +128.118942 -1.144914 2.000000 +128.060059 -1.094462 3.800000 +128.051163 -1.107405 2.000000 +128.006088 -1.049553 3.800000 +127.961174 -0.995570 3.800000 +127.994972 -1.060660 2.000000 +127.925140 -0.930449 3.800000 +127.948227 -1.004471 2.000000 +127.910721 -0.936688 2.000000 +128.742340 0.812219 3.800000 +128.549545 1.049553 3.800000 +128.755493 -0.820815 2.000000 +128.560654 -1.060660 2.000000 +128.549545 -1.049553 3.800000 +128.742340 -0.812219 3.800000 +128.894684 -0.552142 2.000000 +128.880081 -0.546360 3.800000 +128.974960 -0.272945 2.000000 +128.959518 -0.270086 3.800000 +129.000000 0.000000 2.000000 +128.974960 0.272945 2.000000 +128.984299 0.000000 3.800000 +128.959518 0.270086 3.800000 +128.894684 0.552142 2.000000 +128.880081 0.546360 3.800000 +128.755493 0.820815 2.000000 +128.560654 1.060660 2.000000 +127.955467 0.568607 3.800000 +127.877869 0.771522 2.000000 +127.877815 0.777817 2.000000 +127.893524 0.777817 3.800000 +127.893570 0.771769 3.800000 +127.886581 0.694544 2.000000 +127.901947 0.697815 3.800000 +127.908264 0.624744 2.000000 +127.922775 0.630755 3.800000 +127.942291 0.560055 2.000000 +128.006088 0.506082 3.800000 +127.994972 0.494975 2.000000 +128.001846 0.510393 3.800000 +127.990555 0.499462 2.000000 +128.099045 -0.391643 3.800000 +128.006088 -0.506082 3.800000 +128.085892 0.383047 2.000000 +127.994972 0.494975 2.000000 +128.006088 0.506082 3.800000 +128.099045 0.391643 3.800000 +128.150848 0.257666 2.000000 +128.188309 0.127374 2.000000 +128.165451 0.263448 3.800000 +128.203766 0.130232 3.800000 +128.199997 0.000000 2.000000 +128.188309 -0.127374 2.000000 +128.215714 0.000000 3.800000 +128.150848 -0.257666 2.000000 +128.203766 -0.130232 3.800000 +128.165451 -0.263448 3.800000 +128.085892 -0.383047 2.000000 +127.994972 -0.494975 2.000000 +7.106474 -0.777817 3.800000 +7.038827 -0.560065 3.800000 +6.993918 -0.506082 3.800000 +7.005025 -0.494975 2.000000 +7.051770 -0.551164 2.000000 +7.074863 -0.625186 3.800000 +7.089279 -0.618946 2.000000 +7.098320 -0.699072 3.800000 +6.439340 -1.060660 2.000000 +6.450447 -1.049553 3.800000 +6.495529 -1.107405 2.000000 +6.563312 -1.144914 2.000000 +6.504430 -1.094462 3.800000 +6.569551 -1.130498 3.800000 +6.640219 -1.169330 2.000000 +6.643437 -1.153955 3.800000 +6.722183 -1.177817 2.000000 +6.804146 -1.169330 2.000000 +6.722183 -1.162109 3.800000 +6.800928 -1.153955 3.800000 +6.881053 -1.144914 2.000000 +6.948836 -1.107405 2.000000 +6.874815 -1.130498 3.800000 +6.939936 -1.094462 3.800000 +7.005025 -1.060660 2.000000 +6.993918 -1.049553 3.800000 +7.051770 -1.004471 2.000000 +7.038827 -0.995570 3.800000 +7.089279 -0.936688 2.000000 +7.074863 -0.930449 3.800000 +7.113695 -0.859781 2.000000 +7.098320 -0.856562 3.800000 +7.122182 -0.777817 2.000000 +7.113695 -0.695854 2.000000 +6.900955 0.391643 3.800000 +6.993918 0.506082 3.800000 +6.914103 -0.383047 2.000000 +7.005025 -0.494975 2.000000 +6.993918 -0.506082 3.800000 +6.900955 -0.391643 3.800000 +6.849148 -0.257666 2.000000 +6.834543 -0.263448 3.800000 +6.811686 -0.127374 2.000000 +6.796240 -0.130232 3.800000 +6.800000 0.000000 2.000000 +6.811686 0.127374 2.000000 +6.784292 0.000000 3.800000 +6.796240 0.130232 3.800000 +6.849148 0.257666 2.000000 +6.914103 0.383047 2.000000 +6.834543 0.263448 3.800000 +7.005025 0.494975 2.000000 +6.931394 1.100170 3.800000 +7.115259 0.851918 2.000000 +7.122182 0.777817 2.000000 +7.106474 0.777817 3.800000 +7.099823 0.849008 3.800000 +7.091734 0.930891 2.000000 +7.052526 1.003367 2.000000 +7.077222 0.924879 3.800000 +7.000538 1.065077 2.000000 +7.039554 0.994510 3.800000 +6.989607 1.053796 3.800000 +6.939945 1.113346 2.000000 +6.450447 1.049553 3.800000 +6.439340 1.060660 2.000000 +6.505490 1.095189 3.800000 +6.496633 1.108162 2.000000 +6.575120 1.132857 3.800000 +6.650992 1.155457 3.800000 +6.569109 1.147369 2.000000 +6.648082 1.170894 2.000000 +6.728231 1.162061 3.800000 +6.728478 1.177768 2.000000 +6.802186 1.153689 3.800000 +6.805456 1.169053 2.000000 +6.869245 1.132857 3.800000 +6.875256 1.147369 2.000000 +6.040488 -0.270086 3.800000 +6.450447 -1.049553 3.800000 +6.439340 -1.060660 2.000000 +6.257655 -0.812219 3.800000 +6.119923 -0.546360 3.800000 +6.244507 -0.820815 2.000000 +6.439340 1.060660 2.000000 +6.450447 1.049553 3.800000 +6.244507 0.820815 2.000000 +6.257655 0.812219 3.800000 +6.105318 0.552142 2.000000 +6.119923 0.546360 3.800000 +6.025042 0.272945 2.000000 +6.040488 0.270086 3.800000 +6.000000 0.000000 2.000000 +6.015708 0.000000 3.800000 +6.025042 -0.272945 2.000000 +6.105318 -0.552142 2.000000 +45.500000 0.500000 5.800000 +46.000000 0.500000 5.800000 +46.900002 0.500000 4.900000 +46.900002 0.500000 3.800000 +45.500000 0.500000 3.800000 +45.200001 0.200000 3.800000 +45.200001 -0.200000 3.800000 +45.200001 -0.200000 5.800000 +45.200001 0.200000 5.800000 +46.900002 -0.500000 4.900000 +46.000000 -0.500000 5.800000 +45.500000 -0.500000 3.800000 +46.900002 -0.500000 3.800000 +45.500000 -0.500000 5.800000 +47.200001 0.200000 3.800000 +47.200001 0.200000 4.600000 +47.200001 -0.200000 4.600000 +47.200001 -0.200000 3.800000 +45.389572 -0.478936 5.800000 +45.445412 -0.494992 5.800000 +46.000000 -0.500000 5.800000 +46.000000 0.500000 5.800000 +45.500000 -0.500000 5.800000 +45.500000 0.500000 5.800000 +45.445412 0.494992 5.800000 +45.389572 0.478936 5.800000 +45.335838 0.451099 5.800000 +45.287868 0.412132 5.800000 +45.248901 0.364163 5.800000 +45.221062 0.310428 5.800000 +45.205009 0.254589 5.800000 +45.200001 0.200000 5.800000 +45.200001 -0.200000 5.800000 +45.205009 -0.254589 5.800000 +45.221062 -0.310428 5.800000 +45.248901 -0.364163 5.800000 +45.287868 -0.412132 5.800000 +45.335838 -0.451099 5.800000 +60.183014 7.977242 5.800000 +59.933014 7.544229 5.800000 +59.483013 6.764806 4.900000 +59.483013 6.764806 3.800000 +60.183014 7.977242 3.800000 +60.073204 8.387049 3.800000 +59.726795 8.587049 3.800000 +59.726795 8.587049 5.800000 +60.073204 8.387049 5.800000 +59.316986 8.477242 3.800000 +58.616989 7.264806 3.800000 +59.066986 8.044229 5.800000 +59.316986 8.477242 5.800000 +58.616989 7.264806 4.900000 +59.073204 6.654998 3.800000 +59.073204 6.654998 4.600000 +58.726795 6.854998 4.600000 +58.726795 6.854998 3.800000 +59.390442 8.562344 5.800000 +59.348618 8.522013 5.800000 +59.066986 8.044229 5.800000 +59.933014 7.544229 5.800000 +59.316986 8.477242 5.800000 +60.183014 7.977242 5.800000 +60.205971 8.027020 5.800000 +60.219986 8.083406 5.800000 +60.222744 8.143861 5.800000 +60.212982 8.204887 5.800000 +60.190922 8.262618 5.800000 +60.158306 8.313593 5.800000 +60.117977 8.355417 5.800000 +60.073204 8.387049 5.800000 +59.726795 8.587049 5.800000 +59.677017 8.610006 5.800000 +59.620628 8.624022 5.800000 +59.560177 8.626781 5.800000 +59.499149 8.617019 5.800000 +59.441418 8.594960 5.800000 +58.616989 -7.264806 4.900000 +58.616989 -7.264806 3.800000 +59.316986 -8.477242 3.800000 +59.316986 -8.477242 5.800000 +59.066986 -8.044229 5.800000 +59.726795 -8.587049 5.800000 +59.726795 -8.587049 3.800000 +60.073204 -8.387049 3.800000 +60.073204 -8.387049 5.800000 +60.183014 -7.977242 3.800000 +59.483013 -6.764806 3.800000 +59.933014 -7.544229 5.800000 +60.183014 -7.977242 5.800000 +59.483013 -6.764806 4.900000 +58.726795 -6.854998 3.800000 +58.726795 -6.854998 4.600000 +59.073204 -6.654998 4.600000 +59.073204 -6.654998 3.800000 +60.219986 -8.083406 5.800000 +60.205971 -8.027020 5.800000 +60.183014 -7.977242 5.800000 +59.933014 -7.544229 5.800000 +59.066986 -8.044229 5.800000 +59.316986 -8.477242 5.800000 +59.348618 -8.522013 5.800000 +59.390442 -8.562344 5.800000 +59.441418 -8.594960 5.800000 +59.499149 -8.617019 5.800000 +59.560177 -8.626781 5.800000 +59.620628 -8.624022 5.800000 +59.677017 -8.610006 5.800000 +59.726795 -8.587049 5.800000 +60.073204 -8.387049 5.800000 +60.117977 -8.355417 5.800000 +60.158306 -8.313593 5.800000 +60.190922 -8.262618 5.800000 +60.212982 -8.204887 5.800000 +60.222744 -8.143861 5.800000 +47.200001 0.200000 4.600000 +47.194992 0.254589 4.605009 +46.000000 0.500000 5.800000 +46.000000 -0.500000 5.800000 +46.900002 0.500000 4.900000 +46.900002 -0.500000 4.900000 +47.010429 0.478936 4.789572 +47.010429 -0.478936 4.789572 +47.112133 -0.412132 4.687868 +47.151100 -0.364163 4.648901 +47.178936 -0.310428 4.621064 +47.194992 -0.254589 4.605009 +47.200001 -0.200000 4.600000 +47.064163 0.451099 4.735837 +47.112133 0.412132 4.687868 +47.151100 0.364163 4.648901 +47.178936 0.310428 4.621064 +59.073204 6.654998 4.600000 +59.122986 6.632041 4.605009 +59.933014 7.544229 5.800000 +59.066986 8.044229 5.800000 +59.483013 6.764806 4.900000 +59.409557 6.679704 4.789572 +58.616989 7.264806 4.900000 +58.587017 7.192451 4.822354 +58.576794 7.114806 4.750000 +58.586666 7.038483 4.688838 +58.616989 6.964806 4.640193 +58.665634 6.901708 4.609871 +58.695107 6.876082 4.602415 +58.726795 6.854998 4.600000 +59.358582 6.647087 4.735837 +59.300850 6.625028 4.687868 +59.239826 6.615266 4.648901 +59.179371 6.618025 4.621064 +58.726795 -6.854998 4.600000 +58.695107 -6.876082 4.602415 +58.616989 -7.264806 4.900000 +59.066986 -8.044229 5.800000 +59.933014 -7.544229 5.800000 +59.483013 -6.764806 4.900000 +59.409557 -6.679704 4.789572 +58.587017 -7.192451 4.822354 +59.300850 -6.625028 4.687868 +59.239826 -6.615266 4.648901 +59.179371 -6.618025 4.621064 +59.122986 -6.632041 4.605009 +59.073204 -6.654998 4.600000 +58.576794 -7.114806 4.750000 +58.586666 -7.038483 4.688838 +58.616989 -6.964806 4.640193 +58.665634 -6.901708 4.609871 +47.194992 0.254589 4.605009 +47.200001 0.200000 4.600000 +46.900002 0.500000 3.800000 +46.900002 0.500000 4.900000 +46.961472 0.493634 3.800000 +46.954590 0.494992 4.845411 +47.019154 0.475323 3.800000 +47.010429 0.478936 4.789572 +47.069992 0.447191 3.800000 +47.064163 0.451099 4.735837 +47.112133 0.412132 3.800000 +47.089088 0.432906 4.710911 +47.112133 0.412132 4.687868 +47.147190 0.369990 3.800000 +47.132904 0.389089 4.667094 +47.175323 0.319153 3.800000 +47.151100 0.364163 4.648901 +47.193634 0.261473 3.800000 +47.178936 0.310428 4.621064 +47.200001 0.200000 3.800000 +47.200001 -0.200000 3.800000 +47.200001 -0.200000 4.600000 +46.954590 -0.494992 4.845411 +46.900002 -0.500000 4.900000 +46.900002 -0.500000 3.800000 +47.010429 -0.478936 4.789572 +46.961472 -0.493634 3.800000 +47.064163 -0.451099 4.735837 +47.019154 -0.475323 3.800000 +47.089088 -0.432906 4.710911 +47.069992 -0.447191 3.800000 +47.112133 -0.412132 4.687868 +47.132904 -0.389089 4.667094 +47.112133 -0.412132 3.800000 +47.151100 -0.364163 4.648901 +47.147190 -0.369990 3.800000 +47.178936 -0.310428 4.621064 +47.175323 -0.319153 3.800000 +47.194992 -0.254589 4.605009 +47.193634 -0.261473 3.800000 +45.206367 0.261473 3.800000 +45.200001 0.200000 3.800000 +45.438526 0.493634 5.800000 +45.500000 0.500000 5.800000 +45.500000 0.500000 3.800000 +45.438526 0.493634 3.800000 +45.380848 0.475323 5.800000 +45.380848 0.475323 3.800000 +45.330009 0.447191 5.800000 +45.287868 0.412132 5.800000 +45.330009 0.447191 3.800000 +45.287868 0.412132 3.800000 +45.252808 0.369990 5.800000 +45.224678 0.319153 5.800000 +45.252808 0.369990 3.800000 +45.206367 0.261473 5.800000 +45.224678 0.319153 3.800000 +45.200001 0.200000 5.800000 +45.200001 -0.200000 5.800000 +45.200001 -0.200000 3.800000 +45.438526 -0.493634 3.800000 +45.500000 -0.500000 3.800000 +45.500000 -0.500000 5.800000 +45.438526 -0.493634 5.800000 +45.380848 -0.475323 3.800000 +45.330009 -0.447191 3.800000 +45.380848 -0.475323 5.800000 +45.330009 -0.447191 5.800000 +45.287868 -0.412132 3.800000 +45.252808 -0.369990 3.800000 +45.287868 -0.412132 5.800000 +45.252808 -0.369990 5.800000 +45.224678 -0.319153 3.800000 +45.224678 -0.319153 5.800000 +45.206367 -0.261473 3.800000 +45.206367 -0.261473 5.800000 +59.122986 6.632041 4.605009 +59.073204 6.654998 4.600000 +59.483013 6.764806 3.800000 +59.483013 6.764806 4.900000 +59.446762 6.714752 3.800000 +59.451382 6.720035 4.845411 +59.402065 6.673955 3.800000 +59.409557 6.679704 4.789572 +59.352283 6.643994 3.800000 +59.358582 6.647087 4.735837 +59.300850 6.625028 3.800000 +59.330364 6.634596 4.710911 +59.300850 6.625028 4.687868 +59.246826 6.615737 3.800000 +59.270508 6.618558 4.667094 +59.188732 6.616793 3.800000 +59.239826 6.615266 4.648901 +59.129623 6.629775 3.800000 +59.179371 6.618025 4.621064 +59.073204 6.654998 3.800000 +58.577660 7.137560 3.800000 +58.576794 7.114806 3.800000 +58.599697 7.229767 4.861010 +58.616989 7.264806 4.900000 +58.616989 7.264806 3.800000 +58.606358 7.244668 3.800000 +58.587017 7.192451 4.822354 +58.579338 7.153796 4.785039 +58.587017 7.192451 3.800000 +58.576794 7.114806 4.750000 +60.183014 7.977242 5.800000 +60.183014 7.977242 3.800000 +60.123260 8.350800 3.800000 +60.073204 8.387049 3.800000 +60.073204 8.387049 5.800000 +60.123260 8.350800 5.800000 +60.164055 8.306101 3.800000 +60.164055 8.306101 5.800000 +60.194016 8.256320 3.800000 +60.212982 8.204887 3.800000 +60.194016 8.256320 5.800000 +60.222275 8.150862 3.800000 +60.212982 8.204887 5.800000 +60.222275 8.150862 5.800000 +60.221218 8.092770 3.800000 +60.221218 8.092770 5.800000 +60.208237 8.033661 3.800000 +60.208237 8.033661 5.800000 +59.447716 8.598053 5.800000 +59.726795 8.587049 5.800000 +59.726795 8.587049 3.800000 +59.670376 8.612272 5.800000 +59.611267 8.625255 5.800000 +59.670376 8.612272 3.800000 +59.553173 8.626310 5.800000 +59.611267 8.625255 3.800000 +59.499149 8.617019 5.800000 +59.553173 8.626310 3.800000 +59.316986 8.477242 3.800000 +59.316986 8.477242 5.800000 +59.353237 8.527295 3.800000 +59.353237 8.527295 5.800000 +59.397934 8.568092 3.800000 +59.447716 8.598053 3.800000 +59.397934 8.568092 5.800000 +59.499149 8.617019 3.800000 +58.599300 -7.000798 4.662520 +58.726795 -6.854998 4.600000 +58.726795 -6.854998 3.800000 +58.695107 -6.876082 4.602415 +58.665634 -6.901708 4.609871 +58.693016 -6.877687 3.800000 +58.639317 -6.931494 4.622507 +58.651127 -6.917133 3.800000 +58.616989 -6.964806 4.640193 +58.576794 -7.114806 3.800000 +58.576794 -7.114806 4.750000 +58.579556 -7.074208 3.800000 +58.579208 -7.076820 4.718311 +58.592773 -7.018209 3.800000 +58.586666 -7.038483 4.688838 +58.616989 -6.964806 3.800000 +59.073204 -6.654998 3.800000 +59.073204 -6.654998 4.600000 +59.451382 -6.720035 4.845411 +59.483013 -6.764806 4.900000 +59.483013 -6.764806 3.800000 +59.409557 -6.679704 4.789572 +59.446762 -6.714752 3.800000 +59.358582 -6.647087 4.735837 +59.402065 -6.673955 3.800000 +59.330364 -6.634596 4.710911 +59.352283 -6.643994 3.800000 +59.300850 -6.625028 4.687868 +59.270508 -6.618558 4.667094 +59.300850 -6.625028 3.800000 +59.239826 -6.615266 4.648901 +59.246826 -6.615737 3.800000 +59.179371 -6.618025 4.621064 +59.188732 -6.616793 3.800000 +59.122986 -6.632041 4.605009 +59.129623 -6.629775 3.800000 +59.353237 -8.527295 5.800000 +59.316986 -8.477242 5.800000 +59.726795 -8.587049 3.800000 +59.726795 -8.587049 5.800000 +59.670376 -8.612272 3.800000 +59.670376 -8.612272 5.800000 +59.611267 -8.625255 3.800000 +59.553173 -8.626310 3.800000 +59.611267 -8.625255 5.800000 +59.553173 -8.626310 5.800000 +59.499149 -8.617019 3.800000 +59.499149 -8.617019 5.800000 +59.447716 -8.598053 3.800000 +59.447716 -8.598053 5.800000 +59.397934 -8.568092 3.800000 +59.353237 -8.527295 3.800000 +59.397934 -8.568092 5.800000 +59.316986 -8.477242 3.800000 +60.221218 -8.092770 5.800000 +60.208237 -8.033661 3.800000 +60.183014 -7.977242 3.800000 +60.183014 -7.977242 5.800000 +60.221218 -8.092770 3.800000 +60.208237 -8.033661 5.800000 +60.073204 -8.387049 5.800000 +60.073204 -8.387049 3.800000 +60.123260 -8.350800 5.800000 +60.164055 -8.306101 5.800000 +60.123260 -8.350800 3.800000 +60.194016 -8.256320 5.800000 +60.164055 -8.306101 3.800000 +60.194016 -8.256320 3.800000 +60.212982 -8.204887 5.800000 +60.212982 -8.204887 3.800000 +60.222275 -8.150862 5.800000 +60.222275 -8.150862 3.800000 +93.406883 5.475741 6.100000 +93.900002 4.800000 6.100000 +93.505135 5.134044 6.100000 +93.863274 4.399681 6.100000 +93.535782 4.800000 6.100000 +93.745537 3.990192 6.100000 +93.505135 4.465956 6.100000 +93.541389 3.596138 6.100000 +93.406883 4.124259 6.100000 +93.255638 3.244365 6.100000 +93.236542 3.795443 6.100000 +92.903862 2.958610 6.100000 +92.998093 3.501907 6.100000 +92.509811 2.754466 6.100000 +92.704559 3.263460 6.100000 +92.100319 2.636728 6.100000 +92.375740 3.093113 6.100000 +91.699997 2.600000 6.100000 +92.034042 2.994868 6.100000 +91.299683 2.636728 6.100000 +91.699997 2.964220 6.100000 +90.890190 2.754466 6.100000 +91.365959 2.994868 6.100000 +90.496140 2.958610 6.100000 +91.024261 3.093113 6.100000 +90.144363 3.244365 6.100000 +90.695442 3.263460 6.100000 +89.858612 3.596138 6.100000 +90.401909 3.501907 6.100000 +89.654465 3.990192 6.100000 +90.163460 3.795443 6.100000 +89.536728 4.399681 6.100000 +89.993111 4.124259 6.100000 +89.500000 4.800000 6.100000 +89.894867 4.465956 6.100000 +89.536728 5.200319 6.100000 +89.864220 4.800000 6.100000 +89.654465 5.609808 6.100000 +89.894867 5.134044 6.100000 +89.858612 6.003861 6.100000 +89.993111 5.475741 6.100000 +90.144363 6.355635 6.100000 +90.163460 5.804557 6.100000 +90.496140 6.641390 6.100000 +90.401909 6.098093 6.100000 +90.890190 6.845534 6.100000 +90.695442 6.336540 6.100000 +91.299683 6.963272 6.100000 +91.024261 6.506887 6.100000 +91.699997 7.000000 6.100000 +91.365959 6.605133 6.100000 +92.100319 6.963272 6.100000 +91.699997 6.635780 6.100000 +92.509811 6.845534 6.100000 +92.034042 6.605133 6.100000 +92.903862 6.641390 6.100000 +92.375740 6.506887 6.100000 +93.255638 6.355635 6.100000 +92.704559 6.336540 6.100000 +93.541389 6.003861 6.100000 +92.998093 6.098093 6.100000 +93.745537 5.609808 6.100000 +93.236542 5.804557 6.100000 +93.863274 5.200319 6.100000 +89.300003 4.800000 5.900000 +89.300003 4.800000 3.800000 +94.099998 4.800000 3.800000 +94.099998 4.800000 5.900000 +94.059937 4.363289 3.800000 +94.059937 4.363289 5.900000 +93.931496 3.916573 3.800000 +93.931496 3.916573 5.900000 +93.708786 3.486696 3.800000 +93.397057 3.102944 3.800000 +93.708786 3.486696 5.900000 +93.397057 3.102944 5.900000 +93.013306 2.791211 3.800000 +93.013306 2.791211 5.900000 +92.583427 2.568508 3.800000 +92.583427 2.568508 5.900000 +92.136711 2.440067 3.800000 +92.136711 2.440067 5.900000 +91.699997 2.400000 3.800000 +91.699997 2.400000 5.900000 +91.263290 2.440067 3.800000 +91.263290 2.440067 5.900000 +90.816574 2.568508 3.800000 +90.816574 2.568508 5.900000 +90.386696 2.791211 3.800000 +90.386696 2.791211 5.900000 +90.002945 3.102944 3.800000 +90.002945 3.102944 5.900000 +89.691208 3.486696 3.800000 +89.691208 3.486696 5.900000 +89.468506 3.916573 3.800000 +89.468506 3.916573 5.900000 +89.340065 4.363289 3.800000 +89.340065 4.363289 5.900000 +4.250000 -12.700000 1.050000 +4.250000 -13.450000 1.050000 +5.350000 -13.450000 1.050000 +5.350000 -12.700000 1.050000 +4.250000 -13.881399 2.131400 +5.350000 -13.881399 2.131400 +5.350000 -13.450000 1.700000 +4.250000 -13.450000 1.700000 +25.150000 -13.450000 1.050000 +26.250000 -13.450000 1.050000 +26.250000 -12.700000 1.050000 +25.150000 -12.700000 1.050000 +46.049999 -12.700000 1.050000 +46.049999 -13.450000 1.050000 +47.150002 -13.450000 1.050000 +47.150002 -12.700000 1.050000 +66.949997 -13.450000 1.050000 +68.050003 -13.450000 1.050000 +68.050003 -12.700000 1.050000 +66.949997 -12.700000 1.050000 +87.849998 -13.450000 1.050000 +88.949997 -13.450000 1.050000 +88.949997 -12.700000 1.050000 +87.849998 -12.700000 1.050000 +108.750000 -13.450000 1.050000 +109.849998 -13.450000 1.050000 +109.849998 -12.700000 1.050000 +108.750000 -12.700000 1.050000 +129.649994 -13.450000 1.050000 +130.750000 -13.450000 1.050000 +130.750000 -12.700000 1.050000 +129.649994 -12.700000 1.050000 +25.150000 -13.450000 1.700000 +25.150000 -13.881399 2.131400 +26.250000 -13.881399 2.131400 +26.250000 -13.450000 1.700000 +46.049999 -13.881399 2.131400 +47.150002 -13.881399 2.131400 +47.150002 -13.450000 1.700000 +46.049999 -13.450000 1.700000 +66.949997 -13.881399 2.131400 +68.050003 -13.881399 2.131400 +68.050003 -13.450000 1.700000 +66.949997 -13.450000 1.700000 +87.849998 -13.450000 1.700000 +87.849998 -13.881399 2.131400 +88.949997 -13.881399 2.131400 +88.949997 -13.450000 1.700000 +108.750000 -13.881399 2.131400 +109.849998 -13.881399 2.131400 +109.849998 -13.450000 1.700000 +108.750000 -13.450000 1.700000 +129.649994 -13.450000 1.700000 +129.649994 -13.881399 2.131400 +130.750000 -13.881399 2.131400 +130.750000 -13.450000 1.700000 +37.049999 -13.450000 1.050000 +38.150002 -13.450000 1.050000 +38.150002 -12.700000 1.050000 +37.049999 -12.700000 1.050000 +57.950001 -12.700000 1.050000 +57.950001 -13.450000 1.050000 +59.049999 -13.450000 1.050000 +59.049999 -12.700000 1.050000 +75.949997 -13.450000 1.050000 +77.050003 -13.450000 1.050000 +77.050003 -12.700000 1.050000 +75.949997 -12.700000 1.050000 +96.849998 -12.700000 1.050000 +96.849998 -13.450000 1.050000 +97.949997 -13.450000 1.050000 +97.949997 -12.700000 1.050000 +-12.688149 0.548516 2.300000 +-12.400000 0.548516 2.300000 +-12.400000 0.533016 2.300000 +-12.688622 0.537489 2.300000 +-12.687337 -0.566984 2.300000 +-12.400000 -0.566984 2.300000 +-13.400000 -0.566984 1.050000 +-13.400000 -0.566984 2.300000 +-12.700000 -0.566984 1.050000 +-12.645411 -0.566984 1.055008 +-12.589572 -0.566984 1.071064 +-12.535837 -0.566984 1.098901 +-12.487868 -0.566984 1.137868 +-12.448901 -0.566984 1.185837 +-12.421063 -0.566984 1.239572 +-12.405008 -0.566984 1.295411 +-12.400000 -0.566984 1.350000 +-13.400000 0.548516 1.050000 +-13.400000 0.548516 1.700000 +-13.400000 -0.551484 2.300000 +-13.400000 -0.566984 2.300000 +-13.400000 -0.551484 1.700000 +-13.400000 -0.566984 1.050000 +-12.421063 0.548516 1.239572 +-12.405008 0.548516 1.295411 +-12.400000 0.548516 1.350000 +-12.400000 0.548516 2.300000 +-13.400000 0.548516 1.700000 +-13.400000 0.548516 1.050000 +-12.688149 0.548516 2.300000 +-13.869085 0.548516 2.300000 +-13.870219 0.548516 2.170219 +-12.700000 0.548516 1.050000 +-12.645411 0.548516 1.055008 +-12.589572 0.548516 1.071064 +-12.535837 0.548516 1.098901 +-12.487868 0.548516 1.137868 +-12.448901 0.548516 1.185837 +-12.400000 -0.566984 2.300000 +-12.687337 -0.566984 2.300000 +-12.687535 -0.562527 2.300000 +-12.700000 0.548516 1.050000 +-13.400000 0.548516 1.050000 +-13.400000 -0.566984 1.050000 +-12.700000 -0.566984 1.050000 +147.399994 0.533016 2.300000 +147.399994 0.548516 2.300000 +147.688156 0.548516 2.300000 +147.688614 0.537489 2.300000 +147.399994 -0.566984 2.300000 +147.687531 -0.562527 2.300000 +147.687531 -0.562527 2.300000 +147.421066 -0.566984 1.239572 +147.405014 -0.566984 1.295411 +147.399994 -0.566984 1.350000 +147.399994 -0.566984 2.300000 +148.399994 -0.566984 2.300000 +148.399994 -0.566984 1.050000 +147.687332 -0.566984 2.300000 +147.699997 -0.566984 1.050000 +147.645416 -0.566984 1.055008 +147.589569 -0.566984 1.071064 +147.535843 -0.566984 1.098901 +147.487869 -0.566984 1.137868 +147.448898 -0.566984 1.185837 +148.399994 -0.556318 1.700000 +148.399994 0.548516 1.700000 +148.399994 -0.566984 1.050000 +148.399994 -0.566984 2.300000 +148.399994 -0.556318 2.300000 +148.399994 0.548516 1.050000 +147.589569 0.548516 1.071064 +147.645416 0.548516 1.055008 +147.699997 0.548516 1.050000 +148.399994 0.548516 1.050000 +147.688156 0.548516 2.300000 +147.399994 0.548516 2.300000 +148.870224 0.548516 2.170219 +148.869080 0.548516 2.300000 +148.399994 0.548516 1.700000 +147.399994 0.548516 1.350000 +147.405014 0.548516 1.295411 +147.421066 0.548516 1.239572 +147.448898 0.548516 1.185837 +147.487869 0.548516 1.137868 +147.535843 0.548516 1.098901 +147.699997 -0.566984 1.050000 +148.399994 -0.566984 1.050000 +148.399994 0.548516 1.050000 +147.699997 0.548516 1.050000 +-13.400000 -0.551484 2.300000 +-13.400000 -0.551484 1.700000 +-13.870103 -0.551484 2.170102 +-13.868968 -0.551484 2.300000 +148.869904 -0.556318 2.169911 +148.399994 -0.556318 1.700000 +148.399994 -0.556318 2.300000 +148.868774 -0.556318 2.300000 +148.880966 0.000000 2.180967 +148.870224 0.548516 2.170219 +148.399994 0.548516 1.700000 +148.399994 -0.556318 1.700000 +148.869904 -0.556318 2.169911 +-13.400000 0.548516 1.700000 +-13.870219 0.548516 2.170219 +-13.870103 -0.551484 2.170102 +-13.400000 -0.551484 1.700000 +96.849998 -13.881399 2.131400 +97.949997 -13.881399 2.131400 +97.949997 -13.450000 1.700000 +96.849998 -13.450000 1.700000 +75.949997 -13.450000 1.700000 +75.949997 -13.881399 2.131400 +77.050003 -13.881399 2.131400 +77.050003 -13.450000 1.700000 +57.950001 -13.450000 1.700000 +57.950001 -13.881399 2.131400 +59.049999 -13.881399 2.131400 +59.049999 -13.450000 1.700000 +37.049999 -13.881399 2.131400 +38.150002 -13.881399 2.131400 +38.150002 -13.450000 1.700000 +37.049999 -13.450000 1.700000 +37.750000 13.000000 5.800000 +37.750000 13.300000 5.913002 +37.750000 11.400000 7.000000 +37.750000 11.400000 3.850000 +37.750000 12.700000 3.850000 +37.750000 12.300000 7.000000 +37.750000 13.300000 6.400000 +37.750000 12.700000 5.800000 +34.549999 13.300000 5.913002 +34.549999 13.000000 5.800000 +34.549999 12.700000 3.850000 +34.549999 11.400000 3.850000 +34.549999 12.700000 5.800000 +34.549999 11.400000 7.000000 +34.549999 12.300000 7.000000 +34.549999 13.300000 6.400000 +30.049999 -13.000000 5.800000 +30.049999 -13.300000 5.913002 +30.049999 -11.400000 7.000000 +30.049999 -11.400000 3.850000 +30.049999 -12.700000 3.850000 +30.049999 -12.300000 7.000000 +30.049999 -13.300000 6.400000 +30.049999 -12.700000 5.800000 +33.250000 -13.300000 5.913002 +33.250000 -13.000000 5.800000 +33.250000 -12.700000 3.850000 +33.250000 -11.400000 3.850000 +33.250000 -12.700000 5.800000 +33.250000 -11.400000 7.000000 +33.250000 -12.300000 7.000000 +33.250000 -13.300000 6.400000 +37.750000 12.300000 7.000000 +34.549999 12.300000 7.000000 +34.549999 11.400000 7.000000 +37.750000 11.400000 7.000000 +30.049999 -12.300000 7.000000 +33.250000 -12.300000 7.000000 +33.250000 -11.400000 7.000000 +30.049999 -11.400000 7.000000 +34.549999 13.000000 5.800000 +37.750000 13.000000 5.800000 +37.750000 12.700000 5.800000 +34.549999 12.700000 5.800000 +34.549999 13.300000 6.400000 +37.750000 13.300000 6.400000 +37.750000 13.300000 5.913002 +34.549999 13.300000 5.913002 +30.049999 -13.000000 5.800000 +30.049999 -12.700000 5.800000 +33.250000 -12.700000 5.800000 +33.250000 -13.000000 5.800000 +33.250000 -13.300000 5.913002 +33.250000 -13.300000 6.400000 +30.049999 -13.300000 6.400000 +30.049999 -13.300000 5.913002 +58.650002 13.000000 5.800000 +58.650002 13.300000 5.913002 +58.650002 11.400000 7.000000 +58.650002 11.400000 3.850000 +58.650002 12.700000 3.850000 +58.650002 12.300000 7.000000 +58.650002 13.300000 6.400000 +58.650002 12.700000 5.800000 +55.450001 13.300000 6.400000 +55.450001 13.300000 5.913002 +55.450001 12.700000 3.850000 +55.450001 11.400000 3.850000 +55.450001 12.700000 5.800000 +55.450001 11.400000 7.000000 +55.450001 12.300000 7.000000 +55.450001 13.000000 5.800000 +50.950001 -13.000000 5.800000 +50.950001 -13.300000 5.913002 +50.950001 -11.400000 7.000000 +50.950001 -11.400000 3.850000 +50.950001 -12.700000 3.850000 +50.950001 -12.300000 7.000000 +50.950001 -13.300000 6.400000 +50.950001 -12.700000 5.800000 +54.150002 -13.300000 6.400000 +54.150002 -13.300000 5.913002 +54.150002 -12.700000 3.850000 +54.150002 -11.400000 3.850000 +54.150002 -12.700000 5.800000 +54.150002 -11.400000 7.000000 +54.150002 -12.300000 7.000000 +54.150002 -13.000000 5.800000 +58.650002 12.300000 7.000000 +55.450001 12.300000 7.000000 +55.450001 11.400000 7.000000 +58.650002 11.400000 7.000000 +50.950001 -12.300000 7.000000 +54.150002 -12.300000 7.000000 +54.150002 -11.400000 7.000000 +50.950001 -11.400000 7.000000 +58.650002 13.000000 5.800000 +58.650002 12.700000 5.800000 +55.450001 12.700000 5.800000 +55.450001 13.000000 5.800000 +55.450001 13.300000 6.400000 +58.650002 13.300000 6.400000 +58.650002 13.300000 5.913002 +55.450001 13.300000 5.913002 +50.950001 -13.000000 5.800000 +50.950001 -12.700000 5.800000 +54.150002 -12.700000 5.800000 +54.150002 -13.000000 5.800000 +54.150002 -13.300000 6.400000 +50.950001 -13.300000 6.400000 +50.950001 -13.300000 5.913002 +54.150002 -13.300000 5.913002 +97.250000 13.300000 5.913002 +97.250000 13.000000 5.800000 +97.250000 12.700000 3.850000 +97.250000 11.400000 3.850000 +97.250000 12.700000 5.800000 +97.250000 11.400000 7.000000 +97.250000 12.300000 7.000000 +97.250000 13.300000 6.400000 +100.449997 13.000000 5.800000 +100.449997 13.300000 5.913002 +100.449997 11.400000 7.000000 +100.449997 11.400000 3.850000 +100.449997 12.700000 3.850000 +100.449997 12.300000 7.000000 +100.449997 13.300000 6.400000 +100.449997 12.700000 5.800000 +104.949997 -13.300000 5.913002 +104.949997 -13.000000 5.800000 +104.949997 -12.700000 3.850000 +104.949997 -11.400000 3.850000 +104.949997 -12.700000 5.800000 +104.949997 -11.400000 7.000000 +104.949997 -12.300000 7.000000 +104.949997 -13.300000 6.400000 +101.750000 -13.000000 5.800000 +101.750000 -13.300000 5.913002 +101.750000 -11.400000 7.000000 +101.750000 -11.400000 3.850000 +101.750000 -12.700000 3.850000 +101.750000 -12.300000 7.000000 +101.750000 -13.300000 6.400000 +101.750000 -12.700000 5.800000 +76.349998 13.300000 5.913002 +76.349998 13.000000 5.800000 +76.349998 12.700000 3.850000 +76.349998 11.400000 3.850000 +76.349998 12.700000 5.800000 +76.349998 11.400000 7.000000 +76.349998 12.300000 7.000000 +76.349998 13.300000 6.400000 +79.550003 13.000000 5.800000 +79.550003 13.300000 5.913002 +79.550003 11.400000 7.000000 +79.550003 11.400000 3.850000 +79.550003 12.700000 3.850000 +79.550003 12.300000 7.000000 +79.550003 13.300000 6.400000 +79.550003 12.700000 5.800000 +84.050003 -13.300000 5.913002 +84.050003 -13.000000 5.800000 +84.050003 -12.700000 3.850000 +84.050003 -11.400000 3.850000 +84.050003 -12.700000 5.800000 +84.050003 -11.400000 7.000000 +84.050003 -12.300000 7.000000 +84.050003 -13.300000 6.400000 +80.849998 -13.000000 5.800000 +80.849998 -13.300000 5.913002 +80.849998 -11.400000 7.000000 +80.849998 -11.400000 3.850000 +80.849998 -12.700000 3.850000 +80.849998 -12.300000 7.000000 +80.849998 -13.300000 6.400000 +80.849998 -12.700000 5.800000 +97.250000 12.300000 7.000000 +97.250000 11.400000 7.000000 +100.449997 11.400000 7.000000 +100.449997 12.300000 7.000000 +104.949997 -12.300000 7.000000 +104.949997 -11.400000 7.000000 +101.750000 -11.400000 7.000000 +101.750000 -12.300000 7.000000 +79.550003 12.300000 7.000000 +76.349998 12.300000 7.000000 +76.349998 11.400000 7.000000 +79.550003 11.400000 7.000000 +84.050003 -12.300000 7.000000 +84.050003 -11.400000 7.000000 +80.849998 -11.400000 7.000000 +80.849998 -12.300000 7.000000 +100.449997 12.700000 5.800000 +97.250000 12.700000 5.800000 +97.250000 13.000000 5.800000 +100.449997 13.000000 5.800000 +97.250000 13.300000 6.400000 +100.449997 13.300000 6.400000 +100.449997 13.300000 5.913002 +97.250000 13.300000 5.913002 +79.550003 12.700000 5.800000 +76.349998 12.700000 5.800000 +76.349998 13.000000 5.800000 +79.550003 13.000000 5.800000 +76.349998 13.300000 5.913002 +76.349998 13.300000 6.400000 +79.550003 13.300000 6.400000 +79.550003 13.300000 5.913002 +101.750000 -13.000000 5.800000 +101.750000 -12.700000 5.800000 +104.949997 -12.700000 5.800000 +104.949997 -13.000000 5.800000 +104.949997 -13.300000 6.400000 +101.750000 -13.300000 6.400000 +101.750000 -13.300000 5.913002 +104.949997 -13.300000 5.913002 +80.849998 -12.700000 5.800000 +84.050003 -12.700000 5.800000 +84.050003 -13.000000 5.800000 +80.849998 -13.000000 5.800000 +84.050003 -13.300000 6.400000 +80.849998 -13.300000 6.400000 +80.849998 -13.300000 5.913002 +84.050003 -13.300000 5.913002 +5.350000 13.450000 1.050000 +4.250000 13.450000 1.050000 +4.250000 12.700000 1.050000 +5.350000 12.700000 1.050000 +26.250000 13.450000 1.050000 +25.150000 13.450000 1.050000 +25.150000 12.700000 1.050000 +26.250000 12.700000 1.050000 +47.150002 13.450000 1.050000 +46.049999 13.450000 1.050000 +46.049999 12.700000 1.050000 +47.150002 12.700000 1.050000 +68.050003 13.450000 1.050000 +66.949997 13.450000 1.050000 +66.949997 12.700000 1.050000 +68.050003 12.700000 1.050000 +88.949997 13.450000 1.050000 +87.849998 13.450000 1.050000 +87.849998 12.700000 1.050000 +88.949997 12.700000 1.050000 +109.849998 13.450000 1.050000 +108.750000 13.450000 1.050000 +108.750000 12.700000 1.050000 +109.849998 12.700000 1.050000 +130.750000 12.700000 1.050000 +130.750000 13.450000 1.050000 +129.649994 13.450000 1.050000 +129.649994 12.700000 1.050000 +4.250000 13.881399 2.131400 +4.250000 13.450000 1.700000 +5.350000 13.450000 1.700000 +5.350000 13.881399 2.131400 +25.150000 13.881399 2.131400 +25.150000 13.450000 1.700000 +26.250000 13.450000 1.700000 +26.250000 13.881399 2.131400 +47.150002 13.881399 2.131400 +46.049999 13.881399 2.131400 +46.049999 13.450000 1.700000 +47.150002 13.450000 1.700000 +66.949997 13.881399 2.131400 +66.949997 13.450000 1.700000 +68.050003 13.450000 1.700000 +68.050003 13.881399 2.131400 +87.849998 13.881399 2.131400 +87.849998 13.450000 1.700000 +88.949997 13.450000 1.700000 +88.949997 13.881399 2.131400 +108.750000 13.881399 2.131400 +108.750000 13.450000 1.700000 +109.849998 13.450000 1.700000 +109.849998 13.881399 2.131400 +130.750000 13.881399 2.131400 +129.649994 13.881399 2.131400 +129.649994 13.450000 1.700000 +130.750000 13.450000 1.700000 +129.649994 -12.400000 7.750000 +147.385925 -2.806917 7.750000 +147.687531 -0.562527 7.750000 +147.399994 0.533016 7.750000 +147.688614 0.537489 7.750000 +108.750000 12.700000 7.750000 +101.949997 12.700000 7.750000 +135.000000 12.700000 7.750000 +130.750000 12.700000 7.750000 +130.750000 -12.400000 7.750000 +130.750000 -12.700000 7.750000 +106.449997 -12.700000 7.750000 +108.750000 -12.700000 7.750000 +108.750000 12.400000 7.750000 +101.949997 11.400000 7.750000 +109.849998 12.400000 7.750000 +106.449997 -11.400000 7.750000 +135.000000 -11.400000 7.750000 +108.750000 -12.400000 7.750000 +129.649994 12.700000 7.750000 +109.849998 12.700000 7.750000 +129.649994 12.400000 7.750000 +130.750000 12.400000 7.750000 +137.258026 12.497652 7.750000 +135.000000 11.400000 7.750000 +139.564606 11.851343 7.750000 +137.074371 11.209682 7.750000 +141.788712 10.733280 7.750000 +139.196274 10.599586 7.750000 +143.788177 9.168318 7.750000 +141.238190 9.541749 7.750000 +145.436356 7.236889 7.750000 +143.061020 8.061017 7.750000 +146.647537 5.062092 7.750000 +144.541748 6.238191 7.750000 +147.390884 2.784933 7.750000 +145.599594 4.196280 7.750000 +146.209686 2.074379 7.750000 +147.399994 -0.566984 7.750000 +146.399994 0.000000 7.750000 +146.209686 -2.074379 7.750000 +146.639740 -5.079992 7.750000 +145.599594 -4.196280 7.750000 +145.427155 -7.250141 7.750000 +144.541748 -6.238191 7.750000 +143.779114 -9.176985 7.750000 +143.061020 -8.061017 7.750000 +141.781174 -10.738050 7.750000 +141.238190 -9.541749 7.750000 +139.559448 -11.853333 7.750000 +137.255539 -12.498100 7.750000 +139.196274 -10.599586 7.750000 +135.000000 -12.700000 7.750000 +137.074371 -11.209682 7.750000 +109.849998 -12.700000 7.750000 +129.649994 -12.700000 7.750000 +109.849998 -12.400000 7.750000 +88.949997 12.400000 7.750000 +81.050003 11.400000 7.750000 +95.750000 11.400000 7.750000 +87.849998 12.700000 7.750000 +81.050003 12.700000 7.750000 +87.849998 12.400000 7.750000 +95.750000 12.700000 7.750000 +88.949997 12.700000 7.750000 +68.050003 12.400000 7.750000 +60.150002 11.400000 7.750000 +74.849998 11.400000 7.750000 +66.949997 12.700000 7.750000 +60.150002 12.700000 7.750000 +66.949997 12.400000 7.750000 +74.849998 12.700000 7.750000 +68.050003 12.700000 7.750000 +53.950001 12.700000 7.750000 +47.150002 12.700000 7.750000 +39.250000 12.700000 7.750000 +39.250000 11.400000 7.750000 +46.049999 12.400000 7.750000 +46.049999 12.700000 7.750000 +47.150002 12.400000 7.750000 +53.950001 11.400000 7.750000 +4.250000 -12.400000 7.750000 +-12.400000 -0.566984 7.750000 +-12.687535 -0.562527 7.750000 +-12.390890 2.784933 7.750000 +-12.688622 0.537489 7.750000 +25.150000 12.400000 7.750000 +25.150000 12.700000 7.750000 +5.350000 12.700000 7.750000 +4.250000 12.400000 7.750000 +4.250000 12.700000 7.750000 +33.049999 12.700000 7.750000 +26.250000 12.700000 7.750000 +33.049999 11.400000 7.750000 +0.000000 11.400000 7.750000 +26.250000 12.400000 7.750000 +5.350000 12.400000 7.750000 +0.000000 12.700000 7.750000 +-2.074379 11.209682 7.750000 +-2.258031 12.497652 7.750000 +-4.196280 10.599586 7.750000 +-4.564609 11.851343 7.750000 +-6.238191 9.541749 7.750000 +-6.788718 10.733280 7.750000 +-8.061017 8.061017 7.750000 +-8.788171 9.168318 7.750000 +-9.541749 6.238191 7.750000 +-10.436352 7.236889 7.750000 +-10.599586 4.196280 7.750000 +-11.647542 5.062092 7.750000 +-11.209682 2.074379 7.750000 +-11.400000 0.000000 7.750000 +-12.400000 0.533016 7.750000 +-11.209682 -2.074379 7.750000 +-10.599586 -4.196280 7.750000 +-12.385928 -2.806917 7.750000 +-9.541749 -6.238191 7.750000 +-11.639746 -5.079992 7.750000 +-8.061017 -8.061017 7.750000 +-10.427150 -7.250141 7.750000 +-6.238191 -9.541749 7.750000 +-8.779120 -9.176985 7.750000 +-4.196280 -10.599586 7.750000 +-6.781170 -10.738050 7.750000 +-4.559442 -11.853333 7.750000 +-2.074379 -11.209682 7.750000 +-2.255546 -12.498100 7.750000 +0.000000 -11.400000 7.750000 +26.250000 -12.700000 7.750000 +28.549999 -12.700000 7.750000 +26.250000 -12.400000 7.750000 +28.549999 -11.400000 7.750000 +25.150000 -12.400000 7.750000 +0.000000 -12.700000 7.750000 +4.250000 -12.700000 7.750000 +5.350000 -12.700000 7.750000 +25.150000 -12.700000 7.750000 +5.350000 -12.400000 7.750000 +75.949997 -12.400000 7.750000 +55.650002 -11.400000 7.750000 +55.650002 -12.700000 7.750000 +57.950001 -12.700000 7.750000 +79.349998 -11.400000 7.750000 +57.950001 -12.400000 7.750000 +77.050003 -12.700000 7.750000 +79.349998 -12.700000 7.750000 +77.050003 -12.400000 7.750000 +68.050003 -12.700000 7.750000 +75.949997 -12.700000 7.750000 +68.050003 -12.400000 7.750000 +59.049999 -12.700000 7.750000 +66.949997 -12.700000 7.750000 +59.049999 -12.400000 7.750000 +66.949997 -12.400000 7.750000 +96.849998 -12.400000 7.750000 +85.550003 -12.700000 7.750000 +87.849998 -12.700000 7.750000 +85.550003 -11.400000 7.750000 +100.250000 -11.400000 7.750000 +87.849998 -12.400000 7.750000 +97.949997 -12.700000 7.750000 +100.250000 -12.700000 7.750000 +97.949997 -12.400000 7.750000 +88.949997 -12.700000 7.750000 +96.849998 -12.700000 7.750000 +88.949997 -12.400000 7.750000 +37.049999 -12.400000 7.750000 +47.150002 -12.400000 7.750000 +47.150002 -12.700000 7.750000 +49.450001 -12.700000 7.750000 +49.450001 -11.400000 7.750000 +46.049999 -12.400000 7.750000 +38.150002 -12.700000 7.750000 +46.049999 -12.700000 7.750000 +34.750000 -11.400000 7.750000 +34.750000 -12.700000 7.750000 +37.049999 -12.700000 7.750000 +38.150002 -12.400000 7.750000 +37.099998 0.000000 2.000000 +36.595596 0.000000 2.504402 +23.514513 1.200155 2.504402 +23.404402 0.000000 2.504402 +22.900000 0.000000 2.000000 +23.018532 1.291938 2.000000 +23.867491 2.427805 2.504402 +23.398502 2.613472 2.000000 +24.479513 3.609176 2.504402 +24.057331 3.885189 2.000000 +25.336208 4.663792 2.504402 +24.979542 5.020458 2.000000 +26.390825 5.520486 2.504402 +27.572195 6.132510 2.504402 +26.114811 5.942668 2.000000 +27.386528 6.601497 2.000000 +28.799845 6.485487 2.504402 +28.708063 6.981468 2.000000 +30.000000 6.595598 2.504402 +31.200155 6.485487 2.504402 +30.000000 7.100000 2.000000 +31.291937 6.981468 2.000000 +32.427803 6.132510 2.504402 +32.613472 6.601497 2.000000 +33.609177 5.520486 2.504402 +33.885189 5.942668 2.000000 +34.663792 4.663792 2.504402 +35.020458 5.020458 2.000000 +35.520485 3.609176 2.504402 +35.942669 3.885189 2.000000 +36.132511 2.427805 2.504402 +36.601498 2.613472 2.000000 +36.485489 1.200155 2.504402 +36.981468 1.291938 2.000000 +62.099998 0.000000 2.000000 +61.595596 0.000000 2.504402 +48.514511 1.200155 2.504402 +48.404404 0.000000 2.504402 +47.900002 0.000000 2.000000 +48.018532 1.291938 2.000000 +48.867489 2.427805 2.504402 +48.398502 2.613472 2.000000 +49.479515 3.609176 2.504402 +49.057331 3.885189 2.000000 +50.336208 4.663792 2.504402 +49.979542 5.020458 2.000000 +51.390823 5.520486 2.504402 +52.572197 6.132510 2.504402 +51.114811 5.942668 2.000000 +52.386528 6.601497 2.000000 +53.799847 6.485487 2.504402 +53.708061 6.981468 2.000000 +55.000000 6.595598 2.504402 +56.200153 6.485487 2.504402 +55.000000 7.100000 2.000000 +56.291939 6.981468 2.000000 +57.427803 6.132510 2.504402 +57.613472 6.601497 2.000000 +58.609177 5.520486 2.504402 +58.885189 5.942668 2.000000 +59.663792 4.663792 2.504402 +60.020458 5.020458 2.000000 +60.520485 3.609176 2.504402 +60.942669 3.885189 2.000000 +61.132511 2.427805 2.504402 +61.601498 2.613472 2.000000 +61.485489 1.200155 2.504402 +61.981468 1.291938 2.000000 +112.099998 0.000000 2.000000 +111.595596 0.000000 2.504402 +98.514511 1.200155 2.504402 +98.404404 0.000000 2.504402 +97.900002 0.000000 2.000000 +98.018532 1.291938 2.000000 +98.867493 2.427805 2.504402 +98.398506 2.613472 2.000000 +99.479515 3.609176 2.504402 +99.057335 3.885189 2.000000 +100.336205 4.663792 2.504402 +99.979546 5.020458 2.000000 +101.390823 5.520486 2.504402 +102.572197 6.132510 2.504402 +101.114807 5.942668 2.000000 +102.386528 6.601497 2.000000 +103.799843 6.485487 2.504402 +103.708061 6.981468 2.000000 +105.000000 6.595598 2.504402 +106.200157 6.485487 2.504402 +105.000000 7.100000 2.000000 +106.291939 6.981468 2.000000 +107.427803 6.132510 2.504402 +107.613472 6.601497 2.000000 +108.609177 5.520486 2.504402 +108.885193 5.942668 2.000000 +109.663795 4.663792 2.504402 +110.020454 5.020458 2.000000 +110.520485 3.609176 2.504402 +110.942665 3.885189 2.000000 +111.132507 2.427805 2.504402 +111.601494 2.613472 2.000000 +111.485489 1.200155 2.504402 +111.981468 1.291938 2.000000 +90.356499 -3.456497 2.000000 +90.129311 -4.509340 2.302641 +90.102638 -4.800000 2.302641 +89.800003 -4.800000 2.000000 +90.214798 -4.212021 2.302641 +89.831718 -4.454270 2.000000 +90.363014 -3.925910 2.302641 +89.933403 -4.100620 2.000000 +90.109711 -3.760301 2.000000 +90.570496 -3.670497 2.302641 +93.568283 -4.454270 2.000000 +93.599998 -4.800000 2.000000 +93.297356 -4.800000 2.302641 +93.270691 -4.509340 2.302641 +93.466599 -4.100620 2.000000 +93.185204 -4.212021 2.302641 +93.290291 -3.760301 2.000000 +93.036980 -3.925910 2.302641 +93.043503 -3.456497 2.000000 +92.829506 -3.670497 2.302641 +92.739700 -3.209708 2.000000 +92.574089 -3.463018 2.302641 +92.399384 -3.033402 2.000000 +92.287979 -3.314794 2.302641 +92.045731 -2.931720 2.000000 +91.990662 -3.229308 2.302641 +91.699997 -2.900000 2.000000 +91.699997 -3.202641 2.302641 +91.354271 -2.931720 2.000000 +91.409340 -3.229308 2.302641 +91.000618 -3.033402 2.000000 +90.660301 -3.209708 2.000000 +91.112022 -3.314794 2.302641 +90.825912 -3.463018 2.302641 +93.599998 4.800000 2.000000 +93.302597 4.800000 2.297405 +90.097404 4.800000 2.297405 +89.800003 4.800000 2.000000 +90.124161 5.091613 2.297405 +90.209923 5.389907 2.297405 +89.831718 5.145730 2.000000 +90.358635 5.676956 2.297405 +89.933403 5.499380 2.000000 +90.109711 5.839698 2.000000 +90.566795 5.933206 2.297405 +90.356499 6.143503 2.000000 +90.823044 6.141365 2.297405 +91.110092 6.290074 2.297405 +90.660301 6.390292 2.000000 +91.000618 6.566598 2.000000 +91.408386 6.375841 2.297405 +91.354271 6.668280 2.000000 +91.699997 6.402596 2.297405 +91.991615 6.375841 2.297405 +91.699997 6.700000 2.000000 +92.045731 6.668280 2.000000 +92.289909 6.290074 2.297405 +92.399384 6.566598 2.000000 +92.576958 6.141365 2.297405 +92.739700 6.390292 2.000000 +92.833206 5.933206 2.297405 +93.043503 6.143503 2.000000 +93.041367 5.676956 2.297405 +93.290291 5.839698 2.000000 +93.190071 5.389907 2.297405 +93.466599 5.499380 2.000000 +93.275841 5.091613 2.297405 +93.568283 5.145730 2.000000 +89.864220 4.800000 6.100000 +90.065979 4.800000 5.898239 +93.306740 5.097331 5.898239 +93.334023 4.800000 5.898239 +93.535782 4.800000 6.100000 +93.505135 5.134044 6.100000 +93.219292 5.401474 5.898239 +93.406883 5.475741 6.100000 +93.067665 5.694151 5.898239 +93.236542 5.804557 6.100000 +92.855423 5.955426 5.898239 +92.594154 6.167667 5.898239 +92.998093 6.098093 6.100000 +92.704559 6.336540 6.100000 +92.301476 6.319292 5.898239 +92.375740 6.506887 6.100000 +91.997330 6.406740 5.898239 +92.034042 6.605133 6.100000 +91.699997 6.434020 5.898239 +91.402672 6.406740 5.898239 +91.699997 6.635780 6.100000 +91.098526 6.319292 5.898239 +91.365959 6.605133 6.100000 +91.024261 6.506887 6.100000 +90.805847 6.167667 5.898239 +90.544571 5.955426 5.898239 +90.695442 6.336540 6.100000 +90.401909 6.098093 6.100000 +90.332336 5.694151 5.898239 +90.163460 5.804557 6.100000 +90.180710 5.401474 5.898239 +89.993111 5.475741 6.100000 +90.093262 5.097331 5.898239 +89.894867 5.134044 6.100000 +94.099998 4.800000 5.900000 +93.900002 4.800000 6.100000 +89.500000 4.800000 6.100000 +89.300003 4.800000 5.900000 +89.536728 4.399681 6.100000 +89.340065 4.363289 5.900000 +89.654465 3.990192 6.100000 +89.468506 3.916573 5.900000 +89.858612 3.596138 6.100000 +89.691208 3.486696 5.900000 +90.144363 3.244365 6.100000 +90.002945 3.102944 5.900000 +90.496140 2.958610 6.100000 +90.386696 2.791211 5.900000 +90.890190 2.754466 6.100000 +90.816574 2.568508 5.900000 +91.299683 2.636728 6.100000 +91.263290 2.440067 5.900000 +91.699997 2.600000 6.100000 +91.699997 2.400000 5.900000 +92.100319 2.636728 6.100000 +92.136711 2.440067 5.900000 +92.509811 2.754466 6.100000 +92.583427 2.568508 5.900000 +92.903862 2.958610 6.100000 +93.013306 2.791211 5.900000 +93.255638 3.244365 6.100000 +93.397057 3.102944 5.900000 +93.541389 3.596138 6.100000 +93.708786 3.486696 5.900000 +93.745537 3.990192 6.100000 +93.931496 3.916573 5.900000 +93.863274 4.399681 6.100000 +94.059937 4.363289 5.900000 +94.207428 -4.335994 3.600000 +94.250000 -4.800000 3.600000 +88.995911 -4.299602 3.800000 +88.949997 -4.800000 3.800000 +89.150002 -4.800000 3.600000 +89.192574 -4.335994 3.600000 +89.143082 -3.787740 3.800000 +89.329041 -3.861358 3.600000 +89.398262 -3.295173 3.800000 +89.565659 -3.404615 3.600000 +89.755455 -2.855456 3.800000 +89.896881 -2.996878 3.600000 +90.195175 -2.498262 3.800000 +90.304619 -2.665661 3.600000 +90.687737 -2.243082 3.800000 +90.761360 -2.429040 3.600000 +91.199600 -2.095910 3.800000 +91.235992 -2.292571 3.600000 +91.699997 -2.050000 3.800000 +92.200401 -2.095910 3.800000 +91.699997 -2.250000 3.600000 +92.712257 -2.243082 3.800000 +92.164009 -2.292571 3.600000 +93.204826 -2.498262 3.800000 +92.638641 -2.429040 3.600000 +93.095383 -2.665661 3.600000 +93.644547 -2.855456 3.800000 +93.503120 -2.996878 3.600000 +94.001740 -3.295173 3.800000 +93.834335 -3.404615 3.600000 +94.256920 -3.787740 3.800000 +94.404091 -4.299602 3.800000 +94.070961 -3.861358 3.600000 +94.449997 -4.800000 3.800000 +97.250000 0.000000 3.800000 +97.449997 0.000000 3.600000 +112.423958 1.373821 3.600000 +112.550003 0.000000 3.600000 +112.750000 0.000000 3.800000 +112.620613 1.410214 3.800000 +112.019905 2.779115 3.600000 +112.205856 2.852734 3.800000 +111.319313 4.131433 3.600000 +111.486717 4.240876 3.800000 +110.338654 5.338656 3.600000 +110.480080 5.480078 3.800000 +109.131432 6.319316 3.600000 +109.240875 6.486715 3.800000 +107.779114 7.019902 3.600000 +107.852737 7.205859 3.800000 +106.373817 7.423955 3.600000 +106.410217 7.620616 3.800000 +105.000000 7.550000 3.600000 +105.000000 7.750000 3.800000 +103.626183 7.423955 3.600000 +102.220886 7.019902 3.600000 +103.589783 7.620616 3.800000 +102.147263 7.205859 3.800000 +100.868568 6.319316 3.600000 +100.759125 6.486715 3.800000 +99.661346 5.338656 3.600000 +99.519920 5.480078 3.800000 +98.680687 4.131433 3.600000 +98.513283 4.240876 3.800000 +97.980095 2.779115 3.600000 +97.794144 2.852734 3.800000 +97.576042 1.373821 3.600000 +97.379387 1.410214 3.800000 +47.250000 0.000000 3.800000 +47.450001 0.000000 3.600000 +62.423954 1.373821 3.600000 +62.549999 0.000000 3.600000 +62.750000 0.000000 3.800000 +62.620617 1.410214 3.800000 +62.019901 2.779115 3.600000 +62.205860 2.852734 3.800000 +61.319317 4.131433 3.600000 +61.486713 4.240876 3.800000 +60.338657 5.338656 3.600000 +60.480076 5.480078 3.800000 +59.131435 6.319316 3.600000 +59.240875 6.486715 3.800000 +57.779114 7.019902 3.600000 +57.852734 7.205859 3.800000 +56.373821 7.423955 3.600000 +56.410213 7.620616 3.800000 +55.000000 7.550000 3.600000 +55.000000 7.750000 3.800000 +53.626179 7.423955 3.600000 +52.220886 7.019902 3.600000 +53.589787 7.620616 3.800000 +52.147266 7.205859 3.800000 +50.868565 6.319316 3.600000 +50.759125 6.486715 3.800000 +49.661343 5.338656 3.600000 +49.519924 5.480078 3.800000 +48.680683 4.131433 3.600000 +48.513287 4.240876 3.800000 +47.980099 2.779115 3.600000 +47.794140 2.852734 3.800000 +47.576046 1.373821 3.600000 +47.379383 1.410214 3.800000 +22.250000 0.000000 3.800000 +22.450001 0.000000 3.600000 +37.423954 1.373821 3.600000 +37.549999 0.000000 3.600000 +37.750000 0.000000 3.800000 +37.620617 1.410214 3.800000 +37.019901 2.779115 3.600000 +37.205860 2.852734 3.800000 +36.319317 4.131433 3.600000 +36.486713 4.240876 3.800000 +35.338657 5.338656 3.600000 +35.480076 5.480078 3.800000 +34.131435 6.319316 3.600000 +32.779114 7.019902 3.600000 +34.240875 6.486715 3.800000 +32.852734 7.205859 3.800000 +31.373821 7.423955 3.600000 +31.410213 7.620616 3.800000 +30.000000 7.550000 3.600000 +28.626179 7.423955 3.600000 +30.000000 7.750000 3.800000 +28.589787 7.620616 3.800000 +27.220884 7.019902 3.600000 +27.147266 7.205859 3.800000 +25.868567 6.319316 3.600000 +25.759125 6.486715 3.800000 +24.661345 5.338656 3.600000 +24.519922 5.480078 3.800000 +23.680683 4.131433 3.600000 +23.513285 4.240876 3.800000 +22.980099 2.779115 3.600000 +22.794140 2.852734 3.800000 +22.576044 1.373821 3.600000 +22.379383 1.410214 3.800000 +-12.400000 -0.566984 1.350000 +-12.400000 0.548516 1.350000 +-12.638527 0.548516 1.056366 +-12.700000 0.548516 1.050000 +-12.700000 -0.566984 1.050000 +-12.580847 0.548516 1.074677 +-12.638527 -0.566984 1.056366 +-12.580847 -0.566984 1.074677 +-12.530009 0.548516 1.102809 +-12.530009 -0.566984 1.102809 +-12.487868 0.548516 1.137868 +-12.487868 -0.566984 1.137868 +-12.452809 0.548516 1.180010 +-12.452809 -0.566984 1.180010 +-12.424678 0.548516 1.230847 +-12.424678 -0.566984 1.230847 +-12.406365 0.548516 1.288527 +-12.406365 -0.566984 1.288527 +97.949997 -12.589572 1.071064 +96.849998 -12.645411 1.055008 +96.849998 -12.700000 1.050000 +97.949997 -12.700000 1.050000 +97.949997 -12.645411 1.055008 +96.849998 -12.589572 1.071064 +97.949997 -12.400000 1.350000 +96.849998 -12.400000 1.350000 +97.949997 -12.405008 1.295411 +96.849998 -12.405008 1.295411 +97.949997 -12.421063 1.239572 +96.849998 -12.421063 1.239572 +97.949997 -12.448901 1.185837 +96.849998 -12.448901 1.185837 +97.949997 -12.487868 1.137868 +96.849998 -12.487868 1.137868 +97.949997 -12.535837 1.098901 +96.849998 -12.535837 1.098901 +77.050003 -12.406365 1.288527 +77.050003 -12.400000 1.350000 +75.949997 -12.700000 1.050000 +77.050003 -12.700000 1.050000 +75.949997 -12.638527 1.056366 +75.949997 -12.580847 1.074677 +77.050003 -12.638527 1.056366 +75.949997 -12.530009 1.102809 +77.050003 -12.580847 1.074677 +77.050003 -12.530009 1.102809 +75.949997 -12.487868 1.137868 +75.949997 -12.452809 1.180010 +77.050003 -12.487868 1.137868 +77.050003 -12.452809 1.180010 +75.949997 -12.424678 1.230847 +75.949997 -12.406365 1.288527 +77.050003 -12.424678 1.230847 +75.949997 -12.400000 1.350000 +59.049999 -12.406365 1.288527 +59.049999 -12.400000 1.350000 +57.950001 -12.638527 1.056366 +57.950001 -12.700000 1.050000 +59.049999 -12.700000 1.050000 +59.049999 -12.638527 1.056366 +57.950001 -12.580847 1.074677 +59.049999 -12.580847 1.074677 +57.950001 -12.530009 1.102809 +59.049999 -12.530009 1.102809 +57.950001 -12.487868 1.137868 +59.049999 -12.487868 1.137868 +57.950001 -12.452809 1.180010 +59.049999 -12.452809 1.180010 +57.950001 -12.424678 1.230847 +57.950001 -12.406365 1.288527 +59.049999 -12.424678 1.230847 +57.950001 -12.400000 1.350000 +37.049999 -12.638527 1.056366 +37.049999 -12.700000 1.050000 +38.150002 -12.400000 1.350000 +37.049999 -12.400000 1.350000 +38.150002 -12.406365 1.288527 +38.150002 -12.424678 1.230847 +37.049999 -12.406365 1.288527 +38.150002 -12.452809 1.180010 +37.049999 -12.424678 1.230847 +37.049999 -12.452809 1.180010 +38.150002 -12.487868 1.137868 +38.150002 -12.530009 1.102809 +37.049999 -12.487868 1.137868 +38.150002 -12.580847 1.074677 +37.049999 -12.530009 1.102809 +37.049999 -12.580847 1.074677 +38.150002 -12.638527 1.056366 +38.150002 -12.700000 1.050000 +147.448898 0.548516 1.185837 +147.399994 0.548516 1.350000 +147.399994 -0.566984 1.350000 +147.405014 0.548516 1.295411 +147.405014 -0.566984 1.295411 +147.421066 0.548516 1.239572 +147.645416 -0.566984 1.055008 +147.699997 -0.566984 1.050000 +147.699997 0.548516 1.050000 +147.645416 0.548516 1.055008 +147.589569 -0.566984 1.071064 +147.589569 0.548516 1.071064 +147.535843 -0.566984 1.098901 +147.487869 -0.566984 1.137868 +147.535843 0.548516 1.098901 +147.448898 -0.566984 1.185837 +147.487869 0.548516 1.137868 +147.421066 -0.566984 1.239572 +4.250000 12.400000 1.350000 +5.350000 12.400000 1.350000 +5.350000 12.700000 1.050000 +4.250000 12.700000 1.050000 +5.350000 12.638527 1.056366 +4.250000 12.638527 1.056366 +5.350000 12.580847 1.074677 +5.350000 12.530009 1.102809 +4.250000 12.580847 1.074677 +4.250000 12.530009 1.102809 +5.350000 12.487868 1.137868 +5.350000 12.452809 1.180010 +4.250000 12.487868 1.137868 +5.350000 12.424678 1.230847 +4.250000 12.452809 1.180010 +4.250000 12.424678 1.230847 +5.350000 12.406365 1.288527 +4.250000 12.406365 1.288527 +25.150000 12.406365 1.288527 +25.150000 12.400000 1.350000 +26.250000 12.638527 1.056366 +26.250000 12.700000 1.050000 +25.150000 12.700000 1.050000 +25.150000 12.638527 1.056366 +26.250000 12.580847 1.074677 +26.250000 12.530009 1.102809 +25.150000 12.580847 1.074677 +26.250000 12.487868 1.137868 +25.150000 12.530009 1.102809 +26.250000 12.452809 1.180010 +25.150000 12.487868 1.137868 +25.150000 12.452809 1.180010 +26.250000 12.424678 1.230847 +25.150000 12.424678 1.230847 +26.250000 12.406365 1.288527 +26.250000 12.400000 1.350000 +47.150002 12.700000 1.050000 +46.049999 12.700000 1.050000 +46.049999 12.406365 1.288527 +46.049999 12.400000 1.350000 +47.150002 12.400000 1.350000 +46.049999 12.424678 1.230847 +47.150002 12.406365 1.288527 +46.049999 12.452809 1.180010 +47.150002 12.424678 1.230847 +46.049999 12.487868 1.137868 +47.150002 12.452809 1.180010 +46.049999 12.530009 1.102809 +47.150002 12.487868 1.137868 +47.150002 12.530009 1.102809 +46.049999 12.580847 1.074677 +47.150002 12.580847 1.074677 +46.049999 12.638527 1.056366 +47.150002 12.638527 1.056366 +68.050003 12.700000 1.050000 +66.949997 12.700000 1.050000 +66.949997 12.406365 1.288527 +66.949997 12.400000 1.350000 +68.050003 12.400000 1.350000 +68.050003 12.406365 1.288527 +66.949997 12.424678 1.230847 +66.949997 12.452809 1.180010 +68.050003 12.424678 1.230847 +68.050003 12.452809 1.180010 +66.949997 12.487868 1.137868 +66.949997 12.530009 1.102809 +68.050003 12.487868 1.137868 +66.949997 12.580847 1.074677 +68.050003 12.530009 1.102809 +68.050003 12.580847 1.074677 +66.949997 12.638527 1.056366 +68.050003 12.638527 1.056366 +87.849998 12.400000 1.350000 +88.949997 12.400000 1.350000 +88.949997 12.638527 1.056366 +88.949997 12.700000 1.050000 +87.849998 12.700000 1.050000 +88.949997 12.580847 1.074677 +87.849998 12.638527 1.056366 +87.849998 12.580847 1.074677 +88.949997 12.530009 1.102809 +87.849998 12.530009 1.102809 +88.949997 12.487868 1.137868 +88.949997 12.452809 1.180010 +87.849998 12.487868 1.137868 +87.849998 12.452809 1.180010 +88.949997 12.424678 1.230847 +88.949997 12.406365 1.288527 +87.849998 12.424678 1.230847 +87.849998 12.406365 1.288527 +108.750000 12.405008 1.295411 +108.750000 12.400000 1.350000 +109.849998 12.645411 1.055008 +109.849998 12.700000 1.050000 +108.750000 12.700000 1.050000 +109.849998 12.589572 1.071064 +108.750000 12.645411 1.055008 +109.849998 12.535837 1.098901 +108.750000 12.589572 1.071064 +109.849998 12.487868 1.137868 +108.750000 12.535837 1.098901 +109.849998 12.448901 1.185837 +108.750000 12.487868 1.137868 +109.849998 12.421063 1.239572 +108.750000 12.448901 1.185837 +108.750000 12.421063 1.239572 +109.849998 12.405008 1.295411 +109.849998 12.400000 1.350000 +129.649994 12.405008 1.295411 +129.649994 12.400000 1.350000 +130.750000 12.645411 1.055008 +130.750000 12.700000 1.050000 +129.649994 12.700000 1.050000 +130.750000 12.589572 1.071064 +129.649994 12.645411 1.055008 +130.750000 12.535837 1.098901 +129.649994 12.589572 1.071064 +130.750000 12.487868 1.137868 +129.649994 12.535837 1.098901 +130.750000 12.448901 1.185837 +129.649994 12.487868 1.137868 +130.750000 12.421063 1.239572 +129.649994 12.448901 1.185837 +130.750000 12.405008 1.295411 +129.649994 12.421063 1.239572 +130.750000 12.400000 1.350000 +129.649994 -12.700000 1.050000 +130.750000 -12.700000 1.050000 +130.750000 -12.400000 1.350000 +129.649994 -12.400000 1.350000 +130.750000 -12.405008 1.295411 +129.649994 -12.405008 1.295411 +130.750000 -12.421063 1.239572 +130.750000 -12.448901 1.185837 +129.649994 -12.421063 1.239572 +129.649994 -12.448901 1.185837 +130.750000 -12.487868 1.137868 +129.649994 -12.487868 1.137868 +130.750000 -12.535837 1.098901 +129.649994 -12.535837 1.098901 +130.750000 -12.589572 1.071064 +129.649994 -12.589572 1.071064 +130.750000 -12.645411 1.055008 +129.649994 -12.645411 1.055008 +108.750000 -12.645411 1.055008 +108.750000 -12.700000 1.050000 +109.849998 -12.405008 1.295411 +109.849998 -12.400000 1.350000 +108.750000 -12.400000 1.350000 +109.849998 -12.421063 1.239572 +108.750000 -12.405008 1.295411 +109.849998 -12.448901 1.185837 +108.750000 -12.421063 1.239572 +109.849998 -12.487868 1.137868 +108.750000 -12.448901 1.185837 +109.849998 -12.535837 1.098901 +108.750000 -12.487868 1.137868 +109.849998 -12.589572 1.071064 +108.750000 -12.535837 1.098901 +108.750000 -12.589572 1.071064 +109.849998 -12.645411 1.055008 +109.849998 -12.700000 1.050000 +87.849998 -12.700000 1.050000 +88.949997 -12.700000 1.050000 +88.949997 -12.406365 1.288527 +88.949997 -12.400000 1.350000 +87.849998 -12.400000 1.350000 +88.949997 -12.424678 1.230847 +87.849998 -12.406365 1.288527 +88.949997 -12.452809 1.180010 +87.849998 -12.424678 1.230847 +87.849998 -12.452809 1.180010 +88.949997 -12.487868 1.137868 +87.849998 -12.487868 1.137868 +88.949997 -12.530009 1.102809 +88.949997 -12.580847 1.074677 +87.849998 -12.530009 1.102809 +88.949997 -12.638527 1.056366 +87.849998 -12.580847 1.074677 +87.849998 -12.638527 1.056366 +66.949997 -12.700000 1.050000 +68.050003 -12.700000 1.050000 +68.050003 -12.406365 1.288527 +68.050003 -12.400000 1.350000 +66.949997 -12.400000 1.350000 +66.949997 -12.406365 1.288527 +68.050003 -12.424678 1.230847 +66.949997 -12.424678 1.230847 +68.050003 -12.452809 1.180010 +66.949997 -12.452809 1.180010 +68.050003 -12.487868 1.137868 +66.949997 -12.487868 1.137868 +68.050003 -12.530009 1.102809 +68.050003 -12.580847 1.074677 +66.949997 -12.530009 1.102809 +68.050003 -12.638527 1.056366 +66.949997 -12.580847 1.074677 +66.949997 -12.638527 1.056366 +46.049999 -12.700000 1.050000 +47.150002 -12.700000 1.050000 +47.150002 -12.400000 1.350000 +46.049999 -12.400000 1.350000 +47.150002 -12.406365 1.288527 +47.150002 -12.424678 1.230847 +46.049999 -12.406365 1.288527 +47.150002 -12.452809 1.180010 +46.049999 -12.424678 1.230847 +46.049999 -12.452809 1.180010 +47.150002 -12.487868 1.137868 +46.049999 -12.487868 1.137868 +47.150002 -12.530009 1.102809 +47.150002 -12.580847 1.074677 +46.049999 -12.530009 1.102809 +46.049999 -12.580847 1.074677 +47.150002 -12.638527 1.056366 +46.049999 -12.638527 1.056366 +26.250000 -12.452809 1.180010 +26.250000 -12.400000 1.350000 +25.150000 -12.400000 1.350000 +26.250000 -12.406365 1.288527 +25.150000 -12.406365 1.288527 +26.250000 -12.424678 1.230847 +25.150000 -12.700000 1.050000 +26.250000 -12.700000 1.050000 +25.150000 -12.638527 1.056366 +26.250000 -12.638527 1.056366 +25.150000 -12.580847 1.074677 +25.150000 -12.530009 1.102809 +26.250000 -12.580847 1.074677 +25.150000 -12.487868 1.137868 +26.250000 -12.530009 1.102809 +25.150000 -12.452809 1.180010 +26.250000 -12.487868 1.137868 +25.150000 -12.424678 1.230847 +4.250000 -12.638527 1.056366 +4.250000 -12.700000 1.050000 +5.350000 -12.400000 1.350000 +4.250000 -12.400000 1.350000 +5.350000 -12.406365 1.288527 +4.250000 -12.406365 1.288527 +5.350000 -12.424678 1.230847 +5.350000 -12.452809 1.180010 +4.250000 -12.424678 1.230847 +4.250000 -12.452809 1.180010 +5.350000 -12.487868 1.137868 +5.350000 -12.530009 1.102809 +4.250000 -12.487868 1.137868 +5.350000 -12.580847 1.074677 +4.250000 -12.530009 1.102809 +5.350000 -12.638527 1.056366 +4.250000 -12.580847 1.074677 +5.350000 -12.700000 1.050000 +50.950001 -13.300000 6.400000 +54.150002 -13.300000 6.400000 +54.150002 -12.300000 7.000000 +50.950001 -12.300000 7.000000 +30.049999 -13.300000 6.400000 +33.250000 -13.300000 6.400000 +33.250000 -12.300000 7.000000 +30.049999 -12.300000 7.000000 +58.650002 13.300000 6.400000 +55.450001 13.300000 6.400000 +55.450001 12.300000 7.000000 +58.650002 12.300000 7.000000 +37.750000 13.300000 6.400000 +34.549999 13.300000 6.400000 +34.549999 12.300000 7.000000 +37.750000 12.300000 7.000000 +104.949997 -13.300000 6.400000 +104.949997 -12.300000 7.000000 +101.750000 -12.300000 7.000000 +101.750000 -13.300000 6.400000 +84.050003 -13.300000 6.400000 +84.050003 -12.300000 7.000000 +80.849998 -12.300000 7.000000 +80.849998 -13.300000 6.400000 +76.349998 13.300000 6.400000 +76.349998 12.300000 7.000000 +79.550003 12.300000 7.000000 +79.550003 13.300000 6.400000 +97.250000 13.300000 6.400000 +97.250000 12.300000 7.000000 +100.449997 12.300000 7.000000 +100.449997 13.300000 6.400000 +54.150002 -13.000000 5.800000 +54.150002 -13.300000 5.913002 +50.950001 -13.300000 5.913002 +50.950001 -13.000000 5.800000 +33.250000 -13.000000 5.800000 +33.250000 -13.300000 5.913002 +30.049999 -13.300000 5.913002 +30.049999 -13.000000 5.800000 +55.450001 13.300000 5.913002 +58.650002 13.300000 5.913002 +58.650002 13.000000 5.800000 +55.450001 13.000000 5.800000 +34.549999 13.300000 5.913002 +37.750000 13.300000 5.913002 +37.750000 13.000000 5.800000 +34.549999 13.000000 5.800000 +104.949997 -13.300000 5.913002 +101.750000 -13.300000 5.913002 +101.750000 -13.000000 5.800000 +104.949997 -13.000000 5.800000 +80.849998 -13.300000 5.913002 +80.849998 -13.000000 5.800000 +84.050003 -13.000000 5.800000 +84.050003 -13.300000 5.913002 +79.550003 13.300000 5.913002 +79.550003 13.000000 5.800000 +76.349998 13.000000 5.800000 +76.349998 13.300000 5.913002 +100.449997 13.300000 5.913002 +100.449997 13.000000 5.800000 +97.250000 13.000000 5.800000 +97.250000 13.300000 5.913002 +101.250000 -11.400000 3.350000 +101.250000 -12.700000 3.350000 +101.739388 -12.700000 3.747545 +101.750000 -12.700000 3.850000 +101.750000 -11.400000 3.850000 +101.739388 -11.400000 3.747545 +101.708870 -12.700000 3.651411 +101.661987 -12.700000 3.566683 +101.708870 -11.400000 3.651411 +101.661987 -11.400000 3.566683 +101.603554 -12.700000 3.496447 +101.533318 -12.700000 3.438015 +101.603554 -11.400000 3.496447 +101.448586 -12.700000 3.391129 +101.533318 -11.400000 3.438015 +101.448586 -11.400000 3.391129 +101.352455 -12.700000 3.360610 +101.352455 -11.400000 3.360610 +80.452454 -12.700000 3.360610 +80.839394 -12.700000 3.747545 +80.849998 -12.700000 3.850000 +80.849998 -11.400000 3.850000 +80.839394 -11.400000 3.747545 +80.808868 -12.700000 3.651411 +80.761986 -12.700000 3.566683 +80.808868 -11.400000 3.651411 +80.761986 -11.400000 3.566683 +80.703552 -12.700000 3.496447 +80.633316 -12.700000 3.438015 +80.703552 -11.400000 3.496447 +80.633316 -11.400000 3.438015 +80.548592 -12.700000 3.391129 +80.349998 -11.400000 3.350000 +80.349998 -12.700000 3.350000 +80.452454 -11.400000 3.360610 +80.548592 -11.400000 3.391129 +54.150002 -11.400000 3.850000 +54.150002 -12.700000 3.850000 +54.650002 -12.700000 3.350000 +54.650002 -11.400000 3.350000 +54.547546 -12.700000 3.360610 +54.547546 -11.400000 3.360610 +54.451412 -12.700000 3.391129 +54.366684 -12.700000 3.438015 +54.451412 -11.400000 3.391129 +54.296448 -12.700000 3.496447 +54.366684 -11.400000 3.438015 +54.238014 -12.700000 3.566683 +54.296448 -11.400000 3.496447 +54.238014 -11.400000 3.566683 +54.191128 -12.700000 3.651411 +54.191128 -11.400000 3.651411 +54.160610 -12.700000 3.747545 +54.160610 -11.400000 3.747545 +33.250000 -11.400000 3.850000 +33.250000 -12.700000 3.850000 +33.647545 -12.700000 3.360610 +33.750000 -12.700000 3.350000 +33.750000 -11.400000 3.350000 +33.647545 -11.400000 3.360610 +33.551411 -12.700000 3.391129 +33.466682 -12.700000 3.438015 +33.551411 -11.400000 3.391129 +33.466682 -11.400000 3.438015 +33.396446 -12.700000 3.496447 +33.338017 -12.700000 3.566683 +33.396446 -11.400000 3.496447 +33.338017 -11.400000 3.566683 +33.291130 -12.700000 3.651411 +33.291130 -11.400000 3.651411 +33.260609 -12.700000 3.747545 +33.260609 -11.400000 3.747545 +34.152454 12.700000 3.360610 +34.049999 12.700000 3.350000 +34.549999 11.400000 3.850000 +34.549999 12.700000 3.850000 +34.539391 11.400000 3.747545 +34.539391 12.700000 3.747545 +34.508869 11.400000 3.651411 +34.508869 12.700000 3.651411 +34.461983 11.400000 3.566683 +34.403553 11.400000 3.496447 +34.461983 12.700000 3.566683 +34.403553 12.700000 3.496447 +34.333317 11.400000 3.438015 +34.333317 12.700000 3.438015 +34.248589 11.400000 3.391129 +34.248589 12.700000 3.391129 +34.152454 11.400000 3.360610 +34.049999 11.400000 3.350000 +54.950001 12.700000 3.350000 +54.950001 11.400000 3.350000 +55.450001 11.400000 3.850000 +55.450001 12.700000 3.850000 +55.439392 11.400000 3.747545 +55.439392 12.700000 3.747545 +55.408871 11.400000 3.651411 +55.408871 12.700000 3.651411 +55.361984 11.400000 3.566683 +55.361984 12.700000 3.566683 +55.303555 11.400000 3.496447 +55.303555 12.700000 3.496447 +55.233318 11.400000 3.438015 +55.148590 11.400000 3.391129 +55.233318 12.700000 3.438015 +55.148590 12.700000 3.391129 +55.052456 11.400000 3.360610 +55.052456 12.700000 3.360610 +79.947548 11.400000 3.360610 +80.050003 11.400000 3.350000 +79.560608 12.700000 3.747545 +79.550003 12.700000 3.850000 +79.550003 11.400000 3.850000 +79.591125 12.700000 3.651411 +79.560608 11.400000 3.747545 +79.591125 11.400000 3.651411 +79.638016 12.700000 3.566683 +79.638016 11.400000 3.566683 +79.696449 12.700000 3.496447 +79.766685 12.700000 3.438015 +79.696449 11.400000 3.496447 +79.766685 11.400000 3.438015 +79.851410 12.700000 3.391129 +79.851410 11.400000 3.391129 +79.947548 12.700000 3.360610 +80.050003 12.700000 3.350000 +100.460609 11.400000 3.747545 +100.460609 12.700000 3.747545 +100.449997 12.700000 3.850000 +100.449997 11.400000 3.850000 +100.949997 11.400000 3.350000 +100.949997 12.700000 3.350000 +100.847542 11.400000 3.360610 +100.847542 12.700000 3.360610 +100.751411 11.400000 3.391129 +100.666679 11.400000 3.438015 +100.751411 12.700000 3.391129 +100.666679 12.700000 3.438015 +100.596443 11.400000 3.496447 +100.596443 12.700000 3.496447 +100.538017 11.400000 3.566683 +100.491127 11.400000 3.651411 +100.538017 12.700000 3.566683 +100.491127 12.700000 3.651411 +55.639389 -12.700000 3.747545 +55.650002 -12.700000 3.850000 +55.252453 -11.400000 3.360610 +55.150002 -11.400000 3.350000 +55.150002 -12.700000 3.350000 +55.348587 -11.400000 3.391129 +55.252453 -12.700000 3.360610 +55.348587 -12.700000 3.391129 +55.433319 -11.400000 3.438015 +55.503555 -11.400000 3.496447 +55.433319 -12.700000 3.438015 +55.503555 -12.700000 3.496447 +55.561985 -11.400000 3.566683 +55.608871 -11.400000 3.651411 +55.561985 -12.700000 3.566683 +55.608871 -12.700000 3.651411 +55.639389 -11.400000 3.747545 +55.650002 -11.400000 3.850000 +50.552456 -11.400000 3.360610 +50.450001 -11.400000 3.350000 +50.939392 -12.700000 3.747545 +50.950001 -12.700000 3.850000 +50.950001 -11.400000 3.850000 +50.939392 -11.400000 3.747545 +50.908871 -12.700000 3.651411 +50.861984 -12.700000 3.566683 +50.908871 -11.400000 3.651411 +50.861984 -11.400000 3.566683 +50.803555 -12.700000 3.496447 +50.733318 -12.700000 3.438015 +50.803555 -11.400000 3.496447 +50.648590 -12.700000 3.391129 +50.733318 -11.400000 3.438015 +50.648590 -11.400000 3.391129 +50.552456 -12.700000 3.360610 +50.450001 -12.700000 3.350000 +49.450001 -11.400000 3.850000 +49.450001 -12.700000 3.850000 +49.847546 -12.700000 3.360610 +49.950001 -12.700000 3.350000 +49.950001 -11.400000 3.350000 +49.847546 -11.400000 3.360610 +49.751411 -12.700000 3.391129 +49.666683 -12.700000 3.438015 +49.751411 -11.400000 3.391129 +49.596447 -12.700000 3.496447 +49.666683 -11.400000 3.438015 +49.538017 -12.700000 3.566683 +49.596447 -11.400000 3.496447 +49.491131 -12.700000 3.651411 +49.538017 -11.400000 3.566683 +49.491131 -11.400000 3.651411 +49.460609 -12.700000 3.747545 +49.460609 -11.400000 3.747545 +79.849998 -11.400000 3.350000 +79.349998 -11.400000 3.850000 +79.349998 -12.700000 3.850000 +79.360611 -11.400000 3.747545 +79.391129 -11.400000 3.651411 +79.360611 -12.700000 3.747545 +79.391129 -12.700000 3.651411 +79.438019 -11.400000 3.566683 +79.438019 -12.700000 3.566683 +79.496445 -11.400000 3.496447 +79.496445 -12.700000 3.496447 +79.566681 -11.400000 3.438015 +79.651413 -11.400000 3.391129 +79.566681 -12.700000 3.438015 +79.747543 -11.400000 3.360610 +79.651413 -12.700000 3.391129 +79.747543 -12.700000 3.360610 +79.849998 -12.700000 3.350000 +84.196449 -11.400000 3.496447 +84.050003 -11.400000 3.850000 +84.050003 -12.700000 3.850000 +84.060608 -11.400000 3.747545 +84.060608 -12.700000 3.747545 +84.091125 -11.400000 3.651411 +84.138016 -11.400000 3.566683 +84.091125 -12.700000 3.651411 +84.447548 -12.700000 3.360610 +84.550003 -12.700000 3.350000 +84.550003 -11.400000 3.350000 +84.447548 -11.400000 3.360610 +84.351410 -12.700000 3.391129 +84.351410 -11.400000 3.391129 +84.266685 -12.700000 3.438015 +84.266685 -11.400000 3.438015 +84.196449 -12.700000 3.496447 +84.138016 -12.700000 3.566683 +85.403557 -12.700000 3.496447 +85.539391 -12.700000 3.747545 +85.550003 -12.700000 3.850000 +85.550003 -11.400000 3.850000 +85.508873 -12.700000 3.651411 +85.539391 -11.400000 3.747545 +85.508873 -11.400000 3.651411 +85.461983 -12.700000 3.566683 +85.152458 -11.400000 3.360610 +85.050003 -11.400000 3.350000 +85.050003 -12.700000 3.350000 +85.152458 -12.700000 3.360610 +85.248589 -11.400000 3.391129 +85.248589 -12.700000 3.391129 +85.333321 -11.400000 3.438015 +85.333321 -12.700000 3.438015 +85.403557 -11.400000 3.496447 +85.461983 -11.400000 3.566683 +106.052452 -11.400000 3.360610 +105.949997 -11.400000 3.350000 +106.439392 -12.700000 3.747545 +106.449997 -12.700000 3.850000 +106.449997 -11.400000 3.850000 +106.408875 -12.700000 3.651411 +106.439392 -11.400000 3.747545 +106.361984 -12.700000 3.566683 +106.408875 -11.400000 3.651411 +106.303551 -12.700000 3.496447 +106.361984 -11.400000 3.566683 +106.303551 -11.400000 3.496447 +106.233315 -12.700000 3.438015 +106.148590 -12.700000 3.391129 +106.233315 -11.400000 3.438015 +106.148590 -11.400000 3.391129 +106.052452 -12.700000 3.360610 +105.949997 -12.700000 3.350000 +100.338013 -12.700000 3.566683 +100.250000 -11.400000 3.850000 +100.250000 -12.700000 3.850000 +100.260612 -11.400000 3.747545 +100.260612 -12.700000 3.747545 +100.291130 -11.400000 3.651411 +100.291130 -12.700000 3.651411 +100.338013 -11.400000 3.566683 +100.647545 -12.700000 3.360610 +100.750000 -12.700000 3.350000 +100.750000 -11.400000 3.350000 +100.647545 -11.400000 3.360610 +100.551414 -12.700000 3.391129 +100.466682 -12.700000 3.438015 +100.551414 -11.400000 3.391129 +100.396446 -12.700000 3.496447 +100.466682 -11.400000 3.438015 +100.396446 -11.400000 3.496447 +105.096443 -12.700000 3.496447 +104.949997 -11.400000 3.850000 +104.949997 -12.700000 3.850000 +104.960609 -11.400000 3.747545 +104.960609 -12.700000 3.747545 +104.991127 -11.400000 3.651411 +104.991127 -12.700000 3.651411 +105.038017 -11.400000 3.566683 +105.096443 -11.400000 3.496447 +105.038017 -12.700000 3.566683 +105.347542 -12.700000 3.360610 +105.449997 -12.700000 3.350000 +105.449997 -11.400000 3.350000 +105.251411 -12.700000 3.391129 +105.347542 -11.400000 3.360610 +105.251411 -11.400000 3.391129 +105.166679 -12.700000 3.438015 +105.166679 -11.400000 3.438015 +28.549999 -11.400000 3.850000 +28.549999 -12.700000 3.850000 +28.947546 -12.700000 3.360610 +29.049999 -12.700000 3.350000 +29.049999 -11.400000 3.350000 +28.851412 -12.700000 3.391129 +28.947546 -11.400000 3.360610 +28.851412 -11.400000 3.391129 +28.766684 -12.700000 3.438015 +28.766684 -11.400000 3.438015 +28.696447 -12.700000 3.496447 +28.638016 -12.700000 3.566683 +28.696447 -11.400000 3.496447 +28.638016 -11.400000 3.566683 +28.591129 -12.700000 3.651411 +28.591129 -11.400000 3.651411 +28.560610 -12.700000 3.747545 +28.560610 -11.400000 3.747545 +29.903553 -11.400000 3.496447 +29.652454 -11.400000 3.360610 +29.549999 -11.400000 3.350000 +29.549999 -12.700000 3.350000 +29.748589 -11.400000 3.391129 +29.652454 -12.700000 3.360610 +29.833317 -11.400000 3.438015 +29.748589 -12.700000 3.391129 +30.039391 -12.700000 3.747545 +30.049999 -12.700000 3.850000 +30.049999 -11.400000 3.850000 +30.039391 -11.400000 3.747545 +30.008871 -12.700000 3.651411 +30.008871 -11.400000 3.651411 +29.961985 -12.700000 3.566683 +29.961985 -11.400000 3.566683 +29.903553 -12.700000 3.496447 +29.833317 -12.700000 3.438015 +34.750000 -12.700000 3.850000 +34.750000 -11.400000 3.850000 +34.352455 -11.400000 3.360610 +34.250000 -11.400000 3.350000 +34.250000 -12.700000 3.350000 +34.352455 -12.700000 3.360610 +34.448589 -11.400000 3.391129 +34.533318 -11.400000 3.438015 +34.448589 -12.700000 3.391129 +34.603554 -11.400000 3.496447 +34.533318 -12.700000 3.438015 +34.603554 -12.700000 3.496447 +34.661983 -11.400000 3.566683 +34.708870 -11.400000 3.651411 +34.661983 -12.700000 3.566683 +34.708870 -12.700000 3.651411 +34.739391 -11.400000 3.747545 +34.739391 -12.700000 3.747545 +96.147545 11.400000 3.360610 +96.250000 11.400000 3.350000 +95.760612 12.700000 3.747545 +95.750000 12.700000 3.850000 +95.750000 11.400000 3.850000 +95.760612 11.400000 3.747545 +95.791130 12.700000 3.651411 +95.791130 11.400000 3.651411 +95.838013 12.700000 3.566683 +95.838013 11.400000 3.566683 +95.896446 12.700000 3.496447 +95.966682 12.700000 3.438015 +95.896446 11.400000 3.496447 +95.966682 11.400000 3.438015 +96.051414 12.700000 3.391129 +96.147545 12.700000 3.360610 +96.051414 11.400000 3.391129 +96.250000 12.700000 3.350000 +96.852455 12.700000 3.360610 +96.750000 12.700000 3.350000 +97.250000 11.400000 3.850000 +97.250000 12.700000 3.850000 +97.239388 11.400000 3.747545 +97.208870 11.400000 3.651411 +97.239388 12.700000 3.747545 +97.161987 11.400000 3.566683 +97.208870 12.700000 3.651411 +97.103554 11.400000 3.496447 +97.161987 12.700000 3.566683 +97.103554 12.700000 3.496447 +97.033318 11.400000 3.438015 +96.948586 11.400000 3.391129 +97.033318 12.700000 3.438015 +96.852455 11.400000 3.360610 +96.948586 12.700000 3.391129 +96.750000 11.400000 3.350000 +101.449997 12.700000 3.350000 +101.449997 11.400000 3.350000 +101.949997 11.400000 3.850000 +101.949997 12.700000 3.850000 +101.939392 11.400000 3.747545 +101.939392 12.700000 3.747545 +101.908875 11.400000 3.651411 +101.908875 12.700000 3.651411 +101.861984 11.400000 3.566683 +101.803551 11.400000 3.496447 +101.861984 12.700000 3.566683 +101.733315 11.400000 3.438015 +101.803551 12.700000 3.496447 +101.733315 12.700000 3.438015 +101.648590 11.400000 3.391129 +101.648590 12.700000 3.391129 +101.552452 11.400000 3.360610 +101.552452 12.700000 3.360610 +80.961983 11.400000 3.566683 +81.050003 11.400000 3.850000 +81.050003 12.700000 3.850000 +81.039391 11.400000 3.747545 +81.008873 11.400000 3.651411 +81.039391 12.700000 3.747545 +80.652458 12.700000 3.360610 +80.550003 12.700000 3.350000 +80.550003 11.400000 3.350000 +80.652458 11.400000 3.360610 +80.748589 12.700000 3.391129 +80.833321 12.700000 3.438015 +80.748589 11.400000 3.391129 +80.833321 11.400000 3.438015 +80.903557 12.700000 3.496447 +80.903557 11.400000 3.496447 +80.961983 12.700000 3.566683 +81.008873 12.700000 3.651411 +75.849998 12.700000 3.350000 +75.849998 11.400000 3.350000 +76.349998 11.400000 3.850000 +76.349998 12.700000 3.850000 +76.339394 11.400000 3.747545 +76.339394 12.700000 3.747545 +76.308868 11.400000 3.651411 +76.308868 12.700000 3.651411 +76.261986 11.400000 3.566683 +76.203552 11.400000 3.496447 +76.261986 12.700000 3.566683 +76.203552 12.700000 3.496447 +76.133316 11.400000 3.438015 +76.133316 12.700000 3.438015 +76.048592 11.400000 3.391129 +76.048592 12.700000 3.391129 +75.952454 11.400000 3.360610 +75.952454 12.700000 3.360610 +74.891129 12.700000 3.651411 +74.860611 12.700000 3.747545 +74.849998 12.700000 3.850000 +74.849998 11.400000 3.850000 +75.247543 11.400000 3.360610 +75.349998 11.400000 3.350000 +75.349998 12.700000 3.350000 +75.151413 11.400000 3.391129 +75.247543 12.700000 3.360610 +75.151413 12.700000 3.391129 +75.066681 11.400000 3.438015 +75.066681 12.700000 3.438015 +74.996445 11.400000 3.496447 +74.938019 11.400000 3.566683 +74.996445 12.700000 3.496447 +74.938019 12.700000 3.566683 +74.891129 11.400000 3.651411 +74.860611 11.400000 3.747545 +58.650002 11.400000 3.850000 +59.047546 11.400000 3.360610 +59.150002 11.400000 3.350000 +59.150002 12.700000 3.350000 +59.047546 12.700000 3.360610 +58.951412 11.400000 3.391129 +58.951412 12.700000 3.391129 +58.866684 11.400000 3.438015 +58.796448 11.400000 3.496447 +58.866684 12.700000 3.438015 +58.738014 11.400000 3.566683 +58.796448 12.700000 3.496447 +58.738014 12.700000 3.566683 +58.691128 11.400000 3.651411 +58.691128 12.700000 3.651411 +58.660610 11.400000 3.747545 +58.660610 12.700000 3.747545 +58.650002 12.700000 3.850000 +54.347546 12.700000 3.360610 +54.450001 11.400000 3.350000 +54.450001 12.700000 3.350000 +54.347546 11.400000 3.360610 +53.960609 12.700000 3.747545 +53.950001 12.700000 3.850000 +53.950001 11.400000 3.850000 +53.960609 11.400000 3.747545 +53.991131 12.700000 3.651411 +54.038017 12.700000 3.566683 +53.991131 11.400000 3.651411 +54.096447 12.700000 3.496447 +54.038017 11.400000 3.566683 +54.096447 11.400000 3.496447 +54.166683 12.700000 3.438015 +54.166683 11.400000 3.438015 +54.251411 12.700000 3.391129 +54.251411 11.400000 3.391129 +59.933319 12.700000 3.438015 +59.752453 12.700000 3.360610 +59.650002 12.700000 3.350000 +59.650002 11.400000 3.350000 +59.752453 11.400000 3.360610 +59.848587 12.700000 3.391129 +60.150002 11.400000 3.850000 +60.150002 12.700000 3.850000 +60.139389 11.400000 3.747545 +60.139389 12.700000 3.747545 +60.108871 11.400000 3.651411 +60.108871 12.700000 3.651411 +60.061985 11.400000 3.566683 +60.061985 12.700000 3.566683 +60.003555 11.400000 3.496447 +59.933319 11.400000 3.438015 +60.003555 12.700000 3.496447 +59.848587 11.400000 3.391129 +38.948589 11.400000 3.391129 +38.750000 12.700000 3.350000 +38.750000 11.400000 3.350000 +38.852455 12.700000 3.360610 +38.948589 12.700000 3.391129 +38.852455 11.400000 3.360610 +39.250000 11.400000 3.850000 +39.250000 12.700000 3.850000 +39.239391 11.400000 3.747545 +39.208870 11.400000 3.651411 +39.239391 12.700000 3.747545 +39.208870 12.700000 3.651411 +39.161983 11.400000 3.566683 +39.161983 12.700000 3.566683 +39.103554 11.400000 3.496447 +39.033318 11.400000 3.438015 +39.103554 12.700000 3.496447 +39.033318 12.700000 3.438015 +38.051411 11.400000 3.391129 +38.250000 11.400000 3.350000 +38.250000 12.700000 3.350000 +38.147545 11.400000 3.360610 +37.760609 12.700000 3.747545 +37.750000 12.700000 3.850000 +37.750000 11.400000 3.850000 +37.760609 11.400000 3.747545 +37.791130 12.700000 3.651411 +37.791130 11.400000 3.651411 +37.838017 12.700000 3.566683 +37.838017 11.400000 3.566683 +37.896446 12.700000 3.496447 +37.896446 11.400000 3.496447 +37.966682 12.700000 3.438015 +38.051411 12.700000 3.391129 +37.966682 11.400000 3.438015 +38.147545 12.700000 3.360610 +33.266682 11.400000 3.438015 +33.447544 11.400000 3.360610 +33.549999 11.400000 3.350000 +33.549999 12.700000 3.350000 +33.351410 11.400000 3.391129 +33.447544 12.700000 3.360610 +33.060608 12.700000 3.747545 +33.049999 12.700000 3.850000 +33.049999 11.400000 3.850000 +33.060608 11.400000 3.747545 +33.091129 12.700000 3.651411 +33.138016 12.700000 3.566683 +33.091129 11.400000 3.651411 +33.196445 12.700000 3.496447 +33.138016 11.400000 3.566683 +33.266682 12.700000 3.438015 +33.196445 11.400000 3.496447 +33.351410 12.700000 3.391129 + + + + + + + + + + + +-0.695302 0.128667 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +0.695302 0.128667 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.695302 0.128667 0.707107 +0.695302 0.128667 0.707107 +0.707107 0.000000 0.707107 +0.695302 0.128667 0.707107 +0.657460 0.260282 0.707107 +0.695302 0.128667 0.707107 +0.657460 0.260282 0.707107 +0.657460 0.260282 0.707107 +0.695302 0.128667 0.707107 +0.591845 0.386936 0.707107 +0.657460 0.260282 0.707107 +0.657460 0.260282 0.707107 +0.591845 0.386936 0.707107 +0.591845 0.386936 0.707107 +0.657460 0.260282 0.707107 +0.500000 0.500000 0.707107 +0.591845 0.386936 0.707107 +0.591845 0.386936 0.707107 +0.500000 0.500000 0.707107 +0.500000 0.500000 0.707107 +0.591845 0.386936 0.707107 +0.386936 0.591845 0.707107 +0.500000 0.500000 0.707107 +0.500000 0.500000 0.707107 +0.386936 0.591845 0.707107 +0.386936 0.591845 0.707107 +0.500000 0.500000 0.707107 +0.260282 0.657460 0.707107 +0.386936 0.591845 0.707107 +0.386936 0.591845 0.707107 +0.260282 0.657460 0.707107 +0.260282 0.657460 0.707107 +0.386936 0.591845 0.707107 +0.128667 0.695302 0.707107 +0.260282 0.657460 0.707107 +0.260282 0.657460 0.707107 +0.128667 0.695302 0.707107 +0.128667 0.695302 0.707107 +0.260282 0.657460 0.707107 +0.000000 0.707107 0.707107 +0.128667 0.695302 0.707107 +0.128667 0.695302 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.128667 0.695302 0.707107 +-0.128667 0.695302 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +-0.128667 0.695302 0.707107 +-0.128667 0.695302 0.707107 +0.000000 0.707107 0.707107 +-0.260282 0.657460 0.707107 +-0.128667 0.695302 0.707107 +-0.128667 0.695302 0.707107 +-0.260282 0.657460 0.707107 +-0.260282 0.657460 0.707107 +-0.128667 0.695302 0.707107 +-0.386936 0.591845 0.707107 +-0.260282 0.657460 0.707107 +-0.260282 0.657460 0.707107 +-0.386936 0.591845 0.707107 +-0.386936 0.591845 0.707107 +-0.260282 0.657460 0.707107 +-0.500000 0.500000 0.707107 +-0.386936 0.591845 0.707107 +-0.386936 0.591845 0.707107 +-0.500000 0.500000 0.707107 +-0.500000 0.500000 0.707107 +-0.386936 0.591845 0.707107 +-0.591845 0.386936 0.707107 +-0.500000 0.500000 0.707107 +-0.500000 0.500000 0.707107 +-0.591845 0.386936 0.707107 +-0.591845 0.386936 0.707107 +-0.500000 0.500000 0.707107 +-0.657460 0.260282 0.707107 +-0.591845 0.386936 0.707107 +-0.591845 0.386936 0.707107 +-0.657460 0.260282 0.707107 +-0.657460 0.260282 0.707107 +-0.591845 0.386936 0.707107 +-0.695302 0.128667 0.707107 +-0.657460 0.260282 0.707107 +-0.657460 0.260282 0.707107 +-0.695302 0.128667 0.707107 +-0.695302 0.128667 0.707107 +-0.657460 0.260282 0.707107 +-0.707107 0.000000 0.707107 +-0.695302 0.128667 0.707107 +-0.695302 0.128667 0.707107 +-0.695302 0.128667 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +0.695302 0.128667 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.695302 0.128667 0.707107 +0.695302 0.128667 0.707107 +0.707107 0.000000 0.707107 +0.657460 0.260282 0.707107 +0.695302 0.128667 0.707107 +0.695302 0.128667 0.707107 +0.657460 0.260282 0.707107 +0.657460 0.260282 0.707107 +0.695302 0.128667 0.707107 +0.591845 0.386936 0.707107 +0.657460 0.260282 0.707107 +0.657460 0.260282 0.707107 +0.591845 0.386936 0.707107 +0.591845 0.386936 0.707107 +0.657460 0.260282 0.707107 +0.500000 0.500000 0.707107 +0.591845 0.386936 0.707107 +0.591845 0.386936 0.707107 +0.500000 0.500000 0.707107 +0.500000 0.500000 0.707107 +0.591845 0.386936 0.707107 +0.386936 0.591845 0.707107 +0.500000 0.500000 0.707107 +0.500000 0.500000 0.707107 +0.386936 0.591845 0.707107 +0.386936 0.591845 0.707107 +0.500000 0.500000 0.707107 +0.386936 0.591845 0.707107 +0.260282 0.657460 0.707107 +0.386936 0.591845 0.707107 +0.260282 0.657460 0.707107 +0.260282 0.657460 0.707107 +0.386936 0.591845 0.707107 +0.128667 0.695302 0.707107 +0.260282 0.657460 0.707107 +0.260282 0.657460 0.707107 +0.128667 0.695302 0.707107 +0.128667 0.695302 0.707107 +0.260282 0.657460 0.707107 +0.000000 0.707107 0.707107 +0.128667 0.695302 0.707107 +0.128667 0.695302 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.128667 0.695302 0.707107 +-0.128667 0.695302 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +-0.128667 0.695302 0.707107 +-0.128667 0.695302 0.707107 +0.000000 0.707107 0.707107 +-0.260282 0.657460 0.707107 +-0.128667 0.695302 0.707107 +-0.128667 0.695302 0.707107 +-0.260282 0.657460 0.707107 +-0.260282 0.657460 0.707107 +-0.128667 0.695302 0.707107 +-0.386936 0.591845 0.707107 +-0.260282 0.657460 0.707107 +-0.260282 0.657460 0.707107 +-0.386936 0.591845 0.707107 +-0.386936 0.591845 0.707107 +-0.260282 0.657460 0.707107 +-0.500000 0.500000 0.707107 +-0.386936 0.591845 0.707107 +-0.386936 0.591845 0.707107 +-0.500000 0.500000 0.707107 +-0.500000 0.500000 0.707107 +-0.386936 0.591845 0.707107 +-0.591845 0.386936 0.707107 +-0.500000 0.500000 0.707107 +-0.500000 0.500000 0.707107 +-0.591845 0.386936 0.707107 +-0.591845 0.386936 0.707107 +-0.500000 0.500000 0.707107 +-0.657460 0.260282 0.707107 +-0.591845 0.386936 0.707107 +-0.591845 0.386936 0.707107 +-0.657460 0.260282 0.707107 +-0.657460 0.260282 0.707107 +-0.591845 0.386936 0.707107 +-0.695302 0.128667 0.707107 +-0.657460 0.260282 0.707107 +-0.657460 0.260282 0.707107 +-0.695302 0.128667 0.707107 +-0.695302 0.128667 0.707107 +-0.657460 0.260282 0.707107 +-0.707107 0.000000 0.707107 +-0.695302 0.128667 0.707107 +-0.695302 0.128667 0.707107 +-0.695302 0.128667 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +0.695302 0.128667 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.695302 0.128667 0.707107 +0.695302 0.128667 0.707107 +0.707107 0.000000 0.707107 +0.657460 0.260282 0.707107 +0.695302 0.128667 0.707107 +0.695302 0.128667 0.707107 +0.657460 0.260282 0.707107 +0.657460 0.260282 0.707107 +0.695302 0.128667 0.707107 +0.591845 0.386936 0.707107 +0.657460 0.260282 0.707107 +0.657460 0.260282 0.707107 +0.591845 0.386936 0.707107 +0.591845 0.386936 0.707107 +0.657460 0.260282 0.707107 +0.500000 0.500000 0.707107 +0.591845 0.386936 0.707107 +0.591845 0.386936 0.707107 +0.500000 0.500000 0.707107 +0.500000 0.500000 0.707107 +0.591845 0.386936 0.707107 +0.386936 0.591845 0.707107 +0.500000 0.500000 0.707107 +0.500000 0.500000 0.707107 +0.386936 0.591845 0.707107 +0.386936 0.591845 0.707107 +0.500000 0.500000 0.707107 +0.386936 0.591845 0.707107 +0.260282 0.657460 0.707107 +0.386936 0.591845 0.707107 +0.260282 0.657460 0.707107 +0.260282 0.657460 0.707107 +0.386936 0.591845 0.707107 +0.128667 0.695302 0.707107 +0.260282 0.657460 0.707107 +0.260282 0.657460 0.707107 +0.128667 0.695302 0.707107 +0.128667 0.695302 0.707107 +0.260282 0.657460 0.707107 +0.000000 0.707107 0.707107 +0.128667 0.695302 0.707107 +0.128667 0.695302 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.128667 0.695302 0.707107 +-0.128667 0.695302 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +-0.128667 0.695302 0.707107 +-0.128667 0.695302 0.707107 +0.000000 0.707107 0.707107 +-0.260282 0.657460 0.707107 +-0.128667 0.695302 0.707107 +-0.128667 0.695302 0.707107 +-0.260282 0.657460 0.707107 +-0.260282 0.657460 0.707107 +-0.128667 0.695302 0.707107 +-0.386936 0.591845 0.707107 +-0.260282 0.657460 0.707107 +-0.260282 0.657460 0.707107 +-0.386936 0.591845 0.707107 +-0.386936 0.591845 0.707107 +-0.260282 0.657460 0.707107 +-0.500000 0.500000 0.707107 +-0.386936 0.591845 0.707107 +-0.386936 0.591845 0.707107 +-0.500000 0.500000 0.707107 +-0.500000 0.500000 0.707107 +-0.386936 0.591845 0.707107 +-0.591845 0.386936 0.707107 +-0.500000 0.500000 0.707107 +-0.500000 0.500000 0.707107 +-0.591845 0.386936 0.707107 +-0.591845 0.386936 0.707107 +-0.500000 0.500000 0.707107 +-0.657460 0.260282 0.707107 +-0.591845 0.386936 0.707107 +-0.591845 0.386936 0.707107 +-0.657460 0.260282 0.707107 +-0.657460 0.260282 0.707107 +-0.591845 0.386936 0.707107 +-0.695302 0.128667 0.707107 +-0.657460 0.260282 0.707107 +-0.657460 0.260282 0.707107 +-0.695302 0.128667 0.707107 +-0.695302 0.128667 0.707107 +-0.657460 0.260282 0.707107 +-0.707107 0.000000 0.707107 +-0.695302 0.128667 0.707107 +-0.695302 0.128667 0.707107 +-0.695302 0.128667 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.695302 0.128667 0.707107 +0.707107 0.000000 0.707107 +0.695302 0.128667 0.707107 +0.695302 0.128667 0.707107 +0.707107 0.000000 0.707107 +0.657460 0.260282 0.707107 +0.695302 0.128667 0.707107 +0.695302 0.128667 0.707107 +0.657460 0.260282 0.707107 +0.657460 0.260282 0.707107 +0.695302 0.128667 0.707107 +0.591845 0.386936 0.707107 +0.657460 0.260282 0.707107 +0.657460 0.260282 0.707107 +0.591845 0.386936 0.707107 +0.591845 0.386936 0.707107 +0.657460 0.260282 0.707107 +0.500000 0.500000 0.707107 +0.591845 0.386936 0.707107 +0.591845 0.386936 0.707107 +0.500000 0.500000 0.707107 +0.500000 0.500000 0.707107 +0.591845 0.386936 0.707107 +0.386936 0.591845 0.707107 +0.500000 0.500000 0.707107 +0.500000 0.500000 0.707107 +0.386936 0.591845 0.707107 +0.386936 0.591845 0.707107 +0.500000 0.500000 0.707107 +0.260282 0.657460 0.707107 +0.386936 0.591845 0.707107 +0.386936 0.591845 0.707107 +0.260282 0.657460 0.707107 +0.260282 0.657460 0.707107 +0.386936 0.591845 0.707107 +0.128667 0.695302 0.707107 +0.260282 0.657460 0.707107 +0.260282 0.657460 0.707107 +0.128667 0.695302 0.707107 +0.128667 0.695302 0.707107 +0.260282 0.657460 0.707107 +0.000000 0.707107 0.707107 +0.128667 0.695302 0.707107 +0.128667 0.695302 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.128667 0.695302 0.707107 +-0.128667 0.695302 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +-0.128667 0.695302 0.707107 +-0.128667 0.695302 0.707107 +0.000000 0.707107 0.707107 +-0.260282 0.657460 0.707107 +-0.128667 0.695302 0.707107 +-0.128667 0.695302 0.707107 +-0.260282 0.657460 0.707107 +-0.260282 0.657460 0.707107 +-0.128667 0.695302 0.707107 +-0.386936 0.591845 0.707107 +-0.260282 0.657460 0.707107 +-0.260282 0.657460 0.707107 +-0.386936 0.591845 0.707107 +-0.386936 0.591845 0.707107 +-0.260282 0.657460 0.707107 +-0.500000 0.500000 0.707107 +-0.386936 0.591845 0.707107 +-0.386936 0.591845 0.707107 +-0.500000 0.500000 0.707107 +-0.500000 0.500000 0.707107 +-0.386936 0.591845 0.707107 +-0.591845 0.386936 0.707107 +-0.500000 0.500000 0.707107 +-0.500000 0.500000 0.707107 +-0.591845 0.386936 0.707107 +-0.591845 0.386936 0.707107 +-0.500000 0.500000 0.707107 +-0.657460 0.260282 0.707107 +-0.591845 0.386936 0.707107 +-0.591845 0.386936 0.707107 +-0.657460 0.260282 0.707107 +-0.657460 0.260282 0.707107 +-0.591845 0.386936 0.707107 +-0.695302 0.128667 0.707107 +-0.657460 0.260282 0.707107 +-0.657460 0.260282 0.707107 +-0.695302 0.128667 0.707107 +-0.695302 0.128667 0.707107 +-0.657460 0.260282 0.707107 +-0.707107 0.000000 0.707107 +-0.695302 0.128667 0.707107 +-0.695302 0.128667 0.707107 +0.128667 0.695302 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +-0.707107 0.000000 0.707107 +-0.695302 0.128667 0.707107 +-0.707107 0.000000 0.707107 +-0.695302 0.128667 0.707107 +-0.695302 0.128667 0.707107 +-0.707107 0.000000 0.707107 +-0.695302 0.128667 0.707107 +-0.657460 0.260282 0.707107 +-0.695302 0.128667 0.707107 +-0.657460 0.260282 0.707107 +-0.657460 0.260282 0.707107 +-0.695302 0.128667 0.707107 +-0.657460 0.260282 0.707107 +-0.591845 0.386936 0.707107 +-0.657460 0.260282 0.707107 +-0.591845 0.386936 0.707107 +-0.591845 0.386936 0.707107 +-0.657460 0.260282 0.707107 +-0.591845 0.386936 0.707107 +-0.500000 0.500000 0.707107 +-0.591845 0.386936 0.707107 +-0.500000 0.500000 0.707107 +-0.500000 0.500000 0.707107 +-0.591845 0.386936 0.707107 +-0.500000 0.500000 0.707107 +-0.386936 0.591845 0.707107 +-0.500000 0.500000 0.707107 +-0.386936 0.591845 0.707107 +-0.386936 0.591845 0.707107 +-0.500000 0.500000 0.707107 +-0.386936 0.591845 0.707107 +-0.260282 0.657460 0.707107 +-0.386936 0.591845 0.707107 +-0.260282 0.657460 0.707107 +-0.260282 0.657460 0.707107 +-0.386936 0.591845 0.707107 +-0.260282 0.657460 0.707107 +-0.128667 0.695302 0.707107 +-0.260282 0.657460 0.707107 +-0.128667 0.695302 0.707107 +-0.128667 0.695302 0.707107 +-0.260282 0.657460 0.707107 +-0.128667 0.695302 0.707107 +0.000000 0.707107 0.707107 +-0.128667 0.695302 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +-0.128667 0.695302 0.707107 +0.707107 0.000000 0.707107 +0.695302 0.128667 0.707107 +0.707107 0.000000 0.707107 +0.695302 0.128667 0.707107 +0.695302 0.128667 0.707107 +0.707107 0.000000 0.707107 +0.657460 0.260282 0.707107 +0.695302 0.128667 0.707107 +0.695302 0.128667 0.707107 +0.657460 0.260282 0.707107 +0.657460 0.260282 0.707107 +0.695302 0.128667 0.707107 +0.591845 0.386936 0.707107 +0.657460 0.260282 0.707107 +0.657460 0.260282 0.707107 +0.591845 0.386936 0.707107 +0.591845 0.386936 0.707107 +0.657460 0.260282 0.707107 +0.500000 0.500000 0.707107 +0.591845 0.386936 0.707107 +0.591845 0.386936 0.707107 +0.500000 0.500000 0.707107 +0.500000 0.500000 0.707107 +0.591845 0.386936 0.707107 +0.386936 0.591845 0.707107 +0.500000 0.500000 0.707107 +0.500000 0.500000 0.707107 +0.386936 0.591845 0.707107 +0.386936 0.591845 0.707107 +0.500000 0.500000 0.707107 +0.260282 0.657460 0.707107 +0.386936 0.591845 0.707107 +0.386936 0.591845 0.707107 +0.260282 0.657460 0.707107 +0.260282 0.657460 0.707107 +0.386936 0.591845 0.707107 +0.128667 0.695302 0.707107 +0.260282 0.657460 0.707107 +0.260282 0.657460 0.707107 +0.128667 0.695302 0.707107 +0.128667 0.695302 0.707107 +0.260282 0.657460 0.707107 +0.000000 0.707107 0.707107 +0.128667 0.695302 0.707107 +0.128667 0.695302 0.707107 +-0.695302 0.128667 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +0.695302 0.128667 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.695302 0.128667 0.707107 +0.695302 0.128667 0.707107 +0.707107 0.000000 0.707107 +0.657460 0.260282 0.707107 +0.695302 0.128667 0.707107 +0.695302 0.128667 0.707107 +0.657460 0.260282 0.707107 +0.657460 0.260282 0.707107 +0.695302 0.128667 0.707107 +0.591845 0.386936 0.707107 +0.657460 0.260282 0.707107 +0.657460 0.260282 0.707107 +0.591845 0.386936 0.707107 +0.591845 0.386936 0.707107 +0.657460 0.260282 0.707107 +0.500000 0.500000 0.707107 +0.591845 0.386936 0.707107 +0.591845 0.386936 0.707107 +0.500000 0.500000 0.707107 +0.500000 0.500000 0.707107 +0.591845 0.386936 0.707107 +0.386936 0.591845 0.707107 +0.500000 0.500000 0.707107 +0.500000 0.500000 0.707107 +0.386936 0.591845 0.707107 +0.386936 0.591845 0.707107 +0.500000 0.500000 0.707107 +0.260282 0.657460 0.707107 +0.386936 0.591845 0.707107 +0.386936 0.591845 0.707107 +0.260282 0.657460 0.707107 +0.260282 0.657460 0.707107 +0.386936 0.591845 0.707107 +0.128667 0.695302 0.707107 +0.260282 0.657460 0.707107 +0.260282 0.657460 0.707107 +0.128667 0.695302 0.707107 +0.128667 0.695302 0.707107 +0.260282 0.657460 0.707107 +0.000000 0.707107 0.707107 +0.128667 0.695302 0.707107 +0.128667 0.695302 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.128667 0.695302 0.707107 +-0.128667 0.695302 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +-0.128667 0.695302 0.707107 +-0.128667 0.695302 0.707107 +0.000000 0.707107 0.707107 +-0.260282 0.657460 0.707107 +-0.128667 0.695302 0.707107 +-0.128667 0.695302 0.707107 +-0.260282 0.657460 0.707107 +-0.260282 0.657460 0.707107 +-0.128667 0.695302 0.707107 +-0.386936 0.591845 0.707107 +-0.260282 0.657460 0.707107 +-0.260282 0.657460 0.707107 +-0.386936 0.591845 0.707107 +-0.386936 0.591845 0.707107 +-0.260282 0.657460 0.707107 +-0.500000 0.500000 0.707107 +-0.386936 0.591845 0.707107 +-0.386936 0.591845 0.707107 +-0.500000 0.500000 0.707107 +-0.500000 0.500000 0.707107 +-0.386936 0.591845 0.707107 +-0.591845 0.386936 0.707107 +-0.500000 0.500000 0.707107 +-0.500000 0.500000 0.707107 +-0.591845 0.386936 0.707107 +-0.591845 0.386936 0.707107 +-0.500000 0.500000 0.707107 +-0.657460 0.260282 0.707107 +-0.591845 0.386936 0.707107 +-0.591845 0.386936 0.707107 +-0.657460 0.260282 0.707107 +-0.657460 0.260282 0.707107 +-0.591845 0.386936 0.707107 +-0.695302 0.128667 0.707107 +-0.657460 0.260282 0.707107 +-0.657460 0.260282 0.707107 +-0.695302 0.128667 0.707107 +-0.695302 0.128667 0.707107 +-0.657460 0.260282 0.707107 +-0.707107 0.000000 0.707107 +-0.695302 0.128667 0.707107 +-0.695302 0.128667 0.707107 +-0.657460 0.260282 -0.707107 +-0.695302 0.128667 -0.707107 +-0.695302 0.128667 -0.707107 +-0.695302 0.128667 -0.707107 +-0.707107 0.000000 -0.707107 +-0.707107 0.000000 -0.707107 +-0.695302 0.128667 -0.707107 +-0.695302 0.128667 -0.707107 +-0.707107 0.000000 -0.707107 +0.707107 0.000000 -0.707107 +0.695302 0.128667 -0.707107 +0.707107 0.000000 -0.707107 +0.695302 0.128667 -0.707107 +0.695302 0.128667 -0.707107 +0.707107 0.000000 -0.707107 +0.657460 0.260282 -0.707107 +0.695302 0.128667 -0.707107 +0.695302 0.128667 -0.707107 +0.657460 0.260282 -0.707107 +0.657460 0.260282 -0.707107 +0.695302 0.128667 -0.707107 +0.591845 0.386936 -0.707107 +0.657460 0.260282 -0.707107 +0.657460 0.260282 -0.707107 +0.591845 0.386936 -0.707107 +0.591845 0.386936 -0.707107 +0.657460 0.260282 -0.707107 +0.500000 0.500000 -0.707107 +0.591845 0.386936 -0.707107 +0.591845 0.386936 -0.707107 +0.500000 0.500000 -0.707107 +0.500000 0.500000 -0.707107 +0.591845 0.386936 -0.707107 +0.386936 0.591845 -0.707107 +0.500000 0.500000 -0.707107 +0.500000 0.500000 -0.707107 +0.386936 0.591845 -0.707107 +0.386936 0.591845 -0.707107 +0.500000 0.500000 -0.707107 +0.260282 0.657460 -0.707107 +0.386936 0.591845 -0.707107 +0.386936 0.591845 -0.707107 +0.260282 0.657460 -0.707107 +0.260282 0.657460 -0.707107 +0.386936 0.591845 -0.707107 +0.128667 0.695302 -0.707107 +0.260282 0.657460 -0.707107 +0.260282 0.657460 -0.707107 +0.128667 0.695302 -0.707107 +0.128667 0.695302 -0.707107 +0.260282 0.657460 -0.707107 +0.000000 0.707107 -0.707107 +0.128667 0.695302 -0.707107 +0.128667 0.695302 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 +0.128667 0.695302 -0.707107 +-0.128667 0.695302 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 +-0.128667 0.695302 -0.707107 +-0.128667 0.695302 -0.707107 +0.000000 0.707107 -0.707107 +-0.260282 0.657460 -0.707107 +-0.128667 0.695302 -0.707107 +-0.128667 0.695302 -0.707107 +-0.260282 0.657460 -0.707107 +-0.260282 0.657460 -0.707107 +-0.128667 0.695302 -0.707107 +-0.386936 0.591845 -0.707107 +-0.260282 0.657460 -0.707107 +-0.260282 0.657460 -0.707107 +-0.386936 0.591845 -0.707107 +-0.386936 0.591845 -0.707107 +-0.260282 0.657460 -0.707107 +-0.500000 0.500000 -0.707107 +-0.386936 0.591845 -0.707107 +-0.386936 0.591845 -0.707107 +-0.500000 0.500000 -0.707107 +-0.500000 0.500000 -0.707107 +-0.386936 0.591845 -0.707107 +-0.591845 0.386936 -0.707107 +-0.500000 0.500000 -0.707107 +-0.500000 0.500000 -0.707107 +-0.591845 0.386936 -0.707107 +-0.591845 0.386936 -0.707107 +-0.500000 0.500000 -0.707107 +-0.657460 0.260282 -0.707107 +-0.591845 0.386936 -0.707107 +-0.591845 0.386936 -0.707107 +-0.657460 0.260282 -0.707107 +-0.657460 0.260282 -0.707107 +-0.591845 0.386936 -0.707107 +-0.695302 0.128667 -0.707107 +-0.657460 0.260282 -0.707107 +-0.657460 0.260282 -0.707107 +0.707107 0.000000 -0.707107 +0.695302 0.128667 -0.707107 +0.707107 0.000000 -0.707107 +-0.707107 0.000000 -0.707107 +-0.695302 0.128667 -0.707107 +-0.707107 0.000000 -0.707107 +-0.695302 0.128667 -0.707107 +-0.695302 0.128667 -0.707107 +-0.707107 0.000000 -0.707107 +-0.695302 0.128667 -0.707107 +-0.657460 0.260282 -0.707107 +-0.695302 0.128667 -0.707107 +-0.657460 0.260282 -0.707107 +-0.657460 0.260282 -0.707107 +-0.695302 0.128667 -0.707107 +-0.657460 0.260282 -0.707107 +-0.591845 0.386936 -0.707107 +-0.657460 0.260282 -0.707107 +-0.591845 0.386936 -0.707107 +-0.591845 0.386936 -0.707107 +-0.657460 0.260282 -0.707107 +-0.591845 0.386936 -0.707107 +-0.500000 0.500000 -0.707107 +-0.591845 0.386936 -0.707107 +-0.500000 0.500000 -0.707107 +-0.500000 0.500000 -0.707107 +-0.591845 0.386936 -0.707107 +-0.500000 0.500000 -0.707107 +-0.386936 0.591845 -0.707107 +-0.500000 0.500000 -0.707107 +-0.386936 0.591845 -0.707107 +-0.386936 0.591845 -0.707107 +-0.500000 0.500000 -0.707107 +-0.386936 0.591845 -0.707107 +-0.260282 0.657460 -0.707107 +-0.386936 0.591845 -0.707107 +-0.260282 0.657460 -0.707107 +-0.260282 0.657460 -0.707107 +-0.386936 0.591845 -0.707107 +-0.260282 0.657460 -0.707107 +-0.128667 0.695302 -0.707107 +-0.260282 0.657460 -0.707107 +-0.128667 0.695302 -0.707107 +-0.128667 0.695302 -0.707107 +-0.260282 0.657460 -0.707107 +0.000000 0.707107 -0.707107 +-0.128667 0.695302 -0.707107 +-0.128667 0.695302 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 +-0.128667 0.695302 -0.707107 +0.000000 0.707107 -0.707107 +0.128667 0.695302 -0.707107 +0.000000 0.707107 -0.707107 +0.128667 0.695302 -0.707107 +0.128667 0.695302 -0.707107 +0.000000 0.707107 -0.707107 +0.128667 0.695302 -0.707107 +0.260282 0.657460 -0.707107 +0.128667 0.695302 -0.707107 +0.260282 0.657460 -0.707107 +0.260282 0.657460 -0.707107 +0.128667 0.695302 -0.707107 +0.260282 0.657460 -0.707107 +0.386936 0.591845 -0.707107 +0.260282 0.657460 -0.707107 +0.386936 0.591845 -0.707107 +0.386936 0.591845 -0.707107 +0.260282 0.657460 -0.707107 +0.500000 0.500000 -0.707107 +0.386936 0.591845 -0.707107 +0.386936 0.591845 -0.707107 +0.500000 0.500000 -0.707107 +0.500000 0.500000 -0.707107 +0.386936 0.591845 -0.707107 +0.591845 0.386936 -0.707107 +0.500000 0.500000 -0.707107 +0.500000 0.500000 -0.707107 +0.591845 0.386936 -0.707107 +0.591845 0.386936 -0.707107 +0.500000 0.500000 -0.707107 +0.591845 0.386936 -0.707107 +0.657460 0.260282 -0.707107 +0.591845 0.386936 -0.707107 +0.657460 0.260282 -0.707107 +0.657460 0.260282 -0.707107 +0.591845 0.386936 -0.707107 +0.657460 0.260282 -0.707107 +0.695302 0.128667 -0.707107 +0.657460 0.260282 -0.707107 +0.695302 0.128667 -0.707107 +0.695302 0.128667 -0.707107 +0.657460 0.260282 -0.707107 +0.695302 0.128667 -0.707107 +0.707107 0.000000 -0.707107 +0.695302 0.128667 -0.707107 +0.695302 0.128667 -0.707107 +0.707107 0.000000 -0.707107 +0.707107 0.000000 -0.707107 +-0.695302 0.128667 -0.707107 +-0.707107 0.000000 -0.707107 +-0.707107 0.000000 -0.707107 +-0.695302 0.128667 -0.707107 +-0.695302 0.128667 -0.707107 +-0.707107 0.000000 -0.707107 +-0.695302 0.128667 -0.707107 +-0.657460 0.260282 -0.707107 +-0.695302 0.128667 -0.707107 +-0.657460 0.260282 -0.707107 +-0.657460 0.260282 -0.707107 +-0.695302 0.128667 -0.707107 +-0.591845 0.386936 -0.707107 +-0.657460 0.260282 -0.707107 +-0.657460 0.260282 -0.707107 +-0.591845 0.386936 -0.707107 +-0.591845 0.386936 -0.707107 +-0.657460 0.260282 -0.707107 +-0.500000 0.500000 -0.707107 +-0.591845 0.386936 -0.707107 +-0.591845 0.386936 -0.707107 +-0.500000 0.500000 -0.707107 +-0.500000 0.500000 -0.707107 +-0.591845 0.386936 -0.707107 +-0.500000 0.500000 -0.707107 +-0.386936 0.591845 -0.707107 +-0.500000 0.500000 -0.707107 +-0.386936 0.591845 -0.707107 +-0.386936 0.591845 -0.707107 +-0.500000 0.500000 -0.707107 +-0.260282 0.657460 -0.707107 +-0.386936 0.591845 -0.707107 +-0.386936 0.591845 -0.707107 +-0.260282 0.657460 -0.707107 +-0.260282 0.657460 -0.707107 +-0.386936 0.591845 -0.707107 +-0.128667 0.695302 -0.707107 +-0.260282 0.657460 -0.707107 +-0.260282 0.657460 -0.707107 +-0.128667 0.695302 -0.707107 +-0.128667 0.695302 -0.707107 +-0.260282 0.657460 -0.707107 +0.000000 0.707107 -0.707107 +-0.128667 0.695302 -0.707107 +-0.128667 0.695302 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 +-0.128667 0.695302 -0.707107 +0.128667 0.695302 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 +0.128667 0.695302 -0.707107 +0.128667 0.695302 -0.707107 +0.000000 0.707107 -0.707107 +0.260282 0.657460 -0.707107 +0.128667 0.695302 -0.707107 +0.128667 0.695302 -0.707107 +0.260282 0.657460 -0.707107 +0.260282 0.657460 -0.707107 +0.128667 0.695302 -0.707107 +0.386936 0.591845 -0.707107 +0.260282 0.657460 -0.707107 +0.260282 0.657460 -0.707107 +0.386936 0.591845 -0.707107 +0.386936 0.591845 -0.707107 +0.260282 0.657460 -0.707107 +0.500000 0.500000 -0.707107 +0.386936 0.591845 -0.707107 +0.386936 0.591845 -0.707107 +0.500000 0.500000 -0.707107 +0.500000 0.500000 -0.707107 +0.386936 0.591845 -0.707107 +0.591845 0.386936 -0.707107 +0.500000 0.500000 -0.707107 +0.500000 0.500000 -0.707107 +0.591845 0.386936 -0.707107 +0.591845 0.386936 -0.707107 +0.500000 0.500000 -0.707107 +0.657460 0.260282 -0.707107 +0.591845 0.386936 -0.707107 +0.591845 0.386936 -0.707107 +0.657460 0.260282 -0.707107 +0.657460 0.260282 -0.707107 +0.591845 0.386936 -0.707107 +0.695302 0.128667 -0.707107 +0.657460 0.260282 -0.707107 +0.657460 0.260282 -0.707107 +0.695302 0.128667 -0.707107 +0.695302 0.128667 -0.707107 +0.657460 0.260282 -0.707107 +0.707107 0.000000 -0.707107 +0.695302 0.128667 -0.707107 +0.695302 0.128667 -0.707107 +0.695302 0.128667 -0.707107 +0.707107 0.000000 -0.707107 +0.707107 0.000000 -0.707107 +-0.695302 0.128667 -0.707107 +-0.707107 0.000000 -0.707107 +-0.707107 0.000000 -0.707107 +-0.695302 0.128667 -0.707107 +-0.695302 0.128667 -0.707107 +-0.707107 0.000000 -0.707107 +-0.695302 0.128667 -0.707107 +-0.657460 0.260282 -0.707107 +-0.695302 0.128667 -0.707107 +-0.657460 0.260282 -0.707107 +-0.657460 0.260282 -0.707107 +-0.695302 0.128667 -0.707107 +-0.591845 0.386936 -0.707107 +-0.657460 0.260282 -0.707107 +-0.657460 0.260282 -0.707107 +-0.591845 0.386936 -0.707107 +-0.591845 0.386936 -0.707107 +-0.657460 0.260282 -0.707107 +-0.500000 0.500000 -0.707107 +-0.591845 0.386936 -0.707107 +-0.591845 0.386936 -0.707107 +-0.500000 0.500000 -0.707107 +-0.500000 0.500000 -0.707107 +-0.591845 0.386936 -0.707107 +-0.386936 0.591845 -0.707107 +-0.500000 0.500000 -0.707107 +-0.500000 0.500000 -0.707107 +-0.386936 0.591845 -0.707107 +-0.386936 0.591845 -0.707107 +-0.500000 0.500000 -0.707107 +-0.260282 0.657460 -0.707107 +-0.386936 0.591845 -0.707107 +-0.386936 0.591845 -0.707107 +-0.260282 0.657460 -0.707107 +-0.260282 0.657460 -0.707107 +-0.386936 0.591845 -0.707107 +-0.128667 0.695302 -0.707107 +-0.260282 0.657460 -0.707107 +-0.260282 0.657460 -0.707107 +-0.128667 0.695302 -0.707107 +-0.128667 0.695302 -0.707107 +-0.260282 0.657460 -0.707107 +0.000000 0.707107 -0.707107 +-0.128667 0.695302 -0.707107 +-0.128667 0.695302 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 +-0.128667 0.695302 -0.707107 +0.128667 0.695302 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 +0.128667 0.695302 -0.707107 +0.128667 0.695302 -0.707107 +0.000000 0.707107 -0.707107 +0.260282 0.657460 -0.707107 +0.128667 0.695302 -0.707107 +0.128667 0.695302 -0.707107 +0.260282 0.657460 -0.707107 +0.260282 0.657460 -0.707107 +0.128667 0.695302 -0.707107 +0.386936 0.591845 -0.707107 +0.260282 0.657460 -0.707107 +0.260282 0.657460 -0.707107 +0.386936 0.591845 -0.707107 +0.386936 0.591845 -0.707107 +0.260282 0.657460 -0.707107 +0.500000 0.500000 -0.707107 +0.386936 0.591845 -0.707107 +0.386936 0.591845 -0.707107 +0.500000 0.500000 -0.707107 +0.500000 0.500000 -0.707107 +0.386936 0.591845 -0.707107 +0.591845 0.386936 -0.707107 +0.500000 0.500000 -0.707107 +0.500000 0.500000 -0.707107 +0.591845 0.386936 -0.707107 +0.591845 0.386936 -0.707107 +0.500000 0.500000 -0.707107 +0.657460 0.260282 -0.707107 +0.591845 0.386936 -0.707107 +0.591845 0.386936 -0.707107 +0.657460 0.260282 -0.707107 +0.657460 0.260282 -0.707107 +0.591845 0.386936 -0.707107 +0.695302 0.128667 -0.707107 +0.657460 0.260282 -0.707107 +0.657460 0.260282 -0.707107 +0.695302 0.128667 -0.707107 +0.695302 0.128667 -0.707107 +0.657460 0.260282 -0.707107 +0.707107 0.000000 -0.707107 +0.695302 0.128667 -0.707107 +0.695302 0.128667 -0.707107 +0.695302 0.128667 -0.707107 +0.707107 0.000000 -0.707107 +0.707107 0.000000 -0.707107 +-0.695302 0.128667 -0.707107 +-0.707107 0.000000 -0.707107 +-0.707107 0.000000 -0.707107 +-0.695302 0.128667 -0.707107 +-0.695302 0.128667 -0.707107 +-0.707107 0.000000 -0.707107 +-0.695302 0.128667 -0.707107 +-0.657460 0.260282 -0.707107 +-0.695302 0.128667 -0.707107 +-0.657460 0.260282 -0.707107 +-0.657460 0.260282 -0.707107 +-0.695302 0.128667 -0.707107 +-0.591845 0.386936 -0.707107 +-0.657460 0.260282 -0.707107 +-0.657460 0.260282 -0.707107 +-0.591845 0.386936 -0.707107 +-0.591845 0.386936 -0.707107 +-0.657460 0.260282 -0.707107 +-0.500000 0.500000 -0.707107 +-0.591845 0.386936 -0.707107 +-0.591845 0.386936 -0.707107 +-0.500000 0.500000 -0.707107 +-0.500000 0.500000 -0.707107 +-0.591845 0.386936 -0.707107 +-0.386936 0.591845 -0.707107 +-0.500000 0.500000 -0.707107 +-0.500000 0.500000 -0.707107 +-0.386936 0.591845 -0.707107 +-0.386936 0.591845 -0.707107 +-0.500000 0.500000 -0.707107 +-0.260282 0.657460 -0.707107 +-0.386936 0.591845 -0.707107 +-0.386936 0.591845 -0.707107 +-0.260282 0.657460 -0.707107 +-0.260282 0.657460 -0.707107 +-0.386936 0.591845 -0.707107 +-0.128667 0.695302 -0.707107 +-0.260282 0.657460 -0.707107 +-0.260282 0.657460 -0.707107 +-0.128667 0.695302 -0.707107 +-0.128667 0.695302 -0.707107 +-0.260282 0.657460 -0.707107 +0.000000 0.707107 -0.707107 +-0.128667 0.695302 -0.707107 +-0.128667 0.695302 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 +-0.128667 0.695302 -0.707107 +0.128667 0.695302 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 +0.128667 0.695302 -0.707107 +0.128667 0.695302 -0.707107 +0.000000 0.707107 -0.707107 +0.260282 0.657460 -0.707107 +0.128667 0.695302 -0.707107 +0.128667 0.695302 -0.707107 +0.260282 0.657460 -0.707107 +0.260282 0.657460 -0.707107 +0.128667 0.695302 -0.707107 +0.386936 0.591845 -0.707107 +0.260282 0.657460 -0.707107 +0.260282 0.657460 -0.707107 +0.386936 0.591845 -0.707107 +0.386936 0.591845 -0.707107 +0.260282 0.657460 -0.707107 +0.500000 0.500000 -0.707107 +0.386936 0.591845 -0.707107 +0.386936 0.591845 -0.707107 +0.500000 0.500000 -0.707107 +0.500000 0.500000 -0.707107 +0.386936 0.591845 -0.707107 +0.591845 0.386936 -0.707107 +0.500000 0.500000 -0.707107 +0.500000 0.500000 -0.707107 +0.591845 0.386936 -0.707107 +0.591845 0.386936 -0.707107 +0.500000 0.500000 -0.707107 +0.657460 0.260282 -0.707107 +0.591845 0.386936 -0.707107 +0.591845 0.386936 -0.707107 +0.657460 0.260282 -0.707107 +0.657460 0.260282 -0.707107 +0.591845 0.386936 -0.707107 +0.695302 0.128667 -0.707107 +0.657460 0.260282 -0.707107 +0.657460 0.260282 -0.707107 +0.695302 0.128667 -0.707107 +0.695302 0.128667 -0.707107 +0.657460 0.260282 -0.707107 +0.707107 0.000000 -0.707107 +0.695302 0.128667 -0.707107 +0.695302 0.128667 -0.707107 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +-0.965926 -0.258819 0.000000 +-0.923664 -0.383204 0.000000 +-0.965926 -0.258819 0.000000 +-0.996896 -0.078735 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.996896 -0.078735 0.000000 +-0.991518 -0.129968 0.000000 +-1.000000 0.000000 0.000000 +-0.965926 -0.258819 0.000000 +-0.991518 -0.129968 0.000000 +-0.996896 -0.078735 0.000000 +-0.965926 -0.258819 0.000000 +-0.965926 -0.258819 0.000000 +-0.991518 -0.129968 0.000000 +-0.923664 -0.383204 0.000000 +-0.866025 -0.500000 0.000000 +-0.866025 -0.500000 0.000000 +-0.923664 -0.383204 0.000000 +-0.902705 -0.430261 0.000000 +-0.866025 -0.500000 0.000000 +-0.923664 -0.383204 0.000000 +-0.965926 -0.258819 0.000000 +-0.902705 -0.430261 0.000000 +-0.605630 -0.795747 0.000000 +-0.500000 -0.866025 0.000000 +-0.500000 -0.866025 0.000000 +-0.989268 -0.146115 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.989268 -0.146115 0.000000 +-0.991952 -0.126617 0.000000 +-1.000000 0.000000 0.000000 +-0.989268 -0.146115 0.000000 +-0.967097 -0.254408 0.000000 +-0.991952 -0.126617 0.000000 +-0.942549 -0.334068 0.000000 +-0.967097 -0.254408 0.000000 +-0.989268 -0.146115 0.000000 +-0.942549 -0.334068 0.000000 +-0.924976 -0.380026 0.000000 +-0.967097 -0.254408 0.000000 +-0.866025 -0.500000 0.000000 +-0.924976 -0.380026 0.000000 +-0.942549 -0.334068 0.000000 +-0.866025 -0.500000 0.000000 +-0.866025 -0.500000 0.000000 +-0.924976 -0.380026 0.000000 +-0.866025 -0.500000 0.000000 +-0.791600 -0.611040 0.000000 +-0.866025 -0.500000 0.000000 +-0.760586 -0.649237 0.000000 +-0.791600 -0.611040 0.000000 +-0.866025 -0.500000 0.000000 +-0.760586 -0.649237 0.000000 +-0.703872 -0.710326 0.000000 +-0.791600 -0.611040 0.000000 +-0.621173 -0.783674 0.000000 +-0.703872 -0.710326 0.000000 +-0.760586 -0.649237 0.000000 +-0.621173 -0.783674 0.000000 +-0.605630 -0.795747 0.000000 +-0.703872 -0.710326 0.000000 +-0.500000 -0.866025 0.000000 +-0.605630 -0.795747 0.000000 +-0.621173 -0.783674 0.000000 +-0.718121 0.695863 -0.008727 +-0.707080 0.707080 -0.008727 +-0.707080 0.707080 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999838 0.015739 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999838 0.015739 -0.008727 +-0.999838 0.015739 -0.008727 +-0.999962 0.000000 -0.008727 +-0.978053 0.208175 -0.008727 +-0.999838 0.015739 -0.008727 +-0.999838 0.015739 -0.008727 +-0.978053 0.208175 -0.008727 +-0.978053 0.208175 -0.008727 +-0.999838 0.015739 -0.008727 +-0.923844 0.382669 -0.008727 +-0.978053 0.208175 -0.008727 +-0.978053 0.208175 -0.008727 +-0.923844 0.382669 -0.008727 +-0.923844 0.382669 -0.008727 +-0.978053 0.208175 -0.008727 +-0.838790 0.544386 -0.008727 +-0.923844 0.382669 -0.008727 +-0.923844 0.382669 -0.008727 +-0.838790 0.544386 -0.008727 +-0.838790 0.544386 -0.008727 +-0.923844 0.382669 -0.008727 +-0.718121 0.695863 -0.008727 +-0.838790 0.544386 -0.008727 +-0.838790 0.544386 -0.008727 +-0.718121 0.695863 -0.008727 +-0.718121 0.695863 -0.008727 +-0.838790 0.544386 -0.008727 +-0.707080 0.707080 -0.008727 +-0.718121 0.695863 -0.008727 +-0.718121 0.695863 -0.008727 +0.982654 -0.185245 -0.008727 +0.923844 -0.382669 -0.008727 +0.982654 -0.185245 -0.008727 +0.982654 -0.185245 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.982654 -0.185245 -0.008727 +0.982654 -0.185245 -0.008727 +0.999962 0.000000 -0.008727 +-0.563853 -0.825829 -0.008727 +-0.707080 -0.707080 -0.008727 +-0.707080 -0.707080 -0.008727 +-0.563853 -0.825829 -0.008727 +-0.563853 -0.825829 -0.008727 +-0.707080 -0.707080 -0.008727 +-0.382669 -0.923844 -0.008727 +-0.563853 -0.825829 -0.008727 +-0.563853 -0.825829 -0.008727 +-0.382669 -0.923844 -0.008727 +-0.382669 -0.923844 -0.008727 +-0.563853 -0.825829 -0.008727 +-0.185245 -0.982654 -0.008727 +-0.382669 -0.923844 -0.008727 +-0.382669 -0.923844 -0.008727 +-0.185245 -0.982654 -0.008727 +-0.185245 -0.982654 -0.008727 +-0.382669 -0.923844 -0.008727 +-0.185245 -0.982654 -0.008727 +0.015739 -0.999838 -0.008727 +-0.185245 -0.982654 -0.008727 +0.015739 -0.999838 -0.008727 +0.015739 -0.999838 -0.008727 +-0.185245 -0.982654 -0.008727 +0.015739 -0.999838 -0.008727 +0.208175 -0.978053 -0.008727 +0.015739 -0.999838 -0.008727 +0.208175 -0.978053 -0.008727 +0.208175 -0.978053 -0.008727 +0.015739 -0.999838 -0.008727 +0.208175 -0.978053 -0.008727 +0.382669 -0.923844 -0.008727 +0.208175 -0.978053 -0.008727 +0.382669 -0.923844 -0.008727 +0.382669 -0.923844 -0.008727 +0.208175 -0.978053 -0.008727 +0.382669 -0.923844 -0.008727 +0.544386 -0.838790 -0.008727 +0.382669 -0.923844 -0.008727 +0.544386 -0.838790 -0.008727 +0.544386 -0.838790 -0.008727 +0.382669 -0.923844 -0.008727 +0.695863 -0.718121 -0.008727 +0.544386 -0.838790 -0.008727 +0.544386 -0.838790 -0.008727 +0.695863 -0.718121 -0.008727 +0.695863 -0.718121 -0.008727 +0.544386 -0.838790 -0.008727 +0.695863 -0.718121 -0.008727 +0.825829 -0.563853 -0.008727 +0.695863 -0.718121 -0.008727 +0.825829 -0.563853 -0.008727 +0.825829 -0.563853 -0.008727 +0.695863 -0.718121 -0.008727 +0.825829 -0.563853 -0.008727 +0.923844 -0.382669 -0.008727 +0.825829 -0.563853 -0.008727 +0.923844 -0.382669 -0.008727 +0.923844 -0.382669 -0.008727 +0.825829 -0.563853 -0.008727 +0.923844 -0.382669 -0.008727 +0.982654 -0.185245 -0.008727 +0.923844 -0.382669 -0.008727 +0.929222 0.367870 0.034899 +0.836486 0.546876 0.034899 +0.929222 0.367870 0.034899 +0.999391 0.000000 0.034899 +0.982706 0.181852 0.034899 +0.999391 0.000000 0.034899 +0.982706 0.181852 0.034899 +0.982706 0.181852 0.034899 +0.999391 0.000000 0.034899 +0.929222 0.367870 0.034899 +0.982706 0.181852 0.034899 +0.982706 0.181852 0.034899 +0.929222 0.367870 0.034899 +0.929222 0.367870 0.034899 +0.982706 0.181852 0.034899 +-0.982706 0.181852 0.034899 +-0.999391 0.000000 0.034899 +-0.999391 0.000000 0.034899 +-0.982706 0.181852 0.034899 +-0.982706 0.181852 0.034899 +-0.999391 0.000000 0.034899 +-0.929222 0.367870 0.034899 +-0.982706 0.181852 0.034899 +-0.982706 0.181852 0.034899 +-0.929222 0.367870 0.034899 +-0.929222 0.367870 0.034899 +-0.982706 0.181852 0.034899 +-0.836486 0.546876 0.034899 +-0.929222 0.367870 0.034899 +-0.929222 0.367870 0.034899 +-0.836486 0.546876 0.034899 +-0.836486 0.546876 0.034899 +-0.929222 0.367870 0.034899 +-0.706676 0.706676 0.034899 +-0.836486 0.546876 0.034899 +-0.836486 0.546876 0.034899 +-0.706676 0.706676 0.034899 +-0.706676 0.706676 0.034899 +-0.836486 0.546876 0.034899 +-0.546876 0.836486 0.034899 +-0.706676 0.706676 0.034899 +-0.706676 0.706676 0.034899 +-0.546876 0.836486 0.034899 +-0.546876 0.836486 0.034899 +-0.706676 0.706676 0.034899 +-0.367870 0.929222 0.034899 +-0.546876 0.836486 0.034899 +-0.546876 0.836486 0.034899 +-0.367870 0.929222 0.034899 +-0.367870 0.929222 0.034899 +-0.546876 0.836486 0.034899 +-0.181852 0.982706 0.034899 +-0.367870 0.929222 0.034899 +-0.367870 0.929222 0.034899 +-0.181852 0.982706 0.034899 +-0.181852 0.982706 0.034899 +-0.367870 0.929222 0.034899 +0.000000 0.999391 0.034899 +-0.181852 0.982706 0.034899 +-0.181852 0.982706 0.034899 +0.000000 0.999391 0.034899 +0.000000 0.999391 0.034899 +-0.181852 0.982706 0.034899 +0.181852 0.982706 0.034899 +0.000000 0.999391 0.034899 +0.000000 0.999391 0.034899 +0.181852 0.982706 0.034899 +0.181852 0.982706 0.034899 +0.000000 0.999391 0.034899 +0.367870 0.929222 0.034899 +0.181852 0.982706 0.034899 +0.181852 0.982706 0.034899 +0.367870 0.929222 0.034899 +0.367870 0.929222 0.034899 +0.181852 0.982706 0.034899 +0.367870 0.929222 0.034899 +0.546876 0.836486 0.034899 +0.367870 0.929222 0.034899 +0.546876 0.836486 0.034899 +0.546876 0.836486 0.034899 +0.367870 0.929222 0.034899 +0.706676 0.706676 0.034899 +0.546876 0.836486 0.034899 +0.546876 0.836486 0.034899 +0.706676 0.706676 0.034899 +0.706676 0.706676 0.034899 +0.546876 0.836486 0.034899 +0.836486 0.546876 0.034899 +0.706676 0.706676 0.034899 +0.706676 0.706676 0.034899 +0.836486 0.546876 0.034899 +0.836486 0.546876 0.034899 +0.706676 0.706676 0.034899 +0.836486 0.546876 0.034899 +0.929222 0.367870 0.034899 +0.836486 0.546876 0.034899 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.506722 0.092188 0.857166 +-0.515038 0.000000 0.857167 +-0.515038 0.000000 0.857167 +0.515038 0.000000 0.857167 +0.506156 0.095249 0.857166 +0.515038 0.001458 0.857166 +0.506440 0.093718 0.857167 +0.506156 0.095249 0.857166 +0.515038 0.000000 0.857167 +0.478876 0.189583 0.857167 +0.506156 0.095249 0.857166 +0.506440 0.093718 0.857167 +0.478876 0.189583 0.857167 +0.478273 0.191105 0.857166 +0.506156 0.095249 0.857166 +0.431085 0.281834 0.857167 +0.478273 0.191105 0.857166 +0.478876 0.189583 0.857167 +0.431085 0.281834 0.857167 +0.430160 0.283247 0.857166 +0.478273 0.191105 0.857166 +0.364187 0.364187 0.857167 +0.430160 0.283247 0.857166 +0.431085 0.281834 0.857167 +0.364187 0.364187 0.857167 +0.364066 0.364308 0.857167 +0.430160 0.283247 0.857166 +0.281834 0.431085 0.857167 +0.364066 0.364308 0.857167 +0.364187 0.364187 0.857167 +0.281834 0.431085 0.857167 +0.280420 0.432008 0.857166 +0.364066 0.364308 0.857167 +0.189583 0.478876 0.857167 +0.280420 0.432008 0.857166 +0.281834 0.431085 0.857167 +0.189583 0.478876 0.857167 +0.188061 0.479478 0.857166 +0.280420 0.432008 0.857166 +0.093718 0.506440 0.857167 +0.188061 0.479478 0.857166 +0.189583 0.478876 0.857167 +0.093718 0.506440 0.857167 +0.092188 0.506722 0.857166 +0.188061 0.479478 0.857166 +0.000000 0.515038 0.857167 +0.092188 0.506722 0.857166 +0.093718 0.506440 0.857167 +0.000000 0.515038 0.857167 +-0.001458 0.515038 0.857166 +0.092188 0.506722 0.857166 +-0.093718 0.506440 0.857167 +-0.001458 0.515038 0.857166 +0.000000 0.515038 0.857167 +-0.093718 0.506440 0.857167 +-0.095249 0.506156 0.857166 +-0.001458 0.515038 0.857166 +-0.189583 0.478876 0.857167 +-0.095249 0.506156 0.857166 +-0.093718 0.506440 0.857167 +-0.189583 0.478876 0.857167 +-0.191105 0.478273 0.857166 +-0.095249 0.506156 0.857166 +-0.281834 0.431085 0.857167 +-0.191105 0.478273 0.857166 +-0.189583 0.478876 0.857167 +-0.281834 0.431085 0.857167 +-0.283247 0.430160 0.857166 +-0.191105 0.478273 0.857166 +-0.364187 0.364187 0.857167 +-0.283247 0.430160 0.857166 +-0.281834 0.431085 0.857167 +-0.364187 0.364187 0.857167 +-0.364308 0.364066 0.857167 +-0.283247 0.430160 0.857166 +-0.364187 0.364187 0.857167 +-0.432008 0.280420 0.857166 +-0.364308 0.364066 0.857167 +-0.431085 0.281834 0.857167 +-0.432008 0.280420 0.857166 +-0.364187 0.364187 0.857167 +-0.478876 0.189583 0.857167 +-0.432008 0.280420 0.857166 +-0.431085 0.281834 0.857167 +-0.478876 0.189583 0.857167 +-0.479478 0.188061 0.857166 +-0.432008 0.280420 0.857166 +-0.506440 0.093718 0.857167 +-0.479478 0.188061 0.857166 +-0.478876 0.189583 0.857167 +-0.506440 0.093718 0.857167 +-0.506722 0.092188 0.857166 +-0.479478 0.188061 0.857166 +-0.515038 0.000000 0.857167 +-0.506722 0.092188 0.857166 +-0.506440 0.093718 0.857167 +-0.982706 0.181852 0.034899 +-0.999391 0.000000 0.034899 +-0.999391 0.000000 0.034899 +0.982706 0.181852 0.034899 +0.999391 0.000000 0.034899 +0.999391 0.000000 0.034899 +0.982706 0.181852 0.034899 +0.982706 0.181852 0.034899 +0.999391 0.000000 0.034899 +0.982706 0.181852 0.034899 +0.929222 0.367870 0.034899 +0.982706 0.181852 0.034899 +0.929222 0.367870 0.034899 +0.929222 0.367870 0.034899 +0.982706 0.181852 0.034899 +0.836486 0.546876 0.034899 +0.929222 0.367870 0.034899 +0.929222 0.367870 0.034899 +0.836486 0.546876 0.034899 +0.836486 0.546876 0.034899 +0.929222 0.367870 0.034899 +0.706676 0.706676 0.034899 +0.836486 0.546876 0.034899 +0.836486 0.546876 0.034899 +0.706676 0.706676 0.034899 +0.706676 0.706676 0.034899 +0.836486 0.546876 0.034899 +0.706676 0.706676 0.034899 +0.546876 0.836486 0.034899 +0.706676 0.706676 0.034899 +0.546876 0.836486 0.034899 +0.546876 0.836486 0.034899 +0.706676 0.706676 0.034899 +0.367870 0.929222 0.034899 +0.546876 0.836486 0.034899 +0.546876 0.836486 0.034899 +0.367870 0.929222 0.034899 +0.367870 0.929222 0.034899 +0.546876 0.836486 0.034899 +0.181852 0.982706 0.034899 +0.367870 0.929222 0.034899 +0.367870 0.929222 0.034899 +0.181852 0.982706 0.034899 +0.181852 0.982706 0.034899 +0.367870 0.929222 0.034899 +0.000000 0.999391 0.034899 +0.181852 0.982706 0.034899 +0.181852 0.982706 0.034899 +0.000000 0.999391 0.034899 +0.000000 0.999391 0.034899 +0.181852 0.982706 0.034899 +-0.181852 0.982706 0.034899 +0.000000 0.999391 0.034899 +0.000000 0.999391 0.034899 +-0.181852 0.982706 0.034899 +-0.181852 0.982706 0.034899 +0.000000 0.999391 0.034899 +-0.367870 0.929222 0.034899 +-0.181852 0.982706 0.034899 +-0.181852 0.982706 0.034899 +-0.367870 0.929222 0.034899 +-0.367870 0.929222 0.034899 +-0.181852 0.982706 0.034899 +-0.367870 0.929222 0.034899 +-0.546876 0.836486 0.034899 +-0.367870 0.929222 0.034899 +-0.546876 0.836486 0.034899 +-0.546876 0.836486 0.034899 +-0.367870 0.929222 0.034899 +-0.706676 0.706676 0.034899 +-0.546876 0.836486 0.034899 +-0.546876 0.836486 0.034899 +-0.706676 0.706676 0.034899 +-0.706676 0.706676 0.034899 +-0.546876 0.836486 0.034899 +-0.836486 0.546876 0.034899 +-0.706676 0.706676 0.034899 +-0.706676 0.706676 0.034899 +-0.836486 0.546876 0.034899 +-0.836486 0.546876 0.034899 +-0.706676 0.706676 0.034899 +-0.929222 0.367870 0.034899 +-0.836486 0.546876 0.034899 +-0.836486 0.546876 0.034899 +-0.929222 0.367870 0.034899 +-0.929222 0.367870 0.034899 +-0.836486 0.546876 0.034899 +-0.982706 0.181852 0.034899 +-0.929222 0.367870 0.034899 +-0.929222 0.367870 0.034899 +-0.982706 0.181852 0.034899 +-0.982706 0.181852 0.034899 +-0.929222 0.367870 0.034899 +-0.999391 0.000000 0.034899 +-0.982706 0.181852 0.034899 +-0.982706 0.181852 0.034899 +0.985788 0.167769 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.241742 0.970301 0.008727 +0.080766 0.996695 0.008727 +0.075469 0.997110 0.008727 +0.241742 0.970301 0.008727 +0.241742 0.970301 0.008727 +0.080766 0.996695 0.008727 +0.431558 0.902043 0.008727 +0.241742 0.970301 0.008727 +0.241742 0.970301 0.008727 +0.431558 0.902043 0.008727 +0.431558 0.902043 0.008727 +0.241742 0.970301 0.008727 +0.597344 0.801937 0.008727 +0.431558 0.902043 0.008727 +0.431558 0.902043 0.008727 +0.597344 0.801937 0.008727 +0.597344 0.801937 0.008727 +0.431558 0.902043 0.008727 +0.597344 0.801937 0.008727 +0.733295 0.679855 0.008727 +0.597344 0.801937 0.008727 +0.733295 0.679855 0.008727 +0.733295 0.679855 0.008727 +0.597344 0.801937 0.008727 +0.733295 0.679855 0.008727 +0.844761 0.535072 0.008727 +0.733295 0.679855 0.008727 +0.844761 0.535072 0.008727 +0.844761 0.535072 0.008727 +0.733295 0.679855 0.008727 +0.844761 0.535072 0.008727 +0.932060 0.362199 0.008727 +0.844761 0.535072 0.008727 +0.932060 0.362199 0.008727 +0.932060 0.362199 0.008727 +0.844761 0.535072 0.008727 +0.985788 0.167769 0.008727 +0.932060 0.362199 0.008727 +0.932060 0.362199 0.008727 +0.985788 0.167769 0.008727 +0.985788 0.167769 0.008727 +0.932060 0.362199 0.008727 +0.999962 0.000000 0.008727 +0.985788 0.167769 0.008727 +0.985788 0.167769 0.008727 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.506722 0.092188 0.857166 +-0.515038 0.000000 0.857167 +-0.515038 0.000000 0.857167 +0.515038 0.000000 0.857167 +0.506156 0.095249 0.857166 +0.515038 0.001458 0.857166 +0.506440 0.093718 0.857167 +0.506156 0.095249 0.857166 +0.515038 0.000000 0.857167 +0.478876 0.189583 0.857167 +0.506156 0.095249 0.857166 +0.506440 0.093718 0.857167 +0.478876 0.189583 0.857167 +0.478273 0.191105 0.857166 +0.506156 0.095249 0.857166 +0.431085 0.281834 0.857167 +0.478273 0.191105 0.857166 +0.478876 0.189583 0.857167 +0.431085 0.281834 0.857167 +0.430160 0.283247 0.857166 +0.478273 0.191105 0.857166 +0.364187 0.364187 0.857167 +0.430160 0.283247 0.857166 +0.431085 0.281834 0.857167 +0.364187 0.364187 0.857167 +0.364066 0.364308 0.857167 +0.430160 0.283247 0.857166 +0.281834 0.431085 0.857167 +0.364066 0.364308 0.857167 +0.364187 0.364187 0.857167 +0.281834 0.431085 0.857167 +0.280420 0.432008 0.857166 +0.364066 0.364308 0.857167 +0.189583 0.478876 0.857167 +0.280420 0.432008 0.857166 +0.281834 0.431085 0.857167 +0.189583 0.478876 0.857167 +0.188061 0.479478 0.857166 +0.280420 0.432008 0.857166 +0.093718 0.506440 0.857167 +0.188061 0.479478 0.857166 +0.189583 0.478876 0.857167 +0.093718 0.506440 0.857167 +0.092188 0.506722 0.857166 +0.188061 0.479478 0.857166 +0.000000 0.515038 0.857167 +0.092188 0.506722 0.857166 +0.093718 0.506440 0.857167 +0.000000 0.515038 0.857167 +-0.001458 0.515038 0.857166 +0.092188 0.506722 0.857166 +-0.093718 0.506440 0.857167 +-0.001458 0.515038 0.857166 +0.000000 0.515038 0.857167 +-0.093718 0.506440 0.857167 +-0.095249 0.506156 0.857166 +-0.001458 0.515038 0.857166 +-0.189583 0.478876 0.857167 +-0.095249 0.506156 0.857166 +-0.093718 0.506440 0.857167 +-0.189583 0.478876 0.857167 +-0.191105 0.478273 0.857166 +-0.095249 0.506156 0.857166 +-0.281834 0.431085 0.857167 +-0.191105 0.478273 0.857166 +-0.189583 0.478876 0.857167 +-0.281834 0.431085 0.857167 +-0.283247 0.430160 0.857166 +-0.191105 0.478273 0.857166 +-0.364187 0.364187 0.857167 +-0.283247 0.430160 0.857166 +-0.281834 0.431085 0.857167 +-0.364187 0.364187 0.857167 +-0.364308 0.364066 0.857167 +-0.283247 0.430160 0.857166 +-0.431085 0.281834 0.857167 +-0.364308 0.364066 0.857167 +-0.364187 0.364187 0.857167 +-0.431085 0.281834 0.857167 +-0.432008 0.280420 0.857166 +-0.364308 0.364066 0.857167 +-0.478876 0.189583 0.857167 +-0.432008 0.280420 0.857166 +-0.431085 0.281834 0.857167 +-0.478876 0.189583 0.857167 +-0.479478 0.188061 0.857166 +-0.432008 0.280420 0.857166 +-0.506440 0.093718 0.857167 +-0.479478 0.188061 0.857166 +-0.478876 0.189583 0.857167 +-0.506440 0.093718 0.857167 +-0.506722 0.092188 0.857166 +-0.479478 0.188061 0.857166 +-0.515038 0.000000 0.857167 +-0.506722 0.092188 0.857166 +-0.506440 0.093718 0.857167 +-0.989268 -0.146115 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.500000 -0.866025 0.000000 +-0.621173 -0.783674 0.000000 +-0.500000 -0.866025 0.000000 +-0.621173 -0.783674 0.000000 +-0.621173 -0.783674 0.000000 +-0.500000 -0.866025 0.000000 +-0.760586 -0.649237 0.000000 +-0.621173 -0.783674 0.000000 +-0.621173 -0.783674 0.000000 +-0.760586 -0.649237 0.000000 +-0.760586 -0.649237 0.000000 +-0.621173 -0.783674 0.000000 +-0.866025 -0.500000 0.000000 +-0.760586 -0.649237 0.000000 +-0.760586 -0.649237 0.000000 +-0.866025 -0.500000 0.000000 +-0.866025 -0.500000 0.000000 +-0.760586 -0.649237 0.000000 +-0.942549 -0.334068 0.000000 +-0.866025 -0.500000 0.000000 +-0.866025 -0.500000 0.000000 +-0.942549 -0.334068 0.000000 +-0.942549 -0.334068 0.000000 +-0.866025 -0.500000 0.000000 +-0.989268 -0.146115 0.000000 +-0.942549 -0.334068 0.000000 +-0.942549 -0.334068 0.000000 +-0.989268 -0.146115 0.000000 +-0.989268 -0.146115 0.000000 +-0.942549 -0.334068 0.000000 +-1.000000 0.000000 0.000000 +-0.989268 -0.146115 0.000000 +-0.989268 -0.146115 0.000000 +-0.996896 -0.078735 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.902705 -0.430261 0.000000 +-0.866025 -0.500000 0.000000 +-0.866025 -0.500000 0.000000 +-0.902705 -0.430261 0.000000 +-0.902705 -0.430261 0.000000 +-0.866025 -0.500000 0.000000 +-0.965926 -0.258819 0.000000 +-0.902705 -0.430261 0.000000 +-0.902705 -0.430261 0.000000 +-0.965926 -0.258819 0.000000 +-0.965926 -0.258819 0.000000 +-0.902705 -0.430261 0.000000 +-0.996896 -0.078735 0.000000 +-0.965926 -0.258819 0.000000 +-0.965926 -0.258819 0.000000 +-0.996896 -0.078735 0.000000 +-0.996896 -0.078735 0.000000 +-0.965926 -0.258819 0.000000 +-1.000000 0.000000 0.000000 +-0.996896 -0.078735 0.000000 +-0.996896 -0.078735 0.000000 +-0.996896 -0.078735 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.923664 -0.383204 0.000000 +-0.866025 -0.500000 0.000000 +-0.866025 -0.500000 0.000000 +-0.923664 -0.383204 0.000000 +-0.902705 -0.430261 0.000000 +-0.866025 -0.500000 0.000000 +-0.923664 -0.383204 0.000000 +-0.965926 -0.258819 0.000000 +-0.902705 -0.430261 0.000000 +-0.965926 -0.258819 0.000000 +-0.965926 -0.258819 0.000000 +-0.923664 -0.383204 0.000000 +-0.991518 -0.129968 0.000000 +-0.965926 -0.258819 0.000000 +-0.965926 -0.258819 0.000000 +-0.991518 -0.129968 0.000000 +-0.996896 -0.078735 0.000000 +-0.965926 -0.258819 0.000000 +-1.000000 0.000000 0.000000 +-0.996896 -0.078735 0.000000 +-0.991518 -0.129968 0.000000 +-0.605630 -0.795747 0.000000 +-0.500000 -0.866025 0.000000 +-0.500000 -0.866025 0.000000 +-0.989268 -0.146115 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.989268 -0.146115 0.000000 +-0.991952 -0.126617 0.000000 +-1.000000 0.000000 0.000000 +-0.989268 -0.146115 0.000000 +-0.967097 -0.254408 0.000000 +-0.991952 -0.126617 0.000000 +-0.942549 -0.334068 0.000000 +-0.967097 -0.254408 0.000000 +-0.989268 -0.146115 0.000000 +-0.942549 -0.334068 0.000000 +-0.924976 -0.380026 0.000000 +-0.967097 -0.254408 0.000000 +-0.866025 -0.500000 0.000000 +-0.924976 -0.380026 0.000000 +-0.942549 -0.334068 0.000000 +-0.866025 -0.500000 0.000000 +-0.866025 -0.500000 0.000000 +-0.924976 -0.380026 0.000000 +-0.866025 -0.500000 0.000000 +-0.791600 -0.611040 0.000000 +-0.866025 -0.500000 0.000000 +-0.760586 -0.649237 0.000000 +-0.791600 -0.611040 0.000000 +-0.866025 -0.500000 0.000000 +-0.760586 -0.649237 0.000000 +-0.703872 -0.710326 0.000000 +-0.791600 -0.611040 0.000000 +-0.621173 -0.783674 0.000000 +-0.703872 -0.710326 0.000000 +-0.760586 -0.649237 0.000000 +-0.621173 -0.783674 0.000000 +-0.605630 -0.795747 0.000000 +-0.703872 -0.710326 0.000000 +-0.500000 -0.866025 0.000000 +-0.605630 -0.795747 0.000000 +-0.621173 -0.783674 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +0.983268 -0.181956 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +-0.983268 -0.181956 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.983268 -0.181956 0.008727 +-0.983268 -0.181956 0.008727 +-0.999962 0.000000 0.008727 +-0.929753 -0.368081 0.008727 +-0.983268 -0.181956 0.008727 +-0.983268 -0.181956 0.008727 +-0.929753 -0.368081 0.008727 +-0.929753 -0.368081 0.008727 +-0.983268 -0.181956 0.008727 +-0.836964 -0.547189 0.008727 +-0.929753 -0.368081 0.008727 +-0.929753 -0.368081 0.008727 +-0.836964 -0.547189 0.008727 +-0.836964 -0.547189 0.008727 +-0.929753 -0.368081 0.008727 +-0.707080 -0.707080 0.008727 +-0.836964 -0.547189 0.008727 +-0.836964 -0.547189 0.008727 +-0.707080 -0.707080 0.008727 +-0.707080 -0.707080 0.008727 +-0.836964 -0.547189 0.008727 +-0.547189 -0.836964 0.008727 +-0.707080 -0.707080 0.008727 +-0.707080 -0.707080 0.008727 +-0.547189 -0.836964 0.008727 +-0.547189 -0.836964 0.008727 +-0.707080 -0.707080 0.008727 +-0.368081 -0.929753 0.008727 +-0.547189 -0.836964 0.008727 +-0.547189 -0.836964 0.008727 +-0.368081 -0.929753 0.008727 +-0.368081 -0.929753 0.008727 +-0.547189 -0.836964 0.008727 +-0.181956 -0.983268 0.008727 +-0.368081 -0.929753 0.008727 +-0.368081 -0.929753 0.008727 +-0.181956 -0.983268 0.008727 +-0.181956 -0.983268 0.008727 +-0.368081 -0.929753 0.008727 +0.000000 -0.999962 0.008727 +-0.181956 -0.983268 0.008727 +-0.181956 -0.983268 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +-0.181956 -0.983268 0.008727 +0.181956 -0.983268 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.181956 -0.983268 0.008727 +0.181956 -0.983268 0.008727 +0.000000 -0.999962 0.008727 +0.368081 -0.929753 0.008727 +0.181956 -0.983268 0.008727 +0.181956 -0.983268 0.008727 +0.368081 -0.929753 0.008727 +0.368081 -0.929753 0.008727 +0.181956 -0.983268 0.008727 +0.547189 -0.836964 0.008727 +0.368081 -0.929753 0.008727 +0.368081 -0.929753 0.008727 +0.547189 -0.836964 0.008727 +0.547189 -0.836964 0.008727 +0.368081 -0.929753 0.008727 +0.707080 -0.707080 0.008727 +0.547189 -0.836964 0.008727 +0.547189 -0.836964 0.008727 +0.707080 -0.707080 0.008727 +0.707080 -0.707080 0.008727 +0.547189 -0.836964 0.008727 +0.836964 -0.547189 0.008727 +0.707080 -0.707080 0.008727 +0.707080 -0.707080 0.008727 +0.836964 -0.547189 0.008727 +0.836964 -0.547189 0.008727 +0.707080 -0.707080 0.008727 +0.929753 -0.368081 0.008727 +0.836964 -0.547189 0.008727 +0.836964 -0.547189 0.008727 +0.929753 -0.368081 0.008727 +0.929753 -0.368081 0.008727 +0.836964 -0.547189 0.008727 +0.983268 -0.181956 0.008727 +0.929753 -0.368081 0.008727 +0.929753 -0.368081 0.008727 +0.983268 -0.181956 0.008727 +0.983268 -0.181956 0.008727 +0.929753 -0.368081 0.008727 +0.999962 0.000000 0.008727 +0.983268 -0.181956 0.008727 +0.983268 -0.181956 0.008727 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +0.000000 0.158432 -0.987370 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.130543 0.089773 -0.987370 +0.000000 0.000000 -1.000000 +-0.112028 0.112028 -0.987370 +-0.130543 0.089773 -0.987370 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.130543 0.089773 -0.987370 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.145400 0.062926 -0.987370 +0.000000 0.000000 -1.000000 +-0.130543 0.089773 -0.987370 +-0.145400 0.062926 -0.987370 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.155070 0.032464 -0.987370 +0.000000 0.000000 -1.000000 +-0.145400 0.062926 -0.987370 +-0.155070 0.032464 -0.987370 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.112028 0.112028 -0.987370 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.089773 0.130543 -0.987370 +-0.112028 0.112028 -0.987370 +0.000000 0.000000 -1.000000 +-0.089773 0.130543 -0.987370 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.062926 0.145400 -0.987370 +-0.089773 0.130543 -0.987370 +0.000000 0.000000 -1.000000 +-0.062926 0.145400 -0.987370 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.032464 0.155070 -0.987370 +-0.062926 0.145400 -0.987370 +0.000000 0.000000 -1.000000 +-0.032464 0.155070 -0.987370 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.158432 0.000000 -0.987370 +0.000000 0.000000 -1.000000 +-0.155070 0.032464 -0.987370 +-0.158432 0.000000 -0.987370 +0.000000 0.000000 -1.000000 +-0.338451 0.070855 -0.938312 +-0.158432 0.000000 -0.987370 +-0.155070 0.032464 -0.987370 +-0.338451 0.070855 -0.938312 +-0.345789 0.000000 -0.938312 +-0.158432 0.000000 -0.987370 +-0.499916 0.104658 -0.859727 +-0.345789 0.000000 -0.938312 +-0.338451 0.070855 -0.938312 +-0.499916 0.104658 -0.859727 +-0.510754 0.000000 -0.859727 +-0.345789 0.000000 -0.938312 +-0.644689 0.134967 -0.752436 +-0.510754 0.000000 -0.859727 +-0.499916 0.104658 -0.859727 +-0.644689 0.134967 -0.752436 +-0.658666 0.000000 -0.752436 +-0.510754 0.000000 -0.859727 +-0.774562 0.162156 -0.611358 +-0.658666 0.000000 -0.752436 +-0.644689 0.134967 -0.752436 +-0.774562 0.162156 -0.611358 +-0.791354 0.000000 -0.611358 +-0.658666 0.000000 -0.752436 +-0.774562 0.162156 -0.611358 +-0.878218 0.000000 -0.478261 +-0.791354 0.000000 -0.611358 +-0.774562 0.162156 -0.611358 +-0.863556 0.159803 -0.478261 +-0.878218 0.000000 -0.478261 +-0.774562 0.162156 -0.611358 +-0.816557 0.323267 -0.478261 +-0.863556 0.159803 -0.478261 +-0.726259 0.314308 -0.611358 +-0.816557 0.323267 -0.478261 +-0.774562 0.162156 -0.611358 +-0.726259 0.314308 -0.611358 +-0.735064 0.480569 -0.478261 +-0.816557 0.323267 -0.478261 +-0.652051 0.448409 -0.611358 +-0.735064 0.480569 -0.478261 +-0.726259 0.314308 -0.611358 +-0.652051 0.448409 -0.611358 +-0.681807 0.553539 -0.478261 +-0.735064 0.480569 -0.478261 +-0.559572 0.559572 -0.611358 +-0.681807 0.553539 -0.478261 +-0.652051 0.448409 -0.611358 +-0.559572 0.559572 -0.611358 +-0.620994 0.620994 -0.478261 +-0.681807 0.553539 -0.478261 +-0.448409 0.652051 -0.611358 +-0.620994 0.620994 -0.478261 +-0.559572 0.559572 -0.611358 +-0.448409 0.652051 -0.611358 +-0.553539 0.681807 -0.478261 +-0.620994 0.620994 -0.478261 +-0.448409 0.652051 -0.611358 +-0.480569 0.735064 -0.478261 +-0.553539 0.681807 -0.478261 +-0.314308 0.726259 -0.611358 +-0.480569 0.735064 -0.478261 +-0.448409 0.652051 -0.611358 +-0.314308 0.726259 -0.611358 +-0.323267 0.816557 -0.478261 +-0.480569 0.735064 -0.478261 +-0.162156 0.774562 -0.611358 +-0.323267 0.816557 -0.478261 +-0.314308 0.726259 -0.611358 +-0.162156 0.774562 -0.611358 +-0.159803 0.863556 -0.478261 +-0.323267 0.816557 -0.478261 +-0.159803 0.863556 -0.478261 +0.000000 0.791354 -0.611358 +0.000000 0.878218 -0.478261 +-0.162156 0.774562 -0.611358 +0.000000 0.791354 -0.611358 +-0.159803 0.863556 -0.478261 +-0.134967 0.644689 -0.752436 +0.000000 0.791354 -0.611358 +-0.162156 0.774562 -0.611358 +-0.134967 0.644689 -0.752436 +0.000000 0.658666 -0.752436 +0.000000 0.791354 -0.611358 +-0.104658 0.499916 -0.859727 +0.000000 0.658666 -0.752436 +-0.134967 0.644689 -0.752436 +-0.104658 0.499916 -0.859727 +0.000000 0.510754 -0.859727 +0.000000 0.658666 -0.752436 +-0.070855 0.338451 -0.938312 +0.000000 0.510754 -0.859727 +-0.104658 0.499916 -0.859727 +-0.070855 0.338451 -0.938312 +0.000000 0.345789 -0.938312 +0.000000 0.510754 -0.859727 +-0.032464 0.155070 -0.987370 +0.000000 0.345789 -0.938312 +-0.070855 0.338451 -0.938312 +-0.032464 0.155070 -0.987370 +0.000000 0.158432 -0.987370 +0.000000 0.345789 -0.938312 +0.000000 0.000000 -1.000000 +0.000000 0.158432 -0.987370 +-0.032464 0.155070 -0.987370 +-0.162156 0.774562 -0.611358 +-0.261607 0.604485 -0.752436 +-0.134967 0.644689 -0.752436 +-0.261607 0.604485 -0.752436 +-0.162156 0.774562 -0.611358 +-0.314308 0.726259 -0.611358 +-0.134967 0.644689 -0.752436 +-0.202860 0.468740 -0.859727 +-0.104658 0.499916 -0.859727 +-0.202860 0.468740 -0.859727 +-0.134967 0.644689 -0.752436 +-0.261607 0.604485 -0.752436 +-0.104658 0.499916 -0.859727 +-0.137339 0.317345 -0.938312 +-0.070855 0.338451 -0.938312 +-0.137339 0.317345 -0.938312 +-0.104658 0.499916 -0.859727 +-0.202860 0.468740 -0.859727 +-0.070855 0.338451 -0.938312 +-0.062926 0.145400 -0.987370 +-0.032464 0.155070 -0.987370 +-0.062926 0.145400 -0.987370 +-0.070855 0.338451 -0.938312 +-0.137339 0.317345 -0.938312 +-0.314308 0.726259 -0.611358 +-0.373223 0.542720 -0.752436 +-0.261607 0.604485 -0.752436 +-0.373223 0.542720 -0.752436 +-0.314308 0.726259 -0.611358 +-0.448409 0.652051 -0.611358 +-0.261607 0.604485 -0.752436 +-0.289411 0.420846 -0.859727 +-0.202860 0.468740 -0.859727 +-0.289411 0.420846 -0.859727 +-0.261607 0.604485 -0.752436 +-0.373223 0.542720 -0.752436 +-0.448409 0.652051 -0.611358 +-0.465747 0.465747 -0.752436 +-0.373223 0.542720 -0.752436 +-0.465747 0.465747 -0.752436 +-0.448409 0.652051 -0.611358 +-0.559572 0.559572 -0.611358 +-0.373223 0.542720 -0.752436 +-0.361158 0.361158 -0.859727 +-0.289411 0.420846 -0.859727 +-0.361158 0.361158 -0.859727 +-0.373223 0.542720 -0.752436 +-0.465747 0.465747 -0.752436 +-0.202860 0.468740 -0.859727 +-0.195936 0.284919 -0.938312 +-0.137339 0.317345 -0.938312 +-0.195936 0.284919 -0.938312 +-0.202860 0.468740 -0.859727 +-0.289411 0.420846 -0.859727 +-0.137339 0.317345 -0.938312 +-0.089773 0.130543 -0.987370 +-0.062926 0.145400 -0.987370 +-0.089773 0.130543 -0.987370 +-0.137339 0.317345 -0.938312 +-0.195936 0.284919 -0.938312 +-0.289411 0.420846 -0.859727 +-0.244509 0.244509 -0.938312 +-0.195936 0.284919 -0.938312 +-0.244509 0.244509 -0.938312 +-0.289411 0.420846 -0.859727 +-0.361158 0.361158 -0.859727 +-0.195936 0.284919 -0.938312 +-0.112028 0.112028 -0.987370 +-0.089773 0.130543 -0.987370 +-0.112028 0.112028 -0.987370 +-0.195936 0.284919 -0.938312 +-0.244509 0.244509 -0.938312 +-0.559572 0.559572 -0.611358 +-0.542720 0.373223 -0.752436 +-0.465747 0.465747 -0.752436 +-0.542720 0.373223 -0.752436 +-0.559572 0.559572 -0.611358 +-0.652051 0.448409 -0.611358 +-0.465747 0.465747 -0.752436 +-0.420846 0.289411 -0.859727 +-0.361158 0.361158 -0.859727 +-0.420846 0.289411 -0.859727 +-0.465747 0.465747 -0.752436 +-0.542720 0.373223 -0.752436 +-0.652051 0.448409 -0.611358 +-0.604485 0.261607 -0.752436 +-0.542720 0.373223 -0.752436 +-0.604485 0.261607 -0.752436 +-0.652051 0.448409 -0.611358 +-0.726259 0.314308 -0.611358 +-0.542720 0.373223 -0.752436 +-0.468740 0.202860 -0.859727 +-0.420846 0.289411 -0.859727 +-0.468740 0.202860 -0.859727 +-0.542720 0.373223 -0.752436 +-0.604485 0.261607 -0.752436 +-0.361158 0.361158 -0.859727 +-0.284919 0.195936 -0.938312 +-0.244509 0.244509 -0.938312 +-0.284919 0.195936 -0.938312 +-0.361158 0.361158 -0.859727 +-0.420846 0.289411 -0.859727 +-0.244509 0.244509 -0.938312 +-0.130543 0.089773 -0.987370 +-0.112028 0.112028 -0.987370 +-0.130543 0.089773 -0.987370 +-0.244509 0.244509 -0.938312 +-0.284919 0.195936 -0.938312 +-0.420846 0.289411 -0.859727 +-0.317345 0.137339 -0.938312 +-0.284919 0.195936 -0.938312 +-0.317345 0.137339 -0.938312 +-0.420846 0.289411 -0.859727 +-0.468740 0.202860 -0.859727 +-0.284919 0.195936 -0.938312 +-0.145400 0.062926 -0.987370 +-0.130543 0.089773 -0.987370 +-0.145400 0.062926 -0.987370 +-0.284919 0.195936 -0.938312 +-0.317345 0.137339 -0.938312 +-0.726259 0.314308 -0.611358 +-0.644689 0.134967 -0.752436 +-0.604485 0.261607 -0.752436 +-0.644689 0.134967 -0.752436 +-0.726259 0.314308 -0.611358 +-0.774562 0.162156 -0.611358 +-0.604485 0.261607 -0.752436 +-0.499916 0.104658 -0.859727 +-0.468740 0.202860 -0.859727 +-0.499916 0.104658 -0.859727 +-0.604485 0.261607 -0.752436 +-0.644689 0.134967 -0.752436 +-0.468740 0.202860 -0.859727 +-0.338451 0.070855 -0.938312 +-0.317345 0.137339 -0.938312 +-0.338451 0.070855 -0.938312 +-0.468740 0.202860 -0.859727 +-0.499916 0.104658 -0.859727 +-0.317345 0.137339 -0.938312 +-0.155070 0.032464 -0.987370 +-0.145400 0.062926 -0.987370 +-0.155070 0.032464 -0.987370 +-0.317345 0.137339 -0.938312 +-0.338451 0.070855 -0.938312 +0.000000 0.144208 -0.989547 +-0.008882 0.047995 -0.998808 +0.000000 0.048809 -0.998808 +-0.118823 0.081713 -0.989547 +-0.034513 0.034513 -0.998808 +-0.101971 0.101971 -0.989547 +-0.118823 0.081713 -0.989547 +-0.037893 0.030764 -0.998808 +-0.034513 0.034513 -0.998808 +-0.118823 0.081713 -0.989547 +-0.040853 0.026709 -0.998808 +-0.037893 0.030764 -0.998808 +-0.132346 0.057276 -0.989547 +-0.040853 0.026709 -0.998808 +-0.118823 0.081713 -0.989547 +-0.132346 0.057276 -0.989547 +-0.045382 0.017966 -0.998808 +-0.040853 0.026709 -0.998808 +-0.141148 0.029550 -0.989547 +-0.045382 0.017966 -0.998808 +-0.132346 0.057276 -0.989547 +-0.141148 0.029550 -0.989547 +-0.047995 0.008882 -0.998808 +-0.045382 0.017966 -0.998808 +-0.047995 0.008882 -0.998808 +-0.144208 0.000000 -0.989547 +-0.048809 0.000000 -0.998808 +-0.141148 0.029550 -0.989547 +-0.144208 0.000000 -0.989547 +-0.047995 0.008882 -0.998808 +-0.030764 0.037893 -0.998808 +-0.101971 0.101971 -0.989547 +-0.034513 0.034513 -0.998808 +-0.030764 0.037893 -0.998808 +-0.081713 0.118823 -0.989547 +-0.101971 0.101971 -0.989547 +-0.026709 0.040853 -0.998808 +-0.081713 0.118823 -0.989547 +-0.030764 0.037893 -0.998808 +-0.026709 0.040853 -0.998808 +-0.057276 0.132346 -0.989547 +-0.081713 0.118823 -0.989547 +-0.017966 0.045382 -0.998808 +-0.057276 0.132346 -0.989547 +-0.026709 0.040853 -0.998808 +-0.017966 0.045382 -0.998808 +-0.029550 0.141148 -0.989547 +-0.057276 0.132346 -0.989547 +-0.008882 0.047995 -0.998808 +-0.029550 0.141148 -0.989547 +-0.017966 0.045382 -0.998808 +-0.315032 0.065952 -0.946787 +-0.144208 0.000000 -0.989547 +-0.141148 0.029550 -0.989547 +-0.315032 0.065952 -0.946787 +-0.321862 0.000000 -0.946787 +-0.144208 0.000000 -0.989547 +-0.478397 0.100153 -0.872414 +-0.321862 0.000000 -0.946787 +-0.315032 0.065952 -0.946787 +-0.478397 0.100153 -0.872414 +-0.488768 0.000000 -0.872414 +-0.321862 0.000000 -0.946787 +-0.478397 0.100153 -0.872414 +-0.570046 0.000000 -0.821613 +-0.488768 0.000000 -0.872414 +-0.478397 0.100153 -0.872414 +-0.560529 0.103727 -0.821613 +-0.570046 0.000000 -0.821613 +-0.478397 0.100153 -0.872414 +-0.530022 0.209831 -0.821613 +-0.560529 0.103727 -0.821613 +-0.448563 0.194128 -0.872414 +-0.530022 0.209831 -0.821613 +-0.478397 0.100153 -0.872414 +-0.448563 0.194128 -0.872414 +-0.477126 0.311935 -0.821613 +-0.530022 0.209831 -0.821613 +-0.402730 0.276953 -0.872414 +-0.477126 0.311935 -0.821613 +-0.448563 0.194128 -0.872414 +-0.402730 0.276953 -0.872414 +-0.442557 0.359299 -0.821613 +-0.477126 0.311935 -0.821613 +-0.345612 0.345612 -0.872414 +-0.442557 0.359299 -0.821613 +-0.402730 0.276953 -0.872414 +-0.345612 0.345612 -0.872414 +-0.403083 0.403083 -0.821613 +-0.442557 0.359299 -0.821613 +-0.276953 0.402730 -0.872414 +-0.403083 0.403083 -0.821613 +-0.345612 0.345612 -0.872414 +-0.276953 0.402730 -0.872414 +-0.359299 0.442557 -0.821613 +-0.403083 0.403083 -0.821613 +-0.276953 0.402730 -0.872414 +-0.311935 0.477126 -0.821613 +-0.359299 0.442557 -0.821613 +-0.194128 0.448563 -0.872414 +-0.311935 0.477126 -0.821613 +-0.276953 0.402730 -0.872414 +-0.194128 0.448563 -0.872414 +-0.209831 0.530022 -0.821613 +-0.311935 0.477126 -0.821613 +-0.100153 0.478397 -0.872414 +-0.209831 0.530022 -0.821613 +-0.194128 0.448563 -0.872414 +-0.100153 0.478397 -0.872414 +-0.103727 0.560529 -0.821613 +-0.209831 0.530022 -0.821613 +-0.103727 0.560529 -0.821613 +0.000000 0.488768 -0.872414 +0.000000 0.570046 -0.821613 +-0.100153 0.478397 -0.872414 +0.000000 0.488768 -0.872414 +-0.103727 0.560529 -0.821613 +-0.065952 0.315032 -0.946787 +0.000000 0.488768 -0.872414 +-0.100153 0.478397 -0.872414 +-0.065952 0.315032 -0.946787 +0.000000 0.321862 -0.946787 +0.000000 0.488768 -0.872414 +-0.029550 0.141148 -0.989547 +0.000000 0.321862 -0.946787 +-0.065952 0.315032 -0.946787 +-0.029550 0.141148 -0.989547 +0.000000 0.144208 -0.989547 +0.000000 0.321862 -0.946787 +-0.008882 0.047995 -0.998808 +0.000000 0.144208 -0.989547 +-0.029550 0.141148 -0.989547 +-0.100153 0.478397 -0.872414 +-0.127836 0.295386 -0.946787 +-0.065952 0.315032 -0.946787 +-0.127836 0.295386 -0.946787 +-0.100153 0.478397 -0.872414 +-0.194128 0.448563 -0.872414 +-0.065952 0.315032 -0.946787 +-0.057276 0.132346 -0.989547 +-0.029550 0.141148 -0.989547 +-0.057276 0.132346 -0.989547 +-0.065952 0.315032 -0.946787 +-0.127836 0.295386 -0.946787 +-0.194128 0.448563 -0.872414 +-0.182378 0.265204 -0.946787 +-0.127836 0.295386 -0.946787 +-0.182378 0.265204 -0.946787 +-0.194128 0.448563 -0.872414 +-0.276953 0.402730 -0.872414 +-0.276953 0.402730 -0.872414 +-0.227591 0.227591 -0.946787 +-0.182378 0.265204 -0.946787 +-0.227591 0.227591 -0.946787 +-0.276953 0.402730 -0.872414 +-0.345612 0.345612 -0.872414 +-0.127836 0.295386 -0.946787 +-0.081713 0.118823 -0.989547 +-0.057276 0.132346 -0.989547 +-0.081713 0.118823 -0.989547 +-0.127836 0.295386 -0.946787 +-0.182378 0.265204 -0.946787 +-0.182378 0.265204 -0.946787 +-0.101971 0.101971 -0.989547 +-0.081713 0.118823 -0.989547 +-0.101971 0.101971 -0.989547 +-0.182378 0.265204 -0.946787 +-0.227591 0.227591 -0.946787 +-0.345612 0.345612 -0.872414 +-0.265204 0.182378 -0.946787 +-0.227591 0.227591 -0.946787 +-0.265204 0.182378 -0.946787 +-0.345612 0.345612 -0.872414 +-0.402730 0.276953 -0.872414 +-0.402730 0.276953 -0.872414 +-0.295386 0.127836 -0.946787 +-0.265204 0.182378 -0.946787 +-0.295386 0.127836 -0.946787 +-0.402730 0.276953 -0.872414 +-0.448563 0.194128 -0.872414 +-0.227591 0.227591 -0.946787 +-0.118823 0.081713 -0.989547 +-0.101971 0.101971 -0.989547 +-0.118823 0.081713 -0.989547 +-0.227591 0.227591 -0.946787 +-0.265204 0.182378 -0.946787 +-0.265204 0.182378 -0.946787 +-0.132346 0.057276 -0.989547 +-0.118823 0.081713 -0.989547 +-0.132346 0.057276 -0.989547 +-0.265204 0.182378 -0.946787 +-0.295386 0.127836 -0.946787 +-0.448563 0.194128 -0.872414 +-0.315032 0.065952 -0.946787 +-0.295386 0.127836 -0.946787 +-0.315032 0.065952 -0.946787 +-0.448563 0.194128 -0.872414 +-0.478397 0.100153 -0.872414 +-0.295386 0.127836 -0.946787 +-0.141148 0.029550 -0.989547 +-0.132346 0.057276 -0.989547 +-0.141148 0.029550 -0.989547 +-0.295386 0.127836 -0.946787 +-0.315032 0.065952 -0.946787 +0.000000 -0.120008 -0.992773 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.084859 -0.084859 -0.992773 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.098883 -0.068001 -0.992773 +0.000000 0.000000 -1.000000 +-0.084859 -0.084859 -0.992773 +-0.098883 -0.068001 -0.992773 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.110137 -0.047665 -0.992773 +0.000000 0.000000 -1.000000 +-0.098883 -0.068001 -0.992773 +-0.110137 -0.047665 -0.992773 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.117462 -0.024591 -0.992773 +0.000000 0.000000 -1.000000 +-0.110137 -0.047665 -0.992773 +-0.117462 -0.024591 -0.992773 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.068001 -0.098883 -0.992773 +-0.084859 -0.084859 -0.992773 +0.000000 0.000000 -1.000000 +-0.068001 -0.098883 -0.992773 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.068001 -0.098883 -0.992773 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.047665 -0.110137 -0.992773 +-0.068001 -0.098883 -0.992773 +0.000000 0.000000 -1.000000 +-0.047665 -0.110137 -0.992773 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.024591 -0.117462 -0.992773 +-0.047665 -0.110137 -0.992773 +0.000000 0.000000 -1.000000 +-0.024591 -0.117462 -0.992773 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.120008 0.000000 -0.992773 +0.000000 0.000000 -1.000000 +-0.117462 -0.024591 -0.992773 +-0.120008 0.000000 -0.992773 +0.000000 0.000000 -1.000000 +-0.117462 -0.024591 -0.992773 +-0.298653 0.000000 -0.954362 +-0.120008 0.000000 -0.992773 +-0.292316 -0.061197 -0.954362 +-0.298653 0.000000 -0.954362 +-0.117462 -0.024591 -0.992773 +-0.457409 -0.095759 -0.884085 +-0.298653 0.000000 -0.954362 +-0.292316 -0.061197 -0.954362 +-0.457409 -0.095759 -0.884085 +-0.467325 0.000000 -0.884085 +-0.298653 0.000000 -0.954362 +-0.457409 -0.095759 -0.884085 +-0.570046 0.000000 -0.821613 +-0.467325 0.000000 -0.884085 +-0.457409 -0.095759 -0.884085 +-0.560529 -0.103727 -0.821613 +-0.570046 0.000000 -0.821613 +-0.457409 -0.095759 -0.884085 +-0.530022 -0.209831 -0.821613 +-0.560529 -0.103727 -0.821613 +-0.428884 -0.185611 -0.884085 +-0.530022 -0.209831 -0.821613 +-0.457409 -0.095759 -0.884085 +-0.428884 -0.185611 -0.884085 +-0.477126 -0.311935 -0.821613 +-0.530022 -0.209831 -0.821613 +-0.385062 -0.264803 -0.884085 +-0.477126 -0.311935 -0.821613 +-0.428884 -0.185611 -0.884085 +-0.385062 -0.264803 -0.884085 +-0.442557 -0.359299 -0.821613 +-0.477126 -0.311935 -0.821613 +-0.330449 -0.330449 -0.884085 +-0.442557 -0.359299 -0.821613 +-0.385062 -0.264803 -0.884085 +-0.330449 -0.330449 -0.884085 +-0.403083 -0.403083 -0.821613 +-0.442557 -0.359299 -0.821613 +-0.264803 -0.385062 -0.884085 +-0.403083 -0.403083 -0.821613 +-0.330449 -0.330449 -0.884085 +-0.264803 -0.385062 -0.884085 +-0.359299 -0.442557 -0.821613 +-0.403083 -0.403083 -0.821613 +-0.264803 -0.385062 -0.884085 +-0.311935 -0.477126 -0.821613 +-0.359299 -0.442557 -0.821613 +-0.185611 -0.428884 -0.884085 +-0.311935 -0.477126 -0.821613 +-0.264803 -0.385062 -0.884085 +-0.185611 -0.428884 -0.884085 +-0.209831 -0.530022 -0.821613 +-0.311935 -0.477126 -0.821613 +-0.095759 -0.457409 -0.884085 +-0.209831 -0.530022 -0.821613 +-0.185611 -0.428884 -0.884085 +-0.095759 -0.457409 -0.884085 +-0.103727 -0.560529 -0.821613 +-0.209831 -0.530022 -0.821613 +-0.103727 -0.560529 -0.821613 +0.000000 -0.467325 -0.884085 +0.000000 -0.570046 -0.821613 +-0.095759 -0.457409 -0.884085 +0.000000 -0.467325 -0.884085 +-0.103727 -0.560529 -0.821613 +-0.061197 -0.292316 -0.954362 +0.000000 -0.467325 -0.884085 +-0.095759 -0.457409 -0.884085 +-0.061197 -0.292316 -0.954362 +0.000000 -0.298653 -0.954362 +0.000000 -0.467325 -0.884085 +-0.061197 -0.292316 -0.954362 +0.000000 -0.120008 -0.992773 +0.000000 -0.298653 -0.954362 +-0.024591 -0.117462 -0.992773 +0.000000 -0.120008 -0.992773 +-0.061197 -0.292316 -0.954362 +0.000000 0.000000 -1.000000 +0.000000 -0.120008 -0.992773 +-0.024591 -0.117462 -0.992773 +-0.457409 -0.095759 -0.884085 +-0.274086 -0.118618 -0.954362 +-0.428884 -0.185611 -0.884085 +-0.274086 -0.118618 -0.954362 +-0.457409 -0.095759 -0.884085 +-0.292316 -0.061197 -0.954362 +-0.428884 -0.185611 -0.884085 +-0.246081 -0.169227 -0.954362 +-0.385062 -0.264803 -0.884085 +-0.246081 -0.169227 -0.954362 +-0.428884 -0.185611 -0.884085 +-0.274086 -0.118618 -0.954362 +-0.385062 -0.264803 -0.884085 +-0.211179 -0.211179 -0.954362 +-0.330449 -0.330449 -0.884085 +-0.211179 -0.211179 -0.954362 +-0.385062 -0.264803 -0.884085 +-0.246081 -0.169227 -0.954362 +-0.292316 -0.061197 -0.954362 +-0.110137 -0.047665 -0.992773 +-0.274086 -0.118618 -0.954362 +-0.110137 -0.047665 -0.992773 +-0.292316 -0.061197 -0.954362 +-0.117462 -0.024591 -0.992773 +-0.274086 -0.118618 -0.954362 +-0.098883 -0.068001 -0.992773 +-0.246081 -0.169227 -0.954362 +-0.098883 -0.068001 -0.992773 +-0.274086 -0.118618 -0.954362 +-0.110137 -0.047665 -0.992773 +-0.246081 -0.169227 -0.954362 +-0.084859 -0.084859 -0.992773 +-0.211179 -0.211179 -0.954362 +-0.084859 -0.084859 -0.992773 +-0.246081 -0.169227 -0.954362 +-0.098883 -0.068001 -0.992773 +-0.330449 -0.330449 -0.884085 +-0.169227 -0.246081 -0.954362 +-0.264803 -0.385062 -0.884085 +-0.169227 -0.246081 -0.954362 +-0.330449 -0.330449 -0.884085 +-0.211179 -0.211179 -0.954362 +-0.264803 -0.385062 -0.884085 +-0.118618 -0.274086 -0.954362 +-0.185611 -0.428884 -0.884085 +-0.118618 -0.274086 -0.954362 +-0.264803 -0.385062 -0.884085 +-0.169227 -0.246081 -0.954362 +-0.185611 -0.428884 -0.884085 +-0.061197 -0.292316 -0.954362 +-0.095759 -0.457409 -0.884085 +-0.061197 -0.292316 -0.954362 +-0.185611 -0.428884 -0.884085 +-0.118618 -0.274086 -0.954362 +-0.211179 -0.211179 -0.954362 +-0.068001 -0.098883 -0.992773 +-0.169227 -0.246081 -0.954362 +-0.068001 -0.098883 -0.992773 +-0.211179 -0.211179 -0.954362 +-0.084859 -0.084859 -0.992773 +-0.169227 -0.246081 -0.954362 +-0.047665 -0.110137 -0.992773 +-0.118618 -0.274086 -0.954362 +-0.047665 -0.110137 -0.992773 +-0.169227 -0.246081 -0.954362 +-0.068001 -0.098883 -0.992773 +-0.118618 -0.274086 -0.954362 +-0.024591 -0.117462 -0.992773 +-0.061197 -0.292316 -0.954362 +-0.024591 -0.117462 -0.992773 +-0.118618 -0.274086 -0.954362 +-0.047665 -0.110137 -0.992773 +-0.030764 -0.037893 -0.998808 +-0.129039 -0.129039 -0.983208 +-0.034513 -0.034513 -0.998808 +-0.150365 -0.103404 -0.983208 +-0.034513 -0.034513 -0.998808 +-0.129039 -0.129039 -0.983208 +-0.150365 -0.103404 -0.983208 +-0.037893 -0.030764 -0.998808 +-0.034513 -0.034513 -0.998808 +-0.150365 -0.103404 -0.983208 +-0.040853 -0.026709 -0.998808 +-0.037893 -0.030764 -0.998808 +-0.167477 -0.072480 -0.983208 +-0.040853 -0.026709 -0.998808 +-0.150365 -0.103404 -0.983208 +-0.167477 -0.072480 -0.983208 +-0.045382 -0.017966 -0.998808 +-0.040853 -0.026709 -0.998808 +-0.178616 -0.037394 -0.983208 +-0.045382 -0.017966 -0.998808 +-0.167477 -0.072480 -0.983208 +-0.178616 -0.037394 -0.983208 +-0.047995 -0.008882 -0.998808 +-0.045382 -0.017966 -0.998808 +-0.047995 -0.008882 -0.998808 +-0.182489 0.000000 -0.983208 +-0.048809 0.000000 -0.998808 +-0.178616 -0.037394 -0.983208 +-0.182489 0.000000 -0.983208 +-0.047995 -0.008882 -0.998808 +-0.360770 -0.075528 -0.929591 +-0.182489 0.000000 -0.983208 +-0.178616 -0.037394 -0.983208 +-0.360770 -0.075528 -0.929591 +-0.368592 0.000000 -0.929591 +-0.182489 0.000000 -0.983208 +-0.360770 -0.075528 -0.929591 +-0.531589 0.000000 -0.847002 +-0.368592 0.000000 -0.929591 +-0.520310 -0.108928 -0.847002 +-0.531589 0.000000 -0.847002 +-0.360770 -0.075528 -0.929591 +-0.520310 -0.108928 -0.847002 +-0.676838 0.000000 -0.736132 +-0.531589 0.000000 -0.847002 +-0.662476 -0.138690 -0.736132 +-0.676838 0.000000 -0.736132 +-0.520310 -0.108928 -0.847002 +-0.788939 -0.165166 -0.591858 +-0.676838 0.000000 -0.736132 +-0.662476 -0.138690 -0.736132 +-0.788939 -0.165166 -0.591858 +-0.806043 0.000000 -0.591858 +-0.676838 0.000000 -0.736132 +-0.788939 -0.165166 -0.591858 +-0.878218 0.000000 -0.478261 +-0.806043 0.000000 -0.591858 +-0.788939 -0.165166 -0.591858 +-0.863556 -0.159803 -0.478261 +-0.878218 0.000000 -0.478261 +-0.788939 -0.165166 -0.591858 +-0.816557 -0.323267 -0.478261 +-0.863556 -0.159803 -0.478261 +-0.739739 -0.320142 -0.591858 +-0.816557 -0.323267 -0.478261 +-0.788939 -0.165166 -0.591858 +-0.739739 -0.320142 -0.591858 +-0.735064 -0.480569 -0.478261 +-0.816557 -0.323267 -0.478261 +-0.664154 -0.456732 -0.591858 +-0.735064 -0.480569 -0.478261 +-0.739739 -0.320142 -0.591858 +-0.664154 -0.456732 -0.591858 +-0.681807 -0.553539 -0.478261 +-0.735064 -0.480569 -0.478261 +-0.569958 -0.569958 -0.591858 +-0.681807 -0.553539 -0.478261 +-0.664154 -0.456732 -0.591858 +-0.569958 -0.569958 -0.591858 +-0.620994 -0.620994 -0.478261 +-0.681807 -0.553539 -0.478261 +-0.456732 -0.664154 -0.591858 +-0.620994 -0.620994 -0.478261 +-0.569958 -0.569958 -0.591858 +-0.456732 -0.664154 -0.591858 +-0.553539 -0.681807 -0.478261 +-0.620994 -0.620994 -0.478261 +-0.456732 -0.664154 -0.591858 +-0.480569 -0.735064 -0.478261 +-0.553539 -0.681807 -0.478261 +-0.320142 -0.739739 -0.591858 +-0.480569 -0.735064 -0.478261 +-0.456732 -0.664154 -0.591858 +-0.320142 -0.739739 -0.591858 +-0.323267 -0.816557 -0.478261 +-0.480569 -0.735064 -0.478261 +-0.165166 -0.788939 -0.591858 +-0.323267 -0.816557 -0.478261 +-0.320142 -0.739739 -0.591858 +-0.165166 -0.788939 -0.591858 +-0.159803 -0.863556 -0.478261 +-0.323267 -0.816557 -0.478261 +-0.159803 -0.863556 -0.478261 +0.000000 -0.806043 -0.591858 +0.000000 -0.878218 -0.478261 +-0.165166 -0.788939 -0.591858 +0.000000 -0.806043 -0.591858 +-0.159803 -0.863556 -0.478261 +-0.138690 -0.662476 -0.736132 +0.000000 -0.806043 -0.591858 +-0.165166 -0.788939 -0.591858 +-0.138690 -0.662476 -0.736132 +0.000000 -0.676838 -0.736132 +0.000000 -0.806043 -0.591858 +-0.108928 -0.520310 -0.847002 +0.000000 -0.676838 -0.736132 +-0.138690 -0.662476 -0.736132 +-0.108928 -0.520310 -0.847002 +0.000000 -0.531589 -0.847002 +0.000000 -0.676838 -0.736132 +-0.075528 -0.360770 -0.929591 +0.000000 -0.531589 -0.847002 +-0.108928 -0.520310 -0.847002 +-0.075528 -0.360770 -0.929591 +0.000000 -0.368592 -0.929591 +0.000000 -0.531589 -0.847002 +-0.037394 -0.178616 -0.983208 +0.000000 -0.368592 -0.929591 +-0.075528 -0.360770 -0.929591 +-0.037394 -0.178616 -0.983208 +0.000000 -0.182489 -0.983208 +0.000000 -0.368592 -0.929591 +-0.037394 -0.178616 -0.983208 +0.000000 -0.048809 -0.998808 +0.000000 -0.182489 -0.983208 +-0.037394 -0.178616 -0.983208 +-0.008882 -0.047995 -0.998808 +0.000000 -0.048809 -0.998808 +-0.037394 -0.178616 -0.983208 +-0.017966 -0.045382 -0.998808 +-0.008882 -0.047995 -0.998808 +-0.072480 -0.167477 -0.983208 +-0.017966 -0.045382 -0.998808 +-0.037394 -0.178616 -0.983208 +-0.072480 -0.167477 -0.983208 +-0.026709 -0.040853 -0.998808 +-0.017966 -0.045382 -0.998808 +-0.103404 -0.150365 -0.983208 +-0.026709 -0.040853 -0.998808 +-0.072480 -0.167477 -0.983208 +-0.103404 -0.150365 -0.983208 +-0.030764 -0.037893 -0.998808 +-0.026709 -0.040853 -0.998808 +-0.129039 -0.129039 -0.983208 +-0.030764 -0.037893 -0.998808 +-0.103404 -0.150365 -0.983208 +-0.788939 -0.165166 -0.591858 +-0.621162 -0.268825 -0.736132 +-0.739739 -0.320142 -0.591858 +-0.621162 -0.268825 -0.736132 +-0.788939 -0.165166 -0.591858 +-0.662476 -0.138690 -0.736132 +-0.662476 -0.138690 -0.736132 +-0.487862 -0.211135 -0.847002 +-0.621162 -0.268825 -0.736132 +-0.487862 -0.211135 -0.847002 +-0.662476 -0.138690 -0.736132 +-0.520310 -0.108928 -0.847002 +-0.520310 -0.108928 -0.847002 +-0.338272 -0.146396 -0.929591 +-0.487862 -0.211135 -0.847002 +-0.338272 -0.146396 -0.929591 +-0.520310 -0.108928 -0.847002 +-0.360770 -0.075528 -0.929591 +-0.360770 -0.075528 -0.929591 +-0.167477 -0.072480 -0.983208 +-0.338272 -0.146396 -0.929591 +-0.167477 -0.072480 -0.983208 +-0.360770 -0.075528 -0.929591 +-0.178616 -0.037394 -0.983208 +-0.739739 -0.320142 -0.591858 +-0.557693 -0.383520 -0.736132 +-0.664154 -0.456732 -0.591858 +-0.557693 -0.383520 -0.736132 +-0.739739 -0.320142 -0.591858 +-0.621162 -0.268825 -0.736132 +-0.621162 -0.268825 -0.736132 +-0.438013 -0.301217 -0.847002 +-0.557693 -0.383520 -0.736132 +-0.438013 -0.301217 -0.847002 +-0.621162 -0.268825 -0.736132 +-0.487862 -0.211135 -0.847002 +-0.664154 -0.456732 -0.591858 +-0.478597 -0.478597 -0.736132 +-0.569958 -0.569958 -0.591858 +-0.478597 -0.478597 -0.736132 +-0.664154 -0.456732 -0.591858 +-0.557693 -0.383520 -0.736132 +-0.557693 -0.383520 -0.736132 +-0.375890 -0.375890 -0.847002 +-0.478597 -0.478597 -0.736132 +-0.375890 -0.375890 -0.847002 +-0.557693 -0.383520 -0.736132 +-0.438013 -0.301217 -0.847002 +-0.487862 -0.211135 -0.847002 +-0.303708 -0.208857 -0.929591 +-0.438013 -0.301217 -0.847002 +-0.303708 -0.208857 -0.929591 +-0.487862 -0.211135 -0.847002 +-0.338272 -0.146396 -0.929591 +-0.338272 -0.146396 -0.929591 +-0.150365 -0.103404 -0.983208 +-0.303708 -0.208857 -0.929591 +-0.150365 -0.103404 -0.983208 +-0.338272 -0.146396 -0.929591 +-0.167477 -0.072480 -0.983208 +-0.438013 -0.301217 -0.847002 +-0.260634 -0.260634 -0.929591 +-0.375890 -0.375890 -0.847002 +-0.260634 -0.260634 -0.929591 +-0.438013 -0.301217 -0.847002 +-0.303708 -0.208857 -0.929591 +-0.303708 -0.208857 -0.929591 +-0.129039 -0.129039 -0.983208 +-0.260634 -0.260634 -0.929591 +-0.129039 -0.129039 -0.983208 +-0.303708 -0.208857 -0.929591 +-0.150365 -0.103404 -0.983208 +-0.569958 -0.569958 -0.591858 +-0.383520 -0.557693 -0.736132 +-0.456732 -0.664154 -0.591858 +-0.383520 -0.557693 -0.736132 +-0.569958 -0.569958 -0.591858 +-0.478597 -0.478597 -0.736132 +-0.478597 -0.478597 -0.736132 +-0.301217 -0.438013 -0.847002 +-0.383520 -0.557693 -0.736132 +-0.301217 -0.438013 -0.847002 +-0.478597 -0.478597 -0.736132 +-0.375890 -0.375890 -0.847002 +-0.456732 -0.664154 -0.591858 +-0.268825 -0.621162 -0.736132 +-0.320142 -0.739739 -0.591858 +-0.268825 -0.621162 -0.736132 +-0.456732 -0.664154 -0.591858 +-0.383520 -0.557693 -0.736132 +-0.383520 -0.557693 -0.736132 +-0.211135 -0.487862 -0.847002 +-0.268825 -0.621162 -0.736132 +-0.211135 -0.487862 -0.847002 +-0.383520 -0.557693 -0.736132 +-0.301217 -0.438013 -0.847002 +-0.375890 -0.375890 -0.847002 +-0.208857 -0.303708 -0.929591 +-0.301217 -0.438013 -0.847002 +-0.208857 -0.303708 -0.929591 +-0.375890 -0.375890 -0.847002 +-0.260634 -0.260634 -0.929591 +-0.260634 -0.260634 -0.929591 +-0.103404 -0.150365 -0.983208 +-0.208857 -0.303708 -0.929591 +-0.103404 -0.150365 -0.983208 +-0.260634 -0.260634 -0.929591 +-0.129039 -0.129039 -0.983208 +-0.301217 -0.438013 -0.847002 +-0.146396 -0.338272 -0.929591 +-0.211135 -0.487862 -0.847002 +-0.146396 -0.338272 -0.929591 +-0.301217 -0.438013 -0.847002 +-0.208857 -0.303708 -0.929591 +-0.208857 -0.303708 -0.929591 +-0.072480 -0.167477 -0.983208 +-0.146396 -0.338272 -0.929591 +-0.072480 -0.167477 -0.983208 +-0.208857 -0.303708 -0.929591 +-0.103404 -0.150365 -0.983208 +-0.320142 -0.739739 -0.591858 +-0.138690 -0.662476 -0.736132 +-0.165166 -0.788939 -0.591858 +-0.138690 -0.662476 -0.736132 +-0.320142 -0.739739 -0.591858 +-0.268825 -0.621162 -0.736132 +-0.268825 -0.621162 -0.736132 +-0.108928 -0.520310 -0.847002 +-0.138690 -0.662476 -0.736132 +-0.108928 -0.520310 -0.847002 +-0.268825 -0.621162 -0.736132 +-0.211135 -0.487862 -0.847002 +-0.211135 -0.487862 -0.847002 +-0.075528 -0.360770 -0.929591 +-0.108928 -0.520310 -0.847002 +-0.075528 -0.360770 -0.929591 +-0.211135 -0.487862 -0.847002 +-0.146396 -0.338272 -0.929591 +-0.146396 -0.338272 -0.929591 +-0.037394 -0.178616 -0.983208 +-0.075528 -0.360770 -0.929591 +-0.037394 -0.178616 -0.983208 +-0.146396 -0.338272 -0.929591 +-0.072480 -0.167477 -0.983208 +0.999181 0.039514 0.008727 +0.978744 0.204902 0.008727 +0.999181 0.039517 0.008727 +0.204902 0.978744 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.204902 0.978744 0.008727 +0.204902 0.978744 0.008727 +0.000000 0.999962 0.008727 +0.397162 0.917707 0.008727 +0.204902 0.978744 0.008727 +0.204902 0.978744 0.008727 +0.397162 0.917707 0.008727 +0.397162 0.917707 0.008727 +0.204902 0.978744 0.008727 +0.978744 0.204902 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.978744 0.204902 0.008727 +0.999181 0.039514 0.008727 +0.999962 0.000000 0.008727 +0.566613 0.823938 0.008727 +0.397162 0.917707 0.008727 +0.397162 0.917707 0.008727 +0.566613 0.823938 0.008727 +0.566613 0.823938 0.008727 +0.397162 0.917707 0.008727 +0.566613 0.823938 0.008727 +0.707080 0.707080 0.008727 +0.566613 0.823938 0.008727 +0.707080 0.707080 0.008727 +0.707080 0.707080 0.008727 +0.566613 0.823938 0.008727 +0.823938 0.566613 0.008727 +0.707080 0.707080 0.008727 +0.707080 0.707080 0.008727 +0.823938 0.566613 0.008727 +0.823938 0.566613 0.008727 +0.707080 0.707080 0.008727 +0.823938 0.566613 0.008727 +0.917707 0.397162 0.008727 +0.823938 0.566613 0.008727 +0.917707 0.397162 0.008727 +0.917707 0.397162 0.008727 +0.823938 0.566613 0.008727 +0.978744 0.204902 0.008727 +0.917707 0.397162 0.008727 +0.917707 0.397162 0.008727 +0.978744 0.204902 0.008727 +0.978744 0.204902 0.008727 +0.917707 0.397162 0.008727 +0.978744 0.204902 0.008727 +0.999181 0.039514 0.008727 +0.978744 0.204902 0.008727 +0.983268 0.181956 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +-0.983268 0.181956 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.983268 0.181956 -0.008727 +-0.983268 0.181956 -0.008727 +-0.999962 0.000000 -0.008727 +-0.929753 0.368081 -0.008727 +-0.983268 0.181956 -0.008727 +-0.983268 0.181956 -0.008727 +-0.929753 0.368081 -0.008727 +-0.929753 0.368081 -0.008727 +-0.983268 0.181956 -0.008727 +-0.836964 0.547189 -0.008727 +-0.929753 0.368081 -0.008727 +-0.929753 0.368081 -0.008727 +-0.836964 0.547189 -0.008727 +-0.836964 0.547189 -0.008727 +-0.929753 0.368081 -0.008727 +-0.707080 0.707080 -0.008727 +-0.836964 0.547189 -0.008727 +-0.836964 0.547189 -0.008727 +-0.707080 0.707080 -0.008727 +-0.707080 0.707080 -0.008727 +-0.836964 0.547189 -0.008727 +-0.547189 0.836964 -0.008727 +-0.707080 0.707080 -0.008727 +-0.707080 0.707080 -0.008727 +-0.547189 0.836964 -0.008727 +-0.547189 0.836964 -0.008727 +-0.707080 0.707080 -0.008727 +-0.547189 0.836964 -0.008727 +-0.368081 0.929753 -0.008727 +-0.547189 0.836964 -0.008727 +-0.368081 0.929753 -0.008727 +-0.368081 0.929753 -0.008727 +-0.547189 0.836964 -0.008727 +-0.181956 0.983268 -0.008727 +-0.368081 0.929753 -0.008727 +-0.368081 0.929753 -0.008727 +-0.181956 0.983268 -0.008727 +-0.181956 0.983268 -0.008727 +-0.368081 0.929753 -0.008727 +0.000000 0.999962 -0.008727 +-0.181956 0.983268 -0.008727 +-0.181956 0.983268 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +-0.181956 0.983268 -0.008727 +0.181956 0.983268 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.181956 0.983268 -0.008727 +0.181956 0.983268 -0.008727 +0.000000 0.999962 -0.008727 +0.368081 0.929753 -0.008727 +0.181956 0.983268 -0.008727 +0.181956 0.983268 -0.008727 +0.368081 0.929753 -0.008727 +0.368081 0.929753 -0.008727 +0.181956 0.983268 -0.008727 +0.368081 0.929753 -0.008727 +0.547189 0.836964 -0.008727 +0.368081 0.929753 -0.008727 +0.547189 0.836964 -0.008727 +0.547189 0.836964 -0.008727 +0.368081 0.929753 -0.008727 +0.707080 0.707080 -0.008727 +0.547189 0.836964 -0.008727 +0.547189 0.836964 -0.008727 +0.707080 0.707080 -0.008727 +0.707080 0.707080 -0.008727 +0.547189 0.836964 -0.008727 +0.836964 0.547189 -0.008727 +0.707080 0.707080 -0.008727 +0.707080 0.707080 -0.008727 +0.836964 0.547189 -0.008727 +0.836964 0.547189 -0.008727 +0.707080 0.707080 -0.008727 +0.929753 0.368081 -0.008727 +0.836964 0.547189 -0.008727 +0.836964 0.547189 -0.008727 +0.929753 0.368081 -0.008727 +0.929753 0.368081 -0.008727 +0.836964 0.547189 -0.008727 +0.983268 0.181956 -0.008727 +0.929753 0.368081 -0.008727 +0.929753 0.368081 -0.008727 +0.983268 0.181956 -0.008727 +0.983268 0.181956 -0.008727 +0.929753 0.368081 -0.008727 +0.999962 0.000000 -0.008727 +0.983268 0.181956 -0.008727 +0.983268 0.181956 -0.008727 +0.983268 0.181956 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +-0.983268 0.181956 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.983268 0.181956 -0.008727 +-0.983268 0.181956 -0.008727 +-0.999962 0.000000 -0.008727 +-0.983268 0.181956 -0.008727 +-0.929753 0.368081 -0.008727 +-0.983268 0.181956 -0.008727 +-0.929753 0.368081 -0.008727 +-0.929753 0.368081 -0.008727 +-0.983268 0.181956 -0.008727 +-0.836964 0.547189 -0.008727 +-0.929753 0.368081 -0.008727 +-0.929753 0.368081 -0.008727 +-0.836964 0.547189 -0.008727 +-0.836964 0.547189 -0.008727 +-0.929753 0.368081 -0.008727 +-0.707080 0.707080 -0.008727 +-0.836964 0.547189 -0.008727 +-0.836964 0.547189 -0.008727 +-0.707080 0.707080 -0.008727 +-0.707080 0.707080 -0.008727 +-0.836964 0.547189 -0.008727 +-0.707080 0.707080 -0.008727 +-0.547189 0.836964 -0.008727 +-0.707080 0.707080 -0.008727 +-0.547189 0.836964 -0.008727 +-0.547189 0.836964 -0.008727 +-0.707080 0.707080 -0.008727 +-0.368081 0.929753 -0.008727 +-0.547189 0.836964 -0.008727 +-0.547189 0.836964 -0.008727 +-0.368081 0.929753 -0.008727 +-0.368081 0.929753 -0.008727 +-0.547189 0.836964 -0.008727 +-0.181956 0.983268 -0.008727 +-0.368081 0.929753 -0.008727 +-0.368081 0.929753 -0.008727 +-0.181956 0.983268 -0.008727 +-0.181956 0.983268 -0.008727 +-0.368081 0.929753 -0.008727 +0.000000 0.999962 -0.008727 +-0.181956 0.983268 -0.008727 +-0.181956 0.983268 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +-0.181956 0.983268 -0.008727 +0.181956 0.983268 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.181956 0.983268 -0.008727 +0.181956 0.983268 -0.008727 +0.000000 0.999962 -0.008727 +0.368081 0.929753 -0.008727 +0.181956 0.983268 -0.008727 +0.181956 0.983268 -0.008727 +0.368081 0.929753 -0.008727 +0.368081 0.929753 -0.008727 +0.181956 0.983268 -0.008727 +0.547189 0.836964 -0.008727 +0.368081 0.929753 -0.008727 +0.368081 0.929753 -0.008727 +0.547189 0.836964 -0.008727 +0.547189 0.836964 -0.008727 +0.368081 0.929753 -0.008727 +0.707080 0.707080 -0.008727 +0.547189 0.836964 -0.008727 +0.547189 0.836964 -0.008727 +0.707080 0.707080 -0.008727 +0.707080 0.707080 -0.008727 +0.547189 0.836964 -0.008727 +0.836964 0.547189 -0.008727 +0.707080 0.707080 -0.008727 +0.707080 0.707080 -0.008727 +0.836964 0.547189 -0.008727 +0.836964 0.547189 -0.008727 +0.707080 0.707080 -0.008727 +0.929753 0.368081 -0.008727 +0.836964 0.547189 -0.008727 +0.836964 0.547189 -0.008727 +0.929753 0.368081 -0.008727 +0.929753 0.368081 -0.008727 +0.836964 0.547189 -0.008727 +0.983268 0.181956 -0.008727 +0.929753 0.368081 -0.008727 +0.929753 0.368081 -0.008727 +0.983268 0.181956 -0.008727 +0.983268 0.181956 -0.008727 +0.929753 0.368081 -0.008727 +0.999962 0.000000 -0.008727 +0.983268 0.181956 -0.008727 +0.983268 0.181956 -0.008727 +0.983268 0.181956 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +-0.983268 0.181956 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.983268 0.181956 -0.008727 +-0.983268 0.181956 -0.008727 +-0.999962 0.000000 -0.008727 +-0.929753 0.368081 -0.008727 +-0.983268 0.181956 -0.008727 +-0.983268 0.181956 -0.008727 +-0.929753 0.368081 -0.008727 +-0.929753 0.368081 -0.008727 +-0.983268 0.181956 -0.008727 +-0.929753 0.368081 -0.008727 +-0.836964 0.547189 -0.008727 +-0.929753 0.368081 -0.008727 +-0.836964 0.547189 -0.008727 +-0.836964 0.547189 -0.008727 +-0.929753 0.368081 -0.008727 +-0.707080 0.707080 -0.008727 +-0.836964 0.547189 -0.008727 +-0.836964 0.547189 -0.008727 +-0.707080 0.707080 -0.008727 +-0.707080 0.707080 -0.008727 +-0.836964 0.547189 -0.008727 +-0.707080 0.707080 -0.008727 +-0.547189 0.836964 -0.008727 +-0.707080 0.707080 -0.008727 +-0.547189 0.836964 -0.008727 +-0.547189 0.836964 -0.008727 +-0.707080 0.707080 -0.008727 +-0.368081 0.929753 -0.008727 +-0.547189 0.836964 -0.008727 +-0.547189 0.836964 -0.008727 +-0.368081 0.929753 -0.008727 +-0.368081 0.929753 -0.008727 +-0.547189 0.836964 -0.008727 +-0.181956 0.983268 -0.008727 +-0.368081 0.929753 -0.008727 +-0.368081 0.929753 -0.008727 +-0.181956 0.983268 -0.008727 +-0.181956 0.983268 -0.008727 +-0.368081 0.929753 -0.008727 +0.000000 0.999962 -0.008727 +-0.181956 0.983268 -0.008727 +-0.181956 0.983268 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +-0.181956 0.983268 -0.008727 +0.181956 0.983268 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.181956 0.983268 -0.008727 +0.181956 0.983268 -0.008727 +0.000000 0.999962 -0.008727 +0.368081 0.929753 -0.008727 +0.181956 0.983268 -0.008727 +0.181956 0.983268 -0.008727 +0.368081 0.929753 -0.008727 +0.368081 0.929753 -0.008727 +0.181956 0.983268 -0.008727 +0.547189 0.836964 -0.008727 +0.368081 0.929753 -0.008727 +0.368081 0.929753 -0.008727 +0.547189 0.836964 -0.008727 +0.547189 0.836964 -0.008727 +0.368081 0.929753 -0.008727 +0.707080 0.707080 -0.008727 +0.547189 0.836964 -0.008727 +0.547189 0.836964 -0.008727 +0.707080 0.707080 -0.008727 +0.707080 0.707080 -0.008727 +0.547189 0.836964 -0.008727 +0.836964 0.547189 -0.008727 +0.707080 0.707080 -0.008727 +0.707080 0.707080 -0.008727 +0.836964 0.547189 -0.008727 +0.836964 0.547189 -0.008727 +0.707080 0.707080 -0.008727 +0.929753 0.368081 -0.008727 +0.836964 0.547189 -0.008727 +0.836964 0.547189 -0.008727 +0.929753 0.368081 -0.008727 +0.929753 0.368081 -0.008727 +0.836964 0.547189 -0.008727 +0.983268 0.181956 -0.008727 +0.929753 0.368081 -0.008727 +0.929753 0.368081 -0.008727 +0.983268 0.181956 -0.008727 +0.983268 0.181956 -0.008727 +0.929753 0.368081 -0.008727 +0.999962 0.000000 -0.008727 +0.983268 0.181956 -0.008727 +0.983268 0.181956 -0.008727 +-0.707080 0.707080 -0.008727 +-0.547189 0.836964 -0.008727 +-0.707080 0.707080 -0.008727 +-0.983268 0.181956 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.983268 0.181956 -0.008727 +-0.983268 0.181956 -0.008727 +-0.999962 0.000000 -0.008727 +-0.929753 0.368081 -0.008727 +-0.983268 0.181956 -0.008727 +-0.983268 0.181956 -0.008727 +-0.929753 0.368081 -0.008727 +-0.929753 0.368081 -0.008727 +-0.983268 0.181956 -0.008727 +-0.836964 0.547189 -0.008727 +-0.929753 0.368081 -0.008727 +-0.929753 0.368081 -0.008727 +-0.836964 0.547189 -0.008727 +-0.836964 0.547189 -0.008727 +-0.929753 0.368081 -0.008727 +-0.707080 0.707080 -0.008727 +-0.836964 0.547189 -0.008727 +-0.836964 0.547189 -0.008727 +-0.707080 0.707080 -0.008727 +-0.707080 0.707080 -0.008727 +-0.836964 0.547189 -0.008727 +0.999962 0.000000 -0.008727 +0.983268 0.181956 -0.008727 +0.999962 0.000000 -0.008727 +0.983268 0.181956 -0.008727 +0.983268 0.181956 -0.008727 +0.999962 0.000000 -0.008727 +0.983268 0.181956 -0.008727 +0.929753 0.368081 -0.008727 +0.983268 0.181956 -0.008727 +0.929753 0.368081 -0.008727 +0.929753 0.368081 -0.008727 +0.983268 0.181956 -0.008727 +0.836964 0.547189 -0.008727 +0.929753 0.368081 -0.008727 +0.929753 0.368081 -0.008727 +0.836964 0.547189 -0.008727 +0.836964 0.547189 -0.008727 +0.929753 0.368081 -0.008727 +0.707080 0.707080 -0.008727 +0.836964 0.547189 -0.008727 +0.836964 0.547189 -0.008727 +0.707080 0.707080 -0.008727 +0.707080 0.707080 -0.008727 +0.836964 0.547189 -0.008727 +0.547189 0.836964 -0.008727 +0.707080 0.707080 -0.008727 +0.707080 0.707080 -0.008727 +0.547189 0.836964 -0.008727 +0.547189 0.836964 -0.008727 +0.707080 0.707080 -0.008727 +0.368081 0.929753 -0.008727 +0.547189 0.836964 -0.008727 +0.547189 0.836964 -0.008727 +0.368081 0.929753 -0.008727 +0.368081 0.929753 -0.008727 +0.547189 0.836964 -0.008727 +0.181956 0.983268 -0.008727 +0.368081 0.929753 -0.008727 +0.368081 0.929753 -0.008727 +0.181956 0.983268 -0.008727 +0.181956 0.983268 -0.008727 +0.368081 0.929753 -0.008727 +0.000000 0.999962 -0.008727 +0.181956 0.983268 -0.008727 +0.181956 0.983268 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.181956 0.983268 -0.008727 +-0.181956 0.983268 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +-0.181956 0.983268 -0.008727 +-0.181956 0.983268 -0.008727 +0.000000 0.999962 -0.008727 +-0.181956 0.983268 -0.008727 +-0.368081 0.929753 -0.008727 +-0.181956 0.983268 -0.008727 +-0.368081 0.929753 -0.008727 +-0.368081 0.929753 -0.008727 +-0.181956 0.983268 -0.008727 +-0.368081 0.929753 -0.008727 +-0.547189 0.836964 -0.008727 +-0.368081 0.929753 -0.008727 +-0.547189 0.836964 -0.008727 +-0.547189 0.836964 -0.008727 +-0.368081 0.929753 -0.008727 +-0.547189 0.836964 -0.008727 +-0.707080 0.707080 -0.008727 +-0.547189 0.836964 -0.008727 +-0.999384 -0.035088 0.000000 +-0.978781 -0.204909 0.000000 +-0.999273 -0.038112 0.000000 +0.000000 -1.000000 0.000000 +-0.204909 -0.978781 0.000000 +0.000000 -1.000000 0.000000 +-0.204909 -0.978781 0.000000 +-0.204909 -0.978781 0.000000 +0.000000 -1.000000 0.000000 +-0.397177 -0.917742 0.000000 +-0.204909 -0.978781 0.000000 +-0.204909 -0.978781 0.000000 +-0.397177 -0.917742 0.000000 +-0.397177 -0.917742 0.000000 +-0.204909 -0.978781 0.000000 +-0.397177 -0.917742 0.000000 +-0.566635 -0.823969 0.000000 +-0.397177 -0.917742 0.000000 +-0.566635 -0.823969 0.000000 +-0.566635 -0.823969 0.000000 +-0.397177 -0.917742 0.000000 +-0.707107 -0.707107 0.000000 +-0.566635 -0.823969 0.000000 +-0.566635 -0.823969 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.566635 -0.823969 0.000000 +-0.823969 -0.566635 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.823969 -0.566635 0.000000 +-0.823969 -0.566635 0.000000 +-0.707107 -0.707107 0.000000 +-0.823969 -0.566635 0.000000 +-0.917742 -0.397177 0.000000 +-0.823969 -0.566635 0.000000 +-0.917742 -0.397177 0.000000 +-0.917742 -0.397177 0.000000 +-0.823969 -0.566635 0.000000 +-0.978781 -0.204909 0.000000 +-0.917742 -0.397177 0.000000 +-0.917742 -0.397177 0.000000 +-0.978781 -0.204909 0.000000 +-0.978781 -0.204909 0.000000 +-0.917742 -0.397177 0.000000 +-0.978781 -0.204909 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.978781 -0.204909 0.000000 +-0.999384 -0.035088 0.000000 +-1.000000 0.000000 0.000000 +-0.978781 -0.204909 0.000000 +-0.999384 -0.035088 0.000000 +-0.978781 -0.204909 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.811791 0.583948 0.000000 +0.691982 0.721915 0.000000 +0.811791 0.583948 0.000000 +0.999104 0.042322 0.000000 +0.974225 0.225580 0.000000 +0.999104 0.042322 0.000000 +0.999067 0.043190 0.000000 +0.974225 0.225580 0.000000 +0.999104 0.042322 0.000000 +0.974225 0.225580 0.000000 +0.974225 0.225580 0.000000 +0.999067 0.043190 0.000000 +0.909130 0.416513 0.000000 +0.974225 0.225580 0.000000 +0.974225 0.225580 0.000000 +0.909130 0.416513 0.000000 +0.909130 0.416513 0.000000 +0.974225 0.225580 0.000000 +0.909130 0.416513 0.000000 +0.811791 0.583948 0.000000 +0.909130 0.416513 0.000000 +0.811791 0.583948 0.000000 +0.811791 0.583948 0.000000 +0.909130 0.416513 0.000000 +0.184147 0.982899 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.184147 0.982899 0.000000 +0.184147 0.982899 0.000000 +0.000000 1.000000 0.000000 +0.184147 0.982899 0.000000 +0.377664 0.925943 0.000000 +0.184147 0.982899 0.000000 +0.377664 0.925943 0.000000 +0.377664 0.925943 0.000000 +0.184147 0.982899 0.000000 +0.377664 0.925943 0.000000 +0.549068 0.835778 0.000000 +0.377664 0.925943 0.000000 +0.549068 0.835778 0.000000 +0.549068 0.835778 0.000000 +0.377664 0.925943 0.000000 +0.691982 0.721915 0.000000 +0.549068 0.835778 0.000000 +0.549068 0.835778 0.000000 +0.691982 0.721915 0.000000 +0.691982 0.721915 0.000000 +0.549068 0.835778 0.000000 +0.691982 0.721915 0.000000 +0.811791 0.583948 0.000000 +0.691982 0.721915 0.000000 +0.999019 -0.044293 0.000000 +0.999003 -0.044644 0.000000 +0.999019 -0.044293 0.000000 +0.183177 -0.983080 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.183177 -0.983080 0.000000 +0.183177 -0.983080 0.000000 +0.000000 -1.000000 0.000000 +0.376750 -0.926315 0.000000 +0.183177 -0.983080 0.000000 +0.183177 -0.983080 0.000000 +0.376750 -0.926315 0.000000 +0.376750 -0.926315 0.000000 +0.183177 -0.983080 0.000000 +0.376750 -0.926315 0.000000 +0.548243 -0.836319 0.000000 +0.376750 -0.926315 0.000000 +0.548243 -0.836319 0.000000 +0.548243 -0.836319 0.000000 +0.376750 -0.926315 0.000000 +0.691269 -0.722597 0.000000 +0.548243 -0.836319 0.000000 +0.548243 -0.836319 0.000000 +0.691269 -0.722597 0.000000 +0.691269 -0.722597 0.000000 +0.548243 -0.836319 0.000000 +0.811215 -0.584748 0.000000 +0.691269 -0.722597 0.000000 +0.691269 -0.722597 0.000000 +0.811215 -0.584748 0.000000 +0.811215 -0.584748 0.000000 +0.691269 -0.722597 0.000000 +0.908718 -0.417410 0.000000 +0.811215 -0.584748 0.000000 +0.811215 -0.584748 0.000000 +0.908718 -0.417410 0.000000 +0.908718 -0.417410 0.000000 +0.811215 -0.584748 0.000000 +0.908718 -0.417410 0.000000 +0.974002 -0.226541 0.000000 +0.908718 -0.417410 0.000000 +0.974002 -0.226541 0.000000 +0.974002 -0.226541 0.000000 +0.908718 -0.417410 0.000000 +0.974002 -0.226541 0.000000 +0.999019 -0.044293 0.000000 +0.974002 -0.226541 0.000000 +0.999003 -0.044644 0.000000 +0.999019 -0.044293 0.000000 +0.974002 -0.226541 0.000000 +-0.377664 0.925943 0.000000 +-0.549068 0.835778 0.000000 +-0.377664 0.925943 0.000000 +-0.184147 0.982899 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.184147 0.982899 0.000000 +-0.184147 0.982899 0.000000 +0.000000 1.000000 0.000000 +-0.184147 0.982899 0.000000 +-0.377664 0.925943 0.000000 +-0.184147 0.982899 0.000000 +-0.377664 0.925943 0.000000 +-0.377664 0.925943 0.000000 +-0.184147 0.982899 0.000000 +-0.974225 0.225580 0.000000 +-0.999104 0.042322 0.000000 +-0.999104 0.042322 0.000000 +-0.974225 0.225580 0.000000 +-0.999067 0.043190 0.000000 +-0.999104 0.042322 0.000000 +-0.974225 0.225580 0.000000 +-0.974225 0.225580 0.000000 +-0.999067 0.043190 0.000000 +-0.974225 0.225580 0.000000 +-0.909130 0.416513 0.000000 +-0.974225 0.225580 0.000000 +-0.909130 0.416513 0.000000 +-0.909130 0.416513 0.000000 +-0.974225 0.225580 0.000000 +-0.811791 0.583948 0.000000 +-0.909130 0.416513 0.000000 +-0.909130 0.416513 0.000000 +-0.811791 0.583948 0.000000 +-0.811791 0.583948 0.000000 +-0.909130 0.416513 0.000000 +-0.691982 0.721915 0.000000 +-0.811791 0.583948 0.000000 +-0.811791 0.583948 0.000000 +-0.691982 0.721915 0.000000 +-0.691982 0.721915 0.000000 +-0.811791 0.583948 0.000000 +-0.549068 0.835778 0.000000 +-0.691982 0.721915 0.000000 +-0.691982 0.721915 0.000000 +-0.549068 0.835778 0.000000 +-0.549068 0.835778 0.000000 +-0.691982 0.721915 0.000000 +-0.549068 0.835778 0.000000 +-0.377664 0.925943 0.000000 +-0.549068 0.835778 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.978781 0.204909 0.000000 +-0.999384 0.035088 0.000000 +-0.999273 0.038112 0.000000 +0.000000 1.000000 0.000000 +-0.204909 0.978781 0.000000 +0.000000 1.000000 0.000000 +-0.204909 0.978781 0.000000 +-0.204909 0.978781 0.000000 +0.000000 1.000000 0.000000 +-0.204909 0.978781 0.000000 +-0.397177 0.917742 0.000000 +-0.204909 0.978781 0.000000 +-0.397177 0.917742 0.000000 +-0.397177 0.917742 0.000000 +-0.204909 0.978781 0.000000 +-0.397177 0.917742 0.000000 +-0.566635 0.823969 0.000000 +-0.397177 0.917742 0.000000 +-0.566635 0.823969 0.000000 +-0.566635 0.823969 0.000000 +-0.397177 0.917742 0.000000 +-0.566635 0.823969 0.000000 +-0.707107 0.707107 0.000000 +-0.566635 0.823969 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.566635 0.823969 0.000000 +-0.823969 0.566635 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.823969 0.566635 0.000000 +-0.823969 0.566635 0.000000 +-0.707107 0.707107 0.000000 +-0.917742 0.397177 0.000000 +-0.823969 0.566635 0.000000 +-0.823969 0.566635 0.000000 +-0.917742 0.397177 0.000000 +-0.917742 0.397177 0.000000 +-0.823969 0.566635 0.000000 +-0.917742 0.397177 0.000000 +-0.978781 0.204909 0.000000 +-0.917742 0.397177 0.000000 +-0.978781 0.204909 0.000000 +-0.978781 0.204909 0.000000 +-0.917742 0.397177 0.000000 +-0.999384 0.035088 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.999384 0.035088 0.000000 +-0.978781 0.204909 0.000000 +-1.000000 0.000000 0.000000 +-0.999384 0.035088 0.000000 +-0.978781 0.204909 0.000000 +-0.978781 0.204909 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.999273 0.038112 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.999384 0.035088 0.000000 +0.983305 0.181963 0.000000 +0.999273 0.038112 0.000000 +0.999384 0.035088 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.999384 0.035088 0.000000 +0.999384 -0.035088 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.999384 -0.035088 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.999273 -0.038112 0.000000 +0.983305 -0.181963 0.000000 +0.999384 -0.035088 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.999273 -0.038112 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.548243 -0.836319 0.000000 +-0.691269 -0.722597 0.000000 +-0.691269 -0.722597 0.000000 +-0.999003 -0.044644 0.000000 +-0.999019 -0.044293 0.000000 +-0.999019 -0.044293 0.000000 +-0.999003 -0.044644 0.000000 +-0.974002 -0.226541 0.000000 +-0.999019 -0.044293 0.000000 +-0.974002 -0.226541 0.000000 +-0.974002 -0.226541 0.000000 +-0.999003 -0.044644 0.000000 +-0.974002 -0.226541 0.000000 +-0.908718 -0.417410 0.000000 +-0.974002 -0.226541 0.000000 +-0.908718 -0.417410 0.000000 +-0.908718 -0.417410 0.000000 +-0.974002 -0.226541 0.000000 +-0.908718 -0.417410 0.000000 +-0.811215 -0.584748 0.000000 +-0.908718 -0.417410 0.000000 +-0.811215 -0.584748 0.000000 +-0.811215 -0.584748 0.000000 +-0.908718 -0.417410 0.000000 +-0.811215 -0.584748 0.000000 +-0.691269 -0.722597 0.000000 +-0.811215 -0.584748 0.000000 +-0.691269 -0.722597 0.000000 +-0.691269 -0.722597 0.000000 +-0.811215 -0.584748 0.000000 +0.000000 -1.000000 0.000000 +-0.183177 -0.983080 0.000000 +0.000000 -1.000000 0.000000 +-0.183177 -0.983080 0.000000 +-0.183177 -0.983080 0.000000 +0.000000 -1.000000 0.000000 +-0.183177 -0.983080 0.000000 +-0.376750 -0.926315 0.000000 +-0.183177 -0.983080 0.000000 +-0.376750 -0.926315 0.000000 +-0.376750 -0.926315 0.000000 +-0.183177 -0.983080 0.000000 +-0.376750 -0.926315 0.000000 +-0.548243 -0.836319 0.000000 +-0.376750 -0.926315 0.000000 +-0.548243 -0.836319 0.000000 +-0.548243 -0.836319 0.000000 +-0.376750 -0.926315 0.000000 +-0.691269 -0.722597 0.000000 +-0.548243 -0.836319 0.000000 +-0.548243 -0.836319 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.015499 -0.999880 0.000000 +-0.015499 -0.999880 0.000000 +-0.015499 -0.999880 0.000000 +-0.015499 -0.999880 0.000000 +-0.015499 -0.999880 0.000000 +-0.015499 -0.999880 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.015499 0.999880 0.000000 +0.015499 0.999880 0.000000 +0.015499 0.999880 0.000000 +0.015499 0.999880 0.000000 +0.015499 0.999880 0.000000 +0.015499 0.999880 0.000000 +0.015499 -0.999880 0.000000 +0.015499 -0.999880 0.000000 +0.015499 -0.999880 0.000000 +0.015499 -0.999880 0.000000 +0.015499 -0.999880 0.000000 +0.015499 -0.999880 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.015499 0.999880 0.000000 +-0.015499 0.999880 0.000000 +-0.015499 0.999880 0.000000 +-0.015499 0.999880 0.000000 +-0.015499 0.999880 0.000000 +-0.015499 0.999880 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.984947 -0.172639 0.008727 +-0.933196 -0.359262 0.008727 +-0.933196 -0.359262 0.008727 +-0.080766 0.996695 0.008727 +-0.172639 0.984947 0.008727 +-0.075469 0.997110 0.008727 +-0.172639 0.984947 0.008727 +-0.172639 0.984947 0.008727 +-0.080766 0.996695 0.008727 +-0.191257 -0.981501 0.008727 +-0.099525 -0.994997 0.008727 +-0.094336 -0.995502 0.008727 +-0.191257 -0.981501 0.008727 +-0.191257 -0.981501 0.008727 +-0.099525 -0.994997 0.008727 +-0.376867 -0.926226 0.008727 +-0.191257 -0.981501 0.008727 +-0.191257 -0.981501 0.008727 +-0.376867 -0.926226 0.008727 +-0.376867 -0.926226 0.008727 +-0.191257 -0.981501 0.008727 +-0.555088 -0.831746 0.008727 +-0.376867 -0.926226 0.008727 +-0.376867 -0.926226 0.008727 +-0.555088 -0.831746 0.008727 +-0.555088 -0.831746 0.008727 +-0.376867 -0.926226 0.008727 +-0.555088 -0.831746 0.008727 +-0.713743 -0.700354 0.008727 +-0.555088 -0.831746 0.008727 +-0.713743 -0.700354 0.008727 +-0.713743 -0.700354 0.008727 +-0.555088 -0.831746 0.008727 +-0.842107 -0.539240 0.008727 +-0.713743 -0.700354 0.008727 +-0.713743 -0.700354 0.008727 +-0.842107 -0.539240 0.008727 +-0.842107 -0.539240 0.008727 +-0.713743 -0.700354 0.008727 +-0.933196 -0.359262 0.008727 +-0.842107 -0.539240 0.008727 +-0.842107 -0.539240 0.008727 +-0.933196 -0.359262 0.008727 +-0.933196 -0.359262 0.008727 +-0.842107 -0.539240 0.008727 +-0.172639 0.984947 0.008727 +-0.359262 0.933196 0.008727 +-0.172639 0.984947 0.008727 +-0.359262 0.933196 0.008727 +-0.359262 0.933196 0.008727 +-0.172639 0.984947 0.008727 +-0.359262 0.933196 0.008727 +-0.539240 0.842107 0.008727 +-0.359262 0.933196 0.008727 +-0.539240 0.842107 0.008727 +-0.539240 0.842107 0.008727 +-0.359262 0.933196 0.008727 +-0.539240 0.842107 0.008727 +-0.700354 0.713743 0.008727 +-0.539240 0.842107 0.008727 +-0.700354 0.713743 0.008727 +-0.700354 0.713743 0.008727 +-0.539240 0.842107 0.008727 +-0.831746 0.555088 0.008727 +-0.700354 0.713743 0.008727 +-0.700354 0.713743 0.008727 +-0.831746 0.555088 0.008727 +-0.831746 0.555088 0.008727 +-0.700354 0.713743 0.008727 +-0.926226 0.376867 0.008727 +-0.831746 0.555088 0.008727 +-0.831746 0.555088 0.008727 +-0.926226 0.376867 0.008727 +-0.926226 0.376867 0.008727 +-0.831746 0.555088 0.008727 +-0.981501 0.191257 0.008727 +-0.926226 0.376867 0.008727 +-0.926226 0.376867 0.008727 +-0.981501 0.191257 0.008727 +-0.981501 0.191257 0.008727 +-0.926226 0.376867 0.008727 +-0.981501 0.191257 0.008727 +-0.999917 0.009467 0.008727 +-0.981501 0.191257 0.008727 +-0.999917 0.009467 0.008727 +-0.999917 0.009467 0.008727 +-0.981501 0.191257 0.008727 +-0.984947 -0.172639 0.008727 +-0.999917 0.009467 0.008727 +-0.999917 0.009467 0.008727 +-0.984947 -0.172639 0.008727 +-0.984947 -0.172639 0.008727 +-0.999917 0.009467 0.008727 +-0.933196 -0.359262 0.008727 +-0.984947 -0.172639 0.008727 +-0.984947 -0.172639 0.008727 +0.594480 -0.804063 0.008727 +0.730754 -0.682585 0.008727 +0.730865 -0.682466 0.008727 +0.985183 -0.171285 0.008727 +0.999464 -0.031550 0.008727 +0.999624 -0.026011 0.008727 +0.985183 -0.171285 0.008727 +0.979785 -0.199862 0.008727 +0.999464 -0.031550 0.008727 +0.930762 -0.365522 0.008727 +0.979785 -0.199862 0.008727 +0.985183 -0.171285 0.008727 +0.930762 -0.365522 0.008727 +0.928850 -0.370352 0.008727 +0.979785 -0.199862 0.008727 +0.842847 -0.538083 0.008727 +0.928850 -0.370352 0.008727 +0.930762 -0.365522 0.008727 +0.842847 -0.538083 0.008727 +0.845228 -0.534335 0.008727 +0.928850 -0.370352 0.008727 +0.842847 -0.538083 0.008727 +0.730754 -0.682585 0.008727 +0.845228 -0.534335 0.008727 +0.730865 -0.682466 0.008727 +0.730754 -0.682585 0.008727 +0.842847 -0.538083 0.008727 +0.099525 -0.994997 0.008727 +0.238278 -0.971158 0.008727 +0.094336 -0.995502 0.008727 +0.266107 -0.963904 0.008727 +0.238278 -0.971158 0.008727 +0.099525 -0.994997 0.008727 +0.266107 -0.963904 0.008727 +0.428337 -0.903577 0.008727 +0.238278 -0.971158 0.008727 +0.432734 -0.901479 0.008727 +0.428337 -0.903577 0.008727 +0.266107 -0.963904 0.008727 +0.432734 -0.901479 0.008727 +0.594480 -0.804063 0.008727 +0.428337 -0.903577 0.008727 +0.590642 -0.806886 0.008727 +0.594480 -0.804063 0.008727 +0.432734 -0.901479 0.008727 +0.730754 -0.682585 0.008727 +0.594480 -0.804063 0.008727 +0.590642 -0.806886 0.008727 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -0.197878 0.980227 +0.000000 -0.387931 0.921688 +0.000000 -0.387931 0.921688 +0.000000 -0.197878 0.980227 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -0.197878 0.980227 +0.000000 -0.197878 0.980227 +0.000000 0.000000 1.000000 +0.000000 -0.387931 0.921688 +0.000000 -0.197878 0.980227 +0.000000 -0.197878 0.980227 +0.000000 -0.016210 0.999869 +0.000000 -0.197878 0.980227 +0.000000 -0.197878 0.980227 +0.000000 -0.372940 0.927856 +0.000000 -0.387931 0.921688 +0.000000 -0.387931 0.921688 +0.000000 -0.372940 0.927856 +0.000000 -0.197878 0.980227 +0.000000 -0.387931 0.921688 +0.000000 -0.197878 0.980227 +0.000000 -0.197878 0.980227 +0.000000 -0.372940 0.927856 +0.000000 -0.197878 0.980227 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -0.197878 0.980227 +0.000000 -0.016210 0.999869 +0.000000 0.000000 1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.197878 0.980227 +0.000000 0.387931 0.921688 +0.000000 0.387931 0.921688 +0.000000 0.197878 0.980227 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.197878 0.980227 +0.000000 0.197878 0.980227 +0.000000 0.000000 1.000000 +0.000000 0.387931 0.921688 +0.000000 0.197878 0.980227 +0.000000 0.197878 0.980227 +0.000000 0.387931 0.921688 +0.000000 0.372940 0.927856 +0.000000 0.387931 0.921688 +0.000000 0.000000 1.000000 +0.000000 0.197878 0.980227 +0.000000 0.000000 1.000000 +0.000000 0.016210 0.999869 +0.000000 0.197878 0.980227 +0.000000 0.000000 1.000000 +0.000000 0.197878 0.980227 +0.000000 0.197878 0.980227 +0.000000 0.016210 0.999869 +0.000000 0.197878 0.980227 +0.000000 0.387931 0.921688 +0.000000 0.197878 0.980227 +0.000000 0.372940 0.927856 +0.000000 0.387931 0.921688 +0.000000 0.197878 0.980227 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.907564 0.419824 0.008727 +0.973355 0.229138 0.008727 +0.973355 0.229138 0.008727 +0.991485 0.129926 0.008727 +0.973355 0.229138 0.008727 +0.992134 0.124874 0.008727 +0.973355 0.229138 0.008727 +0.973355 0.229138 0.008727 +0.991485 0.129926 0.008727 +0.180539 0.983529 0.008727 +0.080766 0.996695 0.008727 +0.075469 0.997110 0.008727 +0.180539 0.983529 0.008727 +0.180539 0.983529 0.008727 +0.080766 0.996695 0.008727 +0.374256 0.927284 0.008727 +0.180539 0.983529 0.008727 +0.180539 0.983529 0.008727 +0.374256 0.927284 0.008727 +0.374256 0.927284 0.008727 +0.180539 0.983529 0.008727 +0.545982 0.837751 0.008727 +0.374256 0.927284 0.008727 +0.374256 0.927284 0.008727 +0.545982 0.837751 0.008727 +0.545982 0.837751 0.008727 +0.374256 0.927284 0.008727 +0.545982 0.837751 0.008727 +0.689307 0.724417 0.008727 +0.545982 0.837751 0.008727 +0.689307 0.724417 0.008727 +0.689307 0.724417 0.008727 +0.545982 0.837751 0.008727 +0.689307 0.724417 0.008727 +0.809616 0.586894 0.008727 +0.689307 0.724417 0.008727 +0.809616 0.586894 0.008727 +0.809616 0.586894 0.008727 +0.689307 0.724417 0.008727 +0.809616 0.586894 0.008727 +0.907564 0.419824 0.008727 +0.809616 0.586894 0.008727 +0.907564 0.419824 0.008727 +0.907564 0.419824 0.008727 +0.809616 0.586894 0.008727 +0.973355 0.229138 0.008727 +0.907564 0.419824 0.008727 +0.907564 0.419824 0.008727 +0.003010 0.015928 0.999869 +0.000000 0.016210 0.999869 +0.000000 0.000000 1.000000 +0.378731 0.083985 0.921688 +0.197595 0.008538 0.980246 +0.387634 0.015186 0.921688 +0.303088 0.217306 0.927856 +0.268886 0.279626 0.921688 +0.258486 0.268829 0.927856 +0.303088 0.217306 0.927856 +0.319238 0.220403 0.921688 +0.268886 0.279626 0.921688 +0.339292 0.154807 0.927856 +0.319238 0.220403 0.921688 +0.303088 0.217306 0.927856 +0.339292 0.154807 0.927856 +0.356165 0.153743 0.921688 +0.319238 0.220403 0.921688 +0.363458 0.083563 0.927856 +0.356165 0.153743 0.921688 +0.339292 0.154807 0.927856 +0.363458 0.083563 0.927856 +0.378731 0.083985 0.921688 +0.356165 0.153743 0.921688 +0.363458 0.083563 0.927856 +0.197595 0.008538 0.980246 +0.378731 0.083985 0.921688 +0.192847 0.044338 0.980227 +0.197595 0.008538 0.980246 +0.363458 0.083563 0.927856 +0.192847 0.044338 0.980227 +0.000000 0.000000 1.000000 +0.197595 0.008538 0.980246 +0.015798 0.003632 0.999869 +0.000000 0.000000 1.000000 +0.192847 0.044338 0.980227 +0.015798 0.003632 0.999869 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.014747 0.006729 0.999869 +0.000000 0.000000 1.000000 +0.015798 0.003632 0.999869 +0.014747 0.006729 0.999869 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.014747 0.006729 0.999869 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.013174 0.009445 0.999869 +0.000000 0.000000 1.000000 +0.014747 0.006729 0.999869 +0.013174 0.009445 0.999869 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.011235 0.011685 0.999869 +0.000000 0.000000 1.000000 +0.013174 0.009445 0.999869 +0.008921 0.013534 0.999869 +0.000000 0.000000 1.000000 +0.011235 0.011685 0.999869 +0.008921 0.013534 0.999869 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.006145 0.015000 0.999869 +0.000000 0.000000 1.000000 +0.008921 0.013534 0.999869 +0.006145 0.015000 0.999869 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.003010 0.015928 0.999869 +0.000000 0.000000 1.000000 +0.006145 0.015000 0.999869 +0.003010 0.015928 0.999869 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.207738 0.327621 0.921688 +0.258486 0.268829 0.927856 +0.268886 0.279626 0.921688 +0.207738 0.327621 0.921688 +0.205254 0.311376 0.927856 +0.258486 0.268829 0.927856 +0.207738 0.327621 0.921688 +0.141383 0.345101 0.927856 +0.205254 0.311376 0.927856 +0.139684 0.361910 0.921688 +0.141383 0.345101 0.927856 +0.207738 0.327621 0.921688 +0.139684 0.361910 0.921688 +0.069246 0.366455 0.927856 +0.141383 0.345101 0.927856 +0.069095 0.381728 0.921688 +0.069246 0.366455 0.927856 +0.139684 0.361910 0.921688 +0.000000 0.000000 1.000000 +0.000000 0.016210 0.999869 +0.000000 0.000000 1.000000 +0.000000 0.372940 0.927856 +0.069095 0.381728 0.921688 +0.000000 0.387931 0.921688 +0.000000 0.197878 0.980227 +0.069095 0.381728 0.921688 +0.000000 0.372940 0.927856 +0.000000 0.197878 0.980227 +0.069246 0.366455 0.927856 +0.069095 0.381728 0.921688 +0.000000 0.197878 0.980227 +0.036741 0.194437 0.980227 +0.069246 0.366455 0.927856 +0.000000 0.016210 0.999869 +0.036741 0.194437 0.980227 +0.000000 0.197878 0.980227 +0.000000 0.016210 0.999869 +0.003010 0.015928 0.999869 +0.036741 0.194437 0.980227 +0.363458 0.083563 0.927856 +0.180025 0.082139 0.980227 +0.192847 0.044338 0.980227 +0.180025 0.082139 0.980227 +0.363458 0.083563 0.927856 +0.339292 0.154807 0.927856 +0.339292 0.154807 0.927856 +0.160815 0.115301 0.980227 +0.180025 0.082139 0.980227 +0.160815 0.115301 0.980227 +0.339292 0.154807 0.927856 +0.303088 0.217306 0.927856 +0.303088 0.217306 0.927856 +0.137150 0.142638 0.980227 +0.160815 0.115301 0.980227 +0.137150 0.142638 0.980227 +0.303088 0.217306 0.927856 +0.258486 0.268829 0.927856 +0.192847 0.044338 0.980227 +0.014747 0.006729 0.999869 +0.015798 0.003632 0.999869 +0.014747 0.006729 0.999869 +0.192847 0.044338 0.980227 +0.180025 0.082139 0.980227 +0.180025 0.082139 0.980227 +0.013174 0.009445 0.999869 +0.014747 0.006729 0.999869 +0.013174 0.009445 0.999869 +0.180025 0.082139 0.980227 +0.160815 0.115301 0.980227 +0.160815 0.115301 0.980227 +0.011235 0.011685 0.999869 +0.013174 0.009445 0.999869 +0.011235 0.011685 0.999869 +0.160815 0.115301 0.980227 +0.137150 0.142638 0.980227 +0.258486 0.268829 0.927856 +0.108906 0.165213 0.980227 +0.137150 0.142638 0.980227 +0.108906 0.165213 0.980227 +0.258486 0.268829 0.927856 +0.205254 0.311376 0.927856 +0.205254 0.311376 0.927856 +0.075016 0.183107 0.980227 +0.108906 0.165213 0.980227 +0.075016 0.183107 0.980227 +0.205254 0.311376 0.927856 +0.141383 0.345101 0.927856 +0.141383 0.345101 0.927856 +0.036741 0.194437 0.980227 +0.075016 0.183107 0.980227 +0.036741 0.194437 0.980227 +0.141383 0.345101 0.927856 +0.069246 0.366455 0.927856 +0.137150 0.142638 0.980227 +0.008921 0.013534 0.999869 +0.011235 0.011685 0.999869 +0.008921 0.013534 0.999869 +0.137150 0.142638 0.980227 +0.108906 0.165213 0.980227 +0.108906 0.165213 0.980227 +0.006145 0.015000 0.999869 +0.008921 0.013534 0.999869 +0.006145 0.015000 0.999869 +0.108906 0.165213 0.980227 +0.075016 0.183107 0.980227 +0.075016 0.183107 0.980227 +0.003010 0.015928 0.999869 +0.006145 0.015000 0.999869 +0.003010 0.015928 0.999869 +0.075016 0.183107 0.980227 +0.036741 0.194437 0.980227 +0.000000 0.000000 1.000000 +0.003010 -0.015928 0.999869 +0.000000 0.000000 1.000000 +0.197662 -0.008540 0.980233 +0.378731 -0.083985 0.921688 +0.387634 -0.015186 0.921688 +0.258486 -0.268829 0.927856 +0.207738 -0.327621 0.921688 +0.268886 -0.279626 0.921688 +0.205254 -0.311376 0.927856 +0.207738 -0.327621 0.921688 +0.258486 -0.268829 0.927856 +0.141383 -0.345101 0.927856 +0.207738 -0.327621 0.921688 +0.205254 -0.311376 0.927856 +0.141383 -0.345101 0.927856 +0.139684 -0.361910 0.921688 +0.207738 -0.327621 0.921688 +0.069246 -0.366455 0.927856 +0.139684 -0.361910 0.921688 +0.141383 -0.345101 0.927856 +0.069246 -0.366455 0.927856 +0.069095 -0.381728 0.921688 +0.139684 -0.361910 0.921688 +0.268886 -0.279626 0.921688 +0.303088 -0.217306 0.927856 +0.258486 -0.268829 0.927856 +0.319238 -0.220403 0.921688 +0.303088 -0.217306 0.927856 +0.268886 -0.279626 0.921688 +0.319238 -0.220403 0.921688 +0.339292 -0.154807 0.927856 +0.303088 -0.217306 0.927856 +0.356165 -0.153743 0.921688 +0.339292 -0.154807 0.927856 +0.319238 -0.220403 0.921688 +0.356165 -0.153743 0.921688 +0.363458 -0.083563 0.927856 +0.339292 -0.154807 0.927856 +0.378731 -0.083985 0.921688 +0.363458 -0.083563 0.927856 +0.356165 -0.153743 0.921688 +0.197662 -0.008540 0.980233 +0.363458 -0.083563 0.927856 +0.378731 -0.083985 0.921688 +0.197662 -0.008540 0.980233 +0.192847 -0.044338 0.980227 +0.363458 -0.083563 0.927856 +0.000000 0.000000 1.000000 +0.192847 -0.044338 0.980227 +0.197662 -0.008540 0.980233 +0.000000 0.000000 1.000000 +0.015798 -0.003632 0.999869 +0.192847 -0.044338 0.980227 +0.000000 0.000000 1.000000 +0.015798 -0.003632 0.999869 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.014747 -0.006729 0.999869 +0.015798 -0.003632 0.999869 +0.000000 0.000000 1.000000 +0.014747 -0.006729 0.999869 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.014747 -0.006729 0.999869 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.013174 -0.009445 0.999869 +0.014747 -0.006729 0.999869 +0.000000 0.000000 1.000000 +0.013174 -0.009445 0.999869 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.011235 -0.011685 0.999869 +0.013174 -0.009445 0.999869 +0.000000 0.000000 1.000000 +0.008921 -0.013534 0.999869 +0.011235 -0.011685 0.999869 +0.000000 0.000000 1.000000 +0.008921 -0.013534 0.999869 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.006145 -0.015000 0.999869 +0.008921 -0.013534 0.999869 +0.000000 0.000000 1.000000 +0.006145 -0.015000 0.999869 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.003010 -0.015928 0.999869 +0.006145 -0.015000 0.999869 +0.000000 0.000000 1.000000 +0.003010 -0.015928 0.999869 +0.000000 0.000000 1.000000 +0.069095 -0.381728 0.921688 +0.000000 -0.197878 0.980227 +0.000000 -0.387931 0.921688 +0.069246 -0.366455 0.927856 +0.000000 -0.197878 0.980227 +0.069095 -0.381728 0.921688 +0.036741 -0.194437 0.980227 +0.000000 -0.197878 0.980227 +0.069246 -0.366455 0.927856 +0.036741 -0.194437 0.980227 +0.000000 0.000000 1.000000 +0.000000 -0.197878 0.980227 +0.003010 -0.015928 0.999869 +0.000000 0.000000 1.000000 +0.036741 -0.194437 0.980227 +0.069246 -0.366455 0.927856 +0.075016 -0.183107 0.980227 +0.036741 -0.194437 0.980227 +0.075016 -0.183107 0.980227 +0.069246 -0.366455 0.927856 +0.141383 -0.345101 0.927856 +0.141383 -0.345101 0.927856 +0.108906 -0.165213 0.980227 +0.075016 -0.183107 0.980227 +0.108906 -0.165213 0.980227 +0.141383 -0.345101 0.927856 +0.205254 -0.311376 0.927856 +0.205254 -0.311376 0.927856 +0.137150 -0.142638 0.980227 +0.108906 -0.165213 0.980227 +0.137150 -0.142638 0.980227 +0.205254 -0.311376 0.927856 +0.258486 -0.268829 0.927856 +0.036741 -0.194437 0.980227 +0.006145 -0.015000 0.999869 +0.003010 -0.015928 0.999869 +0.006145 -0.015000 0.999869 +0.036741 -0.194437 0.980227 +0.075016 -0.183107 0.980227 +0.075016 -0.183107 0.980227 +0.008921 -0.013534 0.999869 +0.006145 -0.015000 0.999869 +0.008921 -0.013534 0.999869 +0.075016 -0.183107 0.980227 +0.108906 -0.165213 0.980227 +0.108906 -0.165213 0.980227 +0.011235 -0.011685 0.999869 +0.008921 -0.013534 0.999869 +0.011235 -0.011685 0.999869 +0.108906 -0.165213 0.980227 +0.137150 -0.142638 0.980227 +0.258486 -0.268829 0.927856 +0.160815 -0.115301 0.980227 +0.137150 -0.142638 0.980227 +0.160815 -0.115301 0.980227 +0.258486 -0.268829 0.927856 +0.303088 -0.217306 0.927856 +0.303088 -0.217306 0.927856 +0.180025 -0.082139 0.980227 +0.160815 -0.115301 0.980227 +0.180025 -0.082139 0.980227 +0.303088 -0.217306 0.927856 +0.339292 -0.154807 0.927856 +0.339292 -0.154807 0.927856 +0.192847 -0.044338 0.980227 +0.180025 -0.082139 0.980227 +0.192847 -0.044338 0.980227 +0.339292 -0.154807 0.927856 +0.363458 -0.083563 0.927856 +0.137150 -0.142638 0.980227 +0.013174 -0.009445 0.999869 +0.011235 -0.011685 0.999869 +0.013174 -0.009445 0.999869 +0.137150 -0.142638 0.980227 +0.160815 -0.115301 0.980227 +0.160815 -0.115301 0.980227 +0.014747 -0.006729 0.999869 +0.013174 -0.009445 0.999869 +0.014747 -0.006729 0.999869 +0.160815 -0.115301 0.980227 +0.180025 -0.082139 0.980227 +0.180025 -0.082139 0.980227 +0.015798 -0.003632 0.999869 +0.014747 -0.006729 0.999869 +0.015798 -0.003632 0.999869 +0.180025 -0.082139 0.980227 +0.192847 -0.044338 0.980227 +0.000000 -1.000000 0.000000 +-0.185711 -0.982604 0.000000 +0.000000 -1.000000 0.000000 +-0.974582 -0.224029 0.000000 +-0.999234 -0.039145 0.000000 +-0.999234 -0.039142 0.000000 +-0.974582 -0.224029 0.000000 +-0.974582 -0.224029 0.000000 +-0.999234 -0.039145 0.000000 +-0.974582 -0.224029 0.000000 +-0.909791 -0.415066 0.000000 +-0.974582 -0.224029 0.000000 +-0.909791 -0.415066 0.000000 +-0.909791 -0.415066 0.000000 +-0.974582 -0.224029 0.000000 +-0.909791 -0.415066 0.000000 +-0.812720 -0.582655 0.000000 +-0.909791 -0.415066 0.000000 +-0.812720 -0.582655 0.000000 +-0.812720 -0.582655 0.000000 +-0.909791 -0.415066 0.000000 +-0.693130 -0.720813 0.000000 +-0.812720 -0.582655 0.000000 +-0.812720 -0.582655 0.000000 +-0.693130 -0.720813 0.000000 +-0.693130 -0.720813 0.000000 +-0.812720 -0.582655 0.000000 +-0.693130 -0.720813 0.000000 +-0.550397 -0.834903 0.000000 +-0.693130 -0.720813 0.000000 +-0.550397 -0.834903 0.000000 +-0.550397 -0.834903 0.000000 +-0.693130 -0.720813 0.000000 +-0.379137 -0.925341 0.000000 +-0.550397 -0.834903 0.000000 +-0.550397 -0.834903 0.000000 +-0.379137 -0.925341 0.000000 +-0.379137 -0.925341 0.000000 +-0.550397 -0.834903 0.000000 +-0.379137 -0.925341 0.000000 +-0.185711 -0.982604 0.000000 +-0.379137 -0.925341 0.000000 +-0.185711 -0.982604 0.000000 +-0.185711 -0.982604 0.000000 +-0.379137 -0.925341 0.000000 +-0.185711 -0.982604 0.000000 +0.000000 -1.000000 0.000000 +-0.185711 -0.982604 0.000000 +-0.812720 0.582655 0.000000 +-0.693130 0.720813 0.000000 +-0.812720 0.582655 0.000000 +-0.999234 0.039145 0.000000 +-0.974582 0.224029 0.000000 +-0.999234 0.039142 0.000000 +-0.974582 0.224029 0.000000 +-0.974582 0.224029 0.000000 +-0.999234 0.039145 0.000000 +-0.974582 0.224029 0.000000 +-0.909791 0.415066 0.000000 +-0.974582 0.224029 0.000000 +-0.909791 0.415066 0.000000 +-0.909791 0.415066 0.000000 +-0.974582 0.224029 0.000000 +-0.909791 0.415066 0.000000 +-0.812720 0.582655 0.000000 +-0.909791 0.415066 0.000000 +-0.812720 0.582655 0.000000 +-0.812720 0.582655 0.000000 +-0.909791 0.415066 0.000000 +-0.185711 0.982604 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.185711 0.982604 0.000000 +-0.185711 0.982604 0.000000 +0.000000 1.000000 0.000000 +-0.379137 0.925341 0.000000 +-0.185711 0.982604 0.000000 +-0.185711 0.982604 0.000000 +-0.379137 0.925341 0.000000 +-0.379137 0.925341 0.000000 +-0.185711 0.982604 0.000000 +-0.550397 0.834903 0.000000 +-0.379137 0.925341 0.000000 +-0.379137 0.925341 0.000000 +-0.550397 0.834903 0.000000 +-0.550397 0.834903 0.000000 +-0.379137 0.925341 0.000000 +-0.693130 0.720813 0.000000 +-0.550397 0.834903 0.000000 +-0.550397 0.834903 0.000000 +-0.693130 0.720813 0.000000 +-0.693130 0.720813 0.000000 +-0.550397 0.834903 0.000000 +-0.693130 0.720813 0.000000 +-0.812720 0.582655 0.000000 +-0.693130 0.720813 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -0.387931 0.921688 +0.000000 -0.372940 0.927856 +0.000000 -0.387931 0.921688 +0.000000 -0.016210 0.999869 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -0.016210 0.999869 +0.000000 -0.197878 0.980227 +0.000000 0.000000 1.000000 +0.000000 -0.197878 0.980227 +0.000000 -0.197878 0.980227 +0.000000 -0.016210 0.999869 +0.000000 -0.372940 0.927856 +0.000000 -0.197878 0.980227 +0.000000 -0.197878 0.980227 +0.000000 -0.372940 0.927856 +0.000000 -0.387931 0.921688 +0.000000 -0.197878 0.980227 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.930762 -0.365522 0.008727 +-0.985183 -0.171285 0.008727 +-0.985183 -0.171285 0.008727 +-0.999464 -0.031550 0.008727 +-0.985183 -0.171285 0.008727 +-0.999624 -0.026011 0.008727 +-0.985183 -0.171285 0.008727 +-0.985183 -0.171285 0.008727 +-0.999464 -0.031550 0.008727 +-0.238278 -0.971158 0.008727 +-0.099525 -0.994997 0.008727 +-0.094336 -0.995502 0.008727 +-0.238278 -0.971158 0.008727 +-0.238278 -0.971158 0.008727 +-0.099525 -0.994997 0.008727 +-0.238278 -0.971158 0.008727 +-0.428337 -0.903577 0.008727 +-0.238278 -0.971158 0.008727 +-0.428337 -0.903577 0.008727 +-0.428337 -0.903577 0.008727 +-0.238278 -0.971158 0.008727 +-0.594480 -0.804063 0.008727 +-0.428337 -0.903577 0.008727 +-0.428337 -0.903577 0.008727 +-0.594480 -0.804063 0.008727 +-0.594480 -0.804063 0.008727 +-0.428337 -0.903577 0.008727 +-0.730865 -0.682466 0.008727 +-0.594480 -0.804063 0.008727 +-0.594480 -0.804063 0.008727 +-0.730865 -0.682466 0.008727 +-0.730865 -0.682466 0.008727 +-0.594480 -0.804063 0.008727 +-0.730865 -0.682466 0.008727 +-0.842847 -0.538083 0.008727 +-0.730865 -0.682466 0.008727 +-0.842847 -0.538083 0.008727 +-0.842847 -0.538083 0.008727 +-0.730865 -0.682466 0.008727 +-0.930762 -0.365522 0.008727 +-0.842847 -0.538083 0.008727 +-0.842847 -0.538083 0.008727 +-0.930762 -0.365522 0.008727 +-0.930762 -0.365522 0.008727 +-0.842847 -0.538083 0.008727 +-0.985183 -0.171285 0.008727 +-0.930762 -0.365522 0.008727 +-0.930762 -0.365522 0.008727 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.016210 0.999869 +0.000000 0.197878 0.980227 +0.000000 0.197878 0.980227 +0.000000 0.372940 0.927856 +0.000000 0.387931 0.921688 +0.000000 0.387931 0.921688 +0.000000 0.372940 0.927856 +0.000000 0.197878 0.980227 +0.000000 0.387931 0.921688 +0.000000 0.197878 0.980227 +0.000000 0.197878 0.980227 +0.000000 0.372940 0.927856 +0.000000 0.197878 0.980227 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.197878 0.980227 +0.000000 0.016210 0.999869 +0.000000 0.000000 1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.809616 0.586894 0.008727 +-0.689307 0.724417 0.008727 +-0.809616 0.586894 0.008727 +-0.080766 0.996695 0.008727 +-0.180539 0.983529 0.008727 +-0.075469 0.997110 0.008727 +-0.180539 0.983529 0.008727 +-0.180539 0.983529 0.008727 +-0.080766 0.996695 0.008727 +-0.973355 0.229138 0.008727 +-0.991485 0.129926 0.008727 +-0.992134 0.124874 0.008727 +-0.973355 0.229138 0.008727 +-0.973355 0.229138 0.008727 +-0.991485 0.129926 0.008727 +-0.907564 0.419824 0.008727 +-0.973355 0.229138 0.008727 +-0.973355 0.229138 0.008727 +-0.907564 0.419824 0.008727 +-0.907564 0.419824 0.008727 +-0.973355 0.229138 0.008727 +-0.809616 0.586894 0.008727 +-0.907564 0.419824 0.008727 +-0.907564 0.419824 0.008727 +-0.809616 0.586894 0.008727 +-0.809616 0.586894 0.008727 +-0.907564 0.419824 0.008727 +-0.374256 0.927284 0.008727 +-0.180539 0.983529 0.008727 +-0.180539 0.983529 0.008727 +-0.374256 0.927284 0.008727 +-0.374256 0.927284 0.008727 +-0.180539 0.983529 0.008727 +-0.545982 0.837751 0.008727 +-0.374256 0.927284 0.008727 +-0.374256 0.927284 0.008727 +-0.545982 0.837751 0.008727 +-0.545982 0.837751 0.008727 +-0.374256 0.927284 0.008727 +-0.689307 0.724417 0.008727 +-0.545982 0.837751 0.008727 +-0.545982 0.837751 0.008727 +-0.689307 0.724417 0.008727 +-0.689307 0.724417 0.008727 +-0.545982 0.837751 0.008727 +-0.689307 0.724417 0.008727 +-0.809616 0.586894 0.008727 +-0.689307 0.724417 0.008727 +-0.007637 -0.999933 0.008727 +-0.007637 -0.999933 0.008727 +-0.007637 -0.999933 0.008727 +-0.007637 -0.999933 0.008727 +-0.007637 -0.999933 0.008727 +-0.007637 -0.999933 0.008727 +0.007637 0.999933 0.008727 +0.007637 0.999933 0.008727 +0.007637 0.999933 0.008727 +0.007637 0.999933 0.008727 +0.007637 0.999933 0.008727 +0.007637 0.999933 0.008727 +-0.015798 0.003632 0.999869 +0.000000 0.000000 1.000000 +-0.014747 0.006729 0.999869 +-0.197662 0.008540 0.980233 +-0.378731 0.083985 0.921688 +-0.387634 0.015186 0.921688 +0.000000 0.000000 1.000000 +-0.013174 0.009445 0.999869 +-0.014747 0.006729 0.999869 +0.000000 0.000000 1.000000 +-0.013174 0.009445 0.999869 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.011235 0.011685 0.999869 +-0.013174 0.009445 0.999869 +0.000000 0.000000 1.000000 +-0.011235 0.011685 0.999869 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.011235 0.011685 0.999869 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.008921 0.013534 0.999869 +-0.011235 0.011685 0.999869 +0.000000 0.000000 1.000000 +-0.008921 0.013534 0.999869 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.006145 0.015000 0.999869 +-0.008921 0.013534 0.999869 +0.000000 0.000000 1.000000 +-0.006145 0.015000 0.999869 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.003010 0.015928 0.999869 +-0.006145 0.015000 0.999869 +0.000000 0.000000 1.000000 +-0.003010 0.015928 0.999869 +0.000000 0.000000 1.000000 +0.000000 0.197878 0.980227 +-0.003010 0.015928 0.999869 +0.000000 0.000000 1.000000 +0.000000 0.197878 0.980227 +-0.036741 0.194437 0.980227 +-0.003010 0.015928 0.999869 +0.000000 0.387931 0.921688 +-0.036741 0.194437 0.980227 +0.000000 0.197878 0.980227 +0.000000 0.387931 0.921688 +-0.069246 0.366455 0.927856 +-0.036741 0.194437 0.980227 +-0.069095 0.381728 0.921688 +-0.069246 0.366455 0.927856 +0.000000 0.387931 0.921688 +-0.139684 0.361910 0.921688 +-0.069246 0.366455 0.927856 +-0.069095 0.381728 0.921688 +-0.139684 0.361910 0.921688 +-0.141383 0.345101 0.927856 +-0.069246 0.366455 0.927856 +-0.207738 0.327621 0.921688 +-0.141383 0.345101 0.927856 +-0.139684 0.361910 0.921688 +-0.207738 0.327621 0.921688 +-0.205254 0.311376 0.927856 +-0.141383 0.345101 0.927856 +-0.268886 0.279626 0.921688 +-0.205254 0.311376 0.927856 +-0.207738 0.327621 0.921688 +-0.268886 0.279626 0.921688 +-0.258486 0.268829 0.927856 +-0.205254 0.311376 0.927856 +-0.268886 0.279626 0.921688 +-0.303088 0.217306 0.927856 +-0.258486 0.268829 0.927856 +-0.319238 0.220403 0.921688 +-0.303088 0.217306 0.927856 +-0.268886 0.279626 0.921688 +-0.319238 0.220403 0.921688 +-0.339292 0.154807 0.927856 +-0.303088 0.217306 0.927856 +-0.356165 0.153743 0.921688 +-0.339292 0.154807 0.927856 +-0.319238 0.220403 0.921688 +-0.356165 0.153743 0.921688 +-0.363458 0.083563 0.927856 +-0.339292 0.154807 0.927856 +-0.378731 0.083985 0.921688 +-0.363458 0.083563 0.927856 +-0.356165 0.153743 0.921688 +-0.197662 0.008540 0.980233 +-0.363458 0.083563 0.927856 +-0.378731 0.083985 0.921688 +-0.197662 0.008540 0.980233 +-0.192847 0.044338 0.980227 +-0.363458 0.083563 0.927856 +0.000000 0.000000 1.000000 +-0.192847 0.044338 0.980227 +-0.197662 0.008540 0.980233 +0.000000 0.000000 1.000000 +-0.015798 0.003632 0.999869 +-0.192847 0.044338 0.980227 +0.000000 0.000000 1.000000 +-0.015798 0.003632 0.999869 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.015798 0.003632 0.999869 +0.000000 0.000000 1.000000 +-0.069246 0.366455 0.927856 +-0.075016 0.183107 0.980227 +-0.036741 0.194437 0.980227 +-0.075016 0.183107 0.980227 +-0.069246 0.366455 0.927856 +-0.141383 0.345101 0.927856 +-0.141383 0.345101 0.927856 +-0.108906 0.165213 0.980227 +-0.075016 0.183107 0.980227 +-0.108906 0.165213 0.980227 +-0.141383 0.345101 0.927856 +-0.205254 0.311376 0.927856 +-0.205254 0.311376 0.927856 +-0.137150 0.142638 0.980227 +-0.108906 0.165213 0.980227 +-0.137150 0.142638 0.980227 +-0.205254 0.311376 0.927856 +-0.258486 0.268829 0.927856 +-0.036741 0.194437 0.980227 +-0.006145 0.015000 0.999869 +-0.003010 0.015928 0.999869 +-0.006145 0.015000 0.999869 +-0.036741 0.194437 0.980227 +-0.075016 0.183107 0.980227 +-0.075016 0.183107 0.980227 +-0.008921 0.013534 0.999869 +-0.006145 0.015000 0.999869 +-0.008921 0.013534 0.999869 +-0.075016 0.183107 0.980227 +-0.108906 0.165213 0.980227 +-0.108906 0.165213 0.980227 +-0.011235 0.011685 0.999869 +-0.008921 0.013534 0.999869 +-0.011235 0.011685 0.999869 +-0.108906 0.165213 0.980227 +-0.137150 0.142638 0.980227 +-0.258486 0.268829 0.927856 +-0.160815 0.115301 0.980227 +-0.137150 0.142638 0.980227 +-0.160815 0.115301 0.980227 +-0.258486 0.268829 0.927856 +-0.303088 0.217306 0.927856 +-0.303088 0.217306 0.927856 +-0.180025 0.082139 0.980227 +-0.160815 0.115301 0.980227 +-0.180025 0.082139 0.980227 +-0.303088 0.217306 0.927856 +-0.339292 0.154807 0.927856 +-0.339292 0.154807 0.927856 +-0.192847 0.044338 0.980227 +-0.180025 0.082139 0.980227 +-0.192847 0.044338 0.980227 +-0.339292 0.154807 0.927856 +-0.363458 0.083563 0.927856 +-0.137150 0.142638 0.980227 +-0.013174 0.009445 0.999869 +-0.011235 0.011685 0.999869 +-0.013174 0.009445 0.999869 +-0.137150 0.142638 0.980227 +-0.160815 0.115301 0.980227 +-0.160815 0.115301 0.980227 +-0.014747 0.006729 0.999869 +-0.013174 0.009445 0.999869 +-0.014747 0.006729 0.999869 +-0.160815 0.115301 0.980227 +-0.180025 0.082139 0.980227 +-0.180025 0.082139 0.980227 +-0.015798 0.003632 0.999869 +-0.014747 0.006729 0.999869 +-0.015798 0.003632 0.999869 +-0.180025 0.082139 0.980227 +-0.192847 0.044338 0.980227 +0.550397 -0.834903 0.000000 +0.693130 -0.720813 0.000000 +0.693130 -0.720813 0.000000 +0.999234 -0.039145 0.000000 +0.974582 -0.224029 0.000000 +0.999234 -0.039142 0.000000 +0.974582 -0.224029 0.000000 +0.974582 -0.224029 0.000000 +0.999234 -0.039145 0.000000 +0.974582 -0.224029 0.000000 +0.909791 -0.415066 0.000000 +0.974582 -0.224029 0.000000 +0.909791 -0.415066 0.000000 +0.909791 -0.415066 0.000000 +0.974582 -0.224029 0.000000 +0.812720 -0.582655 0.000000 +0.909791 -0.415066 0.000000 +0.909791 -0.415066 0.000000 +0.812720 -0.582655 0.000000 +0.812720 -0.582655 0.000000 +0.909791 -0.415066 0.000000 +0.812720 -0.582655 0.000000 +0.693130 -0.720813 0.000000 +0.812720 -0.582655 0.000000 +0.693130 -0.720813 0.000000 +0.693130 -0.720813 0.000000 +0.812720 -0.582655 0.000000 +0.185711 -0.982604 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.185711 -0.982604 0.000000 +0.185711 -0.982604 0.000000 +0.000000 -1.000000 0.000000 +0.379137 -0.925341 0.000000 +0.185711 -0.982604 0.000000 +0.185711 -0.982604 0.000000 +0.379137 -0.925341 0.000000 +0.379137 -0.925341 0.000000 +0.185711 -0.982604 0.000000 +0.379137 -0.925341 0.000000 +0.550397 -0.834903 0.000000 +0.379137 -0.925341 0.000000 +0.550397 -0.834903 0.000000 +0.550397 -0.834903 0.000000 +0.379137 -0.925341 0.000000 +0.693130 -0.720813 0.000000 +0.550397 -0.834903 0.000000 +0.550397 -0.834903 0.000000 +0.999962 0.000000 -0.008727 +0.983268 -0.181956 -0.008727 +0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.983268 -0.181956 -0.008727 +-0.999962 0.000000 -0.008727 +-0.983268 -0.181956 -0.008727 +-0.983268 -0.181956 -0.008727 +-0.999962 0.000000 -0.008727 +-0.983268 -0.181956 -0.008727 +-0.929753 -0.368081 -0.008727 +-0.983268 -0.181956 -0.008727 +-0.929753 -0.368081 -0.008727 +-0.929753 -0.368081 -0.008727 +-0.983268 -0.181956 -0.008727 +-0.929753 -0.368081 -0.008727 +-0.836964 -0.547189 -0.008727 +-0.929753 -0.368081 -0.008727 +-0.836964 -0.547189 -0.008727 +-0.836964 -0.547189 -0.008727 +-0.929753 -0.368081 -0.008727 +-0.707080 -0.707080 -0.008727 +-0.836964 -0.547189 -0.008727 +-0.836964 -0.547189 -0.008727 +-0.707080 -0.707080 -0.008727 +-0.707080 -0.707080 -0.008727 +-0.836964 -0.547189 -0.008727 +-0.547189 -0.836964 -0.008727 +-0.707080 -0.707080 -0.008727 +-0.707080 -0.707080 -0.008727 +-0.547189 -0.836964 -0.008727 +-0.547189 -0.836964 -0.008727 +-0.707080 -0.707080 -0.008727 +-0.368081 -0.929753 -0.008727 +-0.547189 -0.836964 -0.008727 +-0.547189 -0.836964 -0.008727 +-0.368081 -0.929753 -0.008727 +-0.368081 -0.929753 -0.008727 +-0.547189 -0.836964 -0.008727 +-0.368081 -0.929753 -0.008727 +-0.181956 -0.983268 -0.008727 +-0.368081 -0.929753 -0.008727 +-0.181956 -0.983268 -0.008727 +-0.181956 -0.983268 -0.008727 +-0.368081 -0.929753 -0.008727 +0.000000 -0.999962 -0.008727 +-0.181956 -0.983268 -0.008727 +-0.181956 -0.983268 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +-0.181956 -0.983268 -0.008727 +0.181956 -0.983268 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.181956 -0.983268 -0.008727 +0.181956 -0.983268 -0.008727 +0.000000 -0.999962 -0.008727 +0.368081 -0.929753 -0.008727 +0.181956 -0.983268 -0.008727 +0.181956 -0.983268 -0.008727 +0.368081 -0.929753 -0.008727 +0.368081 -0.929753 -0.008727 +0.181956 -0.983268 -0.008727 +0.368081 -0.929753 -0.008727 +0.547189 -0.836964 -0.008727 +0.368081 -0.929753 -0.008727 +0.547189 -0.836964 -0.008727 +0.547189 -0.836964 -0.008727 +0.368081 -0.929753 -0.008727 +0.707080 -0.707080 -0.008727 +0.547189 -0.836964 -0.008727 +0.547189 -0.836964 -0.008727 +0.707080 -0.707080 -0.008727 +0.707080 -0.707080 -0.008727 +0.547189 -0.836964 -0.008727 +0.707080 -0.707080 -0.008727 +0.836964 -0.547189 -0.008727 +0.707080 -0.707080 -0.008727 +0.836964 -0.547189 -0.008727 +0.836964 -0.547189 -0.008727 +0.707080 -0.707080 -0.008727 +0.836964 -0.547189 -0.008727 +0.929753 -0.368081 -0.008727 +0.836964 -0.547189 -0.008727 +0.929753 -0.368081 -0.008727 +0.929753 -0.368081 -0.008727 +0.836964 -0.547189 -0.008727 +0.983268 -0.181956 -0.008727 +0.929753 -0.368081 -0.008727 +0.929753 -0.368081 -0.008727 +0.983268 -0.181956 -0.008727 +0.983268 -0.181956 -0.008727 +0.929753 -0.368081 -0.008727 +0.983268 -0.181956 -0.008727 +0.999962 0.000000 -0.008727 +0.983268 -0.181956 -0.008727 +-0.999962 0.000000 -0.008727 +-0.983268 -0.181956 -0.008727 +-0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.983268 -0.181956 -0.008727 +0.999962 0.000000 -0.008727 +0.983268 -0.181956 -0.008727 +0.983268 -0.181956 -0.008727 +0.999962 0.000000 -0.008727 +0.929753 -0.368081 -0.008727 +0.983268 -0.181956 -0.008727 +0.983268 -0.181956 -0.008727 +0.929753 -0.368081 -0.008727 +0.929753 -0.368081 -0.008727 +0.983268 -0.181956 -0.008727 +0.836964 -0.547189 -0.008727 +0.929753 -0.368081 -0.008727 +0.929753 -0.368081 -0.008727 +0.836964 -0.547189 -0.008727 +0.836964 -0.547189 -0.008727 +0.929753 -0.368081 -0.008727 +0.707080 -0.707080 -0.008727 +0.836964 -0.547189 -0.008727 +0.836964 -0.547189 -0.008727 +0.707080 -0.707080 -0.008727 +0.707080 -0.707080 -0.008727 +0.836964 -0.547189 -0.008727 +0.547189 -0.836964 -0.008727 +0.707080 -0.707080 -0.008727 +0.707080 -0.707080 -0.008727 +0.547189 -0.836964 -0.008727 +0.547189 -0.836964 -0.008727 +0.707080 -0.707080 -0.008727 +0.368081 -0.929753 -0.008727 +0.547189 -0.836964 -0.008727 +0.547189 -0.836964 -0.008727 +0.368081 -0.929753 -0.008727 +0.368081 -0.929753 -0.008727 +0.547189 -0.836964 -0.008727 +0.181956 -0.983268 -0.008727 +0.368081 -0.929753 -0.008727 +0.368081 -0.929753 -0.008727 +0.181956 -0.983268 -0.008727 +0.181956 -0.983268 -0.008727 +0.368081 -0.929753 -0.008727 +0.000000 -0.999962 -0.008727 +0.181956 -0.983268 -0.008727 +0.181956 -0.983268 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.181956 -0.983268 -0.008727 +-0.181956 -0.983268 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +-0.181956 -0.983268 -0.008727 +-0.181956 -0.983268 -0.008727 +0.000000 -0.999962 -0.008727 +-0.368081 -0.929753 -0.008727 +-0.181956 -0.983268 -0.008727 +-0.181956 -0.983268 -0.008727 +-0.368081 -0.929753 -0.008727 +-0.368081 -0.929753 -0.008727 +-0.181956 -0.983268 -0.008727 +-0.547189 -0.836964 -0.008727 +-0.368081 -0.929753 -0.008727 +-0.368081 -0.929753 -0.008727 +-0.547189 -0.836964 -0.008727 +-0.547189 -0.836964 -0.008727 +-0.368081 -0.929753 -0.008727 +-0.547189 -0.836964 -0.008727 +-0.707080 -0.707080 -0.008727 +-0.547189 -0.836964 -0.008727 +-0.707080 -0.707080 -0.008727 +-0.707080 -0.707080 -0.008727 +-0.547189 -0.836964 -0.008727 +-0.836964 -0.547189 -0.008727 +-0.707080 -0.707080 -0.008727 +-0.707080 -0.707080 -0.008727 +-0.836964 -0.547189 -0.008727 +-0.836964 -0.547189 -0.008727 +-0.707080 -0.707080 -0.008727 +-0.929753 -0.368081 -0.008727 +-0.836964 -0.547189 -0.008727 +-0.836964 -0.547189 -0.008727 +-0.929753 -0.368081 -0.008727 +-0.929753 -0.368081 -0.008727 +-0.836964 -0.547189 -0.008727 +-0.983268 -0.181956 -0.008727 +-0.929753 -0.368081 -0.008727 +-0.929753 -0.368081 -0.008727 +-0.983268 -0.181956 -0.008727 +-0.983268 -0.181956 -0.008727 +-0.929753 -0.368081 -0.008727 +-0.983268 -0.181956 -0.008727 +-0.999962 0.000000 -0.008727 +-0.983268 -0.181956 -0.008727 +-0.983268 -0.181956 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.983268 -0.181956 -0.008727 +0.999962 0.000000 -0.008727 +0.983268 -0.181956 -0.008727 +0.983268 -0.181956 -0.008727 +0.999962 0.000000 -0.008727 +0.929753 -0.368081 -0.008727 +0.983268 -0.181956 -0.008727 +0.983268 -0.181956 -0.008727 +0.929753 -0.368081 -0.008727 +0.929753 -0.368081 -0.008727 +0.983268 -0.181956 -0.008727 +0.836964 -0.547189 -0.008727 +0.929753 -0.368081 -0.008727 +0.929753 -0.368081 -0.008727 +0.836964 -0.547189 -0.008727 +0.836964 -0.547189 -0.008727 +0.929753 -0.368081 -0.008727 +0.707080 -0.707080 -0.008727 +0.836964 -0.547189 -0.008727 +0.836964 -0.547189 -0.008727 +0.707080 -0.707080 -0.008727 +0.707080 -0.707080 -0.008727 +0.836964 -0.547189 -0.008727 +0.707080 -0.707080 -0.008727 +0.547189 -0.836964 -0.008727 +0.707080 -0.707080 -0.008727 +0.547189 -0.836964 -0.008727 +0.547189 -0.836964 -0.008727 +0.707080 -0.707080 -0.008727 +0.547189 -0.836964 -0.008727 +0.368081 -0.929753 -0.008727 +0.547189 -0.836964 -0.008727 +0.368081 -0.929753 -0.008727 +0.368081 -0.929753 -0.008727 +0.547189 -0.836964 -0.008727 +0.181956 -0.983268 -0.008727 +0.368081 -0.929753 -0.008727 +0.368081 -0.929753 -0.008727 +0.181956 -0.983268 -0.008727 +0.181956 -0.983268 -0.008727 +0.368081 -0.929753 -0.008727 +0.000000 -0.999962 -0.008727 +0.181956 -0.983268 -0.008727 +0.181956 -0.983268 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.181956 -0.983268 -0.008727 +0.000000 -0.999962 -0.008727 +-0.181956 -0.983268 -0.008727 +0.000000 -0.999962 -0.008727 +-0.181956 -0.983268 -0.008727 +-0.181956 -0.983268 -0.008727 +0.000000 -0.999962 -0.008727 +-0.368081 -0.929753 -0.008727 +-0.181956 -0.983268 -0.008727 +-0.181956 -0.983268 -0.008727 +-0.368081 -0.929753 -0.008727 +-0.368081 -0.929753 -0.008727 +-0.181956 -0.983268 -0.008727 +-0.547189 -0.836964 -0.008727 +-0.368081 -0.929753 -0.008727 +-0.368081 -0.929753 -0.008727 +-0.547189 -0.836964 -0.008727 +-0.547189 -0.836964 -0.008727 +-0.368081 -0.929753 -0.008727 +-0.707080 -0.707080 -0.008727 +-0.547189 -0.836964 -0.008727 +-0.547189 -0.836964 -0.008727 +-0.707080 -0.707080 -0.008727 +-0.707080 -0.707080 -0.008727 +-0.547189 -0.836964 -0.008727 +-0.836964 -0.547189 -0.008727 +-0.707080 -0.707080 -0.008727 +-0.707080 -0.707080 -0.008727 +-0.836964 -0.547189 -0.008727 +-0.836964 -0.547189 -0.008727 +-0.707080 -0.707080 -0.008727 +-0.929753 -0.368081 -0.008727 +-0.836964 -0.547189 -0.008727 +-0.836964 -0.547189 -0.008727 +-0.929753 -0.368081 -0.008727 +-0.929753 -0.368081 -0.008727 +-0.836964 -0.547189 -0.008727 +-0.983268 -0.181956 -0.008727 +-0.929753 -0.368081 -0.008727 +-0.929753 -0.368081 -0.008727 +-0.983268 -0.181956 -0.008727 +-0.983268 -0.181956 -0.008727 +-0.929753 -0.368081 -0.008727 +-0.999962 0.000000 -0.008727 +-0.983268 -0.181956 -0.008727 +-0.983268 -0.181956 -0.008727 +-0.983268 -0.181956 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.983268 -0.181956 -0.008727 +0.999962 0.000000 -0.008727 +0.983268 -0.181956 -0.008727 +0.983268 -0.181956 -0.008727 +0.999962 0.000000 -0.008727 +0.929753 -0.368081 -0.008727 +0.983268 -0.181956 -0.008727 +0.983268 -0.181956 -0.008727 +0.929753 -0.368081 -0.008727 +0.929753 -0.368081 -0.008727 +0.983268 -0.181956 -0.008727 +0.836964 -0.547189 -0.008727 +0.929753 -0.368081 -0.008727 +0.929753 -0.368081 -0.008727 +0.836964 -0.547189 -0.008727 +0.836964 -0.547189 -0.008727 +0.929753 -0.368081 -0.008727 +0.707080 -0.707080 -0.008727 +0.836964 -0.547189 -0.008727 +0.836964 -0.547189 -0.008727 +0.707080 -0.707080 -0.008727 +0.707080 -0.707080 -0.008727 +0.836964 -0.547189 -0.008727 +0.547189 -0.836964 -0.008727 +0.707080 -0.707080 -0.008727 +0.707080 -0.707080 -0.008727 +0.547189 -0.836964 -0.008727 +0.547189 -0.836964 -0.008727 +0.707080 -0.707080 -0.008727 +0.368081 -0.929753 -0.008727 +0.547189 -0.836964 -0.008727 +0.547189 -0.836964 -0.008727 +0.368081 -0.929753 -0.008727 +0.368081 -0.929753 -0.008727 +0.547189 -0.836964 -0.008727 +0.181956 -0.983268 -0.008727 +0.368081 -0.929753 -0.008727 +0.368081 -0.929753 -0.008727 +0.181956 -0.983268 -0.008727 +0.181956 -0.983268 -0.008727 +0.368081 -0.929753 -0.008727 +0.000000 -0.999962 -0.008727 +0.181956 -0.983268 -0.008727 +0.181956 -0.983268 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.181956 -0.983268 -0.008727 +-0.181956 -0.983268 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +-0.181956 -0.983268 -0.008727 +-0.181956 -0.983268 -0.008727 +0.000000 -0.999962 -0.008727 +-0.368081 -0.929753 -0.008727 +-0.181956 -0.983268 -0.008727 +-0.181956 -0.983268 -0.008727 +-0.368081 -0.929753 -0.008727 +-0.368081 -0.929753 -0.008727 +-0.181956 -0.983268 -0.008727 +-0.547189 -0.836964 -0.008727 +-0.368081 -0.929753 -0.008727 +-0.368081 -0.929753 -0.008727 +-0.547189 -0.836964 -0.008727 +-0.547189 -0.836964 -0.008727 +-0.368081 -0.929753 -0.008727 +-0.547189 -0.836964 -0.008727 +-0.707080 -0.707080 -0.008727 +-0.547189 -0.836964 -0.008727 +-0.707080 -0.707080 -0.008727 +-0.707080 -0.707080 -0.008727 +-0.547189 -0.836964 -0.008727 +-0.836964 -0.547189 -0.008727 +-0.707080 -0.707080 -0.008727 +-0.707080 -0.707080 -0.008727 +-0.836964 -0.547189 -0.008727 +-0.836964 -0.547189 -0.008727 +-0.707080 -0.707080 -0.008727 +-0.929753 -0.368081 -0.008727 +-0.836964 -0.547189 -0.008727 +-0.836964 -0.547189 -0.008727 +-0.929753 -0.368081 -0.008727 +-0.929753 -0.368081 -0.008727 +-0.836964 -0.547189 -0.008727 +-0.983268 -0.181956 -0.008727 +-0.929753 -0.368081 -0.008727 +-0.929753 -0.368081 -0.008727 +-0.983268 -0.181956 -0.008727 +-0.983268 -0.181956 -0.008727 +-0.929753 -0.368081 -0.008727 +-0.999962 0.000000 -0.008727 +-0.983268 -0.181956 -0.008727 +-0.983268 -0.181956 -0.008727 +-0.983268 0.181956 0.008727 +-0.999181 0.039514 0.008727 +-0.999181 0.039517 0.008727 +-0.181956 -0.983268 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +-0.181956 -0.983268 0.008727 +-0.181956 -0.983268 0.008727 +0.000000 -0.999962 0.008727 +-0.368081 -0.929753 0.008727 +-0.181956 -0.983268 0.008727 +-0.181956 -0.983268 0.008727 +-0.368081 -0.929753 0.008727 +-0.368081 -0.929753 0.008727 +-0.181956 -0.983268 0.008727 +-0.547189 -0.836964 0.008727 +-0.368081 -0.929753 0.008727 +-0.368081 -0.929753 0.008727 +-0.547189 -0.836964 0.008727 +-0.547189 -0.836964 0.008727 +-0.368081 -0.929753 0.008727 +-0.707080 -0.707080 0.008727 +-0.547189 -0.836964 0.008727 +-0.547189 -0.836964 0.008727 +-0.707080 -0.707080 0.008727 +-0.707080 -0.707080 0.008727 +-0.547189 -0.836964 0.008727 +-0.836964 -0.547189 0.008727 +-0.707080 -0.707080 0.008727 +-0.707080 -0.707080 0.008727 +-0.836964 -0.547189 0.008727 +-0.836964 -0.547189 0.008727 +-0.707080 -0.707080 0.008727 +-0.929753 -0.368081 0.008727 +-0.836964 -0.547189 0.008727 +-0.836964 -0.547189 0.008727 +-0.929753 -0.368081 0.008727 +-0.929753 -0.368081 0.008727 +-0.836964 -0.547189 0.008727 +-0.983268 -0.181956 0.008727 +-0.929753 -0.368081 0.008727 +-0.929753 -0.368081 0.008727 +-0.983268 -0.181956 0.008727 +-0.983268 -0.181956 0.008727 +-0.929753 -0.368081 0.008727 +-0.983268 -0.181956 0.008727 +-0.999962 0.000000 0.008727 +-0.983268 -0.181956 0.008727 +-0.999172 -0.039728 0.008727 +-0.983268 -0.181956 0.008727 +-0.999172 -0.039731 0.008727 +-0.999172 -0.039728 0.008727 +-0.999962 0.000000 0.008727 +-0.983268 -0.181956 0.008727 +-0.999181 0.039514 0.008727 +-0.999962 0.000000 0.008727 +-0.999172 -0.039728 0.008727 +-0.999181 0.039514 0.008727 +-0.983268 0.181956 0.008727 +-0.999962 0.000000 0.008727 +-0.181956 0.983268 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +-0.181956 0.983268 0.008727 +-0.181956 0.983268 0.008727 +0.000000 0.999962 0.008727 +-0.181956 0.983268 0.008727 +-0.368081 0.929753 0.008727 +-0.181956 0.983268 0.008727 +-0.368081 0.929753 0.008727 +-0.368081 0.929753 0.008727 +-0.181956 0.983268 0.008727 +-0.547189 0.836964 0.008727 +-0.368081 0.929753 0.008727 +-0.368081 0.929753 0.008727 +-0.547189 0.836964 0.008727 +-0.547189 0.836964 0.008727 +-0.368081 0.929753 0.008727 +-0.707080 0.707080 0.008727 +-0.547189 0.836964 0.008727 +-0.547189 0.836964 0.008727 +-0.707080 0.707080 0.008727 +-0.707080 0.707080 0.008727 +-0.547189 0.836964 0.008727 +-0.836964 0.547189 0.008727 +-0.707080 0.707080 0.008727 +-0.707080 0.707080 0.008727 +-0.836964 0.547189 0.008727 +-0.836964 0.547189 0.008727 +-0.707080 0.707080 0.008727 +-0.836964 0.547189 0.008727 +-0.929753 0.368081 0.008727 +-0.836964 0.547189 0.008727 +-0.929753 0.368081 0.008727 +-0.929753 0.368081 0.008727 +-0.836964 0.547189 0.008727 +-0.983268 0.181956 0.008727 +-0.929753 0.368081 0.008727 +-0.929753 0.368081 0.008727 +-0.983268 0.181956 0.008727 +-0.983268 0.181956 0.008727 +-0.929753 0.368081 0.008727 +-0.999181 0.039514 0.008727 +-0.983268 0.181956 0.008727 +-0.983268 0.181956 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.978744 -0.204902 0.008727 +0.999159 -0.040076 0.008727 +0.999158 -0.040079 0.008727 +0.204902 -0.978744 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.204902 -0.978744 0.008727 +0.204902 -0.978744 0.008727 +0.000000 -0.999962 0.008727 +0.397162 -0.917707 0.008727 +0.204902 -0.978744 0.008727 +0.204902 -0.978744 0.008727 +0.397162 -0.917707 0.008727 +0.397162 -0.917707 0.008727 +0.204902 -0.978744 0.008727 +0.397162 -0.917707 0.008727 +0.566613 -0.823938 0.008727 +0.397162 -0.917707 0.008727 +0.566613 -0.823938 0.008727 +0.566613 -0.823938 0.008727 +0.397162 -0.917707 0.008727 +0.566613 -0.823938 0.008727 +0.707080 -0.707080 0.008727 +0.566613 -0.823938 0.008727 +0.707080 -0.707080 0.008727 +0.707080 -0.707080 0.008727 +0.566613 -0.823938 0.008727 +0.823938 -0.566613 0.008727 +0.707080 -0.707080 0.008727 +0.707080 -0.707080 0.008727 +0.823938 -0.566613 0.008727 +0.823938 -0.566613 0.008727 +0.707080 -0.707080 0.008727 +0.917707 -0.397162 0.008727 +0.823938 -0.566613 0.008727 +0.823938 -0.566613 0.008727 +0.917707 -0.397162 0.008727 +0.917707 -0.397162 0.008727 +0.823938 -0.566613 0.008727 +0.917707 -0.397162 0.008727 +0.978744 -0.204902 0.008727 +0.917707 -0.397162 0.008727 +0.978744 -0.204902 0.008727 +0.978744 -0.204902 0.008727 +0.917707 -0.397162 0.008727 +0.999962 0.000000 0.008727 +0.978744 -0.204902 0.008727 +0.978744 -0.204902 0.008727 +0.999159 -0.040076 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999159 -0.040076 0.008727 +0.978744 -0.204902 0.008727 +0.999962 0.000000 0.008727 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -0.806043 -0.591858 +0.000000 -0.676838 -0.736132 +0.000000 -0.676838 -0.736132 +0.000000 -0.182489 -0.983208 +0.000000 -0.048809 -0.998808 +0.000000 -0.048809 -0.998808 +0.000000 -0.182489 -0.983208 +0.000000 -0.182489 -0.983208 +0.000000 -0.048809 -0.998808 +0.000000 -0.368592 -0.929591 +0.000000 -0.182489 -0.983208 +0.000000 -0.182489 -0.983208 +0.000000 -0.368592 -0.929591 +0.000000 -0.368592 -0.929591 +0.000000 -0.182489 -0.983208 +0.000000 -0.531589 -0.847002 +0.000000 -0.368592 -0.929591 +0.000000 -0.368592 -0.929591 +0.000000 -0.531589 -0.847002 +0.000000 -0.531589 -0.847002 +0.000000 -0.368592 -0.929591 +0.000000 -0.531589 -0.847002 +0.000000 -0.676838 -0.736132 +0.000000 -0.531589 -0.847002 +0.000000 -0.676838 -0.736132 +0.000000 -0.676838 -0.736132 +0.000000 -0.531589 -0.847002 +0.000000 -0.878218 -0.478261 +0.000000 -0.806043 -0.591858 +0.000000 -0.878218 -0.478261 +0.000000 -0.806043 -0.591858 +0.000000 -0.806043 -0.591858 +0.000000 -0.878218 -0.478261 +0.000000 -0.676838 -0.736132 +0.000000 -0.806043 -0.591858 +0.000000 -0.806043 -0.591858 +-0.037893 0.030764 -0.998808 +-0.129039 0.129039 -0.983208 +-0.034513 0.034513 -0.998808 +-0.103404 0.150365 -0.983208 +-0.034513 0.034513 -0.998808 +-0.129039 0.129039 -0.983208 +-0.103404 0.150365 -0.983208 +-0.030764 0.037893 -0.998808 +-0.034513 0.034513 -0.998808 +-0.103404 0.150365 -0.983208 +-0.026709 0.040853 -0.998808 +-0.030764 0.037893 -0.998808 +-0.072480 0.167477 -0.983208 +-0.026709 0.040853 -0.998808 +-0.103404 0.150365 -0.983208 +-0.072480 0.167477 -0.983208 +-0.017966 0.045382 -0.998808 +-0.026709 0.040853 -0.998808 +-0.037394 0.178616 -0.983208 +-0.017966 0.045382 -0.998808 +-0.072480 0.167477 -0.983208 +-0.037394 0.178616 -0.983208 +-0.008882 0.047995 -0.998808 +-0.017966 0.045382 -0.998808 +-0.008882 0.047995 -0.998808 +0.000000 0.182489 -0.983208 +0.000000 0.048809 -0.998808 +-0.037394 0.178616 -0.983208 +0.000000 0.182489 -0.983208 +-0.008882 0.047995 -0.998808 +-0.075528 0.360770 -0.929591 +0.000000 0.182489 -0.983208 +-0.037394 0.178616 -0.983208 +-0.075528 0.360770 -0.929591 +0.000000 0.368592 -0.929591 +0.000000 0.182489 -0.983208 +-0.108928 0.520310 -0.847002 +0.000000 0.368592 -0.929591 +-0.075528 0.360770 -0.929591 +-0.108928 0.520310 -0.847002 +0.000000 0.531589 -0.847002 +0.000000 0.368592 -0.929591 +-0.138690 0.662476 -0.736132 +0.000000 0.531589 -0.847002 +-0.108928 0.520310 -0.847002 +-0.138690 0.662476 -0.736132 +0.000000 0.676838 -0.736132 +0.000000 0.531589 -0.847002 +-0.165166 0.788939 -0.591858 +0.000000 0.676838 -0.736132 +-0.138690 0.662476 -0.736132 +-0.165166 0.788939 -0.591858 +0.000000 0.806043 -0.591858 +0.000000 0.676838 -0.736132 +-0.165166 0.788939 -0.591858 +0.000000 0.878218 -0.478261 +0.000000 0.806043 -0.591858 +-0.165166 0.788939 -0.591858 +-0.159803 0.863556 -0.478261 +0.000000 0.878218 -0.478261 +-0.165166 0.788939 -0.591858 +-0.323267 0.816557 -0.478261 +-0.159803 0.863556 -0.478261 +-0.320142 0.739739 -0.591858 +-0.323267 0.816557 -0.478261 +-0.165166 0.788939 -0.591858 +-0.320142 0.739739 -0.591858 +-0.480569 0.735064 -0.478261 +-0.323267 0.816557 -0.478261 +-0.456732 0.664154 -0.591858 +-0.480569 0.735064 -0.478261 +-0.320142 0.739739 -0.591858 +-0.456732 0.664154 -0.591858 +-0.553539 0.681807 -0.478261 +-0.480569 0.735064 -0.478261 +-0.569958 0.569958 -0.591858 +-0.553539 0.681807 -0.478261 +-0.456732 0.664154 -0.591858 +-0.569958 0.569958 -0.591858 +-0.620994 0.620994 -0.478261 +-0.553539 0.681807 -0.478261 +-0.664154 0.456732 -0.591858 +-0.620994 0.620994 -0.478261 +-0.569958 0.569958 -0.591858 +-0.664154 0.456732 -0.591858 +-0.681807 0.553539 -0.478261 +-0.620994 0.620994 -0.478261 +-0.664154 0.456732 -0.591858 +-0.735064 0.480569 -0.478261 +-0.681807 0.553539 -0.478261 +-0.739739 0.320142 -0.591858 +-0.735064 0.480569 -0.478261 +-0.664154 0.456732 -0.591858 +-0.739739 0.320142 -0.591858 +-0.816557 0.323267 -0.478261 +-0.735064 0.480569 -0.478261 +-0.788939 0.165166 -0.591858 +-0.816557 0.323267 -0.478261 +-0.739739 0.320142 -0.591858 +-0.788939 0.165166 -0.591858 +-0.863556 0.159803 -0.478261 +-0.816557 0.323267 -0.478261 +-0.863556 0.159803 -0.478261 +-0.806043 0.000000 -0.591858 +-0.878218 0.000000 -0.478261 +-0.788939 0.165166 -0.591858 +-0.806043 0.000000 -0.591858 +-0.863556 0.159803 -0.478261 +-0.662476 0.138690 -0.736132 +-0.806043 0.000000 -0.591858 +-0.788939 0.165166 -0.591858 +-0.662476 0.138690 -0.736132 +-0.676838 0.000000 -0.736132 +-0.806043 0.000000 -0.591858 +-0.520310 0.108928 -0.847002 +-0.676838 0.000000 -0.736132 +-0.662476 0.138690 -0.736132 +-0.520310 0.108928 -0.847002 +-0.531589 0.000000 -0.847002 +-0.676838 0.000000 -0.736132 +-0.360770 0.075528 -0.929591 +-0.531589 0.000000 -0.847002 +-0.520310 0.108928 -0.847002 +-0.360770 0.075528 -0.929591 +-0.368592 0.000000 -0.929591 +-0.531589 0.000000 -0.847002 +-0.360770 0.075528 -0.929591 +-0.182489 0.000000 -0.983208 +-0.368592 0.000000 -0.929591 +-0.178616 0.037394 -0.983208 +-0.182489 0.000000 -0.983208 +-0.360770 0.075528 -0.929591 +-0.178616 0.037394 -0.983208 +-0.048809 0.000000 -0.998808 +-0.182489 0.000000 -0.983208 +-0.178616 0.037394 -0.983208 +-0.047995 0.008882 -0.998808 +-0.048809 0.000000 -0.998808 +-0.178616 0.037394 -0.983208 +-0.045382 0.017966 -0.998808 +-0.047995 0.008882 -0.998808 +-0.167477 0.072480 -0.983208 +-0.045382 0.017966 -0.998808 +-0.178616 0.037394 -0.983208 +-0.167477 0.072480 -0.983208 +-0.040853 0.026709 -0.998808 +-0.045382 0.017966 -0.998808 +-0.150365 0.103404 -0.983208 +-0.040853 0.026709 -0.998808 +-0.167477 0.072480 -0.983208 +-0.150365 0.103404 -0.983208 +-0.037893 0.030764 -0.998808 +-0.040853 0.026709 -0.998808 +-0.129039 0.129039 -0.983208 +-0.037893 0.030764 -0.998808 +-0.150365 0.103404 -0.983208 +-0.165166 0.788939 -0.591858 +-0.268825 0.621162 -0.736132 +-0.320142 0.739739 -0.591858 +-0.268825 0.621162 -0.736132 +-0.165166 0.788939 -0.591858 +-0.138690 0.662476 -0.736132 +-0.138690 0.662476 -0.736132 +-0.211135 0.487862 -0.847002 +-0.268825 0.621162 -0.736132 +-0.211135 0.487862 -0.847002 +-0.138690 0.662476 -0.736132 +-0.108928 0.520310 -0.847002 +-0.108928 0.520310 -0.847002 +-0.146396 0.338272 -0.929591 +-0.211135 0.487862 -0.847002 +-0.146396 0.338272 -0.929591 +-0.108928 0.520310 -0.847002 +-0.075528 0.360770 -0.929591 +-0.075528 0.360770 -0.929591 +-0.072480 0.167477 -0.983208 +-0.146396 0.338272 -0.929591 +-0.072480 0.167477 -0.983208 +-0.075528 0.360770 -0.929591 +-0.037394 0.178616 -0.983208 +-0.320142 0.739739 -0.591858 +-0.383520 0.557693 -0.736132 +-0.456732 0.664154 -0.591858 +-0.383520 0.557693 -0.736132 +-0.320142 0.739739 -0.591858 +-0.268825 0.621162 -0.736132 +-0.268825 0.621162 -0.736132 +-0.301217 0.438013 -0.847002 +-0.383520 0.557693 -0.736132 +-0.301217 0.438013 -0.847002 +-0.268825 0.621162 -0.736132 +-0.211135 0.487862 -0.847002 +-0.456732 0.664154 -0.591858 +-0.478597 0.478597 -0.736132 +-0.569958 0.569958 -0.591858 +-0.478597 0.478597 -0.736132 +-0.456732 0.664154 -0.591858 +-0.383520 0.557693 -0.736132 +-0.383520 0.557693 -0.736132 +-0.375890 0.375890 -0.847002 +-0.478597 0.478597 -0.736132 +-0.375890 0.375890 -0.847002 +-0.383520 0.557693 -0.736132 +-0.301217 0.438013 -0.847002 +-0.211135 0.487862 -0.847002 +-0.208857 0.303708 -0.929591 +-0.301217 0.438013 -0.847002 +-0.208857 0.303708 -0.929591 +-0.211135 0.487862 -0.847002 +-0.146396 0.338272 -0.929591 +-0.146396 0.338272 -0.929591 +-0.103404 0.150365 -0.983208 +-0.208857 0.303708 -0.929591 +-0.103404 0.150365 -0.983208 +-0.146396 0.338272 -0.929591 +-0.072480 0.167477 -0.983208 +-0.301217 0.438013 -0.847002 +-0.260634 0.260634 -0.929591 +-0.375890 0.375890 -0.847002 +-0.260634 0.260634 -0.929591 +-0.301217 0.438013 -0.847002 +-0.208857 0.303708 -0.929591 +-0.208857 0.303708 -0.929591 +-0.129039 0.129039 -0.983208 +-0.260634 0.260634 -0.929591 +-0.129039 0.129039 -0.983208 +-0.208857 0.303708 -0.929591 +-0.103404 0.150365 -0.983208 +-0.569958 0.569958 -0.591858 +-0.557693 0.383520 -0.736132 +-0.664154 0.456732 -0.591858 +-0.557693 0.383520 -0.736132 +-0.569958 0.569958 -0.591858 +-0.478597 0.478597 -0.736132 +-0.478597 0.478597 -0.736132 +-0.438013 0.301217 -0.847002 +-0.557693 0.383520 -0.736132 +-0.438013 0.301217 -0.847002 +-0.478597 0.478597 -0.736132 +-0.375890 0.375890 -0.847002 +-0.664154 0.456732 -0.591858 +-0.621162 0.268825 -0.736132 +-0.739739 0.320142 -0.591858 +-0.621162 0.268825 -0.736132 +-0.664154 0.456732 -0.591858 +-0.557693 0.383520 -0.736132 +-0.557693 0.383520 -0.736132 +-0.487862 0.211135 -0.847002 +-0.621162 0.268825 -0.736132 +-0.487862 0.211135 -0.847002 +-0.557693 0.383520 -0.736132 +-0.438013 0.301217 -0.847002 +-0.375890 0.375890 -0.847002 +-0.303708 0.208857 -0.929591 +-0.438013 0.301217 -0.847002 +-0.303708 0.208857 -0.929591 +-0.375890 0.375890 -0.847002 +-0.260634 0.260634 -0.929591 +-0.260634 0.260634 -0.929591 +-0.150365 0.103404 -0.983208 +-0.303708 0.208857 -0.929591 +-0.150365 0.103404 -0.983208 +-0.260634 0.260634 -0.929591 +-0.129039 0.129039 -0.983208 +-0.438013 0.301217 -0.847002 +-0.338272 0.146396 -0.929591 +-0.487862 0.211135 -0.847002 +-0.338272 0.146396 -0.929591 +-0.438013 0.301217 -0.847002 +-0.303708 0.208857 -0.929591 +-0.303708 0.208857 -0.929591 +-0.167477 0.072480 -0.983208 +-0.338272 0.146396 -0.929591 +-0.167477 0.072480 -0.983208 +-0.303708 0.208857 -0.929591 +-0.150365 0.103404 -0.983208 +-0.739739 0.320142 -0.591858 +-0.662476 0.138690 -0.736132 +-0.788939 0.165166 -0.591858 +-0.662476 0.138690 -0.736132 +-0.739739 0.320142 -0.591858 +-0.621162 0.268825 -0.736132 +-0.621162 0.268825 -0.736132 +-0.520310 0.108928 -0.847002 +-0.662476 0.138690 -0.736132 +-0.520310 0.108928 -0.847002 +-0.621162 0.268825 -0.736132 +-0.487862 0.211135 -0.847002 +-0.487862 0.211135 -0.847002 +-0.360770 0.075528 -0.929591 +-0.520310 0.108928 -0.847002 +-0.360770 0.075528 -0.929591 +-0.487862 0.211135 -0.847002 +-0.338272 0.146396 -0.929591 +-0.338272 0.146396 -0.929591 +-0.178616 0.037394 -0.983208 +-0.360770 0.075528 -0.929591 +-0.178616 0.037394 -0.983208 +-0.338272 0.146396 -0.929591 +-0.167477 0.072480 -0.983208 +0.569958 -0.569958 -0.591858 +0.480569 -0.735064 -0.478261 +0.441074 -0.674654 -0.591858 +0.296700 -0.749449 -0.591858 +0.159803 -0.863556 -0.478261 +0.146670 -0.792586 -0.591858 +0.296700 -0.749449 -0.591858 +0.323267 -0.816557 -0.478261 +0.159803 -0.863556 -0.478261 +0.441074 -0.674654 -0.591858 +0.323267 -0.816557 -0.478261 +0.296700 -0.749449 -0.591858 +0.441074 -0.674654 -0.591858 +0.480569 -0.735064 -0.478261 +0.323267 -0.816557 -0.478261 +0.000000 0.182489 -0.983208 +0.008882 0.047995 -0.998808 +0.000000 0.048809 -0.998808 +0.000000 -0.806043 -0.591858 +0.159803 -0.863556 -0.478261 +0.000000 -0.878218 -0.478261 +0.000000 -0.806043 -0.591858 +0.146670 -0.792586 -0.591858 +0.159803 -0.863556 -0.478261 +0.000000 -0.806043 -0.591858 +0.123159 -0.665538 -0.736132 +0.146670 -0.792586 -0.591858 +0.000000 -0.676838 -0.736132 +0.123159 -0.665538 -0.736132 +0.000000 -0.806043 -0.591858 +0.000000 -0.531589 -0.847002 +0.123159 -0.665538 -0.736132 +0.000000 -0.676838 -0.736132 +0.000000 -0.531589 -0.847002 +0.096730 -0.522715 -0.847002 +0.123159 -0.665538 -0.736132 +0.000000 -0.368592 -0.929591 +0.096730 -0.522715 -0.847002 +0.000000 -0.531589 -0.847002 +0.000000 -0.368592 -0.929591 +0.067070 -0.362438 -0.929591 +0.096730 -0.522715 -0.847002 +0.000000 -0.182489 -0.983208 +0.067070 -0.362438 -0.929591 +0.000000 -0.368592 -0.929591 +0.000000 -0.182489 -0.983208 +0.033206 -0.179442 -0.983208 +0.067070 -0.362438 -0.929591 +0.000000 -0.048809 -0.998808 +0.033206 -0.179442 -0.983208 +0.000000 -0.182489 -0.983208 +0.008882 -0.047995 -0.998808 +0.033206 -0.179442 -0.983208 +0.000000 -0.048809 -0.998808 +0.008882 -0.047995 -0.998808 +0.067173 -0.169676 -0.983208 +0.033206 -0.179442 -0.983208 +0.017966 -0.045382 -0.998808 +0.067173 -0.169676 -0.983208 +0.008882 -0.047995 -0.998808 +0.017966 -0.045382 -0.998808 +0.099859 -0.152742 -0.983208 +0.067173 -0.169676 -0.983208 +0.026709 -0.040853 -0.998808 +0.099859 -0.152742 -0.983208 +0.017966 -0.045382 -0.998808 +0.026709 -0.040853 -0.998808 +0.129039 -0.129039 -0.983208 +0.099859 -0.152742 -0.983208 +0.034513 -0.034513 -0.998808 +0.129039 -0.129039 -0.983208 +0.026709 -0.040853 -0.998808 +0.034513 -0.034513 -0.998808 +0.152742 -0.099859 -0.983208 +0.129039 -0.129039 -0.983208 +0.040853 -0.026709 -0.998808 +0.152742 -0.099859 -0.983208 +0.034513 -0.034513 -0.998808 +0.040853 -0.026709 -0.998808 +0.169676 -0.067173 -0.983208 +0.152742 -0.099859 -0.983208 +0.045382 -0.017966 -0.998808 +0.169676 -0.067173 -0.983208 +0.040853 -0.026709 -0.998808 +0.045382 -0.017966 -0.998808 +0.179442 -0.033206 -0.983208 +0.169676 -0.067173 -0.983208 +0.047995 -0.008882 -0.998808 +0.179442 -0.033206 -0.983208 +0.045382 -0.017966 -0.998808 +0.047995 -0.008882 -0.998808 +0.182489 0.000000 -0.983208 +0.179442 -0.033206 -0.983208 +0.048809 0.000000 -0.998808 +0.182489 0.000000 -0.983208 +0.047995 -0.008882 -0.998808 +0.048809 0.000000 -0.998808 +0.179442 0.033206 -0.983208 +0.182489 0.000000 -0.983208 +0.047995 0.008882 -0.998808 +0.179442 0.033206 -0.983208 +0.048809 0.000000 -0.998808 +0.047995 0.008882 -0.998808 +0.169676 0.067173 -0.983208 +0.179442 0.033206 -0.983208 +0.045382 0.017966 -0.998808 +0.169676 0.067173 -0.983208 +0.047995 0.008882 -0.998808 +0.045382 0.017966 -0.998808 +0.152742 0.099859 -0.983208 +0.169676 0.067173 -0.983208 +0.040853 0.026709 -0.998808 +0.152742 0.099859 -0.983208 +0.045382 0.017966 -0.998808 +0.040853 0.026709 -0.998808 +0.129039 0.129039 -0.983208 +0.152742 0.099859 -0.983208 +0.034513 0.034513 -0.998808 +0.129039 0.129039 -0.983208 +0.040853 0.026709 -0.998808 +0.034513 0.034513 -0.998808 +0.099859 0.152742 -0.983208 +0.129039 0.129039 -0.983208 +0.026709 0.040853 -0.998808 +0.099859 0.152742 -0.983208 +0.034513 0.034513 -0.998808 +0.026709 0.040853 -0.998808 +0.067173 0.169676 -0.983208 +0.099859 0.152742 -0.983208 +0.017966 0.045382 -0.998808 +0.067173 0.169676 -0.983208 +0.026709 0.040853 -0.998808 +0.017966 0.045382 -0.998808 +0.033206 0.179442 -0.983208 +0.067173 0.169676 -0.983208 +0.008882 0.047995 -0.998808 +0.033206 0.179442 -0.983208 +0.017966 0.045382 -0.998808 +0.000000 0.182489 -0.983208 +0.033206 0.179442 -0.983208 +0.008882 0.047995 -0.998808 +0.000000 0.368592 -0.929591 +0.033206 0.179442 -0.983208 +0.000000 0.182489 -0.983208 +0.000000 0.368592 -0.929591 +0.067070 0.362438 -0.929591 +0.033206 0.179442 -0.983208 +0.000000 0.531589 -0.847002 +0.067070 0.362438 -0.929591 +0.000000 0.368592 -0.929591 +0.000000 0.531589 -0.847002 +0.096730 0.522715 -0.847002 +0.067070 0.362438 -0.929591 +0.000000 0.531589 -0.847002 +0.123159 0.665538 -0.736132 +0.096730 0.522715 -0.847002 +0.000000 0.676838 -0.736132 +0.123159 0.665538 -0.736132 +0.000000 0.531589 -0.847002 +0.000000 0.806043 -0.591858 +0.123159 0.665538 -0.736132 +0.000000 0.676838 -0.736132 +0.000000 0.806043 -0.591858 +0.146670 0.792586 -0.591858 +0.123159 0.665538 -0.736132 +0.000000 0.878218 -0.478261 +0.146670 0.792586 -0.591858 +0.000000 0.806043 -0.591858 +0.159803 0.863556 -0.478261 +0.146670 0.792586 -0.591858 +0.000000 0.878218 -0.478261 +0.323267 0.816557 -0.478261 +0.146670 0.792586 -0.591858 +0.159803 0.863556 -0.478261 +0.323267 0.816557 -0.478261 +0.296700 0.749449 -0.591858 +0.146670 0.792586 -0.591858 +0.480569 0.735064 -0.478261 +0.296700 0.749449 -0.591858 +0.323267 0.816557 -0.478261 +0.480569 0.735064 -0.478261 +0.441074 0.674654 -0.591858 +0.296700 0.749449 -0.591858 +0.480569 0.735064 -0.478261 +0.569958 0.569958 -0.591858 +0.441074 0.674654 -0.591858 +0.620994 0.620994 -0.478261 +0.569958 0.569958 -0.591858 +0.480569 0.735064 -0.478261 +0.620994 0.620994 -0.478261 +0.674654 0.441074 -0.591858 +0.569958 0.569958 -0.591858 +0.735064 0.480569 -0.478261 +0.674654 0.441074 -0.591858 +0.620994 0.620994 -0.478261 +0.816557 0.323267 -0.478261 +0.674654 0.441074 -0.591858 +0.735064 0.480569 -0.478261 +0.816557 0.323267 -0.478261 +0.749449 0.296700 -0.591858 +0.674654 0.441074 -0.591858 +0.863556 0.159803 -0.478261 +0.749449 0.296700 -0.591858 +0.816557 0.323267 -0.478261 +0.863556 0.159803 -0.478261 +0.792586 0.146670 -0.591858 +0.749449 0.296700 -0.591858 +0.878218 0.000000 -0.478261 +0.792586 0.146670 -0.591858 +0.863556 0.159803 -0.478261 +0.878218 0.000000 -0.478261 +0.806043 0.000000 -0.591858 +0.792586 0.146670 -0.591858 +0.863556 -0.159803 -0.478261 +0.806043 0.000000 -0.591858 +0.878218 0.000000 -0.478261 +0.863556 -0.159803 -0.478261 +0.792586 -0.146670 -0.591858 +0.806043 0.000000 -0.591858 +0.816557 -0.323267 -0.478261 +0.792586 -0.146670 -0.591858 +0.863556 -0.159803 -0.478261 +0.816557 -0.323267 -0.478261 +0.749449 -0.296700 -0.591858 +0.792586 -0.146670 -0.591858 +0.735064 -0.480569 -0.478261 +0.749449 -0.296700 -0.591858 +0.816557 -0.323267 -0.478261 +0.735064 -0.480569 -0.478261 +0.674654 -0.441074 -0.591858 +0.749449 -0.296700 -0.591858 +0.620994 -0.620994 -0.478261 +0.674654 -0.441074 -0.591858 +0.735064 -0.480569 -0.478261 +0.620994 -0.620994 -0.478261 +0.569958 -0.569958 -0.591858 +0.674654 -0.441074 -0.591858 +0.480569 -0.735064 -0.478261 +0.569958 -0.569958 -0.591858 +0.620994 -0.620994 -0.478261 +0.146670 -0.792586 -0.591858 +0.249140 -0.629316 -0.736132 +0.296700 -0.749449 -0.591858 +0.249140 -0.629316 -0.736132 +0.146670 -0.792586 -0.591858 +0.123159 -0.665538 -0.736132 +0.123159 -0.665538 -0.736132 +0.195675 -0.494266 -0.847002 +0.249140 -0.629316 -0.736132 +0.195675 -0.494266 -0.847002 +0.123159 -0.665538 -0.736132 +0.096730 -0.522715 -0.847002 +0.096730 -0.522715 -0.847002 +0.135677 -0.342712 -0.929591 +0.195675 -0.494266 -0.847002 +0.135677 -0.342712 -0.929591 +0.096730 -0.522715 -0.847002 +0.067070 -0.362438 -0.929591 +0.067070 -0.362438 -0.929591 +0.067173 -0.169676 -0.983208 +0.135677 -0.342712 -0.929591 +0.067173 -0.169676 -0.983208 +0.067070 -0.362438 -0.929591 +0.033206 -0.179442 -0.983208 +0.296700 -0.749449 -0.591858 +0.370372 -0.566510 -0.736132 +0.441074 -0.674654 -0.591858 +0.370372 -0.566510 -0.736132 +0.296700 -0.749449 -0.591858 +0.249140 -0.629316 -0.736132 +0.249140 -0.629316 -0.736132 +0.290891 -0.444938 -0.847002 +0.370372 -0.566510 -0.736132 +0.290891 -0.444938 -0.847002 +0.249140 -0.629316 -0.736132 +0.195675 -0.494266 -0.847002 +0.441074 -0.674654 -0.591858 +0.478597 -0.478597 -0.736132 +0.569958 -0.569958 -0.591858 +0.478597 -0.478597 -0.736132 +0.441074 -0.674654 -0.591858 +0.370372 -0.566510 -0.736132 +0.370372 -0.566510 -0.736132 +0.375890 -0.375890 -0.847002 +0.478597 -0.478597 -0.736132 +0.375890 -0.375890 -0.847002 +0.370372 -0.566510 -0.736132 +0.290891 -0.444938 -0.847002 +0.195675 -0.494266 -0.847002 +0.201697 -0.308509 -0.929591 +0.290891 -0.444938 -0.847002 +0.201697 -0.308509 -0.929591 +0.195675 -0.494266 -0.847002 +0.135677 -0.342712 -0.929591 +0.135677 -0.342712 -0.929591 +0.099859 -0.152742 -0.983208 +0.201697 -0.308509 -0.929591 +0.099859 -0.152742 -0.983208 +0.135677 -0.342712 -0.929591 +0.067173 -0.169676 -0.983208 +0.290891 -0.444938 -0.847002 +0.260634 -0.260634 -0.929591 +0.375890 -0.375890 -0.847002 +0.260634 -0.260634 -0.929591 +0.290891 -0.444938 -0.847002 +0.201697 -0.308509 -0.929591 +0.201697 -0.308509 -0.929591 +0.129039 -0.129039 -0.983208 +0.260634 -0.260634 -0.929591 +0.129039 -0.129039 -0.983208 +0.201697 -0.308509 -0.929591 +0.099859 -0.152742 -0.983208 +0.569958 -0.569958 -0.591858 +0.566510 -0.370372 -0.736132 +0.674654 -0.441074 -0.591858 +0.566510 -0.370372 -0.736132 +0.569958 -0.569958 -0.591858 +0.478597 -0.478597 -0.736132 +0.478597 -0.478597 -0.736132 +0.444938 -0.290891 -0.847002 +0.566510 -0.370372 -0.736132 +0.444938 -0.290891 -0.847002 +0.478597 -0.478597 -0.736132 +0.375890 -0.375890 -0.847002 +0.674654 -0.441074 -0.591858 +0.629316 -0.249140 -0.736132 +0.749449 -0.296700 -0.591858 +0.629316 -0.249140 -0.736132 +0.674654 -0.441074 -0.591858 +0.566510 -0.370372 -0.736132 +0.566510 -0.370372 -0.736132 +0.494266 -0.195675 -0.847002 +0.629316 -0.249140 -0.736132 +0.494266 -0.195675 -0.847002 +0.566510 -0.370372 -0.736132 +0.444938 -0.290891 -0.847002 +0.375890 -0.375890 -0.847002 +0.308509 -0.201697 -0.929591 +0.444938 -0.290891 -0.847002 +0.308509 -0.201697 -0.929591 +0.375890 -0.375890 -0.847002 +0.260634 -0.260634 -0.929591 +0.260634 -0.260634 -0.929591 +0.152742 -0.099859 -0.983208 +0.308509 -0.201697 -0.929591 +0.152742 -0.099859 -0.983208 +0.260634 -0.260634 -0.929591 +0.129039 -0.129039 -0.983208 +0.444938 -0.290891 -0.847002 +0.342712 -0.135677 -0.929591 +0.494266 -0.195675 -0.847002 +0.342712 -0.135677 -0.929591 +0.444938 -0.290891 -0.847002 +0.308509 -0.201697 -0.929591 +0.308509 -0.201697 -0.929591 +0.169676 -0.067173 -0.983208 +0.342712 -0.135677 -0.929591 +0.169676 -0.067173 -0.983208 +0.308509 -0.201697 -0.929591 +0.152742 -0.099859 -0.983208 +0.749449 -0.296700 -0.591858 +0.665538 -0.123159 -0.736132 +0.792586 -0.146670 -0.591858 +0.665538 -0.123159 -0.736132 +0.749449 -0.296700 -0.591858 +0.629316 -0.249140 -0.736132 +0.629316 -0.249140 -0.736132 +0.522715 -0.096730 -0.847002 +0.665538 -0.123159 -0.736132 +0.522715 -0.096730 -0.847002 +0.629316 -0.249140 -0.736132 +0.494266 -0.195675 -0.847002 +0.792586 -0.146670 -0.591858 +0.676838 0.000000 -0.736132 +0.806043 0.000000 -0.591858 +0.676838 0.000000 -0.736132 +0.792586 -0.146670 -0.591858 +0.665538 -0.123159 -0.736132 +0.665538 -0.123159 -0.736132 +0.531589 0.000000 -0.847002 +0.676838 0.000000 -0.736132 +0.531589 0.000000 -0.847002 +0.665538 -0.123159 -0.736132 +0.522715 -0.096730 -0.847002 +0.494266 -0.195675 -0.847002 +0.362438 -0.067070 -0.929591 +0.522715 -0.096730 -0.847002 +0.362438 -0.067070 -0.929591 +0.494266 -0.195675 -0.847002 +0.342712 -0.135677 -0.929591 +0.342712 -0.135677 -0.929591 +0.179442 -0.033206 -0.983208 +0.362438 -0.067070 -0.929591 +0.179442 -0.033206 -0.983208 +0.342712 -0.135677 -0.929591 +0.169676 -0.067173 -0.983208 +0.522715 -0.096730 -0.847002 +0.368592 0.000000 -0.929591 +0.531589 0.000000 -0.847002 +0.368592 0.000000 -0.929591 +0.522715 -0.096730 -0.847002 +0.362438 -0.067070 -0.929591 +0.362438 -0.067070 -0.929591 +0.182489 0.000000 -0.983208 +0.368592 0.000000 -0.929591 +0.182489 0.000000 -0.983208 +0.362438 -0.067070 -0.929591 +0.179442 -0.033206 -0.983208 +0.806043 0.000000 -0.591858 +0.665538 0.123159 -0.736132 +0.792586 0.146670 -0.591858 +0.665538 0.123159 -0.736132 +0.806043 0.000000 -0.591858 +0.676838 0.000000 -0.736132 +0.676838 0.000000 -0.736132 +0.522715 0.096730 -0.847002 +0.665538 0.123159 -0.736132 +0.522715 0.096730 -0.847002 +0.676838 0.000000 -0.736132 +0.531589 0.000000 -0.847002 +0.792586 0.146670 -0.591858 +0.629316 0.249140 -0.736132 +0.749449 0.296700 -0.591858 +0.629316 0.249140 -0.736132 +0.792586 0.146670 -0.591858 +0.665538 0.123159 -0.736132 +0.665538 0.123159 -0.736132 +0.494266 0.195675 -0.847002 +0.629316 0.249140 -0.736132 +0.494266 0.195675 -0.847002 +0.665538 0.123159 -0.736132 +0.522715 0.096730 -0.847002 +0.531589 0.000000 -0.847002 +0.362438 0.067070 -0.929591 +0.522715 0.096730 -0.847002 +0.362438 0.067070 -0.929591 +0.531589 0.000000 -0.847002 +0.368592 0.000000 -0.929591 +0.368592 0.000000 -0.929591 +0.179442 0.033206 -0.983208 +0.362438 0.067070 -0.929591 +0.179442 0.033206 -0.983208 +0.368592 0.000000 -0.929591 +0.182489 0.000000 -0.983208 +0.522715 0.096730 -0.847002 +0.342712 0.135677 -0.929591 +0.494266 0.195675 -0.847002 +0.342712 0.135677 -0.929591 +0.522715 0.096730 -0.847002 +0.362438 0.067070 -0.929591 +0.362438 0.067070 -0.929591 +0.169676 0.067173 -0.983208 +0.342712 0.135677 -0.929591 +0.169676 0.067173 -0.983208 +0.362438 0.067070 -0.929591 +0.179442 0.033206 -0.983208 +0.749449 0.296700 -0.591858 +0.566510 0.370372 -0.736132 +0.674654 0.441074 -0.591858 +0.566510 0.370372 -0.736132 +0.749449 0.296700 -0.591858 +0.629316 0.249140 -0.736132 +0.629316 0.249140 -0.736132 +0.444938 0.290891 -0.847002 +0.566510 0.370372 -0.736132 +0.444938 0.290891 -0.847002 +0.629316 0.249140 -0.736132 +0.494266 0.195675 -0.847002 +0.674654 0.441074 -0.591858 +0.478597 0.478597 -0.736132 +0.569958 0.569958 -0.591858 +0.478597 0.478597 -0.736132 +0.674654 0.441074 -0.591858 +0.566510 0.370372 -0.736132 +0.566510 0.370372 -0.736132 +0.375890 0.375890 -0.847002 +0.478597 0.478597 -0.736132 +0.375890 0.375890 -0.847002 +0.566510 0.370372 -0.736132 +0.444938 0.290891 -0.847002 +0.494266 0.195675 -0.847002 +0.308509 0.201697 -0.929591 +0.444938 0.290891 -0.847002 +0.308509 0.201697 -0.929591 +0.494266 0.195675 -0.847002 +0.342712 0.135677 -0.929591 +0.342712 0.135677 -0.929591 +0.152742 0.099859 -0.983208 +0.308509 0.201697 -0.929591 +0.152742 0.099859 -0.983208 +0.342712 0.135677 -0.929591 +0.169676 0.067173 -0.983208 +0.444938 0.290891 -0.847002 +0.260634 0.260634 -0.929591 +0.375890 0.375890 -0.847002 +0.260634 0.260634 -0.929591 +0.444938 0.290891 -0.847002 +0.308509 0.201697 -0.929591 +0.308509 0.201697 -0.929591 +0.129039 0.129039 -0.983208 +0.260634 0.260634 -0.929591 +0.129039 0.129039 -0.983208 +0.308509 0.201697 -0.929591 +0.152742 0.099859 -0.983208 +0.569958 0.569958 -0.591858 +0.370372 0.566510 -0.736132 +0.441074 0.674654 -0.591858 +0.370372 0.566510 -0.736132 +0.569958 0.569958 -0.591858 +0.478597 0.478597 -0.736132 +0.478597 0.478597 -0.736132 +0.290891 0.444938 -0.847002 +0.370372 0.566510 -0.736132 +0.290891 0.444938 -0.847002 +0.478597 0.478597 -0.736132 +0.375890 0.375890 -0.847002 +0.441074 0.674654 -0.591858 +0.249140 0.629316 -0.736132 +0.296700 0.749449 -0.591858 +0.249140 0.629316 -0.736132 +0.441074 0.674654 -0.591858 +0.370372 0.566510 -0.736132 +0.370372 0.566510 -0.736132 +0.195675 0.494266 -0.847002 +0.249140 0.629316 -0.736132 +0.195675 0.494266 -0.847002 +0.370372 0.566510 -0.736132 +0.290891 0.444938 -0.847002 +0.375890 0.375890 -0.847002 +0.201697 0.308509 -0.929591 +0.290891 0.444938 -0.847002 +0.201697 0.308509 -0.929591 +0.375890 0.375890 -0.847002 +0.260634 0.260634 -0.929591 +0.260634 0.260634 -0.929591 +0.099859 0.152742 -0.983208 +0.201697 0.308509 -0.929591 +0.099859 0.152742 -0.983208 +0.260634 0.260634 -0.929591 +0.129039 0.129039 -0.983208 +0.290891 0.444938 -0.847002 +0.135677 0.342712 -0.929591 +0.195675 0.494266 -0.847002 +0.135677 0.342712 -0.929591 +0.290891 0.444938 -0.847002 +0.201697 0.308509 -0.929591 +0.201697 0.308509 -0.929591 +0.067173 0.169676 -0.983208 +0.135677 0.342712 -0.929591 +0.067173 0.169676 -0.983208 +0.201697 0.308509 -0.929591 +0.099859 0.152742 -0.983208 +0.296700 0.749449 -0.591858 +0.123159 0.665538 -0.736132 +0.146670 0.792586 -0.591858 +0.123159 0.665538 -0.736132 +0.296700 0.749449 -0.591858 +0.249140 0.629316 -0.736132 +0.249140 0.629316 -0.736132 +0.096730 0.522715 -0.847002 +0.123159 0.665538 -0.736132 +0.096730 0.522715 -0.847002 +0.249140 0.629316 -0.736132 +0.195675 0.494266 -0.847002 +0.195675 0.494266 -0.847002 +0.067070 0.362438 -0.929591 +0.096730 0.522715 -0.847002 +0.067070 0.362438 -0.929591 +0.195675 0.494266 -0.847002 +0.135677 0.342712 -0.929591 +0.135677 0.342712 -0.929591 +0.033206 0.179442 -0.983208 +0.067070 0.362438 -0.929591 +0.033206 0.179442 -0.983208 +0.135677 0.342712 -0.929591 +0.067173 0.169676 -0.983208 +0.000000 0.048809 -0.998808 +0.000000 0.182489 -0.983208 +0.000000 0.048809 -0.998808 +0.000000 0.878218 -0.478261 +0.000000 0.806043 -0.591858 +0.000000 0.878218 -0.478261 +0.000000 0.806043 -0.591858 +0.000000 0.806043 -0.591858 +0.000000 0.878218 -0.478261 +0.000000 0.676838 -0.736132 +0.000000 0.806043 -0.591858 +0.000000 0.806043 -0.591858 +0.000000 0.676838 -0.736132 +0.000000 0.676838 -0.736132 +0.000000 0.806043 -0.591858 +0.000000 0.676838 -0.736132 +0.000000 0.531589 -0.847002 +0.000000 0.676838 -0.736132 +0.000000 0.531589 -0.847002 +0.000000 0.531589 -0.847002 +0.000000 0.676838 -0.736132 +0.000000 0.368592 -0.929591 +0.000000 0.531589 -0.847002 +0.000000 0.531589 -0.847002 +0.000000 0.368592 -0.929591 +0.000000 0.368592 -0.929591 +0.000000 0.531589 -0.847002 +0.000000 0.182489 -0.983208 +0.000000 0.368592 -0.929591 +0.000000 0.368592 -0.929591 +0.000000 0.182489 -0.983208 +0.000000 0.182489 -0.983208 +0.000000 0.368592 -0.929591 +0.000000 0.182489 -0.983208 +0.000000 0.048809 -0.998808 +0.000000 0.182489 -0.983208 +0.000000 0.000000 -1.000000 +0.000000 0.120008 -0.992773 +0.000000 0.000000 -1.000000 +0.000000 0.570046 -0.821613 +0.000000 0.467325 -0.884085 +0.000000 0.570046 -0.821613 +0.000000 0.467325 -0.884085 +0.000000 0.467325 -0.884085 +0.000000 0.570046 -0.821613 +0.000000 0.298653 -0.954362 +0.000000 0.467325 -0.884085 +0.000000 0.467325 -0.884085 +0.000000 0.298653 -0.954362 +0.000000 0.298653 -0.954362 +0.000000 0.467325 -0.884085 +0.000000 0.298653 -0.954362 +0.000000 0.120008 -0.992773 +0.000000 0.298653 -0.954362 +0.000000 0.120008 -0.992773 +0.000000 0.120008 -0.992773 +0.000000 0.298653 -0.954362 +0.000000 0.120008 -0.992773 +0.000000 0.000000 -1.000000 +0.000000 0.120008 -0.992773 +0.111582 0.044174 -0.992773 +0.000000 0.000000 -1.000000 +0.100446 0.065670 -0.992773 +0.100446 0.065670 -0.992773 +0.000000 0.000000 -1.000000 +0.084859 0.084859 -0.992773 +0.100446 0.065670 -0.992773 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.103727 0.560529 -0.821613 +0.000000 0.467325 -0.884085 +0.000000 0.570046 -0.821613 +0.000000 0.000000 -1.000000 +0.084859 0.084859 -0.992773 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.065670 0.100446 -0.992773 +0.084859 0.084859 -0.992773 +0.000000 0.000000 -1.000000 +0.065670 0.100446 -0.992773 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.044174 0.111582 -0.992773 +0.065670 0.100446 -0.992773 +0.000000 0.000000 -1.000000 +0.021837 0.118005 -0.992773 +0.044174 0.111582 -0.992773 +0.000000 0.000000 -1.000000 +0.021837 0.118005 -0.992773 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.021837 0.118005 -0.992773 +0.000000 0.000000 -1.000000 +0.000000 0.120008 -0.992773 +0.021837 0.118005 -0.992773 +0.000000 0.000000 -1.000000 +0.000000 0.298653 -0.954362 +0.021837 0.118005 -0.992773 +0.000000 0.120008 -0.992773 +0.000000 0.298653 -0.954362 +0.054344 0.293667 -0.954362 +0.021837 0.118005 -0.992773 +0.000000 0.467325 -0.884085 +0.054344 0.293667 -0.954362 +0.000000 0.298653 -0.954362 +0.000000 0.467325 -0.884085 +0.085036 0.459524 -0.884085 +0.054344 0.293667 -0.954362 +0.103727 0.560529 -0.821613 +0.085036 0.459524 -0.884085 +0.000000 0.467325 -0.884085 +0.209831 0.530022 -0.821613 +0.085036 0.459524 -0.884085 +0.103727 0.560529 -0.821613 +0.209831 0.530022 -0.821613 +0.172020 0.434514 -0.884085 +0.085036 0.459524 -0.884085 +0.311935 0.477126 -0.821613 +0.172020 0.434514 -0.884085 +0.209831 0.530022 -0.821613 +0.311935 0.477126 -0.821613 +0.255725 0.391149 -0.884085 +0.172020 0.434514 -0.884085 +0.403083 0.403083 -0.821613 +0.255725 0.391149 -0.884085 +0.311935 0.477126 -0.821613 +0.403083 0.403083 -0.821613 +0.330449 0.330449 -0.884085 +0.255725 0.391149 -0.884085 +0.477126 0.311935 -0.821613 +0.330449 0.330449 -0.884085 +0.403083 0.403083 -0.821613 +0.477126 0.311935 -0.821613 +0.391149 0.255725 -0.884085 +0.330449 0.330449 -0.884085 +0.530022 0.209831 -0.821613 +0.391149 0.255725 -0.884085 +0.477126 0.311935 -0.821613 +0.530022 0.209831 -0.821613 +0.434514 0.172020 -0.884085 +0.391149 0.255725 -0.884085 +0.560529 0.103727 -0.821613 +0.434514 0.172020 -0.884085 +0.530022 0.209831 -0.821613 +0.560529 0.103727 -0.821613 +0.459524 0.085036 -0.884085 +0.434514 0.172020 -0.884085 +0.570046 0.000000 -0.821613 +0.459524 0.085036 -0.884085 +0.560529 0.103727 -0.821613 +0.570046 0.000000 -0.821613 +0.467325 0.000000 -0.884085 +0.459524 0.085036 -0.884085 +0.560529 -0.103727 -0.821613 +0.467325 0.000000 -0.884085 +0.570046 0.000000 -0.821613 +0.560529 -0.103727 -0.821613 +0.459524 -0.085036 -0.884085 +0.467325 0.000000 -0.884085 +0.530022 -0.209831 -0.821613 +0.459524 -0.085036 -0.884085 +0.560529 -0.103727 -0.821613 +0.530022 -0.209831 -0.821613 +0.434514 -0.172020 -0.884085 +0.459524 -0.085036 -0.884085 +0.477126 -0.311935 -0.821613 +0.434514 -0.172020 -0.884085 +0.530022 -0.209831 -0.821613 +0.477126 -0.311935 -0.821613 +0.391149 -0.255725 -0.884085 +0.434514 -0.172020 -0.884085 +0.403083 -0.403083 -0.821613 +0.391149 -0.255725 -0.884085 +0.477126 -0.311935 -0.821613 +0.403083 -0.403083 -0.821613 +0.330449 -0.330449 -0.884085 +0.391149 -0.255725 -0.884085 +0.311935 -0.477126 -0.821613 +0.330449 -0.330449 -0.884085 +0.403083 -0.403083 -0.821613 +0.311935 -0.477126 -0.821613 +0.255725 -0.391149 -0.884085 +0.330449 -0.330449 -0.884085 +0.209831 -0.530022 -0.821613 +0.255725 -0.391149 -0.884085 +0.311935 -0.477126 -0.821613 +0.209831 -0.530022 -0.821613 +0.172020 -0.434514 -0.884085 +0.255725 -0.391149 -0.884085 +0.103727 -0.560529 -0.821613 +0.172020 -0.434514 -0.884085 +0.209831 -0.530022 -0.821613 +0.103727 -0.560529 -0.821613 +0.085036 -0.459524 -0.884085 +0.172020 -0.434514 -0.884085 +0.000000 -0.570046 -0.821613 +0.085036 -0.459524 -0.884085 +0.103727 -0.560529 -0.821613 +0.000000 -0.467325 -0.884085 +0.085036 -0.459524 -0.884085 +0.000000 -0.570046 -0.821613 +0.000000 -0.467325 -0.884085 +0.054344 -0.293667 -0.954362 +0.085036 -0.459524 -0.884085 +0.000000 -0.298653 -0.954362 +0.054344 -0.293667 -0.954362 +0.000000 -0.467325 -0.884085 +0.000000 -0.298653 -0.954362 +0.021837 -0.118005 -0.992773 +0.054344 -0.293667 -0.954362 +0.000000 -0.120008 -0.992773 +0.021837 -0.118005 -0.992773 +0.000000 -0.298653 -0.954362 +0.000000 0.000000 -1.000000 +0.021837 -0.118005 -0.992773 +0.000000 -0.120008 -0.992773 +0.000000 0.000000 -1.000000 +0.021837 -0.118005 -0.992773 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.044174 -0.111582 -0.992773 +0.021837 -0.118005 -0.992773 +0.000000 0.000000 -1.000000 +0.044174 -0.111582 -0.992773 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.065670 -0.100446 -0.992773 +0.044174 -0.111582 -0.992773 +0.000000 0.000000 -1.000000 +0.065670 -0.100446 -0.992773 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.065670 -0.100446 -0.992773 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.084859 -0.084859 -0.992773 +0.065670 -0.100446 -0.992773 +0.000000 0.000000 -1.000000 +0.084859 -0.084859 -0.992773 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.100446 -0.065670 -0.992773 +0.084859 -0.084859 -0.992773 +0.000000 0.000000 -1.000000 +0.111582 -0.044174 -0.992773 +0.100446 -0.065670 -0.992773 +0.000000 0.000000 -1.000000 +0.111582 -0.044174 -0.992773 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.118005 -0.021837 -0.992773 +0.111582 -0.044174 -0.992773 +0.000000 0.000000 -1.000000 +0.118005 -0.021837 -0.992773 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.120008 0.000000 -0.992773 +0.118005 -0.021837 -0.992773 +0.000000 0.000000 -1.000000 +0.120008 0.000000 -0.992773 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.120008 0.000000 -0.992773 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.118005 0.021837 -0.992773 +0.120008 0.000000 -0.992773 +0.000000 0.000000 -1.000000 +0.118005 0.021837 -0.992773 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.111582 0.044174 -0.992773 +0.118005 0.021837 -0.992773 +0.000000 0.000000 -1.000000 +0.111582 0.044174 -0.992773 +0.000000 0.000000 -1.000000 +0.085036 -0.459524 -0.884085 +0.109933 -0.277684 -0.954362 +0.172020 -0.434514 -0.884085 +0.109933 -0.277684 -0.954362 +0.085036 -0.459524 -0.884085 +0.054344 -0.293667 -0.954362 +0.172020 -0.434514 -0.884085 +0.163426 -0.249971 -0.954362 +0.255725 -0.391149 -0.884085 +0.163426 -0.249971 -0.954362 +0.172020 -0.434514 -0.884085 +0.109933 -0.277684 -0.954362 +0.255725 -0.391149 -0.884085 +0.211179 -0.211179 -0.954362 +0.330449 -0.330449 -0.884085 +0.211179 -0.211179 -0.954362 +0.255725 -0.391149 -0.884085 +0.163426 -0.249971 -0.954362 +0.054344 -0.293667 -0.954362 +0.044174 -0.111582 -0.992773 +0.109933 -0.277684 -0.954362 +0.044174 -0.111582 -0.992773 +0.054344 -0.293667 -0.954362 +0.021837 -0.118005 -0.992773 +0.109933 -0.277684 -0.954362 +0.065670 -0.100446 -0.992773 +0.163426 -0.249971 -0.954362 +0.065670 -0.100446 -0.992773 +0.109933 -0.277684 -0.954362 +0.044174 -0.111582 -0.992773 +0.163426 -0.249971 -0.954362 +0.084859 -0.084859 -0.992773 +0.211179 -0.211179 -0.954362 +0.084859 -0.084859 -0.992773 +0.163426 -0.249971 -0.954362 +0.065670 -0.100446 -0.992773 +0.330449 -0.330449 -0.884085 +0.249971 -0.163426 -0.954362 +0.391149 -0.255725 -0.884085 +0.249971 -0.163426 -0.954362 +0.330449 -0.330449 -0.884085 +0.211179 -0.211179 -0.954362 +0.391149 -0.255725 -0.884085 +0.277684 -0.109933 -0.954362 +0.434514 -0.172020 -0.884085 +0.277684 -0.109933 -0.954362 +0.391149 -0.255725 -0.884085 +0.249971 -0.163426 -0.954362 +0.434514 -0.172020 -0.884085 +0.293667 -0.054344 -0.954362 +0.459524 -0.085036 -0.884085 +0.293667 -0.054344 -0.954362 +0.434514 -0.172020 -0.884085 +0.277684 -0.109933 -0.954362 +0.459524 -0.085036 -0.884085 +0.298653 0.000000 -0.954362 +0.467325 0.000000 -0.884085 +0.298653 0.000000 -0.954362 +0.459524 -0.085036 -0.884085 +0.293667 -0.054344 -0.954362 +0.211179 -0.211179 -0.954362 +0.100446 -0.065670 -0.992773 +0.249971 -0.163426 -0.954362 +0.100446 -0.065670 -0.992773 +0.211179 -0.211179 -0.954362 +0.084859 -0.084859 -0.992773 +0.249971 -0.163426 -0.954362 +0.111582 -0.044174 -0.992773 +0.277684 -0.109933 -0.954362 +0.111582 -0.044174 -0.992773 +0.249971 -0.163426 -0.954362 +0.100446 -0.065670 -0.992773 +0.277684 -0.109933 -0.954362 +0.118005 -0.021837 -0.992773 +0.293667 -0.054344 -0.954362 +0.118005 -0.021837 -0.992773 +0.277684 -0.109933 -0.954362 +0.111582 -0.044174 -0.992773 +0.293667 -0.054344 -0.954362 +0.120008 0.000000 -0.992773 +0.298653 0.000000 -0.954362 +0.120008 0.000000 -0.992773 +0.293667 -0.054344 -0.954362 +0.118005 -0.021837 -0.992773 +0.467325 0.000000 -0.884085 +0.293667 0.054344 -0.954362 +0.459524 0.085036 -0.884085 +0.293667 0.054344 -0.954362 +0.467325 0.000000 -0.884085 +0.298653 0.000000 -0.954362 +0.459524 0.085036 -0.884085 +0.277684 0.109933 -0.954362 +0.434514 0.172020 -0.884085 +0.277684 0.109933 -0.954362 +0.459524 0.085036 -0.884085 +0.293667 0.054344 -0.954362 +0.434514 0.172020 -0.884085 +0.249971 0.163426 -0.954362 +0.391149 0.255725 -0.884085 +0.249971 0.163426 -0.954362 +0.434514 0.172020 -0.884085 +0.277684 0.109933 -0.954362 +0.391149 0.255725 -0.884085 +0.211179 0.211179 -0.954362 +0.330449 0.330449 -0.884085 +0.211179 0.211179 -0.954362 +0.391149 0.255725 -0.884085 +0.249971 0.163426 -0.954362 +0.298653 0.000000 -0.954362 +0.118005 0.021837 -0.992773 +0.293667 0.054344 -0.954362 +0.118005 0.021837 -0.992773 +0.298653 0.000000 -0.954362 +0.120008 0.000000 -0.992773 +0.293667 0.054344 -0.954362 +0.111582 0.044174 -0.992773 +0.277684 0.109933 -0.954362 +0.111582 0.044174 -0.992773 +0.293667 0.054344 -0.954362 +0.118005 0.021837 -0.992773 +0.277684 0.109933 -0.954362 +0.100446 0.065670 -0.992773 +0.249971 0.163426 -0.954362 +0.100446 0.065670 -0.992773 +0.277684 0.109933 -0.954362 +0.111582 0.044174 -0.992773 +0.249971 0.163426 -0.954362 +0.084859 0.084859 -0.992773 +0.211179 0.211179 -0.954362 +0.084859 0.084859 -0.992773 +0.249971 0.163426 -0.954362 +0.100446 0.065670 -0.992773 +0.330449 0.330449 -0.884085 +0.163426 0.249971 -0.954362 +0.255725 0.391149 -0.884085 +0.163426 0.249971 -0.954362 +0.330449 0.330449 -0.884085 +0.211179 0.211179 -0.954362 +0.255725 0.391149 -0.884085 +0.109933 0.277684 -0.954362 +0.172020 0.434514 -0.884085 +0.109933 0.277684 -0.954362 +0.255725 0.391149 -0.884085 +0.163426 0.249971 -0.954362 +0.172020 0.434514 -0.884085 +0.054344 0.293667 -0.954362 +0.085036 0.459524 -0.884085 +0.054344 0.293667 -0.954362 +0.172020 0.434514 -0.884085 +0.109933 0.277684 -0.954362 +0.211179 0.211179 -0.954362 +0.065670 0.100446 -0.992773 +0.163426 0.249971 -0.954362 +0.065670 0.100446 -0.992773 +0.211179 0.211179 -0.954362 +0.084859 0.084859 -0.992773 +0.163426 0.249971 -0.954362 +0.044174 0.111582 -0.992773 +0.109933 0.277684 -0.954362 +0.044174 0.111582 -0.992773 +0.163426 0.249971 -0.954362 +0.065670 0.100446 -0.992773 +0.109933 0.277684 -0.954362 +0.021837 0.118005 -0.992773 +0.054344 0.293667 -0.954362 +0.021837 0.118005 -0.992773 +0.109933 0.277684 -0.954362 +0.044174 0.111582 -0.992773 +-0.120008 0.000000 -0.992773 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.084859 0.084859 -0.992773 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.068001 0.098883 -0.992773 +0.000000 0.000000 -1.000000 +-0.084859 0.084859 -0.992773 +-0.068001 0.098883 -0.992773 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.047665 0.110137 -0.992773 +0.000000 0.000000 -1.000000 +-0.068001 0.098883 -0.992773 +-0.047665 0.110137 -0.992773 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.024591 0.117462 -0.992773 +0.000000 0.000000 -1.000000 +-0.047665 0.110137 -0.992773 +-0.024591 0.117462 -0.992773 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.098883 0.068001 -0.992773 +-0.084859 0.084859 -0.992773 +0.000000 0.000000 -1.000000 +-0.098883 0.068001 -0.992773 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.098883 0.068001 -0.992773 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.110137 0.047665 -0.992773 +-0.098883 0.068001 -0.992773 +0.000000 0.000000 -1.000000 +-0.110137 0.047665 -0.992773 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.117462 0.024591 -0.992773 +-0.110137 0.047665 -0.992773 +0.000000 0.000000 -1.000000 +-0.117462 0.024591 -0.992773 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.120008 -0.992773 +0.000000 0.000000 -1.000000 +-0.024591 0.117462 -0.992773 +0.000000 0.120008 -0.992773 +0.000000 0.000000 -1.000000 +-0.061197 0.292316 -0.954362 +0.000000 0.120008 -0.992773 +-0.024591 0.117462 -0.992773 +-0.061197 0.292316 -0.954362 +0.000000 0.298653 -0.954362 +0.000000 0.120008 -0.992773 +-0.061197 0.292316 -0.954362 +0.000000 0.467325 -0.884085 +0.000000 0.298653 -0.954362 +-0.095759 0.457409 -0.884085 +0.000000 0.467325 -0.884085 +-0.061197 0.292316 -0.954362 +-0.095759 0.457409 -0.884085 +0.000000 0.570046 -0.821613 +0.000000 0.467325 -0.884085 +-0.095759 0.457409 -0.884085 +-0.103727 0.560529 -0.821613 +0.000000 0.570046 -0.821613 +-0.095759 0.457409 -0.884085 +-0.209831 0.530022 -0.821613 +-0.103727 0.560529 -0.821613 +-0.185611 0.428884 -0.884085 +-0.209831 0.530022 -0.821613 +-0.095759 0.457409 -0.884085 +-0.185611 0.428884 -0.884085 +-0.311935 0.477126 -0.821613 +-0.209831 0.530022 -0.821613 +-0.264803 0.385062 -0.884085 +-0.311935 0.477126 -0.821613 +-0.185611 0.428884 -0.884085 +-0.264803 0.385062 -0.884085 +-0.359299 0.442557 -0.821613 +-0.311935 0.477126 -0.821613 +-0.330449 0.330449 -0.884085 +-0.359299 0.442557 -0.821613 +-0.264803 0.385062 -0.884085 +-0.330449 0.330449 -0.884085 +-0.403083 0.403083 -0.821613 +-0.359299 0.442557 -0.821613 +-0.385062 0.264803 -0.884085 +-0.403083 0.403083 -0.821613 +-0.330449 0.330449 -0.884085 +-0.385062 0.264803 -0.884085 +-0.442557 0.359299 -0.821613 +-0.403083 0.403083 -0.821613 +-0.385062 0.264803 -0.884085 +-0.477126 0.311935 -0.821613 +-0.442557 0.359299 -0.821613 +-0.428884 0.185611 -0.884085 +-0.477126 0.311935 -0.821613 +-0.385062 0.264803 -0.884085 +-0.428884 0.185611 -0.884085 +-0.530022 0.209831 -0.821613 +-0.477126 0.311935 -0.821613 +-0.457409 0.095759 -0.884085 +-0.530022 0.209831 -0.821613 +-0.428884 0.185611 -0.884085 +-0.457409 0.095759 -0.884085 +-0.560529 0.103727 -0.821613 +-0.530022 0.209831 -0.821613 +-0.560529 0.103727 -0.821613 +-0.467325 0.000000 -0.884085 +-0.570046 0.000000 -0.821613 +-0.457409 0.095759 -0.884085 +-0.467325 0.000000 -0.884085 +-0.560529 0.103727 -0.821613 +-0.457409 0.095759 -0.884085 +-0.298653 0.000000 -0.954362 +-0.467325 0.000000 -0.884085 +-0.292316 0.061197 -0.954362 +-0.298653 0.000000 -0.954362 +-0.457409 0.095759 -0.884085 +-0.292316 0.061197 -0.954362 +-0.120008 0.000000 -0.992773 +-0.298653 0.000000 -0.954362 +-0.117462 0.024591 -0.992773 +-0.120008 0.000000 -0.992773 +-0.292316 0.061197 -0.954362 +0.000000 0.000000 -1.000000 +-0.120008 0.000000 -0.992773 +-0.117462 0.024591 -0.992773 +-0.095759 0.457409 -0.884085 +-0.118618 0.274086 -0.954362 +-0.185611 0.428884 -0.884085 +-0.118618 0.274086 -0.954362 +-0.095759 0.457409 -0.884085 +-0.061197 0.292316 -0.954362 +-0.185611 0.428884 -0.884085 +-0.169227 0.246081 -0.954362 +-0.264803 0.385062 -0.884085 +-0.169227 0.246081 -0.954362 +-0.185611 0.428884 -0.884085 +-0.118618 0.274086 -0.954362 +-0.264803 0.385062 -0.884085 +-0.211179 0.211179 -0.954362 +-0.330449 0.330449 -0.884085 +-0.211179 0.211179 -0.954362 +-0.264803 0.385062 -0.884085 +-0.169227 0.246081 -0.954362 +-0.061197 0.292316 -0.954362 +-0.047665 0.110137 -0.992773 +-0.118618 0.274086 -0.954362 +-0.047665 0.110137 -0.992773 +-0.061197 0.292316 -0.954362 +-0.024591 0.117462 -0.992773 +-0.118618 0.274086 -0.954362 +-0.068001 0.098883 -0.992773 +-0.169227 0.246081 -0.954362 +-0.068001 0.098883 -0.992773 +-0.118618 0.274086 -0.954362 +-0.047665 0.110137 -0.992773 +-0.169227 0.246081 -0.954362 +-0.084859 0.084859 -0.992773 +-0.211179 0.211179 -0.954362 +-0.084859 0.084859 -0.992773 +-0.169227 0.246081 -0.954362 +-0.068001 0.098883 -0.992773 +-0.330449 0.330449 -0.884085 +-0.246081 0.169227 -0.954362 +-0.385062 0.264803 -0.884085 +-0.246081 0.169227 -0.954362 +-0.330449 0.330449 -0.884085 +-0.211179 0.211179 -0.954362 +-0.385062 0.264803 -0.884085 +-0.274086 0.118618 -0.954362 +-0.428884 0.185611 -0.884085 +-0.274086 0.118618 -0.954362 +-0.385062 0.264803 -0.884085 +-0.246081 0.169227 -0.954362 +-0.428884 0.185611 -0.884085 +-0.292316 0.061197 -0.954362 +-0.457409 0.095759 -0.884085 +-0.292316 0.061197 -0.954362 +-0.428884 0.185611 -0.884085 +-0.274086 0.118618 -0.954362 +-0.211179 0.211179 -0.954362 +-0.098883 0.068001 -0.992773 +-0.246081 0.169227 -0.954362 +-0.098883 0.068001 -0.992773 +-0.211179 0.211179 -0.954362 +-0.084859 0.084859 -0.992773 +-0.246081 0.169227 -0.954362 +-0.110137 0.047665 -0.992773 +-0.274086 0.118618 -0.954362 +-0.110137 0.047665 -0.992773 +-0.246081 0.169227 -0.954362 +-0.098883 0.068001 -0.992773 +-0.274086 0.118618 -0.954362 +-0.117462 0.024591 -0.992773 +-0.292316 0.061197 -0.954362 +-0.117462 0.024591 -0.992773 +-0.274086 0.118618 -0.954362 +-0.110137 0.047665 -0.992773 +0.000000 -0.120008 -0.992773 +0.000000 0.000000 -1.000000 +0.000000 -0.120008 -0.992773 +0.000000 -0.570046 -0.821613 +0.000000 -0.467325 -0.884085 +0.000000 -0.570046 -0.821613 +0.000000 -0.467325 -0.884085 +0.000000 -0.467325 -0.884085 +0.000000 -0.570046 -0.821613 +0.000000 -0.298653 -0.954362 +0.000000 -0.467325 -0.884085 +0.000000 -0.467325 -0.884085 +0.000000 -0.298653 -0.954362 +0.000000 -0.298653 -0.954362 +0.000000 -0.467325 -0.884085 +0.000000 -0.120008 -0.992773 +0.000000 -0.298653 -0.954362 +0.000000 -0.298653 -0.954362 +0.000000 -0.120008 -0.992773 +0.000000 -0.120008 -0.992773 +0.000000 -0.298653 -0.954362 +0.000000 0.000000 -1.000000 +0.000000 -0.120008 -0.992773 +0.000000 0.000000 -1.000000 +0.000000 -0.488768 -0.872414 +0.000000 -0.570046 -0.821613 +0.000000 -0.570046 -0.821613 +0.000000 -0.144208 -0.989547 +0.000000 -0.048809 -0.998808 +0.000000 -0.048809 -0.998808 +0.000000 -0.144208 -0.989547 +0.000000 -0.144208 -0.989547 +0.000000 -0.048809 -0.998808 +0.000000 -0.321862 -0.946787 +0.000000 -0.144208 -0.989547 +0.000000 -0.144208 -0.989547 +0.000000 -0.321862 -0.946787 +0.000000 -0.321862 -0.946787 +0.000000 -0.144208 -0.989547 +0.000000 -0.488768 -0.872414 +0.000000 -0.321862 -0.946787 +0.000000 -0.321862 -0.946787 +0.000000 -0.488768 -0.872414 +0.000000 -0.488768 -0.872414 +0.000000 -0.321862 -0.946787 +0.000000 -0.570046 -0.821613 +0.000000 -0.488768 -0.872414 +0.000000 -0.488768 -0.872414 +-0.037893 -0.030764 -0.998808 +-0.101971 -0.101971 -0.989547 +-0.034513 -0.034513 -0.998808 +-0.081713 -0.118823 -0.989547 +-0.034513 -0.034513 -0.998808 +-0.101971 -0.101971 -0.989547 +-0.081713 -0.118823 -0.989547 +-0.030764 -0.037893 -0.998808 +-0.034513 -0.034513 -0.998808 +-0.081713 -0.118823 -0.989547 +-0.026709 -0.040853 -0.998808 +-0.030764 -0.037893 -0.998808 +-0.057276 -0.132346 -0.989547 +-0.026709 -0.040853 -0.998808 +-0.081713 -0.118823 -0.989547 +-0.057276 -0.132346 -0.989547 +-0.017966 -0.045382 -0.998808 +-0.026709 -0.040853 -0.998808 +-0.029550 -0.141148 -0.989547 +-0.017966 -0.045382 -0.998808 +-0.057276 -0.132346 -0.989547 +-0.029550 -0.141148 -0.989547 +-0.008882 -0.047995 -0.998808 +-0.017966 -0.045382 -0.998808 +-0.008882 -0.047995 -0.998808 +0.000000 -0.144208 -0.989547 +0.000000 -0.048809 -0.998808 +-0.029550 -0.141148 -0.989547 +0.000000 -0.144208 -0.989547 +-0.008882 -0.047995 -0.998808 +-0.065952 -0.315032 -0.946787 +0.000000 -0.144208 -0.989547 +-0.029550 -0.141148 -0.989547 +-0.065952 -0.315032 -0.946787 +0.000000 -0.321862 -0.946787 +0.000000 -0.144208 -0.989547 +-0.100153 -0.478397 -0.872414 +0.000000 -0.321862 -0.946787 +-0.065952 -0.315032 -0.946787 +-0.100153 -0.478397 -0.872414 +0.000000 -0.488768 -0.872414 +0.000000 -0.321862 -0.946787 +-0.100153 -0.478397 -0.872414 +0.000000 -0.570046 -0.821613 +0.000000 -0.488768 -0.872414 +-0.100153 -0.478397 -0.872414 +-0.103727 -0.560529 -0.821613 +0.000000 -0.570046 -0.821613 +-0.100153 -0.478397 -0.872414 +-0.209831 -0.530022 -0.821613 +-0.103727 -0.560529 -0.821613 +-0.194128 -0.448563 -0.872414 +-0.209831 -0.530022 -0.821613 +-0.100153 -0.478397 -0.872414 +-0.194128 -0.448563 -0.872414 +-0.311935 -0.477126 -0.821613 +-0.209831 -0.530022 -0.821613 +-0.276953 -0.402730 -0.872414 +-0.311935 -0.477126 -0.821613 +-0.194128 -0.448563 -0.872414 +-0.276953 -0.402730 -0.872414 +-0.359299 -0.442557 -0.821613 +-0.311935 -0.477126 -0.821613 +-0.345612 -0.345612 -0.872414 +-0.359299 -0.442557 -0.821613 +-0.276953 -0.402730 -0.872414 +-0.345612 -0.345612 -0.872414 +-0.403083 -0.403083 -0.821613 +-0.359299 -0.442557 -0.821613 +-0.345612 -0.345612 -0.872414 +-0.442557 -0.359299 -0.821613 +-0.403083 -0.403083 -0.821613 +-0.402730 -0.276953 -0.872414 +-0.442557 -0.359299 -0.821613 +-0.345612 -0.345612 -0.872414 +-0.402730 -0.276953 -0.872414 +-0.477126 -0.311935 -0.821613 +-0.442557 -0.359299 -0.821613 +-0.448563 -0.194128 -0.872414 +-0.477126 -0.311935 -0.821613 +-0.402730 -0.276953 -0.872414 +-0.448563 -0.194128 -0.872414 +-0.530022 -0.209831 -0.821613 +-0.477126 -0.311935 -0.821613 +-0.478397 -0.100153 -0.872414 +-0.530022 -0.209831 -0.821613 +-0.448563 -0.194128 -0.872414 +-0.478397 -0.100153 -0.872414 +-0.560529 -0.103727 -0.821613 +-0.530022 -0.209831 -0.821613 +-0.560529 -0.103727 -0.821613 +-0.488768 0.000000 -0.872414 +-0.570046 0.000000 -0.821613 +-0.478397 -0.100153 -0.872414 +-0.488768 0.000000 -0.872414 +-0.560529 -0.103727 -0.821613 +-0.315032 -0.065952 -0.946787 +-0.488768 0.000000 -0.872414 +-0.478397 -0.100153 -0.872414 +-0.315032 -0.065952 -0.946787 +-0.321862 0.000000 -0.946787 +-0.488768 0.000000 -0.872414 +-0.141148 -0.029550 -0.989547 +-0.321862 0.000000 -0.946787 +-0.315032 -0.065952 -0.946787 +-0.141148 -0.029550 -0.989547 +-0.144208 0.000000 -0.989547 +-0.321862 0.000000 -0.946787 +-0.141148 -0.029550 -0.989547 +-0.048809 0.000000 -0.998808 +-0.144208 0.000000 -0.989547 +-0.141148 -0.029550 -0.989547 +-0.047995 -0.008882 -0.998808 +-0.048809 0.000000 -0.998808 +-0.141148 -0.029550 -0.989547 +-0.045382 -0.017966 -0.998808 +-0.047995 -0.008882 -0.998808 +-0.132346 -0.057276 -0.989547 +-0.045382 -0.017966 -0.998808 +-0.141148 -0.029550 -0.989547 +-0.132346 -0.057276 -0.989547 +-0.040853 -0.026709 -0.998808 +-0.045382 -0.017966 -0.998808 +-0.118823 -0.081713 -0.989547 +-0.040853 -0.026709 -0.998808 +-0.132346 -0.057276 -0.989547 +-0.118823 -0.081713 -0.989547 +-0.037893 -0.030764 -0.998808 +-0.040853 -0.026709 -0.998808 +-0.101971 -0.101971 -0.989547 +-0.037893 -0.030764 -0.998808 +-0.118823 -0.081713 -0.989547 +-0.478397 -0.100153 -0.872414 +-0.295386 -0.127836 -0.946787 +-0.315032 -0.065952 -0.946787 +-0.295386 -0.127836 -0.946787 +-0.478397 -0.100153 -0.872414 +-0.448563 -0.194128 -0.872414 +-0.315032 -0.065952 -0.946787 +-0.132346 -0.057276 -0.989547 +-0.141148 -0.029550 -0.989547 +-0.132346 -0.057276 -0.989547 +-0.315032 -0.065952 -0.946787 +-0.295386 -0.127836 -0.946787 +-0.448563 -0.194128 -0.872414 +-0.265204 -0.182378 -0.946787 +-0.295386 -0.127836 -0.946787 +-0.265204 -0.182378 -0.946787 +-0.448563 -0.194128 -0.872414 +-0.402730 -0.276953 -0.872414 +-0.402730 -0.276953 -0.872414 +-0.227591 -0.227591 -0.946787 +-0.265204 -0.182378 -0.946787 +-0.227591 -0.227591 -0.946787 +-0.402730 -0.276953 -0.872414 +-0.345612 -0.345612 -0.872414 +-0.295386 -0.127836 -0.946787 +-0.118823 -0.081713 -0.989547 +-0.132346 -0.057276 -0.989547 +-0.118823 -0.081713 -0.989547 +-0.295386 -0.127836 -0.946787 +-0.265204 -0.182378 -0.946787 +-0.265204 -0.182378 -0.946787 +-0.101971 -0.101971 -0.989547 +-0.118823 -0.081713 -0.989547 +-0.101971 -0.101971 -0.989547 +-0.265204 -0.182378 -0.946787 +-0.227591 -0.227591 -0.946787 +-0.345612 -0.345612 -0.872414 +-0.182378 -0.265204 -0.946787 +-0.227591 -0.227591 -0.946787 +-0.182378 -0.265204 -0.946787 +-0.345612 -0.345612 -0.872414 +-0.276953 -0.402730 -0.872414 +-0.276953 -0.402730 -0.872414 +-0.127836 -0.295386 -0.946787 +-0.182378 -0.265204 -0.946787 +-0.127836 -0.295386 -0.946787 +-0.276953 -0.402730 -0.872414 +-0.194128 -0.448563 -0.872414 +-0.227591 -0.227591 -0.946787 +-0.081713 -0.118823 -0.989547 +-0.101971 -0.101971 -0.989547 +-0.081713 -0.118823 -0.989547 +-0.227591 -0.227591 -0.946787 +-0.182378 -0.265204 -0.946787 +-0.182378 -0.265204 -0.946787 +-0.057276 -0.132346 -0.989547 +-0.081713 -0.118823 -0.989547 +-0.057276 -0.132346 -0.989547 +-0.182378 -0.265204 -0.946787 +-0.127836 -0.295386 -0.946787 +-0.194128 -0.448563 -0.872414 +-0.065952 -0.315032 -0.946787 +-0.127836 -0.295386 -0.946787 +-0.065952 -0.315032 -0.946787 +-0.194128 -0.448563 -0.872414 +-0.100153 -0.478397 -0.872414 +-0.127836 -0.295386 -0.946787 +-0.029550 -0.141148 -0.989547 +-0.057276 -0.132346 -0.989547 +-0.029550 -0.141148 -0.989547 +-0.127836 -0.295386 -0.946787 +-0.065952 -0.315032 -0.946787 +0.000000 -0.144208 -0.989547 +0.008882 -0.047995 -0.998808 +0.000000 -0.048809 -0.998808 +0.053082 -0.134083 -0.989547 +0.008882 -0.047995 -0.998808 +0.026241 -0.141801 -0.989547 +0.053082 -0.134083 -0.989547 +0.017966 -0.045382 -0.998808 +0.008882 -0.047995 -0.998808 +0.078912 -0.120702 -0.989547 +0.017966 -0.045382 -0.998808 +0.053082 -0.134083 -0.989547 +0.078912 -0.120702 -0.989547 +0.026709 -0.040853 -0.998808 +0.017966 -0.045382 -0.998808 +0.101971 -0.101971 -0.989547 +0.026709 -0.040853 -0.998808 +0.078912 -0.120702 -0.989547 +0.101971 -0.101971 -0.989547 +0.034513 -0.034513 -0.998808 +0.026709 -0.040853 -0.998808 +0.120702 -0.078912 -0.989547 +0.034513 -0.034513 -0.998808 +0.101971 -0.101971 -0.989547 +0.120702 -0.078912 -0.989547 +0.040853 -0.026709 -0.998808 +0.034513 -0.034513 -0.998808 +0.134083 -0.053082 -0.989547 +0.040853 -0.026709 -0.998808 +0.120702 -0.078912 -0.989547 +0.134083 -0.053082 -0.989547 +0.045382 -0.017966 -0.998808 +0.040853 -0.026709 -0.998808 +0.141801 -0.026241 -0.989547 +0.045382 -0.017966 -0.998808 +0.134083 -0.053082 -0.989547 +0.141801 -0.026241 -0.989547 +0.047995 -0.008882 -0.998808 +0.045382 -0.017966 -0.998808 +0.144208 0.000000 -0.989547 +0.047995 -0.008882 -0.998808 +0.141801 -0.026241 -0.989547 +0.144208 0.000000 -0.989547 +0.048809 0.000000 -0.998808 +0.047995 -0.008882 -0.998808 +0.141801 0.026241 -0.989547 +0.048809 0.000000 -0.998808 +0.144208 0.000000 -0.989547 +0.141801 0.026241 -0.989547 +0.047995 0.008882 -0.998808 +0.048809 0.000000 -0.998808 +0.134083 0.053082 -0.989547 +0.047995 0.008882 -0.998808 +0.141801 0.026241 -0.989547 +0.134083 0.053082 -0.989547 +0.045382 0.017966 -0.998808 +0.047995 0.008882 -0.998808 +0.120702 0.078912 -0.989547 +0.045382 0.017966 -0.998808 +0.134083 0.053082 -0.989547 +0.120702 0.078912 -0.989547 +0.040853 0.026709 -0.998808 +0.045382 0.017966 -0.998808 +0.101971 0.101971 -0.989547 +0.040853 0.026709 -0.998808 +0.120702 0.078912 -0.989547 +0.101971 0.101971 -0.989547 +0.034513 0.034513 -0.998808 +0.040853 0.026709 -0.998808 +0.078912 0.120702 -0.989547 +0.034513 0.034513 -0.998808 +0.101971 0.101971 -0.989547 +0.078912 0.120702 -0.989547 +0.026709 0.040853 -0.998808 +0.034513 0.034513 -0.998808 +0.053082 0.134083 -0.989547 +0.026709 0.040853 -0.998808 +0.078912 0.120702 -0.989547 +0.053082 0.134083 -0.989547 +0.017966 0.045382 -0.998808 +0.026709 0.040853 -0.998808 +0.026241 0.141801 -0.989547 +0.017966 0.045382 -0.998808 +0.053082 0.134083 -0.989547 +0.026241 0.141801 -0.989547 +0.008882 0.047995 -0.998808 +0.017966 0.045382 -0.998808 +0.026241 0.141801 -0.989547 +0.000000 0.048809 -0.998808 +0.008882 0.047995 -0.998808 +0.026241 0.141801 -0.989547 +0.000000 0.144208 -0.989547 +0.000000 0.048809 -0.998808 +0.058567 0.316488 -0.946787 +0.000000 0.144208 -0.989547 +0.026241 0.141801 -0.989547 +0.058567 0.316488 -0.946787 +0.000000 0.321862 -0.946787 +0.000000 0.144208 -0.989547 +0.088938 0.480609 -0.872414 +0.000000 0.321862 -0.946787 +0.058567 0.316488 -0.946787 +0.088938 0.480609 -0.872414 +0.000000 0.488768 -0.872414 +0.000000 0.321862 -0.946787 +0.088938 0.480609 -0.872414 +0.000000 0.570046 -0.821613 +0.000000 0.488768 -0.872414 +0.088938 0.480609 -0.872414 +0.103727 0.560529 -0.821613 +0.000000 0.570046 -0.821613 +0.179913 0.454451 -0.872414 +0.103727 0.560529 -0.821613 +0.088938 0.480609 -0.872414 +0.179913 0.454451 -0.872414 +0.209831 0.530022 -0.821613 +0.103727 0.560529 -0.821613 +0.267459 0.409097 -0.872414 +0.209831 0.530022 -0.821613 +0.179913 0.454451 -0.872414 +0.267459 0.409097 -0.872414 +0.311935 0.477126 -0.821613 +0.209831 0.530022 -0.821613 +0.345612 0.345612 -0.872414 +0.311935 0.477126 -0.821613 +0.267459 0.409097 -0.872414 +0.345612 0.345612 -0.872414 +0.403083 0.403083 -0.821613 +0.311935 0.477126 -0.821613 +0.409097 0.267459 -0.872414 +0.403083 0.403083 -0.821613 +0.345612 0.345612 -0.872414 +0.409097 0.267459 -0.872414 +0.477126 0.311935 -0.821613 +0.403083 0.403083 -0.821613 +0.454451 0.179913 -0.872414 +0.477126 0.311935 -0.821613 +0.409097 0.267459 -0.872414 +0.454451 0.179913 -0.872414 +0.530022 0.209831 -0.821613 +0.477126 0.311935 -0.821613 +0.480609 0.088938 -0.872414 +0.530022 0.209831 -0.821613 +0.454451 0.179913 -0.872414 +0.480609 0.088938 -0.872414 +0.560529 0.103727 -0.821613 +0.530022 0.209831 -0.821613 +0.488768 0.000000 -0.872414 +0.560529 0.103727 -0.821613 +0.480609 0.088938 -0.872414 +0.488768 0.000000 -0.872414 +0.570046 0.000000 -0.821613 +0.560529 0.103727 -0.821613 +0.480609 -0.088938 -0.872414 +0.570046 0.000000 -0.821613 +0.488768 0.000000 -0.872414 +0.480609 -0.088938 -0.872414 +0.560529 -0.103727 -0.821613 +0.570046 0.000000 -0.821613 +0.454451 -0.179913 -0.872414 +0.560529 -0.103727 -0.821613 +0.480609 -0.088938 -0.872414 +0.454451 -0.179913 -0.872414 +0.530022 -0.209831 -0.821613 +0.560529 -0.103727 -0.821613 +0.409097 -0.267459 -0.872414 +0.530022 -0.209831 -0.821613 +0.454451 -0.179913 -0.872414 +0.409097 -0.267459 -0.872414 +0.477126 -0.311935 -0.821613 +0.530022 -0.209831 -0.821613 +0.345612 -0.345612 -0.872414 +0.477126 -0.311935 -0.821613 +0.409097 -0.267459 -0.872414 +0.345612 -0.345612 -0.872414 +0.403083 -0.403083 -0.821613 +0.477126 -0.311935 -0.821613 +0.267459 -0.409097 -0.872414 +0.403083 -0.403083 -0.821613 +0.345612 -0.345612 -0.872414 +0.267459 -0.409097 -0.872414 +0.311935 -0.477126 -0.821613 +0.403083 -0.403083 -0.821613 +0.179913 -0.454451 -0.872414 +0.311935 -0.477126 -0.821613 +0.267459 -0.409097 -0.872414 +0.179913 -0.454451 -0.872414 +0.209831 -0.530022 -0.821613 +0.311935 -0.477126 -0.821613 +0.088938 -0.480609 -0.872414 +0.209831 -0.530022 -0.821613 +0.179913 -0.454451 -0.872414 +0.088938 -0.480609 -0.872414 +0.103727 -0.560529 -0.821613 +0.209831 -0.530022 -0.821613 +0.088938 -0.480609 -0.872414 +0.000000 -0.570046 -0.821613 +0.103727 -0.560529 -0.821613 +0.088938 -0.480609 -0.872414 +0.000000 -0.488768 -0.872414 +0.000000 -0.570046 -0.821613 +0.058567 -0.316488 -0.946787 +0.000000 -0.488768 -0.872414 +0.088938 -0.480609 -0.872414 +0.058567 -0.316488 -0.946787 +0.000000 -0.321862 -0.946787 +0.000000 -0.488768 -0.872414 +0.026241 -0.141801 -0.989547 +0.000000 -0.321862 -0.946787 +0.058567 -0.316488 -0.946787 +0.026241 -0.141801 -0.989547 +0.000000 -0.144208 -0.989547 +0.000000 -0.321862 -0.946787 +0.008882 -0.047995 -0.998808 +0.000000 -0.144208 -0.989547 +0.026241 -0.141801 -0.989547 +0.088938 -0.480609 -0.872414 +0.118476 -0.299263 -0.946787 +0.058567 -0.316488 -0.946787 +0.118476 -0.299263 -0.946787 +0.088938 -0.480609 -0.872414 +0.179913 -0.454451 -0.872414 +0.058567 -0.316488 -0.946787 +0.053082 -0.134083 -0.989547 +0.026241 -0.141801 -0.989547 +0.053082 -0.134083 -0.989547 +0.058567 -0.316488 -0.946787 +0.118476 -0.299263 -0.946787 +0.179913 -0.454451 -0.872414 +0.176126 -0.269397 -0.946787 +0.118476 -0.299263 -0.946787 +0.176126 -0.269397 -0.946787 +0.179913 -0.454451 -0.872414 +0.267459 -0.409097 -0.872414 +0.267459 -0.409097 -0.872414 +0.227591 -0.227591 -0.946787 +0.176126 -0.269397 -0.946787 +0.227591 -0.227591 -0.946787 +0.267459 -0.409097 -0.872414 +0.345612 -0.345612 -0.872414 +0.118476 -0.299263 -0.946787 +0.078912 -0.120702 -0.989547 +0.053082 -0.134083 -0.989547 +0.078912 -0.120702 -0.989547 +0.118476 -0.299263 -0.946787 +0.176126 -0.269397 -0.946787 +0.176126 -0.269397 -0.946787 +0.101971 -0.101971 -0.989547 +0.078912 -0.120702 -0.989547 +0.101971 -0.101971 -0.989547 +0.176126 -0.269397 -0.946787 +0.227591 -0.227591 -0.946787 +0.345612 -0.345612 -0.872414 +0.269397 -0.176126 -0.946787 +0.227591 -0.227591 -0.946787 +0.269397 -0.176126 -0.946787 +0.345612 -0.345612 -0.872414 +0.409097 -0.267459 -0.872414 +0.409097 -0.267459 -0.872414 +0.299263 -0.118476 -0.946787 +0.269397 -0.176126 -0.946787 +0.299263 -0.118476 -0.946787 +0.409097 -0.267459 -0.872414 +0.454451 -0.179913 -0.872414 +0.227591 -0.227591 -0.946787 +0.120702 -0.078912 -0.989547 +0.101971 -0.101971 -0.989547 +0.120702 -0.078912 -0.989547 +0.227591 -0.227591 -0.946787 +0.269397 -0.176126 -0.946787 +0.269397 -0.176126 -0.946787 +0.134083 -0.053082 -0.989547 +0.120702 -0.078912 -0.989547 +0.134083 -0.053082 -0.989547 +0.269397 -0.176126 -0.946787 +0.299263 -0.118476 -0.946787 +0.454451 -0.179913 -0.872414 +0.316488 -0.058567 -0.946787 +0.299263 -0.118476 -0.946787 +0.316488 -0.058567 -0.946787 +0.454451 -0.179913 -0.872414 +0.480609 -0.088938 -0.872414 +0.480609 -0.088938 -0.872414 +0.321862 0.000000 -0.946787 +0.316488 -0.058567 -0.946787 +0.321862 0.000000 -0.946787 +0.480609 -0.088938 -0.872414 +0.488768 0.000000 -0.872414 +0.299263 -0.118476 -0.946787 +0.141801 -0.026241 -0.989547 +0.134083 -0.053082 -0.989547 +0.141801 -0.026241 -0.989547 +0.299263 -0.118476 -0.946787 +0.316488 -0.058567 -0.946787 +0.316488 -0.058567 -0.946787 +0.144208 0.000000 -0.989547 +0.141801 -0.026241 -0.989547 +0.144208 0.000000 -0.989547 +0.316488 -0.058567 -0.946787 +0.321862 0.000000 -0.946787 +0.488768 0.000000 -0.872414 +0.316488 0.058567 -0.946787 +0.321862 0.000000 -0.946787 +0.316488 0.058567 -0.946787 +0.488768 0.000000 -0.872414 +0.480609 0.088938 -0.872414 +0.480609 0.088938 -0.872414 +0.299263 0.118476 -0.946787 +0.316488 0.058567 -0.946787 +0.299263 0.118476 -0.946787 +0.480609 0.088938 -0.872414 +0.454451 0.179913 -0.872414 +0.321862 0.000000 -0.946787 +0.141801 0.026241 -0.989547 +0.144208 0.000000 -0.989547 +0.141801 0.026241 -0.989547 +0.321862 0.000000 -0.946787 +0.316488 0.058567 -0.946787 +0.316488 0.058567 -0.946787 +0.134083 0.053082 -0.989547 +0.141801 0.026241 -0.989547 +0.134083 0.053082 -0.989547 +0.316488 0.058567 -0.946787 +0.299263 0.118476 -0.946787 +0.454451 0.179913 -0.872414 +0.269397 0.176126 -0.946787 +0.299263 0.118476 -0.946787 +0.269397 0.176126 -0.946787 +0.454451 0.179913 -0.872414 +0.409097 0.267459 -0.872414 +0.409097 0.267459 -0.872414 +0.227591 0.227591 -0.946787 +0.269397 0.176126 -0.946787 +0.227591 0.227591 -0.946787 +0.409097 0.267459 -0.872414 +0.345612 0.345612 -0.872414 +0.299263 0.118476 -0.946787 +0.120702 0.078912 -0.989547 +0.134083 0.053082 -0.989547 +0.120702 0.078912 -0.989547 +0.299263 0.118476 -0.946787 +0.269397 0.176126 -0.946787 +0.269397 0.176126 -0.946787 +0.101971 0.101971 -0.989547 +0.120702 0.078912 -0.989547 +0.101971 0.101971 -0.989547 +0.269397 0.176126 -0.946787 +0.227591 0.227591 -0.946787 +0.345612 0.345612 -0.872414 +0.176126 0.269397 -0.946787 +0.227591 0.227591 -0.946787 +0.176126 0.269397 -0.946787 +0.345612 0.345612 -0.872414 +0.267459 0.409097 -0.872414 +0.267459 0.409097 -0.872414 +0.118476 0.299263 -0.946787 +0.176126 0.269397 -0.946787 +0.118476 0.299263 -0.946787 +0.267459 0.409097 -0.872414 +0.179913 0.454451 -0.872414 +0.227591 0.227591 -0.946787 +0.078912 0.120702 -0.989547 +0.101971 0.101971 -0.989547 +0.078912 0.120702 -0.989547 +0.227591 0.227591 -0.946787 +0.176126 0.269397 -0.946787 +0.176126 0.269397 -0.946787 +0.053082 0.134083 -0.989547 +0.078912 0.120702 -0.989547 +0.053082 0.134083 -0.989547 +0.176126 0.269397 -0.946787 +0.118476 0.299263 -0.946787 +0.179913 0.454451 -0.872414 +0.058567 0.316488 -0.946787 +0.118476 0.299263 -0.946787 +0.058567 0.316488 -0.946787 +0.179913 0.454451 -0.872414 +0.088938 0.480609 -0.872414 +0.118476 0.299263 -0.946787 +0.026241 0.141801 -0.989547 +0.053082 0.134083 -0.989547 +0.026241 0.141801 -0.989547 +0.118476 0.299263 -0.946787 +0.058567 0.316488 -0.946787 +0.000000 0.488768 -0.872414 +0.000000 0.570046 -0.821613 +0.000000 0.570046 -0.821613 +0.000000 0.048809 -0.998808 +0.000000 0.144208 -0.989547 +0.000000 0.048809 -0.998808 +0.000000 0.144208 -0.989547 +0.000000 0.144208 -0.989547 +0.000000 0.048809 -0.998808 +0.000000 0.321862 -0.946787 +0.000000 0.144208 -0.989547 +0.000000 0.144208 -0.989547 +0.000000 0.321862 -0.946787 +0.000000 0.321862 -0.946787 +0.000000 0.144208 -0.989547 +0.000000 0.488768 -0.872414 +0.000000 0.321862 -0.946787 +0.000000 0.321862 -0.946787 +0.000000 0.488768 -0.872414 +0.000000 0.488768 -0.872414 +0.000000 0.321862 -0.946787 +0.000000 0.570046 -0.821613 +0.000000 0.488768 -0.872414 +0.000000 0.488768 -0.872414 +0.000000 0.000000 -1.000000 +0.000000 -0.158432 -0.987370 +0.000000 0.000000 -1.000000 +0.000000 -0.878218 -0.478261 +0.000000 -0.791354 -0.611358 +0.000000 -0.878218 -0.478261 +0.000000 -0.791354 -0.611358 +0.000000 -0.791354 -0.611358 +0.000000 -0.878218 -0.478261 +0.000000 -0.791354 -0.611358 +0.000000 -0.658666 -0.752436 +0.000000 -0.791354 -0.611358 +0.000000 -0.658666 -0.752436 +0.000000 -0.658666 -0.752436 +0.000000 -0.791354 -0.611358 +0.000000 -0.658666 -0.752436 +0.000000 -0.510754 -0.859727 +0.000000 -0.658666 -0.752436 +0.000000 -0.510754 -0.859727 +0.000000 -0.510754 -0.859727 +0.000000 -0.658666 -0.752436 +0.000000 -0.510754 -0.859727 +0.000000 -0.345789 -0.938312 +0.000000 -0.510754 -0.859727 +0.000000 -0.345789 -0.938312 +0.000000 -0.345789 -0.938312 +0.000000 -0.510754 -0.859727 +0.000000 -0.345789 -0.938312 +0.000000 -0.158432 -0.987370 +0.000000 -0.345789 -0.938312 +0.000000 -0.158432 -0.987370 +0.000000 -0.158432 -0.987370 +0.000000 -0.345789 -0.938312 +0.000000 -0.158432 -0.987370 +0.000000 0.000000 -1.000000 +0.000000 -0.158432 -0.987370 +-0.158432 0.000000 -0.987370 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.112028 -0.112028 -0.987370 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.089773 -0.130543 -0.987370 +0.000000 0.000000 -1.000000 +-0.112028 -0.112028 -0.987370 +-0.089773 -0.130543 -0.987370 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.062926 -0.145400 -0.987370 +0.000000 0.000000 -1.000000 +-0.089773 -0.130543 -0.987370 +-0.062926 -0.145400 -0.987370 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.032464 -0.155070 -0.987370 +0.000000 0.000000 -1.000000 +-0.062926 -0.145400 -0.987370 +-0.032464 -0.155070 -0.987370 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.130543 -0.089773 -0.987370 +-0.112028 -0.112028 -0.987370 +0.000000 0.000000 -1.000000 +-0.130543 -0.089773 -0.987370 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.130543 -0.089773 -0.987370 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.145400 -0.062926 -0.987370 +-0.130543 -0.089773 -0.987370 +0.000000 0.000000 -1.000000 +-0.145400 -0.062926 -0.987370 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.155070 -0.032464 -0.987370 +-0.145400 -0.062926 -0.987370 +0.000000 0.000000 -1.000000 +-0.155070 -0.032464 -0.987370 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -0.158432 -0.987370 +0.000000 0.000000 -1.000000 +-0.032464 -0.155070 -0.987370 +0.000000 -0.158432 -0.987370 +0.000000 0.000000 -1.000000 +-0.070855 -0.338451 -0.938312 +0.000000 -0.158432 -0.987370 +-0.032464 -0.155070 -0.987370 +-0.070855 -0.338451 -0.938312 +0.000000 -0.345789 -0.938312 +0.000000 -0.158432 -0.987370 +-0.104658 -0.499916 -0.859727 +0.000000 -0.345789 -0.938312 +-0.070855 -0.338451 -0.938312 +-0.104658 -0.499916 -0.859727 +0.000000 -0.510754 -0.859727 +0.000000 -0.345789 -0.938312 +-0.134967 -0.644689 -0.752436 +0.000000 -0.510754 -0.859727 +-0.104658 -0.499916 -0.859727 +-0.134967 -0.644689 -0.752436 +0.000000 -0.658666 -0.752436 +0.000000 -0.510754 -0.859727 +-0.162156 -0.774562 -0.611358 +0.000000 -0.658666 -0.752436 +-0.134967 -0.644689 -0.752436 +-0.162156 -0.774562 -0.611358 +0.000000 -0.791354 -0.611358 +0.000000 -0.658666 -0.752436 +-0.162156 -0.774562 -0.611358 +0.000000 -0.878218 -0.478261 +0.000000 -0.791354 -0.611358 +-0.162156 -0.774562 -0.611358 +-0.159803 -0.863556 -0.478261 +0.000000 -0.878218 -0.478261 +-0.162156 -0.774562 -0.611358 +-0.323267 -0.816557 -0.478261 +-0.159803 -0.863556 -0.478261 +-0.314308 -0.726259 -0.611358 +-0.323267 -0.816557 -0.478261 +-0.162156 -0.774562 -0.611358 +-0.314308 -0.726259 -0.611358 +-0.480569 -0.735064 -0.478261 +-0.323267 -0.816557 -0.478261 +-0.448409 -0.652051 -0.611358 +-0.480569 -0.735064 -0.478261 +-0.314308 -0.726259 -0.611358 +-0.448409 -0.652051 -0.611358 +-0.553539 -0.681807 -0.478261 +-0.480569 -0.735064 -0.478261 +-0.559572 -0.559572 -0.611358 +-0.553539 -0.681807 -0.478261 +-0.448409 -0.652051 -0.611358 +-0.559572 -0.559572 -0.611358 +-0.620994 -0.620994 -0.478261 +-0.553539 -0.681807 -0.478261 +-0.652051 -0.448409 -0.611358 +-0.620994 -0.620994 -0.478261 +-0.559572 -0.559572 -0.611358 +-0.652051 -0.448409 -0.611358 +-0.681807 -0.553539 -0.478261 +-0.620994 -0.620994 -0.478261 +-0.652051 -0.448409 -0.611358 +-0.735064 -0.480569 -0.478261 +-0.681807 -0.553539 -0.478261 +-0.726259 -0.314308 -0.611358 +-0.735064 -0.480569 -0.478261 +-0.652051 -0.448409 -0.611358 +-0.726259 -0.314308 -0.611358 +-0.816557 -0.323267 -0.478261 +-0.735064 -0.480569 -0.478261 +-0.774562 -0.162156 -0.611358 +-0.816557 -0.323267 -0.478261 +-0.726259 -0.314308 -0.611358 +-0.774562 -0.162156 -0.611358 +-0.863556 -0.159803 -0.478261 +-0.816557 -0.323267 -0.478261 +-0.863556 -0.159803 -0.478261 +-0.791354 0.000000 -0.611358 +-0.878218 0.000000 -0.478261 +-0.774562 -0.162156 -0.611358 +-0.791354 0.000000 -0.611358 +-0.863556 -0.159803 -0.478261 +-0.644689 -0.134967 -0.752436 +-0.791354 0.000000 -0.611358 +-0.774562 -0.162156 -0.611358 +-0.644689 -0.134967 -0.752436 +-0.658666 0.000000 -0.752436 +-0.791354 0.000000 -0.611358 +-0.499916 -0.104658 -0.859727 +-0.658666 0.000000 -0.752436 +-0.644689 -0.134967 -0.752436 +-0.499916 -0.104658 -0.859727 +-0.510754 0.000000 -0.859727 +-0.658666 0.000000 -0.752436 +-0.338451 -0.070855 -0.938312 +-0.510754 0.000000 -0.859727 +-0.499916 -0.104658 -0.859727 +-0.338451 -0.070855 -0.938312 +-0.345789 0.000000 -0.938312 +-0.510754 0.000000 -0.859727 +-0.155070 -0.032464 -0.987370 +-0.345789 0.000000 -0.938312 +-0.338451 -0.070855 -0.938312 +-0.155070 -0.032464 -0.987370 +-0.158432 0.000000 -0.987370 +-0.345789 0.000000 -0.938312 +0.000000 0.000000 -1.000000 +-0.158432 0.000000 -0.987370 +-0.155070 -0.032464 -0.987370 +-0.774562 -0.162156 -0.611358 +-0.604485 -0.261607 -0.752436 +-0.644689 -0.134967 -0.752436 +-0.604485 -0.261607 -0.752436 +-0.774562 -0.162156 -0.611358 +-0.726259 -0.314308 -0.611358 +-0.644689 -0.134967 -0.752436 +-0.468740 -0.202860 -0.859727 +-0.499916 -0.104658 -0.859727 +-0.468740 -0.202860 -0.859727 +-0.644689 -0.134967 -0.752436 +-0.604485 -0.261607 -0.752436 +-0.499916 -0.104658 -0.859727 +-0.317345 -0.137339 -0.938312 +-0.338451 -0.070855 -0.938312 +-0.317345 -0.137339 -0.938312 +-0.499916 -0.104658 -0.859727 +-0.468740 -0.202860 -0.859727 +-0.338451 -0.070855 -0.938312 +-0.145400 -0.062926 -0.987370 +-0.155070 -0.032464 -0.987370 +-0.145400 -0.062926 -0.987370 +-0.338451 -0.070855 -0.938312 +-0.317345 -0.137339 -0.938312 +-0.726259 -0.314308 -0.611358 +-0.542720 -0.373223 -0.752436 +-0.604485 -0.261607 -0.752436 +-0.542720 -0.373223 -0.752436 +-0.726259 -0.314308 -0.611358 +-0.652051 -0.448409 -0.611358 +-0.604485 -0.261607 -0.752436 +-0.420846 -0.289411 -0.859727 +-0.468740 -0.202860 -0.859727 +-0.420846 -0.289411 -0.859727 +-0.604485 -0.261607 -0.752436 +-0.542720 -0.373223 -0.752436 +-0.652051 -0.448409 -0.611358 +-0.465747 -0.465747 -0.752436 +-0.542720 -0.373223 -0.752436 +-0.465747 -0.465747 -0.752436 +-0.652051 -0.448409 -0.611358 +-0.559572 -0.559572 -0.611358 +-0.542720 -0.373223 -0.752436 +-0.361158 -0.361158 -0.859727 +-0.420846 -0.289411 -0.859727 +-0.361158 -0.361158 -0.859727 +-0.542720 -0.373223 -0.752436 +-0.465747 -0.465747 -0.752436 +-0.468740 -0.202860 -0.859727 +-0.284919 -0.195936 -0.938312 +-0.317345 -0.137339 -0.938312 +-0.284919 -0.195936 -0.938312 +-0.468740 -0.202860 -0.859727 +-0.420846 -0.289411 -0.859727 +-0.317345 -0.137339 -0.938312 +-0.130543 -0.089773 -0.987370 +-0.145400 -0.062926 -0.987370 +-0.130543 -0.089773 -0.987370 +-0.317345 -0.137339 -0.938312 +-0.284919 -0.195936 -0.938312 +-0.420846 -0.289411 -0.859727 +-0.244509 -0.244509 -0.938312 +-0.284919 -0.195936 -0.938312 +-0.244509 -0.244509 -0.938312 +-0.420846 -0.289411 -0.859727 +-0.361158 -0.361158 -0.859727 +-0.284919 -0.195936 -0.938312 +-0.112028 -0.112028 -0.987370 +-0.130543 -0.089773 -0.987370 +-0.112028 -0.112028 -0.987370 +-0.284919 -0.195936 -0.938312 +-0.244509 -0.244509 -0.938312 +-0.559572 -0.559572 -0.611358 +-0.373223 -0.542720 -0.752436 +-0.465747 -0.465747 -0.752436 +-0.373223 -0.542720 -0.752436 +-0.559572 -0.559572 -0.611358 +-0.448409 -0.652051 -0.611358 +-0.465747 -0.465747 -0.752436 +-0.289411 -0.420846 -0.859727 +-0.361158 -0.361158 -0.859727 +-0.289411 -0.420846 -0.859727 +-0.465747 -0.465747 -0.752436 +-0.373223 -0.542720 -0.752436 +-0.448409 -0.652051 -0.611358 +-0.261607 -0.604485 -0.752436 +-0.373223 -0.542720 -0.752436 +-0.261607 -0.604485 -0.752436 +-0.448409 -0.652051 -0.611358 +-0.314308 -0.726259 -0.611358 +-0.373223 -0.542720 -0.752436 +-0.202860 -0.468740 -0.859727 +-0.289411 -0.420846 -0.859727 +-0.202860 -0.468740 -0.859727 +-0.373223 -0.542720 -0.752436 +-0.261607 -0.604485 -0.752436 +-0.361158 -0.361158 -0.859727 +-0.195936 -0.284919 -0.938312 +-0.244509 -0.244509 -0.938312 +-0.195936 -0.284919 -0.938312 +-0.361158 -0.361158 -0.859727 +-0.289411 -0.420846 -0.859727 +-0.244509 -0.244509 -0.938312 +-0.089773 -0.130543 -0.987370 +-0.112028 -0.112028 -0.987370 +-0.089773 -0.130543 -0.987370 +-0.244509 -0.244509 -0.938312 +-0.195936 -0.284919 -0.938312 +-0.289411 -0.420846 -0.859727 +-0.137339 -0.317345 -0.938312 +-0.195936 -0.284919 -0.938312 +-0.137339 -0.317345 -0.938312 +-0.289411 -0.420846 -0.859727 +-0.202860 -0.468740 -0.859727 +-0.195936 -0.284919 -0.938312 +-0.062926 -0.145400 -0.987370 +-0.089773 -0.130543 -0.987370 +-0.062926 -0.145400 -0.987370 +-0.195936 -0.284919 -0.938312 +-0.137339 -0.317345 -0.938312 +-0.314308 -0.726259 -0.611358 +-0.134967 -0.644689 -0.752436 +-0.261607 -0.604485 -0.752436 +-0.134967 -0.644689 -0.752436 +-0.314308 -0.726259 -0.611358 +-0.162156 -0.774562 -0.611358 +-0.261607 -0.604485 -0.752436 +-0.104658 -0.499916 -0.859727 +-0.202860 -0.468740 -0.859727 +-0.104658 -0.499916 -0.859727 +-0.261607 -0.604485 -0.752436 +-0.134967 -0.644689 -0.752436 +-0.202860 -0.468740 -0.859727 +-0.070855 -0.338451 -0.938312 +-0.137339 -0.317345 -0.938312 +-0.070855 -0.338451 -0.938312 +-0.202860 -0.468740 -0.859727 +-0.104658 -0.499916 -0.859727 +-0.137339 -0.317345 -0.938312 +-0.032464 -0.155070 -0.987370 +-0.062926 -0.145400 -0.987370 +-0.032464 -0.155070 -0.987370 +-0.137339 -0.317345 -0.938312 +-0.070855 -0.338451 -0.938312 +0.000000 0.000000 -1.000000 +0.132607 -0.086696 -0.987370 +0.000000 0.000000 -1.000000 +0.000000 0.791354 -0.611358 +0.159803 0.863556 -0.478261 +0.000000 0.878218 -0.478261 +0.147308 -0.058318 -0.987370 +0.000000 0.000000 -1.000000 +0.132607 -0.086696 -0.987370 +0.147308 -0.058318 -0.987370 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.155787 -0.028829 -0.987370 +0.000000 0.000000 -1.000000 +0.147308 -0.058318 -0.987370 +0.155787 -0.028829 -0.987370 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.158432 0.000000 -0.987370 +0.000000 0.000000 -1.000000 +0.155787 -0.028829 -0.987370 +0.158432 0.000000 -0.987370 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.155787 0.028829 -0.987370 +0.000000 0.000000 -1.000000 +0.158432 0.000000 -0.987370 +0.155787 0.028829 -0.987370 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.147308 0.058318 -0.987370 +0.000000 0.000000 -1.000000 +0.155787 0.028829 -0.987370 +0.147308 0.058318 -0.987370 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.132607 0.086696 -0.987370 +0.000000 0.000000 -1.000000 +0.147308 0.058318 -0.987370 +0.132607 0.086696 -0.987370 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.112028 0.112028 -0.987370 +0.000000 0.000000 -1.000000 +0.132607 0.086696 -0.987370 +0.112028 0.112028 -0.987370 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.086696 0.132607 -0.987370 +0.000000 0.000000 -1.000000 +0.112028 0.112028 -0.987370 +0.086696 0.132607 -0.987370 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.058318 0.147308 -0.987370 +0.000000 0.000000 -1.000000 +0.086696 0.132607 -0.987370 +0.058318 0.147308 -0.987370 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.028829 0.155787 -0.987370 +0.000000 0.000000 -1.000000 +0.058318 0.147308 -0.987370 +0.028829 0.155787 -0.987370 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.028829 0.155787 -0.987370 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.028829 0.155787 -0.987370 +0.000000 0.158432 -0.987370 +0.000000 0.000000 -1.000000 +0.062921 0.340016 -0.938312 +0.000000 0.158432 -0.987370 +0.028829 0.155787 -0.987370 +0.062921 0.340016 -0.938312 +0.000000 0.345789 -0.938312 +0.000000 0.158432 -0.987370 +0.092938 0.502227 -0.859727 +0.000000 0.345789 -0.938312 +0.062921 0.340016 -0.938312 +0.092938 0.502227 -0.859727 +0.000000 0.510754 -0.859727 +0.000000 0.345789 -0.938312 +0.092938 0.502227 -0.859727 +0.000000 0.658666 -0.752436 +0.000000 0.510754 -0.859727 +0.119853 0.647669 -0.752436 +0.000000 0.658666 -0.752436 +0.092938 0.502227 -0.859727 +0.143997 0.778143 -0.611358 +0.000000 0.658666 -0.752436 +0.119853 0.647669 -0.752436 +0.143997 0.778143 -0.611358 +0.000000 0.791354 -0.611358 +0.000000 0.658666 -0.752436 +0.143997 0.778143 -0.611358 +0.159803 0.863556 -0.478261 +0.000000 0.791354 -0.611358 +0.143997 0.778143 -0.611358 +0.323267 0.816557 -0.478261 +0.159803 0.863556 -0.478261 +0.291293 0.735792 -0.611358 +0.323267 0.816557 -0.478261 +0.143997 0.778143 -0.611358 +0.291293 0.735792 -0.611358 +0.480569 0.735064 -0.478261 +0.323267 0.816557 -0.478261 +0.433037 0.662360 -0.611358 +0.480569 0.735064 -0.478261 +0.291293 0.735792 -0.611358 +0.433037 0.662360 -0.611358 +0.620994 0.620994 -0.478261 +0.480569 0.735064 -0.478261 +0.559572 0.559572 -0.611358 +0.620994 0.620994 -0.478261 +0.433037 0.662360 -0.611358 +0.559572 0.559572 -0.611358 +0.735064 0.480569 -0.478261 +0.620994 0.620994 -0.478261 +0.662360 0.433037 -0.611358 +0.735064 0.480569 -0.478261 +0.559572 0.559572 -0.611358 +0.662360 0.433037 -0.611358 +0.816557 0.323267 -0.478261 +0.735064 0.480569 -0.478261 +0.735792 0.291293 -0.611358 +0.816557 0.323267 -0.478261 +0.662360 0.433037 -0.611358 +0.735792 0.291293 -0.611358 +0.863556 0.159803 -0.478261 +0.816557 0.323267 -0.478261 +0.778143 0.143997 -0.611358 +0.863556 0.159803 -0.478261 +0.735792 0.291293 -0.611358 +0.778143 0.143997 -0.611358 +0.878218 0.000000 -0.478261 +0.863556 0.159803 -0.478261 +0.791354 0.000000 -0.611358 +0.878218 0.000000 -0.478261 +0.778143 0.143997 -0.611358 +0.791354 0.000000 -0.611358 +0.863556 -0.159803 -0.478261 +0.878218 0.000000 -0.478261 +0.778143 -0.143997 -0.611358 +0.863556 -0.159803 -0.478261 +0.791354 0.000000 -0.611358 +0.778143 -0.143997 -0.611358 +0.816557 -0.323267 -0.478261 +0.863556 -0.159803 -0.478261 +0.735792 -0.291293 -0.611358 +0.816557 -0.323267 -0.478261 +0.778143 -0.143997 -0.611358 +0.735792 -0.291293 -0.611358 +0.735064 -0.480569 -0.478261 +0.816557 -0.323267 -0.478261 +0.662360 -0.433037 -0.611358 +0.735064 -0.480569 -0.478261 +0.735792 -0.291293 -0.611358 +0.662360 -0.433037 -0.611358 +0.620994 -0.620994 -0.478261 +0.735064 -0.480569 -0.478261 +0.559572 -0.559572 -0.611358 +0.620994 -0.620994 -0.478261 +0.662360 -0.433037 -0.611358 +0.559572 -0.559572 -0.611358 +0.480569 -0.735064 -0.478261 +0.620994 -0.620994 -0.478261 +0.433037 -0.662360 -0.611358 +0.480569 -0.735064 -0.478261 +0.559572 -0.559572 -0.611358 +0.433037 -0.662360 -0.611358 +0.323267 -0.816557 -0.478261 +0.480569 -0.735064 -0.478261 +0.291293 -0.735792 -0.611358 +0.323267 -0.816557 -0.478261 +0.433037 -0.662360 -0.611358 +0.291293 -0.735792 -0.611358 +0.159803 -0.863556 -0.478261 +0.323267 -0.816557 -0.478261 +0.143997 -0.778143 -0.611358 +0.159803 -0.863556 -0.478261 +0.291293 -0.735792 -0.611358 +0.143997 -0.778143 -0.611358 +0.000000 -0.878218 -0.478261 +0.159803 -0.863556 -0.478261 +0.143997 -0.778143 -0.611358 +0.000000 -0.791354 -0.611358 +0.000000 -0.878218 -0.478261 +0.119853 -0.647669 -0.752436 +0.000000 -0.791354 -0.611358 +0.143997 -0.778143 -0.611358 +0.119853 -0.647669 -0.752436 +0.000000 -0.658666 -0.752436 +0.000000 -0.791354 -0.611358 +0.119853 -0.647669 -0.752436 +0.000000 -0.510754 -0.859727 +0.000000 -0.658666 -0.752436 +0.092938 -0.502227 -0.859727 +0.000000 -0.510754 -0.859727 +0.119853 -0.647669 -0.752436 +0.062921 -0.340016 -0.938312 +0.000000 -0.510754 -0.859727 +0.092938 -0.502227 -0.859727 +0.062921 -0.340016 -0.938312 +0.000000 -0.345789 -0.938312 +0.000000 -0.510754 -0.859727 +0.028829 -0.155787 -0.987370 +0.000000 -0.345789 -0.938312 +0.062921 -0.340016 -0.938312 +0.028829 -0.155787 -0.987370 +0.000000 -0.158432 -0.987370 +0.000000 -0.345789 -0.938312 +0.028829 -0.155787 -0.987370 +0.000000 0.000000 -1.000000 +0.000000 -0.158432 -0.987370 +0.028829 -0.155787 -0.987370 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.058318 -0.147308 -0.987370 +0.000000 0.000000 -1.000000 +0.028829 -0.155787 -0.987370 +0.058318 -0.147308 -0.987370 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.086696 -0.132607 -0.987370 +0.000000 0.000000 -1.000000 +0.058318 -0.147308 -0.987370 +0.086696 -0.132607 -0.987370 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.112028 -0.112028 -0.987370 +0.000000 0.000000 -1.000000 +0.086696 -0.132607 -0.987370 +0.112028 -0.112028 -0.987370 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.132607 -0.086696 -0.987370 +0.000000 0.000000 -1.000000 +0.112028 -0.112028 -0.987370 +0.143997 -0.778143 -0.611358 +0.242451 -0.612420 -0.752436 +0.119853 -0.647669 -0.752436 +0.242451 -0.612420 -0.752436 +0.143997 -0.778143 -0.611358 +0.291293 -0.735792 -0.611358 +0.119853 -0.647669 -0.752436 +0.188006 -0.474893 -0.859727 +0.092938 -0.502227 -0.859727 +0.188006 -0.474893 -0.859727 +0.119853 -0.647669 -0.752436 +0.242451 -0.612420 -0.752436 +0.092938 -0.502227 -0.859727 +0.127283 -0.321510 -0.938312 +0.062921 -0.340016 -0.938312 +0.127283 -0.321510 -0.938312 +0.092938 -0.502227 -0.859727 +0.188006 -0.474893 -0.859727 +0.062921 -0.340016 -0.938312 +0.058318 -0.147308 -0.987370 +0.028829 -0.155787 -0.987370 +0.058318 -0.147308 -0.987370 +0.062921 -0.340016 -0.938312 +0.127283 -0.321510 -0.938312 +0.291293 -0.735792 -0.611358 +0.360428 -0.551300 -0.752436 +0.242451 -0.612420 -0.752436 +0.360428 -0.551300 -0.752436 +0.291293 -0.735792 -0.611358 +0.433037 -0.662360 -0.611358 +0.242451 -0.612420 -0.752436 +0.279490 -0.427499 -0.859727 +0.188006 -0.474893 -0.859727 +0.279490 -0.427499 -0.859727 +0.242451 -0.612420 -0.752436 +0.360428 -0.551300 -0.752436 +0.188006 -0.474893 -0.859727 +0.189219 -0.289423 -0.938312 +0.127283 -0.321510 -0.938312 +0.189219 -0.289423 -0.938312 +0.188006 -0.474893 -0.859727 +0.279490 -0.427499 -0.859727 +0.127283 -0.321510 -0.938312 +0.086696 -0.132607 -0.987370 +0.058318 -0.147308 -0.987370 +0.086696 -0.132607 -0.987370 +0.127283 -0.321510 -0.938312 +0.189219 -0.289423 -0.938312 +0.433037 -0.662360 -0.611358 +0.465747 -0.465747 -0.752436 +0.360428 -0.551300 -0.752436 +0.465747 -0.465747 -0.752436 +0.433037 -0.662360 -0.611358 +0.559572 -0.559572 -0.611358 +0.360428 -0.551300 -0.752436 +0.361158 -0.361158 -0.859727 +0.279490 -0.427499 -0.859727 +0.361158 -0.361158 -0.859727 +0.360428 -0.551300 -0.752436 +0.465747 -0.465747 -0.752436 +0.279490 -0.427499 -0.859727 +0.244509 -0.244509 -0.938312 +0.189219 -0.289423 -0.938312 +0.244509 -0.244509 -0.938312 +0.279490 -0.427499 -0.859727 +0.361158 -0.361158 -0.859727 +0.189219 -0.289423 -0.938312 +0.112028 -0.112028 -0.987370 +0.086696 -0.132607 -0.987370 +0.112028 -0.112028 -0.987370 +0.189219 -0.289423 -0.938312 +0.244509 -0.244509 -0.938312 +0.559572 -0.559572 -0.611358 +0.551300 -0.360428 -0.752436 +0.465747 -0.465747 -0.752436 +0.551300 -0.360428 -0.752436 +0.559572 -0.559572 -0.611358 +0.662360 -0.433037 -0.611358 +0.465747 -0.465747 -0.752436 +0.427499 -0.279490 -0.859727 +0.361158 -0.361158 -0.859727 +0.427499 -0.279490 -0.859727 +0.465747 -0.465747 -0.752436 +0.551300 -0.360428 -0.752436 +0.361158 -0.361158 -0.859727 +0.289423 -0.189219 -0.938312 +0.244509 -0.244509 -0.938312 +0.289423 -0.189219 -0.938312 +0.361158 -0.361158 -0.859727 +0.427499 -0.279490 -0.859727 +0.244509 -0.244509 -0.938312 +0.132607 -0.086696 -0.987370 +0.112028 -0.112028 -0.987370 +0.132607 -0.086696 -0.987370 +0.244509 -0.244509 -0.938312 +0.289423 -0.189219 -0.938312 +0.662360 -0.433037 -0.611358 +0.612420 -0.242451 -0.752436 +0.551300 -0.360428 -0.752436 +0.612420 -0.242451 -0.752436 +0.662360 -0.433037 -0.611358 +0.735792 -0.291293 -0.611358 +0.551300 -0.360428 -0.752436 +0.474893 -0.188006 -0.859727 +0.427499 -0.279490 -0.859727 +0.474893 -0.188006 -0.859727 +0.551300 -0.360428 -0.752436 +0.612420 -0.242451 -0.752436 +0.427499 -0.279490 -0.859727 +0.321510 -0.127283 -0.938312 +0.289423 -0.189219 -0.938312 +0.321510 -0.127283 -0.938312 +0.427499 -0.279490 -0.859727 +0.474893 -0.188006 -0.859727 +0.289423 -0.189219 -0.938312 +0.147308 -0.058318 -0.987370 +0.132607 -0.086696 -0.987370 +0.147308 -0.058318 -0.987370 +0.289423 -0.189219 -0.938312 +0.321510 -0.127283 -0.938312 +0.735792 -0.291293 -0.611358 +0.647669 -0.119853 -0.752436 +0.612420 -0.242451 -0.752436 +0.647669 -0.119853 -0.752436 +0.735792 -0.291293 -0.611358 +0.778143 -0.143997 -0.611358 +0.612420 -0.242451 -0.752436 +0.502227 -0.092938 -0.859727 +0.474893 -0.188006 -0.859727 +0.502227 -0.092938 -0.859727 +0.612420 -0.242451 -0.752436 +0.647669 -0.119853 -0.752436 +0.778143 -0.143997 -0.611358 +0.658666 0.000000 -0.752436 +0.647669 -0.119853 -0.752436 +0.658666 0.000000 -0.752436 +0.778143 -0.143997 -0.611358 +0.791354 0.000000 -0.611358 +0.647669 -0.119853 -0.752436 +0.510754 0.000000 -0.859727 +0.502227 -0.092938 -0.859727 +0.510754 0.000000 -0.859727 +0.647669 -0.119853 -0.752436 +0.658666 0.000000 -0.752436 +0.474893 -0.188006 -0.859727 +0.340016 -0.062921 -0.938312 +0.321510 -0.127283 -0.938312 +0.340016 -0.062921 -0.938312 +0.474893 -0.188006 -0.859727 +0.502227 -0.092938 -0.859727 +0.321510 -0.127283 -0.938312 +0.155787 -0.028829 -0.987370 +0.147308 -0.058318 -0.987370 +0.155787 -0.028829 -0.987370 +0.321510 -0.127283 -0.938312 +0.340016 -0.062921 -0.938312 +0.502227 -0.092938 -0.859727 +0.345789 0.000000 -0.938312 +0.340016 -0.062921 -0.938312 +0.345789 0.000000 -0.938312 +0.502227 -0.092938 -0.859727 +0.510754 0.000000 -0.859727 +0.340016 -0.062921 -0.938312 +0.158432 0.000000 -0.987370 +0.155787 -0.028829 -0.987370 +0.158432 0.000000 -0.987370 +0.340016 -0.062921 -0.938312 +0.345789 0.000000 -0.938312 +0.791354 0.000000 -0.611358 +0.647669 0.119853 -0.752436 +0.658666 0.000000 -0.752436 +0.647669 0.119853 -0.752436 +0.791354 0.000000 -0.611358 +0.778143 0.143997 -0.611358 +0.658666 0.000000 -0.752436 +0.502227 0.092938 -0.859727 +0.510754 0.000000 -0.859727 +0.502227 0.092938 -0.859727 +0.658666 0.000000 -0.752436 +0.647669 0.119853 -0.752436 +0.778143 0.143997 -0.611358 +0.612420 0.242451 -0.752436 +0.647669 0.119853 -0.752436 +0.612420 0.242451 -0.752436 +0.778143 0.143997 -0.611358 +0.735792 0.291293 -0.611358 +0.647669 0.119853 -0.752436 +0.474893 0.188006 -0.859727 +0.502227 0.092938 -0.859727 +0.474893 0.188006 -0.859727 +0.647669 0.119853 -0.752436 +0.612420 0.242451 -0.752436 +0.510754 0.000000 -0.859727 +0.340016 0.062921 -0.938312 +0.345789 0.000000 -0.938312 +0.340016 0.062921 -0.938312 +0.510754 0.000000 -0.859727 +0.502227 0.092938 -0.859727 +0.345789 0.000000 -0.938312 +0.155787 0.028829 -0.987370 +0.158432 0.000000 -0.987370 +0.155787 0.028829 -0.987370 +0.345789 0.000000 -0.938312 +0.340016 0.062921 -0.938312 +0.502227 0.092938 -0.859727 +0.321510 0.127283 -0.938312 +0.340016 0.062921 -0.938312 +0.321510 0.127283 -0.938312 +0.502227 0.092938 -0.859727 +0.474893 0.188006 -0.859727 +0.340016 0.062921 -0.938312 +0.147308 0.058318 -0.987370 +0.155787 0.028829 -0.987370 +0.147308 0.058318 -0.987370 +0.340016 0.062921 -0.938312 +0.321510 0.127283 -0.938312 +0.735792 0.291293 -0.611358 +0.551300 0.360428 -0.752436 +0.612420 0.242451 -0.752436 +0.551300 0.360428 -0.752436 +0.735792 0.291293 -0.611358 +0.662360 0.433037 -0.611358 +0.612420 0.242451 -0.752436 +0.427499 0.279490 -0.859727 +0.474893 0.188006 -0.859727 +0.427499 0.279490 -0.859727 +0.612420 0.242451 -0.752436 +0.551300 0.360428 -0.752436 +0.474893 0.188006 -0.859727 +0.289423 0.189219 -0.938312 +0.321510 0.127283 -0.938312 +0.289423 0.189219 -0.938312 +0.474893 0.188006 -0.859727 +0.427499 0.279490 -0.859727 +0.321510 0.127283 -0.938312 +0.132607 0.086696 -0.987370 +0.147308 0.058318 -0.987370 +0.132607 0.086696 -0.987370 +0.321510 0.127283 -0.938312 +0.289423 0.189219 -0.938312 +0.662360 0.433037 -0.611358 +0.465747 0.465747 -0.752436 +0.551300 0.360428 -0.752436 +0.465747 0.465747 -0.752436 +0.662360 0.433037 -0.611358 +0.559572 0.559572 -0.611358 +0.551300 0.360428 -0.752436 +0.361158 0.361158 -0.859727 +0.427499 0.279490 -0.859727 +0.361158 0.361158 -0.859727 +0.551300 0.360428 -0.752436 +0.465747 0.465747 -0.752436 +0.427499 0.279490 -0.859727 +0.244509 0.244509 -0.938312 +0.289423 0.189219 -0.938312 +0.244509 0.244509 -0.938312 +0.427499 0.279490 -0.859727 +0.361158 0.361158 -0.859727 +0.289423 0.189219 -0.938312 +0.112028 0.112028 -0.987370 +0.132607 0.086696 -0.987370 +0.112028 0.112028 -0.987370 +0.289423 0.189219 -0.938312 +0.244509 0.244509 -0.938312 +0.559572 0.559572 -0.611358 +0.360428 0.551300 -0.752436 +0.465747 0.465747 -0.752436 +0.360428 0.551300 -0.752436 +0.559572 0.559572 -0.611358 +0.433037 0.662360 -0.611358 +0.465747 0.465747 -0.752436 +0.279490 0.427499 -0.859727 +0.361158 0.361158 -0.859727 +0.279490 0.427499 -0.859727 +0.465747 0.465747 -0.752436 +0.360428 0.551300 -0.752436 +0.361158 0.361158 -0.859727 +0.189219 0.289423 -0.938312 +0.244509 0.244509 -0.938312 +0.189219 0.289423 -0.938312 +0.361158 0.361158 -0.859727 +0.279490 0.427499 -0.859727 +0.244509 0.244509 -0.938312 +0.086696 0.132607 -0.987370 +0.112028 0.112028 -0.987370 +0.086696 0.132607 -0.987370 +0.244509 0.244509 -0.938312 +0.189219 0.289423 -0.938312 +0.433037 0.662360 -0.611358 +0.242451 0.612420 -0.752436 +0.360428 0.551300 -0.752436 +0.242451 0.612420 -0.752436 +0.433037 0.662360 -0.611358 +0.291293 0.735792 -0.611358 +0.360428 0.551300 -0.752436 +0.188006 0.474893 -0.859727 +0.279490 0.427499 -0.859727 +0.188006 0.474893 -0.859727 +0.360428 0.551300 -0.752436 +0.242451 0.612420 -0.752436 +0.279490 0.427499 -0.859727 +0.127283 0.321510 -0.938312 +0.189219 0.289423 -0.938312 +0.127283 0.321510 -0.938312 +0.279490 0.427499 -0.859727 +0.188006 0.474893 -0.859727 +0.189219 0.289423 -0.938312 +0.058318 0.147308 -0.987370 +0.086696 0.132607 -0.987370 +0.058318 0.147308 -0.987370 +0.189219 0.289423 -0.938312 +0.127283 0.321510 -0.938312 +0.291293 0.735792 -0.611358 +0.119853 0.647669 -0.752436 +0.242451 0.612420 -0.752436 +0.119853 0.647669 -0.752436 +0.291293 0.735792 -0.611358 +0.143997 0.778143 -0.611358 +0.242451 0.612420 -0.752436 +0.092938 0.502227 -0.859727 +0.188006 0.474893 -0.859727 +0.092938 0.502227 -0.859727 +0.242451 0.612420 -0.752436 +0.119853 0.647669 -0.752436 +0.188006 0.474893 -0.859727 +0.062921 0.340016 -0.938312 +0.127283 0.321510 -0.938312 +0.062921 0.340016 -0.938312 +0.188006 0.474893 -0.859727 +0.092938 0.502227 -0.859727 +0.127283 0.321510 -0.938312 +0.028829 0.155787 -0.987370 +0.058318 0.147308 -0.987370 +0.028829 0.155787 -0.987370 +0.127283 0.321510 -0.938312 +0.062921 0.340016 -0.938312 +0.000000 0.878218 -0.478261 +0.000000 0.791354 -0.611358 +0.000000 0.878218 -0.478261 +0.000000 0.158432 -0.987370 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.158432 -0.987370 +0.000000 0.158432 -0.987370 +0.000000 0.000000 -1.000000 +0.000000 0.158432 -0.987370 +0.000000 0.345789 -0.938312 +0.000000 0.158432 -0.987370 +0.000000 0.345789 -0.938312 +0.000000 0.345789 -0.938312 +0.000000 0.158432 -0.987370 +0.000000 0.345789 -0.938312 +0.000000 0.510754 -0.859727 +0.000000 0.345789 -0.938312 +0.000000 0.510754 -0.859727 +0.000000 0.510754 -0.859727 +0.000000 0.345789 -0.938312 +0.000000 0.510754 -0.859727 +0.000000 0.658666 -0.752436 +0.000000 0.510754 -0.859727 +0.000000 0.658666 -0.752436 +0.000000 0.658666 -0.752436 +0.000000 0.510754 -0.859727 +0.000000 0.658666 -0.752436 +0.000000 0.791354 -0.611358 +0.000000 0.658666 -0.752436 +0.000000 0.791354 -0.611358 +0.000000 0.791354 -0.611358 +0.000000 0.658666 -0.752436 +0.000000 0.791354 -0.611358 +0.000000 0.878218 -0.478261 +0.000000 0.791354 -0.611358 +-0.072029 -0.381185 0.921688 +-0.141383 -0.345101 0.927856 +-0.147066 -0.358974 0.921688 +-0.378068 -0.086922 0.921688 +-0.197990 -0.008553 0.980167 +-0.387634 -0.015186 0.921688 +-0.205254 -0.311376 0.927856 +-0.147066 -0.358974 0.921688 +-0.141383 -0.345101 0.927856 +-0.205254 -0.311376 0.927856 +-0.213504 -0.323892 0.921688 +-0.147066 -0.358974 0.921688 +-0.258486 -0.268829 0.927856 +-0.213504 -0.323892 0.921688 +-0.205254 -0.311376 0.927856 +-0.258486 -0.268829 0.927856 +-0.268877 -0.279635 0.921688 +-0.213504 -0.323892 0.921688 +-0.303088 -0.217306 0.927856 +-0.268877 -0.279635 0.921688 +-0.258486 -0.268829 0.927856 +-0.303088 -0.217306 0.927856 +-0.315271 -0.226041 0.921688 +-0.268877 -0.279635 0.921688 +-0.303088 -0.217306 0.927856 +-0.352931 -0.161030 0.921688 +-0.315271 -0.226041 0.921688 +-0.339292 -0.154807 0.927856 +-0.352931 -0.161030 0.921688 +-0.303088 -0.217306 0.927856 +-0.363458 -0.083563 0.927856 +-0.352931 -0.161030 0.921688 +-0.339292 -0.154807 0.927856 +-0.363458 -0.083563 0.927856 +-0.378068 -0.086922 0.921688 +-0.352931 -0.161030 0.921688 +-0.363458 -0.083563 0.927856 +-0.197990 -0.008553 0.980167 +-0.378068 -0.086922 0.921688 +-0.192847 -0.044337 0.980227 +-0.197990 -0.008553 0.980167 +-0.363458 -0.083563 0.927856 +-0.192847 -0.044337 0.980227 +0.000000 0.000000 1.000000 +-0.197990 -0.008553 0.980167 +-0.015798 -0.003632 0.999869 +0.000000 0.000000 1.000000 +-0.192847 -0.044337 0.980227 +-0.015798 -0.003632 0.999869 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.014747 -0.006729 0.999869 +0.000000 0.000000 1.000000 +-0.015798 -0.003632 0.999869 +-0.014747 -0.006729 0.999869 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.013174 -0.009445 0.999869 +0.000000 0.000000 1.000000 +-0.014747 -0.006729 0.999869 +-0.013174 -0.009445 0.999869 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.011235 -0.011685 0.999869 +0.000000 0.000000 1.000000 +-0.013174 -0.009445 0.999869 +-0.011235 -0.011685 0.999869 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.011235 -0.011685 0.999869 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.008921 -0.013534 0.999869 +0.000000 0.000000 1.000000 +-0.011235 -0.011685 0.999869 +-0.008921 -0.013534 0.999869 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.006145 -0.015000 0.999869 +0.000000 0.000000 1.000000 +-0.008921 -0.013534 0.999869 +-0.003010 -0.015928 0.999869 +0.000000 0.000000 1.000000 +-0.006145 -0.015000 0.999869 +-0.003010 -0.015928 0.999869 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.003010 -0.015928 0.999869 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.003010 -0.015928 0.999869 +0.000000 -0.016210 0.999869 +0.000000 0.000000 1.000000 +-0.003010 -0.015928 0.999869 +0.000000 -0.197878 0.980227 +0.000000 -0.016210 0.999869 +-0.036741 -0.194437 0.980227 +0.000000 -0.197878 0.980227 +-0.003010 -0.015928 0.999869 +-0.036741 -0.194437 0.980227 +0.000000 -0.372940 0.927856 +0.000000 -0.197878 0.980227 +-0.069246 -0.366455 0.927856 +0.000000 -0.372940 0.927856 +-0.036741 -0.194437 0.980227 +-0.069246 -0.366455 0.927856 +0.000000 -0.387931 0.921688 +0.000000 -0.372940 0.927856 +-0.069246 -0.366455 0.927856 +-0.072029 -0.381185 0.921688 +0.000000 -0.387931 0.921688 +-0.141383 -0.345101 0.927856 +-0.072029 -0.381185 0.921688 +-0.069246 -0.366455 0.927856 +-0.363458 -0.083563 0.927856 +-0.180025 -0.082139 0.980227 +-0.192847 -0.044337 0.980227 +-0.180025 -0.082139 0.980227 +-0.363458 -0.083563 0.927856 +-0.339292 -0.154807 0.927856 +-0.339292 -0.154807 0.927856 +-0.160815 -0.115301 0.980227 +-0.180025 -0.082139 0.980227 +-0.160815 -0.115301 0.980227 +-0.339292 -0.154807 0.927856 +-0.303088 -0.217306 0.927856 +-0.303088 -0.217306 0.927856 +-0.137150 -0.142638 0.980227 +-0.160815 -0.115301 0.980227 +-0.137150 -0.142638 0.980227 +-0.303088 -0.217306 0.927856 +-0.258486 -0.268829 0.927856 +-0.192847 -0.044337 0.980227 +-0.014747 -0.006729 0.999869 +-0.015798 -0.003632 0.999869 +-0.014747 -0.006729 0.999869 +-0.192847 -0.044337 0.980227 +-0.180025 -0.082139 0.980227 +-0.180025 -0.082139 0.980227 +-0.013174 -0.009445 0.999869 +-0.014747 -0.006729 0.999869 +-0.013174 -0.009445 0.999869 +-0.180025 -0.082139 0.980227 +-0.160815 -0.115301 0.980227 +-0.160815 -0.115301 0.980227 +-0.011235 -0.011685 0.999869 +-0.013174 -0.009445 0.999869 +-0.011235 -0.011685 0.999869 +-0.160815 -0.115301 0.980227 +-0.137150 -0.142638 0.980227 +-0.258486 -0.268829 0.927856 +-0.108906 -0.165213 0.980227 +-0.137150 -0.142638 0.980227 +-0.108906 -0.165213 0.980227 +-0.258486 -0.268829 0.927856 +-0.205254 -0.311376 0.927856 +-0.205254 -0.311376 0.927856 +-0.075016 -0.183107 0.980227 +-0.108906 -0.165213 0.980227 +-0.075016 -0.183107 0.980227 +-0.205254 -0.311376 0.927856 +-0.141383 -0.345101 0.927856 +-0.141383 -0.345101 0.927856 +-0.036741 -0.194437 0.980227 +-0.075016 -0.183107 0.980227 +-0.036741 -0.194437 0.980227 +-0.141383 -0.345101 0.927856 +-0.069246 -0.366455 0.927856 +-0.137150 -0.142638 0.980227 +-0.008921 -0.013534 0.999869 +-0.011235 -0.011685 0.999869 +-0.008921 -0.013534 0.999869 +-0.137150 -0.142638 0.980227 +-0.108906 -0.165213 0.980227 +-0.108906 -0.165213 0.980227 +-0.006145 -0.015000 0.999869 +-0.008921 -0.013534 0.999869 +-0.006145 -0.015000 0.999869 +-0.108906 -0.165213 0.980227 +-0.075016 -0.183107 0.980227 +-0.075016 -0.183107 0.980227 +-0.003010 -0.015928 0.999869 +-0.006145 -0.015000 0.999869 +-0.003010 -0.015928 0.999869 +-0.075016 -0.183107 0.980227 +-0.036741 -0.194437 0.980227 +0.000000 1.000000 0.000000 +0.185711 0.982604 0.000000 +0.000000 1.000000 0.000000 +0.974582 0.224029 0.000000 +0.999234 0.039145 0.000000 +0.999234 0.039142 0.000000 +0.974582 0.224029 0.000000 +0.974582 0.224029 0.000000 +0.999234 0.039145 0.000000 +0.909791 0.415066 0.000000 +0.974582 0.224029 0.000000 +0.974582 0.224029 0.000000 +0.909791 0.415066 0.000000 +0.909791 0.415066 0.000000 +0.974582 0.224029 0.000000 +0.909791 0.415066 0.000000 +0.812720 0.582655 0.000000 +0.909791 0.415066 0.000000 +0.812720 0.582655 0.000000 +0.812720 0.582655 0.000000 +0.909791 0.415066 0.000000 +0.693130 0.720813 0.000000 +0.812720 0.582655 0.000000 +0.812720 0.582655 0.000000 +0.693130 0.720813 0.000000 +0.693130 0.720813 0.000000 +0.812720 0.582655 0.000000 +0.550397 0.834903 0.000000 +0.693130 0.720813 0.000000 +0.693130 0.720813 0.000000 +0.550397 0.834903 0.000000 +0.550397 0.834903 0.000000 +0.693130 0.720813 0.000000 +0.379137 0.925341 0.000000 +0.550397 0.834903 0.000000 +0.550397 0.834903 0.000000 +0.379137 0.925341 0.000000 +0.379137 0.925341 0.000000 +0.550397 0.834903 0.000000 +0.185711 0.982604 0.000000 +0.379137 0.925341 0.000000 +0.379137 0.925341 0.000000 +0.185711 0.982604 0.000000 +0.185711 0.982604 0.000000 +0.379137 0.925341 0.000000 +0.185711 0.982604 0.000000 +0.000000 1.000000 0.000000 +0.185711 0.982604 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +-0.999962 0.000000 0.008727 +-0.983268 0.181956 0.008727 +-0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.983268 0.181956 0.008727 +0.999962 0.000000 0.008727 +0.983268 0.181956 0.008727 +0.983268 0.181956 0.008727 +0.999962 0.000000 0.008727 +0.983268 0.181956 0.008727 +0.929753 0.368081 0.008727 +0.983268 0.181956 0.008727 +0.929753 0.368081 0.008727 +0.929753 0.368081 0.008727 +0.983268 0.181956 0.008727 +0.929753 0.368081 0.008727 +0.836964 0.547189 0.008727 +0.929753 0.368081 0.008727 +0.836964 0.547189 0.008727 +0.836964 0.547189 0.008727 +0.929753 0.368081 0.008727 +0.836964 0.547189 0.008727 +0.707080 0.707080 0.008727 +0.836964 0.547189 0.008727 +0.707080 0.707080 0.008727 +0.707080 0.707080 0.008727 +0.836964 0.547189 0.008727 +0.707080 0.707080 0.008727 +0.547189 0.836964 0.008727 +0.707080 0.707080 0.008727 +0.547189 0.836964 0.008727 +0.547189 0.836964 0.008727 +0.707080 0.707080 0.008727 +0.547189 0.836964 0.008727 +0.368081 0.929753 0.008727 +0.547189 0.836964 0.008727 +0.368081 0.929753 0.008727 +0.368081 0.929753 0.008727 +0.547189 0.836964 0.008727 +0.368081 0.929753 0.008727 +0.181956 0.983268 0.008727 +0.368081 0.929753 0.008727 +0.181956 0.983268 0.008727 +0.181956 0.983268 0.008727 +0.368081 0.929753 0.008727 +0.181956 0.983268 0.008727 +0.000000 0.999962 0.008727 +0.181956 0.983268 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.181956 0.983268 0.008727 +0.000000 0.999962 0.008727 +-0.181956 0.983268 0.008727 +0.000000 0.999962 0.008727 +-0.181956 0.983268 0.008727 +-0.181956 0.983268 0.008727 +0.000000 0.999962 0.008727 +-0.181956 0.983268 0.008727 +-0.368081 0.929753 0.008727 +-0.181956 0.983268 0.008727 +-0.368081 0.929753 0.008727 +-0.368081 0.929753 0.008727 +-0.181956 0.983268 0.008727 +-0.368081 0.929753 0.008727 +-0.547189 0.836964 0.008727 +-0.368081 0.929753 0.008727 +-0.547189 0.836964 0.008727 +-0.547189 0.836964 0.008727 +-0.368081 0.929753 0.008727 +-0.547189 0.836964 0.008727 +-0.707080 0.707080 0.008727 +-0.547189 0.836964 0.008727 +-0.707080 0.707080 0.008727 +-0.707080 0.707080 0.008727 +-0.547189 0.836964 0.008727 +-0.707080 0.707080 0.008727 +-0.836964 0.547189 0.008727 +-0.707080 0.707080 0.008727 +-0.836964 0.547189 0.008727 +-0.836964 0.547189 0.008727 +-0.707080 0.707080 0.008727 +-0.836964 0.547189 0.008727 +-0.929753 0.368081 0.008727 +-0.836964 0.547189 0.008727 +-0.929753 0.368081 0.008727 +-0.929753 0.368081 0.008727 +-0.836964 0.547189 0.008727 +-0.929753 0.368081 0.008727 +-0.983268 0.181956 0.008727 +-0.929753 0.368081 0.008727 +-0.983268 0.181956 0.008727 +-0.983268 0.181956 0.008727 +-0.929753 0.368081 0.008727 +-0.983268 0.181956 0.008727 +-0.999962 0.000000 0.008727 +-0.983268 0.181956 0.008727 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.204909 0.978781 0.000000 +0.000000 1.000000 0.000000 +0.368095 0.929788 0.000000 +0.204909 0.978781 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.397177 0.917742 0.000000 +0.204909 0.978781 0.000000 +0.547210 0.836995 0.000000 +0.397177 0.917742 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.566635 0.823969 0.000000 +0.397177 0.917742 0.000000 +0.630298 0.776353 0.000000 +0.566635 0.823969 0.000000 +0.547210 0.836995 0.000000 +0.630298 0.776353 0.000000 +0.707107 0.707107 0.000000 +0.566635 0.823969 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.630298 0.776353 0.000000 +0.776353 0.630298 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.776353 0.630298 0.000000 +0.823969 0.566635 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.823969 0.566635 0.000000 +0.776353 0.630298 0.000000 +0.836995 0.547210 0.000000 +0.917742 0.397177 0.000000 +0.823969 0.566635 0.000000 +0.929788 0.368095 0.000000 +0.917742 0.397177 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.978781 0.204909 0.000000 +0.917742 0.397177 0.000000 +0.983305 0.181963 0.000000 +0.978781 0.204909 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.978781 0.204909 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.204909 -0.978781 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.204909 -0.978781 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.204909 -0.978781 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.397177 -0.917742 0.000000 +0.368095 -0.929788 0.000000 +0.204909 -0.978781 0.000000 +0.397177 -0.917742 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.566635 -0.823969 0.000000 +0.547210 -0.836995 0.000000 +0.397177 -0.917742 0.000000 +0.566635 -0.823969 0.000000 +0.630298 -0.776353 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.630298 -0.776353 0.000000 +0.566635 -0.823969 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.630298 -0.776353 0.000000 +0.707107 -0.707107 0.000000 +0.776353 -0.630298 0.000000 +0.707107 -0.707107 0.000000 +0.823969 -0.566635 0.000000 +0.776353 -0.630298 0.000000 +0.707107 -0.707107 0.000000 +0.823969 -0.566635 0.000000 +0.836995 -0.547210 0.000000 +0.776353 -0.630298 0.000000 +0.917742 -0.397177 0.000000 +0.836995 -0.547210 0.000000 +0.823969 -0.566635 0.000000 +0.917742 -0.397177 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.978781 -0.204909 0.000000 +0.929788 -0.368095 0.000000 +0.917742 -0.397177 0.000000 +0.978781 -0.204909 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.978781 -0.204909 0.000000 +-0.204909 0.978781 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.978781 0.204909 0.000000 +-1.000000 0.000000 0.000000 +-0.978781 0.204909 0.000000 +-0.978781 0.204909 0.000000 +-1.000000 0.000000 0.000000 +-0.917742 0.397177 0.000000 +-0.978781 0.204909 0.000000 +-0.978781 0.204909 0.000000 +-0.917742 0.397177 0.000000 +-0.917742 0.397177 0.000000 +-0.978781 0.204909 0.000000 +-0.823969 0.566635 0.000000 +-0.917742 0.397177 0.000000 +-0.917742 0.397177 0.000000 +-0.823969 0.566635 0.000000 +-0.823969 0.566635 0.000000 +-0.917742 0.397177 0.000000 +-0.707107 0.707107 0.000000 +-0.823969 0.566635 0.000000 +-0.823969 0.566635 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.823969 0.566635 0.000000 +-0.566635 0.823969 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.566635 0.823969 0.000000 +-0.566635 0.823969 0.000000 +-0.707107 0.707107 0.000000 +-0.566635 0.823969 0.000000 +-0.397177 0.917742 0.000000 +-0.566635 0.823969 0.000000 +-0.397177 0.917742 0.000000 +-0.397177 0.917742 0.000000 +-0.566635 0.823969 0.000000 +-0.397177 0.917742 0.000000 +-0.204909 0.978781 0.000000 +-0.397177 0.917742 0.000000 +-0.204909 0.978781 0.000000 +-0.204909 0.978781 0.000000 +-0.397177 0.917742 0.000000 +0.000000 1.000000 0.000000 +-0.204909 0.978781 0.000000 +-0.204909 0.978781 0.000000 +-0.204909 -0.978781 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.978781 -0.204909 0.000000 +-1.000000 0.000000 0.000000 +-0.978781 -0.204909 0.000000 +-0.978781 -0.204909 0.000000 +-1.000000 0.000000 0.000000 +-0.917742 -0.397177 0.000000 +-0.978781 -0.204909 0.000000 +-0.978781 -0.204909 0.000000 +-0.917742 -0.397177 0.000000 +-0.917742 -0.397177 0.000000 +-0.978781 -0.204909 0.000000 +-0.823969 -0.566635 0.000000 +-0.917742 -0.397177 0.000000 +-0.917742 -0.397177 0.000000 +-0.823969 -0.566635 0.000000 +-0.823969 -0.566635 0.000000 +-0.917742 -0.397177 0.000000 +-0.707107 -0.707107 0.000000 +-0.823969 -0.566635 0.000000 +-0.823969 -0.566635 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.823969 -0.566635 0.000000 +-0.707107 -0.707107 0.000000 +-0.566635 -0.823969 0.000000 +-0.707107 -0.707107 0.000000 +-0.566635 -0.823969 0.000000 +-0.566635 -0.823969 0.000000 +-0.707107 -0.707107 0.000000 +-0.566635 -0.823969 0.000000 +-0.397177 -0.917742 0.000000 +-0.566635 -0.823969 0.000000 +-0.397177 -0.917742 0.000000 +-0.397177 -0.917742 0.000000 +-0.566635 -0.823969 0.000000 +-0.204909 -0.978781 0.000000 +-0.397177 -0.917742 0.000000 +-0.397177 -0.917742 0.000000 +-0.204909 -0.978781 0.000000 +-0.204909 -0.978781 0.000000 +-0.397177 -0.917742 0.000000 +0.000000 -1.000000 0.000000 +-0.204909 -0.978781 0.000000 +-0.204909 -0.978781 0.000000 +0.866025 -0.500000 0.000000 +0.866025 -0.500000 0.000000 +0.866025 -0.500000 0.000000 +0.866025 -0.500000 0.000000 +0.866025 -0.500000 0.000000 +0.866025 -0.500000 0.000000 +0.866025 -0.500000 0.000000 +0.866025 -0.500000 0.000000 +0.866025 -0.500000 0.000000 +0.500000 0.866025 0.000000 +0.500000 0.866025 0.000000 +0.500000 0.866025 0.000000 +0.500000 0.866025 0.000000 +0.500000 0.866025 0.000000 +0.500000 0.866025 0.000000 +-0.866025 0.500000 0.000000 +-0.866025 0.500000 0.000000 +-0.866025 0.500000 0.000000 +-0.866025 0.500000 0.000000 +-0.866025 0.500000 0.000000 +-0.866025 0.500000 0.000000 +-0.866025 0.500000 0.000000 +-0.866025 0.500000 0.000000 +-0.866025 0.500000 0.000000 +-0.500000 -0.866025 0.000000 +-0.500000 -0.866025 0.000000 +-0.500000 -0.866025 0.000000 +-0.500000 -0.866025 0.000000 +-0.500000 -0.866025 0.000000 +-0.500000 -0.866025 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.866025 -0.500000 0.000000 +-0.866025 -0.500000 0.000000 +-0.866025 -0.500000 0.000000 +-0.866025 -0.500000 0.000000 +-0.866025 -0.500000 0.000000 +-0.866025 -0.500000 0.000000 +-0.866025 -0.500000 0.000000 +-0.866025 -0.500000 0.000000 +-0.866025 -0.500000 0.000000 +0.500000 -0.866025 0.000000 +0.500000 -0.866025 0.000000 +0.500000 -0.866025 0.000000 +0.500000 -0.866025 0.000000 +0.500000 -0.866025 0.000000 +0.500000 -0.866025 0.000000 +0.866025 0.500000 0.000000 +0.866025 0.500000 0.000000 +0.866025 0.500000 0.000000 +0.866025 0.500000 0.000000 +0.866025 0.500000 0.000000 +0.866025 0.500000 0.000000 +0.866025 0.500000 0.000000 +0.866025 0.500000 0.000000 +0.866025 0.500000 0.000000 +-0.500000 0.866025 0.000000 +-0.500000 0.866025 0.000000 +-0.500000 0.866025 0.000000 +-0.500000 0.866025 0.000000 +-0.500000 0.866025 0.000000 +-0.500000 0.866025 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.500000 -0.866025 0.000000 +-0.334068 -0.942549 0.000000 +-0.500000 -0.866025 0.000000 +0.760586 -0.649237 0.000000 +0.866025 -0.500000 0.000000 +0.866025 -0.500000 0.000000 +0.760586 -0.649237 0.000000 +0.745194 -0.666847 0.000000 +0.866025 -0.500000 0.000000 +0.621173 -0.783674 0.000000 +0.745194 -0.666847 0.000000 +0.760586 -0.649237 0.000000 +0.621173 -0.783674 0.000000 +0.596199 -0.802837 0.000000 +0.745194 -0.666847 0.000000 +0.451254 -0.892395 0.000000 +0.596199 -0.802837 0.000000 +0.621173 -0.783674 0.000000 +0.451254 -0.892395 0.000000 +0.430261 -0.902705 0.000000 +0.596199 -0.802837 0.000000 +0.357193 -0.934031 0.000000 +0.430261 -0.902705 0.000000 +0.451254 -0.892395 0.000000 +0.357193 -0.934031 0.000000 +0.258819 -0.965926 0.000000 +0.430261 -0.902705 0.000000 +0.258819 -0.965926 0.000000 +0.258819 -0.965926 0.000000 +0.357193 -0.934031 0.000000 +0.157678 -0.987491 0.000000 +0.258819 -0.965926 0.000000 +0.258819 -0.965926 0.000000 +0.157678 -0.987491 0.000000 +0.078735 -0.996896 0.000000 +0.258819 -0.965926 0.000000 +0.055400 -0.998464 0.000000 +0.078735 -0.996896 0.000000 +0.157678 -0.987491 0.000000 +0.055400 -0.998464 0.000000 +-0.114905 -0.993376 0.000000 +0.078735 -0.996896 0.000000 +-0.146115 -0.989268 0.000000 +-0.114905 -0.993376 0.000000 +0.055400 -0.998464 0.000000 +-0.146115 -0.989268 0.000000 +-0.311934 -0.950104 0.000000 +-0.114905 -0.993376 0.000000 +-0.334068 -0.942549 0.000000 +-0.311934 -0.950104 0.000000 +-0.146115 -0.989268 0.000000 +-0.334068 -0.942549 0.000000 +-0.500000 -0.866025 0.000000 +-0.311934 -0.950104 0.000000 +-1.000000 0.000000 0.000000 +-0.996896 0.078735 0.000000 +-1.000000 0.000000 0.000000 +-0.902705 0.430261 0.000000 +-0.866025 0.500000 0.000000 +-0.866025 0.500000 0.000000 +-0.902705 0.430261 0.000000 +-0.923664 0.383204 0.000000 +-0.866025 0.500000 0.000000 +-0.965926 0.258819 0.000000 +-0.923664 0.383204 0.000000 +-0.902705 0.430261 0.000000 +-0.965926 0.258819 0.000000 +-0.965926 0.258819 0.000000 +-0.923664 0.383204 0.000000 +-0.965926 0.258819 0.000000 +-0.991518 0.129968 0.000000 +-0.965926 0.258819 0.000000 +-0.996896 0.078735 0.000000 +-0.991518 0.129968 0.000000 +-0.965926 0.258819 0.000000 +-0.996896 0.078735 0.000000 +-1.000000 0.000000 0.000000 +-0.991518 0.129968 0.000000 +0.666847 0.745194 0.000000 +0.500000 0.866025 0.000000 +0.500000 0.866025 0.000000 +0.866025 -0.500000 0.000000 +0.950104 -0.311934 0.000000 +0.866025 -0.500000 0.000000 +0.950104 -0.311934 0.000000 +0.950104 -0.311934 0.000000 +0.866025 -0.500000 0.000000 +0.950104 -0.311934 0.000000 +0.993376 -0.114905 0.000000 +0.950104 -0.311934 0.000000 +0.993376 -0.114905 0.000000 +0.993376 -0.114905 0.000000 +0.950104 -0.311934 0.000000 +0.996896 0.078735 0.000000 +0.993376 -0.114905 0.000000 +0.993376 -0.114905 0.000000 +0.996896 0.078735 0.000000 +0.996896 0.078735 0.000000 +0.993376 -0.114905 0.000000 +0.996896 0.078735 0.000000 +0.965926 0.258819 0.000000 +0.996896 0.078735 0.000000 +0.965926 0.258819 0.000000 +0.965926 0.258819 0.000000 +0.996896 0.078735 0.000000 +0.902705 0.430261 0.000000 +0.965926 0.258819 0.000000 +0.965926 0.258819 0.000000 +0.902705 0.430261 0.000000 +0.902705 0.430261 0.000000 +0.965926 0.258819 0.000000 +0.902705 0.430261 0.000000 +0.802837 0.596199 0.000000 +0.902705 0.430261 0.000000 +0.802837 0.596199 0.000000 +0.802837 0.596199 0.000000 +0.902705 0.430261 0.000000 +0.802837 0.596199 0.000000 +0.666847 0.745194 0.000000 +0.802837 0.596199 0.000000 +0.666847 0.745194 0.000000 +0.666847 0.745194 0.000000 +0.802837 0.596199 0.000000 +0.500000 0.866025 0.000000 +0.666847 0.745194 0.000000 +0.666847 0.745194 0.000000 +0.500000 0.866025 0.000000 +0.311934 0.950104 0.000000 +0.500000 0.866025 0.000000 +-0.745194 0.666847 0.000000 +-0.866025 0.500000 0.000000 +-0.866025 0.500000 0.000000 +-0.745194 0.666847 0.000000 +-0.745194 0.666847 0.000000 +-0.866025 0.500000 0.000000 +-0.596199 0.802837 0.000000 +-0.745194 0.666847 0.000000 +-0.745194 0.666847 0.000000 +-0.596199 0.802837 0.000000 +-0.596199 0.802837 0.000000 +-0.745194 0.666847 0.000000 +-0.596199 0.802837 0.000000 +-0.430261 0.902705 0.000000 +-0.596199 0.802837 0.000000 +-0.430261 0.902705 0.000000 +-0.430261 0.902705 0.000000 +-0.596199 0.802837 0.000000 +-0.430261 0.902705 0.000000 +-0.258819 0.965926 0.000000 +-0.430261 0.902705 0.000000 +-0.258819 0.965926 0.000000 +-0.258819 0.965926 0.000000 +-0.430261 0.902705 0.000000 +-0.258819 0.965926 0.000000 +-0.078735 0.996896 0.000000 +-0.258819 0.965926 0.000000 +-0.078735 0.996896 0.000000 +-0.078735 0.996896 0.000000 +-0.258819 0.965926 0.000000 +-0.078735 0.996896 0.000000 +0.114905 0.993376 0.000000 +-0.078735 0.996896 0.000000 +0.114905 0.993376 0.000000 +0.114905 0.993376 0.000000 +-0.078735 0.996896 0.000000 +0.114905 0.993376 0.000000 +0.311934 0.950104 0.000000 +0.114905 0.993376 0.000000 +0.311934 0.950104 0.000000 +0.311934 0.950104 0.000000 +0.114905 0.993376 0.000000 +0.311934 0.950104 0.000000 +0.500000 0.866025 0.000000 +0.311934 0.950104 0.000000 +-0.866025 0.500000 0.000000 +-0.924976 0.380026 0.000000 +-0.866025 0.500000 0.000000 +-0.621173 0.783674 0.000000 +-0.500000 0.866025 0.000000 +-0.500000 0.866025 0.000000 +-0.621173 0.783674 0.000000 +-0.605630 0.795747 0.000000 +-0.500000 0.866025 0.000000 +-0.621173 0.783674 0.000000 +-0.703872 0.710326 0.000000 +-0.605630 0.795747 0.000000 +-0.760586 0.649237 0.000000 +-0.703872 0.710326 0.000000 +-0.621173 0.783674 0.000000 +-0.760586 0.649237 0.000000 +-0.791600 0.611040 0.000000 +-0.703872 0.710326 0.000000 +-0.866025 0.500000 0.000000 +-0.791600 0.611040 0.000000 +-0.760586 0.649237 0.000000 +-0.866025 0.500000 0.000000 +-0.866025 0.500000 0.000000 +-0.791600 0.611040 0.000000 +-0.991952 0.126617 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.991952 0.126617 0.000000 +-0.989268 0.146115 0.000000 +-1.000000 0.000000 0.000000 +-0.967097 0.254408 0.000000 +-0.989268 0.146115 0.000000 +-0.991952 0.126617 0.000000 +-0.967097 0.254408 0.000000 +-0.942549 0.334068 0.000000 +-0.989268 0.146115 0.000000 +-0.924976 0.380026 0.000000 +-0.942549 0.334068 0.000000 +-0.967097 0.254408 0.000000 +-0.924976 0.380026 0.000000 +-0.866025 0.500000 0.000000 +-0.942549 0.334068 0.000000 +-0.334068 0.942549 0.000000 +-0.500000 0.866025 0.000000 +-0.500000 0.866025 0.000000 +0.745194 0.666847 0.000000 +0.866025 0.500000 0.000000 +0.866025 0.500000 0.000000 +0.745194 0.666847 0.000000 +0.760586 0.649237 0.000000 +0.866025 0.500000 0.000000 +0.745194 0.666847 0.000000 +0.621173 0.783674 0.000000 +0.760586 0.649237 0.000000 +0.596199 0.802837 0.000000 +0.621173 0.783674 0.000000 +0.745194 0.666847 0.000000 +0.596199 0.802837 0.000000 +0.451254 0.892395 0.000000 +0.621173 0.783674 0.000000 +0.430261 0.902705 0.000000 +0.451254 0.892395 0.000000 +0.596199 0.802837 0.000000 +0.430261 0.902705 0.000000 +0.357193 0.934031 0.000000 +0.451254 0.892395 0.000000 +0.258819 0.965926 0.000000 +0.357193 0.934031 0.000000 +0.430261 0.902705 0.000000 +0.258819 0.965926 0.000000 +0.258819 0.965926 0.000000 +0.357193 0.934031 0.000000 +0.258819 0.965926 0.000000 +0.157678 0.987491 0.000000 +0.258819 0.965926 0.000000 +0.078735 0.996896 0.000000 +0.157678 0.987491 0.000000 +0.258819 0.965926 0.000000 +0.078735 0.996896 0.000000 +0.055400 0.998464 0.000000 +0.157678 0.987491 0.000000 +-0.114905 0.993376 0.000000 +0.055400 0.998464 0.000000 +0.078735 0.996896 0.000000 +-0.114905 0.993376 0.000000 +-0.146115 0.989268 0.000000 +0.055400 0.998464 0.000000 +-0.311934 0.950104 0.000000 +-0.146115 0.989268 0.000000 +-0.114905 0.993376 0.000000 +-0.311934 0.950104 0.000000 +-0.334068 0.942549 0.000000 +-0.146115 0.989268 0.000000 +-0.500000 0.866025 0.000000 +-0.334068 0.942549 0.000000 +-0.311934 0.950104 0.000000 +-0.745194 -0.666847 0.000000 +-0.866025 -0.500000 0.000000 +-0.866025 -0.500000 0.000000 +0.500000 -0.866025 0.000000 +0.311934 -0.950104 0.000000 +0.500000 -0.866025 0.000000 +0.311934 -0.950104 0.000000 +0.311934 -0.950104 0.000000 +0.500000 -0.866025 0.000000 +0.114905 -0.993376 0.000000 +0.311934 -0.950104 0.000000 +0.311934 -0.950104 0.000000 +0.114905 -0.993376 0.000000 +0.114905 -0.993376 0.000000 +0.311934 -0.950104 0.000000 +0.114905 -0.993376 0.000000 +-0.078735 -0.996896 0.000000 +0.114905 -0.993376 0.000000 +-0.078735 -0.996896 0.000000 +-0.078735 -0.996896 0.000000 +0.114905 -0.993376 0.000000 +-0.078735 -0.996896 0.000000 +-0.258819 -0.965926 0.000000 +-0.078735 -0.996896 0.000000 +-0.258819 -0.965926 0.000000 +-0.258819 -0.965926 0.000000 +-0.078735 -0.996896 0.000000 +-0.430261 -0.902705 0.000000 +-0.258819 -0.965926 0.000000 +-0.258819 -0.965926 0.000000 +-0.430261 -0.902705 0.000000 +-0.430261 -0.902705 0.000000 +-0.258819 -0.965926 0.000000 +-0.596199 -0.802837 0.000000 +-0.430261 -0.902705 0.000000 +-0.430261 -0.902705 0.000000 +-0.596199 -0.802837 0.000000 +-0.596199 -0.802837 0.000000 +-0.430261 -0.902705 0.000000 +-0.745194 -0.666847 0.000000 +-0.596199 -0.802837 0.000000 +-0.596199 -0.802837 0.000000 +-0.745194 -0.666847 0.000000 +-0.745194 -0.666847 0.000000 +-0.596199 -0.802837 0.000000 +-0.866025 -0.500000 0.000000 +-0.745194 -0.666847 0.000000 +-0.745194 -0.666847 0.000000 +0.666847 -0.745194 0.000000 +0.500000 -0.866025 0.000000 +0.500000 -0.866025 0.000000 +0.866025 0.500000 0.000000 +0.950104 0.311934 0.000000 +0.866025 0.500000 0.000000 +0.950104 0.311934 0.000000 +0.950104 0.311934 0.000000 +0.866025 0.500000 0.000000 +0.993376 0.114905 0.000000 +0.950104 0.311934 0.000000 +0.950104 0.311934 0.000000 +0.993376 0.114905 0.000000 +0.993376 0.114905 0.000000 +0.950104 0.311934 0.000000 +0.993376 0.114905 0.000000 +0.996896 -0.078735 0.000000 +0.993376 0.114905 0.000000 +0.996896 -0.078735 0.000000 +0.996896 -0.078735 0.000000 +0.993376 0.114905 0.000000 +0.965926 -0.258819 0.000000 +0.996896 -0.078735 0.000000 +0.996896 -0.078735 0.000000 +0.965926 -0.258819 0.000000 +0.965926 -0.258819 0.000000 +0.996896 -0.078735 0.000000 +0.902705 -0.430261 0.000000 +0.965926 -0.258819 0.000000 +0.965926 -0.258819 0.000000 +0.902705 -0.430261 0.000000 +0.902705 -0.430261 0.000000 +0.965926 -0.258819 0.000000 +0.902705 -0.430261 0.000000 +0.802837 -0.596199 0.000000 +0.902705 -0.430261 0.000000 +0.802837 -0.596199 0.000000 +0.802837 -0.596199 0.000000 +0.902705 -0.430261 0.000000 +0.666847 -0.745194 0.000000 +0.802837 -0.596199 0.000000 +0.802837 -0.596199 0.000000 +0.666847 -0.745194 0.000000 +0.666847 -0.745194 0.000000 +0.802837 -0.596199 0.000000 +0.500000 -0.866025 0.000000 +0.666847 -0.745194 0.000000 +0.666847 -0.745194 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.866025 -0.500000 0.000000 +-0.866025 -0.500000 0.000000 +-0.866025 -0.500000 0.000000 +-0.866025 -0.500000 0.000000 +-0.866025 -0.500000 0.000000 +-0.866025 -0.500000 0.000000 +-0.866025 -0.500000 0.000000 +-0.866025 -0.500000 0.000000 +-0.866025 -0.500000 0.000000 +0.500000 -0.866025 0.000000 +0.500000 -0.866025 0.000000 +0.500000 -0.866025 0.000000 +0.500000 -0.866025 0.000000 +0.500000 -0.866025 0.000000 +0.500000 -0.866025 0.000000 +0.866025 0.500000 0.000000 +0.866025 0.500000 0.000000 +0.866025 0.500000 0.000000 +0.866025 0.500000 0.000000 +0.866025 0.500000 0.000000 +0.866025 0.500000 0.000000 +0.866025 0.500000 0.000000 +0.866025 0.500000 0.000000 +0.866025 0.500000 0.000000 +-0.500000 0.866025 0.000000 +-0.500000 0.866025 0.000000 +-0.500000 0.866025 0.000000 +-0.500000 0.866025 0.000000 +-0.500000 0.866025 0.000000 +-0.500000 0.866025 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.866025 -0.500000 0.000000 +0.866025 -0.500000 0.000000 +0.866025 -0.500000 0.000000 +0.866025 -0.500000 0.000000 +0.866025 -0.500000 0.000000 +0.866025 -0.500000 0.000000 +0.866025 -0.500000 0.000000 +0.866025 -0.500000 0.000000 +0.866025 -0.500000 0.000000 +0.500000 0.866025 0.000000 +0.500000 0.866025 0.000000 +0.500000 0.866025 0.000000 +0.500000 0.866025 0.000000 +0.500000 0.866025 0.000000 +0.500000 0.866025 0.000000 +-0.866025 0.500000 0.000000 +-0.866025 0.500000 0.000000 +-0.866025 0.500000 0.000000 +-0.866025 0.500000 0.000000 +-0.866025 0.500000 0.000000 +-0.866025 0.500000 0.000000 +-0.866025 0.500000 0.000000 +-0.866025 0.500000 0.000000 +-0.866025 0.500000 0.000000 +-0.500000 -0.866025 0.000000 +-0.500000 -0.866025 0.000000 +-0.500000 -0.866025 0.000000 +-0.500000 -0.866025 0.000000 +-0.500000 -0.866025 0.000000 +-0.500000 -0.866025 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +0.353553 -0.612372 0.707107 +0.353553 -0.612372 0.707107 +0.353553 -0.612372 0.707107 +0.353553 -0.612372 0.707107 +0.353553 -0.612372 0.707107 +0.353553 -0.612372 0.707107 +0.353553 -0.612372 0.707107 +0.353553 -0.612372 0.707107 +0.353553 -0.612372 0.707107 +0.353553 -0.612372 0.707107 +0.353553 -0.612372 0.707107 +0.353553 -0.612372 0.707107 +0.353553 -0.612372 0.707107 +0.353553 -0.612372 0.707107 +0.353553 -0.612372 0.707107 +0.353553 -0.612372 0.707107 +0.353553 -0.612372 0.707107 +0.353553 -0.612372 0.707107 +0.353553 -0.612372 0.707107 +0.353553 -0.612372 0.707107 +0.353553 -0.612372 0.707107 +0.353553 -0.612372 0.707107 +0.353553 -0.612372 0.707107 +0.353553 -0.612372 0.707107 +0.353553 -0.612372 0.707107 +0.353553 -0.612372 0.707107 +0.353553 -0.612372 0.707107 +0.353553 -0.612372 0.707107 +0.353553 -0.612372 0.707107 +0.353553 -0.612372 0.707107 +0.353553 -0.612372 0.707107 +0.353553 -0.612372 0.707107 +0.353553 -0.612372 0.707107 +0.353553 -0.612372 0.707107 +0.353553 -0.612372 0.707107 +0.353553 -0.612372 0.707107 +0.353553 -0.612372 0.707107 +0.353553 -0.612372 0.707107 +0.353553 -0.612372 0.707107 +0.353553 -0.612372 0.707107 +0.353553 -0.612372 0.707107 +0.353553 -0.612372 0.707107 +0.353553 -0.612372 0.707107 +0.353553 -0.612372 0.707107 +0.353553 -0.612372 0.707107 +0.353553 0.612372 0.707107 +0.353553 0.612372 0.707107 +0.353553 0.612372 0.707107 +0.353553 0.612372 0.707107 +0.353553 0.612372 0.707107 +0.353553 0.612372 0.707107 +0.353553 0.612372 0.707107 +0.353553 0.612372 0.707107 +0.353553 0.612372 0.707107 +0.353553 0.612372 0.707107 +0.353553 0.612372 0.707107 +0.353553 0.612372 0.707107 +0.353553 0.612372 0.707107 +0.353553 0.612372 0.707107 +0.353553 0.612372 0.707107 +0.353553 0.612372 0.707107 +0.353553 0.612372 0.707107 +0.353553 0.612372 0.707107 +0.353553 0.612372 0.707107 +0.353553 0.612372 0.707107 +0.353553 0.612372 0.707107 +0.353553 0.612372 0.707107 +0.353553 0.612372 0.707107 +0.353553 0.612372 0.707107 +0.353553 0.612372 0.707107 +0.353553 0.612372 0.707107 +0.353553 0.612372 0.707107 +0.353553 0.612372 0.707107 +0.353553 0.612372 0.707107 +0.353553 0.612372 0.707107 +0.353553 0.612372 0.707107 +0.353553 0.612372 0.707107 +0.353553 0.612372 0.707107 +0.353553 0.612372 0.707107 +0.353553 0.612372 0.707107 +0.353553 0.612372 0.707107 +0.353553 0.612372 0.707107 +0.353553 0.612372 0.707107 +0.353553 0.612372 0.707107 +0.353553 0.612372 0.707107 +0.353553 0.612372 0.707107 +0.353553 0.612372 0.707107 +0.353553 0.612372 0.707107 +0.353553 0.612372 0.707107 +0.353553 0.612372 0.707107 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.204909 0.978781 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.204909 0.978781 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.204909 0.978781 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.397177 0.917742 0.000000 +-0.368095 0.929788 0.000000 +-0.204909 0.978781 0.000000 +-0.397177 0.917742 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.566635 0.823969 0.000000 +-0.547210 0.836995 0.000000 +-0.397177 0.917742 0.000000 +-0.566635 0.823969 0.000000 +-0.630298 0.776353 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.630298 0.776353 0.000000 +-0.566635 0.823969 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.630298 0.776353 0.000000 +-0.707107 0.707107 0.000000 +-0.776353 0.630298 0.000000 +-0.707107 0.707107 0.000000 +-0.823969 0.566635 0.000000 +-0.776353 0.630298 0.000000 +-0.707107 0.707107 0.000000 +-0.823969 0.566635 0.000000 +-0.836995 0.547210 0.000000 +-0.776353 0.630298 0.000000 +-0.917742 0.397177 0.000000 +-0.836995 0.547210 0.000000 +-0.823969 0.566635 0.000000 +-0.917742 0.397177 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.978781 0.204909 0.000000 +-0.929788 0.368095 0.000000 +-0.917742 0.397177 0.000000 +-0.978781 0.204909 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.978781 0.204909 0.000000 +-0.707107 -0.707107 0.000000 +-0.630298 -0.776353 0.000000 +-0.707107 -0.707107 0.000000 +-0.978781 -0.204909 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.978781 -0.204909 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.978781 -0.204909 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.917742 -0.397177 0.000000 +-0.929788 -0.368095 0.000000 +-0.978781 -0.204909 0.000000 +-0.917742 -0.397177 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.823969 -0.566635 0.000000 +-0.836995 -0.547210 0.000000 +-0.917742 -0.397177 0.000000 +-0.823969 -0.566635 0.000000 +-0.776353 -0.630298 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.776353 -0.630298 0.000000 +-0.823969 -0.566635 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.776353 -0.630298 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.204909 -0.978781 0.000000 +0.000000 -1.000000 0.000000 +-0.368095 -0.929788 0.000000 +-0.204909 -0.978781 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.397177 -0.917742 0.000000 +-0.204909 -0.978781 0.000000 +-0.547210 -0.836995 0.000000 +-0.397177 -0.917742 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.566635 -0.823969 0.000000 +-0.397177 -0.917742 0.000000 +-0.630298 -0.776353 0.000000 +-0.566635 -0.823969 0.000000 +-0.547210 -0.836995 0.000000 +-0.630298 -0.776353 0.000000 +-0.707107 -0.707107 0.000000 +-0.566635 -0.823969 0.000000 +0.978781 0.204909 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.204909 0.978781 0.000000 +0.000000 1.000000 0.000000 +0.204909 0.978781 0.000000 +0.204909 0.978781 0.000000 +0.000000 1.000000 0.000000 +0.397177 0.917742 0.000000 +0.204909 0.978781 0.000000 +0.204909 0.978781 0.000000 +0.397177 0.917742 0.000000 +0.397177 0.917742 0.000000 +0.204909 0.978781 0.000000 +0.397177 0.917742 0.000000 +0.566635 0.823969 0.000000 +0.397177 0.917742 0.000000 +0.566635 0.823969 0.000000 +0.566635 0.823969 0.000000 +0.397177 0.917742 0.000000 +0.707107 0.707107 0.000000 +0.566635 0.823969 0.000000 +0.566635 0.823969 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.566635 0.823969 0.000000 +0.823969 0.566635 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.823969 0.566635 0.000000 +0.823969 0.566635 0.000000 +0.707107 0.707107 0.000000 +0.917742 0.397177 0.000000 +0.823969 0.566635 0.000000 +0.823969 0.566635 0.000000 +0.917742 0.397177 0.000000 +0.917742 0.397177 0.000000 +0.823969 0.566635 0.000000 +0.978781 0.204909 0.000000 +0.917742 0.397177 0.000000 +0.917742 0.397177 0.000000 +0.978781 0.204909 0.000000 +0.978781 0.204909 0.000000 +0.917742 0.397177 0.000000 +1.000000 0.000000 0.000000 +0.978781 0.204909 0.000000 +0.978781 0.204909 0.000000 +0.204909 -0.978781 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.978781 -0.204909 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.978781 -0.204909 0.000000 +0.978781 -0.204909 0.000000 +1.000000 0.000000 0.000000 +0.917742 -0.397177 0.000000 +0.978781 -0.204909 0.000000 +0.978781 -0.204909 0.000000 +0.917742 -0.397177 0.000000 +0.917742 -0.397177 0.000000 +0.978781 -0.204909 0.000000 +0.823969 -0.566635 0.000000 +0.917742 -0.397177 0.000000 +0.917742 -0.397177 0.000000 +0.823969 -0.566635 0.000000 +0.823969 -0.566635 0.000000 +0.917742 -0.397177 0.000000 +0.707107 -0.707107 0.000000 +0.823969 -0.566635 0.000000 +0.823969 -0.566635 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.823969 -0.566635 0.000000 +0.566635 -0.823969 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.566635 -0.823969 0.000000 +0.566635 -0.823969 0.000000 +0.707107 -0.707107 0.000000 +0.397177 -0.917742 0.000000 +0.566635 -0.823969 0.000000 +0.566635 -0.823969 0.000000 +0.397177 -0.917742 0.000000 +0.397177 -0.917742 0.000000 +0.566635 -0.823969 0.000000 +0.204909 -0.978781 0.000000 +0.397177 -0.917742 0.000000 +0.397177 -0.917742 0.000000 +0.204909 -0.978781 0.000000 +0.204909 -0.978781 0.000000 +0.397177 -0.917742 0.000000 +0.000000 -1.000000 0.000000 +0.204909 -0.978781 0.000000 +0.204909 -0.978781 0.000000 +0.334068 -0.942549 0.000000 +0.500000 -0.866025 0.000000 +0.500000 -0.866025 0.000000 +-0.866025 -0.500000 0.000000 +-0.760586 -0.649237 0.000000 +-0.866025 -0.500000 0.000000 +-0.745194 -0.666847 0.000000 +-0.760586 -0.649237 0.000000 +-0.866025 -0.500000 0.000000 +-0.745194 -0.666847 0.000000 +-0.621173 -0.783674 0.000000 +-0.760586 -0.649237 0.000000 +-0.596199 -0.802837 0.000000 +-0.621173 -0.783674 0.000000 +-0.745194 -0.666847 0.000000 +-0.596199 -0.802837 0.000000 +-0.451254 -0.892395 0.000000 +-0.621173 -0.783674 0.000000 +-0.430261 -0.902705 0.000000 +-0.451254 -0.892395 0.000000 +-0.596199 -0.802837 0.000000 +-0.430261 -0.902705 0.000000 +-0.357193 -0.934031 0.000000 +-0.451254 -0.892395 0.000000 +-0.258819 -0.965926 0.000000 +-0.357193 -0.934031 0.000000 +-0.430261 -0.902705 0.000000 +-0.258819 -0.965926 0.000000 +-0.258819 -0.965926 0.000000 +-0.357193 -0.934031 0.000000 +-0.258819 -0.965926 0.000000 +-0.157678 -0.987491 0.000000 +-0.258819 -0.965926 0.000000 +-0.078735 -0.996896 0.000000 +-0.157678 -0.987491 0.000000 +-0.258819 -0.965926 0.000000 +-0.078735 -0.996896 0.000000 +-0.055400 -0.998464 0.000000 +-0.157678 -0.987491 0.000000 +0.114905 -0.993376 0.000000 +-0.055400 -0.998464 0.000000 +-0.078735 -0.996896 0.000000 +0.114905 -0.993376 0.000000 +0.146115 -0.989268 0.000000 +-0.055400 -0.998464 0.000000 +0.311934 -0.950104 0.000000 +0.146115 -0.989268 0.000000 +0.114905 -0.993376 0.000000 +0.311934 -0.950104 0.000000 +0.334068 -0.942549 0.000000 +0.146115 -0.989268 0.000000 +0.500000 -0.866025 0.000000 +0.334068 -0.942549 0.000000 +0.311934 -0.950104 0.000000 +0.500000 -0.866025 0.000000 +0.649237 -0.760586 0.000000 +0.500000 -0.866025 0.000000 +0.942549 0.334068 0.000000 +0.866025 0.500000 0.000000 +0.866025 0.500000 0.000000 +0.942549 0.334068 0.000000 +0.950104 0.311934 0.000000 +0.866025 0.500000 0.000000 +0.989268 0.146115 0.000000 +0.950104 0.311934 0.000000 +0.942549 0.334068 0.000000 +0.989268 0.146115 0.000000 +0.993376 0.114905 0.000000 +0.950104 0.311934 0.000000 +0.998464 -0.055400 0.000000 +0.993376 0.114905 0.000000 +0.989268 0.146115 0.000000 +0.998464 -0.055400 0.000000 +0.996896 -0.078735 0.000000 +0.993376 0.114905 0.000000 +0.987491 -0.157678 0.000000 +0.996896 -0.078735 0.000000 +0.998464 -0.055400 0.000000 +0.987491 -0.157678 0.000000 +0.965926 -0.258819 0.000000 +0.996896 -0.078735 0.000000 +0.965926 -0.258819 0.000000 +0.965926 -0.258819 0.000000 +0.987491 -0.157678 0.000000 +0.934031 -0.357193 0.000000 +0.965926 -0.258819 0.000000 +0.965926 -0.258819 0.000000 +0.934031 -0.357193 0.000000 +0.902705 -0.430261 0.000000 +0.965926 -0.258819 0.000000 +0.892395 -0.451254 0.000000 +0.902705 -0.430261 0.000000 +0.934031 -0.357193 0.000000 +0.892395 -0.451254 0.000000 +0.802837 -0.596199 0.000000 +0.902705 -0.430261 0.000000 +0.783674 -0.621173 0.000000 +0.802837 -0.596199 0.000000 +0.892395 -0.451254 0.000000 +0.783674 -0.621173 0.000000 +0.666847 -0.745194 0.000000 +0.802837 -0.596199 0.000000 +0.649237 -0.760586 0.000000 +0.666847 -0.745194 0.000000 +0.783674 -0.621173 0.000000 +0.649237 -0.760586 0.000000 +0.500000 -0.866025 0.000000 +0.666847 -0.745194 0.000000 +-0.621173 0.783674 0.000000 +-0.760586 0.649237 0.000000 +-0.621173 0.783674 0.000000 +-0.500000 0.866025 0.000000 +-0.621173 0.783674 0.000000 +-0.500000 0.866025 0.000000 +-0.621173 0.783674 0.000000 +-0.621173 0.783674 0.000000 +-0.500000 0.866025 0.000000 +-0.989268 0.146115 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.989268 0.146115 0.000000 +-0.989268 0.146115 0.000000 +-1.000000 0.000000 0.000000 +-0.942549 0.334068 0.000000 +-0.989268 0.146115 0.000000 +-0.989268 0.146115 0.000000 +-0.942549 0.334068 0.000000 +-0.942549 0.334068 0.000000 +-0.989268 0.146115 0.000000 +-0.942549 0.334068 0.000000 +-0.866025 0.500000 0.000000 +-0.942549 0.334068 0.000000 +-0.866025 0.500000 0.000000 +-0.866025 0.500000 0.000000 +-0.942549 0.334068 0.000000 +-0.760586 0.649237 0.000000 +-0.866025 0.500000 0.000000 +-0.866025 0.500000 0.000000 +-0.760586 0.649237 0.000000 +-0.760586 0.649237 0.000000 +-0.866025 0.500000 0.000000 +-0.760586 0.649237 0.000000 +-0.621173 0.783674 0.000000 +-0.760586 0.649237 0.000000 +0.866025 0.500000 0.000000 +0.745194 0.666847 0.000000 +0.866025 0.500000 0.000000 +-0.500000 0.866025 0.000000 +-0.311934 0.950104 0.000000 +-0.500000 0.866025 0.000000 +-0.311934 0.950104 0.000000 +-0.311934 0.950104 0.000000 +-0.500000 0.866025 0.000000 +-0.114905 0.993376 0.000000 +-0.311934 0.950104 0.000000 +-0.311934 0.950104 0.000000 +-0.114905 0.993376 0.000000 +-0.114905 0.993376 0.000000 +-0.311934 0.950104 0.000000 +0.078735 0.996896 0.000000 +-0.114905 0.993376 0.000000 +-0.114905 0.993376 0.000000 +0.078735 0.996896 0.000000 +0.078735 0.996896 0.000000 +-0.114905 0.993376 0.000000 +0.258819 0.965926 0.000000 +0.078735 0.996896 0.000000 +0.078735 0.996896 0.000000 +0.258819 0.965926 0.000000 +0.258819 0.965926 0.000000 +0.078735 0.996896 0.000000 +0.430261 0.902705 0.000000 +0.258819 0.965926 0.000000 +0.258819 0.965926 0.000000 +0.430261 0.902705 0.000000 +0.430261 0.902705 0.000000 +0.258819 0.965926 0.000000 +0.430261 0.902705 0.000000 +0.596199 0.802837 0.000000 +0.430261 0.902705 0.000000 +0.596199 0.802837 0.000000 +0.596199 0.802837 0.000000 +0.430261 0.902705 0.000000 +0.745194 0.666847 0.000000 +0.596199 0.802837 0.000000 +0.596199 0.802837 0.000000 +0.745194 0.666847 0.000000 +0.745194 0.666847 0.000000 +0.596199 0.802837 0.000000 +0.745194 0.666847 0.000000 +0.866025 0.500000 0.000000 +0.745194 0.666847 0.000000 +0.649237 0.760586 0.000000 +0.500000 0.866025 0.000000 +0.500000 0.866025 0.000000 +0.950104 -0.311934 0.000000 +0.866025 -0.500000 0.000000 +0.866025 -0.500000 0.000000 +0.950104 -0.311934 0.000000 +0.942549 -0.334068 0.000000 +0.866025 -0.500000 0.000000 +0.950104 -0.311934 0.000000 +0.989268 -0.146115 0.000000 +0.942549 -0.334068 0.000000 +0.993376 -0.114905 0.000000 +0.989268 -0.146115 0.000000 +0.950104 -0.311934 0.000000 +0.993376 -0.114905 0.000000 +0.998464 0.055400 0.000000 +0.989268 -0.146115 0.000000 +0.996896 0.078735 0.000000 +0.998464 0.055400 0.000000 +0.993376 -0.114905 0.000000 +0.996896 0.078735 0.000000 +0.987491 0.157678 0.000000 +0.998464 0.055400 0.000000 +0.965926 0.258819 0.000000 +0.987491 0.157678 0.000000 +0.996896 0.078735 0.000000 +0.965926 0.258819 0.000000 +0.965926 0.258819 0.000000 +0.987491 0.157678 0.000000 +0.965926 0.258819 0.000000 +0.934031 0.357193 0.000000 +0.965926 0.258819 0.000000 +0.902705 0.430261 0.000000 +0.934031 0.357193 0.000000 +0.965926 0.258819 0.000000 +0.902705 0.430261 0.000000 +0.892395 0.451254 0.000000 +0.934031 0.357193 0.000000 +0.802837 0.596199 0.000000 +0.892395 0.451254 0.000000 +0.902705 0.430261 0.000000 +0.802837 0.596199 0.000000 +0.783674 0.621173 0.000000 +0.892395 0.451254 0.000000 +0.666847 0.745194 0.000000 +0.783674 0.621173 0.000000 +0.802837 0.596199 0.000000 +0.666847 0.745194 0.000000 +0.649237 0.760586 0.000000 +0.783674 0.621173 0.000000 +0.500000 0.866025 0.000000 +0.649237 0.760586 0.000000 +0.666847 0.745194 0.000000 +-0.258819 0.965926 0.000000 +-0.357193 0.934031 0.000000 +-0.258819 0.965926 0.000000 +0.311934 0.950104 0.000000 +0.500000 0.866025 0.000000 +0.500000 0.866025 0.000000 +0.311934 0.950104 0.000000 +0.334068 0.942549 0.000000 +0.500000 0.866025 0.000000 +0.311934 0.950104 0.000000 +0.146115 0.989268 0.000000 +0.334068 0.942549 0.000000 +0.114905 0.993376 0.000000 +0.146115 0.989268 0.000000 +0.311934 0.950104 0.000000 +0.114905 0.993376 0.000000 +-0.055400 0.998464 0.000000 +0.146115 0.989268 0.000000 +-0.078735 0.996896 0.000000 +-0.055400 0.998464 0.000000 +0.114905 0.993376 0.000000 +-0.078735 0.996896 0.000000 +-0.157678 0.987491 0.000000 +-0.055400 0.998464 0.000000 +-0.258819 0.965926 0.000000 +-0.157678 0.987491 0.000000 +-0.078735 0.996896 0.000000 +-0.258819 0.965926 0.000000 +-0.258819 0.965926 0.000000 +-0.157678 0.987491 0.000000 +-0.760586 0.649237 0.000000 +-0.866025 0.500000 0.000000 +-0.866025 0.500000 0.000000 +-0.760586 0.649237 0.000000 +-0.745194 0.666847 0.000000 +-0.866025 0.500000 0.000000 +-0.621173 0.783674 0.000000 +-0.745194 0.666847 0.000000 +-0.760586 0.649237 0.000000 +-0.621173 0.783674 0.000000 +-0.596199 0.802837 0.000000 +-0.745194 0.666847 0.000000 +-0.451254 0.892395 0.000000 +-0.596199 0.802837 0.000000 +-0.621173 0.783674 0.000000 +-0.451254 0.892395 0.000000 +-0.430261 0.902705 0.000000 +-0.596199 0.802837 0.000000 +-0.357193 0.934031 0.000000 +-0.430261 0.902705 0.000000 +-0.451254 0.892395 0.000000 +-0.357193 0.934031 0.000000 +-0.258819 0.965926 0.000000 +-0.430261 0.902705 0.000000 +-0.311934 -0.950104 0.000000 +-0.500000 -0.866025 0.000000 +-0.500000 -0.866025 0.000000 +0.866025 -0.500000 0.000000 +0.745194 -0.666847 0.000000 +0.866025 -0.500000 0.000000 +0.745194 -0.666847 0.000000 +0.745194 -0.666847 0.000000 +0.866025 -0.500000 0.000000 +0.596199 -0.802837 0.000000 +0.745194 -0.666847 0.000000 +0.745194 -0.666847 0.000000 +0.596199 -0.802837 0.000000 +0.596199 -0.802837 0.000000 +0.745194 -0.666847 0.000000 +0.430261 -0.902705 0.000000 +0.596199 -0.802837 0.000000 +0.596199 -0.802837 0.000000 +0.430261 -0.902705 0.000000 +0.430261 -0.902705 0.000000 +0.596199 -0.802837 0.000000 +0.258819 -0.965926 0.000000 +0.430261 -0.902705 0.000000 +0.430261 -0.902705 0.000000 +0.258819 -0.965926 0.000000 +0.258819 -0.965926 0.000000 +0.430261 -0.902705 0.000000 +0.078735 -0.996896 0.000000 +0.258819 -0.965926 0.000000 +0.258819 -0.965926 0.000000 +0.078735 -0.996896 0.000000 +0.078735 -0.996896 0.000000 +0.258819 -0.965926 0.000000 +-0.114905 -0.993376 0.000000 +0.078735 -0.996896 0.000000 +0.078735 -0.996896 0.000000 +-0.114905 -0.993376 0.000000 +-0.114905 -0.993376 0.000000 +0.078735 -0.996896 0.000000 +-0.311934 -0.950104 0.000000 +-0.114905 -0.993376 0.000000 +-0.114905 -0.993376 0.000000 +-0.311934 -0.950104 0.000000 +-0.311934 -0.950104 0.000000 +-0.114905 -0.993376 0.000000 +-0.500000 -0.866025 0.000000 +-0.311934 -0.950104 0.000000 +-0.311934 -0.950104 0.000000 +-0.965926 0.258819 0.000000 +-0.902705 0.430261 0.000000 +-0.902705 0.430261 0.000000 +-0.902705 0.430261 0.000000 +-0.866025 0.500000 0.000000 +-0.866025 0.500000 0.000000 +-0.902705 0.430261 0.000000 +-0.902705 0.430261 0.000000 +-0.866025 0.500000 0.000000 +-1.000000 0.000000 0.000000 +-0.996896 0.078735 0.000000 +-1.000000 0.000000 0.000000 +-0.996896 0.078735 0.000000 +-0.996896 0.078735 0.000000 +-1.000000 0.000000 0.000000 +-0.996896 0.078735 0.000000 +-0.965926 0.258819 0.000000 +-0.996896 0.078735 0.000000 +-0.965926 0.258819 0.000000 +-0.965926 0.258819 0.000000 +-0.996896 0.078735 0.000000 +-0.902705 0.430261 0.000000 +-0.965926 0.258819 0.000000 +-0.965926 0.258819 0.000000 +-0.974059 -0.226124 0.008727 +-0.912203 -0.409645 0.008727 +-0.974059 -0.226124 0.008727 +-0.991313 -0.131237 0.008727 +-0.974059 -0.226124 0.008727 +-0.992359 -0.123072 0.008727 +-0.974059 -0.226124 0.008727 +-0.974059 -0.226124 0.008727 +-0.991313 -0.131237 0.008727 +0.990475 -0.137418 0.008727 +0.999071 -0.042198 0.008727 +0.999413 -0.033127 0.008727 +0.990475 -0.137418 0.008727 +0.990475 -0.137418 0.008727 +0.999071 -0.042198 0.008727 +0.945410 -0.325767 0.008727 +0.990475 -0.137418 0.008727 +0.990475 -0.137418 0.008727 +0.945410 -0.325767 0.008727 +0.945410 -0.325767 0.008727 +0.990475 -0.137418 0.008727 +0.860794 -0.508878 0.008727 +0.945410 -0.325767 0.008727 +0.945410 -0.325767 0.008727 +0.860794 -0.508878 0.008727 +0.860794 -0.508878 0.008727 +0.945410 -0.325767 0.008727 +0.738255 -0.674465 0.008727 +0.860794 -0.508878 0.008727 +0.860794 -0.508878 0.008727 +0.738255 -0.674465 0.008727 +0.738255 -0.674465 0.008727 +0.860794 -0.508878 0.008727 +0.584386 -0.811429 0.008727 +0.738255 -0.674465 0.008727 +0.738255 -0.674465 0.008727 +0.584386 -0.811429 0.008727 +0.584386 -0.811429 0.008727 +0.738255 -0.674465 0.008727 +0.409645 -0.912203 0.008727 +0.584386 -0.811429 0.008727 +0.584386 -0.811429 0.008727 +0.409645 -0.912203 0.008727 +0.409645 -0.912203 0.008727 +0.584386 -0.811429 0.008727 +0.409645 -0.912203 0.008727 +0.226124 -0.974059 0.008727 +0.409645 -0.912203 0.008727 +0.226124 -0.974059 0.008727 +0.226124 -0.974059 0.008727 +0.409645 -0.912203 0.008727 +0.045106 -0.998944 0.008727 +0.226124 -0.974059 0.008727 +0.226124 -0.974059 0.008727 +0.045106 -0.998944 0.008727 +0.045106 -0.998944 0.008727 +0.226124 -0.974059 0.008727 +-0.137418 -0.990475 0.008727 +0.045106 -0.998944 0.008727 +0.045106 -0.998944 0.008727 +-0.137418 -0.990475 0.008727 +-0.137418 -0.990475 0.008727 +0.045106 -0.998944 0.008727 +-0.137418 -0.990475 0.008727 +-0.325767 -0.945410 0.008727 +-0.137418 -0.990475 0.008727 +-0.325767 -0.945410 0.008727 +-0.325767 -0.945410 0.008727 +-0.137418 -0.990475 0.008727 +-0.508878 -0.860794 0.008727 +-0.325767 -0.945410 0.008727 +-0.325767 -0.945410 0.008727 +-0.508878 -0.860794 0.008727 +-0.508878 -0.860794 0.008727 +-0.325767 -0.945410 0.008727 +-0.674465 -0.738255 0.008727 +-0.508878 -0.860794 0.008727 +-0.508878 -0.860794 0.008727 +-0.674465 -0.738255 0.008727 +-0.674465 -0.738255 0.008727 +-0.508878 -0.860794 0.008727 +-0.811429 -0.584386 0.008727 +-0.674465 -0.738255 0.008727 +-0.674465 -0.738255 0.008727 +-0.811429 -0.584386 0.008727 +-0.811429 -0.584386 0.008727 +-0.674465 -0.738255 0.008727 +-0.912203 -0.409645 0.008727 +-0.811429 -0.584386 0.008727 +-0.811429 -0.584386 0.008727 +-0.912203 -0.409645 0.008727 +-0.912203 -0.409645 0.008727 +-0.811429 -0.584386 0.008727 +-0.912203 -0.409645 0.008727 +-0.974059 -0.226124 0.008727 +-0.912203 -0.409645 0.008727 +0.911955 0.410197 0.008727 +0.973923 0.226713 0.008727 +0.973923 0.226713 0.008727 +-0.990558 0.136819 0.008727 +-0.991313 0.131237 0.008727 +-0.992359 0.123072 0.008727 +0.975356 0.220464 0.008727 +0.973923 0.226713 0.008727 +0.976971 0.213196 0.008727 +0.973923 0.226713 0.008727 +0.973923 0.226713 0.008727 +0.975356 0.220464 0.008727 +-0.990558 0.136819 0.008727 +-0.990558 0.136819 0.008727 +-0.991313 0.131237 0.008727 +-0.945607 0.325195 0.008727 +-0.990558 0.136819 0.008727 +-0.990558 0.136819 0.008727 +-0.945607 0.325195 0.008727 +-0.945607 0.325195 0.008727 +-0.990558 0.136819 0.008727 +-0.861102 0.508358 0.008727 +-0.945607 0.325195 0.008727 +-0.945607 0.325195 0.008727 +-0.861102 0.508358 0.008727 +-0.861102 0.508358 0.008727 +-0.945607 0.325195 0.008727 +-0.738663 0.674019 0.008727 +-0.861102 0.508358 0.008727 +-0.861102 0.508358 0.008727 +-0.738663 0.674019 0.008727 +-0.738663 0.674019 0.008727 +-0.861102 0.508358 0.008727 +-0.738663 0.674019 0.008727 +-0.584876 0.811076 0.008727 +-0.738663 0.674019 0.008727 +-0.584876 0.811076 0.008727 +-0.584876 0.811076 0.008727 +-0.738663 0.674019 0.008727 +-0.410197 0.911955 0.008727 +-0.584876 0.811076 0.008727 +-0.584876 0.811076 0.008727 +-0.410197 0.911955 0.008727 +-0.410197 0.911955 0.008727 +-0.584876 0.811076 0.008727 +-0.226713 0.973923 0.008727 +-0.410197 0.911955 0.008727 +-0.410197 0.911955 0.008727 +-0.226713 0.973923 0.008727 +-0.226713 0.973923 0.008727 +-0.410197 0.911955 0.008727 +-0.226713 0.973923 0.008727 +-0.045710 0.998917 0.008727 +-0.226713 0.973923 0.008727 +-0.045710 0.998917 0.008727 +-0.045710 0.998917 0.008727 +-0.226713 0.973923 0.008727 +0.136819 0.990558 0.008727 +-0.045710 0.998917 0.008727 +-0.045710 0.998917 0.008727 +0.136819 0.990558 0.008727 +0.136819 0.990558 0.008727 +-0.045710 0.998917 0.008727 +0.136819 0.990558 0.008727 +0.325195 0.945607 0.008727 +0.136819 0.990558 0.008727 +0.325195 0.945607 0.008727 +0.325195 0.945607 0.008727 +0.136819 0.990558 0.008727 +0.508358 0.861102 0.008727 +0.325195 0.945607 0.008727 +0.325195 0.945607 0.008727 +0.508358 0.861102 0.008727 +0.508358 0.861102 0.008727 +0.325195 0.945607 0.008727 +0.674019 0.738663 0.008727 +0.508358 0.861102 0.008727 +0.508358 0.861102 0.008727 +0.674019 0.738663 0.008727 +0.674019 0.738663 0.008727 +0.508358 0.861102 0.008727 +0.811076 0.584876 0.008727 +0.674019 0.738663 0.008727 +0.674019 0.738663 0.008727 +0.811076 0.584876 0.008727 +0.811076 0.584876 0.008727 +0.674019 0.738663 0.008727 +0.811076 0.584876 0.008727 +0.911955 0.410197 0.008727 +0.811076 0.584876 0.008727 +0.911955 0.410197 0.008727 +0.911955 0.410197 0.008727 +0.811076 0.584876 0.008727 +0.973923 0.226713 0.008727 +0.911955 0.410197 0.008727 +0.911955 0.410197 0.008727 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.506722 -0.092188 0.857166 +0.515038 0.000000 0.857167 +0.515038 0.000000 0.857167 +-0.515038 0.000000 0.857167 +-0.506156 -0.095249 0.857166 +-0.515038 -0.001458 0.857166 +-0.506440 -0.093718 0.857167 +-0.506156 -0.095249 0.857166 +-0.515038 0.000000 0.857167 +-0.478876 -0.189583 0.857167 +-0.506156 -0.095249 0.857166 +-0.506440 -0.093718 0.857167 +-0.478876 -0.189583 0.857167 +-0.478273 -0.191105 0.857166 +-0.506156 -0.095249 0.857166 +-0.431085 -0.281834 0.857167 +-0.478273 -0.191105 0.857166 +-0.478876 -0.189583 0.857167 +-0.431085 -0.281834 0.857167 +-0.430160 -0.283247 0.857166 +-0.478273 -0.191105 0.857166 +-0.431085 -0.281834 0.857167 +-0.364066 -0.364308 0.857167 +-0.430160 -0.283247 0.857166 +-0.364187 -0.364187 0.857167 +-0.364066 -0.364308 0.857167 +-0.431085 -0.281834 0.857167 +-0.281834 -0.431085 0.857167 +-0.364066 -0.364308 0.857167 +-0.364187 -0.364187 0.857167 +-0.281834 -0.431085 0.857167 +-0.280420 -0.432008 0.857166 +-0.364066 -0.364308 0.857167 +-0.189583 -0.478876 0.857167 +-0.280420 -0.432008 0.857166 +-0.281834 -0.431085 0.857167 +-0.189583 -0.478876 0.857167 +-0.188061 -0.479478 0.857166 +-0.280420 -0.432008 0.857166 +-0.189583 -0.478876 0.857167 +-0.092188 -0.506722 0.857166 +-0.188061 -0.479478 0.857166 +-0.093718 -0.506440 0.857167 +-0.092188 -0.506722 0.857166 +-0.189583 -0.478876 0.857167 +-0.093718 -0.506440 0.857167 +0.001458 -0.515038 0.857166 +-0.092188 -0.506722 0.857166 +0.000000 -0.515038 0.857167 +0.001458 -0.515038 0.857166 +-0.093718 -0.506440 0.857167 +0.093718 -0.506440 0.857167 +0.001458 -0.515038 0.857166 +0.000000 -0.515038 0.857167 +0.093718 -0.506440 0.857167 +0.095249 -0.506156 0.857166 +0.001458 -0.515038 0.857166 +0.189583 -0.478876 0.857167 +0.095249 -0.506156 0.857166 +0.093718 -0.506440 0.857167 +0.189583 -0.478876 0.857167 +0.191105 -0.478273 0.857166 +0.095249 -0.506156 0.857166 +0.281834 -0.431085 0.857167 +0.191105 -0.478273 0.857166 +0.189583 -0.478876 0.857167 +0.281834 -0.431085 0.857167 +0.283247 -0.430160 0.857166 +0.191105 -0.478273 0.857166 +0.364187 -0.364187 0.857167 +0.283247 -0.430160 0.857166 +0.281834 -0.431085 0.857167 +0.364187 -0.364187 0.857167 +0.364308 -0.364066 0.857167 +0.283247 -0.430160 0.857166 +0.364187 -0.364187 0.857167 +0.432008 -0.280420 0.857166 +0.364308 -0.364066 0.857167 +0.431085 -0.281834 0.857167 +0.432008 -0.280420 0.857166 +0.364187 -0.364187 0.857167 +0.431085 -0.281834 0.857167 +0.479478 -0.188061 0.857166 +0.432008 -0.280420 0.857166 +0.478876 -0.189583 0.857167 +0.479478 -0.188061 0.857166 +0.431085 -0.281834 0.857167 +0.478876 -0.189583 0.857167 +0.506722 -0.092188 0.857166 +0.479478 -0.188061 0.857166 +0.506440 -0.093718 0.857167 +0.506722 -0.092188 0.857166 +0.478876 -0.189583 0.857167 +0.515038 0.000000 0.857167 +0.506722 -0.092188 0.857166 +0.506440 -0.093718 0.857167 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.739699 -0.672882 0.008727 +0.604910 -0.796246 0.008727 +0.604910 -0.796246 0.008727 +0.099525 -0.994997 0.008727 +0.250917 -0.967969 0.008727 +0.094336 -0.995502 0.008727 +0.250917 -0.967969 0.008727 +0.250917 -0.967969 0.008727 +0.099525 -0.994997 0.008727 +0.440079 -0.897917 0.008727 +0.250917 -0.967969 0.008727 +0.250917 -0.967969 0.008727 +0.440079 -0.897917 0.008727 +0.440079 -0.897917 0.008727 +0.250917 -0.967969 0.008727 +0.604910 -0.796246 0.008727 +0.440079 -0.897917 0.008727 +0.440079 -0.897917 0.008727 +0.604910 -0.796246 0.008727 +0.604910 -0.796246 0.008727 +0.440079 -0.897917 0.008727 +0.999962 0.000000 0.008727 +0.987332 -0.158428 0.008727 +0.999962 0.000000 0.008727 +0.987332 -0.158428 0.008727 +0.987332 -0.158428 0.008727 +0.999962 0.000000 0.008727 +0.935447 -0.353358 0.008727 +0.987332 -0.158428 0.008727 +0.987332 -0.158428 0.008727 +0.935447 -0.353358 0.008727 +0.935447 -0.353358 0.008727 +0.987332 -0.158428 0.008727 +0.849789 -0.527050 0.008727 +0.935447 -0.353358 0.008727 +0.935447 -0.353358 0.008727 +0.849789 -0.527050 0.008727 +0.849789 -0.527050 0.008727 +0.935447 -0.353358 0.008727 +0.739699 -0.672882 0.008727 +0.849789 -0.527050 0.008727 +0.849789 -0.527050 0.008727 +0.739699 -0.672882 0.008727 +0.739699 -0.672882 0.008727 +0.849789 -0.527050 0.008727 +0.604910 -0.796246 0.008727 +0.739699 -0.672882 0.008727 +0.739699 -0.672882 0.008727 +-0.982706 -0.181852 0.034899 +-0.999391 0.000000 0.034899 +-0.999391 0.000000 0.034899 +0.999391 0.000000 0.034899 +0.982706 -0.181852 0.034899 +0.999391 0.000000 0.034899 +0.982706 -0.181852 0.034899 +0.982706 -0.181852 0.034899 +0.999391 0.000000 0.034899 +0.929222 -0.367870 0.034899 +0.982706 -0.181852 0.034899 +0.982706 -0.181852 0.034899 +0.929222 -0.367870 0.034899 +0.929222 -0.367870 0.034899 +0.982706 -0.181852 0.034899 +0.836486 -0.546876 0.034899 +0.929222 -0.367870 0.034899 +0.929222 -0.367870 0.034899 +0.836486 -0.546876 0.034899 +0.836486 -0.546876 0.034899 +0.929222 -0.367870 0.034899 +0.706676 -0.706676 0.034899 +0.836486 -0.546876 0.034899 +0.836486 -0.546876 0.034899 +0.706676 -0.706676 0.034899 +0.706676 -0.706676 0.034899 +0.836486 -0.546876 0.034899 +0.546876 -0.836486 0.034899 +0.706676 -0.706676 0.034899 +0.706676 -0.706676 0.034899 +0.546876 -0.836486 0.034899 +0.546876 -0.836486 0.034899 +0.706676 -0.706676 0.034899 +0.367870 -0.929222 0.034899 +0.546876 -0.836486 0.034899 +0.546876 -0.836486 0.034899 +0.367870 -0.929222 0.034899 +0.367870 -0.929222 0.034899 +0.546876 -0.836486 0.034899 +0.181852 -0.982706 0.034899 +0.367870 -0.929222 0.034899 +0.367870 -0.929222 0.034899 +0.181852 -0.982706 0.034899 +0.181852 -0.982706 0.034899 +0.367870 -0.929222 0.034899 +0.000000 -0.999391 0.034899 +0.181852 -0.982706 0.034899 +0.181852 -0.982706 0.034899 +0.000000 -0.999391 0.034899 +0.000000 -0.999391 0.034899 +0.181852 -0.982706 0.034899 +-0.181852 -0.982706 0.034899 +0.000000 -0.999391 0.034899 +0.000000 -0.999391 0.034899 +-0.181852 -0.982706 0.034899 +-0.181852 -0.982706 0.034899 +0.000000 -0.999391 0.034899 +-0.367870 -0.929222 0.034899 +-0.181852 -0.982706 0.034899 +-0.181852 -0.982706 0.034899 +-0.367870 -0.929222 0.034899 +-0.367870 -0.929222 0.034899 +-0.181852 -0.982706 0.034899 +-0.546876 -0.836486 0.034899 +-0.367870 -0.929222 0.034899 +-0.367870 -0.929222 0.034899 +-0.546876 -0.836486 0.034899 +-0.546876 -0.836486 0.034899 +-0.367870 -0.929222 0.034899 +-0.706676 -0.706676 0.034899 +-0.546876 -0.836486 0.034899 +-0.546876 -0.836486 0.034899 +-0.706676 -0.706676 0.034899 +-0.706676 -0.706676 0.034899 +-0.546876 -0.836486 0.034899 +-0.836486 -0.546876 0.034899 +-0.706676 -0.706676 0.034899 +-0.706676 -0.706676 0.034899 +-0.836486 -0.546876 0.034899 +-0.836486 -0.546876 0.034899 +-0.706676 -0.706676 0.034899 +-0.929222 -0.367870 0.034899 +-0.836486 -0.546876 0.034899 +-0.836486 -0.546876 0.034899 +-0.929222 -0.367870 0.034899 +-0.929222 -0.367870 0.034899 +-0.836486 -0.546876 0.034899 +-0.982706 -0.181852 0.034899 +-0.929222 -0.367870 0.034899 +-0.929222 -0.367870 0.034899 +-0.982706 -0.181852 0.034899 +-0.982706 -0.181852 0.034899 +-0.929222 -0.367870 0.034899 +-0.999391 0.000000 0.034899 +-0.982706 -0.181852 0.034899 +-0.982706 -0.181852 0.034899 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +-0.973923 0.226713 0.008727 +-0.911955 0.410197 0.008727 +-0.973923 0.226713 0.008727 +0.991313 0.131237 0.008727 +0.990558 0.136819 0.008727 +0.992359 0.123072 0.008727 +-0.973923 0.226713 0.008727 +-0.975356 0.220464 0.008727 +-0.976971 0.213196 0.008727 +-0.973923 0.226713 0.008727 +-0.973923 0.226713 0.008727 +-0.975356 0.220464 0.008727 +0.990558 0.136819 0.008727 +0.990558 0.136819 0.008727 +0.991313 0.131237 0.008727 +0.945607 0.325195 0.008727 +0.990558 0.136819 0.008727 +0.990558 0.136819 0.008727 +0.945607 0.325195 0.008727 +0.945607 0.325195 0.008727 +0.990558 0.136819 0.008727 +0.945607 0.325195 0.008727 +0.861102 0.508358 0.008727 +0.945607 0.325195 0.008727 +0.861102 0.508358 0.008727 +0.861102 0.508358 0.008727 +0.945607 0.325195 0.008727 +0.738663 0.674019 0.008727 +0.861102 0.508358 0.008727 +0.861102 0.508358 0.008727 +0.738663 0.674019 0.008727 +0.738663 0.674019 0.008727 +0.861102 0.508358 0.008727 +0.584876 0.811076 0.008727 +0.738663 0.674019 0.008727 +0.738663 0.674019 0.008727 +0.584876 0.811076 0.008727 +0.584876 0.811076 0.008727 +0.738663 0.674019 0.008727 +0.410197 0.911955 0.008727 +0.584876 0.811076 0.008727 +0.584876 0.811076 0.008727 +0.410197 0.911955 0.008727 +0.410197 0.911955 0.008727 +0.584876 0.811076 0.008727 +0.410197 0.911955 0.008727 +0.226713 0.973923 0.008727 +0.410197 0.911955 0.008727 +0.226713 0.973923 0.008727 +0.226713 0.973923 0.008727 +0.410197 0.911955 0.008727 +0.045710 0.998917 0.008727 +0.226713 0.973923 0.008727 +0.226713 0.973923 0.008727 +0.045710 0.998917 0.008727 +0.045710 0.998917 0.008727 +0.226713 0.973923 0.008727 +0.045710 0.998917 0.008727 +-0.136819 0.990558 0.008727 +0.045710 0.998917 0.008727 +-0.136819 0.990558 0.008727 +-0.136819 0.990558 0.008727 +0.045710 0.998917 0.008727 +-0.325195 0.945607 0.008727 +-0.136819 0.990558 0.008727 +-0.136819 0.990558 0.008727 +-0.325195 0.945607 0.008727 +-0.325195 0.945607 0.008727 +-0.136819 0.990558 0.008727 +-0.508358 0.861102 0.008727 +-0.325195 0.945607 0.008727 +-0.325195 0.945607 0.008727 +-0.508358 0.861102 0.008727 +-0.508358 0.861102 0.008727 +-0.325195 0.945607 0.008727 +-0.674019 0.738663 0.008727 +-0.508358 0.861102 0.008727 +-0.508358 0.861102 0.008727 +-0.674019 0.738663 0.008727 +-0.674019 0.738663 0.008727 +-0.508358 0.861102 0.008727 +-0.811076 0.584876 0.008727 +-0.674019 0.738663 0.008727 +-0.674019 0.738663 0.008727 +-0.811076 0.584876 0.008727 +-0.811076 0.584876 0.008727 +-0.674019 0.738663 0.008727 +-0.811076 0.584876 0.008727 +-0.911955 0.410197 0.008727 +-0.811076 0.584876 0.008727 +-0.911955 0.410197 0.008727 +-0.911955 0.410197 0.008727 +-0.811076 0.584876 0.008727 +-0.911955 0.410197 0.008727 +-0.973923 0.226713 0.008727 +-0.911955 0.410197 0.008727 +-0.990475 -0.137418 0.008727 +-0.945410 -0.325767 0.008727 +-0.990475 -0.137418 0.008727 +0.974059 -0.226124 0.008727 +0.991313 -0.131237 0.008727 +0.992359 -0.123072 0.008727 +0.974059 -0.226124 0.008727 +0.974059 -0.226124 0.008727 +0.991313 -0.131237 0.008727 +-0.999071 -0.042198 0.008727 +-0.990475 -0.137418 0.008727 +-0.999413 -0.033127 0.008727 +-0.990475 -0.137418 0.008727 +-0.990475 -0.137418 0.008727 +-0.999071 -0.042198 0.008727 +0.974059 -0.226124 0.008727 +0.912203 -0.409645 0.008727 +0.974059 -0.226124 0.008727 +0.912203 -0.409645 0.008727 +0.912203 -0.409645 0.008727 +0.974059 -0.226124 0.008727 +0.811429 -0.584386 0.008727 +0.912203 -0.409645 0.008727 +0.912203 -0.409645 0.008727 +0.811429 -0.584386 0.008727 +0.811429 -0.584386 0.008727 +0.912203 -0.409645 0.008727 +0.674465 -0.738255 0.008727 +0.811429 -0.584386 0.008727 +0.811429 -0.584386 0.008727 +0.674465 -0.738255 0.008727 +0.674465 -0.738255 0.008727 +0.811429 -0.584386 0.008727 +0.674465 -0.738255 0.008727 +0.508878 -0.860794 0.008727 +0.674465 -0.738255 0.008727 +0.508878 -0.860794 0.008727 +0.508878 -0.860794 0.008727 +0.674465 -0.738255 0.008727 +0.325767 -0.945410 0.008727 +0.508878 -0.860794 0.008727 +0.508878 -0.860794 0.008727 +0.325767 -0.945410 0.008727 +0.325767 -0.945410 0.008727 +0.508878 -0.860794 0.008727 +0.325767 -0.945410 0.008727 +0.137418 -0.990475 0.008727 +0.325767 -0.945410 0.008727 +0.137418 -0.990475 0.008727 +0.137418 -0.990475 0.008727 +0.325767 -0.945410 0.008727 +-0.045106 -0.998944 0.008727 +0.137418 -0.990475 0.008727 +0.137418 -0.990475 0.008727 +-0.045106 -0.998944 0.008727 +-0.045106 -0.998944 0.008727 +0.137418 -0.990475 0.008727 +-0.226124 -0.974059 0.008727 +-0.045106 -0.998944 0.008727 +-0.045106 -0.998944 0.008727 +-0.226124 -0.974059 0.008727 +-0.226124 -0.974059 0.008727 +-0.045106 -0.998944 0.008727 +-0.226124 -0.974059 0.008727 +-0.409645 -0.912203 0.008727 +-0.226124 -0.974059 0.008727 +-0.409645 -0.912203 0.008727 +-0.409645 -0.912203 0.008727 +-0.226124 -0.974059 0.008727 +-0.584386 -0.811429 0.008727 +-0.409645 -0.912203 0.008727 +-0.409645 -0.912203 0.008727 +-0.584386 -0.811429 0.008727 +-0.584386 -0.811429 0.008727 +-0.409645 -0.912203 0.008727 +-0.738255 -0.674465 0.008727 +-0.584386 -0.811429 0.008727 +-0.584386 -0.811429 0.008727 +-0.738255 -0.674465 0.008727 +-0.738255 -0.674465 0.008727 +-0.584386 -0.811429 0.008727 +-0.860794 -0.508878 0.008727 +-0.738255 -0.674465 0.008727 +-0.738255 -0.674465 0.008727 +-0.860794 -0.508878 0.008727 +-0.860794 -0.508878 0.008727 +-0.738255 -0.674465 0.008727 +-0.945410 -0.325767 0.008727 +-0.860794 -0.508878 0.008727 +-0.860794 -0.508878 0.008727 +-0.945410 -0.325767 0.008727 +-0.945410 -0.325767 0.008727 +-0.860794 -0.508878 0.008727 +-0.945410 -0.325767 0.008727 +-0.990475 -0.137418 0.008727 +-0.945410 -0.325767 0.008727 +0.007637 -0.999933 0.008727 +0.007637 -0.999933 0.008727 +0.007637 -0.999933 0.008727 +0.007637 -0.999933 0.008727 +0.007637 -0.999933 0.008727 +0.007637 -0.999933 0.008727 +-0.007637 0.999933 0.008727 +-0.007637 0.999933 0.008727 +-0.007637 0.999933 0.008727 +-0.007637 0.999933 0.008727 +-0.007637 0.999933 0.008727 +-0.007637 0.999933 0.008727 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.506722 -0.092188 0.857166 +0.515038 0.000000 0.857167 +0.515038 0.000000 0.857167 +-0.515038 0.000000 0.857167 +-0.506156 -0.095249 0.857166 +-0.515038 -0.001458 0.857166 +-0.506440 -0.093718 0.857167 +-0.506156 -0.095249 0.857166 +-0.515038 0.000000 0.857167 +-0.478876 -0.189583 0.857167 +-0.506156 -0.095249 0.857166 +-0.506440 -0.093718 0.857167 +-0.478876 -0.189583 0.857167 +-0.478273 -0.191105 0.857166 +-0.506156 -0.095249 0.857166 +-0.431085 -0.281834 0.857167 +-0.478273 -0.191105 0.857166 +-0.478876 -0.189583 0.857167 +-0.431085 -0.281834 0.857167 +-0.430160 -0.283247 0.857166 +-0.478273 -0.191105 0.857166 +-0.431085 -0.281834 0.857167 +-0.364066 -0.364308 0.857167 +-0.430160 -0.283247 0.857166 +-0.364187 -0.364187 0.857167 +-0.364066 -0.364308 0.857167 +-0.431085 -0.281834 0.857167 +-0.281834 -0.431085 0.857167 +-0.364066 -0.364308 0.857167 +-0.364187 -0.364187 0.857167 +-0.281834 -0.431085 0.857167 +-0.280420 -0.432008 0.857166 +-0.364066 -0.364308 0.857167 +-0.189583 -0.478876 0.857167 +-0.280420 -0.432008 0.857166 +-0.281834 -0.431085 0.857167 +-0.189583 -0.478876 0.857167 +-0.188061 -0.479478 0.857166 +-0.280420 -0.432008 0.857166 +-0.189583 -0.478876 0.857167 +-0.092188 -0.506722 0.857166 +-0.188061 -0.479478 0.857166 +-0.093718 -0.506440 0.857167 +-0.092188 -0.506722 0.857166 +-0.189583 -0.478876 0.857167 +-0.093718 -0.506440 0.857167 +0.001458 -0.515038 0.857166 +-0.092188 -0.506722 0.857166 +0.000000 -0.515038 0.857167 +0.001458 -0.515038 0.857166 +-0.093718 -0.506440 0.857167 +0.093718 -0.506440 0.857167 +0.001458 -0.515038 0.857166 +0.000000 -0.515038 0.857167 +0.093718 -0.506440 0.857167 +0.095249 -0.506156 0.857166 +0.001458 -0.515038 0.857166 +0.189583 -0.478876 0.857167 +0.095249 -0.506156 0.857166 +0.093718 -0.506440 0.857167 +0.189583 -0.478876 0.857167 +0.191105 -0.478273 0.857166 +0.095249 -0.506156 0.857166 +0.281834 -0.431085 0.857167 +0.191105 -0.478273 0.857166 +0.189583 -0.478876 0.857167 +0.281834 -0.431085 0.857167 +0.283247 -0.430160 0.857166 +0.191105 -0.478273 0.857166 +0.364187 -0.364187 0.857167 +0.283247 -0.430160 0.857166 +0.281834 -0.431085 0.857167 +0.364187 -0.364187 0.857167 +0.364308 -0.364066 0.857167 +0.283247 -0.430160 0.857166 +0.364187 -0.364187 0.857167 +0.432008 -0.280420 0.857166 +0.364308 -0.364066 0.857167 +0.431085 -0.281834 0.857167 +0.432008 -0.280420 0.857166 +0.364187 -0.364187 0.857167 +0.431085 -0.281834 0.857167 +0.479478 -0.188061 0.857166 +0.432008 -0.280420 0.857166 +0.478876 -0.189583 0.857167 +0.479478 -0.188061 0.857166 +0.431085 -0.281834 0.857167 +0.478876 -0.189583 0.857167 +0.506722 -0.092188 0.857166 +0.479478 -0.188061 0.857166 +0.506440 -0.093718 0.857167 +0.506722 -0.092188 0.857166 +0.478876 -0.189583 0.857167 +0.515038 0.000000 0.857167 +0.506722 -0.092188 0.857166 +0.506440 -0.093718 0.857167 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +-0.706676 -0.706676 0.034899 +-0.836486 -0.546876 0.034899 +-0.836486 -0.546876 0.034899 +-0.999391 0.000000 0.034899 +-0.982706 -0.181852 0.034899 +-0.999391 0.000000 0.034899 +-0.982706 -0.181852 0.034899 +-0.982706 -0.181852 0.034899 +-0.999391 0.000000 0.034899 +-0.982706 -0.181852 0.034899 +-0.929222 -0.367870 0.034899 +-0.982706 -0.181852 0.034899 +-0.929222 -0.367870 0.034899 +-0.929222 -0.367870 0.034899 +-0.982706 -0.181852 0.034899 +-0.836486 -0.546876 0.034899 +-0.929222 -0.367870 0.034899 +-0.929222 -0.367870 0.034899 +-0.836486 -0.546876 0.034899 +-0.836486 -0.546876 0.034899 +-0.929222 -0.367870 0.034899 +0.982706 -0.181852 0.034899 +0.999391 0.000000 0.034899 +0.999391 0.000000 0.034899 +0.982706 -0.181852 0.034899 +0.982706 -0.181852 0.034899 +0.999391 0.000000 0.034899 +0.929222 -0.367870 0.034899 +0.982706 -0.181852 0.034899 +0.982706 -0.181852 0.034899 +0.929222 -0.367870 0.034899 +0.929222 -0.367870 0.034899 +0.982706 -0.181852 0.034899 +0.836486 -0.546876 0.034899 +0.929222 -0.367870 0.034899 +0.929222 -0.367870 0.034899 +0.836486 -0.546876 0.034899 +0.836486 -0.546876 0.034899 +0.929222 -0.367870 0.034899 +0.706676 -0.706676 0.034899 +0.836486 -0.546876 0.034899 +0.836486 -0.546876 0.034899 +0.706676 -0.706676 0.034899 +0.706676 -0.706676 0.034899 +0.836486 -0.546876 0.034899 +0.546876 -0.836486 0.034899 +0.706676 -0.706676 0.034899 +0.706676 -0.706676 0.034899 +0.546876 -0.836486 0.034899 +0.546876 -0.836486 0.034899 +0.706676 -0.706676 0.034899 +0.367870 -0.929222 0.034899 +0.546876 -0.836486 0.034899 +0.546876 -0.836486 0.034899 +0.367870 -0.929222 0.034899 +0.367870 -0.929222 0.034899 +0.546876 -0.836486 0.034899 +0.181852 -0.982706 0.034899 +0.367870 -0.929222 0.034899 +0.367870 -0.929222 0.034899 +0.181852 -0.982706 0.034899 +0.181852 -0.982706 0.034899 +0.367870 -0.929222 0.034899 +0.000000 -0.999391 0.034899 +0.181852 -0.982706 0.034899 +0.181852 -0.982706 0.034899 +0.000000 -0.999391 0.034899 +0.000000 -0.999391 0.034899 +0.181852 -0.982706 0.034899 +-0.181852 -0.982706 0.034899 +0.000000 -0.999391 0.034899 +0.000000 -0.999391 0.034899 +-0.181852 -0.982706 0.034899 +-0.181852 -0.982706 0.034899 +0.000000 -0.999391 0.034899 +-0.181852 -0.982706 0.034899 +-0.367870 -0.929222 0.034899 +-0.181852 -0.982706 0.034899 +-0.367870 -0.929222 0.034899 +-0.367870 -0.929222 0.034899 +-0.181852 -0.982706 0.034899 +-0.546876 -0.836486 0.034899 +-0.367870 -0.929222 0.034899 +-0.367870 -0.929222 0.034899 +-0.546876 -0.836486 0.034899 +-0.546876 -0.836486 0.034899 +-0.367870 -0.929222 0.034899 +-0.546876 -0.836486 0.034899 +-0.706676 -0.706676 0.034899 +-0.546876 -0.836486 0.034899 +-0.706676 -0.706676 0.034899 +-0.706676 -0.706676 0.034899 +-0.546876 -0.836486 0.034899 +-0.836486 -0.546876 0.034899 +-0.706676 -0.706676 0.034899 +-0.706676 -0.706676 0.034899 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.917707 0.397162 -0.008727 +0.978744 0.204902 -0.008727 +0.978744 0.204902 -0.008727 +0.707080 -0.707080 -0.008727 +0.823938 -0.566613 -0.008727 +0.707080 -0.707080 -0.008727 +0.823938 -0.566613 -0.008727 +0.823938 -0.566613 -0.008727 +0.707080 -0.707080 -0.008727 +0.823938 -0.566613 -0.008727 +0.917707 -0.397162 -0.008727 +0.823938 -0.566613 -0.008727 +0.917707 -0.397162 -0.008727 +0.917707 -0.397162 -0.008727 +0.823938 -0.566613 -0.008727 +0.917707 -0.397162 -0.008727 +0.978744 -0.204902 -0.008727 +0.917707 -0.397162 -0.008727 +0.978744 -0.204902 -0.008727 +0.978744 -0.204902 -0.008727 +0.917707 -0.397162 -0.008727 +0.978744 -0.204902 -0.008727 +0.999962 0.000000 -0.008727 +0.978744 -0.204902 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.978744 -0.204902 -0.008727 +0.999962 0.000000 -0.008727 +0.978744 0.204902 -0.008727 +0.999962 0.000000 -0.008727 +0.978744 0.204902 -0.008727 +0.978744 0.204902 -0.008727 +0.999962 0.000000 -0.008727 +-0.566613 0.823938 -0.008727 +-0.707080 0.707080 -0.008727 +-0.707080 0.707080 -0.008727 +-0.566613 0.823938 -0.008727 +-0.566613 0.823938 -0.008727 +-0.707080 0.707080 -0.008727 +-0.397162 0.917707 -0.008727 +-0.566613 0.823938 -0.008727 +-0.566613 0.823938 -0.008727 +-0.397162 0.917707 -0.008727 +-0.397162 0.917707 -0.008727 +-0.566613 0.823938 -0.008727 +-0.397162 0.917707 -0.008727 +-0.204902 0.978744 -0.008727 +-0.397162 0.917707 -0.008727 +-0.204902 0.978744 -0.008727 +-0.204902 0.978744 -0.008727 +-0.397162 0.917707 -0.008727 +0.000000 0.999962 -0.008727 +-0.204902 0.978744 -0.008727 +-0.204902 0.978744 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +-0.204902 0.978744 -0.008727 +0.204902 0.978744 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.204902 0.978744 -0.008727 +0.204902 0.978744 -0.008727 +0.000000 0.999962 -0.008727 +0.204902 0.978744 -0.008727 +0.397162 0.917707 -0.008727 +0.204902 0.978744 -0.008727 +0.397162 0.917707 -0.008727 +0.397162 0.917707 -0.008727 +0.204902 0.978744 -0.008727 +0.566613 0.823938 -0.008727 +0.397162 0.917707 -0.008727 +0.397162 0.917707 -0.008727 +0.566613 0.823938 -0.008727 +0.566613 0.823938 -0.008727 +0.397162 0.917707 -0.008727 +0.707080 0.707080 -0.008727 +0.566613 0.823938 -0.008727 +0.566613 0.823938 -0.008727 +0.707080 0.707080 -0.008727 +0.707080 0.707080 -0.008727 +0.566613 0.823938 -0.008727 +0.707080 0.707080 -0.008727 +0.823938 0.566613 -0.008727 +0.707080 0.707080 -0.008727 +0.823938 0.566613 -0.008727 +0.823938 0.566613 -0.008727 +0.707080 0.707080 -0.008727 +0.823938 0.566613 -0.008727 +0.917707 0.397162 -0.008727 +0.823938 0.566613 -0.008727 +0.917707 0.397162 -0.008727 +0.917707 0.397162 -0.008727 +0.823938 0.566613 -0.008727 +0.978744 0.204902 -0.008727 +0.917707 0.397162 -0.008727 +0.917707 0.397162 -0.008727 +-0.707080 -0.707080 -0.008727 +-0.836964 -0.547189 -0.008727 +-0.707080 -0.707080 -0.008727 +-0.707080 0.707080 -0.008727 +-0.836964 0.547189 -0.008727 +-0.707080 0.707080 -0.008727 +-0.836964 0.547189 -0.008727 +-0.836964 0.547189 -0.008727 +-0.707080 0.707080 -0.008727 +-0.929753 0.368081 -0.008727 +-0.836964 0.547189 -0.008727 +-0.836964 0.547189 -0.008727 +-0.929753 0.368081 -0.008727 +-0.929753 0.368081 -0.008727 +-0.836964 0.547189 -0.008727 +-0.983268 0.181956 -0.008727 +-0.929753 0.368081 -0.008727 +-0.929753 0.368081 -0.008727 +-0.983268 0.181956 -0.008727 +-0.983268 0.181956 -0.008727 +-0.929753 0.368081 -0.008727 +-0.999962 0.000000 -0.008727 +-0.983268 0.181956 -0.008727 +-0.983268 0.181956 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.983268 0.181956 -0.008727 +-0.999962 0.000000 -0.008727 +-0.983268 -0.181956 -0.008727 +-0.999962 0.000000 -0.008727 +-0.983268 -0.181956 -0.008727 +-0.983268 -0.181956 -0.008727 +-0.999962 0.000000 -0.008727 +-0.929753 -0.368081 -0.008727 +-0.983268 -0.181956 -0.008727 +-0.983268 -0.181956 -0.008727 +-0.929753 -0.368081 -0.008727 +-0.929753 -0.368081 -0.008727 +-0.983268 -0.181956 -0.008727 +-0.836964 -0.547189 -0.008727 +-0.929753 -0.368081 -0.008727 +-0.929753 -0.368081 -0.008727 +-0.836964 -0.547189 -0.008727 +-0.836964 -0.547189 -0.008727 +-0.929753 -0.368081 -0.008727 +-0.836964 -0.547189 -0.008727 +-0.707080 -0.707080 -0.008727 +-0.836964 -0.547189 -0.008727 +0.718121 0.695863 -0.008727 +0.838790 0.544386 -0.008727 +0.838790 0.544386 -0.008727 +0.999962 0.000000 -0.008727 +0.999838 0.015739 -0.008727 +0.999962 0.000000 -0.008727 +0.999838 0.015739 -0.008727 +0.999838 0.015739 -0.008727 +0.999962 0.000000 -0.008727 +0.978053 0.208175 -0.008727 +0.999838 0.015739 -0.008727 +0.999838 0.015739 -0.008727 +0.978053 0.208175 -0.008727 +0.978053 0.208175 -0.008727 +0.999838 0.015739 -0.008727 +0.923844 0.382669 -0.008727 +0.978053 0.208175 -0.008727 +0.978053 0.208175 -0.008727 +0.923844 0.382669 -0.008727 +0.923844 0.382669 -0.008727 +0.978053 0.208175 -0.008727 +0.838790 0.544386 -0.008727 +0.923844 0.382669 -0.008727 +0.923844 0.382669 -0.008727 +0.838790 0.544386 -0.008727 +0.838790 0.544386 -0.008727 +0.923844 0.382669 -0.008727 +0.718121 0.695863 -0.008727 +0.707080 0.707080 -0.008727 +0.707080 0.707080 -0.008727 +0.718121 0.695863 -0.008727 +0.718121 0.695863 -0.008727 +0.707080 0.707080 -0.008727 +0.838790 0.544386 -0.008727 +0.718121 0.695863 -0.008727 +0.718121 0.695863 -0.008727 +0.707080 -0.707080 -0.008727 +0.836964 -0.547189 -0.008727 +0.707080 -0.707080 -0.008727 +0.707080 0.707080 -0.008727 +0.836964 0.547189 -0.008727 +0.707080 0.707080 -0.008727 +0.836964 0.547189 -0.008727 +0.836964 0.547189 -0.008727 +0.707080 0.707080 -0.008727 +0.929753 0.368081 -0.008727 +0.836964 0.547189 -0.008727 +0.836964 0.547189 -0.008727 +0.929753 0.368081 -0.008727 +0.929753 0.368081 -0.008727 +0.836964 0.547189 -0.008727 +0.929753 0.368081 -0.008727 +0.983268 0.181956 -0.008727 +0.929753 0.368081 -0.008727 +0.983268 0.181956 -0.008727 +0.983268 0.181956 -0.008727 +0.929753 0.368081 -0.008727 +0.999962 0.000000 -0.008727 +0.983268 0.181956 -0.008727 +0.983268 0.181956 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.983268 0.181956 -0.008727 +0.999962 0.000000 -0.008727 +0.983268 -0.181956 -0.008727 +0.999962 0.000000 -0.008727 +0.983268 -0.181956 -0.008727 +0.983268 -0.181956 -0.008727 +0.999962 0.000000 -0.008727 +0.983268 -0.181956 -0.008727 +0.929753 -0.368081 -0.008727 +0.983268 -0.181956 -0.008727 +0.929753 -0.368081 -0.008727 +0.929753 -0.368081 -0.008727 +0.983268 -0.181956 -0.008727 +0.836964 -0.547189 -0.008727 +0.929753 -0.368081 -0.008727 +0.929753 -0.368081 -0.008727 +0.836964 -0.547189 -0.008727 +0.836964 -0.547189 -0.008727 +0.929753 -0.368081 -0.008727 +0.836964 -0.547189 -0.008727 +0.707080 -0.707080 -0.008727 +0.836964 -0.547189 -0.008727 +-0.978744 -0.204902 -0.008727 +-0.999962 0.000000 -0.008727 +-0.978744 -0.204902 -0.008727 +-0.707080 -0.707080 -0.008727 +-0.823938 -0.566613 -0.008727 +-0.707080 -0.707080 -0.008727 +-0.823938 -0.566613 -0.008727 +-0.823938 -0.566613 -0.008727 +-0.707080 -0.707080 -0.008727 +-0.917707 -0.397162 -0.008727 +-0.823938 -0.566613 -0.008727 +-0.823938 -0.566613 -0.008727 +-0.917707 -0.397162 -0.008727 +-0.917707 -0.397162 -0.008727 +-0.823938 -0.566613 -0.008727 +-0.978744 -0.204902 -0.008727 +-0.917707 -0.397162 -0.008727 +-0.917707 -0.397162 -0.008727 +-0.978744 -0.204902 -0.008727 +-0.978744 -0.204902 -0.008727 +-0.917707 -0.397162 -0.008727 +0.566613 0.823938 -0.008727 +0.707080 0.707080 -0.008727 +0.707080 0.707080 -0.008727 +0.566613 0.823938 -0.008727 +0.566613 0.823938 -0.008727 +0.707080 0.707080 -0.008727 +0.566613 0.823938 -0.008727 +0.397162 0.917707 -0.008727 +0.566613 0.823938 -0.008727 +0.397162 0.917707 -0.008727 +0.397162 0.917707 -0.008727 +0.566613 0.823938 -0.008727 +0.204902 0.978744 -0.008727 +0.397162 0.917707 -0.008727 +0.397162 0.917707 -0.008727 +0.204902 0.978744 -0.008727 +0.204902 0.978744 -0.008727 +0.397162 0.917707 -0.008727 +0.000000 0.999962 -0.008727 +0.204902 0.978744 -0.008727 +0.204902 0.978744 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.204902 0.978744 -0.008727 +0.000000 0.999962 -0.008727 +-0.204902 0.978744 -0.008727 +0.000000 0.999962 -0.008727 +-0.204902 0.978744 -0.008727 +-0.204902 0.978744 -0.008727 +0.000000 0.999962 -0.008727 +-0.397162 0.917707 -0.008727 +-0.204902 0.978744 -0.008727 +-0.204902 0.978744 -0.008727 +-0.397162 0.917707 -0.008727 +-0.397162 0.917707 -0.008727 +-0.204902 0.978744 -0.008727 +-0.397162 0.917707 -0.008727 +-0.566613 0.823938 -0.008727 +-0.397162 0.917707 -0.008727 +-0.566613 0.823938 -0.008727 +-0.566613 0.823938 -0.008727 +-0.397162 0.917707 -0.008727 +-0.707080 0.707080 -0.008727 +-0.566613 0.823938 -0.008727 +-0.566613 0.823938 -0.008727 +-0.707080 0.707080 -0.008727 +-0.707080 0.707080 -0.008727 +-0.566613 0.823938 -0.008727 +-0.823938 0.566613 -0.008727 +-0.707080 0.707080 -0.008727 +-0.707080 0.707080 -0.008727 +-0.823938 0.566613 -0.008727 +-0.823938 0.566613 -0.008727 +-0.707080 0.707080 -0.008727 +-0.917707 0.397162 -0.008727 +-0.823938 0.566613 -0.008727 +-0.823938 0.566613 -0.008727 +-0.917707 0.397162 -0.008727 +-0.917707 0.397162 -0.008727 +-0.823938 0.566613 -0.008727 +-0.978744 0.204902 -0.008727 +-0.917707 0.397162 -0.008727 +-0.917707 0.397162 -0.008727 +-0.978744 0.204902 -0.008727 +-0.978744 0.204902 -0.008727 +-0.917707 0.397162 -0.008727 +-0.999962 0.000000 -0.008727 +-0.978744 0.204902 -0.008727 +-0.978744 0.204902 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.978744 0.204902 -0.008727 +-0.999962 0.000000 -0.008727 +-0.978744 -0.204902 -0.008727 +-0.999962 0.000000 -0.008727 +-0.707080 0.707080 -0.008727 +-0.836964 0.547189 -0.008727 +-0.707080 0.707080 -0.008727 +-0.707080 -0.707080 -0.008727 +-0.836964 -0.547189 -0.008727 +-0.707080 -0.707080 -0.008727 +-0.836964 -0.547189 -0.008727 +-0.836964 -0.547189 -0.008727 +-0.707080 -0.707080 -0.008727 +-0.929753 -0.368081 -0.008727 +-0.836964 -0.547189 -0.008727 +-0.836964 -0.547189 -0.008727 +-0.929753 -0.368081 -0.008727 +-0.929753 -0.368081 -0.008727 +-0.836964 -0.547189 -0.008727 +-0.983268 -0.181956 -0.008727 +-0.929753 -0.368081 -0.008727 +-0.929753 -0.368081 -0.008727 +-0.983268 -0.181956 -0.008727 +-0.983268 -0.181956 -0.008727 +-0.929753 -0.368081 -0.008727 +-0.999962 0.000000 -0.008727 +-0.983268 -0.181956 -0.008727 +-0.983268 -0.181956 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.983268 -0.181956 -0.008727 +-0.999962 0.000000 -0.008727 +-0.983268 0.181956 -0.008727 +-0.999962 0.000000 -0.008727 +-0.983268 0.181956 -0.008727 +-0.983268 0.181956 -0.008727 +-0.999962 0.000000 -0.008727 +-0.929753 0.368081 -0.008727 +-0.983268 0.181956 -0.008727 +-0.983268 0.181956 -0.008727 +-0.929753 0.368081 -0.008727 +-0.929753 0.368081 -0.008727 +-0.983268 0.181956 -0.008727 +-0.929753 0.368081 -0.008727 +-0.836964 0.547189 -0.008727 +-0.929753 0.368081 -0.008727 +-0.836964 0.547189 -0.008727 +-0.836964 0.547189 -0.008727 +-0.929753 0.368081 -0.008727 +-0.836964 0.547189 -0.008727 +-0.707080 0.707080 -0.008727 +-0.836964 0.547189 -0.008727 +-0.382669 -0.923844 -0.008727 +-0.544386 -0.838790 -0.008727 +-0.544386 -0.838790 -0.008727 +-0.999962 0.000000 -0.008727 +-0.982654 -0.185245 -0.008727 +-0.999962 0.000000 -0.008727 +-0.982654 -0.185245 -0.008727 +-0.982654 -0.185245 -0.008727 +-0.999962 0.000000 -0.008727 +-0.923844 -0.382669 -0.008727 +-0.982654 -0.185245 -0.008727 +-0.982654 -0.185245 -0.008727 +-0.923844 -0.382669 -0.008727 +-0.923844 -0.382669 -0.008727 +-0.982654 -0.185245 -0.008727 +-0.923844 -0.382669 -0.008727 +-0.825829 -0.563853 -0.008727 +-0.923844 -0.382669 -0.008727 +-0.825829 -0.563853 -0.008727 +-0.825829 -0.563853 -0.008727 +-0.923844 -0.382669 -0.008727 +-0.825829 -0.563853 -0.008727 +-0.695863 -0.718121 -0.008727 +-0.825829 -0.563853 -0.008727 +-0.695863 -0.718121 -0.008727 +-0.695863 -0.718121 -0.008727 +-0.825829 -0.563853 -0.008727 +-0.544386 -0.838790 -0.008727 +-0.695863 -0.718121 -0.008727 +-0.695863 -0.718121 -0.008727 +-0.544386 -0.838790 -0.008727 +-0.544386 -0.838790 -0.008727 +-0.695863 -0.718121 -0.008727 +0.563853 -0.825829 -0.008727 +0.707080 -0.707080 -0.008727 +0.707080 -0.707080 -0.008727 +0.563853 -0.825829 -0.008727 +0.563853 -0.825829 -0.008727 +0.707080 -0.707080 -0.008727 +0.382669 -0.923844 -0.008727 +0.563853 -0.825829 -0.008727 +0.563853 -0.825829 -0.008727 +0.382669 -0.923844 -0.008727 +0.382669 -0.923844 -0.008727 +0.563853 -0.825829 -0.008727 +0.382669 -0.923844 -0.008727 +0.185245 -0.982654 -0.008727 +0.382669 -0.923844 -0.008727 +0.185245 -0.982654 -0.008727 +0.185245 -0.982654 -0.008727 +0.382669 -0.923844 -0.008727 +-0.015739 -0.999838 -0.008727 +0.185245 -0.982654 -0.008727 +0.185245 -0.982654 -0.008727 +-0.015739 -0.999838 -0.008727 +-0.015739 -0.999838 -0.008727 +0.185245 -0.982654 -0.008727 +-0.208175 -0.978053 -0.008727 +-0.015739 -0.999838 -0.008727 +-0.015739 -0.999838 -0.008727 +-0.208175 -0.978053 -0.008727 +-0.208175 -0.978053 -0.008727 +-0.015739 -0.999838 -0.008727 +-0.382669 -0.923844 -0.008727 +-0.208175 -0.978053 -0.008727 +-0.208175 -0.978053 -0.008727 +-0.382669 -0.923844 -0.008727 +-0.382669 -0.923844 -0.008727 +-0.208175 -0.978053 -0.008727 +-0.544386 -0.838790 -0.008727 +-0.382669 -0.923844 -0.008727 +-0.382669 -0.923844 -0.008727 +0.929753 0.368081 -0.008727 +0.983268 0.181956 -0.008727 +0.929753 0.368081 -0.008727 +0.836964 0.547189 -0.008727 +0.707080 0.707080 -0.008727 +0.707080 0.707080 -0.008727 +0.836964 0.547189 -0.008727 +0.836964 0.547189 -0.008727 +0.707080 0.707080 -0.008727 +0.836964 0.547189 -0.008727 +0.929753 0.368081 -0.008727 +0.836964 0.547189 -0.008727 +0.929753 0.368081 -0.008727 +0.929753 0.368081 -0.008727 +0.836964 0.547189 -0.008727 +0.836964 -0.547189 -0.008727 +0.707080 -0.707080 -0.008727 +0.707080 -0.707080 -0.008727 +0.836964 -0.547189 -0.008727 +0.836964 -0.547189 -0.008727 +0.707080 -0.707080 -0.008727 +0.929753 -0.368081 -0.008727 +0.836964 -0.547189 -0.008727 +0.836964 -0.547189 -0.008727 +0.929753 -0.368081 -0.008727 +0.929753 -0.368081 -0.008727 +0.836964 -0.547189 -0.008727 +0.983268 -0.181956 -0.008727 +0.929753 -0.368081 -0.008727 +0.929753 -0.368081 -0.008727 +0.983268 -0.181956 -0.008727 +0.983268 -0.181956 -0.008727 +0.929753 -0.368081 -0.008727 +0.999962 0.000000 -0.008727 +0.983268 -0.181956 -0.008727 +0.983268 -0.181956 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.983268 -0.181956 -0.008727 +0.983268 0.181956 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.983268 0.181956 -0.008727 +0.983268 0.181956 -0.008727 +0.999962 0.000000 -0.008727 +0.983268 0.181956 -0.008727 +0.929753 0.368081 -0.008727 +0.983268 0.181956 -0.008727 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.866025 -0.500000 0.000000 +0.866025 -0.500000 0.000000 +0.866025 -0.500000 0.000000 +0.866025 -0.500000 0.000000 +0.866025 -0.500000 0.000000 +0.866025 -0.500000 0.000000 +0.866025 -0.500000 0.000000 +0.866025 -0.500000 0.000000 +0.866025 -0.500000 0.000000 +0.500000 0.866025 0.000000 +0.500000 0.866025 0.000000 +0.500000 0.866025 0.000000 +0.500000 0.866025 0.000000 +0.500000 0.866025 0.000000 +0.500000 0.866025 0.000000 +-0.866025 0.500000 0.000000 +-0.866025 0.500000 0.000000 +-0.866025 0.500000 0.000000 +-0.866025 0.500000 0.000000 +-0.866025 0.500000 0.000000 +-0.866025 0.500000 0.000000 +-0.866025 0.500000 0.000000 +-0.866025 0.500000 0.000000 +-0.866025 0.500000 0.000000 +-0.500000 -0.866025 0.000000 +-0.500000 -0.866025 0.000000 +-0.500000 -0.866025 0.000000 +-0.500000 -0.866025 0.000000 +-0.500000 -0.866025 0.000000 +-0.500000 -0.866025 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.866025 -0.500000 0.000000 +-0.866025 -0.500000 0.000000 +-0.866025 -0.500000 0.000000 +-0.866025 -0.500000 0.000000 +-0.866025 -0.500000 0.000000 +-0.866025 -0.500000 0.000000 +-0.866025 -0.500000 0.000000 +-0.866025 -0.500000 0.000000 +-0.866025 -0.500000 0.000000 +0.500000 -0.866025 0.000000 +0.500000 -0.866025 0.000000 +0.500000 -0.866025 0.000000 +0.500000 -0.866025 0.000000 +0.500000 -0.866025 0.000000 +0.500000 -0.866025 0.000000 +0.866025 0.500000 0.000000 +0.866025 0.500000 0.000000 +0.866025 0.500000 0.000000 +0.866025 0.500000 0.000000 +0.866025 0.500000 0.000000 +0.866025 0.500000 0.000000 +0.866025 0.500000 0.000000 +0.866025 0.500000 0.000000 +0.866025 0.500000 0.000000 +-0.500000 0.866025 0.000000 +-0.500000 0.866025 0.000000 +-0.500000 0.866025 0.000000 +-0.500000 0.866025 0.000000 +-0.500000 0.866025 0.000000 +-0.500000 0.866025 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 -0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +-0.353553 0.612372 0.707107 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.204909 0.978781 0.000000 +0.000000 1.000000 0.000000 +0.368095 0.929788 0.000000 +0.204909 0.978781 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.397177 0.917742 0.000000 +0.204909 0.978781 0.000000 +0.547210 0.836995 0.000000 +0.397177 0.917742 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.566635 0.823969 0.000000 +0.397177 0.917742 0.000000 +0.630298 0.776353 0.000000 +0.566635 0.823969 0.000000 +0.547210 0.836995 0.000000 +0.630298 0.776353 0.000000 +0.707107 0.707107 0.000000 +0.566635 0.823969 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.630298 0.776353 0.000000 +0.776353 0.630298 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.776353 0.630298 0.000000 +0.823969 0.566635 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.823969 0.566635 0.000000 +0.776353 0.630298 0.000000 +0.836995 0.547210 0.000000 +0.917742 0.397177 0.000000 +0.823969 0.566635 0.000000 +0.929788 0.368095 0.000000 +0.917742 0.397177 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.978781 0.204909 0.000000 +0.917742 0.397177 0.000000 +0.983305 0.181963 0.000000 +0.978781 0.204909 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.978781 0.204909 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.204909 -0.978781 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.204909 -0.978781 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.397177 -0.917742 0.000000 +0.368095 -0.929788 0.000000 +0.204909 -0.978781 0.000000 +0.397177 -0.917742 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.566635 -0.823969 0.000000 +0.547210 -0.836995 0.000000 +0.397177 -0.917742 0.000000 +0.566635 -0.823969 0.000000 +0.630298 -0.776353 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.630298 -0.776353 0.000000 +0.566635 -0.823969 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.630298 -0.776353 0.000000 +0.707107 -0.707107 0.000000 +0.776353 -0.630298 0.000000 +0.707107 -0.707107 0.000000 +0.823969 -0.566635 0.000000 +0.776353 -0.630298 0.000000 +0.707107 -0.707107 0.000000 +0.823969 -0.566635 0.000000 +0.836995 -0.547210 0.000000 +0.776353 -0.630298 0.000000 +0.917742 -0.397177 0.000000 +0.836995 -0.547210 0.000000 +0.823969 -0.566635 0.000000 +0.917742 -0.397177 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.978781 -0.204909 0.000000 +0.929788 -0.368095 0.000000 +0.917742 -0.397177 0.000000 +0.978781 -0.204909 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.978781 -0.204909 0.000000 +-1.000000 0.000000 0.000000 +-0.978781 0.204909 0.000000 +-1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +-0.204909 0.978781 0.000000 +0.000000 1.000000 0.000000 +-0.204909 0.978781 0.000000 +-0.204909 0.978781 0.000000 +0.000000 1.000000 0.000000 +-0.397177 0.917742 0.000000 +-0.204909 0.978781 0.000000 +-0.204909 0.978781 0.000000 +-0.397177 0.917742 0.000000 +-0.397177 0.917742 0.000000 +-0.204909 0.978781 0.000000 +-0.566635 0.823969 0.000000 +-0.397177 0.917742 0.000000 +-0.397177 0.917742 0.000000 +-0.566635 0.823969 0.000000 +-0.566635 0.823969 0.000000 +-0.397177 0.917742 0.000000 +-0.566635 0.823969 0.000000 +-0.707107 0.707107 0.000000 +-0.566635 0.823969 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.566635 0.823969 0.000000 +-0.823969 0.566635 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.823969 0.566635 0.000000 +-0.823969 0.566635 0.000000 +-0.707107 0.707107 0.000000 +-0.823969 0.566635 0.000000 +-0.917742 0.397177 0.000000 +-0.823969 0.566635 0.000000 +-0.917742 0.397177 0.000000 +-0.917742 0.397177 0.000000 +-0.823969 0.566635 0.000000 +-0.917742 0.397177 0.000000 +-0.978781 0.204909 0.000000 +-0.917742 0.397177 0.000000 +-0.978781 0.204909 0.000000 +-0.978781 0.204909 0.000000 +-0.917742 0.397177 0.000000 +-0.978781 0.204909 0.000000 +-1.000000 0.000000 0.000000 +-0.978781 0.204909 0.000000 +-0.978781 -0.204909 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.204909 -0.978781 0.000000 +0.000000 -1.000000 0.000000 +-0.204909 -0.978781 0.000000 +-0.204909 -0.978781 0.000000 +0.000000 -1.000000 0.000000 +-0.397177 -0.917742 0.000000 +-0.204909 -0.978781 0.000000 +-0.204909 -0.978781 0.000000 +-0.397177 -0.917742 0.000000 +-0.397177 -0.917742 0.000000 +-0.204909 -0.978781 0.000000 +-0.397177 -0.917742 0.000000 +-0.566635 -0.823969 0.000000 +-0.397177 -0.917742 0.000000 +-0.566635 -0.823969 0.000000 +-0.566635 -0.823969 0.000000 +-0.397177 -0.917742 0.000000 +-0.707107 -0.707107 0.000000 +-0.566635 -0.823969 0.000000 +-0.566635 -0.823969 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.566635 -0.823969 0.000000 +-0.707107 -0.707107 0.000000 +-0.823969 -0.566635 0.000000 +-0.707107 -0.707107 0.000000 +-0.823969 -0.566635 0.000000 +-0.823969 -0.566635 0.000000 +-0.707107 -0.707107 0.000000 +-0.917742 -0.397177 0.000000 +-0.823969 -0.566635 0.000000 +-0.823969 -0.566635 0.000000 +-0.917742 -0.397177 0.000000 +-0.917742 -0.397177 0.000000 +-0.823969 -0.566635 0.000000 +-0.978781 -0.204909 0.000000 +-0.917742 -0.397177 0.000000 +-0.917742 -0.397177 0.000000 +-0.978781 -0.204909 0.000000 +-0.978781 -0.204909 0.000000 +-0.917742 -0.397177 0.000000 +-1.000000 0.000000 0.000000 +-0.978781 -0.204909 0.000000 +-0.978781 -0.204909 0.000000 +-0.500000 -0.866025 0.000000 +-0.334068 -0.942549 0.000000 +-0.500000 -0.866025 0.000000 +0.760586 -0.649237 0.000000 +0.866025 -0.500000 0.000000 +0.866025 -0.500000 0.000000 +0.760586 -0.649237 0.000000 +0.745194 -0.666847 0.000000 +0.866025 -0.500000 0.000000 +0.621173 -0.783674 0.000000 +0.745194 -0.666847 0.000000 +0.760586 -0.649237 0.000000 +0.621173 -0.783674 0.000000 +0.596199 -0.802837 0.000000 +0.745194 -0.666847 0.000000 +0.451254 -0.892395 0.000000 +0.596199 -0.802837 0.000000 +0.621173 -0.783674 0.000000 +0.451254 -0.892395 0.000000 +0.430261 -0.902705 0.000000 +0.596199 -0.802837 0.000000 +0.357193 -0.934031 0.000000 +0.430261 -0.902705 0.000000 +0.451254 -0.892395 0.000000 +0.357193 -0.934031 0.000000 +0.258819 -0.965926 0.000000 +0.430261 -0.902705 0.000000 +0.258819 -0.965926 0.000000 +0.258819 -0.965926 0.000000 +0.357193 -0.934031 0.000000 +0.157678 -0.987491 0.000000 +0.258819 -0.965926 0.000000 +0.258819 -0.965926 0.000000 +0.157678 -0.987491 0.000000 +0.078735 -0.996896 0.000000 +0.258819 -0.965926 0.000000 +0.055400 -0.998464 0.000000 +0.078735 -0.996896 0.000000 +0.157678 -0.987491 0.000000 +0.055400 -0.998464 0.000000 +-0.114905 -0.993376 0.000000 +0.078735 -0.996896 0.000000 +-0.146115 -0.989268 0.000000 +-0.114905 -0.993376 0.000000 +0.055400 -0.998464 0.000000 +-0.146115 -0.989268 0.000000 +-0.311934 -0.950104 0.000000 +-0.114905 -0.993376 0.000000 +-0.334068 -0.942549 0.000000 +-0.311934 -0.950104 0.000000 +-0.146115 -0.989268 0.000000 +-0.334068 -0.942549 0.000000 +-0.500000 -0.866025 0.000000 +-0.311934 -0.950104 0.000000 +-1.000000 0.000000 0.000000 +-0.996896 0.078735 0.000000 +-1.000000 0.000000 0.000000 +-0.866025 0.500000 0.000000 +-0.923664 0.383204 0.000000 +-0.866025 0.500000 0.000000 +-0.902705 0.430261 0.000000 +-0.923664 0.383204 0.000000 +-0.866025 0.500000 0.000000 +-0.965926 0.258819 0.000000 +-0.923664 0.383204 0.000000 +-0.902705 0.430261 0.000000 +-0.965926 0.258819 0.000000 +-0.965926 0.258819 0.000000 +-0.923664 0.383204 0.000000 +-0.965926 0.258819 0.000000 +-0.991518 0.129968 0.000000 +-0.965926 0.258819 0.000000 +-0.996896 0.078735 0.000000 +-0.991518 0.129968 0.000000 +-0.965926 0.258819 0.000000 +-0.996896 0.078735 0.000000 +-1.000000 0.000000 0.000000 +-0.991518 0.129968 0.000000 +0.950104 -0.311934 0.000000 +0.866025 -0.500000 0.000000 +0.866025 -0.500000 0.000000 +0.500000 0.866025 0.000000 +0.666847 0.745194 0.000000 +0.500000 0.866025 0.000000 +0.666847 0.745194 0.000000 +0.666847 0.745194 0.000000 +0.500000 0.866025 0.000000 +0.802837 0.596199 0.000000 +0.666847 0.745194 0.000000 +0.666847 0.745194 0.000000 +0.802837 0.596199 0.000000 +0.802837 0.596199 0.000000 +0.666847 0.745194 0.000000 +0.902705 0.430261 0.000000 +0.802837 0.596199 0.000000 +0.802837 0.596199 0.000000 +0.902705 0.430261 0.000000 +0.902705 0.430261 0.000000 +0.802837 0.596199 0.000000 +0.902705 0.430261 0.000000 +0.965926 0.258819 0.000000 +0.902705 0.430261 0.000000 +0.965926 0.258819 0.000000 +0.965926 0.258819 0.000000 +0.902705 0.430261 0.000000 +0.965926 0.258819 0.000000 +0.996896 0.078735 0.000000 +0.965926 0.258819 0.000000 +0.996896 0.078735 0.000000 +0.996896 0.078735 0.000000 +0.965926 0.258819 0.000000 +0.993376 -0.114905 0.000000 +0.996896 0.078735 0.000000 +0.996896 0.078735 0.000000 +0.993376 -0.114905 0.000000 +0.993376 -0.114905 0.000000 +0.996896 0.078735 0.000000 +0.950104 -0.311934 0.000000 +0.993376 -0.114905 0.000000 +0.993376 -0.114905 0.000000 +0.950104 -0.311934 0.000000 +0.950104 -0.311934 0.000000 +0.993376 -0.114905 0.000000 +0.866025 -0.500000 0.000000 +0.950104 -0.311934 0.000000 +0.950104 -0.311934 0.000000 +-0.258819 0.965926 0.000000 +-0.430261 0.902705 0.000000 +-0.258819 0.965926 0.000000 +0.311934 0.950104 0.000000 +0.500000 0.866025 0.000000 +0.500000 0.866025 0.000000 +0.311934 0.950104 0.000000 +0.311934 0.950104 0.000000 +0.500000 0.866025 0.000000 +0.311934 0.950104 0.000000 +0.114905 0.993376 0.000000 +0.311934 0.950104 0.000000 +0.114905 0.993376 0.000000 +0.114905 0.993376 0.000000 +0.311934 0.950104 0.000000 +0.114905 0.993376 0.000000 +-0.078735 0.996896 0.000000 +0.114905 0.993376 0.000000 +-0.078735 0.996896 0.000000 +-0.078735 0.996896 0.000000 +0.114905 0.993376 0.000000 +-0.078735 0.996896 0.000000 +-0.258819 0.965926 0.000000 +-0.078735 0.996896 0.000000 +-0.258819 0.965926 0.000000 +-0.258819 0.965926 0.000000 +-0.078735 0.996896 0.000000 +-0.745194 0.666847 0.000000 +-0.866025 0.500000 0.000000 +-0.866025 0.500000 0.000000 +-0.745194 0.666847 0.000000 +-0.745194 0.666847 0.000000 +-0.866025 0.500000 0.000000 +-0.596199 0.802837 0.000000 +-0.745194 0.666847 0.000000 +-0.745194 0.666847 0.000000 +-0.596199 0.802837 0.000000 +-0.596199 0.802837 0.000000 +-0.745194 0.666847 0.000000 +-0.596199 0.802837 0.000000 +-0.430261 0.902705 0.000000 +-0.596199 0.802837 0.000000 +-0.430261 0.902705 0.000000 +-0.430261 0.902705 0.000000 +-0.596199 0.802837 0.000000 +-0.430261 0.902705 0.000000 +-0.258819 0.965926 0.000000 +-0.430261 0.902705 0.000000 +-0.866025 0.500000 0.000000 +-0.924976 0.380026 0.000000 +-0.866025 0.500000 0.000000 +-0.621173 0.783674 0.000000 +-0.500000 0.866025 0.000000 +-0.500000 0.866025 0.000000 +-0.621173 0.783674 0.000000 +-0.605630 0.795747 0.000000 +-0.500000 0.866025 0.000000 +-0.621173 0.783674 0.000000 +-0.703872 0.710326 0.000000 +-0.605630 0.795747 0.000000 +-0.760586 0.649237 0.000000 +-0.703872 0.710326 0.000000 +-0.621173 0.783674 0.000000 +-0.760586 0.649237 0.000000 +-0.791600 0.611040 0.000000 +-0.703872 0.710326 0.000000 +-0.866025 0.500000 0.000000 +-0.791600 0.611040 0.000000 +-0.760586 0.649237 0.000000 +-0.866025 0.500000 0.000000 +-0.866025 0.500000 0.000000 +-0.791600 0.611040 0.000000 +-0.991952 0.126617 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.991952 0.126617 0.000000 +-0.989268 0.146115 0.000000 +-1.000000 0.000000 0.000000 +-0.967097 0.254408 0.000000 +-0.989268 0.146115 0.000000 +-0.991952 0.126617 0.000000 +-0.967097 0.254408 0.000000 +-0.942549 0.334068 0.000000 +-0.989268 0.146115 0.000000 +-0.924976 0.380026 0.000000 +-0.942549 0.334068 0.000000 +-0.967097 0.254408 0.000000 +-0.924976 0.380026 0.000000 +-0.866025 0.500000 0.000000 +-0.942549 0.334068 0.000000 +-0.334068 0.942549 0.000000 +-0.500000 0.866025 0.000000 +-0.500000 0.866025 0.000000 +0.866025 0.500000 0.000000 +0.760586 0.649237 0.000000 +0.866025 0.500000 0.000000 +0.745194 0.666847 0.000000 +0.760586 0.649237 0.000000 +0.866025 0.500000 0.000000 +0.745194 0.666847 0.000000 +0.621173 0.783674 0.000000 +0.760586 0.649237 0.000000 +0.596199 0.802837 0.000000 +0.621173 0.783674 0.000000 +0.745194 0.666847 0.000000 +0.596199 0.802837 0.000000 +0.451254 0.892395 0.000000 +0.621173 0.783674 0.000000 +0.430261 0.902705 0.000000 +0.451254 0.892395 0.000000 +0.596199 0.802837 0.000000 +0.430261 0.902705 0.000000 +0.357193 0.934031 0.000000 +0.451254 0.892395 0.000000 +0.258819 0.965926 0.000000 +0.357193 0.934031 0.000000 +0.430261 0.902705 0.000000 +0.258819 0.965926 0.000000 +0.258819 0.965926 0.000000 +0.357193 0.934031 0.000000 +0.258819 0.965926 0.000000 +0.157678 0.987491 0.000000 +0.258819 0.965926 0.000000 +0.078735 0.996896 0.000000 +0.157678 0.987491 0.000000 +0.258819 0.965926 0.000000 +0.078735 0.996896 0.000000 +0.055400 0.998464 0.000000 +0.157678 0.987491 0.000000 +-0.114905 0.993376 0.000000 +0.055400 0.998464 0.000000 +0.078735 0.996896 0.000000 +-0.114905 0.993376 0.000000 +-0.146115 0.989268 0.000000 +0.055400 0.998464 0.000000 +-0.311934 0.950104 0.000000 +-0.146115 0.989268 0.000000 +-0.114905 0.993376 0.000000 +-0.311934 0.950104 0.000000 +-0.334068 0.942549 0.000000 +-0.146115 0.989268 0.000000 +-0.500000 0.866025 0.000000 +-0.334068 0.942549 0.000000 +-0.311934 0.950104 0.000000 +-0.866025 -0.500000 0.000000 +-0.745194 -0.666847 0.000000 +-0.866025 -0.500000 0.000000 +0.311934 -0.950104 0.000000 +0.500000 -0.866025 0.000000 +0.500000 -0.866025 0.000000 +0.311934 -0.950104 0.000000 +0.311934 -0.950104 0.000000 +0.500000 -0.866025 0.000000 +0.114905 -0.993376 0.000000 +0.311934 -0.950104 0.000000 +0.311934 -0.950104 0.000000 +0.114905 -0.993376 0.000000 +0.114905 -0.993376 0.000000 +0.311934 -0.950104 0.000000 +0.114905 -0.993376 0.000000 +-0.078735 -0.996896 0.000000 +0.114905 -0.993376 0.000000 +-0.078735 -0.996896 0.000000 +-0.078735 -0.996896 0.000000 +0.114905 -0.993376 0.000000 +-0.258819 -0.965926 0.000000 +-0.078735 -0.996896 0.000000 +-0.078735 -0.996896 0.000000 +-0.258819 -0.965926 0.000000 +-0.258819 -0.965926 0.000000 +-0.078735 -0.996896 0.000000 +-0.430261 -0.902705 0.000000 +-0.258819 -0.965926 0.000000 +-0.258819 -0.965926 0.000000 +-0.430261 -0.902705 0.000000 +-0.430261 -0.902705 0.000000 +-0.258819 -0.965926 0.000000 +-0.596199 -0.802837 0.000000 +-0.430261 -0.902705 0.000000 +-0.430261 -0.902705 0.000000 +-0.596199 -0.802837 0.000000 +-0.596199 -0.802837 0.000000 +-0.430261 -0.902705 0.000000 +-0.596199 -0.802837 0.000000 +-0.745194 -0.666847 0.000000 +-0.596199 -0.802837 0.000000 +-0.745194 -0.666847 0.000000 +-0.745194 -0.666847 0.000000 +-0.596199 -0.802837 0.000000 +-0.745194 -0.666847 0.000000 +-0.866025 -0.500000 0.000000 +-0.745194 -0.666847 0.000000 +0.996896 -0.078735 0.000000 +0.993376 0.114905 0.000000 +0.993376 0.114905 0.000000 +0.866025 0.500000 0.000000 +0.950104 0.311934 0.000000 +0.866025 0.500000 0.000000 +0.950104 0.311934 0.000000 +0.950104 0.311934 0.000000 +0.866025 0.500000 0.000000 +0.950104 0.311934 0.000000 +0.993376 0.114905 0.000000 +0.950104 0.311934 0.000000 +0.993376 0.114905 0.000000 +0.993376 0.114905 0.000000 +0.950104 0.311934 0.000000 +0.666847 -0.745194 0.000000 +0.500000 -0.866025 0.000000 +0.500000 -0.866025 0.000000 +0.666847 -0.745194 0.000000 +0.666847 -0.745194 0.000000 +0.500000 -0.866025 0.000000 +0.666847 -0.745194 0.000000 +0.802837 -0.596199 0.000000 +0.666847 -0.745194 0.000000 +0.802837 -0.596199 0.000000 +0.802837 -0.596199 0.000000 +0.666847 -0.745194 0.000000 +0.802837 -0.596199 0.000000 +0.902705 -0.430261 0.000000 +0.802837 -0.596199 0.000000 +0.902705 -0.430261 0.000000 +0.902705 -0.430261 0.000000 +0.802837 -0.596199 0.000000 +0.965926 -0.258819 0.000000 +0.902705 -0.430261 0.000000 +0.902705 -0.430261 0.000000 +0.965926 -0.258819 0.000000 +0.965926 -0.258819 0.000000 +0.902705 -0.430261 0.000000 +0.996896 -0.078735 0.000000 +0.965926 -0.258819 0.000000 +0.965926 -0.258819 0.000000 +0.996896 -0.078735 0.000000 +0.996896 -0.078735 0.000000 +0.965926 -0.258819 0.000000 +0.993376 0.114905 0.000000 +0.996896 -0.078735 0.000000 +0.996896 -0.078735 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.695302 -0.128667 -0.707107 +-0.707107 0.000000 -0.707107 +-0.707107 0.000000 -0.707107 +0.707107 0.000000 -0.707107 +0.695302 -0.128667 -0.707107 +0.707107 0.000000 -0.707107 +0.695302 -0.128667 -0.707107 +0.695302 -0.128667 -0.707107 +0.707107 0.000000 -0.707107 +0.657460 -0.260282 -0.707107 +0.695302 -0.128667 -0.707107 +0.695302 -0.128667 -0.707107 +0.657460 -0.260282 -0.707107 +0.657460 -0.260282 -0.707107 +0.695302 -0.128667 -0.707107 +0.591845 -0.386936 -0.707107 +0.657460 -0.260282 -0.707107 +0.657460 -0.260282 -0.707107 +0.591845 -0.386936 -0.707107 +0.591845 -0.386936 -0.707107 +0.657460 -0.260282 -0.707107 +0.500000 -0.500000 -0.707107 +0.591845 -0.386936 -0.707107 +0.591845 -0.386936 -0.707107 +0.500000 -0.500000 -0.707107 +0.500000 -0.500000 -0.707107 +0.591845 -0.386936 -0.707107 +0.386936 -0.591845 -0.707107 +0.500000 -0.500000 -0.707107 +0.500000 -0.500000 -0.707107 +0.386936 -0.591845 -0.707107 +0.386936 -0.591845 -0.707107 +0.500000 -0.500000 -0.707107 +0.386936 -0.591845 -0.707107 +0.260282 -0.657460 -0.707107 +0.386936 -0.591845 -0.707107 +0.260282 -0.657460 -0.707107 +0.260282 -0.657460 -0.707107 +0.386936 -0.591845 -0.707107 +0.128667 -0.695302 -0.707107 +0.260282 -0.657460 -0.707107 +0.260282 -0.657460 -0.707107 +0.128667 -0.695302 -0.707107 +0.128667 -0.695302 -0.707107 +0.260282 -0.657460 -0.707107 +0.000000 -0.707107 -0.707107 +0.128667 -0.695302 -0.707107 +0.128667 -0.695302 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.128667 -0.695302 -0.707107 +0.000000 -0.707107 -0.707107 +-0.128667 -0.695302 -0.707107 +0.000000 -0.707107 -0.707107 +-0.128667 -0.695302 -0.707107 +-0.128667 -0.695302 -0.707107 +0.000000 -0.707107 -0.707107 +-0.260282 -0.657460 -0.707107 +-0.128667 -0.695302 -0.707107 +-0.128667 -0.695302 -0.707107 +-0.260282 -0.657460 -0.707107 +-0.260282 -0.657460 -0.707107 +-0.128667 -0.695302 -0.707107 +-0.386936 -0.591845 -0.707107 +-0.260282 -0.657460 -0.707107 +-0.260282 -0.657460 -0.707107 +-0.386936 -0.591845 -0.707107 +-0.386936 -0.591845 -0.707107 +-0.260282 -0.657460 -0.707107 +-0.500000 -0.500000 -0.707107 +-0.386936 -0.591845 -0.707107 +-0.386936 -0.591845 -0.707107 +-0.500000 -0.500000 -0.707107 +-0.500000 -0.500000 -0.707107 +-0.386936 -0.591845 -0.707107 +-0.591845 -0.386936 -0.707107 +-0.500000 -0.500000 -0.707107 +-0.500000 -0.500000 -0.707107 +-0.591845 -0.386936 -0.707107 +-0.591845 -0.386936 -0.707107 +-0.500000 -0.500000 -0.707107 +-0.657460 -0.260282 -0.707107 +-0.591845 -0.386936 -0.707107 +-0.591845 -0.386936 -0.707107 +-0.657460 -0.260282 -0.707107 +-0.657460 -0.260282 -0.707107 +-0.591845 -0.386936 -0.707107 +-0.695302 -0.128667 -0.707107 +-0.657460 -0.260282 -0.707107 +-0.657460 -0.260282 -0.707107 +-0.695302 -0.128667 -0.707107 +-0.695302 -0.128667 -0.707107 +-0.657460 -0.260282 -0.707107 +-0.707107 0.000000 -0.707107 +-0.695302 -0.128667 -0.707107 +-0.695302 -0.128667 -0.707107 +-0.695302 -0.128667 -0.707107 +-0.707107 0.000000 -0.707107 +-0.707107 0.000000 -0.707107 +0.707107 0.000000 -0.707107 +0.695302 -0.128667 -0.707107 +0.707107 0.000000 -0.707107 +0.695302 -0.128667 -0.707107 +0.695302 -0.128667 -0.707107 +0.707107 0.000000 -0.707107 +0.657460 -0.260282 -0.707107 +0.695302 -0.128667 -0.707107 +0.695302 -0.128667 -0.707107 +0.657460 -0.260282 -0.707107 +0.657460 -0.260282 -0.707107 +0.695302 -0.128667 -0.707107 +0.591845 -0.386936 -0.707107 +0.657460 -0.260282 -0.707107 +0.657460 -0.260282 -0.707107 +0.591845 -0.386936 -0.707107 +0.591845 -0.386936 -0.707107 +0.657460 -0.260282 -0.707107 +0.500000 -0.500000 -0.707107 +0.591845 -0.386936 -0.707107 +0.591845 -0.386936 -0.707107 +0.500000 -0.500000 -0.707107 +0.500000 -0.500000 -0.707107 +0.591845 -0.386936 -0.707107 +0.386936 -0.591845 -0.707107 +0.500000 -0.500000 -0.707107 +0.500000 -0.500000 -0.707107 +0.386936 -0.591845 -0.707107 +0.386936 -0.591845 -0.707107 +0.500000 -0.500000 -0.707107 +0.386936 -0.591845 -0.707107 +0.260282 -0.657460 -0.707107 +0.386936 -0.591845 -0.707107 +0.260282 -0.657460 -0.707107 +0.260282 -0.657460 -0.707107 +0.386936 -0.591845 -0.707107 +0.128667 -0.695302 -0.707107 +0.260282 -0.657460 -0.707107 +0.260282 -0.657460 -0.707107 +0.128667 -0.695302 -0.707107 +0.128667 -0.695302 -0.707107 +0.260282 -0.657460 -0.707107 +0.000000 -0.707107 -0.707107 +0.128667 -0.695302 -0.707107 +0.128667 -0.695302 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.128667 -0.695302 -0.707107 +0.000000 -0.707107 -0.707107 +-0.128667 -0.695302 -0.707107 +0.000000 -0.707107 -0.707107 +-0.128667 -0.695302 -0.707107 +-0.128667 -0.695302 -0.707107 +0.000000 -0.707107 -0.707107 +-0.260282 -0.657460 -0.707107 +-0.128667 -0.695302 -0.707107 +-0.128667 -0.695302 -0.707107 +-0.260282 -0.657460 -0.707107 +-0.260282 -0.657460 -0.707107 +-0.128667 -0.695302 -0.707107 +-0.386936 -0.591845 -0.707107 +-0.260282 -0.657460 -0.707107 +-0.260282 -0.657460 -0.707107 +-0.386936 -0.591845 -0.707107 +-0.386936 -0.591845 -0.707107 +-0.260282 -0.657460 -0.707107 +-0.500000 -0.500000 -0.707107 +-0.386936 -0.591845 -0.707107 +-0.386936 -0.591845 -0.707107 +-0.500000 -0.500000 -0.707107 +-0.500000 -0.500000 -0.707107 +-0.386936 -0.591845 -0.707107 +-0.591845 -0.386936 -0.707107 +-0.500000 -0.500000 -0.707107 +-0.500000 -0.500000 -0.707107 +-0.591845 -0.386936 -0.707107 +-0.591845 -0.386936 -0.707107 +-0.500000 -0.500000 -0.707107 +-0.657460 -0.260282 -0.707107 +-0.591845 -0.386936 -0.707107 +-0.591845 -0.386936 -0.707107 +-0.657460 -0.260282 -0.707107 +-0.657460 -0.260282 -0.707107 +-0.591845 -0.386936 -0.707107 +-0.695302 -0.128667 -0.707107 +-0.657460 -0.260282 -0.707107 +-0.657460 -0.260282 -0.707107 +-0.695302 -0.128667 -0.707107 +-0.695302 -0.128667 -0.707107 +-0.657460 -0.260282 -0.707107 +-0.707107 0.000000 -0.707107 +-0.695302 -0.128667 -0.707107 +-0.695302 -0.128667 -0.707107 +-0.695302 -0.128667 -0.707107 +-0.707107 0.000000 -0.707107 +-0.707107 0.000000 -0.707107 +0.707107 0.000000 -0.707107 +0.695302 -0.128667 -0.707107 +0.707107 0.000000 -0.707107 +0.695302 -0.128667 -0.707107 +0.695302 -0.128667 -0.707107 +0.707107 0.000000 -0.707107 +0.657460 -0.260282 -0.707107 +0.695302 -0.128667 -0.707107 +0.695302 -0.128667 -0.707107 +0.657460 -0.260282 -0.707107 +0.657460 -0.260282 -0.707107 +0.695302 -0.128667 -0.707107 +0.591845 -0.386936 -0.707107 +0.657460 -0.260282 -0.707107 +0.657460 -0.260282 -0.707107 +0.591845 -0.386936 -0.707107 +0.591845 -0.386936 -0.707107 +0.657460 -0.260282 -0.707107 +0.500000 -0.500000 -0.707107 +0.591845 -0.386936 -0.707107 +0.591845 -0.386936 -0.707107 +0.500000 -0.500000 -0.707107 +0.500000 -0.500000 -0.707107 +0.591845 -0.386936 -0.707107 +0.386936 -0.591845 -0.707107 +0.500000 -0.500000 -0.707107 +0.500000 -0.500000 -0.707107 +0.386936 -0.591845 -0.707107 +0.386936 -0.591845 -0.707107 +0.500000 -0.500000 -0.707107 +0.386936 -0.591845 -0.707107 +0.260282 -0.657460 -0.707107 +0.386936 -0.591845 -0.707107 +0.260282 -0.657460 -0.707107 +0.260282 -0.657460 -0.707107 +0.386936 -0.591845 -0.707107 +0.128667 -0.695302 -0.707107 +0.260282 -0.657460 -0.707107 +0.260282 -0.657460 -0.707107 +0.128667 -0.695302 -0.707107 +0.128667 -0.695302 -0.707107 +0.260282 -0.657460 -0.707107 +0.000000 -0.707107 -0.707107 +0.128667 -0.695302 -0.707107 +0.128667 -0.695302 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.128667 -0.695302 -0.707107 +0.000000 -0.707107 -0.707107 +-0.128667 -0.695302 -0.707107 +0.000000 -0.707107 -0.707107 +-0.128667 -0.695302 -0.707107 +-0.128667 -0.695302 -0.707107 +0.000000 -0.707107 -0.707107 +-0.260282 -0.657460 -0.707107 +-0.128667 -0.695302 -0.707107 +-0.128667 -0.695302 -0.707107 +-0.260282 -0.657460 -0.707107 +-0.260282 -0.657460 -0.707107 +-0.128667 -0.695302 -0.707107 +-0.386936 -0.591845 -0.707107 +-0.260282 -0.657460 -0.707107 +-0.260282 -0.657460 -0.707107 +-0.386936 -0.591845 -0.707107 +-0.386936 -0.591845 -0.707107 +-0.260282 -0.657460 -0.707107 +-0.500000 -0.500000 -0.707107 +-0.386936 -0.591845 -0.707107 +-0.386936 -0.591845 -0.707107 +-0.500000 -0.500000 -0.707107 +-0.500000 -0.500000 -0.707107 +-0.386936 -0.591845 -0.707107 +-0.591845 -0.386936 -0.707107 +-0.500000 -0.500000 -0.707107 +-0.500000 -0.500000 -0.707107 +-0.591845 -0.386936 -0.707107 +-0.591845 -0.386936 -0.707107 +-0.500000 -0.500000 -0.707107 +-0.657460 -0.260282 -0.707107 +-0.591845 -0.386936 -0.707107 +-0.591845 -0.386936 -0.707107 +-0.657460 -0.260282 -0.707107 +-0.657460 -0.260282 -0.707107 +-0.591845 -0.386936 -0.707107 +-0.695302 -0.128667 -0.707107 +-0.657460 -0.260282 -0.707107 +-0.657460 -0.260282 -0.707107 +-0.695302 -0.128667 -0.707107 +-0.695302 -0.128667 -0.707107 +-0.657460 -0.260282 -0.707107 +-0.707107 0.000000 -0.707107 +-0.695302 -0.128667 -0.707107 +-0.695302 -0.128667 -0.707107 +0.386936 -0.591845 -0.707107 +0.500000 -0.500000 -0.707107 +0.500000 -0.500000 -0.707107 +0.707107 0.000000 -0.707107 +0.695302 -0.128667 -0.707107 +0.707107 0.000000 -0.707107 +0.695302 -0.128667 -0.707107 +0.695302 -0.128667 -0.707107 +0.707107 0.000000 -0.707107 +0.695302 -0.128667 -0.707107 +0.657460 -0.260282 -0.707107 +0.695302 -0.128667 -0.707107 +0.657460 -0.260282 -0.707107 +0.657460 -0.260282 -0.707107 +0.695302 -0.128667 -0.707107 +0.657460 -0.260282 -0.707107 +0.591845 -0.386936 -0.707107 +0.657460 -0.260282 -0.707107 +0.591845 -0.386936 -0.707107 +0.591845 -0.386936 -0.707107 +0.657460 -0.260282 -0.707107 +0.500000 -0.500000 -0.707107 +0.591845 -0.386936 -0.707107 +0.591845 -0.386936 -0.707107 +0.500000 -0.500000 -0.707107 +0.500000 -0.500000 -0.707107 +0.591845 -0.386936 -0.707107 +-0.707107 0.000000 -0.707107 +-0.695302 -0.128667 -0.707107 +-0.707107 0.000000 -0.707107 +-0.695302 -0.128667 -0.707107 +-0.695302 -0.128667 -0.707107 +-0.707107 0.000000 -0.707107 +-0.657460 -0.260282 -0.707107 +-0.695302 -0.128667 -0.707107 +-0.695302 -0.128667 -0.707107 +-0.657460 -0.260282 -0.707107 +-0.657460 -0.260282 -0.707107 +-0.695302 -0.128667 -0.707107 +-0.591845 -0.386936 -0.707107 +-0.657460 -0.260282 -0.707107 +-0.657460 -0.260282 -0.707107 +-0.591845 -0.386936 -0.707107 +-0.591845 -0.386936 -0.707107 +-0.657460 -0.260282 -0.707107 +-0.500000 -0.500000 -0.707107 +-0.591845 -0.386936 -0.707107 +-0.591845 -0.386936 -0.707107 +-0.500000 -0.500000 -0.707107 +-0.500000 -0.500000 -0.707107 +-0.591845 -0.386936 -0.707107 +-0.386936 -0.591845 -0.707107 +-0.500000 -0.500000 -0.707107 +-0.500000 -0.500000 -0.707107 +-0.386936 -0.591845 -0.707107 +-0.386936 -0.591845 -0.707107 +-0.500000 -0.500000 -0.707107 +-0.260282 -0.657460 -0.707107 +-0.386936 -0.591845 -0.707107 +-0.386936 -0.591845 -0.707107 +-0.260282 -0.657460 -0.707107 +-0.260282 -0.657460 -0.707107 +-0.386936 -0.591845 -0.707107 +-0.128667 -0.695302 -0.707107 +-0.260282 -0.657460 -0.707107 +-0.260282 -0.657460 -0.707107 +-0.128667 -0.695302 -0.707107 +-0.128667 -0.695302 -0.707107 +-0.260282 -0.657460 -0.707107 +0.000000 -0.707107 -0.707107 +-0.128667 -0.695302 -0.707107 +-0.128667 -0.695302 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +-0.128667 -0.695302 -0.707107 +0.128667 -0.695302 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.128667 -0.695302 -0.707107 +0.128667 -0.695302 -0.707107 +0.000000 -0.707107 -0.707107 +0.260282 -0.657460 -0.707107 +0.128667 -0.695302 -0.707107 +0.128667 -0.695302 -0.707107 +0.260282 -0.657460 -0.707107 +0.260282 -0.657460 -0.707107 +0.128667 -0.695302 -0.707107 +0.260282 -0.657460 -0.707107 +0.386936 -0.591845 -0.707107 +0.260282 -0.657460 -0.707107 +0.386936 -0.591845 -0.707107 +0.386936 -0.591845 -0.707107 +0.260282 -0.657460 -0.707107 +0.500000 -0.500000 -0.707107 +0.386936 -0.591845 -0.707107 +0.386936 -0.591845 -0.707107 +-0.695302 -0.128667 -0.707107 +-0.707107 0.000000 -0.707107 +-0.707107 0.000000 -0.707107 +0.695302 -0.128667 -0.707107 +0.707107 0.000000 -0.707107 +0.707107 0.000000 -0.707107 +0.695302 -0.128667 -0.707107 +0.695302 -0.128667 -0.707107 +0.707107 0.000000 -0.707107 +0.695302 -0.128667 -0.707107 +0.657460 -0.260282 -0.707107 +0.695302 -0.128667 -0.707107 +0.657460 -0.260282 -0.707107 +0.657460 -0.260282 -0.707107 +0.695302 -0.128667 -0.707107 +0.657460 -0.260282 -0.707107 +0.591845 -0.386936 -0.707107 +0.657460 -0.260282 -0.707107 +0.591845 -0.386936 -0.707107 +0.591845 -0.386936 -0.707107 +0.657460 -0.260282 -0.707107 +0.500000 -0.500000 -0.707107 +0.591845 -0.386936 -0.707107 +0.591845 -0.386936 -0.707107 +0.500000 -0.500000 -0.707107 +0.500000 -0.500000 -0.707107 +0.591845 -0.386936 -0.707107 +0.386936 -0.591845 -0.707107 +0.500000 -0.500000 -0.707107 +0.500000 -0.500000 -0.707107 +0.386936 -0.591845 -0.707107 +0.386936 -0.591845 -0.707107 +0.500000 -0.500000 -0.707107 +0.386936 -0.591845 -0.707107 +0.260282 -0.657460 -0.707107 +0.386936 -0.591845 -0.707107 +0.260282 -0.657460 -0.707107 +0.260282 -0.657460 -0.707107 +0.386936 -0.591845 -0.707107 +0.128667 -0.695302 -0.707107 +0.260282 -0.657460 -0.707107 +0.260282 -0.657460 -0.707107 +0.128667 -0.695302 -0.707107 +0.128667 -0.695302 -0.707107 +0.260282 -0.657460 -0.707107 +0.000000 -0.707107 -0.707107 +0.128667 -0.695302 -0.707107 +0.128667 -0.695302 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.128667 -0.695302 -0.707107 +0.000000 -0.707107 -0.707107 +-0.128667 -0.695302 -0.707107 +0.000000 -0.707107 -0.707107 +-0.128667 -0.695302 -0.707107 +-0.128667 -0.695302 -0.707107 +0.000000 -0.707107 -0.707107 +-0.260282 -0.657460 -0.707107 +-0.128667 -0.695302 -0.707107 +-0.128667 -0.695302 -0.707107 +-0.260282 -0.657460 -0.707107 +-0.260282 -0.657460 -0.707107 +-0.128667 -0.695302 -0.707107 +-0.386936 -0.591845 -0.707107 +-0.260282 -0.657460 -0.707107 +-0.260282 -0.657460 -0.707107 +-0.386936 -0.591845 -0.707107 +-0.386936 -0.591845 -0.707107 +-0.260282 -0.657460 -0.707107 +-0.500000 -0.500000 -0.707107 +-0.386936 -0.591845 -0.707107 +-0.386936 -0.591845 -0.707107 +-0.500000 -0.500000 -0.707107 +-0.500000 -0.500000 -0.707107 +-0.386936 -0.591845 -0.707107 +-0.591845 -0.386936 -0.707107 +-0.500000 -0.500000 -0.707107 +-0.500000 -0.500000 -0.707107 +-0.591845 -0.386936 -0.707107 +-0.591845 -0.386936 -0.707107 +-0.500000 -0.500000 -0.707107 +-0.657460 -0.260282 -0.707107 +-0.591845 -0.386936 -0.707107 +-0.591845 -0.386936 -0.707107 +-0.657460 -0.260282 -0.707107 +-0.657460 -0.260282 -0.707107 +-0.591845 -0.386936 -0.707107 +-0.695302 -0.128667 -0.707107 +-0.657460 -0.260282 -0.707107 +-0.657460 -0.260282 -0.707107 +-0.695302 -0.128667 -0.707107 +-0.695302 -0.128667 -0.707107 +-0.657460 -0.260282 -0.707107 +-0.707107 0.000000 -0.707107 +-0.695302 -0.128667 -0.707107 +-0.695302 -0.128667 -0.707107 +0.695302 -0.128667 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.695302 -0.128667 0.707107 +-0.707107 0.000000 0.707107 +-0.695302 -0.128667 0.707107 +-0.695302 -0.128667 0.707107 +-0.707107 0.000000 0.707107 +-0.657460 -0.260282 0.707107 +-0.695302 -0.128667 0.707107 +-0.695302 -0.128667 0.707107 +-0.657460 -0.260282 0.707107 +-0.657460 -0.260282 0.707107 +-0.695302 -0.128667 0.707107 +-0.591845 -0.386936 0.707107 +-0.657460 -0.260282 0.707107 +-0.657460 -0.260282 0.707107 +-0.591845 -0.386936 0.707107 +-0.591845 -0.386936 0.707107 +-0.657460 -0.260282 0.707107 +-0.500000 -0.500000 0.707107 +-0.591845 -0.386936 0.707107 +-0.591845 -0.386936 0.707107 +-0.500000 -0.500000 0.707107 +-0.500000 -0.500000 0.707107 +-0.591845 -0.386936 0.707107 +-0.500000 -0.500000 0.707107 +-0.386936 -0.591845 0.707107 +-0.500000 -0.500000 0.707107 +-0.386936 -0.591845 0.707107 +-0.386936 -0.591845 0.707107 +-0.500000 -0.500000 0.707107 +-0.260282 -0.657460 0.707107 +-0.386936 -0.591845 0.707107 +-0.386936 -0.591845 0.707107 +-0.260282 -0.657460 0.707107 +-0.260282 -0.657460 0.707107 +-0.386936 -0.591845 0.707107 +-0.128667 -0.695302 0.707107 +-0.260282 -0.657460 0.707107 +-0.260282 -0.657460 0.707107 +-0.128667 -0.695302 0.707107 +-0.128667 -0.695302 0.707107 +-0.260282 -0.657460 0.707107 +0.000000 -0.707107 0.707107 +-0.128667 -0.695302 0.707107 +-0.128667 -0.695302 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +-0.128667 -0.695302 0.707107 +0.000000 -0.707107 0.707107 +0.128667 -0.695302 0.707107 +0.000000 -0.707107 0.707107 +0.128667 -0.695302 0.707107 +0.128667 -0.695302 0.707107 +0.000000 -0.707107 0.707107 +0.128667 -0.695302 0.707107 +0.260282 -0.657460 0.707107 +0.128667 -0.695302 0.707107 +0.260282 -0.657460 0.707107 +0.260282 -0.657460 0.707107 +0.128667 -0.695302 0.707107 +0.386936 -0.591845 0.707107 +0.260282 -0.657460 0.707107 +0.260282 -0.657460 0.707107 +0.386936 -0.591845 0.707107 +0.386936 -0.591845 0.707107 +0.260282 -0.657460 0.707107 +0.386936 -0.591845 0.707107 +0.500000 -0.500000 0.707107 +0.386936 -0.591845 0.707107 +0.500000 -0.500000 0.707107 +0.500000 -0.500000 0.707107 +0.386936 -0.591845 0.707107 +0.591845 -0.386936 0.707107 +0.500000 -0.500000 0.707107 +0.500000 -0.500000 0.707107 +0.591845 -0.386936 0.707107 +0.591845 -0.386936 0.707107 +0.500000 -0.500000 0.707107 +0.657460 -0.260282 0.707107 +0.591845 -0.386936 0.707107 +0.591845 -0.386936 0.707107 +0.657460 -0.260282 0.707107 +0.657460 -0.260282 0.707107 +0.591845 -0.386936 0.707107 +0.695302 -0.128667 0.707107 +0.657460 -0.260282 0.707107 +0.657460 -0.260282 0.707107 +0.695302 -0.128667 0.707107 +0.695302 -0.128667 0.707107 +0.657460 -0.260282 0.707107 +0.707107 0.000000 0.707107 +0.695302 -0.128667 0.707107 +0.695302 -0.128667 0.707107 +0.695302 -0.128667 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +-0.695302 -0.128667 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.695302 -0.128667 0.707107 +-0.695302 -0.128667 0.707107 +-0.707107 0.000000 0.707107 +-0.657460 -0.260282 0.707107 +-0.695302 -0.128667 0.707107 +-0.695302 -0.128667 0.707107 +-0.657460 -0.260282 0.707107 +-0.657460 -0.260282 0.707107 +-0.695302 -0.128667 0.707107 +-0.591845 -0.386936 0.707107 +-0.657460 -0.260282 0.707107 +-0.657460 -0.260282 0.707107 +-0.591845 -0.386936 0.707107 +-0.591845 -0.386936 0.707107 +-0.657460 -0.260282 0.707107 +-0.500000 -0.500000 0.707107 +-0.591845 -0.386936 0.707107 +-0.591845 -0.386936 0.707107 +-0.500000 -0.500000 0.707107 +-0.500000 -0.500000 0.707107 +-0.591845 -0.386936 0.707107 +-0.386936 -0.591845 0.707107 +-0.500000 -0.500000 0.707107 +-0.500000 -0.500000 0.707107 +-0.386936 -0.591845 0.707107 +-0.386936 -0.591845 0.707107 +-0.500000 -0.500000 0.707107 +-0.260282 -0.657460 0.707107 +-0.386936 -0.591845 0.707107 +-0.386936 -0.591845 0.707107 +-0.260282 -0.657460 0.707107 +-0.260282 -0.657460 0.707107 +-0.386936 -0.591845 0.707107 +-0.128667 -0.695302 0.707107 +-0.260282 -0.657460 0.707107 +-0.260282 -0.657460 0.707107 +-0.128667 -0.695302 0.707107 +-0.128667 -0.695302 0.707107 +-0.260282 -0.657460 0.707107 +0.000000 -0.707107 0.707107 +-0.128667 -0.695302 0.707107 +-0.128667 -0.695302 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +-0.128667 -0.695302 0.707107 +0.128667 -0.695302 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.128667 -0.695302 0.707107 +0.128667 -0.695302 0.707107 +0.000000 -0.707107 0.707107 +0.260282 -0.657460 0.707107 +0.128667 -0.695302 0.707107 +0.128667 -0.695302 0.707107 +0.260282 -0.657460 0.707107 +0.260282 -0.657460 0.707107 +0.128667 -0.695302 0.707107 +0.386936 -0.591845 0.707107 +0.260282 -0.657460 0.707107 +0.260282 -0.657460 0.707107 +0.386936 -0.591845 0.707107 +0.386936 -0.591845 0.707107 +0.260282 -0.657460 0.707107 +0.500000 -0.500000 0.707107 +0.386936 -0.591845 0.707107 +0.386936 -0.591845 0.707107 +0.500000 -0.500000 0.707107 +0.500000 -0.500000 0.707107 +0.386936 -0.591845 0.707107 +0.591845 -0.386936 0.707107 +0.500000 -0.500000 0.707107 +0.500000 -0.500000 0.707107 +0.591845 -0.386936 0.707107 +0.591845 -0.386936 0.707107 +0.500000 -0.500000 0.707107 +0.657460 -0.260282 0.707107 +0.591845 -0.386936 0.707107 +0.591845 -0.386936 0.707107 +0.657460 -0.260282 0.707107 +0.657460 -0.260282 0.707107 +0.591845 -0.386936 0.707107 +0.695302 -0.128667 0.707107 +0.657460 -0.260282 0.707107 +0.657460 -0.260282 0.707107 +0.695302 -0.128667 0.707107 +0.695302 -0.128667 0.707107 +0.657460 -0.260282 0.707107 +0.707107 0.000000 0.707107 +0.695302 -0.128667 0.707107 +0.695302 -0.128667 0.707107 +-0.707107 0.000000 0.707107 +-0.695302 -0.128667 0.707107 +-0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.695302 -0.128667 0.707107 +0.707107 0.000000 0.707107 +0.695302 -0.128667 0.707107 +0.695302 -0.128667 0.707107 +0.707107 0.000000 0.707107 +0.657460 -0.260282 0.707107 +0.695302 -0.128667 0.707107 +0.695302 -0.128667 0.707107 +0.657460 -0.260282 0.707107 +0.657460 -0.260282 0.707107 +0.695302 -0.128667 0.707107 +0.591845 -0.386936 0.707107 +0.657460 -0.260282 0.707107 +0.657460 -0.260282 0.707107 +0.591845 -0.386936 0.707107 +0.591845 -0.386936 0.707107 +0.657460 -0.260282 0.707107 +0.500000 -0.500000 0.707107 +0.591845 -0.386936 0.707107 +0.591845 -0.386936 0.707107 +0.500000 -0.500000 0.707107 +0.500000 -0.500000 0.707107 +0.591845 -0.386936 0.707107 +0.386936 -0.591845 0.707107 +0.500000 -0.500000 0.707107 +0.500000 -0.500000 0.707107 +0.386936 -0.591845 0.707107 +0.386936 -0.591845 0.707107 +0.500000 -0.500000 0.707107 +0.260282 -0.657460 0.707107 +0.386936 -0.591845 0.707107 +0.386936 -0.591845 0.707107 +0.260282 -0.657460 0.707107 +0.260282 -0.657460 0.707107 +0.386936 -0.591845 0.707107 +0.128667 -0.695302 0.707107 +0.260282 -0.657460 0.707107 +0.260282 -0.657460 0.707107 +0.128667 -0.695302 0.707107 +0.128667 -0.695302 0.707107 +0.260282 -0.657460 0.707107 +0.000000 -0.707107 0.707107 +0.128667 -0.695302 0.707107 +0.128667 -0.695302 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.128667 -0.695302 0.707107 +0.000000 -0.707107 0.707107 +-0.128667 -0.695302 0.707107 +0.000000 -0.707107 0.707107 +-0.128667 -0.695302 0.707107 +-0.128667 -0.695302 0.707107 +0.000000 -0.707107 0.707107 +-0.128667 -0.695302 0.707107 +-0.260282 -0.657460 0.707107 +-0.128667 -0.695302 0.707107 +-0.260282 -0.657460 0.707107 +-0.260282 -0.657460 0.707107 +-0.128667 -0.695302 0.707107 +-0.260282 -0.657460 0.707107 +-0.386936 -0.591845 0.707107 +-0.260282 -0.657460 0.707107 +-0.386936 -0.591845 0.707107 +-0.386936 -0.591845 0.707107 +-0.260282 -0.657460 0.707107 +-0.500000 -0.500000 0.707107 +-0.386936 -0.591845 0.707107 +-0.386936 -0.591845 0.707107 +-0.500000 -0.500000 0.707107 +-0.500000 -0.500000 0.707107 +-0.386936 -0.591845 0.707107 +-0.591845 -0.386936 0.707107 +-0.500000 -0.500000 0.707107 +-0.500000 -0.500000 0.707107 +-0.591845 -0.386936 0.707107 +-0.591845 -0.386936 0.707107 +-0.500000 -0.500000 0.707107 +-0.657460 -0.260282 0.707107 +-0.591845 -0.386936 0.707107 +-0.591845 -0.386936 0.707107 +-0.657460 -0.260282 0.707107 +-0.657460 -0.260282 0.707107 +-0.591845 -0.386936 0.707107 +-0.657460 -0.260282 0.707107 +-0.695302 -0.128667 0.707107 +-0.657460 -0.260282 0.707107 +-0.695302 -0.128667 0.707107 +-0.695302 -0.128667 0.707107 +-0.657460 -0.260282 0.707107 +-0.695302 -0.128667 0.707107 +-0.707107 0.000000 0.707107 +-0.695302 -0.128667 0.707107 +0.695302 -0.128667 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.695302 -0.128667 0.707107 +-0.707107 0.000000 0.707107 +-0.695302 -0.128667 0.707107 +-0.695302 -0.128667 0.707107 +-0.707107 0.000000 0.707107 +-0.657460 -0.260282 0.707107 +-0.695302 -0.128667 0.707107 +-0.695302 -0.128667 0.707107 +-0.657460 -0.260282 0.707107 +-0.657460 -0.260282 0.707107 +-0.695302 -0.128667 0.707107 +-0.591845 -0.386936 0.707107 +-0.657460 -0.260282 0.707107 +-0.657460 -0.260282 0.707107 +-0.591845 -0.386936 0.707107 +-0.591845 -0.386936 0.707107 +-0.657460 -0.260282 0.707107 +-0.500000 -0.500000 0.707107 +-0.591845 -0.386936 0.707107 +-0.591845 -0.386936 0.707107 +-0.500000 -0.500000 0.707107 +-0.500000 -0.500000 0.707107 +-0.591845 -0.386936 0.707107 +-0.386936 -0.591845 0.707107 +-0.500000 -0.500000 0.707107 +-0.500000 -0.500000 0.707107 +-0.386936 -0.591845 0.707107 +-0.386936 -0.591845 0.707107 +-0.500000 -0.500000 0.707107 +-0.260282 -0.657460 0.707107 +-0.386936 -0.591845 0.707107 +-0.386936 -0.591845 0.707107 +-0.260282 -0.657460 0.707107 +-0.260282 -0.657460 0.707107 +-0.386936 -0.591845 0.707107 +-0.128667 -0.695302 0.707107 +-0.260282 -0.657460 0.707107 +-0.260282 -0.657460 0.707107 +-0.128667 -0.695302 0.707107 +-0.128667 -0.695302 0.707107 +-0.260282 -0.657460 0.707107 +0.000000 -0.707107 0.707107 +-0.128667 -0.695302 0.707107 +-0.128667 -0.695302 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +-0.128667 -0.695302 0.707107 +0.128667 -0.695302 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.128667 -0.695302 0.707107 +0.128667 -0.695302 0.707107 +0.000000 -0.707107 0.707107 +0.128667 -0.695302 0.707107 +0.260282 -0.657460 0.707107 +0.128667 -0.695302 0.707107 +0.260282 -0.657460 0.707107 +0.260282 -0.657460 0.707107 +0.128667 -0.695302 0.707107 +0.386936 -0.591845 0.707107 +0.260282 -0.657460 0.707107 +0.260282 -0.657460 0.707107 +0.386936 -0.591845 0.707107 +0.386936 -0.591845 0.707107 +0.260282 -0.657460 0.707107 +0.500000 -0.500000 0.707107 +0.386936 -0.591845 0.707107 +0.386936 -0.591845 0.707107 +0.500000 -0.500000 0.707107 +0.500000 -0.500000 0.707107 +0.386936 -0.591845 0.707107 +0.591845 -0.386936 0.707107 +0.500000 -0.500000 0.707107 +0.500000 -0.500000 0.707107 +0.591845 -0.386936 0.707107 +0.591845 -0.386936 0.707107 +0.500000 -0.500000 0.707107 +0.657460 -0.260282 0.707107 +0.591845 -0.386936 0.707107 +0.591845 -0.386936 0.707107 +0.657460 -0.260282 0.707107 +0.657460 -0.260282 0.707107 +0.591845 -0.386936 0.707107 +0.695302 -0.128667 0.707107 +0.657460 -0.260282 0.707107 +0.657460 -0.260282 0.707107 +0.695302 -0.128667 0.707107 +0.695302 -0.128667 0.707107 +0.657460 -0.260282 0.707107 +0.707107 0.000000 0.707107 +0.695302 -0.128667 0.707107 +0.695302 -0.128667 0.707107 +0.695302 -0.128667 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.695302 -0.128667 0.707107 +-0.707107 0.000000 0.707107 +-0.695302 -0.128667 0.707107 +-0.695302 -0.128667 0.707107 +-0.707107 0.000000 0.707107 +-0.657460 -0.260282 0.707107 +-0.695302 -0.128667 0.707107 +-0.695302 -0.128667 0.707107 +-0.657460 -0.260282 0.707107 +-0.657460 -0.260282 0.707107 +-0.695302 -0.128667 0.707107 +-0.591845 -0.386936 0.707107 +-0.657460 -0.260282 0.707107 +-0.657460 -0.260282 0.707107 +-0.591845 -0.386936 0.707107 +-0.591845 -0.386936 0.707107 +-0.657460 -0.260282 0.707107 +-0.500000 -0.500000 0.707107 +-0.591845 -0.386936 0.707107 +-0.591845 -0.386936 0.707107 +-0.500000 -0.500000 0.707107 +-0.500000 -0.500000 0.707107 +-0.591845 -0.386936 0.707107 +-0.386936 -0.591845 0.707107 +-0.500000 -0.500000 0.707107 +-0.500000 -0.500000 0.707107 +-0.386936 -0.591845 0.707107 +-0.386936 -0.591845 0.707107 +-0.500000 -0.500000 0.707107 +-0.260282 -0.657460 0.707107 +-0.386936 -0.591845 0.707107 +-0.386936 -0.591845 0.707107 +-0.260282 -0.657460 0.707107 +-0.260282 -0.657460 0.707107 +-0.386936 -0.591845 0.707107 +-0.128667 -0.695302 0.707107 +-0.260282 -0.657460 0.707107 +-0.260282 -0.657460 0.707107 +-0.128667 -0.695302 0.707107 +-0.128667 -0.695302 0.707107 +-0.260282 -0.657460 0.707107 +0.000000 -0.707107 0.707107 +-0.128667 -0.695302 0.707107 +-0.128667 -0.695302 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +-0.128667 -0.695302 0.707107 +0.128667 -0.695302 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.128667 -0.695302 0.707107 +0.128667 -0.695302 0.707107 +0.000000 -0.707107 0.707107 +0.128667 -0.695302 0.707107 +0.260282 -0.657460 0.707107 +0.128667 -0.695302 0.707107 +0.260282 -0.657460 0.707107 +0.260282 -0.657460 0.707107 +0.128667 -0.695302 0.707107 +0.386936 -0.591845 0.707107 +0.260282 -0.657460 0.707107 +0.260282 -0.657460 0.707107 +0.386936 -0.591845 0.707107 +0.386936 -0.591845 0.707107 +0.260282 -0.657460 0.707107 +0.500000 -0.500000 0.707107 +0.386936 -0.591845 0.707107 +0.386936 -0.591845 0.707107 +0.500000 -0.500000 0.707107 +0.500000 -0.500000 0.707107 +0.386936 -0.591845 0.707107 +0.591845 -0.386936 0.707107 +0.500000 -0.500000 0.707107 +0.500000 -0.500000 0.707107 +0.591845 -0.386936 0.707107 +0.591845 -0.386936 0.707107 +0.500000 -0.500000 0.707107 +0.657460 -0.260282 0.707107 +0.591845 -0.386936 0.707107 +0.591845 -0.386936 0.707107 +0.657460 -0.260282 0.707107 +0.657460 -0.260282 0.707107 +0.591845 -0.386936 0.707107 +0.695302 -0.128667 0.707107 +0.657460 -0.260282 0.707107 +0.657460 -0.260282 0.707107 +0.695302 -0.128667 0.707107 +0.695302 -0.128667 0.707107 +0.657460 -0.260282 0.707107 +0.707107 0.000000 0.707107 +0.695302 -0.128667 0.707107 +0.695302 -0.128667 0.707107 +0.695302 -0.128667 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.695302 -0.128667 0.707107 +-0.707107 0.000000 0.707107 +-0.695302 -0.128667 0.707107 +-0.695302 -0.128667 0.707107 +-0.707107 0.000000 0.707107 +-0.657460 -0.260282 0.707107 +-0.695302 -0.128667 0.707107 +-0.695302 -0.128667 0.707107 +-0.657460 -0.260282 0.707107 +-0.657460 -0.260282 0.707107 +-0.695302 -0.128667 0.707107 +-0.591845 -0.386936 0.707107 +-0.657460 -0.260282 0.707107 +-0.657460 -0.260282 0.707107 +-0.591845 -0.386936 0.707107 +-0.591845 -0.386936 0.707107 +-0.657460 -0.260282 0.707107 +-0.500000 -0.500000 0.707107 +-0.591845 -0.386936 0.707107 +-0.591845 -0.386936 0.707107 +-0.500000 -0.500000 0.707107 +-0.500000 -0.500000 0.707107 +-0.591845 -0.386936 0.707107 +-0.386936 -0.591845 0.707107 +-0.500000 -0.500000 0.707107 +-0.500000 -0.500000 0.707107 +-0.386936 -0.591845 0.707107 +-0.386936 -0.591845 0.707107 +-0.500000 -0.500000 0.707107 +-0.386936 -0.591845 0.707107 +-0.260282 -0.657460 0.707107 +-0.386936 -0.591845 0.707107 +-0.260282 -0.657460 0.707107 +-0.260282 -0.657460 0.707107 +-0.386936 -0.591845 0.707107 +-0.128667 -0.695302 0.707107 +-0.260282 -0.657460 0.707107 +-0.260282 -0.657460 0.707107 +-0.128667 -0.695302 0.707107 +-0.128667 -0.695302 0.707107 +-0.260282 -0.657460 0.707107 +0.000000 -0.707107 0.707107 +-0.128667 -0.695302 0.707107 +-0.128667 -0.695302 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +-0.128667 -0.695302 0.707107 +0.000000 -0.707107 0.707107 +0.128667 -0.695302 0.707107 +0.000000 -0.707107 0.707107 +0.128667 -0.695302 0.707107 +0.128667 -0.695302 0.707107 +0.000000 -0.707107 0.707107 +0.260282 -0.657460 0.707107 +0.128667 -0.695302 0.707107 +0.128667 -0.695302 0.707107 +0.260282 -0.657460 0.707107 +0.260282 -0.657460 0.707107 +0.128667 -0.695302 0.707107 +0.386936 -0.591845 0.707107 +0.260282 -0.657460 0.707107 +0.260282 -0.657460 0.707107 +0.386936 -0.591845 0.707107 +0.386936 -0.591845 0.707107 +0.260282 -0.657460 0.707107 +0.500000 -0.500000 0.707107 +0.386936 -0.591845 0.707107 +0.386936 -0.591845 0.707107 +0.500000 -0.500000 0.707107 +0.500000 -0.500000 0.707107 +0.386936 -0.591845 0.707107 +0.591845 -0.386936 0.707107 +0.500000 -0.500000 0.707107 +0.500000 -0.500000 0.707107 +0.591845 -0.386936 0.707107 +0.591845 -0.386936 0.707107 +0.500000 -0.500000 0.707107 +0.657460 -0.260282 0.707107 +0.591845 -0.386936 0.707107 +0.591845 -0.386936 0.707107 +0.657460 -0.260282 0.707107 +0.657460 -0.260282 0.707107 +0.591845 -0.386936 0.707107 +0.695302 -0.128667 0.707107 +0.657460 -0.260282 0.707107 +0.657460 -0.260282 0.707107 +0.695302 -0.128667 0.707107 +0.695302 -0.128667 0.707107 +0.657460 -0.260282 0.707107 +0.707107 0.000000 0.707107 +0.695302 -0.128667 0.707107 +0.695302 -0.128667 0.707107 +-0.978781 0.000000 0.204909 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +-0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +-0.204909 0.000000 0.978781 +-0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +-0.204909 0.000000 0.978781 +-0.397177 0.000000 0.917742 +-0.204909 0.000000 0.978781 +-0.397177 0.000000 0.917742 +-0.397177 0.000000 0.917742 +-0.204909 0.000000 0.978781 +-0.566635 0.000000 0.823969 +-0.397177 0.000000 0.917742 +-0.397177 0.000000 0.917742 +-0.566635 0.000000 0.823969 +-0.566635 0.000000 0.823969 +-0.397177 0.000000 0.917742 +-0.707107 0.000000 0.707107 +-0.566635 0.000000 0.823969 +-0.566635 0.000000 0.823969 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.566635 0.000000 0.823969 +-0.823969 0.000000 0.566635 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.823969 0.000000 0.566635 +-0.823969 0.000000 0.566635 +-0.707107 0.000000 0.707107 +-0.917742 0.000000 0.397177 +-0.823969 0.000000 0.566635 +-0.823969 0.000000 0.566635 +-0.917742 0.000000 0.397177 +-0.917742 0.000000 0.397177 +-0.823969 0.000000 0.566635 +-0.978781 0.000000 0.204909 +-0.917742 0.000000 0.397177 +-0.917742 0.000000 0.397177 +-0.978781 0.000000 0.204909 +-0.978781 0.000000 0.204909 +-0.917742 0.000000 0.397177 +-1.000000 0.000000 0.000000 +-0.978781 0.000000 0.204909 +-0.978781 0.000000 0.204909 +0.000000 -0.566635 0.823969 +0.000000 -0.397177 0.917742 +0.000000 -0.397177 0.917742 +0.000000 0.000000 1.000000 +0.000000 -0.204909 0.978781 +0.000000 0.000000 1.000000 +0.000000 -0.204909 0.978781 +0.000000 -0.204909 0.978781 +0.000000 0.000000 1.000000 +0.000000 -0.397177 0.917742 +0.000000 -0.204909 0.978781 +0.000000 -0.204909 0.978781 +0.000000 -0.397177 0.917742 +0.000000 -0.397177 0.917742 +0.000000 -0.204909 0.978781 +0.000000 -0.978781 0.204909 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -0.978781 0.204909 +0.000000 -0.978781 0.204909 +0.000000 -1.000000 0.000000 +0.000000 -0.917742 0.397177 +0.000000 -0.978781 0.204909 +0.000000 -0.978781 0.204909 +0.000000 -0.917742 0.397177 +0.000000 -0.917742 0.397177 +0.000000 -0.978781 0.204909 +0.000000 -0.823969 0.566635 +0.000000 -0.917742 0.397177 +0.000000 -0.917742 0.397177 +0.000000 -0.823969 0.566635 +0.000000 -0.823969 0.566635 +0.000000 -0.917742 0.397177 +0.000000 -0.707107 0.707107 +0.000000 -0.823969 0.566635 +0.000000 -0.823969 0.566635 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.823969 0.566635 +0.000000 -0.566635 0.823969 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.566635 0.823969 +0.000000 -0.566635 0.823969 +0.000000 -0.707107 0.707107 +0.000000 -0.397177 0.917742 +0.000000 -0.566635 0.823969 +0.000000 -0.566635 0.823969 +0.000000 -1.000000 0.000000 +0.000000 -0.978781 0.204909 +0.000000 -1.000000 0.000000 +0.000000 -0.204909 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -0.204909 0.978781 +0.000000 -0.204909 0.978781 +0.000000 0.000000 1.000000 +0.000000 -0.204909 0.978781 +0.000000 -0.397177 0.917742 +0.000000 -0.204909 0.978781 +0.000000 -0.397177 0.917742 +0.000000 -0.397177 0.917742 +0.000000 -0.204909 0.978781 +0.000000 -0.397177 0.917742 +0.000000 -0.566635 0.823969 +0.000000 -0.397177 0.917742 +0.000000 -0.566635 0.823969 +0.000000 -0.566635 0.823969 +0.000000 -0.397177 0.917742 +0.000000 -0.707107 0.707107 +0.000000 -0.566635 0.823969 +0.000000 -0.566635 0.823969 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.566635 0.823969 +0.000000 -0.707107 0.707107 +0.000000 -0.823969 0.566635 +0.000000 -0.707107 0.707107 +0.000000 -0.823969 0.566635 +0.000000 -0.823969 0.566635 +0.000000 -0.707107 0.707107 +0.000000 -0.917742 0.397177 +0.000000 -0.823969 0.566635 +0.000000 -0.823969 0.566635 +0.000000 -0.917742 0.397177 +0.000000 -0.917742 0.397177 +0.000000 -0.823969 0.566635 +0.000000 -0.917742 0.397177 +0.000000 -0.978781 0.204909 +0.000000 -0.917742 0.397177 +0.000000 -0.978781 0.204909 +0.000000 -0.978781 0.204909 +0.000000 -0.917742 0.397177 +0.000000 -0.978781 0.204909 +0.000000 -1.000000 0.000000 +0.000000 -0.978781 0.204909 +0.000000 -1.000000 0.000000 +0.000000 -0.978781 0.204909 +0.000000 -1.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 -0.204909 0.978781 +0.000000 0.000000 1.000000 +0.000000 -0.204909 0.978781 +0.000000 -0.204909 0.978781 +0.000000 0.000000 1.000000 +0.000000 -0.397177 0.917742 +0.000000 -0.204909 0.978781 +0.000000 -0.204909 0.978781 +0.000000 -0.397177 0.917742 +0.000000 -0.397177 0.917742 +0.000000 -0.204909 0.978781 +0.000000 -0.566635 0.823969 +0.000000 -0.397177 0.917742 +0.000000 -0.397177 0.917742 +0.000000 -0.566635 0.823969 +0.000000 -0.566635 0.823969 +0.000000 -0.397177 0.917742 +0.000000 -0.707107 0.707107 +0.000000 -0.566635 0.823969 +0.000000 -0.566635 0.823969 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.566635 0.823969 +0.000000 -0.823969 0.566635 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.823969 0.566635 +0.000000 -0.823969 0.566635 +0.000000 -0.707107 0.707107 +0.000000 -0.917742 0.397177 +0.000000 -0.823969 0.566635 +0.000000 -0.823969 0.566635 +0.000000 -0.917742 0.397177 +0.000000 -0.917742 0.397177 +0.000000 -0.823969 0.566635 +0.000000 -0.917742 0.397177 +0.000000 -0.978781 0.204909 +0.000000 -0.917742 0.397177 +0.000000 -0.978781 0.204909 +0.000000 -0.978781 0.204909 +0.000000 -0.917742 0.397177 +0.000000 -0.978781 0.204909 +0.000000 -1.000000 0.000000 +0.000000 -0.978781 0.204909 +0.000000 0.000000 1.000000 +0.000000 -0.204909 0.978781 +0.000000 0.000000 1.000000 +0.000000 -0.978781 0.204909 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -0.978781 0.204909 +0.000000 -0.978781 0.204909 +0.000000 -1.000000 0.000000 +0.000000 -0.978781 0.204909 +0.000000 -0.917742 0.397177 +0.000000 -0.978781 0.204909 +0.000000 -0.917742 0.397177 +0.000000 -0.917742 0.397177 +0.000000 -0.978781 0.204909 +0.000000 -0.917742 0.397177 +0.000000 -0.823969 0.566635 +0.000000 -0.917742 0.397177 +0.000000 -0.823969 0.566635 +0.000000 -0.823969 0.566635 +0.000000 -0.917742 0.397177 +0.000000 -0.707107 0.707107 +0.000000 -0.823969 0.566635 +0.000000 -0.823969 0.566635 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.823969 0.566635 +0.000000 -0.707107 0.707107 +0.000000 -0.566635 0.823969 +0.000000 -0.707107 0.707107 +0.000000 -0.566635 0.823969 +0.000000 -0.566635 0.823969 +0.000000 -0.707107 0.707107 +0.000000 -0.566635 0.823969 +0.000000 -0.397177 0.917742 +0.000000 -0.566635 0.823969 +0.000000 -0.397177 0.917742 +0.000000 -0.397177 0.917742 +0.000000 -0.566635 0.823969 +0.000000 -0.204909 0.978781 +0.000000 -0.397177 0.917742 +0.000000 -0.397177 0.917742 +0.000000 -0.204909 0.978781 +0.000000 -0.204909 0.978781 +0.000000 -0.397177 0.917742 +0.000000 -0.204909 0.978781 +0.000000 0.000000 1.000000 +0.000000 -0.204909 0.978781 +0.917742 0.000000 0.397177 +0.823969 0.000000 0.566635 +0.917742 0.000000 0.397177 +0.978781 0.000000 0.204909 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.978781 0.000000 0.204909 +0.978781 0.000000 0.204909 +1.000000 0.000000 0.000000 +0.917742 0.000000 0.397177 +0.978781 0.000000 0.204909 +0.978781 0.000000 0.204909 +0.917742 0.000000 0.397177 +0.917742 0.000000 0.397177 +0.978781 0.000000 0.204909 +0.000000 0.000000 1.000000 +0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +0.204909 0.000000 0.978781 +0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +0.397177 0.000000 0.917742 +0.204909 0.000000 0.978781 +0.204909 0.000000 0.978781 +0.397177 0.000000 0.917742 +0.397177 0.000000 0.917742 +0.204909 0.000000 0.978781 +0.566635 0.000000 0.823969 +0.397177 0.000000 0.917742 +0.397177 0.000000 0.917742 +0.566635 0.000000 0.823969 +0.566635 0.000000 0.823969 +0.397177 0.000000 0.917742 +0.566635 0.000000 0.823969 +0.707107 0.000000 0.707107 +0.566635 0.000000 0.823969 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.566635 0.000000 0.823969 +0.707107 0.000000 0.707107 +0.823969 0.000000 0.566635 +0.707107 0.000000 0.707107 +0.823969 0.000000 0.566635 +0.823969 0.000000 0.566635 +0.707107 0.000000 0.707107 +0.823969 0.000000 0.566635 +0.917742 0.000000 0.397177 +0.823969 0.000000 0.566635 +0.000000 0.978781 0.204909 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.204909 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.204909 0.978781 +0.000000 0.204909 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.397177 0.917742 +0.000000 0.204909 0.978781 +0.000000 0.204909 0.978781 +0.000000 0.397177 0.917742 +0.000000 0.397177 0.917742 +0.000000 0.204909 0.978781 +0.000000 0.397177 0.917742 +0.000000 0.566635 0.823969 +0.000000 0.397177 0.917742 +0.000000 0.566635 0.823969 +0.000000 0.566635 0.823969 +0.000000 0.397177 0.917742 +0.000000 0.707107 0.707107 +0.000000 0.566635 0.823969 +0.000000 0.566635 0.823969 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.566635 0.823969 +0.000000 0.707107 0.707107 +0.000000 0.823969 0.566635 +0.000000 0.707107 0.707107 +0.000000 0.823969 0.566635 +0.000000 0.823969 0.566635 +0.000000 0.707107 0.707107 +0.000000 0.823969 0.566635 +0.000000 0.917742 0.397177 +0.000000 0.823969 0.566635 +0.000000 0.917742 0.397177 +0.000000 0.917742 0.397177 +0.000000 0.823969 0.566635 +0.000000 0.978781 0.204909 +0.000000 0.917742 0.397177 +0.000000 0.917742 0.397177 +0.000000 0.978781 0.204909 +0.000000 0.978781 0.204909 +0.000000 0.917742 0.397177 +0.000000 1.000000 0.000000 +0.000000 0.978781 0.204909 +0.000000 0.978781 0.204909 +0.000000 1.000000 0.000000 +0.000000 0.978781 0.204909 +0.000000 1.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.204909 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.204909 0.978781 +0.000000 0.204909 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.397177 0.917742 +0.000000 0.204909 0.978781 +0.000000 0.204909 0.978781 +0.000000 0.397177 0.917742 +0.000000 0.397177 0.917742 +0.000000 0.204909 0.978781 +0.000000 0.397177 0.917742 +0.000000 0.566635 0.823969 +0.000000 0.397177 0.917742 +0.000000 0.566635 0.823969 +0.000000 0.566635 0.823969 +0.000000 0.397177 0.917742 +0.000000 0.566635 0.823969 +0.000000 0.707107 0.707107 +0.000000 0.566635 0.823969 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.566635 0.823969 +0.000000 0.707107 0.707107 +0.000000 0.823969 0.566635 +0.000000 0.707107 0.707107 +0.000000 0.823969 0.566635 +0.000000 0.823969 0.566635 +0.000000 0.707107 0.707107 +0.000000 0.917742 0.397177 +0.000000 0.823969 0.566635 +0.000000 0.823969 0.566635 +0.000000 0.917742 0.397177 +0.000000 0.917742 0.397177 +0.000000 0.823969 0.566635 +0.000000 0.978781 0.204909 +0.000000 0.917742 0.397177 +0.000000 0.917742 0.397177 +0.000000 0.978781 0.204909 +0.000000 0.978781 0.204909 +0.000000 0.917742 0.397177 +0.000000 0.978781 0.204909 +0.000000 1.000000 0.000000 +0.000000 0.978781 0.204909 +0.000000 0.204909 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 1.000000 0.000000 +0.000000 0.978781 0.204909 +0.000000 1.000000 0.000000 +0.000000 0.978781 0.204909 +0.000000 0.978781 0.204909 +0.000000 1.000000 0.000000 +0.000000 0.978781 0.204909 +0.000000 0.917742 0.397177 +0.000000 0.978781 0.204909 +0.000000 0.917742 0.397177 +0.000000 0.917742 0.397177 +0.000000 0.978781 0.204909 +0.000000 0.917742 0.397177 +0.000000 0.823969 0.566635 +0.000000 0.917742 0.397177 +0.000000 0.823969 0.566635 +0.000000 0.823969 0.566635 +0.000000 0.917742 0.397177 +0.000000 0.823969 0.566635 +0.000000 0.707107 0.707107 +0.000000 0.823969 0.566635 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.823969 0.566635 +0.000000 0.707107 0.707107 +0.000000 0.566635 0.823969 +0.000000 0.707107 0.707107 +0.000000 0.566635 0.823969 +0.000000 0.566635 0.823969 +0.000000 0.707107 0.707107 +0.000000 0.397177 0.917742 +0.000000 0.566635 0.823969 +0.000000 0.566635 0.823969 +0.000000 0.397177 0.917742 +0.000000 0.397177 0.917742 +0.000000 0.566635 0.823969 +0.000000 0.204909 0.978781 +0.000000 0.397177 0.917742 +0.000000 0.397177 0.917742 +0.000000 0.204909 0.978781 +0.000000 0.204909 0.978781 +0.000000 0.397177 0.917742 +0.000000 0.000000 1.000000 +0.000000 0.204909 0.978781 +0.000000 0.204909 0.978781 +0.000000 0.204909 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 1.000000 0.000000 +0.000000 0.978781 0.204909 +0.000000 1.000000 0.000000 +0.000000 0.978781 0.204909 +0.000000 0.978781 0.204909 +0.000000 1.000000 0.000000 +0.000000 0.917742 0.397177 +0.000000 0.978781 0.204909 +0.000000 0.978781 0.204909 +0.000000 0.917742 0.397177 +0.000000 0.917742 0.397177 +0.000000 0.978781 0.204909 +0.000000 0.917742 0.397177 +0.000000 0.823969 0.566635 +0.000000 0.917742 0.397177 +0.000000 0.823969 0.566635 +0.000000 0.823969 0.566635 +0.000000 0.917742 0.397177 +0.000000 0.707107 0.707107 +0.000000 0.823969 0.566635 +0.000000 0.823969 0.566635 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.823969 0.566635 +0.000000 0.707107 0.707107 +0.000000 0.566635 0.823969 +0.000000 0.707107 0.707107 +0.000000 0.566635 0.823969 +0.000000 0.566635 0.823969 +0.000000 0.707107 0.707107 +0.000000 0.566635 0.823969 +0.000000 0.397177 0.917742 +0.000000 0.566635 0.823969 +0.000000 0.397177 0.917742 +0.000000 0.397177 0.917742 +0.000000 0.566635 0.823969 +0.000000 0.204909 0.978781 +0.000000 0.397177 0.917742 +0.000000 0.397177 0.917742 +0.000000 0.204909 0.978781 +0.000000 0.204909 0.978781 +0.000000 0.397177 0.917742 +0.000000 0.000000 1.000000 +0.000000 0.204909 0.978781 +0.000000 0.204909 0.978781 +0.000000 0.978781 0.204909 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.204909 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.204909 0.978781 +0.000000 0.204909 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.204909 0.978781 +0.000000 0.397177 0.917742 +0.000000 0.204909 0.978781 +0.000000 0.397177 0.917742 +0.000000 0.397177 0.917742 +0.000000 0.204909 0.978781 +0.000000 0.566635 0.823969 +0.000000 0.397177 0.917742 +0.000000 0.397177 0.917742 +0.000000 0.566635 0.823969 +0.000000 0.566635 0.823969 +0.000000 0.397177 0.917742 +0.000000 0.707107 0.707107 +0.000000 0.566635 0.823969 +0.000000 0.566635 0.823969 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.566635 0.823969 +0.000000 0.707107 0.707107 +0.000000 0.823969 0.566635 +0.000000 0.707107 0.707107 +0.000000 0.823969 0.566635 +0.000000 0.823969 0.566635 +0.000000 0.707107 0.707107 +0.000000 0.917742 0.397177 +0.000000 0.823969 0.566635 +0.000000 0.823969 0.566635 +0.000000 0.917742 0.397177 +0.000000 0.917742 0.397177 +0.000000 0.823969 0.566635 +0.000000 0.917742 0.397177 +0.000000 0.978781 0.204909 +0.000000 0.917742 0.397177 +0.000000 0.978781 0.204909 +0.000000 0.978781 0.204909 +0.000000 0.917742 0.397177 +0.000000 1.000000 0.000000 +0.000000 0.978781 0.204909 +0.000000 0.978781 0.204909 +0.000000 1.000000 0.000000 +0.000000 0.978781 0.204909 +0.000000 1.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.204909 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.204909 0.978781 +0.000000 0.204909 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.204909 0.978781 +0.000000 0.397177 0.917742 +0.000000 0.204909 0.978781 +0.000000 0.397177 0.917742 +0.000000 0.397177 0.917742 +0.000000 0.204909 0.978781 +0.000000 0.397177 0.917742 +0.000000 0.566635 0.823969 +0.000000 0.397177 0.917742 +0.000000 0.566635 0.823969 +0.000000 0.566635 0.823969 +0.000000 0.397177 0.917742 +0.000000 0.566635 0.823969 +0.000000 0.707107 0.707107 +0.000000 0.566635 0.823969 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.566635 0.823969 +0.000000 0.707107 0.707107 +0.000000 0.823969 0.566635 +0.000000 0.707107 0.707107 +0.000000 0.823969 0.566635 +0.000000 0.823969 0.566635 +0.000000 0.707107 0.707107 +0.000000 0.823969 0.566635 +0.000000 0.917742 0.397177 +0.000000 0.823969 0.566635 +0.000000 0.917742 0.397177 +0.000000 0.917742 0.397177 +0.000000 0.823969 0.566635 +0.000000 0.978781 0.204909 +0.000000 0.917742 0.397177 +0.000000 0.917742 0.397177 +0.000000 0.978781 0.204909 +0.000000 0.978781 0.204909 +0.000000 0.917742 0.397177 +0.000000 0.978781 0.204909 +0.000000 1.000000 0.000000 +0.000000 0.978781 0.204909 +0.000000 1.000000 0.000000 +0.000000 0.978781 0.204909 +0.000000 1.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.204909 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.204909 0.978781 +0.000000 0.204909 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.204909 0.978781 +0.000000 0.397177 0.917742 +0.000000 0.204909 0.978781 +0.000000 0.397177 0.917742 +0.000000 0.397177 0.917742 +0.000000 0.204909 0.978781 +0.000000 0.397177 0.917742 +0.000000 0.566635 0.823969 +0.000000 0.397177 0.917742 +0.000000 0.566635 0.823969 +0.000000 0.566635 0.823969 +0.000000 0.397177 0.917742 +0.000000 0.566635 0.823969 +0.000000 0.707107 0.707107 +0.000000 0.566635 0.823969 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.566635 0.823969 +0.000000 0.707107 0.707107 +0.000000 0.823969 0.566635 +0.000000 0.707107 0.707107 +0.000000 0.823969 0.566635 +0.000000 0.823969 0.566635 +0.000000 0.707107 0.707107 +0.000000 0.823969 0.566635 +0.000000 0.917742 0.397177 +0.000000 0.823969 0.566635 +0.000000 0.917742 0.397177 +0.000000 0.917742 0.397177 +0.000000 0.823969 0.566635 +0.000000 0.917742 0.397177 +0.000000 0.978781 0.204909 +0.000000 0.917742 0.397177 +0.000000 0.978781 0.204909 +0.000000 0.978781 0.204909 +0.000000 0.917742 0.397177 +0.000000 0.978781 0.204909 +0.000000 1.000000 0.000000 +0.000000 0.978781 0.204909 +0.000000 -0.204909 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -0.978781 0.204909 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -0.978781 0.204909 +0.000000 -0.978781 0.204909 +0.000000 -1.000000 0.000000 +0.000000 -0.917742 0.397177 +0.000000 -0.978781 0.204909 +0.000000 -0.978781 0.204909 +0.000000 -0.917742 0.397177 +0.000000 -0.917742 0.397177 +0.000000 -0.978781 0.204909 +0.000000 -0.917742 0.397177 +0.000000 -0.823969 0.566635 +0.000000 -0.917742 0.397177 +0.000000 -0.823969 0.566635 +0.000000 -0.823969 0.566635 +0.000000 -0.917742 0.397177 +0.000000 -0.707107 0.707107 +0.000000 -0.823969 0.566635 +0.000000 -0.823969 0.566635 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.823969 0.566635 +0.000000 -0.566635 0.823969 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.566635 0.823969 +0.000000 -0.566635 0.823969 +0.000000 -0.707107 0.707107 +0.000000 -0.397177 0.917742 +0.000000 -0.566635 0.823969 +0.000000 -0.566635 0.823969 +0.000000 -0.397177 0.917742 +0.000000 -0.397177 0.917742 +0.000000 -0.566635 0.823969 +0.000000 -0.204909 0.978781 +0.000000 -0.397177 0.917742 +0.000000 -0.397177 0.917742 +0.000000 -0.204909 0.978781 +0.000000 -0.204909 0.978781 +0.000000 -0.397177 0.917742 +0.000000 0.000000 1.000000 +0.000000 -0.204909 0.978781 +0.000000 -0.204909 0.978781 +0.000000 0.000000 1.000000 +0.000000 -0.204909 0.978781 +0.000000 0.000000 1.000000 +0.000000 -1.000000 0.000000 +0.000000 -0.978781 0.204909 +0.000000 -1.000000 0.000000 +0.000000 -0.978781 0.204909 +0.000000 -0.978781 0.204909 +0.000000 -1.000000 0.000000 +0.000000 -0.978781 0.204909 +0.000000 -0.917742 0.397177 +0.000000 -0.978781 0.204909 +0.000000 -0.917742 0.397177 +0.000000 -0.917742 0.397177 +0.000000 -0.978781 0.204909 +0.000000 -0.917742 0.397177 +0.000000 -0.823969 0.566635 +0.000000 -0.917742 0.397177 +0.000000 -0.823969 0.566635 +0.000000 -0.823969 0.566635 +0.000000 -0.917742 0.397177 +0.000000 -0.823969 0.566635 +0.000000 -0.707107 0.707107 +0.000000 -0.823969 0.566635 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.823969 0.566635 +0.000000 -0.707107 0.707107 +0.000000 -0.566635 0.823969 +0.000000 -0.707107 0.707107 +0.000000 -0.566635 0.823969 +0.000000 -0.566635 0.823969 +0.000000 -0.707107 0.707107 +0.000000 -0.566635 0.823969 +0.000000 -0.397177 0.917742 +0.000000 -0.566635 0.823969 +0.000000 -0.397177 0.917742 +0.000000 -0.397177 0.917742 +0.000000 -0.566635 0.823969 +0.000000 -0.204909 0.978781 +0.000000 -0.397177 0.917742 +0.000000 -0.397177 0.917742 +0.000000 -0.204909 0.978781 +0.000000 -0.204909 0.978781 +0.000000 -0.397177 0.917742 +0.000000 -0.204909 0.978781 +0.000000 0.000000 1.000000 +0.000000 -0.204909 0.978781 +0.000000 -0.204909 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -1.000000 0.000000 +0.000000 -0.978781 0.204909 +0.000000 -1.000000 0.000000 +0.000000 -0.978781 0.204909 +0.000000 -0.978781 0.204909 +0.000000 -1.000000 0.000000 +0.000000 -0.978781 0.204909 +0.000000 -0.917742 0.397177 +0.000000 -0.978781 0.204909 +0.000000 -0.917742 0.397177 +0.000000 -0.917742 0.397177 +0.000000 -0.978781 0.204909 +0.000000 -0.917742 0.397177 +0.000000 -0.823969 0.566635 +0.000000 -0.917742 0.397177 +0.000000 -0.823969 0.566635 +0.000000 -0.823969 0.566635 +0.000000 -0.917742 0.397177 +0.000000 -0.707107 0.707107 +0.000000 -0.823969 0.566635 +0.000000 -0.823969 0.566635 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.823969 0.566635 +0.000000 -0.566635 0.823969 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.566635 0.823969 +0.000000 -0.566635 0.823969 +0.000000 -0.707107 0.707107 +0.000000 -0.566635 0.823969 +0.000000 -0.397177 0.917742 +0.000000 -0.566635 0.823969 +0.000000 -0.397177 0.917742 +0.000000 -0.397177 0.917742 +0.000000 -0.566635 0.823969 +0.000000 -0.397177 0.917742 +0.000000 -0.204909 0.978781 +0.000000 -0.397177 0.917742 +0.000000 -0.204909 0.978781 +0.000000 -0.204909 0.978781 +0.000000 -0.397177 0.917742 +0.000000 0.000000 1.000000 +0.000000 -0.204909 0.978781 +0.000000 -0.204909 0.978781 +0.000000 -0.204909 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -1.000000 0.000000 +0.000000 -0.978781 0.204909 +0.000000 -1.000000 0.000000 +0.000000 -0.978781 0.204909 +0.000000 -0.978781 0.204909 +0.000000 -1.000000 0.000000 +0.000000 -0.917742 0.397177 +0.000000 -0.978781 0.204909 +0.000000 -0.978781 0.204909 +0.000000 -0.917742 0.397177 +0.000000 -0.917742 0.397177 +0.000000 -0.978781 0.204909 +0.000000 -0.823969 0.566635 +0.000000 -0.917742 0.397177 +0.000000 -0.917742 0.397177 +0.000000 -0.823969 0.566635 +0.000000 -0.823969 0.566635 +0.000000 -0.917742 0.397177 +0.000000 -0.707107 0.707107 +0.000000 -0.823969 0.566635 +0.000000 -0.823969 0.566635 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.823969 0.566635 +0.000000 -0.566635 0.823969 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.566635 0.823969 +0.000000 -0.566635 0.823969 +0.000000 -0.707107 0.707107 +0.000000 -0.566635 0.823969 +0.000000 -0.397177 0.917742 +0.000000 -0.566635 0.823969 +0.000000 -0.397177 0.917742 +0.000000 -0.397177 0.917742 +0.000000 -0.566635 0.823969 +0.000000 -0.397177 0.917742 +0.000000 -0.204909 0.978781 +0.000000 -0.397177 0.917742 +0.000000 -0.204909 0.978781 +0.000000 -0.204909 0.978781 +0.000000 -0.397177 0.917742 +0.000000 0.000000 1.000000 +0.000000 -0.204909 0.978781 +0.000000 -0.204909 0.978781 +0.000000 -0.204909 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -0.978781 0.204909 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -0.978781 0.204909 +0.000000 -0.978781 0.204909 +0.000000 -1.000000 0.000000 +0.000000 -0.978781 0.204909 +0.000000 -0.917742 0.397177 +0.000000 -0.978781 0.204909 +0.000000 -0.917742 0.397177 +0.000000 -0.917742 0.397177 +0.000000 -0.978781 0.204909 +0.000000 -0.917742 0.397177 +0.000000 -0.823969 0.566635 +0.000000 -0.917742 0.397177 +0.000000 -0.823969 0.566635 +0.000000 -0.823969 0.566635 +0.000000 -0.917742 0.397177 +0.000000 -0.707107 0.707107 +0.000000 -0.823969 0.566635 +0.000000 -0.823969 0.566635 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.823969 0.566635 +0.000000 -0.566635 0.823969 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.566635 0.823969 +0.000000 -0.566635 0.823969 +0.000000 -0.707107 0.707107 +0.000000 -0.566635 0.823969 +0.000000 -0.397177 0.917742 +0.000000 -0.566635 0.823969 +0.000000 -0.397177 0.917742 +0.000000 -0.397177 0.917742 +0.000000 -0.566635 0.823969 +0.000000 -0.204909 0.978781 +0.000000 -0.397177 0.917742 +0.000000 -0.397177 0.917742 +0.000000 -0.204909 0.978781 +0.000000 -0.204909 0.978781 +0.000000 -0.397177 0.917742 +0.000000 0.000000 1.000000 +0.000000 -0.204909 0.978781 +0.000000 -0.204909 0.978781 +0.000000 -0.917742 0.397177 +0.000000 -0.823969 0.566635 +0.000000 -0.917742 0.397177 +0.000000 -0.978781 0.204909 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -0.978781 0.204909 +0.000000 -0.978781 0.204909 +0.000000 -1.000000 0.000000 +0.000000 -0.917742 0.397177 +0.000000 -0.978781 0.204909 +0.000000 -0.978781 0.204909 +0.000000 -0.917742 0.397177 +0.000000 -0.917742 0.397177 +0.000000 -0.978781 0.204909 +0.000000 -0.204909 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -0.204909 0.978781 +0.000000 -0.204909 0.978781 +0.000000 0.000000 1.000000 +0.000000 -0.397177 0.917742 +0.000000 -0.204909 0.978781 +0.000000 -0.204909 0.978781 +0.000000 -0.397177 0.917742 +0.000000 -0.397177 0.917742 +0.000000 -0.204909 0.978781 +0.000000 -0.397177 0.917742 +0.000000 -0.566635 0.823969 +0.000000 -0.397177 0.917742 +0.000000 -0.566635 0.823969 +0.000000 -0.566635 0.823969 +0.000000 -0.397177 0.917742 +0.000000 -0.566635 0.823969 +0.000000 -0.707107 0.707107 +0.000000 -0.566635 0.823969 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.566635 0.823969 +0.000000 -0.707107 0.707107 +0.000000 -0.823969 0.566635 +0.000000 -0.707107 0.707107 +0.000000 -0.823969 0.566635 +0.000000 -0.823969 0.566635 +0.000000 -0.707107 0.707107 +0.000000 -0.823969 0.566635 +0.000000 -0.917742 0.397177 +0.000000 -0.823969 0.566635 +0.000000 0.000000 1.000000 +0.000000 -0.204909 0.978781 +0.000000 0.000000 1.000000 +0.000000 -0.978781 0.204909 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -0.978781 0.204909 +0.000000 -0.978781 0.204909 +0.000000 -1.000000 0.000000 +0.000000 -0.917742 0.397177 +0.000000 -0.978781 0.204909 +0.000000 -0.978781 0.204909 +0.000000 -0.917742 0.397177 +0.000000 -0.917742 0.397177 +0.000000 -0.978781 0.204909 +0.000000 -0.917742 0.397177 +0.000000 -0.823969 0.566635 +0.000000 -0.917742 0.397177 +0.000000 -0.823969 0.566635 +0.000000 -0.823969 0.566635 +0.000000 -0.917742 0.397177 +0.000000 -0.707107 0.707107 +0.000000 -0.823969 0.566635 +0.000000 -0.823969 0.566635 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.823969 0.566635 +0.000000 -0.707107 0.707107 +0.000000 -0.566635 0.823969 +0.000000 -0.707107 0.707107 +0.000000 -0.566635 0.823969 +0.000000 -0.566635 0.823969 +0.000000 -0.707107 0.707107 +0.000000 -0.566635 0.823969 +0.000000 -0.397177 0.917742 +0.000000 -0.566635 0.823969 +0.000000 -0.397177 0.917742 +0.000000 -0.397177 0.917742 +0.000000 -0.566635 0.823969 +0.000000 -0.397177 0.917742 +0.000000 -0.204909 0.978781 +0.000000 -0.397177 0.917742 +0.000000 -0.204909 0.978781 +0.000000 -0.204909 0.978781 +0.000000 -0.397177 0.917742 +0.000000 -0.204909 0.978781 +0.000000 0.000000 1.000000 +0.000000 -0.204909 0.978781 +0.000000 -0.514496 0.857493 +0.000000 -0.514496 0.857493 +0.000000 -0.514496 0.857493 +0.000000 -0.514496 0.857493 +0.000000 -0.514496 0.857493 +0.000000 -0.514496 0.857493 +0.000000 -0.514496 0.857493 +0.000000 -0.514496 0.857493 +0.000000 -0.514496 0.857493 +0.000000 -0.514496 0.857493 +0.000000 -0.514496 0.857493 +0.000000 -0.514496 0.857493 +0.000000 0.514496 0.857493 +0.000000 0.514496 0.857493 +0.000000 0.514496 0.857493 +0.000000 0.514496 0.857493 +0.000000 0.514496 0.857493 +0.000000 0.514496 0.857493 +0.000000 0.514496 0.857493 +0.000000 0.514496 0.857493 +0.000000 0.514496 0.857493 +0.000000 0.514496 0.857493 +0.000000 0.514496 0.857493 +0.000000 0.514496 0.857493 +0.000000 -0.514496 0.857493 +0.000000 -0.514496 0.857493 +0.000000 -0.514496 0.857493 +0.000000 -0.514496 0.857493 +0.000000 -0.514496 0.857493 +0.000000 -0.514496 0.857493 +0.000000 -0.514496 0.857493 +0.000000 -0.514496 0.857493 +0.000000 -0.514496 0.857493 +0.000000 -0.514496 0.857493 +0.000000 -0.514496 0.857493 +0.000000 -0.514496 0.857493 +0.000000 0.514496 0.857493 +0.000000 0.514496 0.857493 +0.000000 0.514496 0.857493 +0.000000 0.514496 0.857493 +0.000000 0.514496 0.857493 +0.000000 0.514496 0.857493 +0.000000 0.514496 0.857493 +0.000000 0.514496 0.857493 +0.000000 0.514496 0.857493 +0.000000 0.514496 0.857493 +0.000000 0.514496 0.857493 +0.000000 0.514496 0.857493 +0.000000 -0.352495 -0.935814 +0.000000 -0.352495 -0.935814 +0.000000 -0.352495 -0.935814 +0.000000 -0.352495 -0.935814 +0.000000 -0.352495 -0.935814 +0.000000 -0.352495 -0.935814 +0.000000 -0.352495 -0.935814 +0.000000 -0.352495 -0.935814 +0.000000 -0.352495 -0.935814 +0.000000 -0.352495 -0.935814 +0.000000 -0.352495 -0.935814 +0.000000 -0.352495 -0.935814 +0.000000 0.352495 -0.935814 +0.000000 0.352495 -0.935814 +0.000000 0.352495 -0.935814 +0.000000 0.352495 -0.935814 +0.000000 0.352495 -0.935814 +0.000000 0.352495 -0.935814 +0.000000 0.352495 -0.935814 +0.000000 0.352495 -0.935814 +0.000000 0.352495 -0.935814 +0.000000 0.352495 -0.935814 +0.000000 0.352495 -0.935814 +0.000000 0.352495 -0.935814 +0.000000 -0.352495 -0.935814 +0.000000 -0.352495 -0.935814 +0.000000 -0.352495 -0.935814 +0.000000 -0.352495 -0.935814 +0.000000 -0.352495 -0.935814 +0.000000 -0.352495 -0.935814 +0.000000 -0.352495 -0.935814 +0.000000 -0.352495 -0.935814 +0.000000 -0.352495 -0.935814 +0.000000 -0.352495 -0.935814 +0.000000 -0.352495 -0.935814 +0.000000 -0.352495 -0.935814 +0.000000 0.352495 -0.935814 +0.000000 0.352495 -0.935814 +0.000000 0.352495 -0.935814 +0.000000 0.352495 -0.935814 +0.000000 0.352495 -0.935814 +0.000000 0.352495 -0.935814 +0.000000 0.352495 -0.935814 +0.000000 0.352495 -0.935814 +0.000000 0.352495 -0.935814 +0.000000 0.352495 -0.935814 +0.000000 0.352495 -0.935814 +0.000000 0.352495 -0.935814 +-0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-0.978781 0.000000 0.204909 +-1.000000 0.000000 0.000000 +-0.978781 0.000000 0.204909 +-0.978781 0.000000 0.204909 +-1.000000 0.000000 0.000000 +-0.917742 0.000000 0.397177 +-0.978781 0.000000 0.204909 +-0.978781 0.000000 0.204909 +-0.917742 0.000000 0.397177 +-0.917742 0.000000 0.397177 +-0.978781 0.000000 0.204909 +-0.917742 0.000000 0.397177 +-0.823969 0.000000 0.566635 +-0.917742 0.000000 0.397177 +-0.823969 0.000000 0.566635 +-0.823969 0.000000 0.566635 +-0.917742 0.000000 0.397177 +-0.707107 0.000000 0.707107 +-0.823969 0.000000 0.566635 +-0.823969 0.000000 0.566635 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.823969 0.000000 0.566635 +-0.707107 0.000000 0.707107 +-0.566635 0.000000 0.823969 +-0.707107 0.000000 0.707107 +-0.566635 0.000000 0.823969 +-0.566635 0.000000 0.823969 +-0.707107 0.000000 0.707107 +-0.566635 0.000000 0.823969 +-0.397177 0.000000 0.917742 +-0.566635 0.000000 0.823969 +-0.397177 0.000000 0.917742 +-0.397177 0.000000 0.917742 +-0.566635 0.000000 0.823969 +-0.204909 0.000000 0.978781 +-0.397177 0.000000 0.917742 +-0.397177 0.000000 0.917742 +-0.204909 0.000000 0.978781 +-0.204909 0.000000 0.978781 +-0.397177 0.000000 0.917742 +0.000000 0.000000 1.000000 +-0.204909 0.000000 0.978781 +-0.204909 0.000000 0.978781 +-0.397177 0.000000 0.917742 +-0.204909 0.000000 0.978781 +-0.397177 0.000000 0.917742 +-1.000000 0.000000 0.000000 +-0.978781 0.000000 0.204909 +-1.000000 0.000000 0.000000 +-0.978781 0.000000 0.204909 +-0.978781 0.000000 0.204909 +-1.000000 0.000000 0.000000 +-0.917742 0.000000 0.397177 +-0.978781 0.000000 0.204909 +-0.978781 0.000000 0.204909 +-0.917742 0.000000 0.397177 +-0.917742 0.000000 0.397177 +-0.978781 0.000000 0.204909 +-0.917742 0.000000 0.397177 +-0.823969 0.000000 0.566635 +-0.917742 0.000000 0.397177 +-0.823969 0.000000 0.566635 +-0.823969 0.000000 0.566635 +-0.917742 0.000000 0.397177 +-0.707107 0.000000 0.707107 +-0.823969 0.000000 0.566635 +-0.823969 0.000000 0.566635 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.823969 0.000000 0.566635 +-0.707107 0.000000 0.707107 +-0.566635 0.000000 0.823969 +-0.707107 0.000000 0.707107 +-0.566635 0.000000 0.823969 +-0.566635 0.000000 0.823969 +-0.707107 0.000000 0.707107 +-0.397177 0.000000 0.917742 +-0.566635 0.000000 0.823969 +-0.566635 0.000000 0.823969 +-0.397177 0.000000 0.917742 +-0.397177 0.000000 0.917742 +-0.566635 0.000000 0.823969 +-0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.204909 0.000000 0.978781 +-0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +-0.204909 0.000000 0.978781 +-0.397177 0.000000 0.917742 +-0.204909 0.000000 0.978781 +0.978781 0.000000 0.204909 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.204909 0.000000 0.978781 +0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +0.397177 0.000000 0.917742 +0.204909 0.000000 0.978781 +0.204909 0.000000 0.978781 +0.397177 0.000000 0.917742 +0.397177 0.000000 0.917742 +0.204909 0.000000 0.978781 +0.397177 0.000000 0.917742 +0.566635 0.000000 0.823969 +0.397177 0.000000 0.917742 +0.566635 0.000000 0.823969 +0.566635 0.000000 0.823969 +0.397177 0.000000 0.917742 +0.566635 0.000000 0.823969 +0.707107 0.000000 0.707107 +0.566635 0.000000 0.823969 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.566635 0.000000 0.823969 +0.707107 0.000000 0.707107 +0.823969 0.000000 0.566635 +0.707107 0.000000 0.707107 +0.823969 0.000000 0.566635 +0.823969 0.000000 0.566635 +0.707107 0.000000 0.707107 +0.917742 0.000000 0.397177 +0.823969 0.000000 0.566635 +0.823969 0.000000 0.566635 +0.917742 0.000000 0.397177 +0.917742 0.000000 0.397177 +0.823969 0.000000 0.566635 +0.978781 0.000000 0.204909 +0.917742 0.000000 0.397177 +0.917742 0.000000 0.397177 +0.978781 0.000000 0.204909 +0.978781 0.000000 0.204909 +0.917742 0.000000 0.397177 +1.000000 0.000000 0.000000 +0.978781 0.000000 0.204909 +0.978781 0.000000 0.204909 +0.978781 0.000000 0.204909 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +0.204909 0.000000 0.978781 +0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +0.397177 0.000000 0.917742 +0.204909 0.000000 0.978781 +0.204909 0.000000 0.978781 +0.397177 0.000000 0.917742 +0.397177 0.000000 0.917742 +0.204909 0.000000 0.978781 +0.397177 0.000000 0.917742 +0.566635 0.000000 0.823969 +0.397177 0.000000 0.917742 +0.566635 0.000000 0.823969 +0.566635 0.000000 0.823969 +0.397177 0.000000 0.917742 +0.707107 0.000000 0.707107 +0.566635 0.000000 0.823969 +0.566635 0.000000 0.823969 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.566635 0.000000 0.823969 +0.707107 0.000000 0.707107 +0.823969 0.000000 0.566635 +0.707107 0.000000 0.707107 +0.823969 0.000000 0.566635 +0.823969 0.000000 0.566635 +0.707107 0.000000 0.707107 +0.917742 0.000000 0.397177 +0.823969 0.000000 0.566635 +0.823969 0.000000 0.566635 +0.917742 0.000000 0.397177 +0.917742 0.000000 0.397177 +0.823969 0.000000 0.566635 +0.978781 0.000000 0.204909 +0.917742 0.000000 0.397177 +0.917742 0.000000 0.397177 +0.978781 0.000000 0.204909 +0.978781 0.000000 0.204909 +0.917742 0.000000 0.397177 +1.000000 0.000000 0.000000 +0.978781 0.000000 0.204909 +0.978781 0.000000 0.204909 +0.000000 0.000000 1.000000 +-0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +-0.978781 0.000000 0.204909 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.978781 0.000000 0.204909 +-0.978781 0.000000 0.204909 +-1.000000 0.000000 0.000000 +-0.917742 0.000000 0.397177 +-0.978781 0.000000 0.204909 +-0.978781 0.000000 0.204909 +-0.917742 0.000000 0.397177 +-0.917742 0.000000 0.397177 +-0.978781 0.000000 0.204909 +-0.823969 0.000000 0.566635 +-0.917742 0.000000 0.397177 +-0.917742 0.000000 0.397177 +-0.823969 0.000000 0.566635 +-0.823969 0.000000 0.566635 +-0.917742 0.000000 0.397177 +-0.823969 0.000000 0.566635 +-0.707107 0.000000 0.707107 +-0.823969 0.000000 0.566635 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.823969 0.000000 0.566635 +-0.566635 0.000000 0.823969 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.566635 0.000000 0.823969 +-0.566635 0.000000 0.823969 +-0.707107 0.000000 0.707107 +-0.397177 0.000000 0.917742 +-0.566635 0.000000 0.823969 +-0.566635 0.000000 0.823969 +-0.397177 0.000000 0.917742 +-0.397177 0.000000 0.917742 +-0.566635 0.000000 0.823969 +-0.204909 0.000000 0.978781 +-0.397177 0.000000 0.917742 +-0.397177 0.000000 0.917742 +-0.204909 0.000000 0.978781 +-0.204909 0.000000 0.978781 +-0.397177 0.000000 0.917742 +-0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +-0.204909 0.000000 0.978781 +-0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.978781 0.000000 0.204909 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.978781 0.000000 0.204909 +-0.978781 0.000000 0.204909 +-1.000000 0.000000 0.000000 +-0.917742 0.000000 0.397177 +-0.978781 0.000000 0.204909 +-0.978781 0.000000 0.204909 +-0.917742 0.000000 0.397177 +-0.917742 0.000000 0.397177 +-0.978781 0.000000 0.204909 +-0.823969 0.000000 0.566635 +-0.917742 0.000000 0.397177 +-0.917742 0.000000 0.397177 +-0.823969 0.000000 0.566635 +-0.823969 0.000000 0.566635 +-0.917742 0.000000 0.397177 +-0.707107 0.000000 0.707107 +-0.823969 0.000000 0.566635 +-0.823969 0.000000 0.566635 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.823969 0.000000 0.566635 +-0.566635 0.000000 0.823969 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.566635 0.000000 0.823969 +-0.566635 0.000000 0.823969 +-0.707107 0.000000 0.707107 +-0.566635 0.000000 0.823969 +-0.397177 0.000000 0.917742 +-0.566635 0.000000 0.823969 +-0.397177 0.000000 0.917742 +-0.397177 0.000000 0.917742 +-0.566635 0.000000 0.823969 +-0.204909 0.000000 0.978781 +-0.397177 0.000000 0.917742 +-0.397177 0.000000 0.917742 +-0.204909 0.000000 0.978781 +-0.204909 0.000000 0.978781 +-0.397177 0.000000 0.917742 +0.000000 0.000000 1.000000 +-0.204909 0.000000 0.978781 +-0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 +0.978781 0.000000 0.204909 +1.000000 0.000000 0.000000 +0.978781 0.000000 0.204909 +0.978781 0.000000 0.204909 +1.000000 0.000000 0.000000 +0.978781 0.000000 0.204909 +0.917742 0.000000 0.397177 +0.978781 0.000000 0.204909 +0.917742 0.000000 0.397177 +0.917742 0.000000 0.397177 +0.978781 0.000000 0.204909 +0.823969 0.000000 0.566635 +0.917742 0.000000 0.397177 +0.917742 0.000000 0.397177 +0.823969 0.000000 0.566635 +0.823969 0.000000 0.566635 +0.917742 0.000000 0.397177 +0.707107 0.000000 0.707107 +0.823969 0.000000 0.566635 +0.823969 0.000000 0.566635 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.823969 0.000000 0.566635 +0.707107 0.000000 0.707107 +0.566635 0.000000 0.823969 +0.707107 0.000000 0.707107 +0.566635 0.000000 0.823969 +0.566635 0.000000 0.823969 +0.707107 0.000000 0.707107 +0.397177 0.000000 0.917742 +0.566635 0.000000 0.823969 +0.566635 0.000000 0.823969 +0.397177 0.000000 0.917742 +0.397177 0.000000 0.917742 +0.566635 0.000000 0.823969 +0.204909 0.000000 0.978781 +0.397177 0.000000 0.917742 +0.397177 0.000000 0.917742 +0.204909 0.000000 0.978781 +0.204909 0.000000 0.978781 +0.397177 0.000000 0.917742 +0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +0.204909 0.000000 0.978781 +0.917742 0.000000 0.397177 +0.978781 0.000000 0.204909 +0.978781 0.000000 0.204909 +1.000000 0.000000 0.000000 +0.978781 0.000000 0.204909 +1.000000 0.000000 0.000000 +0.978781 0.000000 0.204909 +0.978781 0.000000 0.204909 +1.000000 0.000000 0.000000 +0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.204909 0.000000 0.978781 +0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +0.397177 0.000000 0.917742 +0.204909 0.000000 0.978781 +0.204909 0.000000 0.978781 +0.397177 0.000000 0.917742 +0.397177 0.000000 0.917742 +0.204909 0.000000 0.978781 +0.397177 0.000000 0.917742 +0.566635 0.000000 0.823969 +0.397177 0.000000 0.917742 +0.566635 0.000000 0.823969 +0.566635 0.000000 0.823969 +0.397177 0.000000 0.917742 +0.707107 0.000000 0.707107 +0.566635 0.000000 0.823969 +0.566635 0.000000 0.823969 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.566635 0.000000 0.823969 +0.823969 0.000000 0.566635 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.823969 0.000000 0.566635 +0.823969 0.000000 0.566635 +0.707107 0.000000 0.707107 +0.823969 0.000000 0.566635 +0.917742 0.000000 0.397177 +0.823969 0.000000 0.566635 +0.917742 0.000000 0.397177 +0.917742 0.000000 0.397177 +0.823969 0.000000 0.566635 +0.978781 0.000000 0.204909 +0.917742 0.000000 0.397177 +0.917742 0.000000 0.397177 +-1.000000 0.000000 0.000000 +-0.978781 0.000000 0.204909 +-1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +-0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +-0.204909 0.000000 0.978781 +-0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +-0.204909 0.000000 0.978781 +-0.397177 0.000000 0.917742 +-0.204909 0.000000 0.978781 +-0.397177 0.000000 0.917742 +-0.397177 0.000000 0.917742 +-0.204909 0.000000 0.978781 +-0.566635 0.000000 0.823969 +-0.397177 0.000000 0.917742 +-0.397177 0.000000 0.917742 +-0.566635 0.000000 0.823969 +-0.566635 0.000000 0.823969 +-0.397177 0.000000 0.917742 +-0.566635 0.000000 0.823969 +-0.707107 0.000000 0.707107 +-0.566635 0.000000 0.823969 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.566635 0.000000 0.823969 +-0.823969 0.000000 0.566635 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.823969 0.000000 0.566635 +-0.823969 0.000000 0.566635 +-0.707107 0.000000 0.707107 +-0.823969 0.000000 0.566635 +-0.917742 0.000000 0.397177 +-0.823969 0.000000 0.566635 +-0.917742 0.000000 0.397177 +-0.917742 0.000000 0.397177 +-0.823969 0.000000 0.566635 +-0.978781 0.000000 0.204909 +-0.917742 0.000000 0.397177 +-0.917742 0.000000 0.397177 +-0.978781 0.000000 0.204909 +-0.978781 0.000000 0.204909 +-0.917742 0.000000 0.397177 +-0.978781 0.000000 0.204909 +-1.000000 0.000000 0.000000 +-0.978781 0.000000 0.204909 +0.000000 0.000000 1.000000 +-0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-0.978781 0.000000 0.204909 +-1.000000 0.000000 0.000000 +-0.978781 0.000000 0.204909 +-0.978781 0.000000 0.204909 +-1.000000 0.000000 0.000000 +-0.917742 0.000000 0.397177 +-0.978781 0.000000 0.204909 +-0.978781 0.000000 0.204909 +-0.917742 0.000000 0.397177 +-0.917742 0.000000 0.397177 +-0.978781 0.000000 0.204909 +-0.917742 0.000000 0.397177 +-0.823969 0.000000 0.566635 +-0.917742 0.000000 0.397177 +-0.823969 0.000000 0.566635 +-0.823969 0.000000 0.566635 +-0.917742 0.000000 0.397177 +-0.707107 0.000000 0.707107 +-0.823969 0.000000 0.566635 +-0.823969 0.000000 0.566635 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.823969 0.000000 0.566635 +-0.707107 0.000000 0.707107 +-0.566635 0.000000 0.823969 +-0.707107 0.000000 0.707107 +-0.566635 0.000000 0.823969 +-0.566635 0.000000 0.823969 +-0.707107 0.000000 0.707107 +-0.566635 0.000000 0.823969 +-0.397177 0.000000 0.917742 +-0.566635 0.000000 0.823969 +-0.397177 0.000000 0.917742 +-0.397177 0.000000 0.917742 +-0.566635 0.000000 0.823969 +-0.204909 0.000000 0.978781 +-0.397177 0.000000 0.917742 +-0.397177 0.000000 0.917742 +-0.204909 0.000000 0.978781 +-0.204909 0.000000 0.978781 +-0.397177 0.000000 0.917742 +-0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +-0.204909 0.000000 0.978781 +0.978781 0.000000 0.204909 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +0.204909 0.000000 0.978781 +0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +0.397177 0.000000 0.917742 +0.204909 0.000000 0.978781 +0.204909 0.000000 0.978781 +0.397177 0.000000 0.917742 +0.397177 0.000000 0.917742 +0.204909 0.000000 0.978781 +0.397177 0.000000 0.917742 +0.566635 0.000000 0.823969 +0.397177 0.000000 0.917742 +0.566635 0.000000 0.823969 +0.566635 0.000000 0.823969 +0.397177 0.000000 0.917742 +0.566635 0.000000 0.823969 +0.707107 0.000000 0.707107 +0.566635 0.000000 0.823969 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.566635 0.000000 0.823969 +0.707107 0.000000 0.707107 +0.823969 0.000000 0.566635 +0.707107 0.000000 0.707107 +0.823969 0.000000 0.566635 +0.823969 0.000000 0.566635 +0.707107 0.000000 0.707107 +0.823969 0.000000 0.566635 +0.917742 0.000000 0.397177 +0.823969 0.000000 0.566635 +0.917742 0.000000 0.397177 +0.917742 0.000000 0.397177 +0.823969 0.000000 0.566635 +0.978781 0.000000 0.204909 +0.917742 0.000000 0.397177 +0.917742 0.000000 0.397177 +0.978781 0.000000 0.204909 +0.978781 0.000000 0.204909 +0.917742 0.000000 0.397177 +1.000000 0.000000 0.000000 +0.978781 0.000000 0.204909 +0.978781 0.000000 0.204909 +0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +0.204909 0.000000 0.978781 +0.978781 0.000000 0.204909 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.978781 0.000000 0.204909 +0.978781 0.000000 0.204909 +1.000000 0.000000 0.000000 +0.978781 0.000000 0.204909 +0.917742 0.000000 0.397177 +0.978781 0.000000 0.204909 +0.917742 0.000000 0.397177 +0.917742 0.000000 0.397177 +0.978781 0.000000 0.204909 +0.823969 0.000000 0.566635 +0.917742 0.000000 0.397177 +0.917742 0.000000 0.397177 +0.823969 0.000000 0.566635 +0.823969 0.000000 0.566635 +0.917742 0.000000 0.397177 +0.707107 0.000000 0.707107 +0.823969 0.000000 0.566635 +0.823969 0.000000 0.566635 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.823969 0.000000 0.566635 +0.566635 0.000000 0.823969 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.566635 0.000000 0.823969 +0.566635 0.000000 0.823969 +0.707107 0.000000 0.707107 +0.566635 0.000000 0.823969 +0.397177 0.000000 0.917742 +0.566635 0.000000 0.823969 +0.397177 0.000000 0.917742 +0.397177 0.000000 0.917742 +0.566635 0.000000 0.823969 +0.397177 0.000000 0.917742 +0.204909 0.000000 0.978781 +0.397177 0.000000 0.917742 +0.204909 0.000000 0.978781 +0.204909 0.000000 0.978781 +0.397177 0.000000 0.917742 +0.000000 0.000000 1.000000 +0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +0.823969 0.000000 0.566635 +0.707107 0.000000 0.707107 +0.823969 0.000000 0.566635 +0.978781 0.000000 0.204909 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.978781 0.000000 0.204909 +0.978781 0.000000 0.204909 +1.000000 0.000000 0.000000 +0.917742 0.000000 0.397177 +0.978781 0.000000 0.204909 +0.978781 0.000000 0.204909 +0.917742 0.000000 0.397177 +0.917742 0.000000 0.397177 +0.978781 0.000000 0.204909 +0.917742 0.000000 0.397177 +0.823969 0.000000 0.566635 +0.917742 0.000000 0.397177 +0.823969 0.000000 0.566635 +0.823969 0.000000 0.566635 +0.917742 0.000000 0.397177 +0.000000 0.000000 1.000000 +0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +0.204909 0.000000 0.978781 +0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +0.397177 0.000000 0.917742 +0.204909 0.000000 0.978781 +0.204909 0.000000 0.978781 +0.397177 0.000000 0.917742 +0.397177 0.000000 0.917742 +0.204909 0.000000 0.978781 +0.566635 0.000000 0.823969 +0.397177 0.000000 0.917742 +0.397177 0.000000 0.917742 +0.566635 0.000000 0.823969 +0.566635 0.000000 0.823969 +0.397177 0.000000 0.917742 +0.707107 0.000000 0.707107 +0.566635 0.000000 0.823969 +0.566635 0.000000 0.823969 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.566635 0.000000 0.823969 +0.707107 0.000000 0.707107 +0.823969 0.000000 0.566635 +0.707107 0.000000 0.707107 +-0.823969 0.000000 0.566635 +-0.707107 0.000000 0.707107 +-0.823969 0.000000 0.566635 +-1.000000 0.000000 0.000000 +-0.978781 0.000000 0.204909 +-1.000000 0.000000 0.000000 +-0.978781 0.000000 0.204909 +-0.978781 0.000000 0.204909 +-1.000000 0.000000 0.000000 +-0.978781 0.000000 0.204909 +-0.917742 0.000000 0.397177 +-0.978781 0.000000 0.204909 +-0.917742 0.000000 0.397177 +-0.917742 0.000000 0.397177 +-0.978781 0.000000 0.204909 +-0.823969 0.000000 0.566635 +-0.917742 0.000000 0.397177 +-0.917742 0.000000 0.397177 +-0.823969 0.000000 0.566635 +-0.823969 0.000000 0.566635 +-0.917742 0.000000 0.397177 +0.000000 0.000000 1.000000 +-0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +-0.204909 0.000000 0.978781 +-0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +-0.397177 0.000000 0.917742 +-0.204909 0.000000 0.978781 +-0.204909 0.000000 0.978781 +-0.397177 0.000000 0.917742 +-0.397177 0.000000 0.917742 +-0.204909 0.000000 0.978781 +-0.566635 0.000000 0.823969 +-0.397177 0.000000 0.917742 +-0.397177 0.000000 0.917742 +-0.566635 0.000000 0.823969 +-0.566635 0.000000 0.823969 +-0.397177 0.000000 0.917742 +-0.707107 0.000000 0.707107 +-0.566635 0.000000 0.823969 +-0.566635 0.000000 0.823969 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.566635 0.000000 0.823969 +-0.707107 0.000000 0.707107 +-0.823969 0.000000 0.566635 +-0.707107 0.000000 0.707107 +0.000000 0.000000 1.000000 +-0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-0.978781 0.000000 0.204909 +-1.000000 0.000000 0.000000 +-0.978781 0.000000 0.204909 +-0.978781 0.000000 0.204909 +-1.000000 0.000000 0.000000 +-0.978781 0.000000 0.204909 +-0.917742 0.000000 0.397177 +-0.978781 0.000000 0.204909 +-0.917742 0.000000 0.397177 +-0.917742 0.000000 0.397177 +-0.978781 0.000000 0.204909 +-0.917742 0.000000 0.397177 +-0.823969 0.000000 0.566635 +-0.917742 0.000000 0.397177 +-0.823969 0.000000 0.566635 +-0.823969 0.000000 0.566635 +-0.917742 0.000000 0.397177 +-0.823969 0.000000 0.566635 +-0.707107 0.000000 0.707107 +-0.823969 0.000000 0.566635 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.823969 0.000000 0.566635 +-0.566635 0.000000 0.823969 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.566635 0.000000 0.823969 +-0.566635 0.000000 0.823969 +-0.707107 0.000000 0.707107 +-0.566635 0.000000 0.823969 +-0.397177 0.000000 0.917742 +-0.566635 0.000000 0.823969 +-0.397177 0.000000 0.917742 +-0.397177 0.000000 0.917742 +-0.566635 0.000000 0.823969 +-0.204909 0.000000 0.978781 +-0.397177 0.000000 0.917742 +-0.397177 0.000000 0.917742 +-0.204909 0.000000 0.978781 +-0.204909 0.000000 0.978781 +-0.397177 0.000000 0.917742 +-0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +-0.204909 0.000000 0.978781 +0.707107 0.000000 0.707107 +0.823969 0.000000 0.566635 +0.823969 0.000000 0.566635 +0.978781 0.000000 0.204909 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.978781 0.000000 0.204909 +0.978781 0.000000 0.204909 +1.000000 0.000000 0.000000 +0.917742 0.000000 0.397177 +0.978781 0.000000 0.204909 +0.978781 0.000000 0.204909 +0.917742 0.000000 0.397177 +0.917742 0.000000 0.397177 +0.978781 0.000000 0.204909 +0.823969 0.000000 0.566635 +0.917742 0.000000 0.397177 +0.917742 0.000000 0.397177 +0.823969 0.000000 0.566635 +0.823969 0.000000 0.566635 +0.917742 0.000000 0.397177 +0.000000 0.000000 1.000000 +0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +0.204909 0.000000 0.978781 +0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +0.397177 0.000000 0.917742 +0.204909 0.000000 0.978781 +0.204909 0.000000 0.978781 +0.397177 0.000000 0.917742 +0.397177 0.000000 0.917742 +0.204909 0.000000 0.978781 +0.397177 0.000000 0.917742 +0.566635 0.000000 0.823969 +0.397177 0.000000 0.917742 +0.566635 0.000000 0.823969 +0.566635 0.000000 0.823969 +0.397177 0.000000 0.917742 +0.566635 0.000000 0.823969 +0.707107 0.000000 0.707107 +0.566635 0.000000 0.823969 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.566635 0.000000 0.823969 +0.823969 0.000000 0.566635 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.566635 0.000000 0.823969 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.978781 0.000000 0.204909 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.978781 0.000000 0.204909 +0.978781 0.000000 0.204909 +1.000000 0.000000 0.000000 +0.917742 0.000000 0.397177 +0.978781 0.000000 0.204909 +0.978781 0.000000 0.204909 +0.917742 0.000000 0.397177 +0.917742 0.000000 0.397177 +0.978781 0.000000 0.204909 +0.823969 0.000000 0.566635 +0.917742 0.000000 0.397177 +0.917742 0.000000 0.397177 +0.823969 0.000000 0.566635 +0.823969 0.000000 0.566635 +0.917742 0.000000 0.397177 +0.823969 0.000000 0.566635 +0.707107 0.000000 0.707107 +0.823969 0.000000 0.566635 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.823969 0.000000 0.566635 +0.000000 0.000000 1.000000 +0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +0.204909 0.000000 0.978781 +0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +0.204909 0.000000 0.978781 +0.397177 0.000000 0.917742 +0.204909 0.000000 0.978781 +0.397177 0.000000 0.917742 +0.397177 0.000000 0.917742 +0.204909 0.000000 0.978781 +0.566635 0.000000 0.823969 +0.397177 0.000000 0.917742 +0.397177 0.000000 0.917742 +0.566635 0.000000 0.823969 +0.566635 0.000000 0.823969 +0.397177 0.000000 0.917742 +0.707107 0.000000 0.707107 +0.566635 0.000000 0.823969 +0.566635 0.000000 0.823969 +0.978781 0.000000 0.204909 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +0.204909 0.000000 0.978781 +0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +0.204909 0.000000 0.978781 +0.397177 0.000000 0.917742 +0.204909 0.000000 0.978781 +0.397177 0.000000 0.917742 +0.397177 0.000000 0.917742 +0.204909 0.000000 0.978781 +0.566635 0.000000 0.823969 +0.397177 0.000000 0.917742 +0.397177 0.000000 0.917742 +0.566635 0.000000 0.823969 +0.566635 0.000000 0.823969 +0.397177 0.000000 0.917742 +0.707107 0.000000 0.707107 +0.566635 0.000000 0.823969 +0.566635 0.000000 0.823969 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.566635 0.000000 0.823969 +0.707107 0.000000 0.707107 +0.823969 0.000000 0.566635 +0.707107 0.000000 0.707107 +0.823969 0.000000 0.566635 +0.823969 0.000000 0.566635 +0.707107 0.000000 0.707107 +0.917742 0.000000 0.397177 +0.823969 0.000000 0.566635 +0.823969 0.000000 0.566635 +0.917742 0.000000 0.397177 +0.917742 0.000000 0.397177 +0.823969 0.000000 0.566635 +0.978781 0.000000 0.204909 +0.917742 0.000000 0.397177 +0.917742 0.000000 0.397177 +0.978781 0.000000 0.204909 +0.978781 0.000000 0.204909 +0.917742 0.000000 0.397177 +1.000000 0.000000 0.000000 +0.978781 0.000000 0.204909 +0.978781 0.000000 0.204909 +-0.566635 0.000000 0.823969 +-0.707107 0.000000 0.707107 +-0.566635 0.000000 0.823969 +0.000000 0.000000 1.000000 +-0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +-0.204909 0.000000 0.978781 +-0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +-0.204909 0.000000 0.978781 +-0.397177 0.000000 0.917742 +-0.204909 0.000000 0.978781 +-0.397177 0.000000 0.917742 +-0.397177 0.000000 0.917742 +-0.204909 0.000000 0.978781 +-0.397177 0.000000 0.917742 +-0.566635 0.000000 0.823969 +-0.397177 0.000000 0.917742 +-0.566635 0.000000 0.823969 +-0.566635 0.000000 0.823969 +-0.397177 0.000000 0.917742 +-1.000000 0.000000 0.000000 +-0.978781 0.000000 0.204909 +-1.000000 0.000000 0.000000 +-0.978781 0.000000 0.204909 +-0.978781 0.000000 0.204909 +-1.000000 0.000000 0.000000 +-0.917742 0.000000 0.397177 +-0.978781 0.000000 0.204909 +-0.978781 0.000000 0.204909 +-0.917742 0.000000 0.397177 +-0.917742 0.000000 0.397177 +-0.978781 0.000000 0.204909 +-0.823969 0.000000 0.566635 +-0.917742 0.000000 0.397177 +-0.917742 0.000000 0.397177 +-0.823969 0.000000 0.566635 +-0.823969 0.000000 0.566635 +-0.917742 0.000000 0.397177 +-0.707107 0.000000 0.707107 +-0.823969 0.000000 0.566635 +-0.823969 0.000000 0.566635 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.823969 0.000000 0.566635 +-0.707107 0.000000 0.707107 +-0.566635 0.000000 0.823969 +-0.707107 0.000000 0.707107 +-0.978781 0.000000 0.204909 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +-0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +-0.204909 0.000000 0.978781 +-0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +-0.397177 0.000000 0.917742 +-0.204909 0.000000 0.978781 +-0.204909 0.000000 0.978781 +-0.397177 0.000000 0.917742 +-0.397177 0.000000 0.917742 +-0.204909 0.000000 0.978781 +-0.397177 0.000000 0.917742 +-0.566635 0.000000 0.823969 +-0.397177 0.000000 0.917742 +-0.566635 0.000000 0.823969 +-0.566635 0.000000 0.823969 +-0.397177 0.000000 0.917742 +-0.566635 0.000000 0.823969 +-0.707107 0.000000 0.707107 +-0.566635 0.000000 0.823969 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.566635 0.000000 0.823969 +-0.823969 0.000000 0.566635 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.823969 0.000000 0.566635 +-0.823969 0.000000 0.566635 +-0.707107 0.000000 0.707107 +-0.823969 0.000000 0.566635 +-0.917742 0.000000 0.397177 +-0.823969 0.000000 0.566635 +-0.917742 0.000000 0.397177 +-0.917742 0.000000 0.397177 +-0.823969 0.000000 0.566635 +-0.978781 0.000000 0.204909 +-0.917742 0.000000 0.397177 +-0.917742 0.000000 0.397177 +-0.978781 0.000000 0.204909 +-0.978781 0.000000 0.204909 +-0.917742 0.000000 0.397177 +-1.000000 0.000000 0.000000 +-0.978781 0.000000 0.204909 +-0.978781 0.000000 0.204909 +0.000000 0.000000 1.000000 +0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 +0.978781 0.000000 0.204909 +1.000000 0.000000 0.000000 +0.978781 0.000000 0.204909 +0.978781 0.000000 0.204909 +1.000000 0.000000 0.000000 +0.917742 0.000000 0.397177 +0.978781 0.000000 0.204909 +0.978781 0.000000 0.204909 +0.917742 0.000000 0.397177 +0.917742 0.000000 0.397177 +0.978781 0.000000 0.204909 +0.823969 0.000000 0.566635 +0.917742 0.000000 0.397177 +0.917742 0.000000 0.397177 +0.823969 0.000000 0.566635 +0.823969 0.000000 0.566635 +0.917742 0.000000 0.397177 +0.707107 0.000000 0.707107 +0.823969 0.000000 0.566635 +0.823969 0.000000 0.566635 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.823969 0.000000 0.566635 +0.707107 0.000000 0.707107 +0.566635 0.000000 0.823969 +0.707107 0.000000 0.707107 +0.566635 0.000000 0.823969 +0.566635 0.000000 0.823969 +0.707107 0.000000 0.707107 +0.397177 0.000000 0.917742 +0.566635 0.000000 0.823969 +0.566635 0.000000 0.823969 +0.397177 0.000000 0.917742 +0.397177 0.000000 0.917742 +0.566635 0.000000 0.823969 +0.397177 0.000000 0.917742 +0.204909 0.000000 0.978781 +0.397177 0.000000 0.917742 +0.204909 0.000000 0.978781 +0.204909 0.000000 0.978781 +0.397177 0.000000 0.917742 +0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +-0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +-0.978781 0.000000 0.204909 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.978781 0.000000 0.204909 +-0.978781 0.000000 0.204909 +-1.000000 0.000000 0.000000 +-0.978781 0.000000 0.204909 +-0.917742 0.000000 0.397177 +-0.978781 0.000000 0.204909 +-0.917742 0.000000 0.397177 +-0.917742 0.000000 0.397177 +-0.978781 0.000000 0.204909 +-0.917742 0.000000 0.397177 +-0.823969 0.000000 0.566635 +-0.917742 0.000000 0.397177 +-0.823969 0.000000 0.566635 +-0.823969 0.000000 0.566635 +-0.917742 0.000000 0.397177 +-0.823969 0.000000 0.566635 +-0.707107 0.000000 0.707107 +-0.823969 0.000000 0.566635 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.823969 0.000000 0.566635 +-0.566635 0.000000 0.823969 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.566635 0.000000 0.823969 +-0.566635 0.000000 0.823969 +-0.707107 0.000000 0.707107 +-0.566635 0.000000 0.823969 +-0.397177 0.000000 0.917742 +-0.566635 0.000000 0.823969 +-0.397177 0.000000 0.917742 +-0.397177 0.000000 0.917742 +-0.566635 0.000000 0.823969 +-0.397177 0.000000 0.917742 +-0.204909 0.000000 0.978781 +-0.397177 0.000000 0.917742 +-0.204909 0.000000 0.978781 +-0.204909 0.000000 0.978781 +-0.397177 0.000000 0.917742 +-0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +-0.204909 0.000000 0.978781 +-0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.978781 0.000000 0.204909 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.978781 0.000000 0.204909 +-0.978781 0.000000 0.204909 +-1.000000 0.000000 0.000000 +-0.917742 0.000000 0.397177 +-0.978781 0.000000 0.204909 +-0.978781 0.000000 0.204909 +-0.917742 0.000000 0.397177 +-0.917742 0.000000 0.397177 +-0.978781 0.000000 0.204909 +-0.823969 0.000000 0.566635 +-0.917742 0.000000 0.397177 +-0.917742 0.000000 0.397177 +-0.823969 0.000000 0.566635 +-0.823969 0.000000 0.566635 +-0.917742 0.000000 0.397177 +-0.823969 0.000000 0.566635 +-0.707107 0.000000 0.707107 +-0.823969 0.000000 0.566635 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.823969 0.000000 0.566635 +-0.707107 0.000000 0.707107 +-0.566635 0.000000 0.823969 +-0.707107 0.000000 0.707107 +-0.566635 0.000000 0.823969 +-0.566635 0.000000 0.823969 +-0.707107 0.000000 0.707107 +-0.397177 0.000000 0.917742 +-0.566635 0.000000 0.823969 +-0.566635 0.000000 0.823969 +-0.397177 0.000000 0.917742 +-0.397177 0.000000 0.917742 +-0.566635 0.000000 0.823969 +-0.204909 0.000000 0.978781 +-0.397177 0.000000 0.917742 +-0.397177 0.000000 0.917742 +-0.204909 0.000000 0.978781 +-0.204909 0.000000 0.978781 +-0.397177 0.000000 0.917742 +0.000000 0.000000 1.000000 +-0.204909 0.000000 0.978781 +-0.204909 0.000000 0.978781 +-0.917742 0.000000 0.397177 +-0.823969 0.000000 0.566635 +-0.917742 0.000000 0.397177 +-0.978781 0.000000 0.204909 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.978781 0.000000 0.204909 +-0.978781 0.000000 0.204909 +-1.000000 0.000000 0.000000 +-0.978781 0.000000 0.204909 +-0.917742 0.000000 0.397177 +-0.978781 0.000000 0.204909 +-0.917742 0.000000 0.397177 +-0.917742 0.000000 0.397177 +-0.978781 0.000000 0.204909 +0.000000 0.000000 1.000000 +-0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +-0.204909 0.000000 0.978781 +-0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +-0.397177 0.000000 0.917742 +-0.204909 0.000000 0.978781 +-0.204909 0.000000 0.978781 +-0.397177 0.000000 0.917742 +-0.397177 0.000000 0.917742 +-0.204909 0.000000 0.978781 +-0.397177 0.000000 0.917742 +-0.566635 0.000000 0.823969 +-0.397177 0.000000 0.917742 +-0.566635 0.000000 0.823969 +-0.566635 0.000000 0.823969 +-0.397177 0.000000 0.917742 +-0.707107 0.000000 0.707107 +-0.566635 0.000000 0.823969 +-0.566635 0.000000 0.823969 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.566635 0.000000 0.823969 +-0.823969 0.000000 0.566635 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.823969 0.000000 0.566635 +-0.823969 0.000000 0.566635 +-0.707107 0.000000 0.707107 +-0.823969 0.000000 0.566635 +-0.917742 0.000000 0.397177 +-0.823969 0.000000 0.566635 +-0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.978781 0.000000 0.204909 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.978781 0.000000 0.204909 +-0.978781 0.000000 0.204909 +-1.000000 0.000000 0.000000 +-0.917742 0.000000 0.397177 +-0.978781 0.000000 0.204909 +-0.978781 0.000000 0.204909 +-0.917742 0.000000 0.397177 +-0.917742 0.000000 0.397177 +-0.978781 0.000000 0.204909 +-0.823969 0.000000 0.566635 +-0.917742 0.000000 0.397177 +-0.917742 0.000000 0.397177 +-0.823969 0.000000 0.566635 +-0.823969 0.000000 0.566635 +-0.917742 0.000000 0.397177 +-0.823969 0.000000 0.566635 +-0.707107 0.000000 0.707107 +-0.823969 0.000000 0.566635 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.823969 0.000000 0.566635 +-0.566635 0.000000 0.823969 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.566635 0.000000 0.823969 +-0.566635 0.000000 0.823969 +-0.707107 0.000000 0.707107 +-0.397177 0.000000 0.917742 +-0.566635 0.000000 0.823969 +-0.566635 0.000000 0.823969 +-0.397177 0.000000 0.917742 +-0.397177 0.000000 0.917742 +-0.566635 0.000000 0.823969 +-0.204909 0.000000 0.978781 +-0.397177 0.000000 0.917742 +-0.397177 0.000000 0.917742 +-0.204909 0.000000 0.978781 +-0.204909 0.000000 0.978781 +-0.397177 0.000000 0.917742 +0.000000 0.000000 1.000000 +-0.204909 0.000000 0.978781 +-0.204909 0.000000 0.978781 +0.978781 0.000000 0.204909 +0.917742 0.000000 0.397177 +0.978781 0.000000 0.204909 +1.000000 0.000000 0.000000 +0.978781 0.000000 0.204909 +1.000000 0.000000 0.000000 +0.978781 0.000000 0.204909 +0.978781 0.000000 0.204909 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +0.204909 0.000000 0.978781 +0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +0.204909 0.000000 0.978781 +0.397177 0.000000 0.917742 +0.204909 0.000000 0.978781 +0.397177 0.000000 0.917742 +0.397177 0.000000 0.917742 +0.204909 0.000000 0.978781 +0.566635 0.000000 0.823969 +0.397177 0.000000 0.917742 +0.397177 0.000000 0.917742 +0.566635 0.000000 0.823969 +0.566635 0.000000 0.823969 +0.397177 0.000000 0.917742 +0.707107 0.000000 0.707107 +0.566635 0.000000 0.823969 +0.566635 0.000000 0.823969 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.566635 0.000000 0.823969 +0.707107 0.000000 0.707107 +0.823969 0.000000 0.566635 +0.707107 0.000000 0.707107 +0.823969 0.000000 0.566635 +0.823969 0.000000 0.566635 +0.707107 0.000000 0.707107 +0.917742 0.000000 0.397177 +0.823969 0.000000 0.566635 +0.823969 0.000000 0.566635 +0.917742 0.000000 0.397177 +0.917742 0.000000 0.397177 +0.823969 0.000000 0.566635 +0.917742 0.000000 0.397177 +0.978781 0.000000 0.204909 +0.917742 0.000000 0.397177 +0.978781 0.000000 0.204909 +1.000000 0.000000 0.000000 +0.978781 0.000000 0.204909 +0.000000 0.000000 1.000000 +0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +0.204909 0.000000 0.978781 +0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +0.397177 0.000000 0.917742 +0.204909 0.000000 0.978781 +0.204909 0.000000 0.978781 +0.397177 0.000000 0.917742 +0.397177 0.000000 0.917742 +0.204909 0.000000 0.978781 +0.566635 0.000000 0.823969 +0.397177 0.000000 0.917742 +0.397177 0.000000 0.917742 +0.566635 0.000000 0.823969 +0.566635 0.000000 0.823969 +0.397177 0.000000 0.917742 +0.566635 0.000000 0.823969 +0.707107 0.000000 0.707107 +0.566635 0.000000 0.823969 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.566635 0.000000 0.823969 +0.707107 0.000000 0.707107 +0.823969 0.000000 0.566635 +0.707107 0.000000 0.707107 +0.823969 0.000000 0.566635 +0.823969 0.000000 0.566635 +0.707107 0.000000 0.707107 +0.917742 0.000000 0.397177 +0.823969 0.000000 0.566635 +0.823969 0.000000 0.566635 +0.917742 0.000000 0.397177 +0.917742 0.000000 0.397177 +0.823969 0.000000 0.566635 +0.978781 0.000000 0.204909 +0.917742 0.000000 0.397177 +0.917742 0.000000 0.397177 +0.978781 0.000000 0.204909 +0.978781 0.000000 0.204909 +0.917742 0.000000 0.397177 +1.000000 0.000000 0.000000 +0.978781 0.000000 0.204909 +1.000000 0.000000 0.000000 +0.397177 0.000000 0.917742 +0.204909 0.000000 0.978781 +0.204909 0.000000 0.978781 +0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.204909 0.000000 0.978781 +0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 +0.978781 0.000000 0.204909 +1.000000 0.000000 0.000000 +0.978781 0.000000 0.204909 +0.978781 0.000000 0.204909 +1.000000 0.000000 0.000000 +0.917742 0.000000 0.397177 +0.978781 0.000000 0.204909 +0.978781 0.000000 0.204909 +0.917742 0.000000 0.397177 +0.917742 0.000000 0.397177 +0.978781 0.000000 0.204909 +0.917742 0.000000 0.397177 +0.823969 0.000000 0.566635 +0.917742 0.000000 0.397177 +0.823969 0.000000 0.566635 +0.823969 0.000000 0.566635 +0.917742 0.000000 0.397177 +0.823969 0.000000 0.566635 +0.707107 0.000000 0.707107 +0.823969 0.000000 0.566635 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.823969 0.000000 0.566635 +0.566635 0.000000 0.823969 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.566635 0.000000 0.823969 +0.566635 0.000000 0.823969 +0.707107 0.000000 0.707107 +0.397177 0.000000 0.917742 +0.566635 0.000000 0.823969 +0.566635 0.000000 0.823969 +0.397177 0.000000 0.917742 +0.397177 0.000000 0.917742 +0.566635 0.000000 0.823969 +0.204909 0.000000 0.978781 +0.397177 0.000000 0.917742 +0.397177 0.000000 0.917742 +-0.397177 0.000000 0.917742 +-0.566635 0.000000 0.823969 +-0.397177 0.000000 0.917742 +0.000000 0.000000 1.000000 +-0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +-0.204909 0.000000 0.978781 +-0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +-0.397177 0.000000 0.917742 +-0.204909 0.000000 0.978781 +-0.204909 0.000000 0.978781 +-0.397177 0.000000 0.917742 +-0.397177 0.000000 0.917742 +-0.204909 0.000000 0.978781 +-0.978781 0.000000 0.204909 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.978781 0.000000 0.204909 +-0.978781 0.000000 0.204909 +-1.000000 0.000000 0.000000 +-0.917742 0.000000 0.397177 +-0.978781 0.000000 0.204909 +-0.978781 0.000000 0.204909 +-0.917742 0.000000 0.397177 +-0.917742 0.000000 0.397177 +-0.978781 0.000000 0.204909 +-0.823969 0.000000 0.566635 +-0.917742 0.000000 0.397177 +-0.917742 0.000000 0.397177 +-0.823969 0.000000 0.566635 +-0.823969 0.000000 0.566635 +-0.917742 0.000000 0.397177 +-0.707107 0.000000 0.707107 +-0.823969 0.000000 0.566635 +-0.823969 0.000000 0.566635 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.823969 0.000000 0.566635 +-0.707107 0.000000 0.707107 +-0.566635 0.000000 0.823969 +-0.707107 0.000000 0.707107 +-0.566635 0.000000 0.823969 +-0.566635 0.000000 0.823969 +-0.707107 0.000000 0.707107 +-0.566635 0.000000 0.823969 +-0.397177 0.000000 0.917742 +-0.566635 0.000000 0.823969 +-0.566635 0.000000 0.823969 +-0.397177 0.000000 0.917742 +-0.397177 0.000000 0.917742 +-0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.204909 0.000000 0.978781 +-0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +-0.204909 0.000000 0.978781 +-0.397177 0.000000 0.917742 +-0.204909 0.000000 0.978781 +-0.397177 0.000000 0.917742 +-0.397177 0.000000 0.917742 +-0.204909 0.000000 0.978781 +-0.978781 0.000000 0.204909 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.978781 0.000000 0.204909 +-0.978781 0.000000 0.204909 +-1.000000 0.000000 0.000000 +-0.978781 0.000000 0.204909 +-0.917742 0.000000 0.397177 +-0.978781 0.000000 0.204909 +-0.917742 0.000000 0.397177 +-0.917742 0.000000 0.397177 +-0.978781 0.000000 0.204909 +-0.823969 0.000000 0.566635 +-0.917742 0.000000 0.397177 +-0.917742 0.000000 0.397177 +-0.823969 0.000000 0.566635 +-0.823969 0.000000 0.566635 +-0.917742 0.000000 0.397177 +-0.707107 0.000000 0.707107 +-0.823969 0.000000 0.566635 +-0.823969 0.000000 0.566635 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.823969 0.000000 0.566635 +-0.707107 0.000000 0.707107 +-0.566635 0.000000 0.823969 +-0.707107 0.000000 0.707107 +-0.566635 0.000000 0.823969 +-0.566635 0.000000 0.823969 +-0.707107 0.000000 0.707107 +-0.397177 0.000000 0.917742 +-0.566635 0.000000 0.823969 +-0.566635 0.000000 0.823969 +0.204909 0.000000 0.978781 +0.397177 0.000000 0.917742 +0.204909 0.000000 0.978781 +0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.204909 0.000000 0.978781 +0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 +0.978781 0.000000 0.204909 +1.000000 0.000000 0.000000 +0.978781 0.000000 0.204909 +0.978781 0.000000 0.204909 +1.000000 0.000000 0.000000 +0.917742 0.000000 0.397177 +0.978781 0.000000 0.204909 +0.978781 0.000000 0.204909 +0.917742 0.000000 0.397177 +0.917742 0.000000 0.397177 +0.978781 0.000000 0.204909 +0.823969 0.000000 0.566635 +0.917742 0.000000 0.397177 +0.917742 0.000000 0.397177 +0.823969 0.000000 0.566635 +0.823969 0.000000 0.566635 +0.917742 0.000000 0.397177 +0.707107 0.000000 0.707107 +0.823969 0.000000 0.566635 +0.823969 0.000000 0.566635 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.823969 0.000000 0.566635 +0.566635 0.000000 0.823969 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.566635 0.000000 0.823969 +0.566635 0.000000 0.823969 +0.707107 0.000000 0.707107 +0.566635 0.000000 0.823969 +0.397177 0.000000 0.917742 +0.566635 0.000000 0.823969 +0.397177 0.000000 0.917742 +0.397177 0.000000 0.917742 +0.566635 0.000000 0.823969 +0.397177 0.000000 0.917742 +0.204909 0.000000 0.978781 +0.397177 0.000000 0.917742 +0.397177 0.000000 0.917742 +0.566635 0.000000 0.823969 +0.397177 0.000000 0.917742 +0.000000 0.000000 1.000000 +0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +0.204909 0.000000 0.978781 +0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +0.204909 0.000000 0.978781 +0.397177 0.000000 0.917742 +0.204909 0.000000 0.978781 +0.397177 0.000000 0.917742 +0.397177 0.000000 0.917742 +0.204909 0.000000 0.978781 +1.000000 0.000000 0.000000 +0.978781 0.000000 0.204909 +1.000000 0.000000 0.000000 +0.978781 0.000000 0.204909 +0.978781 0.000000 0.204909 +1.000000 0.000000 0.000000 +0.917742 0.000000 0.397177 +0.978781 0.000000 0.204909 +0.978781 0.000000 0.204909 +0.917742 0.000000 0.397177 +0.917742 0.000000 0.397177 +0.978781 0.000000 0.204909 +0.917742 0.000000 0.397177 +0.823969 0.000000 0.566635 +0.917742 0.000000 0.397177 +0.823969 0.000000 0.566635 +0.823969 0.000000 0.566635 +0.917742 0.000000 0.397177 +0.823969 0.000000 0.566635 +0.707107 0.000000 0.707107 +0.823969 0.000000 0.566635 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.823969 0.000000 0.566635 +0.707107 0.000000 0.707107 +0.566635 0.000000 0.823969 +0.707107 0.000000 0.707107 +0.566635 0.000000 0.823969 +0.566635 0.000000 0.823969 +0.707107 0.000000 0.707107 +0.566635 0.000000 0.823969 +0.397177 0.000000 0.917742 +0.566635 0.000000 0.823969 + + + + + + + + + + + +0.664764 0.213395 +0.665936 0.213395 +0.754455 0.213395 +0.755627 0.213395 +0.753716 0.205513 +0.751347 0.197451 +0.754869 0.205304 +0.752437 0.197028 +0.747240 0.189692 +0.748222 0.189064 +0.741491 0.182766 +0.742321 0.181955 +0.734415 0.177140 +0.735056 0.176180 +0.726487 0.173121 +0.726919 0.172054 +0.718249 0.170803 +0.718462 0.169675 +0.710195 0.170080 +0.710195 0.168932 +0.702142 0.170803 +0.701929 0.169675 +0.693904 0.173121 +0.693472 0.172054 +0.685976 0.177140 +0.685335 0.176180 +0.678899 0.182766 +0.678070 0.181955 +0.673151 0.189692 +0.672169 0.189064 +0.669044 0.197451 +0.667953 0.197028 +0.666675 0.205513 +0.665522 0.205304 +0.518210 0.213395 +0.519382 0.213395 +0.607901 0.213395 +0.609073 0.213395 +0.607162 0.205513 +0.608315 0.205304 +0.604793 0.197451 +0.605883 0.197028 +0.600686 0.189692 +0.601668 0.189064 +0.594937 0.182766 +0.595766 0.181955 +0.587860 0.177140 +0.579933 0.173121 +0.588502 0.176180 +0.580365 0.172054 +0.571695 0.170803 +0.571908 0.169675 +0.563641 0.170080 +0.563641 0.168932 +0.555588 0.170803 +0.555374 0.169675 +0.547350 0.173121 +0.546918 0.172054 +0.539422 0.177140 +0.538781 0.176180 +0.532345 0.182766 +0.531516 0.181955 +0.526596 0.189692 +0.525615 0.189064 +0.522489 0.197451 +0.521399 0.197028 +0.520121 0.205513 +0.518968 0.205304 +0.225101 0.213395 +0.226274 0.213395 +0.314793 0.213395 +0.315965 0.213395 +0.314054 0.205513 +0.315206 0.205304 +0.311685 0.197451 +0.312775 0.197028 +0.307578 0.189692 +0.308559 0.189064 +0.301829 0.182766 +0.302658 0.181955 +0.294752 0.177140 +0.286825 0.173121 +0.295394 0.176180 +0.287256 0.172054 +0.278587 0.170803 +0.278800 0.169675 +0.270533 0.170080 +0.270533 0.168932 +0.262480 0.170803 +0.262266 0.169675 +0.254242 0.173121 +0.253810 0.172054 +0.246314 0.177140 +0.245672 0.176180 +0.239237 0.182766 +0.238408 0.181955 +0.233488 0.189692 +0.232507 0.189064 +0.229381 0.197451 +0.228291 0.197028 +0.227013 0.205513 +0.225860 0.205304 +0.332379 0.185857 +0.333551 0.185857 +0.363199 0.183195 +0.363448 0.185857 +0.364621 0.185857 +0.364352 0.182986 +0.362399 0.180472 +0.363489 0.180049 +0.361012 0.177851 +0.361993 0.177223 +0.359070 0.175512 +0.359899 0.174701 +0.356680 0.173612 +0.357322 0.172651 +0.354002 0.172254 +0.354434 0.171187 +0.351220 0.171471 +0.351433 0.170343 +0.348500 0.171227 +0.348500 0.170080 +0.345780 0.171471 +0.345567 0.170343 +0.342997 0.172254 +0.342566 0.171187 +0.340320 0.173612 +0.339678 0.172651 +0.337930 0.175512 +0.337101 0.174701 +0.335988 0.177851 +0.335007 0.177223 +0.334601 0.180472 +0.333511 0.180049 +0.333801 0.183195 +0.332648 0.182986 +0.348500 0.253554 +0.362334 0.243438 +0.362569 0.240933 +0.361397 0.240933 +0.361581 0.246001 +0.361181 0.243229 +0.360276 0.248467 +0.360491 0.245579 +0.358448 0.250669 +0.359295 0.247839 +0.356199 0.252457 +0.357619 0.249858 +0.353679 0.253735 +0.355557 0.251497 +0.351060 0.254472 +0.353247 0.252668 +0.348500 0.254702 +0.350847 0.253344 +0.335818 0.243229 +0.335603 0.240933 +0.334431 0.240933 +0.334666 0.243438 +0.336509 0.245579 +0.335419 0.246001 +0.337705 0.247839 +0.336724 0.248467 +0.339381 0.249858 +0.338552 0.250669 +0.341443 0.251497 +0.340801 0.252457 +0.343753 0.252668 +0.343321 0.253735 +0.346153 0.253344 +0.345940 0.254472 +0.337738 0.240933 +0.338921 0.240933 +0.358079 0.240933 +0.359262 0.240933 +0.357919 0.239227 +0.359082 0.239016 +0.357406 0.237482 +0.358506 0.237056 +0.356517 0.235803 +0.357507 0.235170 +0.355273 0.234304 +0.356110 0.233485 +0.353742 0.233086 +0.354389 0.232117 +0.352026 0.232216 +0.352461 0.231140 +0.350243 0.231715 +0.350458 0.230577 +0.348500 0.231558 +0.348500 0.230401 +0.346757 0.231715 +0.346542 0.230577 +0.344974 0.232216 +0.344539 0.231140 +0.343258 0.233086 +0.342611 0.232117 +0.341727 0.234304 +0.340890 0.233485 +0.340483 0.235803 +0.339493 0.235170 +0.339594 0.237482 +0.338494 0.237056 +0.339081 0.239227 +0.337918 0.239016 +0.337548 0.238949 +0.339105 0.240933 +0.337362 0.240933 +0.339262 0.239260 +0.359452 0.238949 +0.359638 0.240933 +0.357895 0.240933 +0.357738 0.239260 +0.358856 0.236920 +0.357235 0.237548 +0.357822 0.234968 +0.356363 0.235902 +0.356376 0.233225 +0.355143 0.234431 +0.354595 0.231809 +0.353641 0.233237 +0.352600 0.230798 +0.351958 0.232384 +0.350527 0.230214 +0.350209 0.231892 +0.348500 0.230032 +0.348500 0.231738 +0.346473 0.230214 +0.346790 0.231892 +0.344400 0.230798 +0.345042 0.232384 +0.342405 0.231809 +0.343359 0.233237 +0.340624 0.233225 +0.341857 0.234431 +0.339177 0.234968 +0.340637 0.235902 +0.338144 0.236920 +0.339765 0.237548 +0.359452 0.183873 +0.359638 0.185857 +0.339292 0.184189 +0.339136 0.185857 +0.337362 0.185857 +0.339793 0.182483 +0.337548 0.183873 +0.340662 0.180842 +0.338144 0.181844 +0.341879 0.179377 +0.339177 0.179892 +0.343376 0.178186 +0.340624 0.178149 +0.345053 0.177336 +0.342405 0.176733 +0.346796 0.176845 +0.344400 0.175722 +0.346473 0.175138 +0.348500 0.176692 +0.350204 0.176845 +0.348500 0.174956 +0.351947 0.177336 +0.350527 0.175138 +0.353624 0.178186 +0.352600 0.175722 +0.354595 0.176733 +0.355121 0.179377 +0.356376 0.178149 +0.356338 0.180842 +0.357206 0.182483 +0.357822 0.179892 +0.357708 0.184189 +0.358856 0.181844 +0.357864 0.185857 +0.312155 0.213395 +0.309198 0.213395 +0.231869 0.213395 +0.228912 0.213395 +0.232514 0.206509 +0.234583 0.199466 +0.229607 0.205983 +0.231834 0.198401 +0.238171 0.192688 +0.235696 0.191105 +0.243193 0.186638 +0.249376 0.181723 +0.241102 0.184592 +0.247758 0.179301 +0.256301 0.178212 +0.255213 0.175521 +0.263498 0.176187 +0.262960 0.173341 +0.270533 0.175555 +0.270533 0.172661 +0.277569 0.176187 +0.278107 0.173341 +0.284765 0.178212 +0.285854 0.175521 +0.291691 0.181723 +0.293309 0.179301 +0.297873 0.186638 +0.299964 0.184592 +0.302895 0.192688 +0.305370 0.191105 +0.306483 0.199466 +0.309232 0.198401 +0.308552 0.206509 +0.311460 0.205983 +0.605263 0.213395 +0.602306 0.213395 +0.524977 0.213395 +0.522020 0.213395 +0.525622 0.206509 +0.527692 0.199466 +0.522715 0.205983 +0.524942 0.198401 +0.531279 0.192689 +0.528804 0.191105 +0.536301 0.186638 +0.534211 0.184592 +0.542484 0.181723 +0.540866 0.179301 +0.549409 0.178212 +0.548321 0.175521 +0.556606 0.176187 +0.556068 0.173341 +0.563641 0.175555 +0.563641 0.172661 +0.570677 0.176187 +0.571215 0.173341 +0.577874 0.178212 +0.578962 0.175521 +0.584799 0.181723 +0.586417 0.179301 +0.590981 0.186638 +0.593072 0.184592 +0.596003 0.192689 +0.598478 0.191105 +0.599591 0.199466 +0.602340 0.198401 +0.601660 0.206509 +0.604568 0.205983 +0.751817 0.213395 +0.748860 0.213395 +0.671531 0.213395 +0.668574 0.213395 +0.672176 0.206509 +0.674246 0.199466 +0.669269 0.205983 +0.671496 0.198401 +0.677833 0.192689 +0.675359 0.191105 +0.682856 0.186638 +0.680765 0.184592 +0.689038 0.181723 +0.687420 0.179301 +0.695963 0.178212 +0.694875 0.175521 +0.703160 0.176187 +0.702622 0.173341 +0.710195 0.175555 +0.710195 0.172661 +0.717231 0.176187 +0.717769 0.173341 +0.724428 0.178212 +0.725516 0.175521 +0.731353 0.181723 +0.732971 0.179301 +0.737535 0.186638 +0.739626 0.184592 +0.742557 0.192689 +0.745032 0.191105 +0.746145 0.199466 +0.748895 0.198401 +0.748214 0.206509 +0.751122 0.205983 +0.334431 0.240933 +0.334431 0.240933 +0.362334 0.243438 +0.362569 0.240933 +0.362569 0.240933 +0.362334 0.243438 +0.361581 0.246001 +0.360276 0.248467 +0.361581 0.246001 +0.358448 0.250669 +0.360276 0.248467 +0.358448 0.250669 +0.356199 0.252457 +0.353679 0.253735 +0.356199 0.252457 +0.351060 0.254472 +0.353679 0.253735 +0.351060 0.254472 +0.348500 0.254702 +0.348500 0.254702 +0.345940 0.254472 +0.345940 0.254472 +0.343321 0.253735 +0.343321 0.253735 +0.340801 0.252457 +0.340801 0.252457 +0.338552 0.250669 +0.338552 0.250669 +0.336724 0.248467 +0.336724 0.248467 +0.335419 0.246001 +0.335419 0.246001 +0.334666 0.243438 +0.334666 0.243438 +0.542539 0.171917 +0.542674 0.172577 +0.542674 0.172577 +0.542659 0.172353 +0.542668 0.172446 +0.542614 0.172131 +0.542438 0.171716 +0.542438 0.171716 +0.542500 0.171831 +0.542614 0.172131 +0.541794 0.252722 +0.541794 0.252722 +0.542674 0.254213 +0.542674 0.254213 +0.542659 0.253995 +0.542616 0.253775 +0.542657 0.253980 +0.542542 0.253559 +0.542580 0.253659 +0.542438 0.253352 +0.542307 0.253161 +0.542438 0.253352 +0.542153 0.252990 +0.542238 0.253079 +0.541980 0.252843 +0.541992 0.252853 +0.844996 0.216235 +0.845061 0.216298 +0.844401 0.217823 +0.844401 0.217857 +0.844309 0.217857 +0.844309 0.217821 +0.844450 0.217398 +0.844360 0.217379 +0.844572 0.217013 +0.844487 0.216979 +0.844764 0.216657 +0.844687 0.216608 +0.845036 0.216323 +0.844970 0.216260 +0.136156 0.218701 +0.136328 0.217857 +0.136420 0.217857 +0.136289 0.218265 +0.132417 0.219480 +0.132482 0.219416 +0.132752 0.219752 +0.132805 0.219678 +0.133177 0.219977 +0.133213 0.219894 +0.133640 0.220112 +0.134112 0.220152 +0.133657 0.220024 +0.134563 0.220102 +0.134110 0.220061 +0.134972 0.219977 +0.134544 0.220013 +0.135351 0.219782 +0.134937 0.219894 +0.135301 0.219706 +0.135707 0.219505 +0.136011 0.219151 +0.135642 0.219440 +0.136241 0.218735 +0.135935 0.219100 +0.136379 0.218282 +0.160714 0.199267 +0.164574 0.208697 +0.165014 0.213395 +0.165731 0.213395 +0.165278 0.208569 +0.163162 0.203892 +0.111538 0.213395 +0.112255 0.213395 +0.111991 0.208569 +0.112695 0.208697 +0.113441 0.203633 +0.114107 0.203892 +0.115955 0.198884 +0.116555 0.199267 +0.119475 0.194644 +0.119981 0.195139 +0.123807 0.191199 +0.124199 0.191786 +0.128660 0.188738 +0.128924 0.189390 +0.133704 0.187319 +0.133834 0.188009 +0.138635 0.186877 +0.138635 0.187578 +0.143565 0.187319 +0.143435 0.188009 +0.148608 0.188738 +0.153462 0.191199 +0.148345 0.189390 +0.153070 0.191786 +0.157794 0.194644 +0.157288 0.195139 +0.161314 0.198884 +0.163828 0.203633 +0.059349 0.213395 +0.059349 0.213395 +0.071366 0.213395 +0.071366 0.213395 +0.071266 0.212325 +0.071266 0.212325 +0.070944 0.211230 +0.070944 0.211230 +0.070387 0.210177 +0.070387 0.210177 +0.069606 0.209236 +0.069606 0.209236 +0.068645 0.208473 +0.068645 0.208473 +0.067569 0.207927 +0.067569 0.207927 +0.066451 0.207612 +0.066451 0.207612 +0.065357 0.207514 +0.065357 0.207514 +0.064264 0.207612 +0.064264 0.207612 +0.063146 0.207927 +0.063146 0.207927 +0.062069 0.208473 +0.062069 0.208473 +0.061109 0.209236 +0.061109 0.209236 +0.060328 0.210177 +0.060328 0.210177 +0.059771 0.211230 +0.059771 0.211230 +0.059449 0.212325 +0.059449 0.212325 +0.059349 0.213395 +0.065357 0.213395 +0.071366 0.213395 +0.071266 0.212325 +0.070944 0.211230 +0.070387 0.210177 +0.069606 0.209236 +0.068645 0.208473 +0.067569 0.207927 +0.066451 0.207612 +0.065357 0.207514 +0.064264 0.207612 +0.063146 0.207927 +0.062069 0.208473 +0.061109 0.209236 +0.060328 0.210177 +0.059771 0.211230 +0.059449 0.212325 +0.065357 0.213395 +0.065357 0.213395 +0.065357 0.213395 +0.065357 0.213395 +0.065357 0.213395 +0.065357 0.213395 +0.065357 0.213395 +0.065357 0.213395 +0.065357 0.213395 +0.065357 0.213395 +0.065357 0.213395 +0.065357 0.213395 +0.065357 0.213395 +0.065357 0.213395 +0.065357 0.213395 +0.065357 0.213395 +0.814998 0.213395 +0.815714 0.213395 +0.868474 0.213395 +0.869190 0.213395 +0.868033 0.208697 +0.866622 0.203892 +0.868738 0.208569 +0.867288 0.203634 +0.864174 0.199268 +0.864774 0.198884 +0.860747 0.195140 +0.856529 0.191786 +0.861254 0.194644 +0.856921 0.191199 +0.851804 0.189391 +0.852068 0.188739 +0.846894 0.188009 +0.847025 0.187319 +0.842094 0.187578 +0.842094 0.186877 +0.837294 0.188009 +0.837164 0.187319 +0.832384 0.189391 +0.827659 0.191786 +0.832120 0.188739 +0.827267 0.191199 +0.823441 0.195139 +0.822934 0.194644 +0.820014 0.199268 +0.819415 0.198884 +0.817567 0.203892 +0.816900 0.203634 +0.816155 0.208697 +0.815450 0.208569 +0.811025 0.213395 +0.810846 0.213395 +0.839570 0.243877 +0.839749 0.243715 +0.834540 0.243069 +0.834583 0.242899 +0.828608 0.240982 +0.828685 0.240824 +0.823427 0.237920 +0.819179 0.234187 +0.823534 0.237780 +0.815696 0.229759 +0.819310 0.234068 +0.812968 0.224472 +0.815847 0.229665 +0.813134 0.224408 +0.811289 0.218526 +0.811465 0.218496 +0.909362 0.213395 +0.909362 0.213395 +0.921380 0.213395 +0.921380 0.213395 +0.921280 0.212325 +0.921280 0.212325 +0.920958 0.211230 +0.920958 0.211230 +0.920400 0.210177 +0.920400 0.210177 +0.919620 0.209237 +0.919620 0.209237 +0.918659 0.208473 +0.918659 0.208473 +0.917583 0.207927 +0.917583 0.207927 +0.916465 0.207612 +0.916465 0.207612 +0.915371 0.207514 +0.915371 0.207514 +0.914278 0.207612 +0.914278 0.207612 +0.913159 0.207927 +0.913159 0.207927 +0.912083 0.208473 +0.912083 0.208473 +0.911122 0.209237 +0.911122 0.209237 +0.910342 0.210177 +0.910342 0.210177 +0.909784 0.211230 +0.909784 0.211230 +0.909463 0.212325 +0.909463 0.212325 +0.909362 0.213395 +0.915371 0.213395 +0.921380 0.213395 +0.921280 0.212325 +0.920958 0.211230 +0.920400 0.210177 +0.919620 0.209237 +0.918659 0.208473 +0.917583 0.207927 +0.916465 0.207612 +0.915371 0.207514 +0.914278 0.207612 +0.913159 0.207927 +0.912083 0.208473 +0.911122 0.209237 +0.910342 0.210177 +0.909784 0.211230 +0.909463 0.212325 +0.915371 0.213395 +0.915371 0.213395 +0.915371 0.213395 +0.915371 0.213395 +0.915371 0.213395 +0.915371 0.213395 +0.915371 0.213395 +0.915371 0.213395 +0.915371 0.213395 +0.915371 0.213395 +0.915371 0.213395 +0.915371 0.213395 +0.915371 0.213395 +0.915371 0.213395 +0.915371 0.213395 +0.915371 0.213395 +0.301152 0.166768 +0.301152 0.166768 +0.300471 0.165408 +0.300273 0.165277 +0.300273 0.165277 +0.300471 0.165408 +0.300717 0.165634 +0.300717 0.165634 +0.300917 0.165907 +0.300917 0.165907 +0.301059 0.166214 +0.301059 0.166214 +0.301136 0.166535 +0.301136 0.166535 +0.301152 0.260021 +0.301152 0.260021 +0.300917 0.259161 +0.300917 0.259161 +0.300979 0.259276 +0.300979 0.259276 +0.301093 0.259576 +0.301093 0.259576 +0.301147 0.259891 +0.301147 0.259891 +0.689228 0.172577 +0.689228 0.172577 +0.688992 0.171716 +0.688992 0.171716 +0.689054 0.171831 +0.689168 0.172131 +0.689093 0.171917 +0.689168 0.172131 +0.689223 0.172446 +0.689213 0.172353 +0.688348 0.252722 +0.688348 0.252722 +0.689228 0.254213 +0.689228 0.254213 +0.689213 0.253995 +0.689170 0.253775 +0.689209 0.253962 +0.689096 0.253559 +0.689127 0.253638 +0.688992 0.253352 +0.688861 0.253161 +0.688992 0.253352 +0.688707 0.252990 +0.688807 0.253096 +0.688534 0.252843 +0.688561 0.252864 +0.655091 0.213395 +0.655091 0.213395 +0.659781 0.213395 +0.659781 0.213395 +0.659742 0.212977 +0.659742 0.212977 +0.659616 0.212550 +0.659399 0.212139 +0.659616 0.212550 +0.659399 0.212139 +0.659094 0.211772 +0.659094 0.211772 +0.658719 0.211474 +0.658719 0.211474 +0.658299 0.211261 +0.658299 0.211261 +0.657863 0.211138 +0.657863 0.211138 +0.657436 0.211100 +0.657436 0.211100 +0.657009 0.211138 +0.657009 0.211138 +0.656573 0.211261 +0.656573 0.211261 +0.656153 0.211474 +0.656153 0.211474 +0.655778 0.211772 +0.655778 0.211772 +0.655473 0.212139 +0.655473 0.212139 +0.655256 0.212550 +0.655256 0.212550 +0.655130 0.212977 +0.655130 0.212977 +0.757956 0.173970 +0.759398 0.175686 +0.759438 0.176104 +0.759438 0.176104 +0.759273 0.175259 +0.759398 0.175686 +0.759055 0.174848 +0.759273 0.175259 +0.759055 0.174848 +0.758751 0.174481 +0.758376 0.174183 +0.758751 0.174481 +0.758376 0.174183 +0.757956 0.173970 +0.754748 0.176104 +0.754748 0.176104 +0.754787 0.175686 +0.754787 0.175686 +0.754912 0.175259 +0.754912 0.175259 +0.755130 0.174848 +0.755130 0.174848 +0.755435 0.174481 +0.755435 0.174481 +0.755810 0.174183 +0.755810 0.174183 +0.756230 0.173970 +0.756230 0.173970 +0.756666 0.173847 +0.756666 0.173847 +0.757093 0.173809 +0.757093 0.173809 +0.757519 0.173847 +0.757519 0.173847 +0.759273 0.249841 +0.759438 0.250686 +0.759438 0.250686 +0.759398 0.250268 +0.759273 0.249841 +0.759398 0.250268 +0.754787 0.250268 +0.754748 0.250686 +0.754748 0.250686 +0.754787 0.250268 +0.754912 0.249841 +0.754912 0.249841 +0.755130 0.249430 +0.755130 0.249430 +0.755435 0.249063 +0.755435 0.249063 +0.755810 0.248765 +0.755810 0.248765 +0.756230 0.248552 +0.756230 0.248552 +0.756666 0.248429 +0.756666 0.248429 +0.757093 0.248391 +0.757093 0.248391 +0.757519 0.248429 +0.757519 0.248429 +0.757956 0.248552 +0.757956 0.248552 +0.758376 0.248765 +0.758376 0.248765 +0.758751 0.249063 +0.758751 0.249063 +0.759055 0.249430 +0.759055 0.249430 +0.514399 0.176104 +0.514399 0.176104 +0.519050 0.175686 +0.519089 0.176104 +0.519089 0.176104 +0.519050 0.175686 +0.518924 0.175259 +0.518924 0.175259 +0.518707 0.174848 +0.518707 0.174848 +0.518402 0.174481 +0.518402 0.174481 +0.518027 0.174183 +0.518027 0.174183 +0.517607 0.173970 +0.517607 0.173970 +0.517171 0.173847 +0.517171 0.173847 +0.516744 0.173809 +0.516744 0.173809 +0.516317 0.173847 +0.516317 0.173847 +0.515881 0.173970 +0.515881 0.173970 +0.515461 0.174183 +0.515461 0.174183 +0.515086 0.174481 +0.515086 0.174481 +0.514781 0.174848 +0.514781 0.174848 +0.514564 0.175259 +0.514564 0.175259 +0.514438 0.175686 +0.514438 0.175686 +0.518924 0.249841 +0.519050 0.250268 +0.519089 0.250686 +0.519089 0.250686 +0.518924 0.249841 +0.519050 0.250268 +0.514399 0.250686 +0.514399 0.250686 +0.514438 0.250268 +0.514438 0.250268 +0.514564 0.249841 +0.514781 0.249430 +0.514564 0.249841 +0.515086 0.249063 +0.514781 0.249430 +0.515086 0.249063 +0.515461 0.248765 +0.515881 0.248552 +0.515461 0.248765 +0.515881 0.248552 +0.516317 0.248429 +0.516317 0.248429 +0.516744 0.248391 +0.516744 0.248391 +0.517171 0.248429 +0.517171 0.248429 +0.517607 0.248552 +0.517607 0.248552 +0.518027 0.248765 +0.518027 0.248765 +0.518402 0.249063 +0.518402 0.249063 +0.518707 0.249430 +0.518707 0.249430 +0.393013 0.175686 +0.393013 0.175686 +0.393052 0.176104 +0.393052 0.176104 +0.388402 0.175686 +0.388363 0.176104 +0.388363 0.176104 +0.388402 0.175686 +0.388527 0.175259 +0.388527 0.175259 +0.388745 0.174848 +0.388745 0.174848 +0.389049 0.174481 +0.389049 0.174481 +0.389424 0.174183 +0.389844 0.173970 +0.389424 0.174183 +0.389844 0.173970 +0.390281 0.173847 +0.390281 0.173847 +0.390707 0.173809 +0.390707 0.173809 +0.391134 0.173847 +0.391134 0.173847 +0.391571 0.173970 +0.391571 0.173970 +0.391991 0.174183 +0.391991 0.174183 +0.392366 0.174481 +0.392670 0.174848 +0.392366 0.174481 +0.392670 0.174848 +0.392888 0.175259 +0.392888 0.175259 +0.392888 0.249841 +0.393052 0.250686 +0.393052 0.250686 +0.393013 0.250268 +0.388363 0.250686 +0.388363 0.250686 +0.388402 0.250268 +0.388402 0.250268 +0.388527 0.249841 +0.388527 0.249841 +0.388745 0.249430 +0.388745 0.249430 +0.389049 0.249063 +0.389049 0.249063 +0.389424 0.248765 +0.389424 0.248765 +0.389844 0.248552 +0.389844 0.248552 +0.390281 0.248429 +0.390281 0.248429 +0.390707 0.248391 +0.390707 0.248391 +0.391134 0.248429 +0.391134 0.248429 +0.391571 0.248552 +0.391571 0.248552 +0.391991 0.248765 +0.391991 0.248765 +0.392366 0.249063 +0.392366 0.249063 +0.392670 0.249430 +0.392670 0.249430 +0.392888 0.249841 +0.393013 0.250268 +0.224919 0.174183 +0.225942 0.175686 +0.225981 0.176104 +0.225981 0.176104 +0.225816 0.175259 +0.225942 0.175686 +0.225816 0.175259 +0.225598 0.174848 +0.225294 0.174481 +0.225598 0.174848 +0.225294 0.174481 +0.224919 0.174183 +0.221291 0.176104 +0.221291 0.176104 +0.221330 0.175686 +0.221330 0.175686 +0.221456 0.175259 +0.221456 0.175259 +0.221673 0.174848 +0.221978 0.174481 +0.221673 0.174848 +0.222353 0.174183 +0.221978 0.174481 +0.222353 0.174183 +0.222773 0.173970 +0.222773 0.173970 +0.223209 0.173847 +0.223209 0.173847 +0.223636 0.173809 +0.223636 0.173809 +0.224062 0.173847 +0.224062 0.173847 +0.224499 0.173970 +0.224499 0.173970 +0.225816 0.249841 +0.225981 0.250686 +0.225981 0.250686 +0.225942 0.250268 +0.225816 0.249841 +0.225942 0.250268 +0.221291 0.250686 +0.221291 0.250686 +0.221330 0.250268 +0.221330 0.250268 +0.221456 0.249841 +0.221456 0.249841 +0.221673 0.249430 +0.221673 0.249430 +0.221978 0.249063 +0.221978 0.249063 +0.222353 0.248765 +0.222773 0.248552 +0.222353 0.248765 +0.222773 0.248552 +0.223209 0.248429 +0.223209 0.248429 +0.223636 0.248391 +0.223636 0.248391 +0.224062 0.248429 +0.224062 0.248429 +0.224499 0.248552 +0.224499 0.248552 +0.224919 0.248765 +0.224919 0.248765 +0.225294 0.249063 +0.225294 0.249063 +0.225598 0.249430 +0.225598 0.249430 +0.651574 0.213395 +0.651574 0.213395 +0.663200 0.214439 +0.663298 0.213395 +0.663298 0.213395 +0.663200 0.214439 +0.662887 0.215507 +0.662887 0.215507 +0.662343 0.216534 +0.662343 0.216534 +0.661581 0.217451 +0.661581 0.217451 +0.660644 0.218197 +0.660644 0.218197 +0.659594 0.218729 +0.659594 0.218729 +0.658503 0.219036 +0.658503 0.219036 +0.657436 0.219132 +0.657436 0.219132 +0.656369 0.219036 +0.656369 0.219036 +0.655278 0.218729 +0.655278 0.218729 +0.654228 0.218197 +0.654228 0.218197 +0.653291 0.217451 +0.653291 0.217451 +0.652529 0.216534 +0.652529 0.216534 +0.651985 0.215507 +0.651985 0.215507 +0.651672 0.214439 +0.651672 0.214439 +0.751328 0.177148 +0.751328 0.177148 +0.751231 0.176104 +0.751231 0.176104 +0.762955 0.176104 +0.762955 0.176104 +0.762857 0.177148 +0.762857 0.177148 +0.762543 0.178216 +0.762543 0.178216 +0.761999 0.179243 +0.761999 0.179243 +0.761238 0.180160 +0.761238 0.180160 +0.760301 0.180906 +0.759251 0.181438 +0.760301 0.180906 +0.759251 0.181438 +0.758159 0.181745 +0.757093 0.181841 +0.758159 0.181745 +0.757093 0.181841 +0.756026 0.181745 +0.756026 0.181745 +0.754935 0.181438 +0.754935 0.181438 +0.753885 0.180906 +0.753885 0.180906 +0.752948 0.180160 +0.752948 0.180160 +0.752186 0.179243 +0.752186 0.179243 +0.751642 0.178215 +0.751642 0.178215 +0.522606 0.176104 +0.522606 0.176104 +0.510980 0.177148 +0.510882 0.176104 +0.510882 0.176104 +0.510980 0.177148 +0.511293 0.178215 +0.511293 0.178215 +0.511837 0.179243 +0.511837 0.179243 +0.512599 0.180160 +0.512599 0.180160 +0.513536 0.180906 +0.514586 0.181438 +0.513536 0.180906 +0.514586 0.181438 +0.515677 0.181745 +0.515677 0.181745 +0.516744 0.181841 +0.516744 0.181841 +0.517811 0.181745 +0.517811 0.181745 +0.518902 0.181438 +0.518902 0.181438 +0.519952 0.180906 +0.519952 0.180906 +0.520889 0.180160 +0.520889 0.180160 +0.521651 0.179243 +0.521651 0.179243 +0.522195 0.178215 +0.522195 0.178215 +0.522508 0.177148 +0.522508 0.177148 +0.522508 0.251730 +0.522508 0.251730 +0.522606 0.250686 +0.522606 0.250686 +0.510882 0.250686 +0.510882 0.250686 +0.510980 0.251730 +0.510980 0.251730 +0.511293 0.252798 +0.511293 0.252798 +0.511837 0.253825 +0.511837 0.253825 +0.512599 0.254743 +0.512599 0.254743 +0.513536 0.255488 +0.514586 0.256020 +0.513536 0.255488 +0.515677 0.256327 +0.514586 0.256020 +0.515677 0.256327 +0.516744 0.256423 +0.516744 0.256423 +0.517811 0.256327 +0.518902 0.256020 +0.517811 0.256327 +0.518902 0.256020 +0.519952 0.255488 +0.519952 0.255488 +0.520889 0.254743 +0.520889 0.254743 +0.521651 0.253825 +0.521651 0.253825 +0.522195 0.252798 +0.522195 0.252798 +0.762955 0.250686 +0.762955 0.250686 +0.751328 0.251730 +0.751231 0.250686 +0.751231 0.250686 +0.751328 0.251730 +0.751642 0.252798 +0.751642 0.252798 +0.752186 0.253825 +0.752948 0.254743 +0.752186 0.253825 +0.752948 0.254743 +0.753885 0.255488 +0.753885 0.255488 +0.754935 0.256020 +0.756026 0.256327 +0.754935 0.256020 +0.757093 0.256423 +0.756026 0.256327 +0.757093 0.256423 +0.758159 0.256327 +0.758159 0.256327 +0.759251 0.256020 +0.759251 0.256020 +0.760301 0.255488 +0.761238 0.254743 +0.760301 0.255488 +0.761238 0.254743 +0.761999 0.253825 +0.761999 0.253825 +0.762543 0.252798 +0.762543 0.252798 +0.762857 0.251730 +0.762857 0.251730 +0.384943 0.177148 +0.384943 0.177148 +0.384845 0.176104 +0.384845 0.176104 +0.396570 0.176104 +0.396570 0.176104 +0.396472 0.177148 +0.396472 0.177148 +0.396158 0.178215 +0.396158 0.178215 +0.395614 0.179243 +0.395614 0.179243 +0.394853 0.180160 +0.394853 0.180160 +0.393915 0.180906 +0.392865 0.181438 +0.393915 0.180906 +0.392865 0.181438 +0.391774 0.181745 +0.391774 0.181745 +0.390707 0.181841 +0.390707 0.181841 +0.389641 0.181745 +0.389641 0.181745 +0.388550 0.181438 +0.387500 0.180906 +0.388550 0.181438 +0.387500 0.180906 +0.386562 0.180160 +0.386562 0.180160 +0.385801 0.179243 +0.385801 0.179243 +0.385257 0.178215 +0.385257 0.178215 +0.217871 0.177148 +0.217774 0.176104 +0.217774 0.176104 +0.217871 0.177148 +0.229498 0.176104 +0.229498 0.176104 +0.229400 0.177148 +0.229400 0.177148 +0.229086 0.178215 +0.229086 0.178215 +0.228542 0.179243 +0.228542 0.179243 +0.227781 0.180160 +0.227781 0.180160 +0.226844 0.180905 +0.226844 0.180905 +0.225794 0.181438 +0.225794 0.181438 +0.224702 0.181745 +0.224702 0.181745 +0.223636 0.181841 +0.223636 0.181841 +0.222569 0.181745 +0.221478 0.181438 +0.222569 0.181745 +0.221478 0.181438 +0.220428 0.180905 +0.220428 0.180905 +0.219491 0.180160 +0.219491 0.180160 +0.218729 0.179243 +0.218729 0.179243 +0.218185 0.178215 +0.218185 0.178215 +0.217774 0.250686 +0.217774 0.250686 +0.229400 0.251730 +0.229498 0.250686 +0.229498 0.250686 +0.229400 0.251730 +0.229086 0.252798 +0.229086 0.252798 +0.228542 0.253825 +0.228542 0.253825 +0.227781 0.254743 +0.227781 0.254743 +0.226844 0.255488 +0.226844 0.255488 +0.225794 0.256020 +0.225794 0.256020 +0.224702 0.256327 +0.224702 0.256327 +0.223636 0.256423 +0.223636 0.256423 +0.222569 0.256327 +0.222569 0.256327 +0.221478 0.256020 +0.221478 0.256020 +0.220428 0.255488 +0.220428 0.255488 +0.219491 0.254743 +0.219491 0.254743 +0.218729 0.253825 +0.218729 0.253825 +0.218185 0.252798 +0.218185 0.252798 +0.217871 0.251730 +0.217871 0.251730 +0.396570 0.250686 +0.396570 0.250686 +0.384943 0.251730 +0.384845 0.250686 +0.384845 0.250686 +0.384943 0.251730 +0.385257 0.252798 +0.385257 0.252798 +0.385801 0.253825 +0.385801 0.253825 +0.386562 0.254743 +0.386562 0.254743 +0.387500 0.255488 +0.387500 0.255488 +0.388550 0.256020 +0.388550 0.256020 +0.389641 0.256327 +0.389641 0.256327 +0.390707 0.256423 +0.390707 0.256423 +0.391774 0.256327 +0.392865 0.256020 +0.391774 0.256327 +0.392865 0.256020 +0.393915 0.255488 +0.393915 0.255488 +0.394853 0.254743 +0.394853 0.254743 +0.395614 0.253825 +0.395614 0.253825 +0.396158 0.252798 +0.396158 0.252798 +0.396472 0.251730 +0.396472 0.251730 +0.333551 0.185857 +0.333551 0.185857 +0.363448 0.185857 +0.363448 0.185857 +0.363199 0.183195 +0.363199 0.183195 +0.362399 0.180472 +0.362399 0.180472 +0.361012 0.177851 +0.359070 0.175512 +0.361012 0.177851 +0.359070 0.175512 +0.356680 0.173612 +0.356680 0.173612 +0.354002 0.172254 +0.354002 0.172254 +0.351220 0.171471 +0.351220 0.171471 +0.348500 0.171227 +0.348500 0.171227 +0.345780 0.171471 +0.345780 0.171471 +0.342997 0.172254 +0.342997 0.172254 +0.340320 0.173612 +0.340320 0.173612 +0.337930 0.175512 +0.337930 0.175512 +0.335988 0.177851 +0.335988 0.177851 +0.334601 0.180472 +0.334601 0.180472 +0.333801 0.183195 +0.333801 0.183195 +0.358079 0.240933 +0.357895 0.240933 +0.339105 0.240933 +0.338921 0.240933 +0.339262 0.242606 +0.339081 0.242639 +0.339765 0.244317 +0.339594 0.244383 +0.340637 0.245964 +0.340483 0.246062 +0.341857 0.247434 +0.341727 0.247561 +0.343359 0.248628 +0.343258 0.248779 +0.345042 0.249481 +0.344974 0.249649 +0.346790 0.249973 +0.346757 0.250151 +0.348500 0.250127 +0.348500 0.250307 +0.350209 0.249973 +0.350243 0.250151 +0.351958 0.249481 +0.352026 0.249649 +0.353641 0.248628 +0.353742 0.248779 +0.355143 0.247434 +0.355273 0.247561 +0.356363 0.245964 +0.356517 0.246062 +0.357235 0.244317 +0.357406 0.244383 +0.357738 0.242606 +0.357919 0.242639 +0.226274 0.213395 +0.226274 0.213395 +0.314793 0.213395 +0.314793 0.213395 +0.314054 0.205513 +0.314054 0.205513 +0.311685 0.197451 +0.311685 0.197451 +0.307578 0.189692 +0.307578 0.189692 +0.301829 0.182766 +0.301829 0.182766 +0.294752 0.177140 +0.294752 0.177140 +0.286825 0.173121 +0.286825 0.173121 +0.278587 0.170803 +0.278587 0.170803 +0.270533 0.170080 +0.270533 0.170080 +0.262480 0.170803 +0.262480 0.170803 +0.254242 0.173121 +0.254242 0.173121 +0.246314 0.177140 +0.246314 0.177140 +0.239237 0.182766 +0.239237 0.182766 +0.233488 0.189692 +0.233488 0.189692 +0.229381 0.197451 +0.229381 0.197451 +0.227013 0.205513 +0.227013 0.205513 +0.519382 0.213395 +0.519382 0.213395 +0.607901 0.213395 +0.607901 0.213395 +0.607162 0.205513 +0.607162 0.205513 +0.604793 0.197451 +0.604793 0.197451 +0.600686 0.189692 +0.600686 0.189692 +0.594937 0.182766 +0.594937 0.182766 +0.587860 0.177140 +0.587860 0.177140 +0.579933 0.173121 +0.579933 0.173121 +0.571695 0.170803 +0.571695 0.170803 +0.563641 0.170080 +0.563641 0.170080 +0.555588 0.170803 +0.555588 0.170803 +0.547350 0.173121 +0.547350 0.173121 +0.539422 0.177140 +0.539422 0.177140 +0.532345 0.182766 +0.532345 0.182766 +0.526596 0.189692 +0.526596 0.189692 +0.522489 0.197451 +0.522489 0.197451 +0.520121 0.205513 +0.520121 0.205513 +0.665936 0.213395 +0.665936 0.213395 +0.754455 0.213395 +0.754455 0.213395 +0.753716 0.205513 +0.753716 0.205513 +0.751347 0.197451 +0.751347 0.197451 +0.747240 0.189692 +0.747240 0.189692 +0.741491 0.182766 +0.741491 0.182766 +0.734415 0.177140 +0.734415 0.177140 +0.726487 0.173121 +0.726487 0.173121 +0.718249 0.170803 +0.718249 0.170803 +0.710195 0.170080 +0.710195 0.170080 +0.702142 0.170803 +0.702142 0.170803 +0.693904 0.173121 +0.693904 0.173121 +0.685976 0.177140 +0.685976 0.177140 +0.678899 0.182766 +0.678899 0.182766 +0.673151 0.189692 +0.673151 0.189692 +0.669044 0.197451 +0.669044 0.197451 +0.666675 0.205513 +0.666675 0.205513 +0.080457 0.138236 +0.094668 0.136960 +0.034034 0.165218 +0.029298 0.171569 +0.022051 0.185260 +0.017871 0.199486 +0.039443 0.159347 +0.045441 0.154055 +0.051931 0.149419 +0.065920 0.142327 +0.016998 0.213395 +0.016568 0.213395 +0.017545 0.213395 +0.018064 0.213395 +0.018527 0.213395 +0.018908 0.213395 +0.019142 0.213395 +0.020403 0.199945 +0.024445 0.186187 +0.031453 0.172948 +0.036033 0.166806 +0.041263 0.161129 +0.047064 0.156010 +0.053339 0.151528 +0.066867 0.144669 +0.080925 0.140713 +0.094668 0.139251 +0.094668 0.139480 +0.094668 0.138878 +0.094668 0.138425 +0.094668 0.137916 +0.094668 0.137381 +0.030698 0.170342 +0.039771 0.159669 +0.023418 0.183217 +0.018679 0.197826 +0.050677 0.150790 +0.063833 0.143665 +0.078760 0.139027 +0.019217 0.197936 +0.019690 0.198033 +0.020114 0.198120 +0.020495 0.198198 +0.025121 0.183938 +0.032227 0.171371 +0.041083 0.160953 +0.051728 0.152286 +0.064570 0.145331 +0.079140 0.140804 +0.079060 0.140431 +0.078971 0.140016 +0.078872 0.139553 +0.064415 0.144982 +0.064243 0.144592 +0.064051 0.144158 +0.051508 0.151972 +0.051262 0.151622 +0.040808 0.160683 +0.040501 0.160383 +0.050988 0.151232 +0.040159 0.160049 +0.031906 0.171155 +0.031549 0.170914 +0.024764 0.183787 +0.024366 0.183619 +0.031151 0.170646 +0.023922 0.183431 +0.082518 0.149136 +0.094668 0.148045 +0.042828 0.172205 +0.038778 0.177634 +0.032582 0.189340 +0.029008 0.201503 +0.028163 0.213395 +0.027893 0.213395 +0.047451 0.167185 +0.052580 0.162660 +0.058128 0.158697 +0.070089 0.152633 +0.028694 0.213395 +0.029192 0.213395 +0.029421 0.213395 +0.030511 0.201775 +0.034002 0.189890 +0.040057 0.178453 +0.044014 0.173147 +0.048532 0.168242 +0.053543 0.163821 +0.058964 0.159948 +0.070651 0.154023 +0.082796 0.150606 +0.094668 0.149315 +0.094668 0.149540 +0.094668 0.148828 +0.094668 0.148308 +0.039878 0.176520 +0.047649 0.167379 +0.033643 0.187548 +0.029584 0.200060 +0.056990 0.159774 +0.068258 0.153671 +0.081043 0.149699 +0.030094 0.200164 +0.030573 0.200262 +0.034570 0.187940 +0.040710 0.177080 +0.048363 0.168078 +0.057562 0.160588 +0.068659 0.154578 +0.081250 0.150667 +0.081149 0.150198 +0.068465 0.154139 +0.057285 0.160194 +0.048017 0.167739 +0.040307 0.176809 +0.034121 0.187750 +0.085228 0.263320 +0.094668 0.264168 +0.054391 0.245397 +0.051245 0.241178 +0.046431 0.232084 +0.043654 0.222633 +0.057983 0.249297 +0.061968 0.252813 +0.066279 0.255892 +0.075571 0.260603 +0.039974 0.213395 +0.042788 0.213395 +0.035785 0.213395 +0.031830 0.213395 +0.029421 0.213395 +0.030511 0.225014 +0.034002 0.236899 +0.040057 0.248337 +0.044014 0.253642 +0.048532 0.258547 +0.053543 0.262968 +0.058964 0.266841 +0.070651 0.272766 +0.082796 0.276183 +0.094668 0.274892 +0.094668 0.277249 +0.094668 0.271021 +0.094668 0.266922 +0.055994 0.251244 +0.049602 0.243725 +0.044473 0.234654 +0.041135 0.224363 +0.063677 0.257499 +0.072945 0.262519 +0.083461 0.265786 +0.037035 0.225203 +0.033163 0.225996 +0.036999 0.237820 +0.042891 0.248241 +0.050235 0.256880 +0.059062 0.264067 +0.069710 0.269833 +0.081792 0.273587 +0.082602 0.269799 +0.040629 0.236283 +0.046150 0.246048 +0.053032 0.254143 +0.061303 0.260877 +0.071281 0.266281 +0.047451 0.259604 +0.042828 0.254585 +0.038778 0.249155 +0.032582 0.237450 +0.029008 0.225286 +0.026483 0.213395 +0.027893 0.213395 +0.024519 0.213395 +0.022799 0.213395 +0.021267 0.213395 +0.019903 0.213395 +0.019142 0.213395 +0.020403 0.226844 +0.024445 0.240602 +0.031453 0.253842 +0.036033 0.259983 +0.041263 0.265660 +0.047064 0.270779 +0.053339 0.275261 +0.066867 0.282120 +0.080925 0.286076 +0.094668 0.286564 +0.094668 0.287310 +0.094668 0.285230 +0.094668 0.283730 +0.094668 0.282047 +0.094668 0.280125 +0.094668 0.278745 +0.082518 0.277654 +0.070089 0.274156 +0.058128 0.268092 +0.052580 0.264129 +0.046454 0.260580 +0.038486 0.251206 +0.032092 0.239898 +0.027930 0.227068 +0.026008 0.227462 +0.024324 0.227807 +0.022824 0.228114 +0.021490 0.228388 +0.026053 0.242456 +0.033064 0.254855 +0.041801 0.265133 +0.052304 0.273684 +0.064973 0.280546 +0.079348 0.285012 +0.079628 0.283706 +0.079942 0.282238 +0.080294 0.280590 +0.080696 0.278709 +0.067587 0.274636 +0.056032 0.268378 +0.027304 0.241926 +0.028711 0.241330 +0.030290 0.240662 +0.034188 0.254099 +0.035450 0.253249 +0.042765 0.264190 +0.043849 0.263129 +0.036867 0.252295 +0.045065 0.261939 +0.053076 0.272585 +0.053945 0.271349 +0.065515 0.279321 +0.066123 0.277944 +0.054919 0.269962 +0.066807 0.276400 +0.015028 0.229712 +0.013365 0.216541 +0.094668 0.293140 +0.094668 0.293025 +0.077971 0.291448 +0.077995 0.291335 +0.062305 0.286580 +0.013296 0.213395 +0.013184 0.213395 +0.013359 0.216541 +0.062351 0.286475 +0.048496 0.279102 +0.037050 0.269783 +0.048563 0.279007 +0.037133 0.269701 +0.027528 0.258581 +0.019887 0.245068 +0.027625 0.258516 +0.019995 0.245022 +0.014913 0.229735 +0.748860 0.213395 +0.748850 0.213395 +0.671541 0.213395 +0.671531 0.213395 +0.672186 0.206511 +0.672176 0.206509 +0.674255 0.199470 +0.674246 0.199466 +0.677842 0.192694 +0.677833 0.192689 +0.682863 0.186645 +0.682856 0.186638 +0.689043 0.181731 +0.695967 0.178221 +0.689038 0.181723 +0.695963 0.178212 +0.703162 0.176197 +0.703160 0.176187 +0.710195 0.175565 +0.710195 0.175555 +0.717229 0.176197 +0.717231 0.176187 +0.724424 0.178221 +0.731348 0.181731 +0.724428 0.178212 +0.731353 0.181723 +0.737528 0.186645 +0.737535 0.186638 +0.742549 0.192694 +0.742557 0.192689 +0.746136 0.199470 +0.746145 0.199466 +0.748205 0.206511 +0.748214 0.206509 +0.602306 0.213395 +0.602296 0.213395 +0.524987 0.213395 +0.524977 0.213395 +0.525632 0.206511 +0.527701 0.199470 +0.525622 0.206509 +0.527692 0.199466 +0.531288 0.192694 +0.531279 0.192689 +0.536308 0.186645 +0.542489 0.181731 +0.536301 0.186638 +0.542484 0.181723 +0.549413 0.178221 +0.549409 0.178212 +0.556608 0.176197 +0.556606 0.176187 +0.563641 0.175565 +0.563641 0.175555 +0.570675 0.176197 +0.570677 0.176187 +0.577870 0.178221 +0.577874 0.178212 +0.584793 0.181731 +0.584799 0.181723 +0.590974 0.186645 +0.590981 0.186638 +0.595995 0.192694 +0.596003 0.192689 +0.599582 0.199470 +0.599591 0.199466 +0.601650 0.206511 +0.601660 0.206509 +0.309198 0.213395 +0.309188 0.213395 +0.231879 0.213395 +0.231869 0.213395 +0.232524 0.206511 +0.232514 0.206509 +0.234593 0.199470 +0.238180 0.192694 +0.234583 0.199466 +0.238171 0.192688 +0.243200 0.186645 +0.249381 0.181731 +0.243193 0.186638 +0.249376 0.181723 +0.256305 0.178221 +0.256301 0.178212 +0.263499 0.176196 +0.263498 0.176187 +0.270533 0.175565 +0.270533 0.175555 +0.277567 0.176196 +0.277569 0.176187 +0.284762 0.178221 +0.284765 0.178212 +0.291685 0.181731 +0.291691 0.181723 +0.297866 0.186645 +0.297873 0.186638 +0.302887 0.192694 +0.302895 0.192688 +0.306474 0.199470 +0.306483 0.199466 +0.308542 0.206511 +0.308552 0.206509 +0.343387 0.178203 +0.339156 0.185857 +0.339136 0.185857 +0.339312 0.184193 +0.339292 0.184189 +0.339812 0.182491 +0.339793 0.182483 +0.340679 0.180853 +0.340662 0.180842 +0.341893 0.179391 +0.357708 0.184189 +0.357864 0.185857 +0.357844 0.185857 +0.357206 0.182483 +0.357688 0.184193 +0.357188 0.182491 +0.356338 0.180842 +0.356321 0.180853 +0.355121 0.179377 +0.355107 0.179391 +0.353624 0.178186 +0.353613 0.178203 +0.351947 0.177336 +0.351939 0.177354 +0.350204 0.176845 +0.350200 0.176865 +0.348500 0.176692 +0.348500 0.176712 +0.346796 0.176845 +0.345053 0.177336 +0.346800 0.176865 +0.343376 0.178186 +0.345061 0.177354 +0.341879 0.179377 +0.029258 0.226796 +0.027888 0.215887 +0.080974 0.277410 +0.094668 0.278797 +0.094668 0.278797 +0.080974 0.277410 +0.068125 0.273417 +0.056801 0.267284 +0.068125 0.273417 +0.056801 0.267284 +0.047413 0.259641 +0.047410 0.259638 +0.039603 0.250454 +0.033337 0.239371 +0.039603 0.250454 +0.033337 0.239371 +0.029258 0.226796 +0.027840 0.213395 +0.027840 0.213395 +0.027881 0.215689 +0.094668 0.286256 +0.094668 0.286256 +0.119582 0.286256 +0.119582 0.286256 +0.126031 0.286256 +0.126031 0.286256 +0.242102 0.286256 +0.242102 0.286256 +0.291344 0.286256 +0.288413 0.286256 +0.248550 0.286256 +0.288413 0.286256 +0.288462 0.286256 +0.315965 0.286256 +0.297206 0.286256 +0.315965 0.286256 +0.364621 0.286256 +0.324758 0.286256 +0.364621 0.286256 +0.324758 0.286256 +0.324709 0.286256 +0.288619 0.286256 +0.297206 0.286256 +0.316014 0.286256 +0.297157 0.286256 +0.316171 0.286256 +0.288890 0.286256 +0.324552 0.286256 +0.297000 0.286256 +0.316443 0.286256 +0.324280 0.286256 +0.289271 0.286256 +0.296728 0.286256 +0.316823 0.286256 +0.289740 0.286256 +0.323900 0.286256 +0.296347 0.286256 +0.317292 0.286256 +0.323431 0.286256 +0.290265 0.286256 +0.295879 0.286256 +0.317817 0.286256 +0.290810 0.286256 +0.322906 0.286256 +0.295354 0.286256 +0.318363 0.286256 +0.322360 0.286256 +0.248550 0.286256 +0.321827 0.286256 +0.318896 0.286256 +0.294808 0.286256 +0.294275 0.286256 +0.413863 0.286256 +0.410932 0.286256 +0.371069 0.286256 +0.410932 0.286256 +0.410981 0.286256 +0.438484 0.286256 +0.419725 0.286256 +0.438484 0.286256 +0.487140 0.286256 +0.447277 0.286256 +0.487140 0.286256 +0.447277 0.286256 +0.447228 0.286256 +0.411138 0.286256 +0.419725 0.286256 +0.438533 0.286256 +0.419676 0.286256 +0.438690 0.286256 +0.411410 0.286256 +0.447072 0.286256 +0.419519 0.286256 +0.438962 0.286256 +0.446800 0.286256 +0.411790 0.286256 +0.419247 0.286256 +0.439343 0.286256 +0.412259 0.286256 +0.446419 0.286256 +0.418867 0.286256 +0.439811 0.286256 +0.445950 0.286256 +0.412784 0.286256 +0.418398 0.286256 +0.440336 0.286256 +0.413330 0.286256 +0.445425 0.286256 +0.417873 0.286256 +0.440882 0.286256 +0.444880 0.286256 +0.371069 0.286256 +0.444346 0.286256 +0.441415 0.286256 +0.417327 0.286256 +0.416794 0.286256 +0.536382 0.286256 +0.533451 0.286256 +0.493589 0.286256 +0.533451 0.286256 +0.533500 0.286256 +0.561003 0.286256 +0.542244 0.286256 +0.561003 0.286256 +0.609659 0.286256 +0.569797 0.286256 +0.609659 0.286256 +0.569797 0.286256 +0.569748 0.286256 +0.533657 0.286256 +0.542244 0.286256 +0.561052 0.286256 +0.542195 0.286256 +0.561209 0.286256 +0.533929 0.286256 +0.569591 0.286256 +0.542039 0.286256 +0.561481 0.286256 +0.569319 0.286256 +0.534310 0.286256 +0.541767 0.286256 +0.561862 0.286256 +0.534778 0.286256 +0.568938 0.286256 +0.541386 0.286256 +0.562330 0.286256 +0.568469 0.286256 +0.535303 0.286256 +0.540917 0.286256 +0.562855 0.286256 +0.535849 0.286256 +0.567944 0.286256 +0.540392 0.286256 +0.563401 0.286256 +0.567399 0.286256 +0.493589 0.286256 +0.566865 0.286256 +0.563934 0.286256 +0.539847 0.286256 +0.539313 0.286256 +0.689918 0.286256 +0.683523 0.286256 +0.683523 0.286256 +0.664764 0.286256 +0.732179 0.286256 +0.692316 0.286256 +0.732179 0.286256 +0.692316 0.286256 +0.655970 0.286256 +0.616108 0.286256 +0.655970 0.286256 +0.656019 0.286256 +0.656176 0.286256 +0.692267 0.286256 +0.664764 0.286256 +0.683572 0.286256 +0.664715 0.286256 +0.683728 0.286256 +0.692110 0.286256 +0.656448 0.286256 +0.664558 0.286256 +0.684000 0.286256 +0.656829 0.286256 +0.691838 0.286256 +0.664286 0.286256 +0.684381 0.286256 +0.691457 0.286256 +0.657298 0.286256 +0.663905 0.286256 +0.684850 0.286256 +0.657823 0.286256 +0.690989 0.286256 +0.663436 0.286256 +0.685375 0.286256 +0.690464 0.286256 +0.658368 0.286256 +0.662911 0.286256 +0.685920 0.286256 +0.658901 0.286256 +0.616108 0.286256 +0.661833 0.286256 +0.662366 0.286256 +0.686454 0.286256 +0.689385 0.286256 +0.738627 0.286256 +0.854698 0.286256 +0.854698 0.286256 +0.738627 0.286256 +0.861146 0.286256 +0.886060 0.286256 +0.886060 0.286256 +0.861146 0.286256 +0.559831 0.147992 +0.420898 0.147992 +0.417967 0.147992 +0.562762 0.147992 +0.418500 0.147992 +0.562229 0.147992 +0.419046 0.147992 +0.561683 0.147992 +0.419571 0.147992 +0.561158 0.147992 +0.420039 0.147992 +0.560689 0.147992 +0.420420 0.147992 +0.560309 0.147992 +0.420692 0.147992 +0.560037 0.147992 +0.420849 0.147992 +0.559880 0.147992 +0.420898 0.147992 +0.559831 0.147992 +0.386950 0.140534 +0.420898 0.140534 +0.420898 0.140534 +0.434381 0.140534 +0.420849 0.140534 +0.420692 0.140534 +0.420420 0.140534 +0.393345 0.140534 +0.412104 0.140534 +0.393345 0.140534 +0.371069 0.140534 +0.384552 0.140534 +0.371069 0.140534 +0.384552 0.140534 +0.384601 0.140534 +0.384758 0.140534 +0.412104 0.140534 +0.393297 0.140534 +0.385030 0.140534 +0.420039 0.140534 +0.412153 0.140534 +0.393140 0.140534 +0.419571 0.140534 +0.385411 0.140534 +0.412310 0.140534 +0.392868 0.140534 +0.385879 0.140534 +0.419046 0.140534 +0.412582 0.140534 +0.392487 0.140534 +0.412963 0.140534 +0.392018 0.140534 +0.418500 0.140534 +0.434381 0.140534 +0.417967 0.140534 +0.415036 0.140534 +0.414502 0.140534 +0.413957 0.140534 +0.413432 0.140534 +0.386404 0.140534 +0.391493 0.140534 +0.390948 0.140534 +0.390414 0.140534 +0.387483 0.140534 +0.298378 0.147992 +0.295447 0.147992 +0.387483 0.147992 +0.295981 0.147992 +0.386950 0.147992 +0.296526 0.147992 +0.386404 0.147992 +0.297051 0.147992 +0.385879 0.147992 +0.297520 0.147992 +0.385411 0.147992 +0.297901 0.147992 +0.385030 0.147992 +0.298173 0.147992 +0.384758 0.147992 +0.298330 0.147992 +0.384601 0.147992 +0.298378 0.147992 +0.384552 0.147992 +0.384552 0.147992 +0.324758 0.278797 +0.410932 0.278797 +0.413863 0.278797 +0.321827 0.278797 +0.413330 0.278797 +0.322360 0.278797 +0.412784 0.278797 +0.322906 0.278797 +0.412259 0.278797 +0.323431 0.278797 +0.411790 0.278797 +0.323900 0.278797 +0.411410 0.278797 +0.324280 0.278797 +0.411138 0.278797 +0.324552 0.278797 +0.410981 0.278797 +0.324709 0.278797 +0.410932 0.278797 +0.324758 0.278797 +0.533451 0.278797 +0.536382 0.278797 +0.444346 0.278797 +0.535849 0.278797 +0.444880 0.278797 +0.535303 0.278797 +0.445425 0.278797 +0.534778 0.278797 +0.445950 0.278797 +0.534310 0.278797 +0.446419 0.278797 +0.533929 0.278797 +0.446800 0.278797 +0.533657 0.278797 +0.447072 0.278797 +0.533500 0.278797 +0.447228 0.278797 +0.533451 0.278797 +0.447277 0.278797 +0.447277 0.278797 +0.264431 0.140534 +0.298378 0.140534 +0.298378 0.140534 +0.311861 0.140534 +0.298330 0.140534 +0.298173 0.140534 +0.297901 0.140534 +0.270826 0.140534 +0.270826 0.140534 +0.289585 0.140534 +0.248550 0.140534 +0.262033 0.140534 +0.248550 0.140534 +0.262033 0.140534 +0.262082 0.140534 +0.262239 0.140534 +0.289585 0.140534 +0.270777 0.140534 +0.262511 0.140534 +0.297520 0.140534 +0.289634 0.140534 +0.270620 0.140534 +0.297051 0.140534 +0.262892 0.140534 +0.289791 0.140534 +0.270348 0.140534 +0.263360 0.140534 +0.296526 0.140534 +0.290063 0.140534 +0.269968 0.140534 +0.290444 0.140534 +0.269499 0.140534 +0.295981 0.140534 +0.311861 0.140534 +0.295447 0.140534 +0.292516 0.140534 +0.291983 0.140534 +0.291437 0.140534 +0.290912 0.140534 +0.263885 0.140534 +0.268974 0.140534 +0.268429 0.140534 +0.267895 0.140534 +0.264964 0.140534 +0.094668 0.147992 +0.135501 0.147992 +0.141768 0.147992 +0.264964 0.147992 +0.264431 0.147992 +0.263885 0.147992 +0.263360 0.147992 +0.262892 0.147992 +0.262511 0.147992 +0.262239 0.147992 +0.262082 0.147992 +0.141565 0.147992 +0.262033 0.147992 +0.262033 0.147992 +0.135703 0.147992 +0.094668 0.147992 +0.136290 0.278797 +0.136088 0.278797 +0.290810 0.278797 +0.291344 0.278797 +0.290265 0.278797 +0.289740 0.278797 +0.289271 0.278797 +0.288890 0.278797 +0.288619 0.278797 +0.288462 0.278797 +0.288413 0.278797 +0.141181 0.278797 +0.288413 0.278797 +0.094668 0.278797 +0.140979 0.278797 +0.094668 0.278797 +0.562229 0.140534 +0.568624 0.140534 +0.587383 0.140534 +0.568624 0.140534 +0.596176 0.140534 +0.609659 0.140534 +0.596176 0.140534 +0.596127 0.140534 +0.595971 0.140534 +0.595699 0.140534 +0.546348 0.140534 +0.559831 0.140534 +0.546348 0.140534 +0.559831 0.140534 +0.559880 0.140534 +0.560037 0.140534 +0.587383 0.140534 +0.568575 0.140534 +0.560309 0.140534 +0.595318 0.140534 +0.587432 0.140534 +0.568418 0.140534 +0.594849 0.140534 +0.560689 0.140534 +0.587589 0.140534 +0.568146 0.140534 +0.561158 0.140534 +0.594324 0.140534 +0.587861 0.140534 +0.567766 0.140534 +0.588242 0.140534 +0.567297 0.140534 +0.593779 0.140534 +0.609659 0.140534 +0.593245 0.140534 +0.590314 0.140534 +0.589781 0.140534 +0.589235 0.140534 +0.588710 0.140534 +0.561683 0.140534 +0.566772 0.140534 +0.566226 0.140534 +0.565693 0.140534 +0.562762 0.140534 +0.682350 0.147992 +0.596176 0.147992 +0.593245 0.147992 +0.685281 0.147992 +0.593779 0.147992 +0.684748 0.147992 +0.594324 0.147992 +0.684202 0.147992 +0.594849 0.147992 +0.683677 0.147992 +0.595318 0.147992 +0.683209 0.147992 +0.595699 0.147992 +0.682828 0.147992 +0.595971 0.147992 +0.682556 0.147992 +0.596127 0.147992 +0.682399 0.147992 +0.596176 0.147992 +0.682350 0.147992 +0.684748 0.140534 +0.718696 0.140534 +0.732179 0.140534 +0.718696 0.140534 +0.718647 0.140534 +0.718490 0.140534 +0.718218 0.140534 +0.691143 0.140534 +0.709902 0.140534 +0.691143 0.140534 +0.668867 0.140534 +0.682350 0.140534 +0.668867 0.140534 +0.682350 0.140534 +0.682399 0.140534 +0.682556 0.140534 +0.709902 0.140534 +0.691094 0.140534 +0.682828 0.140534 +0.717837 0.140534 +0.709951 0.140534 +0.690938 0.140534 +0.717368 0.140534 +0.683209 0.140534 +0.710108 0.140534 +0.690666 0.140534 +0.683677 0.140534 +0.716843 0.140534 +0.710380 0.140534 +0.690285 0.140534 +0.710761 0.140534 +0.689816 0.140534 +0.716298 0.140534 +0.732179 0.140534 +0.715765 0.140534 +0.712833 0.140534 +0.712300 0.140534 +0.711755 0.140534 +0.711230 0.140534 +0.684202 0.140534 +0.689291 0.140534 +0.688746 0.140534 +0.688212 0.140534 +0.685281 0.140534 +0.845025 0.147992 +0.845227 0.147992 +0.716298 0.147992 +0.715765 0.147992 +0.716843 0.147992 +0.717368 0.147992 +0.717837 0.147992 +0.718218 0.147992 +0.718490 0.147992 +0.718647 0.147992 +0.718696 0.147992 +0.838961 0.147992 +0.718696 0.147992 +0.886060 0.147992 +0.839163 0.147992 +0.886060 0.147992 +0.569797 0.278797 +0.655970 0.278797 +0.658901 0.278797 +0.566865 0.278797 +0.658368 0.278797 +0.567399 0.278797 +0.657823 0.278797 +0.567944 0.278797 +0.657298 0.278797 +0.568469 0.278797 +0.656829 0.278797 +0.568938 0.278797 +0.656448 0.278797 +0.569319 0.278797 +0.656176 0.278797 +0.569591 0.278797 +0.656019 0.278797 +0.569748 0.278797 +0.655970 0.278797 +0.569797 0.278797 +0.043151 0.265994 +0.022138 0.229831 +0.020286 0.216478 +0.020286 0.216478 +0.020288 0.216541 +0.022138 0.229831 +0.026984 0.243742 +0.034231 0.255942 +0.026984 0.243742 +0.094668 0.286256 +0.094668 0.286256 +0.080959 0.285010 +0.066551 0.280860 +0.080959 0.285010 +0.053790 0.274290 +0.066551 0.280860 +0.053790 0.274290 +0.043151 0.265994 +0.034231 0.255942 +0.020292 0.210167 +0.020292 0.210167 +0.094668 0.140534 +0.094668 0.140534 +0.081031 0.141766 +0.081031 0.141766 +0.066619 0.145902 +0.053852 0.152460 +0.066619 0.145902 +0.053852 0.152460 +0.043204 0.160745 +0.043204 0.160745 +0.034274 0.170789 +0.034274 0.170789 +0.027015 0.182982 +0.022154 0.196889 +0.027015 0.182982 +0.020292 0.210167 +0.022154 0.196889 +0.926938 0.274290 +0.886060 0.286256 +0.886060 0.286256 +0.899770 0.285010 +0.914177 0.280860 +0.899770 0.285010 +0.960443 0.216478 +0.960443 0.216478 +0.960440 0.216542 +0.958591 0.229831 +0.953745 0.243742 +0.958591 0.229831 +0.953745 0.243742 +0.946498 0.255942 +0.946498 0.255942 +0.937578 0.265994 +0.937578 0.265994 +0.926938 0.274290 +0.914177 0.280860 +0.364621 0.140534 +0.318310 0.140534 +0.318310 0.140534 +0.364621 0.140534 +0.487140 0.140534 +0.440829 0.140534 +0.440829 0.140534 +0.487140 0.140534 +0.242102 0.140534 +0.242102 0.140534 +0.126031 0.140534 +0.126031 0.140534 +0.539900 0.140534 +0.493589 0.140534 +0.493589 0.140534 +0.539900 0.140534 +0.662419 0.140534 +0.616108 0.140534 +0.616108 0.140534 +0.662419 0.140534 +0.854698 0.140534 +0.854698 0.140534 +0.738627 0.140534 +0.738627 0.140534 +0.886060 0.140534 +0.886060 0.140534 +0.861146 0.140534 +0.861146 0.140534 +0.886060 0.278798 +0.844641 0.278797 +0.839547 0.278797 +0.689385 0.278797 +0.689918 0.278797 +0.690464 0.278797 +0.690989 0.278797 +0.691457 0.278797 +0.691838 0.278797 +0.692110 0.278797 +0.692267 0.278797 +0.839749 0.278797 +0.692316 0.278797 +0.692316 0.278797 +0.844439 0.278797 +0.886060 0.278798 +0.027881 0.211100 +0.027888 0.210902 +0.080974 0.149380 +0.094668 0.147992 +0.094668 0.147992 +0.068125 0.153372 +0.080974 0.149380 +0.056801 0.159505 +0.068125 0.153372 +0.047410 0.167151 +0.056801 0.159505 +0.047413 0.167148 +0.039603 0.176335 +0.039603 0.176335 +0.033337 0.187418 +0.029258 0.199993 +0.033337 0.187418 +0.027840 0.213395 +0.027840 0.213395 +0.029258 0.199993 +0.898221 0.277706 +0.886060 0.278798 +0.886060 0.147992 +0.886060 0.147992 +0.898221 0.149084 +0.898221 0.149084 +0.910660 0.152584 +0.922630 0.158653 +0.910660 0.152584 +0.922630 0.158653 +0.933315 0.167148 +0.933315 0.167148 +0.941996 0.177606 +0.941996 0.177606 +0.948197 0.189320 +0.948197 0.189320 +0.951773 0.201494 +0.951773 0.201494 +0.952840 0.210902 +0.952889 0.213395 +0.952848 0.211100 +0.952889 0.213395 +0.951773 0.225296 +0.952848 0.215690 +0.952840 0.215887 +0.951773 0.225296 +0.948197 0.237469 +0.948197 0.237469 +0.941996 0.249184 +0.933315 0.259642 +0.941996 0.249184 +0.922630 0.268137 +0.933315 0.259642 +0.922630 0.268137 +0.910660 0.274206 +0.898221 0.277706 +0.910660 0.274206 +0.886060 0.278798 +0.119582 0.140534 +0.094668 0.140534 +0.094668 0.140534 +0.119582 0.140534 +0.937525 0.160746 +0.960437 0.210168 +0.960437 0.210168 +0.958574 0.196889 +0.960436 0.210142 +0.953714 0.182982 +0.958574 0.196889 +0.946455 0.170789 +0.953714 0.182982 +0.937525 0.160746 +0.946455 0.170789 +0.899698 0.141767 +0.886060 0.140534 +0.886060 0.140534 +0.914109 0.145903 +0.899698 0.141767 +0.926877 0.152460 +0.914109 0.145903 +0.926877 0.152460 +0.861146 0.142134 +0.861146 0.142226 +0.861146 0.142255 +0.861146 0.140534 +0.861146 0.142255 +0.861146 0.136231 +0.861146 0.136231 +0.861146 0.140534 +0.861146 0.133764 +0.861146 0.133756 +0.861146 0.140534 +0.861146 0.140847 +0.861146 0.141167 +0.861146 0.141476 +0.861146 0.141751 +0.861146 0.141974 +0.854698 0.142255 +0.854698 0.142255 +0.861146 0.142255 +0.861146 0.142255 +0.854698 0.141167 +0.854698 0.140847 +0.854698 0.140534 +0.854698 0.140534 +0.854698 0.142255 +0.854698 0.133756 +0.854698 0.133764 +0.854698 0.136231 +0.854698 0.136231 +0.854698 0.140534 +0.854698 0.142255 +0.854698 0.142226 +0.854698 0.142134 +0.854698 0.141974 +0.854698 0.141751 +0.854698 0.141476 +0.738627 0.142134 +0.738627 0.142226 +0.738627 0.142255 +0.738627 0.140534 +0.738627 0.142255 +0.738627 0.140534 +0.738627 0.133764 +0.738627 0.133756 +0.738627 0.136231 +0.738627 0.136231 +0.738627 0.140534 +0.738627 0.140847 +0.738627 0.141167 +0.738627 0.141476 +0.738627 0.141751 +0.738627 0.141974 +0.732179 0.142255 +0.732179 0.142255 +0.738627 0.142255 +0.738627 0.142255 +0.732179 0.141167 +0.732179 0.140847 +0.732179 0.140534 +0.732179 0.136231 +0.732179 0.140534 +0.732179 0.140534 +0.732179 0.142255 +0.732179 0.133756 +0.732179 0.133764 +0.732179 0.136231 +0.732179 0.142255 +0.732179 0.142226 +0.732179 0.142134 +0.732179 0.141974 +0.732179 0.141751 +0.732179 0.141476 +0.616108 0.142134 +0.616108 0.142226 +0.616108 0.142255 +0.616108 0.140534 +0.616108 0.142255 +0.616108 0.136231 +0.616108 0.136231 +0.616108 0.140534 +0.616108 0.133764 +0.616108 0.133756 +0.616108 0.140534 +0.616108 0.140847 +0.616108 0.141167 +0.616108 0.141476 +0.616108 0.141751 +0.616108 0.141974 +0.609659 0.142255 +0.609659 0.142255 +0.616108 0.142255 +0.616108 0.142255 +0.609659 0.141167 +0.609659 0.140847 +0.609659 0.140534 +0.609659 0.136231 +0.609659 0.140534 +0.609659 0.140534 +0.609659 0.142255 +0.609659 0.133756 +0.609659 0.133764 +0.609659 0.136231 +0.609659 0.142255 +0.609659 0.142226 +0.609659 0.142134 +0.609659 0.141974 +0.609659 0.141751 +0.609659 0.141476 +0.493589 0.142134 +0.493589 0.142226 +0.493589 0.142255 +0.493589 0.140534 +0.493589 0.142255 +0.493589 0.140534 +0.493589 0.133764 +0.493589 0.133756 +0.493589 0.136231 +0.493589 0.136231 +0.493589 0.140534 +0.493589 0.140847 +0.493589 0.141167 +0.493589 0.141476 +0.493589 0.141751 +0.493589 0.141974 +0.493589 0.142255 +0.487140 0.142255 +0.487140 0.142255 +0.493589 0.142255 +0.487140 0.141167 +0.487140 0.140847 +0.487140 0.140534 +0.487140 0.140534 +0.487140 0.142255 +0.487140 0.133756 +0.487140 0.133764 +0.487140 0.136231 +0.487140 0.136231 +0.487140 0.140534 +0.487140 0.142255 +0.487140 0.142226 +0.487140 0.142134 +0.487140 0.141974 +0.487140 0.141751 +0.487140 0.141476 +0.371069 0.142134 +0.371069 0.142226 +0.371069 0.142255 +0.371069 0.140534 +0.371069 0.142255 +0.371069 0.140534 +0.371069 0.133764 +0.371069 0.133756 +0.371069 0.136231 +0.371069 0.136231 +0.371069 0.140534 +0.371069 0.140847 +0.371069 0.141167 +0.371069 0.141475 +0.371069 0.141751 +0.371069 0.141974 +0.371069 0.142255 +0.364621 0.142255 +0.364621 0.142255 +0.371069 0.142255 +0.364621 0.141167 +0.364621 0.140847 +0.364621 0.140534 +0.364621 0.136231 +0.364621 0.140534 +0.364621 0.140534 +0.364621 0.142255 +0.364621 0.133756 +0.364621 0.133764 +0.364621 0.136231 +0.364621 0.142255 +0.364621 0.142226 +0.364621 0.142134 +0.364621 0.141974 +0.364621 0.141751 +0.364621 0.141475 +0.248550 0.142134 +0.248550 0.142226 +0.248550 0.142255 +0.248550 0.140534 +0.248550 0.142255 +0.248550 0.136231 +0.248550 0.136231 +0.248550 0.140534 +0.248550 0.133764 +0.248550 0.133756 +0.248550 0.140534 +0.248550 0.140847 +0.248550 0.141167 +0.248550 0.141475 +0.248550 0.141751 +0.248550 0.141974 +0.248550 0.142255 +0.242102 0.142255 +0.242102 0.142255 +0.248550 0.142255 +0.242102 0.141167 +0.242102 0.140847 +0.242102 0.140534 +0.242102 0.136231 +0.242102 0.140534 +0.242102 0.140534 +0.242102 0.142255 +0.242102 0.133756 +0.242102 0.133764 +0.242102 0.136231 +0.242102 0.142255 +0.242102 0.142226 +0.242102 0.142134 +0.242102 0.141974 +0.242102 0.141751 +0.242102 0.141475 +0.126031 0.142134 +0.126031 0.142226 +0.126031 0.142255 +0.126031 0.140534 +0.126031 0.142255 +0.126031 0.136231 +0.126031 0.136231 +0.126031 0.140534 +0.126031 0.133764 +0.126031 0.133756 +0.126031 0.140534 +0.126031 0.140847 +0.126031 0.141167 +0.126031 0.141475 +0.126031 0.141751 +0.126031 0.141974 +0.119582 0.142255 +0.119582 0.142255 +0.126031 0.142255 +0.126031 0.142255 +0.119582 0.141167 +0.119582 0.140847 +0.119582 0.140534 +0.119582 0.136231 +0.119582 0.140534 +0.119582 0.140534 +0.119582 0.142255 +0.119582 0.133756 +0.119582 0.133764 +0.119582 0.136231 +0.119582 0.142255 +0.119582 0.142226 +0.119582 0.142134 +0.119582 0.141974 +0.119582 0.141751 +0.119582 0.141475 +0.546348 0.142134 +0.546348 0.142226 +0.546348 0.142255 +0.546348 0.140534 +0.546348 0.142255 +0.546348 0.140534 +0.546348 0.133764 +0.546348 0.133756 +0.546348 0.136231 +0.546348 0.136231 +0.546348 0.140534 +0.546348 0.140847 +0.546348 0.141167 +0.546348 0.141476 +0.546348 0.141751 +0.546348 0.141974 +0.539900 0.142255 +0.539900 0.142255 +0.546348 0.142255 +0.546348 0.142255 +0.539900 0.141167 +0.539900 0.140847 +0.539900 0.140534 +0.539900 0.140534 +0.539900 0.142255 +0.539900 0.133756 +0.539900 0.133764 +0.539900 0.136231 +0.539900 0.136231 +0.539900 0.140534 +0.539900 0.142255 +0.539900 0.142226 +0.539900 0.142134 +0.539900 0.141974 +0.539900 0.141751 +0.539900 0.141476 +0.440829 0.142134 +0.440829 0.142226 +0.440829 0.142255 +0.440829 0.140534 +0.440829 0.142255 +0.440829 0.136231 +0.440829 0.136231 +0.440829 0.140534 +0.440829 0.133764 +0.440829 0.133756 +0.440829 0.140534 +0.440829 0.140847 +0.440829 0.141167 +0.440829 0.141475 +0.440829 0.141751 +0.440829 0.141974 +0.434381 0.142255 +0.434381 0.142255 +0.440829 0.142255 +0.440829 0.142255 +0.434381 0.141167 +0.434381 0.140847 +0.434381 0.140534 +0.434381 0.140534 +0.434381 0.142255 +0.434381 0.133756 +0.434381 0.133764 +0.434381 0.136231 +0.434381 0.136231 +0.434381 0.140534 +0.434381 0.142255 +0.434381 0.142226 +0.434381 0.142134 +0.434381 0.141974 +0.434381 0.141751 +0.434381 0.141475 +0.318310 0.142134 +0.318310 0.142226 +0.318310 0.142255 +0.318310 0.140534 +0.318310 0.142255 +0.318310 0.136231 +0.318310 0.136231 +0.318310 0.140534 +0.318310 0.133764 +0.318310 0.133756 +0.318310 0.140534 +0.318310 0.140847 +0.318310 0.141167 +0.318310 0.141475 +0.318310 0.141751 +0.318310 0.141974 +0.311861 0.142255 +0.311861 0.142255 +0.318310 0.142255 +0.318310 0.142255 +0.311861 0.141167 +0.311861 0.140847 +0.311861 0.140534 +0.311861 0.136231 +0.311861 0.140534 +0.311861 0.140534 +0.311861 0.142255 +0.311861 0.133756 +0.311861 0.133764 +0.311861 0.136231 +0.311861 0.142255 +0.311861 0.142226 +0.311861 0.142134 +0.311861 0.141974 +0.311861 0.141751 +0.311861 0.141475 +0.668867 0.142134 +0.668867 0.142226 +0.668867 0.142255 +0.668867 0.140534 +0.668867 0.142255 +0.668867 0.136231 +0.668867 0.136231 +0.668867 0.140534 +0.668867 0.133764 +0.668867 0.133756 +0.668867 0.140534 +0.668867 0.140847 +0.668867 0.141167 +0.668867 0.141476 +0.668867 0.141751 +0.668867 0.141974 +0.662419 0.142255 +0.662419 0.142255 +0.668867 0.142255 +0.668867 0.142255 +0.662419 0.141167 +0.662419 0.140847 +0.662419 0.140534 +0.662419 0.140534 +0.662419 0.142255 +0.662419 0.133756 +0.662419 0.133764 +0.662419 0.136231 +0.662419 0.136231 +0.662419 0.140534 +0.662419 0.142255 +0.662419 0.142226 +0.662419 0.142134 +0.662419 0.141974 +0.662419 0.141751 +0.662419 0.141476 +0.960443 0.216478 +0.960443 0.216478 +0.958751 0.216453 +0.958751 0.216453 +0.958751 0.216453 +0.958751 0.216542 +0.958751 0.210142 +0.958751 0.210142 +0.958751 0.216453 +0.958751 0.210142 +0.958751 0.216542 +0.958751 0.210142 +0.960437 0.210168 +0.960437 0.210168 +0.958751 0.210142 +0.021977 0.216453 +0.020286 0.216478 +0.020286 0.216478 +0.021977 0.216453 +0.021977 0.210142 +0.021977 0.216453 +0.021977 0.210142 +0.021977 0.216453 +0.021977 0.216541 +0.021977 0.216541 +0.021977 0.210142 +0.020292 0.210167 +0.020292 0.210167 +0.021977 0.210142 +0.021977 0.210142 +0.655970 0.286256 +0.655970 0.278797 +0.655970 0.278797 +0.655970 0.286256 +0.692316 0.286256 +0.692316 0.286256 +0.692316 0.278797 +0.692316 0.278797 +0.718696 0.140534 +0.718696 0.147992 +0.718696 0.147992 +0.718696 0.140534 +0.682350 0.147992 +0.682350 0.140534 +0.682350 0.140534 +0.682350 0.147992 +0.533451 0.286256 +0.533451 0.278797 +0.533451 0.278797 +0.533451 0.286256 +0.569797 0.286256 +0.569797 0.286256 +0.569797 0.278797 +0.569797 0.278797 +0.596176 0.140534 +0.596176 0.147992 +0.596176 0.147992 +0.596176 0.140534 +0.559831 0.147992 +0.559831 0.140534 +0.559831 0.140534 +0.559831 0.147992 +0.324758 0.286256 +0.324758 0.286256 +0.324758 0.278797 +0.324758 0.278797 +0.288413 0.278797 +0.288413 0.286256 +0.288413 0.286256 +0.288413 0.278797 +0.262033 0.140534 +0.262033 0.140534 +0.262033 0.147992 +0.262033 0.147992 +0.298378 0.147992 +0.298378 0.147992 +0.298378 0.140534 +0.298378 0.140534 +0.447277 0.286256 +0.447277 0.286256 +0.447277 0.278797 +0.447277 0.278797 +0.410932 0.278797 +0.410932 0.286256 +0.410932 0.286256 +0.410932 0.278797 +0.384552 0.140534 +0.384552 0.140534 +0.384552 0.147992 +0.384552 0.147992 +0.420898 0.147992 +0.420898 0.140534 +0.420898 0.140534 +0.420898 0.147992 +0.861146 0.284535 +0.861146 0.284535 +0.854698 0.284535 +0.854698 0.284535 +0.854698 0.284655 +0.854698 0.284563 +0.854698 0.284535 +0.854698 0.286256 +0.854698 0.284535 +0.854698 0.290559 +0.854698 0.290559 +0.854698 0.286256 +0.854698 0.293025 +0.854698 0.293034 +0.854698 0.286256 +0.854698 0.285943 +0.854698 0.285622 +0.854698 0.285314 +0.854698 0.285039 +0.854698 0.284815 +0.861146 0.285622 +0.861146 0.285943 +0.861146 0.286256 +0.861146 0.286256 +0.861146 0.284535 +0.861146 0.293034 +0.861146 0.293025 +0.861146 0.290559 +0.861146 0.290559 +0.861146 0.286256 +0.861146 0.284535 +0.861146 0.284563 +0.861146 0.284655 +0.861146 0.284815 +0.861146 0.285039 +0.861146 0.285314 +0.738627 0.284535 +0.732179 0.284535 +0.732179 0.284535 +0.738627 0.284535 +0.732179 0.284655 +0.732179 0.284563 +0.732179 0.284535 +0.732179 0.286256 +0.732179 0.284535 +0.732179 0.286256 +0.732179 0.293025 +0.732179 0.293033 +0.732179 0.290558 +0.732179 0.290558 +0.732179 0.286256 +0.732179 0.285943 +0.732179 0.285622 +0.732179 0.285314 +0.732179 0.285039 +0.732179 0.284815 +0.738627 0.285622 +0.738627 0.285943 +0.738627 0.286256 +0.738627 0.286256 +0.738627 0.284535 +0.738627 0.293033 +0.738627 0.293025 +0.738627 0.290558 +0.738627 0.290558 +0.738627 0.286256 +0.738627 0.284535 +0.738627 0.284563 +0.738627 0.284655 +0.738627 0.284815 +0.738627 0.285039 +0.738627 0.285314 +0.616108 0.284535 +0.609659 0.284535 +0.609659 0.284535 +0.616108 0.284535 +0.609659 0.284655 +0.609659 0.284563 +0.609659 0.284535 +0.609659 0.286256 +0.609659 0.284535 +0.609659 0.286256 +0.609659 0.293025 +0.609659 0.293033 +0.609659 0.290558 +0.609659 0.290558 +0.609659 0.286256 +0.609659 0.285943 +0.609659 0.285622 +0.609659 0.285314 +0.609659 0.285039 +0.609659 0.284815 +0.616108 0.285622 +0.616108 0.285943 +0.616108 0.286256 +0.616108 0.286256 +0.616108 0.284535 +0.616108 0.293033 +0.616108 0.293025 +0.616108 0.290558 +0.616108 0.290558 +0.616108 0.286256 +0.616108 0.284535 +0.616108 0.284563 +0.616108 0.284655 +0.616108 0.284815 +0.616108 0.285039 +0.616108 0.285314 +0.493589 0.284535 +0.493589 0.284535 +0.487140 0.284535 +0.487140 0.284535 +0.487140 0.284655 +0.487140 0.284563 +0.487140 0.284535 +0.487140 0.286256 +0.487140 0.284535 +0.487140 0.286256 +0.487140 0.293025 +0.487140 0.293033 +0.487140 0.290558 +0.487140 0.290558 +0.487140 0.286256 +0.487140 0.285943 +0.487140 0.285622 +0.487140 0.285314 +0.487140 0.285039 +0.487140 0.284815 +0.493589 0.285622 +0.493589 0.285943 +0.493589 0.286256 +0.493589 0.286256 +0.493589 0.284535 +0.493589 0.293033 +0.493589 0.293025 +0.493589 0.290558 +0.493589 0.290558 +0.493589 0.286256 +0.493589 0.284535 +0.493589 0.284563 +0.493589 0.284655 +0.493589 0.284815 +0.493589 0.285039 +0.493589 0.285314 +0.371069 0.284535 +0.371069 0.284535 +0.364621 0.284535 +0.364621 0.284535 +0.364621 0.284655 +0.364621 0.284563 +0.364621 0.284535 +0.364621 0.286256 +0.364621 0.284535 +0.364621 0.290558 +0.364621 0.290558 +0.364621 0.286256 +0.364621 0.293025 +0.364621 0.293033 +0.364621 0.286256 +0.364621 0.285942 +0.364621 0.285622 +0.364621 0.285314 +0.364621 0.285039 +0.364621 0.284815 +0.371069 0.285622 +0.371069 0.285942 +0.371069 0.286256 +0.371069 0.286256 +0.371069 0.284535 +0.371069 0.286256 +0.371069 0.290558 +0.371069 0.293033 +0.371069 0.293025 +0.371069 0.290558 +0.371069 0.284535 +0.371069 0.284563 +0.371069 0.284655 +0.371069 0.284815 +0.371069 0.285039 +0.371069 0.285314 +0.248550 0.284535 +0.248550 0.284535 +0.242102 0.284535 +0.242102 0.284535 +0.242102 0.284655 +0.242102 0.284563 +0.242102 0.284535 +0.242102 0.286256 +0.242102 0.284535 +0.242102 0.286256 +0.242102 0.293025 +0.242102 0.293033 +0.242102 0.290558 +0.242102 0.290558 +0.242102 0.286256 +0.242102 0.285942 +0.242102 0.285622 +0.242102 0.285314 +0.242102 0.285039 +0.242102 0.284815 +0.248550 0.285622 +0.248550 0.285942 +0.248550 0.286256 +0.248550 0.286256 +0.248550 0.284535 +0.248550 0.286256 +0.248550 0.290558 +0.248550 0.293033 +0.248550 0.293025 +0.248550 0.290558 +0.248550 0.284535 +0.248550 0.284563 +0.248550 0.284655 +0.248550 0.284815 +0.248550 0.285039 +0.248550 0.285314 +0.126031 0.284535 +0.119582 0.284535 +0.119582 0.284535 +0.126031 0.284535 +0.119582 0.284655 +0.119582 0.284563 +0.119582 0.284535 +0.119582 0.286256 +0.119582 0.284535 +0.119582 0.286256 +0.119582 0.293025 +0.119582 0.293033 +0.119582 0.290558 +0.119582 0.290558 +0.119582 0.286256 +0.119582 0.285942 +0.119582 0.285622 +0.119582 0.285314 +0.119582 0.285039 +0.119582 0.284815 +0.126031 0.285622 +0.126031 0.285942 +0.126031 0.286256 +0.126031 0.286256 +0.126031 0.284535 +0.126031 0.293033 +0.126031 0.293025 +0.126031 0.290558 +0.126031 0.290558 +0.126031 0.286256 +0.126031 0.284535 +0.126031 0.284563 +0.126031 0.284655 +0.126031 0.284815 +0.126031 0.285039 +0.126031 0.285314 +0.242102 0.286256 +0.126031 0.286256 +0.126031 0.293025 +0.242102 0.293025 +0.094668 0.293025 +0.119582 0.293025 +0.020288 0.216541 +0.013365 0.216541 +0.022044 0.229428 +0.015237 0.230660 +0.026408 0.242481 +0.019974 0.244975 +0.033512 0.254947 +0.027721 0.258652 +0.043174 0.266016 +0.038282 0.270804 +0.054891 0.274984 +0.051106 0.280651 +0.067923 0.281392 +0.065377 0.287686 +0.081438 0.285096 +0.080179 0.291752 +0.094668 0.286256 +0.119582 0.286256 +0.119582 0.293033 +0.119582 0.293025 +0.732179 0.293033 +0.732179 0.293025 +0.616108 0.293025 +0.854698 0.293025 +0.738627 0.293025 +0.854698 0.293034 +0.886060 0.293140 +0.886060 0.293025 +0.861146 0.293025 +0.094668 0.293140 +0.861146 0.293034 +0.738627 0.293033 +0.616108 0.293033 +0.242102 0.293033 +0.242102 0.293025 +0.126031 0.293025 +0.364621 0.293025 +0.248550 0.293025 +0.364621 0.293033 +0.487140 0.293025 +0.371069 0.293025 +0.487140 0.293033 +0.609659 0.293025 +0.493589 0.293025 +0.609659 0.293033 +0.493589 0.293033 +0.371069 0.293033 +0.248550 0.293033 +0.126031 0.293033 +0.094668 0.293025 +0.126031 0.290558 +0.119582 0.290558 +0.119582 0.290558 +0.126031 0.290558 +0.364621 0.286256 +0.248550 0.286256 +0.248550 0.293025 +0.364621 0.293025 +0.248550 0.290558 +0.242102 0.290558 +0.242102 0.290558 +0.248550 0.290558 +0.487140 0.286256 +0.371069 0.286256 +0.371069 0.293025 +0.487140 0.293025 +0.371069 0.290558 +0.364621 0.290558 +0.364621 0.290558 +0.371069 0.290558 +0.609659 0.286256 +0.493589 0.286256 +0.493589 0.293025 +0.609659 0.293025 +0.493589 0.290558 +0.487140 0.290558 +0.487140 0.290558 +0.493589 0.290558 +0.732179 0.293025 +0.732179 0.286256 +0.616108 0.286256 +0.616108 0.293025 +0.616108 0.290558 +0.609659 0.290558 +0.609659 0.290558 +0.616108 0.290558 +0.854698 0.286256 +0.738627 0.286256 +0.738627 0.293025 +0.854698 0.293025 +0.738627 0.290558 +0.738627 0.290558 +0.732179 0.290558 +0.732179 0.290558 +0.886060 0.286256 +0.861146 0.286256 +0.965491 0.230661 +0.967363 0.216542 +0.960440 0.216542 +0.960755 0.244975 +0.958685 0.229428 +0.953008 0.258653 +0.954320 0.242482 +0.942447 0.270804 +0.947216 0.254947 +0.929623 0.280651 +0.937555 0.266016 +0.915352 0.287686 +0.925837 0.274985 +0.900550 0.291752 +0.912805 0.281392 +0.886060 0.293025 +0.899291 0.285096 +0.861146 0.293025 +0.861146 0.290559 +0.861146 0.290559 +0.854698 0.290559 +0.854698 0.290559 +0.412104 0.147992 +0.393345 0.147992 +0.390414 0.147992 +0.415036 0.147992 +0.390948 0.147992 +0.414502 0.147992 +0.391493 0.147992 +0.413957 0.147992 +0.392018 0.147992 +0.413432 0.147992 +0.392487 0.147992 +0.412963 0.147992 +0.392868 0.147992 +0.412582 0.147992 +0.393140 0.147992 +0.412310 0.147992 +0.393297 0.147992 +0.412153 0.147992 +0.393345 0.147992 +0.412104 0.147992 +0.419725 0.278797 +0.438484 0.278797 +0.441415 0.278797 +0.416794 0.278797 +0.440882 0.278797 +0.417327 0.278797 +0.440336 0.278797 +0.417873 0.278797 +0.439811 0.278797 +0.418398 0.278797 +0.439343 0.278797 +0.418867 0.278797 +0.438962 0.278797 +0.419247 0.278797 +0.438690 0.278797 +0.419519 0.278797 +0.438533 0.278797 +0.419676 0.278797 +0.438484 0.278797 +0.419725 0.278797 +0.289585 0.147992 +0.270826 0.147992 +0.267895 0.147992 +0.292516 0.147992 +0.268429 0.147992 +0.291983 0.147992 +0.268974 0.147992 +0.291437 0.147992 +0.269499 0.147992 +0.290912 0.147992 +0.269968 0.147992 +0.290444 0.147992 +0.270348 0.147992 +0.290063 0.147992 +0.270620 0.147992 +0.289791 0.147992 +0.270777 0.147992 +0.289634 0.147992 +0.270826 0.147992 +0.289585 0.147992 +0.297206 0.278797 +0.318896 0.278797 +0.294275 0.278797 +0.318363 0.278797 +0.294808 0.278797 +0.317817 0.278797 +0.295354 0.278797 +0.317292 0.278797 +0.295879 0.278797 +0.316823 0.278797 +0.296347 0.278797 +0.316443 0.278797 +0.296728 0.278797 +0.316171 0.278797 +0.297000 0.278797 +0.316014 0.278797 +0.297157 0.278797 +0.315965 0.278797 +0.297206 0.278797 +0.315965 0.278797 +0.587383 0.147992 +0.568624 0.147992 +0.565693 0.147992 +0.590314 0.147992 +0.566226 0.147992 +0.589781 0.147992 +0.566772 0.147992 +0.589235 0.147992 +0.567297 0.147992 +0.588710 0.147992 +0.567766 0.147992 +0.588242 0.147992 +0.568146 0.147992 +0.587861 0.147992 +0.568418 0.147992 +0.587589 0.147992 +0.568575 0.147992 +0.587432 0.147992 +0.568624 0.147992 +0.587383 0.147992 +0.542244 0.278797 +0.561003 0.278797 +0.563934 0.278797 +0.539313 0.278797 +0.563401 0.278797 +0.539847 0.278797 +0.562855 0.278797 +0.540392 0.278797 +0.562330 0.278797 +0.540917 0.278797 +0.561862 0.278797 +0.541386 0.278797 +0.561481 0.278797 +0.541767 0.278797 +0.561209 0.278797 +0.542039 0.278797 +0.561052 0.278797 +0.542195 0.278797 +0.561003 0.278797 +0.542244 0.278797 +0.709902 0.147992 +0.688212 0.147992 +0.712833 0.147992 +0.688746 0.147992 +0.712300 0.147992 +0.689291 0.147992 +0.711755 0.147992 +0.689816 0.147992 +0.711230 0.147992 +0.690285 0.147992 +0.710761 0.147992 +0.690666 0.147992 +0.710380 0.147992 +0.690938 0.147992 +0.710108 0.147992 +0.691094 0.147992 +0.709951 0.147992 +0.691143 0.147992 +0.709902 0.147992 +0.691143 0.147992 +0.664764 0.278797 +0.683523 0.278797 +0.686454 0.278797 +0.661833 0.278797 +0.685920 0.278797 +0.662366 0.278797 +0.685375 0.278797 +0.662911 0.278797 +0.684850 0.278797 +0.663436 0.278797 +0.684381 0.278797 +0.663905 0.278797 +0.684000 0.278797 +0.664286 0.278797 +0.683728 0.278797 +0.664558 0.278797 +0.683572 0.278797 +0.664715 0.278797 +0.683523 0.278797 +0.664764 0.278797 +0.958664 0.197269 +0.960436 0.210142 +0.964613 0.210231 +0.967363 0.210231 +0.964613 0.210142 +0.886060 0.133764 +0.861146 0.133764 +0.861146 0.140534 +0.900548 0.135037 +0.886060 0.140534 +0.915348 0.139102 +0.899280 0.141692 +0.929618 0.146135 +0.912783 0.145389 +0.942441 0.155980 +0.925805 0.151785 +0.953001 0.168128 +0.937516 0.160737 +0.960749 0.181802 +0.947176 0.171787 +0.965488 0.196114 +0.954286 0.184232 +0.364621 0.140534 +0.364621 0.133764 +0.318310 0.133764 +0.318310 0.140534 +0.311861 0.136231 +0.311861 0.136231 +0.318310 0.136231 +0.318310 0.136231 +0.487140 0.140534 +0.487140 0.133764 +0.440829 0.133764 +0.440829 0.140534 +0.440829 0.136231 +0.434381 0.136231 +0.434381 0.136231 +0.440829 0.136231 +0.609659 0.140534 +0.609659 0.133764 +0.546348 0.133764 +0.546348 0.140534 +0.539900 0.136231 +0.539900 0.136231 +0.546348 0.136231 +0.546348 0.136231 +0.732179 0.140534 +0.732179 0.133764 +0.668867 0.133764 +0.668867 0.140534 +0.668867 0.136231 +0.662419 0.136231 +0.662419 0.136231 +0.668867 0.136231 +0.016115 0.210142 +0.020293 0.210142 +0.015246 0.196090 +0.013367 0.210203 +0.016115 0.210203 +0.119582 0.140534 +0.119582 0.133764 +0.094668 0.140534 +0.094668 0.133764 +0.081448 0.141691 +0.080183 0.135036 +0.067945 0.145389 +0.065386 0.139100 +0.054924 0.151785 +0.051119 0.146130 +0.043213 0.160737 +0.038298 0.155970 +0.033552 0.171786 +0.027738 0.168113 +0.026442 0.184232 +0.019988 0.181782 +0.022065 0.197269 +0.242102 0.140534 +0.242102 0.133764 +0.126031 0.133764 +0.126031 0.140534 +0.119582 0.136231 +0.119582 0.136231 +0.126031 0.136231 +0.126031 0.136231 +0.248550 0.140534 +0.311861 0.140534 +0.311861 0.133764 +0.248550 0.133764 +0.242102 0.136231 +0.242102 0.136231 +0.248550 0.136231 +0.248550 0.136231 +0.371069 0.140534 +0.434381 0.140534 +0.434381 0.133764 +0.371069 0.133764 +0.364621 0.136231 +0.364621 0.136231 +0.371069 0.136231 +0.371069 0.136231 +0.493589 0.133764 +0.493589 0.140534 +0.539900 0.140534 +0.539900 0.133764 +0.487140 0.136231 +0.487140 0.136231 +0.493589 0.136231 +0.493589 0.136231 +0.616108 0.133764 +0.616108 0.140534 +0.662419 0.140534 +0.662419 0.133764 +0.609659 0.136231 +0.609659 0.136231 +0.616108 0.136231 +0.616108 0.136231 +0.854698 0.140534 +0.854698 0.133764 +0.738627 0.133764 +0.738627 0.140534 +0.732179 0.136231 +0.732179 0.136231 +0.738627 0.136231 +0.738627 0.136231 +0.861146 0.136231 +0.854698 0.136231 +0.854698 0.136231 +0.861146 0.136231 +0.683109 0.163918 +0.755920 0.214542 +0.609366 0.214542 +0.224808 0.212247 +0.225860 0.221485 +0.224808 0.214542 +0.609073 0.213395 +0.609396 0.214855 +0.754869 0.205304 +0.755920 0.212247 +0.608315 0.205304 +0.609366 0.212247 +0.755627 0.213395 +0.755950 0.214855 +0.225101 0.213395 +0.224779 0.211934 +0.224685 0.211614 +0.756044 0.215176 +0.609396 0.211934 +0.755950 0.211934 +0.609490 0.215176 +0.224779 0.214855 +0.224685 0.215176 +0.609653 0.215484 +0.756044 0.211614 +0.609490 0.211614 +0.756207 0.215484 +0.224522 0.211305 +0.224293 0.211030 +0.756435 0.215759 +0.609653 0.211305 +0.756207 0.211305 +0.609881 0.215759 +0.224522 0.215484 +0.756435 0.211030 +0.609881 0.211030 +0.610162 0.215983 +0.756717 0.215983 +0.224293 0.215759 +0.224012 0.210807 +0.742321 0.181955 +0.752186 0.179243 +0.752948 0.180160 +0.525615 0.189064 +0.522195 0.178215 +0.521651 0.179243 +0.531516 0.244834 +0.521651 0.247546 +0.520889 0.246629 +0.748222 0.237725 +0.751642 0.248574 +0.752186 0.247546 +0.238408 0.244834 +0.228542 0.247546 +0.227781 0.246629 +0.232507 0.189064 +0.229086 0.178215 +0.228542 0.179243 +0.227781 0.180160 +0.226844 0.245884 +0.752948 0.246629 +0.519952 0.245884 +0.753885 0.180906 +0.520889 0.180160 +0.756717 0.210807 +0.610162 0.210807 +0.610477 0.216142 +0.757032 0.216142 +0.224012 0.215983 +0.223697 0.210647 +0.169461 0.208388 +0.213084 0.214542 +0.621091 0.212247 +0.767645 0.212247 +0.312775 0.197028 +0.335007 0.194490 +0.333511 0.191664 +0.334666 0.238427 +0.315206 0.221485 +0.335419 0.235864 +0.213113 0.214855 +0.385257 0.178215 +0.363489 0.180049 +0.362334 0.243438 +0.384943 0.249642 +0.213084 0.212247 +0.384943 0.177148 +0.685695 0.175427 +0.651574 0.213395 +0.539141 0.175427 +0.538787 0.251347 +0.651672 0.214439 +0.685341 0.251347 +0.811322 0.218715 +0.767645 0.214542 +0.295033 0.251363 +0.384845 0.250686 +0.295388 0.175442 +0.810846 0.213395 +0.767615 0.211934 +0.308559 0.189064 +0.332648 0.188727 +0.757032 0.210647 +0.664764 0.213395 +0.663200 0.212351 +0.662887 0.211283 +0.662343 0.210255 +0.661581 0.209338 +0.660644 0.208593 +0.621061 0.211934 +0.610477 0.210647 +0.610805 0.216235 +0.621091 0.214542 +0.663298 0.213395 +0.665522 0.221485 +0.663200 0.214439 +0.662887 0.215507 +0.662343 0.216534 +0.661581 0.217451 +0.757359 0.216235 +0.223697 0.216142 +0.312775 0.229761 +0.334431 0.240933 +0.223370 0.210555 +0.754935 0.181438 +0.751642 0.178215 +0.522508 0.177148 +0.519952 0.180906 +0.518902 0.245351 +0.522195 0.248574 +0.751328 0.249642 +0.753885 0.245884 +0.225794 0.245351 +0.229086 0.248574 +0.229400 0.177148 +0.226844 0.180905 +0.362569 0.240933 +0.364352 0.182986 +0.385801 0.179243 +0.685341 0.175442 +0.538787 0.175442 +0.538429 0.251403 +0.684983 0.251403 +0.295388 0.251347 +0.385257 0.248574 +0.295745 0.175386 +0.839570 0.264168 +0.839570 0.243877 +0.146509 0.242990 +0.141158 0.243876 +0.336724 0.233398 +0.337101 0.197013 +0.767615 0.214855 +0.213207 0.215176 +0.141745 0.162621 +0.141745 0.182965 +0.833681 0.183942 +0.838984 0.182965 +0.767521 0.211614 +0.213113 0.211934 +0.334666 0.243438 +0.332379 0.185857 +0.678070 0.181955 +0.684983 0.175386 +0.684645 0.175260 +0.684346 0.175073 +0.651672 0.212351 +0.620967 0.211614 +0.531516 0.181955 +0.538429 0.175386 +0.538091 0.175260 +0.537792 0.175073 +0.537547 0.174841 +0.537361 0.174584 +0.522606 0.176104 +0.522508 0.175060 +0.522195 0.173992 +0.521651 0.172964 +0.533258 0.167629 +0.533123 0.167343 +0.520889 0.172047 +0.684101 0.174841 +0.538781 0.250610 +0.538091 0.251530 +0.537792 0.251717 +0.537547 0.251948 +0.537361 0.252205 +0.533258 0.259161 +0.522508 0.249642 +0.522606 0.250686 +0.522508 0.251730 +0.522195 0.252798 +0.533123 0.259446 +0.521651 0.253825 +0.533041 0.259770 +0.651985 0.215507 +0.621061 0.214855 +0.685335 0.250610 +0.684645 0.251530 +0.684346 0.251717 +0.684101 0.251948 +0.683915 0.252205 +0.302658 0.244834 +0.295745 0.251403 +0.296084 0.251530 +0.296383 0.251717 +0.296628 0.251948 +0.361581 0.246001 +0.384943 0.251730 +0.315206 0.205304 +0.339678 0.199062 +0.384845 0.176104 +0.361993 0.177223 +0.295394 0.176180 +0.296084 0.175260 +0.296383 0.175073 +0.296628 0.174841 +0.296813 0.174584 +0.315965 0.213395 +0.338552 0.231197 +0.342566 0.200526 +0.340801 0.229408 +0.345567 0.201370 +0.343321 0.228130 +0.348500 0.201634 +0.345940 0.227393 +0.348500 0.227164 +0.351433 0.201370 +0.351060 0.227393 +0.354434 0.200526 +0.168014 0.202977 +0.213207 0.211614 +0.757359 0.210555 +0.610805 0.210555 +0.611125 0.216263 +0.757679 0.216263 +0.223370 0.216235 +0.223050 0.210526 +0.811312 0.208133 +0.767358 0.211306 +0.533041 0.167020 +0.533025 0.260117 +0.812839 0.224142 +0.767521 0.215176 +0.169360 0.218969 +0.213371 0.215484 +0.748222 0.189064 +0.756026 0.181745 +0.757093 0.181841 +0.521399 0.197028 +0.518902 0.181438 +0.517811 0.181745 +0.525615 0.237725 +0.517811 0.245044 +0.516744 0.244949 +0.752437 0.229761 +0.754935 0.245352 +0.756026 0.245044 +0.232507 0.237725 +0.224702 0.245044 +0.223636 0.244949 +0.362334 0.238427 +0.385801 0.247546 +0.758159 0.181745 +0.516744 0.181841 +0.515677 0.245044 +0.757093 0.244949 +0.222569 0.245044 +0.386562 0.180160 +0.364621 0.185857 +0.384943 0.175060 +0.228291 0.197028 +0.225794 0.181438 +0.224702 0.181745 +0.223636 0.181841 +0.735056 0.176180 +0.751328 0.177148 +0.751231 0.176104 +0.751328 0.175060 +0.683915 0.174584 +0.679812 0.259161 +0.742321 0.244834 +0.751231 0.250686 +0.751328 0.251730 +0.751642 0.252798 +0.245672 0.250610 +0.229400 0.249642 +0.229498 0.250686 +0.229400 0.251730 +0.296813 0.252205 +0.300917 0.167629 +0.238408 0.181955 +0.229498 0.176104 +0.229400 0.175060 +0.229086 0.173992 +0.385257 0.252798 +0.302658 0.181955 +0.332648 0.182986 +0.301093 0.167213 +0.333511 0.180049 +0.301152 0.166768 +0.335007 0.177223 +0.301095 0.166330 +0.353679 0.228130 +0.357322 0.199062 +0.620804 0.211305 +0.519952 0.171302 +0.520889 0.254743 +0.620967 0.215176 +0.308559 0.237725 +0.335419 0.246001 +0.300917 0.259161 +0.336724 0.248467 +0.301093 0.259576 +0.338552 0.250669 +0.301152 0.260021 +0.757679 0.210526 +0.611125 0.210526 +0.651985 0.211283 +0.619332 0.216263 +0.652529 0.216534 +0.765886 0.216263 +0.213599 0.215759 +0.223050 0.216263 +0.214843 0.210526 +0.659594 0.208060 +0.533025 0.166673 +0.533082 0.260467 +0.660644 0.218197 +0.767358 0.215484 +0.213371 0.211305 +0.767130 0.211030 +0.360276 0.248467 +0.387500 0.180906 +0.386562 0.246629 +0.359899 0.174701 +0.385257 0.173992 +0.361581 0.235864 +0.385801 0.253825 +0.834191 0.242982 +0.151884 0.241091 +0.147077 0.183950 +0.828373 0.185919 +0.751642 0.173992 +0.752186 0.253825 +0.229086 0.252798 +0.340801 0.252457 +0.301095 0.260459 +0.364352 0.188727 +0.300917 0.165907 +0.228542 0.172964 +0.165478 0.197739 +0.213599 0.211030 +0.759251 0.181438 +0.515677 0.181745 +0.514586 0.245351 +0.758159 0.245044 +0.815458 0.229385 +0.767130 0.215759 +0.221478 0.245351 +0.337101 0.174701 +0.222569 0.181745 +0.812793 0.202767 +0.766848 0.210807 +0.620575 0.211030 +0.620804 0.215484 +0.167809 0.224352 +0.213880 0.215983 +0.356199 0.229408 +0.359899 0.197013 +0.388550 0.181438 +0.686026 0.175346 +0.685335 0.176180 +0.686318 0.175214 +0.688348 0.174067 +0.688707 0.173799 +0.688992 0.173437 +0.689170 0.173014 +0.689228 0.172577 +0.689168 0.172131 +0.688992 0.171716 +0.684889 0.164760 +0.693472 0.172054 +0.539472 0.175346 +0.538781 0.176180 +0.539764 0.175214 +0.541794 0.174067 +0.542153 0.173799 +0.542438 0.173437 +0.542616 0.173014 +0.542674 0.172577 +0.542614 0.172131 +0.542438 0.171716 +0.538334 0.164760 +0.546918 0.172054 +0.539141 0.251363 +0.546918 0.254735 +0.539472 0.251443 +0.539764 0.251575 +0.541794 0.252722 +0.542153 0.252990 +0.542438 0.253352 +0.542616 0.253775 +0.542674 0.254213 +0.542614 0.254658 +0.542438 0.255074 +0.555374 0.257115 +0.685695 0.251363 +0.693472 0.254735 +0.686026 0.251443 +0.686318 0.251575 +0.688348 0.252722 +0.688707 0.252990 +0.688992 0.253352 +0.689170 0.253775 +0.689228 0.254213 +0.689168 0.254658 +0.688992 0.255074 +0.701928 0.257115 +0.294703 0.251443 +0.295394 0.250610 +0.294411 0.251575 +0.292380 0.252722 +0.292118 0.252904 +0.291881 0.253144 +0.291690 0.253436 +0.291561 0.253767 +0.291504 0.254118 +0.291520 0.254464 +0.291602 0.254788 +0.291737 0.255073 +0.295840 0.262029 +0.287256 0.254735 +0.295033 0.175426 +0.287256 0.172054 +0.294703 0.175346 +0.294411 0.175214 +0.292380 0.174067 +0.292118 0.173885 +0.291881 0.173646 +0.291690 0.173353 +0.291561 0.173022 +0.291504 0.172672 +0.291520 0.172325 +0.291602 0.172001 +0.291737 0.171716 +0.278800 0.169675 +0.652529 0.210255 +0.653291 0.217451 +0.752437 0.197028 +0.760301 0.180906 +0.765886 0.210526 +0.766206 0.210555 +0.761238 0.180160 +0.766533 0.210647 +0.761999 0.179243 +0.762543 0.178216 +0.762857 0.177148 +0.815348 0.197580 +0.762955 0.176104 +0.762857 0.175060 +0.818925 0.192875 +0.762543 0.173992 +0.665522 0.205304 +0.658503 0.207753 +0.657436 0.207658 +0.605883 0.197028 +0.518902 0.170769 +0.533082 0.166323 +0.519952 0.255488 +0.533211 0.260798 +0.608315 0.221485 +0.667953 0.229761 +0.659594 0.218729 +0.658503 0.219036 +0.754869 0.221485 +0.759251 0.245352 +0.766206 0.216235 +0.766533 0.216142 +0.760301 0.245884 +0.766848 0.215983 +0.761238 0.246629 +0.761999 0.247546 +0.762543 0.248574 +0.819123 0.234128 +0.762857 0.249642 +0.762955 0.250686 +0.823657 0.238086 +0.762857 0.251730 +0.762543 0.252798 +0.228291 0.229761 +0.220428 0.245884 +0.214843 0.216263 +0.214523 0.216235 +0.219491 0.246629 +0.214195 0.216142 +0.218729 0.247546 +0.218185 0.248574 +0.217871 0.249642 +0.165171 0.229543 +0.217774 0.250686 +0.217871 0.251730 +0.161505 0.234233 +0.218185 0.252798 +0.218729 0.253825 +0.387500 0.245884 +0.225860 0.205304 +0.221478 0.181438 +0.214523 0.210555 +0.214195 0.210647 +0.220428 0.180905 +0.213880 0.210807 +0.219491 0.180160 +0.218729 0.179243 +0.218185 0.178215 +0.161902 0.192981 +0.217871 0.177148 +0.217774 0.176104 +0.157460 0.188985 +0.217871 0.175060 +0.218185 0.173992 +0.761999 0.172964 +0.823353 0.188924 +0.761238 0.172047 +0.760301 0.171302 +0.152415 0.185947 +0.218729 0.172964 +0.219491 0.172047 +0.385801 0.172964 +0.156987 0.238147 +0.219491 0.254743 +0.220428 0.255488 +0.828785 0.241064 +0.761999 0.253825 +0.761238 0.254743 +0.358448 0.250669 +0.386562 0.254743 +0.357322 0.172651 +0.620294 0.210807 +0.620575 0.215759 +0.360276 0.233398 +0.300632 0.165545 +0.358448 0.231197 +0.388550 0.245351 +0.361993 0.194490 +0.389641 0.245044 +0.363489 0.191664 +0.389641 0.181745 +0.390707 0.181841 +0.390707 0.244949 +0.391774 0.181745 +0.391774 0.245044 +0.392865 0.181438 +0.392865 0.245351 +0.393915 0.180906 +0.393915 0.245884 +0.394853 0.180160 +0.752186 0.172964 +0.656369 0.207753 +0.619332 0.210526 +0.619652 0.216235 +0.657436 0.219132 +0.726919 0.172054 +0.752948 0.254743 +0.735056 0.250610 +0.228542 0.253825 +0.253810 0.254735 +0.300917 0.260882 +0.227781 0.172047 +0.245672 0.176180 +0.514586 0.181438 +0.518968 0.205304 +0.521399 0.229761 +0.513536 0.245884 +0.752948 0.172047 +0.753885 0.255488 +0.227781 0.254743 +0.343321 0.253735 +0.394853 0.246629 +0.395614 0.179243 +0.226844 0.171302 +0.684703 0.164503 +0.538149 0.164503 +0.533211 0.165991 +0.513536 0.180906 +0.512599 0.246629 +0.533403 0.261091 +0.538334 0.262029 +0.684888 0.262029 +0.296025 0.262286 +0.295840 0.164760 +0.386562 0.172047 +0.339678 0.172651 +0.653291 0.209338 +0.654228 0.218197 +0.517811 0.170462 +0.518902 0.256020 +0.387500 0.255488 +0.356199 0.252457 +0.760301 0.255488 +0.221478 0.256020 +0.220428 0.171302 +0.759251 0.170769 +0.672169 0.189064 +0.679812 0.167629 +0.678070 0.244834 +0.679677 0.259447 +0.679677 0.167343 +0.679595 0.259770 +0.619979 0.210647 +0.620294 0.215983 +0.354434 0.171187 +0.619652 0.210555 +0.601668 0.189064 +0.654228 0.208593 +0.655278 0.208060 +0.667953 0.197028 +0.679595 0.167020 +0.595766 0.181955 +0.679579 0.166673 +0.679636 0.166323 +0.588502 0.176180 +0.679765 0.165991 +0.679957 0.165699 +0.580365 0.172054 +0.680193 0.165459 +0.619979 0.216142 +0.605883 0.229761 +0.655278 0.218729 +0.656369 0.219036 +0.672169 0.237725 +0.679579 0.260117 +0.601668 0.237725 +0.679636 0.260467 +0.679765 0.260798 +0.595766 0.244834 +0.679957 0.261091 +0.680193 0.261330 +0.588502 0.250610 +0.680455 0.261512 +0.300273 0.165277 +0.533403 0.165699 +0.533639 0.261330 +0.300632 0.261244 +0.395614 0.247546 +0.396158 0.178215 +0.387500 0.171302 +0.684458 0.164272 +0.680455 0.165278 +0.537904 0.164272 +0.538149 0.262286 +0.682486 0.262659 +0.684703 0.262286 +0.296271 0.262518 +0.345940 0.254472 +0.296025 0.164503 +0.753885 0.171302 +0.512599 0.180160 +0.511837 0.247546 +0.754935 0.256020 +0.226844 0.255488 +0.225794 0.170769 +0.388550 0.256020 +0.342566 0.171187 +0.298242 0.164130 +0.516744 0.170367 +0.517811 0.256327 +0.701929 0.169675 +0.555374 0.169675 +0.563641 0.257857 +0.710195 0.257857 +0.278800 0.257115 +0.270533 0.168932 +0.221478 0.170769 +0.684159 0.164085 +0.537605 0.164085 +0.537904 0.262518 +0.684458 0.262518 +0.296569 0.262705 +0.296271 0.164272 +0.758159 0.170462 +0.759251 0.256020 +0.222569 0.256327 +0.300273 0.261512 +0.682486 0.164130 +0.571908 0.169675 +0.518210 0.213395 +0.518968 0.221485 +0.511837 0.179243 +0.511293 0.248574 +0.580365 0.254735 +0.682778 0.262791 +0.353679 0.253735 +0.718462 0.169675 +0.533639 0.165459 +0.533901 0.261512 +0.726919 0.254735 +0.262266 0.257115 +0.253810 0.172054 +0.224702 0.170462 +0.225794 0.256020 +0.756026 0.256327 +0.754935 0.170769 +0.297951 0.163998 +0.511293 0.178215 +0.396158 0.248574 +0.351433 0.170343 +0.510980 0.249642 +0.396472 0.177148 +0.388550 0.170769 +0.348500 0.254702 +0.298242 0.262659 +0.533901 0.165278 +0.515677 0.170462 +0.535932 0.262659 +0.516744 0.256423 +0.389641 0.256327 +0.345567 0.170343 +0.683821 0.163958 +0.682778 0.163998 +0.537267 0.163958 +0.537605 0.262705 +0.683109 0.262871 +0.684159 0.262705 +0.758159 0.256327 +0.223636 0.256423 +0.296908 0.262831 +0.296569 0.164085 +0.222569 0.170462 +0.757093 0.170367 +0.563641 0.168932 +0.536909 0.163902 +0.571908 0.257115 +0.537267 0.262831 +0.351060 0.254472 +0.297951 0.262791 +0.390707 0.256423 +0.535932 0.164130 +0.536224 0.262791 +0.756026 0.170462 +0.757093 0.256423 +0.224702 0.256327 +0.718462 0.257115 +0.683821 0.262831 +0.141158 0.264168 +0.683463 0.262887 +0.536909 0.262887 +0.536554 0.262871 +0.270533 0.257857 +0.297266 0.262887 +0.297620 0.262871 +0.391774 0.256327 +0.515677 0.256327 +0.392865 0.256020 +0.514586 0.256020 +0.393915 0.255488 +0.513536 0.255488 +0.394853 0.254743 +0.512599 0.254743 +0.395614 0.253825 +0.511837 0.253825 +0.396158 0.252798 +0.511293 0.252798 +0.396472 0.251730 +0.510980 0.251730 +0.396570 0.250686 +0.510882 0.250686 +0.396472 0.249642 +0.510980 0.177148 +0.396570 0.176104 +0.510882 0.176104 +0.396472 0.175060 +0.510980 0.175060 +0.396158 0.173992 +0.511293 0.173992 +0.395614 0.172964 +0.511837 0.172964 +0.394853 0.172047 +0.512599 0.172047 +0.393915 0.171302 +0.513536 0.171302 +0.392865 0.170769 +0.514586 0.170769 +0.391774 0.170462 +0.536224 0.163998 +0.390707 0.170367 +0.297620 0.163918 +0.223636 0.170367 +0.262266 0.169675 +0.296908 0.163958 +0.838984 0.162622 +0.297266 0.163902 +0.710195 0.168932 +0.683463 0.163902 +0.389641 0.170462 +0.348500 0.170080 +0.536554 0.163918 +0.556068 0.253448 +0.132746 0.207041 +0.337548 0.187840 +0.311460 0.205983 +0.338144 0.189869 +0.309232 0.228388 +0.339177 0.234968 +0.338144 0.236920 +0.847773 0.219874 +0.751122 0.220807 +0.844353 0.217414 +0.229607 0.205983 +0.136370 0.209402 +0.136420 0.208932 +0.668574 0.213395 +0.604568 0.220807 +0.605263 0.213395 +0.669269 0.205983 +0.309232 0.198401 +0.337362 0.185857 +0.305370 0.235684 +0.337548 0.238949 +0.844309 0.217857 +0.751817 0.213395 +0.228912 0.213395 +0.844487 0.216979 +0.136227 0.209844 +0.132417 0.207310 +0.848312 0.219480 +0.339177 0.191822 +0.340624 0.233225 +0.133143 0.206826 +0.337548 0.183873 +0.337362 0.240933 +0.669269 0.220807 +0.602340 0.228388 +0.604568 0.205983 +0.671496 0.198401 +0.136370 0.208462 +0.231834 0.198401 +0.748895 0.228388 +0.312155 0.213395 +0.340624 0.193564 +0.311460 0.220807 +0.342405 0.231809 +0.342405 0.194980 +0.344400 0.230798 +0.344400 0.195992 +0.346473 0.230214 +0.346473 0.196575 +0.348500 0.230032 +0.348500 0.196757 +0.350527 0.230214 +0.350527 0.196575 +0.352600 0.230798 +0.844405 0.218509 +0.847111 0.220108 +0.844707 0.216579 +0.751122 0.205983 +0.229607 0.220807 +0.136007 0.210233 +0.131389 0.208518 +0.849339 0.218271 +0.133594 0.206686 +0.136227 0.208021 +0.305370 0.191105 +0.338144 0.181844 +0.299964 0.242197 +0.337548 0.242916 +0.352600 0.195992 +0.354595 0.231809 +0.671496 0.228388 +0.598478 0.235684 +0.602340 0.198401 +0.675359 0.191105 +0.135733 0.210555 +0.844996 0.216235 +0.845475 0.215670 +0.845860 0.214990 +0.846111 0.214218 +0.846198 0.213395 +0.846111 0.212572 +0.845860 0.211800 +0.845475 0.211119 +0.844996 0.210555 +0.844722 0.210233 +0.844502 0.209844 +0.844359 0.209403 +0.844309 0.208932 +0.844359 0.208462 +0.844502 0.208021 +0.844722 0.207632 +0.135253 0.211119 +0.134868 0.211800 +0.134618 0.212572 +0.134531 0.213395 +0.134618 0.214218 +0.134868 0.214990 +0.135253 0.215670 +0.135733 0.216234 +0.136022 0.216578 +0.136241 0.216979 +0.136375 0.217414 +0.136420 0.217857 +0.136323 0.218509 +0.136024 0.219132 +0.339177 0.179892 +0.338144 0.244945 +0.085228 0.163469 +0.075571 0.166186 +0.130564 0.209977 +0.066279 0.170898 +0.057983 0.177492 +0.051245 0.185611 +0.046431 0.194705 +0.043654 0.204156 +0.130028 0.211631 +0.042788 0.213395 +0.043654 0.222633 +0.046431 0.232084 +0.051245 0.241178 +0.057983 0.249297 +0.066279 0.255892 +0.129841 0.213395 +0.075571 0.260603 +0.085228 0.263320 +0.094668 0.264168 +0.130028 0.215158 +0.130564 0.216813 +0.131389 0.218271 +0.132417 0.219480 +0.132956 0.219874 +0.895501 0.263320 +0.905157 0.260603 +0.850164 0.216813 +0.914450 0.255892 +0.922745 0.249297 +0.929484 0.241178 +0.934298 0.232084 +0.937074 0.222634 +0.850701 0.215158 +0.937940 0.213395 +0.937074 0.204156 +0.934298 0.194705 +0.929484 0.185611 +0.922745 0.177493 +0.914450 0.170898 +0.850887 0.213395 +0.905157 0.166186 +0.895501 0.163469 +0.886060 0.162622 +0.850701 0.211631 +0.850164 0.209977 +0.849339 0.208519 +0.848312 0.207310 +0.847982 0.207041 +0.847585 0.206826 +0.231834 0.228388 +0.135550 0.219640 +0.745032 0.235684 +0.844704 0.219132 +0.748895 0.198401 +0.844996 0.207310 +0.235696 0.191105 +0.136007 0.207632 +0.847134 0.206686 +0.134075 0.206637 +0.133617 0.220108 +0.846409 0.220139 +0.354595 0.194980 +0.356376 0.233225 +0.675359 0.235684 +0.593072 0.242198 +0.598478 0.191105 +0.680765 0.184592 +0.845325 0.207041 +0.135733 0.207310 +0.299964 0.184592 +0.340624 0.178149 +0.293309 0.247488 +0.339177 0.246898 +0.846654 0.206638 +0.134555 0.206686 +0.235696 0.235684 +0.134972 0.219977 +0.739626 0.242198 +0.845178 0.219641 +0.745032 0.191105 +0.241102 0.184592 +0.845722 0.206826 +0.135403 0.207041 +0.356376 0.193564 +0.357822 0.234968 +0.680765 0.242198 +0.586417 0.247488 +0.593072 0.184592 +0.687420 0.179301 +0.342405 0.176733 +0.340624 0.248640 +0.134320 0.220139 +0.241102 0.242197 +0.845756 0.219977 +0.732971 0.247488 +0.725516 0.251268 +0.247758 0.247488 +0.293309 0.179301 +0.285854 0.251268 +0.846173 0.206686 +0.739626 0.184592 +0.732971 0.179301 +0.135006 0.206826 +0.247758 0.179301 +0.255213 0.175521 +0.342405 0.250056 +0.344400 0.175722 +0.357822 0.191822 +0.358856 0.236920 +0.687420 0.247488 +0.578962 0.251268 +0.586417 0.179301 +0.694875 0.175521 +0.255213 0.251268 +0.717769 0.253448 +0.725516 0.175521 +0.262960 0.173341 +0.346473 0.175138 +0.358856 0.189869 +0.285854 0.175521 +0.359452 0.238949 +0.344400 0.251068 +0.278107 0.253448 +0.694875 0.251268 +0.571215 0.253448 +0.578962 0.175521 +0.702622 0.173341 +0.262960 0.253448 +0.886060 0.264168 +0.270533 0.254128 +0.710195 0.254128 +0.717769 0.173341 +0.094668 0.162621 +0.710195 0.172661 +0.270533 0.172661 +0.348500 0.174956 +0.346473 0.251651 +0.348500 0.251833 +0.350527 0.251651 +0.352600 0.251068 +0.354595 0.250056 +0.359452 0.187840 +0.702622 0.253448 +0.571215 0.173341 +0.563641 0.172661 +0.278107 0.173341 +0.350527 0.175138 +0.556068 0.173341 +0.352600 0.175722 +0.548321 0.175521 +0.354595 0.176733 +0.356376 0.178149 +0.540866 0.179301 +0.357822 0.179892 +0.534211 0.184592 +0.358856 0.181844 +0.528804 0.191105 +0.359452 0.183873 +0.524942 0.198401 +0.359638 0.185857 +0.522715 0.205983 +0.522020 0.213395 +0.359638 0.240933 +0.522715 0.220807 +0.359452 0.242916 +0.358856 0.244945 +0.524942 0.228388 +0.357822 0.246898 +0.528804 0.235684 +0.356376 0.248640 +0.534211 0.242198 +0.540866 0.247488 +0.548321 0.251268 +0.563641 0.254128 +0.845236 0.219571 +0.856529 0.235003 +0.848247 0.219416 +0.860747 0.231650 +0.849264 0.218220 +0.864174 0.227522 +0.850079 0.216777 +0.866622 0.222898 +0.850611 0.215140 +0.868033 0.218093 +0.850795 0.213395 +0.868474 0.213395 +0.850611 0.211650 +0.868033 0.208697 +0.850079 0.210013 +0.866622 0.203892 +0.849264 0.208570 +0.864174 0.199268 +0.848247 0.207373 +0.860747 0.195140 +0.847930 0.207116 +0.851804 0.237399 +0.847729 0.219795 +0.856529 0.191786 +0.847549 0.206909 +0.847115 0.206774 +0.851804 0.189391 +0.846654 0.206728 +0.846894 0.238781 +0.847093 0.220020 +0.842094 0.239212 +0.846418 0.220050 +0.846894 0.188009 +0.846192 0.206774 +0.845759 0.206909 +0.842094 0.187578 +0.845377 0.207116 +0.837294 0.238781 +0.845792 0.219894 +0.832384 0.237399 +0.837294 0.188009 +0.845061 0.207373 +0.832384 0.189391 +0.844798 0.207683 +0.827659 0.191786 +0.844586 0.208057 +0.823441 0.195139 +0.844449 0.208481 +0.820014 0.199268 +0.844401 0.208932 +0.817567 0.203892 +0.816155 0.208697 +0.844449 0.209384 +0.815714 0.213395 +0.844586 0.209808 +0.816155 0.218092 +0.817567 0.222898 +0.844798 0.210182 +0.820014 0.227522 +0.845061 0.210491 +0.823441 0.231650 +0.845551 0.211068 +0.845945 0.211764 +0.846201 0.212553 +0.846290 0.213395 +0.846201 0.214236 +0.845945 0.215026 +0.845551 0.215721 +0.845061 0.216298 +0.844783 0.216629 +0.844572 0.217013 +0.844443 0.217431 +0.844401 0.217857 +0.844494 0.218483 +0.844781 0.219082 +0.827659 0.235003 +0.109608 0.202068 +0.044116 0.201979 +0.042850 0.210925 +0.046293 0.210925 +0.047019 0.207728 +0.135524 0.182965 +0.135524 0.162621 +0.130319 0.183916 +0.125112 0.185825 +0.120177 0.188718 +0.115799 0.192519 +0.048384 0.204547 +0.047190 0.192927 +0.050400 0.201565 +0.084140 0.209353 +0.084571 0.212600 +0.107401 0.212430 +0.083071 0.206066 +0.053009 0.198966 +0.052156 0.184292 +0.056081 0.196908 +0.058887 0.176630 +0.059435 0.195489 +0.062873 0.194731 +0.067035 0.170423 +0.112221 0.197053 +0.081334 0.202919 +0.076089 0.165989 +0.069534 0.195023 +0.085477 0.163425 +0.072890 0.196078 +0.094668 0.162621 +0.076101 0.197785 +0.078973 0.200103 +0.167630 0.202470 +0.143998 0.243345 +0.140979 0.243714 +0.141158 0.243876 +0.141745 0.182965 +0.141565 0.183124 +0.144611 0.183377 +0.144577 0.183549 +0.150411 0.185068 +0.150344 0.185230 +0.155981 0.187957 +0.160939 0.191976 +0.155881 0.188103 +0.160811 0.192098 +0.164950 0.196903 +0.164799 0.196998 +0.167797 0.202407 +0.149797 0.241771 +0.144029 0.243517 +0.155389 0.239001 +0.149861 0.241935 +0.160395 0.235098 +0.155486 0.239149 +0.160520 0.235223 +0.164477 0.230274 +0.164626 0.230371 +0.167413 0.224854 +0.167579 0.224920 +0.169130 0.219210 +0.169703 0.213682 +0.169306 0.219244 +0.169882 0.213684 +0.169237 0.208145 +0.169414 0.208115 +0.115926 0.192642 +0.107401 0.212430 +0.107575 0.212604 +0.108016 0.207282 +0.108024 0.208186 +0.109608 0.202068 +0.109715 0.202280 +0.112221 0.197053 +0.115799 0.192519 +0.112447 0.197033 +0.131231 0.183864 +0.135703 0.183124 +0.135524 0.182965 +0.125326 0.185919 +0.130319 0.183916 +0.120164 0.188945 +0.125112 0.185825 +0.120177 0.188718 +0.267895 0.147992 +0.267895 0.140534 +0.565693 0.147992 +0.565693 0.140534 +0.562762 0.140534 +0.593245 0.147992 +0.593245 0.140534 +0.590314 0.140534 +0.141768 0.149713 +0.838961 0.149713 +0.838961 0.147992 +0.295447 0.147992 +0.295447 0.140534 +0.292516 0.140534 +0.390414 0.140534 +0.387483 0.140534 +0.390414 0.147992 +0.417967 0.140534 +0.415036 0.140534 +0.417967 0.147992 +0.688212 0.140534 +0.685281 0.140534 +0.688212 0.147992 +0.715765 0.140534 +0.712833 0.140534 +0.715765 0.147992 +0.712833 0.147992 +0.685281 0.147992 +0.590314 0.147992 +0.562762 0.147992 +0.415036 0.147992 +0.387483 0.147992 +0.292516 0.147992 +0.264964 0.147992 +0.141768 0.147992 +0.264964 0.140534 +0.135501 0.147992 +0.029411 0.199295 +0.027888 0.210902 +0.029648 0.210902 +0.033291 0.187523 +0.031141 0.199608 +0.039648 0.176272 +0.034926 0.188157 +0.048322 0.166275 +0.041120 0.177214 +0.058861 0.158173 +0.049566 0.167492 +0.070591 0.152384 +0.059823 0.159613 +0.082758 0.149039 +0.071238 0.153984 +0.094668 0.147992 +0.083078 0.150731 +0.094668 0.149713 +0.135501 0.149713 +0.838961 0.149713 +0.141768 0.149713 +0.141745 0.162621 +0.838984 0.162622 +0.141750 0.156037 +0.838978 0.156037 +0.094668 0.156037 +0.135501 0.149713 +0.094668 0.149713 +0.135518 0.156037 +0.094668 0.150193 +0.094668 0.162621 +0.135524 0.162621 +0.094668 0.162102 +0.838961 0.149713 +0.838961 0.149713 +0.141768 0.149713 +0.141768 0.149713 +0.094668 0.149713 +0.094668 0.149713 +0.135501 0.149713 +0.135501 0.149713 +0.081653 0.223390 +0.046293 0.215865 +0.042850 0.215865 +0.048204 0.221904 +0.050018 0.224746 +0.044116 0.224810 +0.052358 0.227264 +0.055124 0.229329 +0.047190 0.233862 +0.058173 0.230852 +0.094668 0.264168 +0.136111 0.264168 +0.136111 0.243876 +0.126160 0.241434 +0.121397 0.238903 +0.117091 0.235547 +0.064486 0.232196 +0.052156 0.242497 +0.110636 0.226974 +0.107651 0.217368 +0.084115 0.217544 +0.058887 0.250160 +0.070897 0.231418 +0.067035 0.256366 +0.074074 0.230171 +0.076089 0.260800 +0.077020 0.228359 +0.085477 0.263365 +0.079584 0.226058 +0.113454 0.231504 +0.686454 0.286256 +0.689385 0.286256 +0.658901 0.286256 +0.661833 0.286256 +0.658901 0.278797 +0.536382 0.278797 +0.536382 0.286256 +0.539313 0.286256 +0.441415 0.286256 +0.444346 0.286256 +0.441415 0.278797 +0.318896 0.286256 +0.321827 0.286256 +0.318896 0.278797 +0.839547 0.277076 +0.141181 0.277076 +0.141181 0.278797 +0.563934 0.286256 +0.566865 0.286256 +0.563934 0.278797 +0.413863 0.286256 +0.416794 0.286256 +0.413863 0.278797 +0.291344 0.286256 +0.294275 0.286256 +0.291344 0.278797 +0.294275 0.278797 +0.321827 0.278797 +0.416794 0.278797 +0.444346 0.278797 +0.539313 0.278797 +0.566865 0.278797 +0.661833 0.278797 +0.689385 0.278797 +0.839547 0.278797 +0.686454 0.278797 +0.094668 0.278797 +0.029648 0.215887 +0.027888 0.215887 +0.031141 0.227181 +0.029411 0.227495 +0.034926 0.238633 +0.033291 0.239266 +0.041120 0.249575 +0.039648 0.250517 +0.049566 0.259297 +0.048322 0.260514 +0.059823 0.267176 +0.058861 0.268617 +0.071238 0.272805 +0.070591 0.274405 +0.083078 0.276058 +0.082758 0.277750 +0.094668 0.277076 +0.136088 0.278797 +0.136088 0.277076 +0.141182 0.277076 +0.839547 0.277076 +0.839570 0.264168 +0.141158 0.264168 +0.839564 0.270752 +0.141164 0.270752 +0.094668 0.276596 +0.094668 0.277076 +0.136105 0.270752 +0.136111 0.264168 +0.094668 0.264168 +0.094668 0.264687 +0.136087 0.277076 +0.094668 0.270752 +0.141182 0.277076 +0.839547 0.277076 +0.839547 0.277076 +0.141182 0.277076 +0.136088 0.277076 +0.094668 0.277076 +0.094668 0.277076 +0.136088 0.277076 +0.108217 0.220402 +0.108392 0.220362 +0.107808 0.217192 +0.107651 0.217368 +0.136111 0.243876 +0.136290 0.243714 +0.132993 0.243474 +0.133025 0.243301 +0.126939 0.241754 +0.127006 0.241591 +0.121573 0.239016 +0.117094 0.235549 +0.121670 0.238869 +0.113334 0.231344 +0.117217 0.235422 +0.110273 0.226234 +0.113479 0.231241 +0.110436 0.226161 +0.036118 0.215870 +0.029648 0.215887 +0.041121 0.249575 +0.034926 0.238633 +0.031141 0.227181 +0.042850 0.215865 +0.044116 0.224810 +0.047190 0.233862 +0.052156 0.242497 +0.058887 0.250160 +0.067035 0.256366 +0.076089 0.260800 +0.085477 0.263365 +0.049566 0.259297 +0.059823 0.267176 +0.071238 0.272805 +0.094668 0.264687 +0.094668 0.264168 +0.083078 0.276058 +0.094668 0.277076 +0.094668 0.276596 +0.094668 0.270752 +0.084933 0.263815 +0.042200 0.250210 +0.049921 0.258939 +0.035933 0.239622 +0.031749 0.227552 +0.037550 0.226246 +0.043570 0.224892 +0.046968 0.234694 +0.052057 0.243294 +0.058328 0.250383 +0.065812 0.256237 +0.074791 0.260877 +0.059136 0.266147 +0.070193 0.271861 +0.082681 0.275479 +0.083786 0.269755 +0.041348 0.237204 +0.047038 0.246816 +0.054047 0.254740 +0.062412 0.261284 +0.072450 0.266471 +0.085477 0.163425 +0.031141 0.199608 +0.029648 0.210902 +0.059823 0.159613 +0.071238 0.153984 +0.083078 0.150731 +0.049566 0.167492 +0.041121 0.177214 +0.034926 0.188157 +0.036116 0.210919 +0.042850 0.210925 +0.044116 0.201979 +0.047190 0.192927 +0.052156 0.184292 +0.058887 0.176630 +0.067035 0.170423 +0.076089 0.165989 +0.094668 0.156037 +0.094668 0.149713 +0.094668 0.162621 +0.084933 0.162974 +0.049921 0.167850 +0.059136 0.160642 +0.070193 0.154928 +0.082681 0.151310 +0.042200 0.176579 +0.035933 0.187168 +0.031749 0.199238 +0.037550 0.200543 +0.043570 0.201897 +0.046968 0.192095 +0.052057 0.183496 +0.058328 0.176407 +0.065812 0.170553 +0.074791 0.165912 +0.083786 0.157034 +0.072450 0.160318 +0.062412 0.165505 +0.054047 0.172049 +0.047038 0.179973 +0.041348 0.189586 +0.082584 0.275968 +0.094668 0.277076 +0.029648 0.215887 +0.029648 0.215887 +0.031252 0.227661 +0.035468 0.239827 +0.031252 0.227661 +0.041784 0.250499 +0.035468 0.239827 +0.041784 0.250499 +0.049566 0.259297 +0.058854 0.266563 +0.049566 0.259297 +0.058854 0.266563 +0.069998 0.272322 +0.082584 0.275968 +0.069998 0.272322 +0.094668 0.277076 +0.049566 0.167492 +0.031252 0.199128 +0.029648 0.210902 +0.029648 0.210902 +0.035468 0.186963 +0.031252 0.199128 +0.041784 0.176290 +0.035468 0.186963 +0.094668 0.149713 +0.094668 0.149713 +0.082584 0.150821 +0.082584 0.150821 +0.069998 0.154467 +0.069998 0.154467 +0.058854 0.160227 +0.058854 0.160227 +0.049566 0.167492 +0.041784 0.176290 +0.868507 0.197053 +0.934436 0.210925 +0.937879 0.210925 +0.933710 0.207728 +0.932345 0.204548 +0.886060 0.162622 +0.845204 0.162622 +0.845204 0.182965 +0.850410 0.183916 +0.855617 0.185825 +0.860551 0.188718 +0.930329 0.201565 +0.936612 0.201979 +0.927719 0.198966 +0.873327 0.212430 +0.896157 0.212601 +0.871120 0.202068 +0.896589 0.209353 +0.924648 0.196908 +0.933539 0.192928 +0.921294 0.195489 +0.928572 0.184293 +0.917855 0.194732 +0.911194 0.195023 +0.921842 0.176630 +0.864930 0.192519 +0.897658 0.206066 +0.913694 0.170423 +0.907839 0.196078 +0.904639 0.165989 +0.904628 0.197785 +0.895252 0.163425 +0.901756 0.200103 +0.899394 0.202919 +0.886060 0.147992 +0.845227 0.147992 +0.951081 0.210902 +0.952840 0.210902 +0.949587 0.199608 +0.951317 0.199295 +0.945802 0.188157 +0.947438 0.187523 +0.939608 0.177214 +0.941081 0.176272 +0.931162 0.167492 +0.932406 0.166275 +0.920906 0.159614 +0.921868 0.158173 +0.909490 0.153985 +0.910138 0.152384 +0.897650 0.150731 +0.897970 0.149039 +0.886060 0.149713 +0.845227 0.149713 +0.886060 0.150212 +0.886060 0.149713 +0.845204 0.162622 +0.886060 0.162622 +0.845210 0.156037 +0.886060 0.162082 +0.886060 0.156037 +0.845227 0.149713 +0.845227 0.149713 +0.886060 0.149713 +0.886060 0.149713 +0.845227 0.149713 +0.872881 0.208156 +0.872704 0.208186 +0.873153 0.212604 +0.873327 0.212430 +0.845204 0.182965 +0.845025 0.183124 +0.849540 0.183694 +0.855480 0.185761 +0.849498 0.183864 +0.855403 0.185919 +0.860671 0.188804 +0.860565 0.188945 +0.864933 0.192523 +0.868433 0.196939 +0.864803 0.192643 +0.868282 0.197033 +0.871180 0.202216 +0.871013 0.202280 +0.901145 0.226059 +0.936612 0.224811 +0.937879 0.215865 +0.934436 0.215865 +0.932524 0.221905 +0.933539 0.233862 +0.930711 0.224746 +0.928370 0.227265 +0.928572 0.242497 +0.925605 0.229330 +0.844618 0.243877 +0.844618 0.264168 +0.854569 0.241434 +0.859332 0.238903 +0.863637 0.235547 +0.867274 0.231505 +0.922556 0.230853 +0.921842 0.250160 +0.896613 0.217544 +0.873078 0.217368 +0.899076 0.223390 +0.913694 0.256366 +0.916243 0.232196 +0.904639 0.260801 +0.909831 0.231418 +0.895252 0.263365 +0.906654 0.230171 +0.886060 0.264168 +0.903709 0.228360 +0.870093 0.226974 +0.886060 0.277076 +0.844641 0.277076 +0.951317 0.227495 +0.952840 0.215887 +0.951081 0.215887 +0.947438 0.239267 +0.949587 0.227181 +0.941081 0.250518 +0.945802 0.238633 +0.932406 0.260515 +0.939608 0.249575 +0.921868 0.268617 +0.931162 0.259297 +0.910138 0.274405 +0.920906 0.267176 +0.897970 0.277751 +0.909490 0.272805 +0.886060 0.278798 +0.897650 0.276058 +0.844641 0.278797 +0.886060 0.270752 +0.844641 0.277076 +0.886060 0.277076 +0.844624 0.270752 +0.886060 0.276578 +0.886060 0.264168 +0.844618 0.264168 +0.886060 0.264707 +0.844641 0.277076 +0.844641 0.277076 +0.886060 0.277076 +0.886060 0.277076 +0.863635 0.235550 +0.847704 0.243302 +0.844439 0.243715 +0.844618 0.243877 +0.873078 0.217368 +0.872920 0.217192 +0.872511 0.220402 +0.872337 0.220362 +0.870455 0.226234 +0.870293 0.226161 +0.867394 0.231344 +0.847736 0.243474 +0.853723 0.241591 +0.853790 0.241754 +0.859058 0.238869 +0.859156 0.239016 +0.863511 0.235423 +0.867249 0.231241 +0.873153 0.212604 +0.896330 0.212777 +0.896157 0.212601 +0.873327 0.212430 +0.873078 0.217368 +0.896613 0.217544 +0.896757 0.217370 +0.872920 0.217192 +0.949587 0.227182 +0.951081 0.215888 +0.933260 0.234471 +0.928223 0.242980 +0.922019 0.249994 +0.914613 0.255786 +0.905728 0.260378 +0.895693 0.263285 +0.886060 0.264168 +0.886060 0.270752 +0.886060 0.277076 +0.897650 0.276058 +0.909490 0.272805 +0.920905 0.267176 +0.931162 0.259297 +0.939608 0.249576 +0.945802 0.238633 +0.944613 0.215871 +0.937879 0.215865 +0.936621 0.224771 +0.937159 0.224892 +0.933761 0.234695 +0.928671 0.243294 +0.922401 0.250383 +0.914917 0.256237 +0.905937 0.260877 +0.895796 0.263815 +0.896942 0.269755 +0.898048 0.275479 +0.910535 0.271861 +0.921592 0.266148 +0.930807 0.258939 +0.938528 0.250210 +0.944796 0.239622 +0.948979 0.227552 +0.943178 0.226247 +0.908279 0.266471 +0.918316 0.261284 +0.926682 0.254740 +0.933691 0.246816 +0.939381 0.237204 +0.931162 0.259297 +0.949476 0.227661 +0.951081 0.215887 +0.951081 0.215888 +0.945260 0.239827 +0.949476 0.227661 +0.945260 0.239827 +0.938944 0.250499 +0.931162 0.259297 +0.938944 0.250499 +0.886060 0.277076 +0.886060 0.277076 +0.898145 0.275969 +0.898145 0.275969 +0.910731 0.272322 +0.921875 0.266563 +0.910731 0.272322 +0.921875 0.266563 +0.357688 0.187521 +0.357844 0.185857 +0.339292 0.187524 +0.339136 0.185857 +0.339156 0.185857 +0.339793 0.189230 +0.339312 0.187521 +0.340662 0.190871 +0.339812 0.189223 +0.340679 0.190861 +0.341879 0.192337 +0.341893 0.192323 +0.343376 0.193527 +0.343387 0.193510 +0.345053 0.194377 +0.346796 0.194868 +0.345061 0.194359 +0.346800 0.194848 +0.348500 0.195021 +0.348500 0.195001 +0.350204 0.194868 +0.350200 0.194848 +0.351947 0.194377 +0.353624 0.193527 +0.351939 0.194359 +0.353613 0.193510 +0.355121 0.192337 +0.356338 0.190871 +0.355107 0.192323 +0.357206 0.189230 +0.356321 0.190861 +0.357188 0.189223 +0.357708 0.187524 +0.357864 0.185857 +0.232514 0.220280 +0.231869 0.213395 +0.308542 0.220278 +0.309188 0.213395 +0.309198 0.213395 +0.308552 0.220280 +0.306474 0.227320 +0.306483 0.227323 +0.302887 0.234095 +0.302895 0.234101 +0.297866 0.240144 +0.297873 0.240151 +0.291685 0.245058 +0.291691 0.245066 +0.284762 0.248568 +0.284765 0.248577 +0.277567 0.250593 +0.277569 0.250602 +0.270533 0.251224 +0.270533 0.251234 +0.263499 0.250593 +0.263498 0.250602 +0.256305 0.248568 +0.256301 0.248577 +0.249381 0.245058 +0.243200 0.240144 +0.249376 0.245066 +0.243193 0.240151 +0.238180 0.234095 +0.238171 0.234101 +0.234593 0.227320 +0.234583 0.227323 +0.232524 0.220278 +0.231879 0.213395 +0.524977 0.213395 +0.524987 0.213395 +0.601650 0.220278 +0.602296 0.213395 +0.602306 0.213395 +0.601660 0.220280 +0.599582 0.227320 +0.599591 0.227323 +0.595995 0.234095 +0.596003 0.234101 +0.590974 0.240144 +0.584793 0.245058 +0.590981 0.240151 +0.577870 0.248568 +0.584799 0.245066 +0.577874 0.248577 +0.570675 0.250593 +0.570677 0.250603 +0.563641 0.251224 +0.556608 0.250593 +0.563641 0.251234 +0.556606 0.250603 +0.549413 0.248568 +0.549409 0.248577 +0.542489 0.245058 +0.542484 0.245066 +0.536308 0.240144 +0.536301 0.240151 +0.531288 0.234095 +0.531279 0.234101 +0.527701 0.227320 +0.527692 0.227323 +0.525632 0.220278 +0.525622 0.220280 +0.671531 0.213395 +0.671541 0.213395 +0.748205 0.220278 +0.748850 0.213395 +0.748860 0.213395 +0.748214 0.220280 +0.746136 0.227320 +0.746145 0.227323 +0.742549 0.234096 +0.742557 0.234101 +0.737528 0.240144 +0.737535 0.240151 +0.731348 0.245058 +0.731353 0.245066 +0.724424 0.248568 +0.724428 0.248577 +0.717229 0.250593 +0.717231 0.250603 +0.710195 0.251224 +0.710195 0.251234 +0.703162 0.250593 +0.703160 0.250603 +0.695967 0.248568 +0.695963 0.248577 +0.689043 0.245058 +0.682863 0.240144 +0.689038 0.245066 +0.682856 0.240151 +0.677842 0.234096 +0.677833 0.234101 +0.674255 0.227320 +0.674246 0.227323 +0.672186 0.220278 +0.672176 0.220280 +0.967370 0.216542 +0.967363 0.216542 +0.886060 0.133649 +0.886060 0.133764 +0.900887 0.134981 +0.900866 0.135094 +0.916054 0.139248 +0.916011 0.139355 +0.930649 0.146648 +0.930585 0.146745 +0.943678 0.157006 +0.943595 0.157088 +0.954262 0.169757 +0.954164 0.169820 +0.961823 0.184041 +0.961714 0.184083 +0.966184 0.198884 +0.967544 0.213395 +0.966068 0.198905 +0.967363 0.210231 +0.967369 0.210231 +0.966184 0.227906 +0.886060 0.293025 +0.886060 0.293140 +0.900866 0.291696 +0.916011 0.287434 +0.900887 0.291809 +0.916054 0.287541 +0.930585 0.280045 +0.930649 0.280141 +0.943595 0.269702 +0.943678 0.269783 +0.954164 0.256969 +0.961714 0.242706 +0.954262 0.257032 +0.961823 0.242749 +0.966068 0.227885 +0.854698 0.133756 +0.738627 0.133756 +0.738627 0.133764 +0.854698 0.133764 +0.668867 0.133764 +0.732179 0.133764 +0.668867 0.133756 +0.546348 0.133756 +0.546348 0.133764 +0.609659 0.133764 +0.493589 0.133764 +0.539900 0.133764 +0.493589 0.133756 +0.248550 0.133764 +0.311861 0.133764 +0.248550 0.133756 +0.126031 0.133764 +0.242102 0.133764 +0.126031 0.133756 +0.094668 0.133764 +0.119582 0.133764 +0.094668 0.133649 +0.886060 0.133649 +0.119582 0.133756 +0.242102 0.133756 +0.311861 0.133756 +0.861146 0.133764 +0.886060 0.133764 +0.861146 0.133756 +0.616108 0.133764 +0.662419 0.133764 +0.616108 0.133756 +0.440829 0.133764 +0.487140 0.133764 +0.440829 0.133756 +0.371069 0.133764 +0.434381 0.133764 +0.371069 0.133756 +0.318310 0.133764 +0.364621 0.133764 +0.318310 0.133756 +0.364621 0.133756 +0.434381 0.133756 +0.487140 0.133756 +0.539900 0.133756 +0.609659 0.133756 +0.662419 0.133756 +0.732179 0.133756 +0.013361 0.210203 +0.013367 0.210203 +0.094668 0.133764 +0.094668 0.133649 +0.077995 0.135454 +0.077971 0.135341 +0.062351 0.140315 +0.048563 0.147782 +0.062305 0.140209 +0.037133 0.157088 +0.048496 0.147687 +0.037050 0.157006 +0.027625 0.168273 +0.027528 0.168208 +0.019995 0.181767 +0.015028 0.197078 +0.019887 0.181721 +0.014913 0.197054 +0.013184 0.213395 +0.013296 0.213395 +0.094668 0.289829 +0.026466 0.257032 +0.022051 0.241530 +0.037050 0.269783 +0.029298 0.255220 +0.050079 0.280141 +0.039443 0.267442 +0.064674 0.287541 +0.051931 0.277370 +0.079841 0.291809 +0.065920 0.284462 +0.094668 0.293140 +0.080457 0.288553 +0.018905 0.242748 +0.017871 0.227303 +0.014545 0.227905 +0.016568 0.213395 +0.013184 0.213395 +0.017871 0.199486 +0.014545 0.198884 +0.022051 0.185260 +0.018905 0.184041 +0.029298 0.171569 +0.026466 0.169757 +0.039443 0.159347 +0.037050 0.157006 +0.051931 0.149419 +0.050079 0.146648 +0.065920 0.142327 +0.064674 0.139248 +0.080457 0.138236 +0.079841 0.134980 +0.094668 0.136960 +0.094668 0.133649 +0.886060 0.136960 +0.886060 0.133649 +0.900272 0.138237 +0.900887 0.134981 +0.914809 0.142327 +0.916054 0.139248 +0.928798 0.149420 +0.930649 0.146648 +0.941286 0.159348 +0.943678 0.157006 +0.951430 0.171569 +0.954262 0.169757 +0.958677 0.185260 +0.961823 0.184041 +0.962857 0.199487 +0.966184 0.198884 +0.964161 0.213395 +0.967544 0.213395 +0.962857 0.227303 +0.966184 0.227906 +0.958677 0.241530 +0.961823 0.242749 +0.951430 0.255220 +0.954262 0.257032 +0.941286 0.267442 +0.943678 0.269783 +0.928798 0.277370 +0.930649 0.280141 +0.914809 0.284462 +0.916054 0.287541 +0.900272 0.288553 +0.900887 0.291809 +0.886060 0.289829 +0.886060 0.293140 +0.886060 0.285230 +0.094668 0.278745 +0.886060 0.278745 +0.094668 0.280125 +0.886060 0.280125 +0.094668 0.282047 +0.886060 0.282047 +0.094668 0.283730 +0.094668 0.285230 +0.886060 0.283730 +0.886060 0.286565 +0.886060 0.287310 +0.094668 0.287310 +0.094668 0.286564 +0.047451 0.167185 +0.052580 0.162660 +0.058128 0.158697 +0.070089 0.152633 +0.082518 0.149136 +0.094668 0.146664 +0.094668 0.148045 +0.094668 0.144742 +0.094668 0.143059 +0.094668 0.141559 +0.094668 0.140225 +0.094668 0.139480 +0.080925 0.140713 +0.066867 0.144669 +0.053339 0.151528 +0.047064 0.156010 +0.041263 0.161129 +0.036033 0.166806 +0.031453 0.172948 +0.024445 0.186187 +0.020403 0.199945 +0.019903 0.213395 +0.019142 0.213395 +0.021267 0.213395 +0.022799 0.213395 +0.024519 0.213395 +0.026483 0.213395 +0.027893 0.213395 +0.029008 0.201503 +0.032582 0.189340 +0.038778 0.177634 +0.042828 0.172205 +0.046454 0.166209 +0.056032 0.158411 +0.067587 0.152153 +0.080696 0.148080 +0.080294 0.146199 +0.079942 0.144552 +0.079628 0.143083 +0.079348 0.141777 +0.064973 0.146244 +0.052304 0.153105 +0.041801 0.161656 +0.033064 0.171934 +0.026053 0.184333 +0.021490 0.198401 +0.022824 0.198675 +0.024324 0.198982 +0.026008 0.199327 +0.027930 0.199721 +0.032092 0.186891 +0.038486 0.175583 +0.065515 0.147468 +0.066123 0.148845 +0.066807 0.150390 +0.053076 0.154204 +0.053945 0.155440 +0.042765 0.162599 +0.043849 0.163660 +0.054919 0.156827 +0.045065 0.164850 +0.034188 0.172690 +0.035450 0.173540 +0.027304 0.184863 +0.028711 0.185459 +0.036867 0.174494 +0.030290 0.186127 +0.913861 0.282120 +0.927389 0.275261 +0.898211 0.149136 +0.886060 0.148045 +0.899803 0.286076 +0.886060 0.287310 +0.886060 0.286565 +0.886060 0.285230 +0.886060 0.283730 +0.886060 0.282047 +0.886060 0.280125 +0.886060 0.278745 +0.898211 0.277654 +0.910640 0.274156 +0.922600 0.268092 +0.933277 0.259604 +0.941950 0.249155 +0.948147 0.237450 +0.951720 0.225286 +0.952835 0.213395 +0.951720 0.201504 +0.948147 0.189340 +0.941951 0.177635 +0.933277 0.167185 +0.922600 0.158697 +0.910640 0.152633 +0.886060 0.146664 +0.886060 0.144743 +0.886060 0.143059 +0.886060 0.141559 +0.886060 0.140225 +0.886060 0.139480 +0.899803 0.140714 +0.913861 0.144669 +0.927389 0.151528 +0.939466 0.161129 +0.949276 0.172948 +0.956284 0.186187 +0.960326 0.199945 +0.961587 0.213395 +0.960326 0.226845 +0.956284 0.240603 +0.949276 0.253842 +0.939466 0.265661 +0.938927 0.265134 +0.926972 0.274637 +0.913581 0.281427 +0.899665 0.285343 +0.899417 0.284031 +0.899138 0.282556 +0.898825 0.280901 +0.898468 0.279011 +0.911159 0.275440 +0.923372 0.269248 +0.934275 0.260580 +0.943131 0.249910 +0.949458 0.237958 +0.953107 0.225537 +0.954246 0.213395 +0.953107 0.201252 +0.949458 0.188832 +0.943131 0.176879 +0.934275 0.166209 +0.923372 0.157542 +0.911159 0.151350 +0.898468 0.147778 +0.898825 0.145889 +0.899138 0.144233 +0.899417 0.142759 +0.899665 0.141447 +0.913581 0.145362 +0.926973 0.152152 +0.938927 0.161656 +0.948638 0.173356 +0.955576 0.186461 +0.959577 0.200081 +0.960825 0.213395 +0.959577 0.226709 +0.955576 0.240328 +0.948638 0.253434 +0.913079 0.280187 +0.912515 0.278792 +0.911882 0.277227 +0.926226 0.273521 +0.925388 0.272265 +0.937963 0.264190 +0.936879 0.263130 +0.924447 0.270856 +0.935663 0.261939 +0.947497 0.252704 +0.946214 0.251883 +0.954308 0.239837 +0.952883 0.239285 +0.944775 0.250962 +0.951284 0.238665 +0.958237 0.226466 +0.956729 0.226193 +0.959462 0.213395 +0.957929 0.213395 +0.955038 0.225887 +0.956209 0.213395 +0.958237 0.200323 +0.956729 0.200596 +0.954308 0.186953 +0.952883 0.187505 +0.955038 0.200903 +0.951284 0.188124 +0.947497 0.174086 +0.946214 0.174907 +0.937963 0.162599 +0.936879 0.163660 +0.944775 0.175828 +0.935663 0.164850 +0.926226 0.153269 +0.925388 0.154524 +0.913079 0.146603 +0.912515 0.147998 +0.924447 0.155933 +0.911882 0.149563 +0.886060 0.146664 +0.886060 0.148045 +0.094668 0.140225 +0.094668 0.139480 +0.886060 0.139480 +0.886060 0.140225 +0.094668 0.141559 +0.094668 0.143059 +0.886060 0.141559 +0.886060 0.143059 +0.094668 0.144742 +0.886060 0.144743 +0.094668 0.146664 +0.094668 0.148045 +0.886060 0.159868 +0.886060 0.162622 +0.094668 0.151897 +0.094668 0.149540 +0.886060 0.149540 +0.886060 0.151897 +0.094668 0.155768 +0.094668 0.159867 +0.886060 0.155768 +0.094668 0.162621 +0.929484 0.185611 +0.886060 0.151897 +0.886060 0.149540 +0.922745 0.177493 +0.914450 0.170898 +0.905157 0.166186 +0.895501 0.163469 +0.886060 0.162622 +0.886060 0.159868 +0.886060 0.155768 +0.897933 0.150606 +0.910077 0.154023 +0.921764 0.159949 +0.932197 0.168243 +0.940672 0.178453 +0.946726 0.189890 +0.950218 0.201776 +0.951307 0.213395 +0.950218 0.225014 +0.946726 0.236899 +0.940672 0.248337 +0.932197 0.258547 +0.921764 0.266841 +0.910077 0.272766 +0.897933 0.276184 +0.886060 0.277250 +0.886060 0.274892 +0.886060 0.271022 +0.886060 0.266922 +0.886060 0.264168 +0.895501 0.263320 +0.905157 0.260603 +0.914450 0.255892 +0.922745 0.249297 +0.929484 0.241178 +0.934298 0.232084 +0.937074 0.222634 +0.937940 0.213395 +0.937074 0.204156 +0.934298 0.194705 +0.936914 0.193692 +0.931839 0.184104 +0.924735 0.175545 +0.915990 0.168593 +0.906193 0.163626 +0.896013 0.160761 +0.896775 0.156730 +0.897495 0.152924 +0.909191 0.156215 +0.920446 0.161922 +0.930494 0.169909 +0.938656 0.179743 +0.944487 0.190758 +0.947850 0.202205 +0.948899 0.213395 +0.947850 0.224585 +0.944487 0.236032 +0.938656 0.247047 +0.930494 0.256880 +0.920446 0.264868 +0.909191 0.270575 +0.897495 0.273866 +0.896775 0.270059 +0.896013 0.266028 +0.906193 0.263164 +0.915990 0.258197 +0.924735 0.251244 +0.931839 0.242685 +0.936914 0.233098 +0.939841 0.223135 +0.940755 0.213395 +0.939841 0.203655 +0.907735 0.266976 +0.918282 0.261628 +0.927697 0.254143 +0.935345 0.244929 +0.940809 0.234607 +0.943960 0.223881 +0.944944 0.213395 +0.943960 0.202909 +0.940809 0.192183 +0.935345 0.181861 +0.927697 0.172646 +0.918282 0.165161 +0.907735 0.159814 +0.043654 0.204156 +0.042788 0.213395 +0.061968 0.173977 +0.066279 0.170898 +0.075571 0.166186 +0.085228 0.163469 +0.057983 0.177492 +0.054391 0.181392 +0.051245 0.185611 +0.046431 0.194705 +0.094668 0.159867 +0.094668 0.162621 +0.094668 0.155768 +0.094668 0.151897 +0.094668 0.149540 +0.082796 0.150606 +0.070651 0.154023 +0.058964 0.159948 +0.053543 0.163821 +0.048532 0.168242 +0.044014 0.173147 +0.040057 0.178453 +0.034002 0.189890 +0.030511 0.201775 +0.031830 0.213395 +0.029421 0.213395 +0.035785 0.213395 +0.039974 0.213395 +0.055994 0.175545 +0.063677 0.169290 +0.072945 0.164270 +0.083461 0.161003 +0.049602 0.183064 +0.044473 0.192135 +0.041135 0.202426 +0.082602 0.156991 +0.081792 0.153202 +0.069710 0.156956 +0.059062 0.162722 +0.050235 0.169909 +0.042891 0.178548 +0.036999 0.188969 +0.033163 0.200793 +0.037035 0.201586 +0.071281 0.160508 +0.061303 0.165912 +0.053032 0.172646 +0.046150 0.180741 +0.040629 0.190507 +0.886060 0.264168 +0.886060 0.274892 +0.886060 0.277250 +0.094668 0.277249 +0.094668 0.274892 +0.886060 0.271022 +0.094668 0.271021 +0.886060 0.266922 +0.094668 0.266922 +0.094668 0.264168 +0.094668 0.277249 +0.886060 0.277250 +0.886060 0.278745 +0.094668 0.278745 +0.886060 0.278481 +0.094668 0.278481 +0.886060 0.277961 +0.094668 0.277961 +0.886060 0.277474 +0.094668 0.277474 +0.047451 0.259604 +0.052580 0.264129 +0.058128 0.268092 +0.070089 0.274156 +0.082518 0.277654 +0.094668 0.278481 +0.094668 0.278745 +0.094668 0.277961 +0.094668 0.277474 +0.094668 0.277249 +0.082796 0.276183 +0.070651 0.272766 +0.058964 0.266841 +0.053543 0.262968 +0.048532 0.258547 +0.044014 0.253642 +0.040057 0.248337 +0.034002 0.236899 +0.030511 0.225014 +0.029192 0.213395 +0.029421 0.213395 +0.028694 0.213395 +0.028163 0.213395 +0.027893 0.213395 +0.029008 0.225286 +0.032582 0.237450 +0.038778 0.249155 +0.042828 0.254585 +0.047649 0.259411 +0.056990 0.267015 +0.068258 0.273118 +0.081043 0.277090 +0.081149 0.276591 +0.081250 0.276123 +0.068659 0.272211 +0.057562 0.266201 +0.048363 0.258712 +0.040710 0.249709 +0.034570 0.238849 +0.030573 0.226527 +0.030094 0.226625 +0.029584 0.226729 +0.033643 0.239241 +0.039878 0.250269 +0.034121 0.239039 +0.040307 0.249980 +0.048017 0.259050 +0.057285 0.266596 +0.068465 0.272650 +0.898211 0.277654 +0.886060 0.278745 +0.910640 0.274156 +0.922600 0.268092 +0.933277 0.259604 +0.941950 0.249155 +0.948147 0.237450 +0.951720 0.225286 +0.952835 0.213395 +0.951720 0.201504 +0.948147 0.189340 +0.941951 0.177635 +0.933277 0.167185 +0.922600 0.158697 +0.910640 0.152633 +0.898211 0.149136 +0.886060 0.148045 +0.886060 0.148308 +0.886060 0.148828 +0.886060 0.149316 +0.886060 0.149540 +0.897933 0.150606 +0.910077 0.154023 +0.921764 0.159949 +0.932197 0.168243 +0.940672 0.178453 +0.946726 0.189890 +0.950218 0.201776 +0.951307 0.213395 +0.950218 0.225014 +0.946726 0.236899 +0.940672 0.248337 +0.932197 0.258547 +0.921764 0.266841 +0.910077 0.272766 +0.897933 0.276184 +0.886060 0.277250 +0.886060 0.277474 +0.886060 0.277961 +0.886060 0.278481 +0.910537 0.273902 +0.898160 0.277385 +0.922447 0.267863 +0.933079 0.259411 +0.941716 0.249005 +0.947887 0.237349 +0.951445 0.225236 +0.952555 0.213395 +0.951445 0.201553 +0.947887 0.189441 +0.941716 0.177784 +0.933079 0.167379 +0.922447 0.158926 +0.910537 0.152888 +0.898160 0.149405 +0.898065 0.149906 +0.897976 0.150377 +0.910165 0.153807 +0.921894 0.159753 +0.932365 0.168078 +0.940871 0.178325 +0.946948 0.189804 +0.950452 0.201733 +0.951546 0.213395 +0.950452 0.225056 +0.946948 0.236985 +0.940871 0.248464 +0.932365 0.258712 +0.921894 0.267036 +0.910165 0.272983 +0.897976 0.276413 +0.898065 0.276884 +0.910345 0.273428 +0.922162 0.267437 +0.932711 0.259050 +0.941281 0.248726 +0.947403 0.237161 +0.950933 0.225144 +0.952035 0.213395 +0.950933 0.201646 +0.947403 0.189628 +0.941281 0.178063 +0.932711 0.167739 +0.922162 0.159353 +0.910345 0.153361 +0.886060 0.149540 +0.094668 0.149540 +0.094668 0.148308 +0.094668 0.148045 +0.886060 0.148045 +0.886060 0.148308 +0.094668 0.148828 +0.886060 0.148828 +0.094668 0.149315 +0.886060 0.149316 +0.886060 0.289408 +0.886060 0.289829 +0.094668 0.287538 +0.094668 0.287310 +0.886060 0.287310 +0.094668 0.287911 +0.886060 0.287538 +0.094668 0.288364 +0.886060 0.287911 +0.094668 0.288873 +0.886060 0.288364 +0.094668 0.289408 +0.886060 0.288873 +0.094668 0.289829 +0.017871 0.227303 +0.016568 0.213395 +0.045441 0.272735 +0.051931 0.277370 +0.065920 0.284462 +0.080457 0.288553 +0.039443 0.267442 +0.034034 0.261571 +0.029298 0.255220 +0.022051 0.241530 +0.094668 0.289408 +0.094668 0.289829 +0.094668 0.288873 +0.094668 0.288364 +0.094668 0.287911 +0.094668 0.287538 +0.094668 0.287310 +0.080925 0.286076 +0.066867 0.282120 +0.053339 0.275261 +0.047064 0.270779 +0.041263 0.265660 +0.036033 0.259983 +0.031453 0.253842 +0.024445 0.240602 +0.020403 0.226844 +0.018908 0.213395 +0.019142 0.213395 +0.018527 0.213395 +0.018064 0.213395 +0.017545 0.213395 +0.016998 0.213395 +0.039771 0.267120 +0.050677 0.276000 +0.063833 0.283124 +0.078760 0.287762 +0.030698 0.256447 +0.023418 0.243572 +0.018679 0.228964 +0.078872 0.287236 +0.078971 0.286773 +0.079060 0.286358 +0.079140 0.285985 +0.064570 0.281458 +0.051728 0.274504 +0.041083 0.265837 +0.032227 0.255419 +0.025121 0.242851 +0.020495 0.228592 +0.020114 0.228670 +0.019690 0.228757 +0.019217 0.228853 +0.024764 0.243002 +0.024366 0.243171 +0.023922 0.243359 +0.031906 0.255634 +0.031549 0.255875 +0.040808 0.266106 +0.040501 0.266406 +0.031151 0.256143 +0.040159 0.266740 +0.051508 0.274817 +0.051262 0.275167 +0.064415 0.281808 +0.064243 0.282197 +0.050988 0.275557 +0.064051 0.282631 +0.951430 0.255220 +0.899803 0.140714 +0.886060 0.139480 +0.958677 0.241530 +0.962857 0.227303 +0.964161 0.213395 +0.962857 0.199487 +0.958677 0.185260 +0.951430 0.171569 +0.941286 0.159348 +0.928798 0.149420 +0.914809 0.142327 +0.900272 0.138237 +0.886060 0.136960 +0.886060 0.137415 +0.886060 0.137952 +0.886060 0.138426 +0.886060 0.138850 +0.886060 0.139230 +0.913861 0.144669 +0.927389 0.151528 +0.939466 0.161129 +0.949276 0.172948 +0.956284 0.186187 +0.960326 0.199945 +0.961587 0.213395 +0.960326 0.226845 +0.956284 0.240603 +0.949276 0.253842 +0.939466 0.265661 +0.927389 0.275261 +0.913861 0.282120 +0.899803 0.286076 +0.886060 0.287310 +0.886060 0.287559 +0.886060 0.287940 +0.886060 0.288364 +0.886060 0.288837 +0.886060 0.289375 +0.886060 0.289829 +0.900272 0.288553 +0.914809 0.284462 +0.928798 0.277370 +0.941286 0.267442 +0.951042 0.254972 +0.958246 0.241363 +0.962401 0.227220 +0.963697 0.213395 +0.962401 0.199569 +0.958246 0.185427 +0.951042 0.171818 +0.940958 0.159669 +0.928544 0.149800 +0.914638 0.142750 +0.900187 0.138683 +0.900087 0.139212 +0.899999 0.139677 +0.899921 0.140094 +0.899850 0.140469 +0.913955 0.144438 +0.927529 0.151320 +0.939646 0.160953 +0.949489 0.172811 +0.956521 0.186095 +0.960576 0.199900 +0.961842 0.213395 +0.960576 0.226890 +0.956521 0.240694 +0.949489 0.253978 +0.939646 0.265837 +0.927529 0.275470 +0.913955 0.282352 +0.899850 0.286321 +0.899920 0.286695 +0.899999 0.287112 +0.900087 0.287578 +0.900187 0.288106 +0.914638 0.284040 +0.928544 0.276990 +0.940957 0.267121 +0.914098 0.282706 +0.914258 0.283100 +0.914436 0.283540 +0.927741 0.275789 +0.927979 0.276144 +0.928243 0.276540 +0.939921 0.266106 +0.940227 0.266406 +0.940569 0.266741 +0.949814 0.254187 +0.950177 0.254419 +0.950582 0.254678 +0.956882 0.240834 +0.957285 0.240991 +0.957735 0.241165 +0.960959 0.226959 +0.961385 0.227036 +0.962230 0.213395 +0.962664 0.213395 +0.961861 0.227123 +0.963148 0.213395 +0.960959 0.199830 +0.961385 0.199753 +0.956882 0.185955 +0.957286 0.185799 +0.961861 0.199667 +0.957735 0.185625 +0.949814 0.172603 +0.950177 0.172371 +0.950582 0.172112 +0.939921 0.160684 +0.940227 0.160384 +0.940569 0.160049 +0.927741 0.151001 +0.927979 0.150646 +0.928243 0.150250 +0.914098 0.144084 +0.914258 0.143689 +0.914436 0.143249 +0.886060 0.139251 +0.886060 0.139480 +0.094668 0.136960 +0.886060 0.136960 +0.094668 0.137381 +0.094668 0.137916 +0.886060 0.137381 +0.094668 0.138425 +0.886060 0.137917 +0.094668 0.138878 +0.886060 0.138426 +0.094668 0.139251 +0.886060 0.138878 +0.094668 0.139480 +0.910729 0.154467 +0.944624 0.210919 +0.951081 0.210902 +0.921873 0.160226 +0.931161 0.167491 +0.938943 0.176289 +0.945260 0.186961 +0.949476 0.199126 +0.937879 0.210925 +0.936621 0.202018 +0.933260 0.192319 +0.928223 0.183810 +0.922019 0.176796 +0.914613 0.171003 +0.905728 0.166412 +0.895693 0.163504 +0.886060 0.162622 +0.886060 0.162082 +0.886060 0.156037 +0.886060 0.150212 +0.886060 0.149713 +0.898142 0.150820 +0.910535 0.154928 +0.921592 0.160642 +0.930807 0.167850 +0.938528 0.176579 +0.944796 0.187168 +0.948979 0.199238 +0.943178 0.200543 +0.937159 0.201898 +0.933761 0.192095 +0.928671 0.183496 +0.922401 0.176407 +0.914917 0.170553 +0.905937 0.165912 +0.895796 0.162974 +0.896942 0.157035 +0.898048 0.151311 +0.939381 0.189586 +0.933691 0.179973 +0.926682 0.172049 +0.918316 0.165506 +0.908279 0.160319 +0.898145 0.150821 +0.886060 0.149713 +0.951081 0.210902 +0.951081 0.210902 +0.949476 0.199128 +0.949476 0.199128 +0.945261 0.186963 +0.938944 0.176290 +0.945261 0.186963 +0.938944 0.176290 +0.931162 0.167492 +0.931162 0.167492 +0.921875 0.160227 +0.921875 0.160227 +0.910731 0.154468 +0.910731 0.154468 +0.898145 0.150821 +0.886060 0.149713 +0.674255 0.199470 +0.678899 0.182766 +0.677842 0.192694 +0.685976 0.177140 +0.682863 0.186645 +0.693904 0.173121 +0.689043 0.181731 +0.702142 0.170803 +0.695967 0.178221 +0.710195 0.170080 +0.703162 0.176197 +0.718249 0.170803 +0.710195 0.175565 +0.726487 0.173121 +0.717229 0.176197 +0.734415 0.177140 +0.724424 0.178221 +0.741491 0.182766 +0.731348 0.181731 +0.747240 0.189692 +0.737528 0.186645 +0.751347 0.197451 +0.742549 0.192694 +0.753716 0.205513 +0.746136 0.199470 +0.754455 0.213395 +0.748205 0.206511 +0.753716 0.221277 +0.748850 0.213395 +0.751347 0.229339 +0.748205 0.220278 +0.747240 0.237097 +0.746136 0.227320 +0.741491 0.244023 +0.742549 0.234096 +0.734415 0.249649 +0.737528 0.240144 +0.726487 0.253669 +0.731348 0.245058 +0.718249 0.255987 +0.724424 0.248568 +0.710195 0.256710 +0.717229 0.250593 +0.702142 0.255987 +0.710195 0.251224 +0.693904 0.253669 +0.703162 0.250593 +0.685976 0.249649 +0.695967 0.248568 +0.678899 0.244023 +0.689043 0.245058 +0.673151 0.237097 +0.682863 0.240144 +0.669044 0.229339 +0.677842 0.234096 +0.666675 0.221277 +0.674255 0.227320 +0.665936 0.213395 +0.672186 0.220278 +0.666675 0.205513 +0.671541 0.213395 +0.669044 0.197451 +0.672186 0.206511 +0.673151 0.189692 +0.754455 0.213395 +0.754455 0.213395 +0.666675 0.221277 +0.665936 0.213395 +0.665936 0.213395 +0.666675 0.221277 +0.669044 0.229339 +0.669044 0.229339 +0.673151 0.237097 +0.673151 0.237097 +0.678899 0.244023 +0.678899 0.244023 +0.685976 0.249649 +0.693904 0.253669 +0.685976 0.249649 +0.693904 0.253669 +0.702142 0.255987 +0.702142 0.255987 +0.710195 0.256710 +0.710195 0.256710 +0.718249 0.255987 +0.718249 0.255987 +0.726487 0.253669 +0.726487 0.253669 +0.734415 0.249649 +0.734415 0.249649 +0.741491 0.244023 +0.741491 0.244023 +0.747240 0.237097 +0.747240 0.237097 +0.751347 0.229339 +0.751347 0.229339 +0.753716 0.221277 +0.753716 0.221277 +0.599582 0.227320 +0.594937 0.244023 +0.595995 0.234095 +0.587860 0.249649 +0.590974 0.240144 +0.579933 0.253669 +0.584793 0.245058 +0.571695 0.255987 +0.577870 0.248568 +0.563641 0.256710 +0.570675 0.250593 +0.555588 0.255987 +0.563641 0.251224 +0.547350 0.253669 +0.556608 0.250593 +0.539422 0.249649 +0.549413 0.248568 +0.532345 0.244023 +0.542489 0.245058 +0.526596 0.237097 +0.536308 0.240144 +0.522489 0.229339 +0.531288 0.234095 +0.520121 0.221276 +0.527701 0.227320 +0.519382 0.213395 +0.525632 0.220278 +0.520121 0.205513 +0.524987 0.213395 +0.522489 0.197451 +0.525632 0.206511 +0.526596 0.189692 +0.527701 0.199470 +0.532345 0.182766 +0.531288 0.192694 +0.539422 0.177140 +0.536308 0.186645 +0.547350 0.173121 +0.542489 0.181731 +0.555588 0.170803 +0.549413 0.178221 +0.563641 0.170080 +0.556608 0.176197 +0.571695 0.170803 +0.563641 0.175565 +0.579933 0.173121 +0.570675 0.176197 +0.587860 0.177140 +0.577870 0.178221 +0.594937 0.182766 +0.584793 0.181731 +0.600686 0.189692 +0.590974 0.186645 +0.604793 0.197451 +0.595995 0.192694 +0.607162 0.205513 +0.599582 0.199470 +0.607901 0.213395 +0.601650 0.206511 +0.607162 0.221276 +0.602296 0.213395 +0.604793 0.229339 +0.601650 0.220278 +0.600686 0.237097 +0.607901 0.213395 +0.607901 0.213395 +0.520121 0.221276 +0.519382 0.213395 +0.519382 0.213395 +0.520121 0.221276 +0.522489 0.229339 +0.522489 0.229339 +0.526596 0.237097 +0.526596 0.237097 +0.532345 0.244023 +0.532345 0.244023 +0.539422 0.249649 +0.539422 0.249649 +0.547350 0.253669 +0.547350 0.253669 +0.555588 0.255987 +0.555588 0.255987 +0.563641 0.256710 +0.563641 0.256710 +0.571695 0.255987 +0.571695 0.255987 +0.579933 0.253669 +0.579933 0.253669 +0.587860 0.249649 +0.587860 0.249649 +0.594937 0.244023 +0.594937 0.244023 +0.600686 0.237097 +0.600686 0.237097 +0.604793 0.229339 +0.604793 0.229339 +0.607162 0.221276 +0.607162 0.221276 +0.309188 0.213395 +0.311685 0.229339 +0.308542 0.220278 +0.307578 0.237097 +0.306474 0.227320 +0.301829 0.244023 +0.302887 0.234095 +0.294752 0.249649 +0.297866 0.240144 +0.286825 0.253668 +0.291685 0.245058 +0.278587 0.255987 +0.284762 0.248568 +0.270533 0.256710 +0.277567 0.250593 +0.262480 0.255987 +0.270533 0.251224 +0.254242 0.253668 +0.263499 0.250593 +0.246314 0.249649 +0.256305 0.248568 +0.239237 0.244023 +0.249381 0.245058 +0.233488 0.237097 +0.243200 0.240144 +0.229381 0.229339 +0.238180 0.234095 +0.227013 0.221276 +0.234593 0.227320 +0.226274 0.213395 +0.232524 0.220278 +0.227013 0.205513 +0.231879 0.213395 +0.229381 0.197451 +0.232524 0.206511 +0.233488 0.189692 +0.234593 0.199470 +0.239237 0.182766 +0.238180 0.192694 +0.246314 0.177140 +0.243200 0.186645 +0.254242 0.173121 +0.249381 0.181731 +0.262480 0.170803 +0.256305 0.178221 +0.270533 0.170080 +0.263499 0.176196 +0.278587 0.170803 +0.270533 0.175565 +0.286825 0.173121 +0.277567 0.176196 +0.294752 0.177140 +0.284762 0.178221 +0.301829 0.182766 +0.291685 0.181731 +0.307578 0.189692 +0.297866 0.186645 +0.311685 0.197451 +0.302887 0.192694 +0.314054 0.205513 +0.306474 0.199470 +0.314793 0.213395 +0.308542 0.206511 +0.314054 0.221276 +0.314793 0.213395 +0.314793 0.213395 +0.227013 0.221276 +0.226274 0.213395 +0.226274 0.213395 +0.229381 0.229339 +0.227013 0.221276 +0.233488 0.237097 +0.229381 0.229339 +0.239237 0.244023 +0.233488 0.237097 +0.239237 0.244023 +0.246314 0.249649 +0.246314 0.249649 +0.254242 0.253668 +0.254242 0.253668 +0.262480 0.255987 +0.262480 0.255987 +0.270533 0.256710 +0.270533 0.256710 +0.278587 0.255987 +0.278587 0.255987 +0.286825 0.253668 +0.286825 0.253668 +0.294752 0.249649 +0.294752 0.249649 +0.301829 0.244023 +0.301829 0.244023 +0.307578 0.237097 +0.307578 0.237097 +0.311685 0.229339 +0.311685 0.229339 +0.314054 0.221276 +0.314054 0.221276 +0.339081 0.239227 +0.338921 0.240933 +0.357738 0.239260 +0.357895 0.240933 +0.358079 0.240933 +0.357235 0.237548 +0.357919 0.239227 +0.356363 0.235902 +0.357406 0.237482 +0.355143 0.234431 +0.356517 0.235803 +0.353641 0.233237 +0.355273 0.234304 +0.351958 0.232384 +0.353742 0.233086 +0.350209 0.231892 +0.352026 0.232216 +0.348500 0.231738 +0.350243 0.231715 +0.346790 0.231892 +0.348500 0.231558 +0.345042 0.232384 +0.346757 0.231715 +0.343359 0.233237 +0.344974 0.232216 +0.341857 0.234431 +0.343258 0.233086 +0.340637 0.235902 +0.341727 0.234304 +0.339765 0.237548 +0.340483 0.235803 +0.339262 0.239260 +0.339594 0.237482 +0.339105 0.240933 +0.339156 0.185857 +0.334601 0.180472 +0.339312 0.184193 +0.335988 0.177851 +0.339812 0.182491 +0.337930 0.175512 +0.340679 0.180853 +0.340320 0.173612 +0.341893 0.179391 +0.342997 0.172254 +0.343387 0.178203 +0.345780 0.171471 +0.345061 0.177354 +0.348500 0.171227 +0.346800 0.176865 +0.351220 0.171471 +0.348500 0.176712 +0.354002 0.172254 +0.350200 0.176865 +0.356680 0.173612 +0.351939 0.177354 +0.359070 0.175512 +0.353613 0.178203 +0.361012 0.177851 +0.355107 0.179391 +0.362399 0.180472 +0.356321 0.180853 +0.363199 0.183195 +0.357188 0.182491 +0.363448 0.185857 +0.357688 0.184193 +0.363199 0.188519 +0.357844 0.185857 +0.362399 0.191242 +0.357688 0.187521 +0.361012 0.193862 +0.357188 0.189223 +0.359070 0.196201 +0.356321 0.190861 +0.356680 0.198102 +0.355107 0.192323 +0.354002 0.199459 +0.353613 0.193510 +0.351220 0.200242 +0.351939 0.194359 +0.348500 0.200486 +0.350200 0.194848 +0.345780 0.200242 +0.348500 0.195001 +0.342997 0.199459 +0.346800 0.194848 +0.340320 0.198102 +0.345061 0.194359 +0.337930 0.196201 +0.343387 0.193510 +0.335988 0.193862 +0.341893 0.192323 +0.334601 0.191242 +0.340679 0.190861 +0.333801 0.188519 +0.339812 0.189223 +0.333551 0.185857 +0.339312 0.187521 +0.333801 0.183195 +0.333551 0.185857 +0.333551 0.185857 +0.363448 0.185857 +0.363448 0.185857 +0.363199 0.188519 +0.363199 0.188519 +0.362399 0.191242 +0.362399 0.191242 +0.361012 0.193862 +0.361012 0.193862 +0.359070 0.196201 +0.359070 0.196201 +0.356680 0.198102 +0.356680 0.198102 +0.354002 0.199459 +0.354002 0.199459 +0.351220 0.200242 +0.351220 0.200242 +0.348500 0.200486 +0.348500 0.200486 +0.345780 0.200242 +0.345780 0.200242 +0.342997 0.199459 +0.342997 0.199459 +0.340320 0.198102 +0.340320 0.198102 +0.337930 0.196201 +0.337930 0.196201 +0.335988 0.193862 +0.335988 0.193862 +0.334601 0.191242 +0.334601 0.191242 +0.333801 0.188519 +0.333801 0.188519 +0.396472 0.249642 +0.396472 0.249642 +0.396570 0.250686 +0.396570 0.250686 +0.384845 0.250686 +0.384845 0.250686 +0.384943 0.249642 +0.384943 0.249642 +0.385257 0.248574 +0.385257 0.248574 +0.385801 0.247546 +0.385801 0.247546 +0.386562 0.246629 +0.386562 0.246629 +0.387500 0.245884 +0.387500 0.245884 +0.388550 0.245351 +0.388550 0.245351 +0.389641 0.245044 +0.389641 0.245044 +0.390707 0.244949 +0.390707 0.244949 +0.391774 0.245044 +0.391774 0.245044 +0.392865 0.245351 +0.392865 0.245351 +0.393915 0.245884 +0.393915 0.245884 +0.394853 0.246629 +0.394853 0.246629 +0.395614 0.247546 +0.395614 0.247546 +0.396158 0.248574 +0.396158 0.248574 +0.393052 0.250686 +0.396158 0.252798 +0.393013 0.251103 +0.395614 0.253825 +0.392888 0.251530 +0.394853 0.254743 +0.392670 0.251942 +0.393915 0.255488 +0.392366 0.252308 +0.392865 0.256020 +0.391991 0.252607 +0.391774 0.256327 +0.391571 0.252819 +0.390707 0.256423 +0.391134 0.252942 +0.389641 0.256327 +0.390707 0.252981 +0.388550 0.256020 +0.390281 0.252942 +0.387500 0.255488 +0.389844 0.252819 +0.386562 0.254743 +0.389424 0.252607 +0.385801 0.253825 +0.389049 0.252308 +0.385257 0.252798 +0.388745 0.251942 +0.384943 0.251730 +0.388527 0.251530 +0.384845 0.250686 +0.388402 0.251103 +0.384943 0.249642 +0.388363 0.250686 +0.385257 0.248574 +0.388402 0.250268 +0.385801 0.247546 +0.388527 0.249841 +0.386562 0.246629 +0.388745 0.249430 +0.387500 0.245884 +0.389049 0.249063 +0.388550 0.245351 +0.389424 0.248765 +0.389641 0.245044 +0.389844 0.248552 +0.390707 0.244949 +0.390281 0.248429 +0.391774 0.245044 +0.390707 0.248391 +0.392865 0.245351 +0.391134 0.248429 +0.393915 0.245884 +0.391571 0.248552 +0.394853 0.246629 +0.391991 0.248765 +0.395614 0.247546 +0.392366 0.249063 +0.396158 0.248574 +0.392670 0.249430 +0.396472 0.249642 +0.392888 0.249841 +0.396570 0.250686 +0.393013 0.250268 +0.396472 0.251730 +0.229400 0.249642 +0.229400 0.249642 +0.229498 0.250686 +0.229498 0.250686 +0.217774 0.250686 +0.217774 0.250686 +0.217871 0.249642 +0.217871 0.249642 +0.218185 0.248574 +0.218185 0.248574 +0.218729 0.247546 +0.218729 0.247546 +0.219491 0.246629 +0.219491 0.246629 +0.220428 0.245884 +0.220428 0.245884 +0.221478 0.245351 +0.221478 0.245351 +0.222569 0.245044 +0.222569 0.245044 +0.223636 0.244949 +0.223636 0.244949 +0.224702 0.245044 +0.224702 0.245044 +0.225794 0.245351 +0.225794 0.245351 +0.226844 0.245884 +0.226844 0.245884 +0.227781 0.246629 +0.227781 0.246629 +0.228542 0.247546 +0.228542 0.247546 +0.229086 0.248574 +0.229086 0.248574 +0.221978 0.252308 +0.218185 0.252798 +0.221673 0.251941 +0.217871 0.251730 +0.221456 0.251530 +0.217774 0.250686 +0.221330 0.251103 +0.217871 0.249642 +0.221291 0.250686 +0.218185 0.248574 +0.221330 0.250268 +0.218729 0.247546 +0.221456 0.249841 +0.219491 0.246629 +0.221673 0.249430 +0.220428 0.245884 +0.221978 0.249063 +0.221478 0.245351 +0.222353 0.248765 +0.222569 0.245044 +0.222773 0.248552 +0.223636 0.244949 +0.223209 0.248429 +0.224702 0.245044 +0.223636 0.248391 +0.225794 0.245351 +0.224062 0.248429 +0.226844 0.245884 +0.224499 0.248552 +0.227781 0.246629 +0.224919 0.248765 +0.228542 0.247546 +0.225294 0.249063 +0.229086 0.248574 +0.225598 0.249430 +0.229400 0.249642 +0.225816 0.249841 +0.229498 0.250686 +0.225942 0.250268 +0.229400 0.251730 +0.225981 0.250686 +0.229086 0.252798 +0.225942 0.251103 +0.228542 0.253825 +0.225816 0.251530 +0.227781 0.254743 +0.225598 0.251941 +0.226844 0.255488 +0.225294 0.252308 +0.225794 0.256020 +0.224919 0.252606 +0.224702 0.256327 +0.224499 0.252819 +0.223636 0.256423 +0.224062 0.252942 +0.222569 0.256327 +0.223636 0.252981 +0.221478 0.256020 +0.223209 0.252942 +0.220428 0.255488 +0.222773 0.252819 +0.219491 0.254743 +0.222353 0.252606 +0.218729 0.253825 +0.217774 0.176104 +0.217774 0.176104 +0.229498 0.176104 +0.229498 0.176104 +0.229400 0.175060 +0.229400 0.175060 +0.229086 0.173992 +0.229086 0.173992 +0.228542 0.172964 +0.228542 0.172964 +0.227781 0.172047 +0.227781 0.172047 +0.226844 0.171302 +0.226844 0.171302 +0.225794 0.170769 +0.225794 0.170769 +0.224702 0.170462 +0.224702 0.170462 +0.223636 0.170367 +0.223636 0.170367 +0.222569 0.170462 +0.222569 0.170462 +0.221478 0.170769 +0.221478 0.170769 +0.220428 0.171302 +0.220428 0.171302 +0.219491 0.172047 +0.219491 0.172047 +0.218729 0.172964 +0.218729 0.172964 +0.218185 0.173992 +0.218185 0.173992 +0.217871 0.175060 +0.217871 0.175060 +0.225816 0.175259 +0.229498 0.176104 +0.225942 0.175686 +0.229400 0.177148 +0.225981 0.176104 +0.229086 0.178215 +0.225942 0.176521 +0.228542 0.179243 +0.225816 0.176948 +0.227781 0.180160 +0.225598 0.177359 +0.226844 0.180905 +0.225294 0.177726 +0.225794 0.181438 +0.224919 0.178024 +0.224702 0.181745 +0.224499 0.178237 +0.223636 0.181841 +0.224062 0.178360 +0.222569 0.181745 +0.223636 0.178398 +0.221478 0.181438 +0.223209 0.178360 +0.220428 0.180905 +0.222773 0.178237 +0.219491 0.180160 +0.222353 0.178024 +0.218729 0.179243 +0.221978 0.177726 +0.218185 0.178215 +0.221673 0.177359 +0.217871 0.177148 +0.221456 0.176948 +0.217774 0.176104 +0.221330 0.176521 +0.217871 0.175060 +0.221291 0.176104 +0.218185 0.173992 +0.221330 0.175686 +0.218729 0.172964 +0.221456 0.175259 +0.219491 0.172047 +0.221673 0.174848 +0.220428 0.171302 +0.221978 0.174481 +0.221478 0.170769 +0.222353 0.174183 +0.222569 0.170462 +0.222773 0.173970 +0.223636 0.170367 +0.223209 0.173847 +0.224702 0.170462 +0.223636 0.173809 +0.225794 0.170769 +0.224062 0.173847 +0.226844 0.171302 +0.224499 0.173970 +0.227781 0.172047 +0.224919 0.174183 +0.228542 0.172964 +0.225294 0.174481 +0.229086 0.173992 +0.225598 0.174848 +0.229400 0.175060 +0.396472 0.175060 +0.396570 0.176104 +0.396570 0.176104 +0.396472 0.175060 +0.384845 0.176104 +0.384845 0.176104 +0.384943 0.175060 +0.384943 0.175060 +0.385257 0.173992 +0.385801 0.172964 +0.385257 0.173992 +0.385801 0.172964 +0.386562 0.172047 +0.386562 0.172047 +0.387500 0.171302 +0.388550 0.170769 +0.387500 0.171302 +0.388550 0.170769 +0.389641 0.170462 +0.389641 0.170462 +0.390707 0.170367 +0.390707 0.170367 +0.391774 0.170462 +0.391774 0.170462 +0.392865 0.170769 +0.392865 0.170769 +0.393915 0.171302 +0.393915 0.171302 +0.394853 0.172047 +0.394853 0.172047 +0.395614 0.172964 +0.395614 0.172964 +0.396158 0.173992 +0.396158 0.173992 +0.393013 0.175686 +0.396472 0.177148 +0.393052 0.176104 +0.396158 0.178215 +0.393013 0.176521 +0.395614 0.179243 +0.392888 0.176948 +0.394853 0.180160 +0.392670 0.177359 +0.393915 0.180906 +0.392366 0.177726 +0.392865 0.181438 +0.391991 0.178024 +0.391774 0.181745 +0.391571 0.178237 +0.390707 0.181841 +0.391134 0.178360 +0.389641 0.181745 +0.390707 0.178398 +0.388550 0.181438 +0.390281 0.178360 +0.387500 0.180906 +0.389844 0.178237 +0.386562 0.180160 +0.389424 0.178024 +0.385801 0.179243 +0.389049 0.177726 +0.385257 0.178215 +0.388745 0.177359 +0.384943 0.177148 +0.388527 0.176948 +0.384845 0.176104 +0.388402 0.176521 +0.384943 0.175060 +0.388363 0.176104 +0.385257 0.173992 +0.388402 0.175686 +0.385801 0.172964 +0.388527 0.175259 +0.386562 0.172047 +0.388745 0.174848 +0.387500 0.171302 +0.389049 0.174481 +0.388550 0.170769 +0.389424 0.174183 +0.389641 0.170462 +0.389844 0.173970 +0.390707 0.170367 +0.390281 0.173847 +0.391774 0.170462 +0.390707 0.173809 +0.392865 0.170769 +0.391134 0.173847 +0.393915 0.171302 +0.391571 0.173970 +0.394853 0.172047 +0.391991 0.174183 +0.395614 0.172964 +0.392366 0.174481 +0.396158 0.173992 +0.392670 0.174848 +0.396472 0.175060 +0.392888 0.175259 +0.396570 0.176104 +0.762955 0.250686 +0.762955 0.250686 +0.751328 0.249642 +0.751231 0.250686 +0.751231 0.250686 +0.751328 0.249642 +0.751642 0.248574 +0.752186 0.247546 +0.751642 0.248574 +0.752948 0.246629 +0.752186 0.247546 +0.752948 0.246629 +0.753885 0.245884 +0.753885 0.245884 +0.754935 0.245352 +0.754935 0.245352 +0.756026 0.245044 +0.756026 0.245044 +0.757093 0.244949 +0.757093 0.244949 +0.758159 0.245044 +0.758159 0.245044 +0.759251 0.245352 +0.759251 0.245352 +0.760301 0.245884 +0.760301 0.245884 +0.761238 0.246629 +0.761238 0.246629 +0.761999 0.247546 +0.761999 0.247546 +0.762543 0.248574 +0.762543 0.248574 +0.762857 0.249642 +0.762857 0.249642 +0.759055 0.249430 +0.762857 0.249642 +0.759273 0.249841 +0.762955 0.250686 +0.759398 0.250268 +0.762857 0.251730 +0.759438 0.250686 +0.762543 0.252798 +0.759398 0.251103 +0.761999 0.253825 +0.759273 0.251531 +0.761238 0.254743 +0.759055 0.251942 +0.760301 0.255488 +0.758751 0.252308 +0.759251 0.256020 +0.758376 0.252607 +0.758159 0.256327 +0.757956 0.252820 +0.757093 0.256423 +0.757519 0.252942 +0.756026 0.256327 +0.757093 0.252981 +0.754935 0.256020 +0.756666 0.252942 +0.753885 0.255488 +0.756230 0.252820 +0.752948 0.254743 +0.755810 0.252607 +0.752186 0.253825 +0.755435 0.252308 +0.751642 0.252798 +0.755130 0.251942 +0.751328 0.251730 +0.754912 0.251531 +0.751231 0.250686 +0.754787 0.251103 +0.751328 0.249642 +0.754748 0.250686 +0.751642 0.248574 +0.754787 0.250268 +0.752186 0.247546 +0.754912 0.249841 +0.752948 0.246629 +0.755130 0.249430 +0.753885 0.245884 +0.755435 0.249063 +0.754935 0.245352 +0.755810 0.248765 +0.756026 0.245044 +0.756230 0.248552 +0.757093 0.244949 +0.756666 0.248429 +0.758159 0.245044 +0.757093 0.248391 +0.759251 0.245352 +0.757519 0.248429 +0.760301 0.245884 +0.757956 0.248552 +0.761238 0.246629 +0.758376 0.248765 +0.761999 0.247546 +0.758751 0.249063 +0.762543 0.248574 +0.510882 0.250686 +0.510882 0.250686 +0.522606 0.250686 +0.522606 0.250686 +0.522508 0.249642 +0.522508 0.249642 +0.522195 0.248574 +0.522195 0.248574 +0.521651 0.247546 +0.521651 0.247546 +0.520889 0.246629 +0.520889 0.246629 +0.519952 0.245884 +0.519952 0.245884 +0.518902 0.245351 +0.518902 0.245351 +0.517811 0.245044 +0.517811 0.245044 +0.516744 0.244949 +0.516744 0.244949 +0.515677 0.245044 +0.515677 0.245044 +0.514586 0.245351 +0.514586 0.245351 +0.513536 0.245884 +0.513536 0.245884 +0.512599 0.246629 +0.512599 0.246629 +0.511837 0.247546 +0.511837 0.247546 +0.511293 0.248574 +0.511293 0.248574 +0.510980 0.249642 +0.510980 0.249642 +0.519089 0.250686 +0.522195 0.252798 +0.519050 0.251103 +0.521651 0.253825 +0.518924 0.251530 +0.520889 0.254743 +0.518707 0.251942 +0.519952 0.255488 +0.518402 0.252308 +0.518902 0.256020 +0.518027 0.252607 +0.517811 0.256327 +0.517607 0.252819 +0.516744 0.256423 +0.517171 0.252942 +0.515677 0.256327 +0.516744 0.252981 +0.514586 0.256020 +0.516317 0.252942 +0.513536 0.255488 +0.515881 0.252819 +0.512599 0.254743 +0.515461 0.252607 +0.511837 0.253825 +0.515086 0.252308 +0.511293 0.252798 +0.514781 0.251942 +0.510980 0.251730 +0.514564 0.251530 +0.510882 0.250686 +0.514438 0.251103 +0.510980 0.249642 +0.514399 0.250686 +0.511293 0.248574 +0.514438 0.250268 +0.511837 0.247546 +0.514564 0.249841 +0.512599 0.246629 +0.514781 0.249430 +0.513536 0.245884 +0.515086 0.249063 +0.514586 0.245351 +0.515461 0.248765 +0.515677 0.245044 +0.515881 0.248552 +0.516744 0.244949 +0.516317 0.248429 +0.517811 0.245044 +0.516744 0.248391 +0.518902 0.245351 +0.517171 0.248429 +0.519952 0.245884 +0.517607 0.248552 +0.520889 0.246629 +0.518027 0.248765 +0.521651 0.247546 +0.518402 0.249063 +0.522195 0.248574 +0.518707 0.249430 +0.522508 0.249642 +0.518924 0.249841 +0.522606 0.250686 +0.519050 0.250268 +0.522508 0.251730 +0.510882 0.176104 +0.510882 0.176104 +0.522606 0.176104 +0.522606 0.176104 +0.522508 0.175060 +0.522508 0.175060 +0.522195 0.173992 +0.522195 0.173992 +0.521651 0.172964 +0.521651 0.172964 +0.520889 0.172047 +0.520889 0.172047 +0.519952 0.171302 +0.519952 0.171302 +0.518902 0.170769 +0.518902 0.170769 +0.517811 0.170462 +0.517811 0.170462 +0.516744 0.170367 +0.516744 0.170367 +0.515677 0.170462 +0.515677 0.170462 +0.514586 0.170769 +0.514586 0.170769 +0.513536 0.171302 +0.513536 0.171302 +0.512599 0.172047 +0.512599 0.172047 +0.511837 0.172964 +0.511837 0.172964 +0.511293 0.173992 +0.511293 0.173992 +0.510980 0.175060 +0.510980 0.175060 +0.515086 0.174481 +0.514586 0.170769 +0.515461 0.174183 +0.515677 0.170462 +0.515881 0.173970 +0.516744 0.170367 +0.516317 0.173847 +0.517811 0.170462 +0.516744 0.173809 +0.518902 0.170769 +0.517171 0.173847 +0.519952 0.171302 +0.517607 0.173970 +0.520889 0.172047 +0.518027 0.174183 +0.521651 0.172964 +0.518402 0.174481 +0.522195 0.173992 +0.518707 0.174848 +0.522508 0.175060 +0.518924 0.175259 +0.522606 0.176104 +0.519050 0.175686 +0.522508 0.177148 +0.519089 0.176104 +0.522195 0.178215 +0.519050 0.176521 +0.521651 0.179243 +0.518924 0.176948 +0.520889 0.180160 +0.518707 0.177359 +0.519952 0.180906 +0.518402 0.177726 +0.518902 0.181438 +0.518027 0.178024 +0.517811 0.181745 +0.517607 0.178237 +0.516744 0.181841 +0.517171 0.178360 +0.515677 0.181745 +0.516744 0.178398 +0.514586 0.181438 +0.516317 0.178360 +0.513536 0.180906 +0.515881 0.178237 +0.512599 0.180160 +0.515461 0.178024 +0.511837 0.179243 +0.515086 0.177726 +0.511293 0.178215 +0.514781 0.177359 +0.510980 0.177148 +0.514564 0.176948 +0.510882 0.176104 +0.514438 0.176521 +0.510980 0.175060 +0.514399 0.176104 +0.511293 0.173992 +0.514438 0.175686 +0.511837 0.172964 +0.514564 0.175259 +0.512599 0.172047 +0.514781 0.174848 +0.513536 0.171302 +0.762955 0.176104 +0.762955 0.176104 +0.751328 0.175060 +0.751231 0.176104 +0.751231 0.176104 +0.751642 0.173992 +0.751328 0.175060 +0.751642 0.173992 +0.752186 0.172964 +0.752186 0.172964 +0.752948 0.172047 +0.753885 0.171302 +0.752948 0.172047 +0.753885 0.171302 +0.754935 0.170769 +0.754935 0.170769 +0.756026 0.170462 +0.756026 0.170462 +0.757093 0.170367 +0.757093 0.170367 +0.758159 0.170462 +0.758159 0.170462 +0.759251 0.170769 +0.759251 0.170769 +0.760301 0.171302 +0.760301 0.171302 +0.761238 0.172047 +0.761238 0.172047 +0.761999 0.172964 +0.761999 0.172964 +0.762543 0.173992 +0.762543 0.173992 +0.762857 0.175060 +0.762857 0.175060 +0.759055 0.174848 +0.762857 0.175060 +0.759273 0.175259 +0.762955 0.176104 +0.759398 0.175686 +0.762857 0.177148 +0.759438 0.176104 +0.762543 0.178216 +0.759398 0.176521 +0.761999 0.179243 +0.759273 0.176948 +0.761238 0.180160 +0.759055 0.177359 +0.760301 0.180906 +0.758751 0.177726 +0.759251 0.181438 +0.758376 0.178024 +0.758159 0.181745 +0.757956 0.178237 +0.757093 0.181841 +0.757519 0.178360 +0.756026 0.181745 +0.757093 0.178399 +0.754935 0.181438 +0.756666 0.178360 +0.753885 0.180906 +0.756230 0.178237 +0.752948 0.180160 +0.755810 0.178024 +0.752186 0.179243 +0.755435 0.177726 +0.751642 0.178215 +0.755130 0.177359 +0.751328 0.177148 +0.754912 0.176948 +0.751231 0.176104 +0.754787 0.176521 +0.751328 0.175060 +0.754748 0.176104 +0.751642 0.173992 +0.754787 0.175686 +0.752186 0.172964 +0.754912 0.175259 +0.752948 0.172047 +0.755130 0.174848 +0.753885 0.171302 +0.755435 0.174481 +0.754935 0.170769 +0.755810 0.174183 +0.756026 0.170462 +0.756230 0.173970 +0.757093 0.170367 +0.756666 0.173847 +0.758159 0.170462 +0.757093 0.173809 +0.759251 0.170769 +0.757519 0.173847 +0.760301 0.171302 +0.757956 0.173970 +0.761238 0.172047 +0.758376 0.174183 +0.761999 0.172964 +0.758751 0.174481 +0.762543 0.173992 +0.651574 0.213395 +0.651574 0.213395 +0.663298 0.213395 +0.663298 0.213395 +0.663200 0.212351 +0.663200 0.212351 +0.662887 0.211283 +0.662887 0.211283 +0.662343 0.210255 +0.662343 0.210255 +0.661581 0.209338 +0.661581 0.209338 +0.660644 0.208593 +0.660644 0.208593 +0.659594 0.208060 +0.659594 0.208060 +0.658503 0.207753 +0.658503 0.207753 +0.657436 0.207658 +0.657436 0.207658 +0.656369 0.207753 +0.656369 0.207753 +0.655278 0.208060 +0.655278 0.208060 +0.654228 0.208593 +0.654228 0.208593 +0.653291 0.209338 +0.653291 0.209338 +0.652529 0.210255 +0.652529 0.210255 +0.651985 0.211283 +0.651985 0.211283 +0.651672 0.212351 +0.651672 0.212351 +0.655091 0.213395 +0.651985 0.211283 +0.655130 0.212977 +0.652529 0.210255 +0.655256 0.212550 +0.653291 0.209338 +0.655473 0.212139 +0.654228 0.208593 +0.655778 0.211772 +0.655278 0.208060 +0.656153 0.211474 +0.656369 0.207753 +0.656573 0.211261 +0.657436 0.207658 +0.657009 0.211138 +0.658503 0.207753 +0.657436 0.211100 +0.659594 0.208060 +0.657863 0.211138 +0.660644 0.208593 +0.658299 0.211261 +0.661581 0.209338 +0.658719 0.211474 +0.662343 0.210255 +0.659094 0.211772 +0.662887 0.211283 +0.659399 0.212139 +0.663200 0.212351 +0.659616 0.212550 +0.663298 0.213395 +0.659742 0.212977 +0.663200 0.214439 +0.659781 0.213395 +0.662887 0.215507 +0.659742 0.213812 +0.662343 0.216534 +0.659616 0.214240 +0.661581 0.217451 +0.659399 0.214651 +0.660644 0.218197 +0.659094 0.215017 +0.659594 0.218729 +0.658719 0.215315 +0.658503 0.219036 +0.658299 0.215528 +0.657436 0.219132 +0.657863 0.215651 +0.656369 0.219036 +0.657436 0.215690 +0.655278 0.218729 +0.657009 0.215651 +0.654228 0.218197 +0.656573 0.215528 +0.653291 0.217451 +0.656153 0.215315 +0.652529 0.216534 +0.655778 0.215017 +0.651985 0.215507 +0.655473 0.214651 +0.651672 0.214439 +0.655256 0.214240 +0.651574 0.213395 +0.655130 0.213812 +0.651672 0.212351 +0.225942 0.251103 +0.225981 0.250686 +0.221330 0.251103 +0.221291 0.250686 +0.221291 0.250686 +0.221330 0.251103 +0.221456 0.251530 +0.221456 0.251530 +0.221673 0.251941 +0.221673 0.251941 +0.221978 0.252308 +0.221978 0.252308 +0.222353 0.252606 +0.222773 0.252819 +0.222353 0.252606 +0.223209 0.252942 +0.222773 0.252819 +0.223209 0.252942 +0.223636 0.252981 +0.224062 0.252942 +0.223636 0.252981 +0.224499 0.252819 +0.224062 0.252942 +0.224499 0.252819 +0.224919 0.252606 +0.224919 0.252606 +0.225294 0.252308 +0.225294 0.252308 +0.225598 0.251941 +0.225816 0.251530 +0.225598 0.251941 +0.225816 0.251530 +0.225942 0.251103 +0.225981 0.250686 +0.224499 0.248552 +0.224062 0.248429 +0.221673 0.249430 +0.221456 0.249841 +0.221978 0.249063 +0.222353 0.248765 +0.221330 0.250268 +0.222773 0.248552 +0.221291 0.250686 +0.223209 0.248429 +0.221330 0.251103 +0.221456 0.251530 +0.221673 0.251941 +0.221978 0.252308 +0.222353 0.252606 +0.222773 0.252819 +0.223209 0.252942 +0.223636 0.248391 +0.223636 0.252981 +0.224062 0.252942 +0.224499 0.252819 +0.224919 0.252606 +0.225294 0.252308 +0.225598 0.251941 +0.225816 0.251530 +0.225942 0.251103 +0.225981 0.250686 +0.225942 0.250268 +0.225816 0.249841 +0.225598 0.249430 +0.225294 0.249063 +0.224919 0.248765 +0.225598 0.177359 +0.225942 0.176521 +0.225981 0.176104 +0.225981 0.176104 +0.225942 0.176521 +0.225816 0.176948 +0.225598 0.177359 +0.225816 0.176948 +0.221291 0.176104 +0.221291 0.176104 +0.221330 0.176521 +0.221330 0.176521 +0.221456 0.176948 +0.221456 0.176948 +0.221673 0.177359 +0.221673 0.177359 +0.221978 0.177726 +0.221978 0.177726 +0.222353 0.178024 +0.222353 0.178024 +0.222773 0.178237 +0.222773 0.178237 +0.223209 0.178360 +0.223636 0.178398 +0.223209 0.178360 +0.223636 0.178398 +0.224062 0.178360 +0.224062 0.178360 +0.224499 0.178237 +0.224919 0.178024 +0.224499 0.178237 +0.224919 0.178024 +0.225294 0.177726 +0.225294 0.177726 +0.223636 0.173809 +0.223209 0.173847 +0.221673 0.174848 +0.221456 0.175259 +0.221978 0.174481 +0.222353 0.174183 +0.221330 0.175686 +0.222773 0.173970 +0.221291 0.176104 +0.221330 0.176521 +0.221456 0.176948 +0.221673 0.177359 +0.221978 0.177726 +0.222353 0.178024 +0.222773 0.178237 +0.223209 0.178360 +0.223636 0.178398 +0.224062 0.178360 +0.224499 0.178237 +0.224919 0.178024 +0.225294 0.177726 +0.225598 0.177359 +0.225816 0.176948 +0.225942 0.176521 +0.225981 0.176104 +0.225942 0.175686 +0.225816 0.175259 +0.225598 0.174848 +0.225294 0.174481 +0.224919 0.174183 +0.224499 0.173970 +0.224062 0.173847 +0.389049 0.252308 +0.388402 0.251103 +0.388363 0.250686 +0.388363 0.250686 +0.388402 0.251103 +0.388527 0.251530 +0.388745 0.251942 +0.388527 0.251530 +0.388745 0.251942 +0.389049 0.252308 +0.393052 0.250686 +0.393052 0.250686 +0.393013 0.251103 +0.392888 0.251530 +0.393013 0.251103 +0.392888 0.251530 +0.392670 0.251942 +0.392670 0.251942 +0.392366 0.252308 +0.392366 0.252308 +0.391991 0.252607 +0.391571 0.252819 +0.391991 0.252607 +0.391134 0.252942 +0.391571 0.252819 +0.390707 0.252981 +0.391134 0.252942 +0.390281 0.252942 +0.390707 0.252981 +0.389844 0.252819 +0.390281 0.252942 +0.389424 0.252607 +0.389844 0.252819 +0.389424 0.252607 +0.390707 0.248391 +0.390281 0.248429 +0.388745 0.249430 +0.388527 0.249841 +0.389049 0.249063 +0.389424 0.248765 +0.388402 0.250268 +0.389844 0.248552 +0.388363 0.250686 +0.388402 0.251103 +0.388527 0.251530 +0.388745 0.251942 +0.389049 0.252308 +0.389424 0.252607 +0.389844 0.252819 +0.390281 0.252942 +0.390707 0.252981 +0.391134 0.252942 +0.391571 0.252819 +0.391991 0.252607 +0.392366 0.252308 +0.392670 0.251942 +0.392888 0.251530 +0.393013 0.251103 +0.393052 0.250686 +0.393013 0.250268 +0.392888 0.249841 +0.392670 0.249430 +0.392366 0.249063 +0.391991 0.248765 +0.391571 0.248552 +0.391134 0.248429 +0.393052 0.176104 +0.393052 0.176104 +0.388363 0.176104 +0.388363 0.176104 +0.388402 0.176521 +0.388527 0.176948 +0.388402 0.176521 +0.388527 0.176948 +0.388745 0.177359 +0.388745 0.177359 +0.389049 0.177726 +0.389424 0.178024 +0.389049 0.177726 +0.389424 0.178024 +0.389844 0.178237 +0.389844 0.178237 +0.390281 0.178360 +0.390707 0.178398 +0.390281 0.178360 +0.390707 0.178398 +0.391134 0.178360 +0.391134 0.178360 +0.391571 0.178237 +0.391571 0.178237 +0.391991 0.178024 +0.392366 0.177726 +0.391991 0.178024 +0.392670 0.177359 +0.392366 0.177726 +0.392670 0.177359 +0.392888 0.176948 +0.393013 0.176521 +0.392888 0.176948 +0.393013 0.176521 +0.391134 0.173847 +0.390707 0.173809 +0.388745 0.174848 +0.388527 0.175259 +0.389049 0.174481 +0.389424 0.174183 +0.388402 0.175686 +0.389844 0.173970 +0.388363 0.176104 +0.390281 0.173847 +0.388402 0.176521 +0.388527 0.176948 +0.388745 0.177359 +0.389049 0.177726 +0.389424 0.178024 +0.389844 0.178237 +0.390281 0.178360 +0.390707 0.178398 +0.391134 0.178360 +0.391571 0.178237 +0.391991 0.178024 +0.392366 0.177726 +0.392670 0.177359 +0.392888 0.176948 +0.393013 0.176521 +0.393052 0.176104 +0.393013 0.175686 +0.392888 0.175259 +0.392670 0.174848 +0.392366 0.174481 +0.391991 0.174183 +0.391571 0.173970 +0.518027 0.252607 +0.519050 0.251103 +0.519089 0.250686 +0.519089 0.250686 +0.518924 0.251530 +0.519050 0.251103 +0.518707 0.251942 +0.518924 0.251530 +0.518402 0.252308 +0.518707 0.251942 +0.514399 0.250686 +0.514399 0.250686 +0.514438 0.251103 +0.514438 0.251103 +0.514564 0.251530 +0.514564 0.251530 +0.514781 0.251942 +0.515086 0.252308 +0.514781 0.251942 +0.515461 0.252607 +0.515086 0.252308 +0.515461 0.252607 +0.515881 0.252819 +0.516317 0.252942 +0.515881 0.252819 +0.516744 0.252981 +0.516317 0.252942 +0.517171 0.252942 +0.516744 0.252981 +0.517607 0.252819 +0.517171 0.252942 +0.518027 0.252607 +0.517607 0.252819 +0.518402 0.252308 +0.517607 0.248552 +0.517171 0.248429 +0.514781 0.249430 +0.514564 0.249841 +0.515086 0.249063 +0.515461 0.248765 +0.514438 0.250268 +0.515881 0.248552 +0.514399 0.250686 +0.516317 0.248429 +0.514438 0.251103 +0.514564 0.251530 +0.514781 0.251942 +0.515086 0.252308 +0.515461 0.252607 +0.515881 0.252819 +0.516317 0.252942 +0.516744 0.252981 +0.517171 0.252942 +0.517607 0.252819 +0.518027 0.252607 +0.518402 0.252308 +0.518707 0.251942 +0.518924 0.251530 +0.519050 0.251103 +0.516744 0.248391 +0.519089 0.250686 +0.519050 0.250268 +0.518924 0.249841 +0.518707 0.249430 +0.518402 0.249063 +0.518027 0.248765 +0.519089 0.176104 +0.519089 0.176104 +0.514438 0.176521 +0.514399 0.176104 +0.514399 0.176104 +0.514438 0.176521 +0.514564 0.176948 +0.514781 0.177359 +0.514564 0.176948 +0.514781 0.177359 +0.515086 0.177726 +0.515461 0.178024 +0.515086 0.177726 +0.515881 0.178237 +0.515461 0.178024 +0.516317 0.178360 +0.515881 0.178237 +0.516744 0.178398 +0.516317 0.178360 +0.516744 0.178398 +0.517171 0.178360 +0.517607 0.178237 +0.517171 0.178360 +0.518027 0.178024 +0.517607 0.178237 +0.518027 0.178024 +0.518402 0.177726 +0.518402 0.177726 +0.518707 0.177359 +0.518707 0.177359 +0.518924 0.176948 +0.518924 0.176948 +0.519050 0.176521 +0.519050 0.176521 +0.517171 0.173847 +0.516744 0.173809 +0.514781 0.174848 +0.514564 0.175259 +0.515086 0.174481 +0.515461 0.174183 +0.514438 0.175686 +0.515881 0.173970 +0.514399 0.176104 +0.516317 0.173847 +0.514438 0.176521 +0.514564 0.176948 +0.514781 0.177359 +0.515086 0.177726 +0.515461 0.178024 +0.515881 0.178237 +0.516317 0.178360 +0.516744 0.178398 +0.517171 0.178360 +0.517607 0.178237 +0.518027 0.178024 +0.518402 0.177726 +0.518707 0.177359 +0.518924 0.176948 +0.519050 0.176521 +0.519089 0.176104 +0.519050 0.175686 +0.518924 0.175259 +0.518707 0.174848 +0.518402 0.174481 +0.518027 0.174183 +0.517607 0.173970 +0.757093 0.252981 +0.759398 0.251103 +0.759438 0.250686 +0.759438 0.250686 +0.759273 0.251531 +0.759398 0.251103 +0.759273 0.251531 +0.759055 0.251942 +0.759055 0.251942 +0.758751 0.252308 +0.758376 0.252607 +0.758751 0.252308 +0.757956 0.252820 +0.758376 0.252607 +0.757519 0.252942 +0.757956 0.252820 +0.754748 0.250686 +0.754748 0.250686 +0.754787 0.251103 +0.754787 0.251103 +0.754912 0.251531 +0.754912 0.251531 +0.755130 0.251942 +0.755130 0.251942 +0.755435 0.252308 +0.755435 0.252308 +0.755810 0.252607 +0.755810 0.252607 +0.756230 0.252820 +0.756230 0.252820 +0.756666 0.252942 +0.756666 0.252942 +0.757093 0.252981 +0.757519 0.252942 +0.757093 0.248391 +0.756666 0.248429 +0.755130 0.249430 +0.754912 0.249841 +0.755435 0.249063 +0.755810 0.248765 +0.754787 0.250268 +0.756230 0.248552 +0.754748 0.250686 +0.754787 0.251103 +0.754912 0.251531 +0.755130 0.251942 +0.755435 0.252308 +0.755810 0.252607 +0.756230 0.252820 +0.756666 0.252942 +0.757093 0.252981 +0.757519 0.252942 +0.757956 0.252820 +0.758376 0.252607 +0.758751 0.252308 +0.759055 0.251942 +0.759273 0.251531 +0.759398 0.251103 +0.759438 0.250686 +0.759398 0.250268 +0.759273 0.249841 +0.759055 0.249430 +0.758751 0.249063 +0.758376 0.248765 +0.757956 0.248552 +0.757519 0.248429 +0.759438 0.176104 +0.759438 0.176104 +0.754787 0.176521 +0.754748 0.176104 +0.754748 0.176104 +0.754787 0.176521 +0.754912 0.176948 +0.754912 0.176948 +0.755130 0.177359 +0.755130 0.177359 +0.755435 0.177726 +0.755435 0.177726 +0.755810 0.178024 +0.755810 0.178024 +0.756230 0.178237 +0.756230 0.178237 +0.756666 0.178360 +0.756666 0.178360 +0.757093 0.178399 +0.757093 0.178399 +0.757519 0.178360 +0.757519 0.178360 +0.757956 0.178237 +0.757956 0.178237 +0.758376 0.178024 +0.758751 0.177726 +0.758376 0.178024 +0.758751 0.177726 +0.759055 0.177359 +0.759055 0.177359 +0.759273 0.176948 +0.759273 0.176948 +0.759398 0.176521 +0.759398 0.176521 +0.757956 0.173970 +0.757519 0.173847 +0.755130 0.174848 +0.754912 0.175259 +0.755435 0.174481 +0.755810 0.174183 +0.754787 0.175686 +0.756230 0.173970 +0.754748 0.176104 +0.756666 0.173847 +0.754787 0.176521 +0.754912 0.176948 +0.755130 0.177359 +0.755435 0.177726 +0.755810 0.178024 +0.756230 0.178237 +0.756666 0.178360 +0.757093 0.173809 +0.757093 0.178399 +0.757519 0.178360 +0.757956 0.178237 +0.758376 0.178024 +0.758751 0.177726 +0.759055 0.177359 +0.759273 0.176948 +0.759398 0.176521 +0.759438 0.176104 +0.759398 0.175686 +0.759273 0.175259 +0.759055 0.174848 +0.758751 0.174481 +0.758376 0.174183 +0.659781 0.213395 +0.659781 0.213395 +0.655130 0.213812 +0.655091 0.213395 +0.655091 0.213395 +0.655130 0.213812 +0.655256 0.214240 +0.655256 0.214240 +0.655473 0.214651 +0.655473 0.214651 +0.655778 0.215017 +0.656153 0.215315 +0.655778 0.215017 +0.656153 0.215315 +0.656573 0.215528 +0.656573 0.215528 +0.657009 0.215651 +0.657009 0.215651 +0.657436 0.215690 +0.657436 0.215690 +0.657863 0.215651 +0.657863 0.215651 +0.658299 0.215528 +0.658299 0.215528 +0.658719 0.215315 +0.658719 0.215315 +0.659094 0.215017 +0.659094 0.215017 +0.659399 0.214651 +0.659399 0.214651 +0.659616 0.214240 +0.659616 0.214240 +0.659742 0.213812 +0.659742 0.213812 +0.657863 0.211138 +0.657436 0.211100 +0.655473 0.212139 +0.655256 0.212550 +0.655778 0.211772 +0.656153 0.211474 +0.655130 0.212977 +0.656573 0.211261 +0.655091 0.213395 +0.655130 0.213812 +0.655256 0.214240 +0.655473 0.214651 +0.655778 0.215017 +0.656153 0.215315 +0.656573 0.215528 +0.657009 0.215651 +0.657436 0.215690 +0.657009 0.211138 +0.657863 0.215651 +0.658299 0.215528 +0.658719 0.215315 +0.659094 0.215017 +0.659399 0.214651 +0.659616 0.214240 +0.659742 0.213812 +0.659781 0.213395 +0.659742 0.212977 +0.659616 0.212550 +0.659399 0.212139 +0.659094 0.211772 +0.658719 0.211474 +0.658299 0.211261 +0.765886 0.216263 +0.762955 0.216263 +0.757679 0.216263 +0.765886 0.216263 +0.757679 0.216263 +0.767645 0.214542 +0.767645 0.212247 +0.767645 0.212247 +0.767645 0.214542 +0.757679 0.210526 +0.762955 0.210526 +0.765886 0.210526 +0.765886 0.210526 +0.757679 0.210526 +0.755920 0.214542 +0.755920 0.212247 +0.755920 0.212247 +0.755920 0.214542 +0.766533 0.210647 +0.766206 0.210555 +0.762955 0.210526 +0.762955 0.216263 +0.765886 0.210526 +0.765886 0.216263 +0.766206 0.216235 +0.766533 0.216142 +0.766848 0.215983 +0.767130 0.215759 +0.767358 0.215484 +0.767521 0.215176 +0.767615 0.214855 +0.767645 0.214542 +0.767645 0.212247 +0.767615 0.211934 +0.767521 0.211614 +0.767358 0.211306 +0.767130 0.211030 +0.766848 0.210807 +0.755920 0.214542 +0.755950 0.214855 +0.757679 0.216263 +0.762955 0.216263 +0.762955 0.210526 +0.757679 0.210526 +0.757032 0.216142 +0.757032 0.210647 +0.756435 0.211030 +0.756207 0.211305 +0.756044 0.211614 +0.755950 0.211934 +0.755920 0.212247 +0.756717 0.215983 +0.756435 0.215759 +0.756207 0.215484 +0.756044 0.215176 +0.755950 0.214855 +0.755920 0.214542 +0.757679 0.216263 +0.757679 0.216263 +0.757319 0.216227 +0.757359 0.216235 +0.756980 0.216122 +0.757032 0.216142 +0.756682 0.215960 +0.756717 0.215983 +0.756435 0.215759 +0.756570 0.215878 +0.756435 0.215759 +0.756230 0.215517 +0.756314 0.215627 +0.756065 0.215226 +0.756207 0.215484 +0.755958 0.214895 +0.756044 0.215176 +0.755920 0.214542 +0.755920 0.212247 +0.755920 0.212247 +0.757679 0.210526 +0.757679 0.210526 +0.757359 0.210555 +0.757032 0.210647 +0.757319 0.210563 +0.756717 0.210807 +0.756980 0.210668 +0.756570 0.210911 +0.756682 0.210829 +0.756435 0.211030 +0.756314 0.211163 +0.756435 0.211030 +0.756207 0.211305 +0.756230 0.211272 +0.756044 0.211614 +0.756065 0.211564 +0.755950 0.211934 +0.755958 0.211895 +0.765886 0.216263 +0.765886 0.216263 +0.767607 0.214895 +0.767645 0.214542 +0.767645 0.214542 +0.767607 0.214895 +0.767500 0.215226 +0.767500 0.215226 +0.767335 0.215517 +0.767335 0.215517 +0.767130 0.215759 +0.767130 0.215759 +0.766882 0.215960 +0.766584 0.216122 +0.766882 0.215960 +0.766246 0.216227 +0.766584 0.216122 +0.766246 0.216227 +0.765886 0.210526 +0.765886 0.210526 +0.767607 0.211895 +0.767645 0.212247 +0.767645 0.212247 +0.767607 0.211895 +0.767500 0.211564 +0.767500 0.211564 +0.767335 0.211272 +0.767335 0.211272 +0.767130 0.211030 +0.766882 0.210829 +0.767130 0.211030 +0.766584 0.210668 +0.766882 0.210829 +0.766584 0.210668 +0.766246 0.210563 +0.766246 0.210563 +0.679812 0.259161 +0.681277 0.256677 +0.683915 0.252205 +0.683915 0.252205 +0.679812 0.259161 +0.680455 0.261512 +0.682486 0.262659 +0.682486 0.262659 +0.680455 0.261512 +0.688992 0.255074 +0.686354 0.259545 +0.684888 0.262029 +0.688992 0.255074 +0.684888 0.262029 +0.686318 0.251575 +0.686318 0.251575 +0.688348 0.252722 +0.688348 0.252722 +0.684458 0.262518 +0.684703 0.262286 +0.686354 0.259545 +0.681277 0.256677 +0.684888 0.262029 +0.679812 0.259161 +0.679677 0.259447 +0.679595 0.259770 +0.679579 0.260117 +0.679636 0.260467 +0.679765 0.260798 +0.679957 0.261091 +0.680193 0.261330 +0.680455 0.261512 +0.682486 0.262659 +0.682778 0.262791 +0.683109 0.262871 +0.683463 0.262887 +0.683821 0.262831 +0.684159 0.262705 +0.684889 0.164760 +0.686354 0.167244 +0.688992 0.171716 +0.688992 0.171716 +0.684889 0.164760 +0.682486 0.164130 +0.682486 0.164130 +0.680455 0.165278 +0.680455 0.165278 +0.679812 0.167629 +0.683915 0.174584 +0.681277 0.170113 +0.679812 0.167629 +0.683915 0.174584 +0.688348 0.174067 +0.688348 0.174067 +0.686318 0.175214 +0.686318 0.175214 +0.679595 0.167020 +0.679677 0.167343 +0.679812 0.167629 +0.681277 0.170113 +0.686354 0.167244 +0.684889 0.164760 +0.684703 0.164503 +0.684458 0.164272 +0.684159 0.164085 +0.683821 0.163958 +0.683463 0.163902 +0.683109 0.163918 +0.682778 0.163998 +0.682486 0.164130 +0.680455 0.165278 +0.680193 0.165459 +0.679957 0.165699 +0.679765 0.165991 +0.679636 0.166323 +0.679579 0.166673 +0.686318 0.251575 +0.686026 0.251443 +0.683915 0.252205 +0.681277 0.256677 +0.686354 0.259545 +0.684346 0.251717 +0.688992 0.255074 +0.689168 0.254658 +0.689228 0.254213 +0.689170 0.253775 +0.688992 0.253352 +0.688707 0.252990 +0.688534 0.252843 +0.688348 0.252722 +0.684645 0.251530 +0.684983 0.251403 +0.685341 0.251347 +0.685695 0.251363 +0.688348 0.174067 +0.688534 0.173946 +0.686354 0.167244 +0.681277 0.170113 +0.688992 0.171716 +0.683915 0.174584 +0.684346 0.175073 +0.689168 0.172131 +0.684983 0.175386 +0.685341 0.175442 +0.685695 0.175427 +0.686026 0.175346 +0.686318 0.175214 +0.689228 0.172577 +0.689170 0.173014 +0.688992 0.173437 +0.688707 0.173799 +0.686026 0.251443 +0.686318 0.251575 +0.683915 0.252205 +0.683915 0.252205 +0.684128 0.251918 +0.684101 0.251948 +0.684390 0.251684 +0.684346 0.251717 +0.684682 0.251512 +0.684645 0.251530 +0.684983 0.251403 +0.684810 0.251458 +0.684983 0.251403 +0.685300 0.251350 +0.685161 0.251366 +0.685640 0.251356 +0.685341 0.251347 +0.685987 0.251430 +0.685695 0.251363 +0.686318 0.251575 +0.689223 0.254344 +0.689228 0.254213 +0.688992 0.255074 +0.688992 0.255074 +0.689093 0.254872 +0.689054 0.254958 +0.689168 0.254658 +0.689213 0.254437 +0.689168 0.254658 +0.689228 0.254213 +0.680455 0.261512 +0.680455 0.261512 +0.679664 0.259484 +0.679812 0.259161 +0.679812 0.259161 +0.679588 0.259824 +0.679664 0.259484 +0.679588 0.259824 +0.679582 0.260157 +0.679636 0.260467 +0.679582 0.260157 +0.679636 0.260467 +0.679747 0.260762 +0.679923 0.261048 +0.679747 0.260762 +0.680162 0.261304 +0.679923 0.261048 +0.680162 0.261304 +0.682817 0.262804 +0.682486 0.262659 +0.684888 0.262029 +0.684888 0.262029 +0.684676 0.262317 +0.684676 0.262317 +0.684414 0.262551 +0.684122 0.262722 +0.684414 0.262551 +0.683821 0.262831 +0.684122 0.262722 +0.683504 0.262885 +0.683821 0.262831 +0.683163 0.262879 +0.683504 0.262885 +0.682817 0.262804 +0.683163 0.262879 +0.682486 0.262659 +0.689096 0.173231 +0.688348 0.174067 +0.688348 0.174067 +0.688534 0.173946 +0.688707 0.173799 +0.688561 0.173925 +0.688861 0.173628 +0.688807 0.173694 +0.688992 0.173437 +0.689228 0.172577 +0.689228 0.172577 +0.689209 0.172828 +0.689214 0.172794 +0.689127 0.173151 +0.689170 0.173014 +0.688992 0.173437 +0.686318 0.175214 +0.686318 0.175214 +0.683915 0.174584 +0.683915 0.174584 +0.684101 0.174841 +0.684346 0.175073 +0.684128 0.174872 +0.684645 0.175260 +0.684390 0.175106 +0.684810 0.175332 +0.684682 0.175278 +0.684983 0.175386 +0.685161 0.175424 +0.684983 0.175386 +0.685341 0.175442 +0.685300 0.175440 +0.685695 0.175427 +0.685640 0.175434 +0.686026 0.175346 +0.685987 0.175359 +0.684889 0.164760 +0.684889 0.164760 +0.682817 0.163985 +0.682486 0.164130 +0.682486 0.164130 +0.682817 0.163985 +0.683163 0.163911 +0.683504 0.163905 +0.683163 0.163911 +0.683821 0.163958 +0.683504 0.163905 +0.683821 0.163958 +0.684122 0.164067 +0.684122 0.164067 +0.684414 0.164239 +0.684414 0.164239 +0.684676 0.164473 +0.684676 0.164473 +0.680455 0.165278 +0.680455 0.165278 +0.679664 0.167305 +0.679812 0.167629 +0.679812 0.167629 +0.679664 0.167305 +0.679588 0.166966 +0.679582 0.166633 +0.679588 0.166966 +0.679582 0.166633 +0.679636 0.166323 +0.679636 0.166323 +0.679747 0.166028 +0.679923 0.165742 +0.679747 0.166028 +0.679923 0.165742 +0.680162 0.165485 +0.680162 0.165485 +0.214843 0.216263 +0.223050 0.216263 +0.217774 0.216263 +0.214843 0.216263 +0.223050 0.216263 +0.224808 0.212247 +0.224808 0.212247 +0.224808 0.214542 +0.224808 0.214542 +0.223050 0.210526 +0.223050 0.210526 +0.214843 0.210526 +0.214843 0.210526 +0.217774 0.210526 +0.213084 0.214542 +0.213084 0.212247 +0.213084 0.212247 +0.213084 0.214542 +0.214195 0.216142 +0.214523 0.216235 +0.217774 0.216263 +0.217774 0.210526 +0.214843 0.216263 +0.214843 0.210526 +0.214523 0.210555 +0.214195 0.210647 +0.213880 0.210807 +0.213599 0.211030 +0.213371 0.211305 +0.213207 0.211614 +0.213113 0.211934 +0.213084 0.212247 +0.213084 0.214542 +0.213113 0.214855 +0.213207 0.215176 +0.213371 0.215484 +0.213599 0.215759 +0.213880 0.215983 +0.300917 0.259161 +0.296813 0.252205 +0.299451 0.256677 +0.300917 0.259161 +0.296813 0.252205 +0.294411 0.251575 +0.292380 0.252722 +0.292380 0.252722 +0.294411 0.251575 +0.295840 0.262029 +0.294374 0.259545 +0.291737 0.255073 +0.291737 0.255073 +0.295840 0.262029 +0.300273 0.261512 +0.298242 0.262659 +0.298242 0.262659 +0.300273 0.261512 +0.297620 0.262871 +0.297951 0.262791 +0.299451 0.256677 +0.294374 0.259545 +0.300917 0.259161 +0.301093 0.259576 +0.301152 0.260021 +0.301095 0.260459 +0.300917 0.260882 +0.300632 0.261244 +0.300273 0.261512 +0.298242 0.262659 +0.295840 0.262029 +0.296025 0.262286 +0.296271 0.262518 +0.296569 0.262705 +0.296908 0.262831 +0.297266 0.262887 +0.295840 0.164760 +0.291737 0.171716 +0.294374 0.167244 +0.295840 0.164760 +0.291737 0.171716 +0.294411 0.175214 +0.294411 0.175214 +0.292380 0.174067 +0.292380 0.174067 +0.296813 0.174584 +0.296813 0.174584 +0.300917 0.167629 +0.300917 0.167629 +0.299451 0.170113 +0.300273 0.165277 +0.300273 0.165277 +0.298242 0.164130 +0.298242 0.164130 +0.296271 0.164272 +0.296025 0.164503 +0.294374 0.167244 +0.299451 0.170113 +0.295840 0.164760 +0.300917 0.167629 +0.301093 0.167213 +0.301152 0.166768 +0.301095 0.166330 +0.300917 0.165907 +0.300632 0.165545 +0.300273 0.165277 +0.298242 0.164130 +0.297951 0.163998 +0.297620 0.163918 +0.297266 0.163902 +0.296908 0.163958 +0.296569 0.164085 +0.224808 0.212247 +0.224779 0.211934 +0.217774 0.210526 +0.217774 0.216263 +0.223050 0.210526 +0.223050 0.216263 +0.223697 0.210647 +0.223697 0.216142 +0.224293 0.215759 +0.224522 0.215484 +0.224685 0.215176 +0.224779 0.214855 +0.224808 0.214542 +0.224012 0.210807 +0.224293 0.211030 +0.224522 0.211305 +0.224685 0.211614 +0.292380 0.252722 +0.292118 0.252904 +0.291737 0.255073 +0.294374 0.259545 +0.299451 0.256677 +0.296813 0.252205 +0.291520 0.254464 +0.296383 0.251717 +0.295745 0.251403 +0.295388 0.251347 +0.295033 0.251363 +0.294703 0.251443 +0.294411 0.251575 +0.291504 0.254118 +0.291561 0.253767 +0.291690 0.253436 +0.291881 0.253144 +0.294411 0.175214 +0.294703 0.175346 +0.296813 0.174584 +0.299451 0.170113 +0.294374 0.167244 +0.291737 0.171716 +0.296383 0.175073 +0.291520 0.172325 +0.291561 0.173022 +0.291690 0.173353 +0.291881 0.173646 +0.292118 0.173885 +0.292380 0.174067 +0.296084 0.175260 +0.295745 0.175386 +0.295388 0.175442 +0.295033 0.175426 +0.224808 0.214542 +0.224808 0.214542 +0.223050 0.216263 +0.223050 0.216263 +0.223370 0.216235 +0.223697 0.216142 +0.223370 0.216235 +0.224012 0.215983 +0.223697 0.216142 +0.224158 0.215878 +0.224012 0.215983 +0.224293 0.215759 +0.224415 0.215627 +0.224293 0.215759 +0.224522 0.215484 +0.224522 0.215484 +0.224685 0.215176 +0.224685 0.215176 +0.224779 0.214855 +0.224779 0.214855 +0.224158 0.210911 +0.224808 0.212247 +0.224808 0.212247 +0.224779 0.211934 +0.224685 0.211614 +0.224779 0.211934 +0.224522 0.211305 +0.224685 0.211614 +0.224415 0.211162 +0.224522 0.211305 +0.224293 0.211030 +0.223050 0.210526 +0.223050 0.210526 +0.223370 0.210555 +0.223370 0.210555 +0.223697 0.210647 +0.223697 0.210647 +0.224012 0.210807 +0.224012 0.210807 +0.224293 0.211030 +0.213084 0.214542 +0.213084 0.214542 +0.214523 0.216235 +0.214843 0.216263 +0.214843 0.216263 +0.214523 0.216235 +0.214195 0.216142 +0.213880 0.215983 +0.214195 0.216142 +0.213880 0.215983 +0.213599 0.215759 +0.213599 0.215759 +0.213371 0.215484 +0.213371 0.215484 +0.213207 0.215176 +0.213207 0.215176 +0.213113 0.214855 +0.213113 0.214855 +0.214843 0.210526 +0.214843 0.210526 +0.213084 0.212247 +0.213084 0.212247 +0.213113 0.211934 +0.213113 0.211934 +0.213207 0.211614 +0.213207 0.211614 +0.213371 0.211305 +0.213371 0.211305 +0.213599 0.211030 +0.213599 0.211030 +0.213880 0.210807 +0.213880 0.210807 +0.214195 0.210647 +0.214195 0.210647 +0.214523 0.210555 +0.214523 0.210555 +0.294411 0.251575 +0.294411 0.251575 +0.296628 0.251948 +0.296813 0.252205 +0.296813 0.252205 +0.296383 0.251717 +0.296628 0.251948 +0.296084 0.251530 +0.296383 0.251717 +0.295918 0.251458 +0.296084 0.251530 +0.295745 0.251403 +0.295568 0.251366 +0.295745 0.251403 +0.295388 0.251347 +0.295388 0.251347 +0.295033 0.251363 +0.295033 0.251363 +0.294703 0.251443 +0.294703 0.251443 +0.292118 0.252904 +0.292380 0.252722 +0.291737 0.255073 +0.291737 0.255073 +0.291602 0.254788 +0.291602 0.254788 +0.291520 0.254464 +0.291520 0.254464 +0.291504 0.254118 +0.291504 0.254118 +0.291561 0.253767 +0.291523 0.253942 +0.291561 0.253767 +0.291690 0.253436 +0.291617 0.253598 +0.291881 0.253144 +0.291690 0.253436 +0.292118 0.252904 +0.291881 0.253144 +0.292380 0.252722 +0.300717 0.261155 +0.300471 0.261382 +0.300273 0.261512 +0.300273 0.261512 +0.301152 0.260021 +0.301152 0.260021 +0.301136 0.260254 +0.301136 0.260254 +0.301059 0.260576 +0.300917 0.260882 +0.301059 0.260576 +0.300917 0.260882 +0.300717 0.261155 +0.300471 0.261382 +0.296025 0.262286 +0.295840 0.262029 +0.297951 0.262791 +0.298242 0.262659 +0.298242 0.262659 +0.297951 0.262791 +0.297620 0.262871 +0.297620 0.262871 +0.297266 0.262887 +0.297266 0.262887 +0.296908 0.262831 +0.296908 0.262831 +0.296569 0.262705 +0.296271 0.262518 +0.296569 0.262705 +0.296271 0.262518 +0.296025 0.262286 +0.295840 0.262029 +0.292380 0.174067 +0.292380 0.174067 +0.291737 0.171716 +0.291737 0.171716 +0.291602 0.172001 +0.291520 0.172325 +0.291602 0.172001 +0.291504 0.172672 +0.291520 0.172325 +0.291523 0.172848 +0.291504 0.172672 +0.291561 0.173022 +0.291617 0.173191 +0.291561 0.173022 +0.291690 0.173353 +0.291690 0.173353 +0.291881 0.173646 +0.291881 0.173646 +0.292118 0.173885 +0.292118 0.173885 +0.295918 0.175331 +0.294411 0.175214 +0.294411 0.175214 +0.294703 0.175346 +0.295033 0.175426 +0.294703 0.175346 +0.295388 0.175442 +0.295033 0.175426 +0.295568 0.175423 +0.295388 0.175442 +0.295745 0.175386 +0.296813 0.174584 +0.296813 0.174584 +0.296628 0.174841 +0.296628 0.174841 +0.296383 0.175073 +0.296383 0.175073 +0.296084 0.175260 +0.296084 0.175260 +0.295745 0.175386 +0.298242 0.164130 +0.298242 0.164130 +0.296025 0.164503 +0.295840 0.164760 +0.295840 0.164760 +0.296025 0.164503 +0.296271 0.164272 +0.296271 0.164272 +0.296569 0.164085 +0.296569 0.164085 +0.296908 0.163958 +0.296908 0.163958 +0.297266 0.163902 +0.297266 0.163902 +0.297620 0.163918 +0.297620 0.163918 +0.297951 0.163998 +0.297951 0.163998 +0.300979 0.167513 +0.300917 0.167629 +0.300917 0.167629 +0.300979 0.167513 +0.301147 0.166899 +0.301152 0.166768 +0.301152 0.166768 +0.301093 0.167213 +0.301147 0.166899 +0.301093 0.167213 +0.932751 0.205756 +0.933930 0.209178 +0.934278 0.211100 +0.934436 0.210925 +0.896157 0.212601 +0.896330 0.212777 +0.896323 0.210808 +0.896500 0.210832 +0.897189 0.207263 +0.897359 0.207321 +0.898817 0.203817 +0.898971 0.203906 +0.901173 0.200700 +0.901305 0.200819 +0.904132 0.198123 +0.904237 0.198265 +0.907493 0.196226 +0.911022 0.195062 +0.907566 0.196386 +0.911063 0.195232 +0.914504 0.194593 +0.914512 0.194768 +0.918014 0.194753 +0.921636 0.195601 +0.917989 0.194926 +0.921578 0.195766 +0.925158 0.197193 +0.925067 0.197344 +0.928342 0.199500 +0.928222 0.199629 +0.930976 0.202396 +0.930831 0.202498 +0.932914 0.205685 +0.934104 0.209139 +0.896641 0.217662 +0.934436 0.215865 +0.934278 0.215690 +0.896815 0.217622 +0.896757 0.217370 +0.896613 0.217544 +0.934421 0.215970 +0.934244 0.215946 +0.933557 0.219515 +0.933388 0.219458 +0.931932 0.222963 +0.931778 0.222874 +0.929577 0.226081 +0.926619 0.228660 +0.929445 0.225963 +0.926515 0.228518 +0.923260 0.230559 +0.923187 0.230399 +0.919731 0.231725 +0.916250 0.232196 +0.919691 0.231555 +0.916242 0.232021 +0.912740 0.232039 +0.909117 0.231193 +0.912764 0.231865 +0.909175 0.231027 +0.905594 0.229602 +0.905686 0.229451 +0.902409 0.227298 +0.902529 0.227168 +0.899773 0.224403 +0.897833 0.221115 +0.899918 0.224301 +0.897996 0.221043 +0.909463 0.214465 +0.899480 0.203110 +0.909784 0.211230 +0.897770 0.206257 +0.909463 0.212325 +0.896731 0.209540 +0.909362 0.213395 +0.901819 0.200290 +0.910342 0.210177 +0.904672 0.197967 +0.911122 0.209237 +0.907868 0.196256 +0.912083 0.208473 +0.911209 0.195200 +0.913159 0.207927 +0.914512 0.194768 +0.914278 0.207612 +0.917841 0.194907 +0.915371 0.207514 +0.921266 0.195664 +0.916465 0.207612 +0.924606 0.197086 +0.811025 0.213395 +0.815450 0.218220 +0.811501 0.218700 +0.816900 0.223156 +0.813019 0.224114 +0.819415 0.227906 +0.815641 0.229343 +0.822934 0.232146 +0.819311 0.234068 +0.827267 0.235590 +0.823848 0.238006 +0.832120 0.238051 +0.828978 0.240959 +0.837164 0.239470 +0.834379 0.242849 +0.842094 0.239913 +0.917583 0.207927 +0.927661 0.199148 +0.918659 0.208473 +0.930251 0.201750 +0.811491 0.208147 +0.814998 0.213395 +0.812973 0.202795 +0.815450 0.208569 +0.815531 0.197622 +0.816900 0.203634 +0.819112 0.192933 +0.819415 0.198884 +0.823544 0.189003 +0.822934 0.194644 +0.828565 0.186023 +0.827267 0.191199 +0.833869 0.184073 +0.832120 0.188739 +0.839163 0.183124 +0.837164 0.187319 +0.919620 0.209237 +0.932243 0.204734 +0.920400 0.210177 +0.933581 0.207911 +0.934278 0.211100 +0.920958 0.211230 +0.845025 0.147992 +0.839163 0.147992 +0.845025 0.183124 +0.842094 0.186877 +0.850239 0.184052 +0.847025 0.187319 +0.855461 0.185946 +0.852068 0.188739 +0.860412 0.188835 +0.856921 0.191199 +0.864803 0.192643 +0.861254 0.194644 +0.868384 0.197190 +0.864774 0.198884 +0.870990 0.202222 +0.872564 0.207449 +0.867288 0.203634 +0.873153 0.212604 +0.868738 0.208569 +0.952848 0.215690 +0.952848 0.211100 +0.934278 0.215690 +0.921280 0.212325 +0.932420 0.221718 +0.921380 0.213395 +0.921280 0.214465 +0.930630 0.224559 +0.920958 0.215559 +0.928310 0.227081 +0.920400 0.216613 +0.925561 0.229149 +0.919620 0.217553 +0.922527 0.230675 +0.918659 0.218317 +0.916242 0.232021 +0.917583 0.218862 +0.916465 0.219177 +0.909858 0.231243 +0.915371 0.219275 +0.914278 0.219177 +0.906694 0.229994 +0.913159 0.218862 +0.903764 0.228180 +0.901218 0.225877 +0.912083 0.218317 +0.899171 0.223207 +0.911122 0.217553 +0.896757 0.217370 +0.910342 0.216613 +0.909784 0.215559 +0.839749 0.243715 +0.839749 0.278797 +0.844439 0.278797 +0.847025 0.239470 +0.844439 0.243715 +0.852068 0.238051 +0.856921 0.235590 +0.854413 0.241309 +0.859192 0.238783 +0.861254 0.232146 +0.863511 0.235423 +0.864774 0.227906 +0.867155 0.231368 +0.867288 0.223156 +0.869970 0.226822 +0.868738 0.218220 +0.869190 0.213395 +0.872920 0.217192 +0.896330 0.212777 +0.951081 0.215887 +0.944613 0.215871 +0.951081 0.215888 +0.952848 0.215690 +0.934278 0.215690 +0.934436 0.215865 +0.937879 0.215865 +0.952840 0.215887 +0.937879 0.210925 +0.934436 0.210925 +0.951081 0.210902 +0.951081 0.210902 +0.934278 0.211100 +0.952848 0.211100 +0.952840 0.210902 +0.944624 0.210919 +0.921380 0.213395 +0.915371 0.213395 +0.909362 0.213395 +0.909463 0.214465 +0.909784 0.215559 +0.910342 0.216613 +0.911122 0.217553 +0.912083 0.218317 +0.913159 0.218862 +0.914278 0.219177 +0.915371 0.219275 +0.916465 0.219177 +0.917583 0.218862 +0.918659 0.218317 +0.919620 0.217553 +0.920400 0.216613 +0.920958 0.215559 +0.921280 0.214465 +0.915371 0.213395 +0.915371 0.213395 +0.915371 0.213395 +0.915371 0.213395 +0.915371 0.213395 +0.915371 0.213395 +0.915371 0.213395 +0.915371 0.213395 +0.915371 0.213395 +0.915371 0.213395 +0.915371 0.213395 +0.915371 0.213395 +0.915371 0.213395 +0.915371 0.213395 +0.915371 0.213395 +0.915371 0.213395 +0.921380 0.213395 +0.921380 0.213395 +0.909463 0.214465 +0.909362 0.213395 +0.909362 0.213395 +0.909784 0.215559 +0.909463 0.214465 +0.910342 0.216613 +0.909784 0.215559 +0.910342 0.216613 +0.911122 0.217553 +0.911122 0.217553 +0.912083 0.218317 +0.912083 0.218317 +0.913159 0.218862 +0.914278 0.219177 +0.913159 0.218862 +0.915371 0.219275 +0.914278 0.219177 +0.916465 0.219177 +0.915371 0.219275 +0.916465 0.219177 +0.917583 0.218862 +0.917583 0.218862 +0.918659 0.218317 +0.918659 0.218317 +0.919620 0.217553 +0.919620 0.217553 +0.920400 0.216613 +0.920400 0.216613 +0.920958 0.215559 +0.920958 0.215559 +0.921280 0.214465 +0.921280 0.214465 +0.823191 0.189043 +0.834298 0.183961 +0.839163 0.183124 +0.838984 0.182965 +0.834253 0.183791 +0.828421 0.186091 +0.828342 0.185934 +0.823299 0.189183 +0.811240 0.208550 +0.810846 0.213395 +0.811025 0.213395 +0.811417 0.208577 +0.812862 0.202588 +0.813029 0.202650 +0.815538 0.197276 +0.815691 0.197368 +0.818979 0.192816 +0.819111 0.192934 +0.815714 0.213395 +0.814998 0.213395 +0.868738 0.218220 +0.869190 0.213395 +0.868474 0.213395 +0.868033 0.218093 +0.867288 0.223156 +0.866622 0.222898 +0.864774 0.227906 +0.864174 0.227522 +0.861254 0.232146 +0.860747 0.231650 +0.856921 0.235590 +0.856529 0.235003 +0.852068 0.238051 +0.851804 0.237399 +0.847025 0.239470 +0.846894 0.238781 +0.842094 0.239913 +0.842094 0.239212 +0.837164 0.239470 +0.837294 0.238781 +0.832120 0.238051 +0.832384 0.237399 +0.827267 0.235590 +0.827659 0.235003 +0.822934 0.232146 +0.823441 0.231650 +0.819415 0.227906 +0.820014 0.227522 +0.816900 0.223156 +0.817567 0.222898 +0.815450 0.218220 +0.816155 0.218092 +0.844641 0.278797 +0.844641 0.277076 +0.844641 0.277076 +0.844618 0.243877 +0.844439 0.243715 +0.844618 0.264168 +0.844624 0.270752 +0.844439 0.278797 +0.839547 0.277076 +0.839564 0.270752 +0.839547 0.277076 +0.839749 0.278797 +0.839749 0.243715 +0.839570 0.243877 +0.839570 0.264168 +0.839547 0.278797 +0.845227 0.149713 +0.845210 0.156037 +0.845227 0.149713 +0.845025 0.147992 +0.845025 0.183124 +0.845204 0.182965 +0.845204 0.162622 +0.845227 0.147992 +0.838961 0.147992 +0.838961 0.149713 +0.838961 0.149713 +0.838984 0.182965 +0.839163 0.183124 +0.838984 0.162622 +0.838978 0.156037 +0.839163 0.147992 +0.082896 0.221115 +0.046485 0.215946 +0.046450 0.215689 +0.084115 0.217544 +0.083971 0.217370 +0.084088 0.217662 +0.046293 0.215865 +0.046307 0.215970 +0.047341 0.219458 +0.048951 0.222874 +0.047172 0.219515 +0.048797 0.222963 +0.051284 0.225963 +0.051152 0.226081 +0.054214 0.228518 +0.054109 0.228660 +0.057542 0.230399 +0.061038 0.231555 +0.057469 0.230559 +0.060997 0.231725 +0.064486 0.232021 +0.067964 0.231865 +0.064478 0.232196 +0.067989 0.232038 +0.071553 0.231027 +0.071612 0.231192 +0.075043 0.229451 +0.075134 0.229602 +0.078199 0.227168 +0.078320 0.227297 +0.080811 0.224300 +0.082733 0.221043 +0.080956 0.224403 +0.083913 0.217622 +0.083370 0.207320 +0.046293 0.210925 +0.046450 0.211100 +0.046624 0.209139 +0.084229 0.210832 +0.084399 0.212777 +0.084571 0.212600 +0.047814 0.205684 +0.046799 0.209178 +0.047977 0.205756 +0.049752 0.202396 +0.049897 0.202498 +0.052386 0.199500 +0.055571 0.197193 +0.052507 0.199629 +0.055662 0.197344 +0.059092 0.195601 +0.062715 0.194752 +0.059151 0.195766 +0.062739 0.194926 +0.066225 0.194593 +0.066217 0.194768 +0.069706 0.195061 +0.073236 0.196226 +0.069666 0.195232 +0.073162 0.196385 +0.076596 0.198122 +0.076492 0.198265 +0.079555 0.200700 +0.079423 0.200818 +0.081912 0.203817 +0.081758 0.203906 +0.083539 0.207263 +0.084406 0.210808 +0.084571 0.212600 +0.084399 0.212777 +0.107575 0.212604 +0.107401 0.212430 +0.083971 0.217370 +0.084115 0.217544 +0.107651 0.217368 +0.107808 0.217192 +0.027881 0.211100 +0.027840 0.213395 +0.112345 0.197190 +0.113441 0.203633 +0.115926 0.192642 +0.115955 0.198884 +0.120317 0.188835 +0.119475 0.194644 +0.125268 0.185946 +0.123807 0.191199 +0.130489 0.184052 +0.128660 0.188738 +0.135703 0.183124 +0.133704 0.187319 +0.081249 0.203110 +0.069606 0.209236 +0.078910 0.200289 +0.068645 0.208473 +0.076056 0.197967 +0.067569 0.207927 +0.072861 0.196256 +0.066451 0.207612 +0.069520 0.195199 +0.065357 0.207514 +0.066217 0.194768 +0.064264 0.207612 +0.062888 0.194906 +0.063146 0.207927 +0.059463 0.195664 +0.082958 0.206257 +0.070387 0.210177 +0.083998 0.209540 +0.070944 0.211230 +0.084399 0.212777 +0.071266 0.212325 +0.062069 0.208473 +0.056123 0.197086 +0.061109 0.209236 +0.053067 0.199147 +0.109739 0.202222 +0.111991 0.208569 +0.108165 0.207449 +0.111538 0.213395 +0.060328 0.210177 +0.050478 0.201750 +0.048485 0.204734 +0.059771 0.211230 +0.047148 0.207911 +0.059449 0.212325 +0.141565 0.183124 +0.141565 0.147992 +0.135703 0.147992 +0.138635 0.186877 +0.146889 0.184081 +0.143565 0.187319 +0.152223 0.186050 +0.148608 0.188738 +0.157269 0.189064 +0.153462 0.191199 +0.161716 0.193040 +0.157794 0.194644 +0.165295 0.197781 +0.161314 0.198884 +0.167834 0.203005 +0.163828 0.203633 +0.169282 0.208402 +0.165278 0.208569 +0.169180 0.218955 +0.165731 0.213395 +0.167628 0.224323 +0.165278 0.218220 +0.164988 0.229500 +0.163828 0.223156 +0.161318 0.234173 +0.161314 0.227906 +0.156795 0.238066 +0.157794 0.232146 +0.151691 0.240986 +0.153462 0.235590 +0.146320 0.242856 +0.148608 0.238051 +0.140979 0.243714 +0.143565 0.239470 +0.136290 0.243714 +0.136290 0.278797 +0.140979 0.278797 +0.138635 0.239913 +0.126315 0.241309 +0.133704 0.239470 +0.128660 0.238051 +0.121536 0.238783 +0.117217 0.235422 +0.123807 0.235590 +0.113574 0.231368 +0.119475 0.232146 +0.110758 0.226822 +0.115955 0.227906 +0.107808 0.217192 +0.113441 0.223156 +0.111991 0.218220 +0.083971 0.217370 +0.107575 0.212604 +0.071366 0.213395 +0.081558 0.223207 +0.071266 0.214465 +0.070944 0.215559 +0.079511 0.225877 +0.070387 0.216612 +0.076965 0.228180 +0.069606 0.217553 +0.074034 0.229994 +0.068645 0.218317 +0.070871 0.231242 +0.064486 0.232021 +0.067569 0.218862 +0.066451 0.219177 +0.058201 0.230675 +0.065357 0.219275 +0.064264 0.219177 +0.055167 0.229149 +0.063146 0.218862 +0.052419 0.227081 +0.062069 0.218317 +0.050098 0.224559 +0.061109 0.217553 +0.048309 0.221718 +0.046450 0.215689 +0.060328 0.216612 +0.059771 0.215559 +0.059449 0.214465 +0.059349 0.213395 +0.046450 0.211100 +0.027881 0.215689 +0.042850 0.215865 +0.046293 0.215865 +0.029648 0.215887 +0.029648 0.215887 +0.046450 0.215689 +0.027881 0.215689 +0.027888 0.215887 +0.036118 0.215870 +0.046450 0.211100 +0.046293 0.210925 +0.027888 0.210902 +0.027881 0.211100 +0.029648 0.210902 +0.036116 0.210919 +0.042850 0.210925 +0.071366 0.213395 +0.065357 0.213395 +0.059349 0.213395 +0.059449 0.214465 +0.059771 0.215559 +0.060328 0.216612 +0.061109 0.217553 +0.062069 0.218317 +0.063146 0.218862 +0.064264 0.219177 +0.065357 0.219275 +0.066451 0.219177 +0.067569 0.218862 +0.068645 0.218317 +0.069606 0.217553 +0.070387 0.216612 +0.070944 0.215559 +0.071266 0.214465 +0.065357 0.213395 +0.065357 0.213395 +0.065357 0.213395 +0.065357 0.213395 +0.065357 0.213395 +0.065357 0.213395 +0.065357 0.213395 +0.065357 0.213395 +0.065357 0.213395 +0.065357 0.213395 +0.065357 0.213395 +0.065357 0.213395 +0.065357 0.213395 +0.065357 0.213395 +0.065357 0.213395 +0.065357 0.213395 +0.071366 0.213395 +0.071366 0.213395 +0.059449 0.214465 +0.059349 0.213395 +0.059349 0.213395 +0.059449 0.214465 +0.059771 0.215559 +0.060328 0.216612 +0.059771 0.215559 +0.060328 0.216612 +0.061109 0.217553 +0.062069 0.218317 +0.061109 0.217553 +0.063146 0.218862 +0.062069 0.218317 +0.063146 0.218862 +0.064264 0.219177 +0.064264 0.219177 +0.065357 0.219275 +0.065357 0.219275 +0.066451 0.219177 +0.066451 0.219177 +0.067569 0.218862 +0.067569 0.218862 +0.068645 0.218317 +0.068645 0.218317 +0.069606 0.217553 +0.069606 0.217553 +0.070387 0.216612 +0.070387 0.216612 +0.070944 0.215559 +0.070944 0.215559 +0.071266 0.214465 +0.071266 0.214465 +0.115955 0.227906 +0.112695 0.218092 +0.112255 0.213395 +0.111538 0.213395 +0.114107 0.222898 +0.111991 0.218220 +0.113441 0.223156 +0.116555 0.227522 +0.165731 0.213395 +0.165014 0.213395 +0.165278 0.218220 +0.164574 0.218092 +0.163828 0.223156 +0.163162 0.222898 +0.161314 0.227906 +0.160714 0.227522 +0.157794 0.232146 +0.157288 0.231650 +0.153462 0.235590 +0.153070 0.235003 +0.148608 0.238051 +0.148345 0.237399 +0.143565 0.239470 +0.143435 0.238780 +0.138635 0.239913 +0.138635 0.239211 +0.133704 0.239470 +0.128660 0.238051 +0.133834 0.238780 +0.128924 0.237399 +0.123807 0.235590 +0.119475 0.232146 +0.124199 0.235003 +0.119981 0.231650 +0.135948 0.219082 +0.116555 0.227522 +0.132482 0.219416 +0.114107 0.222898 +0.131465 0.218220 +0.119981 0.231650 +0.133000 0.219795 +0.112695 0.218092 +0.130649 0.216777 +0.112255 0.213395 +0.130118 0.215139 +0.112695 0.208697 +0.129933 0.213395 +0.114107 0.203892 +0.130118 0.211650 +0.116555 0.199267 +0.130649 0.210012 +0.119981 0.195139 +0.131465 0.208569 +0.124199 0.191786 +0.132482 0.207373 +0.124199 0.235003 +0.133635 0.220019 +0.128924 0.189390 +0.132798 0.207116 +0.133180 0.206909 +0.133834 0.188009 +0.133613 0.206774 +0.128924 0.237399 +0.134310 0.220050 +0.133834 0.238780 +0.134937 0.219894 +0.138635 0.187578 +0.134075 0.206727 +0.134536 0.206774 +0.143435 0.188009 +0.134970 0.206909 +0.138635 0.239211 +0.135492 0.219570 +0.143435 0.238780 +0.148345 0.189390 +0.135351 0.207116 +0.153070 0.191786 +0.135668 0.207373 +0.157288 0.195139 +0.135931 0.207683 +0.160714 0.199267 +0.136142 0.208057 +0.163162 0.203892 +0.136280 0.208480 +0.164574 0.208697 +0.165014 0.213395 +0.136328 0.208932 +0.164574 0.218092 +0.136280 0.209384 +0.163162 0.222898 +0.160714 0.227522 +0.136142 0.209808 +0.157288 0.231650 +0.135931 0.210181 +0.135668 0.210491 +0.135177 0.211068 +0.134784 0.211764 +0.134528 0.212553 +0.134439 0.213395 +0.134528 0.214236 +0.134784 0.215025 +0.135177 0.215721 +0.135668 0.216298 +0.135946 0.216629 +0.136156 0.217013 +0.136285 0.217431 +0.136328 0.217857 +0.153070 0.235003 +0.136235 0.218483 +0.148345 0.237399 +0.141181 0.278797 +0.141181 0.277076 +0.141181 0.277076 +0.141158 0.243876 +0.140979 0.243714 +0.141158 0.264168 +0.141164 0.270752 +0.140979 0.278797 +0.136088 0.277076 +0.136105 0.270752 +0.136088 0.277076 +0.136290 0.278797 +0.136290 0.243714 +0.136111 0.243876 +0.136111 0.264168 +0.136088 0.278797 +0.141565 0.183124 +0.141745 0.182965 +0.141750 0.156037 +0.141768 0.149713 +0.141768 0.147992 +0.141565 0.147992 +0.141768 0.149713 +0.141745 0.162621 +0.135501 0.147992 +0.135501 0.149713 +0.135501 0.149713 +0.135524 0.182965 +0.135703 0.183124 +0.135524 0.162621 +0.135518 0.156037 +0.135703 0.147992 +0.136280 0.208480 +0.136007 0.210233 +0.135733 0.210555 +0.135668 0.210491 +0.136227 0.209844 +0.135931 0.210181 +0.136370 0.209402 +0.136142 0.209808 +0.136420 0.208932 +0.136280 0.209384 +0.136370 0.208462 +0.136328 0.208932 +0.132482 0.207373 +0.132417 0.207310 +0.132798 0.207116 +0.132746 0.207041 +0.133180 0.206909 +0.133613 0.206774 +0.133143 0.206826 +0.133594 0.206686 +0.134075 0.206727 +0.134075 0.206637 +0.134536 0.206774 +0.134970 0.206909 +0.134555 0.206686 +0.135006 0.206826 +0.135351 0.207116 +0.135403 0.207041 +0.135668 0.207373 +0.135931 0.207683 +0.135733 0.207310 +0.136142 0.208057 +0.136007 0.207632 +0.136227 0.208021 +0.131352 0.218054 +0.132482 0.219416 +0.131275 0.208686 +0.132417 0.207310 +0.132482 0.207373 +0.131352 0.208735 +0.130459 0.210227 +0.130544 0.210260 +0.129988 0.211829 +0.130079 0.211845 +0.129841 0.213395 +0.129988 0.214961 +0.129933 0.213395 +0.130079 0.214944 +0.130459 0.216562 +0.130544 0.216529 +0.131275 0.218104 +0.132417 0.219480 +0.135964 0.216657 +0.136419 0.217821 +0.136420 0.217857 +0.136328 0.217857 +0.136327 0.217822 +0.136368 0.217379 +0.136278 0.217398 +0.136241 0.216979 +0.136156 0.217013 +0.136042 0.216608 +0.135668 0.216298 +0.135733 0.216234 +0.135693 0.216323 +0.135759 0.216260 +0.135123 0.211148 +0.135668 0.210491 +0.135200 0.215592 +0.135733 0.216234 +0.135668 0.216298 +0.135123 0.215641 +0.134819 0.214873 +0.134599 0.214125 +0.134733 0.214906 +0.134509 0.214142 +0.134531 0.213395 +0.134599 0.212664 +0.134439 0.213395 +0.134819 0.211916 +0.134509 0.212647 +0.134733 0.211883 +0.135200 0.211197 +0.135733 0.210555 +0.844401 0.208932 +0.844798 0.210182 +0.845061 0.210491 +0.844996 0.210555 +0.844722 0.210233 +0.844586 0.209808 +0.844502 0.209844 +0.844449 0.209384 +0.848312 0.207310 +0.848247 0.207373 +0.847982 0.207041 +0.847585 0.206826 +0.847930 0.207116 +0.847549 0.206909 +0.847134 0.206686 +0.847115 0.206774 +0.846654 0.206638 +0.846173 0.206686 +0.846654 0.206728 +0.846192 0.206774 +0.845722 0.206826 +0.845325 0.207041 +0.845759 0.206909 +0.845377 0.207116 +0.844996 0.207310 +0.845061 0.207373 +0.844722 0.207632 +0.844798 0.207683 +0.844502 0.208021 +0.844586 0.208057 +0.844359 0.208462 +0.844449 0.208481 +0.844309 0.208932 +0.844359 0.209403 +0.845606 0.215642 +0.845061 0.216298 +0.845529 0.211197 +0.844996 0.210555 +0.845061 0.210491 +0.845606 0.211148 +0.845910 0.211917 +0.845995 0.211883 +0.846129 0.212664 +0.846220 0.212648 +0.846198 0.213395 +0.846129 0.214126 +0.846290 0.213395 +0.846220 0.214142 +0.845910 0.214873 +0.845529 0.215592 +0.845995 0.214906 +0.844996 0.216235 +0.845427 0.219707 +0.844350 0.218282 +0.844309 0.217857 +0.844401 0.217857 +0.844440 0.218266 +0.844487 0.218735 +0.844717 0.219151 +0.844572 0.218701 +0.845022 0.219505 +0.844793 0.219100 +0.845086 0.219441 +0.845377 0.219782 +0.848247 0.219416 +0.848312 0.219480 +0.847924 0.219678 +0.847976 0.219752 +0.847516 0.219894 +0.847071 0.220024 +0.847551 0.219977 +0.847088 0.220112 +0.846618 0.220062 +0.846617 0.220152 +0.846185 0.220014 +0.846166 0.220102 +0.845792 0.219894 +0.845756 0.219977 +0.850650 0.211845 +0.848247 0.207373 +0.848312 0.207310 +0.849377 0.208735 +0.850184 0.210260 +0.849454 0.208686 +0.848312 0.219480 +0.848247 0.219416 +0.849454 0.218104 +0.849377 0.218055 +0.850270 0.216562 +0.850184 0.216529 +0.850741 0.214961 +0.850650 0.214944 +0.850887 0.213395 +0.850795 0.213395 +0.850741 0.211829 +0.850270 0.210227 +0.619332 0.216263 +0.616401 0.216263 +0.611125 0.216263 +0.611125 0.216263 +0.619332 0.216263 +0.621091 0.214542 +0.621091 0.212247 +0.621091 0.212247 +0.621091 0.214542 +0.611125 0.210526 +0.616401 0.210526 +0.619332 0.210526 +0.611125 0.210526 +0.619332 0.210526 +0.609366 0.214542 +0.609366 0.214542 +0.609366 0.212247 +0.609366 0.212247 +0.619979 0.210647 +0.619652 0.210555 +0.616401 0.210526 +0.616401 0.216263 +0.619332 0.210526 +0.619332 0.216263 +0.619652 0.216235 +0.619979 0.216142 +0.620294 0.215983 +0.620575 0.215759 +0.620804 0.215484 +0.620967 0.215176 +0.621061 0.214855 +0.621091 0.214542 +0.621091 0.212247 +0.621061 0.211934 +0.620967 0.211614 +0.620804 0.211305 +0.620575 0.211030 +0.620294 0.210807 +0.533258 0.259161 +0.534723 0.256677 +0.537361 0.252205 +0.537361 0.252205 +0.533258 0.259161 +0.533901 0.261512 +0.535932 0.262659 +0.535932 0.262659 +0.533901 0.261512 +0.538334 0.262029 +0.542438 0.255074 +0.539800 0.259545 +0.538334 0.262029 +0.542438 0.255074 +0.539764 0.251575 +0.539764 0.251575 +0.541794 0.252722 +0.541794 0.252722 +0.537904 0.262518 +0.538149 0.262286 +0.539800 0.259545 +0.534723 0.256677 +0.538334 0.262029 +0.533258 0.259161 +0.533123 0.259446 +0.533041 0.259770 +0.533025 0.260117 +0.533082 0.260467 +0.533211 0.260798 +0.533403 0.261091 +0.533639 0.261330 +0.533901 0.261512 +0.535932 0.262659 +0.536224 0.262791 +0.536554 0.262871 +0.536909 0.262887 +0.537267 0.262831 +0.537605 0.262705 +0.542438 0.171716 +0.542438 0.171716 +0.538334 0.164760 +0.538334 0.164760 +0.539800 0.167244 +0.535932 0.164130 +0.535932 0.164130 +0.533901 0.165278 +0.533901 0.165278 +0.533258 0.167629 +0.537361 0.174584 +0.534723 0.170113 +0.533258 0.167629 +0.537361 0.174584 +0.541794 0.174067 +0.541794 0.174067 +0.539764 0.175214 +0.539764 0.175214 +0.533041 0.167020 +0.533123 0.167343 +0.533258 0.167629 +0.534723 0.170113 +0.539800 0.167244 +0.538334 0.164760 +0.538149 0.164503 +0.537904 0.164272 +0.537605 0.164085 +0.537267 0.163958 +0.536909 0.163902 +0.536554 0.163918 +0.536224 0.163998 +0.535932 0.164130 +0.533901 0.165278 +0.533639 0.165459 +0.533403 0.165699 +0.533211 0.165991 +0.533082 0.166323 +0.533025 0.166673 +0.609366 0.214542 +0.609396 0.214855 +0.616401 0.216263 +0.616401 0.210526 +0.611125 0.216263 +0.611125 0.210526 +0.610477 0.216142 +0.610477 0.210647 +0.609881 0.211030 +0.609653 0.211305 +0.609490 0.211614 +0.609396 0.211934 +0.609366 0.212247 +0.610162 0.215983 +0.609881 0.215759 +0.609653 0.215484 +0.609490 0.215176 +0.539764 0.251575 +0.539472 0.251443 +0.534723 0.256677 +0.539800 0.259545 +0.537361 0.252205 +0.537792 0.251717 +0.542438 0.255074 +0.542614 0.254658 +0.542674 0.254213 +0.542616 0.253775 +0.542438 0.253352 +0.542153 0.252990 +0.541980 0.252843 +0.541794 0.252722 +0.538091 0.251530 +0.538429 0.251403 +0.538787 0.251347 +0.539141 0.251363 +0.541794 0.174067 +0.541980 0.173946 +0.542438 0.171716 +0.539800 0.167244 +0.534723 0.170113 +0.537361 0.174584 +0.537792 0.175073 +0.542614 0.172131 +0.538429 0.175386 +0.538787 0.175442 +0.539141 0.175427 +0.539472 0.175346 +0.539764 0.175214 +0.542674 0.172577 +0.542616 0.173014 +0.542438 0.173437 +0.542153 0.173799 +0.609396 0.214855 +0.609366 0.214542 +0.611125 0.216263 +0.611125 0.216263 +0.610765 0.216227 +0.610805 0.216235 +0.610426 0.216122 +0.610477 0.216142 +0.610128 0.215960 +0.610162 0.215983 +0.609881 0.215759 +0.610016 0.215878 +0.609881 0.215759 +0.609676 0.215517 +0.609760 0.215627 +0.609511 0.215226 +0.609653 0.215484 +0.609403 0.214895 +0.609490 0.215176 +0.609366 0.214542 +0.609366 0.212247 +0.609366 0.212247 +0.610805 0.210555 +0.611125 0.210526 +0.611125 0.210526 +0.610477 0.210647 +0.610765 0.210563 +0.610162 0.210807 +0.610426 0.210668 +0.610016 0.210911 +0.610128 0.210829 +0.609881 0.211030 +0.609760 0.211162 +0.609881 0.211030 +0.609653 0.211305 +0.609676 0.211272 +0.609490 0.211614 +0.609511 0.211564 +0.609396 0.211934 +0.609403 0.211895 +0.621053 0.214895 +0.621091 0.214542 +0.619692 0.216227 +0.619332 0.216263 +0.619332 0.216263 +0.619692 0.216227 +0.620030 0.216122 +0.620030 0.216122 +0.620328 0.215960 +0.620575 0.215759 +0.620328 0.215960 +0.620575 0.215759 +0.620781 0.215517 +0.620946 0.215226 +0.620781 0.215517 +0.621053 0.214895 +0.620946 0.215226 +0.621091 0.214542 +0.621091 0.212247 +0.621091 0.212247 +0.619692 0.210563 +0.619332 0.210526 +0.619332 0.210526 +0.619692 0.210563 +0.620030 0.210668 +0.620328 0.210829 +0.620030 0.210668 +0.620328 0.210829 +0.620575 0.211030 +0.620781 0.211272 +0.620575 0.211030 +0.620781 0.211272 +0.620946 0.211564 +0.620946 0.211564 +0.621053 0.211895 +0.621053 0.211895 +0.539472 0.251443 +0.539764 0.251575 +0.537361 0.252205 +0.537361 0.252205 +0.537574 0.251918 +0.537547 0.251948 +0.537836 0.251684 +0.537792 0.251717 +0.538128 0.251512 +0.538091 0.251530 +0.538429 0.251403 +0.538256 0.251458 +0.538429 0.251403 +0.538746 0.251350 +0.538607 0.251366 +0.539086 0.251356 +0.538787 0.251347 +0.539433 0.251430 +0.539141 0.251363 +0.539764 0.251575 +0.542668 0.254343 +0.542674 0.254213 +0.542539 0.254872 +0.542438 0.255074 +0.542438 0.255074 +0.542500 0.254958 +0.542614 0.254658 +0.542659 0.254437 +0.542614 0.254658 +0.542674 0.254213 +0.533258 0.259161 +0.533258 0.259161 +0.533608 0.261304 +0.533901 0.261512 +0.533901 0.261512 +0.533608 0.261304 +0.533369 0.261047 +0.533369 0.261047 +0.533193 0.260762 +0.533082 0.260467 +0.533193 0.260762 +0.533027 0.260157 +0.533082 0.260467 +0.533027 0.260157 +0.533034 0.259824 +0.533034 0.259824 +0.533110 0.259484 +0.533110 0.259484 +0.537568 0.262722 +0.535932 0.262659 +0.535932 0.262659 +0.536263 0.262804 +0.536609 0.262879 +0.536263 0.262804 +0.536950 0.262885 +0.536609 0.262879 +0.537267 0.262831 +0.536950 0.262885 +0.538334 0.262029 +0.538334 0.262029 +0.538122 0.262316 +0.538122 0.262316 +0.537860 0.262551 +0.537568 0.262722 +0.537860 0.262551 +0.537267 0.262831 +0.542542 0.173231 +0.541794 0.174067 +0.541794 0.174067 +0.541980 0.173946 +0.542153 0.173799 +0.541992 0.173937 +0.542307 0.173628 +0.542238 0.173711 +0.542438 0.173437 +0.542674 0.172577 +0.542674 0.172577 +0.542657 0.172809 +0.542659 0.172794 +0.542580 0.173131 +0.542616 0.173014 +0.542438 0.173437 +0.539764 0.175214 +0.539764 0.175214 +0.537547 0.174841 +0.537361 0.174584 +0.537361 0.174584 +0.537792 0.175073 +0.537574 0.174872 +0.538091 0.175260 +0.537836 0.175106 +0.538256 0.175331 +0.538128 0.175278 +0.538429 0.175386 +0.538607 0.175423 +0.538429 0.175386 +0.538787 0.175442 +0.538746 0.175440 +0.539141 0.175427 +0.539086 0.175434 +0.539472 0.175346 +0.539433 0.175359 +0.538122 0.164473 +0.538334 0.164760 +0.535932 0.164130 +0.535932 0.164130 +0.536263 0.163985 +0.536263 0.163985 +0.536609 0.163911 +0.536950 0.163905 +0.536609 0.163911 +0.536950 0.163905 +0.537267 0.163958 +0.537267 0.163958 +0.537568 0.164067 +0.537568 0.164067 +0.537860 0.164239 +0.538122 0.164473 +0.537860 0.164239 +0.538334 0.164760 +0.533034 0.166966 +0.533110 0.167305 +0.533258 0.167629 +0.533258 0.167629 +0.533034 0.166966 +0.533110 0.167305 +0.533901 0.165278 +0.533901 0.165278 +0.533608 0.165485 +0.533369 0.165742 +0.533608 0.165485 +0.533193 0.166028 +0.533369 0.165742 +0.533193 0.166028 +0.533082 0.166323 +0.533082 0.166323 +0.533027 0.166633 +0.533027 0.166633 +0.338494 0.244810 +0.335603 0.240933 +0.337918 0.242849 +0.335818 0.238636 +0.337738 0.240933 +0.336509 0.236287 +0.337918 0.239016 +0.337705 0.234026 +0.338494 0.237056 +0.339381 0.232008 +0.339493 0.235170 +0.341443 0.230368 +0.340890 0.233485 +0.343753 0.229197 +0.342611 0.232117 +0.346153 0.228522 +0.344539 0.231140 +0.348500 0.228311 +0.346542 0.230577 +0.350847 0.228522 +0.348500 0.230401 +0.353247 0.229197 +0.350458 0.230577 +0.355557 0.230368 +0.352461 0.231140 +0.357619 0.232008 +0.354389 0.232117 +0.359295 0.234026 +0.356110 0.233485 +0.360491 0.236287 +0.357507 0.235170 +0.361181 0.238636 +0.358506 0.237056 +0.361397 0.240933 +0.359082 0.239016 +0.361181 0.243229 +0.359262 0.240933 +0.360491 0.245579 +0.359082 0.242849 +0.359295 0.247839 +0.358506 0.244810 +0.357619 0.249858 +0.357507 0.246696 +0.355557 0.251497 +0.356110 0.248380 +0.353247 0.252668 +0.354389 0.249748 +0.350847 0.253344 +0.352461 0.250725 +0.348500 0.253554 +0.350458 0.251289 +0.346153 0.253344 +0.348500 0.251465 +0.343753 0.252668 +0.346542 0.251289 +0.341443 0.251497 +0.344539 0.250725 +0.339381 0.249858 +0.342611 0.249748 +0.337705 0.247839 +0.340890 0.248380 +0.336509 0.245579 +0.339493 0.246696 +0.335818 0.243229 +0.362569 0.240933 +0.362569 0.240933 +0.334431 0.240933 +0.334431 0.240933 +0.334666 0.238427 +0.334666 0.238427 +0.335419 0.235864 +0.335419 0.235864 +0.336724 0.233398 +0.338552 0.231197 +0.336724 0.233398 +0.338552 0.231197 +0.340801 0.229408 +0.340801 0.229408 +0.343321 0.228130 +0.343321 0.228130 +0.345940 0.227393 +0.345940 0.227393 +0.348500 0.227164 +0.348500 0.227164 +0.351060 0.227393 +0.351060 0.227393 +0.353679 0.228130 +0.353679 0.228130 +0.356199 0.229408 +0.356199 0.229408 +0.358448 0.231197 +0.358448 0.231197 +0.360276 0.233398 +0.360276 0.233398 +0.361581 0.235864 +0.361581 0.235864 +0.362334 0.238427 +0.362334 0.238427 +0.861146 0.140534 +0.861146 0.136231 +0.854698 0.136231 +0.854698 0.140534 +0.861146 0.133756 +0.854698 0.133756 +0.854698 0.136231 +0.861146 0.136231 +0.738627 0.136231 +0.732179 0.136231 +0.732179 0.140534 +0.738627 0.140534 +0.616108 0.140534 +0.616108 0.136231 +0.609659 0.136231 +0.609659 0.140534 +0.493589 0.136231 +0.487140 0.136231 +0.487140 0.140534 +0.493589 0.140534 +0.371069 0.136231 +0.364621 0.136231 +0.364621 0.140534 +0.371069 0.140534 +0.248550 0.136231 +0.242102 0.136231 +0.242102 0.140534 +0.248550 0.140534 +0.126031 0.136231 +0.119582 0.136231 +0.119582 0.140534 +0.126031 0.140534 +0.738627 0.136231 +0.738627 0.133756 +0.732179 0.133756 +0.732179 0.136231 +0.616108 0.133756 +0.609659 0.133756 +0.609659 0.136231 +0.616108 0.136231 +0.493589 0.133756 +0.487140 0.133756 +0.487140 0.136231 +0.493589 0.136231 +0.371069 0.136231 +0.371069 0.133756 +0.364621 0.133756 +0.364621 0.136231 +0.248550 0.133756 +0.242102 0.133756 +0.242102 0.136231 +0.248550 0.136231 +0.126031 0.136231 +0.126031 0.133756 +0.119582 0.133756 +0.119582 0.136231 +0.668867 0.136231 +0.662419 0.136231 +0.662419 0.140534 +0.668867 0.140534 +0.546348 0.140534 +0.546348 0.136231 +0.539900 0.136231 +0.539900 0.140534 +0.440829 0.136231 +0.434381 0.136231 +0.434381 0.140534 +0.440829 0.140534 +0.318310 0.140534 +0.318310 0.136231 +0.311861 0.136231 +0.311861 0.140534 +0.960440 0.216542 +0.958751 0.216542 +0.958751 0.216453 +0.960443 0.216478 +0.960436 0.210142 +0.958751 0.210142 +0.964613 0.210142 +0.964613 0.210142 +0.960510 0.210142 +0.960190 0.210142 +0.959862 0.210142 +0.959547 0.210142 +0.959266 0.210142 +0.959038 0.210142 +0.958875 0.210142 +0.958781 0.210142 +0.958751 0.210142 +0.964613 0.216542 +0.964613 0.216542 +0.964613 0.210231 +0.964613 0.210142 +0.964613 0.210231 +0.964613 0.210142 +0.958875 0.216542 +0.958781 0.216542 +0.958751 0.216542 +0.958751 0.216542 +0.964613 0.216542 +0.964613 0.216542 +0.960440 0.216542 +0.967363 0.216542 +0.967370 0.216542 +0.960510 0.216542 +0.960190 0.216542 +0.959862 0.216542 +0.959547 0.216542 +0.959266 0.216542 +0.959038 0.216542 +0.958751 0.210142 +0.960436 0.210142 +0.960437 0.210168 +0.960510 0.216542 +0.964613 0.216542 +0.964613 0.210142 +0.960510 0.210142 +0.021977 0.216453 +0.021977 0.216541 +0.020288 0.216541 +0.020286 0.216478 +0.021977 0.210142 +0.020292 0.210167 +0.020292 0.210167 +0.021854 0.210142 +0.021948 0.210142 +0.021977 0.210142 +0.021977 0.210142 +0.016115 0.210142 +0.016115 0.210142 +0.020293 0.210142 +0.020219 0.210142 +0.020539 0.210142 +0.020866 0.210142 +0.021181 0.210142 +0.021462 0.210142 +0.021691 0.210142 +0.016115 0.210203 +0.016115 0.216541 +0.016115 0.210142 +0.016115 0.210142 +0.016115 0.210203 +0.016115 0.216541 +0.020866 0.216541 +0.020539 0.216541 +0.020219 0.216541 +0.016115 0.216541 +0.020288 0.216541 +0.021977 0.216541 +0.013359 0.216541 +0.013365 0.216541 +0.016115 0.216541 +0.021977 0.216541 +0.021948 0.216541 +0.021854 0.216541 +0.021691 0.216541 +0.021462 0.216541 +0.021181 0.216541 +0.020219 0.210142 +0.016115 0.210142 +0.016115 0.216541 +0.020219 0.216541 +0.964613 0.210231 +0.964613 0.210231 +0.967369 0.210231 +0.967363 0.210231 +0.013361 0.210203 +0.016115 0.210203 +0.016115 0.210203 +0.013367 0.210203 +0.013296 0.213395 +0.013359 0.216541 +0.016115 0.216541 +0.016115 0.210203 +0.013361 0.210203 +0.964613 0.216542 +0.967370 0.216542 +0.967369 0.210231 +0.964613 0.210231 +0.318310 0.133756 +0.311861 0.133756 +0.311861 0.136231 +0.318310 0.136231 +0.440829 0.136231 +0.440829 0.133756 +0.434381 0.133756 +0.434381 0.136231 +0.546348 0.136231 +0.546348 0.133756 +0.539900 0.133756 +0.539900 0.136231 +0.668867 0.133756 +0.662419 0.133756 +0.662419 0.136231 +0.668867 0.136231 +0.664764 0.287977 +0.664764 0.289698 +0.664764 0.278797 +0.664764 0.278797 +0.664764 0.286256 +0.664764 0.283961 +0.664764 0.289698 +0.664764 0.286256 +0.683523 0.289698 +0.683523 0.287977 +0.683523 0.286256 +0.683523 0.278797 +0.683523 0.286256 +0.683523 0.278797 +0.683523 0.283961 +0.683523 0.289698 +0.709902 0.138813 +0.709902 0.137092 +0.709902 0.147992 +0.709902 0.147992 +0.709902 0.140534 +0.709902 0.142829 +0.709902 0.137092 +0.709902 0.140534 +0.691143 0.137092 +0.691143 0.138813 +0.691143 0.140534 +0.691143 0.147992 +0.691143 0.140534 +0.691143 0.147992 +0.691143 0.142829 +0.691143 0.137092 +0.664764 0.283961 +0.683523 0.283961 +0.683523 0.278797 +0.664764 0.278797 +0.709902 0.142829 +0.691143 0.142829 +0.691143 0.147992 +0.709902 0.147992 +0.683523 0.287977 +0.664764 0.287977 +0.664764 0.286256 +0.683523 0.286256 +0.683523 0.289698 +0.664764 0.289698 +0.664764 0.289698 +0.683523 0.289698 +0.709902 0.138813 +0.709902 0.140534 +0.691143 0.140534 +0.691143 0.138813 +0.691143 0.137092 +0.691143 0.137092 +0.709902 0.137092 +0.709902 0.137092 +0.542244 0.287977 +0.542244 0.289698 +0.542244 0.278797 +0.542244 0.278797 +0.542244 0.286256 +0.542244 0.283961 +0.542244 0.289698 +0.542244 0.286256 +0.561003 0.289698 +0.561003 0.289698 +0.561003 0.286256 +0.561003 0.278797 +0.561003 0.286256 +0.561003 0.278797 +0.561003 0.283961 +0.561003 0.287977 +0.587383 0.138813 +0.587383 0.137091 +0.587383 0.147992 +0.587383 0.147992 +0.587383 0.140534 +0.587383 0.142829 +0.587383 0.137091 +0.587383 0.140534 +0.568624 0.137091 +0.568624 0.137091 +0.568624 0.140534 +0.568624 0.147992 +0.568624 0.140534 +0.568624 0.147992 +0.568624 0.142829 +0.568624 0.138813 +0.542244 0.283961 +0.561003 0.283961 +0.561003 0.278797 +0.542244 0.278797 +0.587383 0.142829 +0.568624 0.142829 +0.568624 0.147992 +0.587383 0.147992 +0.542244 0.287977 +0.542244 0.286256 +0.561003 0.286256 +0.561003 0.287977 +0.561003 0.289698 +0.542244 0.289698 +0.542244 0.289698 +0.561003 0.289698 +0.587383 0.138813 +0.587383 0.140534 +0.568624 0.140534 +0.568624 0.138813 +0.568624 0.137091 +0.587383 0.137091 +0.587383 0.137091 +0.568624 0.137091 +0.315965 0.289698 +0.315965 0.287977 +0.315965 0.286256 +0.315965 0.278797 +0.315965 0.286256 +0.315965 0.278797 +0.315965 0.283961 +0.315965 0.289698 +0.297206 0.287977 +0.297206 0.289698 +0.297206 0.278797 +0.297206 0.278797 +0.297206 0.286256 +0.297206 0.283961 +0.297206 0.289698 +0.297206 0.286256 +0.270826 0.137091 +0.270826 0.138813 +0.270826 0.140534 +0.270826 0.147992 +0.270826 0.140534 +0.270826 0.147992 +0.270826 0.142828 +0.270826 0.137091 +0.289585 0.138813 +0.289585 0.137091 +0.289585 0.147992 +0.289585 0.147992 +0.289585 0.140534 +0.289585 0.142828 +0.289585 0.137091 +0.289585 0.140534 +0.438484 0.289698 +0.438484 0.287977 +0.438484 0.286256 +0.438484 0.278797 +0.438484 0.286256 +0.438484 0.278797 +0.438484 0.283961 +0.438484 0.289698 +0.419725 0.287977 +0.419725 0.289698 +0.419725 0.278797 +0.419725 0.278797 +0.419725 0.286256 +0.419725 0.283961 +0.419725 0.289698 +0.419725 0.286256 +0.393345 0.137091 +0.393345 0.138813 +0.393345 0.140534 +0.393345 0.147992 +0.393345 0.140534 +0.393345 0.147992 +0.393345 0.142829 +0.393345 0.137091 +0.412104 0.138813 +0.412104 0.137091 +0.412104 0.147992 +0.412104 0.147992 +0.412104 0.140534 +0.412104 0.142829 +0.412104 0.137091 +0.412104 0.140534 +0.315965 0.283961 +0.315965 0.278797 +0.297206 0.278797 +0.297206 0.283961 +0.270826 0.142828 +0.270826 0.147992 +0.289585 0.147992 +0.289585 0.142828 +0.419725 0.283961 +0.438484 0.283961 +0.438484 0.278797 +0.419725 0.278797 +0.393345 0.142829 +0.393345 0.147992 +0.412104 0.147992 +0.412104 0.142829 +0.297206 0.286256 +0.315965 0.286256 +0.315965 0.287977 +0.297206 0.287977 +0.315965 0.289698 +0.297206 0.289698 +0.297206 0.289698 +0.315965 0.289698 +0.419725 0.286256 +0.438484 0.286256 +0.438484 0.287977 +0.419725 0.287977 +0.438484 0.289698 +0.438484 0.289698 +0.419725 0.289698 +0.419725 0.289698 +0.289585 0.138813 +0.289585 0.140534 +0.270826 0.140534 +0.270826 0.138813 +0.270826 0.137091 +0.289585 0.137091 +0.289585 0.137091 +0.270826 0.137091 +0.412104 0.140534 +0.393345 0.140534 +0.393345 0.138813 +0.412104 0.138813 +0.393345 0.137091 +0.412104 0.137091 +0.412104 0.137091 +0.393345 0.137091 +0.854698 0.290559 +0.861146 0.290559 +0.861146 0.286256 +0.854698 0.286256 +0.732179 0.290558 +0.738627 0.290558 +0.738627 0.286256 +0.732179 0.286256 +0.609659 0.290558 +0.616108 0.290558 +0.616108 0.286256 +0.609659 0.286256 +0.487140 0.290558 +0.493589 0.290558 +0.493589 0.286256 +0.487140 0.286256 +0.364621 0.290558 +0.371069 0.290558 +0.371069 0.286256 +0.364621 0.286256 +0.242102 0.290558 +0.248550 0.290558 +0.248550 0.286256 +0.242102 0.286256 +0.119582 0.286256 +0.119582 0.290558 +0.126031 0.290558 +0.126031 0.286256 +0.861146 0.293034 +0.861146 0.290559 +0.854698 0.290559 +0.854698 0.293034 +0.738627 0.293033 +0.738627 0.290558 +0.732179 0.290558 +0.732179 0.293033 +0.609659 0.293033 +0.616108 0.293033 +0.616108 0.290558 +0.609659 0.290558 +0.493589 0.293033 +0.493589 0.290558 +0.487140 0.290558 +0.487140 0.293033 +0.371069 0.293033 +0.371069 0.290558 +0.364621 0.290558 +0.364621 0.293033 +0.248550 0.293033 +0.248550 0.290558 +0.242102 0.290558 +0.242102 0.293033 +0.119582 0.293033 +0.126031 0.293033 +0.126031 0.290558 +0.119582 0.290558 +0.126031 0.142255 +0.022060 0.197291 +0.020292 0.210167 +0.021977 0.216453 +0.020286 0.216478 +0.248550 0.286256 +0.288413 0.286256 +0.094668 0.286256 +0.119582 0.286256 +0.119582 0.142255 +0.119582 0.140534 +0.262033 0.140534 +0.248550 0.140534 +0.248550 0.284535 +0.288413 0.278797 +0.242102 0.284535 +0.262033 0.147992 +0.094668 0.147992 +0.248550 0.142255 +0.126031 0.286256 +0.242102 0.286256 +0.126031 0.284535 +0.119582 0.284535 +0.081431 0.285095 +0.094668 0.278797 +0.067910 0.281387 +0.082508 0.277705 +0.054872 0.274972 +0.070069 0.274205 +0.043151 0.265994 +0.058099 0.268136 +0.033489 0.254913 +0.047413 0.259641 +0.026389 0.242436 +0.038733 0.249184 +0.022031 0.229372 +0.032532 0.237469 +0.028955 0.225295 +0.021977 0.210142 +0.027840 0.213395 +0.028955 0.201494 +0.026434 0.184250 +0.032532 0.189320 +0.033542 0.171800 +0.038733 0.177606 +0.043204 0.160745 +0.047413 0.167148 +0.054916 0.151789 +0.058099 0.158653 +0.067940 0.145391 +0.081446 0.141692 +0.070069 0.152584 +0.094668 0.140534 +0.082508 0.149084 +0.242102 0.140534 +0.126031 0.140534 +0.242102 0.142255 +0.364621 0.284535 +0.410932 0.278797 +0.324758 0.278797 +0.371069 0.286256 +0.410932 0.286256 +0.371069 0.284535 +0.324758 0.286256 +0.364621 0.286256 +0.487140 0.284535 +0.533451 0.278797 +0.447277 0.278797 +0.493589 0.286256 +0.533451 0.286256 +0.493589 0.284535 +0.447277 0.286256 +0.487140 0.286256 +0.569797 0.286256 +0.609659 0.286256 +0.655970 0.286256 +0.655970 0.278797 +0.616108 0.284535 +0.616108 0.286256 +0.609659 0.284535 +0.569797 0.278797 +0.861146 0.142255 +0.958751 0.210142 +0.960437 0.210168 +0.958698 0.229372 +0.960443 0.216478 +0.738627 0.284535 +0.738627 0.286256 +0.854698 0.286256 +0.861146 0.284535 +0.861146 0.286256 +0.692316 0.286256 +0.732179 0.286256 +0.692316 0.278797 +0.886060 0.278798 +0.732179 0.284535 +0.854698 0.284535 +0.886060 0.286256 +0.898221 0.277706 +0.899297 0.285095 +0.910660 0.274206 +0.912819 0.281387 +0.922630 0.268137 +0.925857 0.274973 +0.933315 0.259642 +0.937578 0.265994 +0.941996 0.249184 +0.947240 0.254913 +0.948197 0.237469 +0.954340 0.242436 +0.951773 0.225296 +0.952889 0.213395 +0.958751 0.216453 +0.951773 0.201494 +0.948197 0.189320 +0.958669 0.197291 +0.941996 0.177606 +0.954294 0.184250 +0.933315 0.167148 +0.947186 0.171800 +0.922630 0.158653 +0.937525 0.160746 +0.910660 0.152584 +0.925813 0.151790 +0.912789 0.145391 +0.898221 0.149084 +0.899283 0.141692 +0.886060 0.147992 +0.732179 0.140534 +0.718696 0.140534 +0.732179 0.142255 +0.718696 0.147992 +0.738627 0.142255 +0.886060 0.140534 +0.861146 0.140534 +0.854698 0.140534 +0.738627 0.140534 +0.854698 0.142255 +0.440829 0.142255 +0.559831 0.147992 +0.559831 0.140534 +0.546348 0.140534 +0.420898 0.147992 +0.546348 0.142255 +0.434381 0.140534 +0.420898 0.140534 +0.434381 0.142255 +0.487140 0.140534 +0.440829 0.140534 +0.487140 0.142255 +0.539900 0.140534 +0.493589 0.140534 +0.539900 0.142255 +0.493589 0.142255 +0.318310 0.142255 +0.384552 0.140534 +0.371069 0.140534 +0.384552 0.147992 +0.298378 0.147992 +0.371069 0.142255 +0.311861 0.140534 +0.298378 0.140534 +0.311861 0.142255 +0.364621 0.140534 +0.318310 0.140534 +0.364621 0.142255 +0.668867 0.142255 +0.609659 0.142255 +0.609659 0.140534 +0.596176 0.140534 +0.596176 0.147992 +0.616108 0.142255 +0.662419 0.140534 +0.616108 0.140534 +0.682350 0.147992 +0.682350 0.140534 +0.668867 0.140534 +0.662419 0.142255 +0.668574 0.213395 +0.671531 0.213395 +0.748214 0.220280 +0.748860 0.213395 +0.751817 0.213395 +0.751122 0.220807 +0.746145 0.227323 +0.748895 0.228388 +0.742557 0.234101 +0.745032 0.235684 +0.737535 0.240151 +0.739626 0.242198 +0.731353 0.245066 +0.724428 0.248577 +0.732971 0.247488 +0.725516 0.251268 +0.717231 0.250603 +0.717769 0.253448 +0.710195 0.251234 +0.703160 0.250603 +0.710195 0.254128 +0.702622 0.253448 +0.695963 0.248577 +0.694875 0.251268 +0.689038 0.245066 +0.687420 0.247488 +0.682856 0.240151 +0.680765 0.242198 +0.677833 0.234101 +0.675359 0.235684 +0.674246 0.227323 +0.671496 0.228388 +0.672176 0.220280 +0.669269 0.220807 +0.522020 0.213395 +0.524977 0.213395 +0.601660 0.220280 +0.602306 0.213395 +0.605263 0.213395 +0.604568 0.220807 +0.599591 0.227323 +0.602340 0.228388 +0.596003 0.234101 +0.598478 0.235684 +0.590981 0.240151 +0.593072 0.242198 +0.584799 0.245066 +0.577874 0.248577 +0.586417 0.247488 +0.578962 0.251268 +0.570677 0.250603 +0.571215 0.253448 +0.563641 0.251234 +0.556606 0.250603 +0.563641 0.254128 +0.556068 0.253448 +0.549409 0.248577 +0.548321 0.251268 +0.542484 0.245066 +0.540866 0.247488 +0.536301 0.240151 +0.534211 0.242198 +0.531279 0.234101 +0.528804 0.235684 +0.527692 0.227323 +0.524942 0.228388 +0.525622 0.220280 +0.522715 0.220807 +0.228912 0.213395 +0.231869 0.213395 +0.308552 0.220280 +0.309198 0.213395 +0.312155 0.213395 +0.311460 0.220807 +0.306483 0.227323 +0.309232 0.228388 +0.302895 0.234101 +0.305370 0.235684 +0.297873 0.240151 +0.299964 0.242197 +0.291691 0.245066 +0.284765 0.248577 +0.293309 0.247488 +0.285854 0.251268 +0.277569 0.250602 +0.278107 0.253448 +0.270533 0.251234 +0.263498 0.250602 +0.270533 0.254128 +0.262960 0.253448 +0.256301 0.248577 +0.255213 0.251268 +0.249376 0.245066 +0.247758 0.247488 +0.243193 0.240151 +0.241102 0.242197 +0.238171 0.234101 +0.235696 0.235684 +0.234583 0.227323 +0.231834 0.228388 +0.232514 0.220280 +0.229607 0.220807 +0.356376 0.193564 +0.357708 0.187524 +0.357864 0.185857 +0.359638 0.185857 +0.357206 0.189230 +0.359452 0.187840 +0.356338 0.190871 +0.358856 0.189869 +0.357822 0.191822 +0.355121 0.192337 +0.337548 0.187840 +0.337362 0.185857 +0.339136 0.185857 +0.339292 0.187524 +0.338144 0.189869 +0.339793 0.189230 +0.339177 0.191822 +0.340662 0.190871 +0.340624 0.193564 +0.341879 0.192337 +0.342405 0.194980 +0.343376 0.193527 +0.344400 0.195992 +0.345053 0.194377 +0.346473 0.196575 +0.346796 0.194868 +0.348500 0.196757 +0.348500 0.195021 +0.350527 0.196575 +0.350204 0.194868 +0.352600 0.195992 +0.354595 0.194980 +0.351947 0.194377 +0.353624 0.193527 +0.337362 0.240933 +0.339105 0.240933 +0.357895 0.240933 +0.359638 0.240933 +0.357738 0.242606 +0.357235 0.244317 +0.359452 0.242916 +0.356363 0.245964 +0.358856 0.244945 +0.357822 0.246898 +0.355143 0.247434 +0.356376 0.248640 +0.353641 0.248628 +0.351958 0.249481 +0.354595 0.250056 +0.352600 0.251068 +0.350209 0.249973 +0.350527 0.251651 +0.348500 0.250127 +0.346790 0.249973 +0.348500 0.251833 +0.346473 0.251651 +0.345042 0.249481 +0.344400 0.251068 +0.343359 0.248628 +0.342405 0.250056 +0.341857 0.247434 +0.340624 0.248640 +0.340637 0.245964 +0.339177 0.246898 +0.339765 0.244317 +0.338144 0.244945 +0.339262 0.242606 +0.337548 0.242916 +0.359262 0.240933 +0.358079 0.240933 +0.339081 0.242639 +0.338921 0.240933 +0.337738 0.240933 +0.337918 0.242849 +0.339594 0.244383 +0.338494 0.244810 +0.340483 0.246062 +0.339493 0.246696 +0.341727 0.247561 +0.343258 0.248779 +0.340890 0.248380 +0.342611 0.249748 +0.344974 0.249649 +0.344539 0.250725 +0.346757 0.250151 +0.346542 0.251289 +0.348500 0.250307 +0.350243 0.250151 +0.348500 0.251465 +0.352026 0.249649 +0.350458 0.251289 +0.352461 0.250725 +0.353742 0.248779 +0.355273 0.247561 +0.354389 0.249748 +0.356110 0.248380 +0.356517 0.246062 +0.357507 0.246696 +0.357406 0.244383 +0.358506 0.244810 +0.357919 0.242639 +0.359082 0.242849 +0.334431 0.240933 +0.335603 0.240933 +0.361397 0.240933 +0.362569 0.240933 +0.361181 0.238636 +0.362334 0.238427 +0.360491 0.236287 +0.361581 0.235864 +0.359295 0.234026 +0.360276 0.233398 +0.357619 0.232008 +0.358448 0.231197 +0.355557 0.230368 +0.356199 0.229408 +0.353247 0.229197 +0.353679 0.228130 +0.350847 0.228522 +0.351060 0.227393 +0.348500 0.228311 +0.348500 0.227164 +0.346153 0.228522 +0.345940 0.227393 +0.343753 0.229197 +0.343321 0.228130 +0.341443 0.230368 +0.340801 0.229408 +0.339381 0.232008 +0.338552 0.231197 +0.337705 0.234026 +0.336724 0.233398 +0.336509 0.236287 +0.335419 0.235864 +0.335818 0.238636 +0.334666 0.238427 +0.333801 0.188519 +0.333551 0.185857 +0.364352 0.188727 +0.364621 0.185857 +0.363448 0.185857 +0.363199 0.188519 +0.363489 0.191664 +0.362399 0.191242 +0.361993 0.194490 +0.361012 0.193862 +0.359899 0.197013 +0.359070 0.196201 +0.357322 0.199062 +0.356680 0.198102 +0.354434 0.200526 +0.354002 0.199459 +0.351433 0.201370 +0.351220 0.200242 +0.348500 0.201634 +0.345567 0.201370 +0.348500 0.200486 +0.342566 0.200526 +0.345780 0.200242 +0.339678 0.199062 +0.342997 0.199459 +0.340320 0.198102 +0.337101 0.197013 +0.337930 0.196201 +0.335007 0.194490 +0.335988 0.193862 +0.333511 0.191664 +0.332648 0.188727 +0.334601 0.191242 +0.332379 0.185857 +0.315965 0.213395 +0.314793 0.213395 +0.227013 0.221276 +0.226274 0.213395 +0.225101 0.213395 +0.225860 0.221485 +0.229381 0.229339 +0.228291 0.229761 +0.233488 0.237097 +0.232507 0.237725 +0.239237 0.244023 +0.238408 0.244834 +0.246314 0.249649 +0.245672 0.250610 +0.254242 0.253668 +0.253810 0.254735 +0.262480 0.255987 +0.262266 0.257115 +0.270533 0.256710 +0.270533 0.257857 +0.278587 0.255987 +0.286825 0.253668 +0.278800 0.257115 +0.287256 0.254735 +0.294752 0.249649 +0.295394 0.250610 +0.301829 0.244023 +0.302658 0.244834 +0.307578 0.237097 +0.308559 0.237725 +0.311685 0.229339 +0.312775 0.229761 +0.314054 0.221276 +0.315206 0.221485 +0.609073 0.213395 +0.607901 0.213395 +0.520121 0.221276 +0.519382 0.213395 +0.518210 0.213395 +0.518968 0.221485 +0.522489 0.229339 +0.521399 0.229761 +0.526596 0.237097 +0.525615 0.237725 +0.532345 0.244023 +0.531516 0.244834 +0.539422 0.249649 +0.538781 0.250610 +0.547350 0.253669 +0.546918 0.254735 +0.555588 0.255987 +0.555374 0.257115 +0.563641 0.256710 +0.563641 0.257857 +0.571695 0.255987 +0.579933 0.253669 +0.571908 0.257115 +0.580365 0.254735 +0.587860 0.249649 +0.588502 0.250610 +0.594937 0.244023 +0.595766 0.244834 +0.600686 0.237097 +0.601668 0.237725 +0.604793 0.229339 +0.605883 0.229761 +0.607162 0.221276 +0.608315 0.221485 +0.755627 0.213395 +0.754455 0.213395 +0.666675 0.221277 +0.665936 0.213395 +0.664764 0.213395 +0.665522 0.221485 +0.669044 0.229339 +0.667953 0.229761 +0.673151 0.237097 +0.672169 0.237725 +0.678899 0.244023 +0.678070 0.244834 +0.685976 0.249649 +0.693904 0.253669 +0.685335 0.250610 +0.693472 0.254735 +0.702142 0.255987 +0.701928 0.257115 +0.710195 0.256710 +0.718249 0.255987 +0.710195 0.257857 +0.718462 0.257115 +0.726487 0.253669 +0.726919 0.254735 +0.734415 0.249649 +0.735056 0.250610 +0.741491 0.244023 +0.742321 0.244834 +0.747240 0.237097 +0.748222 0.237725 +0.751347 0.229339 +0.752437 0.229761 +0.753716 0.221277 +0.754869 0.221485 +0.958751 0.210142 +0.958751 0.216542 +0.960149 0.216542 +0.960510 0.216542 +0.960510 0.210142 +0.959811 0.216542 +0.960149 0.210142 +0.959811 0.210142 +0.959513 0.216542 +0.959513 0.210142 +0.959266 0.216542 +0.959266 0.210142 +0.959061 0.216542 +0.959061 0.210142 +0.958896 0.216542 +0.958896 0.210142 +0.958789 0.216542 +0.958789 0.210142 +0.311861 0.141167 +0.318310 0.140847 +0.318310 0.140534 +0.311861 0.140534 +0.311861 0.140847 +0.318310 0.141167 +0.311861 0.142255 +0.318310 0.142255 +0.311861 0.142226 +0.318310 0.142226 +0.311861 0.142134 +0.318310 0.142134 +0.311861 0.141974 +0.318310 0.141974 +0.311861 0.141751 +0.318310 0.141751 +0.311861 0.141475 +0.318310 0.141475 +0.434381 0.142218 +0.434381 0.142255 +0.440829 0.140534 +0.434381 0.140534 +0.440829 0.140886 +0.440829 0.141217 +0.434381 0.140886 +0.440829 0.141509 +0.434381 0.141217 +0.434381 0.141509 +0.440829 0.141751 +0.440829 0.141952 +0.434381 0.141751 +0.434381 0.141952 +0.440829 0.142113 +0.440829 0.142218 +0.434381 0.142113 +0.440829 0.142255 +0.539900 0.142218 +0.539900 0.142255 +0.546348 0.140886 +0.546348 0.140534 +0.539900 0.140534 +0.539900 0.140886 +0.546348 0.141217 +0.539900 0.141217 +0.546348 0.141509 +0.539900 0.141509 +0.546348 0.141751 +0.539900 0.141751 +0.546348 0.141952 +0.539900 0.141952 +0.546348 0.142113 +0.546348 0.142218 +0.539900 0.142113 +0.546348 0.142255 +0.668867 0.140886 +0.668867 0.140534 +0.662419 0.142255 +0.668867 0.142255 +0.662419 0.142218 +0.662419 0.142113 +0.668867 0.142218 +0.662419 0.141952 +0.668867 0.142113 +0.668867 0.141952 +0.662419 0.141751 +0.662419 0.141509 +0.668867 0.141751 +0.662419 0.141217 +0.668867 0.141509 +0.668867 0.141217 +0.662419 0.140886 +0.662419 0.140534 +0.021691 0.216541 +0.021977 0.216541 +0.021977 0.210142 +0.021948 0.216541 +0.021948 0.210142 +0.021854 0.216541 +0.020539 0.210142 +0.020219 0.210142 +0.020219 0.216541 +0.020539 0.216541 +0.020866 0.210142 +0.020866 0.216541 +0.021181 0.210142 +0.021462 0.210142 +0.021181 0.216541 +0.021691 0.210142 +0.021462 0.216541 +0.021854 0.210142 +0.861146 0.284535 +0.854698 0.284535 +0.854698 0.286256 +0.861146 0.286256 +0.854698 0.285903 +0.861146 0.285903 +0.854698 0.285572 +0.854698 0.285281 +0.861146 0.285572 +0.861146 0.285281 +0.854698 0.285039 +0.854698 0.284838 +0.861146 0.285039 +0.854698 0.284676 +0.861146 0.284838 +0.861146 0.284676 +0.854698 0.284571 +0.861146 0.284571 +0.738627 0.284571 +0.738627 0.284535 +0.732179 0.285903 +0.732179 0.286256 +0.738627 0.286256 +0.738627 0.285903 +0.732179 0.285572 +0.732179 0.285280 +0.738627 0.285572 +0.732179 0.285039 +0.738627 0.285280 +0.732179 0.284838 +0.738627 0.285039 +0.738627 0.284838 +0.732179 0.284676 +0.738627 0.284676 +0.732179 0.284571 +0.732179 0.284535 +0.609659 0.286256 +0.616108 0.286256 +0.616108 0.284571 +0.616108 0.284535 +0.609659 0.284535 +0.616108 0.284676 +0.609659 0.284571 +0.616108 0.284838 +0.609659 0.284676 +0.616108 0.285039 +0.609659 0.284838 +0.616108 0.285280 +0.609659 0.285039 +0.609659 0.285280 +0.616108 0.285572 +0.609659 0.285572 +0.616108 0.285903 +0.609659 0.285903 +0.487140 0.286256 +0.493589 0.286256 +0.493589 0.284571 +0.493589 0.284535 +0.487140 0.284535 +0.487140 0.284571 +0.493589 0.284676 +0.493589 0.284837 +0.487140 0.284676 +0.487140 0.284837 +0.493589 0.285039 +0.493589 0.285280 +0.487140 0.285039 +0.493589 0.285572 +0.487140 0.285280 +0.487140 0.285572 +0.493589 0.285903 +0.487140 0.285903 +0.371069 0.284535 +0.364621 0.284535 +0.364621 0.285903 +0.364621 0.286256 +0.371069 0.286256 +0.364621 0.285572 +0.371069 0.285903 +0.371069 0.285572 +0.364621 0.285280 +0.371069 0.285280 +0.364621 0.285039 +0.364621 0.284837 +0.371069 0.285039 +0.371069 0.284837 +0.364621 0.284676 +0.364621 0.284571 +0.371069 0.284676 +0.371069 0.284571 +0.248550 0.284563 +0.248550 0.284535 +0.242102 0.285942 +0.242102 0.286256 +0.248550 0.286256 +0.242102 0.285622 +0.248550 0.285942 +0.242102 0.285314 +0.248550 0.285622 +0.242102 0.285039 +0.248550 0.285314 +0.242102 0.284815 +0.248550 0.285039 +0.242102 0.284655 +0.248550 0.284815 +0.248550 0.284655 +0.242102 0.284563 +0.242102 0.284535 +0.126031 0.284563 +0.126031 0.284535 +0.119582 0.285942 +0.119582 0.286256 +0.126031 0.286256 +0.119582 0.285622 +0.126031 0.285942 +0.119582 0.285314 +0.126031 0.285622 +0.119582 0.285039 +0.126031 0.285314 +0.119582 0.284815 +0.126031 0.285039 +0.119582 0.284655 +0.126031 0.284815 +0.119582 0.284563 +0.126031 0.284655 +0.119582 0.284535 +0.126031 0.140534 +0.119582 0.140534 +0.119582 0.142255 +0.126031 0.142255 +0.119582 0.142226 +0.126031 0.142226 +0.119582 0.142134 +0.119582 0.141974 +0.126031 0.142134 +0.126031 0.141974 +0.119582 0.141751 +0.126031 0.141751 +0.119582 0.141475 +0.126031 0.141475 +0.119582 0.141167 +0.126031 0.141167 +0.119582 0.140847 +0.126031 0.140847 +0.248550 0.140847 +0.248550 0.140534 +0.242102 0.142226 +0.242102 0.142255 +0.248550 0.142255 +0.242102 0.142134 +0.248550 0.142226 +0.242102 0.141974 +0.248550 0.142134 +0.242102 0.141751 +0.248550 0.141974 +0.242102 0.141475 +0.248550 0.141751 +0.242102 0.141167 +0.248550 0.141475 +0.248550 0.141167 +0.242102 0.140847 +0.242102 0.140534 +0.371069 0.140534 +0.364621 0.140534 +0.364621 0.142218 +0.364621 0.142255 +0.371069 0.142255 +0.364621 0.142113 +0.371069 0.142218 +0.364621 0.141952 +0.371069 0.142113 +0.371069 0.141952 +0.364621 0.141751 +0.371069 0.141751 +0.364621 0.141509 +0.364621 0.141217 +0.371069 0.141509 +0.364621 0.140886 +0.371069 0.141217 +0.371069 0.140886 +0.493589 0.140534 +0.487140 0.140534 +0.487140 0.142218 +0.487140 0.142255 +0.493589 0.142255 +0.493589 0.142218 +0.487140 0.142113 +0.493589 0.142113 +0.487140 0.141952 +0.493589 0.141952 +0.487140 0.141751 +0.493589 0.141751 +0.487140 0.141509 +0.487140 0.141217 +0.493589 0.141509 +0.487140 0.140886 +0.493589 0.141217 +0.493589 0.140886 +0.616108 0.140534 +0.609659 0.140534 +0.609659 0.142255 +0.616108 0.142255 +0.609659 0.142218 +0.609659 0.142113 +0.616108 0.142218 +0.609659 0.141952 +0.616108 0.142113 +0.616108 0.141952 +0.609659 0.141751 +0.616108 0.141751 +0.609659 0.141509 +0.609659 0.141217 +0.616108 0.141509 +0.616108 0.141217 +0.609659 0.140886 +0.616108 0.140886 +0.732179 0.141952 +0.732179 0.142255 +0.738627 0.142255 +0.732179 0.142218 +0.738627 0.142218 +0.732179 0.142113 +0.738627 0.140534 +0.732179 0.140534 +0.738627 0.140886 +0.732179 0.140886 +0.738627 0.141217 +0.738627 0.141509 +0.732179 0.141217 +0.738627 0.141751 +0.732179 0.141509 +0.738627 0.141952 +0.732179 0.141751 +0.738627 0.142113 +0.861146 0.140887 +0.861146 0.140534 +0.854698 0.142255 +0.861146 0.142255 +0.854698 0.142218 +0.861146 0.142218 +0.854698 0.142113 +0.854698 0.141952 +0.861146 0.142113 +0.861146 0.141952 +0.854698 0.141751 +0.854698 0.141509 +0.861146 0.141751 +0.854698 0.141217 +0.861146 0.141509 +0.854698 0.140887 +0.861146 0.141217 +0.854698 0.140534 +0.587383 0.137091 +0.568624 0.137091 +0.568624 0.142829 +0.587383 0.142829 +0.709902 0.137092 +0.691143 0.137092 +0.691143 0.142829 +0.709902 0.142829 +0.542244 0.289698 +0.561003 0.289698 +0.561003 0.283961 +0.542244 0.283961 +0.664764 0.289698 +0.683523 0.289698 +0.683523 0.283961 +0.664764 0.283961 +0.270826 0.137091 +0.270826 0.142828 +0.289585 0.142828 +0.289585 0.137091 +0.393345 0.137091 +0.393345 0.142829 +0.412104 0.142829 +0.412104 0.137091 +0.438484 0.289698 +0.438484 0.283961 +0.419725 0.283961 +0.419725 0.289698 +0.315965 0.289698 +0.315965 0.283961 +0.297206 0.283961 +0.297206 0.289698 +0.568624 0.138813 +0.568624 0.137091 +0.587383 0.137091 +0.587383 0.138813 +0.691143 0.138813 +0.691143 0.137092 +0.709902 0.137092 +0.709902 0.138813 +0.561003 0.289698 +0.542244 0.289698 +0.542244 0.287977 +0.561003 0.287977 +0.683523 0.289698 +0.664764 0.289698 +0.664764 0.287977 +0.683523 0.287977 +0.270826 0.137091 +0.289585 0.137091 +0.289585 0.138813 +0.270826 0.138813 +0.412104 0.137091 +0.412104 0.138813 +0.393345 0.138813 +0.393345 0.137091 +0.419725 0.289698 +0.419725 0.287977 +0.438484 0.287977 +0.438484 0.289698 +0.297206 0.289698 +0.297206 0.287977 +0.315965 0.287977 +0.315965 0.289698 +0.292516 0.147992 +0.292516 0.140534 +0.289647 0.140534 +0.289585 0.140534 +0.289585 0.147992 +0.289647 0.147992 +0.289826 0.140534 +0.290101 0.140534 +0.289826 0.147992 +0.290101 0.147992 +0.290444 0.140534 +0.290855 0.140534 +0.290444 0.147992 +0.291352 0.140534 +0.290855 0.147992 +0.291352 0.147992 +0.291916 0.140534 +0.291916 0.147992 +0.414435 0.140534 +0.412167 0.140534 +0.412104 0.140534 +0.412104 0.147992 +0.412167 0.147992 +0.412346 0.140534 +0.412620 0.140534 +0.412346 0.147992 +0.412620 0.147992 +0.412963 0.140534 +0.413375 0.140534 +0.412963 0.147992 +0.413375 0.147992 +0.413871 0.140534 +0.415036 0.147992 +0.415036 0.140534 +0.414435 0.147992 +0.413871 0.147992 +0.568624 0.147992 +0.568624 0.140534 +0.565693 0.140534 +0.565693 0.147992 +0.566294 0.140534 +0.566294 0.147992 +0.566857 0.140534 +0.567354 0.140534 +0.566857 0.147992 +0.567766 0.140534 +0.567354 0.147992 +0.568108 0.140534 +0.567766 0.147992 +0.568108 0.147992 +0.568383 0.140534 +0.568383 0.147992 +0.568562 0.140534 +0.568562 0.147992 +0.691143 0.147992 +0.691143 0.140534 +0.688813 0.140534 +0.688212 0.140534 +0.688212 0.147992 +0.688813 0.147992 +0.689376 0.140534 +0.689873 0.140534 +0.689376 0.147992 +0.689873 0.147992 +0.690285 0.140534 +0.690627 0.140534 +0.690285 0.147992 +0.690627 0.147992 +0.690902 0.140534 +0.690902 0.147992 +0.691081 0.140534 +0.691081 0.147992 +0.685853 0.286256 +0.686454 0.286256 +0.683523 0.278797 +0.683523 0.286256 +0.683585 0.278797 +0.683585 0.286256 +0.683764 0.278797 +0.683764 0.286256 +0.684039 0.278797 +0.684381 0.278797 +0.684039 0.286256 +0.684381 0.286256 +0.684793 0.278797 +0.684793 0.286256 +0.685290 0.278797 +0.685290 0.286256 +0.685853 0.278797 +0.686454 0.278797 +0.563934 0.286256 +0.563934 0.278797 +0.561003 0.278797 +0.561003 0.286256 +0.561065 0.278797 +0.561065 0.286256 +0.561244 0.278797 +0.561244 0.286256 +0.561519 0.278797 +0.561519 0.286256 +0.561862 0.278797 +0.561862 0.286256 +0.562274 0.278797 +0.562770 0.278797 +0.562274 0.286256 +0.562770 0.286256 +0.563334 0.278797 +0.563334 0.286256 +0.417395 0.278797 +0.416794 0.278797 +0.419663 0.286256 +0.419725 0.286256 +0.419725 0.278797 +0.419484 0.286256 +0.419663 0.278797 +0.419484 0.278797 +0.419209 0.286256 +0.419209 0.278797 +0.418867 0.286256 +0.418455 0.286256 +0.418867 0.278797 +0.418455 0.278797 +0.417958 0.286256 +0.417958 0.278797 +0.417395 0.286256 +0.416794 0.286256 +0.297144 0.278797 +0.297144 0.286256 +0.297206 0.286256 +0.297206 0.278797 +0.294275 0.278797 +0.294275 0.286256 +0.294876 0.278797 +0.294876 0.286256 +0.295439 0.278797 +0.295936 0.278797 +0.295439 0.286256 +0.295936 0.286256 +0.296347 0.278797 +0.296347 0.286256 +0.296690 0.278797 +0.296965 0.278797 +0.296690 0.286256 +0.296965 0.286256 +0.559893 0.140534 +0.559831 0.140534 +0.562161 0.147992 +0.562762 0.147992 +0.562762 0.140534 +0.561598 0.147992 +0.562161 0.140534 +0.561598 0.140534 +0.561101 0.147992 +0.560689 0.147992 +0.561101 0.140534 +0.560689 0.140534 +0.560347 0.147992 +0.560072 0.147992 +0.560347 0.140534 +0.560072 0.140534 +0.559893 0.147992 +0.559831 0.147992 +0.589714 0.147992 +0.590314 0.147992 +0.587445 0.140534 +0.587383 0.140534 +0.587383 0.147992 +0.587445 0.147992 +0.587624 0.140534 +0.587899 0.140534 +0.587624 0.147992 +0.587899 0.147992 +0.588242 0.140534 +0.588653 0.140534 +0.588242 0.147992 +0.589150 0.140534 +0.588653 0.147992 +0.589150 0.147992 +0.589714 0.140534 +0.590314 0.140534 +0.596176 0.147992 +0.596176 0.140534 +0.593846 0.140534 +0.593245 0.140534 +0.593245 0.147992 +0.593846 0.147992 +0.594409 0.140534 +0.594906 0.140534 +0.594409 0.147992 +0.595318 0.140534 +0.594906 0.147992 +0.595660 0.140534 +0.595318 0.147992 +0.595935 0.140534 +0.595660 0.147992 +0.595935 0.147992 +0.596114 0.140534 +0.596114 0.147992 +0.417967 0.147992 +0.420898 0.147992 +0.420898 0.140534 +0.420836 0.147992 +0.420657 0.147992 +0.420836 0.140534 +0.420657 0.140534 +0.420382 0.147992 +0.420382 0.140534 +0.420039 0.147992 +0.420039 0.140534 +0.419627 0.147992 +0.419131 0.147992 +0.419627 0.140534 +0.418567 0.147992 +0.419131 0.140534 +0.418567 0.140534 +0.417967 0.140534 +0.392487 0.147992 +0.393345 0.147992 +0.393345 0.140534 +0.393283 0.147992 +0.393283 0.140534 +0.393104 0.147992 +0.392830 0.147992 +0.393104 0.140534 +0.391015 0.140534 +0.390414 0.140534 +0.390414 0.147992 +0.391015 0.147992 +0.391579 0.140534 +0.391579 0.147992 +0.392075 0.140534 +0.392075 0.147992 +0.392487 0.140534 +0.392830 0.140534 +0.385411 0.140534 +0.384614 0.140534 +0.384552 0.140534 +0.384552 0.147992 +0.384793 0.140534 +0.384614 0.147992 +0.384793 0.147992 +0.385068 0.140534 +0.386883 0.147992 +0.387483 0.147992 +0.387483 0.140534 +0.386883 0.140534 +0.386319 0.147992 +0.386319 0.140534 +0.385823 0.147992 +0.385823 0.140534 +0.385411 0.147992 +0.385068 0.147992 +0.264364 0.147992 +0.264964 0.147992 +0.262095 0.140534 +0.262033 0.140534 +0.262033 0.147992 +0.262274 0.140534 +0.262095 0.147992 +0.262549 0.140534 +0.262274 0.147992 +0.262892 0.140534 +0.262549 0.147992 +0.262892 0.147992 +0.263303 0.140534 +0.263800 0.140534 +0.263303 0.147992 +0.263800 0.147992 +0.264364 0.140534 +0.264964 0.140534 +0.297862 0.140534 +0.298378 0.147992 +0.298378 0.140534 +0.298316 0.147992 +0.298316 0.140534 +0.298137 0.147992 +0.298137 0.140534 +0.297862 0.147992 +0.296048 0.140534 +0.295447 0.140534 +0.295447 0.147992 +0.296048 0.147992 +0.296611 0.140534 +0.297108 0.140534 +0.296611 0.147992 +0.297520 0.140534 +0.297108 0.147992 +0.297520 0.147992 +0.269968 0.140534 +0.270826 0.147992 +0.270826 0.140534 +0.270764 0.147992 +0.270764 0.140534 +0.270585 0.147992 +0.270585 0.140534 +0.270310 0.147992 +0.269968 0.147992 +0.270310 0.140534 +0.268496 0.140534 +0.267895 0.140534 +0.267895 0.147992 +0.269059 0.140534 +0.268496 0.147992 +0.269059 0.147992 +0.269556 0.140534 +0.269556 0.147992 +0.718696 0.147992 +0.718696 0.140534 +0.716365 0.140534 +0.715765 0.140534 +0.715765 0.147992 +0.716929 0.140534 +0.716365 0.147992 +0.716929 0.147992 +0.717425 0.140534 +0.717425 0.147992 +0.717837 0.140534 +0.718180 0.140534 +0.717837 0.147992 +0.718180 0.147992 +0.718454 0.140534 +0.718454 0.147992 +0.718633 0.140534 +0.718633 0.147992 +0.710761 0.147992 +0.712233 0.147992 +0.712833 0.147992 +0.712833 0.140534 +0.711669 0.147992 +0.712233 0.140534 +0.711173 0.147992 +0.711669 0.140534 +0.709965 0.140534 +0.709902 0.140534 +0.709902 0.147992 +0.709965 0.147992 +0.710143 0.140534 +0.710143 0.147992 +0.710418 0.140534 +0.710418 0.147992 +0.710761 0.140534 +0.711173 0.140534 +0.682350 0.140534 +0.682350 0.147992 +0.684681 0.147992 +0.685281 0.147992 +0.685281 0.140534 +0.684681 0.140534 +0.684117 0.147992 +0.683620 0.147992 +0.684117 0.140534 +0.683209 0.147992 +0.683620 0.140534 +0.683209 0.140534 +0.682866 0.147992 +0.682591 0.147992 +0.682866 0.140534 +0.682591 0.140534 +0.682412 0.147992 +0.682412 0.140534 +0.322428 0.278797 +0.321827 0.278797 +0.324696 0.286256 +0.324758 0.286256 +0.324758 0.278797 +0.324696 0.278797 +0.324517 0.286256 +0.324517 0.278797 +0.324242 0.286256 +0.324242 0.278797 +0.323900 0.286256 +0.323488 0.286256 +0.323900 0.278797 +0.323488 0.278797 +0.322991 0.286256 +0.322428 0.286256 +0.322991 0.278797 +0.321827 0.286256 +0.318295 0.286256 +0.318896 0.286256 +0.315965 0.278797 +0.315965 0.286256 +0.316027 0.278797 +0.316206 0.278797 +0.316027 0.286256 +0.316481 0.278797 +0.316206 0.286256 +0.316823 0.278797 +0.316481 0.286256 +0.316823 0.286256 +0.317235 0.278797 +0.317732 0.278797 +0.317235 0.286256 +0.318295 0.278797 +0.317732 0.286256 +0.318896 0.278797 +0.291344 0.286256 +0.291344 0.278797 +0.288413 0.278797 +0.288413 0.286256 +0.288475 0.278797 +0.288475 0.286256 +0.288654 0.278797 +0.288654 0.286256 +0.288929 0.278797 +0.289271 0.278797 +0.288929 0.286256 +0.289683 0.278797 +0.289271 0.286256 +0.289683 0.286256 +0.290180 0.278797 +0.290180 0.286256 +0.290743 0.278797 +0.290743 0.286256 +0.411448 0.278797 +0.410932 0.278797 +0.410932 0.286256 +0.410994 0.278797 +0.411173 0.278797 +0.410994 0.286256 +0.413262 0.286256 +0.413863 0.286256 +0.413863 0.278797 +0.413262 0.278797 +0.412699 0.286256 +0.412202 0.286256 +0.412699 0.278797 +0.412202 0.278797 +0.411790 0.286256 +0.411790 0.278797 +0.411448 0.286256 +0.411173 0.286256 +0.441415 0.286256 +0.441415 0.278797 +0.438484 0.278797 +0.438484 0.286256 +0.438546 0.278797 +0.438546 0.286256 +0.438725 0.278797 +0.438725 0.286256 +0.439000 0.278797 +0.439343 0.278797 +0.439000 0.286256 +0.439343 0.286256 +0.439754 0.278797 +0.439754 0.286256 +0.440251 0.278797 +0.440251 0.286256 +0.440815 0.278797 +0.440815 0.286256 +0.447036 0.286256 +0.447215 0.286256 +0.447277 0.286256 +0.447277 0.278797 +0.444947 0.278797 +0.444346 0.278797 +0.444346 0.286256 +0.445510 0.278797 +0.444947 0.286256 +0.445510 0.286256 +0.446007 0.278797 +0.446007 0.286256 +0.446419 0.278797 +0.446761 0.278797 +0.446419 0.286256 +0.446761 0.286256 +0.447036 0.278797 +0.447215 0.278797 +0.542244 0.278797 +0.539914 0.278797 +0.539313 0.278797 +0.539313 0.286256 +0.539914 0.286256 +0.540477 0.278797 +0.540477 0.286256 +0.540974 0.278797 +0.541386 0.278797 +0.540974 0.286256 +0.541728 0.278797 +0.541386 0.286256 +0.541728 0.286256 +0.542003 0.278797 +0.542003 0.286256 +0.542182 0.278797 +0.542182 0.286256 +0.542244 0.286256 +0.567466 0.286256 +0.566865 0.278797 +0.566865 0.286256 +0.567466 0.278797 +0.569734 0.286256 +0.569797 0.286256 +0.569797 0.278797 +0.569734 0.278797 +0.569555 0.286256 +0.569281 0.286256 +0.569555 0.278797 +0.568938 0.286256 +0.569281 0.278797 +0.568938 0.278797 +0.568526 0.286256 +0.568526 0.278797 +0.568030 0.286256 +0.568030 0.278797 +0.534721 0.286256 +0.535782 0.286256 +0.536382 0.286256 +0.536382 0.278797 +0.535782 0.278797 +0.535218 0.286256 +0.533451 0.278797 +0.533451 0.286256 +0.533513 0.278797 +0.533513 0.286256 +0.533692 0.278797 +0.533692 0.286256 +0.533967 0.278797 +0.533967 0.286256 +0.534310 0.278797 +0.534721 0.278797 +0.534310 0.286256 +0.535218 0.278797 +0.657737 0.278797 +0.658901 0.286256 +0.658901 0.278797 +0.658301 0.286256 +0.657737 0.286256 +0.658301 0.278797 +0.655970 0.278797 +0.655970 0.286256 +0.656033 0.278797 +0.656211 0.278797 +0.656033 0.286256 +0.656211 0.286256 +0.656486 0.278797 +0.656486 0.286256 +0.656829 0.278797 +0.657241 0.278797 +0.656829 0.286256 +0.657241 0.286256 +0.662997 0.278797 +0.661833 0.278797 +0.661833 0.286256 +0.662433 0.278797 +0.664701 0.286256 +0.664764 0.286256 +0.664764 0.278797 +0.664701 0.278797 +0.664523 0.286256 +0.664523 0.278797 +0.664248 0.286256 +0.664248 0.278797 +0.663905 0.286256 +0.663905 0.278797 +0.663493 0.286256 +0.662997 0.286256 +0.663493 0.278797 +0.662433 0.286256 +0.691046 0.278797 +0.689985 0.278797 +0.689385 0.278797 +0.689385 0.286256 +0.690549 0.278797 +0.689985 0.286256 +0.692254 0.286256 +0.692316 0.286256 +0.692316 0.278797 +0.692254 0.278797 +0.692075 0.286256 +0.691800 0.286256 +0.692075 0.278797 +0.691457 0.286256 +0.691800 0.278797 +0.691046 0.286256 +0.691457 0.278797 +0.690549 0.286256 + + + + + + + + + + + +

32 0 32 0 1 0 1 2 1 6 3 6 2 4 2 3 5 3 6 6 6 4 7 4 2 8 2 6 9 6 5 10 5 4 11 4 7 12 7 5 13 5 6 14 6 9 15 9 5 16 5 7 17 7 9 18 9 8 19 8 5 20 5 11 21 11 8 22 8 9 23 9 11 24 11 10 25 10 8 26 8 13 27 13 10 28 10 11 29 11 13 30 13 12 31 12 10 32 10 15 33 15 12 34 12 13 35 13 15 36 15 14 37 14 12 38 12 17 39 17 14 40 14 15 41 15 17 42 17 16 43 16 14 44 14 19 45 19 16 46 16 17 47 17 19 48 19 18 49 18 16 50 16 21 51 21 18 52 18 19 53 19 21 54 21 20 55 20 18 56 18 23 57 23 20 58 20 21 59 21 23 60 23 22 61 22 20 62 20 25 63 25 22 64 22 23 65 23 25 66 25 24 67 24 22 68 22 27 69 27 24 70 24 25 71 25 27 72 27 26 73 26 24 74 24 29 75 29 26 76 26 27 77 27 29 78 29 28 79 28 26 80 26 31 81 31 28 82 28 29 83 29 31 84 31 30 85 30 28 86 28 33 87 33 30 88 30 31 89 31 33 90 33 32 91 32 30 92 30 0 93 0 32 94 32 33 95 33 66 96 66 34 97 34 35 98 35 39 99 39 36 100 36 37 101 37 39 102 39 38 103 38 36 104 36 41 105 41 38 106 38 39 107 39 41 108 41 40 109 40 38 110 38 43 111 43 40 112 40 41 113 41 43 114 43 42 115 42 40 116 40 45 117 45 42 118 42 43 119 43 45 120 45 44 121 44 42 122 42 48 123 48 44 124 44 45 125 45 48 126 48 46 127 46 44 128 44 48 129 48 47 130 47 46 131 46 49 132 49 47 133 47 48 134 48 51 135 51 47 136 47 49 137 49 51 138 51 50 139 50 47 140 47 53 141 53 50 142 50 51 143 51 53 144 53 52 145 52 50 146 50 55 147 55 52 148 52 53 149 53 55 150 55 54 151 54 52 152 52 57 153 57 54 154 54 55 155 55 57 156 57 56 157 56 54 158 54 59 159 59 56 160 56 57 161 57 59 162 59 58 163 58 56 164 56 61 165 61 58 166 58 59 167 59 61 168 61 60 169 60 58 170 58 63 171 63 60 172 60 61 173 61 63 174 63 62 175 62 60 176 60 65 177 65 62 178 62 63 179 63 65 180 65 64 181 64 62 182 62 67 183 67 64 184 64 65 185 65 67 186 67 66 187 66 64 188 64 34 189 34 66 190 66 67 191 67 100 192 100 68 193 68 69 194 69 73 195 73 70 196 70 71 197 71 73 198 73 72 199 72 70 200 70 75 201 75 72 202 72 73 203 73 75 204 75 74 205 74 72 206 72 77 207 77 74 208 74 75 209 75 77 210 77 76 211 76 74 212 74 79 213 79 76 214 76 77 215 77 79 216 79 78 217 78 76 218 76 82 219 82 78 220 78 79 221 79 82 222 82 80 223 80 78 224 78 82 225 82 81 226 81 80 227 80 83 228 83 81 229 81 82 230 82 85 231 85 81 232 81 83 233 83 85 234 85 84 235 84 81 236 81 87 237 87 84 238 84 85 239 85 87 240 87 86 241 86 84 242 84 89 243 89 86 244 86 87 245 87 89 246 89 88 247 88 86 248 86 91 249 91 88 250 88 89 251 89 91 252 91 90 253 90 88 254 88 93 255 93 90 256 90 91 257 91 93 258 93 92 259 92 90 260 90 95 261 95 92 262 92 93 263 93 95 264 95 94 265 94 92 266 92 97 267 97 94 268 94 95 269 95 97 270 97 96 271 96 94 272 94 99 273 99 96 274 96 97 275 97 99 276 99 98 277 98 96 278 96 101 279 101 98 280 98 99 281 99 101 282 101 100 283 100 98 284 98 68 285 68 100 286 100 101 287 101 134 288 134 102 289 102 103 290 103 106 291 106 104 292 104 105 293 105 107 294 107 104 295 104 106 296 106 109 297 109 104 298 104 107 299 107 109 300 109 108 301 108 104 302 104 111 303 111 108 304 108 109 305 109 111 306 111 110 307 110 108 308 108 113 309 113 110 310 110 111 311 111 113 312 113 112 313 112 110 314 110 115 315 115 112 316 112 113 317 113 115 318 115 114 319 114 112 320 112 117 321 117 114 322 114 115 323 115 117 324 117 116 325 116 114 326 114 119 327 119 116 328 116 117 329 117 119 330 119 118 331 118 116 332 116 121 333 121 118 334 118 119 335 119 121 336 121 120 337 120 118 338 118 123 339 123 120 340 120 121 341 121 123 342 123 122 343 122 120 344 120 125 345 125 122 346 122 123 347 123 125 348 125 124 349 124 122 350 122 127 351 127 124 352 124 125 353 125 127 354 127 126 355 126 124 356 124 129 357 129 126 358 126 127 359 127 129 360 129 128 361 128 126 362 126 131 363 131 128 364 128 129 365 129 131 366 131 130 367 130 128 368 128 133 369 133 130 370 130 131 371 131 133 372 133 132 373 132 130 374 130 135 375 135 132 376 132 133 377 133 135 378 135 134 379 134 132 380 132 102 381 102 134 382 134 135 383 135 168 384 168 152 385 152 136 386 136 139 387 139 137 388 137 138 389 138 141 390 141 137 391 137 139 392 139 141 393 141 140 394 140 137 395 137 143 396 143 140 397 140 141 398 141 143 399 143 142 400 142 140 401 140 145 402 145 142 403 142 143 404 143 145 405 145 144 406 144 142 407 142 147 408 147 144 409 144 145 410 145 147 411 147 146 412 146 144 413 144 149 414 149 146 415 146 147 416 147 149 417 149 148 418 148 146 419 146 151 420 151 148 421 148 149 422 149 151 423 151 150 424 150 148 425 148 153 426 153 150 427 150 151 428 151 153 429 153 152 430 152 150 431 150 136 432 136 152 433 152 153 434 153 156 435 156 154 436 154 155 437 155 157 438 157 154 439 154 156 440 156 159 441 159 154 442 154 157 443 157 159 444 159 158 445 158 154 446 154 161 447 161 158 448 158 159 449 159 161 450 161 160 451 160 158 452 158 163 453 163 160 454 160 161 455 161 163 456 163 162 457 162 160 458 160 165 459 165 162 460 162 163 461 163 165 462 165 164 463 164 162 464 162 167 465 167 164 466 164 165 467 165 167 468 167 166 469 166 164 470 164 169 471 169 166 472 166 167 473 167 169 474 169 168 475 168 166 476 166 152 477 152 168 478 168 169 479 169 202 480 202 170 481 170 171 482 171 175 483 175 172 484 172 173 485 173 175 486 175 174 487 174 172 488 172 177 489 177 174 490 174 175 491 175 177 492 177 176 493 176 174 494 174 179 495 179 176 496 176 177 497 177 179 498 179 178 499 178 176 500 176 181 501 181 178 502 178 179 503 179 181 504 181 180 505 180 178 506 178 183 507 183 180 508 180 181 509 181 183 510 183 182 511 182 180 512 180 185 513 185 182 514 182 183 515 183 185 516 185 184 517 184 182 518 182 187 519 187 184 520 184 185 521 185 187 522 187 186 523 186 184 524 184 189 525 189 186 526 186 187 527 187 189 528 189 188 529 188 186 530 186 191 531 191 188 532 188 189 533 189 191 534 191 190 535 190 188 536 188 193 537 193 190 538 190 191 539 191 193 540 193 192 541 192 190 542 190 195 543 195 192 544 192 193 545 193 195 546 195 194 547 194 192 548 192 197 549 197 194 550 194 195 551 195 197 552 197 196 553 196 194 554 194 199 555 199 196 556 196 197 557 197 199 558 199 198 559 198 196 560 196 201 561 201 198 562 198 199 563 199 201 564 201 200 565 200 198 566 198 203 567 203 200 568 200 201 569 201 203 570 203 202 571 202 200 572 200 170 573 170 202 574 202 203 575 203 236 576 236 207 577 207 204 578 204 204 579 204 205 580 205 206 581 206 204 582 204 207 583 207 205 584 205 210 585 210 208 586 208 209 587 209 211 588 211 208 589 208 210 590 210 213 591 213 208 592 208 211 593 211 213 594 213 212 595 212 208 596 208 215 597 215 212 598 212 213 599 213 215 600 215 214 601 214 212 602 212 217 603 217 214 604 214 215 605 215 217 606 217 216 607 216 214 608 214 219 609 219 216 610 216 217 611 217 219 612 219 218 613 218 216 614 216 221 615 221 218 616 218 219 617 219 221 618 221 220 619 220 218 620 218 223 621 223 220 622 220 221 623 221 223 624 223 222 625 222 220 626 220 225 627 225 222 628 222 223 629 223 225 630 225 224 631 224 222 632 222 227 633 227 224 634 224 225 635 225 227 636 227 226 637 226 224 638 224 229 639 229 226 640 226 227 641 227 229 642 229 228 643 228 226 644 226 231 645 231 228 646 228 229 647 229 231 648 231 230 649 230 228 650 228 233 651 233 230 652 230 231 653 231 233 654 233 232 655 232 230 656 230 235 657 235 232 658 232 233 659 233 235 660 235 234 661 234 232 662 232 237 663 237 234 664 234 235 665 235 237 666 237 236 667 236 234 668 234 207 669 207 236 670 236 237 671 237 271 672 271 238 673 238 239 674 239 242 675 242 240 676 240 241 677 241 244 678 244 240 679 240 242 680 242 244 681 244 243 682 243 240 683 240 246 684 246 243 685 243 244 686 244 246 687 246 245 688 245 243 689 243 248 690 248 245 691 245 246 692 246 248 693 248 247 694 247 245 695 245 250 696 250 247 697 247 248 698 248 250 699 250 249 700 249 247 701 247 252 702 252 249 703 249 250 704 250 252 705 252 251 706 251 249 707 249 254 708 254 251 709 251 252 710 252 254 711 254 253 712 253 251 713 251 255 714 255 253 715 253 254 716 254 258 717 258 253 718 253 255 719 255 258 720 258 256 721 256 253 722 253 258 723 258 257 724 257 256 725 256 260 726 260 257 727 257 258 728 258 260 729 260 259 730 259 257 731 257 262 732 262 259 733 259 260 734 260 262 735 262 261 736 261 259 737 259 263 738 263 261 739 261 262 740 262 265 741 265 261 742 261 263 743 263 265 744 265 264 745 264 261 746 261 268 747 268 264 748 264 265 749 265 268 750 268 266 751 266 264 752 264 268 753 268 267 754 267 266 755 266 270 756 270 267 757 267 268 758 268 270 759 270 269 760 269 267 761 267 238 762 238 269 763 269 270 764 270 238 765 238 271 766 271 269 767 269 304 768 304 272 769 272 273 770 273 278 771 278 274 772 274 275 773 275 278 774 278 276 775 276 274 776 274 278 777 278 277 778 277 276 779 276 279 780 279 277 781 277 278 782 278 281 783 281 277 784 277 279 785 279 281 786 281 280 787 280 277 788 277 284 789 284 280 790 280 281 791 281 284 792 284 282 793 282 280 794 280 284 795 284 283 796 283 282 797 282 285 798 285 283 799 283 284 800 284 287 801 287 283 802 283 285 803 285 287 804 287 286 805 286 283 806 283 289 807 289 286 808 286 287 809 287 289 810 289 288 811 288 286 812 286 291 813 291 288 814 288 289 815 289 291 816 291 290 817 290 288 818 288 293 819 293 290 820 290 291 821 291 293 822 293 292 823 292 290 824 290 295 825 295 292 826 292 293 827 293 295 828 295 294 829 294 292 830 292 297 831 297 294 832 294 295 833 295 297 834 297 296 835 296 294 836 294 299 837 299 296 838 296 297 839 297 299 840 299 298 841 298 296 842 296 301 843 301 298 844 298 299 845 299 301 846 301 300 847 300 298 848 298 303 849 303 300 850 300 301 851 301 303 852 303 302 853 302 300 854 300 305 855 305 302 856 302 303 857 303 305 858 305 304 859 304 302 860 302 272 861 272 304 862 304 305 863 305 338 864 338 306 865 306 307 866 307 312 867 312 308 868 308 309 869 309 312 870 312 310 871 310 308 872 308 312 873 312 311 874 311 310 875 310 313 876 313 311 877 311 312 878 312 315 879 315 311 880 311 313 881 313 315 882 315 314 883 314 311 884 311 317 885 317 314 886 314 315 887 315 317 888 317 316 889 316 314 890 314 319 891 319 316 892 316 317 893 317 319 894 319 318 895 318 316 896 316 321 897 321 318 898 318 319 899 319 321 900 321 320 901 320 318 902 318 323 903 323 320 904 320 321 905 321 323 906 323 322 907 322 320 908 320 325 909 325 322 910 322 323 911 323 325 912 325 324 913 324 322 914 322 327 915 327 324 916 324 325 917 325 327 918 327 326 919 326 324 920 324 329 921 329 326 922 326 327 923 327 329 924 329 328 925 328 326 926 326 331 927 331 328 928 328 329 929 329 331 930 331 330 931 330 328 932 328 333 933 333 330 934 330 331 935 331 333 936 333 332 937 332 330 938 330 335 939 335 332 940 332 333 941 333 335 942 335 334 943 334 332 944 332 337 945 337 334 946 334 335 947 335 337 948 337 336 949 336 334 950 334 339 951 339 336 952 336 337 953 337 339 954 339 338 955 338 336 956 336 306 957 306 338 958 338 339 959 339 372 960 372 340 961 340 341 962 341 346 963 346 342 964 342 343 965 343 346 966 346 344 967 344 342 968 342 346 969 346 345 970 345 344 971 344 347 972 347 345 973 345 346 974 346 349 975 349 345 976 345 347 977 347 349 978 349 348 979 348 345 980 345 351 981 351 348 982 348 349 983 349 351 984 351 350 985 350 348 986 348 353 987 353 350 988 350 351 989 351 353 990 353 352 991 352 350 992 350 355 993 355 352 994 352 353 995 353 355 996 355 354 997 354 352 998 352 357 999 357 354 1000 354 355 1001 355 357 1002 357 356 1003 356 354 1004 354 359 1005 359 356 1006 356 357 1007 357 359 1008 359 358 1009 358 356 1010 356 361 1011 361 358 1012 358 359 1013 359 361 1014 361 360 1015 360 358 1016 358 363 1017 363 360 1018 360 361 1019 361 363 1020 363 362 1021 362 360 1022 360 365 1023 365 362 1024 362 363 1025 363 365 1026 365 364 1027 364 362 1028 362 367 1029 367 364 1030 364 365 1031 365 367 1032 367 366 1033 366 364 1034 364 369 1035 369 366 1036 366 367 1037 367 369 1038 369 368 1039 368 366 1040 366 371 1041 371 368 1042 368 369 1043 369 371 1044 371 370 1045 370 368 1046 368 373 1047 373 370 1048 370 371 1049 371 373 1050 373 372 1051 372 370 1052 370 340 1053 340 372 1054 372 373 1055 373 406 1056 406 374 1057 374 375 1058 375 378 1059 378 376 1060 376 377 1061 377 379 1062 379 376 1063 376 378 1064 378 382 1065 382 376 1066 376 379 1067 379 382 1068 382 380 1069 380 376 1070 376 382 1071 382 381 1072 381 380 1073 380 384 1074 384 381 1075 381 382 1076 382 384 1077 384 383 1078 383 381 1079 381 385 1080 385 383 1081 383 384 1082 384 388 1083 388 383 1084 383 385 1085 385 388 1086 388 386 1087 386 383 1088 383 388 1089 388 387 1090 387 386 1091 386 390 1092 390 387 1093 387 388 1094 388 390 1095 390 389 1096 389 387 1097 387 391 1098 391 389 1099 389 390 1100 390 393 1101 393 389 1102 389 391 1103 391 393 1104 393 392 1105 392 389 1106 389 395 1107 395 392 1108 392 393 1109 393 395 1110 395 394 1111 394 392 1112 392 397 1113 397 394 1114 394 395 1115 395 397 1116 397 396 1117 396 394 1118 394 399 1119 399 396 1120 396 397 1121 397 399 1122 399 398 1123 398 396 1124 396 401 1125 401 398 1126 398 399 1127 399 401 1128 401 400 1129 400 398 1130 398 403 1131 403 400 1132 400 401 1133 401 403 1134 403 402 1135 402 400 1136 400 405 1137 405 402 1138 402 403 1139 403 405 1140 405 404 1141 404 402 1142 402 407 1143 407 404 1144 404 405 1145 405 407 1146 407 406 1147 406 404 1148 404 374 1149 374 406 1150 406 407 1151 407 417 1152 417 408 1153 408 413 1154 413 412 1155 412 409 1156 409 410 1157 410 412 1158 412 411 1159 411 409 1160 409 417 1161 417 411 1162 411 412 1163 412 417 1164 417 413 1165 413 411 1166 411 408 1167 408 414 1168 414 415 1169 415 408 1170 408 416 1171 416 414 1172 414 408 1173 408 417 1174 417 416 1175 416 432 1176 432 418 1177 418 419 1178 419 424 1179 424 420 1180 420 421 1181 421 424 1182 424 422 1183 422 420 1184 420 424 1185 424 423 1186 423 422 1187 422 426 1188 426 423 1189 423 424 1190 424 426 1191 426 425 1192 425 423 1193 423 429 1194 429 425 1195 425 426 1196 426 429 1197 429 427 1198 427 425 1199 425 429 1200 429 428 1201 428 427 1202 427 431 1203 431 428 1204 428 429 1205 429 431 1206 431 430 1207 430 428 1208 428 433 1209 433 430 1210 430 431 1211 431 433 1212 433 432 1213 432 430 1214 430 418 1215 418 432 1216 432 433 1217 433 446 1218 446 434 1219 434 435 1220 435 438 1221 438 436 1222 436 437 1223 437 439 1224 439 436 1225 436 438 1226 438 441 1227 441 436 1228 436 439 1229 439 441 1230 441 440 1231 440 436 1232 436 443 1233 443 440 1234 440 441 1235 441 443 1236 443 442 1237 442 440 1238 440 445 1239 445 442 1240 442 443 1241 443 445 1242 445 444 1243 444 442 1244 442 447 1245 447 444 1246 444 445 1247 445 447 1248 447 446 1249 446 444 1250 444 434 1251 434 446 1252 446 447 1253 447 473 1254 473 448 1255 448 451 1256 451 473 1257 473 449 1258 449 450 1259 450 473 1260 473 451 1261 451 449 1262 449 455 1263 455 452 1264 452 453 1265 453 455 1266 455 454 1267 454 452 1268 452 457 1269 457 454 1270 454 455 1271 455 457 1272 457 456 1273 456 454 1274 454 460 1275 460 456 1276 456 457 1277 457 460 1278 460 458 1279 458 456 1280 456 460 1281 460 459 1282 459 458 1283 458 462 1284 462 459 1285 459 460 1286 460 462 1287 462 461 1288 461 459 1289 459 464 1290 464 461 1291 461 462 1292 462 464 1293 464 463 1294 463 461 1295 461 466 1296 466 463 1297 463 464 1298 464 466 1299 466 465 1300 465 463 1301 463 467 1302 467 465 1303 465 466 1304 466 470 1305 470 465 1306 465 467 1307 467 470 1308 470 468 1309 468 465 1310 465 470 1311 470 469 1312 469 468 1313 468 472 1314 472 469 1315 469 470 1316 470 472 1317 472 471 1318 471 469 1319 469 448 1320 448 471 1321 471 472 1322 472 448 1323 448 473 1324 473 471 1325 471 507 1326 507 474 1327 474 479 1328 479 477 1329 477 475 1330 475 476 1331 476 478 1332 478 475 1333 475 477 1334 477 507 1335 507 475 1336 475 478 1337 478 507 1338 507 479 1339 479 475 1340 475 483 1341 483 480 1342 480 481 1343 481 483 1344 483 482 1345 482 480 1346 480 485 1347 485 482 1348 482 483 1349 483 485 1350 485 484 1351 484 482 1352 482 487 1353 487 484 1354 484 485 1355 485 487 1356 487 486 1357 486 484 1358 484 489 1359 489 486 1360 486 487 1361 487 489 1362 489 488 1363 488 486 1364 486 491 1365 491 488 1366 488 489 1367 489 491 1368 491 490 1369 490 488 1370 488 493 1371 493 490 1372 490 491 1373 491 493 1374 493 492 1375 492 490 1376 490 495 1377 495 492 1378 492 493 1379 493 495 1380 495 494 1381 494 492 1382 492 497 1383 497 494 1384 494 495 1385 495 497 1386 497 496 1387 496 494 1388 494 499 1389 499 496 1390 496 497 1391 497 499 1392 499 498 1393 498 496 1394 496 502 1395 502 498 1396 498 499 1397 499 502 1398 502 500 1399 500 498 1400 498 502 1401 502 501 1402 501 500 1403 500 503 1404 503 501 1405 501 502 1406 502 505 1407 505 501 1408 501 503 1409 503 505 1410 505 504 1411 504 501 1412 501 474 1413 474 504 1414 504 505 1415 505 474 1416 474 506 1417 506 504 1418 504 474 1419 474 507 1420 507 506 1421 506 540 1422 540 508 1423 508 509 1424 509 513 1425 513 510 1426 510 511 1427 511 513 1428 513 512 1429 512 510 1430 510 515 1431 515 512 1432 512 513 1433 513 515 1434 515 514 1435 514 512 1436 512 517 1437 517 514 1438 514 515 1439 515 517 1440 517 516 1441 516 514 1442 514 519 1443 519 516 1444 516 517 1445 517 519 1446 519 518 1447 518 516 1448 516 521 1449 521 518 1450 518 519 1451 519 521 1452 521 520 1453 520 518 1454 518 523 1455 523 520 1456 520 521 1457 521 523 1458 523 522 1459 522 520 1460 520 525 1461 525 522 1462 522 523 1463 523 525 1464 525 524 1465 524 522 1466 522 527 1467 527 524 1468 524 525 1469 525 527 1470 527 526 1471 526 524 1472 524 529 1473 529 526 1474 526 527 1475 527 529 1476 529 528 1477 528 526 1478 526 531 1479 531 528 1480 528 529 1481 529 531 1482 531 530 1483 530 528 1484 528 533 1485 533 530 1486 530 531 1487 531 533 1488 533 532 1489 532 530 1490 530 535 1491 535 532 1492 532 533 1493 533 535 1494 535 534 1495 534 532 1496 532 537 1497 537 534 1498 534 535 1499 535 537 1500 537 536 1501 536 534 1502 534 539 1503 539 536 1504 536 537 1505 537 539 1506 539 538 1507 538 536 1508 536 541 1509 541 538 1510 538 539 1511 539 541 1512 541 540 1513 540 538 1514 538 508 1515 508 540 1516 540 541 1517 541 560 1518 560 542 1519 542 561 1520 561 544 1521 544 562 1522 562 543 1523 543 545 1524 545 562 1525 562 544 1526 544 546 1527 546 562 1528 562 545 1529 545 546 1530 546 563 1531 563 562 1532 562 547 1533 547 563 1534 563 546 1535 546 547 1536 547 564 1537 564 563 1538 563 548 1539 548 564 1540 564 547 1541 547 548 1542 548 565 1543 565 564 1544 564 549 1545 549 565 1546 565 548 1547 548 549 1548 549 566 1549 566 565 1550 565 550 1551 550 566 1552 566 549 1553 549 550 1554 550 567 1555 567 566 1556 566 551 1557 551 567 1558 567 550 1559 550 551 1560 551 568 1561 568 567 1562 567 552 1563 552 568 1564 568 551 1565 551 552 1566 552 569 1567 569 568 1568 568 553 1569 553 569 1570 569 552 1571 552 553 1572 553 570 1573 570 569 1574 569 554 1575 554 570 1576 570 553 1577 553 554 1578 554 571 1579 571 570 1580 570 555 1581 555 571 1582 571 554 1583 554 555 1584 555 572 1585 572 571 1586 571 556 1587 556 572 1588 572 555 1589 555 556 1590 556 573 1591 573 572 1592 572 556 1593 556 574 1594 574 573 1595 573 557 1596 557 574 1597 574 556 1598 556 558 1599 558 574 1600 574 557 1601 557 558 1602 558 575 1603 575 574 1604 574 559 1605 559 575 1606 575 558 1607 558 559 1608 559 560 1609 560 575 1610 575 542 1611 542 560 1612 560 559 1613 559 608 1614 608 576 1615 576 577 1616 577 582 1617 582 578 1618 578 579 1619 579 582 1620 582 580 1621 580 578 1622 578 582 1623 582 581 1624 581 580 1625 580 583 1626 583 581 1627 581 582 1628 582 585 1629 585 581 1630 581 583 1631 583 585 1632 585 584 1633 584 581 1634 581 588 1635 588 584 1636 584 585 1637 585 588 1638 588 586 1639 586 584 1640 584 588 1641 588 587 1642 587 586 1643 586 589 1644 589 587 1645 587 588 1646 588 591 1647 591 587 1648 587 589 1649 589 591 1650 591 590 1651 590 587 1652 587 593 1653 593 590 1654 590 591 1655 591 593 1656 593 592 1657 592 590 1658 590 595 1659 595 592 1660 592 593 1661 593 595 1662 595 594 1663 594 592 1664 592 597 1665 597 594 1666 594 595 1667 595 597 1668 597 596 1669 596 594 1670 594 600 1671 600 596 1672 596 597 1673 597 600 1674 600 598 1675 598 596 1676 596 600 1677 600 599 1678 599 598 1679 598 601 1680 601 599 1681 599 600 1682 600 603 1683 603 599 1684 599 601 1685 601 603 1686 603 602 1687 602 599 1688 599 605 1689 605 602 1690 602 603 1691 603 605 1692 605 604 1693 604 602 1694 602 607 1695 607 604 1696 604 605 1697 605 607 1698 607 606 1699 606 604 1700 604 609 1701 609 606 1702 606 607 1703 607 609 1704 609 608 1705 608 606 1706 606 576 1707 576 608 1708 608 609 1709 609 626 1710 626 610 1711 610 611 1712 611 615 1713 615 612 1714 612 613 1715 613 615 1716 615 614 1717 614 612 1718 612 617 1719 617 614 1720 614 615 1721 615 617 1722 617 616 1723 616 614 1724 614 620 1725 620 616 1726 616 617 1727 617 620 1728 620 618 1729 618 616 1730 616 620 1731 620 619 1732 619 618 1733 618 622 1734 622 619 1735 619 620 1736 620 622 1737 622 621 1738 621 619 1739 619 624 1740 624 621 1741 621 622 1742 622 624 1743 624 623 1744 623 621 1745 621 625 1746 625 623 1747 623 624 1748 624 627 1749 627 623 1750 623 625 1751 625 627 1752 627 626 1753 626 623 1754 623 610 1755 610 626 1756 626 627 1757 627 660 1758 660 628 1759 628 629 1760 629 633 1761 633 630 1762 630 631 1763 631 633 1764 633 632 1765 632 630 1766 630 635 1767 635 632 1768 632 633 1769 633 635 1770 635 634 1771 634 632 1772 632 637 1773 637 634 1774 634 635 1775 635 637 1776 637 636 1777 636 634 1778 634 639 1779 639 636 1780 636 637 1781 637 639 1782 639 638 1783 638 636 1784 636 641 1785 641 638 1786 638 639 1787 639 641 1788 641 640 1789 640 638 1790 638 643 1791 643 640 1792 640 641 1793 641 643 1794 643 642 1795 642 640 1796 640 645 1797 645 642 1798 642 643 1799 643 645 1800 645 644 1801 644 642 1802 642 647 1803 647 644 1804 644 645 1805 645 647 1806 647 646 1807 646 644 1808 644 649 1809 649 646 1810 646 647 1811 647 649 1812 649 648 1813 648 646 1814 646 651 1815 651 648 1816 648 649 1817 649 651 1818 651 650 1819 650 648 1820 648 653 1821 653 650 1822 650 651 1823 651 653 1824 653 652 1825 652 650 1826 650 655 1827 655 652 1828 652 653 1829 653 655 1830 655 654 1831 654 652 1832 652 657 1833 657 654 1834 654 655 1835 655 657 1836 657 656 1837 656 654 1838 654 659 1839 659 656 1840 656 657 1841 657 659 1842 659 658 1843 658 656 1844 656 661 1845 661 658 1846 658 659 1847 659 661 1848 661 660 1849 660 658 1850 658 628 1851 628 660 1852 660 661 1853 661 680 1854 680 662 1855 662 681 1856 681 664 1857 664 682 1858 682 663 1859 663 665 1860 665 682 1861 682 664 1862 664 666 1863 666 682 1864 682 665 1865 665 666 1866 666 683 1867 683 682 1868 682 667 1869 667 683 1870 683 666 1871 666 667 1872 667 684 1873 684 683 1874 683 668 1875 668 684 1876 684 667 1877 667 668 1878 668 685 1879 685 684 1880 684 669 1881 669 685 1882 685 668 1883 668 669 1884 669 686 1885 686 685 1886 685 670 1887 670 686 1888 686 669 1889 669 670 1890 670 687 1891 687 686 1892 686 671 1893 671 687 1894 687 670 1895 670 671 1896 671 688 1897 688 687 1898 687 672 1899 672 688 1900 688 671 1901 671 672 1902 672 689 1903 689 688 1904 688 673 1905 673 689 1906 689 672 1907 672 673 1908 673 690 1909 690 689 1910 689 674 1911 674 690 1912 690 673 1913 673 674 1914 674 691 1915 691 690 1916 690 675 1917 675 691 1918 691 674 1919 674 675 1920 675 692 1921 692 691 1922 691 676 1923 676 692 1924 692 675 1925 675 676 1926 676 693 1927 693 692 1928 692 677 1929 677 693 1930 693 676 1931 676 677 1932 677 694 1933 694 693 1934 693 678 1935 678 694 1936 694 677 1937 677 678 1938 678 695 1939 695 694 1940 694 679 1941 679 695 1942 695 678 1943 678 679 1944 679 680 1945 680 695 1946 695 662 1947 662 680 1948 680 679 1949 679 708 1950 708 696 1951 696 697 1952 697 700 1953 700 698 1954 698 699 1955 699 701 1956 701 698 1957 698 700 1958 700 703 1959 703 698 1960 698 701 1961 701 703 1962 703 702 1963 702 698 1964 698 705 1965 705 702 1966 702 703 1967 703 705 1968 705 704 1969 704 702 1970 702 707 1971 707 704 1972 704 705 1973 705 707 1974 707 706 1975 706 704 1976 704 709 1977 709 706 1978 706 707 1979 707 709 1980 709 708 1981 708 706 1982 706 696 1983 696 708 1984 708 709 1985 709 718 1986 718 710 1987 710 711 1988 711 715 1989 715 712 1990 712 713 1991 713 715 1992 715 714 1993 714 712 1994 712 717 1995 717 714 1996 714 715 1997 715 717 1998 717 716 1999 716 714 2000 714 719 2001 719 716 2002 716 717 2003 717 719 2004 719 718 2005 718 716 2006 716 710 2007 710 718 2008 718 719 2009 719 728 2010 728 720 2011 720 721 2012 721 726 2013 726 722 2014 722 723 2015 723 726 2016 726 724 2017 724 722 2018 722 726 2019 726 725 2020 725 724 2021 724 727 2022 727 725 2023 725 726 2024 726 729 2025 729 725 2026 725 727 2027 727 729 2028 729 728 2029 728 725 2030 725 720 2031 720 728 2032 728 729 2033 729 744 2034 744 730 2035 730 731 2036 731 736 2037 736 732 2038 732 733 2039 733 736 2040 736 734 2041 734 732 2042 732 736 2043 736 735 2044 735 734 2045 734 738 2046 738 735 2047 735 736 2048 736 738 2049 738 737 2050 737 735 2051 735 741 2052 741 737 2053 737 738 2054 738 741 2055 741 739 2056 739 737 2057 737 741 2058 741 740 2059 740 739 2060 739 743 2061 743 740 2062 740 741 2063 741 743 2064 743 742 2065 742 740 2066 740 745 2067 745 742 2068 742 743 2069 743 745 2070 745 744 2071 744 742 2072 742 730 2073 730 744 2074 744 745 2075 745 778 2076 778 746 2077 746 747 2078 747 751 2079 751 748 2080 748 749 2081 749 751 2082 751 750 2083 750 748 2084 748 754 2085 754 750 2086 750 751 2087 751 754 2088 754 752 2089 752 750 2090 750 754 2091 754 753 2092 753 752 2093 752 755 2094 755 753 2095 753 754 2096 754 757 2097 757 753 2098 753 755 2099 755 757 2100 757 756 2101 756 753 2102 753 759 2103 759 756 2104 756 757 2105 757 759 2106 759 758 2107 758 756 2108 756 761 2109 761 758 2110 758 759 2111 759 761 2112 761 760 2113 760 758 2114 758 763 2115 763 760 2116 760 761 2117 761 763 2118 763 762 2119 762 760 2120 760 765 2121 765 762 2122 762 763 2123 763 765 2124 765 764 2125 764 762 2126 762 767 2127 767 764 2128 764 765 2129 765 767 2130 767 766 2131 766 764 2132 764 769 2133 769 766 2134 766 767 2135 767 769 2136 769 768 2137 768 766 2138 766 771 2139 771 768 2140 768 769 2141 769 771 2142 771 770 2143 770 768 2144 768 773 2145 773 770 2146 770 771 2147 771 773 2148 773 772 2149 772 770 2150 770 775 2151 775 772 2152 772 773 2153 773 775 2154 775 774 2155 774 772 2156 772 777 2157 777 774 2158 774 775 2159 775 777 2160 777 776 2161 776 774 2162 774 779 2163 779 776 2164 776 777 2165 777 779 2166 779 778 2167 778 776 2168 776 746 2169 746 778 2170 778 779 2171 779 812 2172 812 793 2173 793 780 2174 780 783 2175 783 781 2176 781 782 2177 782 785 2178 785 781 2179 781 783 2180 783 785 2181 785 784 2182 784 781 2183 781 787 2184 787 784 2185 784 785 2186 785 787 2187 787 786 2188 786 784 2189 784 788 2190 788 786 2191 786 787 2192 787 791 2193 791 786 2194 786 788 2195 788 791 2196 791 789 2197 789 786 2198 786 791 2199 791 790 2200 790 789 2201 789 792 2202 792 790 2203 790 791 2204 791 780 2205 780 790 2206 790 792 2207 792 780 2208 780 793 2209 793 790 2210 790 797 2211 797 794 2212 794 795 2213 795 797 2214 797 796 2215 796 794 2216 794 799 2217 799 796 2218 796 797 2219 797 799 2220 799 798 2221 798 796 2222 796 801 2223 801 798 2224 798 799 2225 799 801 2226 801 800 2227 800 798 2228 798 803 2229 803 800 2230 800 801 2231 801 803 2232 803 802 2233 802 800 2234 800 805 2235 805 802 2236 802 803 2237 803 805 2238 805 804 2239 804 802 2240 802 807 2241 807 804 2242 804 805 2243 805 807 2244 807 806 2245 806 804 2246 804 809 2247 809 806 2248 806 807 2249 807 809 2250 809 808 2251 808 806 2252 806 811 2253 811 808 2254 808 809 2255 809 811 2256 811 810 2257 810 808 2258 808 813 2259 813 810 2260 810 811 2261 811 813 2262 813 812 2263 812 810 2264 810 793 2265 793 812 2266 812 813 2267 813 846 2268 846 818 2269 818 814 2270 814 819 2271 819 815 2272 815 816 2273 816 819 2274 819 817 2275 817 815 2276 815 819 2277 819 818 2278 818 817 2279 817 814 2280 814 818 2281 818 819 2282 819 822 2283 822 820 2284 820 821 2285 821 823 2286 823 820 2287 820 822 2288 822 825 2289 825 820 2290 820 823 2291 823 825 2292 825 824 2293 824 820 2294 820 827 2295 827 824 2296 824 825 2297 825 827 2298 827 826 2299 826 824 2300 824 829 2301 829 826 2302 826 827 2303 827 829 2304 829 828 2305 828 826 2306 826 831 2307 831 828 2308 828 829 2309 829 831 2310 831 830 2311 830 828 2312 828 833 2313 833 830 2314 830 831 2315 831 833 2316 833 832 2317 832 830 2318 830 835 2319 835 832 2320 832 833 2321 833 835 2322 835 834 2323 834 832 2324 832 837 2325 837 834 2326 834 835 2327 835 837 2328 837 836 2329 836 834 2330 834 839 2331 839 836 2332 836 837 2333 837 839 2334 839 838 2335 838 836 2336 836 841 2337 841 838 2338 838 839 2339 839 841 2340 841 840 2341 840 838 2342 838 843 2343 843 840 2344 840 841 2345 841 843 2346 843 842 2347 842 840 2348 840 845 2349 845 842 2350 842 843 2351 843 845 2352 845 844 2353 844 842 2354 842 847 2355 847 844 2356 844 845 2357 845 847 2358 847 846 2359 846 844 2360 844 818 2361 818 846 2362 846 847 2363 847 880 2364 880 848 2365 848 849 2366 849 852 2367 852 850 2368 850 851 2369 851 853 2370 853 850 2371 850 852 2372 852 855 2373 855 850 2374 850 853 2375 853 855 2376 855 854 2377 854 850 2378 850 857 2379 857 854 2380 854 855 2381 855 857 2382 857 856 2383 856 854 2384 854 859 2385 859 856 2386 856 857 2387 857 859 2388 859 858 2389 858 856 2390 856 861 2391 861 858 2392 858 859 2393 859 861 2394 861 860 2395 860 858 2396 858 863 2397 863 860 2398 860 861 2399 861 863 2400 863 862 2401 862 860 2402 860 865 2403 865 862 2404 862 863 2405 863 865 2406 865 864 2407 864 862 2408 862 867 2409 867 864 2410 864 865 2411 865 867 2412 867 866 2413 866 864 2414 864 869 2415 869 866 2416 866 867 2417 867 869 2418 869 868 2419 868 866 2420 866 871 2421 871 868 2422 868 869 2423 869 871 2424 871 870 2425 870 868 2426 868 873 2427 873 870 2428 870 871 2429 871 873 2430 873 872 2431 872 870 2432 870 875 2433 875 872 2434 872 873 2435 873 875 2436 875 874 2437 874 872 2438 872 877 2439 877 874 2440 874 875 2441 875 877 2442 877 876 2443 876 874 2444 874 879 2445 879 876 2446 876 877 2447 877 879 2448 879 878 2449 878 876 2450 876 881 2451 881 878 2452 878 879 2453 879 881 2454 881 880 2455 880 878 2456 878 848 2457 848 880 2458 880 881 2459 881 914 2460 914 886 2461 886 882 2462 882 885 2463 885 883 2464 883 884 2465 884 887 2466 887 883 2467 883 885 2468 885 887 2469 887 886 2470 886 883 2471 883 882 2472 882 886 2473 886 887 2474 887 891 2475 891 888 2476 888 889 2477 889 891 2478 891 890 2479 890 888 2480 888 894 2481 894 890 2482 890 891 2483 891 894 2484 894 892 2485 892 890 2486 890 894 2487 894 893 2488 893 892 2489 892 896 2490 896 893 2491 893 894 2492 894 896 2493 896 895 2494 895 893 2495 893 897 2496 897 895 2497 895 896 2498 896 900 2499 900 895 2500 895 897 2501 897 900 2502 900 898 2503 898 895 2504 895 900 2505 900 899 2506 899 898 2507 898 901 2508 901 899 2509 899 900 2510 900 903 2511 903 899 2512 899 901 2513 901 903 2514 903 902 2515 902 899 2516 899 905 2517 905 902 2518 902 903 2519 903 905 2520 905 904 2521 904 902 2522 902 907 2523 907 904 2524 904 905 2525 905 907 2526 907 906 2527 906 904 2528 904 909 2529 909 906 2530 906 907 2531 907 909 2532 909 908 2533 908 906 2534 906 911 2535 911 908 2536 908 909 2537 909 911 2538 911 910 2539 910 908 2540 908 913 2541 913 910 2542 910 911 2543 911 913 2544 913 912 2545 912 910 2546 910 915 2547 915 912 2548 912 913 2549 913 915 2550 915 914 2551 914 912 2552 912 886 2553 886 914 2554 914 915 2555 915 948 2556 948 917 2557 917 916 2558 916 919 2559 919 917 2560 917 918 2561 918 916 2562 916 917 2563 917 919 2564 919 922 2565 922 920 2566 920 921 2567 921 923 2568 923 920 2569 920 922 2570 922 925 2571 925 920 2572 920 923 2573 923 925 2574 925 924 2575 924 920 2576 920 927 2577 927 924 2578 924 925 2579 925 927 2580 927 926 2581 926 924 2582 924 929 2583 929 926 2584 926 927 2585 927 929 2586 929 928 2587 928 926 2588 926 932 2589 932 928 2590 928 929 2591 929 932 2592 932 930 2593 930 928 2594 928 932 2595 932 931 2596 931 930 2597 930 933 2598 933 931 2599 931 932 2600 932 935 2601 935 931 2602 931 933 2603 933 935 2604 935 934 2605 934 931 2606 931 937 2607 937 934 2608 934 935 2609 935 937 2610 937 936 2611 936 934 2612 934 939 2613 939 936 2614 936 937 2615 937 939 2616 939 938 2617 938 936 2618 936 941 2619 941 938 2620 938 939 2621 939 941 2622 941 940 2623 940 938 2624 938 943 2625 943 940 2626 940 941 2627 941 943 2628 943 942 2629 942 940 2630 940 946 2631 946 942 2632 942 943 2633 943 946 2634 946 944 2635 944 942 2636 942 946 2637 946 945 2638 945 944 2639 944 947 2640 947 945 2641 945 946 2642 946 949 2643 949 945 2644 945 947 2645 947 949 2646 949 948 2647 948 945 2648 945 917 2649 917 948 2650 948 949 2651 949 983 2652 983 950 2653 950 953 2654 953 983 2655 983 951 2656 951 952 2657 952 983 2658 983 953 2659 953 951 2660 951 957 2661 957 954 2662 954 955 2663 955 957 2664 957 956 2665 956 954 2666 954 959 2667 959 956 2668 956 957 2669 957 959 2670 959 958 2671 958 956 2672 956 961 2673 961 958 2674 958 959 2675 959 961 2676 961 960 2677 960 958 2678 958 963 2679 963 960 2680 960 961 2681 961 963 2682 963 962 2683 962 960 2684 960 965 2685 965 962 2686 962 963 2687 963 965 2688 965 964 2689 964 962 2690 962 967 2691 967 964 2692 964 965 2693 965 967 2694 967 966 2695 966 964 2696 964 969 2697 969 966 2698 966 967 2699 967 969 2700 969 968 2701 968 966 2702 966 971 2703 971 968 2704 968 969 2705 969 971 2706 971 970 2707 970 968 2708 968 973 2709 973 970 2710 970 971 2711 971 973 2712 973 972 2713 972 970 2714 970 975 2715 975 972 2716 972 973 2717 973 975 2718 975 974 2719 974 972 2720 972 977 2721 977 974 2722 974 975 2723 975 977 2724 977 976 2725 976 974 2726 974 979 2727 979 976 2728 976 977 2729 977 979 2730 979 978 2731 978 976 2732 976 981 2733 981 978 2734 978 979 2735 979 981 2736 981 980 2737 980 978 2738 978 950 2739 950 980 2740 980 981 2741 981 950 2742 950 982 2743 982 980 2744 980 950 2745 950 983 2746 983 982 2747 982 1016 2748 1016 995 2749 995 984 2750 984 987 2751 987 985 2752 985 986 2753 986 989 2754 989 985 2755 985 987 2756 987 989 2757 989 988 2758 988 985 2759 985 990 2760 990 988 2761 988 989 2762 989 993 2763 993 988 2764 988 990 2765 990 993 2766 993 991 2767 991 988 2768 988 993 2769 993 992 2770 992 991 2771 991 994 2772 994 992 2773 992 993 2774 993 984 2775 984 992 2776 992 994 2777 994 984 2778 984 995 2779 995 992 2780 992 999 2781 999 996 2782 996 997 2783 997 999 2784 999 998 2785 998 996 2786 996 1001 2787 1001 998 2788 998 999 2789 999 1001 2790 1001 1000 2791 1000 998 2792 998 1004 2793 1004 1000 2794 1000 1001 2795 1001 1004 2796 1004 1002 2797 1002 1000 2798 1000 1004 2799 1004 1003 2800 1003 1002 2801 1002 1006 2802 1006 1003 2803 1003 1004 2804 1004 1006 2805 1006 1005 2806 1005 1003 2807 1003 1007 2808 1007 1005 2809 1005 1006 2810 1006 1009 2811 1009 1005 2812 1005 1007 2813 1007 1009 2814 1009 1008 2815 1008 1005 2816 1005 1011 2817 1011 1008 2818 1008 1009 2819 1009 1011 2820 1011 1010 2821 1010 1008 2822 1008 1013 2823 1013 1010 2824 1010 1011 2825 1011 1013 2826 1013 1012 2827 1012 1010 2828 1010 1015 2829 1015 1012 2830 1012 1013 2831 1013 1015 2832 1015 1014 2833 1014 1012 2834 1012 1017 2835 1017 1014 2836 1014 1015 2837 1015 1017 2838 1017 1016 2839 1016 1014 2840 1014 995 2841 995 1016 2842 1016 1017 2843 1017 1050 2844 1050 1022 2845 1022 1018 2846 1018 1023 2847 1023 1019 2848 1019 1020 2849 1020 1023 2850 1023 1021 2851 1021 1019 2852 1019 1023 2853 1023 1022 2854 1022 1021 2855 1021 1018 2856 1018 1022 2857 1022 1023 2858 1023 1027 2859 1027 1024 2860 1024 1025 2861 1025 1027 2862 1027 1026 2863 1026 1024 2864 1024 1029 2865 1029 1026 2866 1026 1027 2867 1027 1029 2868 1029 1028 2869 1028 1026 2870 1026 1031 2871 1031 1028 2872 1028 1029 2873 1029 1031 2874 1031 1030 2875 1030 1028 2876 1028 1033 2877 1033 1030 2878 1030 1031 2879 1031 1033 2880 1033 1032 2881 1032 1030 2882 1030 1036 2883 1036 1032 2884 1032 1033 2885 1033 1036 2886 1036 1034 2887 1034 1032 2888 1032 1036 2889 1036 1035 2890 1035 1034 2891 1034 1037 2892 1037 1035 2893 1035 1036 2894 1036 1039 2895 1039 1035 2896 1035 1037 2897 1037 1039 2898 1039 1038 2899 1038 1035 2900 1035 1041 2901 1041 1038 2902 1038 1039 2903 1039 1041 2904 1041 1040 2905 1040 1038 2906 1038 1043 2907 1043 1040 2908 1040 1041 2909 1041 1043 2910 1043 1042 2911 1042 1040 2912 1040 1045 2913 1045 1042 2914 1042 1043 2915 1043 1045 2916 1045 1044 2917 1044 1042 2918 1042 1047 2919 1047 1044 2920 1044 1045 2921 1045 1047 2922 1047 1046 2923 1046 1044 2924 1044 1049 2925 1049 1046 2926 1046 1047 2927 1047 1049 2928 1049 1048 2929 1048 1046 2930 1046 1051 2931 1051 1048 2932 1048 1049 2933 1049 1051 2934 1051 1050 2935 1050 1048 2936 1048 1022 2937 1022 1050 2938 1050 1051 2939 1051 1084 2940 1084 1052 2941 1052 1053 2942 1053 1056 2943 1056 1054 2944 1054 1055 2945 1055 1057 2946 1057 1054 2947 1054 1056 2948 1056 1059 2949 1059 1054 2950 1054 1057 2951 1057 1059 2952 1059 1058 2953 1058 1054 2954 1054 1061 2955 1061 1058 2956 1058 1059 2957 1059 1061 2958 1061 1060 2959 1060 1058 2960 1058 1063 2961 1063 1060 2962 1060 1061 2963 1061 1063 2964 1063 1062 2965 1062 1060 2966 1060 1065 2967 1065 1062 2968 1062 1063 2969 1063 1065 2970 1065 1064 2971 1064 1062 2972 1062 1067 2973 1067 1064 2974 1064 1065 2975 1065 1067 2976 1067 1066 2977 1066 1064 2978 1064 1069 2979 1069 1066 2980 1066 1067 2981 1067 1069 2982 1069 1068 2983 1068 1066 2984 1066 1071 2985 1071 1068 2986 1068 1069 2987 1069 1071 2988 1071 1070 2989 1070 1068 2990 1068 1073 2991 1073 1070 2992 1070 1071 2993 1071 1073 2994 1073 1072 2995 1072 1070 2996 1070 1075 2997 1075 1072 2998 1072 1073 2999 1073 1075 3000 1075 1074 3001 1074 1072 3002 1072 1077 3003 1077 1074 3004 1074 1075 3005 1075 1077 3006 1077 1076 3007 1076 1074 3008 1074 1079 3009 1079 1076 3010 1076 1077 3011 1077 1079 3012 1079 1078 3013 1078 1076 3014 1076 1081 3015 1081 1078 3016 1078 1079 3017 1079 1081 3018 1081 1080 3019 1080 1078 3020 1078 1083 3021 1083 1080 3022 1080 1081 3023 1081 1083 3024 1083 1082 3025 1082 1080 3026 1080 1085 3027 1085 1082 3028 1082 1083 3029 1083 1085 3030 1085 1084 3031 1084 1082 3032 1082 1052 3033 1052 1084 3034 1084 1085 3035 1085 1118 3036 1118 1087 3037 1087 1086 3038 1086 1089 3039 1089 1087 3040 1087 1088 3041 1088 1086 3042 1086 1087 3043 1087 1089 3044 1089 1093 3045 1093 1090 3046 1090 1091 3047 1091 1093 3048 1093 1092 3049 1092 1090 3050 1090 1095 3051 1095 1092 3052 1092 1093 3053 1093 1095 3054 1095 1094 3055 1094 1092 3056 1092 1097 3057 1097 1094 3058 1094 1095 3059 1095 1097 3060 1097 1096 3061 1096 1094 3062 1094 1099 3063 1099 1096 3064 1096 1097 3065 1097 1099 3066 1099 1098 3067 1098 1096 3068 1096 1102 3069 1102 1098 3070 1098 1099 3071 1099 1102 3072 1102 1100 3073 1100 1098 3074 1098 1102 3075 1102 1101 3076 1101 1100 3077 1100 1103 3078 1103 1101 3079 1101 1102 3080 1102 1106 3081 1106 1101 3082 1101 1103 3083 1103 1106 3084 1106 1104 3085 1104 1101 3086 1101 1106 3087 1106 1105 3088 1105 1104 3089 1104 1107 3090 1107 1105 3091 1105 1106 3092 1106 1109 3093 1109 1105 3094 1105 1107 3095 1107 1109 3096 1109 1108 3097 1108 1105 3098 1105 1111 3099 1111 1108 3100 1108 1109 3101 1109 1111 3102 1111 1110 3103 1110 1108 3104 1108 1113 3105 1113 1110 3106 1110 1111 3107 1111 1113 3108 1113 1112 3109 1112 1110 3110 1110 1115 3111 1115 1112 3112 1112 1113 3113 1113 1115 3114 1115 1114 3115 1114 1112 3116 1112 1117 3117 1117 1114 3118 1114 1115 3119 1115 1117 3120 1117 1116 3121 1116 1114 3122 1114 1119 3123 1119 1116 3124 1116 1117 3125 1117 1119 3126 1119 1118 3127 1118 1116 3128 1116 1087 3129 1087 1118 3130 1118 1119 3131 1119 1152 3132 1152 1120 3133 1120 1121 3134 1121 1124 3135 1124 1122 3136 1122 1123 3137 1123 1125 3138 1125 1122 3139 1122 1124 3140 1124 1127 3141 1127 1122 3142 1122 1125 3143 1125 1127 3144 1127 1126 3145 1126 1122 3146 1122 1129 3147 1129 1126 3148 1126 1127 3149 1127 1129 3150 1129 1128 3151 1128 1126 3152 1126 1131 3153 1131 1128 3154 1128 1129 3155 1129 1131 3156 1131 1130 3157 1130 1128 3158 1128 1134 3159 1134 1130 3160 1130 1131 3161 1131 1134 3162 1134 1132 3163 1132 1130 3164 1130 1134 3165 1134 1133 3166 1133 1132 3167 1132 1135 3168 1135 1133 3169 1133 1134 3170 1134 1137 3171 1137 1133 3172 1133 1135 3173 1135 1137 3174 1137 1136 3175 1136 1133 3176 1133 1139 3177 1139 1136 3178 1136 1137 3179 1137 1139 3180 1139 1138 3181 1138 1136 3182 1136 1141 3183 1141 1138 3184 1138 1139 3185 1139 1141 3186 1141 1140 3187 1140 1138 3188 1138 1143 3189 1143 1140 3190 1140 1141 3191 1141 1143 3192 1143 1142 3193 1142 1140 3194 1140 1145 3195 1145 1142 3196 1142 1143 3197 1143 1145 3198 1145 1144 3199 1144 1142 3200 1142 1147 3201 1147 1144 3202 1144 1145 3203 1145 1147 3204 1147 1146 3205 1146 1144 3206 1144 1149 3207 1149 1146 3208 1146 1147 3209 1147 1149 3210 1149 1148 3211 1148 1146 3212 1146 1151 3213 1151 1148 3214 1148 1149 3215 1149 1151 3216 1151 1150 3217 1150 1148 3218 1148 1153 3219 1153 1150 3220 1150 1151 3221 1151 1153 3222 1153 1152 3223 1152 1150 3224 1150 1120 3225 1120 1152 3226 1152 1153 3227 1153 1186 3228 1186 1155 3229 1155 1154 3230 1154 1157 3231 1157 1155 3232 1155 1156 3233 1156 1154 3234 1154 1155 3235 1155 1157 3236 1157 1161 3237 1161 1158 3238 1158 1159 3239 1159 1161 3240 1161 1160 3241 1160 1158 3242 1158 1163 3243 1163 1160 3244 1160 1161 3245 1161 1163 3246 1163 1162 3247 1162 1160 3248 1160 1165 3249 1165 1162 3250 1162 1163 3251 1163 1165 3252 1165 1164 3253 1164 1162 3254 1162 1167 3255 1167 1164 3256 1164 1165 3257 1165 1167 3258 1167 1166 3259 1166 1164 3260 1164 1170 3261 1170 1166 3262 1166 1167 3263 1167 1170 3264 1170 1168 3265 1168 1166 3266 1166 1170 3267 1170 1169 3268 1169 1168 3269 1168 1172 3270 1172 1169 3271 1169 1170 3272 1170 1172 3273 1172 1171 3274 1171 1169 3275 1169 1173 3276 1173 1171 3277 1171 1172 3278 1172 1175 3279 1175 1171 3280 1171 1173 3281 1173 1175 3282 1175 1174 3283 1174 1171 3284 1171 1178 3285 1178 1174 3286 1174 1175 3287 1175 1178 3288 1178 1176 3289 1176 1174 3290 1174 1178 3291 1178 1177 3292 1177 1176 3293 1176 1179 3294 1179 1177 3295 1177 1178 3296 1178 1181 3297 1181 1177 3298 1177 1179 3299 1179 1181 3300 1181 1180 3301 1180 1177 3302 1177 1183 3303 1183 1180 3304 1180 1181 3305 1181 1183 3306 1183 1182 3307 1182 1180 3308 1180 1185 3309 1185 1182 3310 1182 1183 3311 1183 1185 3312 1185 1184 3313 1184 1182 3314 1182 1187 3315 1187 1184 3316 1184 1185 3317 1185 1187 3318 1187 1186 3319 1186 1184 3320 1184 1155 3321 1155 1186 3322 1186 1187 3323 1187 1220 3324 1220 1188 3325 1188 1189 3326 1189 1192 3327 1192 1190 3328 1190 1191 3329 1191 1193 3330 1193 1190 3331 1190 1192 3332 1192 1195 3333 1195 1190 3334 1190 1193 3335 1193 1195 3336 1195 1194 3337 1194 1190 3338 1190 1198 3339 1198 1194 3340 1194 1195 3341 1195 1198 3342 1198 1196 3343 1196 1194 3344 1194 1198 3345 1198 1197 3346 1197 1196 3347 1196 1199 3348 1199 1197 3349 1197 1198 3350 1198 1201 3351 1201 1197 3352 1197 1199 3353 1199 1201 3354 1201 1200 3355 1200 1197 3356 1197 1204 3357 1204 1200 3358 1200 1201 3359 1201 1204 3360 1204 1202 3361 1202 1200 3362 1200 1204 3363 1204 1203 3364 1203 1202 3365 1202 1206 3366 1206 1203 3367 1203 1204 3368 1204 1206 3369 1206 1205 3370 1205 1203 3371 1203 1207 3372 1207 1205 3373 1205 1206 3374 1206 1209 3375 1209 1205 3376 1205 1207 3377 1207 1209 3378 1209 1208 3379 1208 1205 3380 1205 1211 3381 1211 1208 3382 1208 1209 3383 1209 1211 3384 1211 1210 3385 1210 1208 3386 1208 1214 3387 1214 1210 3388 1210 1211 3389 1211 1214 3390 1214 1212 3391 1212 1210 3392 1210 1214 3393 1214 1213 3394 1213 1212 3395 1212 1215 3396 1215 1213 3397 1213 1214 3398 1214 1217 3399 1217 1213 3400 1213 1215 3401 1215 1217 3402 1217 1216 3403 1216 1213 3404 1213 1219 3405 1219 1216 3406 1216 1217 3407 1217 1219 3408 1219 1218 3409 1218 1216 3410 1216 1221 3411 1221 1218 3412 1218 1219 3413 1219 1221 3414 1221 1220 3415 1220 1218 3416 1218 1188 3417 1188 1220 3418 1220 1221 3419 1221 1254 3420 1254 1223 3421 1223 1222 3422 1222 1225 3423 1225 1223 3424 1223 1224 3425 1224 1222 3426 1222 1223 3427 1223 1225 3428 1225 1229 3429 1229 1226 3430 1226 1227 3431 1227 1229 3432 1229 1228 3433 1228 1226 3434 1226 1231 3435 1231 1228 3436 1228 1229 3437 1229 1231 3438 1231 1230 3439 1230 1228 3440 1228 1233 3441 1233 1230 3442 1230 1231 3443 1231 1233 3444 1233 1232 3445 1232 1230 3446 1230 1235 3447 1235 1232 3448 1232 1233 3449 1233 1235 3450 1235 1234 3451 1234 1232 3452 1232 1238 3453 1238 1234 3454 1234 1235 3455 1235 1238 3456 1238 1236 3457 1236 1234 3458 1234 1238 3459 1238 1237 3460 1237 1236 3461 1236 1239 3462 1239 1237 3463 1237 1238 3464 1238 1241 3465 1241 1237 3466 1237 1239 3467 1239 1241 3468 1241 1240 3469 1240 1237 3470 1237 1243 3471 1243 1240 3472 1240 1241 3473 1241 1243 3474 1243 1242 3475 1242 1240 3476 1240 1245 3477 1245 1242 3478 1242 1243 3479 1243 1245 3480 1245 1244 3481 1244 1242 3482 1242 1248 3483 1248 1244 3484 1244 1245 3485 1245 1248 3486 1248 1246 3487 1246 1244 3488 1244 1248 3489 1248 1247 3490 1247 1246 3491 1246 1249 3492 1249 1247 3493 1247 1248 3494 1248 1251 3495 1251 1247 3496 1247 1249 3497 1249 1251 3498 1251 1250 3499 1250 1247 3500 1247 1253 3501 1253 1250 3502 1250 1251 3503 1251 1253 3504 1253 1252 3505 1252 1250 3506 1250 1255 3507 1255 1252 3508 1252 1253 3509 1253 1255 3510 1255 1254 3511 1254 1252 3512 1252 1223 3513 1223 1254 3514 1254 1255 3515 1255 1288 3516 1288 1259 3517 1259 1256 3518 1256 1256 3519 1256 1257 3520 1257 1258 3521 1258 1256 3522 1256 1259 3523 1259 1257 3524 1257 1263 3525 1263 1260 3526 1260 1261 3527 1261 1263 3528 1263 1262 3529 1262 1260 3530 1260 1265 3531 1265 1262 3532 1262 1263 3533 1263 1265 3534 1265 1264 3535 1264 1262 3536 1262 1267 3537 1267 1264 3538 1264 1265 3539 1265 1267 3540 1267 1266 3541 1266 1264 3542 1264 1269 3543 1269 1266 3544 1266 1267 3545 1267 1269 3546 1269 1268 3547 1268 1266 3548 1266 1271 3549 1271 1268 3550 1268 1269 3551 1269 1271 3552 1271 1270 3553 1270 1268 3554 1268 1273 3555 1273 1270 3556 1270 1271 3557 1271 1273 3558 1273 1272 3559 1272 1270 3560 1270 1275 3561 1275 1272 3562 1272 1273 3563 1273 1275 3564 1275 1274 3565 1274 1272 3566 1272 1277 3567 1277 1274 3568 1274 1275 3569 1275 1277 3570 1277 1276 3571 1276 1274 3572 1274 1280 3573 1280 1276 3574 1276 1277 3575 1277 1280 3576 1280 1278 3577 1278 1276 3578 1276 1280 3579 1280 1279 3580 1279 1278 3581 1278 1281 3582 1281 1279 3583 1279 1280 3584 1280 1283 3585 1283 1279 3586 1279 1281 3587 1281 1283 3588 1283 1282 3589 1282 1279 3590 1279 1285 3591 1285 1282 3592 1282 1283 3593 1283 1285 3594 1285 1284 3595 1284 1282 3596 1282 1287 3597 1287 1284 3598 1284 1285 3599 1285 1287 3600 1287 1286 3601 1286 1284 3602 1284 1289 3603 1289 1286 3604 1286 1287 3605 1287 1289 3606 1289 1288 3607 1288 1286 3608 1286 1259 3609 1259 1288 3610 1288 1289 3611 1289 1322 3612 1322 1290 3613 1290 1291 3614 1291 1294 3615 1294 1292 3616 1292 1293 3617 1293 1295 3618 1295 1292 3619 1292 1294 3620 1294 1297 3621 1297 1292 3622 1292 1295 3623 1295 1297 3624 1297 1296 3625 1296 1292 3626 1292 1299 3627 1299 1296 3628 1296 1297 3629 1297 1299 3630 1299 1298 3631 1298 1296 3632 1296 1301 3633 1301 1298 3634 1298 1299 3635 1299 1301 3636 1301 1300 3637 1300 1298 3638 1298 1303 3639 1303 1300 3640 1300 1301 3641 1301 1303 3642 1303 1302 3643 1302 1300 3644 1300 1305 3645 1305 1302 3646 1302 1303 3647 1303 1305 3648 1305 1304 3649 1304 1302 3650 1302 1307 3651 1307 1304 3652 1304 1305 3653 1305 1307 3654 1307 1306 3655 1306 1304 3656 1304 1309 3657 1309 1306 3658 1306 1307 3659 1307 1309 3660 1309 1308 3661 1308 1306 3662 1306 1311 3663 1311 1308 3664 1308 1309 3665 1309 1311 3666 1311 1310 3667 1310 1308 3668 1308 1313 3669 1313 1310 3670 1310 1311 3671 1311 1313 3672 1313 1312 3673 1312 1310 3674 1310 1315 3675 1315 1312 3676 1312 1313 3677 1313 1315 3678 1315 1314 3679 1314 1312 3680 1312 1317 3681 1317 1314 3682 1314 1315 3683 1315 1317 3684 1317 1316 3685 1316 1314 3686 1314 1319 3687 1319 1316 3688 1316 1317 3689 1317 1319 3690 1319 1318 3691 1318 1316 3692 1316 1321 3693 1321 1318 3694 1318 1319 3695 1319 1321 3696 1321 1320 3697 1320 1318 3698 1318 1323 3699 1323 1320 3700 1320 1321 3701 1321 1323 3702 1323 1322 3703 1322 1320 3704 1320 1290 3705 1290 1322 3706 1322 1323 3707 1323 1356 3708 1356 1324 3709 1324 1325 3710 1325 1328 3711 1328 1326 3712 1326 1327 3713 1327 1329 3714 1329 1326 3715 1326 1328 3716 1328 1331 3717 1331 1326 3718 1326 1329 3719 1329 1331 3720 1331 1330 3721 1330 1326 3722 1326 1333 3723 1333 1330 3724 1330 1331 3725 1331 1333 3726 1333 1332 3727 1332 1330 3728 1330 1335 3729 1335 1332 3730 1332 1333 3731 1333 1335 3732 1335 1334 3733 1334 1332 3734 1332 1337 3735 1337 1334 3736 1334 1335 3737 1335 1337 3738 1337 1336 3739 1336 1334 3740 1334 1339 3741 1339 1336 3742 1336 1337 3743 1337 1339 3744 1339 1338 3745 1338 1336 3746 1336 1341 3747 1341 1338 3748 1338 1339 3749 1339 1341 3750 1341 1340 3751 1340 1338 3752 1338 1343 3753 1343 1340 3754 1340 1341 3755 1341 1343 3756 1343 1342 3757 1342 1340 3758 1340 1346 3759 1346 1342 3760 1342 1343 3761 1343 1346 3762 1346 1344 3763 1344 1342 3764 1342 1346 3765 1346 1345 3766 1345 1344 3767 1344 1347 3768 1347 1345 3769 1345 1346 3770 1346 1349 3771 1349 1345 3772 1345 1347 3773 1347 1349 3774 1349 1348 3775 1348 1345 3776 1345 1351 3777 1351 1348 3778 1348 1349 3779 1349 1351 3780 1351 1350 3781 1350 1348 3782 1348 1353 3783 1353 1350 3784 1350 1351 3785 1351 1353 3786 1353 1352 3787 1352 1350 3788 1350 1355 3789 1355 1352 3790 1352 1353 3791 1353 1355 3792 1355 1354 3793 1354 1352 3794 1352 1357 3795 1357 1354 3796 1354 1355 3797 1355 1357 3798 1357 1356 3799 1356 1354 3800 1354 1324 3801 1324 1356 3802 1356 1357 3803 1357 1390 3804 1390 1358 3805 1358 1359 3806 1359 1363 3807 1363 1360 3808 1360 1361 3809 1361 1363 3810 1363 1362 3811 1362 1360 3812 1360 1365 3813 1365 1362 3814 1362 1363 3815 1363 1365 3816 1365 1364 3817 1364 1362 3818 1362 1368 3819 1368 1364 3820 1364 1365 3821 1365 1368 3822 1368 1366 3823 1366 1364 3824 1364 1368 3825 1368 1367 3826 1367 1366 3827 1366 1369 3828 1369 1367 3829 1367 1368 3830 1368 1371 3831 1371 1367 3832 1367 1369 3833 1369 1371 3834 1371 1370 3835 1370 1367 3836 1367 1373 3837 1373 1370 3838 1370 1371 3839 1371 1373 3840 1373 1372 3841 1372 1370 3842 1370 1375 3843 1375 1372 3844 1372 1373 3845 1373 1375 3846 1375 1374 3847 1374 1372 3848 1372 1377 3849 1377 1374 3850 1374 1375 3851 1375 1377 3852 1377 1376 3853 1376 1374 3854 1374 1379 3855 1379 1376 3856 1376 1377 3857 1377 1379 3858 1379 1378 3859 1378 1376 3860 1376 1381 3861 1381 1378 3862 1378 1379 3863 1379 1381 3864 1381 1380 3865 1380 1378 3866 1378 1383 3867 1383 1380 3868 1380 1381 3869 1381 1383 3870 1383 1382 3871 1382 1380 3872 1380 1385 3873 1385 1382 3874 1382 1383 3875 1383 1385 3876 1385 1384 3877 1384 1382 3878 1382 1387 3879 1387 1384 3880 1384 1385 3881 1385 1387 3882 1387 1386 3883 1386 1384 3884 1384 1389 3885 1389 1386 3886 1386 1387 3887 1387 1389 3888 1389 1388 3889 1388 1386 3890 1386 1391 3891 1391 1388 3892 1388 1389 3893 1389 1391 3894 1391 1390 3895 1390 1388 3896 1388 1358 3897 1358 1390 3898 1390 1391 3899 1391 1424 3900 1424 1392 3901 1392 1393 3902 1393 1397 3903 1397 1394 3904 1394 1395 3905 1395 1397 3906 1397 1396 3907 1396 1394 3908 1394 1399 3909 1399 1396 3910 1396 1397 3911 1397 1399 3912 1399 1398 3913 1398 1396 3914 1396 1401 3915 1401 1398 3916 1398 1399 3917 1399 1401 3918 1401 1400 3919 1400 1398 3920 1398 1403 3921 1403 1400 3922 1400 1401 3923 1401 1403 3924 1403 1402 3925 1402 1400 3926 1400 1405 3927 1405 1402 3928 1402 1403 3929 1403 1405 3930 1405 1404 3931 1404 1402 3932 1402 1407 3933 1407 1404 3934 1404 1405 3935 1405 1407 3936 1407 1406 3937 1406 1404 3938 1404 1409 3939 1409 1406 3940 1406 1407 3941 1407 1409 3942 1409 1408 3943 1408 1406 3944 1406 1411 3945 1411 1408 3946 1408 1409 3947 1409 1411 3948 1411 1410 3949 1410 1408 3950 1408 1413 3951 1413 1410 3952 1410 1411 3953 1411 1413 3954 1413 1412 3955 1412 1410 3956 1410 1415 3957 1415 1412 3958 1412 1413 3959 1413 1415 3960 1415 1414 3961 1414 1412 3962 1412 1417 3963 1417 1414 3964 1414 1415 3965 1415 1417 3966 1417 1416 3967 1416 1414 3968 1414 1419 3969 1419 1416 3970 1416 1417 3971 1417 1419 3972 1419 1418 3973 1418 1416 3974 1416 1421 3975 1421 1418 3976 1418 1419 3977 1419 1421 3978 1421 1420 3979 1420 1418 3980 1418 1423 3981 1423 1420 3982 1420 1421 3983 1421 1423 3984 1423 1422 3985 1422 1420 3986 1420 1425 3987 1425 1422 3988 1422 1423 3989 1423 1425 3990 1425 1424 3991 1424 1422 3992 1422 1392 3993 1392 1424 3994 1424 1425 3995 1425 1458 3996 1458 1426 3997 1426 1427 3998 1427 1431 3999 1431 1428 4000 1428 1429 4001 1429 1431 4002 1431 1430 4003 1430 1428 4004 1428 1433 4005 1433 1430 4006 1430 1431 4007 1431 1433 4008 1433 1432 4009 1432 1430 4010 1430 1435 4011 1435 1432 4012 1432 1433 4013 1433 1435 4014 1435 1434 4015 1434 1432 4016 1432 1437 4017 1437 1434 4018 1434 1435 4019 1435 1437 4020 1437 1436 4021 1436 1434 4022 1434 1439 4023 1439 1436 4024 1436 1437 4025 1437 1439 4026 1439 1438 4027 1438 1436 4028 1436 1441 4029 1441 1438 4030 1438 1439 4031 1439 1441 4032 1441 1440 4033 1440 1438 4034 1438 1443 4035 1443 1440 4036 1440 1441 4037 1441 1443 4038 1443 1442 4039 1442 1440 4040 1440 1445 4041 1445 1442 4042 1442 1443 4043 1443 1445 4044 1445 1444 4045 1444 1442 4046 1442 1447 4047 1447 1444 4048 1444 1445 4049 1445 1447 4050 1447 1446 4051 1446 1444 4052 1444 1449 4053 1449 1446 4054 1446 1447 4055 1447 1449 4056 1449 1448 4057 1448 1446 4058 1446 1451 4059 1451 1448 4060 1448 1449 4061 1449 1451 4062 1451 1450 4063 1450 1448 4064 1448 1453 4065 1453 1450 4066 1450 1451 4067 1451 1453 4068 1453 1452 4069 1452 1450 4070 1450 1455 4071 1455 1452 4072 1452 1453 4073 1453 1455 4074 1455 1454 4075 1454 1452 4076 1452 1457 4077 1457 1454 4078 1454 1455 4079 1455 1457 4080 1457 1456 4081 1456 1454 4082 1454 1459 4083 1459 1456 4084 1456 1457 4085 1457 1459 4086 1459 1458 4087 1458 1456 4088 1456 1426 4089 1426 1458 4090 1458 1459 4091 1459 1492 4092 1492 1460 4093 1460 1461 4094 1461 1465 4095 1465 1462 4096 1462 1463 4097 1463 1465 4098 1465 1464 4099 1464 1462 4100 1462 1467 4101 1467 1464 4102 1464 1465 4103 1465 1467 4104 1467 1466 4105 1466 1464 4106 1464 1469 4107 1469 1466 4108 1466 1467 4109 1467 1469 4110 1469 1468 4111 1468 1466 4112 1466 1471 4113 1471 1468 4114 1468 1469 4115 1469 1471 4116 1471 1470 4117 1470 1468 4118 1468 1473 4119 1473 1470 4120 1470 1471 4121 1471 1473 4122 1473 1472 4123 1472 1470 4124 1470 1475 4125 1475 1472 4126 1472 1473 4127 1473 1475 4128 1475 1474 4129 1474 1472 4130 1472 1477 4131 1477 1474 4132 1474 1475 4133 1475 1477 4134 1477 1476 4135 1476 1474 4136 1474 1479 4137 1479 1476 4138 1476 1477 4139 1477 1479 4140 1479 1478 4141 1478 1476 4142 1476 1481 4143 1481 1478 4144 1478 1479 4145 1479 1481 4146 1481 1480 4147 1480 1478 4148 1478 1483 4149 1483 1480 4150 1480 1481 4151 1481 1483 4152 1483 1482 4153 1482 1480 4154 1480 1485 4155 1485 1482 4156 1482 1483 4157 1483 1485 4158 1485 1484 4159 1484 1482 4160 1482 1487 4161 1487 1484 4162 1484 1485 4163 1485 1487 4164 1487 1486 4165 1486 1484 4166 1484 1489 4167 1489 1486 4168 1486 1487 4169 1487 1489 4170 1489 1488 4171 1488 1486 4172 1486 1491 4173 1491 1488 4174 1488 1489 4175 1489 1491 4176 1491 1490 4177 1490 1488 4178 1488 1493 4179 1493 1490 4180 1490 1491 4181 1491 1493 4182 1493 1492 4183 1492 1490 4184 1490 1460 4185 1460 1492 4186 1492 1493 4187 1493 1526 4188 1526 1494 4189 1494 1495 4190 1495 1499 4191 1499 1496 4192 1496 1497 4193 1497 1499 4194 1499 1498 4195 1498 1496 4196 1496 1501 4197 1501 1498 4198 1498 1499 4199 1499 1501 4200 1501 1500 4201 1500 1498 4202 1498 1503 4203 1503 1500 4204 1500 1501 4205 1501 1503 4206 1503 1502 4207 1502 1500 4208 1500 1505 4209 1505 1502 4210 1502 1503 4211 1503 1505 4212 1505 1504 4213 1504 1502 4214 1502 1507 4215 1507 1504 4216 1504 1505 4217 1505 1507 4218 1507 1506 4219 1506 1504 4220 1504 1509 4221 1509 1506 4222 1506 1507 4223 1507 1509 4224 1509 1508 4225 1508 1506 4226 1506 1511 4227 1511 1508 4228 1508 1509 4229 1509 1511 4230 1511 1510 4231 1510 1508 4232 1508 1513 4233 1513 1510 4234 1510 1511 4235 1511 1513 4236 1513 1512 4237 1512 1510 4238 1510 1515 4239 1515 1512 4240 1512 1513 4241 1513 1515 4242 1515 1514 4243 1514 1512 4244 1512 1517 4245 1517 1514 4246 1514 1515 4247 1515 1517 4248 1517 1516 4249 1516 1514 4250 1514 1519 4251 1519 1516 4252 1516 1517 4253 1517 1519 4254 1519 1518 4255 1518 1516 4256 1516 1521 4257 1521 1518 4258 1518 1519 4259 1519 1521 4260 1521 1520 4261 1520 1518 4262 1518 1523 4263 1523 1520 4264 1520 1521 4265 1521 1523 4266 1523 1522 4267 1522 1520 4268 1520 1525 4269 1525 1522 4270 1522 1523 4271 1523 1525 4272 1525 1524 4273 1524 1522 4274 1522 1527 4275 1527 1524 4276 1524 1525 4277 1525 1527 4278 1527 1526 4279 1526 1524 4280 1524 1494 4281 1494 1526 4282 1526 1527 4283 1527 1559 4284 1559 1528 4285 1528 1529 4286 1529 1560 4287 1560 1534 4288 1534 1561 4289 1561 1560 4290 1560 1530 4291 1530 1534 4292 1534 1560 4293 1560 1531 4294 1531 1530 4295 1530 1562 4296 1562 1531 4297 1531 1560 4298 1560 1562 4299 1562 1532 4300 1532 1531 4301 1531 1563 4302 1563 1532 4303 1532 1562 4304 1562 1563 4305 1563 1533 4306 1533 1532 4307 1532 1535 4308 1535 1561 4309 1561 1534 4310 1534 1535 4311 1535 1564 4312 1564 1561 4313 1561 1536 4314 1536 1564 4315 1564 1535 4316 1535 1536 4317 1536 1565 4318 1565 1564 4319 1564 1537 4320 1537 1565 4321 1565 1536 4322 1536 1537 4323 1537 1566 4324 1566 1565 4325 1565 1528 4326 1528 1566 4327 1566 1537 4328 1537 1533 4329 1533 1538 4330 1538 1539 4331 1539 1563 4332 1563 1538 4333 1538 1533 4334 1533 1567 4335 1567 1538 4336 1538 1563 4337 1563 1567 4338 1567 1540 4339 1540 1538 4340 1538 1568 4341 1568 1540 4342 1540 1567 4343 1567 1568 4344 1568 1541 4345 1541 1540 4346 1540 1569 4347 1569 1541 4348 1541 1568 4349 1568 1569 4350 1569 1542 4351 1542 1541 4352 1541 1570 4353 1570 1542 4354 1542 1569 4355 1569 1570 4356 1570 1543 4357 1543 1542 4358 1542 1570 4359 1570 1544 4360 1544 1543 4361 1543 1570 4362 1570 1545 4363 1545 1544 4364 1544 1570 4365 1570 1546 4366 1546 1545 4367 1545 1571 4368 1571 1546 4369 1546 1570 4370 1570 1571 4371 1571 1547 4372 1547 1546 4373 1546 1572 4374 1572 1547 4375 1547 1571 4376 1571 1572 4377 1572 1548 4378 1548 1547 4379 1547 1573 4380 1573 1548 4381 1548 1572 4382 1572 1573 4383 1573 1549 4384 1549 1548 4385 1548 1574 4386 1574 1549 4387 1549 1573 4388 1573 1574 4389 1574 1550 4390 1550 1549 4391 1549 1574 4392 1574 1551 4393 1551 1550 4394 1550 1575 4395 1575 1551 4396 1551 1574 4397 1574 1575 4398 1575 1552 4399 1552 1551 4400 1551 1576 4401 1576 1552 4402 1552 1575 4403 1575 1576 4404 1576 1553 4405 1553 1552 4406 1552 1553 4407 1553 1554 4408 1554 1555 4409 1555 1576 4410 1576 1554 4411 1554 1553 4412 1553 1577 4413 1577 1554 4414 1554 1576 4415 1576 1577 4416 1577 1556 4417 1556 1554 4418 1554 1578 4419 1578 1556 4420 1556 1577 4421 1577 1578 4422 1578 1557 4423 1557 1556 4424 1556 1579 4425 1579 1557 4426 1557 1578 4427 1578 1579 4428 1579 1558 4429 1558 1557 4430 1557 1566 4431 1566 1558 4432 1558 1579 4433 1579 1566 4434 1566 1559 4435 1559 1558 4436 1558 1528 4437 1528 1559 4438 1559 1566 4439 1566 1576 4440 1576 1580 4441 1580 1577 4442 1577 1580 4443 1580 1576 4444 1576 1575 4445 1575 1577 4446 1577 1581 4447 1581 1578 4448 1578 1581 4449 1581 1577 4450 1577 1580 4451 1580 1578 4452 1578 1582 4453 1582 1579 4454 1579 1582 4455 1582 1578 4456 1578 1581 4457 1581 1579 4458 1579 1565 4459 1565 1566 4460 1566 1565 4461 1565 1579 4462 1579 1582 4463 1582 1575 4464 1575 1583 4465 1583 1580 4466 1580 1583 4467 1583 1575 4468 1575 1574 4469 1574 1580 4470 1580 1584 4471 1584 1581 4472 1581 1584 4473 1584 1580 4474 1580 1583 4475 1583 1574 4476 1574 1585 4477 1585 1583 4478 1583 1585 4479 1585 1574 4480 1574 1573 4481 1573 1583 4482 1583 1586 4483 1586 1584 4484 1584 1586 4485 1586 1583 4486 1583 1585 4487 1585 1581 4488 1581 1587 4489 1587 1582 4490 1582 1587 4491 1587 1581 4492 1581 1584 4493 1584 1582 4494 1582 1564 4495 1564 1565 4496 1565 1564 4497 1564 1582 4498 1582 1587 4499 1587 1584 4500 1584 1588 4501 1588 1587 4502 1587 1588 4503 1588 1584 4504 1584 1586 4505 1586 1587 4506 1587 1561 4507 1561 1564 4508 1564 1561 4509 1561 1587 4510 1587 1588 4511 1588 1573 4512 1573 1589 4513 1589 1585 4514 1585 1589 4515 1589 1573 4516 1573 1572 4517 1572 1585 4518 1585 1590 4519 1590 1586 4520 1586 1590 4521 1590 1585 4522 1585 1589 4523 1589 1572 4524 1572 1591 4525 1591 1589 4526 1589 1591 4527 1591 1572 4528 1572 1571 4529 1571 1589 4530 1589 1592 4531 1592 1590 4532 1590 1592 4533 1592 1589 4534 1589 1591 4535 1591 1586 4536 1586 1593 4537 1593 1588 4538 1588 1593 4539 1593 1586 4540 1586 1590 4541 1590 1588 4542 1588 1560 4543 1560 1561 4544 1561 1560 4545 1560 1588 4546 1588 1593 4547 1593 1590 4548 1590 1594 4549 1594 1593 4550 1593 1594 4551 1594 1590 4552 1590 1592 4553 1592 1593 4554 1593 1562 4555 1562 1560 4556 1560 1562 4557 1562 1593 4558 1593 1594 4559 1594 1571 4560 1571 1569 4561 1569 1591 4562 1591 1569 4563 1569 1571 4564 1571 1570 4565 1570 1591 4566 1591 1568 4567 1568 1592 4568 1592 1568 4569 1568 1591 4570 1591 1569 4571 1569 1592 4572 1592 1567 4573 1567 1594 4574 1594 1567 4575 1567 1592 4576 1592 1568 4577 1568 1594 4578 1594 1563 4579 1563 1562 4580 1562 1563 4581 1563 1594 4582 1594 1567 4583 1567 1622 4584 1622 1595 4585 1595 1596 4586 1596 1623 4587 1623 1603 4588 1603 1624 4589 1624 1623 4590 1623 1597 4591 1597 1603 4592 1603 1623 4593 1623 1598 4594 1598 1597 4595 1597 1625 4596 1625 1598 4597 1598 1623 4598 1623 1625 4599 1625 1599 4600 1599 1598 4601 1598 1626 4602 1626 1599 4603 1599 1625 4604 1625 1626 4605 1626 1600 4606 1600 1599 4607 1599 1600 4608 1600 1601 4609 1601 1602 4610 1602 1626 4611 1626 1601 4612 1601 1600 4613 1600 1604 4614 1604 1624 4615 1624 1603 4616 1603 1604 4617 1604 1627 4618 1627 1624 4619 1624 1605 4620 1605 1627 4621 1627 1604 4622 1604 1605 4623 1605 1628 4624 1628 1627 4625 1627 1606 4626 1606 1628 4627 1628 1605 4628 1605 1606 4629 1606 1629 4630 1629 1628 4631 1628 1595 4632 1595 1629 4633 1629 1606 4634 1606 1630 4635 1630 1601 4636 1601 1626 4637 1626 1630 4638 1630 1607 4639 1607 1601 4640 1601 1631 4641 1631 1607 4642 1607 1630 4643 1630 1631 4644 1631 1608 4645 1608 1607 4646 1607 1631 4647 1631 1609 4648 1609 1608 4649 1608 1631 4650 1631 1610 4651 1610 1609 4652 1609 1631 4653 1631 1611 4654 1611 1610 4655 1610 1632 4656 1632 1611 4657 1611 1631 4658 1631 1632 4659 1632 1612 4660 1612 1611 4661 1611 1633 4662 1633 1612 4663 1612 1632 4664 1632 1633 4665 1633 1613 4666 1613 1612 4667 1612 1634 4668 1634 1613 4669 1613 1633 4670 1633 1634 4671 1634 1614 4672 1614 1613 4673 1613 1635 4674 1635 1614 4675 1614 1634 4676 1634 1635 4677 1635 1615 4678 1615 1614 4679 1614 1635 4680 1635 1616 4681 1616 1615 4682 1615 1636 4683 1636 1616 4684 1616 1635 4685 1635 1636 4686 1636 1617 4687 1617 1616 4688 1616 1637 4689 1637 1617 4690 1617 1636 4691 1636 1637 4692 1637 1618 4693 1618 1617 4694 1617 1618 4695 1618 1619 4696 1619 1620 4697 1620 1637 4698 1637 1619 4699 1619 1618 4700 1618 1638 4701 1638 1619 4702 1619 1637 4703 1637 1638 4704 1638 1621 4705 1621 1619 4706 1619 1629 4707 1629 1621 4708 1621 1638 4709 1638 1629 4710 1629 1622 4711 1622 1621 4712 1621 1595 4713 1595 1622 4714 1622 1629 4715 1629 1637 4716 1637 1639 4717 1639 1638 4718 1638 1639 4719 1639 1637 4720 1637 1636 4721 1636 1638 4722 1638 1628 4723 1628 1629 4724 1629 1628 4725 1628 1638 4726 1638 1639 4727 1639 1636 4728 1636 1640 4729 1640 1639 4730 1639 1640 4731 1640 1636 4732 1636 1635 4733 1635 1635 4734 1635 1641 4735 1641 1640 4736 1640 1641 4737 1641 1635 4738 1635 1634 4739 1634 1639 4740 1639 1627 4741 1627 1628 4742 1628 1627 4743 1627 1639 4744 1639 1640 4745 1640 1640 4746 1640 1624 4747 1624 1627 4748 1627 1624 4749 1624 1640 4750 1640 1641 4751 1641 1634 4752 1634 1642 4753 1642 1641 4754 1641 1642 4755 1642 1634 4756 1634 1633 4757 1633 1633 4758 1633 1643 4759 1643 1642 4760 1642 1643 4761 1643 1633 4762 1633 1632 4763 1632 1641 4764 1641 1623 4765 1623 1624 4766 1624 1623 4767 1623 1641 4768 1641 1642 4769 1642 1642 4770 1642 1625 4771 1625 1623 4772 1623 1625 4773 1625 1642 4774 1642 1643 4775 1643 1632 4776 1632 1630 4777 1630 1643 4778 1643 1630 4779 1630 1632 4780 1632 1631 4781 1631 1643 4782 1643 1626 4783 1626 1625 4784 1625 1626 4785 1626 1643 4786 1643 1630 4787 1630 1671 4788 1671 1644 4789 1644 1645 4790 1645 1672 4791 1672 1646 4792 1646 1650 4793 1650 1673 4794 1673 1646 4795 1646 1672 4796 1672 1673 4797 1673 1647 4798 1647 1646 4799 1646 1674 4800 1674 1647 4801 1647 1673 4802 1673 1674 4803 1674 1648 4804 1648 1647 4805 1647 1675 4806 1675 1648 4807 1648 1674 4808 1674 1675 4809 1675 1649 4810 1649 1648 4811 1648 1650 4812 1650 1676 4813 1676 1672 4814 1672 1651 4815 1651 1676 4816 1676 1650 4817 1650 1652 4818 1652 1676 4819 1676 1651 4820 1651 1652 4821 1652 1677 4822 1677 1676 4823 1676 1653 4824 1653 1677 4825 1677 1652 4826 1652 1653 4827 1653 1678 4828 1678 1677 4829 1677 1644 4830 1644 1678 4831 1678 1653 4832 1653 1649 4833 1649 1654 4834 1654 1655 4835 1655 1675 4836 1675 1654 4837 1654 1649 4838 1649 1675 4839 1675 1656 4840 1656 1654 4841 1654 1679 4842 1679 1656 4843 1656 1675 4844 1675 1680 4845 1680 1656 4846 1656 1679 4847 1679 1680 4848 1680 1657 4849 1657 1656 4850 1656 1680 4851 1680 1658 4852 1658 1657 4853 1657 1680 4854 1680 1659 4855 1659 1658 4856 1658 1680 4857 1680 1660 4858 1660 1659 4859 1659 1681 4860 1681 1660 4861 1660 1680 4862 1680 1681 4863 1681 1661 4864 1661 1660 4865 1660 1682 4866 1682 1661 4867 1661 1681 4868 1681 1682 4869 1682 1662 4870 1662 1661 4871 1661 1683 4872 1683 1662 4873 1662 1682 4874 1682 1683 4875 1683 1663 4876 1663 1662 4877 1662 1684 4878 1684 1663 4879 1663 1683 4880 1683 1684 4881 1684 1664 4882 1664 1663 4883 1663 1684 4884 1684 1665 4885 1665 1664 4886 1664 1685 4887 1685 1665 4888 1665 1684 4889 1684 1685 4890 1685 1666 4891 1666 1665 4892 1665 1686 4893 1686 1666 4894 1666 1685 4895 1685 1686 4896 1686 1667 4897 1667 1666 4898 1666 1667 4899 1667 1668 4900 1668 1669 4901 1669 1686 4902 1686 1668 4903 1668 1667 4904 1667 1687 4905 1687 1668 4906 1668 1686 4907 1686 1687 4908 1687 1670 4909 1670 1668 4910 1668 1687 4911 1687 1671 4912 1671 1670 4913 1670 1678 4914 1678 1671 4915 1671 1687 4916 1687 1644 4917 1644 1671 4918 1671 1678 4919 1678 1680 4920 1680 1688 4921 1688 1681 4922 1681 1688 4923 1688 1680 4924 1680 1679 4925 1679 1681 4926 1681 1689 4927 1689 1682 4928 1682 1689 4929 1689 1681 4930 1681 1688 4931 1688 1682 4932 1682 1690 4933 1690 1683 4934 1683 1690 4935 1690 1682 4936 1682 1689 4937 1689 1679 4938 1679 1674 4939 1674 1688 4940 1688 1674 4941 1674 1679 4942 1679 1675 4943 1675 1688 4944 1688 1673 4945 1673 1689 4946 1689 1673 4947 1673 1688 4948 1688 1674 4949 1674 1689 4950 1689 1672 4951 1672 1690 4952 1690 1672 4953 1672 1689 4954 1689 1673 4955 1673 1683 4956 1683 1691 4957 1691 1684 4958 1684 1691 4959 1691 1683 4960 1683 1690 4961 1690 1684 4962 1684 1692 4963 1692 1685 4964 1685 1692 4965 1692 1684 4966 1684 1691 4967 1691 1685 4968 1685 1687 4969 1687 1686 4970 1686 1687 4971 1687 1685 4972 1685 1692 4973 1692 1690 4974 1690 1676 4975 1676 1691 4976 1691 1676 4977 1676 1690 4978 1690 1672 4979 1672 1691 4980 1691 1677 4981 1677 1692 4982 1692 1677 4983 1677 1691 4984 1691 1676 4985 1676 1692 4986 1692 1678 4987 1678 1687 4988 1687 1678 4989 1678 1692 4990 1692 1677 4991 1677 1724 4992 1724 1725 4993 1725 1693 4994 1693 1726 4995 1726 1693 4996 1693 1725 4997 1725 1726 4998 1726 1694 4999 1694 1693 5000 1693 1726 5001 1726 1695 5002 1695 1694 5003 1694 1727 5004 1727 1695 5005 1695 1726 5006 1726 1727 5007 1727 1696 5008 1696 1695 5009 1695 1728 5010 1728 1696 5011 1696 1727 5012 1727 1728 5013 1728 1697 5014 1697 1696 5015 1696 1697 5016 1697 1698 5017 1698 1699 5018 1699 1728 5019 1728 1698 5020 1698 1697 5021 1697 1729 5022 1729 1698 5023 1698 1728 5024 1728 1729 5025 1729 1700 5026 1700 1698 5027 1698 1729 5028 1729 1701 5029 1701 1700 5030 1700 1730 5031 1730 1701 5032 1701 1729 5033 1729 1730 5034 1730 1702 5035 1702 1701 5036 1701 1731 5037 1731 1702 5038 1702 1730 5039 1730 1732 5040 1732 1702 5041 1702 1731 5042 1731 1732 5043 1732 1703 5044 1703 1702 5045 1702 1732 5046 1732 1704 5047 1704 1703 5048 1703 1732 5049 1732 1705 5050 1705 1704 5051 1704 1732 5052 1732 1706 5053 1706 1705 5054 1705 1733 5055 1733 1706 5056 1706 1732 5057 1732 1733 5058 1733 1707 5059 1707 1706 5060 1706 1734 5061 1734 1707 5062 1707 1733 5063 1733 1734 5064 1734 1708 5065 1708 1707 5066 1707 1735 5067 1735 1708 5068 1708 1734 5069 1734 1735 5070 1735 1709 5071 1709 1708 5072 1708 1736 5073 1736 1709 5074 1709 1735 5075 1735 1736 5076 1736 1710 5077 1710 1709 5078 1709 1736 5079 1736 1711 5080 1711 1710 5081 1710 1737 5082 1737 1711 5083 1711 1736 5084 1736 1737 5085 1737 1712 5086 1712 1711 5087 1711 1738 5088 1738 1712 5089 1712 1737 5090 1737 1738 5091 1738 1713 5092 1713 1712 5093 1712 1713 5094 1713 1714 5095 1714 1715 5096 1715 1738 5097 1738 1714 5098 1714 1713 5099 1713 1739 5100 1739 1714 5101 1714 1738 5102 1738 1739 5103 1739 1716 5104 1716 1714 5105 1714 1740 5106 1740 1716 5107 1716 1739 5108 1739 1740 5109 1740 1717 5110 1717 1716 5111 1716 1741 5112 1741 1717 5113 1717 1740 5114 1740 1741 5115 1741 1718 5116 1718 1717 5117 1717 1742 5118 1742 1718 5119 1718 1741 5120 1741 1742 5121 1742 1719 5122 1719 1718 5123 1718 1742 5124 1742 1720 5125 1720 1719 5126 1719 1742 5127 1742 1721 5128 1721 1720 5129 1720 1742 5130 1742 1722 5131 1722 1721 5132 1721 1743 5133 1743 1722 5134 1722 1742 5135 1742 1743 5136 1743 1723 5137 1723 1722 5138 1722 1744 5139 1744 1723 5140 1723 1743 5141 1743 1744 5142 1744 1724 5143 1724 1723 5144 1723 1725 5145 1725 1724 5146 1724 1744 5147 1744 1732 5148 1732 1745 5149 1745 1733 5150 1733 1745 5151 1745 1732 5152 1732 1731 5153 1731 1731 5154 1731 1746 5155 1746 1745 5156 1745 1746 5157 1746 1731 5158 1731 1730 5159 1730 1730 5160 1730 1747 5161 1747 1746 5162 1746 1747 5163 1747 1730 5164 1730 1729 5165 1729 1729 5166 1729 1727 5167 1727 1747 5168 1747 1727 5169 1727 1729 5170 1729 1728 5171 1728 1733 5172 1733 1748 5173 1748 1734 5174 1734 1748 5175 1748 1733 5176 1733 1745 5177 1745 1745 5178 1745 1749 5179 1749 1748 5180 1748 1749 5181 1749 1745 5182 1745 1746 5183 1746 1734 5184 1734 1750 5185 1750 1735 5186 1735 1750 5187 1750 1734 5188 1734 1748 5189 1748 1748 5190 1748 1751 5191 1751 1750 5192 1750 1751 5193 1751 1748 5194 1748 1749 5195 1749 1746 5196 1746 1752 5197 1752 1749 5198 1749 1752 5199 1752 1746 5200 1746 1747 5201 1747 1747 5202 1747 1726 5203 1726 1752 5204 1752 1726 5205 1726 1747 5206 1747 1727 5207 1727 1749 5208 1749 1753 5209 1753 1751 5210 1751 1753 5211 1753 1749 5212 1749 1752 5213 1752 1752 5214 1752 1725 5215 1725 1753 5216 1753 1725 5217 1725 1752 5218 1752 1726 5219 1726 1735 5220 1735 1754 5221 1754 1736 5222 1736 1754 5223 1754 1735 5224 1735 1750 5225 1750 1750 5226 1750 1755 5227 1755 1754 5228 1754 1755 5229 1755 1750 5230 1750 1751 5231 1751 1736 5232 1736 1756 5233 1756 1737 5234 1737 1756 5235 1756 1736 5236 1736 1754 5237 1754 1754 5238 1754 1757 5239 1757 1756 5240 1756 1757 5241 1757 1754 5242 1754 1755 5243 1755 1751 5244 1751 1758 5245 1758 1755 5246 1755 1758 5247 1758 1751 5248 1751 1753 5249 1753 1753 5250 1753 1744 5251 1744 1758 5252 1758 1744 5253 1744 1753 5254 1753 1725 5255 1725 1755 5256 1755 1759 5257 1759 1757 5258 1757 1759 5259 1759 1755 5260 1755 1758 5261 1758 1758 5262 1758 1743 5263 1743 1759 5264 1759 1743 5265 1743 1758 5266 1758 1744 5267 1744 1737 5268 1737 1739 5269 1739 1738 5270 1738 1739 5271 1739 1737 5272 1737 1756 5273 1756 1756 5274 1756 1740 5275 1740 1739 5276 1739 1740 5277 1740 1756 5278 1756 1757 5279 1757 1757 5280 1757 1741 5281 1741 1740 5282 1740 1741 5283 1741 1757 5284 1757 1759 5285 1759 1759 5286 1759 1742 5287 1742 1741 5288 1741 1742 5289 1742 1759 5290 1759 1743 5291 1743 1769 5292 1769 1760 5293 1760 1761 5294 1761 1765 5295 1765 1762 5296 1762 1763 5297 1763 1765 5298 1765 1764 5299 1764 1762 5300 1762 1770 5301 1770 1764 5302 1764 1765 5303 1765 1770 5304 1770 1766 5305 1766 1764 5306 1764 1779 5307 1779 1767 5308 1767 1768 5309 1768 1779 5310 1779 1769 5311 1769 1767 5312 1767 1773 5313 1773 1766 5314 1766 1770 5315 1770 1773 5316 1773 1771 5317 1771 1766 5318 1766 1773 5319 1773 1772 5320 1772 1771 5321 1771 1774 5322 1774 1772 5323 1772 1773 5324 1773 1777 5325 1777 1772 5326 1772 1774 5327 1774 1777 5328 1777 1775 5329 1775 1772 5330 1772 1777 5331 1777 1776 5332 1776 1775 5333 1775 1778 5334 1778 1776 5335 1776 1777 5336 1777 1760 5337 1760 1776 5338 1776 1778 5339 1778 1760 5340 1760 1779 5341 1779 1776 5342 1776 1760 5343 1760 1769 5344 1769 1779 5345 1779 1812 5346 1812 1780 5347 1780 1781 5348 1781 1785 5349 1785 1782 5350 1782 1783 5351 1783 1785 5352 1785 1784 5353 1784 1782 5354 1782 1787 5355 1787 1784 5356 1784 1785 5357 1785 1787 5358 1787 1786 5359 1786 1784 5360 1784 1789 5361 1789 1786 5362 1786 1787 5363 1787 1789 5364 1789 1788 5365 1788 1786 5366 1786 1791 5367 1791 1788 5368 1788 1789 5369 1789 1791 5370 1791 1790 5371 1790 1788 5372 1788 1794 5373 1794 1790 5374 1790 1791 5375 1791 1794 5376 1794 1792 5377 1792 1790 5378 1790 1794 5379 1794 1793 5380 1793 1792 5381 1792 1795 5382 1795 1793 5383 1793 1794 5384 1794 1797 5385 1797 1793 5386 1793 1795 5387 1795 1797 5388 1797 1796 5389 1796 1793 5390 1793 1799 5391 1799 1796 5392 1796 1797 5393 1797 1799 5394 1799 1798 5395 1798 1796 5396 1796 1801 5397 1801 1798 5398 1798 1799 5399 1799 1801 5400 1801 1800 5401 1800 1798 5402 1798 1804 5403 1804 1800 5404 1800 1801 5405 1801 1804 5406 1804 1802 5407 1802 1800 5408 1800 1804 5409 1804 1803 5410 1803 1802 5411 1802 1805 5412 1805 1803 5413 1803 1804 5414 1804 1807 5415 1807 1803 5416 1803 1805 5417 1805 1807 5418 1807 1806 5419 1806 1803 5420 1803 1809 5421 1809 1806 5422 1806 1807 5423 1807 1809 5424 1809 1808 5425 1808 1806 5426 1806 1811 5427 1811 1808 5428 1808 1809 5429 1809 1811 5430 1811 1810 5431 1810 1808 5432 1808 1813 5433 1813 1810 5434 1810 1811 5435 1811 1813 5436 1813 1812 5437 1812 1810 5438 1810 1780 5439 1780 1812 5440 1812 1813 5441 1813 1846 5442 1846 1814 5443 1814 1815 5444 1815 1820 5445 1820 1816 5446 1816 1817 5447 1817 1820 5448 1820 1818 5449 1818 1816 5450 1816 1820 5451 1820 1819 5452 1819 1818 5453 1818 1821 5454 1821 1819 5455 1819 1820 5456 1820 1823 5457 1823 1819 5458 1819 1821 5459 1821 1823 5460 1823 1822 5461 1822 1819 5462 1819 1826 5463 1826 1822 5464 1822 1823 5465 1823 1826 5466 1826 1824 5467 1824 1822 5468 1822 1826 5469 1826 1825 5470 1825 1824 5471 1824 1827 5472 1827 1825 5473 1825 1826 5474 1826 1829 5475 1829 1825 5476 1825 1827 5477 1827 1829 5478 1829 1828 5479 1828 1825 5480 1825 1831 5481 1831 1828 5482 1828 1829 5483 1829 1831 5484 1831 1830 5485 1830 1828 5486 1828 1833 5487 1833 1830 5488 1830 1831 5489 1831 1833 5490 1833 1832 5491 1832 1830 5492 1830 1835 5493 1835 1832 5494 1832 1833 5495 1833 1835 5496 1835 1834 5497 1834 1832 5498 1832 1837 5499 1837 1834 5500 1834 1835 5501 1835 1837 5502 1837 1836 5503 1836 1834 5504 1834 1839 5505 1839 1836 5506 1836 1837 5507 1837 1839 5508 1839 1838 5509 1838 1836 5510 1836 1841 5511 1841 1838 5512 1838 1839 5513 1839 1841 5514 1841 1840 5515 1840 1838 5516 1838 1843 5517 1843 1840 5518 1840 1841 5519 1841 1843 5520 1843 1842 5521 1842 1840 5522 1840 1845 5523 1845 1842 5524 1842 1843 5525 1843 1845 5526 1845 1844 5527 1844 1842 5528 1842 1847 5529 1847 1844 5530 1844 1845 5531 1845 1847 5532 1847 1846 5533 1846 1844 5534 1844 1814 5535 1814 1846 5536 1846 1847 5537 1847 1880 5538 1880 1848 5539 1848 1849 5540 1849 1853 5541 1853 1850 5542 1850 1851 5543 1851 1853 5544 1853 1852 5545 1852 1850 5546 1850 1856 5547 1856 1852 5548 1852 1853 5549 1853 1856 5550 1856 1854 5551 1854 1852 5552 1852 1856 5553 1856 1855 5554 1855 1854 5555 1854 1857 5556 1857 1855 5557 1855 1856 5558 1856 1860 5559 1860 1855 5560 1855 1857 5561 1857 1860 5562 1860 1858 5563 1858 1855 5564 1855 1860 5565 1860 1859 5566 1859 1858 5567 1858 1861 5568 1861 1859 5569 1859 1860 5570 1860 1863 5571 1863 1859 5572 1859 1861 5573 1861 1863 5574 1863 1862 5575 1862 1859 5576 1859 1865 5577 1865 1862 5578 1862 1863 5579 1863 1865 5580 1865 1864 5581 1864 1862 5582 1862 1867 5583 1867 1864 5584 1864 1865 5585 1865 1867 5586 1867 1866 5587 1866 1864 5588 1864 1869 5589 1869 1866 5590 1866 1867 5591 1867 1869 5592 1869 1868 5593 1868 1866 5594 1866 1871 5595 1871 1868 5596 1868 1869 5597 1869 1871 5598 1871 1870 5599 1870 1868 5600 1868 1873 5601 1873 1870 5602 1870 1871 5603 1871 1873 5604 1873 1872 5605 1872 1870 5606 1870 1875 5607 1875 1872 5608 1872 1873 5609 1873 1875 5610 1875 1874 5611 1874 1872 5612 1872 1877 5613 1877 1874 5614 1874 1875 5615 1875 1877 5616 1877 1876 5617 1876 1874 5618 1874 1879 5619 1879 1876 5620 1876 1877 5621 1877 1879 5622 1879 1878 5623 1878 1876 5624 1876 1881 5625 1881 1878 5626 1878 1879 5627 1879 1881 5628 1881 1880 5629 1880 1878 5630 1878 1848 5631 1848 1880 5632 1880 1881 5633 1881 1915 5634 1915 1882 5635 1882 1891 5636 1891 1886 5637 1886 1883 5638 1883 1884 5639 1884 1886 5640 1886 1885 5641 1885 1883 5642 1883 1888 5643 1888 1885 5644 1885 1886 5645 1886 1888 5646 1888 1887 5647 1887 1885 5648 1885 1890 5649 1890 1887 5650 1887 1888 5651 1888 1890 5652 1890 1889 5653 1889 1887 5654 1887 1915 5655 1915 1889 5656 1889 1890 5657 1890 1915 5658 1915 1891 5659 1891 1889 5660 1889 1894 5661 1894 1892 5662 1892 1893 5663 1893 1896 5664 1896 1892 5665 1892 1894 5666 1894 1896 5667 1896 1895 5668 1895 1892 5669 1892 1897 5670 1897 1895 5671 1895 1896 5672 1896 1899 5673 1899 1895 5674 1895 1897 5675 1897 1899 5676 1899 1898 5677 1898 1895 5678 1895 1901 5679 1901 1898 5680 1898 1899 5681 1899 1901 5682 1901 1900 5683 1900 1898 5684 1898 1903 5685 1903 1900 5686 1900 1901 5687 1901 1903 5688 1903 1902 5689 1902 1900 5690 1900 1905 5691 1905 1902 5692 1902 1903 5693 1903 1905 5694 1905 1904 5695 1904 1902 5696 1902 1907 5697 1907 1904 5698 1904 1905 5699 1905 1907 5700 1907 1906 5701 1906 1904 5702 1904 1909 5703 1909 1906 5704 1906 1907 5705 1907 1909 5706 1909 1908 5707 1908 1906 5708 1906 1912 5709 1912 1908 5710 1908 1909 5711 1909 1912 5712 1912 1910 5713 1910 1908 5714 1908 1912 5715 1912 1911 5716 1911 1910 5717 1910 1914 5718 1914 1911 5719 1911 1912 5720 1912 1914 5721 1914 1913 5722 1913 1911 5723 1911 1882 5724 1882 1913 5725 1913 1914 5726 1914 1882 5727 1882 1915 5728 1915 1913 5729 1913 1935 5730 1935 1916 5731 1916 1917 5732 1917 1920 5733 1920 1918 5734 1918 1919 5735 1919 1921 5736 1921 1918 5737 1918 1920 5738 1920 1924 5739 1924 1918 5740 1918 1921 5741 1921 1924 5742 1924 1922 5743 1922 1918 5744 1918 1924 5745 1924 1923 5746 1923 1922 5747 1922 1925 5748 1925 1923 5749 1923 1924 5750 1924 1927 5751 1927 1923 5752 1923 1925 5753 1925 1927 5754 1927 1926 5755 1926 1923 5756 1923 1930 5757 1930 1926 5758 1926 1927 5759 1927 1930 5760 1930 1928 5761 1928 1926 5762 1926 1930 5763 1930 1929 5764 1929 1928 5765 1928 1931 5766 1931 1929 5767 1929 1930 5768 1930 1916 5769 1916 1929 5770 1929 1931 5771 1931 1916 5772 1916 1932 5773 1932 1929 5774 1929 1932 5775 1932 1933 5776 1933 1934 5777 1934 1932 5778 1932 1935 5779 1935 1933 5780 1933 1916 5781 1916 1935 5782 1935 1932 5783 1932 1938 5784 1938 1936 5785 1936 1937 5786 1937 1936 5787 1936 1938 5788 1938 1939 5789 1939 1942 5790 1942 1940 5791 1940 1941 5792 1941 1940 5793 1940 1942 5794 1942 1943 5795 1943 1983 5796 1983 1944 5797 1944 1978 5798 1978 1983 5799 1983 1945 5800 1945 1946 5801 1946 1983 5802 1983 1947 5803 1947 1945 5804 1945 1983 5805 1983 1948 5806 1948 1947 5807 1947 1958 5808 1958 1949 5809 1949 1950 5810 1950 1958 5811 1958 1951 5812 1951 1949 5813 1949 1955 5814 1955 1952 5815 1952 1953 5816 1953 1955 5817 1955 1954 5818 1954 1952 5819 1952 1956 5820 1956 1954 5821 1954 1955 5822 1955 1963 5823 1963 1954 5824 1954 1956 5825 1956 1983 5826 1983 1957 5827 1957 1948 5828 1948 1960 5829 1960 1951 5830 1951 1958 5831 1958 1960 5832 1960 1959 5833 1959 1951 5834 1951 1964 5835 1964 1959 5836 1959 1960 5837 1960 1964 5838 1964 1961 5839 1961 1959 5840 1959 1983 5841 1983 1962 5842 1962 1957 5843 1957 1966 5844 1966 1954 5845 1954 1963 5846 1963 1968 5847 1968 1961 5848 1961 1964 5849 1964 1968 5850 1968 1965 5851 1965 1961 5852 1961 1971 5853 1971 1954 5854 1954 1966 5855 1966 1983 5856 1983 1967 5857 1967 1962 5858 1962 1972 5859 1972 1965 5860 1965 1968 5861 1968 1972 5862 1972 1969 5863 1969 1965 5864 1965 1983 5865 1983 1970 5866 1970 1967 5867 1967 1974 5868 1974 1954 5869 1954 1971 5870 1971 1976 5871 1976 1969 5872 1969 1972 5873 1972 1976 5874 1976 1973 5875 1973 1969 5876 1969 1979 5877 1979 1954 5878 1954 1974 5879 1974 1983 5880 1983 1975 5881 1975 1970 5882 1970 1980 5883 1980 1973 5884 1973 1976 5885 1976 1980 5886 1980 1977 5887 1977 1973 5888 1973 1983 5889 1983 1978 5890 1978 1975 5891 1975 1982 5892 1982 1954 5893 1954 1979 5894 1979 1986 5895 1986 1977 5896 1977 1980 5897 1980 1986 5898 1986 1981 5899 1981 1977 5900 1977 1984 5901 1984 1954 5902 1954 1982 5903 1982 1984 5904 1984 1983 5905 1983 1954 5906 1954 1985 5907 1985 1983 5908 1983 1984 5909 1984 1981 5910 1981 1983 5911 1983 1985 5912 1985 1986 5913 1986 1983 5914 1983 1981 5915 1981 1987 5916 1987 1983 5917 1983 1986 5918 1986 1944 5919 1944 1983 5920 1983 1987 5921 1987 2027 5922 2027 1988 5923 1988 2022 5924 2022 2027 5925 2027 1989 5926 1989 1990 5927 1990 2027 5928 2027 1991 5929 1991 1989 5930 1989 2027 5931 2027 1992 5932 1992 1991 5933 1991 2002 5934 2002 1993 5935 1993 1994 5936 1994 2002 5937 2002 1995 5938 1995 1993 5939 1993 1999 5940 1999 1996 5941 1996 1997 5942 1997 1999 5943 1999 1998 5944 1998 1996 5945 1996 2000 5946 2000 1998 5947 1998 1999 5948 1999 2007 5949 2007 1998 5950 1998 2000 5951 2000 2027 5952 2027 2001 5953 2001 1992 5954 1992 2004 5955 2004 1995 5956 1995 2002 5957 2002 2004 5958 2004 2003 5959 2003 1995 5960 1995 2008 5961 2008 2003 5962 2003 2004 5963 2004 2008 5964 2008 2005 5965 2005 2003 5966 2003 2027 5967 2027 2006 5968 2006 2001 5969 2001 2010 5970 2010 1998 5971 1998 2007 5972 2007 2012 5973 2012 2005 5974 2005 2008 5975 2008 2012 5976 2012 2009 5977 2009 2005 5978 2005 2015 5979 2015 1998 5980 1998 2010 5981 2010 2027 5982 2027 2011 5983 2011 2006 5984 2006 2016 5985 2016 2009 5986 2009 2012 5987 2012 2016 5988 2016 2013 5989 2013 2009 5990 2009 2027 5991 2027 2014 5992 2014 2011 5993 2011 2018 5994 2018 1998 5995 1998 2015 5996 2015 2020 5997 2020 2013 5998 2013 2016 5999 2016 2020 6000 2020 2017 6001 2017 2013 6002 2013 2023 6003 2023 1998 6004 1998 2018 6005 2018 2027 6006 2027 2019 6007 2019 2014 6008 2014 2024 6009 2024 2017 6010 2017 2020 6011 2020 2024 6012 2024 2021 6013 2021 2017 6014 2017 2027 6015 2027 2022 6016 2022 2019 6017 2019 2026 6018 2026 1998 6019 1998 2023 6020 2023 2030 6021 2030 2021 6022 2021 2024 6023 2024 2030 6024 2030 2025 6025 2025 2021 6026 2021 2028 6027 2028 1998 6028 1998 2026 6029 2026 2028 6030 2028 2027 6031 2027 1998 6032 1998 2029 6033 2029 2027 6034 2027 2028 6035 2028 2025 6036 2025 2027 6037 2027 2029 6038 2029 2030 6039 2030 2027 6040 2027 2025 6041 2025 2031 6042 2031 2027 6043 2027 2030 6044 2030 1988 6045 1988 2027 6046 2027 2031 6047 2031 2071 6048 2071 2032 6049 2032 2066 6050 2066 2071 6051 2071 2033 6052 2033 2034 6053 2034 2071 6054 2071 2035 6055 2035 2033 6056 2033 2071 6057 2071 2036 6058 2036 2035 6059 2035 2046 6060 2046 2037 6061 2037 2038 6062 2038 2046 6063 2046 2039 6064 2039 2037 6065 2037 2043 6066 2043 2040 6067 2040 2041 6068 2041 2043 6069 2043 2042 6070 2042 2040 6071 2040 2044 6072 2044 2042 6073 2042 2043 6074 2043 2051 6075 2051 2042 6076 2042 2044 6077 2044 2071 6078 2071 2045 6079 2045 2036 6080 2036 2048 6081 2048 2039 6082 2039 2046 6083 2046 2048 6084 2048 2047 6085 2047 2039 6086 2039 2052 6087 2052 2047 6088 2047 2048 6089 2048 2052 6090 2052 2049 6091 2049 2047 6092 2047 2071 6093 2071 2050 6094 2050 2045 6095 2045 2054 6096 2054 2042 6097 2042 2051 6098 2051 2056 6099 2056 2049 6100 2049 2052 6101 2052 2056 6102 2056 2053 6103 2053 2049 6104 2049 2059 6105 2059 2042 6106 2042 2054 6107 2054 2071 6108 2071 2055 6109 2055 2050 6110 2050 2060 6111 2060 2053 6112 2053 2056 6113 2056 2060 6114 2060 2057 6115 2057 2053 6116 2053 2071 6117 2071 2058 6118 2058 2055 6119 2055 2062 6120 2062 2042 6121 2042 2059 6122 2059 2064 6123 2064 2057 6124 2057 2060 6125 2060 2064 6126 2064 2061 6127 2061 2057 6128 2057 2067 6129 2067 2042 6130 2042 2062 6131 2062 2071 6132 2071 2063 6133 2063 2058 6134 2058 2068 6135 2068 2061 6136 2061 2064 6137 2064 2068 6138 2068 2065 6139 2065 2061 6140 2061 2071 6141 2071 2066 6142 2066 2063 6143 2063 2070 6144 2070 2042 6145 2042 2067 6146 2067 2074 6147 2074 2065 6148 2065 2068 6149 2068 2074 6150 2074 2069 6151 2069 2065 6152 2065 2072 6153 2072 2042 6154 2042 2070 6155 2070 2072 6156 2072 2071 6157 2071 2042 6158 2042 2073 6159 2073 2071 6160 2071 2072 6161 2072 2069 6162 2069 2071 6163 2071 2073 6164 2073 2074 6165 2074 2071 6166 2071 2069 6167 2069 2075 6168 2075 2071 6169 2071 2074 6170 2074 2032 6171 2032 2071 6172 2071 2075 6173 2075 2119 6174 2119 2082 6175 2082 2076 6176 2076 2079 6177 2079 2077 6178 2077 2078 6179 2078 2090 6180 2090 2077 6181 2077 2079 6182 2079 2083 6183 2083 2080 6184 2080 2081 6185 2081 2083 6186 2083 2082 6187 2082 2080 6188 2080 2089 6189 2089 2082 6190 2082 2083 6191 2083 2115 6192 2115 2084 6193 2084 2085 6194 2085 2115 6195 2115 2086 6196 2086 2084 6197 2084 2115 6198 2115 2087 6199 2087 2086 6200 2086 2115 6201 2115 2088 6202 2088 2087 6203 2087 2094 6204 2094 2082 6205 2082 2089 6206 2089 2092 6207 2092 2077 6208 2077 2090 6209 2090 2092 6210 2092 2091 6211 2091 2077 6212 2077 2096 6213 2096 2091 6214 2091 2092 6215 2092 2096 6216 2096 2093 6217 2093 2091 6218 2091 2099 6219 2099 2082 6220 2082 2094 6221 2094 2115 6222 2115 2095 6223 2095 2088 6224 2088 2100 6225 2100 2093 6226 2093 2096 6227 2096 2100 6228 2100 2097 6229 2097 2093 6230 2093 2115 6231 2115 2098 6232 2098 2095 6233 2095 2102 6234 2102 2082 6235 2082 2099 6236 2099 2104 6237 2104 2097 6238 2097 2100 6239 2100 2104 6240 2104 2101 6241 2101 2097 6242 2097 2107 6243 2107 2082 6244 2082 2102 6245 2102 2115 6246 2115 2103 6247 2103 2098 6248 2098 2108 6249 2108 2101 6250 2101 2104 6251 2104 2108 6252 2108 2105 6253 2105 2101 6254 2101 2115 6255 2115 2106 6256 2106 2103 6257 2103 2110 6258 2110 2082 6259 2082 2107 6260 2107 2112 6261 2112 2105 6262 2105 2108 6263 2108 2112 6264 2112 2109 6265 2109 2105 6266 2105 2076 6267 2076 2082 6268 2082 2110 6269 2110 2115 6270 2115 2111 6271 2111 2106 6272 2106 2117 6273 2117 2109 6274 2109 2112 6275 2112 2117 6276 2117 2113 6277 2113 2109 6278 2109 2115 6279 2115 2114 6280 2114 2111 6281 2111 2082 6282 2082 2114 6283 2114 2115 6284 2115 2082 6285 2082 2116 6286 2116 2114 6287 2114 2082 6288 2082 2117 6289 2117 2116 6290 2116 2082 6291 2082 2113 6292 2113 2117 6293 2117 2082 6294 2082 2118 6295 2118 2113 6296 2113 2082 6297 2082 2119 6298 2119 2118 6299 2118 2122 6300 2122 2120 6301 2120 2121 6302 2121 2120 6303 2120 2122 6304 2122 2123 6305 2123 2126 6306 2126 2124 6307 2124 2125 6308 2125 2124 6309 2124 2126 6310 2126 2127 6311 2127 2146 6312 2146 2128 6313 2128 2129 6314 2129 2133 6315 2133 2130 6316 2130 2131 6317 2131 2133 6318 2133 2132 6319 2132 2130 6320 2130 2135 6321 2135 2132 6322 2132 2133 6323 2133 2135 6324 2135 2134 6325 2134 2132 6326 2132 2137 6327 2137 2134 6328 2134 2135 6329 2135 2137 6330 2137 2136 6331 2136 2134 6332 2134 2139 6333 2139 2136 6334 2136 2137 6335 2137 2139 6336 2139 2138 6337 2138 2136 6338 2136 2141 6339 2141 2138 6340 2138 2139 6341 2139 2141 6342 2141 2140 6343 2140 2138 6344 2138 2143 6345 2143 2140 6346 2140 2141 6347 2141 2143 6348 2143 2142 6349 2142 2140 6350 2140 2145 6351 2145 2142 6352 2142 2143 6353 2143 2145 6354 2145 2144 6355 2144 2142 6356 2142 2147 6357 2147 2144 6358 2144 2145 6359 2145 2147 6360 2147 2146 6361 2146 2144 6362 2144 2128 6363 2128 2146 6364 2146 2147 6365 2147 2191 6366 2191 2160 6367 2160 2148 6368 2148 2151 6369 2151 2149 6370 2149 2150 6371 2150 2181 6372 2181 2149 6373 2149 2151 6374 2151 2181 6375 2181 2152 6376 2152 2149 6377 2149 2181 6378 2181 2153 6379 2153 2152 6380 2152 2181 6381 2181 2154 6382 2154 2153 6383 2153 2164 6384 2164 2155 6385 2155 2156 6386 2156 2164 6387 2164 2157 6388 2157 2155 6389 2155 2161 6390 2161 2158 6391 2158 2159 6392 2159 2161 6393 2161 2160 6394 2160 2158 6395 2158 2162 6396 2162 2160 6397 2160 2161 6398 2161 2163 6399 2163 2160 6400 2160 2162 6401 2162 2166 6402 2166 2160 6403 2160 2163 6404 2163 2168 6405 2168 2157 6406 2157 2164 6407 2164 2168 6408 2168 2165 6409 2165 2157 6410 2157 2171 6411 2171 2160 6412 2160 2166 6413 2166 2181 6414 2181 2167 6415 2167 2154 6416 2154 2172 6417 2172 2165 6418 2165 2168 6419 2168 2172 6420 2172 2169 6421 2169 2165 6422 2165 2181 6423 2181 2170 6424 2170 2167 6425 2167 2174 6426 2174 2160 6427 2160 2171 6428 2171 2176 6429 2176 2169 6430 2169 2172 6431 2172 2176 6432 2176 2173 6433 2173 2169 6434 2169 2187 6435 2187 2160 6436 2160 2174 6437 2174 2181 6438 2181 2175 6439 2175 2170 6440 2170 2178 6441 2178 2173 6442 2173 2176 6443 2176 2178 6444 2178 2177 6445 2177 2173 6446 2173 2186 6447 2186 2177 6448 2177 2178 6449 2178 2186 6450 2186 2179 6451 2179 2177 6452 2177 2181 6453 2181 2180 6454 2180 2175 6455 2175 2160 6456 2160 2180 6457 2180 2181 6458 2181 2160 6459 2160 2182 6460 2182 2180 6461 2180 2160 6462 2160 2183 6463 2183 2182 6464 2182 2160 6465 2160 2184 6466 2184 2183 6467 2183 2160 6468 2160 2185 6469 2185 2184 6470 2184 2160 6471 2160 2186 6472 2186 2185 6473 2185 2148 6474 2148 2160 6475 2160 2187 6476 2187 2186 6477 2186 2188 6478 2188 2179 6479 2179 2160 6480 2160 2188 6481 2188 2186 6482 2186 2160 6483 2160 2189 6484 2189 2188 6485 2188 2160 6486 2160 2190 6487 2190 2189 6488 2189 2160 6489 2160 2191 6490 2191 2190 6491 2190 2210 6492 2210 2192 6493 2192 2209 6494 2209 2196 6495 2196 2193 6496 2193 2194 6497 2194 2196 6498 2196 2195 6499 2195 2193 6500 2193 2198 6501 2198 2195 6502 2195 2196 6503 2196 2198 6504 2198 2197 6505 2197 2195 6506 2195 2200 6507 2200 2197 6508 2197 2198 6509 2198 2200 6510 2200 2199 6511 2199 2197 6512 2197 2202 6513 2202 2199 6514 2199 2200 6515 2200 2202 6516 2202 2201 6517 2201 2199 6518 2199 2204 6519 2204 2201 6520 2201 2202 6521 2202 2204 6522 2204 2203 6523 2203 2201 6524 2201 2206 6525 2206 2203 6526 2203 2204 6527 2204 2206 6528 2206 2205 6529 2205 2203 6530 2203 2208 6531 2208 2205 6532 2205 2206 6533 2206 2208 6534 2208 2207 6535 2207 2205 6536 2205 2210 6537 2210 2207 6538 2207 2208 6539 2208 2210 6540 2210 2209 6541 2209 2207 6542 2207 2192 6543 2192 2210 6544 2210 2211 6545 2211 2230 6546 2230 2212 6547 2212 2213 6548 2213 2217 6549 2217 2214 6550 2214 2215 6551 2215 2217 6552 2217 2216 6553 2216 2214 6554 2214 2219 6555 2219 2216 6556 2216 2217 6557 2217 2219 6558 2219 2218 6559 2218 2216 6560 2216 2221 6561 2221 2218 6562 2218 2219 6563 2219 2221 6564 2221 2220 6565 2220 2218 6566 2218 2223 6567 2223 2220 6568 2220 2221 6569 2221 2223 6570 2223 2222 6571 2222 2220 6572 2220 2225 6573 2225 2222 6574 2222 2223 6575 2223 2225 6576 2225 2224 6577 2224 2222 6578 2222 2227 6579 2227 2224 6580 2224 2225 6581 2225 2227 6582 2227 2226 6583 2226 2224 6584 2224 2229 6585 2229 2226 6586 2226 2227 6587 2227 2229 6588 2229 2228 6589 2228 2226 6590 2226 2231 6591 2231 2228 6592 2228 2229 6593 2229 2231 6594 2231 2230 6595 2230 2228 6596 2228 2212 6597 2212 2230 6598 2230 2231 6599 2231 2250 6600 2250 2232 6601 2232 2249 6602 2249 2236 6603 2236 2233 6604 2233 2234 6605 2234 2236 6606 2236 2235 6607 2235 2233 6608 2233 2238 6609 2238 2235 6610 2235 2236 6611 2236 2238 6612 2238 2237 6613 2237 2235 6614 2235 2240 6615 2240 2237 6616 2237 2238 6617 2238 2240 6618 2240 2239 6619 2239 2237 6620 2237 2242 6621 2242 2239 6622 2239 2240 6623 2240 2242 6624 2242 2241 6625 2241 2239 6626 2239 2244 6627 2244 2241 6628 2241 2242 6629 2242 2244 6630 2244 2243 6631 2243 2241 6632 2241 2246 6633 2246 2243 6634 2243 2244 6635 2244 2246 6636 2246 2245 6637 2245 2243 6638 2243 2248 6639 2248 2245 6640 2245 2246 6641 2246 2248 6642 2248 2247 6643 2247 2245 6644 2245 2250 6645 2250 2247 6646 2247 2248 6647 2248 2250 6648 2250 2249 6649 2249 2247 6650 2247 2232 6651 2232 2250 6652 2250 2251 6653 2251 2295 6654 2295 2264 6655 2264 2252 6656 2252 2255 6657 2255 2253 6658 2253 2254 6659 2254 2285 6660 2285 2253 6661 2253 2255 6662 2255 2285 6663 2285 2256 6664 2256 2253 6665 2253 2285 6666 2285 2257 6667 2257 2256 6668 2256 2285 6669 2285 2258 6670 2258 2257 6671 2257 2261 6672 2261 2259 6673 2259 2260 6674 2260 2268 6675 2268 2259 6676 2259 2261 6677 2261 2265 6678 2265 2262 6679 2262 2263 6680 2263 2265 6681 2265 2264 6682 2264 2262 6683 2262 2266 6684 2266 2264 6685 2264 2265 6686 2265 2267 6687 2267 2264 6688 2264 2266 6689 2266 2270 6690 2270 2264 6691 2264 2267 6692 2267 2272 6693 2272 2259 6694 2259 2268 6695 2268 2272 6696 2272 2269 6697 2269 2259 6698 2259 2275 6699 2275 2264 6700 2264 2270 6701 2270 2285 6702 2285 2271 6703 2271 2258 6704 2258 2276 6705 2276 2269 6706 2269 2272 6707 2272 2276 6708 2276 2273 6709 2273 2269 6710 2269 2285 6711 2285 2274 6712 2274 2271 6713 2271 2278 6714 2278 2264 6715 2264 2275 6716 2275 2280 6717 2280 2273 6718 2273 2276 6719 2276 2280 6720 2280 2277 6721 2277 2273 6722 2273 2291 6723 2291 2264 6724 2264 2278 6725 2278 2285 6726 2285 2279 6727 2279 2274 6728 2274 2282 6729 2282 2277 6730 2277 2280 6731 2280 2282 6732 2282 2281 6733 2281 2277 6734 2277 2290 6735 2290 2281 6736 2281 2282 6737 2282 2290 6738 2290 2283 6739 2283 2281 6740 2281 2285 6741 2285 2284 6742 2284 2279 6743 2279 2264 6744 2264 2284 6745 2284 2285 6746 2285 2264 6747 2264 2286 6748 2286 2284 6749 2284 2264 6750 2264 2287 6751 2287 2286 6752 2286 2264 6753 2264 2288 6754 2288 2287 6755 2287 2264 6756 2264 2289 6757 2289 2288 6758 2288 2264 6759 2264 2290 6760 2290 2289 6761 2289 2252 6762 2252 2264 6763 2264 2291 6764 2291 2290 6765 2290 2292 6766 2292 2283 6767 2283 2264 6768 2264 2292 6769 2292 2290 6770 2290 2264 6771 2264 2293 6772 2293 2292 6773 2292 2264 6774 2264 2294 6775 2294 2293 6776 2293 2264 6777 2264 2295 6778 2295 2294 6779 2294 2310 6780 2310 2296 6781 2296 2297 6782 2297 2300 6783 2300 2298 6784 2298 2299 6785 2299 2301 6786 2301 2298 6787 2298 2300 6788 2300 2302 6789 2302 2298 6790 2298 2301 6791 2301 2303 6792 2303 2298 6793 2298 2302 6794 2302 2304 6795 2304 2298 6796 2298 2303 6797 2303 2305 6798 2305 2298 6799 2298 2304 6800 2304 2306 6801 2306 2298 6802 2298 2305 6803 2305 2308 6804 2308 2298 6805 2298 2306 6806 2306 2308 6807 2308 2307 6808 2307 2298 6809 2298 2309 6810 2309 2307 6811 2307 2308 6812 2308 2311 6813 2311 2307 6814 2307 2309 6815 2309 2311 6816 2311 2310 6817 2310 2307 6818 2307 2296 6819 2296 2310 6820 2310 2311 6821 2311 2327 6822 2327 2312 6823 2312 2313 6824 2313 2323 6825 2323 2314 6826 2314 2315 6827 2315 2323 6828 2323 2316 6829 2316 2314 6830 2314 2323 6831 2323 2317 6832 2317 2316 6833 2316 2323 6834 2323 2318 6835 2318 2317 6836 2317 2323 6837 2323 2319 6838 2319 2318 6839 2318 2323 6840 2323 2320 6841 2320 2319 6842 2319 2323 6843 2323 2321 6844 2321 2320 6845 2320 2323 6846 2323 2322 6847 2322 2321 6848 2321 2326 6849 2326 2322 6850 2322 2323 6851 2323 2326 6852 2326 2324 6853 2324 2322 6854 2322 2326 6855 2326 2325 6856 2325 2324 6857 2324 2312 6858 2312 2325 6859 2325 2326 6860 2326 2312 6861 2312 2327 6862 2327 2325 6863 2325 2371 6864 2371 2340 6865 2340 2328 6866 2328 2344 6867 2344 2329 6868 2329 2330 6869 2330 2344 6870 2344 2331 6871 2331 2329 6872 2329 2361 6873 2361 2332 6874 2332 2333 6875 2333 2361 6876 2361 2334 6877 2334 2332 6878 2332 2361 6879 2361 2335 6880 2335 2334 6881 2334 2361 6882 2361 2336 6883 2336 2335 6884 2335 2361 6885 2361 2337 6886 2337 2336 6887 2336 2341 6888 2341 2338 6889 2338 2339 6890 2339 2341 6891 2341 2340 6892 2340 2338 6893 2338 2342 6894 2342 2340 6895 2340 2341 6896 2341 2343 6897 2343 2340 6898 2340 2342 6899 2342 2346 6900 2346 2340 6901 2340 2343 6902 2343 2348 6903 2348 2331 6904 2331 2344 6905 2344 2348 6906 2348 2345 6907 2345 2331 6908 2331 2351 6909 2351 2340 6910 2340 2346 6911 2346 2361 6912 2361 2347 6913 2347 2337 6914 2337 2352 6915 2352 2345 6916 2345 2348 6917 2348 2352 6918 2352 2349 6919 2349 2345 6920 2345 2361 6921 2361 2350 6922 2350 2347 6923 2347 2354 6924 2354 2340 6925 2340 2351 6926 2351 2356 6927 2356 2349 6928 2349 2352 6929 2352 2356 6930 2356 2353 6931 2353 2349 6932 2349 2367 6933 2367 2340 6934 2340 2354 6935 2354 2361 6936 2361 2355 6937 2355 2350 6938 2350 2358 6939 2358 2353 6940 2353 2356 6941 2356 2358 6942 2358 2357 6943 2357 2353 6944 2353 2366 6945 2366 2357 6946 2357 2358 6947 2358 2366 6948 2366 2359 6949 2359 2357 6950 2357 2361 6951 2361 2360 6952 2360 2355 6953 2355 2340 6954 2340 2360 6955 2360 2361 6956 2361 2340 6957 2340 2362 6958 2362 2360 6959 2360 2340 6960 2340 2363 6961 2363 2362 6962 2362 2340 6963 2340 2364 6964 2364 2363 6965 2363 2340 6966 2340 2365 6967 2365 2364 6968 2364 2340 6969 2340 2366 6970 2366 2365 6971 2365 2328 6972 2328 2340 6973 2340 2367 6974 2367 2366 6975 2366 2368 6976 2368 2359 6977 2359 2340 6978 2340 2368 6979 2368 2366 6980 2366 2340 6981 2340 2369 6982 2369 2368 6983 2368 2340 6984 2340 2370 6985 2370 2369 6986 2369 2340 6987 2340 2371 6988 2371 2370 6989 2370 2390 6990 2390 2372 6991 2372 2373 6992 2373 2377 6993 2377 2374 6994 2374 2375 6995 2375 2377 6996 2377 2376 6997 2376 2374 6998 2374 2379 6999 2379 2376 7000 2376 2377 7001 2377 2379 7002 2379 2378 7003 2378 2376 7004 2376 2381 7005 2381 2378 7006 2378 2379 7007 2379 2381 7008 2381 2380 7009 2380 2378 7010 2378 2383 7011 2383 2380 7012 2380 2381 7013 2381 2383 7014 2383 2382 7015 2382 2380 7016 2380 2385 7017 2385 2382 7018 2382 2383 7019 2383 2385 7020 2385 2384 7021 2384 2382 7022 2382 2387 7023 2387 2384 7024 2384 2385 7025 2385 2387 7026 2387 2386 7027 2386 2384 7028 2384 2389 7029 2389 2386 7030 2386 2387 7031 2387 2389 7032 2389 2388 7033 2388 2386 7034 2386 2391 7035 2391 2388 7036 2388 2389 7037 2389 2391 7038 2391 2390 7039 2390 2388 7040 2388 2372 7041 2372 2390 7042 2390 2391 7043 2391 2435 7044 2435 2404 7045 2404 2392 7046 2392 2425 7047 2425 2393 7048 2393 2394 7049 2394 2425 7050 2425 2395 7051 2395 2393 7052 2393 2425 7053 2425 2396 7054 2396 2395 7055 2395 2425 7056 2425 2397 7057 2397 2396 7058 2396 2425 7059 2425 2398 7060 2398 2397 7061 2397 2408 7062 2408 2399 7063 2399 2400 7064 2400 2408 7065 2408 2401 7066 2401 2399 7067 2399 2405 7068 2405 2402 7069 2402 2403 7070 2403 2405 7071 2405 2404 7072 2404 2402 7073 2402 2406 7074 2406 2404 7075 2404 2405 7076 2405 2407 7077 2407 2404 7078 2404 2406 7079 2406 2410 7080 2410 2404 7081 2404 2407 7082 2407 2412 7083 2412 2401 7084 2401 2408 7085 2408 2412 7086 2412 2409 7087 2409 2401 7088 2401 2415 7089 2415 2404 7090 2404 2410 7091 2410 2425 7092 2425 2411 7093 2411 2398 7094 2398 2416 7095 2416 2409 7096 2409 2412 7097 2412 2416 7098 2416 2413 7099 2413 2409 7100 2409 2425 7101 2425 2414 7102 2414 2411 7103 2411 2418 7104 2418 2404 7105 2404 2415 7106 2415 2420 7107 2420 2413 7108 2413 2416 7109 2416 2420 7110 2420 2417 7111 2417 2413 7112 2413 2431 7113 2431 2404 7114 2404 2418 7115 2418 2425 7116 2425 2419 7117 2419 2414 7118 2414 2422 7119 2422 2417 7120 2417 2420 7121 2420 2422 7122 2422 2421 7123 2421 2417 7124 2417 2430 7125 2430 2421 7126 2421 2422 7127 2422 2430 7128 2430 2423 7129 2423 2421 7130 2421 2425 7131 2425 2424 7132 2424 2419 7133 2419 2404 7134 2404 2424 7135 2424 2425 7136 2425 2404 7137 2404 2426 7138 2426 2424 7139 2424 2404 7140 2404 2427 7141 2427 2426 7142 2426 2404 7143 2404 2428 7144 2428 2427 7145 2427 2404 7146 2404 2429 7147 2429 2428 7148 2428 2404 7149 2404 2430 7150 2430 2429 7151 2429 2392 7152 2392 2404 7153 2404 2431 7154 2431 2430 7155 2430 2432 7156 2432 2423 7157 2423 2404 7158 2404 2432 7159 2432 2430 7160 2430 2404 7161 2404 2433 7162 2433 2432 7163 2432 2404 7164 2404 2434 7165 2434 2433 7166 2433 2404 7167 2404 2435 7168 2435 2434 7169 2434 2451 7170 2451 2436 7171 2436 2437 7172 2437 2447 7173 2447 2438 7174 2438 2439 7175 2439 2447 7176 2447 2440 7177 2440 2438 7178 2438 2447 7179 2447 2441 7180 2441 2440 7181 2440 2447 7182 2447 2442 7183 2442 2441 7184 2441 2447 7185 2447 2443 7186 2443 2442 7187 2442 2447 7188 2447 2444 7189 2444 2443 7190 2443 2447 7191 2447 2445 7192 2445 2444 7193 2444 2447 7194 2447 2446 7195 2446 2445 7196 2445 2450 7197 2450 2446 7198 2446 2447 7199 2447 2450 7200 2450 2448 7201 2448 2446 7202 2446 2450 7203 2450 2449 7204 2449 2448 7205 2448 2436 7206 2436 2449 7207 2449 2450 7208 2450 2436 7209 2436 2451 7210 2451 2449 7211 2449 2470 7212 2470 2452 7213 2452 2453 7214 2453 2457 7215 2457 2454 7216 2454 2455 7217 2455 2457 7218 2457 2456 7219 2456 2454 7220 2454 2459 7221 2459 2456 7222 2456 2457 7223 2457 2459 7224 2459 2458 7225 2458 2456 7226 2456 2461 7227 2461 2458 7228 2458 2459 7229 2459 2461 7230 2461 2460 7231 2460 2458 7232 2458 2463 7233 2463 2460 7234 2460 2461 7235 2461 2463 7236 2463 2462 7237 2462 2460 7238 2460 2465 7239 2465 2462 7240 2462 2463 7241 2463 2465 7242 2465 2464 7243 2464 2462 7244 2462 2467 7245 2467 2464 7246 2464 2465 7247 2465 2467 7248 2467 2466 7249 2466 2464 7250 2464 2469 7251 2469 2466 7252 2466 2467 7253 2467 2469 7254 2469 2468 7255 2468 2466 7256 2466 2471 7257 2471 2468 7258 2468 2469 7259 2469 2471 7260 2471 2470 7261 2470 2468 7262 2468 2452 7263 2452 2470 7264 2470 2471 7265 2471 2490 7266 2490 2472 7267 2472 2479 7268 2479 2475 7269 2475 2473 7270 2473 2474 7271 2474 2476 7272 2476 2473 7273 2473 2475 7274 2475 2477 7275 2477 2473 7276 2473 2476 7277 2476 2480 7278 2480 2473 7279 2473 2477 7280 2477 2480 7281 2480 2478 7282 2478 2473 7283 2473 2480 7284 2480 2479 7285 2479 2478 7286 2478 2490 7287 2490 2479 7288 2479 2480 7289 2480 2485 7290 2485 2481 7291 2481 2482 7292 2482 2485 7293 2485 2483 7294 2483 2481 7295 2481 2485 7296 2485 2484 7297 2484 2483 7298 2483 2487 7299 2487 2484 7300 2484 2485 7301 2485 2487 7302 2487 2486 7303 2486 2484 7304 2484 2488 7305 2488 2486 7306 2486 2487 7307 2487 2472 7308 2472 2486 7309 2486 2488 7310 2488 2472 7311 2472 2489 7312 2489 2486 7313 2486 2472 7314 2472 2490 7315 2490 2489 7316 2489 2508 7317 2508 2491 7318 2491 2492 7319 2492 2496 7320 2496 2493 7321 2493 2494 7322 2494 2496 7323 2496 2495 7324 2495 2493 7325 2493 2499 7326 2499 2495 7327 2495 2496 7328 2496 2499 7329 2499 2497 7330 2497 2495 7331 2495 2499 7332 2499 2498 7333 2498 2497 7334 2497 2500 7335 2500 2498 7336 2498 2499 7337 2499 2502 7338 2502 2498 7339 2498 2500 7340 2500 2502 7341 2502 2501 7342 2501 2498 7343 2498 2504 7344 2504 2501 7345 2501 2502 7346 2502 2504 7347 2504 2503 7348 2503 2501 7349 2501 2507 7350 2507 2503 7351 2503 2504 7352 2504 2507 7353 2507 2505 7354 2505 2503 7355 2503 2507 7356 2507 2506 7357 2506 2505 7358 2505 2509 7359 2509 2506 7360 2506 2507 7361 2507 2509 7362 2509 2508 7363 2508 2506 7364 2506 2491 7365 2491 2508 7366 2508 2509 7367 2509 2528 7368 2528 2510 7369 2510 2514 7370 2514 2515 7371 2515 2511 7372 2511 2512 7373 2512 2515 7374 2515 2513 7375 2513 2511 7376 2511 2515 7377 2515 2514 7378 2514 2513 7379 2513 2528 7380 2528 2514 7381 2514 2515 7382 2515 2521 7383 2521 2516 7384 2516 2517 7385 2517 2521 7386 2521 2518 7387 2518 2516 7388 2516 2521 7389 2521 2519 7390 2519 2518 7391 2518 2521 7392 2521 2520 7393 2520 2519 7394 2519 2522 7395 2522 2520 7396 2520 2521 7397 2521 2524 7398 2524 2520 7399 2520 2522 7400 2522 2524 7401 2524 2523 7402 2523 2520 7403 2520 2526 7404 2526 2523 7405 2523 2524 7406 2524 2526 7407 2526 2525 7408 2525 2523 7409 2523 2510 7410 2510 2525 7411 2525 2526 7412 2526 2510 7413 2510 2527 7414 2527 2525 7415 2525 2510 7416 2510 2528 7417 2528 2527 7418 2527 2531 7419 2531 2529 7420 2529 2530 7421 2530 2529 7422 2529 2531 7423 2531 2532 7424 2532 2535 7425 2535 2533 7426 2533 2534 7427 2534 2533 7428 2533 2535 7429 2535 2536 7430 2536 2539 7431 2539 2537 7432 2537 2538 7433 2538 2537 7434 2537 2539 7435 2539 2540 7436 2540 2543 7437 2543 2541 7438 2541 2542 7439 2542 2541 7440 2541 2543 7441 2543 2544 7442 2544 2547 7443 2547 2545 7444 2545 2546 7445 2546 2545 7446 2545 2547 7447 2547 2548 7448 2548 2551 7449 2551 2549 7450 2549 2550 7451 2550 2549 7452 2549 2551 7453 2551 2552 7454 2552 2555 7455 2555 2553 7456 2553 2554 7457 2554 2553 7458 2553 2555 7459 2555 2556 7460 2556 2571 7461 2571 2557 7462 2557 2558 7463 2558 2561 7464 2561 2559 7465 2559 2560 7466 2560 2562 7467 2562 2559 7468 2559 2561 7469 2561 2563 7470 2563 2559 7471 2559 2562 7472 2562 2564 7473 2564 2559 7474 2559 2563 7475 2563 2565 7476 2565 2559 7477 2559 2564 7478 2564 2566 7479 2566 2559 7480 2559 2565 7481 2565 2567 7482 2567 2559 7483 2559 2566 7484 2566 2569 7485 2569 2559 7486 2559 2567 7487 2567 2569 7488 2569 2568 7489 2568 2559 7490 2559 2570 7491 2570 2568 7492 2568 2569 7493 2569 2572 7494 2572 2568 7495 2568 2570 7496 2570 2572 7497 2572 2571 7498 2571 2568 7499 2568 2557 7500 2557 2571 7501 2571 2572 7502 2572 2588 7503 2588 2573 7504 2573 2574 7505 2574 2577 7506 2577 2575 7507 2575 2576 7508 2576 2579 7509 2579 2575 7510 2575 2577 7511 2577 2579 7512 2579 2578 7513 2578 2575 7514 2575 2581 7515 2581 2578 7516 2578 2579 7517 2579 2581 7518 2581 2580 7519 2580 2578 7520 2578 2583 7521 2583 2580 7522 2580 2581 7523 2581 2583 7524 2583 2582 7525 2582 2580 7526 2580 2584 7527 2584 2582 7528 2582 2583 7529 2583 2586 7530 2586 2582 7531 2582 2584 7532 2584 2586 7533 2586 2585 7534 2585 2582 7535 2582 2589 7536 2589 2585 7537 2585 2586 7538 2586 2589 7539 2589 2587 7540 2587 2585 7541 2585 2589 7542 2589 2588 7543 2588 2587 7544 2587 2592 7545 2592 2588 7546 2588 2589 7547 2589 2573 7548 2573 2590 7549 2590 2591 7550 2591 2573 7551 2573 2592 7552 2592 2590 7553 2590 2573 7554 2573 2588 7555 2588 2592 7556 2592 2630 7557 2630 2593 7558 2593 2594 7559 2594 2598 7560 2598 2595 7561 2595 2596 7562 2596 2598 7563 2598 2597 7564 2597 2595 7565 2595 2601 7566 2601 2597 7567 2597 2598 7568 2598 2601 7569 2601 2599 7570 2599 2597 7571 2597 2601 7572 2601 2600 7573 2600 2599 7574 2599 2602 7575 2602 2600 7576 2600 2601 7577 2601 2604 7578 2604 2600 7579 2600 2602 7580 2602 2604 7581 2604 2603 7582 2603 2600 7583 2600 2606 7584 2606 2603 7585 2603 2604 7586 2604 2606 7587 2606 2605 7588 2605 2603 7589 2603 2608 7590 2608 2605 7591 2605 2606 7592 2606 2608 7593 2608 2607 7594 2607 2605 7595 2605 2610 7596 2610 2607 7597 2607 2608 7598 2608 2610 7599 2610 2609 7600 2609 2607 7601 2607 2611 7602 2611 2609 7603 2609 2610 7604 2610 2613 7605 2613 2609 7606 2609 2611 7607 2611 2613 7608 2613 2612 7609 2612 2609 7610 2609 2614 7611 2614 2612 7612 2612 2613 7613 2613 2616 7614 2616 2612 7615 2612 2614 7616 2614 2616 7617 2616 2615 7618 2615 2612 7619 2612 2617 7620 2617 2615 7621 2615 2616 7622 2616 2618 7623 2618 2615 7624 2615 2617 7625 2617 2620 7626 2620 2615 7627 2615 2618 7628 2618 2620 7629 2620 2619 7630 2619 2615 7631 2615 2623 7632 2623 2619 7633 2619 2620 7634 2620 2623 7635 2623 2621 7636 2621 2619 7637 2619 2623 7638 2623 2622 7639 2622 2621 7640 2621 2625 7641 2625 2622 7642 2622 2623 7643 2623 2625 7644 2625 2624 7645 2624 2622 7646 2622 2626 7647 2626 2624 7648 2624 2625 7649 2625 2629 7650 2629 2624 7651 2624 2626 7652 2626 2629 7653 2629 2627 7654 2627 2624 7655 2624 2629 7656 2629 2628 7657 2628 2627 7658 2627 2593 7659 2593 2628 7660 2628 2629 7661 2629 2593 7662 2593 2630 7663 2630 2628 7664 2628 2633 7665 2633 2631 7666 2631 2632 7667 2632 2631 7668 2631 2633 7669 2633 2634 7670 2634 2651 7671 2651 2644 7672 2644 2635 7673 2635 2639 7674 2639 2636 7675 2636 2637 7676 2637 2639 7677 2639 2638 7678 2638 2636 7679 2636 2641 7680 2641 2638 7681 2638 2639 7682 2639 2641 7683 2641 2640 7684 2640 2638 7685 2638 2643 7686 2643 2640 7687 2640 2641 7688 2641 2643 7689 2643 2642 7690 2642 2640 7691 2640 2645 7692 2645 2642 7693 2642 2643 7694 2643 2645 7695 2645 2644 7696 2644 2642 7697 2642 2635 7698 2635 2644 7699 2644 2645 7700 2645 2648 7701 2648 2646 7702 2646 2647 7703 2647 2650 7704 2650 2646 7705 2646 2648 7706 2648 2650 7707 2650 2649 7708 2649 2646 7709 2646 2652 7710 2652 2649 7711 2649 2650 7712 2650 2652 7713 2652 2651 7714 2651 2649 7715 2649 2653 7716 2653 2651 7717 2651 2652 7718 2652 2644 7719 2644 2651 7720 2651 2653 7721 2653 2658 7722 2658 2654 7723 2654 2655 7724 2655 2661 7725 2661 2656 7726 2656 2657 7727 2657 2661 7728 2661 2658 7729 2658 2656 7730 2656 2664 7731 2664 2659 7732 2659 2660 7733 2660 2663 7734 2663 2661 7735 2661 2662 7736 2662 2659 7737 2659 2661 7738 2661 2663 7739 2663 2659 7740 2659 2658 7741 2658 2661 7742 2661 2664 7743 2664 2658 7744 2658 2659 7745 2659 2665 7746 2665 2658 7747 2658 2664 7748 2664 2666 7749 2666 2658 7750 2658 2665 7751 2665 2667 7752 2667 2658 7753 2658 2666 7754 2666 2668 7755 2668 2658 7756 2658 2667 7757 2667 2669 7758 2669 2658 7759 2658 2668 7760 2668 2654 7761 2654 2658 7762 2658 2669 7763 2669 2672 7764 2672 2670 7765 2670 2671 7766 2671 2670 7767 2670 2672 7768 2672 2673 7769 2673 2683 7770 2683 2674 7771 2674 2675 7772 2675 2678 7773 2678 2676 7774 2676 2677 7775 2677 2684 7776 2684 2676 7777 2676 2678 7778 2678 2676 7779 2676 2679 7780 2679 2680 7781 2680 2676 7782 2676 2681 7783 2681 2679 7784 2679 2684 7785 2684 2681 7786 2681 2676 7787 2676 2684 7788 2684 2682 7789 2682 2681 7790 2681 2684 7791 2684 2683 7792 2683 2682 7793 2682 2685 7794 2685 2683 7795 2683 2684 7796 2684 2686 7797 2686 2683 7798 2683 2685 7799 2685 2687 7800 2687 2683 7801 2683 2686 7802 2686 2688 7803 2688 2683 7804 2683 2687 7805 2687 2689 7806 2689 2683 7807 2683 2688 7808 2688 2674 7809 2674 2683 7810 2683 2689 7811 2689 2694 7812 2694 2690 7813 2690 2691 7814 2691 2695 7815 2695 2692 7816 2692 2693 7817 2693 2695 7818 2695 2694 7819 2694 2692 7820 2692 2697 7821 2697 2695 7822 2695 2696 7823 2696 2698 7824 2698 2695 7825 2695 2697 7826 2697 2698 7827 2698 2694 7828 2694 2695 7829 2695 2699 7830 2699 2694 7831 2694 2698 7832 2698 2700 7833 2700 2694 7834 2694 2699 7835 2699 2701 7836 2701 2694 7837 2694 2700 7838 2700 2702 7839 2702 2694 7840 2694 2701 7841 2701 2703 7842 2703 2694 7843 2694 2702 7844 2702 2704 7845 2704 2694 7846 2694 2703 7847 2703 2705 7848 2705 2694 7849 2694 2704 7850 2704 2690 7851 2690 2694 7852 2694 2705 7853 2705 2708 7854 2708 2706 7855 2706 2707 7856 2707 2706 7857 2706 2708 7858 2708 2709 7859 2709 2712 7860 2712 2710 7861 2710 2711 7862 2711 2719 7863 2719 2712 7864 2712 2713 7865 2713 2716 7866 2716 2714 7867 2714 2715 7868 2715 2720 7869 2720 2714 7870 2714 2716 7871 2716 2714 7872 2714 2717 7873 2717 2718 7874 2718 2714 7875 2714 2719 7876 2719 2717 7877 2717 2720 7878 2720 2719 7879 2719 2714 7880 2714 2720 7881 2720 2712 7882 2712 2719 7883 2719 2721 7884 2721 2712 7885 2712 2720 7886 2720 2722 7887 2722 2712 7888 2712 2721 7889 2721 2723 7890 2723 2712 7891 2712 2722 7892 2722 2724 7893 2724 2712 7894 2712 2723 7895 2723 2725 7896 2725 2712 7897 2712 2724 7898 2724 2710 7899 2710 2712 7900 2712 2725 7901 2725 2730 7902 2730 2726 7903 2726 2727 7904 2727 2733 7905 2733 2728 7906 2728 2729 7907 2729 2733 7908 2733 2730 7909 2730 2728 7910 2728 2736 7911 2736 2731 7912 2731 2732 7913 2732 2735 7914 2735 2733 7915 2733 2734 7916 2734 2731 7917 2731 2733 7918 2733 2735 7919 2735 2731 7920 2731 2730 7921 2730 2733 7922 2733 2736 7923 2736 2730 7924 2730 2731 7925 2731 2737 7926 2737 2730 7927 2730 2736 7928 2736 2738 7929 2738 2730 7930 2730 2737 7931 2737 2739 7932 2739 2730 7933 2730 2738 7934 2738 2740 7935 2740 2730 7936 2730 2739 7937 2739 2741 7938 2741 2730 7939 2730 2740 7940 2740 2726 7941 2726 2730 7942 2730 2741 7943 2741 2744 7944 2744 2742 7945 2742 2743 7946 2743 2742 7947 2742 2744 7948 2744 2745 7949 2745 2748 7950 2748 2746 7951 2746 2747 7952 2747 2755 7953 2755 2748 7954 2748 2749 7955 2749 2752 7956 2752 2750 7957 2750 2751 7958 2751 2756 7959 2756 2750 7960 2750 2752 7961 2752 2750 7962 2750 2753 7963 2753 2754 7964 2754 2750 7965 2750 2755 7966 2755 2753 7967 2753 2756 7968 2756 2755 7969 2755 2750 7970 2750 2756 7971 2756 2748 7972 2748 2755 7973 2755 2757 7974 2757 2748 7975 2748 2756 7976 2756 2758 7977 2758 2748 7978 2748 2757 7979 2757 2759 7980 2759 2748 7981 2748 2758 7982 2758 2760 7983 2760 2748 7984 2748 2759 7985 2759 2761 7986 2761 2748 7987 2748 2760 7988 2760 2746 7989 2746 2748 7990 2748 2761 7991 2761 2766 7992 2766 2762 7993 2762 2763 7994 2763 2767 7995 2767 2764 7996 2764 2765 7997 2765 2767 7998 2767 2766 7999 2766 2764 8000 2764 2769 8001 2769 2767 8002 2767 2768 8003 2768 2770 8004 2770 2767 8005 2767 2769 8006 2769 2770 8007 2770 2766 8008 2766 2767 8009 2767 2771 8010 2771 2766 8011 2766 2770 8012 2770 2772 8013 2772 2766 8014 2766 2771 8015 2771 2773 8016 2773 2766 8017 2766 2772 8018 2772 2774 8019 2774 2766 8020 2766 2773 8021 2773 2775 8022 2775 2766 8023 2766 2774 8024 2774 2776 8025 2776 2766 8026 2766 2775 8027 2775 2777 8028 2777 2766 8029 2766 2776 8030 2776 2762 8031 2762 2766 8032 2766 2777 8033 2777 2780 8034 2780 2778 8035 2778 2779 8036 2779 2778 8037 2778 2780 8038 2780 2781 8039 2781 2791 8040 2791 2782 8041 2782 2783 8042 2783 2786 8043 2786 2784 8044 2784 2785 8045 2785 2792 8046 2792 2784 8047 2784 2786 8048 2786 2784 8049 2784 2787 8050 2787 2788 8051 2788 2784 8052 2784 2789 8053 2789 2787 8054 2787 2792 8055 2792 2789 8056 2789 2784 8057 2784 2792 8058 2792 2790 8059 2790 2789 8060 2789 2792 8061 2792 2791 8062 2791 2790 8063 2790 2793 8064 2793 2791 8065 2791 2792 8066 2792 2794 8067 2794 2791 8068 2791 2793 8069 2793 2795 8070 2795 2791 8071 2791 2794 8072 2794 2796 8073 2796 2791 8074 2791 2795 8075 2795 2797 8076 2797 2791 8077 2791 2796 8078 2796 2782 8079 2782 2791 8080 2791 2797 8081 2797 2802 8082 2802 2798 8083 2798 2799 8084 2799 2803 8085 2803 2800 8086 2800 2801 8087 2801 2803 8088 2803 2802 8089 2802 2800 8090 2800 2805 8091 2805 2803 8092 2803 2804 8093 2804 2806 8094 2806 2803 8095 2803 2805 8096 2805 2806 8097 2806 2802 8098 2802 2803 8099 2803 2807 8100 2807 2802 8101 2802 2806 8102 2806 2808 8103 2808 2802 8104 2802 2807 8105 2807 2809 8106 2809 2802 8107 2802 2808 8108 2808 2810 8109 2810 2802 8110 2802 2809 8111 2809 2811 8112 2811 2802 8113 2802 2810 8114 2810 2812 8115 2812 2802 8116 2802 2811 8117 2811 2813 8118 2813 2802 8119 2802 2812 8120 2812 2798 8121 2798 2802 8122 2802 2813 8123 2813 2816 8124 2816 2814 8125 2814 2815 8126 2815 2814 8127 2814 2816 8128 2816 2817 8129 2817 2820 8130 2820 2818 8131 2818 2819 8132 2819 2827 8133 2827 2820 8134 2820 2821 8135 2821 2824 8136 2824 2822 8137 2822 2823 8138 2823 2828 8139 2828 2822 8140 2822 2824 8141 2824 2822 8142 2822 2825 8143 2825 2826 8144 2826 2822 8145 2822 2827 8146 2827 2825 8147 2825 2828 8148 2828 2827 8149 2827 2822 8150 2822 2828 8151 2828 2820 8152 2820 2827 8153 2827 2829 8154 2829 2820 8155 2820 2828 8156 2828 2830 8157 2830 2820 8158 2820 2829 8159 2829 2831 8160 2831 2820 8161 2820 2830 8162 2830 2832 8163 2832 2820 8164 2820 2831 8165 2831 2833 8166 2833 2820 8167 2820 2832 8168 2832 2818 8169 2818 2820 8170 2820 2833 8171 2833 2838 8172 2838 2834 8173 2834 2835 8174 2835 2841 8175 2841 2836 8176 2836 2837 8177 2837 2841 8178 2841 2838 8179 2838 2836 8180 2836 2844 8181 2844 2839 8182 2839 2840 8183 2840 2843 8184 2843 2841 8185 2841 2842 8186 2842 2839 8187 2839 2841 8188 2841 2843 8189 2843 2839 8190 2839 2838 8191 2838 2841 8192 2841 2844 8193 2844 2838 8194 2838 2839 8195 2839 2845 8196 2845 2838 8197 2838 2844 8198 2844 2846 8199 2846 2838 8200 2838 2845 8201 2845 2847 8202 2847 2838 8203 2838 2846 8204 2846 2848 8205 2848 2838 8206 2838 2847 8207 2847 2849 8208 2849 2838 8209 2838 2848 8210 2848 2834 8211 2834 2838 8212 2838 2849 8213 2849 2852 8214 2852 2850 8215 2850 2851 8216 2851 2850 8217 2850 2852 8218 2852 2853 8219 2853 2856 8220 2856 2854 8221 2854 2855 8222 2855 2863 8223 2863 2856 8224 2856 2857 8225 2857 2860 8226 2860 2858 8227 2858 2859 8228 2859 2864 8229 2864 2858 8230 2858 2860 8231 2860 2858 8232 2858 2861 8233 2861 2862 8234 2862 2858 8235 2858 2863 8236 2863 2861 8237 2861 2864 8238 2864 2863 8239 2863 2858 8240 2858 2864 8241 2864 2856 8242 2856 2863 8243 2863 2865 8244 2865 2856 8245 2856 2864 8246 2864 2866 8247 2866 2856 8248 2856 2865 8249 2865 2867 8250 2867 2856 8251 2856 2866 8252 2866 2868 8253 2868 2856 8254 2856 2867 8255 2867 2869 8256 2869 2856 8257 2856 2868 8258 2868 2854 8259 2854 2856 8260 2856 2869 8261 2869 2874 8262 2874 2870 8263 2870 2871 8264 2871 2877 8265 2877 2872 8266 2872 2873 8267 2873 2877 8268 2877 2874 8269 2874 2872 8270 2872 2880 8271 2880 2875 8272 2875 2876 8273 2876 2879 8274 2879 2877 8275 2877 2878 8276 2878 2875 8277 2875 2877 8278 2877 2879 8279 2879 2875 8280 2875 2874 8281 2874 2877 8282 2877 2880 8283 2880 2874 8284 2874 2875 8285 2875 2881 8286 2881 2874 8287 2874 2880 8288 2880 2882 8289 2882 2874 8290 2874 2881 8291 2881 2883 8292 2883 2874 8293 2874 2882 8294 2882 2884 8295 2884 2874 8296 2874 2883 8297 2883 2885 8298 2885 2874 8299 2874 2884 8300 2884 2870 8301 2870 2874 8302 2874 2885 8303 2885 2888 8304 2888 2886 8305 2886 2887 8306 2887 2886 8307 2886 2888 8308 2888 2889 8309 2889 2892 8310 2892 2890 8311 2890 2891 8312 2891 2899 8313 2899 2892 8314 2892 2893 8315 2893 2896 8316 2896 2894 8317 2894 2895 8318 2895 2900 8319 2900 2894 8320 2894 2896 8321 2896 2894 8322 2894 2897 8323 2897 2898 8324 2898 2894 8325 2894 2899 8326 2899 2897 8327 2897 2900 8328 2900 2899 8329 2899 2894 8330 2894 2900 8331 2900 2892 8332 2892 2899 8333 2899 2901 8334 2901 2892 8335 2892 2900 8336 2900 2902 8337 2902 2892 8338 2892 2901 8339 2901 2903 8340 2903 2892 8341 2892 2902 8342 2902 2904 8343 2904 2892 8344 2892 2903 8345 2903 2905 8346 2905 2892 8347 2892 2904 8348 2904 2890 8349 2890 2892 8350 2892 2905 8351 2905 2910 8352 2910 2906 8353 2906 2907 8354 2907 2911 8355 2911 2908 8356 2908 2909 8357 2909 2911 8358 2911 2910 8359 2910 2908 8360 2908 2913 8361 2913 2911 8362 2911 2912 8363 2912 2914 8364 2914 2911 8365 2911 2913 8366 2913 2914 8367 2914 2910 8368 2910 2911 8369 2911 2915 8370 2915 2910 8371 2910 2914 8372 2914 2916 8373 2916 2910 8374 2910 2915 8375 2915 2917 8376 2917 2910 8377 2910 2916 8378 2916 2918 8379 2918 2910 8380 2910 2917 8381 2917 2919 8382 2919 2910 8383 2910 2918 8384 2918 2920 8385 2920 2910 8386 2910 2919 8387 2919 2921 8388 2921 2910 8389 2910 2920 8390 2920 2906 8391 2906 2910 8392 2910 2921 8393 2921 2924 8394 2924 2922 8395 2922 2923 8396 2923 2922 8397 2922 2924 8398 2924 2925 8399 2925 2935 8400 2935 2926 8401 2926 2927 8402 2927 2930 8403 2930 2928 8404 2928 2929 8405 2929 2936 8406 2936 2928 8407 2928 2930 8408 2930 2928 8409 2928 2931 8410 2931 2932 8411 2932 2928 8412 2928 2933 8413 2933 2931 8414 2931 2936 8415 2936 2933 8416 2933 2928 8417 2928 2936 8418 2936 2934 8419 2934 2933 8420 2933 2936 8421 2936 2935 8422 2935 2934 8423 2934 2937 8424 2937 2935 8425 2935 2936 8426 2936 2938 8427 2938 2935 8428 2935 2937 8429 2937 2939 8430 2939 2935 8431 2935 2938 8432 2938 2940 8433 2940 2935 8434 2935 2939 8435 2939 2941 8436 2941 2935 8437 2935 2940 8438 2940 2926 8439 2926 2935 8440 2935 2941 8441 2941 2946 8442 2946 2942 8443 2942 2943 8444 2943 2949 8445 2949 2944 8446 2944 2945 8447 2945 2949 8448 2949 2946 8449 2946 2944 8450 2944 2952 8451 2952 2947 8452 2947 2948 8453 2948 2951 8454 2951 2949 8455 2949 2950 8456 2950 2947 8457 2947 2949 8458 2949 2951 8459 2951 2947 8460 2947 2946 8461 2946 2949 8462 2949 2952 8463 2952 2946 8464 2946 2947 8465 2947 2953 8466 2953 2946 8467 2946 2952 8468 2952 2954 8469 2954 2946 8470 2946 2953 8471 2953 2955 8472 2955 2946 8473 2946 2954 8474 2954 2956 8475 2956 2946 8476 2946 2955 8477 2955 2957 8478 2957 2946 8479 2946 2956 8480 2956 2942 8481 2942 2946 8482 2946 2957 8483 2957 2960 8484 2960 2958 8485 2958 2959 8486 2959 2958 8487 2958 2960 8488 2960 2961 8489 2961 2971 8490 2971 2962 8491 2962 2963 8492 2963 2966 8493 2966 2964 8494 2964 2965 8495 2965 2972 8496 2972 2964 8497 2964 2966 8498 2966 2964 8499 2964 2967 8500 2967 2968 8501 2968 2964 8502 2964 2969 8503 2969 2967 8504 2967 2972 8505 2972 2969 8506 2969 2964 8507 2964 2972 8508 2972 2970 8509 2970 2969 8510 2969 2972 8511 2972 2971 8512 2971 2970 8513 2970 2973 8514 2973 2971 8515 2971 2972 8516 2972 2974 8517 2974 2971 8518 2971 2973 8519 2973 2975 8520 2975 2971 8521 2971 2974 8522 2974 2976 8523 2976 2971 8524 2971 2975 8525 2975 2977 8526 2977 2971 8527 2971 2976 8528 2976 2962 8529 2962 2971 8530 2971 2977 8531 2977 2982 8532 2982 2978 8533 2978 2979 8534 2979 2985 8535 2985 2980 8536 2980 2981 8537 2981 2985 8538 2985 2982 8539 2982 2980 8540 2980 2988 8541 2988 2983 8542 2983 2984 8543 2984 2987 8544 2987 2985 8545 2985 2986 8546 2986 2983 8547 2983 2985 8548 2985 2987 8549 2987 2983 8550 2983 2982 8551 2982 2985 8552 2985 2988 8553 2988 2982 8554 2982 2983 8555 2983 2989 8556 2989 2982 8557 2982 2988 8558 2988 2990 8559 2990 2982 8560 2982 2989 8561 2989 2991 8562 2991 2982 8563 2982 2990 8564 2990 2992 8565 2992 2982 8566 2982 2991 8567 2991 2993 8568 2993 2982 8569 2982 2992 8570 2992 2978 8571 2978 2982 8572 2982 2993 8573 2993 2996 8574 2996 2994 8575 2994 2995 8576 2995 2994 8577 2994 2996 8578 2996 2997 8579 2997 3000 8580 3000 2998 8581 2998 2999 8582 2999 3007 8583 3007 3000 8584 3000 3001 8585 3001 3004 8586 3004 3002 8587 3002 3003 8588 3003 3008 8589 3008 3002 8590 3002 3004 8591 3004 3002 8592 3002 3005 8593 3005 3006 8594 3006 3002 8595 3002 3007 8596 3007 3005 8597 3005 3008 8598 3008 3007 8599 3007 3002 8600 3002 3008 8601 3008 3000 8602 3000 3007 8603 3007 3009 8604 3009 3000 8605 3000 3008 8606 3008 3010 8607 3010 3000 8608 3000 3009 8609 3009 3011 8610 3011 3000 8611 3000 3010 8612 3010 3012 8613 3012 3000 8614 3000 3011 8615 3011 3013 8616 3013 3000 8617 3000 3012 8618 3012 2998 8619 2998 3000 8620 3000 3013 8621 3013 3018 8622 3018 3014 8623 3014 3015 8624 3015 3021 8625 3021 3016 8626 3016 3017 8627 3017 3021 8628 3021 3018 8629 3018 3016 8630 3016 3024 8631 3024 3019 8632 3019 3020 8633 3020 3023 8634 3023 3021 8635 3021 3022 8636 3022 3019 8637 3019 3021 8638 3021 3023 8639 3023 3019 8640 3019 3018 8641 3018 3021 8642 3021 3024 8643 3024 3018 8644 3018 3019 8645 3019 3025 8646 3025 3018 8647 3018 3024 8648 3024 3026 8649 3026 3018 8650 3018 3025 8651 3025 3027 8652 3027 3018 8653 3018 3026 8654 3026 3028 8655 3028 3018 8656 3018 3027 8657 3027 3029 8658 3029 3018 8659 3018 3028 8660 3028 3014 8661 3014 3018 8662 3018 3029 8663 3029 3032 8664 3032 3030 8665 3030 3031 8666 3031 3030 8667 3030 3032 8668 3032 3033 8669 3033 3043 8670 3043 3034 8671 3034 3035 8672 3035 3038 8673 3038 3036 8674 3036 3037 8675 3037 3044 8676 3044 3036 8677 3036 3038 8678 3038 3036 8679 3036 3039 8680 3039 3040 8681 3040 3036 8682 3036 3041 8683 3041 3039 8684 3039 3044 8685 3044 3041 8686 3041 3036 8687 3036 3044 8688 3044 3042 8689 3042 3041 8690 3041 3044 8691 3044 3043 8692 3043 3042 8693 3042 3045 8694 3045 3043 8695 3043 3044 8696 3044 3046 8697 3046 3043 8698 3043 3045 8699 3045 3047 8700 3047 3043 8701 3043 3046 8702 3046 3048 8703 3048 3043 8704 3043 3047 8705 3047 3049 8706 3049 3043 8707 3043 3048 8708 3048 3034 8709 3034 3043 8710 3043 3049 8711 3049 3052 8712 3052 3050 8713 3050 3051 8714 3051 3050 8715 3050 3052 8716 3052 3053 8717 3053 3060 8718 3060 3054 8719 3054 3055 8720 3055 3058 8721 3058 3056 8722 3056 3057 8723 3057 3054 8724 3054 3056 8725 3056 3058 8726 3058 3054 8727 3054 3059 8728 3059 3056 8729 3056 3054 8730 3054 3060 8731 3060 3059 8732 3059 3063 8733 3063 3061 8734 3061 3062 8735 3062 3061 8736 3061 3063 8737 3063 3064 8738 3064 3067 8739 3067 3065 8740 3065 3066 8741 3066 3065 8742 3065 3067 8743 3067 3068 8744 3068 3075 8745 3075 3072 8746 3072 3069 8747 3069 3069 8748 3069 3070 8749 3070 3071 8750 3071 3069 8751 3069 3072 8752 3072 3070 8753 3070 3072 8754 3072 3073 8755 3073 3074 8756 3074 3072 8757 3072 3075 8758 3075 3073 8759 3073 3078 8760 3078 3076 8761 3076 3077 8762 3077 3076 8763 3076 3078 8764 3078 3079 8765 3079 3082 8766 3082 3080 8767 3080 3081 8768 3081 3080 8769 3080 3082 8770 3082 3083 8771 3083 3086 8772 3086 3084 8773 3084 3085 8774 3085 3084 8775 3084 3086 8776 3086 3087 8777 3087 3090 8778 3090 3088 8779 3088 3089 8780 3089 3088 8781 3088 3090 8782 3090 3091 8783 3091 3094 8784 3094 3092 8785 3092 3093 8786 3093 3092 8787 3092 3094 8788 3094 3095 8789 3095 3098 8790 3098 3096 8791 3096 3097 8792 3097 3096 8793 3096 3098 8794 3098 3099 8795 3099 3102 8796 3102 3100 8797 3100 3101 8798 3101 3100 8799 3100 3102 8800 3102 3103 8801 3103 3106 8802 3106 3104 8803 3104 3105 8804 3105 3104 8805 3104 3106 8806 3106 3107 8807 3107 3110 8808 3110 3108 8809 3108 3109 8810 3109 3108 8811 3108 3110 8812 3110 3111 8813 3111 3114 8814 3114 3112 8815 3112 3113 8816 3113 3112 8817 3112 3114 8818 3114 3115 8819 3115 3118 8820 3118 3116 8821 3116 3117 8822 3117 3116 8823 3116 3118 8824 3118 3119 8825 3119 3122 8826 3122 3120 8827 3120 3121 8828 3121 3120 8829 3120 3122 8830 3122 3123 8831 3123 3126 8832 3126 3124 8833 3124 3125 8834 3125 3124 8835 3124 3126 8836 3126 3127 8837 3127 3130 8838 3130 3128 8839 3128 3129 8840 3129 3128 8841 3128 3130 8842 3130 3131 8843 3131 3134 8844 3134 3132 8845 3132 3133 8846 3133 3132 8847 3132 3134 8848 3134 3135 8849 3135 3138 8850 3138 3136 8851 3136 3137 8852 3137 3136 8853 3136 3138 8854 3138 3139 8855 3139 3142 8856 3142 3140 8857 3140 3141 8858 3141 3140 8859 3140 3142 8860 3142 3143 8861 3143 3146 8862 3146 3144 8863 3144 3145 8864 3145 3144 8865 3144 3146 8866 3146 3147 8867 3147 3152 8868 3152 3148 8869 3148 3149 8870 3149 3155 8871 3155 3150 8872 3150 3151 8873 3151 3155 8874 3155 3152 8875 3152 3150 8876 3150 3158 8877 3158 3153 8878 3153 3154 8879 3154 3157 8880 3157 3155 8881 3155 3156 8882 3156 3153 8883 3153 3155 8884 3155 3157 8885 3157 3153 8886 3153 3152 8887 3152 3155 8888 3155 3158 8889 3158 3152 8890 3152 3153 8891 3153 3159 8892 3159 3152 8893 3152 3158 8894 3158 3160 8895 3160 3152 8896 3152 3159 8897 3159 3161 8898 3161 3152 8899 3152 3160 8900 3160 3162 8901 3162 3152 8902 3152 3161 8903 3161 3163 8904 3163 3152 8905 3152 3162 8906 3162 3148 8907 3148 3152 8908 3152 3163 8909 3163 3173 8910 3173 3164 8911 3164 3165 8912 3165 3168 8913 3168 3166 8914 3166 3167 8915 3167 3174 8916 3174 3166 8917 3166 3168 8918 3168 3166 8919 3166 3169 8920 3169 3170 8921 3170 3166 8922 3166 3171 8923 3171 3169 8924 3169 3174 8925 3174 3171 8926 3171 3166 8927 3166 3174 8928 3174 3172 8929 3172 3171 8930 3171 3174 8931 3174 3173 8932 3173 3172 8933 3172 3175 8934 3175 3173 8935 3173 3174 8936 3174 3176 8937 3176 3173 8938 3173 3175 8939 3175 3177 8940 3177 3173 8941 3173 3176 8942 3176 3178 8943 3178 3173 8944 3173 3177 8945 3177 3179 8946 3179 3173 8947 3173 3178 8948 3178 3164 8949 3164 3173 8950 3173 3179 8951 3179 3182 8952 3182 3180 8953 3180 3181 8954 3181 3180 8955 3180 3182 8956 3182 3183 8957 3183 3188 8958 3188 3184 8959 3184 3185 8960 3185 3189 8961 3189 3186 8962 3186 3187 8963 3187 3189 8964 3189 3188 8965 3188 3186 8966 3186 3191 8967 3191 3189 8968 3189 3190 8969 3190 3192 8970 3192 3189 8971 3189 3191 8972 3191 3192 8973 3192 3188 8974 3188 3189 8975 3189 3193 8976 3193 3188 8977 3188 3192 8978 3192 3194 8979 3194 3188 8980 3188 3193 8981 3193 3195 8982 3195 3188 8983 3188 3194 8984 3194 3196 8985 3196 3188 8986 3188 3195 8987 3195 3197 8988 3197 3188 8989 3188 3196 8990 3196 3198 8991 3198 3188 8992 3188 3197 8993 3197 3199 8994 3199 3188 8995 3188 3198 8996 3198 3184 8997 3184 3188 8998 3188 3199 8999 3199 3209 9000 3209 3200 9001 3200 3201 9002 3201 3204 9003 3204 3202 9004 3202 3203 9005 3203 3210 9006 3210 3202 9007 3202 3204 9008 3204 3202 9009 3202 3205 9010 3205 3206 9011 3206 3202 9012 3202 3207 9013 3207 3205 9014 3205 3210 9015 3210 3207 9016 3207 3202 9017 3202 3210 9018 3210 3208 9019 3208 3207 9020 3207 3210 9021 3210 3209 9022 3209 3208 9023 3208 3211 9024 3211 3209 9025 3209 3210 9026 3210 3212 9027 3212 3209 9028 3209 3211 9029 3211 3213 9030 3213 3209 9031 3209 3212 9032 3212 3214 9033 3214 3209 9034 3209 3213 9035 3213 3215 9036 3215 3209 9037 3209 3214 9038 3214 3200 9039 3200 3209 9040 3209 3215 9041 3215 3218 9042 3218 3216 9043 3216 3217 9044 3217 3216 9045 3216 3218 9046 3218 3219 9047 3219 3224 9048 3224 3220 9049 3220 3221 9050 3221 3225 9051 3225 3222 9052 3222 3223 9053 3223 3225 9054 3225 3224 9055 3224 3222 9056 3222 3227 9057 3227 3225 9058 3225 3226 9059 3226 3228 9060 3228 3225 9061 3225 3227 9062 3227 3228 9063 3228 3224 9064 3224 3225 9065 3225 3229 9066 3229 3224 9067 3224 3228 9068 3228 3230 9069 3230 3224 9070 3224 3229 9071 3229 3231 9072 3231 3224 9073 3224 3230 9074 3230 3232 9075 3232 3224 9076 3224 3231 9077 3231 3233 9078 3233 3224 9079 3224 3232 9080 3232 3234 9081 3234 3224 9082 3224 3233 9083 3233 3235 9084 3235 3224 9085 3224 3234 9086 3234 3220 9087 3220 3224 9088 3224 3235 9089 3235 3245 9090 3245 3236 9091 3236 3237 9092 3237 3240 9093 3240 3238 9094 3238 3239 9095 3239 3246 9096 3246 3238 9097 3238 3240 9098 3240 3238 9099 3238 3241 9100 3241 3242 9101 3242 3238 9102 3238 3243 9103 3243 3241 9104 3241 3246 9105 3246 3243 9106 3243 3238 9107 3238 3246 9108 3246 3244 9109 3244 3243 9110 3243 3246 9111 3246 3245 9112 3245 3244 9113 3244 3247 9114 3247 3245 9115 3245 3246 9116 3246 3248 9117 3248 3245 9118 3245 3247 9119 3247 3249 9120 3249 3245 9121 3245 3248 9122 3248 3250 9123 3250 3245 9124 3245 3249 9125 3249 3251 9126 3251 3245 9127 3245 3250 9128 3250 3236 9129 3236 3245 9130 3245 3251 9131 3251 3254 9132 3254 3252 9133 3252 3253 9134 3253 3252 9135 3252 3254 9136 3254 3255 9137 3255 3260 9138 3260 3256 9139 3256 3257 9140 3257 3261 9141 3261 3258 9142 3258 3259 9143 3259 3261 9144 3261 3260 9145 3260 3258 9146 3258 3263 9147 3263 3261 9148 3261 3262 9149 3262 3264 9150 3264 3261 9151 3261 3263 9152 3263 3264 9153 3264 3260 9154 3260 3261 9155 3261 3265 9156 3265 3260 9157 3260 3264 9158 3264 3266 9159 3266 3260 9160 3260 3265 9161 3265 3267 9162 3267 3260 9163 3260 3266 9164 3266 3268 9165 3268 3260 9166 3260 3267 9167 3267 3269 9168 3269 3260 9169 3260 3268 9170 3268 3270 9171 3270 3260 9172 3260 3269 9173 3269 3271 9174 3271 3260 9175 3260 3270 9176 3270 3256 9177 3256 3260 9178 3260 3271 9179 3271 3281 9180 3281 3272 9181 3272 3273 9182 3273 3276 9183 3276 3274 9184 3274 3275 9185 3275 3282 9186 3282 3274 9187 3274 3276 9188 3276 3274 9189 3274 3277 9190 3277 3278 9191 3278 3274 9192 3274 3279 9193 3279 3277 9194 3277 3282 9195 3282 3279 9196 3279 3274 9197 3274 3282 9198 3282 3280 9199 3280 3279 9200 3279 3282 9201 3282 3281 9202 3281 3280 9203 3280 3283 9204 3283 3281 9205 3281 3282 9206 3282 3284 9207 3284 3281 9208 3281 3283 9209 3283 3285 9210 3285 3281 9211 3281 3284 9212 3284 3286 9213 3286 3281 9214 3281 3285 9215 3285 3287 9216 3287 3281 9217 3281 3286 9218 3286 3272 9219 3272 3281 9220 3281 3287 9221 3287 3290 9222 3290 3288 9223 3288 3289 9224 3289 3288 9225 3288 3290 9226 3290 3291 9227 3291 3296 9228 3296 3292 9229 3292 3293 9230 3293 3299 9231 3299 3294 9232 3294 3295 9233 3295 3299 9234 3299 3296 9235 3296 3294 9236 3294 3302 9237 3302 3297 9238 3297 3298 9239 3298 3301 9240 3301 3299 9241 3299 3300 9242 3300 3297 9243 3297 3299 9244 3299 3301 9245 3301 3297 9246 3297 3296 9247 3296 3299 9248 3299 3302 9249 3302 3296 9250 3296 3297 9251 3297 3303 9252 3303 3296 9253 3296 3302 9254 3302 3304 9255 3304 3296 9256 3296 3303 9257 3303 3305 9258 3305 3296 9259 3296 3304 9260 3304 3306 9261 3306 3296 9262 3296 3305 9263 3305 3307 9264 3307 3296 9265 3296 3306 9266 3306 3292 9267 3292 3296 9268 3296 3307 9269 3307 3313 9270 3313 3308 9271 3308 3309 9272 3309 3312 9273 3312 3310 9274 3310 3311 9275 3311 3318 9276 3318 3310 9277 3310 3312 9278 3312 3317 9279 3317 3313 9280 3313 3314 9281 3314 3310 9282 3310 3315 9283 3315 3316 9284 3316 3310 9285 3310 3317 9286 3317 3315 9287 3315 3318 9288 3318 3317 9289 3317 3310 9290 3310 3318 9291 3318 3313 9292 3313 3317 9293 3317 3319 9294 3319 3313 9295 3313 3318 9296 3318 3320 9297 3320 3313 9298 3313 3319 9299 3319 3321 9300 3321 3313 9301 3313 3320 9302 3320 3322 9303 3322 3313 9304 3313 3321 9305 3321 3323 9306 3323 3313 9307 3313 3322 9308 3322 3308 9309 3308 3313 9310 3313 3323 9311 3323 3326 9312 3326 3324 9313 3324 3325 9314 3325 3324 9315 3324 3326 9316 3326 3327 9317 3327 3332 9318 3332 3328 9319 3328 3329 9320 3329 3333 9321 3333 3330 9322 3330 3331 9323 3331 3333 9324 3333 3332 9325 3332 3330 9326 3330 3335 9327 3335 3333 9328 3333 3334 9329 3334 3336 9330 3336 3333 9331 3333 3335 9332 3335 3336 9333 3336 3332 9334 3332 3333 9335 3333 3337 9336 3337 3332 9337 3332 3336 9338 3336 3338 9339 3338 3332 9340 3332 3337 9341 3337 3339 9342 3339 3332 9343 3332 3338 9344 3338 3340 9345 3340 3332 9346 3332 3339 9347 3339 3341 9348 3341 3332 9349 3332 3340 9350 3340 3342 9351 3342 3332 9352 3332 3341 9353 3341 3343 9354 3343 3332 9355 3332 3342 9356 3342 3328 9357 3328 3332 9358 3332 3343 9359 3343 3349 9360 3349 3344 9361 3344 3345 9362 3345 3348 9363 3348 3346 9364 3346 3347 9365 3347 3354 9366 3354 3346 9367 3346 3348 9368 3348 3353 9369 3353 3349 9370 3349 3350 9371 3350 3346 9372 3346 3351 9373 3351 3352 9374 3352 3346 9375 3346 3353 9376 3353 3351 9377 3351 3354 9378 3354 3353 9379 3353 3346 9380 3346 3354 9381 3354 3349 9382 3349 3353 9383 3353 3355 9384 3355 3349 9385 3349 3354 9386 3354 3356 9387 3356 3349 9388 3349 3355 9389 3355 3357 9390 3357 3349 9391 3349 3356 9392 3356 3358 9393 3358 3349 9394 3349 3357 9395 3357 3359 9396 3359 3349 9397 3349 3358 9398 3358 3344 9399 3344 3349 9400 3349 3359 9401 3359 3362 9402 3362 3360 9403 3360 3361 9404 3361 3360 9405 3360 3362 9406 3362 3363 9407 3363 3368 9408 3368 3364 9409 3364 3365 9410 3365 3369 9411 3369 3366 9412 3366 3367 9413 3367 3369 9414 3369 3368 9415 3368 3366 9416 3366 3371 9417 3371 3369 9418 3369 3370 9419 3370 3372 9420 3372 3369 9421 3369 3371 9422 3371 3372 9423 3372 3368 9424 3368 3369 9425 3369 3373 9426 3373 3368 9427 3368 3372 9428 3372 3374 9429 3374 3368 9430 3368 3373 9431 3373 3375 9432 3375 3368 9433 3368 3374 9434 3374 3376 9435 3376 3368 9436 3368 3375 9437 3375 3377 9438 3377 3368 9439 3368 3376 9440 3376 3378 9441 3378 3368 9442 3368 3377 9443 3377 3379 9444 3379 3368 9445 3368 3378 9446 3378 3364 9447 3364 3368 9448 3368 3379 9449 3379 3389 9450 3389 3380 9451 3380 3381 9452 3381 3384 9453 3384 3382 9454 3382 3383 9455 3383 3390 9456 3390 3382 9457 3382 3384 9458 3384 3382 9459 3382 3385 9460 3385 3386 9461 3386 3382 9462 3382 3387 9463 3387 3385 9464 3385 3390 9465 3390 3387 9466 3387 3382 9467 3382 3390 9468 3390 3388 9469 3388 3387 9470 3387 3390 9471 3390 3389 9472 3389 3388 9473 3388 3391 9474 3391 3389 9475 3389 3390 9476 3390 3392 9477 3392 3389 9478 3389 3391 9479 3391 3393 9480 3393 3389 9481 3389 3392 9482 3392 3394 9483 3394 3389 9484 3389 3393 9485 3393 3395 9486 3395 3389 9487 3389 3394 9488 3394 3380 9489 3380 3389 9490 3389 3395 9491 3395 3398 9492 3398 3396 9493 3396 3397 9494 3397 3396 9495 3396 3398 9496 3398 3399 9497 3399 3419 9498 3419 3400 9499 3400 3401 9500 3401 3405 9501 3405 3402 9502 3402 3403 9503 3403 3405 9504 3405 3404 9505 3404 3402 9506 3402 3407 9507 3407 3404 9508 3404 3405 9509 3405 3407 9510 3407 3406 9511 3406 3404 9512 3404 3409 9513 3409 3406 9514 3406 3407 9515 3407 3409 9516 3409 3408 9517 3408 3406 9518 3406 3411 9519 3411 3408 9520 3408 3409 9521 3409 3411 9522 3411 3410 9523 3410 3408 9524 3408 3413 9525 3413 3410 9526 3410 3411 9527 3411 3413 9528 3413 3412 9529 3412 3410 9530 3410 3415 9531 3415 3412 9532 3412 3413 9533 3413 3415 9534 3415 3414 9535 3414 3412 9536 3412 3417 9537 3417 3414 9538 3414 3415 9539 3415 3417 9540 3417 3416 9541 3416 3414 9542 3414 3400 9543 3400 3416 9544 3416 3417 9545 3417 3400 9546 3400 3418 9547 3418 3416 9548 3416 3400 9549 3400 3419 9550 3419 3418 9551 3418 3451 9552 3451 3420 9553 3420 3421 9554 3421 3424 9555 3424 3422 9556 3422 3423 9557 3423 3434 9558 3434 3422 9559 3422 3424 9560 3424 3433 9561 3433 3425 9562 3425 3426 9563 3426 3433 9564 3433 3427 9565 3427 3425 9566 3425 3430 9567 3430 3428 9568 3428 3429 9569 3429 3432 9570 3432 3428 9571 3428 3430 9572 3430 3432 9573 3432 3431 9574 3431 3428 9575 3428 3427 9576 3427 3431 9577 3431 3432 9578 3432 3433 9579 3433 3431 9580 3431 3427 9581 3427 3422 9582 3422 3431 9583 3431 3433 9584 3433 3434 9585 3434 3431 9586 3431 3422 9587 3422 3446 9588 3446 3431 9589 3431 3434 9590 3434 3437 9591 3437 3435 9592 3435 3436 9593 3436 3450 9594 3450 3435 9595 3435 3437 9596 3437 3449 9597 3449 3438 9598 3438 3439 9599 3439 3449 9600 3449 3440 9601 3440 3438 9602 3438 3448 9603 3448 3441 9604 3441 3442 9605 3442 3448 9606 3448 3443 9607 3443 3441 9608 3441 3447 9609 3447 3444 9610 3444 3445 9611 3445 3447 9612 3447 3446 9613 3446 3444 9614 3444 3447 9615 3447 3431 9616 3431 3446 9617 3446 3443 9618 3443 3431 9619 3431 3447 9620 3447 3448 9621 3448 3431 9622 3431 3443 9623 3443 3440 9624 3440 3431 9625 3431 3448 9626 3448 3449 9627 3449 3431 9628 3431 3440 9629 3440 3435 9630 3435 3431 9631 3431 3449 9632 3449 3450 9633 3450 3431 9634 3431 3435 9635 3435 3420 9636 3420 3431 9637 3431 3450 9638 3450 3420 9639 3420 3451 9640 3451 3431 9641 3431 3454 9642 3454 3452 9643 3452 3453 9644 3453 3452 9645 3452 3454 9646 3454 3455 9647 3455 3458 9648 3458 3456 9649 3456 3457 9650 3457 3456 9651 3456 3458 9652 3458 3459 9653 3459 3462 9654 3462 3460 9655 3460 3461 9656 3461 3460 9657 3460 3462 9658 3462 3463 9659 3463 3466 9660 3466 3464 9661 3464 3465 9662 3465 3464 9663 3464 3466 9664 3466 3467 9665 3467 3470 9666 3470 3468 9667 3468 3469 9668 3469 3468 9669 3468 3470 9670 3470 3471 9671 3471 3474 9672 3474 3472 9673 3472 3473 9674 3473 3472 9675 3472 3474 9676 3474 3475 9677 3475 3478 9678 3478 3476 9679 3476 3477 9680 3477 3476 9681 3476 3478 9682 3478 3479 9683 3479 3482 9684 3482 3480 9685 3480 3481 9686 3481 3480 9687 3480 3482 9688 3482 3483 9689 3483 3486 9690 3486 3484 9691 3484 3485 9692 3485 3484 9693 3484 3486 9694 3486 3487 9695 3487 3490 9696 3490 3488 9697 3488 3489 9698 3489 3488 9699 3488 3490 9700 3490 3491 9701 3491 3494 9702 3494 3492 9703 3492 3493 9704 3493 3492 9705 3492 3494 9706 3494 3495 9707 3495 3515 9708 3515 3496 9709 3496 3497 9710 3497 3500 9711 3500 3498 9712 3498 3499 9713 3499 3502 9714 3502 3498 9715 3498 3500 9716 3500 3502 9717 3502 3501 9718 3501 3498 9719 3498 3504 9720 3504 3501 9721 3501 3502 9722 3502 3504 9723 3504 3503 9724 3503 3501 9725 3501 3506 9726 3506 3503 9727 3503 3504 9728 3504 3506 9729 3506 3505 9730 3505 3503 9731 3503 3508 9732 3508 3505 9733 3505 3506 9734 3506 3508 9735 3508 3507 9736 3507 3505 9737 3505 3510 9738 3510 3507 9739 3507 3508 9740 3508 3510 9741 3510 3509 9742 3509 3507 9743 3507 3512 9744 3512 3509 9745 3509 3510 9746 3510 3512 9747 3512 3511 9748 3511 3509 9749 3509 3514 9750 3514 3511 9751 3511 3512 9752 3512 3514 9753 3514 3513 9754 3513 3511 9755 3511 3496 9756 3496 3513 9757 3513 3514 9758 3514 3496 9759 3496 3515 9760 3515 3513 9761 3513 3518 9762 3518 3516 9763 3516 3517 9764 3517 3516 9765 3516 3518 9766 3518 3519 9767 3519 3538 9768 3538 3520 9769 3520 3521 9770 3521 3525 9771 3525 3522 9772 3522 3523 9773 3523 3525 9774 3525 3524 9775 3524 3522 9776 3522 3527 9777 3527 3524 9778 3524 3525 9779 3525 3527 9780 3527 3526 9781 3526 3524 9782 3524 3529 9783 3529 3526 9784 3526 3527 9785 3527 3529 9786 3529 3528 9787 3528 3526 9788 3526 3531 9789 3531 3528 9790 3528 3529 9791 3529 3531 9792 3531 3530 9793 3530 3528 9794 3528 3533 9795 3533 3530 9796 3530 3531 9797 3531 3533 9798 3533 3532 9799 3532 3530 9800 3530 3535 9801 3535 3532 9802 3532 3533 9803 3533 3535 9804 3535 3534 9805 3534 3532 9806 3532 3537 9807 3537 3534 9808 3534 3535 9809 3535 3537 9810 3537 3536 9811 3536 3534 9812 3534 3539 9813 3539 3536 9814 3536 3537 9815 3537 3539 9816 3539 3538 9817 3538 3536 9818 3536 3520 9819 3520 3538 9820 3538 3539 9821 3539 3558 9822 3558 3540 9823 3540 3541 9824 3541 3545 9825 3545 3542 9826 3542 3543 9827 3543 3545 9828 3545 3544 9829 3544 3542 9830 3542 3547 9831 3547 3544 9832 3544 3545 9833 3545 3547 9834 3547 3546 9835 3546 3544 9836 3544 3549 9837 3549 3546 9838 3546 3547 9839 3547 3549 9840 3549 3548 9841 3548 3546 9842 3546 3551 9843 3551 3548 9844 3548 3549 9845 3549 3551 9846 3551 3550 9847 3550 3548 9848 3548 3553 9849 3553 3550 9850 3550 3551 9851 3551 3553 9852 3553 3552 9853 3552 3550 9854 3550 3555 9855 3555 3552 9856 3552 3553 9857 3553 3555 9858 3555 3554 9859 3554 3552 9860 3552 3557 9861 3557 3554 9862 3554 3555 9863 3555 3557 9864 3557 3556 9865 3556 3554 9866 3554 3559 9867 3559 3556 9868 3556 3557 9869 3557 3559 9870 3559 3558 9871 3558 3556 9872 3556 3540 9873 3540 3558 9874 3558 3559 9875 3559 3578 9876 3578 3560 9877 3560 3561 9878 3561 3565 9879 3565 3562 9880 3562 3563 9881 3563 3565 9882 3565 3564 9883 3564 3562 9884 3562 3567 9885 3567 3564 9886 3564 3565 9887 3565 3567 9888 3567 3566 9889 3566 3564 9890 3564 3569 9891 3569 3566 9892 3566 3567 9893 3567 3569 9894 3569 3568 9895 3568 3566 9896 3566 3571 9897 3571 3568 9898 3568 3569 9899 3569 3571 9900 3571 3570 9901 3570 3568 9902 3568 3573 9903 3573 3570 9904 3570 3571 9905 3571 3573 9906 3573 3572 9907 3572 3570 9908 3570 3575 9909 3575 3572 9910 3572 3573 9911 3573 3575 9912 3575 3574 9913 3574 3572 9914 3572 3577 9915 3577 3574 9916 3574 3575 9917 3575 3577 9918 3577 3576 9919 3576 3574 9920 3574 3579 9921 3579 3576 9922 3576 3577 9923 3577 3579 9924 3579 3578 9925 3578 3576 9926 3576 3560 9927 3560 3578 9928 3578 3579 9929 3579 3598 9930 3598 3597 9931 3597 3580 9932 3580 3584 9933 3584 3581 9934 3581 3582 9935 3582 3584 9936 3584 3583 9937 3583 3581 9938 3581 3586 9939 3586 3583 9940 3583 3584 9941 3584 3586 9942 3586 3585 9943 3585 3583 9944 3583 3588 9945 3588 3585 9946 3585 3586 9947 3586 3588 9948 3588 3587 9949 3587 3585 9950 3585 3590 9951 3590 3587 9952 3587 3588 9953 3588 3590 9954 3590 3589 9955 3589 3587 9956 3587 3592 9957 3592 3589 9958 3589 3590 9959 3590 3592 9960 3592 3591 9961 3591 3589 9962 3589 3594 9963 3594 3591 9964 3591 3592 9965 3592 3594 9966 3594 3593 9967 3593 3591 9968 3591 3596 9969 3596 3593 9970 3593 3594 9971 3594 3596 9972 3596 3595 9973 3595 3593 9974 3593 3580 9975 3580 3595 9976 3595 3596 9977 3596 3580 9978 3580 3597 9979 3597 3595 9980 3595 3597 9981 3597 3598 9982 3598 3599 9983 3599 3618 9984 3618 3600 9985 3600 3601 9986 3601 3605 9987 3605 3602 9988 3602 3603 9989 3603 3605 9990 3605 3604 9991 3604 3602 9992 3602 3607 9993 3607 3604 9994 3604 3605 9995 3605 3607 9996 3607 3606 9997 3606 3604 9998 3604 3609 9999 3609 3606 10000 3606 3607 10001 3607 3609 10002 3609 3608 10003 3608 3606 10004 3606 3611 10005 3611 3608 10006 3608 3609 10007 3609 3611 10008 3611 3610 10009 3610 3608 10010 3608 3613 10011 3613 3610 10012 3610 3611 10013 3611 3613 10014 3613 3612 10015 3612 3610 10016 3610 3615 10017 3615 3612 10018 3612 3613 10019 3613 3615 10020 3615 3614 10021 3614 3612 10022 3612 3617 10023 3617 3614 10024 3614 3615 10025 3615 3617 10026 3617 3616 10027 3616 3614 10028 3614 3619 10029 3619 3616 10030 3616 3617 10031 3617 3619 10032 3619 3618 10033 3618 3616 10034 3616 3600 10035 3600 3618 10036 3618 3619 10037 3619 3638 10038 3638 3620 10039 3620 3621 10040 3621 3625 10041 3625 3622 10042 3622 3623 10043 3623 3625 10044 3625 3624 10045 3624 3622 10046 3622 3627 10047 3627 3624 10048 3624 3625 10049 3625 3627 10050 3627 3626 10051 3626 3624 10052 3624 3629 10053 3629 3626 10054 3626 3627 10055 3627 3629 10056 3629 3628 10057 3628 3626 10058 3626 3631 10059 3631 3628 10060 3628 3629 10061 3629 3631 10062 3631 3630 10063 3630 3628 10064 3628 3633 10065 3633 3630 10066 3630 3631 10067 3631 3633 10068 3633 3632 10069 3632 3630 10070 3630 3635 10071 3635 3632 10072 3632 3633 10073 3633 3635 10074 3635 3634 10075 3634 3632 10076 3632 3637 10077 3637 3634 10078 3634 3635 10079 3635 3637 10080 3637 3636 10081 3636 3634 10082 3634 3639 10083 3639 3636 10084 3636 3637 10085 3637 3639 10086 3639 3638 10087 3638 3636 10088 3636 3620 10089 3620 3638 10090 3638 3639 10091 3639 3658 10092 3658 3657 10093 3657 3640 10094 3640 3644 10095 3644 3641 10096 3641 3642 10097 3642 3644 10098 3644 3643 10099 3643 3641 10100 3641 3646 10101 3646 3643 10102 3643 3644 10103 3644 3646 10104 3646 3645 10105 3645 3643 10106 3643 3648 10107 3648 3645 10108 3645 3646 10109 3646 3648 10110 3648 3647 10111 3647 3645 10112 3645 3650 10113 3650 3647 10114 3647 3648 10115 3648 3650 10116 3650 3649 10117 3649 3647 10118 3647 3652 10119 3652 3649 10120 3649 3650 10121 3650 3652 10122 3652 3651 10123 3651 3649 10124 3649 3654 10125 3654 3651 10126 3651 3652 10127 3652 3654 10128 3654 3653 10129 3653 3651 10130 3651 3656 10131 3656 3653 10132 3653 3654 10133 3654 3656 10134 3656 3655 10135 3655 3653 10136 3653 3640 10137 3640 3655 10138 3655 3656 10139 3656 3640 10140 3640 3657 10141 3657 3655 10142 3655 3657 10143 3657 3658 10144 3658 3659 10145 3659 3678 10146 3678 3660 10147 3660 3661 10148 3661 3665 10149 3665 3662 10150 3662 3663 10151 3663 3665 10152 3665 3664 10153 3664 3662 10154 3662 3667 10155 3667 3664 10156 3664 3665 10157 3665 3667 10158 3667 3666 10159 3666 3664 10160 3664 3669 10161 3669 3666 10162 3666 3667 10163 3667 3669 10164 3669 3668 10165 3668 3666 10166 3666 3671 10167 3671 3668 10168 3668 3669 10169 3669 3671 10170 3671 3670 10171 3670 3668 10172 3668 3673 10173 3673 3670 10174 3670 3671 10175 3671 3673 10176 3673 3672 10177 3672 3670 10178 3670 3675 10179 3675 3672 10180 3672 3673 10181 3673 3675 10182 3675 3674 10183 3674 3672 10184 3672 3677 10185 3677 3674 10186 3674 3675 10187 3675 3677 10188 3677 3676 10189 3676 3674 10190 3674 3679 10191 3679 3676 10192 3676 3677 10193 3677 3679 10194 3679 3678 10195 3678 3676 10196 3676 3660 10197 3660 3678 10198 3678 3679 10199 3679 3684 10200 3684 3680 10201 3680 3681 10202 3681 3700 10203 3700 3682 10204 3682 3683 10205 3683 3700 10206 3700 3684 10207 3684 3682 10208 3682 3687 10209 3687 3685 10210 3685 3686 10211 3686 3689 10212 3689 3685 10213 3685 3687 10214 3687 3689 10215 3689 3688 10216 3688 3685 10217 3685 3691 10218 3691 3688 10219 3688 3689 10220 3689 3691 10221 3691 3690 10222 3690 3688 10223 3688 3693 10224 3693 3690 10225 3690 3691 10226 3691 3693 10227 3693 3692 10228 3692 3690 10229 3690 3695 10230 3695 3692 10231 3692 3693 10232 3693 3695 10233 3695 3694 10234 3694 3692 10235 3692 3697 10236 3697 3694 10237 3694 3695 10238 3695 3697 10239 3697 3696 10240 3696 3694 10241 3694 3699 10242 3699 3696 10243 3696 3697 10244 3697 3699 10245 3699 3698 10246 3698 3696 10247 3696 3701 10248 3701 3698 10249 3698 3699 10250 3699 3701 10251 3701 3700 10252 3700 3698 10253 3698 3680 10254 3680 3700 10255 3700 3701 10256 3701 3680 10257 3680 3684 10258 3684 3700 10259 3700 3704 10260 3704 3702 10261 3702 3703 10262 3703 3702 10263 3702 3704 10264 3704 3705 10265 3705 3708 10266 3708 3706 10267 3706 3707 10268 3707 3706 10269 3706 3708 10270 3708 3709 10271 3709 3712 10272 3712 3710 10273 3710 3711 10274 3711 3710 10275 3710 3712 10276 3712 3713 10277 3713 3716 10278 3716 3714 10279 3714 3715 10280 3715 3714 10281 3714 3716 10282 3716 3717 10283 3717 3720 10284 3720 3718 10285 3718 3719 10286 3719 3718 10287 3718 3720 10288 3720 3721 10289 3721 3724 10290 3724 3722 10291 3722 3723 10292 3723 3722 10293 3722 3724 10294 3724 3725 10295 3725 3728 10296 3728 3726 10297 3726 3727 10298 3727 3726 10299 3726 3728 10300 3728 3729 10301 3729 3732 10302 3732 3730 10303 3730 3731 10304 3731 3730 10305 3730 3732 10306 3732 3733 10307 3733 3755 10308 3755 3734 10309 3734 3735 10310 3735 3738 10311 3738 3736 10312 3736 3737 10313 3737 3734 10314 3734 3736 10315 3736 3738 10316 3738 3742 10317 3742 3739 10318 3739 3740 10319 3740 3742 10320 3742 3741 10321 3741 3739 10322 3739 3744 10323 3744 3741 10324 3741 3742 10325 3742 3744 10326 3744 3743 10327 3743 3741 10328 3741 3746 10329 3746 3743 10330 3743 3744 10331 3744 3746 10332 3746 3745 10333 3745 3743 10334 3743 3748 10335 3748 3745 10336 3745 3746 10337 3746 3748 10338 3748 3747 10339 3747 3745 10340 3745 3750 10341 3750 3747 10342 3747 3748 10343 3748 3750 10344 3750 3749 10345 3749 3747 10346 3747 3752 10347 3752 3749 10348 3749 3750 10349 3750 3752 10350 3752 3751 10351 3751 3749 10352 3749 3754 10353 3754 3751 10354 3751 3752 10355 3752 3754 10356 3754 3753 10357 3753 3751 10358 3751 3736 10359 3736 3753 10360 3753 3754 10361 3754 3736 10362 3736 3755 10363 3755 3753 10364 3753 3734 10365 3734 3755 10366 3755 3736 10367 3736 3758 10368 3758 3756 10369 3756 3757 10370 3757 3756 10371 3756 3758 10372 3758 3759 10373 3759 3762 10374 3762 3760 10375 3760 3761 10376 3761 3760 10377 3760 3762 10378 3762 3763 10379 3763 3766 10380 3766 3764 10381 3764 3765 10382 3765 3764 10383 3764 3766 10384 3766 3767 10385 3767 3770 10386 3770 3768 10387 3768 3769 10388 3769 3768 10389 3768 3770 10390 3770 3771 10391 3771 3774 10392 3774 3772 10393 3772 3773 10394 3773 3772 10395 3772 3774 10396 3774 3775 10397 3775 3778 10398 3778 3776 10399 3776 3777 10400 3777 3776 10401 3776 3778 10402 3778 3779 10403 3779 3782 10404 3782 3780 10405 3780 3781 10406 3781 3780 10407 3780 3782 10408 3782 3783 10409 3783 3786 10410 3786 3784 10411 3784 3785 10412 3785 3784 10413 3784 3786 10414 3786 3787 10415 3787 3790 10416 3790 3788 10417 3788 3789 10418 3789 3788 10419 3788 3790 10420 3790 3791 10421 3791 3794 10422 3794 3792 10423 3792 3793 10424 3793 3792 10425 3792 3794 10426 3794 3795 10427 3795 3798 10428 3798 3796 10429 3796 3797 10430 3797 3796 10431 3796 3798 10432 3798 3799 10433 3799 3802 10434 3802 3800 10435 3800 3801 10436 3801 3800 10437 3800 3802 10438 3802 3803 10439 3803 3806 10440 3806 3804 10441 3804 3805 10442 3805 3804 10443 3804 3806 10444 3806 3807 10445 3807 4601 10446 4601 4539 10447 4539 3808 10448 3808 3817 10449 3817 3820 10450 3820 3809 10451 3809 3814 10452 3814 3810 10453 3810 3819 10454 3819 3813 10455 3813 3822 10456 3822 3811 10457 3811 3813 10458 3813 3812 10459 3812 3822 10460 3822 3829 10461 3829 3812 10462 3812 3813 10463 3813 4279 10464 4279 3810 10465 3810 3814 10466 3814 4279 10467 4279 3815 10468 3815 3810 10469 3810 3817 10470 3817 3816 10471 3816 3820 10472 3820 3827 10473 3827 3816 10474 3816 3817 10475 3817 3819 10476 3819 3818 10477 3818 3814 10478 3814 3826 10479 3826 3818 10480 3818 3819 10481 3819 4283 10482 4283 3809 10483 3809 3820 10484 3820 4283 10485 4283 3821 10486 3821 3809 10487 3809 4314 10488 4314 3811 10489 3811 3822 10490 3822 4314 10491 4314 3823 10492 3823 3811 10493 3811 4314 10494 4314 3824 10495 3824 3823 10496 3823 4283 10497 4283 3825 10498 3825 3821 10499 3821 3833 10500 3833 3818 10501 3818 3826 10502 3826 3832 10503 3832 3816 10504 3816 3827 10505 3827 4279 10506 4279 3828 10507 3828 3815 10508 3815 3830 10509 3830 3812 10510 3812 3829 10511 3829 3841 10512 3841 3812 10513 3812 3830 10514 3830 4279 10515 4279 3831 10516 3831 3828 10517 3828 3839 10518 3839 3816 10519 3816 3832 10520 3832 3838 10521 3838 3818 10522 3818 3833 10523 3833 4283 10524 4283 3834 10525 3834 3825 10526 3825 4314 10527 4314 3835 10528 3835 3824 10529 3824 4314 10530 4314 3836 10531 3836 3835 10532 3835 4283 10533 4283 3837 10534 3837 3834 10535 3834 3843 10536 3843 3818 10537 3818 3838 10538 3838 3842 10539 3842 3816 10540 3816 3839 10541 3839 4279 10542 4279 3840 10543 3840 3831 10544 3831 3846 10545 3846 3812 10546 3812 3841 10547 3841 3872 10548 3872 3816 10549 3816 3842 10550 3842 3873 10551 3873 3818 10552 3818 3843 10553 3843 4279 10554 4279 3844 10555 3844 3840 10556 3840 4283 10557 4283 3845 10558 3845 3837 10559 3837 3876 10560 3876 3812 10561 3812 3846 10562 3846 4314 10563 4314 3847 10564 3847 3836 10565 3836 4054 10566 4054 3933 10567 3933 3848 10568 3848 4054 10569 4054 3849 10570 3849 3933 10571 3933 4054 10572 4054 3850 10573 3850 3849 10574 3849 3852 10575 3852 3851 10576 3851 3976 10577 3976 3853 10578 3853 3851 10579 3851 3852 10580 3852 3871 10581 3871 3851 10582 3851 3853 10583 3853 4060 10584 4060 3937 10585 3937 3854 10586 3854 4060 10587 4060 3855 10588 3855 3937 10589 3937 4060 10590 4060 3856 10591 3856 3855 10592 3855 3858 10593 3858 3857 10594 3857 4089 10595 4089 3859 10596 3859 3857 10597 3857 3858 10598 3858 3868 10599 3868 3857 10600 3857 3859 10601 3859 4066 10602 4066 3941 10603 3941 3860 10604 3860 4066 10605 4066 3861 10606 3861 3941 10607 3941 4066 10608 4066 3862 10609 3862 3861 10610 3861 3864 10611 3864 3863 10612 3863 4099 10613 4099 3865 10614 3865 3863 10615 3863 3864 10616 3864 3866 10617 3866 3863 10618 3863 3865 10619 3865 3943 10620 3943 3863 10621 3863 3866 10622 3866 4066 10623 4066 3867 10624 3867 3862 10625 3862 3939 10626 3939 3857 10627 3857 3868 10628 3868 4060 10629 4060 3869 10630 3869 3856 10631 3856 4054 10632 4054 3870 10633 3870 3850 10634 3850 3935 10635 3935 3851 10636 3851 3871 10637 3871 3910 10638 3910 3816 10639 3816 3872 10640 3872 3918 10641 3918 3818 10642 3818 3873 10643 3873 4279 10644 4279 3874 10645 3874 3844 10646 3844 4283 10647 4283 3875 10648 3875 3845 10649 3845 3928 10650 3928 3812 10651 3812 3876 10652 3876 4314 10653 4314 3877 10654 3877 3847 10655 3847 4052 10656 4052 3893 10657 3893 3878 10658 3878 4052 10659 4052 3879 10660 3879 3893 10661 3893 3920 10662 3920 3896 10663 3896 3880 10664 3880 3902 10665 3902 3906 10666 3906 3881 10667 3881 4017 10668 4017 3884 10669 3884 3882 10670 3882 4017 10671 4017 3883 10672 3883 3884 10673 3884 3909 10674 3909 3882 10675 3882 3884 10676 3884 3929 10677 3929 3885 10678 3885 3887 10679 3887 3887 10680 3887 3886 10681 3886 3929 10682 3929 3958 10683 3958 3886 10684 3886 3887 10685 3887 4052 10686 4052 3888 10687 3888 3879 10688 3879 3945 10689 3945 3889 10690 3889 3894 10691 3894 3894 10692 3894 3890 10693 3890 3945 10694 3945 4015 10695 4015 3892 10696 3892 3891 10697 3891 3952 10698 3952 3891 10699 3891 3892 10700 3892 3967 10701 3967 3878 10702 3878 3893 10703 3893 4019 10704 4019 3890 10705 3890 3894 10706 3894 4180 10707 4180 3895 10708 3895 3947 10709 3947 3974 10710 3974 3880 10711 3880 3896 10712 3896 4192 10713 4192 3897 10714 3897 3948 10715 3948 4203 10716 4203 3990 10717 3990 3898 10718 3898 3920 10719 3920 3899 10720 3899 3896 10721 3896 4215 10722 4215 4005 10723 4005 3900 10724 3900 3902 10725 3902 3901 10726 3901 3906 10727 3906 3960 10728 3960 3901 10729 3901 3902 10730 3902 4228 10731 4228 3903 10732 3903 3951 10733 3951 4015 10734 4015 3904 10735 3904 3892 10736 3892 4241 10737 4241 4021 10738 4021 3905 10739 3905 4046 10740 4046 3881 10741 3881 3906 10742 3906 4046 10743 4046 3907 10744 3907 3881 10745 3881 3909 10746 3909 3908 10747 3908 3882 10748 3882 3969 10749 3969 3908 10750 3908 3909 10751 3909 4040 10752 4040 3816 10753 3816 3910 10754 3910 4271 10755 4271 3921 10756 3921 3911 10757 3911 4271 10758 4271 3912 10759 3912 3921 10760 3921 4271 10761 4271 3913 10762 3913 3912 10763 3912 4271 10764 4271 3914 10765 3914 3913 10766 3913 4271 10767 4271 3915 10768 3915 3914 10769 3914 4271 10770 4271 3916 10771 3916 3915 10772 3915 3974 10773 3974 3917 10774 3917 3880 10775 3880 4041 10776 4041 3818 10777 3818 3918 10778 3918 4279 10779 4279 3919 10780 3919 3874 10781 3874 4004 10782 4004 3899 10783 3899 3920 10784 3920 3923 10785 3923 3911 10786 3911 3921 10787 3921 3923 10788 3923 3922 10789 3922 3911 10790 3911 3924 10791 3924 3922 10792 3922 3923 10793 3923 3925 10794 3925 3922 10795 3922 3924 10796 3924 3926 10797 3926 3922 10798 3922 3925 10799 3925 4136 10800 4136 3922 10801 3922 3926 10802 3926 4283 10803 4283 3927 10804 3927 3875 10805 3875 4044 10806 4044 3812 10807 3812 3928 10808 3928 4117 10809 4117 3885 10810 3885 3929 10811 3929 4117 10812 4117 3930 10813 3930 3885 10814 3885 4314 10815 4314 3931 10816 3931 3877 10817 3877 4054 10818 4054 3932 10819 3932 3870 10820 3870 4084 10821 4084 3848 10822 3848 3933 10823 3933 3976 10824 3976 3934 10825 3934 3852 10826 3852 4058 10827 4058 3851 10828 3851 3935 10829 3935 4060 10830 4060 3936 10831 3936 3869 10832 3869 3996 10833 3996 3854 10834 3854 3937 10835 3937 4089 10836 4089 3938 10837 3938 3858 10838 3858 4064 10839 4064 3857 10840 3857 3939 10841 3939 4066 10842 4066 3940 10843 3940 3867 10844 3867 4094 10845 4094 3860 10846 3860 3941 10847 3941 4099 10848 4099 3942 10849 3942 3864 10850 3864 4080 10851 4080 3863 10852 3863 3943 10853 3943 3952 10854 3952 3944 10855 3944 3891 10856 3891 4077 10857 4077 3889 10858 3889 3945 10859 3945 4077 10860 4077 3946 10861 3946 3889 10862 3889 3971 10863 3971 4180 10864 4180 3947 10865 3947 3977 10866 3977 4192 10867 4192 3948 10868 3948 3990 10869 3990 3949 10870 3949 3898 10871 3898 4005 10872 4005 3950 10873 3950 3900 10874 3900 4011 10875 4011 4228 10876 4228 3951 10877 3951 4070 10878 4070 3944 10879 3944 3952 10880 3952 4021 10881 4021 3953 10882 3953 3905 10883 3905 4147 10884 4147 3954 10885 3954 3955 10886 3955 4552 10887 4552 3956 10888 3956 3957 10889 3957 4027 10890 4027 3886 10891 3886 3958 10892 3958 4017 10893 4017 3959 10894 3959 3883 10895 3883 4051 10896 4051 3901 10897 3901 3960 10898 3960 4052 10899 4052 3961 10900 3961 3888 10901 3888 4149 10902 4149 3962 10903 3962 3963 10904 3963 4598 10905 4598 3964 10906 3964 3965 10907 3965 4046 10908 4046 3966 10909 3966 3907 10910 3907 4039 10911 4039 3878 10912 3878 3967 10913 3967 4117 10914 4117 3968 10915 3968 3930 10916 3930 4105 10917 4105 3908 10918 3908 3969 10919 3969 3971 10920 3971 3970 10921 3970 4180 10922 4180 3972 10923 3972 3970 10924 3970 3971 10925 3971 3973 10926 3973 3970 10927 3970 3972 10928 3972 3989 10929 3989 3970 10930 3970 3973 10931 3973 4126 10932 4126 3917 10933 3917 3974 10934 3974 4126 10935 4126 3975 10936 3975 3917 10937 3917 3977 10938 3977 3976 10939 3976 4192 10940 4192 3978 10941 3978 3976 10942 3976 3977 10943 3977 3979 10944 3979 3976 10945 3976 3978 10946 3978 3980 10947 3980 3976 10948 3976 3979 10949 3979 3980 10950 3980 3934 10951 3934 3976 10952 3976 3981 10953 3981 3934 10954 3934 3980 10955 3980 3986 10956 3986 3934 10957 3934 3981 10958 3981 3986 10959 3986 3982 10960 3982 3934 10961 3934 3986 10962 3986 3983 10963 3983 3982 10964 3982 3986 10965 3986 3984 10966 3984 3983 10967 3983 3986 10968 3986 3985 10969 3985 3984 10970 3984 3987 10971 3987 3985 10972 3985 3986 10973 3986 4048 10974 4048 3985 10975 3985 3987 10976 3987 4048 10977 4048 3988 10978 3988 3985 10979 3985 4087 10980 4087 3970 10981 3970 3989 10982 3989 3854 10983 3854 3949 10984 3949 3990 10985 3990 3854 10986 3854 3991 10987 3991 3949 10988 3949 3854 10989 3854 3992 10990 3992 3991 10991 3991 3854 10992 3854 3993 10993 3993 3992 10994 3992 3996 10995 3996 3993 10996 3993 3854 10997 3854 3996 10998 3996 3994 10999 3994 3993 11000 3993 3996 11001 3996 3995 11002 3995 3994 11003 3994 3997 11004 3997 3995 11005 3995 3996 11006 3996 3998 11007 3998 3995 11008 3995 3997 11009 3997 3999 11010 3999 3995 11011 3995 3998 11012 3998 4001 11013 4001 3995 11014 3995 3999 11015 3999 4001 11016 4001 4000 11017 4000 3995 11018 3995 4115 11019 4115 4000 11020 4000 4001 11021 4001 4115 11022 4115 4002 11023 4002 4000 11024 4000 4004 11025 4004 4003 11026 4003 3899 11027 3899 4116 11028 4116 4003 11029 4003 4004 11030 4004 4413 11031 4413 3950 11032 3950 4005 11033 4005 4413 11034 4413 4006 11035 4006 3950 11036 3950 4413 11037 4413 4007 11038 4007 4006 11039 4006 4413 11040 4413 4008 11041 4008 4007 11042 4007 4413 11043 4413 4009 11044 4009 4008 11045 4008 4011 11046 4011 4010 11047 4010 4228 11048 4228 4012 11049 4012 4010 11050 4010 4011 11051 4011 4013 11052 4013 4010 11053 4010 4012 11054 4012 4014 11055 4014 4010 11056 4010 4013 11057 4013 4097 11058 4097 4010 11059 4010 4014 11060 4014 4140 11061 4140 3904 11062 3904 4015 11063 4015 4140 11064 4140 4016 11065 4016 3904 11066 3904 4026 11067 4026 3959 11068 3959 4017 11069 4017 4026 11070 4026 4018 11071 4018 3959 11072 3959 4078 11073 4078 3890 11074 3890 4019 11075 4019 4078 11076 4078 4020 11077 4020 3890 11078 3890 4104 11079 4104 3953 11080 3953 4021 11081 4021 4104 11082 4104 4022 11083 4022 3953 11084 3953 4104 11085 4104 4023 11086 4023 4022 11087 4022 4104 11088 4104 4024 11089 4024 4023 11090 4023 4104 11091 4104 4025 11092 4025 4024 11093 4024 4027 11094 4027 4026 11095 4026 3886 11096 3886 4027 11097 4027 4018 11098 4018 4026 11099 4026 4029 11100 4029 4018 11101 4018 4027 11102 4027 4029 11103 4029 4028 11104 4028 4018 11105 4018 4031 11106 4031 4028 11107 4028 4029 11108 4029 4031 11109 4031 4030 11110 4030 4028 11111 4028 4033 11112 4033 4030 11113 4030 4031 11114 4031 4033 11115 4033 4032 11116 4032 4030 11117 4030 4034 11118 4034 4032 11119 4032 4033 11120 4033 4036 11121 4036 4032 11122 4032 4034 11123 4034 4036 11124 4036 4035 11125 4035 4032 11126 4032 4111 11127 4111 4035 11128 4035 4036 11129 4036 4111 11130 4111 4037 11131 4037 4035 11132 4035 4039 11133 4039 4038 11134 4038 3878 11135 3878 4138 11136 4138 4038 11137 4038 4039 11138 4039 4124 11139 4124 3816 11140 3816 4040 11141 4040 4125 11142 4125 3818 11143 3818 4041 11144 4041 4279 11145 4279 4042 11146 4042 3919 11147 3919 4283 11148 4283 4043 11149 4043 3927 11150 3927 4131 11151 4131 3812 11152 3812 4044 11153 4044 4314 11154 4314 4045 11155 4045 3931 11156 3931 4170 11157 4170 3966 11158 3966 4046 11159 4046 4170 11160 4170 4047 11161 4047 3966 11162 3966 4134 11163 4134 3988 11164 3988 4048 11165 4048 4115 11166 4115 4049 11167 4049 4002 11168 4002 4051 11169 4051 4050 11170 4050 3901 11171 3901 4137 11172 4137 4050 11173 4050 4051 11174 4051 4174 11175 4174 3961 11176 3961 4052 11177 4052 4174 11178 4174 4053 11179 4053 3961 11180 3961 4257 11181 4257 3932 11182 3932 4054 11183 4054 4257 11184 4257 4055 11185 4055 3932 11186 3932 4257 11187 4257 4056 11188 4056 4055 11189 4055 4058 11190 4058 4057 11191 4057 3851 11192 3851 4059 11193 4059 4057 11194 4057 4058 11195 4058 4072 11196 4072 4057 11197 4057 4059 11198 4059 4380 11199 4380 3936 11200 3936 4060 11201 4060 4380 11202 4380 4061 11203 4061 3936 11204 3936 4380 11205 4380 4062 11206 4062 4061 11207 4061 4064 11208 4064 4063 11209 4063 3857 11210 3857 4065 11211 4065 4063 11212 4063 4064 11213 4064 4074 11214 4074 4063 11215 4063 4065 11216 4065 4298 11217 4298 3940 11218 3940 4066 11219 4066 4298 11220 4298 4067 11221 4067 3940 11222 3940 4298 11223 4298 4068 11224 4068 4067 11225 4067 4070 11226 4070 4069 11227 4069 3944 11228 3944 4142 11229 4142 4069 11230 4069 4070 11231 4070 4257 11232 4257 4071 11233 4071 4056 11234 4056 4162 11235 4162 4057 11236 4057 4072 11237 4072 4380 11238 4380 4073 11239 4073 4062 11240 4062 4164 11241 4164 4063 11242 4063 4074 11243 4074 4298 11244 4298 4075 11245 4075 4068 11246 4068 4077 11247 4077 4076 11248 4076 3946 11249 3946 4156 11250 4156 4076 11251 4076 4077 11252 4077 4144 11253 4144 4020 11254 4020 4078 11255 4078 4080 11256 4080 4079 11257 4079 3863 11258 3863 4081 11259 4081 4079 11260 4079 4080 11261 4080 4082 11262 4082 4079 11263 4079 4081 11264 4081 4169 11265 4169 4079 11266 4079 4082 11267 4082 4084 11268 4084 4083 11269 4083 3848 11270 3848 4085 11271 4085 4083 11272 4083 4084 11273 4084 4086 11274 4086 4083 11275 4083 4085 11276 4085 4151 11277 4151 4083 11278 4083 4086 11279 4086 4412 11280 4412 3970 11281 3970 4087 11282 4087 4413 11283 4413 4088 11284 4088 4009 11285 4009 4372 11286 4372 3938 11287 3938 4089 11288 4089 4372 11289 4372 4090 11290 4090 3938 11291 3938 4372 11292 4372 4091 11293 4091 4090 11294 4090 4372 11295 4372 4092 11296 4092 4091 11297 4091 4094 11298 4094 4093 11299 4093 3860 11300 3860 4095 11301 4095 4093 11302 4093 4094 11303 4094 4096 11304 4096 4093 11305 4093 4095 11306 4095 4153 11307 4153 4093 11308 4093 4096 11309 4096 4119 11310 4119 4010 11311 4010 4097 11312 4097 4104 11313 4104 4098 11314 4098 4025 11315 4025 4377 11316 4377 3942 11317 3942 4099 11318 4099 4377 11319 4377 4100 11320 4100 3942 11321 3942 4377 11322 4377 4101 11323 4101 4100 11324 4100 4377 11325 4377 4102 11326 4102 4101 11327 4101 4140 11328 4140 4103 11329 4103 4016 11330 4016 4105 11331 4105 4104 11332 4104 3908 11333 3908 4105 11334 4105 4098 11335 4098 4104 11336 4104 4107 11337 4107 4098 11338 4098 4105 11339 4105 4107 11340 4107 4106 11341 4106 4098 11342 4098 4109 11343 4109 4106 11344 4106 4107 11345 4107 4109 11346 4109 4108 11347 4108 4106 11348 4106 4168 11349 4168 4108 11350 4108 4109 11351 4109 4168 11352 4168 4110 11353 4110 4108 11354 4108 4176 11355 4176 4037 11356 4037 4111 11357 4111 4176 11358 4176 4112 11359 4112 4037 11360 4037 4126 11361 4126 4113 11362 4113 3975 11363 3975 4134 11364 4134 4114 11365 4114 3988 11366 3988 4277 11367 4277 4049 11368 4049 4115 11369 4115 4173 11370 4173 4003 11371 4003 4116 11372 4116 4010 11373 4010 3968 11374 3968 4117 11375 4117 4119 11376 4119 3968 11377 3968 4010 11378 4010 4119 11379 4119 4118 11380 4118 3968 11381 3968 4121 11382 4121 4118 11383 4118 4119 11384 4119 4121 11385 4121 4120 11386 4120 4118 11387 4118 4123 11388 4123 4120 11389 4120 4121 11390 4121 4123 11391 4123 4122 11392 4122 4120 11393 4120 4155 11394 4155 4122 11395 4122 4123 11396 4123 4259 11397 4259 3816 11398 3816 4124 11399 4124 4367 11400 4367 3818 11401 3818 4125 11402 4125 4255 11403 4255 4113 11404 4113 4126 11405 4126 4279 11406 4279 4127 11407 4127 4042 11408 4042 4173 11409 4173 4128 11410 4128 4003 11411 4003 4283 11412 4283 4129 11413 4129 4043 11414 4043 4174 11415 4174 4130 11416 4130 4053 11417 4053 4300 11418 4300 3812 11419 3812 4131 11420 4131 4314 11421 4314 4132 11422 4132 4045 11423 4045 4271 11424 4271 4133 11425 4133 3916 11426 3916 4276 11427 4276 4114 11428 4114 4134 11429 4134 4277 11430 4277 4135 11431 4135 4049 11432 4049 4281 11433 4281 3922 11434 3922 4136 11435 4136 4166 11436 4166 4050 11437 4050 4137 11438 4137 4160 11439 4160 4038 11440 4038 4138 11441 4138 4170 11442 4170 4139 11443 4139 4047 11444 4047 4343 11445 4343 4103 11446 4103 4140 11447 4140 4156 11448 4156 4141 11449 4141 4076 11450 4076 4313 11451 4313 4069 11452 4069 4142 11453 4142 4144 11454 4144 4143 11455 4143 4020 11456 4020 4336 11457 4336 4143 11458 4143 4144 11459 4144 4313 11460 4313 4145 11461 4145 4069 11462 4069 4343 11463 4343 4146 11464 4146 4103 11465 4103 4340 11466 4340 3954 11467 3954 4147 11468 4147 4552 11469 4552 4148 11470 4148 3956 11471 3956 4333 11472 4333 3962 11473 3962 4149 11474 4149 4598 11475 4598 4150 11476 4150 3964 11477 3964 4365 11478 4365 4083 11479 4083 4151 11480 4151 4372 11481 4372 4152 11482 4152 4092 11483 4092 4373 11484 4373 4093 11485 4093 4153 11486 4153 4155 11487 4155 4154 11488 4154 4122 11489 4122 4375 11490 4375 4154 11491 4154 4155 11492 4155 4354 11493 4354 4141 11494 4141 4156 11495 4156 4168 11496 4168 4157 11497 4157 4110 11498 4110 4377 11499 4377 4158 11500 4158 4102 11501 4102 4160 11502 4160 4159 11503 4159 4038 11504 4038 4319 11505 4319 4159 11506 4159 4160 11507 4160 4257 11508 4257 4161 11509 4161 4071 11510 4071 4378 11511 4378 4057 11512 4057 4162 11513 4162 4380 11514 4380 4163 11515 4163 4073 11516 4073 4284 11517 4284 4063 11518 4063 4164 11519 4164 4166 11520 4166 4165 11521 4165 4050 11522 4050 4288 11523 4288 4165 11524 4165 4166 11525 4166 4298 11526 4298 4167 11527 4167 4075 11528 4075 4400 11529 4400 4157 11530 4157 4168 11531 4168 4315 11532 4315 4079 11533 4079 4169 11534 4169 4266 11535 4266 4139 11536 4139 4170 11537 4170 4266 11538 4266 4171 11539 4171 4139 11540 4139 4255 11541 4255 4172 11542 4172 4113 11543 4113 4347 11544 4347 4128 11545 4128 4173 11546 4173 4307 11547 4307 4130 11548 4130 4174 11549 4174 4307 11550 4307 4175 11551 4175 4130 11552 4130 4350 11553 4350 4112 11554 4112 4176 11555 4176 4350 11556 4350 4177 11557 4177 4112 11558 4112 4354 11559 4354 4178 11560 4178 4141 11561 4141 4180 11562 4180 4179 11563 4179 3895 11564 3895 4190 11565 4190 4179 11566 4179 4180 11567 4180 4190 11568 4190 4181 11569 4181 4179 11570 4179 4190 11571 4190 4182 11572 4182 4181 11573 4181 4190 11574 4190 4183 11575 4183 4182 11576 4182 4190 11577 4190 4184 11578 4184 4183 11579 4183 4190 11580 4190 4185 11581 4185 4184 11582 4184 4190 11583 4190 4186 11584 4186 4185 11585 4185 4190 11586 4190 4187 11587 4187 4186 11588 4186 4190 11589 4190 4188 11590 4188 4187 11591 4187 4190 11592 4190 4189 11593 4189 4188 11594 4188 4475 11595 4475 4189 11596 4189 4190 11597 4190 4192 11598 4192 4191 11599 4191 3897 11600 3897 4202 11601 4202 4191 11602 4191 4192 11603 4192 4202 11604 4202 4193 11605 4193 4191 11606 4191 4202 11607 4202 4194 11608 4194 4193 11609 4193 4202 11610 4202 4195 11611 4195 4194 11612 4194 4202 11613 4202 4196 11614 4196 4195 11615 4195 4202 11616 4202 4197 11617 4197 4196 11618 4196 4202 11619 4202 4198 11620 4198 4197 11621 4197 4202 11622 4202 4199 11623 4199 4198 11624 4198 4202 11625 4202 4200 11626 4200 4199 11627 4199 4202 11628 4202 4201 11629 4201 4200 11630 4200 4476 11631 4476 4201 11632 4201 4202 11633 4202 4205 11634 4205 3990 11635 3990 4203 11636 4203 4205 11637 4205 4204 11638 4204 3990 11639 3990 4206 11640 4206 4204 11641 4204 4205 11642 4205 4207 11643 4207 4204 11644 4204 4206 11645 4206 4208 11646 4208 4204 11647 4204 4207 11648 4207 4209 11649 4209 4204 11650 4204 4208 11651 4208 4210 11652 4210 4204 11653 4204 4209 11654 4209 4211 11655 4211 4204 11656 4204 4210 11657 4210 4212 11658 4212 4204 11659 4204 4211 11660 4211 4213 11661 4213 4204 11662 4204 4212 11663 4212 4395 11664 4395 4204 11665 4204 4213 11666 4213 4395 11667 4395 4214 11668 4214 4204 11669 4204 4217 11670 4217 4005 11671 4005 4215 11672 4215 4217 11673 4217 4216 11674 4216 4005 11675 4005 4218 11676 4218 4216 11677 4216 4217 11678 4217 4219 11679 4219 4216 11680 4216 4218 11681 4218 4220 11682 4220 4216 11683 4216 4219 11684 4219 4221 11685 4221 4216 11686 4216 4220 11687 4220 4222 11688 4222 4216 11689 4216 4221 11690 4221 4223 11691 4223 4216 11692 4216 4222 11693 4222 4224 11694 4224 4216 11695 4216 4223 11696 4223 4225 11697 4225 4216 11698 4216 4224 11699 4224 4396 11700 4396 4216 11701 4216 4225 11702 4225 4396 11703 4396 4226 11704 4226 4216 11705 4216 4228 11706 4228 4227 11707 4227 3903 11708 3903 4240 11709 4240 4227 11710 4227 4228 11711 4228 4240 11712 4240 4229 11713 4229 4227 11714 4227 4240 11715 4240 4230 11716 4230 4229 11717 4229 4240 11718 4240 4231 11719 4231 4230 11720 4230 4240 11721 4240 4232 11722 4232 4231 11723 4231 4240 11724 4240 4233 11725 4233 4232 11726 4232 4240 11727 4240 4234 11728 4234 4233 11729 4233 4240 11730 4240 4235 11731 4235 4234 11732 4234 4240 11733 4240 4236 11734 4236 4235 11735 4235 4240 11736 4240 4237 11737 4237 4236 11738 4236 4240 11739 4240 4238 11740 4238 4237 11741 4237 4240 11742 4240 4239 11743 4239 4238 11744 4238 4479 11745 4479 4239 11746 4239 4240 11747 4240 4243 11748 4243 4021 11749 4021 4241 11750 4241 4243 11751 4243 4242 11752 4242 4021 11753 4021 4244 11754 4244 4242 11755 4242 4243 11756 4243 4245 11757 4245 4242 11758 4242 4244 11759 4244 4246 11760 4246 4242 11761 4242 4245 11762 4245 4247 11763 4247 4242 11764 4242 4246 11765 4246 4248 11766 4248 4242 11767 4242 4247 11768 4247 4249 11769 4249 4242 11770 4242 4248 11771 4248 4250 11772 4250 4242 11773 4242 4249 11774 4249 4251 11775 4251 4242 11776 4242 4250 11777 4250 4252 11778 4252 4242 11779 4242 4251 11780 4251 4253 11781 4253 4242 11782 4242 4252 11783 4252 4398 11784 4398 4242 11785 4242 4253 11786 4253 4398 11787 4398 4254 11788 4254 4242 11789 4242 4401 11790 4401 4172 11791 4172 4255 11792 4255 4347 11793 4347 4256 11794 4256 4128 11795 4128 4259 11796 4259 4257 11797 4257 3816 11798 3816 4259 11799 4259 4161 11800 4161 4257 11801 4257 4259 11802 4259 4258 11803 4258 4161 11804 4161 4260 11805 4260 4258 11806 4258 4259 11807 4259 4262 11808 4262 4258 11809 4258 4260 11810 4260 4262 11811 4262 4261 11812 4261 4258 11813 4258 4171 11814 4171 4261 11815 4261 4262 11816 4262 4266 11817 4266 4261 11818 4261 4171 11819 4171 4266 11820 4266 4263 11821 4263 4261 11822 4261 4266 11823 4266 4264 11824 4264 4263 11825 4263 4266 11826 4266 4265 11827 4265 4264 11828 4264 4269 11829 4269 4265 11830 4265 4266 11831 4266 4269 11832 4269 4267 11833 4267 4265 11834 4265 4269 11835 4269 4268 11836 4268 4267 11837 4267 4330 11838 4330 4268 11839 4268 4269 11840 4269 4330 11841 4330 4270 11842 4270 4268 11843 4268 4424 11844 4424 4133 11845 4133 4271 11846 4271 4424 11847 4424 4272 11848 4272 4133 11849 4133 4424 11850 4424 4273 11851 4273 4272 11852 4272 4367 11853 4367 4274 11854 4274 3818 11855 3818 4276 11856 4276 4275 11857 4275 4114 11858 4114 4391 11859 4391 4275 11860 4275 4276 11861 4276 4404 11862 4404 4135 11863 4135 4277 11864 4277 4404 11865 4404 4278 11866 4278 4135 11867 4135 4435 11868 4435 4127 11869 4127 4279 11870 4279 4281 11871 4281 4280 11872 4280 3922 11873 3922 4282 11874 4282 4280 11875 4280 4281 11876 4281 4369 11877 4369 4280 11878 4280 4282 11879 4282 4063 11880 4063 4129 11881 4129 4283 11882 4283 4284 11883 4284 4129 11884 4129 4063 11885 4063 4287 11886 4287 4129 11887 4129 4284 11888 4284 4287 11889 4287 4285 11890 4285 4129 11891 4129 4287 11892 4287 4286 11893 4286 4285 11894 4285 4289 11895 4289 4286 11896 4286 4287 11897 4287 4289 11898 4289 4288 11899 4288 4286 11900 4286 4289 11901 4289 4165 11902 4165 4288 11903 4288 4290 11904 4290 4165 11905 4165 4289 11906 4289 4291 11907 4291 4165 11908 4165 4290 11909 4290 4293 11910 4293 4165 11911 4165 4291 11912 4291 4293 11913 4293 4292 11914 4292 4165 11915 4165 4294 11916 4294 4292 11917 4292 4293 11918 4293 4296 11919 4296 4292 11920 4292 4294 11921 4294 4296 11922 4296 4295 11923 4295 4292 11924 4292 4297 11925 4297 4295 11926 4295 4296 11927 4296 4341 11928 4341 4295 11929 4295 4297 11930 4297 4300 11931 4300 4298 11932 4298 3812 11933 3812 4300 11934 4300 4167 11935 4167 4298 11936 4298 4300 11937 4300 4299 11938 4299 4167 11939 4167 4301 11940 4301 4299 11941 4299 4300 11942 4300 4303 11943 4303 4299 11944 4299 4301 11945 4301 4303 11946 4303 4302 11947 4302 4299 11948 4299 4175 11949 4175 4302 11950 4302 4303 11951 4303 4307 11952 4307 4302 11953 4302 4175 11954 4175 4307 11955 4307 4304 11956 4304 4302 11957 4302 4307 11958 4307 4305 11959 4305 4304 11960 4304 4307 11961 4307 4306 11962 4306 4305 11963 4305 4310 11964 4310 4306 11965 4306 4307 11966 4307 4310 11967 4310 4308 11968 4308 4306 11969 4306 4310 11970 4310 4309 11971 4309 4308 11972 4308 4337 11973 4337 4309 11974 4309 4310 11975 4310 4337 11976 4337 4311 11977 4311 4309 11978 4309 4337 11979 4337 4312 11980 4312 4311 11981 4311 4351 11982 4351 4145 11983 4145 4313 11984 4313 4079 11985 4079 4132 11986 4132 4314 11987 4314 4315 11988 4315 4132 11989 4132 4079 11990 4079 4318 11991 4318 4132 11992 4132 4315 11993 4315 4318 11994 4318 4316 11995 4316 4132 11996 4132 4318 11997 4318 4317 11998 4317 4316 11999 4316 4320 12000 4320 4317 12001 4317 4318 12002 4318 4320 12003 4320 4319 12004 4319 4317 12005 4317 4320 12006 4320 4159 12007 4159 4319 12008 4319 4321 12009 4321 4159 12010 4159 4320 12011 4320 4322 12012 4322 4159 12013 4159 4321 12014 4321 4324 12015 4324 4159 12016 4159 4322 12017 4322 4324 12018 4324 4323 12019 4323 4159 12020 4159 4325 12021 4325 4323 12022 4323 4324 12023 4324 4327 12024 4327 4323 12025 4323 4325 12026 4325 4327 12027 4327 4326 12028 4326 4323 12029 4323 4328 12030 4328 4326 12031 4326 4327 12032 4327 4334 12033 4334 4326 12034 4326 4328 12035 4328 4330 12036 4330 4329 12037 4329 4270 12038 4270 4150 12039 4150 4329 12040 4329 4330 12041 4330 4598 12042 4598 4329 12043 4329 4150 12044 4150 4598 12045 4598 4331 12046 4331 4329 12047 4329 4598 12048 4598 4332 12049 4332 4331 12050 4331 4334 12051 4334 4333 12052 4333 4326 12053 4326 4334 12054 4334 3962 12055 3962 4333 12056 4333 4335 12057 4335 3962 12058 3962 4334 12059 4334 4409 12060 4409 3962 12061 3962 4335 12062 4335 4399 12063 4399 4143 12064 4143 4336 12065 4336 4148 12066 4148 4312 12067 4312 4337 12068 4337 4552 12069 4552 4312 12070 4312 4148 12071 4148 4552 12072 4552 4338 12073 4338 4312 12074 4312 4552 12075 4552 4339 12076 4339 4338 12077 4338 4341 12078 4341 4340 12079 4340 4295 12080 4295 4341 12081 4341 3954 12082 3954 4340 12083 4340 4342 12084 4342 3954 12085 3954 4341 12086 4341 4407 12087 4407 3954 12088 3954 4342 12089 4342 4406 12090 4406 4146 12091 4146 4343 12092 4343 4406 12093 4406 4344 12094 4344 4146 12095 4146 4399 12096 4399 4345 12097 4345 4143 12098 4143 4401 12099 4401 4346 12100 4346 4172 12101 4172 4418 12102 4418 4256 12103 4256 4347 12104 4347 4351 12105 4351 4348 12106 4348 4145 12107 4145 4400 12108 4400 4349 12109 4349 4157 12110 4157 4348 12111 4348 4177 12112 4177 4350 12113 4350 4351 12114 4351 4177 12115 4177 4348 12116 4348 4353 12117 4353 4177 12118 4177 4351 12119 4351 4353 12120 4353 4352 12121 4352 4177 12122 4177 4357 12123 4357 4352 12124 4352 4353 12125 4353 4357 12126 4357 4354 12127 4354 4352 12128 4352 4357 12129 4357 4178 12130 4178 4354 12131 4354 4357 12132 4357 4355 12133 4355 4178 12134 4178 4357 12135 4357 4356 12136 4356 4355 12137 4355 4359 12138 4359 4356 12139 4356 4357 12140 4357 4359 12141 4359 4358 12142 4358 4356 12143 4356 4361 12144 4361 4358 12145 4358 4359 12146 4359 4361 12147 4361 4360 12148 4360 4358 12149 4358 4363 12150 4363 4360 12151 4360 4361 12152 4361 4363 12153 4363 4362 12154 4362 4360 12155 4360 4386 12156 4386 4362 12157 4362 4363 12158 4363 4386 12159 4386 4364 12160 4364 4362 12161 4362 4382 12162 4382 4083 12163 4083 4365 12164 4365 4424 12165 4424 4366 12166 4366 4273 12167 4273 4420 12168 4420 4274 12169 4274 4367 12170 4367 4435 12171 4435 4368 12172 4368 4127 12173 4127 4437 12174 4437 4280 12175 4280 4369 12176 4369 4382 12177 4382 4370 12178 4370 4083 12179 4083 4372 12180 4372 4371 12181 4371 4152 12182 4152 4504 12183 4504 4371 12184 4371 4372 12185 4372 4384 12186 4384 4093 12187 4093 4373 12188 4373 4384 12189 4384 4374 12190 4374 4093 12191 4093 4451 12192 4451 4154 12193 4154 4375 12194 4375 4377 12195 4377 4376 12196 4376 4158 12197 4158 4506 12198 4506 4376 12199 4376 4377 12200 4377 4392 12201 4392 4057 12202 4057 4378 12203 4378 4392 12204 4392 4379 12205 4379 4057 12206 4057 4495 12207 4495 4163 12208 4163 4380 12209 4380 4495 12210 4495 4381 12211 4381 4163 12212 4163 4464 12213 4464 4370 12214 4370 4382 12215 4382 4504 12216 4504 4383 12217 4383 4371 12218 4371 4468 12219 4468 4374 12220 4374 4384 12221 4384 4451 12222 4451 4385 12223 4385 4154 12224 4154 4452 12225 4452 4364 12226 4364 4386 12227 4386 4452 12228 4452 4387 12229 4387 4364 12230 4364 4506 12231 4506 4388 12232 4388 4376 12233 4376 4475 12234 4475 4389 12235 4389 4189 12236 4189 4476 12237 4476 4390 12238 4390 4201 12239 4201 4449 12240 4449 4275 12241 4275 4391 12242 4391 4465 12243 4465 4379 12244 4379 4392 12245 4392 4495 12246 4495 4393 12247 4393 4381 12248 4381 4404 12249 4404 4394 12250 4394 4278 12251 4278 4458 12252 4458 4214 12253 4214 4395 12254 4395 4460 12255 4460 4226 12256 4226 4396 12257 4396 4479 12258 4479 4397 12259 4397 4239 12260 4239 4463 12261 4463 4254 12262 4254 4398 12263 4398 4454 12264 4454 4345 12265 4345 4399 12266 4399 4471 12267 4471 4349 12268 4349 4400 12269 4400 4422 12270 4422 4346 12271 4346 4401 12272 4401 4418 12273 4418 4402 12274 4402 4256 12275 4256 4449 12276 4449 4403 12277 4403 4275 12278 4275 4474 12279 4474 4394 12280 4394 4404 12281 4404 4406 12282 4406 4405 12283 4405 4344 12284 4344 4500 12285 4500 4405 12286 4405 4406 12287 4406 4489 12288 4489 3954 12289 3954 4407 12290 4407 4552 12291 4552 4408 12292 4408 4339 12293 4339 4481 12294 4481 3962 12295 3962 4409 12296 4409 4598 12297 4598 4410 12298 4410 4332 12299 4332 4412 12300 4412 4411 12301 4411 3970 12302 3970 4415 12303 4415 4411 12304 4411 4412 12305 4412 4438 12306 4438 4088 12307 4088 4413 12308 4413 4438 12309 4438 4414 12310 4414 4088 12311 4088 4425 12312 4425 4411 12313 4411 4415 12314 4415 4438 12315 4438 4416 12316 4416 4414 12317 4414 4422 12318 4422 4417 12319 4417 4346 12320 4346 4434 12321 4434 4402 12322 4402 4418 12323 4418 4454 12324 4454 4419 12325 4419 4345 12326 4345 4417 12327 4417 4274 12328 4274 4420 12329 4420 4422 12330 4422 4274 12331 4274 4417 12332 4417 4422 12333 4422 4421 12334 4421 4274 12335 4274 4423 12336 4423 4421 12337 4421 4422 12338 4422 4366 12339 4366 4421 12340 4421 4423 12341 4423 4424 12342 4424 4421 12343 4421 4366 12344 4366 4411 12345 4411 4421 12346 4421 4424 12347 4424 4425 12348 4425 4421 12349 4421 4411 12350 4411 4427 12351 4427 4421 12352 4421 4425 12353 4425 4427 12354 4427 4426 12355 4426 4421 12356 4421 4428 12357 4428 4426 12358 4426 4427 12359 4427 4430 12360 4430 4426 12361 4426 4428 12362 4428 4430 12363 4430 4429 12364 4429 4426 12365 4426 4431 12366 4431 4429 12367 4429 4430 12368 4430 4433 12369 4433 4429 12370 4429 4431 12371 4431 4433 12372 4433 4432 12373 4432 4429 12374 4429 4456 12375 4456 4432 12376 4432 4433 12377 4433 4435 12378 4435 4434 12379 4434 4368 12380 4368 4435 12381 4435 4402 12382 4402 4434 12383 4434 4440 12384 4440 4402 12385 4402 4435 12386 4435 4440 12387 4440 4436 12388 4436 4402 12389 4402 4440 12390 4440 4437 12391 4437 4436 12392 4436 4440 12393 4440 4280 12394 4280 4437 12395 4437 4440 12396 4440 4438 12397 4438 4280 12398 4280 4440 12399 4440 4416 12400 4416 4438 12401 4438 4440 12402 4440 4439 12403 4439 4416 12404 4416 4443 12405 4443 4439 12406 4439 4440 12407 4440 4443 12408 4443 4441 12409 4441 4439 12410 4439 4443 12411 4443 4442 12412 4442 4441 12413 4441 4446 12414 4446 4442 12415 4442 4443 12416 4443 4446 12417 4446 4444 12418 4444 4442 12419 4442 4446 12420 4446 4445 12421 4445 4444 12422 4444 4498 12423 4498 4445 12424 4445 4446 12425 4446 4498 12426 4498 4447 12427 4447 4445 12428 4445 4471 12429 4471 4448 12430 4448 4349 12431 4349 4502 12432 4502 4403 12433 4403 4449 12434 4449 4474 12435 4474 4450 12436 4450 4394 12437 4394 4491 12438 4491 4385 12439 4385 4451 12440 4451 4513 12441 4513 4387 12442 4387 4452 12443 4452 4513 12444 4513 4453 12445 4453 4387 12446 4387 4517 12447 4517 4419 12448 4419 4454 12449 4454 4475 12450 4475 4455 12451 4455 4389 12452 4389 4492 12453 4492 4432 12454 4432 4456 12455 4456 4476 12456 4476 4457 12457 4457 4390 12458 4390 4484 12459 4484 4214 12460 4214 4458 12461 4458 4498 12462 4498 4459 12463 4459 4447 12464 4447 4485 12465 4485 4226 12466 4226 4460 12467 4460 4479 12468 4479 4461 12469 4461 4397 12470 4397 4491 12471 4491 4462 12472 4462 4385 12473 4385 4487 12474 4487 4254 12475 4254 4463 12476 4463 4510 12477 4510 4370 12478 4370 4464 12479 4464 4496 12480 4496 4379 12481 4379 4465 12482 4465 4495 12483 4495 4466 12484 4466 4393 12485 4393 4504 12486 4504 4467 12487 4467 4383 12488 4383 4508 12489 4508 4374 12490 4374 4468 12491 4468 4506 12492 4506 4469 12493 4469 4388 12494 4388 4500 12495 4500 4470 12496 4470 4405 12497 4405 4525 12498 4525 4448 12499 4448 4471 12500 4471 4525 12501 4525 4472 12502 4472 4448 12503 4448 4502 12504 4502 4473 12505 4473 4403 12506 4403 4523 12507 4523 4450 12508 4450 4474 12509 4474 4600 12510 4600 4455 12511 4455 4475 12512 4475 4538 12513 4538 4457 12514 4457 4476 12515 4476 4484 12516 4484 4477 12517 4477 4214 12518 4214 4485 12519 4485 4478 12520 4478 4226 12521 4226 4556 12522 4556 4461 12523 4461 4479 12524 4479 4487 12525 4487 4480 12526 4480 4254 12527 4254 4536 12528 4536 3962 12529 3962 4481 12530 4481 4600 12531 4600 4482 12532 4482 4455 12533 4455 4538 12534 4538 4483 12535 4483 4457 12536 4457 4529 12537 4529 4477 12538 4477 4484 12539 4484 4531 12540 4531 4478 12541 4478 4485 12542 4485 4556 12543 4556 4486 12544 4486 4461 12545 4461 4535 12546 4535 4480 12547 4480 4487 12548 4487 4598 12549 4598 4488 12550 4488 4410 12551 4410 4532 12552 4532 3954 12553 3954 4489 12554 4489 4552 12555 4552 4490 12556 4490 4408 12557 4408 4519 12558 4519 4462 12559 4462 4491 12560 4491 4527 12561 4527 4432 12562 4432 4492 12563 4492 4527 12564 4527 4493 12565 4493 4432 12566 4432 4496 12567 4496 4494 12568 4494 4379 12569 4379 4494 12570 4494 4466 12571 4466 4495 12572 4495 4496 12573 4496 4466 12574 4466 4494 12575 4494 4512 12576 4512 4466 12577 4466 4496 12578 4496 4512 12579 4512 4497 12580 4497 4466 12581 4466 4540 12582 4540 4459 12583 4459 4498 12584 4498 4540 12585 4540 4499 12586 4499 4459 12587 4459 4542 12588 4542 4470 12589 4470 4500 12590 4500 4510 12591 4510 4501 12592 4501 4370 12593 4370 4520 12594 4520 4473 12595 4473 4502 12596 4502 4523 12597 4523 4503 12598 4503 4450 12599 4450 4550 12600 4550 4467 12601 4467 4504 12602 4504 4508 12603 4508 4505 12604 4505 4374 12605 4374 4596 12606 4596 4469 12607 4469 4506 12608 4506 4596 12609 4596 4507 12610 4507 4469 12611 4469 4549 12612 4549 4505 12613 4505 4508 12614 4508 4550 12615 4550 4509 12616 4509 4467 12617 4467 4547 12618 4547 4501 12619 4501 4510 12620 4510 4525 12621 4525 4511 12622 4511 4472 12623 4472 4576 12624 4576 4497 12625 4497 4512 12626 4512 4575 12627 4575 4453 12628 4453 4513 12629 4513 4517 12630 4517 4514 12631 4514 4419 12632 4419 4576 12633 4576 4515 12634 4515 4497 12635 4497 4575 12636 4575 4516 12637 4516 4453 12638 4453 4602 12639 4602 4514 12640 4514 4517 12641 4517 4519 12642 4519 4518 12643 4518 4462 12644 4462 4543 12645 4543 4518 12646 4518 4519 12647 4519 4545 12648 4545 4473 12649 4473 4520 12650 4520 4545 12651 4545 4521 12652 4521 4473 12653 4473 4523 12654 4523 4522 12655 4522 4503 12656 4503 4560 12657 4560 4522 12658 4522 4523 12659 4523 4542 12660 4542 4524 12661 4524 4470 12662 4470 4603 12663 4603 4511 12664 4511 4525 12665 4525 4600 12666 4600 4526 12667 4526 4482 12668 4482 3808 12669 3808 4493 12670 4493 4527 12671 4527 4538 12672 4538 4528 12673 4528 4483 12674 4483 4541 12675 4541 4477 12676 4477 4529 12677 4529 4540 12678 4540 4530 12679 4530 4499 12680 4499 4551 12681 4551 4478 12682 4478 4531 12683 4531 4548 12684 4548 3954 12685 3954 4532 12686 4532 4552 12687 4552 4533 12688 4533 4490 12689 4490 4556 12690 4556 4534 12691 4534 4486 12692 4486 4597 12693 4597 4480 12694 4480 4535 12695 4535 4595 12696 4595 3962 12697 3962 4536 12698 4536 4598 12699 4598 4537 12700 4537 4488 12701 4488 3808 12702 3808 4538 12703 4538 4493 12704 4493 3808 12705 3808 4528 12706 4528 4538 12707 4538 3808 12708 3808 4539 12709 4539 4528 12710 4528 4477 12711 4477 4530 12712 4530 4540 12713 4540 4541 12714 4541 4530 12715 4530 4477 12716 4477 4554 12717 4554 4530 12718 4530 4541 12719 4541 4518 12720 4518 4524 12721 4524 4542 12722 4542 4543 12723 4543 4524 12724 4524 4518 12725 4518 4558 12726 4558 4524 12727 4524 4543 12728 4543 4558 12729 4558 4544 12730 4544 4524 12731 4524 4592 12732 4592 4521 12733 4521 4545 12734 4545 4560 12735 4560 4546 12736 4546 4522 12737 4522 4537 12738 4537 4501 12739 4501 4547 12740 4547 4550 12741 4550 4548 12742 4548 4509 12743 4509 4533 12744 4533 4505 12745 4505 4549 12746 4549 4550 12747 4550 3954 12748 3954 4548 12749 4548 4478 12750 4478 3954 12751 3954 4550 12752 4550 4551 12753 4551 3954 12754 3954 4478 12755 4478 4553 12756 4553 3954 12757 3954 4551 12758 4551 4553 12759 4553 4552 12760 4552 3954 12761 3954 4530 12762 4530 4552 12763 4552 4553 12764 4553 4554 12765 4554 4552 12766 4552 4530 12767 4530 4555 12768 4555 4552 12769 4552 4554 12770 4554 4546 12771 4546 4552 12772 4552 4555 12773 4555 4552 12774 4552 4505 12775 4505 4533 12776 4533 4552 12777 4552 4556 12778 4556 4505 12779 4505 4552 12780 4552 4534 12781 4534 4556 12782 4556 4552 12783 4552 4557 12784 4557 4534 12785 4534 4546 12786 4546 4557 12787 4557 4552 12788 4552 4546 12789 4546 4558 12790 4558 4557 12791 4557 4546 12792 4546 4544 12793 4544 4558 12794 4558 4546 12795 4546 4559 12796 4559 4544 12797 4544 4560 12798 4560 4559 12799 4559 4546 12800 4546 4562 12801 4562 4559 12802 4559 4560 12803 4560 4562 12804 4562 4561 12805 4561 4559 12806 4559 4564 12807 4564 4561 12808 4561 4562 12809 4562 4564 12810 4564 4563 12811 4563 4561 12812 4561 4566 12813 4566 4563 12814 4563 4564 12815 4564 4566 12816 4566 4565 12817 4565 4563 12818 4563 4568 12819 4568 4565 12820 4565 4566 12821 4566 4568 12822 4568 4567 12823 4567 4565 12824 4565 4570 12825 4570 4567 12826 4567 4568 12827 4568 4570 12828 4570 4569 12829 4569 4567 12830 4567 4572 12831 4572 4569 12832 4569 4570 12833 4570 4572 12834 4572 4571 12835 4571 4569 12836 4569 4574 12837 4574 4571 12838 4571 4572 12839 4572 4574 12840 4574 4573 12841 4573 4571 12842 4571 4515 12843 4515 4573 12844 4573 4574 12845 4574 4576 12846 4576 4573 12847 4573 4515 12848 4515 4576 12849 4576 4575 12850 4575 4573 12851 4573 4576 12852 4576 4516 12853 4516 4575 12854 4575 4578 12855 4578 4516 12856 4516 4576 12857 4576 4578 12858 4578 4577 12859 4577 4516 12860 4516 4580 12861 4580 4577 12862 4577 4578 12863 4578 4580 12864 4580 4579 12865 4579 4577 12866 4577 4582 12867 4582 4579 12868 4579 4580 12869 4580 4582 12870 4582 4581 12871 4581 4579 12872 4579 4584 12873 4584 4581 12874 4581 4582 12875 4582 4584 12876 4584 4583 12877 4583 4581 12878 4581 4586 12879 4586 4583 12880 4583 4584 12881 4584 4586 12882 4586 4585 12883 4585 4583 12884 4583 4588 12885 4588 4585 12886 4585 4586 12887 4586 4588 12888 4588 4587 12889 4587 4585 12890 4585 4590 12891 4590 4587 12892 4587 4588 12893 4588 4590 12894 4590 4589 12895 4589 4587 12896 4587 4521 12897 4521 4589 12898 4589 4590 12899 4590 4592 12900 4592 4589 12901 4589 4521 12902 4521 4592 12903 4592 4591 12904 4591 4589 12905 4589 4604 12906 4604 4591 12907 4591 4592 12908 4592 4604 12909 4604 4593 12910 4593 4591 12911 4591 4603 12912 4603 4594 12913 4594 4511 12914 4511 4596 12915 4596 4595 12916 4595 4507 12917 4507 4596 12918 4596 3962 12919 3962 4595 12920 4595 4480 12921 4480 3962 12922 3962 4596 12923 4596 4597 12924 4597 3962 12925 3962 4480 12926 4480 4599 12927 4599 3962 12928 3962 4597 12929 4597 4599 12930 4599 4598 12931 4598 3962 12932 3962 4594 12933 4594 4598 12934 4598 4599 12935 4599 4598 12936 4598 4501 12937 4501 4537 12938 4537 4598 12939 4598 4600 12940 4600 4501 12941 4501 4598 12942 4598 4526 12943 4526 4600 12944 4600 4598 12945 4598 4601 12946 4601 4526 12947 4526 4593 12948 4593 4514 12949 4514 4602 12950 4602 4593 12951 4593 4603 12952 4603 4514 12953 4514 4593 12954 4593 4594 12955 4594 4603 12956 4603 4604 12957 4604 4594 12958 4594 4593 12959 4593 4539 12960 4539 4594 12961 4594 4604 12962 4604 4539 12963 4539 4598 12964 4598 4594 12965 4594 4539 12966 4539 4601 12967 4601 4598 12968 4598 4886 12969 4886 4882 12970 4882 4605 12971 4605 4845 12972 4845 4606 12973 4606 4632 12974 4632 4623 12975 4623 4607 12976 4607 4609 12977 4609 4609 12978 4609 4608 12979 4608 4623 12980 4623 4634 12981 4634 4608 12982 4608 4609 12983 4609 4648 12984 4648 4612 12985 4612 4610 12986 4610 4648 12987 4648 4611 12988 4611 4612 12989 4612 4626 12990 4626 4610 12991 4610 4612 12992 4612 4841 12993 4841 4613 12994 4613 4633 12995 4633 4627 12996 4627 4614 12997 4614 4628 12998 4628 4628 12999 4628 4615 13000 4615 4627 13001 4627 4618 13002 4618 4616 13003 4616 4629 13004 4629 4629 13005 4629 4617 13006 4617 4618 13007 4618 4643 13008 4643 4616 13009 4616 4618 13010 4618 4639 13011 4639 4621 13012 4621 4619 13013 4619 4639 13014 4639 4620 13015 4620 4621 13016 4621 4641 13017 4641 4619 13018 4619 4621 13019 4621 4641 13020 4641 4622 13021 4622 4619 13022 4619 4670 13023 4670 4607 13024 4607 4623 13025 4623 4670 13026 4670 4624 13027 4624 4607 13028 4607 4626 13029 4626 4625 13030 4625 4610 13031 4610 4638 13032 4638 4625 13033 4625 4626 13034 4626 4660 13035 4660 4614 13036 4614 4627 13037 4627 4663 13038 4663 4615 13039 4615 4628 13040 4628 4664 13041 4664 4617 13042 4617 4629 13043 4629 4663 13044 4663 4630 13045 4630 4615 13046 4615 4664 13047 4664 4631 13048 4631 4617 13049 4617 4666 13050 4666 4845 13051 4845 4632 13052 4632 4667 13053 4667 4841 13054 4841 4633 13055 4633 4647 13056 4647 4608 13057 4608 4634 13058 4634 4648 13059 4648 4635 13060 4635 4611 13061 4611 4845 13062 4845 4636 13063 4636 4606 13064 4606 4670 13065 4670 4637 13066 4637 4624 13067 4624 4673 13068 4673 4625 13069 4625 4638 13070 4638 4676 13071 4676 4620 13072 4620 4639 13073 4639 4676 13074 4676 4640 13075 4640 4620 13076 4620 4678 13077 4678 4622 13078 4622 4641 13079 4641 4678 13080 4678 4642 13081 4642 4622 13082 4622 4669 13083 4669 4616 13084 4616 4643 13085 4643 4669 13086 4669 4644 13087 4644 4616 13088 4616 4660 13089 4660 4645 13090 4645 4614 13091 4614 4647 13092 4647 4646 13093 4646 4608 13094 4608 4650 13095 4650 4646 13096 4646 4647 13097 4647 4646 13098 4646 4635 13099 4635 4648 13100 4648 4650 13101 4650 4635 13102 4635 4646 13103 4646 4650 13104 4650 4649 13105 4649 4635 13106 4635 4652 13107 4652 4649 13108 4649 4650 13109 4650 4652 13110 4652 4651 13111 4651 4649 13112 4649 4654 13113 4654 4651 13114 4651 4652 13115 4652 4654 13116 4654 4653 13117 4653 4651 13118 4651 4656 13119 4656 4653 13120 4653 4654 13121 4654 4656 13122 4656 4655 13123 4655 4653 13124 4653 4658 13125 4658 4655 13126 4655 4656 13127 4656 4658 13128 4658 4657 13129 4657 4655 13130 4655 4674 13131 4674 4657 13132 4657 4658 13133 4658 4674 13134 4674 4659 13135 4659 4657 13136 4657 4765 13137 4765 4645 13138 4645 4660 13139 4660 4841 13140 4841 4661 13141 4661 4613 13142 4613 4663 13143 4663 4662 13144 4662 4630 13145 4630 4766 13146 4766 4662 13147 4662 4663 13148 4663 4762 13149 4762 4631 13150 4631 4664 13151 4664 4762 13152 4762 4665 13153 4665 4631 13154 4631 4715 13155 4715 4845 13156 4845 4666 13157 4666 4739 13158 4739 4841 13159 4841 4667 13160 4667 4845 13161 4845 4668 13162 4668 4636 13163 4636 4769 13164 4769 4644 13165 4644 4669 13166 4669 4782 13167 4782 4637 13168 4637 4670 13169 4670 4782 13170 4782 4671 13171 4671 4637 13172 4637 4673 13173 4673 4672 13174 4672 4625 13175 4625 4712 13176 4712 4672 13177 4672 4673 13178 4673 4774 13179 4774 4659 13180 4659 4674 13181 4674 4774 13182 4774 4675 13183 4675 4659 13184 4659 4776 13185 4776 4640 13186 4640 4676 13187 4676 4776 13188 4776 4677 13189 4677 4640 13190 4640 4778 13191 4778 4642 13192 4642 4678 13193 4678 4778 13194 4778 4679 13195 4679 4642 13196 4642 4762 13197 4762 4680 13198 4680 4665 13199 4665 4766 13200 4766 4681 13201 4681 4662 13202 4662 4766 13203 4766 4682 13204 4682 4681 13205 4681 4766 13206 4766 4683 13207 4683 4682 13208 4682 4766 13209 4766 4684 13210 4684 4683 13211 4683 4766 13212 4766 4685 13213 4685 4684 13214 4684 4766 13215 4766 4686 13216 4686 4685 13217 4685 4766 13218 4766 4687 13219 4687 4686 13220 4686 4766 13221 4766 4688 13222 4688 4687 13223 4687 4766 13224 4766 4689 13225 4689 4688 13226 4688 4766 13227 4766 4690 13228 4690 4689 13229 4689 4766 13230 4766 4691 13231 4691 4690 13232 4690 4766 13233 4766 4692 13234 4692 4691 13235 4691 4766 13236 4766 4693 13237 4693 4692 13238 4692 4766 13239 4766 4694 13240 4694 4693 13241 4693 4766 13242 4766 4695 13243 4695 4694 13244 4694 4766 13245 4766 4696 13246 4696 4695 13247 4695 4762 13248 4762 4697 13249 4697 4680 13250 4680 4762 13251 4762 4698 13252 4698 4697 13253 4697 4762 13254 4762 4699 13255 4699 4698 13256 4698 4762 13257 4762 4700 13258 4700 4699 13259 4699 4762 13260 4762 4701 13261 4701 4700 13262 4700 4762 13263 4762 4702 13264 4702 4701 13265 4701 4762 13266 4762 4703 13267 4703 4702 13268 4702 4762 13269 4762 4704 13270 4704 4703 13271 4703 4762 13272 4762 4705 13273 4705 4704 13274 4704 4762 13275 4762 4706 13276 4706 4705 13277 4705 4762 13278 4762 4707 13279 4707 4706 13280 4706 4762 13281 4762 4708 13282 4708 4707 13283 4707 4762 13284 4762 4709 13285 4709 4708 13286 4708 4762 13287 4762 4710 13288 4710 4709 13289 4709 4782 13290 4782 4711 13291 4711 4671 13292 4671 4785 13293 4785 4672 13294 4672 4712 13295 4712 4715 13296 4715 4713 13297 4713 4845 13298 4845 4715 13299 4715 4714 13300 4714 4713 13301 4713 4721 13302 4721 4714 13303 4714 4715 13304 4715 4721 13305 4721 4716 13306 4716 4714 13307 4714 4721 13308 4721 4717 13309 4717 4716 13310 4716 4721 13311 4721 4718 13312 4718 4717 13313 4717 4721 13314 4721 4719 13315 4719 4718 13316 4718 4721 13317 4721 4720 13318 4720 4719 13319 4719 4728 13320 4728 4720 13321 4720 4721 13322 4721 4728 13323 4728 4722 13324 4722 4720 13325 4720 4728 13326 4728 4723 13327 4723 4722 13328 4722 4728 13329 4728 4724 13330 4724 4723 13331 4723 4728 13332 4728 4725 13333 4725 4724 13334 4724 4728 13335 4728 4726 13336 4726 4725 13337 4725 4728 13338 4728 4727 13339 4727 4726 13340 4726 4732 13341 4732 4727 13342 4727 4728 13343 4728 4732 13344 4732 4729 13345 4729 4727 13346 4727 4732 13347 4732 4730 13348 4730 4729 13349 4729 4732 13350 4732 4731 13351 4731 4730 13352 4730 4733 13353 4733 4731 13354 4731 4732 13355 4732 4734 13356 4734 4731 13357 4731 4733 13358 4733 4735 13359 4735 4731 13360 4731 4734 13361 4734 4736 13362 4736 4731 13363 4731 4735 13364 4735 4772 13365 4772 4731 13366 4731 4736 13367 4736 4739 13368 4739 4737 13369 4737 4841 13370 4841 4739 13371 4739 4738 13372 4738 4737 13373 4737 4745 13374 4745 4738 13375 4738 4739 13376 4739 4745 13377 4745 4740 13378 4740 4738 13379 4738 4745 13380 4745 4741 13381 4741 4740 13382 4740 4745 13383 4745 4742 13384 4742 4741 13385 4741 4745 13386 4745 4743 13387 4743 4742 13388 4742 4745 13389 4745 4744 13390 4744 4743 13391 4743 4752 13392 4752 4744 13393 4744 4745 13394 4745 4752 13395 4752 4746 13396 4746 4744 13397 4744 4752 13398 4752 4747 13399 4747 4746 13400 4746 4752 13401 4752 4748 13402 4748 4747 13403 4747 4752 13404 4752 4749 13405 4749 4748 13406 4748 4752 13407 4752 4750 13408 4750 4749 13409 4749 4752 13410 4752 4751 13411 4751 4750 13412 4750 4756 13413 4756 4751 13414 4751 4752 13415 4752 4756 13416 4756 4753 13417 4753 4751 13418 4751 4756 13419 4756 4754 13420 4754 4753 13421 4753 4756 13422 4756 4755 13423 4755 4754 13424 4754 4757 13425 4757 4755 13426 4755 4756 13427 4756 4758 13428 4758 4755 13429 4755 4757 13430 4757 4759 13431 4759 4755 13432 4755 4758 13433 4758 4760 13434 4760 4755 13435 4755 4759 13436 4759 4761 13437 4761 4755 13438 4755 4760 13439 4760 4770 13440 4770 4755 13441 4755 4761 13442 4761 4788 13443 4788 4710 13444 4710 4762 13445 4762 4788 13446 4788 4763 13447 4763 4710 13448 4710 4765 13449 4765 4764 13450 4764 4645 13451 4645 4791 13452 4791 4764 13453 4764 4765 13454 4765 4792 13455 4792 4696 13456 4696 4766 13457 4766 4792 13458 4792 4767 13459 4767 4696 13460 4696 4769 13461 4769 4768 13462 4768 4644 13463 4644 4781 13464 4781 4768 13465 4768 4769 13466 4769 4786 13467 4786 4755 13468 4755 4770 13469 4770 4845 13470 4845 4771 13471 4771 4668 13472 4668 4804 13473 4804 4731 13474 4731 4772 13475 4772 4841 13476 4841 4773 13477 4773 4661 13478 4661 4796 13479 4796 4675 13480 4675 4774 13481 4774 4796 13482 4796 4775 13483 4775 4675 13484 4675 4798 13485 4798 4677 13486 4677 4776 13487 4776 4798 13488 4798 4777 13489 4777 4677 13490 4677 4800 13491 4800 4679 13492 4679 4778 13493 4778 4800 13494 4800 4779 13495 4779 4679 13496 4679 4792 13497 4792 4780 13498 4780 4767 13499 4767 4795 13500 4795 4768 13501 4768 4781 13502 4781 4810 13503 4810 4711 13504 4711 4782 13505 4782 4810 13506 4810 4783 13507 4783 4711 13508 4711 4785 13509 4785 4784 13510 4784 4672 13511 4672 4803 13512 4803 4784 13513 4784 4785 13514 4785 4812 13515 4812 4755 13516 4755 4786 13517 4786 4845 13518 4845 4787 13519 4787 4771 13520 4771 4805 13521 4805 4763 13522 4763 4788 13523 4788 4805 13524 4805 4789 13525 4789 4763 13526 4763 4791 13527 4791 4790 13528 4790 4764 13529 4764 4806 13530 4806 4790 13531 4790 4791 13532 4791 4813 13533 4813 4780 13534 4780 4792 13535 4792 4795 13536 4795 4793 13537 4793 4768 13538 4768 4813 13539 4813 4794 13540 4794 4780 13541 4780 4815 13542 4815 4793 13543 4793 4795 13544 4795 4820 13545 4820 4775 13546 4775 4796 13547 4796 4820 13548 4820 4797 13549 4797 4775 13550 4775 4822 13551 4822 4777 13552 4777 4798 13553 4798 4822 13554 4822 4799 13555 4799 4777 13556 4777 4824 13557 4824 4779 13558 4779 4800 13559 4800 4824 13560 4824 4801 13561 4801 4779 13562 4779 4810 13563 4810 4802 13564 4802 4783 13565 4783 4818 13566 4818 4784 13567 4784 4803 13568 4803 4789 13569 4789 4731 13570 4731 4804 13571 4804 4805 13572 4805 4731 13573 4731 4789 13574 4789 4809 13575 4809 4731 13576 4731 4805 13577 4805 4841 13578 4841 4806 13579 4806 4773 13580 4773 4841 13581 4841 4790 13582 4790 4806 13583 4806 4841 13584 4841 4807 13585 4807 4790 13586 4790 4841 13587 4841 4808 13588 4808 4807 13589 4807 4826 13590 4826 4731 13591 4731 4809 13592 4809 4832 13593 4832 4802 13594 4802 4810 13595 4810 4818 13596 4818 4811 13597 4811 4784 13598 4784 4794 13599 4794 4755 13600 4755 4812 13601 4812 4813 13602 4813 4755 13603 4755 4794 13604 4794 4814 13605 4814 4755 13606 4755 4813 13607 4813 4828 13608 4828 4755 13609 4755 4814 13610 4814 4845 13611 4845 4815 13612 4815 4787 13613 4787 4845 13614 4845 4793 13615 4793 4815 13616 4815 4845 13617 4845 4816 13618 4816 4793 13619 4793 4845 13620 4845 4817 13621 4817 4816 13622 4816 4834 13623 4834 4811 13624 4811 4818 13625 4818 4832 13626 4832 4819 13627 4819 4802 13628 4802 4831 13629 4831 4797 13630 4797 4820 13631 4820 4831 13632 4831 4821 13633 4821 4797 13634 4797 4836 13635 4836 4799 13636 4799 4822 13637 4822 4836 13638 4836 4823 13639 4823 4799 13640 4799 4838 13641 4838 4801 13642 4801 4824 13643 4824 4838 13644 4838 4825 13645 4825 4801 13646 4801 4840 13647 4840 4731 13648 4731 4826 13649 4826 4841 13650 4841 4827 13651 4827 4808 13652 4808 4844 13653 4844 4755 13654 4755 4828 13655 4828 4845 13656 4845 4829 13657 4829 4817 13658 4817 4832 13659 4832 4830 13660 4830 4819 13661 4819 4854 13662 4854 4821 13663 4821 4831 13664 4831 4858 13665 4858 4830 13666 4830 4832 13667 4832 4854 13668 4854 4833 13669 4833 4821 13670 4821 4849 13671 4849 4811 13672 4811 4834 13673 4834 4849 13674 4849 4835 13675 4835 4811 13676 4811 4855 13677 4855 4823 13678 4823 4836 13679 4836 4855 13680 4855 4837 13681 4837 4823 13682 4823 4856 13683 4856 4825 13684 4825 4838 13685 4838 4856 13686 4856 4839 13687 4839 4825 13688 4825 4842 13689 4842 4731 13690 4731 4840 13691 4840 4842 13692 4842 4841 13693 4841 4731 13694 4731 4835 13695 4835 4841 13696 4841 4842 13697 4842 4841 13698 4841 4843 13699 4843 4827 13700 4827 4846 13701 4846 4755 13702 4755 4844 13703 4844 4846 13704 4846 4845 13705 4845 4755 13706 4755 4839 13707 4839 4845 13708 4845 4846 13709 4846 4845 13710 4845 4847 13711 4847 4829 13712 4829 4858 13713 4858 4848 13714 4848 4830 13715 4830 4850 13716 4850 4835 13717 4835 4849 13718 4849 4850 13719 4850 4841 13720 4841 4835 13721 4835 4851 13722 4851 4841 13723 4841 4850 13724 4850 4852 13725 4852 4841 13726 4841 4851 13727 4851 4853 13728 4853 4841 13729 4841 4852 13730 4852 4882 13731 4882 4841 13732 4841 4853 13733 4853 4872 13734 4872 4833 13735 4833 4854 13736 4854 4843 13737 4843 4837 13738 4837 4855 13739 4855 4857 13740 4857 4839 13741 4839 4856 13742 4856 4857 13743 4857 4845 13744 4845 4839 13745 4839 4857 13746 4857 4847 13747 4847 4845 13748 4845 4860 13749 4860 4847 13750 4847 4857 13751 4857 4860 13752 4860 4858 13753 4858 4847 13754 4847 4860 13755 4860 4848 13756 4848 4858 13757 4858 4860 13758 4860 4859 13759 4859 4848 13760 4848 4862 13761 4862 4859 13762 4859 4860 13763 4860 4862 13764 4862 4861 13765 4861 4859 13766 4859 4865 13767 4865 4861 13768 4861 4862 13769 4862 4865 13770 4865 4863 13771 4863 4861 13772 4861 4865 13773 4865 4864 13774 4864 4863 13775 4863 4867 13776 4867 4864 13777 4864 4865 13778 4865 4867 13779 4867 4866 13780 4866 4864 13781 4864 4869 13782 4869 4866 13783 4866 4867 13784 4867 4869 13785 4869 4868 13786 4868 4866 13787 4866 4871 13788 4871 4868 13789 4868 4869 13790 4869 4871 13791 4871 4870 13792 4870 4868 13793 4868 4873 13794 4873 4870 13795 4870 4871 13796 4871 4873 13797 4873 4872 13798 4872 4870 13799 4870 4873 13800 4873 4833 13801 4833 4872 13802 4872 4874 13803 4874 4833 13804 4833 4873 13805 4873 4876 13806 4876 4833 13807 4833 4874 13808 4874 4876 13809 4876 4875 13810 4875 4833 13811 4833 4879 13812 4879 4875 13813 4875 4876 13814 4876 4879 13815 4879 4877 13816 4877 4875 13817 4875 4879 13818 4879 4878 13819 4878 4877 13820 4877 4881 13821 4881 4878 13822 4878 4879 13823 4879 4881 13824 4881 4880 13825 4880 4878 13826 4878 4883 13827 4883 4880 13828 4880 4881 13829 4881 4883 13830 4883 4882 13831 4882 4880 13832 4880 4884 13833 4884 4882 13834 4882 4883 13835 4883 4885 13836 4885 4882 13837 4882 4884 13838 4884 4605 13839 4605 4882 13840 4882 4885 13841 4885 4843 13842 4843 4886 13843 4886 4837 13844 4837 4841 13845 4841 4886 13846 4886 4843 13847 4843 4882 13848 4882 4886 13849 4886 4841 13850 4841 4961 13851 4961 4926 13852 4926 4887 13853 4887 4889 13854 4889 4888 13855 4888 4890 13856 4890 4909 13857 4909 4888 13858 4888 4889 13859 4889 4892 13860 4892 4889 13861 4889 4890 13862 4890 4892 13863 4892 4891 13864 4891 4889 13865 4889 4894 13866 4894 4891 13867 4891 4892 13868 4892 4894 13869 4894 4893 13870 4893 4891 13871 4891 4896 13872 4896 4893 13873 4893 4894 13874 4894 4896 13875 4896 4895 13876 4895 4893 13877 4893 4898 13878 4898 4895 13879 4895 4896 13880 4896 4898 13881 4898 4897 13882 4897 4895 13883 4895 4900 13884 4900 4897 13885 4897 4898 13886 4898 4900 13887 4900 4899 13888 4899 4897 13889 4897 4902 13890 4902 4899 13891 4899 4900 13892 4900 4902 13893 4902 4901 13894 4901 4899 13895 4899 4904 13896 4904 4901 13897 4901 4902 13898 4902 4904 13899 4904 4903 13900 4903 4901 13901 4901 4906 13902 4906 4903 13903 4903 4904 13904 4904 4906 13905 4906 4905 13906 4905 4903 13907 4903 4910 13908 4910 4905 13909 4905 4906 13910 4906 4910 13911 4910 4907 13912 4907 4905 13913 4905 4909 13914 4909 4908 13915 4908 4888 13916 4888 4916 13917 4916 4908 13918 4908 4909 13919 4909 4913 13920 4913 4907 13921 4907 4910 13922 4910 4913 13923 4913 4911 13924 4911 4907 13925 4907 4913 13926 4913 4912 13927 4912 4911 13928 4911 4919 13929 4919 4912 13930 4912 4913 13931 4913 4919 13932 4919 4914 13933 4914 4912 13934 4912 4916 13935 4916 4915 13936 4915 4908 13937 4908 4918 13938 4918 4915 13939 4915 4916 13940 4916 4918 13941 4918 4917 13942 4917 4915 13943 4915 4925 13944 4925 4917 13945 4917 4918 13946 4918 4922 13947 4922 4914 13948 4914 4919 13949 4919 4922 13950 4922 4920 13951 4920 4914 13952 4914 4922 13953 4922 4921 13954 4921 4920 13955 4920 4927 13956 4927 4921 13957 4921 4922 13958 4922 4927 13959 4927 4923 13960 4923 4921 13961 4921 4925 13962 4925 4924 13963 4924 4917 13964 4917 4887 13965 4887 4924 13966 4924 4925 13967 4925 4887 13968 4887 4926 13969 4926 4924 13970 4924 4929 13971 4929 4923 13972 4923 4927 13973 4927 4929 13974 4929 4928 13975 4928 4923 13976 4923 4931 13977 4931 4928 13978 4928 4929 13979 4929 4931 13980 4931 4930 13981 4930 4928 13982 4928 4933 13983 4933 4930 13984 4930 4931 13985 4931 4933 13986 4933 4932 13987 4932 4930 13988 4930 4935 13989 4935 4932 13990 4932 4933 13991 4933 4935 13992 4935 4934 13993 4934 4932 13994 4932 4937 13995 4937 4934 13996 4934 4935 13997 4935 4937 13998 4937 4936 13999 4936 4934 14000 4934 4938 14001 4938 4936 14002 4936 4937 14003 4937 4940 14004 4940 4936 14005 4936 4938 14006 4938 4940 14007 4940 4939 14008 4939 4936 14009 4936 4942 14010 4942 4939 14011 4939 4940 14012 4940 4942 14013 4942 4941 14014 4941 4939 14015 4939 4943 14016 4943 4941 14017 4941 4942 14018 4942 4945 14019 4945 4941 14020 4941 4943 14021 4943 4945 14022 4945 4944 14023 4944 4941 14024 4941 4947 14025 4947 4944 14026 4944 4945 14027 4945 4947 14028 4947 4946 14029 4946 4944 14030 4944 4962 14031 4962 4946 14032 4946 4947 14033 4947 4962 14034 4962 4948 14035 4948 4946 14036 4946 4962 14037 4962 4949 14038 4949 4948 14039 4948 4962 14040 4962 4950 14041 4950 4949 14042 4949 4962 14043 4962 4951 14044 4951 4950 14045 4950 4962 14046 4962 4952 14047 4952 4951 14048 4951 4962 14049 4962 4953 14050 4953 4952 14051 4952 4962 14052 4962 4954 14053 4954 4953 14054 4953 4962 14055 4962 4955 14056 4955 4954 14057 4954 4962 14058 4962 4956 14059 4956 4955 14060 4955 4962 14061 4962 4957 14062 4957 4956 14063 4956 4962 14064 4962 4958 14065 4958 4957 14066 4957 4962 14067 4962 4959 14068 4959 4958 14069 4958 4962 14070 4962 4960 14071 4960 4959 14072 4959 4962 14073 4962 4961 14074 4961 4960 14075 4960 4926 14076 4926 4961 14077 4961 4962 14078 4962 4988 14079 4988 4989 14080 4989 4963 14081 4963 4966 14082 4966 4964 14083 4964 4965 14084 4965 4967 14085 4967 4964 14086 4964 4966 14087 4966 4974 14088 4974 4964 14089 4964 4967 14090 4967 4994 14091 4994 4968 14092 4968 4969 14093 4969 4994 14094 4994 4970 14095 4970 4968 14096 4968 4994 14097 4994 4971 14098 4971 4970 14099 4970 4994 14100 4994 4972 14101 4972 4971 14102 4971 4994 14103 4994 4973 14104 4973 4972 14105 4972 4976 14106 4976 4964 14107 4964 4974 14108 4974 4976 14109 4976 4975 14110 4975 4964 14111 4964 4981 14112 4981 4975 14113 4975 4976 14114 4976 4979 14115 4979 4977 14116 4977 4978 14117 4978 4963 14118 4963 4977 14119 4977 4979 14120 4979 4963 14121 4963 4980 14122 4980 4977 14123 4977 4983 14124 4983 4975 14125 4975 4981 14126 4981 4983 14127 4983 4982 14128 4982 4975 14129 4975 4985 14130 4985 4982 14131 4982 4983 14132 4983 4985 14133 4985 4984 14134 4984 4982 14135 4982 4986 14136 4986 4984 14137 4984 4985 14138 4985 4991 14139 4991 4984 14140 4984 4986 14141 4986 4991 14142 4991 4987 14143 4987 4984 14144 4984 4994 14145 4994 4988 14146 4988 4973 14147 4973 4963 14148 4963 4989 14149 4989 4980 14150 4980 4991 14151 4991 4990 14152 4990 4987 14153 4987 4993 14154 4993 4990 14155 4990 4991 14156 4991 4993 14157 4993 4992 14158 4992 4990 14159 4990 4995 14160 4995 4992 14161 4992 4993 14162 4993 4995 14163 4995 4994 14164 4994 4992 14165 4992 4995 14166 4995 4988 14167 4988 4994 14168 4994 4996 14169 4996 4988 14170 4988 4995 14171 4995 4989 14172 4989 4988 14173 4988 4996 14174 4996 5029 14175 5029 5013 14176 5013 4997 14177 4997 5000 14178 5000 4998 14179 4998 4999 14180 4999 5015 14181 5015 4998 14182 4998 5000 14183 5000 5004 14184 5004 5001 14185 5001 5002 14186 5002 5004 14187 5004 5003 14188 5003 5001 14189 5001 5006 14190 5006 5003 14191 5003 5004 14192 5004 5006 14193 5006 5005 14194 5005 5003 14195 5003 5009 14196 5009 5005 14197 5005 5006 14198 5006 5009 14199 5009 5007 14200 5007 5005 14201 5005 5009 14202 5009 5008 14203 5008 5007 14204 5007 5010 14205 5010 5008 14206 5008 5009 14207 5009 5012 14208 5012 5008 14209 5008 5010 14210 5010 5012 14211 5012 5011 14212 5011 5008 14213 5008 4997 14214 4997 5011 14215 5011 5012 14216 5012 4997 14217 4997 5013 14218 5013 5011 14219 5011 5015 14220 5015 5014 14221 5014 4998 14222 4998 5017 14223 5017 5014 14224 5014 5015 14225 5015 5017 14226 5017 5016 14227 5016 5014 14228 5014 5019 14229 5019 5016 14230 5016 5017 14231 5017 5019 14232 5019 5018 14233 5018 5016 14234 5016 5020 14235 5020 5018 14236 5018 5019 14237 5019 5022 14238 5022 5018 14239 5018 5020 14240 5020 5022 14241 5022 5021 14242 5021 5018 14243 5018 5024 14244 5024 5021 14245 5021 5022 14246 5022 5024 14247 5024 5023 14248 5023 5021 14249 5021 5027 14250 5027 5023 14251 5023 5024 14252 5024 5027 14253 5027 5025 14254 5025 5023 14255 5023 5027 14256 5027 5026 14257 5026 5025 14258 5025 5028 14259 5028 5026 14260 5026 5027 14261 5027 5030 14262 5030 5026 14263 5026 5028 14264 5028 5030 14265 5030 5029 14266 5029 5026 14267 5026 5013 14268 5013 5029 14269 5029 5030 14270 5030 5046 14271 5046 5039 14272 5039 5031 14273 5031 5035 14274 5035 5032 14275 5032 5033 14276 5033 5035 14277 5035 5034 14278 5034 5032 14279 5032 5037 14280 5037 5034 14281 5034 5035 14282 5035 5037 14283 5037 5036 14284 5036 5034 14285 5034 5040 14286 5040 5036 14287 5036 5037 14288 5037 5040 14289 5040 5038 14290 5038 5036 14291 5036 5040 14292 5040 5039 14293 5039 5038 14294 5038 5031 14295 5031 5039 14296 5039 5040 14297 5040 5043 14298 5043 5041 14299 5041 5042 14300 5042 5045 14301 5045 5041 14302 5041 5043 14303 5043 5045 14304 5045 5044 14305 5044 5041 14306 5041 5047 14307 5047 5044 14308 5044 5045 14309 5045 5047 14310 5047 5046 14311 5046 5044 14312 5044 5048 14313 5048 5046 14314 5046 5047 14315 5047 5039 14316 5039 5046 14317 5046 5048 14318 5048 5084 14319 5084 5049 14320 5049 5050 14321 5050 5053 14322 5053 5051 14323 5051 5052 14324 5052 5078 14325 5078 5051 14326 5051 5053 14327 5053 5056 14328 5056 5054 14329 5054 5055 14330 5055 5077 14331 5077 5054 14332 5054 5056 14333 5056 5059 14334 5059 5057 14335 5057 5058 14336 5058 5074 14337 5074 5057 14338 5057 5059 14339 5059 5062 14340 5062 5060 14341 5060 5061 14342 5061 5081 14343 5081 5060 14344 5060 5062 14345 5062 5080 14346 5080 5063 14347 5063 5064 14348 5064 5080 14349 5080 5065 14350 5065 5063 14351 5063 5079 14352 5079 5066 14353 5066 5067 14354 5067 5079 14355 5079 5068 14356 5068 5066 14357 5066 5076 14358 5076 5069 14359 5069 5070 14360 5070 5076 14361 5076 5071 14362 5071 5069 14363 5069 5075 14364 5075 5072 14365 5072 5073 14366 5073 5075 14367 5075 5074 14368 5074 5072 14369 5072 5075 14370 5075 5057 14371 5057 5074 14372 5074 5071 14373 5071 5057 14374 5057 5075 14375 5075 5076 14376 5076 5057 14377 5057 5071 14378 5071 5054 14379 5054 5057 14380 5057 5076 14381 5076 5077 14382 5077 5057 14383 5057 5054 14384 5054 5051 14385 5051 5057 14386 5057 5077 14387 5077 5078 14388 5078 5057 14389 5057 5051 14390 5051 5068 14391 5068 5057 14392 5057 5078 14393 5078 5079 14394 5079 5057 14395 5057 5068 14396 5068 5065 14397 5065 5057 14398 5057 5079 14399 5079 5080 14400 5080 5057 14401 5057 5065 14402 5065 5060 14403 5060 5057 14404 5057 5080 14405 5080 5081 14406 5081 5057 14407 5057 5060 14408 5060 5049 14409 5049 5057 14410 5057 5081 14411 5081 5057 14412 5057 5082 14413 5082 5083 14414 5083 5049 14415 5049 5082 14416 5082 5057 14417 5057 5049 14418 5049 5084 14419 5084 5082 14420 5082 5103 14421 5103 5085 14422 5085 5101 14423 5101 5088 14424 5088 5086 14425 5086 5087 14426 5087 5090 14427 5090 5086 14428 5086 5088 14429 5088 5090 14430 5090 5089 14431 5089 5086 14432 5086 5092 14433 5092 5089 14434 5089 5090 14435 5090 5092 14436 5092 5091 14437 5091 5089 14438 5089 5094 14439 5094 5091 14440 5091 5092 14441 5092 5094 14442 5094 5093 14443 5093 5091 14444 5091 5096 14445 5096 5093 14446 5093 5094 14447 5094 5096 14448 5096 5095 14449 5095 5093 14450 5093 5098 14451 5098 5095 14452 5095 5096 14453 5096 5098 14454 5098 5097 14455 5097 5095 14456 5095 5100 14457 5100 5097 14458 5097 5098 14459 5098 5100 14460 5100 5099 14461 5099 5097 14462 5097 5102 14463 5102 5099 14464 5099 5100 14465 5100 5102 14466 5102 5101 14467 5101 5099 14468 5099 5103 14469 5103 5101 14470 5101 5102 14471 5102 5085 14472 5085 5103 14473 5103 5104 14474 5104 5109 14475 5109 5105 14476 5105 5106 14477 5106 5110 14478 5110 5107 14479 5107 5108 14480 5108 5110 14481 5110 5109 14482 5109 5107 14483 5107 5105 14484 5105 5109 14485 5109 5110 14486 5110 5118 14487 5118 5114 14488 5114 5111 14489 5111 5115 14490 5115 5112 14491 5112 5113 14492 5113 5115 14493 5115 5114 14494 5114 5112 14495 5112 5111 14496 5111 5114 14497 5114 5115 14498 5115 5114 14499 5114 5116 14500 5116 5117 14501 5117 5114 14502 5114 5118 14503 5118 5116 14504 5116 5121 14505 5121 5119 14506 5119 5120 14507 5120 5119 14508 5119 5121 14509 5121 5122 14510 5122 5125 14511 5125 5123 14512 5123 5124 14513 5124 5123 14514 5123 5125 14515 5125 5126 14516 5126 5155 14517 5155 5145 14518 5145 5127 14519 5127 5132 14520 5132 5128 14521 5128 5129 14522 5129 5132 14523 5132 5130 14524 5130 5128 14525 5128 5132 14526 5132 5131 14527 5131 5130 14528 5130 5135 14529 5135 5131 14530 5131 5132 14531 5132 5135 14532 5135 5133 14533 5133 5131 14534 5131 5135 14535 5135 5134 14536 5134 5133 14537 5133 5144 14538 5144 5134 14539 5134 5135 14540 5135 5144 14541 5144 5136 14542 5136 5134 14543 5134 5139 14544 5139 5137 14545 5137 5138 14546 5138 5140 14547 5140 5137 14548 5137 5139 14549 5139 5141 14550 5141 5137 14551 5137 5140 14552 5140 5142 14553 5142 5137 14554 5137 5141 14555 5141 5156 14556 5156 5137 14557 5137 5142 14558 5142 5144 14559 5144 5143 14560 5143 5136 14561 5136 5148 14562 5148 5143 14563 5143 5144 14564 5144 5147 14565 5147 5145 14566 5145 5146 14567 5146 5127 14568 5127 5145 14569 5145 5147 14570 5147 5150 14571 5150 5143 14572 5143 5148 14573 5148 5150 14574 5150 5149 14575 5149 5143 14576 5143 5152 14577 5152 5149 14578 5149 5150 14579 5150 5152 14580 5152 5151 14581 5151 5149 14582 5149 5154 14583 5154 5151 14584 5151 5152 14585 5152 5154 14586 5154 5153 14587 5153 5151 14588 5151 5137 14589 5137 5153 14590 5153 5154 14591 5154 5156 14592 5156 5153 14593 5153 5137 14594 5137 5156 14595 5156 5155 14596 5155 5153 14597 5153 5145 14598 5145 5155 14599 5155 5156 14600 5156 5190 14601 5190 5157 14602 5157 5158 14603 5158 5189 14604 5189 5159 14605 5159 5160 14606 5160 5189 14607 5189 5161 14608 5161 5159 14609 5159 5164 14610 5164 5162 14611 5162 5163 14612 5163 5187 14613 5187 5162 14614 5162 5164 14615 5164 5186 14616 5186 5165 14617 5165 5166 14618 5166 5186 14619 5186 5167 14620 5167 5165 14621 5165 5184 14622 5184 5168 14623 5168 5169 14624 5169 5184 14625 5184 5170 14626 5170 5168 14627 5168 5173 14628 5173 5171 14629 5171 5172 14630 5172 5182 14631 5182 5171 14632 5171 5173 14633 5173 5188 14634 5188 5174 14635 5174 5175 14636 5175 5188 14637 5188 5176 14638 5176 5174 14639 5174 5185 14640 5185 5177 14641 5177 5178 14642 5178 5185 14643 5185 5179 14644 5179 5177 14645 5177 5183 14646 5183 5180 14647 5180 5181 14648 5181 5183 14649 5183 5182 14650 5182 5180 14651 5180 5183 14652 5183 5171 14653 5171 5182 14654 5182 5170 14655 5170 5171 14656 5171 5183 14657 5183 5184 14658 5184 5171 14659 5171 5170 14660 5170 5179 14661 5179 5171 14662 5171 5184 14663 5184 5185 14664 5185 5171 14665 5171 5179 14666 5179 5167 14667 5167 5171 14668 5171 5185 14669 5185 5186 14670 5186 5171 14671 5171 5167 14672 5167 5162 14673 5162 5171 14674 5171 5186 14675 5186 5187 14676 5187 5171 14677 5171 5162 14678 5162 5176 14679 5176 5171 14680 5171 5187 14681 5187 5188 14682 5188 5171 14683 5171 5176 14684 5176 5161 14685 5161 5171 14686 5171 5188 14687 5188 5189 14688 5189 5171 14689 5171 5161 14690 5161 5192 14691 5192 5171 14692 5171 5189 14693 5189 5171 14694 5171 5190 14695 5190 5191 14696 5191 5192 14697 5192 5190 14698 5190 5171 14699 5171 5157 14700 5157 5190 14701 5190 5192 14702 5192 5211 14703 5211 5210 14704 5210 5193 14705 5193 5197 14706 5197 5194 14707 5194 5195 14708 5195 5197 14709 5197 5196 14710 5196 5194 14711 5194 5199 14712 5199 5196 14713 5196 5197 14714 5197 5199 14715 5199 5198 14716 5198 5196 14717 5196 5201 14718 5201 5198 14719 5198 5199 14720 5199 5201 14721 5201 5200 14722 5200 5198 14723 5198 5203 14724 5203 5200 14725 5200 5201 14726 5201 5203 14727 5203 5202 14728 5202 5200 14729 5200 5205 14730 5205 5202 14731 5202 5203 14732 5203 5205 14733 5205 5204 14734 5204 5202 14735 5202 5207 14736 5207 5204 14737 5204 5205 14738 5205 5207 14739 5207 5206 14740 5206 5204 14741 5204 5209 14742 5209 5206 14743 5206 5207 14744 5207 5209 14745 5209 5208 14746 5208 5206 14747 5206 5193 14748 5193 5208 14749 5208 5209 14750 5209 5193 14751 5193 5210 14752 5210 5208 14753 5208 5210 14754 5210 5211 14755 5211 5212 14756 5212 5217 14757 5217 5213 14758 5213 5214 14759 5214 5218 14760 5218 5215 14761 5215 5216 14762 5216 5218 14763 5218 5217 14764 5217 5215 14765 5215 5213 14766 5213 5217 14767 5217 5218 14768 5218 5225 14769 5225 5219 14770 5219 5220 14771 5220 5223 14772 5223 5221 14773 5221 5222 14774 5222 5224 14775 5224 5221 14776 5221 5223 14777 5223 5226 14778 5226 5221 14779 5221 5224 14780 5224 5226 14781 5226 5225 14782 5225 5221 14783 5221 5219 14784 5219 5225 14785 5225 5226 14786 5226 5229 14787 5229 5227 14788 5227 5228 14789 5228 5227 14790 5227 5229 14791 5229 5230 14792 5230 5233 14793 5233 5231 14794 5231 5232 14795 5232 5231 14796 5231 5233 14797 5233 5234 14798 5234 5250 14799 5250 5236 14800 5236 5235 14801 5235 5238 14802 5238 5236 14803 5236 5237 14804 5237 5235 14805 5235 5236 14806 5236 5238 14807 5238 5242 14808 5242 5239 14809 5239 5240 14810 5240 5242 14811 5242 5241 14812 5241 5239 14813 5239 5244 14814 5244 5241 14815 5241 5242 14816 5242 5244 14817 5244 5243 14818 5243 5241 14819 5241 5247 14820 5247 5243 14821 5243 5244 14822 5244 5247 14823 5247 5245 14824 5245 5243 14825 5243 5247 14826 5247 5246 14827 5246 5245 14828 5245 5249 14829 5249 5246 14830 5246 5247 14831 5247 5249 14832 5249 5248 14833 5248 5246 14834 5246 5251 14835 5251 5248 14836 5248 5249 14837 5249 5251 14838 5251 5250 14839 5250 5248 14840 5248 5252 14841 5252 5250 14842 5250 5251 14843 5251 5236 14844 5236 5250 14845 5250 5252 14846 5252 5275 14847 5275 5269 14848 5269 5265 14849 5265 5257 14850 5257 5253 14851 5253 5254 14852 5254 5276 14853 5276 5266 14854 5266 5277 14855 5277 5276 14856 5276 5255 14857 5255 5266 14858 5266 5278 14859 5278 5255 14860 5255 5276 14861 5276 5278 14862 5278 5256 14863 5256 5255 14864 5255 5279 14865 5279 5256 14866 5256 5278 14867 5278 5279 14868 5279 5257 14869 5257 5256 14870 5256 5279 14871 5279 5253 14872 5253 5257 14873 5257 5280 14874 5280 5253 14875 5253 5279 14876 5279 5280 14877 5280 5258 14878 5258 5253 14879 5253 5281 14880 5281 5258 14881 5258 5280 14882 5280 5281 14883 5281 5259 14884 5259 5258 14885 5258 5282 14886 5282 5259 14887 5259 5281 14888 5281 5282 14889 5282 5260 14890 5260 5259 14891 5259 5282 14892 5282 5261 14893 5261 5260 14894 5260 5283 14895 5283 5261 14896 5261 5282 14897 5282 5283 14898 5283 5262 14899 5262 5261 14900 5261 5284 14901 5284 5262 14902 5262 5283 14903 5283 5285 14904 5285 5262 14905 5262 5284 14906 5284 5285 14907 5285 5263 14908 5263 5262 14909 5262 5286 14910 5286 5263 14911 5263 5285 14912 5285 5286 14913 5286 5264 14914 5264 5263 14915 5263 5275 14916 5275 5264 14917 5264 5286 14918 5286 5275 14919 5275 5265 14920 5265 5264 14921 5264 5267 14922 5267 5277 14923 5277 5266 14924 5266 5267 14925 5267 5287 14926 5287 5277 14927 5277 5267 14928 5267 5288 14929 5288 5287 14930 5287 5268 14931 5268 5288 14932 5288 5267 14933 5267 5268 14934 5268 5289 14935 5289 5288 14936 5288 5271 14937 5271 5289 14938 5289 5268 14939 5268 5265 14940 5265 5269 14941 5269 5270 14942 5270 5273 14943 5273 5271 14944 5271 5272 14945 5272 5274 14946 5274 5271 14947 5271 5273 14948 5273 5274 14949 5274 5289 14950 5289 5271 14951 5271 5274 14952 5274 5290 14953 5290 5289 14954 5289 5269 14955 5269 5290 14956 5290 5274 14957 5274 5269 14958 5269 5275 14959 5275 5290 14960 5290 5279 14961 5279 5291 14962 5291 5280 14963 5280 5291 14964 5291 5279 14965 5279 5278 14966 5278 5278 14967 5278 5292 14968 5292 5291 14969 5291 5292 14970 5292 5278 14971 5278 5276 14972 5276 5276 14973 5276 5293 14974 5293 5292 14975 5292 5293 14976 5293 5276 14977 5276 5277 14978 5277 5280 14979 5280 5282 14980 5282 5281 14981 5281 5282 14982 5282 5280 14983 5280 5291 14984 5291 5291 14985 5291 5283 14986 5283 5282 14987 5282 5283 14988 5283 5291 14989 5291 5292 14990 5292 5292 14991 5292 5284 14992 5284 5283 14993 5283 5284 14994 5284 5292 14995 5292 5293 14996 5293 5277 14997 5277 5294 14998 5294 5293 14999 5293 5294 15000 5294 5277 15001 5277 5287 15002 5287 5287 15003 5287 5295 15004 5295 5294 15005 5294 5295 15006 5295 5287 15007 5287 5288 15008 5288 5288 15009 5288 5290 15010 5290 5295 15011 5295 5290 15012 5290 5288 15013 5288 5289 15014 5289 5293 15015 5293 5285 15016 5285 5284 15017 5284 5285 15018 5285 5293 15019 5293 5294 15020 5294 5294 15021 5294 5286 15022 5286 5285 15023 5285 5286 15024 5286 5294 15025 5294 5295 15026 5295 5295 15027 5295 5275 15028 5275 5286 15029 5286 5275 15030 5275 5295 15031 5295 5290 15032 5290 5315 15033 5315 5316 15034 5316 5296 15035 5296 5305 15036 5305 5297 15037 5297 5298 15038 5298 5317 15039 5317 5299 15040 5299 5302 15041 5302 5318 15042 5318 5299 15043 5299 5317 15044 5317 5319 15045 5319 5299 15046 5299 5318 15047 5318 5319 15048 5319 5300 15049 5300 5299 15050 5299 5320 15051 5320 5300 15052 5300 5319 15053 5319 5320 15054 5320 5301 15055 5301 5300 15056 5300 5302 15057 5302 5321 15058 5321 5317 15059 5317 5303 15060 5303 5321 15061 5321 5302 15062 5302 5303 15063 5303 5322 15064 5322 5321 15065 5321 5304 15066 5304 5322 15067 5322 5303 15068 5303 5304 15069 5304 5323 15070 5323 5322 15071 5322 5297 15072 5297 5323 15073 5323 5304 15074 5304 5305 15075 5305 5323 15076 5323 5297 15077 5297 5305 15078 5305 5324 15079 5324 5323 15080 5323 5306 15081 5306 5324 15082 5324 5305 15083 5305 5306 15084 5306 5325 15085 5325 5324 15086 5324 5307 15087 5307 5325 15088 5325 5306 15089 5306 5307 15090 5307 5326 15091 5326 5325 15092 5325 5308 15093 5308 5326 15094 5326 5307 15095 5307 5309 15096 5309 5326 15097 5326 5308 15098 5308 5309 15099 5309 5327 15100 5327 5326 15101 5326 5310 15102 5310 5327 15103 5327 5309 15104 5309 5310 15105 5310 5328 15106 5328 5327 15107 5327 5310 15108 5310 5329 15109 5329 5328 15110 5328 5311 15111 5311 5329 15112 5329 5310 15113 5310 5311 15114 5311 5330 15115 5330 5329 15116 5329 5312 15117 5312 5330 15118 5330 5311 15119 5311 5312 15120 5312 5316 15121 5316 5330 15122 5330 5296 15123 5296 5316 15124 5316 5312 15125 5312 5301 15126 5301 5313 15127 5313 5314 15128 5314 5320 15129 5320 5313 15130 5313 5301 15131 5301 5331 15132 5331 5313 15133 5313 5320 15134 5320 5331 15135 5331 5315 15136 5315 5313 15137 5313 5316 15138 5316 5315 15139 5315 5331 15140 5331 5320 15141 5320 5332 15142 5332 5331 15143 5331 5332 15144 5332 5320 15145 5320 5319 15146 5319 5319 15147 5319 5333 15148 5333 5332 15149 5332 5333 15150 5333 5319 15151 5319 5318 15152 5318 5318 15153 5318 5334 15154 5334 5333 15155 5333 5334 15156 5334 5318 15157 5318 5317 15158 5317 5331 15159 5331 5330 15160 5330 5316 15161 5316 5330 15162 5330 5331 15163 5331 5332 15164 5332 5332 15165 5332 5329 15166 5329 5330 15167 5330 5329 15168 5329 5332 15169 5332 5333 15170 5333 5333 15171 5333 5328 15172 5328 5329 15173 5329 5328 15174 5328 5333 15175 5333 5334 15176 5334 5317 15177 5317 5335 15178 5335 5334 15179 5334 5335 15180 5335 5317 15181 5317 5321 15182 5321 5321 15183 5321 5336 15184 5336 5335 15185 5335 5336 15186 5336 5321 15187 5321 5322 15188 5322 5322 15189 5322 5324 15190 5324 5336 15191 5336 5324 15192 5324 5322 15193 5322 5323 15194 5323 5334 15195 5334 5327 15196 5327 5328 15197 5328 5327 15198 5327 5334 15199 5334 5335 15200 5335 5335 15201 5335 5326 15202 5326 5327 15203 5327 5326 15204 5326 5335 15205 5335 5336 15206 5336 5336 15207 5336 5325 15208 5325 5326 15209 5326 5325 15210 5325 5336 15211 5336 5324 15212 5324 5354 15213 5354 5337 15214 5337 5338 15215 5338 5343 15216 5343 5339 15217 5339 5340 15218 5340 5343 15219 5343 5341 15220 5341 5339 15221 5339 5343 15222 5343 5342 15223 5342 5341 15224 5341 5345 15225 5345 5342 15226 5342 5343 15227 5343 5345 15228 5345 5344 15229 5344 5342 15230 5342 5346 15231 5346 5344 15232 5344 5345 15233 5345 5349 15234 5349 5344 15235 5344 5346 15236 5346 5349 15237 5349 5347 15238 5347 5344 15239 5344 5349 15240 5349 5348 15241 5348 5347 15242 5347 5350 15243 5350 5348 15244 5348 5349 15245 5349 5353 15246 5353 5348 15247 5348 5350 15248 5350 5353 15249 5353 5351 15250 5351 5348 15251 5348 5353 15252 5353 5352 15253 5352 5351 15254 5351 5337 15255 5337 5352 15256 5352 5353 15257 5353 5337 15258 5337 5354 15259 5354 5352 15260 5352 5372 15261 5372 5355 15262 5355 5361 15263 5361 5358 15264 5358 5356 15265 5356 5357 15266 5357 5360 15267 5360 5356 15268 5356 5358 15269 5358 5360 15270 5360 5359 15271 5359 5356 15272 5356 5362 15273 5362 5359 15274 5359 5360 15275 5360 5362 15276 5362 5361 15277 5361 5359 15278 5359 5372 15279 5372 5361 15280 5361 5362 15281 5362 5366 15282 5366 5363 15283 5363 5364 15284 5364 5366 15285 5366 5365 15286 5365 5363 15287 5363 5368 15288 5368 5365 15289 5365 5366 15290 5366 5368 15291 5368 5367 15292 5367 5365 15293 5365 5370 15294 5370 5367 15295 5367 5368 15296 5368 5370 15297 5370 5369 15298 5369 5367 15299 5367 5355 15300 5355 5369 15301 5369 5370 15302 5370 5355 15303 5355 5371 15304 5371 5369 15305 5369 5355 15306 5355 5372 15307 5372 5371 15308 5371 5406 15309 5406 5373 15310 5373 5389 15311 5389 5385 15312 5385 5374 15313 5374 5375 15314 5375 5385 15315 5385 5376 15316 5376 5374 15317 5374 5385 15318 5385 5377 15319 5377 5376 15320 5376 5380 15321 5380 5378 15322 5378 5379 15323 5379 5381 15324 5381 5378 15325 5378 5380 15326 5380 5382 15327 5382 5378 15328 5378 5381 15329 5381 5383 15330 5383 5378 15331 5378 5382 15332 5382 5398 15333 5398 5378 15334 5378 5383 15335 5383 5385 15336 5385 5384 15337 5384 5377 15338 5377 5392 15339 5392 5384 15340 5384 5385 15341 5385 5392 15342 5392 5386 15343 5386 5384 15344 5384 5390 15345 5390 5387 15346 5387 5388 15347 5388 5390 15348 5390 5389 15349 5389 5387 15350 5387 5399 15351 5399 5389 15352 5389 5390 15353 5390 5392 15354 5392 5391 15355 5391 5386 15356 5386 5394 15357 5394 5391 15358 5391 5392 15359 5392 5394 15360 5394 5393 15361 5393 5391 15362 5391 5397 15363 5397 5393 15364 5393 5394 15365 5394 5397 15366 5397 5395 15367 5395 5393 15368 5393 5397 15369 5397 5396 15370 5396 5395 15371 5395 5400 15372 5400 5396 15373 5396 5397 15374 5397 5373 15375 5373 5378 15376 5378 5398 15377 5398 5406 15378 5406 5389 15379 5389 5399 15380 5399 5402 15381 5402 5396 15382 5396 5400 15383 5400 5402 15384 5402 5401 15385 5401 5396 15386 5396 5404 15387 5404 5401 15388 5401 5402 15389 5402 5404 15390 5404 5403 15391 5403 5401 15392 5401 5378 15393 5378 5403 15394 5403 5404 15395 5404 5373 15396 5373 5403 15397 5403 5378 15398 5378 5373 15399 5373 5405 15400 5405 5403 15401 5403 5373 15402 5373 5406 15403 5406 5405 15404 5405 5426 15405 5426 5407 15406 5407 5408 15407 5408 5412 15408 5412 5409 15409 5409 5410 15410 5410 5412 15411 5412 5411 15412 5411 5409 15413 5409 5414 15414 5414 5411 15415 5411 5412 15416 5412 5414 15417 5414 5413 15418 5413 5411 15419 5411 5416 15420 5416 5413 15421 5413 5414 15422 5414 5416 15423 5416 5415 15424 5415 5413 15425 5413 5418 15426 5418 5415 15427 5415 5416 15428 5416 5418 15429 5418 5417 15430 5417 5415 15431 5415 5420 15432 5420 5417 15433 5417 5418 15434 5418 5420 15435 5420 5419 15436 5419 5417 15437 5417 5422 15438 5422 5419 15439 5419 5420 15440 5420 5422 15441 5422 5421 15442 5421 5419 15443 5419 5424 15444 5424 5421 15445 5421 5422 15446 5422 5424 15447 5424 5423 15448 5423 5421 15449 5421 5407 15450 5407 5423 15451 5423 5424 15452 5424 5407 15453 5407 5425 15454 5425 5423 15455 5423 5407 15456 5407 5426 15457 5426 5425 15458 5425 5434 15459 5434 5427 15460 5427 5428 15461 5428 5432 15462 5432 5429 15463 5429 5430 15464 5430 5432 15465 5432 5431 15466 5431 5429 15467 5429 5433 15468 5433 5431 15469 5431 5432 15470 5432 5427 15471 5427 5431 15472 5431 5433 15473 5433 5427 15474 5427 5434 15475 5434 5431 15476 5431 5437 15477 5437 5435 15478 5435 5436 15479 5436 5435 15480 5435 5437 15481 5437 5438 15482 5438 5455 15483 5455 5440 15484 5440 5439 15485 5439 5442 15486 5442 5440 15487 5440 5441 15488 5441 5439 15489 5439 5440 15490 5440 5442 15491 5442 5447 15492 5447 5443 15493 5443 5444 15494 5444 5447 15495 5447 5445 15496 5445 5443 15497 5443 5447 15498 5447 5446 15499 5446 5445 15500 5445 5448 15501 5448 5446 15502 5446 5447 15503 5447 5450 15504 5450 5446 15505 5446 5448 15506 5448 5450 15507 5450 5449 15508 5449 5446 15509 5446 5453 15510 5453 5449 15511 5449 5450 15512 5450 5453 15513 5453 5451 15514 5451 5449 15515 5449 5453 15516 5453 5452 15517 5452 5451 15518 5451 5454 15519 5454 5452 15520 5452 5453 15521 5453 5456 15522 5456 5452 15523 5452 5454 15524 5454 5456 15525 5456 5455 15526 5455 5452 15527 5452 5440 15528 5440 5455 15529 5455 5456 15530 5456 5486 15531 5486 5457 15532 5457 5477 15533 5477 5460 15534 5460 5458 15535 5458 5459 15536 5459 5461 15537 5461 5458 15538 5458 5460 15539 5460 5463 15540 5463 5458 15541 5458 5461 15542 5461 5463 15543 5463 5462 15544 5462 5458 15545 5458 5464 15546 5464 5462 15547 5462 5463 15548 5463 5466 15549 5466 5462 15550 5462 5464 15551 5464 5466 15552 5466 5465 15553 5465 5462 15554 5462 5473 15555 5473 5465 15556 5465 5466 15557 5466 5484 15558 5484 5467 15559 5467 5468 15560 5468 5484 15561 5484 5469 15562 5469 5467 15563 5467 5484 15564 5484 5470 15565 5470 5469 15566 5469 5484 15567 5484 5471 15568 5471 5470 15569 5470 5484 15570 5484 5472 15571 5472 5471 15572 5471 5479 15573 5479 5465 15574 5465 5473 15575 5473 5479 15576 5479 5474 15577 5474 5465 15578 5465 5486 15579 5486 5475 15580 5475 5476 15581 5476 5486 15582 5486 5477 15583 5477 5475 15584 5475 5479 15585 5479 5478 15586 5478 5474 15587 5474 5481 15588 5481 5478 15589 5478 5479 15590 5479 5481 15591 5481 5480 15592 5480 5478 15593 5478 5483 15594 5483 5480 15595 5480 5481 15596 5481 5483 15597 5483 5482 15598 5482 5480 15599 5480 5485 15600 5485 5482 15601 5482 5483 15602 5483 5485 15603 5485 5484 15604 5484 5482 15605 5482 5485 15606 5485 5472 15607 5472 5484 15608 5484 5457 15609 5457 5472 15610 5472 5485 15611 5485 5457 15612 5457 5486 15613 5486 5472 15614 5472 5506 15615 5506 5487 15616 5487 5488 15617 5488 5491 15618 5491 5489 15619 5489 5490 15620 5490 5493 15621 5493 5489 15622 5489 5491 15623 5491 5493 15624 5493 5492 15625 5492 5489 15626 5489 5495 15627 5495 5492 15628 5492 5493 15629 5493 5495 15630 5495 5494 15631 5494 5492 15632 5492 5497 15633 5497 5494 15634 5494 5495 15635 5495 5497 15636 5497 5496 15637 5496 5494 15638 5494 5499 15639 5499 5496 15640 5496 5497 15641 5497 5499 15642 5499 5498 15643 5498 5496 15644 5496 5501 15645 5501 5498 15646 5498 5499 15647 5499 5501 15648 5501 5500 15649 5500 5498 15650 5498 5503 15651 5503 5500 15652 5500 5501 15653 5501 5503 15654 5503 5502 15655 5502 5500 15656 5500 5505 15657 5505 5502 15658 5502 5503 15659 5503 5505 15660 5505 5504 15661 5504 5502 15662 5502 5487 15663 5487 5504 15664 5504 5505 15665 5505 5487 15666 5487 5506 15667 5506 5504 15668 5504 5514 15669 5514 5510 15670 5510 5507 15671 5507 5511 15672 5511 5508 15673 5508 5509 15674 5509 5511 15675 5511 5510 15676 5510 5508 15677 5508 5507 15678 5507 5510 15679 5510 5511 15680 5511 5510 15681 5510 5512 15682 5512 5513 15683 5513 5510 15684 5510 5514 15685 5514 5512 15686 5512 5517 15687 5517 5515 15688 5515 5516 15689 5516 5515 15690 5515 5517 15691 5517 5518 15692 5518 5536 15693 5536 5519 15694 5519 5529 15695 5529 5522 15696 5522 5520 15697 5520 5521 15698 5521 5530 15699 5530 5520 15700 5520 5522 15701 5522 5526 15702 5526 5523 15703 5523 5524 15704 5524 5526 15705 5526 5525 15706 5525 5523 15707 5523 5528 15708 5528 5525 15709 5525 5526 15710 5526 5528 15711 5528 5527 15712 5527 5525 15713 5525 5536 15714 5536 5527 15715 5527 5528 15716 5528 5536 15717 5536 5529 15718 5529 5527 15719 5527 5532 15720 5532 5520 15721 5520 5530 15722 5530 5532 15723 5532 5531 15724 5531 5520 15725 5520 5534 15726 5534 5531 15727 5531 5532 15728 5532 5534 15729 5534 5533 15730 5533 5531 15731 5531 5519 15732 5519 5533 15733 5533 5534 15734 5534 5519 15735 5519 5535 15736 5535 5533 15737 5533 5519 15738 5519 5536 15739 5536 5535 15740 5535 5539 15741 5539 5537 15742 5537 5538 15743 5538 5537 15744 5537 5539 15745 5539 5540 15746 5540 5543 15747 5543 5541 15748 5541 5542 15749 5542 5541 15750 5541 5543 15751 5543 5544 15752 5544 5565 15753 5565 5547 15754 5547 5566 15755 5566 5562 15756 5562 5545 15757 5545 5546 15758 5546 5547 15759 5547 5567 15760 5567 5566 15761 5566 5548 15762 5548 5567 15763 5567 5547 15764 5547 5548 15765 5548 5568 15766 5568 5567 15767 5567 5549 15768 5549 5568 15769 5568 5548 15770 5548 5550 15771 5550 5568 15772 5568 5549 15773 5549 5550 15774 5550 5569 15775 5569 5568 15776 5568 5551 15777 5551 5569 15778 5569 5550 15779 5550 5551 15780 5551 5570 15781 5570 5569 15782 5569 5552 15783 5552 5570 15784 5570 5551 15785 5551 5552 15786 5552 5571 15787 5571 5570 15788 5570 5553 15789 5553 5571 15790 5571 5552 15791 5552 5554 15792 5554 5571 15793 5571 5553 15794 5553 5554 15795 5554 5572 15796 5572 5571 15797 5571 5555 15798 5555 5572 15799 5572 5554 15800 5554 5555 15801 5555 5573 15802 5573 5572 15803 5572 5556 15804 5556 5573 15805 5573 5555 15806 5555 5557 15807 5557 5573 15808 5573 5556 15809 5556 5557 15810 5557 5574 15811 5574 5573 15812 5573 5558 15813 5558 5574 15814 5574 5557 15815 5557 5558 15816 5558 5575 15817 5575 5574 15818 5574 5559 15819 5559 5575 15820 5575 5558 15821 5558 5559 15822 5559 5576 15823 5576 5575 15824 5575 5559 15825 5559 5577 15826 5577 5576 15827 5576 5560 15828 5560 5577 15829 5577 5559 15830 5559 5560 15831 5560 5578 15832 5578 5577 15833 5577 5561 15834 5561 5578 15835 5578 5560 15836 5560 5561 15837 5561 5579 15838 5579 5578 15839 5578 5545 15840 5545 5579 15841 5579 5561 15842 5561 5562 15843 5562 5579 15844 5579 5545 15845 5545 5562 15846 5562 5580 15847 5580 5579 15848 5579 5563 15849 5563 5580 15850 5580 5562 15851 5562 5563 15852 5563 5565 15853 5565 5580 15854 5580 5564 15855 5564 5565 15856 5565 5563 15857 5563 5547 15858 5547 5565 15859 5565 5564 15860 5564 5573 15861 5573 5581 15862 5581 5572 15863 5572 5581 15864 5581 5573 15865 5573 5574 15866 5574 5574 15867 5574 5582 15868 5582 5581 15869 5581 5582 15870 5582 5574 15871 5574 5575 15872 5575 5575 15873 5575 5583 15874 5583 5582 15875 5582 5583 15876 5583 5575 15877 5575 5576 15878 5576 5572 15879 5572 5570 15880 5570 5571 15881 5571 5570 15882 5570 5572 15883 5572 5581 15884 5581 5581 15885 5581 5569 15886 5569 5570 15887 5570 5569 15888 5569 5581 15889 5581 5582 15890 5582 5582 15891 5582 5568 15892 5568 5569 15893 5569 5568 15894 5568 5582 15895 5582 5583 15896 5583 5576 15897 5576 5584 15898 5584 5583 15899 5583 5584 15900 5584 5576 15901 5576 5577 15902 5577 5577 15903 5577 5585 15904 5585 5584 15905 5584 5585 15906 5585 5577 15907 5577 5578 15908 5578 5578 15909 5578 5580 15910 5580 5585 15911 5585 5580 15912 5580 5578 15913 5578 5579 15914 5579 5583 15915 5583 5567 15916 5567 5568 15917 5568 5567 15918 5567 5583 15919 5583 5584 15920 5584 5584 15921 5584 5566 15922 5566 5567 15923 5567 5566 15924 5566 5584 15925 5584 5585 15926 5585 5585 15927 5585 5565 15928 5565 5566 15929 5566 5565 15930 5565 5585 15931 5585 5580 15932 5580 5601 15933 5601 5594 15934 5594 5586 15935 5586 5589 15936 5589 5587 15937 5587 5588 15938 5588 5591 15939 5591 5587 15940 5587 5589 15941 5589 5591 15942 5591 5590 15943 5590 5587 15944 5587 5592 15945 5592 5590 15946 5590 5591 15947 5591 5595 15948 5595 5590 15949 5590 5592 15950 5592 5595 15951 5595 5593 15952 5593 5590 15953 5590 5595 15954 5595 5594 15955 5594 5593 15956 5593 5586 15957 5586 5594 15958 5594 5595 15959 5595 5599 15960 5599 5596 15961 5596 5597 15962 5597 5599 15963 5599 5598 15964 5598 5596 15965 5596 5602 15966 5602 5598 15967 5598 5599 15968 5599 5602 15969 5602 5600 15970 5600 5598 15971 5598 5602 15972 5602 5601 15973 5601 5600 15974 5600 5603 15975 5603 5601 15976 5601 5602 15977 5602 5594 15978 5594 5601 15979 5601 5603 15980 5603 5637 15981 5637 5604 15982 5604 5605 15983 5605 5608 15984 5608 5606 15985 5606 5607 15986 5607 5610 15987 5610 5606 15988 5606 5608 15989 5608 5610 15990 5610 5609 15991 5609 5606 15992 5606 5612 15993 5612 5609 15994 5609 5610 15995 5610 5612 15996 5612 5611 15997 5611 5609 15998 5609 5613 15999 5613 5611 16000 5611 5612 16001 5612 5615 16002 5615 5611 16003 5611 5613 16004 5613 5615 16005 5615 5614 16006 5614 5611 16007 5611 5617 16008 5617 5614 16009 5614 5615 16010 5615 5617 16011 5617 5616 16012 5616 5614 16013 5614 5620 16014 5620 5616 16015 5616 5617 16016 5617 5620 16017 5620 5618 16018 5618 5616 16019 5616 5620 16020 5620 5619 16021 5619 5618 16022 5618 5621 16023 5621 5619 16024 5619 5620 16025 5620 5623 16026 5623 5619 16027 5619 5621 16028 5621 5623 16029 5623 5622 16030 5622 5619 16031 5619 5625 16032 5625 5622 16033 5622 5623 16034 5623 5625 16035 5625 5624 16036 5624 5622 16037 5622 5628 16038 5628 5624 16039 5624 5625 16040 5625 5628 16041 5628 5626 16042 5626 5624 16043 5624 5628 16044 5628 5627 16045 5627 5626 16046 5626 5629 16047 5629 5627 16048 5627 5628 16049 5628 5632 16050 5632 5627 16051 5627 5629 16052 5629 5632 16053 5632 5630 16054 5630 5627 16055 5627 5632 16056 5632 5631 16057 5631 5630 16058 5630 5634 16059 5634 5631 16060 5631 5632 16061 5632 5634 16062 5634 5633 16063 5633 5631 16064 5631 5635 16065 5635 5633 16066 5633 5634 16067 5634 5604 16068 5604 5633 16069 5633 5635 16070 5635 5604 16071 5604 5636 16072 5636 5633 16073 5633 5604 16074 5604 5637 16075 5637 5636 16076 5636 5671 16077 5671 5638 16078 5638 5639 16079 5639 5642 16080 5642 5640 16081 5640 5641 16082 5641 5643 16083 5643 5640 16084 5640 5642 16085 5642 5645 16086 5645 5640 16087 5640 5643 16088 5643 5645 16089 5645 5644 16090 5644 5640 16091 5640 5647 16092 5647 5644 16093 5644 5645 16094 5645 5647 16095 5647 5646 16096 5646 5644 16097 5644 5649 16098 5649 5646 16099 5646 5647 16100 5647 5649 16101 5649 5648 16102 5648 5646 16103 5646 5651 16104 5651 5648 16105 5648 5649 16106 5649 5651 16107 5651 5650 16108 5650 5648 16109 5648 5653 16110 5653 5650 16111 5650 5651 16112 5651 5653 16113 5653 5652 16114 5652 5650 16115 5650 5655 16116 5655 5652 16117 5652 5653 16118 5653 5655 16119 5655 5654 16120 5654 5652 16121 5652 5657 16122 5657 5654 16123 5654 5655 16124 5655 5657 16125 5657 5656 16126 5656 5654 16127 5654 5659 16128 5659 5656 16129 5656 5657 16130 5657 5659 16131 5659 5658 16132 5658 5656 16133 5656 5661 16134 5661 5658 16135 5658 5659 16136 5659 5661 16137 5661 5660 16138 5660 5658 16139 5658 5664 16140 5664 5660 16141 5660 5661 16142 5661 5664 16143 5664 5662 16144 5662 5660 16145 5660 5664 16146 5664 5663 16147 5663 5662 16148 5662 5665 16149 5665 5663 16150 5663 5664 16151 5664 5667 16152 5667 5663 16153 5663 5665 16154 5665 5667 16155 5667 5666 16156 5666 5663 16157 5663 5669 16158 5669 5666 16159 5666 5667 16160 5667 5669 16161 5669 5668 16162 5668 5666 16163 5666 5638 16164 5638 5668 16165 5668 5669 16166 5669 5638 16167 5638 5670 16168 5670 5668 16169 5668 5638 16170 5638 5671 16171 5671 5670 16172 5670 5704 16173 5704 5672 16174 5672 5673 16175 5673 5676 16176 5676 5674 16177 5674 5675 16178 5675 5677 16179 5677 5674 16180 5674 5676 16181 5676 5679 16182 5679 5674 16183 5674 5677 16184 5677 5679 16185 5679 5678 16186 5678 5674 16187 5674 5681 16188 5681 5678 16189 5678 5679 16190 5679 5681 16191 5681 5680 16192 5680 5678 16193 5678 5684 16194 5684 5680 16195 5680 5681 16196 5681 5684 16197 5684 5682 16198 5682 5680 16199 5680 5684 16200 5684 5683 16201 5683 5682 16202 5682 5686 16203 5686 5683 16204 5683 5684 16205 5684 5686 16206 5686 5685 16207 5685 5683 16208 5683 5687 16209 5687 5685 16210 5685 5686 16211 5686 5689 16212 5689 5685 16213 5685 5687 16214 5687 5689 16215 5689 5688 16216 5688 5685 16217 5685 5692 16218 5692 5688 16219 5688 5689 16220 5689 5692 16221 5692 5690 16222 5690 5688 16223 5688 5692 16224 5692 5691 16225 5691 5690 16226 5690 5693 16227 5693 5691 16228 5691 5692 16229 5692 5695 16230 5695 5691 16231 5691 5693 16232 5693 5695 16233 5695 5694 16234 5694 5691 16235 5691 5697 16236 5697 5694 16237 5694 5695 16238 5695 5697 16239 5697 5696 16240 5696 5694 16241 5694 5699 16242 5699 5696 16243 5696 5697 16244 5697 5699 16245 5699 5698 16246 5698 5696 16247 5696 5701 16248 5701 5698 16249 5698 5699 16250 5699 5701 16251 5701 5700 16252 5700 5698 16253 5698 5703 16254 5703 5700 16255 5700 5701 16256 5701 5703 16257 5703 5702 16258 5702 5700 16259 5700 5705 16260 5705 5702 16261 5702 5703 16262 5703 5705 16263 5705 5704 16264 5704 5702 16265 5702 5672 16266 5672 5704 16267 5704 5705 16268 5705 5738 16269 5738 5706 16270 5706 5707 16271 5707 5710 16272 5710 5708 16273 5708 5709 16274 5709 5711 16275 5711 5708 16276 5708 5710 16277 5710 5713 16278 5713 5708 16279 5708 5711 16280 5711 5713 16281 5713 5712 16282 5712 5708 16283 5708 5715 16284 5715 5712 16285 5712 5713 16286 5713 5715 16287 5715 5714 16288 5714 5712 16289 5712 5717 16290 5717 5714 16291 5714 5715 16292 5715 5717 16293 5717 5716 16294 5716 5714 16295 5714 5719 16296 5719 5716 16297 5716 5717 16298 5717 5719 16299 5719 5718 16300 5718 5716 16301 5716 5721 16302 5721 5718 16303 5718 5719 16304 5719 5721 16305 5721 5720 16306 5720 5718 16307 5718 5723 16308 5723 5720 16309 5720 5721 16310 5721 5723 16311 5723 5722 16312 5722 5720 16313 5720 5725 16314 5725 5722 16315 5722 5723 16316 5723 5725 16317 5725 5724 16318 5724 5722 16319 5722 5727 16320 5727 5724 16321 5724 5725 16322 5725 5727 16323 5727 5726 16324 5726 5724 16325 5724 5729 16326 5729 5726 16327 5726 5727 16328 5727 5729 16329 5729 5728 16330 5728 5726 16331 5726 5732 16332 5732 5728 16333 5728 5729 16334 5729 5732 16335 5732 5730 16336 5730 5728 16337 5728 5732 16338 5732 5731 16339 5731 5730 16340 5730 5733 16341 5733 5731 16342 5731 5732 16343 5732 5735 16344 5735 5731 16345 5731 5733 16346 5733 5735 16347 5735 5734 16348 5734 5731 16349 5731 5737 16350 5737 5734 16351 5734 5735 16352 5735 5737 16353 5737 5736 16354 5736 5734 16355 5734 5739 16356 5739 5736 16357 5736 5737 16358 5737 5739 16359 5739 5738 16360 5738 5736 16361 5736 5706 16362 5706 5738 16363 5738 5739 16364 5739 5776 16365 5776 5740 16366 5740 5741 16367 5741 5745 16368 5745 5742 16369 5742 5743 16370 5743 5745 16371 5745 5744 16372 5744 5742 16373 5742 5747 16374 5747 5744 16375 5744 5745 16376 5745 5747 16377 5747 5746 16378 5746 5744 16379 5744 5749 16380 5749 5746 16381 5746 5747 16382 5747 5749 16383 5749 5748 16384 5748 5746 16385 5746 5751 16386 5751 5748 16387 5748 5749 16388 5749 5751 16389 5751 5750 16390 5750 5748 16391 5748 5753 16392 5753 5750 16393 5750 5751 16394 5751 5753 16395 5753 5752 16396 5752 5750 16397 5750 5755 16398 5755 5752 16399 5752 5753 16400 5753 5755 16401 5755 5754 16402 5754 5752 16403 5752 5758 16404 5758 5754 16405 5754 5755 16406 5755 5758 16407 5758 5756 16408 5756 5754 16409 5754 5758 16410 5758 5757 16411 5757 5756 16412 5756 5760 16413 5760 5758 16414 5758 5759 16415 5759 5760 16416 5760 5757 16417 5757 5758 16418 5758 5740 16419 5740 5757 16420 5757 5760 16421 5760 5740 16422 5740 5761 16423 5761 5757 16424 5757 5766 16425 5766 5762 16426 5762 5763 16427 5763 5766 16428 5766 5764 16429 5764 5762 16430 5762 5766 16431 5766 5765 16432 5765 5764 16433 5764 5767 16434 5767 5765 16435 5765 5766 16436 5766 5769 16437 5769 5765 16438 5765 5767 16439 5767 5769 16440 5769 5768 16441 5768 5765 16442 5765 5771 16443 5771 5768 16444 5768 5769 16445 5769 5771 16446 5771 5770 16447 5770 5768 16448 5768 5774 16449 5774 5770 16450 5770 5771 16451 5771 5774 16452 5774 5772 16453 5772 5770 16454 5770 5774 16455 5774 5773 16456 5773 5772 16457 5772 5775 16458 5775 5773 16459 5773 5774 16460 5774 5761 16461 5761 5773 16462 5773 5775 16463 5775 5761 16464 5761 5776 16465 5776 5773 16466 5773 5740 16467 5740 5776 16468 5776 5761 16469 5761 5799 16470 5799 5777 16471 5777 5805 16472 5805 5780 16473 5780 5778 16474 5778 5779 16475 5779 5777 16476 5777 5778 16477 5778 5780 16478 5780 5824 16479 5824 5781 16480 5781 5782 16481 5782 5824 16482 5824 5783 16483 5783 5781 16484 5781 5786 16485 5786 5784 16486 5784 5785 16487 5785 5822 16488 5822 5784 16489 5784 5786 16490 5786 5821 16491 5821 5787 16492 5787 5788 16493 5788 5821 16494 5821 5789 16495 5789 5787 16496 5787 5802 16497 5802 5790 16498 5790 5791 16499 5791 5802 16500 5802 5792 16501 5792 5790 16502 5790 5801 16503 5801 5793 16504 5793 5794 16505 5794 5801 16506 5801 5795 16507 5795 5793 16508 5793 5800 16509 5800 5796 16510 5796 5797 16511 5797 5800 16512 5800 5798 16513 5798 5796 16514 5796 5800 16515 5800 5799 16516 5799 5798 16517 5798 5795 16518 5795 5799 16519 5799 5800 16520 5800 5801 16521 5801 5799 16522 5799 5795 16523 5795 5792 16524 5792 5799 16525 5799 5801 16526 5801 5802 16527 5802 5799 16528 5799 5792 16529 5792 5817 16530 5817 5799 16531 5799 5802 16532 5802 5799 16533 5799 5803 16534 5803 5804 16535 5804 5799 16536 5799 5805 16537 5805 5803 16538 5803 5823 16539 5823 5806 16540 5806 5807 16541 5807 5823 16542 5823 5808 16543 5808 5806 16544 5806 5820 16545 5820 5809 16546 5809 5810 16547 5810 5820 16548 5820 5811 16549 5811 5809 16550 5809 5819 16551 5819 5812 16552 5812 5813 16553 5813 5819 16554 5819 5814 16555 5814 5812 16556 5812 5818 16557 5818 5815 16558 5815 5816 16559 5816 5818 16560 5818 5817 16561 5817 5815 16562 5815 5818 16563 5818 5799 16564 5799 5817 16565 5817 5814 16566 5814 5799 16567 5799 5818 16568 5818 5819 16569 5819 5799 16570 5799 5814 16571 5814 5811 16572 5811 5799 16573 5799 5819 16574 5819 5820 16575 5820 5799 16576 5799 5811 16577 5811 5789 16578 5789 5799 16579 5799 5820 16580 5820 5821 16581 5821 5799 16582 5799 5789 16583 5789 5784 16584 5784 5799 16585 5799 5821 16586 5821 5822 16587 5822 5799 16588 5799 5784 16589 5784 5808 16590 5808 5799 16591 5799 5822 16592 5822 5823 16593 5823 5799 16594 5799 5808 16595 5808 5783 16596 5783 5799 16597 5799 5823 16598 5823 5824 16599 5824 5799 16600 5799 5783 16601 5783 5778 16602 5778 5799 16603 5799 5824 16604 5824 5777 16605 5777 5799 16606 5799 5778 16607 5778 5840 16608 5840 5825 16609 5825 5826 16610 5826 5830 16611 5830 5827 16612 5827 5828 16613 5828 5830 16614 5830 5829 16615 5829 5827 16616 5827 5833 16617 5833 5829 16618 5829 5830 16619 5830 5833 16620 5833 5831 16621 5831 5829 16622 5829 5833 16623 5833 5832 16624 5832 5831 16625 5831 5835 16626 5835 5832 16627 5832 5833 16628 5833 5835 16629 5835 5834 16630 5834 5832 16631 5832 5836 16632 5836 5834 16633 5834 5835 16634 5835 5838 16635 5838 5834 16636 5834 5836 16637 5836 5838 16638 5838 5837 16639 5837 5834 16640 5834 5841 16641 5841 5837 16642 5837 5838 16643 5838 5841 16644 5841 5839 16645 5839 5837 16646 5837 5841 16647 5841 5840 16648 5840 5839 16649 5839 5842 16650 5842 5840 16651 5840 5841 16652 5841 5843 16653 5843 5840 16654 5840 5842 16655 5842 5825 16656 5825 5843 16657 5843 5844 16658 5844 5825 16659 5825 5840 16660 5840 5843 16661 5843 5911 16662 5911 5856 16663 5856 5845 16664 5845 5847 16665 5847 5846 16666 5846 5858 16667 5858 5849 16668 5849 5846 16669 5846 5847 16670 5847 5849 16671 5849 5848 16672 5848 5846 16673 5846 5851 16674 5851 5848 16675 5848 5849 16676 5849 5851 16677 5851 5850 16678 5850 5848 16679 5848 5853 16680 5853 5850 16681 5850 5851 16682 5851 5853 16683 5853 5852 16684 5852 5850 16685 5850 5855 16686 5855 5852 16687 5852 5853 16688 5853 5855 16689 5855 5854 16690 5854 5852 16691 5852 5857 16692 5857 5854 16693 5854 5855 16694 5855 5857 16695 5857 5856 16696 5856 5854 16697 5854 5845 16698 5845 5856 16699 5856 5857 16700 5857 5860 16701 5860 5847 16702 5847 5858 16703 5858 5860 16704 5860 5859 16705 5859 5847 16706 5847 5862 16707 5862 5859 16708 5859 5860 16709 5860 5862 16710 5862 5861 16711 5861 5859 16712 5859 5864 16713 5864 5861 16714 5861 5862 16715 5862 5864 16716 5864 5863 16717 5863 5861 16718 5861 5866 16719 5866 5863 16720 5863 5864 16721 5864 5866 16722 5866 5865 16723 5865 5863 16724 5863 5868 16725 5868 5865 16726 5865 5866 16727 5866 5868 16728 5868 5867 16729 5867 5865 16730 5865 5870 16731 5870 5867 16732 5867 5868 16733 5868 5870 16734 5870 5869 16735 5869 5867 16736 5867 5872 16737 5872 5869 16738 5869 5870 16739 5870 5872 16740 5872 5871 16741 5871 5869 16742 5869 5874 16743 5874 5871 16744 5871 5872 16745 5872 5874 16746 5874 5873 16747 5873 5871 16748 5871 5876 16749 5876 5873 16750 5873 5874 16751 5874 5876 16752 5876 5875 16753 5875 5873 16754 5873 5878 16755 5878 5875 16756 5875 5876 16757 5876 5878 16758 5878 5877 16759 5877 5875 16760 5875 5880 16761 5880 5877 16762 5877 5878 16763 5878 5880 16764 5880 5879 16765 5879 5877 16766 5877 5882 16767 5882 5879 16768 5879 5880 16769 5880 5882 16770 5882 5881 16771 5881 5879 16772 5879 5884 16773 5884 5881 16774 5881 5882 16775 5882 5884 16776 5884 5883 16777 5883 5881 16778 5881 5886 16779 5886 5883 16780 5883 5884 16781 5884 5886 16782 5886 5885 16783 5885 5883 16784 5883 5888 16785 5888 5885 16786 5885 5886 16787 5886 5888 16788 5888 5887 16789 5887 5885 16790 5885 5890 16791 5890 5887 16792 5887 5888 16793 5888 5890 16794 5890 5889 16795 5889 5887 16796 5887 5892 16797 5892 5889 16798 5889 5890 16799 5890 5892 16800 5892 5891 16801 5891 5889 16802 5889 5894 16803 5894 5891 16804 5891 5892 16805 5892 5894 16806 5894 5893 16807 5893 5891 16808 5891 5896 16809 5896 5893 16810 5893 5894 16811 5894 5896 16812 5896 5895 16813 5895 5893 16814 5893 5898 16815 5898 5895 16816 5895 5896 16817 5896 5898 16818 5898 5897 16819 5897 5895 16820 5895 5900 16821 5900 5897 16822 5897 5898 16823 5898 5900 16824 5900 5899 16825 5899 5897 16826 5897 5902 16827 5902 5899 16828 5899 5900 16829 5900 5902 16830 5902 5901 16831 5901 5899 16832 5899 5904 16833 5904 5901 16834 5901 5902 16835 5902 5904 16836 5904 5903 16837 5903 5901 16838 5901 5906 16839 5906 5903 16840 5903 5904 16841 5904 5906 16842 5906 5905 16843 5905 5903 16844 5903 5908 16845 5908 5905 16846 5905 5906 16847 5906 5908 16848 5908 5907 16849 5907 5905 16850 5905 5910 16851 5910 5907 16852 5907 5908 16853 5908 5910 16854 5910 5909 16855 5909 5907 16856 5907 5912 16857 5912 5909 16858 5909 5910 16859 5910 5912 16860 5912 5911 16861 5911 5909 16862 5909 5856 16863 5856 5911 16864 5911 5912 16865 5912 5923 16866 5923 5921 16867 5921 5913 16868 5913 5917 16869 5917 5914 16870 5914 5915 16871 5915 5917 16872 5917 5916 16873 5916 5914 16874 5914 5919 16875 5919 5916 16876 5916 5917 16877 5917 5919 16878 5919 5918 16879 5918 5916 16880 5916 5922 16881 5922 5918 16882 5918 5919 16883 5919 5922 16884 5922 5920 16885 5920 5918 16886 5918 5922 16887 5922 5921 16888 5921 5920 16889 5920 5913 16890 5913 5921 16891 5921 5922 16892 5922 5925 16893 5925 5923 16894 5923 5924 16895 5924 5926 16896 5926 5923 16897 5923 5925 16898 5925 5921 16899 5921 5923 16900 5923 5926 16901 5926 5958 16902 5958 5959 16903 5959 5927 16904 5927 5960 16905 5960 5927 16906 5927 5959 16907 5959 5960 16908 5960 5928 16909 5928 5927 16910 5927 5960 16911 5960 5929 16912 5929 5928 16913 5928 5961 16914 5961 5929 16915 5929 5960 16916 5960 5961 16917 5961 5930 16918 5930 5929 16919 5929 5962 16920 5962 5930 16921 5930 5961 16922 5961 5962 16923 5962 5931 16924 5931 5930 16925 5930 5931 16926 5931 5932 16927 5932 5933 16928 5933 5962 16929 5962 5932 16930 5932 5931 16931 5931 5963 16932 5963 5932 16933 5932 5962 16934 5962 5963 16935 5963 5934 16936 5934 5932 16937 5932 5964 16938 5964 5934 16939 5934 5963 16940 5963 5964 16941 5964 5935 16942 5935 5934 16943 5934 5965 16944 5965 5935 16945 5935 5964 16946 5964 5965 16947 5965 5936 16948 5936 5935 16949 5935 5966 16950 5966 5936 16951 5936 5965 16952 5965 5966 16953 5966 5937 16954 5937 5936 16955 5936 5966 16956 5966 5938 16957 5938 5937 16958 5937 5966 16959 5966 5939 16960 5939 5938 16961 5938 5966 16962 5966 5940 16963 5940 5939 16964 5939 5967 16965 5967 5940 16966 5940 5966 16967 5966 5967 16968 5967 5941 16969 5941 5940 16970 5940 5968 16971 5968 5941 16972 5941 5967 16973 5967 5968 16974 5968 5942 16975 5942 5941 16976 5941 5969 16977 5969 5942 16978 5942 5968 16979 5968 5969 16980 5969 5943 16981 5943 5942 16982 5942 5970 16983 5970 5943 16984 5943 5969 16985 5969 5970 16986 5970 5944 16987 5944 5943 16988 5943 5970 16989 5970 5945 16990 5945 5944 16991 5944 5971 16992 5971 5945 16993 5945 5970 16994 5970 5971 16995 5971 5946 16996 5946 5945 16997 5945 5972 16998 5972 5946 16999 5946 5971 17000 5971 5972 17001 5972 5947 17002 5947 5946 17003 5946 5947 17004 5947 5948 17005 5948 5949 17006 5949 5972 17007 5972 5948 17008 5948 5947 17009 5947 5973 17010 5973 5948 17011 5948 5972 17012 5972 5973 17013 5973 5950 17014 5950 5948 17015 5948 5974 17016 5974 5950 17017 5950 5973 17018 5973 5974 17019 5974 5951 17020 5951 5950 17021 5950 5975 17022 5975 5951 17023 5951 5974 17024 5974 5975 17025 5975 5952 17026 5952 5951 17027 5951 5975 17028 5975 5953 17029 5953 5952 17030 5952 5976 17031 5976 5953 17032 5953 5975 17033 5975 5976 17034 5976 5954 17035 5954 5953 17036 5953 5976 17037 5976 5955 17038 5955 5954 17039 5954 5976 17040 5976 5956 17041 5956 5955 17042 5955 5977 17043 5977 5956 17044 5956 5976 17045 5976 5977 17046 5977 5957 17047 5957 5956 17048 5956 5978 17049 5978 5957 17050 5957 5977 17051 5977 5978 17052 5978 5958 17053 5958 5957 17054 5957 5959 17055 5959 5958 17056 5958 5978 17057 5978 5966 17058 5966 5979 17059 5979 5967 17060 5967 5979 17061 5979 5966 17062 5966 5965 17063 5965 5965 17064 5965 5980 17065 5980 5979 17066 5979 5980 17067 5980 5965 17068 5965 5964 17069 5964 5964 17070 5964 5981 17071 5981 5980 17072 5980 5981 17073 5981 5964 17074 5964 5963 17075 5963 5963 17076 5963 5961 17077 5961 5981 17078 5981 5961 17079 5961 5963 17080 5963 5962 17081 5962 5967 17082 5967 5982 17083 5982 5968 17084 5968 5982 17085 5982 5967 17086 5967 5979 17087 5979 5979 17088 5979 5983 17089 5983 5982 17090 5982 5983 17091 5983 5979 17092 5979 5980 17093 5980 5968 17094 5968 5984 17095 5984 5969 17096 5969 5984 17097 5984 5968 17098 5968 5982 17099 5982 5982 17100 5982 5985 17101 5985 5984 17102 5984 5985 17103 5985 5982 17104 5982 5983 17105 5983 5980 17106 5980 5986 17107 5986 5983 17108 5983 5986 17109 5986 5980 17110 5980 5981 17111 5981 5981 17112 5981 5960 17113 5960 5986 17114 5986 5960 17115 5960 5981 17116 5981 5961 17117 5961 5983 17118 5983 5987 17119 5987 5985 17120 5985 5987 17121 5987 5983 17122 5983 5986 17123 5986 5986 17124 5986 5959 17125 5959 5987 17126 5987 5959 17127 5959 5986 17128 5986 5960 17129 5960 5969 17130 5969 5988 17131 5988 5970 17132 5970 5988 17133 5988 5969 17134 5969 5984 17135 5984 5984 17136 5984 5989 17137 5989 5988 17138 5988 5989 17139 5989 5984 17140 5984 5985 17141 5985 5970 17142 5970 5990 17143 5990 5971 17144 5971 5990 17145 5990 5970 17146 5970 5988 17147 5988 5988 17148 5988 5991 17149 5991 5990 17150 5990 5991 17151 5991 5988 17152 5988 5989 17153 5989 5985 17154 5985 5992 17155 5992 5989 17156 5989 5992 17157 5992 5985 17158 5985 5987 17159 5987 5987 17160 5987 5978 17161 5978 5992 17162 5992 5978 17163 5978 5987 17164 5987 5959 17165 5959 5989 17166 5989 5993 17167 5993 5991 17168 5991 5993 17169 5993 5989 17170 5989 5992 17171 5992 5992 17172 5992 5977 17173 5977 5993 17174 5993 5977 17175 5977 5992 17176 5992 5978 17177 5978 5971 17178 5971 5973 17179 5973 5972 17180 5972 5973 17181 5973 5971 17182 5971 5990 17183 5990 5990 17184 5990 5974 17185 5974 5973 17186 5973 5974 17187 5974 5990 17188 5990 5991 17189 5991 5991 17190 5991 5975 17191 5975 5974 17192 5974 5975 17193 5975 5991 17194 5991 5993 17195 5993 5993 17196 5993 5976 17197 5976 5975 17198 5975 5976 17199 5976 5993 17200 5993 5977 17201 5977 6038 17202 6038 5995 17203 5995 6039 17204 6039 6040 17205 6040 5998 17206 5998 6041 17207 6041 6040 17208 6040 5994 17209 5994 5998 17210 5998 6039 17211 6039 5994 17212 5994 6040 17213 6040 6039 17214 6039 5995 17215 5995 5994 17216 5994 6020 17217 6020 5996 17218 5996 5997 17219 5997 6000 17220 6000 5998 17221 5998 5999 17222 5999 6000 17223 6000 6041 17224 6041 5998 17225 5998 6000 17226 6000 6042 17227 6042 6041 17228 6041 6001 17229 6001 6042 17230 6042 6000 17231 6000 6002 17232 6002 6042 17233 6042 6001 17234 6001 6002 17235 6002 6043 17236 6043 6042 17237 6042 6003 17238 6003 6043 17239 6043 6002 17240 6002 6003 17241 6003 6044 17242 6044 6043 17243 6043 6004 17244 6004 6044 17245 6044 6003 17246 6003 6004 17247 6004 6045 17248 6045 6044 17249 6044 6005 17250 6005 6045 17251 6045 6004 17252 6004 6006 17253 6006 6045 17254 6045 6005 17255 6005 6006 17256 6006 6046 17257 6046 6045 17258 6045 6007 17259 6007 6046 17260 6046 6006 17261 6006 6007 17262 6007 6047 17263 6047 6046 17264 6046 6008 17265 6008 6047 17266 6047 6007 17267 6007 6008 17268 6008 6048 17269 6048 6047 17270 6047 6009 17271 6009 6048 17272 6048 6008 17273 6008 6009 17274 6009 6049 17275 6049 6048 17276 6048 6010 17277 6010 6049 17278 6049 6009 17279 6009 6010 17280 6010 6050 17281 6050 6049 17282 6049 6011 17283 6011 6050 17284 6050 6010 17285 6010 6011 17286 6011 6051 17287 6051 6050 17288 6050 6012 17289 6012 6051 17290 6051 6011 17291 6011 6012 17292 6012 6052 17293 6052 6051 17294 6051 6013 17295 6013 6052 17296 6052 6012 17297 6012 6013 17298 6013 6053 17299 6053 6052 17300 6052 6014 17301 6014 6053 17302 6053 6013 17303 6013 6014 17304 6014 6054 17305 6054 6053 17306 6053 6015 17307 6015 6054 17308 6054 6014 17309 6014 6015 17310 6015 6055 17311 6055 6054 17312 6054 6016 17313 6016 6055 17314 6055 6015 17315 6015 6016 17316 6016 6056 17317 6056 6055 17318 6055 6017 17319 6017 6056 17320 6056 6016 17321 6016 6017 17322 6017 6057 17323 6057 6056 17324 6056 6018 17325 6018 6057 17326 6057 6017 17327 6017 6018 17328 6018 6058 17329 6058 6057 17330 6057 6019 17331 6019 6058 17332 6058 6018 17333 6018 6019 17334 6019 6059 17335 6059 6058 17336 6058 5996 17337 5996 6059 17338 6059 6019 17339 6019 6020 17340 6020 6059 17341 6059 5996 17342 5996 6021 17343 6021 6059 17344 6059 6020 17345 6020 6021 17346 6021 6060 17347 6060 6059 17348 6059 6022 17349 6022 6060 17350 6060 6021 17351 6021 6022 17352 6022 6061 17353 6061 6060 17354 6060 6022 17355 6022 6062 17356 6062 6061 17357 6061 6023 17358 6023 6062 17359 6062 6022 17360 6022 6024 17361 6024 6062 17362 6062 6023 17363 6023 6024 17364 6024 6063 17365 6063 6062 17366 6062 6025 17367 6025 6063 17368 6063 6024 17369 6024 6026 17370 6026 6063 17371 6063 6025 17372 6025 6027 17373 6027 6063 17374 6063 6026 17375 6026 6027 17376 6027 6064 17377 6064 6063 17378 6063 6028 17379 6028 6064 17380 6064 6027 17381 6027 6028 17382 6028 6065 17383 6065 6064 17384 6064 6028 17385 6028 6066 17386 6066 6065 17387 6065 6029 17388 6029 6066 17389 6066 6028 17390 6028 6029 17391 6029 6067 17392 6067 6066 17393 6066 6030 17394 6030 6067 17395 6067 6029 17396 6029 6031 17397 6031 6067 17398 6067 6030 17399 6030 6031 17400 6031 6068 17401 6068 6067 17402 6067 6032 17403 6032 6068 17404 6068 6031 17405 6031 6032 17406 6032 6069 17407 6069 6068 17408 6068 6033 17409 6033 6069 17410 6069 6032 17411 6032 6033 17412 6033 6070 17413 6070 6069 17414 6069 6034 17415 6034 6070 17416 6070 6033 17417 6033 6034 17418 6034 6071 17419 6071 6070 17420 6070 6035 17421 6035 6071 17422 6071 6034 17423 6034 6035 17424 6035 6072 17425 6072 6071 17426 6071 6036 17427 6036 6072 17428 6072 6035 17429 6035 6036 17430 6036 6073 17431 6073 6072 17432 6072 6037 17433 6037 6073 17434 6073 6036 17435 6036 6037 17436 6037 6038 17437 6038 6073 17438 6073 5995 17439 5995 6038 17440 6038 6037 17441 6037 6041 17442 6041 6074 17443 6074 6040 17444 6040 6074 17445 6074 6041 17446 6041 6042 17447 6042 6042 17448 6042 6075 17449 6075 6074 17450 6074 6075 17451 6075 6042 17452 6042 6043 17453 6043 6043 17454 6043 6076 17455 6076 6075 17456 6075 6076 17457 6076 6043 17458 6043 6044 17459 6044 6044 17460 6044 6046 17461 6046 6076 17462 6076 6046 17463 6046 6044 17464 6044 6045 17465 6045 6040 17466 6040 6077 17467 6077 6039 17468 6039 6077 17469 6077 6040 17470 6040 6074 17471 6074 6074 17472 6074 6078 17473 6078 6077 17474 6077 6078 17475 6078 6074 17476 6074 6075 17477 6075 6039 17478 6039 6079 17479 6079 6038 17480 6038 6079 17481 6079 6039 17482 6039 6077 17483 6077 6077 17484 6077 6080 17485 6080 6079 17486 6079 6080 17487 6080 6077 17488 6077 6078 17489 6078 6075 17490 6075 6081 17491 6081 6078 17492 6078 6081 17493 6081 6075 17494 6075 6076 17495 6076 6076 17496 6076 6047 17497 6047 6081 17498 6081 6047 17499 6047 6076 17500 6076 6046 17501 6046 6078 17502 6078 6082 17503 6082 6080 17504 6080 6082 17505 6082 6078 17506 6078 6081 17507 6081 6081 17508 6081 6048 17509 6048 6082 17510 6082 6048 17511 6048 6081 17512 6081 6047 17513 6047 6038 17514 6038 6083 17515 6083 6073 17516 6073 6083 17517 6083 6038 17518 6038 6079 17519 6079 6079 17520 6079 6084 17521 6084 6083 17522 6083 6084 17523 6084 6079 17524 6079 6080 17525 6080 6073 17526 6073 6085 17527 6085 6072 17528 6072 6085 17529 6085 6073 17530 6073 6083 17531 6083 6083 17532 6083 6086 17533 6086 6085 17534 6085 6086 17535 6086 6083 17536 6083 6084 17537 6084 6080 17538 6080 6087 17539 6087 6084 17540 6084 6087 17541 6087 6080 17542 6080 6082 17543 6082 6082 17544 6082 6049 17545 6049 6087 17546 6087 6049 17547 6049 6082 17548 6082 6048 17549 6048 6084 17550 6084 6088 17551 6088 6086 17552 6086 6088 17553 6088 6084 17554 6084 6087 17555 6087 6087 17556 6087 6050 17557 6050 6088 17558 6088 6050 17559 6050 6087 17560 6087 6049 17561 6049 6072 17562 6072 6089 17563 6089 6071 17564 6071 6089 17565 6089 6072 17566 6072 6085 17567 6085 6085 17568 6085 6090 17569 6090 6089 17570 6089 6090 17571 6090 6085 17572 6085 6086 17573 6086 6071 17574 6071 6091 17575 6091 6070 17576 6070 6091 17577 6091 6071 17578 6071 6089 17579 6089 6089 17580 6089 6092 17581 6092 6091 17582 6091 6092 17583 6092 6089 17584 6089 6090 17585 6090 6086 17586 6086 6093 17587 6093 6090 17588 6090 6093 17589 6093 6086 17590 6086 6088 17591 6088 6088 17592 6088 6051 17593 6051 6093 17594 6093 6051 17595 6051 6088 17596 6088 6050 17597 6050 6090 17598 6090 6094 17599 6094 6092 17600 6092 6094 17601 6094 6090 17602 6090 6093 17603 6093 6093 17604 6093 6052 17605 6052 6094 17606 6094 6052 17607 6052 6093 17608 6093 6051 17609 6051 6070 17610 6070 6095 17611 6095 6069 17612 6069 6095 17613 6095 6070 17614 6070 6091 17615 6091 6091 17616 6091 6096 17617 6096 6095 17618 6095 6096 17619 6096 6091 17620 6091 6092 17621 6092 6069 17622 6069 6097 17623 6097 6068 17624 6068 6097 17625 6097 6069 17626 6069 6095 17627 6095 6095 17628 6095 6098 17629 6098 6097 17630 6097 6098 17631 6098 6095 17632 6095 6096 17633 6096 6092 17634 6092 6099 17635 6099 6096 17636 6096 6099 17637 6099 6092 17638 6092 6094 17639 6094 6094 17640 6094 6053 17641 6053 6099 17642 6099 6053 17643 6053 6094 17644 6094 6052 17645 6052 6096 17646 6096 6100 17647 6100 6098 17648 6098 6100 17649 6100 6096 17650 6096 6099 17651 6099 6099 17652 6099 6054 17653 6054 6100 17654 6100 6054 17655 6054 6099 17656 6099 6053 17657 6053 6068 17658 6068 6101 17659 6101 6067 17660 6067 6101 17661 6101 6068 17662 6068 6097 17663 6097 6097 17664 6097 6102 17665 6102 6101 17666 6101 6102 17667 6102 6097 17668 6097 6098 17669 6098 6067 17670 6067 6103 17671 6103 6066 17672 6066 6103 17673 6103 6067 17674 6067 6101 17675 6101 6101 17676 6101 6104 17677 6104 6103 17678 6103 6104 17679 6104 6101 17680 6101 6102 17681 6102 6098 17682 6098 6105 17683 6105 6102 17684 6102 6105 17685 6105 6098 17686 6098 6100 17687 6100 6100 17688 6100 6055 17689 6055 6105 17690 6105 6055 17691 6055 6100 17692 6100 6054 17693 6054 6102 17694 6102 6106 17695 6106 6104 17696 6104 6106 17697 6106 6102 17698 6102 6105 17699 6105 6105 17700 6105 6056 17701 6056 6106 17702 6106 6056 17703 6056 6105 17704 6105 6055 17705 6055 6066 17706 6066 6107 17707 6107 6065 17708 6065 6107 17709 6107 6066 17710 6066 6103 17711 6103 6103 17712 6103 6108 17713 6108 6107 17714 6107 6108 17715 6108 6103 17716 6103 6104 17717 6104 6065 17718 6065 6109 17719 6109 6064 17720 6064 6109 17721 6109 6065 17722 6065 6107 17723 6107 6107 17724 6107 6110 17725 6110 6109 17726 6109 6110 17727 6110 6107 17728 6107 6108 17729 6108 6104 17730 6104 6111 17731 6111 6108 17732 6108 6111 17733 6111 6104 17734 6104 6106 17735 6106 6106 17736 6106 6057 17737 6057 6111 17738 6111 6057 17739 6057 6106 17740 6106 6056 17741 6056 6108 17742 6108 6112 17743 6112 6110 17744 6110 6112 17745 6112 6108 17746 6108 6111 17747 6111 6111 17748 6111 6058 17749 6058 6112 17750 6112 6058 17751 6058 6111 17752 6111 6057 17753 6057 6064 17754 6064 6062 17755 6062 6063 17756 6063 6062 17757 6062 6064 17758 6064 6109 17759 6109 6109 17760 6109 6061 17761 6061 6062 17762 6062 6061 17763 6061 6109 17764 6109 6110 17765 6110 6110 17766 6110 6060 17767 6060 6061 17768 6061 6060 17769 6060 6110 17770 6110 6112 17771 6112 6112 17772 6112 6059 17773 6059 6060 17774 6060 6059 17775 6059 6112 17776 6112 6058 17777 6058 6126 17778 6126 6113 17779 6113 6114 17780 6114 6117 17781 6117 6115 17782 6115 6116 17783 6116 6118 17784 6118 6115 17785 6115 6117 17786 6117 6121 17787 6121 6115 17788 6115 6118 17789 6118 6121 17790 6121 6119 17791 6119 6115 17792 6115 6121 17793 6121 6120 17794 6120 6119 17795 6119 6122 17796 6122 6120 17797 6120 6121 17798 6121 6124 17799 6124 6120 17800 6120 6122 17801 6122 6124 17802 6124 6123 17803 6123 6120 17804 6120 6113 17805 6113 6123 17806 6123 6124 17807 6124 6113 17808 6113 6125 17809 6125 6123 17810 6123 6113 17811 6113 6126 17812 6126 6125 17813 6125 6136 17814 6136 6127 17815 6127 6128 17816 6128 6131 17817 6131 6129 17818 6129 6130 17819 6130 6132 17820 6132 6129 17821 6129 6131 17822 6131 6135 17823 6135 6129 17824 6129 6132 17825 6132 6135 17826 6135 6133 17827 6133 6129 17828 6129 6135 17829 6135 6134 17830 6134 6133 17831 6133 6127 17832 6127 6134 17833 6134 6135 17834 6135 6127 17835 6127 6136 17836 6136 6134 17837 6134 6177 17838 6177 6137 17839 6137 6178 17840 6178 6178 17841 6178 6140 17842 6140 6179 17843 6179 6178 17844 6178 6137 17845 6137 6140 17846 6140 6147 17847 6147 6138 17848 6138 6139 17849 6139 6141 17850 6141 6179 17851 6179 6140 17852 6140 6141 17853 6141 6180 17854 6180 6179 17855 6179 6142 17856 6142 6180 17857 6180 6141 17858 6141 6142 17859 6142 6181 17860 6181 6180 17861 6180 6142 17862 6142 6182 17863 6182 6181 17864 6181 6143 17865 6143 6182 17866 6182 6142 17867 6142 6144 17868 6144 6182 17869 6182 6143 17870 6143 6145 17871 6145 6182 17872 6182 6144 17873 6144 6146 17874 6146 6182 17875 6182 6145 17876 6145 6146 17877 6146 6183 17878 6183 6182 17879 6182 6138 17880 6138 6183 17881 6183 6146 17882 6146 6138 17883 6138 6184 17884 6184 6183 17885 6183 6147 17886 6147 6184 17887 6184 6138 17888 6138 6148 17889 6148 6184 17890 6184 6147 17891 6147 6148 17892 6148 6185 17893 6185 6184 17894 6184 6149 17895 6149 6185 17896 6185 6148 17897 6148 6149 17898 6149 6186 17899 6186 6185 17900 6185 6150 17901 6150 6186 17902 6186 6149 17903 6149 6150 17904 6150 6187 17905 6187 6186 17906 6186 6151 17907 6151 6187 17908 6187 6150 17909 6150 6151 17910 6151 6188 17911 6188 6187 17912 6187 6152 17913 6152 6188 17914 6188 6151 17915 6151 6152 17916 6152 6189 17917 6189 6188 17918 6188 6153 17919 6153 6189 17920 6189 6152 17921 6152 6153 17922 6153 6190 17923 6190 6189 17924 6189 6154 17925 6154 6190 17926 6190 6153 17927 6153 6154 17928 6154 6191 17929 6191 6190 17930 6190 6155 17931 6155 6191 17932 6191 6154 17933 6154 6155 17934 6155 6192 17935 6192 6191 17936 6191 6156 17937 6156 6192 17938 6192 6155 17939 6155 6156 17940 6156 6193 17941 6193 6192 17942 6192 6157 17943 6157 6193 17944 6193 6156 17945 6156 6157 17946 6157 6194 17947 6194 6193 17948 6193 6158 17949 6158 6194 17950 6194 6157 17951 6157 6158 17952 6158 6195 17953 6195 6194 17954 6194 6159 17955 6159 6195 17956 6195 6158 17957 6158 6159 17958 6159 6196 17959 6196 6195 17960 6195 6160 17961 6160 6196 17962 6196 6159 17963 6159 6160 17964 6160 6197 17965 6197 6196 17966 6196 6161 17967 6161 6197 17968 6197 6160 17969 6160 6161 17970 6161 6198 17971 6198 6197 17972 6197 6162 17973 6162 6198 17974 6198 6161 17975 6161 6163 17976 6163 6198 17977 6198 6162 17978 6162 6163 17979 6163 6199 17980 6199 6198 17981 6198 6164 17982 6164 6199 17983 6199 6163 17984 6163 6164 17985 6164 6200 17986 6200 6199 17987 6199 6165 17988 6165 6200 17989 6200 6164 17990 6164 6166 17991 6166 6200 17992 6200 6165 17993 6165 6167 17994 6167 6200 17995 6200 6166 17996 6166 6167 17997 6167 6201 17998 6201 6200 17999 6200 6168 18000 6168 6201 18001 6201 6167 18002 6167 6168 18003 6168 6202 18004 6202 6201 18005 6201 6169 18006 6169 6202 18007 6202 6168 18008 6168 6170 18009 6170 6202 18010 6202 6169 18011 6169 6170 18012 6170 6203 18013 6203 6202 18014 6202 6171 18015 6171 6203 18016 6203 6170 18017 6170 6171 18018 6171 6204 18019 6204 6203 18020 6203 6171 18021 6171 6205 18022 6205 6204 18023 6204 6172 18024 6172 6205 18025 6205 6171 18026 6171 6172 18027 6172 6206 18028 6206 6205 18029 6205 6173 18030 6173 6206 18031 6206 6172 18032 6172 6173 18033 6173 6207 18034 6207 6206 18035 6206 6174 18036 6174 6207 18037 6207 6173 18038 6173 6175 18039 6175 6207 18040 6207 6174 18041 6174 6175 18042 6175 6208 18043 6208 6207 18044 6207 6176 18045 6176 6208 18046 6208 6175 18047 6175 6176 18048 6176 6177 18049 6177 6208 18050 6208 6137 18051 6137 6177 18052 6177 6176 18053 6176 6198 18054 6198 6209 18055 6209 6197 18056 6197 6209 18057 6209 6198 18058 6198 6199 18059 6199 6197 18060 6197 6210 18061 6210 6196 18062 6196 6210 18063 6210 6197 18064 6197 6209 18065 6209 6196 18066 6196 6211 18067 6211 6195 18068 6195 6211 18069 6211 6196 18070 6196 6210 18071 6210 6199 18072 6199 6201 18073 6201 6209 18074 6209 6201 18075 6201 6199 18076 6199 6200 18077 6200 6209 18078 6209 6202 18079 6202 6210 18080 6210 6202 18081 6202 6209 18082 6209 6201 18083 6201 6210 18084 6210 6203 18085 6203 6211 18086 6211 6203 18087 6203 6210 18088 6210 6202 18089 6202 6195 18090 6195 6212 18091 6212 6194 18092 6194 6212 18093 6212 6195 18094 6195 6211 18095 6211 6194 18096 6194 6213 18097 6213 6193 18098 6193 6213 18099 6213 6194 18100 6194 6212 18101 6212 6193 18102 6193 6214 18103 6214 6192 18104 6192 6214 18105 6214 6193 18106 6193 6213 18107 6213 6192 18108 6192 6215 18109 6215 6191 18110 6191 6215 18111 6215 6192 18112 6192 6214 18113 6214 6211 18114 6211 6204 18115 6204 6212 18116 6212 6204 18117 6204 6211 18118 6211 6203 18119 6203 6212 18120 6212 6205 18121 6205 6213 18122 6213 6205 18123 6205 6212 18124 6212 6204 18125 6204 6213 18126 6213 6206 18127 6206 6214 18128 6214 6206 18129 6206 6213 18130 6213 6205 18131 6205 6214 18132 6214 6207 18133 6207 6215 18134 6215 6207 18135 6207 6214 18136 6214 6206 18137 6206 6191 18138 6191 6216 18139 6216 6190 18140 6190 6216 18141 6216 6191 18142 6191 6215 18143 6215 6190 18144 6190 6217 18145 6217 6189 18146 6189 6217 18147 6217 6190 18148 6190 6216 18149 6216 6189 18150 6189 6218 18151 6218 6188 18152 6188 6218 18153 6218 6189 18154 6189 6217 18155 6217 6188 18156 6188 6219 18157 6219 6187 18158 6187 6219 18159 6219 6188 18160 6188 6218 18161 6218 6215 18162 6215 6208 18163 6208 6216 18164 6216 6208 18165 6208 6215 18166 6215 6207 18167 6207 6216 18168 6216 6177 18169 6177 6217 18170 6217 6177 18171 6177 6216 18172 6216 6208 18173 6208 6217 18174 6217 6178 18175 6178 6218 18176 6218 6178 18177 6178 6217 18178 6217 6177 18179 6177 6218 18180 6218 6179 18181 6179 6219 18182 6219 6179 18183 6179 6218 18184 6218 6178 18185 6178 6187 18186 6187 6220 18187 6220 6186 18188 6186 6220 18189 6220 6187 18190 6187 6219 18191 6219 6186 18192 6186 6221 18193 6221 6185 18194 6185 6221 18195 6221 6186 18196 6186 6220 18197 6220 6185 18198 6185 6183 18199 6183 6184 18200 6184 6183 18201 6183 6185 18202 6185 6221 18203 6221 6219 18204 6219 6180 18205 6180 6220 18206 6220 6180 18207 6180 6219 18208 6219 6179 18209 6179 6220 18210 6220 6181 18211 6181 6221 18212 6221 6181 18213 6181 6220 18214 6220 6180 18215 6180 6221 18216 6221 6182 18217 6182 6183 18218 6183 6182 18219 6182 6221 18220 6221 6181 18221 6181 6249 18222 6249 6222 18223 6222 6223 18224 6223 6250 18225 6250 6224 18226 6224 6228 18227 6228 6251 18228 6251 6224 18229 6224 6250 18230 6250 6251 18231 6251 6225 18232 6225 6224 18233 6224 6252 18234 6252 6225 18235 6225 6251 18236 6251 6252 18237 6252 6226 18238 6226 6225 18239 6225 6253 18240 6253 6226 18241 6226 6252 18242 6252 6253 18243 6253 6227 18244 6227 6226 18245 6226 6228 18246 6228 6254 18247 6254 6250 18248 6250 6229 18249 6229 6254 18250 6254 6228 18251 6228 6230 18252 6230 6254 18253 6254 6229 18254 6229 6230 18255 6230 6255 18256 6255 6254 18257 6254 6231 18258 6231 6255 18259 6255 6230 18260 6230 6231 18261 6231 6256 18262 6256 6255 18263 6255 6222 18264 6222 6256 18265 6256 6231 18266 6231 6227 18267 6227 6232 18268 6232 6233 18269 6233 6253 18270 6253 6232 18271 6232 6227 18272 6227 6257 18273 6257 6232 18274 6232 6253 18275 6253 6257 18276 6257 6234 18277 6234 6232 18278 6232 6257 18279 6257 6235 18280 6235 6234 18281 6234 6258 18282 6258 6235 18283 6235 6257 18284 6257 6258 18285 6258 6236 18286 6236 6235 18287 6235 6258 18288 6258 6237 18289 6237 6236 18290 6236 6258 18291 6258 6238 18292 6238 6237 18293 6237 6259 18294 6259 6238 18295 6238 6258 18296 6258 6259 18297 6259 6239 18298 6239 6238 18299 6238 6260 18300 6260 6239 18301 6239 6259 18302 6259 6260 18303 6260 6240 18304 6240 6239 18305 6239 6261 18306 6261 6240 18307 6240 6260 18308 6260 6261 18309 6261 6241 18310 6241 6240 18311 6240 6262 18312 6262 6241 18313 6241 6261 18314 6261 6262 18315 6262 6242 18316 6242 6241 18317 6241 6262 18318 6262 6243 18319 6243 6242 18320 6242 6263 18321 6263 6243 18322 6243 6262 18323 6262 6263 18324 6263 6244 18325 6244 6243 18326 6243 6264 18327 6264 6244 18328 6244 6263 18329 6263 6264 18330 6264 6245 18331 6245 6244 18332 6244 6245 18333 6245 6246 18334 6246 6247 18335 6247 6264 18336 6264 6246 18337 6246 6245 18338 6245 6264 18339 6264 6248 18340 6248 6246 18341 6246 6265 18342 6265 6248 18343 6248 6264 18344 6264 6265 18345 6265 6249 18346 6249 6248 18347 6248 6256 18348 6256 6249 18349 6249 6265 18350 6265 6222 18351 6222 6249 18352 6249 6256 18353 6256 6258 18354 6258 6266 18355 6266 6259 18356 6259 6266 18357 6266 6258 18358 6258 6257 18359 6257 6259 18360 6259 6267 18361 6267 6260 18362 6260 6267 18363 6267 6259 18364 6259 6266 18365 6266 6260 18366 6260 6268 18367 6268 6261 18368 6261 6268 18369 6268 6260 18370 6260 6267 18371 6267 6257 18372 6257 6252 18373 6252 6266 18374 6266 6252 18375 6252 6257 18376 6257 6253 18377 6253 6266 18378 6266 6251 18379 6251 6267 18380 6267 6251 18381 6251 6266 18382 6266 6252 18383 6252 6267 18384 6267 6250 18385 6250 6268 18386 6268 6250 18387 6250 6267 18388 6267 6251 18389 6251 6261 18390 6261 6269 18391 6269 6262 18392 6262 6269 18393 6269 6261 18394 6261 6268 18395 6268 6262 18396 6262 6270 18397 6270 6263 18398 6263 6270 18399 6270 6262 18400 6262 6269 18401 6269 6263 18402 6263 6265 18403 6265 6264 18404 6264 6265 18405 6265 6263 18406 6263 6270 18407 6270 6268 18408 6268 6254 18409 6254 6269 18410 6269 6254 18411 6254 6268 18412 6268 6250 18413 6250 6269 18414 6269 6255 18415 6255 6270 18416 6270 6255 18417 6255 6269 18418 6269 6254 18419 6254 6270 18420 6270 6256 18421 6256 6265 18422 6265 6256 18423 6256 6270 18424 6270 6255 18425 6255 6279 18426 6279 6271 18427 6271 6278 18428 6278 6274 18429 6274 6272 18430 6272 6273 18431 6273 6275 18432 6275 6272 18433 6272 6274 18434 6274 6277 18435 6277 6272 18436 6272 6275 18437 6275 6277 18438 6277 6276 18439 6276 6272 18440 6272 6279 18441 6279 6276 18442 6276 6277 18443 6277 6279 18444 6279 6278 18445 6278 6276 18446 6276 6271 18447 6271 6279 18448 6279 6280 18449 6280 6289 18450 6289 6281 18451 6281 6282 18452 6282 6286 18453 6286 6283 18454 6283 6284 18455 6284 6286 18456 6286 6285 18457 6285 6283 18458 6283 6288 18459 6288 6285 18460 6285 6286 18461 6286 6288 18462 6288 6287 18463 6287 6285 18464 6285 6290 18465 6290 6287 18466 6287 6288 18467 6288 6290 18468 6290 6289 18469 6289 6287 18470 6287 6281 18471 6281 6289 18472 6289 6290 18473 6290 6318 18474 6318 6319 18475 6319 6291 18476 6291 6320 18477 6320 6291 18478 6291 6319 18479 6319 6320 18480 6320 6292 18481 6292 6291 18482 6291 6320 18483 6320 6293 18484 6293 6292 18485 6292 6321 18486 6321 6293 18487 6293 6320 18488 6320 6321 18489 6321 6294 18490 6294 6293 18491 6293 6322 18492 6322 6294 18493 6294 6321 18494 6321 6322 18495 6322 6295 18496 6295 6294 18497 6294 6295 18498 6295 6296 18499 6296 6297 18500 6297 6322 18501 6322 6296 18502 6296 6295 18503 6295 6323 18504 6323 6296 18505 6296 6322 18506 6322 6323 18507 6323 6298 18508 6298 6296 18509 6296 6324 18510 6324 6298 18511 6298 6323 18512 6323 6324 18513 6324 6299 18514 6299 6298 18515 6298 6324 18516 6324 6300 18517 6300 6299 18518 6299 6324 18519 6324 6301 18520 6301 6300 18521 6300 6324 18522 6324 6302 18523 6302 6301 18524 6301 6325 18525 6325 6302 18526 6302 6324 18527 6324 6325 18528 6325 6303 18529 6303 6302 18530 6302 6326 18531 6326 6303 18532 6303 6325 18533 6325 6326 18534 6326 6304 18535 6304 6303 18536 6303 6327 18537 6327 6304 18538 6304 6326 18539 6326 6327 18540 6327 6305 18541 6305 6304 18542 6304 6327 18543 6327 6306 18544 6306 6305 18545 6305 6328 18546 6328 6306 18547 6306 6327 18548 6327 6328 18549 6328 6307 18550 6307 6306 18551 6306 6329 18552 6329 6307 18553 6307 6328 18554 6328 6329 18555 6329 6308 18556 6308 6307 18557 6307 6330 18558 6330 6308 18559 6308 6329 18560 6329 6330 18561 6330 6309 18562 6309 6308 18563 6308 6309 18564 6309 6310 18565 6310 6311 18566 6311 6330 18567 6330 6310 18568 6310 6309 18569 6309 6331 18570 6331 6310 18571 6310 6330 18572 6330 6331 18573 6331 6312 18574 6312 6310 18575 6310 6332 18576 6332 6312 18577 6312 6331 18578 6331 6332 18579 6332 6313 18580 6313 6312 18581 6312 6332 18582 6332 6314 18583 6314 6313 18584 6313 6332 18585 6332 6315 18586 6315 6314 18587 6314 6332 18588 6332 6316 18589 6316 6315 18590 6315 6333 18591 6333 6316 18592 6316 6332 18593 6332 6333 18594 6333 6317 18595 6317 6316 18596 6316 6334 18597 6334 6317 18598 6317 6333 18599 6333 6334 18600 6334 6318 18601 6318 6317 18602 6317 6319 18603 6319 6318 18604 6318 6334 18605 6334 6330 18606 6330 6335 18607 6335 6331 18608 6331 6335 18609 6335 6330 18610 6330 6329 18611 6329 6331 18612 6331 6333 18613 6333 6332 18614 6332 6333 18615 6333 6331 18616 6331 6335 18617 6335 6329 18618 6329 6336 18619 6336 6335 18620 6335 6336 18621 6336 6329 18622 6329 6328 18623 6328 6328 18624 6328 6337 18625 6337 6336 18626 6336 6337 18627 6337 6328 18628 6328 6327 18629 6327 6335 18630 6335 6334 18631 6334 6333 18632 6333 6334 18633 6334 6335 18634 6335 6336 18635 6336 6336 18636 6336 6319 18637 6319 6334 18638 6334 6319 18639 6319 6336 18640 6336 6337 18641 6337 6327 18642 6327 6338 18643 6338 6337 18644 6337 6338 18645 6338 6327 18646 6327 6326 18647 6326 6326 18648 6326 6339 18649 6339 6338 18650 6338 6339 18651 6339 6326 18652 6326 6325 18653 6325 6337 18654 6337 6320 18655 6320 6319 18656 6319 6320 18657 6320 6337 18658 6337 6338 18659 6338 6338 18660 6338 6321 18661 6321 6320 18662 6320 6321 18663 6321 6338 18664 6338 6339 18665 6339 6325 18666 6325 6323 18667 6323 6339 18668 6339 6323 18669 6323 6325 18670 6325 6324 18671 6324 6339 18672 6339 6322 18673 6322 6321 18674 6321 6322 18675 6322 6339 18676 6339 6323 18677 6323 6379 18678 6379 6340 18679 6340 6341 18680 6341 6380 18681 6380 6340 18682 6340 6381 18683 6381 6380 18684 6380 6342 18685 6342 6340 18686 6340 6382 18687 6382 6342 18688 6342 6380 18689 6380 6382 18690 6382 6343 18691 6343 6342 18692 6342 6383 18693 6383 6343 18694 6343 6382 18695 6382 6383 18696 6383 6344 18697 6344 6343 18698 6343 6384 18699 6384 6344 18700 6344 6383 18701 6383 6384 18702 6384 6345 18703 6345 6344 18704 6344 6385 18705 6385 6345 18706 6345 6384 18707 6384 6385 18708 6385 6346 18709 6346 6345 18710 6345 6386 18711 6386 6346 18712 6346 6385 18713 6385 6386 18714 6386 6347 18715 6347 6346 18716 6346 6387 18717 6387 6347 18718 6347 6386 18719 6386 6387 18720 6387 6348 18721 6348 6347 18722 6347 6388 18723 6388 6348 18724 6348 6387 18725 6387 6388 18726 6388 6349 18727 6349 6348 18728 6348 6389 18729 6389 6349 18730 6349 6388 18731 6388 6389 18732 6389 6350 18733 6350 6349 18734 6349 6390 18735 6390 6350 18736 6350 6389 18737 6389 6390 18738 6390 6351 18739 6351 6350 18740 6350 6391 18741 6391 6351 18742 6351 6390 18743 6390 6391 18744 6391 6352 18745 6352 6351 18746 6351 6392 18747 6392 6352 18748 6352 6391 18749 6391 6392 18750 6392 6353 18751 6353 6352 18752 6352 6393 18753 6393 6353 18754 6353 6392 18755 6392 6393 18756 6393 6354 18757 6354 6353 18758 6353 6394 18759 6394 6354 18760 6354 6393 18761 6393 6394 18762 6394 6355 18763 6355 6354 18764 6354 6394 18765 6394 6356 18766 6356 6355 18767 6355 6394 18768 6394 6357 18769 6357 6356 18770 6356 6395 18771 6395 6357 18772 6357 6394 18773 6394 6395 18774 6395 6358 18775 6358 6357 18776 6357 6396 18777 6396 6358 18778 6358 6395 18779 6395 6396 18780 6396 6359 18781 6359 6358 18782 6358 6396 18783 6396 6360 18784 6360 6359 18785 6359 6396 18786 6396 6361 18787 6361 6360 18788 6360 6397 18789 6397 6361 18790 6361 6396 18791 6396 6397 18792 6397 6362 18793 6362 6361 18794 6361 6398 18795 6398 6362 18796 6362 6397 18797 6397 6398 18798 6398 6363 18799 6363 6362 18800 6362 6399 18801 6399 6363 18802 6363 6398 18803 6398 6399 18804 6399 6364 18805 6364 6363 18806 6363 6400 18807 6400 6364 18808 6364 6399 18809 6399 6400 18810 6400 6365 18811 6365 6364 18812 6364 6401 18813 6401 6365 18814 6365 6400 18815 6400 6401 18816 6401 6366 18817 6366 6365 18818 6365 6402 18819 6402 6366 18820 6366 6401 18821 6401 6402 18822 6402 6367 18823 6367 6366 18824 6366 6403 18825 6403 6367 18826 6367 6402 18827 6402 6403 18828 6403 6368 18829 6368 6367 18830 6367 6404 18831 6404 6368 18832 6368 6403 18833 6403 6404 18834 6404 6369 18835 6369 6368 18836 6368 6405 18837 6405 6369 18838 6369 6404 18839 6404 6405 18840 6405 6370 18841 6370 6369 18842 6369 6406 18843 6406 6370 18844 6370 6405 18845 6405 6406 18846 6406 6371 18847 6371 6370 18848 6370 6407 18849 6407 6371 18850 6371 6406 18851 6406 6407 18852 6407 6372 18853 6372 6371 18854 6371 6408 18855 6408 6372 18856 6372 6407 18857 6407 6408 18858 6408 6373 18859 6373 6372 18860 6372 6409 18861 6409 6373 18862 6373 6408 18863 6408 6409 18864 6409 6374 18865 6374 6373 18866 6373 6410 18867 6410 6374 18868 6374 6409 18869 6409 6410 18870 6410 6375 18871 6375 6374 18872 6374 6410 18873 6410 6376 18874 6376 6375 18875 6375 6410 18876 6410 6377 18877 6377 6376 18878 6376 6411 18879 6411 6377 18880 6377 6410 18881 6410 6411 18882 6411 6378 18883 6378 6377 18884 6377 6381 18885 6381 6378 18886 6378 6411 18887 6411 6381 18888 6381 6379 18889 6379 6378 18890 6378 6340 18891 6340 6379 18892 6379 6381 18893 6381 6410 18894 6410 6412 18895 6412 6411 18896 6411 6412 18897 6412 6410 18898 6410 6409 18899 6409 6411 18900 6411 6380 18901 6380 6381 18902 6381 6380 18903 6380 6411 18904 6411 6412 18905 6412 6409 18906 6409 6413 18907 6413 6412 18908 6412 6413 18909 6413 6409 18910 6409 6408 18911 6408 6408 18912 6408 6414 18913 6414 6413 18914 6413 6414 18915 6414 6408 18916 6408 6407 18917 6407 6412 18918 6412 6382 18919 6382 6380 18920 6380 6382 18921 6382 6412 18922 6412 6413 18923 6413 6413 18924 6413 6383 18925 6383 6382 18926 6382 6383 18927 6383 6413 18928 6413 6414 18929 6414 6407 18930 6407 6415 18931 6415 6414 18932 6414 6415 18933 6415 6407 18934 6407 6406 18935 6406 6406 18936 6406 6416 18937 6416 6415 18938 6415 6416 18939 6416 6406 18940 6406 6405 18941 6405 6414 18942 6414 6384 18943 6384 6383 18944 6383 6384 18945 6384 6414 18946 6414 6415 18947 6415 6415 18948 6415 6385 18949 6385 6384 18950 6384 6385 18951 6385 6415 18952 6415 6416 18953 6416 6405 18954 6405 6417 18955 6417 6416 18956 6416 6417 18957 6417 6405 18958 6405 6404 18959 6404 6404 18960 6404 6418 18961 6418 6417 18962 6417 6418 18963 6418 6404 18964 6404 6403 18965 6403 6416 18966 6416 6386 18967 6386 6385 18968 6385 6386 18969 6386 6416 18970 6416 6417 18971 6417 6417 18972 6417 6387 18973 6387 6386 18974 6386 6387 18975 6387 6417 18976 6417 6418 18977 6418 6403 18978 6403 6419 18979 6419 6418 18980 6418 6419 18981 6419 6403 18982 6403 6402 18983 6402 6402 18984 6402 6420 18985 6420 6419 18986 6419 6420 18987 6420 6402 18988 6402 6401 18989 6401 6418 18990 6418 6388 18991 6388 6387 18992 6387 6388 18993 6388 6418 18994 6418 6419 18995 6419 6419 18996 6419 6389 18997 6389 6388 18998 6388 6389 18999 6389 6419 19000 6419 6420 19001 6420 6401 19002 6401 6421 19003 6421 6420 19004 6420 6421 19005 6421 6401 19006 6401 6400 19007 6400 6400 19008 6400 6422 19009 6422 6421 19010 6421 6422 19011 6422 6400 19012 6400 6399 19013 6399 6420 19014 6420 6390 19015 6390 6389 19016 6389 6390 19017 6390 6420 19018 6420 6421 19019 6421 6421 19020 6421 6391 19021 6391 6390 19022 6390 6391 19023 6391 6421 19024 6421 6422 19025 6422 6399 19026 6399 6423 19027 6423 6422 19028 6422 6423 19029 6423 6399 19030 6399 6398 19031 6398 6398 19032 6398 6424 19033 6424 6423 19034 6423 6424 19035 6424 6398 19036 6398 6397 19037 6397 6422 19038 6422 6392 19039 6392 6391 19040 6391 6392 19041 6392 6422 19042 6422 6423 19043 6423 6423 19044 6423 6393 19045 6393 6392 19046 6392 6393 19047 6393 6423 19048 6423 6424 19049 6424 6397 19050 6397 6395 19051 6395 6424 19052 6424 6395 19053 6395 6397 19054 6397 6396 19055 6396 6424 19056 6424 6394 19057 6394 6393 19058 6393 6394 19059 6394 6424 19060 6424 6395 19061 6395 6433 19062 6433 6425 19063 6425 6426 19064 6426 6429 19065 6429 6427 19066 6427 6428 19067 6428 6430 19068 6430 6427 19069 6427 6429 19070 6429 6432 19071 6432 6427 19072 6427 6430 19073 6430 6432 19074 6432 6431 19075 6431 6427 19076 6427 6434 19077 6434 6431 19078 6431 6432 19079 6432 6434 19080 6434 6433 19081 6433 6431 19082 6431 6425 19083 6425 6433 19084 6433 6434 19085 6434 6448 19086 6448 6435 19087 6435 6436 19088 6436 6439 19089 6439 6437 19090 6437 6438 19091 6438 6441 19092 6441 6437 19093 6437 6439 19094 6439 6441 19095 6441 6440 19096 6440 6437 19097 6437 6443 19098 6443 6440 19099 6440 6441 19100 6441 6443 19101 6443 6442 19102 6442 6440 19103 6440 6445 19104 6445 6442 19105 6442 6443 19106 6443 6445 19107 6445 6444 19108 6444 6442 19109 6442 6447 19110 6447 6444 19111 6444 6445 19112 6445 6447 19113 6447 6446 19114 6446 6444 19115 6444 6435 19116 6435 6446 19117 6446 6447 19118 6447 6435 19119 6435 6448 19120 6448 6446 19121 6446 6480 19122 6480 6449 19123 6449 6450 19124 6450 6481 19125 6481 6451 19126 6451 6455 19127 6455 6482 19128 6482 6451 19129 6451 6481 19130 6481 6482 19131 6482 6452 19132 6452 6451 19133 6451 6483 19134 6483 6452 19135 6452 6482 19136 6482 6483 19137 6483 6453 19138 6453 6452 19139 6452 6484 19140 6484 6453 19141 6453 6483 19142 6483 6484 19143 6484 6454 19144 6454 6453 19145 6453 6455 19146 6455 6485 19147 6485 6481 19148 6481 6456 19149 6456 6485 19150 6485 6455 19151 6455 6457 19152 6457 6485 19153 6485 6456 19154 6456 6457 19155 6457 6486 19156 6486 6485 19157 6485 6458 19158 6458 6486 19159 6486 6457 19160 6457 6458 19161 6458 6487 19162 6487 6486 19163 6486 6449 19164 6449 6487 19165 6487 6458 19166 6458 6454 19167 6454 6459 19168 6459 6460 19169 6460 6484 19170 6484 6459 19171 6459 6454 19172 6454 6488 19173 6488 6459 19174 6459 6484 19175 6484 6488 19176 6488 6461 19177 6461 6459 19178 6459 6489 19179 6489 6461 19180 6461 6488 19181 6488 6489 19182 6489 6462 19183 6462 6461 19184 6461 6490 19185 6490 6462 19186 6462 6489 19187 6489 6490 19188 6490 6463 19189 6463 6462 19190 6462 6491 19191 6491 6463 19192 6463 6490 19193 6490 6491 19194 6491 6464 19195 6464 6463 19196 6463 6491 19197 6491 6465 19198 6465 6464 19199 6464 6491 19200 6491 6466 19201 6466 6465 19202 6465 6491 19203 6491 6467 19204 6467 6466 19205 6466 6492 19206 6492 6467 19207 6467 6491 19208 6491 6492 19209 6492 6468 19210 6468 6467 19211 6467 6493 19212 6493 6468 19213 6468 6492 19214 6492 6493 19215 6493 6469 19216 6469 6468 19217 6468 6494 19218 6494 6469 19219 6469 6493 19220 6493 6494 19221 6494 6470 19222 6470 6469 19223 6469 6495 19224 6495 6470 19225 6470 6494 19226 6494 6495 19227 6495 6471 19228 6471 6470 19229 6470 6495 19230 6495 6472 19231 6472 6471 19232 6471 6496 19233 6496 6472 19234 6472 6495 19235 6495 6496 19236 6496 6473 19237 6473 6472 19238 6472 6497 19239 6497 6473 19240 6473 6496 19241 6496 6497 19242 6497 6474 19243 6474 6473 19244 6473 6474 19245 6474 6475 19246 6475 6476 19247 6476 6497 19248 6497 6475 19249 6475 6474 19250 6474 6498 19251 6498 6475 19252 6475 6497 19253 6497 6498 19254 6498 6477 19255 6477 6475 19256 6475 6499 19257 6499 6477 19258 6477 6498 19259 6498 6499 19260 6499 6478 19261 6478 6477 19262 6477 6500 19263 6500 6478 19264 6478 6499 19265 6499 6500 19266 6500 6479 19267 6479 6478 19268 6478 6487 19269 6487 6479 19270 6479 6500 19271 6500 6487 19272 6487 6480 19273 6480 6479 19274 6479 6449 19275 6449 6480 19276 6480 6487 19277 6487 6497 19278 6497 6501 19279 6501 6498 19280 6498 6501 19281 6501 6497 19282 6497 6496 19283 6496 6498 19284 6498 6502 19285 6502 6499 19286 6499 6502 19287 6502 6498 19288 6498 6501 19289 6501 6499 19290 6499 6503 19291 6503 6500 19292 6500 6503 19293 6503 6499 19294 6499 6502 19295 6502 6500 19296 6500 6486 19297 6486 6487 19298 6487 6486 19299 6486 6500 19300 6500 6503 19301 6503 6496 19302 6496 6504 19303 6504 6501 19304 6501 6504 19305 6504 6496 19306 6496 6495 19307 6495 6501 19308 6501 6505 19309 6505 6502 19310 6502 6505 19311 6505 6501 19312 6501 6504 19313 6504 6495 19314 6495 6506 19315 6506 6504 19316 6504 6506 19317 6506 6495 19318 6495 6494 19319 6494 6504 19320 6504 6507 19321 6507 6505 19322 6505 6507 19323 6507 6504 19324 6504 6506 19325 6506 6502 19326 6502 6508 19327 6508 6503 19328 6503 6508 19329 6508 6502 19330 6502 6505 19331 6505 6503 19332 6503 6485 19333 6485 6486 19334 6486 6485 19335 6485 6503 19336 6503 6508 19337 6508 6505 19338 6505 6509 19339 6509 6508 19340 6508 6509 19341 6509 6505 19342 6505 6507 19343 6507 6508 19344 6508 6481 19345 6481 6485 19346 6485 6481 19347 6481 6508 19348 6508 6509 19349 6509 6494 19350 6494 6510 19351 6510 6506 19352 6506 6510 19353 6510 6494 19354 6494 6493 19355 6493 6506 19356 6506 6511 19357 6511 6507 19358 6507 6511 19359 6511 6506 19360 6506 6510 19361 6510 6493 19362 6493 6512 19363 6512 6510 19364 6510 6512 19365 6512 6493 19366 6493 6492 19367 6492 6510 19368 6510 6513 19369 6513 6511 19370 6511 6513 19371 6513 6510 19372 6510 6512 19373 6512 6507 19374 6507 6514 19375 6514 6509 19376 6509 6514 19377 6514 6507 19378 6507 6511 19379 6511 6509 19380 6509 6482 19381 6482 6481 19382 6481 6482 19383 6482 6509 19384 6509 6514 19385 6514 6511 19386 6511 6515 19387 6515 6514 19388 6514 6515 19389 6515 6511 19390 6511 6513 19391 6513 6514 19392 6514 6483 19393 6483 6482 19394 6482 6483 19395 6483 6514 19396 6514 6515 19397 6515 6492 19398 6492 6490 19399 6490 6512 19400 6512 6490 19401 6490 6492 19402 6492 6491 19403 6491 6512 19404 6512 6489 19405 6489 6513 19406 6513 6489 19407 6489 6512 19408 6512 6490 19409 6490 6513 19410 6513 6488 19411 6488 6515 19412 6515 6488 19413 6488 6513 19414 6513 6489 19415 6489 6515 19416 6515 6484 19417 6484 6483 19418 6483 6484 19419 6484 6515 19420 6515 6488 19421 6488 6559 19422 6559 6560 19423 6560 6516 19424 6516 6534 19425 6534 6517 19426 6517 6518 19427 6518 6561 19428 6561 6516 19429 6516 6560 19430 6560 6561 19431 6561 6519 19432 6519 6516 19433 6516 6562 19434 6562 6519 19435 6519 6561 19436 6561 6562 19437 6562 6520 19438 6520 6519 19439 6519 6563 19440 6563 6520 19441 6520 6562 19442 6562 6563 19443 6563 6521 19444 6521 6520 19445 6520 6564 19446 6564 6521 19447 6521 6563 19448 6563 6564 19449 6564 6522 19450 6522 6521 19451 6521 6565 19452 6565 6522 19453 6522 6564 19454 6564 6565 19455 6565 6523 19456 6523 6522 19457 6522 6566 19458 6566 6523 19459 6523 6565 19460 6565 6566 19461 6566 6524 19462 6524 6523 19463 6523 6567 19464 6567 6524 19465 6524 6566 19466 6566 6567 19467 6567 6525 19468 6525 6524 19469 6524 6568 19470 6568 6525 19471 6525 6567 19472 6567 6568 19473 6568 6526 19474 6526 6525 19475 6525 6569 19476 6569 6526 19477 6526 6568 19478 6568 6569 19479 6569 6527 19480 6527 6526 19481 6526 6570 19482 6570 6527 19483 6527 6569 19484 6569 6570 19485 6570 6528 19486 6528 6527 19487 6527 6570 19488 6570 6529 19489 6529 6528 19490 6528 6570 19491 6570 6530 19492 6530 6529 19493 6529 6571 19494 6571 6530 19495 6530 6570 19496 6570 6571 19497 6571 6531 19498 6531 6530 19499 6530 6572 19500 6572 6531 19501 6531 6571 19502 6571 6572 19503 6572 6532 19504 6532 6531 19505 6531 6572 19506 6572 6533 19507 6533 6532 19508 6532 6573 19509 6573 6533 19510 6533 6572 19511 6572 6574 19512 6574 6533 19513 6533 6573 19514 6573 6574 19515 6574 6534 19516 6534 6533 19517 6533 6574 19518 6574 6517 19519 6517 6534 19520 6534 6574 19521 6574 6535 19522 6535 6517 19523 6517 6575 19524 6575 6535 19525 6535 6574 19526 6574 6575 19527 6575 6536 19528 6536 6535 19529 6535 6576 19530 6576 6536 19531 6536 6575 19532 6575 6576 19533 6576 6537 19534 6537 6536 19535 6536 6577 19536 6577 6537 19537 6537 6576 19538 6576 6577 19539 6577 6538 19540 6538 6537 19541 6537 6578 19542 6578 6538 19543 6538 6577 19544 6577 6578 19545 6578 6539 19546 6539 6538 19547 6538 6579 19548 6579 6539 19549 6539 6578 19550 6578 6579 19551 6579 6540 19552 6540 6539 19553 6539 6580 19554 6580 6540 19555 6540 6579 19556 6579 6580 19557 6580 6541 19558 6541 6540 19559 6540 6581 19560 6581 6541 19561 6541 6580 19562 6580 6581 19563 6581 6542 19564 6542 6541 19565 6541 6582 19566 6582 6542 19567 6542 6581 19568 6581 6582 19569 6582 6543 19570 6543 6542 19571 6542 6583 19572 6583 6543 19573 6543 6582 19574 6582 6583 19575 6583 6544 19576 6544 6543 19577 6543 6584 19578 6584 6544 19579 6544 6583 19580 6583 6584 19581 6584 6545 19582 6545 6544 19583 6544 6585 19584 6585 6545 19585 6545 6584 19586 6584 6585 19587 6585 6546 19588 6546 6545 19589 6545 6586 19590 6586 6546 19591 6546 6585 19592 6585 6586 19593 6586 6547 19594 6547 6546 19595 6546 6587 19596 6587 6547 19597 6547 6586 19598 6586 6587 19599 6587 6548 19600 6548 6547 19601 6547 6588 19602 6588 6548 19603 6548 6587 19604 6587 6588 19605 6588 6549 19606 6549 6548 19607 6548 6588 19608 6588 6550 19609 6550 6549 19610 6549 6589 19611 6589 6550 19612 6550 6588 19613 6588 6589 19614 6589 6551 19615 6551 6550 19616 6550 6589 19617 6589 6552 19618 6552 6551 19619 6551 6590 19620 6590 6552 19621 6552 6589 19622 6589 6591 19623 6591 6552 19624 6552 6590 19625 6590 6591 19626 6591 6553 19627 6553 6552 19628 6552 6592 19629 6592 6553 19630 6553 6591 19631 6591 6592 19632 6592 6554 19633 6554 6553 19634 6553 6592 19635 6592 6555 19636 6555 6554 19637 6554 6592 19638 6592 6556 19639 6556 6555 19640 6555 6593 19641 6593 6556 19642 6556 6592 19643 6592 6593 19644 6593 6557 19645 6557 6556 19646 6556 6594 19647 6594 6557 19648 6557 6593 19649 6593 6594 19650 6594 6558 19651 6558 6557 19652 6557 6595 19653 6595 6558 19654 6558 6594 19655 6594 6595 19656 6595 6559 19657 6559 6558 19658 6558 6560 19659 6560 6559 19660 6559 6595 19661 6595 6588 19662 6588 6596 19663 6596 6589 19664 6589 6596 19665 6596 6588 19666 6588 6587 19667 6587 6589 19668 6589 6597 19669 6597 6590 19670 6590 6597 19671 6597 6589 19672 6589 6596 19673 6596 6590 19674 6590 6598 19675 6598 6591 19676 6591 6598 19677 6598 6590 19678 6590 6597 19679 6597 6591 19680 6591 6593 19681 6593 6592 19682 6592 6593 19683 6593 6591 19684 6591 6598 19685 6598 6587 19686 6587 6599 19687 6599 6596 19688 6596 6599 19689 6599 6587 19690 6587 6586 19691 6586 6596 19692 6596 6600 19693 6600 6597 19694 6597 6600 19695 6600 6596 19696 6596 6599 19697 6599 6597 19698 6597 6601 19699 6601 6598 19700 6598 6601 19701 6601 6597 19702 6597 6600 19703 6600 6598 19704 6598 6594 19705 6594 6593 19706 6593 6594 19707 6594 6598 19708 6598 6601 19709 6601 6586 19710 6586 6602 19711 6602 6599 19712 6599 6602 19713 6602 6586 19714 6586 6585 19715 6585 6599 19716 6599 6603 19717 6603 6600 19718 6600 6603 19719 6603 6599 19720 6599 6602 19721 6602 6600 19722 6600 6604 19723 6604 6601 19724 6601 6604 19725 6604 6600 19726 6600 6603 19727 6603 6601 19728 6601 6595 19729 6595 6594 19730 6594 6595 19731 6595 6601 19732 6601 6604 19733 6604 6585 19734 6585 6605 19735 6605 6602 19736 6602 6605 19737 6605 6585 19738 6585 6584 19739 6584 6602 19740 6602 6606 19741 6606 6603 19742 6603 6606 19743 6606 6602 19744 6602 6605 19745 6605 6603 19746 6603 6607 19747 6607 6604 19748 6604 6607 19749 6607 6603 19750 6603 6606 19751 6606 6604 19752 6604 6560 19753 6560 6595 19754 6595 6560 19755 6560 6604 19756 6604 6607 19757 6607 6584 19758 6584 6608 19759 6608 6605 19760 6605 6608 19761 6608 6584 19762 6584 6583 19763 6583 6605 19764 6605 6609 19765 6609 6606 19766 6606 6609 19767 6609 6605 19768 6605 6608 19769 6608 6606 19770 6606 6610 19771 6610 6607 19772 6607 6610 19773 6610 6606 19774 6606 6609 19775 6609 6607 19776 6607 6561 19777 6561 6560 19778 6560 6561 19779 6561 6607 19780 6607 6610 19781 6610 6583 19782 6583 6611 19783 6611 6608 19784 6608 6611 19785 6611 6583 19786 6583 6582 19787 6582 6608 19788 6608 6612 19789 6612 6609 19790 6609 6612 19791 6612 6608 19792 6608 6611 19793 6611 6582 19794 6582 6613 19795 6613 6611 19796 6611 6613 19797 6613 6582 19798 6582 6581 19799 6581 6611 19800 6611 6614 19801 6614 6612 19802 6612 6614 19803 6614 6611 19804 6611 6613 19805 6613 6609 19806 6609 6615 19807 6615 6610 19808 6610 6615 19809 6615 6609 19810 6609 6612 19811 6612 6610 19812 6610 6562 19813 6562 6561 19814 6561 6562 19815 6562 6610 19816 6610 6615 19817 6615 6612 19818 6612 6616 19819 6616 6615 19820 6615 6616 19821 6616 6612 19822 6612 6614 19823 6614 6615 19824 6615 6563 19825 6563 6562 19826 6562 6563 19827 6563 6615 19828 6615 6616 19829 6616 6581 19830 6581 6617 19831 6617 6613 19832 6613 6617 19833 6617 6581 19834 6581 6580 19835 6580 6613 19836 6613 6618 19837 6618 6614 19838 6614 6618 19839 6618 6613 19840 6613 6617 19841 6617 6580 19842 6580 6619 19843 6619 6617 19844 6617 6619 19845 6619 6580 19846 6580 6579 19847 6579 6617 19848 6617 6620 19849 6620 6618 19850 6618 6620 19851 6620 6617 19852 6617 6619 19853 6619 6614 19854 6614 6621 19855 6621 6616 19856 6616 6621 19857 6621 6614 19858 6614 6618 19859 6618 6616 19860 6616 6564 19861 6564 6563 19862 6563 6564 19863 6564 6616 19864 6616 6621 19865 6621 6618 19866 6618 6622 19867 6622 6621 19868 6621 6622 19869 6622 6618 19870 6618 6620 19871 6620 6621 19872 6621 6565 19873 6565 6564 19874 6564 6565 19875 6565 6621 19876 6621 6622 19877 6622 6579 19878 6579 6623 19879 6623 6619 19880 6619 6623 19881 6623 6579 19882 6579 6578 19883 6578 6619 19884 6619 6624 19885 6624 6620 19886 6620 6624 19887 6624 6619 19888 6619 6623 19889 6623 6620 19890 6620 6625 19891 6625 6622 19892 6622 6625 19893 6625 6620 19894 6620 6624 19895 6624 6622 19896 6622 6566 19897 6566 6565 19898 6565 6566 19899 6566 6622 19900 6622 6625 19901 6625 6578 19902 6578 6626 19903 6626 6623 19904 6623 6626 19905 6626 6578 19906 6578 6577 19907 6577 6623 19908 6623 6627 19909 6627 6624 19910 6624 6627 19911 6627 6623 19912 6623 6626 19913 6626 6624 19914 6624 6628 19915 6628 6625 19916 6625 6628 19917 6628 6624 19918 6624 6627 19919 6627 6625 19920 6625 6567 19921 6567 6566 19922 6566 6567 19923 6567 6625 19924 6625 6628 19925 6628 6577 19926 6577 6629 19927 6629 6626 19928 6626 6629 19929 6629 6577 19930 6577 6576 19931 6576 6626 19932 6626 6630 19933 6630 6627 19934 6627 6630 19935 6630 6626 19936 6626 6629 19937 6629 6627 19938 6627 6631 19939 6631 6628 19940 6628 6631 19941 6631 6627 19942 6627 6630 19943 6630 6628 19944 6628 6568 19945 6568 6567 19946 6567 6568 19947 6568 6628 19948 6628 6631 19949 6631 6576 19950 6576 6632 19951 6632 6629 19952 6629 6632 19953 6632 6576 19954 6576 6575 19955 6575 6629 19956 6629 6633 19957 6633 6630 19958 6630 6633 19959 6633 6629 19960 6629 6632 19961 6632 6630 19962 6630 6634 19963 6634 6631 19964 6631 6634 19965 6634 6630 19966 6630 6633 19967 6633 6631 19968 6631 6569 19969 6569 6568 19970 6568 6569 19971 6569 6631 19972 6631 6634 19973 6634 6575 19974 6575 6573 19975 6573 6632 19976 6632 6573 19977 6573 6575 19978 6575 6574 19979 6574 6632 19980 6632 6572 19981 6572 6633 19982 6633 6572 19983 6572 6632 19984 6632 6573 19985 6573 6633 19986 6633 6571 19987 6571 6634 19988 6634 6571 19989 6571 6633 19990 6633 6572 19991 6572 6634 19992 6634 6570 19993 6570 6569 19994 6569 6570 19995 6570 6634 19996 6634 6571 19997 6571 6648 19998 6648 6635 19999 6635 6636 20000 6636 6641 20001 6641 6637 20002 6637 6638 20003 6638 6641 20004 6641 6639 20005 6639 6637 20006 6637 6641 20007 6641 6640 20008 6640 6639 20009 6639 6643 20010 6643 6640 20011 6640 6641 20012 6641 6643 20013 6643 6642 20014 6642 6640 20015 6640 6645 20016 6645 6642 20017 6642 6643 20018 6643 6645 20019 6645 6644 20020 6644 6642 20021 6642 6647 20022 6647 6644 20023 6644 6645 20024 6645 6647 20025 6647 6646 20026 6646 6644 20027 6644 6635 20028 6635 6646 20029 6646 6647 20030 6647 6635 20031 6635 6648 20032 6648 6646 20033 6646 6670 20034 6670 6671 20035 6671 6649 20036 6649 6656 20037 6656 6650 20038 6650 6651 20039 6651 6672 20040 6672 6649 20041 6649 6671 20042 6671 6672 20043 6672 6652 20044 6652 6649 20045 6649 6673 20046 6673 6652 20047 6652 6672 20048 6672 6673 20049 6673 6653 20050 6653 6652 20051 6652 6674 20052 6674 6653 20053 6653 6673 20054 6673 6674 20055 6674 6654 20056 6654 6653 20057 6653 6674 20058 6674 6655 20059 6655 6654 20060 6654 6675 20061 6675 6655 20062 6655 6674 20063 6674 6676 20064 6676 6655 20065 6655 6675 20066 6675 6676 20067 6676 6656 20068 6656 6655 20069 6655 6676 20070 6676 6650 20071 6650 6656 20072 6656 6677 20073 6677 6650 20074 6650 6676 20075 6676 6677 20076 6677 6657 20077 6657 6650 20078 6650 6678 20079 6678 6657 20080 6657 6677 20081 6677 6678 20082 6678 6658 20083 6658 6657 20084 6657 6679 20085 6679 6658 20086 6658 6678 20087 6678 6679 20088 6679 6659 20089 6659 6658 20090 6658 6680 20091 6680 6659 20092 6659 6679 20093 6679 6680 20094 6680 6660 20095 6660 6659 20096 6659 6681 20097 6681 6660 20098 6660 6680 20099 6680 6681 20100 6681 6661 20101 6661 6660 20102 6660 6681 20103 6681 6662 20104 6662 6661 20105 6661 6682 20106 6682 6662 20107 6662 6681 20108 6681 6682 20109 6682 6663 20110 6663 6662 20111 6662 6683 20112 6683 6663 20113 6663 6682 20114 6682 6684 20115 6684 6663 20116 6663 6683 20117 6683 6684 20118 6684 6664 20119 6664 6663 20120 6663 6684 20121 6684 6665 20122 6665 6664 20123 6664 6684 20124 6684 6666 20125 6666 6665 20126 6665 6684 20127 6684 6667 20128 6667 6666 20129 6666 6685 20130 6685 6667 20131 6667 6684 20132 6684 6685 20133 6685 6668 20134 6668 6667 20135 6667 6686 20136 6686 6668 20137 6668 6685 20138 6685 6686 20139 6686 6669 20140 6669 6668 20141 6668 6686 20142 6686 6670 20143 6670 6669 20144 6669 6671 20145 6671 6670 20146 6670 6686 20147 6686 6676 20148 6676 6687 20149 6687 6677 20150 6677 6687 20151 6687 6676 20152 6676 6675 20153 6675 6675 20154 6675 6688 20155 6688 6687 20156 6687 6688 20157 6688 6675 20158 6675 6674 20159 6674 6674 20160 6674 6689 20161 6689 6688 20162 6688 6689 20163 6689 6674 20164 6674 6673 20165 6673 6677 20166 6677 6679 20167 6679 6678 20168 6678 6679 20169 6679 6677 20170 6677 6687 20171 6687 6687 20172 6687 6680 20173 6680 6679 20174 6679 6680 20175 6680 6687 20176 6687 6688 20177 6688 6688 20178 6688 6681 20179 6681 6680 20180 6680 6681 20181 6681 6688 20182 6688 6689 20183 6689 6673 20184 6673 6690 20185 6690 6689 20186 6689 6690 20187 6690 6673 20188 6673 6672 20189 6672 6672 20190 6672 6691 20191 6691 6690 20192 6690 6691 20193 6691 6672 20194 6672 6671 20195 6671 6671 20196 6671 6685 20197 6685 6691 20198 6691 6685 20199 6685 6671 20200 6671 6686 20201 6686 6689 20202 6689 6682 20203 6682 6681 20204 6681 6682 20205 6682 6689 20206 6689 6690 20207 6690 6690 20208 6690 6683 20209 6683 6682 20210 6682 6683 20211 6683 6690 20212 6690 6691 20213 6691 6691 20214 6691 6684 20215 6684 6683 20216 6683 6684 20217 6684 6691 20218 6691 6685 20219 6685 6709 20220 6709 6692 20221 6692 6693 20222 6693 6697 20223 6697 6694 20224 6694 6695 20225 6695 6697 20226 6697 6696 20227 6696 6694 20228 6694 6700 20229 6700 6696 20230 6696 6697 20231 6697 6700 20232 6700 6698 20233 6698 6696 20234 6696 6700 20235 6700 6699 20236 6699 6698 20237 6698 6701 20238 6701 6699 20239 6699 6700 20240 6700 6703 20241 6703 6699 20242 6699 6701 20243 6701 6703 20244 6703 6702 20245 6702 6699 20246 6699 6705 20247 6705 6702 20248 6702 6703 20249 6703 6705 20250 6705 6704 20251 6704 6702 20252 6702 6707 20253 6707 6704 20254 6704 6705 20255 6705 6707 20256 6707 6706 20257 6706 6704 20258 6704 6692 20259 6692 6706 20260 6706 6707 20261 6707 6692 20262 6692 6708 20263 6708 6706 20264 6706 6692 20265 6692 6709 20266 6709 6708 20267 6708 6773 20268 6773 6710 20269 6710 6712 20270 6712 6712 20271 6712 6711 20272 6711 6773 20273 6773 6714 20274 6714 6711 20275 6711 6712 20276 6712 6714 20277 6714 6713 20278 6713 6711 20279 6711 6716 20280 6716 6713 20281 6713 6714 20282 6714 6716 20283 6716 6715 20284 6715 6713 20285 6713 6718 20286 6718 6715 20287 6715 6716 20288 6716 6718 20289 6718 6717 20290 6717 6715 20291 6715 6720 20292 6720 6717 20293 6717 6718 20294 6718 6720 20295 6720 6719 20296 6719 6717 20297 6717 6722 20298 6722 6719 20299 6719 6720 20300 6720 6722 20301 6722 6721 20302 6721 6719 20303 6719 6724 20304 6724 6721 20305 6721 6722 20306 6722 6724 20307 6724 6723 20308 6723 6721 20309 6721 6726 20310 6726 6723 20311 6723 6724 20312 6724 6726 20313 6726 6725 20314 6725 6723 20315 6723 6728 20316 6728 6725 20317 6725 6726 20318 6726 6728 20319 6728 6727 20320 6727 6725 20321 6725 6730 20322 6730 6727 20323 6727 6728 20324 6728 6730 20325 6730 6729 20326 6729 6727 20327 6727 6732 20328 6732 6729 20329 6729 6730 20330 6730 6732 20331 6732 6731 20332 6731 6729 20333 6729 6734 20334 6734 6731 20335 6731 6732 20336 6732 6734 20337 6734 6733 20338 6733 6731 20339 6731 6736 20340 6736 6733 20341 6733 6734 20342 6734 6736 20343 6736 6735 20344 6735 6733 20345 6733 6738 20346 6738 6735 20347 6735 6736 20348 6736 6738 20349 6738 6737 20350 6737 6735 20351 6735 6740 20352 6740 6737 20353 6737 6738 20354 6738 6740 20355 6740 6739 20356 6739 6737 20357 6737 6742 20358 6742 6739 20359 6739 6740 20360 6740 6742 20361 6742 6741 20362 6741 6739 20363 6739 6744 20364 6744 6741 20365 6741 6742 20366 6742 6744 20367 6744 6743 20368 6743 6741 20369 6741 6746 20370 6746 6743 20371 6743 6744 20372 6744 6746 20373 6746 6745 20374 6745 6743 20375 6743 6748 20376 6748 6745 20377 6745 6746 20378 6746 6748 20379 6748 6747 20380 6747 6745 20381 6745 6750 20382 6750 6747 20383 6747 6748 20384 6748 6750 20385 6750 6749 20386 6749 6747 20387 6747 6752 20388 6752 6749 20389 6749 6750 20390 6750 6752 20391 6752 6751 20392 6751 6749 20393 6749 6754 20394 6754 6751 20395 6751 6752 20396 6752 6754 20397 6754 6753 20398 6753 6751 20399 6751 6756 20400 6756 6753 20401 6753 6754 20402 6754 6756 20403 6756 6755 20404 6755 6753 20405 6753 6758 20406 6758 6755 20407 6755 6756 20408 6756 6758 20409 6758 6757 20410 6757 6755 20411 6755 6760 20412 6760 6757 20413 6757 6758 20414 6758 6760 20415 6760 6759 20416 6759 6757 20417 6757 6762 20418 6762 6759 20419 6759 6760 20420 6760 6762 20421 6762 6761 20422 6761 6759 20423 6759 6764 20424 6764 6761 20425 6761 6762 20426 6762 6764 20427 6764 6763 20428 6763 6761 20429 6761 6766 20430 6766 6763 20431 6763 6764 20432 6764 6766 20433 6766 6765 20434 6765 6763 20435 6763 6768 20436 6768 6765 20437 6765 6766 20438 6766 6768 20439 6768 6767 20440 6767 6765 20441 6765 6770 20442 6770 6767 20443 6767 6768 20444 6768 6770 20445 6770 6769 20446 6769 6767 20447 6767 6772 20448 6772 6769 20449 6769 6770 20450 6770 6772 20451 6772 6771 20452 6771 6769 20453 6769 6710 20454 6710 6771 20455 6771 6772 20456 6772 6710 20457 6710 6773 20458 6773 6771 20459 6771 6806 20460 6806 6774 20461 6774 6775 20462 6775 6778 20463 6778 6776 20464 6776 6777 20465 6777 6779 20466 6779 6776 20467 6776 6778 20468 6778 6781 20469 6781 6776 20470 6776 6779 20471 6779 6781 20472 6781 6780 20473 6780 6776 20474 6776 6783 20475 6783 6780 20476 6780 6781 20477 6781 6783 20478 6783 6782 20479 6782 6780 20480 6780 6785 20481 6785 6782 20482 6782 6783 20483 6783 6785 20484 6785 6784 20485 6784 6782 20486 6782 6788 20487 6788 6784 20488 6784 6785 20489 6785 6788 20490 6788 6786 20491 6786 6784 20492 6784 6788 20493 6788 6787 20494 6787 6786 20495 6786 6789 20496 6789 6787 20497 6787 6788 20498 6788 6791 20499 6791 6787 20500 6787 6789 20501 6789 6791 20502 6791 6790 20503 6790 6787 20504 6787 6793 20505 6793 6790 20506 6790 6791 20507 6791 6793 20508 6793 6792 20509 6792 6790 20510 6790 6795 20511 6795 6792 20512 6792 6793 20513 6793 6795 20514 6795 6794 20515 6794 6792 20516 6792 6797 20517 6797 6794 20518 6794 6795 20519 6795 6797 20520 6797 6796 20521 6796 6794 20522 6794 6799 20523 6799 6796 20524 6796 6797 20525 6797 6799 20526 6799 6798 20527 6798 6796 20528 6796 6801 20529 6801 6798 20530 6798 6799 20531 6799 6801 20532 6801 6800 20533 6800 6798 20534 6798 6803 20535 6803 6800 20536 6800 6801 20537 6801 6803 20538 6803 6802 20539 6802 6800 20540 6800 6805 20541 6805 6802 20542 6802 6803 20543 6803 6805 20544 6805 6804 20545 6804 6802 20546 6802 6807 20547 6807 6804 20548 6804 6805 20549 6805 6807 20550 6807 6806 20551 6806 6804 20552 6804 6774 20553 6774 6806 20554 6806 6807 20555 6807 6871 20556 6871 6808 20557 6808 6810 20558 6810 6810 20559 6810 6809 20560 6809 6871 20561 6871 6812 20562 6812 6809 20563 6809 6810 20564 6810 6812 20565 6812 6811 20566 6811 6809 20567 6809 6814 20568 6814 6811 20569 6811 6812 20570 6812 6814 20571 6814 6813 20572 6813 6811 20573 6811 6816 20574 6816 6813 20575 6813 6814 20576 6814 6816 20577 6816 6815 20578 6815 6813 20579 6813 6818 20580 6818 6815 20581 6815 6816 20582 6816 6818 20583 6818 6817 20584 6817 6815 20585 6815 6820 20586 6820 6817 20587 6817 6818 20588 6818 6820 20589 6820 6819 20590 6819 6817 20591 6817 6822 20592 6822 6819 20593 6819 6820 20594 6820 6822 20595 6822 6821 20596 6821 6819 20597 6819 6824 20598 6824 6821 20599 6821 6822 20600 6822 6824 20601 6824 6823 20602 6823 6821 20603 6821 6826 20604 6826 6823 20605 6823 6824 20606 6824 6826 20607 6826 6825 20608 6825 6823 20609 6823 6828 20610 6828 6825 20611 6825 6826 20612 6826 6828 20613 6828 6827 20614 6827 6825 20615 6825 6830 20616 6830 6827 20617 6827 6828 20618 6828 6830 20619 6830 6829 20620 6829 6827 20621 6827 6832 20622 6832 6829 20623 6829 6830 20624 6830 6832 20625 6832 6831 20626 6831 6829 20627 6829 6834 20628 6834 6831 20629 6831 6832 20630 6832 6834 20631 6834 6833 20632 6833 6831 20633 6831 6836 20634 6836 6833 20635 6833 6834 20636 6834 6836 20637 6836 6835 20638 6835 6833 20639 6833 6838 20640 6838 6835 20641 6835 6836 20642 6836 6838 20643 6838 6837 20644 6837 6835 20645 6835 6840 20646 6840 6837 20647 6837 6838 20648 6838 6840 20649 6840 6839 20650 6839 6837 20651 6837 6842 20652 6842 6839 20653 6839 6840 20654 6840 6842 20655 6842 6841 20656 6841 6839 20657 6839 6844 20658 6844 6841 20659 6841 6842 20660 6842 6844 20661 6844 6843 20662 6843 6841 20663 6841 6846 20664 6846 6843 20665 6843 6844 20666 6844 6846 20667 6846 6845 20668 6845 6843 20669 6843 6848 20670 6848 6845 20671 6845 6846 20672 6846 6848 20673 6848 6847 20674 6847 6845 20675 6845 6850 20676 6850 6847 20677 6847 6848 20678 6848 6850 20679 6850 6849 20680 6849 6847 20681 6847 6852 20682 6852 6849 20683 6849 6850 20684 6850 6852 20685 6852 6851 20686 6851 6849 20687 6849 6854 20688 6854 6851 20689 6851 6852 20690 6852 6854 20691 6854 6853 20692 6853 6851 20693 6851 6856 20694 6856 6853 20695 6853 6854 20696 6854 6856 20697 6856 6855 20698 6855 6853 20699 6853 6858 20700 6858 6855 20701 6855 6856 20702 6856 6858 20703 6858 6857 20704 6857 6855 20705 6855 6860 20706 6860 6857 20707 6857 6858 20708 6858 6860 20709 6860 6859 20710 6859 6857 20711 6857 6862 20712 6862 6859 20713 6859 6860 20714 6860 6862 20715 6862 6861 20716 6861 6859 20717 6859 6864 20718 6864 6861 20719 6861 6862 20720 6862 6864 20721 6864 6863 20722 6863 6861 20723 6861 6866 20724 6866 6863 20725 6863 6864 20726 6864 6866 20727 6866 6865 20728 6865 6863 20729 6863 6868 20730 6868 6865 20731 6865 6866 20732 6866 6868 20733 6868 6867 20734 6867 6865 20735 6865 6870 20736 6870 6867 20737 6867 6868 20738 6868 6870 20739 6870 6869 20740 6869 6867 20741 6867 6808 20742 6808 6869 20743 6869 6870 20744 6870 6808 20745 6808 6871 20746 6871 6869 20747 6869 6904 20748 6904 6872 20749 6872 6873 20750 6873 6876 20751 6876 6874 20752 6874 6875 20753 6875 6877 20754 6877 6874 20755 6874 6876 20756 6876 6879 20757 6879 6874 20758 6874 6877 20759 6877 6879 20760 6879 6878 20761 6878 6874 20762 6874 6881 20763 6881 6878 20764 6878 6879 20765 6879 6881 20766 6881 6880 20767 6880 6878 20768 6878 6883 20769 6883 6880 20770 6880 6881 20771 6881 6883 20772 6883 6882 20773 6882 6880 20774 6880 6885 20775 6885 6882 20776 6882 6883 20777 6883 6885 20778 6885 6884 20779 6884 6882 20780 6882 6887 20781 6887 6884 20782 6884 6885 20783 6885 6887 20784 6887 6886 20785 6886 6884 20786 6884 6889 20787 6889 6886 20788 6886 6887 20789 6887 6889 20790 6889 6888 20791 6888 6886 20792 6886 6891 20793 6891 6888 20794 6888 6889 20795 6889 6891 20796 6891 6890 20797 6890 6888 20798 6888 6893 20799 6893 6890 20800 6890 6891 20801 6891 6893 20802 6893 6892 20803 6892 6890 20804 6890 6895 20805 6895 6892 20806 6892 6893 20807 6893 6895 20808 6895 6894 20809 6894 6892 20810 6892 6897 20811 6897 6894 20812 6894 6895 20813 6895 6897 20814 6897 6896 20815 6896 6894 20816 6894 6899 20817 6899 6896 20818 6896 6897 20819 6897 6899 20820 6899 6898 20821 6898 6896 20822 6896 6901 20823 6901 6898 20824 6898 6899 20825 6899 6901 20826 6901 6900 20827 6900 6898 20828 6898 6903 20829 6903 6900 20830 6900 6901 20831 6901 6903 20832 6903 6902 20833 6902 6900 20834 6900 6905 20835 6905 6902 20836 6902 6903 20837 6903 6905 20838 6905 6904 20839 6904 6902 20840 6902 6872 20841 6872 6904 20842 6904 6905 20843 6905 6969 20844 6969 6906 20845 6906 6908 20846 6908 6908 20847 6908 6907 20848 6907 6969 20849 6969 6910 20850 6910 6907 20851 6907 6908 20852 6908 6910 20853 6910 6909 20854 6909 6907 20855 6907 6912 20856 6912 6909 20857 6909 6910 20858 6910 6912 20859 6912 6911 20860 6911 6909 20861 6909 6914 20862 6914 6911 20863 6911 6912 20864 6912 6914 20865 6914 6913 20866 6913 6911 20867 6911 6916 20868 6916 6913 20869 6913 6914 20870 6914 6916 20871 6916 6915 20872 6915 6913 20873 6913 6918 20874 6918 6915 20875 6915 6916 20876 6916 6918 20877 6918 6917 20878 6917 6915 20879 6915 6920 20880 6920 6917 20881 6917 6918 20882 6918 6920 20883 6920 6919 20884 6919 6917 20885 6917 6922 20886 6922 6919 20887 6919 6920 20888 6920 6922 20889 6922 6921 20890 6921 6919 20891 6919 6924 20892 6924 6921 20893 6921 6922 20894 6922 6924 20895 6924 6923 20896 6923 6921 20897 6921 6926 20898 6926 6923 20899 6923 6924 20900 6924 6926 20901 6926 6925 20902 6925 6923 20903 6923 6928 20904 6928 6925 20905 6925 6926 20906 6926 6928 20907 6928 6927 20908 6927 6925 20909 6925 6930 20910 6930 6927 20911 6927 6928 20912 6928 6930 20913 6930 6929 20914 6929 6927 20915 6927 6932 20916 6932 6929 20917 6929 6930 20918 6930 6932 20919 6932 6931 20920 6931 6929 20921 6929 6934 20922 6934 6931 20923 6931 6932 20924 6932 6934 20925 6934 6933 20926 6933 6931 20927 6931 6936 20928 6936 6933 20929 6933 6934 20930 6934 6936 20931 6936 6935 20932 6935 6933 20933 6933 6938 20934 6938 6935 20935 6935 6936 20936 6936 6938 20937 6938 6937 20938 6937 6935 20939 6935 6940 20940 6940 6937 20941 6937 6938 20942 6938 6940 20943 6940 6939 20944 6939 6937 20945 6937 6942 20946 6942 6939 20947 6939 6940 20948 6940 6942 20949 6942 6941 20950 6941 6939 20951 6939 6944 20952 6944 6941 20953 6941 6942 20954 6942 6944 20955 6944 6943 20956 6943 6941 20957 6941 6946 20958 6946 6943 20959 6943 6944 20960 6944 6946 20961 6946 6945 20962 6945 6943 20963 6943 6948 20964 6948 6945 20965 6945 6946 20966 6946 6948 20967 6948 6947 20968 6947 6945 20969 6945 6950 20970 6950 6947 20971 6947 6948 20972 6948 6950 20973 6950 6949 20974 6949 6947 20975 6947 6952 20976 6952 6949 20977 6949 6950 20978 6950 6952 20979 6952 6951 20980 6951 6949 20981 6949 6954 20982 6954 6951 20983 6951 6952 20984 6952 6954 20985 6954 6953 20986 6953 6951 20987 6951 6956 20988 6956 6953 20989 6953 6954 20990 6954 6956 20991 6956 6955 20992 6955 6953 20993 6953 6958 20994 6958 6955 20995 6955 6956 20996 6956 6958 20997 6958 6957 20998 6957 6955 20999 6955 6960 21000 6960 6957 21001 6957 6958 21002 6958 6960 21003 6960 6959 21004 6959 6957 21005 6957 6962 21006 6962 6959 21007 6959 6960 21008 6960 6962 21009 6962 6961 21010 6961 6959 21011 6959 6964 21012 6964 6961 21013 6961 6962 21014 6962 6964 21015 6964 6963 21016 6963 6961 21017 6961 6966 21018 6966 6963 21019 6963 6964 21020 6964 6966 21021 6966 6965 21022 6965 6963 21023 6963 6968 21024 6968 6965 21025 6965 6966 21026 6966 6968 21027 6968 6967 21028 6967 6965 21029 6965 6906 21030 6906 6967 21031 6967 6968 21032 6968 6906 21033 6906 6969 21034 6969 6967 21035 6967 7002 21036 7002 6970 21037 6970 6971 21038 6971 6974 21039 6974 6972 21040 6972 6973 21041 6973 6976 21042 6976 6972 21043 6972 6974 21044 6974 6976 21045 6976 6975 21046 6975 6972 21047 6972 6978 21048 6978 6975 21049 6975 6976 21050 6976 6978 21051 6978 6977 21052 6977 6975 21053 6975 6980 21054 6980 6977 21055 6977 6978 21056 6978 6980 21057 6980 6979 21058 6979 6977 21059 6977 6981 21060 6981 6979 21061 6979 6980 21062 6980 6983 21063 6983 6979 21064 6979 6981 21065 6981 6983 21066 6983 6982 21067 6982 6979 21068 6979 6985 21069 6985 6982 21070 6982 6983 21071 6983 6985 21072 6985 6984 21073 6984 6982 21074 6982 6987 21075 6987 6984 21076 6984 6985 21077 6985 6987 21078 6987 6986 21079 6986 6984 21080 6984 6989 21081 6989 6986 21082 6986 6987 21083 6987 6989 21084 6989 6988 21085 6988 6986 21086 6986 6991 21087 6991 6988 21088 6988 6989 21089 6989 6991 21090 6991 6990 21091 6990 6988 21092 6988 6993 21093 6993 6990 21094 6990 6991 21095 6991 6993 21096 6993 6992 21097 6992 6990 21098 6990 6995 21099 6995 6992 21100 6992 6993 21101 6993 6995 21102 6995 6994 21103 6994 6992 21104 6992 6997 21105 6997 6994 21106 6994 6995 21107 6995 6997 21108 6997 6996 21109 6996 6994 21110 6994 6999 21111 6999 6996 21112 6996 6997 21113 6997 6999 21114 6999 6998 21115 6998 6996 21116 6996 7001 21117 7001 6998 21118 6998 6999 21119 6999 7001 21120 7001 7000 21121 7000 6998 21122 6998 7003 21123 7003 7000 21124 7000 7001 21125 7001 7003 21126 7003 7002 21127 7002 7000 21128 7000 6970 21129 6970 7002 21130 7002 7003 21131 7003 7037 21132 7037 7004 21133 7004 7005 21134 7005 7008 21135 7008 7006 21136 7006 7007 21137 7007 7010 21138 7010 7006 21139 7006 7008 21140 7008 7010 21141 7010 7009 21142 7009 7006 21143 7006 7012 21144 7012 7009 21145 7009 7010 21146 7010 7012 21147 7012 7011 21148 7011 7009 21149 7009 7014 21150 7014 7011 21151 7011 7012 21152 7012 7014 21153 7014 7013 21154 7013 7011 21155 7011 7016 21156 7016 7013 21157 7013 7014 21158 7014 7016 21159 7016 7015 21160 7015 7013 21161 7013 7018 21162 7018 7015 21163 7015 7016 21164 7016 7018 21165 7018 7017 21166 7017 7015 21167 7015 7020 21168 7020 7017 21169 7017 7018 21170 7018 7020 21171 7020 7019 21172 7019 7017 21173 7017 7022 21174 7022 7019 21175 7019 7020 21176 7020 7022 21177 7022 7021 21178 7021 7019 21179 7019 7024 21180 7024 7021 21181 7021 7022 21182 7022 7024 21183 7024 7023 21184 7023 7021 21185 7021 7026 21186 7026 7023 21187 7023 7024 21188 7024 7026 21189 7026 7025 21190 7025 7023 21191 7023 7028 21192 7028 7025 21193 7025 7026 21194 7026 7028 21195 7028 7027 21196 7027 7025 21197 7025 7030 21198 7030 7027 21199 7027 7028 21200 7028 7030 21201 7030 7029 21202 7029 7027 21203 7027 7032 21204 7032 7029 21205 7029 7030 21206 7030 7032 21207 7032 7031 21208 7031 7029 21209 7029 7034 21210 7034 7031 21211 7031 7032 21212 7032 7034 21213 7034 7033 21214 7033 7031 21215 7031 7036 21216 7036 7033 21217 7033 7034 21218 7034 7036 21219 7036 7035 21220 7035 7033 21221 7033 7004 21222 7004 7035 21223 7035 7036 21224 7036 7004 21225 7004 7037 21226 7037 7035 21227 7035 7101 21228 7101 7038 21229 7038 7040 21230 7040 7040 21231 7040 7039 21232 7039 7101 21233 7101 7042 21234 7042 7039 21235 7039 7040 21236 7040 7042 21237 7042 7041 21238 7041 7039 21239 7039 7044 21240 7044 7041 21241 7041 7042 21242 7042 7044 21243 7044 7043 21244 7043 7041 21245 7041 7046 21246 7046 7043 21247 7043 7044 21248 7044 7046 21249 7046 7045 21250 7045 7043 21251 7043 7048 21252 7048 7045 21253 7045 7046 21254 7046 7048 21255 7048 7047 21256 7047 7045 21257 7045 7050 21258 7050 7047 21259 7047 7048 21260 7048 7050 21261 7050 7049 21262 7049 7047 21263 7047 7052 21264 7052 7049 21265 7049 7050 21266 7050 7052 21267 7052 7051 21268 7051 7049 21269 7049 7054 21270 7054 7051 21271 7051 7052 21272 7052 7054 21273 7054 7053 21274 7053 7051 21275 7051 7056 21276 7056 7053 21277 7053 7054 21278 7054 7056 21279 7056 7055 21280 7055 7053 21281 7053 7058 21282 7058 7055 21283 7055 7056 21284 7056 7058 21285 7058 7057 21286 7057 7055 21287 7055 7060 21288 7060 7057 21289 7057 7058 21290 7058 7060 21291 7060 7059 21292 7059 7057 21293 7057 7062 21294 7062 7059 21295 7059 7060 21296 7060 7062 21297 7062 7061 21298 7061 7059 21299 7059 7064 21300 7064 7061 21301 7061 7062 21302 7062 7064 21303 7064 7063 21304 7063 7061 21305 7061 7066 21306 7066 7063 21307 7063 7064 21308 7064 7066 21309 7066 7065 21310 7065 7063 21311 7063 7068 21312 7068 7065 21313 7065 7066 21314 7066 7068 21315 7068 7067 21316 7067 7065 21317 7065 7070 21318 7070 7067 21319 7067 7068 21320 7068 7070 21321 7070 7069 21322 7069 7067 21323 7067 7072 21324 7072 7069 21325 7069 7070 21326 7070 7072 21327 7072 7071 21328 7071 7069 21329 7069 7074 21330 7074 7071 21331 7071 7072 21332 7072 7074 21333 7074 7073 21334 7073 7071 21335 7071 7076 21336 7076 7073 21337 7073 7074 21338 7074 7076 21339 7076 7075 21340 7075 7073 21341 7073 7078 21342 7078 7075 21343 7075 7076 21344 7076 7078 21345 7078 7077 21346 7077 7075 21347 7075 7080 21348 7080 7077 21349 7077 7078 21350 7078 7080 21351 7080 7079 21352 7079 7077 21353 7077 7082 21354 7082 7079 21355 7079 7080 21356 7080 7082 21357 7082 7081 21358 7081 7079 21359 7079 7084 21360 7084 7081 21361 7081 7082 21362 7082 7084 21363 7084 7083 21364 7083 7081 21365 7081 7086 21366 7086 7083 21367 7083 7084 21368 7084 7086 21369 7086 7085 21370 7085 7083 21371 7083 7088 21372 7088 7085 21373 7085 7086 21374 7086 7088 21375 7088 7087 21376 7087 7085 21377 7085 7090 21378 7090 7087 21379 7087 7088 21380 7088 7090 21381 7090 7089 21382 7089 7087 21383 7087 7092 21384 7092 7089 21385 7089 7090 21386 7090 7092 21387 7092 7091 21388 7091 7089 21389 7089 7094 21390 7094 7091 21391 7091 7092 21392 7092 7094 21393 7094 7093 21394 7093 7091 21395 7091 7096 21396 7096 7093 21397 7093 7094 21398 7094 7096 21399 7096 7095 21400 7095 7093 21401 7093 7098 21402 7098 7095 21403 7095 7096 21404 7096 7098 21405 7098 7097 21406 7097 7095 21407 7095 7100 21408 7100 7097 21409 7097 7098 21410 7098 7100 21411 7100 7099 21412 7099 7097 21413 7097 7038 21414 7038 7099 21415 7099 7100 21416 7100 7038 21417 7038 7101 21418 7101 7099 21419 7099 7134 21420 7134 7102 21421 7102 7103 21422 7103 7107 21423 7107 7104 21424 7104 7105 21425 7105 7107 21426 7107 7106 21427 7106 7104 21428 7104 7109 21429 7109 7106 21430 7106 7107 21431 7107 7109 21432 7109 7108 21433 7108 7106 21434 7106 7111 21435 7111 7108 21436 7108 7109 21437 7109 7111 21438 7111 7110 21439 7110 7108 21440 7108 7113 21441 7113 7110 21442 7110 7111 21443 7111 7113 21444 7113 7112 21445 7112 7110 21446 7110 7115 21447 7115 7112 21448 7112 7113 21449 7113 7115 21450 7115 7114 21451 7114 7112 21452 7112 7117 21453 7117 7114 21454 7114 7115 21455 7115 7117 21456 7117 7116 21457 7116 7114 21458 7114 7119 21459 7119 7116 21460 7116 7117 21461 7117 7119 21462 7119 7118 21463 7118 7116 21464 7116 7121 21465 7121 7118 21466 7118 7119 21467 7119 7121 21468 7121 7120 21469 7120 7118 21470 7118 7123 21471 7123 7120 21472 7120 7121 21473 7121 7123 21474 7123 7122 21475 7122 7120 21476 7120 7125 21477 7125 7122 21478 7122 7123 21479 7123 7125 21480 7125 7124 21481 7124 7122 21482 7122 7127 21483 7127 7124 21484 7124 7125 21485 7125 7127 21486 7127 7126 21487 7126 7124 21488 7124 7129 21489 7129 7126 21490 7126 7127 21491 7127 7129 21492 7129 7128 21493 7128 7126 21494 7126 7131 21495 7131 7128 21496 7128 7129 21497 7129 7131 21498 7131 7130 21499 7130 7128 21500 7128 7133 21501 7133 7130 21502 7130 7131 21503 7131 7133 21504 7133 7132 21505 7132 7130 21506 7130 7135 21507 7135 7132 21508 7132 7133 21509 7133 7135 21510 7135 7134 21511 7134 7132 21512 7132 7102 21513 7102 7134 21514 7134 7135 21515 7135 7168 21516 7168 7137 21517 7137 7136 21518 7136 7139 21519 7139 7137 21520 7137 7138 21521 7138 7136 21522 7136 7137 21523 7137 7139 21524 7139 7143 21525 7143 7140 21526 7140 7141 21527 7141 7143 21528 7143 7142 21529 7142 7140 21530 7140 7145 21531 7145 7142 21532 7142 7143 21533 7143 7145 21534 7145 7144 21535 7144 7142 21536 7142 7147 21537 7147 7144 21538 7144 7145 21539 7145 7147 21540 7147 7146 21541 7146 7144 21542 7144 7149 21543 7149 7146 21544 7146 7147 21545 7147 7149 21546 7149 7148 21547 7148 7146 21548 7146 7151 21549 7151 7148 21550 7148 7149 21551 7149 7151 21552 7151 7150 21553 7150 7148 21554 7148 7153 21555 7153 7150 21556 7150 7151 21557 7151 7153 21558 7153 7152 21559 7152 7150 21560 7150 7155 21561 7155 7152 21562 7152 7153 21563 7153 7155 21564 7155 7154 21565 7154 7152 21566 7152 7157 21567 7157 7154 21568 7154 7155 21569 7155 7157 21570 7157 7156 21571 7156 7154 21572 7154 7159 21573 7159 7156 21574 7156 7157 21575 7157 7159 21576 7159 7158 21577 7158 7156 21578 7156 7161 21579 7161 7158 21580 7158 7159 21581 7159 7161 21582 7161 7160 21583 7160 7158 21584 7158 7163 21585 7163 7160 21586 7160 7161 21587 7161 7163 21588 7163 7162 21589 7162 7160 21590 7160 7165 21591 7165 7162 21592 7162 7163 21593 7163 7165 21594 7165 7164 21595 7164 7162 21596 7162 7167 21597 7167 7164 21598 7164 7165 21599 7165 7167 21600 7167 7166 21601 7166 7164 21602 7164 7169 21603 7169 7166 21604 7166 7167 21605 7167 7169 21606 7169 7168 21607 7168 7166 21608 7166 7137 21609 7137 7168 21610 7168 7169 21611 7169 7233 21612 7233 7170 21613 7170 7172 21614 7172 7172 21615 7172 7171 21616 7171 7233 21617 7233 7174 21618 7174 7171 21619 7171 7172 21620 7172 7174 21621 7174 7173 21622 7173 7171 21623 7171 7176 21624 7176 7173 21625 7173 7174 21626 7174 7176 21627 7176 7175 21628 7175 7173 21629 7173 7178 21630 7178 7175 21631 7175 7176 21632 7176 7178 21633 7178 7177 21634 7177 7175 21635 7175 7180 21636 7180 7177 21637 7177 7178 21638 7178 7180 21639 7180 7179 21640 7179 7177 21641 7177 7182 21642 7182 7179 21643 7179 7180 21644 7180 7182 21645 7182 7181 21646 7181 7179 21647 7179 7184 21648 7184 7181 21649 7181 7182 21650 7182 7184 21651 7184 7183 21652 7183 7181 21653 7181 7186 21654 7186 7183 21655 7183 7184 21656 7184 7186 21657 7186 7185 21658 7185 7183 21659 7183 7188 21660 7188 7185 21661 7185 7186 21662 7186 7188 21663 7188 7187 21664 7187 7185 21665 7185 7190 21666 7190 7187 21667 7187 7188 21668 7188 7190 21669 7190 7189 21670 7189 7187 21671 7187 7192 21672 7192 7189 21673 7189 7190 21674 7190 7192 21675 7192 7191 21676 7191 7189 21677 7189 7194 21678 7194 7191 21679 7191 7192 21680 7192 7194 21681 7194 7193 21682 7193 7191 21683 7191 7196 21684 7196 7193 21685 7193 7194 21686 7194 7196 21687 7196 7195 21688 7195 7193 21689 7193 7198 21690 7198 7195 21691 7195 7196 21692 7196 7198 21693 7198 7197 21694 7197 7195 21695 7195 7200 21696 7200 7197 21697 7197 7198 21698 7198 7200 21699 7200 7199 21700 7199 7197 21701 7197 7202 21702 7202 7199 21703 7199 7200 21704 7200 7202 21705 7202 7201 21706 7201 7199 21707 7199 7204 21708 7204 7201 21709 7201 7202 21710 7202 7204 21711 7204 7203 21712 7203 7201 21713 7201 7206 21714 7206 7203 21715 7203 7204 21716 7204 7206 21717 7206 7205 21718 7205 7203 21719 7203 7208 21720 7208 7205 21721 7205 7206 21722 7206 7208 21723 7208 7207 21724 7207 7205 21725 7205 7210 21726 7210 7207 21727 7207 7208 21728 7208 7210 21729 7210 7209 21730 7209 7207 21731 7207 7212 21732 7212 7209 21733 7209 7210 21734 7210 7212 21735 7212 7211 21736 7211 7209 21737 7209 7214 21738 7214 7211 21739 7211 7212 21740 7212 7214 21741 7214 7213 21742 7213 7211 21743 7211 7216 21744 7216 7213 21745 7213 7214 21746 7214 7216 21747 7216 7215 21748 7215 7213 21749 7213 7218 21750 7218 7215 21751 7215 7216 21752 7216 7218 21753 7218 7217 21754 7217 7215 21755 7215 7220 21756 7220 7217 21757 7217 7218 21758 7218 7220 21759 7220 7219 21760 7219 7217 21761 7217 7222 21762 7222 7219 21763 7219 7220 21764 7220 7222 21765 7222 7221 21766 7221 7219 21767 7219 7224 21768 7224 7221 21769 7221 7222 21770 7222 7224 21771 7224 7223 21772 7223 7221 21773 7221 7226 21774 7226 7223 21775 7223 7224 21776 7224 7226 21777 7226 7225 21778 7225 7223 21779 7223 7228 21780 7228 7225 21781 7225 7226 21782 7226 7228 21783 7228 7227 21784 7227 7225 21785 7225 7230 21786 7230 7227 21787 7227 7228 21788 7228 7230 21789 7230 7229 21790 7229 7227 21791 7227 7232 21792 7232 7229 21793 7229 7230 21794 7230 7232 21795 7232 7231 21796 7231 7229 21797 7229 7170 21798 7170 7231 21799 7231 7232 21800 7232 7170 21801 7170 7233 21802 7233 7231 21803 7231 7266 21804 7266 7235 21805 7235 7234 21806 7234 7237 21807 7237 7235 21808 7235 7236 21809 7236 7234 21810 7234 7235 21811 7235 7237 21812 7237 7241 21813 7241 7238 21814 7238 7239 21815 7239 7241 21816 7241 7240 21817 7240 7238 21818 7238 7243 21819 7243 7240 21820 7240 7241 21821 7241 7243 21822 7243 7242 21823 7242 7240 21824 7240 7245 21825 7245 7242 21826 7242 7243 21827 7243 7245 21828 7245 7244 21829 7244 7242 21830 7242 7247 21831 7247 7244 21832 7244 7245 21833 7245 7247 21834 7247 7246 21835 7246 7244 21836 7244 7249 21837 7249 7246 21838 7246 7247 21839 7247 7249 21840 7249 7248 21841 7248 7246 21842 7246 7251 21843 7251 7248 21844 7248 7249 21845 7249 7251 21846 7251 7250 21847 7250 7248 21848 7248 7253 21849 7253 7250 21850 7250 7251 21851 7251 7253 21852 7253 7252 21853 7252 7250 21854 7250 7255 21855 7255 7252 21856 7252 7253 21857 7253 7255 21858 7255 7254 21859 7254 7252 21860 7252 7257 21861 7257 7254 21862 7254 7255 21863 7255 7257 21864 7257 7256 21865 7256 7254 21866 7254 7259 21867 7259 7256 21868 7256 7257 21869 7257 7259 21870 7259 7258 21871 7258 7256 21872 7256 7261 21873 7261 7258 21874 7258 7259 21875 7259 7261 21876 7261 7260 21877 7260 7258 21878 7258 7263 21879 7263 7260 21880 7260 7261 21881 7261 7263 21882 7263 7262 21883 7262 7260 21884 7260 7265 21885 7265 7262 21886 7262 7263 21887 7263 7265 21888 7265 7264 21889 7264 7262 21890 7262 7267 21891 7267 7264 21892 7264 7265 21893 7265 7267 21894 7267 7266 21895 7266 7264 21896 7264 7235 21897 7235 7266 21898 7266 7267 21899 7267 7331 21900 7331 7268 21901 7268 7270 21902 7270 7270 21903 7270 7269 21904 7269 7331 21905 7331 7272 21906 7272 7269 21907 7269 7270 21908 7270 7272 21909 7272 7271 21910 7271 7269 21911 7269 7274 21912 7274 7271 21913 7271 7272 21914 7272 7274 21915 7274 7273 21916 7273 7271 21917 7271 7276 21918 7276 7273 21919 7273 7274 21920 7274 7276 21921 7276 7275 21922 7275 7273 21923 7273 7278 21924 7278 7275 21925 7275 7276 21926 7276 7278 21927 7278 7277 21928 7277 7275 21929 7275 7280 21930 7280 7277 21931 7277 7278 21932 7278 7280 21933 7280 7279 21934 7279 7277 21935 7277 7282 21936 7282 7279 21937 7279 7280 21938 7280 7282 21939 7282 7281 21940 7281 7279 21941 7279 7284 21942 7284 7281 21943 7281 7282 21944 7282 7284 21945 7284 7283 21946 7283 7281 21947 7281 7286 21948 7286 7283 21949 7283 7284 21950 7284 7286 21951 7286 7285 21952 7285 7283 21953 7283 7288 21954 7288 7285 21955 7285 7286 21956 7286 7288 21957 7288 7287 21958 7287 7285 21959 7285 7290 21960 7290 7287 21961 7287 7288 21962 7288 7290 21963 7290 7289 21964 7289 7287 21965 7287 7292 21966 7292 7289 21967 7289 7290 21968 7290 7292 21969 7292 7291 21970 7291 7289 21971 7289 7294 21972 7294 7291 21973 7291 7292 21974 7292 7294 21975 7294 7293 21976 7293 7291 21977 7291 7296 21978 7296 7293 21979 7293 7294 21980 7294 7296 21981 7296 7295 21982 7295 7293 21983 7293 7298 21984 7298 7295 21985 7295 7296 21986 7296 7298 21987 7298 7297 21988 7297 7295 21989 7295 7300 21990 7300 7297 21991 7297 7298 21992 7298 7300 21993 7300 7299 21994 7299 7297 21995 7297 7302 21996 7302 7299 21997 7299 7300 21998 7300 7302 21999 7302 7301 22000 7301 7299 22001 7299 7304 22002 7304 7301 22003 7301 7302 22004 7302 7304 22005 7304 7303 22006 7303 7301 22007 7301 7306 22008 7306 7303 22009 7303 7304 22010 7304 7306 22011 7306 7305 22012 7305 7303 22013 7303 7308 22014 7308 7305 22015 7305 7306 22016 7306 7308 22017 7308 7307 22018 7307 7305 22019 7305 7310 22020 7310 7307 22021 7307 7308 22022 7308 7310 22023 7310 7309 22024 7309 7307 22025 7307 7312 22026 7312 7309 22027 7309 7310 22028 7310 7312 22029 7312 7311 22030 7311 7309 22031 7309 7314 22032 7314 7311 22033 7311 7312 22034 7312 7314 22035 7314 7313 22036 7313 7311 22037 7311 7316 22038 7316 7313 22039 7313 7314 22040 7314 7316 22041 7316 7315 22042 7315 7313 22043 7313 7318 22044 7318 7315 22045 7315 7316 22046 7316 7318 22047 7318 7317 22048 7317 7315 22049 7315 7320 22050 7320 7317 22051 7317 7318 22052 7318 7320 22053 7320 7319 22054 7319 7317 22055 7317 7322 22056 7322 7319 22057 7319 7320 22058 7320 7322 22059 7322 7321 22060 7321 7319 22061 7319 7324 22062 7324 7321 22063 7321 7322 22064 7322 7324 22065 7324 7323 22066 7323 7321 22067 7321 7326 22068 7326 7323 22069 7323 7324 22070 7324 7326 22071 7326 7325 22072 7325 7323 22073 7323 7328 22074 7328 7325 22075 7325 7326 22076 7326 7328 22077 7328 7327 22078 7327 7325 22079 7325 7330 22080 7330 7327 22081 7327 7328 22082 7328 7330 22083 7330 7329 22084 7329 7327 22085 7327 7268 22086 7268 7329 22087 7329 7330 22088 7330 7268 22089 7268 7331 22090 7331 7329 22091 7329 7364 22092 7364 7332 22093 7332 7333 22094 7333 7337 22095 7337 7334 22096 7334 7335 22097 7335 7337 22098 7337 7336 22099 7336 7334 22100 7334 7339 22101 7339 7336 22102 7336 7337 22103 7337 7339 22104 7339 7338 22105 7338 7336 22106 7336 7341 22107 7341 7338 22108 7338 7339 22109 7339 7341 22110 7341 7340 22111 7340 7338 22112 7338 7343 22113 7343 7340 22114 7340 7341 22115 7341 7343 22116 7343 7342 22117 7342 7340 22118 7340 7345 22119 7345 7342 22120 7342 7343 22121 7343 7345 22122 7345 7344 22123 7344 7342 22124 7342 7347 22125 7347 7344 22126 7344 7345 22127 7345 7347 22128 7347 7346 22129 7346 7344 22130 7344 7349 22131 7349 7346 22132 7346 7347 22133 7347 7349 22134 7349 7348 22135 7348 7346 22136 7346 7351 22137 7351 7348 22138 7348 7349 22139 7349 7351 22140 7351 7350 22141 7350 7348 22142 7348 7353 22143 7353 7350 22144 7350 7351 22145 7351 7353 22146 7353 7352 22147 7352 7350 22148 7350 7355 22149 7355 7352 22150 7352 7353 22151 7353 7355 22152 7355 7354 22153 7354 7352 22154 7352 7357 22155 7357 7354 22156 7354 7355 22157 7355 7357 22158 7357 7356 22159 7356 7354 22160 7354 7359 22161 7359 7356 22162 7356 7357 22163 7357 7359 22164 7359 7358 22165 7358 7356 22166 7356 7361 22167 7361 7358 22168 7358 7359 22169 7359 7361 22170 7361 7360 22171 7360 7358 22172 7358 7363 22173 7363 7360 22174 7360 7361 22175 7361 7363 22176 7363 7362 22177 7362 7360 22178 7360 7365 22179 7365 7362 22180 7362 7363 22181 7363 7365 22182 7365 7364 22183 7364 7362 22184 7362 7332 22185 7332 7364 22186 7364 7365 22187 7365 7429 22188 7429 7366 22189 7366 7368 22190 7368 7368 22191 7368 7367 22192 7367 7429 22193 7429 7370 22194 7370 7367 22195 7367 7368 22196 7368 7370 22197 7370 7369 22198 7369 7367 22199 7367 7372 22200 7372 7369 22201 7369 7370 22202 7370 7372 22203 7372 7371 22204 7371 7369 22205 7369 7374 22206 7374 7371 22207 7371 7372 22208 7372 7374 22209 7374 7373 22210 7373 7371 22211 7371 7376 22212 7376 7373 22213 7373 7374 22214 7374 7376 22215 7376 7375 22216 7375 7373 22217 7373 7378 22218 7378 7375 22219 7375 7376 22220 7376 7378 22221 7378 7377 22222 7377 7375 22223 7375 7380 22224 7380 7377 22225 7377 7378 22226 7378 7380 22227 7380 7379 22228 7379 7377 22229 7377 7382 22230 7382 7379 22231 7379 7380 22232 7380 7382 22233 7382 7381 22234 7381 7379 22235 7379 7384 22236 7384 7381 22237 7381 7382 22238 7382 7384 22239 7384 7383 22240 7383 7381 22241 7381 7386 22242 7386 7383 22243 7383 7384 22244 7384 7386 22245 7386 7385 22246 7385 7383 22247 7383 7388 22248 7388 7385 22249 7385 7386 22250 7386 7388 22251 7388 7387 22252 7387 7385 22253 7385 7390 22254 7390 7387 22255 7387 7388 22256 7388 7390 22257 7390 7389 22258 7389 7387 22259 7387 7392 22260 7392 7389 22261 7389 7390 22262 7390 7392 22263 7392 7391 22264 7391 7389 22265 7389 7394 22266 7394 7391 22267 7391 7392 22268 7392 7394 22269 7394 7393 22270 7393 7391 22271 7391 7396 22272 7396 7393 22273 7393 7394 22274 7394 7396 22275 7396 7395 22276 7395 7393 22277 7393 7398 22278 7398 7395 22279 7395 7396 22280 7396 7398 22281 7398 7397 22282 7397 7395 22283 7395 7400 22284 7400 7397 22285 7397 7398 22286 7398 7400 22287 7400 7399 22288 7399 7397 22289 7397 7402 22290 7402 7399 22291 7399 7400 22292 7400 7402 22293 7402 7401 22294 7401 7399 22295 7399 7404 22296 7404 7401 22297 7401 7402 22298 7402 7404 22299 7404 7403 22300 7403 7401 22301 7401 7406 22302 7406 7403 22303 7403 7404 22304 7404 7406 22305 7406 7405 22306 7405 7403 22307 7403 7408 22308 7408 7405 22309 7405 7406 22310 7406 7408 22311 7408 7407 22312 7407 7405 22313 7405 7410 22314 7410 7407 22315 7407 7408 22316 7408 7410 22317 7410 7409 22318 7409 7407 22319 7407 7412 22320 7412 7409 22321 7409 7410 22322 7410 7412 22323 7412 7411 22324 7411 7409 22325 7409 7414 22326 7414 7411 22327 7411 7412 22328 7412 7414 22329 7414 7413 22330 7413 7411 22331 7411 7416 22332 7416 7413 22333 7413 7414 22334 7414 7416 22335 7416 7415 22336 7415 7413 22337 7413 7418 22338 7418 7415 22339 7415 7416 22340 7416 7418 22341 7418 7417 22342 7417 7415 22343 7415 7420 22344 7420 7417 22345 7417 7418 22346 7418 7420 22347 7420 7419 22348 7419 7417 22349 7417 7422 22350 7422 7419 22351 7419 7420 22352 7420 7422 22353 7422 7421 22354 7421 7419 22355 7419 7424 22356 7424 7421 22357 7421 7422 22358 7422 7424 22359 7424 7423 22360 7423 7421 22361 7421 7426 22362 7426 7423 22363 7423 7424 22364 7424 7426 22365 7426 7425 22366 7425 7423 22367 7423 7428 22368 7428 7425 22369 7425 7426 22370 7426 7428 22371 7428 7427 22372 7427 7425 22373 7425 7366 22374 7366 7427 22375 7427 7428 22376 7428 7366 22377 7366 7429 22378 7429 7427 22379 7427 7462 22380 7462 7433 22381 7433 7430 22382 7430 7430 22383 7430 7431 22384 7431 7432 22385 7432 7430 22386 7430 7433 22387 7433 7431 22388 7431 7437 22389 7437 7434 22390 7434 7435 22391 7435 7437 22392 7437 7436 22393 7436 7434 22394 7434 7440 22395 7440 7436 22396 7436 7437 22397 7437 7440 22398 7440 7438 22399 7438 7436 22400 7436 7440 22401 7440 7439 22402 7439 7438 22403 7438 7441 22404 7441 7439 22405 7439 7440 22406 7440 7443 22407 7443 7439 22408 7439 7441 22409 7441 7443 22410 7443 7442 22411 7442 7439 22412 7439 7446 22413 7446 7442 22414 7442 7443 22415 7443 7446 22416 7446 7444 22417 7444 7442 22418 7442 7446 22419 7446 7445 22420 7445 7444 22421 7444 7447 22422 7447 7445 22423 7445 7446 22424 7446 7449 22425 7449 7445 22426 7445 7447 22427 7447 7449 22428 7449 7448 22429 7448 7445 22430 7445 7451 22431 7451 7448 22432 7448 7449 22433 7449 7451 22434 7451 7450 22435 7450 7448 22436 7448 7453 22437 7453 7450 22438 7450 7451 22439 7451 7453 22440 7453 7452 22441 7452 7450 22442 7450 7455 22443 7455 7452 22444 7452 7453 22445 7453 7455 22446 7455 7454 22447 7454 7452 22448 7452 7457 22449 7457 7454 22450 7454 7455 22451 7455 7457 22452 7457 7456 22453 7456 7454 22454 7454 7459 22455 7459 7456 22456 7456 7457 22457 7457 7459 22458 7459 7458 22459 7458 7456 22460 7456 7461 22461 7461 7458 22462 7458 7459 22463 7459 7461 22464 7461 7460 22465 7460 7458 22466 7458 7463 22467 7463 7460 22468 7460 7461 22469 7461 7463 22470 7463 7462 22471 7462 7460 22472 7460 7433 22473 7433 7462 22474 7462 7463 22475 7463 7527 22476 7527 7464 22477 7464 7466 22478 7466 7466 22479 7466 7465 22480 7465 7527 22481 7527 7468 22482 7468 7465 22483 7465 7466 22484 7466 7468 22485 7468 7467 22486 7467 7465 22487 7465 7470 22488 7470 7467 22489 7467 7468 22490 7468 7470 22491 7470 7469 22492 7469 7467 22493 7467 7472 22494 7472 7469 22495 7469 7470 22496 7470 7472 22497 7472 7471 22498 7471 7469 22499 7469 7474 22500 7474 7471 22501 7471 7472 22502 7472 7474 22503 7474 7473 22504 7473 7471 22505 7471 7476 22506 7476 7473 22507 7473 7474 22508 7474 7476 22509 7476 7475 22510 7475 7473 22511 7473 7478 22512 7478 7475 22513 7475 7476 22514 7476 7478 22515 7478 7477 22516 7477 7475 22517 7475 7480 22518 7480 7477 22519 7477 7478 22520 7478 7480 22521 7480 7479 22522 7479 7477 22523 7477 7482 22524 7482 7479 22525 7479 7480 22526 7480 7482 22527 7482 7481 22528 7481 7479 22529 7479 7484 22530 7484 7481 22531 7481 7482 22532 7482 7484 22533 7484 7483 22534 7483 7481 22535 7481 7486 22536 7486 7483 22537 7483 7484 22538 7484 7486 22539 7486 7485 22540 7485 7483 22541 7483 7488 22542 7488 7485 22543 7485 7486 22544 7486 7488 22545 7488 7487 22546 7487 7485 22547 7485 7490 22548 7490 7487 22549 7487 7488 22550 7488 7490 22551 7490 7489 22552 7489 7487 22553 7487 7492 22554 7492 7489 22555 7489 7490 22556 7490 7492 22557 7492 7491 22558 7491 7489 22559 7489 7494 22560 7494 7491 22561 7491 7492 22562 7492 7494 22563 7494 7493 22564 7493 7491 22565 7491 7496 22566 7496 7493 22567 7493 7494 22568 7494 7496 22569 7496 7495 22570 7495 7493 22571 7493 7498 22572 7498 7495 22573 7495 7496 22574 7496 7498 22575 7498 7497 22576 7497 7495 22577 7495 7500 22578 7500 7497 22579 7497 7498 22580 7498 7500 22581 7500 7499 22582 7499 7497 22583 7497 7502 22584 7502 7499 22585 7499 7500 22586 7500 7502 22587 7502 7501 22588 7501 7499 22589 7499 7504 22590 7504 7501 22591 7501 7502 22592 7502 7504 22593 7504 7503 22594 7503 7501 22595 7501 7506 22596 7506 7503 22597 7503 7504 22598 7504 7506 22599 7506 7505 22600 7505 7503 22601 7503 7508 22602 7508 7505 22603 7505 7506 22604 7506 7508 22605 7508 7507 22606 7507 7505 22607 7505 7510 22608 7510 7507 22609 7507 7508 22610 7508 7510 22611 7510 7509 22612 7509 7507 22613 7507 7512 22614 7512 7509 22615 7509 7510 22616 7510 7512 22617 7512 7511 22618 7511 7509 22619 7509 7514 22620 7514 7511 22621 7511 7512 22622 7512 7514 22623 7514 7513 22624 7513 7511 22625 7511 7516 22626 7516 7513 22627 7513 7514 22628 7514 7516 22629 7516 7515 22630 7515 7513 22631 7513 7518 22632 7518 7515 22633 7515 7516 22634 7516 7518 22635 7518 7517 22636 7517 7515 22637 7515 7520 22638 7520 7517 22639 7517 7518 22640 7518 7520 22641 7520 7519 22642 7519 7517 22643 7517 7522 22644 7522 7519 22645 7519 7520 22646 7520 7522 22647 7522 7521 22648 7521 7519 22649 7519 7524 22650 7524 7521 22651 7521 7522 22652 7522 7524 22653 7524 7523 22654 7523 7521 22655 7521 7526 22656 7526 7523 22657 7523 7524 22658 7524 7526 22659 7526 7525 22660 7525 7523 22661 7523 7464 22662 7464 7525 22663 7525 7526 22664 7526 7464 22665 7464 7527 22666 7527 7525 22667 7525 7560 22668 7560 7528 22669 7528 7529 22670 7529 7532 22671 7532 7530 22672 7530 7531 22673 7531 7533 22674 7533 7530 22675 7530 7532 22676 7532 7536 22677 7536 7530 22678 7530 7533 22679 7533 7536 22680 7536 7534 22681 7534 7530 22682 7530 7536 22683 7536 7535 22684 7535 7534 22685 7534 7538 22686 7538 7535 22687 7535 7536 22688 7536 7538 22689 7538 7537 22690 7537 7535 22691 7535 7539 22692 7539 7537 22693 7537 7538 22694 7538 7541 22695 7541 7537 22696 7537 7539 22697 7539 7541 22698 7541 7540 22699 7540 7537 22700 7537 7543 22701 7543 7540 22702 7540 7541 22703 7541 7543 22704 7543 7542 22705 7542 7540 22706 7540 7545 22707 7545 7542 22708 7542 7543 22709 7543 7545 22710 7545 7544 22711 7544 7542 22712 7542 7547 22713 7547 7544 22714 7544 7545 22715 7545 7547 22716 7547 7546 22717 7546 7544 22718 7544 7549 22719 7549 7546 22720 7546 7547 22721 7547 7549 22722 7549 7548 22723 7548 7546 22724 7546 7551 22725 7551 7548 22726 7548 7549 22727 7549 7551 22728 7551 7550 22729 7550 7548 22730 7548 7553 22731 7553 7550 22732 7550 7551 22733 7551 7553 22734 7553 7552 22735 7552 7550 22736 7550 7555 22737 7555 7552 22738 7552 7553 22739 7553 7555 22740 7555 7554 22741 7554 7552 22742 7552 7557 22743 7557 7554 22744 7554 7555 22745 7555 7557 22746 7557 7556 22747 7556 7554 22748 7554 7559 22749 7559 7556 22750 7556 7557 22751 7557 7559 22752 7559 7558 22753 7558 7556 22754 7556 7561 22755 7561 7558 22756 7558 7559 22757 7559 7561 22758 7561 7560 22759 7560 7558 22760 7558 7528 22761 7528 7560 22762 7560 7561 22763 7561 7625 22764 7625 7562 22765 7562 7564 22766 7564 7564 22767 7564 7563 22768 7563 7625 22769 7625 7566 22770 7566 7563 22771 7563 7564 22772 7564 7566 22773 7566 7565 22774 7565 7563 22775 7563 7568 22776 7568 7565 22777 7565 7566 22778 7566 7568 22779 7568 7567 22780 7567 7565 22781 7565 7570 22782 7570 7567 22783 7567 7568 22784 7568 7570 22785 7570 7569 22786 7569 7567 22787 7567 7572 22788 7572 7569 22789 7569 7570 22790 7570 7572 22791 7572 7571 22792 7571 7569 22793 7569 7574 22794 7574 7571 22795 7571 7572 22796 7572 7574 22797 7574 7573 22798 7573 7571 22799 7571 7576 22800 7576 7573 22801 7573 7574 22802 7574 7576 22803 7576 7575 22804 7575 7573 22805 7573 7578 22806 7578 7575 22807 7575 7576 22808 7576 7578 22809 7578 7577 22810 7577 7575 22811 7575 7580 22812 7580 7577 22813 7577 7578 22814 7578 7580 22815 7580 7579 22816 7579 7577 22817 7577 7582 22818 7582 7579 22819 7579 7580 22820 7580 7582 22821 7582 7581 22822 7581 7579 22823 7579 7584 22824 7584 7581 22825 7581 7582 22826 7582 7584 22827 7584 7583 22828 7583 7581 22829 7581 7586 22830 7586 7583 22831 7583 7584 22832 7584 7586 22833 7586 7585 22834 7585 7583 22835 7583 7588 22836 7588 7585 22837 7585 7586 22838 7586 7588 22839 7588 7587 22840 7587 7585 22841 7585 7590 22842 7590 7587 22843 7587 7588 22844 7588 7590 22845 7590 7589 22846 7589 7587 22847 7587 7592 22848 7592 7589 22849 7589 7590 22850 7590 7592 22851 7592 7591 22852 7591 7589 22853 7589 7594 22854 7594 7591 22855 7591 7592 22856 7592 7594 22857 7594 7593 22858 7593 7591 22859 7591 7596 22860 7596 7593 22861 7593 7594 22862 7594 7596 22863 7596 7595 22864 7595 7593 22865 7593 7598 22866 7598 7595 22867 7595 7596 22868 7596 7598 22869 7598 7597 22870 7597 7595 22871 7595 7600 22872 7600 7597 22873 7597 7598 22874 7598 7600 22875 7600 7599 22876 7599 7597 22877 7597 7602 22878 7602 7599 22879 7599 7600 22880 7600 7602 22881 7602 7601 22882 7601 7599 22883 7599 7604 22884 7604 7601 22885 7601 7602 22886 7602 7604 22887 7604 7603 22888 7603 7601 22889 7601 7606 22890 7606 7603 22891 7603 7604 22892 7604 7606 22893 7606 7605 22894 7605 7603 22895 7603 7608 22896 7608 7605 22897 7605 7606 22898 7606 7608 22899 7608 7607 22900 7607 7605 22901 7605 7610 22902 7610 7607 22903 7607 7608 22904 7608 7610 22905 7610 7609 22906 7609 7607 22907 7607 7612 22908 7612 7609 22909 7609 7610 22910 7610 7612 22911 7612 7611 22912 7611 7609 22913 7609 7614 22914 7614 7611 22915 7611 7612 22916 7612 7614 22917 7614 7613 22918 7613 7611 22919 7611 7616 22920 7616 7613 22921 7613 7614 22922 7614 7616 22923 7616 7615 22924 7615 7613 22925 7613 7618 22926 7618 7615 22927 7615 7616 22928 7616 7618 22929 7618 7617 22930 7617 7615 22931 7615 7620 22932 7620 7617 22933 7617 7618 22934 7618 7620 22935 7620 7619 22936 7619 7617 22937 7617 7622 22938 7622 7619 22939 7619 7620 22940 7620 7622 22941 7622 7621 22942 7621 7619 22943 7619 7624 22944 7624 7621 22945 7621 7622 22946 7622 7624 22947 7624 7623 22948 7623 7621 22949 7621 7562 22950 7562 7623 22951 7623 7624 22952 7624 7562 22953 7562 7625 22954 7625 7623 22955 7623 7658 22956 7658 7626 22957 7626 7627 22958 7627 7631 22959 7631 7628 22960 7628 7629 22961 7629 7631 22962 7631 7630 22963 7630 7628 22964 7628 7633 22965 7633 7630 22966 7630 7631 22967 7631 7633 22968 7633 7632 22969 7632 7630 22970 7630 7635 22971 7635 7632 22972 7632 7633 22973 7633 7635 22974 7635 7634 22975 7634 7632 22976 7632 7637 22977 7637 7634 22978 7634 7635 22979 7635 7637 22980 7637 7636 22981 7636 7634 22982 7634 7639 22983 7639 7636 22984 7636 7637 22985 7637 7639 22986 7639 7638 22987 7638 7636 22988 7636 7641 22989 7641 7638 22990 7638 7639 22991 7639 7641 22992 7641 7640 22993 7640 7638 22994 7638 7643 22995 7643 7640 22996 7640 7641 22997 7641 7643 22998 7643 7642 22999 7642 7640 23000 7640 7645 23001 7645 7642 23002 7642 7643 23003 7643 7645 23004 7645 7644 23005 7644 7642 23006 7642 7647 23007 7647 7644 23008 7644 7645 23009 7645 7647 23010 7647 7646 23011 7646 7644 23012 7644 7649 23013 7649 7646 23014 7646 7647 23015 7647 7649 23016 7649 7648 23017 7648 7646 23018 7646 7651 23019 7651 7648 23020 7648 7649 23021 7649 7651 23022 7651 7650 23023 7650 7648 23024 7648 7653 23025 7653 7650 23026 7650 7651 23027 7651 7653 23028 7653 7652 23029 7652 7650 23030 7650 7655 23031 7655 7652 23032 7652 7653 23033 7653 7655 23034 7655 7654 23035 7654 7652 23036 7652 7657 23037 7657 7654 23038 7654 7655 23039 7655 7657 23040 7657 7656 23041 7656 7654 23042 7654 7659 23043 7659 7656 23044 7656 7657 23045 7657 7659 23046 7659 7658 23047 7658 7656 23048 7656 7626 23049 7626 7658 23050 7658 7659 23051 7659 7723 23052 7723 7660 23053 7660 7662 23054 7662 7662 23055 7662 7661 23056 7661 7723 23057 7723 7664 23058 7664 7661 23059 7661 7662 23060 7662 7664 23061 7664 7663 23062 7663 7661 23063 7661 7666 23064 7666 7663 23065 7663 7664 23066 7664 7666 23067 7666 7665 23068 7665 7663 23069 7663 7668 23070 7668 7665 23071 7665 7666 23072 7666 7668 23073 7668 7667 23074 7667 7665 23075 7665 7670 23076 7670 7667 23077 7667 7668 23078 7668 7670 23079 7670 7669 23080 7669 7667 23081 7667 7672 23082 7672 7669 23083 7669 7670 23084 7670 7672 23085 7672 7671 23086 7671 7669 23087 7669 7674 23088 7674 7671 23089 7671 7672 23090 7672 7674 23091 7674 7673 23092 7673 7671 23093 7671 7676 23094 7676 7673 23095 7673 7674 23096 7674 7676 23097 7676 7675 23098 7675 7673 23099 7673 7678 23100 7678 7675 23101 7675 7676 23102 7676 7678 23103 7678 7677 23104 7677 7675 23105 7675 7680 23106 7680 7677 23107 7677 7678 23108 7678 7680 23109 7680 7679 23110 7679 7677 23111 7677 7682 23112 7682 7679 23113 7679 7680 23114 7680 7682 23115 7682 7681 23116 7681 7679 23117 7679 7684 23118 7684 7681 23119 7681 7682 23120 7682 7684 23121 7684 7683 23122 7683 7681 23123 7681 7686 23124 7686 7683 23125 7683 7684 23126 7684 7686 23127 7686 7685 23128 7685 7683 23129 7683 7688 23130 7688 7685 23131 7685 7686 23132 7686 7688 23133 7688 7687 23134 7687 7685 23135 7685 7690 23136 7690 7687 23137 7687 7688 23138 7688 7690 23139 7690 7689 23140 7689 7687 23141 7687 7692 23142 7692 7689 23143 7689 7690 23144 7690 7692 23145 7692 7691 23146 7691 7689 23147 7689 7694 23148 7694 7691 23149 7691 7692 23150 7692 7694 23151 7694 7693 23152 7693 7691 23153 7691 7696 23154 7696 7693 23155 7693 7694 23156 7694 7696 23157 7696 7695 23158 7695 7693 23159 7693 7698 23160 7698 7695 23161 7695 7696 23162 7696 7698 23163 7698 7697 23164 7697 7695 23165 7695 7700 23166 7700 7697 23167 7697 7698 23168 7698 7700 23169 7700 7699 23170 7699 7697 23171 7697 7702 23172 7702 7699 23173 7699 7700 23174 7700 7702 23175 7702 7701 23176 7701 7699 23177 7699 7704 23178 7704 7701 23179 7701 7702 23180 7702 7704 23181 7704 7703 23182 7703 7701 23183 7701 7706 23184 7706 7703 23185 7703 7704 23186 7704 7706 23187 7706 7705 23188 7705 7703 23189 7703 7708 23190 7708 7705 23191 7705 7706 23192 7706 7708 23193 7708 7707 23194 7707 7705 23195 7705 7710 23196 7710 7707 23197 7707 7708 23198 7708 7710 23199 7710 7709 23200 7709 7707 23201 7707 7712 23202 7712 7709 23203 7709 7710 23204 7710 7712 23205 7712 7711 23206 7711 7709 23207 7709 7714 23208 7714 7711 23209 7711 7712 23210 7712 7714 23211 7714 7713 23212 7713 7711 23213 7711 7716 23214 7716 7713 23215 7713 7714 23216 7714 7716 23217 7716 7715 23218 7715 7713 23219 7713 7718 23220 7718 7715 23221 7715 7716 23222 7716 7718 23223 7718 7717 23224 7717 7715 23225 7715 7720 23226 7720 7717 23227 7717 7718 23228 7718 7720 23229 7720 7719 23230 7719 7717 23231 7717 7722 23232 7722 7719 23233 7719 7720 23234 7720 7722 23235 7722 7721 23236 7721 7719 23237 7719 7660 23238 7660 7721 23239 7721 7722 23240 7722 7660 23241 7660 7723 23242 7723 7721 23243 7721 7756 23244 7756 7724 23245 7724 7725 23246 7725 7729 23247 7729 7726 23248 7726 7727 23249 7727 7729 23250 7729 7728 23251 7728 7726 23252 7726 7731 23253 7731 7728 23254 7728 7729 23255 7729 7731 23256 7731 7730 23257 7730 7728 23258 7728 7733 23259 7733 7730 23260 7730 7731 23261 7731 7733 23262 7733 7732 23263 7732 7730 23264 7730 7735 23265 7735 7732 23266 7732 7733 23267 7733 7735 23268 7735 7734 23269 7734 7732 23270 7732 7737 23271 7737 7734 23272 7734 7735 23273 7735 7737 23274 7737 7736 23275 7736 7734 23276 7734 7739 23277 7739 7736 23278 7736 7737 23279 7737 7739 23280 7739 7738 23281 7738 7736 23282 7736 7741 23283 7741 7738 23284 7738 7739 23285 7739 7741 23286 7741 7740 23287 7740 7738 23288 7738 7743 23289 7743 7740 23290 7740 7741 23291 7741 7743 23292 7743 7742 23293 7742 7740 23294 7740 7745 23295 7745 7742 23296 7742 7743 23297 7743 7745 23298 7745 7744 23299 7744 7742 23300 7742 7747 23301 7747 7744 23302 7744 7745 23303 7745 7747 23304 7747 7746 23305 7746 7744 23306 7744 7749 23307 7749 7746 23308 7746 7747 23309 7747 7749 23310 7749 7748 23311 7748 7746 23312 7746 7751 23313 7751 7748 23314 7748 7749 23315 7749 7751 23316 7751 7750 23317 7750 7748 23318 7748 7753 23319 7753 7750 23320 7750 7751 23321 7751 7753 23322 7753 7752 23323 7752 7750 23324 7750 7755 23325 7755 7752 23326 7752 7753 23327 7753 7755 23328 7755 7754 23329 7754 7752 23330 7752 7757 23331 7757 7754 23332 7754 7755 23333 7755 7757 23334 7757 7756 23335 7756 7754 23336 7754 7724 23337 7724 7756 23338 7756 7757 23339 7757 7821 23340 7821 7758 23341 7758 7760 23342 7760 7760 23343 7760 7759 23344 7759 7821 23345 7821 7762 23346 7762 7759 23347 7759 7760 23348 7760 7762 23349 7762 7761 23350 7761 7759 23351 7759 7764 23352 7764 7761 23353 7761 7762 23354 7762 7764 23355 7764 7763 23356 7763 7761 23357 7761 7766 23358 7766 7763 23359 7763 7764 23360 7764 7766 23361 7766 7765 23362 7765 7763 23363 7763 7768 23364 7768 7765 23365 7765 7766 23366 7766 7768 23367 7768 7767 23368 7767 7765 23369 7765 7770 23370 7770 7767 23371 7767 7768 23372 7768 7770 23373 7770 7769 23374 7769 7767 23375 7767 7772 23376 7772 7769 23377 7769 7770 23378 7770 7772 23379 7772 7771 23380 7771 7769 23381 7769 7774 23382 7774 7771 23383 7771 7772 23384 7772 7774 23385 7774 7773 23386 7773 7771 23387 7771 7776 23388 7776 7773 23389 7773 7774 23390 7774 7776 23391 7776 7775 23392 7775 7773 23393 7773 7778 23394 7778 7775 23395 7775 7776 23396 7776 7778 23397 7778 7777 23398 7777 7775 23399 7775 7780 23400 7780 7777 23401 7777 7778 23402 7778 7780 23403 7780 7779 23404 7779 7777 23405 7777 7782 23406 7782 7779 23407 7779 7780 23408 7780 7782 23409 7782 7781 23410 7781 7779 23411 7779 7784 23412 7784 7781 23413 7781 7782 23414 7782 7784 23415 7784 7783 23416 7783 7781 23417 7781 7786 23418 7786 7783 23419 7783 7784 23420 7784 7786 23421 7786 7785 23422 7785 7783 23423 7783 7788 23424 7788 7785 23425 7785 7786 23426 7786 7788 23427 7788 7787 23428 7787 7785 23429 7785 7790 23430 7790 7787 23431 7787 7788 23432 7788 7790 23433 7790 7789 23434 7789 7787 23435 7787 7792 23436 7792 7789 23437 7789 7790 23438 7790 7792 23439 7792 7791 23440 7791 7789 23441 7789 7794 23442 7794 7791 23443 7791 7792 23444 7792 7794 23445 7794 7793 23446 7793 7791 23447 7791 7796 23448 7796 7793 23449 7793 7794 23450 7794 7796 23451 7796 7795 23452 7795 7793 23453 7793 7798 23454 7798 7795 23455 7795 7796 23456 7796 7798 23457 7798 7797 23458 7797 7795 23459 7795 7800 23460 7800 7797 23461 7797 7798 23462 7798 7800 23463 7800 7799 23464 7799 7797 23465 7797 7802 23466 7802 7799 23467 7799 7800 23468 7800 7802 23469 7802 7801 23470 7801 7799 23471 7799 7804 23472 7804 7801 23473 7801 7802 23474 7802 7804 23475 7804 7803 23476 7803 7801 23477 7801 7806 23478 7806 7803 23479 7803 7804 23480 7804 7806 23481 7806 7805 23482 7805 7803 23483 7803 7808 23484 7808 7805 23485 7805 7806 23486 7806 7808 23487 7808 7807 23488 7807 7805 23489 7805 7810 23490 7810 7807 23491 7807 7808 23492 7808 7810 23493 7810 7809 23494 7809 7807 23495 7807 7812 23496 7812 7809 23497 7809 7810 23498 7810 7812 23499 7812 7811 23500 7811 7809 23501 7809 7814 23502 7814 7811 23503 7811 7812 23504 7812 7814 23505 7814 7813 23506 7813 7811 23507 7811 7816 23508 7816 7813 23509 7813 7814 23510 7814 7816 23511 7816 7815 23512 7815 7813 23513 7813 7818 23514 7818 7815 23515 7815 7816 23516 7816 7818 23517 7818 7817 23518 7817 7815 23519 7815 7820 23520 7820 7817 23521 7817 7818 23522 7818 7820 23523 7820 7819 23524 7819 7817 23525 7817 7758 23526 7758 7819 23527 7819 7820 23528 7820 7758 23529 7758 7821 23530 7821 7819 23531 7819 7854 23532 7854 7822 23533 7822 7823 23534 7823 7826 23535 7826 7824 23536 7824 7825 23537 7825 7828 23538 7828 7824 23539 7824 7826 23540 7826 7828 23541 7828 7827 23542 7827 7824 23543 7824 7829 23544 7829 7827 23545 7827 7828 23546 7828 7831 23547 7831 7827 23548 7827 7829 23549 7829 7831 23550 7831 7830 23551 7830 7827 23552 7827 7834 23553 7834 7830 23554 7830 7831 23555 7831 7834 23556 7834 7832 23557 7832 7830 23558 7830 7834 23559 7834 7833 23560 7833 7832 23561 7832 7835 23562 7835 7833 23563 7833 7834 23564 7834 7837 23565 7837 7833 23566 7833 7835 23567 7835 7837 23568 7837 7836 23569 7836 7833 23570 7833 7839 23571 7839 7836 23572 7836 7837 23573 7837 7839 23574 7839 7838 23575 7838 7836 23576 7836 7841 23577 7841 7838 23578 7838 7839 23579 7839 7841 23580 7841 7840 23581 7840 7838 23582 7838 7843 23583 7843 7840 23584 7840 7841 23585 7841 7843 23586 7843 7842 23587 7842 7840 23588 7840 7845 23589 7845 7842 23590 7842 7843 23591 7843 7845 23592 7845 7844 23593 7844 7842 23594 7842 7847 23595 7847 7844 23596 7844 7845 23597 7845 7847 23598 7847 7846 23599 7846 7844 23600 7844 7849 23601 7849 7846 23602 7846 7847 23603 7847 7849 23604 7849 7848 23605 7848 7846 23606 7846 7851 23607 7851 7848 23608 7848 7849 23609 7849 7851 23610 7851 7850 23611 7850 7848 23612 7848 7853 23613 7853 7850 23614 7850 7851 23615 7851 7853 23616 7853 7852 23617 7852 7850 23618 7850 7855 23619 7855 7852 23620 7852 7853 23621 7853 7855 23622 7855 7854 23623 7854 7852 23624 7852 7822 23625 7822 7854 23626 7854 7855 23627 7855 7919 23628 7919 7856 23629 7856 7858 23630 7858 7858 23631 7858 7857 23632 7857 7919 23633 7919 7860 23634 7860 7857 23635 7857 7858 23636 7858 7860 23637 7860 7859 23638 7859 7857 23639 7857 7862 23640 7862 7859 23641 7859 7860 23642 7860 7862 23643 7862 7861 23644 7861 7859 23645 7859 7864 23646 7864 7861 23647 7861 7862 23648 7862 7864 23649 7864 7863 23650 7863 7861 23651 7861 7866 23652 7866 7863 23653 7863 7864 23654 7864 7866 23655 7866 7865 23656 7865 7863 23657 7863 7868 23658 7868 7865 23659 7865 7866 23660 7866 7868 23661 7868 7867 23662 7867 7865 23663 7865 7870 23664 7870 7867 23665 7867 7868 23666 7868 7870 23667 7870 7869 23668 7869 7867 23669 7867 7872 23670 7872 7869 23671 7869 7870 23672 7870 7872 23673 7872 7871 23674 7871 7869 23675 7869 7874 23676 7874 7871 23677 7871 7872 23678 7872 7874 23679 7874 7873 23680 7873 7871 23681 7871 7876 23682 7876 7873 23683 7873 7874 23684 7874 7876 23685 7876 7875 23686 7875 7873 23687 7873 7878 23688 7878 7875 23689 7875 7876 23690 7876 7878 23691 7878 7877 23692 7877 7875 23693 7875 7880 23694 7880 7877 23695 7877 7878 23696 7878 7880 23697 7880 7879 23698 7879 7877 23699 7877 7882 23700 7882 7879 23701 7879 7880 23702 7880 7882 23703 7882 7881 23704 7881 7879 23705 7879 7884 23706 7884 7881 23707 7881 7882 23708 7882 7884 23709 7884 7883 23710 7883 7881 23711 7881 7886 23712 7886 7883 23713 7883 7884 23714 7884 7886 23715 7886 7885 23716 7885 7883 23717 7883 7888 23718 7888 7885 23719 7885 7886 23720 7886 7888 23721 7888 7887 23722 7887 7885 23723 7885 7890 23724 7890 7887 23725 7887 7888 23726 7888 7890 23727 7890 7889 23728 7889 7887 23729 7887 7892 23730 7892 7889 23731 7889 7890 23732 7890 7892 23733 7892 7891 23734 7891 7889 23735 7889 7894 23736 7894 7891 23737 7891 7892 23738 7892 7894 23739 7894 7893 23740 7893 7891 23741 7891 7896 23742 7896 7893 23743 7893 7894 23744 7894 7896 23745 7896 7895 23746 7895 7893 23747 7893 7898 23748 7898 7895 23749 7895 7896 23750 7896 7898 23751 7898 7897 23752 7897 7895 23753 7895 7900 23754 7900 7897 23755 7897 7898 23756 7898 7900 23757 7900 7899 23758 7899 7897 23759 7897 7902 23760 7902 7899 23761 7899 7900 23762 7900 7902 23763 7902 7901 23764 7901 7899 23765 7899 7904 23766 7904 7901 23767 7901 7902 23768 7902 7904 23769 7904 7903 23770 7903 7901 23771 7901 7906 23772 7906 7903 23773 7903 7904 23774 7904 7906 23775 7906 7905 23776 7905 7903 23777 7903 7908 23778 7908 7905 23779 7905 7906 23780 7906 7908 23781 7908 7907 23782 7907 7905 23783 7905 7910 23784 7910 7907 23785 7907 7908 23786 7908 7910 23787 7910 7909 23788 7909 7907 23789 7907 7912 23790 7912 7909 23791 7909 7910 23792 7910 7912 23793 7912 7911 23794 7911 7909 23795 7909 7914 23796 7914 7911 23797 7911 7912 23798 7912 7914 23799 7914 7913 23800 7913 7911 23801 7911 7916 23802 7916 7913 23803 7913 7914 23804 7914 7916 23805 7916 7915 23806 7915 7913 23807 7913 7918 23808 7918 7915 23809 7915 7916 23810 7916 7918 23811 7918 7917 23812 7917 7915 23813 7915 7856 23814 7856 7917 23815 7917 7918 23816 7918 7856 23817 7856 7919 23818 7919 7917 23819 7917 7952 23820 7952 7920 23821 7920 7921 23822 7921 7925 23823 7925 7922 23824 7922 7923 23825 7923 7925 23826 7925 7924 23827 7924 7922 23828 7922 7927 23829 7927 7924 23830 7924 7925 23831 7925 7927 23832 7927 7926 23833 7926 7924 23834 7924 7929 23835 7929 7926 23836 7926 7927 23837 7927 7929 23838 7929 7928 23839 7928 7926 23840 7926 7931 23841 7931 7928 23842 7928 7929 23843 7929 7931 23844 7931 7930 23845 7930 7928 23846 7928 7933 23847 7933 7930 23848 7930 7931 23849 7931 7933 23850 7933 7932 23851 7932 7930 23852 7930 7935 23853 7935 7932 23854 7932 7933 23855 7933 7935 23856 7935 7934 23857 7934 7932 23858 7932 7937 23859 7937 7934 23860 7934 7935 23861 7935 7937 23862 7937 7936 23863 7936 7934 23864 7934 7939 23865 7939 7936 23866 7936 7937 23867 7937 7939 23868 7939 7938 23869 7938 7936 23870 7936 7941 23871 7941 7938 23872 7938 7939 23873 7939 7941 23874 7941 7940 23875 7940 7938 23876 7938 7943 23877 7943 7940 23878 7940 7941 23879 7941 7943 23880 7943 7942 23881 7942 7940 23882 7940 7945 23883 7945 7942 23884 7942 7943 23885 7943 7945 23886 7945 7944 23887 7944 7942 23888 7942 7947 23889 7947 7944 23890 7944 7945 23891 7945 7947 23892 7947 7946 23893 7946 7944 23894 7944 7949 23895 7949 7946 23896 7946 7947 23897 7947 7949 23898 7949 7948 23899 7948 7946 23900 7946 7951 23901 7951 7948 23902 7948 7949 23903 7949 7951 23904 7951 7950 23905 7950 7948 23906 7948 7953 23907 7953 7950 23908 7950 7951 23909 7951 7953 23910 7953 7952 23911 7952 7950 23912 7950 7920 23913 7920 7952 23914 7952 7953 23915 7953 8017 23916 8017 7954 23917 7954 7956 23918 7956 7956 23919 7956 7955 23920 7955 8017 23921 8017 7958 23922 7958 7955 23923 7955 7956 23924 7956 7958 23925 7958 7957 23926 7957 7955 23927 7955 7960 23928 7960 7957 23929 7957 7958 23930 7958 7960 23931 7960 7959 23932 7959 7957 23933 7957 7962 23934 7962 7959 23935 7959 7960 23936 7960 7962 23937 7962 7961 23938 7961 7959 23939 7959 7964 23940 7964 7961 23941 7961 7962 23942 7962 7964 23943 7964 7963 23944 7963 7961 23945 7961 7966 23946 7966 7963 23947 7963 7964 23948 7964 7966 23949 7966 7965 23950 7965 7963 23951 7963 7968 23952 7968 7965 23953 7965 7966 23954 7966 7968 23955 7968 7967 23956 7967 7965 23957 7965 7970 23958 7970 7967 23959 7967 7968 23960 7968 7970 23961 7970 7969 23962 7969 7967 23963 7967 7972 23964 7972 7969 23965 7969 7970 23966 7970 7972 23967 7972 7971 23968 7971 7969 23969 7969 7974 23970 7974 7971 23971 7971 7972 23972 7972 7974 23973 7974 7973 23974 7973 7971 23975 7971 7976 23976 7976 7973 23977 7973 7974 23978 7974 7976 23979 7976 7975 23980 7975 7973 23981 7973 7978 23982 7978 7975 23983 7975 7976 23984 7976 7978 23985 7978 7977 23986 7977 7975 23987 7975 7980 23988 7980 7977 23989 7977 7978 23990 7978 7980 23991 7980 7979 23992 7979 7977 23993 7977 7982 23994 7982 7979 23995 7979 7980 23996 7980 7982 23997 7982 7981 23998 7981 7979 23999 7979 7984 24000 7984 7981 24001 7981 7982 24002 7982 7984 24003 7984 7983 24004 7983 7981 24005 7981 7986 24006 7986 7983 24007 7983 7984 24008 7984 7986 24009 7986 7985 24010 7985 7983 24011 7983 7988 24012 7988 7985 24013 7985 7986 24014 7986 7988 24015 7988 7987 24016 7987 7985 24017 7985 7990 24018 7990 7987 24019 7987 7988 24020 7988 7990 24021 7990 7989 24022 7989 7987 24023 7987 7992 24024 7992 7989 24025 7989 7990 24026 7990 7992 24027 7992 7991 24028 7991 7989 24029 7989 7994 24030 7994 7991 24031 7991 7992 24032 7992 7994 24033 7994 7993 24034 7993 7991 24035 7991 7996 24036 7996 7993 24037 7993 7994 24038 7994 7996 24039 7996 7995 24040 7995 7993 24041 7993 7998 24042 7998 7995 24043 7995 7996 24044 7996 7998 24045 7998 7997 24046 7997 7995 24047 7995 8000 24048 8000 7997 24049 7997 7998 24050 7998 8000 24051 8000 7999 24052 7999 7997 24053 7997 8002 24054 8002 7999 24055 7999 8000 24056 8000 8002 24057 8002 8001 24058 8001 7999 24059 7999 8004 24060 8004 8001 24061 8001 8002 24062 8002 8004 24063 8004 8003 24064 8003 8001 24065 8001 8006 24066 8006 8003 24067 8003 8004 24068 8004 8006 24069 8006 8005 24070 8005 8003 24071 8003 8008 24072 8008 8005 24073 8005 8006 24074 8006 8008 24075 8008 8007 24076 8007 8005 24077 8005 8010 24078 8010 8007 24079 8007 8008 24080 8008 8010 24081 8010 8009 24082 8009 8007 24083 8007 8012 24084 8012 8009 24085 8009 8010 24086 8010 8012 24087 8012 8011 24088 8011 8009 24089 8009 8014 24090 8014 8011 24091 8011 8012 24092 8012 8014 24093 8014 8013 24094 8013 8011 24095 8011 8016 24096 8016 8013 24097 8013 8014 24098 8014 8016 24099 8016 8015 24100 8015 8013 24101 8013 7954 24102 7954 8015 24103 8015 8016 24104 8016 7954 24105 7954 8017 24106 8017 8015 24107 8015 8051 24108 8051 8018 24109 8018 8019 24110 8019 8022 24111 8022 8020 24112 8020 8021 24113 8021 8023 24114 8023 8020 24115 8020 8022 24116 8022 8025 24117 8025 8020 24118 8020 8023 24119 8023 8025 24120 8025 8024 24121 8024 8020 24122 8020 8027 24123 8027 8024 24124 8024 8025 24125 8025 8027 24126 8027 8026 24127 8026 8024 24128 8024 8029 24129 8029 8026 24130 8026 8027 24131 8027 8029 24132 8029 8028 24133 8028 8026 24134 8026 8032 24135 8032 8028 24136 8028 8029 24137 8029 8032 24138 8032 8030 24139 8030 8028 24140 8028 8032 24141 8032 8031 24142 8031 8030 24143 8030 8034 24144 8034 8031 24145 8031 8032 24146 8032 8034 24147 8034 8033 24148 8033 8031 24149 8031 8035 24150 8035 8033 24151 8033 8034 24152 8034 8038 24153 8038 8033 24154 8033 8035 24155 8035 8038 24156 8038 8036 24157 8036 8033 24158 8033 8038 24159 8038 8037 24160 8037 8036 24161 8036 8040 24162 8040 8037 24163 8037 8038 24164 8038 8040 24165 8040 8039 24166 8039 8037 24167 8037 8041 24168 8041 8039 24169 8039 8040 24170 8040 8043 24171 8043 8039 24172 8039 8041 24173 8041 8043 24174 8043 8042 24175 8042 8039 24176 8039 8045 24177 8045 8042 24178 8042 8043 24179 8043 8045 24180 8045 8044 24181 8044 8042 24182 8042 8048 24183 8048 8044 24184 8044 8045 24185 8045 8048 24186 8048 8046 24187 8046 8044 24188 8044 8048 24189 8048 8047 24190 8047 8046 24191 8046 8049 24192 8049 8047 24193 8047 8048 24194 8048 8018 24195 8018 8047 24196 8047 8049 24197 8049 8018 24198 8018 8050 24199 8050 8047 24200 8047 8018 24201 8018 8051 24202 8051 8050 24203 8050 8069 24204 8069 8052 24205 8052 8053 24206 8053 8058 24207 8058 8054 24208 8054 8055 24209 8055 8058 24210 8058 8056 24211 8056 8054 24212 8054 8058 24213 8058 8057 24214 8057 8056 24215 8056 8060 24216 8060 8057 24217 8057 8058 24218 8058 8060 24219 8060 8059 24220 8059 8057 24221 8057 8062 24222 8062 8059 24223 8059 8060 24224 8060 8062 24225 8062 8061 24226 8061 8059 24227 8059 8063 24228 8063 8061 24229 8061 8062 24230 8062 8064 24231 8064 8061 24232 8061 8063 24233 8063 8065 24234 8065 8061 24235 8061 8064 24236 8064 8066 24237 8066 8061 24238 8061 8065 24239 8065 8067 24240 8067 8061 24241 8061 8066 24242 8066 8068 24243 8068 8061 24244 8061 8067 24245 8067 8070 24246 8070 8061 24247 8061 8068 24248 8068 8070 24249 8070 8069 24250 8069 8061 24251 8061 8071 24252 8071 8069 24253 8069 8070 24254 8070 8072 24255 8072 8069 24256 8069 8071 24257 8071 8073 24258 8073 8069 24259 8069 8072 24260 8072 8074 24261 8074 8069 24262 8069 8073 24263 8073 8075 24264 8075 8069 24265 8069 8074 24266 8074 8076 24267 8076 8069 24268 8069 8075 24269 8075 8077 24270 8077 8069 24271 8069 8076 24272 8076 8078 24273 8078 8069 24274 8069 8077 24275 8077 8079 24276 8079 8069 24277 8069 8078 24278 8078 8080 24279 8080 8069 24280 8069 8079 24281 8079 8081 24282 8081 8069 24283 8069 8080 24284 8080 8082 24285 8082 8069 24286 8069 8081 24287 8081 8083 24288 8083 8069 24289 8069 8082 24290 8082 8052 24291 8052 8069 24292 8069 8083 24293 8083 8116 24294 8116 8090 24295 8090 8084 24296 8084 8087 24297 8087 8085 24298 8085 8086 24299 8086 8088 24300 8088 8085 24301 8085 8087 24302 8087 8091 24303 8091 8085 24304 8085 8088 24305 8088 8091 24306 8091 8089 24307 8089 8085 24308 8085 8091 24309 8091 8090 24310 8090 8089 24311 8089 8084 24312 8084 8090 24313 8090 8091 24314 8091 8095 24315 8095 8092 24316 8092 8093 24317 8093 8095 24318 8095 8094 24319 8094 8092 24320 8092 8097 24321 8097 8094 24322 8094 8095 24323 8095 8097 24324 8097 8096 24325 8096 8094 24326 8094 8099 24327 8099 8096 24328 8096 8097 24329 8097 8099 24330 8099 8098 24331 8098 8096 24332 8096 8101 24333 8101 8098 24334 8098 8099 24335 8099 8101 24336 8101 8100 24337 8100 8098 24338 8098 8103 24339 8103 8100 24340 8100 8101 24341 8101 8103 24342 8103 8102 24343 8102 8100 24344 8100 8105 24345 8105 8102 24346 8102 8103 24347 8103 8105 24348 8105 8104 24349 8104 8102 24350 8102 8108 24351 8108 8104 24352 8104 8105 24353 8105 8108 24354 8108 8106 24355 8106 8104 24356 8104 8108 24357 8108 8107 24358 8107 8106 24359 8106 8109 24360 8109 8107 24361 8107 8108 24362 8108 8111 24363 8111 8107 24364 8107 8109 24365 8109 8111 24366 8111 8110 24367 8110 8107 24368 8107 8114 24369 8114 8110 24370 8110 8111 24371 8111 8114 24372 8114 8112 24373 8112 8110 24374 8110 8114 24375 8114 8113 24376 8113 8112 24377 8112 8115 24378 8115 8113 24379 8113 8114 24380 8114 8117 24381 8117 8113 24382 8113 8115 24383 8115 8117 24384 8117 8116 24385 8116 8113 24386 8113 8090 24387 8090 8116 24388 8116 8117 24389 8117 8125 24390 8125 8118 24391 8118 8119 24392 8119 8124 24393 8124 8120 24394 8120 8121 24395 8121 8124 24396 8124 8122 24397 8122 8120 24398 8120 8124 24399 8124 8123 24400 8123 8122 24401 8122 8126 24402 8126 8123 24403 8123 8124 24404 8124 8126 24405 8126 8125 24406 8125 8123 24407 8123 8127 24408 8127 8125 24409 8125 8126 24410 8126 8128 24411 8128 8125 24412 8125 8127 24413 8127 8129 24414 8129 8125 24415 8125 8128 24416 8128 8130 24417 8130 8125 24418 8125 8129 24419 8129 8131 24420 8131 8125 24421 8125 8130 24422 8130 8132 24423 8132 8125 24424 8125 8131 24425 8131 8133 24426 8133 8125 24427 8125 8132 24428 8132 8134 24429 8134 8125 24430 8125 8133 24431 8133 8135 24432 8135 8125 24433 8125 8134 24434 8134 8136 24435 8136 8125 24436 8125 8135 24437 8135 8137 24438 8137 8125 24439 8125 8136 24440 8136 8138 24441 8138 8125 24442 8125 8137 24443 8137 8139 24444 8139 8125 24445 8125 8138 24446 8138 8140 24447 8140 8125 24448 8125 8139 24449 8139 8141 24450 8141 8125 24451 8125 8140 24452 8140 8142 24453 8142 8125 24454 8125 8141 24455 8141 8143 24456 8143 8125 24457 8125 8142 24458 8142 8144 24459 8144 8125 24460 8125 8143 24461 8143 8145 24462 8145 8125 24463 8125 8144 24464 8144 8146 24465 8146 8125 24466 8125 8145 24467 8145 8147 24468 8147 8125 24469 8125 8146 24470 8146 8148 24471 8148 8125 24472 8125 8147 24473 8147 8149 24474 8149 8125 24475 8125 8148 24476 8148 8118 24477 8118 8125 24478 8125 8149 24479 8149 8181 24480 8181 8159 24481 8159 8150 24482 8150 8153 24483 8153 8151 24484 8151 8152 24485 8152 8154 24486 8154 8151 24487 8151 8153 24488 8153 8157 24489 8157 8151 24490 8151 8154 24491 8154 8157 24492 8157 8155 24493 8155 8151 24494 8151 8157 24495 8157 8156 24496 8156 8155 24497 8155 8158 24498 8158 8156 24499 8156 8157 24500 8157 8150 24501 8150 8156 24502 8156 8158 24503 8158 8150 24504 8150 8159 24505 8159 8156 24506 8156 8164 24507 8164 8160 24508 8160 8161 24509 8161 8164 24510 8164 8162 24511 8162 8160 24512 8160 8164 24513 8164 8163 24514 8163 8162 24515 8162 8165 24516 8165 8163 24517 8163 8164 24518 8164 8167 24519 8167 8163 24520 8163 8165 24521 8165 8167 24522 8167 8166 24523 8166 8163 24524 8163 8169 24525 8169 8166 24526 8166 8167 24527 8167 8169 24528 8169 8168 24529 8168 8166 24530 8166 8172 24531 8172 8168 24532 8168 8169 24533 8169 8172 24534 8172 8170 24535 8170 8168 24536 8168 8172 24537 8172 8171 24538 8171 8170 24539 8170 8174 24540 8174 8171 24541 8171 8172 24542 8172 8174 24543 8174 8173 24544 8173 8171 24545 8171 8176 24546 8176 8173 24547 8173 8174 24548 8174 8176 24549 8176 8175 24550 8175 8173 24551 8173 8178 24552 8178 8175 24553 8175 8176 24554 8176 8178 24555 8178 8177 24556 8177 8175 24557 8175 8180 24558 8180 8177 24559 8177 8178 24560 8178 8180 24561 8180 8179 24562 8179 8177 24563 8177 8182 24564 8182 8179 24565 8179 8180 24566 8180 8182 24567 8182 8181 24568 8181 8179 24569 8179 8183 24570 8183 8181 24571 8181 8182 24572 8182 8159 24573 8159 8181 24574 8181 8183 24575 8183 8191 24576 8191 8184 24577 8184 8185 24578 8185 8190 24579 8190 8186 24580 8186 8187 24581 8187 8190 24582 8190 8188 24583 8188 8186 24584 8186 8190 24585 8190 8189 24586 8189 8188 24587 8188 8192 24588 8192 8189 24589 8189 8190 24590 8190 8192 24591 8192 8191 24592 8191 8189 24593 8189 8193 24594 8193 8191 24595 8191 8192 24596 8192 8194 24597 8194 8191 24598 8191 8193 24599 8193 8195 24600 8195 8191 24601 8191 8194 24602 8194 8196 24603 8196 8191 24604 8191 8195 24605 8195 8197 24606 8197 8191 24607 8191 8196 24608 8196 8198 24609 8198 8191 24610 8191 8197 24611 8197 8199 24612 8199 8191 24613 8191 8198 24614 8198 8200 24615 8200 8191 24616 8191 8199 24617 8199 8201 24618 8201 8191 24619 8191 8200 24620 8200 8202 24621 8202 8191 24622 8191 8201 24623 8201 8203 24624 8203 8191 24625 8191 8202 24626 8202 8204 24627 8204 8191 24628 8191 8203 24629 8203 8205 24630 8205 8191 24631 8191 8204 24632 8204 8206 24633 8206 8191 24634 8191 8205 24635 8205 8207 24636 8207 8191 24637 8191 8206 24638 8206 8208 24639 8208 8191 24640 8191 8207 24641 8207 8209 24642 8209 8191 24643 8191 8208 24644 8208 8210 24645 8210 8191 24646 8191 8209 24647 8209 8211 24648 8211 8191 24649 8191 8210 24650 8210 8212 24651 8212 8191 24652 8191 8211 24653 8211 8213 24654 8213 8191 24655 8191 8212 24656 8212 8214 24657 8214 8191 24658 8191 8213 24659 8213 8215 24660 8215 8191 24661 8191 8214 24662 8214 8184 24663 8184 8191 24664 8191 8215 24665 8215 8247 24666 8247 8216 24667 8216 8217 24668 8217 8222 24669 8222 8218 24670 8218 8219 24671 8219 8222 24672 8222 8220 24673 8220 8218 24674 8218 8222 24675 8222 8221 24676 8221 8220 24677 8220 8223 24678 8223 8221 24679 8221 8222 24680 8222 8225 24681 8225 8221 24682 8221 8223 24683 8223 8225 24684 8225 8224 24685 8224 8221 24686 8221 8228 24687 8228 8224 24688 8224 8225 24689 8225 8228 24690 8228 8226 24691 8226 8224 24692 8224 8228 24693 8228 8227 24694 8227 8226 24695 8226 8229 24696 8229 8227 24697 8227 8228 24698 8228 8231 24699 8231 8227 24700 8227 8229 24701 8229 8231 24702 8231 8230 24703 8230 8227 24704 8227 8234 24705 8234 8230 24706 8230 8231 24707 8231 8234 24708 8234 8232 24709 8232 8230 24710 8230 8234 24711 8234 8233 24712 8233 8232 24713 8232 8235 24714 8235 8233 24715 8233 8234 24716 8234 8237 24717 8237 8233 24718 8233 8235 24719 8235 8237 24720 8237 8236 24721 8236 8233 24722 8233 8239 24723 8239 8236 24724 8236 8237 24725 8237 8239 24726 8239 8238 24727 8238 8236 24728 8236 8242 24729 8242 8238 24730 8238 8239 24731 8239 8242 24732 8242 8240 24733 8240 8238 24734 8238 8242 24735 8242 8241 24736 8241 8240 24737 8240 8244 24738 8244 8241 24739 8241 8242 24740 8242 8244 24741 8244 8243 24742 8243 8241 24743 8241 8245 24744 8245 8243 24745 8243 8244 24746 8244 8248 24747 8248 8243 24748 8243 8245 24749 8245 8248 24750 8248 8246 24751 8246 8243 24752 8243 8248 24753 8248 8247 24754 8247 8246 24755 8246 8249 24756 8249 8247 24757 8247 8248 24758 8248 8216 24759 8216 8247 24760 8247 8249 24761 8249 8259 24762 8259 8250 24763 8250 8251 24764 8251 8256 24765 8256 8252 24766 8252 8253 24767 8253 8256 24768 8256 8254 24769 8254 8252 24770 8252 8256 24771 8256 8255 24772 8255 8254 24773 8254 8258 24774 8258 8255 24775 8255 8256 24776 8256 8258 24777 8258 8257 24778 8257 8255 24779 8255 8260 24780 8260 8257 24781 8257 8258 24782 8258 8260 24783 8260 8259 24784 8259 8257 24785 8257 8261 24786 8261 8259 24787 8259 8260 24788 8260 8262 24789 8262 8259 24790 8259 8261 24791 8261 8263 24792 8263 8259 24793 8259 8262 24794 8262 8264 24795 8264 8259 24796 8259 8263 24797 8263 8265 24798 8265 8259 24799 8259 8264 24800 8264 8266 24801 8266 8259 24802 8259 8265 24803 8265 8267 24804 8267 8259 24805 8259 8266 24806 8266 8268 24807 8268 8259 24808 8259 8267 24809 8267 8269 24810 8269 8259 24811 8259 8268 24812 8268 8270 24813 8270 8259 24814 8259 8269 24815 8269 8271 24816 8271 8259 24817 8259 8270 24818 8270 8272 24819 8272 8259 24820 8259 8271 24821 8271 8273 24822 8273 8259 24823 8259 8272 24824 8272 8274 24825 8274 8259 24826 8259 8273 24827 8273 8275 24828 8275 8259 24829 8259 8274 24830 8274 8276 24831 8276 8259 24832 8259 8275 24833 8275 8277 24834 8277 8259 24835 8259 8276 24836 8276 8278 24837 8278 8259 24838 8259 8277 24839 8277 8279 24840 8279 8259 24841 8259 8278 24842 8278 8280 24843 8280 8259 24844 8259 8279 24845 8279 8281 24846 8281 8259 24847 8259 8280 24848 8280 8250 24849 8250 8259 24850 8259 8281 24851 8281 8315 24852 8315 8282 24853 8282 8290 24854 8290 8285 24855 8285 8283 24856 8283 8284 24857 8284 8287 24858 8287 8283 24859 8283 8285 24860 8285 8287 24861 8287 8286 24862 8286 8283 24863 8283 8289 24864 8289 8286 24865 8286 8287 24866 8287 8289 24867 8289 8288 24868 8288 8286 24869 8286 8291 24870 8291 8288 24871 8288 8289 24872 8289 8291 24873 8291 8290 24874 8290 8288 24875 8288 8315 24876 8315 8290 24877 8290 8291 24878 8291 8295 24879 8295 8292 24880 8292 8293 24881 8293 8295 24882 8295 8294 24883 8294 8292 24884 8292 8297 24885 8297 8294 24886 8294 8295 24887 8295 8297 24888 8297 8296 24889 8296 8294 24890 8294 8300 24891 8300 8296 24892 8296 8297 24893 8297 8300 24894 8300 8298 24895 8298 8296 24896 8296 8300 24897 8300 8299 24898 8299 8298 24899 8298 8302 24900 8302 8299 24901 8299 8300 24902 8300 8302 24903 8302 8301 24904 8301 8299 24905 8299 8303 24906 8303 8301 24907 8301 8302 24908 8302 8306 24909 8306 8301 24910 8301 8303 24911 8303 8306 24912 8306 8304 24913 8304 8301 24914 8301 8306 24915 8306 8305 24916 8305 8304 24917 8304 8308 24918 8308 8305 24919 8305 8306 24920 8306 8308 24921 8308 8307 24922 8307 8305 24923 8305 8310 24924 8310 8307 24925 8307 8308 24926 8308 8310 24927 8310 8309 24928 8309 8307 24929 8307 8312 24930 8312 8309 24931 8309 8310 24932 8310 8312 24933 8312 8311 24934 8311 8309 24935 8309 8314 24936 8314 8311 24937 8311 8312 24938 8312 8314 24939 8314 8313 24940 8313 8311 24941 8311 8282 24942 8282 8313 24943 8313 8314 24944 8314 8282 24945 8282 8315 24946 8315 8313 24947 8313 8341 24948 8341 8316 24949 8316 8317 24950 8317 8322 24951 8322 8318 24952 8318 8319 24953 8319 8322 24954 8322 8320 24955 8320 8318 24956 8318 8322 24957 8322 8321 24958 8321 8320 24959 8320 8324 24960 8324 8321 24961 8321 8322 24962 8322 8324 24963 8324 8323 24964 8323 8321 24965 8321 8326 24966 8326 8323 24967 8323 8324 24968 8324 8326 24969 8326 8325 24970 8325 8323 24971 8323 8327 24972 8327 8325 24973 8325 8326 24974 8326 8328 24975 8328 8325 24976 8325 8327 24977 8327 8329 24978 8329 8325 24979 8325 8328 24980 8328 8330 24981 8330 8325 24982 8325 8329 24983 8329 8331 24984 8331 8325 24985 8325 8330 24986 8330 8332 24987 8332 8325 24988 8325 8331 24989 8331 8333 24990 8333 8325 24991 8325 8332 24992 8332 8334 24993 8334 8325 24994 8325 8333 24995 8333 8335 24996 8335 8325 24997 8325 8334 24998 8334 8336 24999 8336 8325 25000 8325 8335 25001 8335 8337 25002 8337 8325 25003 8325 8336 25004 8336 8338 25005 8338 8325 25006 8325 8337 25007 8337 8339 25008 8339 8325 25009 8325 8338 25010 8338 8340 25011 8340 8325 25012 8325 8339 25013 8339 8342 25014 8342 8325 25015 8325 8340 25016 8340 8342 25017 8342 8341 25018 8341 8325 25019 8325 8343 25020 8343 8341 25021 8341 8342 25022 8342 8344 25023 8344 8341 25024 8341 8343 25025 8343 8345 25026 8345 8341 25027 8341 8344 25028 8344 8346 25029 8346 8341 25030 8341 8345 25031 8345 8347 25032 8347 8341 25033 8341 8346 25034 8346 8316 25035 8316 8341 25036 8341 8347 25037 8347 8380 25038 8380 8348 25039 8348 8349 25040 8349 8352 25041 8352 8350 25042 8350 8351 25043 8351 8353 25044 8353 8350 25045 8350 8352 25046 8352 8356 25047 8356 8350 25048 8350 8353 25049 8353 8356 25050 8356 8354 25051 8354 8350 25052 8350 8356 25053 8356 8355 25054 8355 8354 25055 8354 8357 25056 8357 8355 25057 8355 8356 25058 8356 8360 25059 8360 8355 25060 8355 8357 25061 8357 8360 25062 8360 8358 25063 8358 8355 25064 8355 8360 25065 8360 8359 25066 8359 8358 25067 8358 8362 25068 8362 8359 25069 8359 8360 25070 8360 8362 25071 8362 8361 25072 8361 8359 25073 8359 8364 25074 8364 8361 25075 8361 8362 25076 8362 8364 25077 8364 8363 25078 8363 8361 25079 8361 8366 25080 8366 8363 25081 8363 8364 25082 8364 8366 25083 8366 8365 25084 8365 8363 25085 8363 8367 25086 8367 8365 25087 8365 8366 25088 8366 8370 25089 8370 8365 25090 8365 8367 25091 8367 8370 25092 8370 8368 25093 8368 8365 25094 8365 8370 25095 8370 8369 25096 8369 8368 25097 8368 8372 25098 8372 8369 25099 8369 8370 25100 8370 8372 25101 8372 8371 25102 8371 8369 25103 8369 8373 25104 8373 8371 25105 8371 8372 25106 8372 8375 25107 8375 8371 25108 8371 8373 25109 8373 8375 25110 8375 8374 25111 8374 8371 25112 8371 8377 25113 8377 8374 25114 8374 8375 25115 8375 8377 25116 8377 8376 25117 8376 8374 25118 8374 8379 25119 8379 8376 25120 8376 8377 25121 8377 8379 25122 8379 8378 25123 8378 8376 25124 8376 8381 25125 8381 8378 25126 8378 8379 25127 8379 8381 25128 8381 8380 25129 8380 8378 25130 8378 8348 25131 8348 8380 25132 8380 8381 25133 8381 8391 25134 8391 8382 25135 8382 8383 25136 8383 8388 25137 8388 8384 25138 8384 8385 25139 8385 8388 25140 8388 8386 25141 8386 8384 25142 8384 8388 25143 8388 8387 25144 8387 8386 25145 8386 8390 25146 8390 8387 25147 8387 8388 25148 8388 8390 25149 8390 8389 25150 8389 8387 25151 8387 8392 25152 8392 8389 25153 8389 8390 25154 8390 8392 25155 8392 8391 25156 8391 8389 25157 8389 8393 25158 8393 8391 25159 8391 8392 25160 8392 8394 25161 8394 8391 25162 8391 8393 25163 8393 8395 25164 8395 8391 25165 8391 8394 25166 8394 8396 25167 8396 8391 25168 8391 8395 25169 8395 8397 25170 8397 8391 25171 8391 8396 25172 8396 8398 25173 8398 8391 25174 8391 8397 25175 8397 8399 25176 8399 8391 25177 8391 8398 25178 8398 8400 25179 8400 8391 25180 8391 8399 25181 8399 8401 25182 8401 8391 25183 8391 8400 25184 8400 8402 25185 8402 8391 25186 8391 8401 25187 8401 8403 25188 8403 8391 25189 8391 8402 25190 8402 8404 25191 8404 8391 25192 8391 8403 25193 8403 8405 25194 8405 8391 25195 8391 8404 25196 8404 8406 25197 8406 8391 25198 8391 8405 25199 8405 8407 25200 8407 8391 25201 8391 8406 25202 8406 8408 25203 8408 8391 25204 8391 8407 25205 8407 8409 25206 8409 8391 25207 8391 8408 25208 8408 8410 25209 8410 8391 25210 8391 8409 25211 8409 8411 25212 8411 8391 25213 8391 8410 25214 8410 8412 25215 8412 8391 25216 8391 8411 25217 8411 8413 25218 8413 8391 25219 8391 8412 25220 8412 8382 25221 8382 8391 25222 8391 8413 25223 8413 8447 25224 8447 8414 25225 8414 8428 25226 8428 8417 25227 8417 8415 25228 8415 8416 25229 8416 8419 25230 8419 8415 25231 8415 8417 25232 8417 8419 25233 8419 8418 25234 8418 8415 25235 8415 8420 25236 8420 8418 25237 8418 8419 25238 8419 8422 25239 8422 8418 25240 8418 8420 25241 8420 8422 25242 8422 8421 25243 8421 8418 25244 8418 8425 25245 8425 8421 25246 8421 8422 25247 8422 8425 25248 8425 8423 25249 8423 8421 25250 8421 8425 25251 8425 8424 25252 8424 8423 25253 8423 8427 25254 8427 8424 25255 8424 8425 25256 8425 8427 25257 8427 8426 25258 8426 8424 25259 8424 8429 25260 8429 8426 25261 8426 8427 25262 8427 8429 25263 8429 8428 25264 8428 8426 25265 8426 8447 25266 8447 8428 25267 8428 8429 25268 8429 8433 25269 8433 8430 25270 8430 8431 25271 8431 8433 25272 8433 8432 25273 8432 8430 25274 8430 8435 25275 8435 8432 25276 8432 8433 25277 8433 8435 25278 8435 8434 25279 8434 8432 25280 8432 8437 25281 8437 8434 25282 8434 8435 25283 8435 8437 25284 8437 8436 25285 8436 8434 25286 8434 8439 25287 8439 8436 25288 8436 8437 25289 8437 8439 25290 8439 8438 25291 8438 8436 25292 8436 8441 25293 8441 8438 25294 8438 8439 25295 8439 8441 25296 8441 8440 25297 8440 8438 25298 8438 8443 25299 8443 8440 25300 8440 8441 25301 8441 8443 25302 8443 8442 25303 8442 8440 25304 8440 8445 25305 8445 8442 25306 8442 8443 25307 8443 8445 25308 8445 8444 25309 8444 8442 25310 8442 8414 25311 8414 8444 25312 8444 8445 25313 8445 8414 25314 8414 8446 25315 8446 8444 25316 8444 8414 25317 8414 8447 25318 8447 8446 25319 8446 8455 25320 8455 8448 25321 8448 8449 25322 8449 8454 25323 8454 8450 25324 8450 8451 25325 8451 8454 25326 8454 8452 25327 8452 8450 25328 8450 8454 25329 8454 8453 25330 8453 8452 25331 8452 8456 25332 8456 8453 25333 8453 8454 25334 8454 8456 25335 8456 8455 25336 8455 8453 25337 8453 8457 25338 8457 8455 25339 8455 8456 25340 8456 8458 25341 8458 8455 25342 8455 8457 25343 8457 8459 25344 8459 8455 25345 8455 8458 25346 8458 8460 25347 8460 8455 25348 8455 8459 25349 8459 8461 25350 8461 8455 25351 8455 8460 25352 8460 8462 25353 8462 8455 25354 8455 8461 25355 8461 8463 25356 8463 8455 25357 8455 8462 25358 8462 8464 25359 8464 8455 25360 8455 8463 25361 8463 8465 25362 8465 8455 25363 8455 8464 25364 8464 8466 25365 8466 8455 25366 8455 8465 25367 8465 8467 25368 8467 8455 25369 8455 8466 25370 8466 8468 25371 8468 8455 25372 8455 8467 25373 8467 8469 25374 8469 8455 25375 8455 8468 25376 8468 8470 25377 8470 8455 25378 8455 8469 25379 8469 8471 25380 8471 8455 25381 8455 8470 25382 8470 8472 25383 8472 8455 25384 8455 8471 25385 8471 8473 25386 8473 8455 25387 8455 8472 25388 8472 8474 25389 8474 8455 25390 8455 8473 25391 8473 8475 25392 8475 8455 25393 8455 8474 25394 8474 8476 25395 8476 8455 25396 8455 8475 25397 8475 8477 25398 8477 8455 25399 8455 8476 25400 8476 8478 25401 8478 8455 25402 8455 8477 25403 8477 8479 25404 8479 8455 25405 8455 8478 25406 8478 8448 25407 8448 8455 25408 8455 8479 25409 8479 8512 25410 8512 8480 25411 8480 8481 25412 8481 8484 25413 8484 8482 25414 8482 8483 25415 8483 8485 25416 8485 8482 25417 8482 8484 25418 8484 8487 25419 8487 8482 25420 8482 8485 25421 8485 8487 25422 8487 8486 25423 8486 8482 25424 8482 8489 25425 8489 8486 25426 8486 8487 25427 8487 8489 25428 8489 8488 25429 8488 8486 25430 8486 8491 25431 8491 8488 25432 8488 8489 25433 8489 8491 25434 8491 8490 25435 8490 8488 25436 8488 8493 25437 8493 8490 25438 8490 8491 25439 8491 8493 25440 8493 8492 25441 8492 8490 25442 8490 8495 25443 8495 8492 25444 8492 8493 25445 8493 8495 25446 8495 8494 25447 8494 8492 25448 8492 8497 25449 8497 8494 25450 8494 8495 25451 8495 8497 25452 8497 8496 25453 8496 8494 25454 8494 8499 25455 8499 8496 25456 8496 8497 25457 8497 8499 25458 8499 8498 25459 8498 8496 25460 8496 8501 25461 8501 8498 25462 8498 8499 25463 8499 8501 25464 8501 8500 25465 8500 8498 25466 8498 8503 25467 8503 8500 25468 8500 8501 25469 8501 8503 25470 8503 8502 25471 8502 8500 25472 8500 8506 25473 8506 8502 25474 8502 8503 25475 8503 8506 25476 8506 8504 25477 8504 8502 25478 8502 8506 25479 8506 8505 25480 8505 8504 25481 8504 8507 25482 8507 8505 25483 8505 8506 25484 8506 8509 25485 8509 8505 25486 8505 8507 25487 8507 8509 25488 8509 8508 25489 8508 8505 25490 8505 8511 25491 8511 8508 25492 8508 8509 25493 8509 8511 25494 8511 8510 25495 8510 8508 25496 8508 8513 25497 8513 8510 25498 8510 8511 25499 8511 8513 25500 8513 8512 25501 8512 8510 25502 8510 8480 25503 8480 8512 25504 8512 8513 25505 8513 8531 25506 8531 8514 25507 8514 8515 25508 8515 8520 25509 8520 8516 25510 8516 8517 25511 8517 8520 25512 8520 8518 25513 8518 8516 25514 8516 8520 25515 8520 8519 25516 8519 8518 25517 8518 8522 25518 8522 8519 25519 8519 8520 25520 8520 8522 25521 8522 8521 25522 8521 8519 25523 8519 8524 25524 8524 8521 25525 8521 8522 25526 8522 8524 25527 8524 8523 25528 8523 8521 25529 8521 8525 25530 8525 8523 25531 8523 8524 25532 8524 8526 25533 8526 8523 25534 8523 8525 25535 8525 8527 25536 8527 8523 25537 8523 8526 25538 8526 8528 25539 8528 8523 25540 8523 8527 25541 8527 8529 25542 8529 8523 25543 8523 8528 25544 8528 8530 25545 8530 8523 25546 8523 8529 25547 8529 8532 25548 8532 8523 25549 8523 8530 25550 8530 8532 25551 8532 8531 25552 8531 8523 25553 8523 8533 25554 8533 8531 25555 8531 8532 25556 8532 8534 25557 8534 8531 25558 8531 8533 25559 8533 8535 25560 8535 8531 25561 8531 8534 25562 8534 8536 25563 8536 8531 25564 8531 8535 25565 8535 8537 25566 8537 8531 25567 8531 8536 25568 8536 8538 25569 8538 8531 25570 8531 8537 25571 8537 8539 25572 8539 8531 25573 8531 8538 25574 8538 8540 25575 8540 8531 25576 8531 8539 25577 8539 8541 25578 8541 8531 25579 8531 8540 25580 8540 8542 25581 8542 8531 25582 8531 8541 25583 8541 8543 25584 8543 8531 25585 8531 8542 25586 8542 8544 25587 8544 8531 25588 8531 8543 25589 8543 8545 25590 8545 8531 25591 8531 8544 25592 8544 8514 25593 8514 8531 25594 8531 8545 25595 8545 8578 25596 8578 8546 25597 8546 8547 25598 8547 8550 25599 8550 8548 25600 8548 8549 25601 8549 8551 25602 8551 8548 25603 8548 8550 25604 8550 8553 25605 8553 8548 25606 8548 8551 25607 8551 8553 25608 8553 8552 25609 8552 8548 25610 8548 8555 25611 8555 8552 25612 8552 8553 25613 8553 8555 25614 8555 8554 25615 8554 8552 25616 8552 8558 25617 8558 8554 25618 8554 8555 25619 8555 8558 25620 8558 8556 25621 8556 8554 25622 8554 8558 25623 8558 8557 25624 8557 8556 25625 8556 8559 25626 8559 8557 25627 8557 8558 25628 8558 8561 25629 8561 8557 25630 8557 8559 25631 8559 8561 25632 8561 8560 25633 8560 8557 25634 8557 8563 25635 8563 8560 25636 8560 8561 25637 8561 8563 25638 8563 8562 25639 8562 8560 25640 8560 8565 25641 8565 8562 25642 8562 8563 25643 8563 8565 25644 8565 8564 25645 8564 8562 25646 8562 8567 25647 8567 8564 25648 8564 8565 25649 8565 8567 25650 8567 8566 25651 8566 8564 25652 8564 8569 25653 8569 8566 25654 8566 8567 25655 8567 8569 25656 8569 8568 25657 8568 8566 25658 8566 8571 25659 8571 8568 25660 8568 8569 25661 8569 8571 25662 8571 8570 25663 8570 8568 25664 8568 8573 25665 8573 8570 25666 8570 8571 25667 8571 8573 25668 8573 8572 25669 8572 8570 25670 8570 8575 25671 8575 8572 25672 8572 8573 25673 8573 8575 25674 8575 8574 25675 8574 8572 25676 8572 8577 25677 8577 8574 25678 8574 8575 25679 8575 8577 25680 8577 8576 25681 8576 8574 25682 8574 8579 25683 8579 8576 25684 8576 8577 25685 8577 8579 25686 8579 8578 25687 8578 8576 25688 8576 8546 25689 8546 8578 25690 8578 8579 25691 8579 8597 25692 8597 8580 25693 8580 8581 25694 8581 8586 25695 8586 8582 25696 8582 8583 25697 8583 8586 25698 8586 8584 25699 8584 8582 25700 8582 8586 25701 8586 8585 25702 8585 8584 25703 8584 8588 25704 8588 8585 25705 8585 8586 25706 8586 8588 25707 8588 8587 25708 8587 8585 25709 8585 8589 25710 8589 8587 25711 8587 8588 25712 8588 8590 25713 8590 8587 25714 8587 8589 25715 8589 8591 25716 8591 8587 25717 8587 8590 25718 8590 8592 25719 8592 8587 25720 8587 8591 25721 8591 8593 25722 8593 8587 25723 8587 8592 25724 8592 8594 25725 8594 8587 25726 8587 8593 25727 8593 8595 25728 8595 8587 25729 8587 8594 25730 8594 8596 25731 8596 8587 25732 8587 8595 25733 8595 8598 25734 8598 8587 25735 8587 8596 25736 8596 8598 25737 8598 8597 25738 8597 8587 25739 8587 8599 25740 8599 8597 25741 8597 8598 25742 8598 8600 25743 8600 8597 25744 8597 8599 25745 8599 8601 25746 8601 8597 25747 8597 8600 25748 8600 8602 25749 8602 8597 25750 8597 8601 25751 8601 8603 25752 8603 8597 25753 8597 8602 25754 8602 8604 25755 8604 8597 25756 8597 8603 25757 8603 8605 25758 8605 8597 25759 8597 8604 25760 8604 8606 25761 8606 8597 25762 8597 8605 25763 8605 8607 25764 8607 8597 25765 8597 8606 25766 8606 8608 25767 8608 8597 25768 8597 8607 25769 8607 8609 25770 8609 8597 25771 8597 8608 25772 8608 8610 25773 8610 8597 25774 8597 8609 25775 8609 8611 25776 8611 8597 25777 8597 8610 25778 8610 8580 25779 8580 8597 25780 8597 8611 25781 8611 8616 25782 8616 8612 25783 8612 8613 25784 8613 8612 25785 8612 8614 25786 8614 8615 25787 8615 8612 25788 8612 8616 25789 8616 8614 25790 8614 8619 25791 8619 8617 25792 8617 8618 25793 8618 8617 25794 8617 8619 25795 8619 8620 25796 8620 8623 25797 8623 8621 25798 8621 8622 25799 8622 8625 25800 8625 8623 25801 8623 8624 25802 8624 8621 25803 8621 8623 25804 8623 8625 25805 8625 8628 25806 8628 8626 25807 8626 8627 25808 8627 8626 25809 8626 8628 25810 8628 8629 25811 8629 8634 25812 8634 8630 25813 8630 8631 25814 8631 8635 25815 8635 8632 25816 8632 8633 25817 8633 8635 25818 8635 8634 25819 8634 8632 25820 8632 8636 25821 8636 8634 25822 8634 8635 25823 8635 8637 25824 8637 8634 25825 8634 8636 25826 8636 8638 25827 8638 8634 25828 8634 8637 25829 8637 8639 25830 8639 8634 25831 8634 8638 25832 8638 8640 25833 8640 8634 25834 8634 8639 25835 8639 8641 25836 8641 8634 25837 8634 8640 25838 8640 8642 25839 8642 8634 25840 8634 8641 25841 8641 8643 25842 8643 8634 25843 8634 8642 25844 8642 8644 25845 8644 8634 25846 8634 8643 25847 8643 8645 25848 8645 8634 25849 8634 8644 25850 8644 8646 25851 8646 8634 25852 8634 8645 25853 8645 8647 25854 8647 8634 25855 8634 8646 25856 8646 8648 25857 8648 8634 25858 8634 8647 25859 8647 8649 25860 8649 8634 25861 8634 8648 25862 8648 8630 25863 8630 8634 25864 8634 8649 25865 8649 8666 25866 8666 8650 25867 8650 8651 25868 8651 8654 25869 8654 8652 25870 8652 8653 25871 8653 8655 25872 8655 8652 25873 8652 8654 25874 8654 8657 25875 8657 8652 25876 8652 8655 25877 8655 8657 25878 8657 8656 25879 8656 8652 25880 8652 8658 25881 8658 8656 25882 8656 8657 25883 8657 8659 25884 8659 8656 25885 8656 8658 25886 8658 8660 25887 8660 8656 25888 8656 8659 25889 8659 8661 25890 8661 8656 25891 8656 8660 25892 8660 8662 25893 8662 8656 25894 8656 8661 25895 8661 8650 25896 8650 8656 25897 8656 8662 25898 8662 8650 25899 8650 8663 25900 8663 8656 25901 8656 8650 25902 8650 8664 25903 8664 8663 25904 8663 8650 25905 8650 8665 25906 8665 8664 25907 8664 8650 25908 8650 8666 25909 8666 8665 25910 8665 8686 25911 8686 8667 25912 8667 8668 25913 8668 8672 25914 8672 8669 25915 8669 8670 25916 8670 8672 25917 8672 8671 25918 8671 8669 25919 8669 8674 25920 8674 8671 25921 8671 8672 25922 8672 8674 25923 8674 8673 25924 8673 8671 25925 8671 8676 25926 8676 8673 25927 8673 8674 25928 8674 8676 25929 8676 8675 25930 8675 8673 25931 8673 8678 25932 8678 8675 25933 8675 8676 25934 8676 8678 25935 8678 8677 25936 8677 8675 25937 8675 8679 25938 8679 8677 25939 8677 8678 25940 8678 8681 25941 8681 8677 25942 8677 8679 25943 8679 8681 25944 8681 8680 25945 8680 8677 25946 8677 8683 25947 8683 8680 25948 8680 8681 25949 8681 8683 25950 8683 8682 25951 8682 8680 25952 8680 8685 25953 8685 8682 25954 8682 8683 25955 8683 8685 25956 8685 8684 25957 8684 8682 25958 8682 8667 25959 8667 8684 25960 8684 8685 25961 8685 8667 25962 8667 8686 25963 8686 8684 25964 8684 8705 25965 8705 8687 25966 8687 8688 25967 8688 8693 25968 8693 8689 25969 8689 8690 25970 8690 8693 25971 8693 8691 25972 8691 8689 25973 8689 8693 25974 8693 8692 25975 8692 8691 25976 8691 8695 25977 8695 8692 25978 8692 8693 25979 8693 8695 25980 8695 8694 25981 8694 8692 25982 8692 8697 25983 8697 8694 25984 8694 8695 25985 8695 8697 25986 8697 8696 25987 8696 8694 25988 8694 8700 25989 8700 8696 25990 8696 8697 25991 8697 8700 25992 8700 8698 25993 8698 8696 25994 8696 8700 25995 8700 8699 25996 8699 8698 25997 8698 8702 25998 8702 8699 25999 8699 8700 26000 8700 8702 26001 8702 8701 26002 8701 8699 26003 8699 8704 26004 8704 8701 26005 8701 8702 26006 8702 8704 26007 8704 8703 26008 8703 8701 26009 8701 8706 26010 8706 8703 26011 8703 8704 26012 8704 8706 26013 8706 8705 26014 8705 8703 26015 8703 8687 26016 8687 8705 26017 8705 8706 26018 8706 8722 26019 8722 8707 26020 8707 8708 26021 8708 8711 26022 8711 8709 26023 8709 8710 26024 8710 8712 26025 8712 8709 26026 8709 8711 26027 8711 8714 26028 8714 8709 26029 8709 8712 26030 8712 8714 26031 8714 8713 26032 8713 8709 26033 8709 8716 26034 8716 8713 26035 8713 8714 26036 8714 8716 26037 8716 8715 26038 8715 8713 26039 8713 8718 26040 8718 8715 26041 8715 8716 26042 8716 8718 26043 8718 8717 26044 8717 8715 26045 8715 8721 26046 8721 8717 26047 8717 8718 26048 8718 8721 26049 8721 8719 26050 8719 8717 26051 8717 8721 26052 8721 8720 26053 8720 8719 26054 8719 8723 26055 8723 8720 26056 8720 8721 26057 8721 8723 26058 8723 8722 26059 8722 8720 26060 8720 8724 26061 8724 8722 26062 8722 8723 26063 8723 8707 26064 8707 8722 26065 8722 8724 26066 8724 8741 26067 8741 8725 26068 8725 8726 26069 8726 8729 26070 8729 8727 26071 8727 8728 26072 8728 8730 26073 8730 8727 26074 8727 8729 26075 8729 8732 26076 8732 8727 26077 8727 8730 26078 8730 8732 26079 8732 8731 26080 8731 8727 26081 8727 8734 26082 8734 8731 26083 8731 8732 26084 8732 8734 26085 8734 8733 26086 8733 8731 26087 8731 8737 26088 8737 8733 26089 8733 8734 26090 8734 8737 26091 8737 8735 26092 8735 8733 26093 8733 8737 26094 8737 8736 26095 8736 8735 26096 8735 8739 26097 8739 8736 26098 8736 8737 26099 8737 8739 26100 8739 8738 26101 8738 8736 26102 8736 8740 26103 8740 8738 26104 8738 8739 26105 8739 8742 26106 8742 8738 26107 8738 8740 26108 8740 8742 26109 8742 8741 26110 8741 8738 26111 8738 8725 26112 8725 8741 26113 8741 8742 26114 8742 8745 26115 8745 8743 26116 8743 8744 26117 8744 8747 26118 8747 8745 26119 8745 8746 26120 8746 8743 26121 8743 8745 26122 8745 8747 26123 8747 8750 26124 8750 8748 26125 8748 8749 26126 8749 8748 26127 8748 8750 26128 8750 8751 26129 8751 8756 26130 8756 8752 26131 8752 8753 26132 8753 8752 26133 8752 8754 26134 8754 8755 26135 8755 8752 26136 8752 8756 26137 8756 8754 26138 8754 8759 26139 8759 8757 26140 8757 8758 26141 8758 8757 26142 8757 8759 26143 8759 8760 26144 8760 8765 26145 8765 8761 26146 8761 8762 26147 8762 8766 26148 8766 8763 26149 8763 8764 26150 8764 8766 26151 8766 8765 26152 8765 8763 26153 8763 8767 26154 8767 8765 26155 8765 8766 26156 8766 8768 26157 8768 8765 26158 8765 8767 26159 8767 8769 26160 8769 8765 26161 8765 8768 26162 8768 8770 26163 8770 8765 26164 8765 8769 26165 8769 8771 26166 8771 8765 26167 8765 8770 26168 8770 8772 26169 8772 8765 26170 8765 8771 26171 8771 8773 26172 8773 8765 26173 8765 8772 26174 8772 8774 26175 8774 8765 26176 8765 8773 26177 8773 8775 26178 8775 8765 26179 8765 8774 26180 8774 8776 26181 8776 8765 26182 8765 8775 26183 8775 8777 26184 8777 8765 26185 8765 8776 26186 8776 8778 26187 8778 8765 26188 8765 8777 26189 8777 8779 26190 8779 8765 26191 8765 8778 26192 8778 8780 26193 8780 8765 26194 8765 8779 26195 8779 8761 26196 8761 8765 26197 8765 8780 26198 8780 8783 26199 8783 8781 26200 8781 8782 26201 8782 8785 26202 8785 8783 26203 8783 8784 26204 8784 8781 26205 8781 8783 26206 8783 8785 26207 8785 8788 26208 8788 8786 26209 8786 8787 26210 8787 8786 26211 8786 8788 26212 8788 8789 26213 8789 8794 26214 8794 8790 26215 8790 8791 26216 8791 8790 26217 8790 8792 26218 8792 8793 26219 8793 8790 26220 8790 8794 26221 8794 8792 26222 8792 8797 26223 8797 8795 26224 8795 8796 26225 8796 8795 26226 8795 8797 26227 8797 8798 26228 8798 8801 26229 8801 8799 26230 8799 8800 26231 8800 8803 26232 8803 8801 26233 8801 8802 26234 8802 8804 26235 8804 8801 26236 8801 8803 26237 8803 8805 26238 8805 8801 26239 8801 8804 26240 8804 8806 26241 8806 8801 26242 8801 8805 26243 8805 8807 26244 8807 8801 26245 8801 8806 26246 8806 8808 26247 8808 8801 26248 8801 8807 26249 8807 8809 26250 8809 8801 26251 8801 8808 26252 8808 8810 26253 8810 8801 26254 8801 8809 26255 8809 8811 26256 8811 8801 26257 8801 8810 26258 8810 8812 26259 8812 8801 26260 8801 8811 26261 8811 8813 26262 8813 8801 26263 8801 8812 26264 8812 8814 26265 8814 8801 26266 8801 8813 26267 8813 8815 26268 8815 8801 26269 8801 8814 26270 8814 8816 26271 8816 8801 26272 8801 8815 26273 8815 8817 26274 8817 8801 26275 8801 8816 26276 8816 8818 26277 8818 8801 26278 8801 8817 26279 8817 8799 26280 8799 8801 26281 8801 8818 26282 8818 8836 26283 8836 8819 26284 8819 8820 26285 8820 8823 26286 8823 8821 26287 8821 8822 26288 8822 8825 26289 8825 8821 26290 8821 8823 26291 8823 8825 26292 8825 8824 26293 8824 8821 26294 8821 8826 26295 8826 8824 26296 8824 8825 26297 8825 8827 26298 8827 8824 26299 8824 8826 26300 8826 8828 26301 8828 8824 26302 8824 8827 26303 8827 8829 26304 8829 8824 26305 8824 8828 26306 8828 8830 26307 8830 8824 26308 8824 8829 26309 8829 8831 26310 8831 8824 26311 8824 8830 26312 8830 8832 26313 8832 8824 26314 8824 8831 26315 8831 8819 26316 8819 8824 26317 8824 8832 26318 8832 8819 26319 8819 8833 26320 8833 8824 26321 8824 8819 26322 8819 8834 26323 8834 8833 26324 8833 8819 26325 8819 8835 26326 8835 8834 26327 8834 8819 26328 8819 8836 26329 8836 8835 26330 8835 8853 26331 8853 8837 26332 8837 8838 26333 8838 8842 26334 8842 8839 26335 8839 8840 26336 8840 8842 26337 8842 8841 26338 8841 8839 26339 8839 8843 26340 8843 8841 26341 8841 8842 26342 8842 8845 26343 8845 8841 26344 8841 8843 26345 8843 8845 26346 8845 8844 26347 8844 8841 26348 8841 8846 26349 8846 8844 26350 8844 8845 26351 8845 8847 26352 8847 8844 26353 8844 8846 26354 8846 8848 26355 8848 8844 26356 8844 8847 26357 8847 8849 26358 8849 8844 26359 8844 8848 26360 8848 8837 26361 8837 8844 26362 8844 8849 26363 8849 8837 26364 8837 8850 26365 8850 8844 26366 8844 8837 26367 8837 8851 26368 8851 8850 26369 8850 8837 26370 8837 8852 26371 8852 8851 26372 8851 8837 26373 8837 8853 26374 8853 8852 26375 8852 8873 26376 8873 8854 26377 8854 8855 26378 8855 8859 26379 8859 8856 26380 8856 8857 26381 8857 8859 26382 8859 8858 26383 8858 8856 26384 8856 8861 26385 8861 8858 26386 8858 8859 26387 8859 8861 26388 8861 8860 26389 8860 8858 26390 8858 8863 26391 8863 8860 26392 8860 8861 26393 8861 8863 26394 8863 8862 26395 8862 8860 26396 8860 8865 26397 8865 8862 26398 8862 8863 26399 8863 8865 26400 8865 8864 26401 8864 8862 26402 8862 8866 26403 8866 8864 26404 8864 8865 26405 8865 8868 26406 8868 8864 26407 8864 8866 26408 8866 8868 26409 8868 8867 26410 8867 8864 26411 8864 8870 26412 8870 8867 26413 8867 8868 26414 8868 8870 26415 8870 8869 26416 8869 8867 26417 8867 8872 26418 8872 8869 26419 8869 8870 26420 8870 8872 26421 8872 8871 26422 8871 8869 26423 8869 8854 26424 8854 8871 26425 8871 8872 26426 8872 8854 26427 8854 8873 26428 8873 8871 26429 8871 8883 26430 8883 8874 26431 8874 8875 26432 8875 8879 26433 8879 8876 26434 8876 8877 26435 8877 8879 26436 8879 8878 26437 8878 8876 26438 8876 8882 26439 8882 8878 26440 8878 8879 26441 8879 8882 26442 8882 8880 26443 8880 8878 26444 8878 8882 26445 8882 8881 26446 8881 8880 26447 8880 8874 26448 8874 8881 26449 8881 8882 26450 8882 8874 26451 8874 8883 26452 8883 8881 26453 8881 8899 26454 8899 8884 26455 8884 8885 26456 8885 8888 26457 8888 8886 26458 8886 8887 26459 8887 8890 26460 8890 8886 26461 8886 8888 26462 8888 8890 26463 8890 8889 26464 8889 8886 26465 8886 8891 26466 8891 8889 26467 8889 8890 26468 8890 8894 26469 8894 8889 26470 8889 8891 26471 8891 8894 26472 8894 8892 26473 8892 8889 26474 8889 8894 26475 8894 8893 26476 8893 8892 26477 8892 8895 26478 8895 8893 26479 8893 8894 26480 8894 8898 26481 8898 8893 26482 8893 8895 26483 8895 8898 26484 8898 8896 26485 8896 8893 26486 8893 8898 26487 8898 8897 26488 8897 8896 26489 8896 8900 26490 8900 8897 26491 8897 8898 26492 8898 8900 26493 8900 8899 26494 8899 8897 26495 8897 8901 26496 8901 8899 26497 8899 8900 26498 8900 8884 26499 8884 8899 26500 8899 8901 26501 8901 8919 26502 8919 8902 26503 8902 8903 26504 8903 8907 26505 8907 8904 26506 8904 8905 26507 8905 8907 26508 8907 8906 26509 8906 8904 26510 8904 8910 26511 8910 8906 26512 8906 8907 26513 8907 8910 26514 8910 8908 26515 8908 8906 26516 8906 8910 26517 8910 8909 26518 8909 8908 26519 8908 8912 26520 8912 8909 26521 8909 8910 26522 8910 8912 26523 8912 8911 26524 8911 8909 26525 8909 8914 26526 8914 8911 26527 8911 8912 26528 8912 8914 26529 8914 8913 26530 8913 8911 26531 8911 8916 26532 8916 8913 26533 8913 8914 26534 8914 8916 26535 8916 8915 26536 8915 8913 26537 8913 8918 26538 8918 8915 26539 8915 8916 26540 8916 8918 26541 8918 8917 26542 8917 8915 26543 8915 8902 26544 8902 8917 26545 8917 8918 26546 8918 8902 26547 8902 8919 26548 8919 8917 26549 8917 8935 26550 8935 8920 26551 8920 8928 26552 8928 8925 26553 8925 8921 26554 8921 8922 26555 8922 8925 26556 8925 8923 26557 8923 8921 26558 8921 8925 26559 8925 8924 26560 8924 8923 26561 8923 8927 26562 8927 8924 26563 8924 8925 26564 8925 8927 26565 8927 8926 26566 8926 8924 26567 8924 8935 26568 8935 8926 26569 8926 8927 26570 8927 8935 26571 8935 8928 26572 8928 8926 26573 8926 8932 26574 8932 8929 26575 8929 8930 26576 8930 8932 26577 8932 8931 26578 8931 8929 26579 8929 8934 26580 8934 8931 26581 8931 8932 26582 8932 8934 26583 8934 8933 26584 8933 8931 26585 8931 8920 26586 8920 8933 26587 8933 8934 26588 8934 8920 26589 8920 8935 26590 8935 8933 26591 8933 8954 26592 8954 8936 26593 8936 8937 26594 8937 8942 26595 8942 8938 26596 8938 8939 26597 8939 8942 26598 8942 8940 26599 8940 8938 26600 8938 8942 26601 8942 8941 26602 8941 8940 26603 8940 8944 26604 8944 8941 26605 8941 8942 26606 8942 8944 26607 8944 8943 26608 8943 8941 26609 8941 8946 26610 8946 8943 26611 8943 8944 26612 8944 8946 26613 8946 8945 26614 8945 8943 26615 8943 8949 26616 8949 8945 26617 8945 8946 26618 8946 8949 26619 8949 8947 26620 8947 8945 26621 8945 8949 26622 8949 8948 26623 8948 8947 26624 8947 8951 26625 8951 8948 26626 8948 8949 26627 8949 8951 26628 8951 8950 26629 8950 8948 26630 8948 8953 26631 8953 8950 26632 8950 8951 26633 8951 8953 26634 8953 8952 26635 8952 8950 26636 8950 8955 26637 8955 8952 26638 8952 8953 26639 8953 8955 26640 8955 8954 26641 8954 8952 26642 8952 8936 26643 8936 8954 26644 8954 8955 26645 8955 8972 26646 8972 8956 26647 8956 8957 26648 8957 8960 26649 8960 8958 26650 8958 8959 26651 8959 8961 26652 8961 8958 26653 8958 8960 26654 8960 8964 26655 8964 8958 26656 8958 8961 26657 8961 8964 26658 8964 8962 26659 8962 8958 26660 8958 8964 26661 8964 8963 26662 8963 8962 26663 8962 8966 26664 8966 8963 26665 8963 8964 26666 8964 8966 26667 8966 8965 26668 8965 8963 26669 8963 8967 26670 8967 8965 26671 8965 8966 26672 8966 8969 26673 8969 8965 26674 8965 8967 26675 8967 8969 26676 8969 8968 26677 8968 8965 26678 8965 8971 26679 8971 8968 26680 8968 8969 26681 8969 8971 26682 8971 8970 26683 8970 8968 26684 8968 8973 26685 8973 8970 26686 8970 8971 26687 8971 8973 26688 8973 8972 26689 8972 8970 26690 8970 8956 26691 8956 8972 26692 8972 8973 26693 8973 8990 26694 8990 8974 26695 8974 8975 26696 8975 8978 26697 8978 8976 26698 8976 8977 26699 8977 8979 26700 8979 8976 26701 8976 8978 26702 8978 8982 26703 8982 8976 26704 8976 8979 26705 8979 8982 26706 8982 8980 26707 8980 8976 26708 8976 8982 26709 8982 8981 26710 8981 8980 26711 8980 8983 26712 8983 8981 26713 8981 8982 26714 8982 8985 26715 8985 8981 26716 8981 8983 26717 8983 8985 26718 8985 8984 26719 8984 8981 26720 8981 8988 26721 8988 8984 26722 8984 8985 26723 8985 8988 26724 8988 8986 26725 8986 8984 26726 8984 8988 26727 8988 8987 26728 8987 8986 26729 8986 8989 26730 8989 8987 26731 8987 8988 26732 8988 8991 26733 8991 8987 26734 8987 8989 26735 8989 8991 26736 8991 8990 26737 8990 8987 26738 8987 8974 26739 8974 8990 26740 8990 8991 26741 8991 8996 26742 8996 8992 26743 8992 8993 26744 8993 8992 26745 8992 8994 26746 8994 8995 26747 8995 8992 26748 8992 8996 26749 8996 8994 26750 8994 8999 26751 8999 8997 26752 8997 8998 26753 8998 8997 26754 8997 8999 26755 8999 9000 26756 9000 9003 26757 9003 9001 26758 9001 9002 26759 9002 9005 26760 9005 9003 26761 9003 9004 26762 9004 9001 26763 9001 9003 26764 9003 9005 26765 9005 9008 26766 9008 9006 26767 9006 9007 26768 9007 9006 26769 9006 9008 26770 9008 9009 26771 9009 9014 26772 9014 9010 26773 9010 9011 26774 9011 9015 26775 9015 9012 26776 9012 9013 26777 9013 9015 26778 9015 9014 26779 9014 9012 26780 9012 9016 26781 9016 9014 26782 9014 9015 26783 9015 9017 26784 9017 9014 26785 9014 9016 26786 9016 9018 26787 9018 9014 26788 9014 9017 26789 9017 9019 26790 9019 9014 26791 9014 9018 26792 9018 9020 26793 9020 9014 26794 9014 9019 26795 9019 9021 26796 9021 9014 26797 9014 9020 26798 9020 9022 26799 9022 9014 26800 9014 9021 26801 9021 9023 26802 9023 9014 26803 9014 9022 26804 9022 9024 26805 9024 9014 26806 9014 9023 26807 9023 9025 26808 9025 9014 26809 9014 9024 26810 9024 9026 26811 9026 9014 26812 9014 9025 26813 9025 9027 26814 9027 9014 26815 9014 9026 26816 9026 9028 26817 9028 9014 26818 9014 9027 26819 9027 9029 26820 9029 9014 26821 9014 9028 26822 9028 9010 26823 9010 9014 26824 9014 9029 26825 9029 9034 26826 9034 9030 26827 9030 9031 26828 9031 9030 26829 9030 9032 26830 9032 9033 26831 9033 9030 26832 9030 9034 26833 9034 9032 26834 9032 9037 26835 9037 9035 26836 9035 9036 26837 9036 9035 26838 9035 9037 26839 9037 9038 26840 9038 9041 26841 9041 9039 26842 9039 9040 26843 9040 9043 26844 9043 9041 26845 9041 9042 26846 9042 9039 26847 9039 9041 26848 9041 9043 26849 9043 9046 26850 9046 9044 26851 9044 9045 26852 9045 9044 26853 9044 9046 26854 9046 9047 26855 9047 9059 26856 9059 9048 26857 9048 9049 26858 9049 9060 26859 9060 9050 26860 9050 9051 26861 9051 9060 26862 9060 9052 26863 9052 9050 26864 9050 9060 26865 9060 9053 26866 9053 9052 26867 9052 9060 26868 9060 9054 26869 9054 9053 26870 9053 9060 26871 9060 9055 26872 9055 9054 26873 9054 9060 26874 9060 9056 26875 9056 9055 26876 9055 9060 26877 9060 9057 26878 9057 9056 26879 9056 9060 26880 9060 9058 26881 9058 9057 26882 9057 9060 26883 9060 9059 26884 9059 9058 26885 9058 9061 26886 9061 9059 26887 9059 9060 26888 9060 9062 26889 9062 9059 26890 9059 9061 26891 9061 9063 26892 9063 9059 26893 9059 9062 26894 9062 9064 26895 9064 9059 26896 9059 9063 26897 9063 9065 26898 9065 9059 26899 9059 9064 26900 9064 9048 26901 9048 9059 26902 9059 9065 26903 9065 9070 26904 9070 9066 26905 9066 9067 26906 9067 9066 26907 9066 9068 26908 9068 9069 26909 9069 9066 26910 9066 9070 26911 9070 9068 26912 9068 9073 26913 9073 9071 26914 9071 9072 26915 9072 9071 26916 9071 9073 26917 9073 9074 26918 9074 9077 26919 9077 9075 26920 9075 9076 26921 9076 9079 26922 9079 9077 26923 9077 9078 26924 9078 9075 26925 9075 9077 26926 9077 9079 26927 9079 9082 26928 9082 9080 26929 9080 9081 26930 9081 9080 26931 9080 9082 26932 9082 9083 26933 9083 9088 26934 9088 9084 26935 9084 9085 26936 9085 9089 26937 9089 9086 26938 9086 9087 26939 9087 9089 26940 9089 9088 26941 9088 9086 26942 9086 9090 26943 9090 9088 26944 9088 9089 26945 9089 9091 26946 9091 9088 26947 9088 9090 26948 9090 9092 26949 9092 9088 26950 9088 9091 26951 9091 9093 26952 9093 9088 26953 9088 9092 26954 9092 9094 26955 9094 9088 26956 9088 9093 26957 9093 9095 26958 9095 9088 26959 9088 9094 26960 9094 9096 26961 9096 9088 26962 9088 9095 26963 9095 9097 26964 9097 9088 26965 9088 9096 26966 9096 9098 26967 9098 9088 26968 9088 9097 26969 9097 9099 26970 9099 9088 26971 9088 9098 26972 9098 9100 26973 9100 9088 26974 9088 9099 26975 9099 9101 26976 9101 9088 26977 9088 9100 26978 9100 9084 26979 9084 9088 26980 9088 9101 26981 9101 9118 26982 9118 9102 26983 9102 9103 26984 9103 9107 26985 9107 9104 26986 9104 9105 26987 9105 9107 26988 9107 9106 26989 9106 9104 26990 9104 9109 26991 9109 9106 26992 9106 9107 26993 9107 9109 26994 9109 9108 26995 9108 9106 26996 9106 9110 26997 9110 9108 26998 9108 9109 26999 9109 9111 27000 9111 9108 27001 9108 9110 27002 9110 9112 27003 9112 9108 27004 9108 9111 27005 9111 9113 27006 9113 9108 27007 9108 9112 27008 9112 9114 27009 9114 9108 27010 9108 9113 27011 9113 9102 27012 9102 9108 27013 9108 9114 27014 9114 9102 27015 9102 9115 27016 9115 9108 27017 9108 9102 27018 9102 9116 27019 9116 9115 27020 9115 9102 27021 9102 9117 27022 9117 9116 27023 9116 9102 27024 9102 9118 27025 9118 9117 27026 9117 9135 27027 9135 9119 27028 9119 9120 27029 9120 9123 27030 9123 9121 27031 9121 9122 27032 9122 9124 27033 9124 9121 27034 9121 9123 27035 9123 9126 27036 9126 9121 27037 9121 9124 27038 9124 9126 27039 9126 9125 27040 9125 9121 27041 9121 9127 27042 9127 9125 27043 9125 9126 27044 9126 9128 27045 9128 9125 27046 9125 9127 27047 9127 9129 27048 9129 9125 27049 9125 9128 27050 9128 9130 27051 9130 9125 27052 9125 9129 27053 9129 9131 27054 9131 9125 27055 9125 9130 27056 9130 9119 27057 9119 9125 27058 9125 9131 27059 9131 9119 27060 9119 9132 27061 9132 9125 27062 9125 9119 27063 9119 9133 27064 9133 9132 27065 9132 9119 27066 9119 9134 27067 9134 9133 27068 9133 9119 27069 9119 9135 27070 9135 9134 27071 9134 9152 27072 9152 9136 27073 9136 9137 27074 9137 9140 27075 9140 9138 27076 9138 9139 27077 9139 9141 27078 9141 9138 27079 9138 9140 27080 9140 9143 27081 9143 9138 27082 9138 9141 27083 9141 9143 27084 9143 9142 27085 9142 9138 27086 9138 9144 27087 9144 9142 27088 9142 9143 27089 9143 9145 27090 9145 9142 27091 9142 9144 27092 9144 9146 27093 9146 9142 27094 9142 9145 27095 9145 9147 27096 9147 9142 27097 9142 9146 27098 9146 9148 27099 9148 9142 27100 9142 9147 27101 9147 9136 27102 9136 9142 27103 9142 9148 27104 9148 9136 27105 9136 9149 27106 9149 9142 27107 9142 9136 27108 9136 9150 27109 9150 9149 27110 9149 9136 27111 9136 9151 27112 9151 9150 27113 9150 9136 27114 9136 9152 27115 9152 9151 27116 9151 9171 27117 9171 9153 27118 9153 9154 27119 9154 9159 27120 9159 9155 27121 9155 9156 27122 9156 9159 27123 9159 9157 27124 9157 9155 27125 9155 9159 27126 9159 9158 27127 9158 9157 27128 9157 9161 27129 9161 9158 27130 9158 9159 27131 9159 9161 27132 9161 9160 27133 9160 9158 27134 9158 9163 27135 9163 9160 27136 9160 9161 27137 9161 9163 27138 9163 9162 27139 9162 9160 27140 9160 9166 27141 9166 9162 27142 9162 9163 27143 9163 9166 27144 9166 9164 27145 9164 9162 27146 9162 9166 27147 9166 9165 27148 9165 9164 27149 9164 9168 27150 9168 9165 27151 9165 9166 27152 9166 9168 27153 9168 9167 27154 9167 9165 27155 9165 9170 27156 9170 9167 27157 9167 9168 27158 9168 9170 27159 9170 9169 27160 9169 9167 27161 9167 9172 27162 9172 9169 27163 9169 9170 27164 9170 9172 27165 9172 9171 27166 9171 9169 27167 9169 9153 27168 9153 9171 27169 9171 9172 27170 9172 9192 27171 9192 9173 27172 9173 9183 27173 9183 9178 27174 9178 9174 27175 9174 9175 27176 9175 9178 27177 9178 9176 27178 9176 9174 27179 9174 9178 27180 9178 9177 27181 9177 9176 27182 9176 9180 27183 9180 9177 27184 9177 9178 27185 9178 9180 27186 9180 9179 27187 9179 9177 27188 9177 9182 27189 9182 9179 27190 9179 9180 27191 9180 9182 27192 9182 9181 27193 9181 9179 27194 9179 9192 27195 9192 9181 27196 9181 9182 27197 9182 9192 27198 9192 9183 27199 9183 9181 27200 9181 9187 27201 9187 9184 27202 9184 9185 27203 9185 9187 27204 9187 9186 27205 9186 9184 27206 9184 9189 27207 9189 9186 27208 9186 9187 27209 9187 9189 27210 9189 9188 27211 9188 9186 27212 9186 9191 27213 9191 9188 27214 9188 9189 27215 9189 9191 27216 9191 9190 27217 9190 9188 27218 9188 9173 27219 9173 9190 27220 9190 9191 27221 9191 9173 27222 9173 9192 27223 9192 9190 27224 9190 9209 27225 9209 9193 27226 9193 9194 27227 9194 9197 27228 9197 9195 27229 9195 9196 27230 9196 9198 27231 9198 9195 27232 9195 9197 27233 9197 9201 27234 9201 9195 27235 9195 9198 27236 9198 9201 27237 9201 9199 27238 9199 9195 27239 9195 9201 27240 9201 9200 27241 9200 9199 27242 9199 9202 27243 9202 9200 27244 9200 9201 27245 9201 9204 27246 9204 9200 27247 9200 9202 27248 9202 9204 27249 9204 9203 27250 9203 9200 27251 9200 9206 27252 9206 9203 27253 9203 9204 27254 9204 9206 27255 9206 9205 27256 9205 9203 27257 9203 9208 27258 9208 9205 27259 9205 9206 27260 9206 9208 27261 9208 9207 27262 9207 9205 27263 9205 9210 27264 9210 9207 27265 9207 9208 27266 9208 9210 27267 9210 9209 27268 9209 9207 27269 9207 9193 27270 9193 9209 27271 9209 9210 27272 9210 9227 27273 9227 9211 27274 9211 9212 27275 9212 9216 27276 9216 9213 27277 9213 9214 27278 9214 9216 27279 9216 9215 27280 9215 9213 27281 9213 9218 27282 9218 9215 27283 9215 9216 27284 9216 9218 27285 9218 9217 27286 9217 9215 27287 9215 9220 27288 9220 9217 27289 9217 9218 27290 9218 9220 27291 9220 9219 27292 9219 9217 27293 9217 9222 27294 9222 9219 27295 9219 9220 27296 9220 9222 27297 9222 9221 27298 9221 9219 27299 9219 9224 27300 9224 9221 27301 9221 9222 27302 9222 9224 27303 9224 9223 27304 9223 9221 27305 9221 9226 27306 9226 9223 27307 9223 9224 27308 9224 9226 27309 9226 9225 27310 9225 9223 27311 9223 9228 27312 9228 9225 27313 9225 9226 27314 9226 9228 27315 9228 9227 27316 9227 9225 27317 9225 9211 27318 9211 9227 27319 9227 9228 27320 9228 9247 27321 9247 9229 27322 9229 9230 27323 9230 9233 27324 9233 9231 27325 9231 9232 27326 9232 9235 27327 9235 9231 27328 9231 9233 27329 9233 9235 27330 9235 9234 27331 9234 9231 27332 9231 9237 27333 9237 9234 27334 9234 9235 27335 9235 9237 27336 9237 9236 27337 9236 9234 27338 9234 9239 27339 9239 9236 27340 9236 9237 27341 9237 9239 27342 9239 9238 27343 9238 9236 27344 9236 9242 27345 9242 9238 27346 9238 9239 27347 9239 9242 27348 9242 9240 27349 9240 9238 27350 9238 9242 27351 9242 9241 27352 9241 9240 27353 9240 9244 27354 9244 9241 27355 9241 9242 27356 9242 9244 27357 9244 9243 27358 9243 9241 27359 9241 9246 27360 9246 9243 27361 9243 9244 27362 9244 9246 27363 9246 9245 27364 9245 9243 27365 9243 9248 27366 9248 9245 27367 9245 9246 27368 9246 9248 27369 9248 9247 27370 9247 9245 27371 9245 9229 27372 9229 9247 27373 9247 9248 27374 9248 9268 27375 9268 9249 27376 9249 9250 27377 9250 9254 27378 9254 9251 27379 9251 9252 27380 9252 9254 27381 9254 9253 27382 9253 9251 27383 9251 9256 27384 9256 9253 27385 9253 9254 27386 9254 9256 27387 9256 9255 27388 9255 9253 27389 9253 9258 27390 9258 9255 27391 9255 9256 27392 9256 9258 27393 9258 9257 27394 9257 9255 27395 9255 9260 27396 9260 9257 27397 9257 9258 27398 9258 9260 27399 9260 9259 27400 9259 9257 27401 9257 9261 27402 9261 9259 27403 9259 9260 27404 9260 9263 27405 9263 9259 27406 9259 9261 27407 9261 9263 27408 9263 9262 27409 9262 9259 27410 9259 9265 27411 9265 9262 27412 9262 9263 27413 9263 9265 27414 9265 9264 27415 9264 9262 27416 9262 9267 27417 9267 9264 27418 9264 9265 27419 9265 9267 27420 9267 9266 27421 9266 9264 27422 9264 9249 27423 9249 9266 27424 9266 9267 27425 9267 9249 27426 9249 9268 27427 9268 9266 27428 9266 9282 27429 9282 9269 27430 9269 9270 27431 9270 9272 27432 9272 9270 27433 9270 9271 27434 9271 9282 27435 9282 9270 27436 9270 9272 27437 9272 9276 27438 9276 9273 27439 9273 9274 27440 9274 9276 27441 9276 9275 27442 9275 9273 27443 9273 9279 27444 9279 9275 27445 9275 9276 27446 9276 9279 27447 9279 9277 27448 9277 9275 27449 9275 9279 27450 9279 9278 27451 9278 9277 27452 9277 9280 27453 9280 9278 27454 9278 9279 27455 9279 9269 27456 9269 9278 27457 9278 9280 27458 9280 9269 27459 9269 9281 27460 9281 9278 27461 9278 9269 27462 9269 9282 27463 9282 9281 27464 9281 9300 27465 9300 9283 27466 9283 9284 27467 9284 9287 27468 9287 9285 27469 9285 9286 27470 9286 9288 27471 9288 9285 27472 9285 9287 27473 9287 9290 27474 9290 9285 27475 9285 9288 27476 9288 9290 27477 9290 9289 27478 9289 9285 27479 9285 9292 27480 9292 9289 27481 9289 9290 27482 9290 9292 27483 9292 9291 27484 9291 9289 27485 9289 9294 27486 9294 9291 27487 9291 9292 27488 9292 9294 27489 9294 9293 27490 9293 9291 27491 9291 9297 27492 9297 9293 27493 9293 9294 27494 9294 9297 27495 9297 9295 27496 9295 9293 27497 9293 9297 27498 9297 9296 27499 9296 9295 27500 9295 9298 27501 9298 9296 27502 9296 9297 27503 9297 9283 27504 9283 9296 27505 9296 9298 27506 9298 9283 27507 9283 9299 27508 9299 9296 27509 9296 9283 27510 9283 9300 27511 9300 9299 27512 9299 9319 27513 9319 9301 27514 9301 9302 27515 9302 9307 27516 9307 9303 27517 9303 9304 27518 9304 9307 27519 9307 9305 27520 9305 9303 27521 9303 9307 27522 9307 9306 27523 9306 9305 27524 9305 9309 27525 9309 9306 27526 9306 9307 27527 9307 9309 27528 9309 9308 27529 9308 9306 27530 9306 9311 27531 9311 9308 27532 9308 9309 27533 9309 9311 27534 9311 9310 27535 9310 9308 27536 9308 9314 27537 9314 9310 27538 9310 9311 27539 9311 9314 27540 9314 9312 27541 9312 9310 27542 9310 9314 27543 9314 9313 27544 9313 9312 27545 9312 9316 27546 9316 9313 27547 9313 9314 27548 9314 9316 27549 9316 9315 27550 9315 9313 27551 9313 9318 27552 9318 9315 27553 9315 9316 27554 9316 9318 27555 9318 9317 27556 9317 9315 27557 9315 9320 27558 9320 9317 27559 9317 9318 27560 9318 9320 27561 9320 9319 27562 9319 9317 27563 9317 9301 27564 9301 9319 27565 9319 9320 27566 9320 9340 27567 9340 9321 27568 9321 9331 27569 9331 9326 27570 9326 9322 27571 9322 9323 27572 9323 9326 27573 9326 9324 27574 9324 9322 27575 9322 9326 27576 9326 9325 27577 9325 9324 27578 9324 9328 27579 9328 9325 27580 9325 9326 27581 9326 9328 27582 9328 9327 27583 9327 9325 27584 9325 9330 27585 9330 9327 27586 9327 9328 27587 9328 9330 27588 9330 9329 27589 9329 9327 27590 9327 9340 27591 9340 9329 27592 9329 9330 27593 9330 9340 27594 9340 9331 27595 9331 9329 27596 9329 9335 27597 9335 9332 27598 9332 9333 27599 9333 9335 27600 9335 9334 27601 9334 9332 27602 9332 9337 27603 9337 9334 27604 9334 9335 27605 9335 9337 27606 9337 9336 27607 9336 9334 27608 9334 9339 27609 9339 9336 27610 9336 9337 27611 9337 9339 27612 9339 9338 27613 9338 9336 27614 9336 9321 27615 9321 9338 27616 9338 9339 27617 9339 9321 27618 9321 9340 27619 9340 9338 27620 9338 9357 27621 9357 9341 27622 9341 9342 27623 9342 9345 27624 9345 9343 27625 9343 9344 27626 9344 9346 27627 9346 9343 27628 9343 9345 27629 9345 9348 27630 9348 9343 27631 9343 9346 27632 9346 9348 27633 9348 9347 27634 9347 9343 27635 9343 9350 27636 9350 9347 27637 9347 9348 27638 9348 9350 27639 9350 9349 27640 9349 9347 27641 9347 9352 27642 9352 9349 27643 9349 9350 27644 9350 9352 27645 9352 9351 27646 9351 9349 27647 9349 9354 27648 9354 9351 27649 9351 9352 27650 9352 9354 27651 9354 9353 27652 9353 9351 27653 9351 9356 27654 9356 9353 27655 9353 9354 27656 9354 9356 27657 9356 9355 27658 9355 9353 27659 9353 9358 27660 9358 9355 27661 9355 9356 27662 9356 9358 27663 9358 9357 27664 9357 9355 27665 9355 9341 27666 9341 9357 27667 9357 9358 27668 9358 9366 27669 9366 9362 27670 9362 9359 27671 9359 9359 27672 9359 9360 27673 9360 9361 27674 9361 9359 27675 9359 9362 27676 9362 9360 27677 9360 9365 27678 9365 9363 27679 9363 9364 27680 9364 9367 27681 9367 9363 27682 9363 9365 27683 9365 9367 27684 9367 9366 27685 9366 9363 27686 9363 9368 27687 9368 9366 27688 9366 9367 27689 9367 9362 27690 9362 9366 27691 9366 9368 27692 9368 9402 27693 9402 9369 27694 9369 9370 27695 9370 9372 27696 9372 9370 27697 9370 9371 27698 9371 9402 27699 9402 9370 27700 9370 9372 27701 9372 9376 27702 9376 9373 27703 9373 9374 27704 9374 9376 27705 9376 9375 27706 9375 9373 27707 9373 9378 27708 9378 9375 27709 9375 9376 27710 9376 9378 27711 9378 9377 27712 9377 9375 27713 9375 9380 27714 9380 9377 27715 9377 9378 27716 9378 9380 27717 9380 9379 27718 9379 9377 27719 9377 9382 27720 9382 9379 27721 9379 9380 27722 9380 9382 27723 9382 9381 27724 9381 9379 27725 9379 9384 27726 9384 9381 27727 9381 9382 27728 9382 9384 27729 9384 9383 27730 9383 9381 27731 9381 9387 27732 9387 9383 27733 9383 9384 27734 9384 9387 27735 9387 9385 27736 9385 9383 27737 9383 9387 27738 9387 9386 27739 9386 9385 27740 9385 9388 27741 9388 9386 27742 9386 9387 27743 9387 9390 27744 9390 9386 27745 9386 9388 27746 9388 9390 27747 9390 9389 27748 9389 9386 27749 9386 9393 27750 9393 9389 27751 9389 9390 27752 9390 9393 27753 9393 9391 27754 9391 9389 27755 9389 9393 27756 9393 9392 27757 9392 9391 27758 9391 9394 27759 9394 9392 27760 9392 9393 27761 9393 9396 27762 9396 9392 27763 9392 9394 27764 9394 9396 27765 9396 9395 27766 9395 9392 27767 9392 9398 27768 9398 9395 27769 9395 9396 27770 9396 9398 27771 9398 9397 27772 9397 9395 27773 9395 9400 27774 9400 9397 27775 9397 9398 27776 9398 9400 27777 9400 9399 27778 9399 9397 27779 9397 9369 27780 9369 9399 27781 9399 9400 27782 9400 9369 27783 9369 9401 27784 9401 9399 27785 9399 9369 27786 9369 9402 27787 9402 9401 27788 9401 9434 27789 9434 9406 27790 9406 9403 27791 9403 9410 27792 9410 9404 27793 9404 9405 27794 9405 9408 27795 9408 9406 27796 9406 9407 27797 9407 9403 27798 9403 9406 27799 9406 9408 27800 9408 9410 27801 9410 9409 27802 9409 9404 27803 9404 9412 27804 9412 9409 27805 9409 9410 27806 9410 9412 27807 9412 9411 27808 9411 9409 27809 9409 9414 27810 9414 9411 27811 9411 9412 27812 9412 9414 27813 9414 9413 27814 9413 9411 27815 9411 9417 27816 9417 9413 27817 9413 9414 27818 9414 9417 27819 9417 9415 27820 9415 9413 27821 9413 9417 27822 9417 9416 27823 9416 9415 27824 9415 9418 27825 9418 9416 27826 9416 9417 27827 9417 9420 27828 9420 9416 27829 9416 9418 27830 9418 9420 27831 9420 9419 27832 9419 9416 27833 9416 9423 27834 9423 9419 27835 9419 9420 27836 9420 9423 27837 9423 9421 27838 9421 9419 27839 9419 9423 27840 9423 9422 27841 9422 9421 27842 9421 9424 27843 9424 9422 27844 9422 9423 27845 9423 9427 27846 9427 9422 27847 9422 9424 27848 9424 9427 27849 9427 9425 27850 9425 9422 27851 9422 9427 27852 9427 9426 27853 9426 9425 27854 9425 9428 27855 9428 9426 27856 9426 9427 27857 9427 9430 27858 9430 9426 27859 9426 9428 27860 9428 9430 27861 9430 9429 27862 9429 9426 27863 9426 9432 27864 9432 9429 27865 9429 9430 27866 9430 9432 27867 9432 9431 27868 9431 9429 27869 9429 9435 27870 9435 9431 27871 9431 9432 27872 9432 9435 27873 9435 9433 27874 9433 9431 27875 9431 9435 27876 9435 9434 27877 9434 9433 27878 9433 9436 27879 9436 9434 27880 9434 9435 27881 9435 9406 27882 9406 9434 27883 9434 9436 27884 9436 9569 27885 9569 9437 27886 9437 9443 27887 9443 9440 27888 9440 9445 27889 9445 9438 27890 9438 9440 27891 9440 9439 27892 9439 9445 27893 9445 9442 27894 9442 9439 27895 9439 9440 27896 9440 9442 27897 9442 9441 27898 9441 9439 27899 9439 9569 27900 9569 9441 27901 9441 9442 27902 9442 9569 27903 9569 9443 27904 9443 9441 27905 9441 9445 27906 9445 9444 27907 9444 9438 27908 9438 9447 27909 9447 9444 27910 9444 9445 27911 9445 9447 27912 9447 9446 27913 9446 9444 27914 9444 9449 27915 9449 9446 27916 9446 9447 27917 9447 9449 27918 9449 9448 27919 9448 9446 27920 9446 9451 27921 9451 9448 27922 9448 9449 27923 9449 9451 27924 9451 9450 27925 9450 9448 27926 9448 9453 27927 9453 9450 27928 9450 9451 27929 9451 9453 27930 9453 9452 27931 9452 9450 27932 9450 9455 27933 9455 9452 27934 9452 9453 27935 9453 9455 27936 9455 9454 27937 9454 9452 27938 9452 9457 27939 9457 9454 27940 9454 9455 27941 9455 9457 27942 9457 9456 27943 9456 9454 27944 9454 9475 27945 9475 9456 27946 9456 9457 27947 9457 9475 27948 9475 9458 27949 9458 9456 27950 9456 9461 27951 9461 9480 27952 9480 9459 27953 9459 9461 27954 9461 9460 27955 9460 9480 27956 9480 9463 27957 9463 9460 27958 9460 9461 27959 9461 9463 27960 9463 9462 27961 9462 9460 27962 9460 9465 27963 9465 9462 27964 9462 9463 27965 9463 9465 27966 9465 9464 27967 9464 9462 27968 9462 9467 27969 9467 9464 27970 9464 9465 27971 9465 9467 27972 9467 9466 27973 9466 9464 27974 9464 9469 27975 9469 9466 27976 9466 9467 27977 9467 9469 27978 9469 9468 27979 9468 9466 27980 9466 9471 27981 9471 9468 27982 9468 9469 27983 9469 9471 27984 9471 9470 27985 9470 9468 27986 9468 9473 27987 9473 9470 27988 9470 9471 27989 9471 9473 27990 9473 9472 27991 9472 9470 27992 9470 9551 27993 9551 9472 27994 9472 9473 27995 9473 9551 27996 9551 9474 27997 9474 9472 27998 9472 9477 27999 9477 9458 28000 9458 9475 28001 9475 9477 28002 9477 9476 28003 9476 9458 28004 9458 9495 28005 9495 9476 28006 9476 9477 28007 9477 9495 28008 9495 9478 28009 9478 9476 28010 9476 9480 28011 9480 9479 28012 9479 9459 28013 9459 9482 28014 9482 9479 28015 9479 9480 28016 9480 9482 28017 9482 9481 28018 9481 9479 28019 9479 9484 28020 9484 9481 28021 9481 9482 28022 9482 9484 28023 9484 9483 28024 9483 9481 28025 9481 9486 28026 9486 9483 28027 9483 9484 28028 9484 9486 28029 9486 9485 28030 9485 9483 28031 9483 9488 28032 9488 9485 28033 9485 9486 28034 9486 9488 28035 9488 9487 28036 9487 9485 28037 9485 9490 28038 9490 9487 28039 9487 9488 28040 9488 9490 28041 9490 9489 28042 9489 9487 28043 9487 9492 28044 9492 9489 28045 9489 9490 28046 9490 9492 28047 9492 9491 28048 9491 9489 28049 9489 9494 28050 9494 9491 28051 9491 9492 28052 9492 9494 28053 9494 9493 28054 9493 9491 28055 9491 9504 28056 9504 9493 28057 9493 9494 28058 9494 9497 28059 9497 9478 28060 9478 9495 28061 9495 9497 28062 9497 9496 28063 9496 9478 28064 9478 9500 28065 9500 9496 28066 9496 9497 28067 9497 9500 28068 9500 9498 28069 9498 9496 28070 9496 9500 28071 9500 9499 28072 9499 9498 28073 9498 9523 28074 9523 9499 28075 9499 9500 28076 9500 9493 28077 9493 9501 28078 9501 9502 28079 9502 9493 28080 9493 9503 28081 9503 9501 28082 9501 9504 28083 9504 9503 28084 9503 9493 28085 9493 9506 28086 9506 9503 28087 9503 9504 28088 9504 9506 28089 9506 9505 28090 9505 9503 28091 9503 9508 28092 9508 9505 28093 9505 9506 28094 9506 9508 28095 9508 9507 28096 9507 9505 28097 9505 9510 28098 9510 9507 28099 9507 9508 28100 9508 9510 28101 9510 9509 28102 9509 9507 28103 9507 9512 28104 9512 9509 28105 9509 9510 28106 9510 9512 28107 9512 9511 28108 9511 9509 28109 9509 9514 28110 9514 9511 28111 9511 9512 28112 9512 9514 28113 9514 9513 28114 9513 9511 28115 9511 9517 28116 9517 9513 28117 9513 9514 28118 9514 9517 28119 9517 9515 28120 9515 9513 28121 9513 9517 28122 9517 9516 28123 9516 9515 28124 9515 9519 28125 9519 9516 28126 9516 9517 28127 9517 9519 28128 9519 9518 28129 9518 9516 28130 9516 9567 28131 9567 9518 28132 9518 9519 28133 9519 9499 28134 9499 9520 28135 9520 9521 28136 9521 9499 28137 9499 9522 28138 9522 9520 28139 9520 9523 28140 9523 9522 28141 9522 9499 28142 9499 9525 28143 9525 9522 28144 9522 9523 28145 9523 9525 28146 9525 9524 28147 9524 9522 28148 9522 9526 28149 9526 9524 28150 9524 9525 28151 9525 9528 28152 9528 9524 28153 9524 9526 28154 9526 9528 28155 9528 9527 28156 9527 9524 28157 9524 9530 28158 9530 9527 28159 9527 9528 28160 9528 9530 28161 9530 9529 28162 9529 9527 28163 9527 9532 28164 9532 9529 28165 9529 9530 28166 9530 9532 28167 9532 9531 28168 9531 9529 28169 9529 9534 28170 9534 9531 28171 9531 9532 28172 9532 9534 28173 9534 9533 28174 9533 9531 28175 9531 9536 28176 9536 9533 28177 9533 9534 28178 9534 9536 28179 9536 9535 28180 9535 9533 28181 9533 9537 28182 9537 9535 28183 9535 9536 28184 9536 9539 28185 9539 9535 28186 9535 9537 28187 9537 9539 28188 9539 9538 28189 9538 9535 28190 9535 9540 28191 9540 9538 28192 9538 9539 28193 9539 9542 28194 9542 9538 28195 9538 9540 28196 9540 9542 28197 9542 9541 28198 9541 9538 28199 9538 9545 28200 9545 9541 28201 9541 9542 28202 9542 9545 28203 9545 9543 28204 9543 9541 28205 9541 9545 28206 9545 9544 28207 9544 9543 28208 9543 9547 28209 9547 9544 28210 9544 9545 28211 9545 9547 28212 9547 9546 28213 9546 9544 28214 9544 9549 28215 9549 9546 28216 9546 9547 28217 9547 9549 28218 9549 9548 28219 9548 9546 28220 9546 9550 28221 9550 9548 28222 9548 9549 28223 9549 9437 28224 9437 9548 28225 9548 9550 28226 9550 9553 28227 9553 9551 28228 9551 9552 28229 9552 9555 28230 9555 9551 28231 9551 9553 28232 9553 9555 28233 9555 9474 28234 9474 9551 28235 9551 9555 28236 9555 9554 28237 9554 9474 28238 9474 9558 28239 9558 9554 28240 9554 9555 28241 9555 9558 28242 9558 9556 28243 9556 9554 28244 9554 9558 28245 9558 9557 28246 9557 9556 28247 9556 9559 28248 9559 9557 28249 9557 9558 28250 9558 9561 28251 9561 9557 28252 9557 9559 28253 9559 9561 28254 9561 9560 28255 9560 9557 28256 9557 9563 28257 9563 9560 28258 9560 9561 28259 9561 9563 28260 9563 9562 28261 9562 9560 28262 9560 9565 28263 9565 9562 28264 9562 9563 28265 9563 9565 28266 9565 9564 28267 9564 9562 28268 9562 9568 28269 9568 9564 28270 9564 9565 28271 9565 9568 28272 9568 9566 28273 9566 9564 28274 9564 9568 28275 9568 9567 28276 9567 9566 28277 9566 9568 28278 9568 9518 28279 9518 9567 28280 9567 9548 28281 9548 9518 28282 9518 9568 28283 9568 9548 28284 9548 9569 28285 9569 9518 28286 9518 9437 28287 9437 9569 28288 9569 9548 28289 9548 9577 28290 9577 9571 28291 9571 9570 28292 9570 9570 28293 9570 9571 28294 9571 9572 28295 9572 9575 28296 9575 9573 28297 9573 9574 28298 9574 9576 28299 9576 9573 28300 9573 9575 28301 9575 9571 28302 9571 9573 28303 9573 9576 28304 9576 9571 28305 9571 9577 28306 9577 9573 28307 9573 9582 28308 9582 9578 28309 9578 9579 28310 9579 9585 28311 9585 9580 28312 9580 9581 28313 9581 9584 28314 9584 9582 28315 9582 9583 28316 9583 9580 28317 9580 9582 28318 9582 9584 28319 9584 9585 28320 9585 9582 28321 9582 9580 28322 9580 9578 28323 9578 9582 28324 9582 9585 28325 9585 9604 28326 9604 9586 28327 9586 9605 28328 9605 9588 28329 9588 9606 28330 9606 9587 28331 9587 9589 28332 9589 9606 28333 9606 9588 28334 9588 9590 28335 9590 9606 28336 9606 9589 28337 9589 9590 28338 9590 9607 28339 9607 9606 28340 9606 9591 28341 9591 9607 28342 9607 9590 28343 9590 9591 28344 9591 9608 28345 9608 9607 28346 9607 9591 28347 9591 9609 28348 9609 9608 28349 9608 9592 28350 9592 9609 28351 9609 9591 28352 9591 9593 28353 9593 9609 28354 9609 9592 28355 9592 9593 28356 9593 9610 28357 9610 9609 28358 9609 9594 28359 9594 9610 28360 9610 9593 28361 9593 9594 28362 9594 9611 28363 9611 9610 28364 9610 9594 28365 9594 9612 28366 9612 9611 28367 9611 9595 28368 9595 9612 28369 9612 9594 28370 9594 9595 28371 9595 9613 28372 9613 9612 28373 9612 9596 28374 9596 9613 28375 9613 9595 28376 9595 9597 28377 9597 9613 28378 9613 9596 28379 9596 9597 28380 9597 9614 28381 9614 9613 28382 9613 9598 28383 9598 9614 28384 9614 9597 28385 9597 9598 28386 9598 9615 28387 9615 9614 28388 9614 9599 28389 9599 9615 28390 9615 9598 28391 9598 9599 28392 9599 9616 28393 9616 9615 28394 9615 9600 28395 9600 9616 28396 9616 9599 28397 9599 9600 28398 9600 9617 28399 9617 9616 28400 9616 9600 28401 9600 9618 28402 9618 9617 28403 9617 9601 28404 9601 9618 28405 9618 9600 28406 9600 9601 28407 9601 9619 28408 9619 9618 28409 9618 9602 28410 9602 9619 28411 9619 9601 28412 9601 9602 28413 9602 9604 28414 9604 9619 28415 9619 9603 28416 9603 9604 28417 9604 9602 28418 9602 9586 28419 9586 9604 28420 9604 9603 28421 9603 9652 28422 9652 9620 28423 9620 9621 28424 9621 9624 28425 9624 9622 28426 9622 9623 28427 9623 9626 28428 9626 9622 28429 9622 9624 28430 9624 9626 28431 9626 9625 28432 9625 9622 28433 9622 9628 28434 9628 9625 28435 9625 9626 28436 9626 9628 28437 9628 9627 28438 9627 9625 28439 9625 9629 28440 9629 9627 28441 9627 9628 28442 9628 9631 28443 9631 9627 28444 9627 9629 28445 9629 9631 28446 9631 9630 28447 9630 9627 28448 9627 9633 28449 9633 9630 28450 9630 9631 28451 9631 9633 28452 9633 9632 28453 9632 9630 28454 9630 9636 28455 9636 9632 28456 9632 9633 28457 9633 9636 28458 9636 9634 28459 9634 9632 28460 9632 9636 28461 9636 9635 28462 9635 9634 28463 9634 9638 28464 9638 9635 28465 9635 9636 28466 9636 9638 28467 9638 9637 28468 9637 9635 28469 9635 9640 28470 9640 9637 28471 9637 9638 28472 9638 9640 28473 9640 9639 28474 9639 9637 28475 9637 9641 28476 9641 9639 28477 9639 9640 28478 9640 9643 28479 9643 9639 28480 9639 9641 28481 9641 9643 28482 9643 9642 28483 9642 9639 28484 9639 9645 28485 9645 9642 28486 9642 9643 28487 9643 9645 28488 9645 9644 28489 9644 9642 28490 9642 9647 28491 9647 9644 28492 9644 9645 28493 9645 9647 28494 9647 9646 28495 9646 9644 28496 9644 9649 28497 9649 9646 28498 9646 9647 28499 9647 9649 28500 9649 9648 28501 9648 9646 28502 9646 9651 28503 9651 9648 28504 9648 9649 28505 9649 9651 28506 9651 9650 28507 9650 9648 28508 9648 9653 28509 9653 9650 28510 9650 9651 28511 9651 9653 28512 9653 9652 28513 9652 9650 28514 9650 9620 28515 9620 9652 28516 9652 9653 28517 9653 9670 28518 9670 9661 28519 9661 9654 28520 9654 9657 28521 9657 9655 28522 9655 9656 28523 9656 9658 28524 9658 9655 28525 9655 9657 28526 9657 9660 28527 9660 9655 28528 9655 9658 28529 9658 9660 28530 9660 9659 28531 9659 9655 28532 9655 9654 28533 9654 9659 28534 9659 9660 28535 9660 9654 28536 9654 9661 28537 9661 9659 28538 9659 9664 28539 9664 9662 28540 9662 9663 28541 9663 9665 28542 9665 9662 28543 9662 9664 28544 9664 9667 28545 9667 9662 28546 9662 9665 28547 9665 9667 28548 9667 9666 28549 9666 9662 28550 9662 9669 28551 9669 9666 28552 9666 9667 28553 9667 9669 28554 9669 9668 28555 9668 9666 28556 9666 9671 28557 9671 9668 28558 9668 9669 28559 9669 9671 28560 9671 9670 28561 9670 9668 28562 9668 9661 28563 9661 9670 28564 9670 9671 28565 9671 9704 28566 9704 9672 28567 9672 9673 28568 9673 9676 28569 9676 9674 28570 9674 9675 28571 9675 9677 28572 9677 9674 28573 9674 9676 28574 9676 9679 28575 9679 9674 28576 9674 9677 28577 9677 9679 28578 9679 9678 28579 9678 9674 28580 9674 9681 28581 9681 9678 28582 9678 9679 28583 9679 9681 28584 9681 9680 28585 9680 9678 28586 9678 9683 28587 9683 9680 28588 9680 9681 28589 9681 9683 28590 9683 9682 28591 9682 9680 28592 9680 9685 28593 9685 9682 28594 9682 9683 28595 9683 9685 28596 9685 9684 28597 9684 9682 28598 9682 9687 28599 9687 9684 28600 9684 9685 28601 9685 9687 28602 9687 9686 28603 9686 9684 28604 9684 9689 28605 9689 9686 28606 9686 9687 28607 9687 9689 28608 9689 9688 28609 9688 9686 28610 9686 9691 28611 9691 9688 28612 9688 9689 28613 9689 9691 28614 9691 9690 28615 9690 9688 28616 9688 9693 28617 9693 9690 28618 9690 9691 28619 9691 9693 28620 9693 9692 28621 9692 9690 28622 9690 9695 28623 9695 9692 28624 9692 9693 28625 9693 9695 28626 9695 9694 28627 9694 9692 28628 9692 9697 28629 9697 9694 28630 9694 9695 28631 9695 9697 28632 9697 9696 28633 9696 9694 28634 9694 9699 28635 9699 9696 28636 9696 9697 28637 9697 9699 28638 9699 9698 28639 9698 9696 28640 9696 9701 28641 9701 9698 28642 9698 9699 28643 9699 9701 28644 9701 9700 28645 9700 9698 28646 9698 9703 28647 9703 9700 28648 9700 9701 28649 9701 9703 28650 9703 9702 28651 9702 9700 28652 9700 9705 28653 9705 9702 28654 9702 9703 28655 9703 9705 28656 9705 9704 28657 9704 9702 28658 9702 9672 28659 9672 9704 28660 9704 9705 28661 9705 9712 28662 9712 9706 28663 9706 9707 28664 9707 9712 28665 9712 9707 28666 9707 9708 28667 9708 9713 28668 9713 9709 28669 9709 9710 28670 9710 9713 28671 9713 9711 28672 9711 9709 28673 9709 9713 28674 9713 9712 28675 9712 9711 28676 9711 9706 28677 9706 9712 28678 9712 9713 28679 9713 9721 28680 9721 9715 28681 9715 9714 28682 9714 9714 28683 9714 9715 28684 9715 9716 28685 9716 9719 28686 9719 9717 28687 9717 9718 28688 9718 9720 28689 9720 9717 28690 9717 9719 28691 9719 9715 28692 9715 9717 28693 9717 9720 28694 9720 9715 28695 9715 9721 28696 9721 9717 28697 9717 9729 28698 9729 9723 28699 9723 9722 28700 9722 9722 28701 9722 9723 28702 9723 9724 28703 9724 9727 28704 9727 9725 28705 9725 9726 28706 9726 9728 28707 9728 9725 28708 9725 9727 28709 9727 9723 28710 9723 9725 28711 9725 9728 28712 9728 9723 28713 9723 9729 28714 9729 9725 28715 9725 9736 28716 9736 9730 28717 9730 9731 28718 9731 9736 28719 9736 9731 28720 9731 9732 28721 9732 9737 28722 9737 9733 28723 9733 9734 28724 9734 9737 28725 9737 9735 28726 9735 9733 28727 9733 9737 28728 9737 9736 28729 9736 9735 28730 9735 9730 28731 9730 9736 28732 9736 9737 28733 9737 9771 28734 9771 9738 28735 9738 9743 28736 9743 9744 28737 9744 9739 28738 9739 9740 28739 9740 9771 28740 9771 9741 28741 9741 9742 28742 9742 9771 28743 9771 9743 28744 9743 9741 28745 9741 9745 28746 9745 9739 28747 9739 9744 28748 9744 9748 28749 9748 9739 28750 9739 9745 28751 9745 9748 28752 9748 9746 28753 9746 9739 28754 9739 9748 28755 9748 9747 28756 9747 9746 28757 9746 9749 28758 9749 9747 28759 9747 9748 28760 9748 9751 28761 9751 9747 28762 9747 9749 28763 9749 9751 28764 9751 9750 28765 9750 9747 28766 9747 9753 28767 9753 9750 28768 9750 9751 28769 9751 9753 28770 9753 9752 28771 9752 9750 28772 9750 9756 28773 9756 9752 28774 9752 9753 28775 9753 9756 28776 9756 9754 28777 9754 9752 28778 9752 9756 28779 9756 9755 28780 9755 9754 28781 9754 9757 28782 9757 9755 28783 9755 9756 28784 9756 9760 28785 9760 9755 28786 9755 9757 28787 9757 9760 28788 9760 9758 28789 9758 9755 28790 9755 9760 28791 9760 9759 28792 9759 9758 28793 9758 9761 28794 9761 9759 28795 9759 9760 28796 9760 9763 28797 9763 9759 28798 9759 9761 28799 9761 9763 28800 9763 9762 28801 9762 9759 28802 9759 9765 28803 9765 9762 28804 9762 9763 28805 9763 9765 28806 9765 9764 28807 9764 9762 28808 9762 9767 28809 9767 9764 28810 9764 9765 28811 9765 9767 28812 9767 9766 28813 9766 9764 28814 9764 9770 28815 9770 9766 28816 9766 9767 28817 9767 9770 28818 9770 9768 28819 9768 9766 28820 9766 9770 28821 9770 9769 28822 9769 9768 28823 9768 9738 28824 9738 9769 28825 9769 9770 28826 9770 9738 28827 9738 9771 28828 9771 9769 28829 9769 9805 28830 9805 9772 28831 9772 9776 28832 9776 9780 28833 9780 9773 28834 9773 9774 28835 9774 9780 28836 9780 9775 28837 9775 9773 28838 9773 9778 28839 9778 9776 28840 9776 9777 28841 9777 9805 28842 9805 9776 28843 9776 9778 28844 9778 9780 28845 9780 9779 28846 9779 9775 28847 9775 9781 28848 9781 9779 28849 9779 9780 28850 9780 9783 28851 9783 9779 28852 9779 9781 28853 9781 9783 28854 9783 9782 28855 9782 9779 28856 9779 9786 28857 9786 9782 28858 9782 9783 28859 9783 9786 28860 9786 9784 28861 9784 9782 28862 9782 9786 28863 9786 9785 28864 9785 9784 28865 9784 9787 28866 9787 9785 28867 9785 9786 28868 9786 9790 28869 9790 9785 28870 9785 9787 28871 9787 9790 28872 9790 9788 28873 9788 9785 28874 9785 9790 28875 9790 9789 28876 9789 9788 28877 9788 9791 28878 9791 9789 28879 9789 9790 28880 9790 9793 28881 9793 9789 28882 9789 9791 28883 9791 9793 28884 9793 9792 28885 9792 9789 28886 9789 9796 28887 9796 9792 28888 9792 9793 28889 9793 9796 28890 9796 9794 28891 9794 9792 28892 9792 9796 28893 9796 9795 28894 9795 9794 28895 9794 9797 28896 9797 9795 28897 9795 9796 28898 9796 9799 28899 9799 9795 28900 9795 9797 28901 9797 9799 28902 9799 9798 28903 9798 9795 28904 9795 9801 28905 9801 9798 28906 9798 9799 28907 9799 9801 28908 9801 9800 28909 9800 9798 28910 9798 9803 28911 9803 9800 28912 9800 9801 28913 9801 9803 28914 9803 9802 28915 9802 9800 28916 9800 9772 28917 9772 9802 28918 9802 9803 28919 9803 9772 28920 9772 9804 28921 9804 9802 28922 9802 9772 28923 9772 9805 28924 9805 9804 28925 9804 9808 28926 9808 9806 28927 9806 9807 28928 9807 9806 28929 9806 9808 28930 9808 9809 28931 9809 9812 28932 9812 9810 28933 9810 9811 28934 9811 9810 28935 9810 9812 28936 9812 9813 28937 9813 9946 28938 9946 9814 28939 9814 9815 28940 9815 9817 28941 9817 9816 28942 9816 9853 28943 9853 9819 28944 9819 9816 28945 9816 9817 28946 9817 9819 28947 9819 9818 28948 9818 9816 28949 9816 9821 28950 9821 9818 28951 9818 9819 28952 9819 9821 28953 9821 9820 28954 9820 9818 28955 9818 9823 28956 9823 9820 28957 9820 9821 28958 9821 9823 28959 9823 9822 28960 9822 9820 28961 9820 9825 28962 9825 9822 28963 9822 9823 28964 9823 9825 28965 9825 9824 28966 9824 9822 28967 9822 9827 28968 9827 9824 28969 9824 9825 28970 9825 9827 28971 9827 9826 28972 9826 9824 28973 9824 9866 28974 9866 9826 28975 9826 9827 28976 9827 9830 28977 9830 9844 28978 9844 9828 28979 9828 9830 28980 9830 9829 28981 9829 9844 28982 9844 9832 28983 9832 9829 28984 9829 9830 28985 9830 9832 28986 9832 9831 28987 9831 9829 28988 9829 9834 28989 9834 9831 28990 9831 9832 28991 9832 9834 28992 9834 9833 28993 9833 9831 28994 9831 9836 28995 9836 9833 28996 9833 9834 28997 9834 9836 28998 9836 9835 28999 9835 9833 29000 9833 9838 29001 9838 9835 29002 9835 9836 29003 9836 9838 29004 9838 9837 29005 9837 9835 29006 9835 9840 29007 9840 9837 29008 9837 9838 29009 9838 9840 29010 9840 9839 29011 9839 9837 29012 9837 9842 29013 9842 9839 29014 9839 9840 29015 9840 9842 29016 9842 9841 29017 9841 9839 29018 9839 9850 29019 9850 9841 29020 9841 9842 29021 9842 9844 29022 9844 9843 29023 9843 9828 29024 9828 9846 29025 9846 9843 29026 9843 9844 29027 9844 9846 29028 9846 9845 29029 9845 9843 29030 9843 9848 29031 9848 9845 29032 9845 9846 29033 9846 9848 29034 9848 9847 29035 9847 9845 29036 9845 9916 29037 9916 9847 29038 9847 9848 29039 9848 9850 29040 9850 9849 29041 9849 9841 29042 9841 9852 29043 9852 9849 29044 9849 9850 29045 9850 9852 29046 9852 9851 29047 9851 9849 29048 9849 9858 29049 9858 9851 29050 9851 9852 29051 9852 9855 29052 9855 9817 29053 9817 9853 29054 9853 9855 29055 9855 9854 29056 9854 9817 29057 9817 9915 29058 9915 9854 29059 9854 9855 29060 9855 9915 29061 9915 9856 29062 9856 9854 29063 9854 9858 29064 9858 9857 29065 9857 9851 29066 9851 9859 29067 9859 9857 29068 9857 9858 29069 9858 9861 29070 9861 9857 29071 9857 9859 29072 9859 9861 29073 9861 9860 29074 9860 9857 29075 9857 9945 29076 9945 9860 29077 9860 9861 29078 9861 9945 29079 9945 9862 29080 9862 9860 29081 9860 9865 29082 9865 9863 29083 9863 9864 29084 9864 9826 29085 9826 9863 29086 9863 9865 29087 9865 9866 29088 9866 9863 29089 9863 9826 29090 9826 9868 29091 9868 9863 29092 9863 9866 29093 9866 9868 29094 9868 9867 29095 9867 9863 29096 9863 9870 29097 9870 9867 29098 9867 9868 29099 9868 9870 29100 9870 9869 29101 9869 9867 29102 9867 9872 29103 9872 9869 29104 9869 9870 29105 9870 9872 29106 9872 9871 29107 9871 9869 29108 9869 9874 29109 9874 9871 29110 9871 9872 29111 9872 9874 29112 9874 9873 29113 9873 9871 29114 9871 9876 29115 9876 9873 29116 9873 9874 29117 9874 9876 29118 9876 9875 29119 9875 9873 29120 9873 9878 29121 9878 9875 29122 9875 9876 29123 9876 9878 29124 9878 9877 29125 9877 9875 29126 9875 9880 29127 9880 9877 29128 9877 9878 29129 9878 9880 29130 9880 9879 29131 9879 9877 29132 9877 9882 29133 9882 9879 29134 9879 9880 29135 9880 9882 29136 9882 9881 29137 9881 9879 29138 9879 9884 29139 9884 9881 29140 9881 9882 29141 9882 9884 29142 9884 9883 29143 9883 9881 29144 9881 9886 29145 9886 9883 29146 9883 9884 29147 9884 9886 29148 9886 9885 29149 9885 9883 29150 9883 9888 29151 9888 9885 29152 9885 9886 29153 9886 9888 29154 9888 9887 29155 9887 9885 29156 9885 9890 29157 9890 9887 29158 9887 9888 29159 9888 9890 29160 9890 9889 29161 9889 9887 29162 9887 9892 29163 9892 9889 29164 9889 9890 29165 9890 9892 29166 9892 9891 29167 9891 9889 29168 9889 9894 29169 9894 9891 29170 9891 9892 29171 9892 9894 29172 9894 9893 29173 9893 9891 29174 9891 9896 29175 9896 9893 29176 9893 9894 29177 9894 9896 29178 9896 9895 29179 9895 9893 29180 9893 9900 29181 9900 9895 29182 9895 9896 29183 9896 9899 29184 9899 9897 29185 9897 9898 29186 9898 9895 29187 9895 9897 29188 9897 9899 29189 9899 9900 29190 9900 9897 29191 9897 9895 29192 9895 9902 29193 9902 9897 29194 9897 9900 29195 9900 9902 29196 9902 9901 29197 9901 9897 29198 9897 9903 29199 9903 9901 29200 9901 9902 29201 9902 9906 29202 9906 9901 29203 9901 9903 29204 9903 9906 29205 9906 9904 29206 9904 9901 29207 9901 9906 29208 9906 9905 29209 9905 9904 29210 9904 9908 29211 9908 9905 29212 9905 9906 29213 9906 9908 29214 9908 9907 29215 9907 9905 29216 9905 9910 29217 9910 9907 29218 9907 9908 29219 9908 9910 29220 9910 9909 29221 9909 9907 29222 9907 9912 29223 9912 9909 29224 9909 9910 29225 9910 9912 29226 9912 9911 29227 9911 9909 29228 9909 9913 29229 9913 9911 29230 9911 9912 29231 9912 9856 29232 9856 9911 29233 9911 9913 29234 9913 9915 29235 9915 9911 29236 9911 9856 29237 9856 9915 29238 9915 9914 29239 9914 9911 29240 9911 9847 29241 9847 9914 29242 9914 9915 29243 9915 9916 29244 9916 9914 29245 9914 9847 29246 9847 9918 29247 9918 9914 29248 9914 9916 29249 9916 9918 29250 9918 9917 29251 9917 9914 29252 9914 9919 29253 9919 9917 29254 9917 9918 29255 9918 9921 29256 9921 9917 29257 9917 9919 29258 9919 9921 29259 9921 9920 29260 9920 9917 29261 9917 9923 29262 9923 9920 29263 9920 9921 29264 9921 9923 29265 9923 9922 29266 9922 9920 29267 9920 9925 29268 9925 9922 29269 9922 9923 29270 9923 9925 29271 9925 9924 29272 9924 9922 29273 9922 9928 29274 9928 9924 29275 9924 9925 29276 9925 9928 29277 9928 9926 29278 9926 9924 29279 9924 9928 29280 9928 9927 29281 9927 9926 29282 9926 9929 29283 9929 9927 29284 9927 9928 29285 9928 9931 29286 9931 9927 29287 9927 9929 29288 9929 9931 29289 9931 9930 29290 9930 9927 29291 9927 9932 29292 9932 9930 29293 9930 9931 29294 9931 9934 29295 9934 9930 29296 9930 9932 29297 9932 9934 29298 9934 9933 29299 9933 9930 29300 9930 9936 29301 9936 9933 29302 9933 9934 29303 9934 9936 29304 9936 9935 29305 9935 9933 29306 9933 9938 29307 9938 9935 29308 9935 9936 29309 9936 9938 29310 9938 9937 29311 9937 9935 29312 9935 9941 29313 9941 9937 29314 9937 9938 29315 9938 9941 29316 9941 9939 29317 9939 9937 29318 9937 9941 29319 9941 9940 29320 9940 9939 29321 9939 9942 29322 9942 9940 29323 9940 9941 29324 9941 9943 29325 9943 9940 29326 9940 9942 29327 9942 9944 29328 9944 9940 29329 9940 9943 29330 9943 9945 29331 9945 9944 29332 9944 9862 29333 9862 9945 29334 9945 9940 29335 9940 9944 29336 9944 9814 29337 9814 9940 29338 9940 9945 29339 9945 9814 29340 9814 9946 29341 9946 9940 29342 9940 9951 29343 9951 9947 29344 9947 9948 29345 9948 9954 29346 9954 9949 29347 9949 9950 29348 9950 9953 29349 9953 9951 29350 9951 9952 29351 9952 9949 29352 9949 9951 29353 9951 9953 29354 9953 9954 29355 9954 9951 29356 9951 9949 29357 9949 9947 29358 9947 9951 29359 9951 9954 29360 9954 9961 29361 9961 9955 29362 9955 9956 29363 9956 9955 29364 9955 9957 29365 9957 9958 29366 9958 9955 29367 9955 9959 29368 9959 9957 29369 9957 9955 29370 9955 9960 29371 9960 9959 29372 9959 9955 29373 9955 9961 29374 9961 9960 29375 9960 9980 29376 9980 9962 29377 9962 9981 29378 9981 9964 29379 9964 9982 29380 9982 9963 29381 9963 9965 29382 9965 9982 29383 9982 9964 29384 9964 9966 29385 9966 9982 29386 9982 9965 29387 9965 9966 29388 9966 9983 29389 9983 9982 29390 9982 9967 29391 9967 9983 29392 9983 9966 29393 9966 9967 29394 9967 9984 29395 9984 9983 29396 9983 9967 29397 9967 9985 29398 9985 9984 29399 9984 9968 29400 9968 9985 29401 9985 9967 29402 9967 9969 29403 9969 9985 29404 9985 9968 29405 9968 9969 29406 9969 9986 29407 9986 9985 29408 9985 9970 29409 9970 9986 29410 9986 9969 29411 9969 9970 29412 9970 9987 29413 9987 9986 29414 9986 9970 29415 9970 9988 29416 9988 9987 29417 9987 9971 29418 9971 9988 29419 9988 9970 29420 9970 9971 29421 9971 9989 29422 9989 9988 29423 9988 9972 29424 9972 9989 29425 9989 9971 29426 9971 9973 29427 9973 9989 29428 9989 9972 29429 9972 9973 29430 9973 9990 29431 9990 9989 29432 9989 9974 29433 9974 9990 29434 9990 9973 29435 9973 9974 29436 9974 9991 29437 9991 9990 29438 9990 9975 29439 9975 9991 29440 9991 9974 29441 9974 9975 29442 9975 9992 29443 9992 9991 29444 9991 9976 29445 9976 9992 29446 9992 9975 29447 9975 9976 29448 9976 9993 29449 9993 9992 29450 9992 9976 29451 9976 9994 29452 9994 9993 29453 9993 9977 29454 9977 9994 29455 9994 9976 29456 9976 9977 29457 9977 9995 29458 9995 9994 29459 9994 9978 29460 9978 9995 29461 9995 9977 29462 9977 9978 29463 9978 9980 29464 9980 9995 29465 9995 9979 29466 9979 9980 29467 9980 9978 29468 9978 9962 29469 9962 9980 29470 9980 9979 29471 9979 10028 29472 10028 9996 29473 9996 9997 29474 9997 10000 29475 10000 9998 29476 9998 9999 29477 9999 10001 29478 10001 9998 29479 9998 10000 29480 10000 10004 29481 10004 9998 29482 9998 10001 29483 10001 10004 29484 10004 10002 29485 10002 9998 29486 9998 10004 29487 10004 10003 29488 10003 10002 29489 10002 10005 29490 10005 10003 29491 10003 10004 29492 10004 10008 29493 10008 10003 29494 10003 10005 29495 10005 10008 29496 10008 10006 29497 10006 10003 29498 10003 10008 29499 10008 10007 29500 10007 10006 29501 10006 10010 29502 10010 10007 29503 10007 10008 29504 10008 10010 29505 10010 10009 29506 10009 10007 29507 10007 10011 29508 10011 10009 29509 10009 10010 29510 10010 10013 29511 10013 10009 29512 10009 10011 29513 10011 10013 29514 10013 10012 29515 10012 10009 29516 10009 10015 29517 10015 10012 29518 10012 10013 29519 10013 10015 29520 10015 10014 29521 10014 10012 29522 10012 10017 29523 10017 10014 29524 10014 10015 29525 10015 10017 29526 10017 10016 29527 10016 10014 29528 10014 10019 29529 10019 10016 29530 10016 10017 29531 10017 10019 29532 10019 10018 29533 10018 10016 29534 10016 10021 29535 10021 10018 29536 10018 10019 29537 10019 10021 29538 10021 10020 29539 10020 10018 29540 10018 10023 29541 10023 10020 29542 10020 10021 29543 10021 10023 29544 10023 10022 29545 10022 10020 29546 10020 10025 29547 10025 10022 29548 10022 10023 29549 10023 10025 29550 10025 10024 29551 10024 10022 29552 10022 10027 29553 10027 10024 29554 10024 10025 29555 10025 10027 29556 10027 10026 29557 10026 10024 29558 10024 10029 29559 10029 10026 29560 10026 10027 29561 10027 10029 29562 10029 10028 29563 10028 10026 29564 10026 9996 29565 9996 10028 29566 10028 10029 29567 10029 10061 29568 10061 10037 29569 10037 10030 29570 10030 10033 29571 10033 10031 29572 10031 10032 29573 10032 10035 29574 10035 10031 29575 10031 10033 29576 10033 10035 29577 10035 10034 29578 10034 10031 29579 10031 10036 29580 10036 10034 29581 10034 10035 29582 10035 10030 29583 10030 10034 29584 10034 10036 29585 10036 10030 29586 10030 10037 29587 10037 10034 29588 10034 10041 29589 10041 10038 29590 10038 10039 29591 10039 10041 29592 10041 10040 29593 10040 10038 29594 10038 10043 29595 10043 10040 29596 10040 10041 29597 10041 10043 29598 10043 10042 29599 10042 10040 29600 10040 10045 29601 10045 10042 29602 10042 10043 29603 10043 10045 29604 10045 10044 29605 10044 10042 29606 10042 10047 29607 10047 10044 29608 10044 10045 29609 10045 10047 29610 10047 10046 29611 10046 10044 29612 10044 10049 29613 10049 10046 29614 10046 10047 29615 10047 10049 29616 10049 10048 29617 10048 10046 29618 10046 10051 29619 10051 10048 29620 10048 10049 29621 10049 10051 29622 10051 10050 29623 10050 10048 29624 10048 10053 29625 10053 10050 29626 10050 10051 29627 10051 10053 29628 10053 10052 29629 10052 10050 29630 10050 10055 29631 10055 10052 29632 10052 10053 29633 10053 10055 29634 10055 10054 29635 10054 10052 29636 10052 10058 29637 10058 10054 29638 10054 10055 29639 10055 10058 29640 10058 10056 29641 10056 10054 29642 10054 10058 29643 10058 10057 29644 10057 10056 29645 10056 10059 29646 10059 10057 29647 10057 10058 29648 10058 10062 29649 10062 10057 29650 10057 10059 29651 10059 10062 29652 10062 10060 29653 10060 10057 29654 10057 10062 29655 10062 10061 29656 10061 10060 29657 10060 10063 29658 10063 10061 29659 10061 10062 29660 10062 10037 29661 10037 10061 29662 10061 10063 29663 10063 10139 29664 10139 10064 29665 10064 10102 29666 10102 10066 29667 10066 10065 29668 10065 10069 29669 10069 10068 29670 10068 10065 29671 10065 10066 29672 10066 10068 29673 10068 10067 29674 10067 10065 29675 10065 10072 29676 10072 10067 29677 10067 10068 29678 10068 10085 29679 10085 10066 29680 10066 10069 29681 10069 10085 29682 10085 10070 29683 10070 10066 29684 10066 10072 29685 10072 10071 29686 10071 10067 29687 10067 10074 29688 10074 10071 29689 10071 10072 29690 10072 10074 29691 10074 10073 29692 10073 10071 29693 10071 10076 29694 10076 10073 29695 10073 10074 29696 10074 10076 29697 10076 10075 29698 10075 10073 29699 10073 10078 29700 10078 10075 29701 10075 10076 29702 10076 10078 29703 10078 10077 29704 10077 10075 29705 10075 10080 29706 10080 10077 29707 10077 10078 29708 10078 10080 29709 10080 10079 29710 10079 10077 29711 10077 10082 29712 10082 10079 29713 10079 10080 29714 10080 10082 29715 10082 10081 29716 10081 10079 29717 10079 10084 29718 10084 10081 29719 10081 10082 29720 10082 10084 29721 10084 10083 29722 10083 10081 29723 10081 10088 29724 10088 10083 29725 10083 10084 29726 10084 10092 29727 10092 10070 29728 10070 10085 29729 10085 10092 29730 10092 10086 29731 10086 10070 29732 10070 10088 29733 10088 10087 29734 10087 10083 29735 10083 10089 29736 10089 10087 29737 10087 10088 29738 10088 10091 29739 10091 10087 29740 10087 10089 29741 10089 10091 29742 10091 10090 29743 10090 10087 29744 10087 10097 29745 10097 10090 29746 10090 10091 29747 10091 10094 29748 10094 10086 29749 10086 10092 29750 10092 10094 29751 10094 10093 29752 10093 10086 29753 10086 10101 29754 10101 10093 29755 10093 10094 29756 10094 10101 29757 10101 10095 29758 10095 10093 29759 10093 10097 29760 10097 10096 29761 10096 10090 29762 10090 10098 29763 10098 10096 29764 10096 10097 29765 10097 10100 29766 10100 10096 29767 10096 10098 29768 10098 10100 29769 10100 10099 29770 10099 10096 29771 10096 10105 29772 10105 10099 29773 10099 10100 29774 10100 10103 29775 10103 10095 29776 10095 10101 29777 10101 10103 29778 10103 10102 29779 10102 10095 29780 10095 10139 29781 10139 10102 29782 10102 10103 29783 10103 10105 29784 10105 10104 29785 10104 10099 29786 10099 10107 29787 10107 10104 29788 10104 10105 29789 10105 10107 29790 10107 10106 29791 10106 10104 29792 10104 10109 29793 10109 10106 29794 10106 10107 29795 10107 10109 29796 10109 10108 29797 10108 10106 29798 10106 10111 29799 10111 10108 29800 10108 10109 29801 10109 10111 29802 10111 10110 29803 10110 10108 29804 10108 10113 29805 10113 10110 29806 10110 10111 29807 10111 10113 29808 10113 10112 29809 10112 10110 29810 10110 10116 29811 10116 10112 29812 10112 10113 29813 10113 10116 29814 10116 10114 29815 10114 10112 29816 10112 10116 29817 10116 10115 29818 10115 10114 29819 10114 10118 29820 10118 10115 29821 10115 10116 29822 10116 10118 29823 10118 10117 29824 10117 10115 29825 10115 10121 29826 10121 10117 29827 10117 10118 29828 10118 10121 29829 10121 10119 29830 10119 10117 29831 10117 10121 29832 10121 10120 29833 10120 10119 29834 10119 10123 29835 10123 10120 29836 10120 10121 29837 10121 10123 29838 10123 10122 29839 10122 10120 29840 10120 10124 29841 10124 10122 29842 10122 10123 29843 10123 10125 29844 10125 10122 29845 10122 10124 29846 10124 10126 29847 10126 10122 29848 10122 10125 29849 10125 10127 29850 10127 10122 29851 10122 10126 29852 10126 10128 29853 10128 10122 29854 10122 10127 29855 10127 10129 29856 10129 10122 29857 10122 10128 29858 10128 10130 29859 10130 10122 29860 10122 10129 29861 10129 10131 29862 10131 10122 29863 10122 10130 29864 10130 10132 29865 10132 10122 29866 10122 10131 29867 10131 10133 29868 10133 10122 29869 10122 10132 29870 10132 10134 29871 10134 10122 29872 10122 10133 29873 10133 10135 29874 10135 10122 29875 10122 10134 29876 10134 10136 29877 10136 10122 29878 10122 10135 29879 10135 10138 29880 10138 10122 29881 10122 10136 29882 10136 10138 29883 10138 10137 29884 10137 10122 29885 10122 10064 29886 10064 10137 29887 10137 10138 29888 10138 10064 29889 10064 10139 29890 10139 10137 29891 10137 10146 29892 10146 10140 29893 10140 10141 29894 10141 10146 29895 10146 10141 29896 10141 10142 29897 10142 10147 29898 10147 10143 29899 10143 10144 29900 10144 10147 29901 10147 10145 29902 10145 10143 29903 10143 10147 29904 10147 10146 29905 10146 10145 29906 10145 10140 29907 10140 10146 29908 10146 10147 29909 10147 10155 29910 10155 10149 29911 10149 10148 29912 10148 10148 29913 10148 10149 29914 10149 10150 29915 10150 10153 29916 10153 10151 29917 10151 10152 29918 10152 10154 29919 10154 10151 29920 10151 10153 29921 10153 10149 29922 10149 10151 29923 10151 10154 29924 10154 10149 29925 10149 10155 29926 10155 10151 29927 10151 10163 29928 10163 10156 29929 10156 10157 29930 10157 10162 29931 10162 10158 29932 10158 10159 29933 10159 10156 29934 10156 10160 29935 10160 10161 29936 10161 10156 29937 10156 10162 29938 10162 10160 29939 10160 10156 29940 10156 10158 29941 10158 10162 29942 10162 10156 29943 10156 10163 29944 10163 10158 29945 10158 10170 29946 10170 10164 29947 10164 10165 29948 10165 10170 29949 10170 10165 29950 10165 10166 29951 10166 10171 29952 10171 10167 29953 10167 10168 29954 10168 10171 29955 10171 10169 29956 10169 10167 29957 10167 10171 29958 10171 10170 29959 10170 10169 29960 10169 10164 29961 10164 10170 29962 10170 10171 29963 10171 10203 29964 10203 10182 29965 10182 10172 29966 10172 10175 29967 10175 10173 29968 10173 10174 29969 10174 10177 29970 10177 10173 29971 10173 10175 29972 10175 10177 29973 10177 10176 29974 10176 10173 29975 10173 10179 29976 10179 10176 29977 10176 10177 29978 10177 10179 29979 10179 10178 29980 10178 10176 29981 10176 10181 29982 10181 10178 29983 10178 10179 29984 10179 10181 29985 10181 10180 29986 10180 10178 29987 10178 10183 29988 10183 10180 29989 10180 10181 29990 10181 10183 29991 10183 10182 29992 10182 10180 29993 10180 10172 29994 10172 10182 29995 10182 10183 29996 10183 10187 29997 10187 10184 29998 10184 10185 29999 10185 10187 30000 10187 10186 30001 10186 10184 30002 10184 10190 30003 10190 10186 30004 10186 10187 30005 10187 10190 30006 10190 10188 30007 10188 10186 30008 10186 10190 30009 10190 10189 30010 10189 10188 30011 10188 10191 30012 10191 10189 30013 10189 10190 30014 10190 10193 30015 10193 10189 30016 10189 10191 30017 10191 10193 30018 10193 10192 30019 10192 10189 30020 10189 10196 30021 10196 10192 30022 10192 10193 30023 10193 10196 30024 10196 10194 30025 10194 10192 30026 10192 10196 30027 10196 10195 30028 10195 10194 30029 10194 10197 30030 10197 10195 30031 10195 10196 30032 10196 10199 30033 10199 10195 30034 10195 10197 30035 10197 10199 30036 10199 10198 30037 10198 10195 30038 10195 10202 30039 10202 10198 30040 10198 10199 30041 10199 10202 30042 10202 10200 30043 10200 10198 30044 10198 10202 30045 10202 10201 30046 10201 10200 30047 10200 10204 30048 10204 10201 30049 10201 10202 30050 10202 10204 30051 10204 10203 30052 10203 10201 30053 10201 10205 30054 10205 10203 30055 10203 10204 30056 10204 10182 30057 10182 10203 30058 10203 10205 30059 10205 10223 30060 10223 10206 30061 10206 10207 30062 10207 10210 30063 10210 10208 30064 10208 10209 30065 10209 10211 30066 10211 10208 30067 10208 10210 30068 10210 10213 30069 10213 10208 30070 10208 10211 30071 10211 10213 30072 10213 10212 30073 10212 10208 30074 10208 10215 30075 10215 10212 30076 10212 10213 30077 10213 10215 30078 10215 10214 30079 10214 10212 30080 10212 10218 30081 10218 10214 30082 10214 10215 30083 10215 10218 30084 10218 10216 30085 10216 10214 30086 10214 10218 30087 10218 10217 30088 10217 10216 30089 10216 10219 30090 10219 10217 30091 10217 10218 30092 10218 10221 30093 10221 10217 30094 10217 10219 30095 10219 10221 30096 10221 10220 30097 10220 10217 30098 10217 10206 30099 10206 10220 30100 10220 10221 30101 10221 10206 30102 10206 10222 30103 10222 10220 30104 10220 10206 30105 10206 10223 30106 10223 10222 30107 10222 10236 30108 10236 10233 30109 10233 10224 30110 10224 10227 30111 10227 10225 30112 10225 10226 30113 10226 10228 30114 10228 10225 30115 10225 10227 30116 10227 10230 30117 10230 10225 30118 10225 10228 30119 10228 10230 30120 10230 10229 30121 10229 10225 30122 10225 10232 30123 10232 10229 30124 10229 10230 30125 10230 10232 30126 10232 10231 30127 10231 10229 30128 10229 10224 30129 10224 10231 30130 10231 10232 30131 10232 10224 30132 10224 10233 30133 10233 10231 30134 10231 10237 30135 10237 10234 30136 10234 10235 30137 10235 10237 30138 10237 10236 30139 10236 10234 30140 10234 10233 30141 10233 10236 30142 10236 10237 30143 10237 10255 30144 10255 10238 30145 10238 10239 30146 10239 10242 30147 10242 10240 30148 10240 10241 30149 10241 10243 30150 10243 10240 30151 10240 10242 30152 10242 10246 30153 10246 10240 30154 10240 10243 30155 10243 10246 30156 10246 10244 30157 10244 10240 30158 10240 10246 30159 10246 10245 30160 10245 10244 30161 10244 10247 30162 10247 10245 30163 10245 10246 30164 10246 10250 30165 10250 10245 30166 10245 10247 30167 10247 10250 30168 10250 10248 30169 10248 10245 30170 10245 10250 30171 10250 10249 30172 10249 10248 30173 10248 10252 30174 10252 10249 30175 10249 10250 30176 10250 10252 30177 10252 10251 30178 10251 10249 30179 10249 10253 30180 10253 10251 30181 10251 10252 30182 10252 10238 30183 10238 10251 30184 10251 10253 30185 10253 10238 30186 10238 10254 30187 10254 10251 30188 10251 10238 30189 10238 10255 30190 10255 10254 30191 10254 10289 30192 10289 10256 30193 10256 10263 30194 10263 10259 30195 10259 10257 30196 10257 10258 30197 10258 10260 30198 10260 10257 30199 10257 10259 30200 10259 10262 30201 10262 10257 30202 10257 10260 30203 10260 10262 30204 10262 10261 30205 10261 10257 30206 10257 10289 30207 10289 10261 30208 10261 10262 30209 10262 10289 30210 10289 10263 30211 10263 10261 30212 10261 10268 30213 10268 10264 30214 10264 10265 30215 10265 10268 30216 10268 10266 30217 10266 10264 30218 10264 10268 30219 10268 10267 30220 10267 10266 30221 10266 10269 30222 10269 10267 30223 10267 10268 30224 10268 10271 30225 10271 10267 30226 10267 10269 30227 10269 10271 30228 10271 10270 30229 10270 10267 30230 10267 10274 30231 10274 10270 30232 10270 10271 30233 10271 10274 30234 10274 10272 30235 10272 10270 30236 10270 10274 30237 10274 10273 30238 10273 10272 30239 10272 10275 30240 10275 10273 30241 10273 10274 30242 10274 10278 30243 10278 10273 30244 10273 10275 30245 10275 10278 30246 10278 10276 30247 10276 10273 30248 10273 10278 30249 10278 10277 30250 10277 10276 30251 10276 10279 30252 10279 10277 30253 10277 10278 30254 10278 10281 30255 10281 10277 30256 10277 10279 30257 10279 10281 30258 10281 10280 30259 10280 10277 30260 10277 10283 30261 10283 10280 30262 10280 10281 30263 10281 10283 30264 10283 10282 30265 10282 10280 30266 10280 10285 30267 10285 10282 30268 10282 10283 30269 10283 10285 30270 10285 10284 30271 10284 10282 30272 10282 10287 30273 10287 10284 30274 10284 10285 30275 10285 10287 30276 10287 10286 30277 10286 10284 30278 10284 10256 30279 10256 10286 30280 10286 10287 30281 10287 10256 30282 10256 10288 30283 10288 10286 30284 10286 10256 30285 10256 10289 30286 10289 10288 30287 10288 10307 30288 10307 10290 30289 10290 10291 30290 10291 10294 30291 10294 10292 30292 10292 10293 30293 10293 10295 30294 10295 10292 30295 10292 10294 30296 10294 10297 30297 10297 10292 30298 10292 10295 30299 10295 10297 30300 10297 10296 30301 10296 10292 30302 10292 10299 30303 10299 10296 30304 10296 10297 30305 10297 10299 30306 10299 10298 30307 10298 10296 30308 10296 10302 30309 10302 10298 30310 10298 10299 30311 10299 10302 30312 10302 10300 30313 10300 10298 30314 10298 10302 30315 10302 10301 30316 10301 10300 30317 10300 10303 30318 10303 10301 30319 10301 10302 30320 10302 10306 30321 10306 10301 30322 10301 10303 30323 10303 10306 30324 10306 10304 30325 10304 10301 30326 10301 10306 30327 10306 10305 30328 10305 10304 30329 10304 10290 30330 10290 10305 30331 10305 10306 30332 10306 10290 30333 10290 10307 30334 10307 10305 30335 10305 10332 30336 10332 10319 30337 10319 10308 30338 10308 10311 30339 10311 10309 30340 10309 10310 30341 10310 10312 30342 10312 10309 30343 10309 10311 30344 10311 10315 30345 10315 10309 30346 10309 10312 30347 10312 10315 30348 10315 10313 30349 10313 10309 30350 10309 10315 30351 10315 10314 30352 10314 10313 30353 10313 10317 30354 10317 10314 30355 10314 10315 30356 10315 10317 30357 10317 10316 30358 10316 10314 30359 10314 10318 30360 10318 10316 30361 10316 10317 30362 10317 10308 30363 10308 10316 30364 10316 10318 30365 10318 10308 30366 10308 10319 30367 10319 10316 30368 10316 10323 30369 10323 10320 30370 10320 10321 30371 10321 10323 30372 10323 10322 30373 10322 10320 30374 10320 10326 30375 10326 10322 30376 10322 10323 30377 10323 10326 30378 10326 10324 30379 10324 10322 30380 10322 10326 30381 10326 10325 30382 10325 10324 30383 10324 10327 30384 10327 10325 30385 10325 10326 30386 10326 10329 30387 10329 10325 30388 10325 10327 30389 10327 10329 30390 10329 10328 30391 10328 10325 30392 10325 10331 30393 10331 10328 30394 10328 10329 30395 10329 10331 30396 10331 10330 30397 10330 10328 30398 10328 10333 30399 10333 10330 30400 10330 10331 30401 10331 10333 30402 10333 10332 30403 10332 10330 30404 10330 10319 30405 10319 10332 30406 10332 10333 30407 10333 10351 30408 10351 10334 30409 10334 10338 30410 10338 10339 30411 10339 10335 30412 10335 10336 30413 10336 10339 30414 10339 10337 30415 10337 10335 30416 10335 10339 30417 10339 10338 30418 10338 10337 30419 10337 10351 30420 10351 10338 30421 10338 10339 30422 10339 10343 30423 10343 10340 30424 10340 10341 30425 10341 10343 30426 10343 10342 30427 10342 10340 30428 10340 10345 30429 10345 10342 30430 10342 10343 30431 10343 10345 30432 10345 10344 30433 10344 10342 30434 10342 10347 30435 10347 10344 30436 10344 10345 30437 10345 10347 30438 10347 10346 30439 10346 10344 30440 10344 10349 30441 10349 10346 30442 10346 10347 30443 10347 10349 30444 10349 10348 30445 10348 10346 30446 10346 10334 30447 10334 10348 30448 10348 10349 30449 10349 10334 30450 10334 10350 30451 10350 10348 30452 10348 10334 30453 10334 10351 30454 10351 10350 30455 10350 10354 30456 10354 10352 30457 10352 10353 30458 10353 10356 30459 10356 10354 30460 10354 10355 30461 10355 10352 30462 10352 10354 30463 10354 10356 30464 10356 10359 30465 10359 10357 30466 10357 10358 30467 10358 10357 30468 10357 10359 30469 10359 10360 30470 10360 10365 30471 10365 10361 30472 10361 10362 30473 10362 10361 30474 10361 10363 30475 10363 10364 30476 10364 10361 30477 10361 10365 30478 10365 10363 30479 10363 10368 30480 10368 10366 30481 10366 10367 30482 10367 10366 30483 10366 10368 30484 10368 10369 30485 10369 10374 30486 10374 10370 30487 10370 10371 30488 10371 10375 30489 10375 10372 30490 10372 10373 30491 10373 10375 30492 10375 10374 30493 10374 10372 30494 10372 10376 30495 10376 10374 30496 10374 10375 30497 10375 10377 30498 10377 10374 30499 10374 10376 30500 10376 10378 30501 10378 10374 30502 10374 10377 30503 10377 10379 30504 10379 10374 30505 10374 10378 30506 10378 10380 30507 10380 10374 30508 10374 10379 30509 10379 10381 30510 10381 10374 30511 10374 10380 30512 10380 10382 30513 10382 10374 30514 10374 10381 30515 10381 10383 30516 10383 10374 30517 10374 10382 30518 10382 10384 30519 10384 10374 30520 10374 10383 30521 10383 10385 30522 10385 10374 30523 10374 10384 30524 10384 10386 30525 10386 10374 30526 10374 10385 30527 10385 10387 30528 10387 10374 30529 10374 10386 30530 10386 10388 30531 10388 10374 30532 10374 10387 30533 10387 10389 30534 10389 10374 30535 10374 10388 30536 10388 10370 30537 10370 10374 30538 10374 10389 30539 10389 10392 30540 10392 10390 30541 10390 10391 30542 10391 10394 30543 10394 10392 30544 10392 10393 30545 10393 10390 30546 10390 10392 30547 10392 10394 30548 10394 10397 30549 10397 10395 30550 10395 10396 30551 10396 10395 30552 10395 10397 30553 10397 10398 30554 10398 10403 30555 10403 10399 30556 10399 10400 30557 10400 10399 30558 10399 10401 30559 10401 10402 30560 10402 10399 30561 10399 10403 30562 10403 10401 30563 10401 10406 30564 10406 10404 30565 10404 10405 30566 10405 10404 30567 10404 10406 30568 10406 10407 30569 10407 10412 30570 10412 10408 30571 10408 10409 30572 10409 10413 30573 10413 10410 30574 10410 10411 30575 10411 10413 30576 10413 10412 30577 10412 10410 30578 10410 10414 30579 10414 10412 30580 10412 10413 30581 10413 10415 30582 10415 10412 30583 10412 10414 30584 10414 10416 30585 10416 10412 30586 10412 10415 30587 10415 10417 30588 10417 10412 30589 10412 10416 30590 10416 10418 30591 10418 10412 30592 10412 10417 30593 10417 10419 30594 10419 10412 30595 10412 10418 30596 10418 10420 30597 10420 10412 30598 10412 10419 30599 10419 10421 30600 10421 10412 30601 10412 10420 30602 10420 10422 30603 10422 10412 30604 10412 10421 30605 10421 10423 30606 10423 10412 30607 10412 10422 30608 10422 10424 30609 10424 10412 30610 10412 10423 30611 10423 10425 30612 10425 10412 30613 10412 10424 30614 10424 10426 30615 10426 10412 30616 10412 10425 30617 10425 10427 30618 10427 10412 30619 10412 10426 30620 10426 10408 30621 10408 10412 30622 10412 10427 30623 10427 10430 30624 10430 10428 30625 10428 10429 30626 10429 10432 30627 10432 10430 30628 10430 10431 30629 10431 10428 30630 10428 10430 30631 10430 10432 30632 10432 10435 30633 10435 10433 30634 10433 10434 30635 10434 10433 30636 10433 10435 30637 10435 10436 30638 10436 10441 30639 10441 10437 30640 10437 10438 30641 10438 10437 30642 10437 10439 30643 10439 10440 30644 10440 10437 30645 10437 10441 30646 10441 10439 30647 10439 10444 30648 10444 10442 30649 10442 10443 30650 10443 10442 30651 10442 10444 30652 10444 10445 30653 10445 10448 30654 10448 10446 30655 10446 10447 30656 10447 10450 30657 10450 10448 30658 10448 10449 30659 10449 10451 30660 10451 10448 30661 10448 10450 30662 10450 10452 30663 10452 10448 30664 10448 10451 30665 10451 10453 30666 10453 10448 30667 10448 10452 30668 10452 10454 30669 10454 10448 30670 10448 10453 30671 10453 10455 30672 10455 10448 30673 10448 10454 30674 10454 10456 30675 10456 10448 30676 10448 10455 30677 10455 10457 30678 10457 10448 30679 10448 10456 30680 10456 10458 30681 10458 10448 30682 10448 10457 30683 10457 10459 30684 10459 10448 30685 10448 10458 30686 10458 10460 30687 10460 10448 30688 10448 10459 30689 10459 10461 30690 10461 10448 30691 10448 10460 30692 10460 10462 30693 10462 10448 30694 10448 10461 30695 10461 10463 30696 10463 10448 30697 10448 10462 30698 10462 10464 30699 10464 10448 30700 10448 10463 30701 10463 10465 30702 10465 10448 30703 10448 10464 30704 10464 10446 30705 10446 10448 30706 10448 10465 30707 10465 10482 30708 10482 10466 30709 10466 10467 30710 10467 10471 30711 10471 10468 30712 10468 10469 30713 10469 10471 30714 10471 10470 30715 10470 10468 30716 10468 10473 30717 10473 10470 30718 10470 10471 30719 10471 10473 30720 10473 10472 30721 10472 10470 30722 10470 10474 30723 10474 10472 30724 10472 10473 30725 10473 10475 30726 10475 10472 30727 10472 10474 30728 10474 10476 30729 10476 10472 30730 10472 10475 30731 10475 10477 30732 10477 10472 30733 10472 10476 30734 10476 10478 30735 10478 10472 30736 10472 10477 30737 10477 10466 30738 10466 10472 30739 10472 10478 30740 10478 10466 30741 10466 10479 30742 10479 10472 30743 10472 10466 30744 10466 10480 30745 10480 10479 30746 10479 10466 30747 10466 10481 30748 10481 10480 30749 10480 10466 30750 10466 10482 30751 10482 10481 30752 10481 10500 30753 10500 10483 30754 10483 10484 30755 10484 10489 30756 10489 10485 30757 10485 10486 30758 10486 10489 30759 10489 10487 30760 10487 10485 30761 10485 10489 30762 10489 10488 30763 10488 10487 30764 10487 10490 30765 10490 10488 30766 10488 10489 30767 10489 10491 30768 10491 10488 30769 10488 10490 30770 10490 10492 30771 10492 10488 30772 10488 10491 30773 10491 10493 30774 10493 10488 30775 10488 10492 30776 10492 10494 30777 10494 10488 30778 10488 10493 30779 10493 10495 30780 10495 10488 30781 10488 10494 30782 10494 10496 30783 10496 10488 30784 10488 10495 30785 10495 10483 30786 10483 10488 30787 10488 10496 30788 10496 10483 30789 10483 10497 30790 10497 10488 30791 10488 10483 30792 10483 10498 30793 10498 10497 30794 10497 10483 30795 10483 10499 30796 10499 10498 30797 10498 10483 30798 10483 10500 30799 10500 10499 30800 10499 10517 30801 10517 10501 30802 10501 10502 30803 10502 10505 30804 10505 10503 30805 10503 10504 30806 10504 10506 30807 10506 10503 30808 10503 10505 30809 10505 10507 30810 10507 10503 30811 10503 10506 30812 10506 10509 30813 10509 10503 30814 10503 10507 30815 10507 10509 30816 10509 10508 30817 10508 10503 30818 10503 10510 30819 10510 10508 30820 10508 10509 30821 10509 10511 30822 10511 10508 30823 10508 10510 30824 10510 10512 30825 10512 10508 30826 10508 10511 30827 10511 10513 30828 10513 10508 30829 10508 10512 30830 10512 10501 30831 10501 10508 30832 10508 10513 30833 10513 10501 30834 10501 10514 30835 10514 10508 30836 10508 10501 30837 10501 10515 30838 10515 10514 30839 10514 10501 30840 10501 10516 30841 10516 10515 30842 10515 10501 30843 10501 10517 30844 10517 10516 30845 10516 10537 30846 10537 10518 30847 10518 10519 30848 10519 10523 30849 10523 10520 30850 10520 10521 30851 10521 10523 30852 10523 10522 30853 10522 10520 30854 10520 10525 30855 10525 10522 30856 10522 10523 30857 10523 10525 30858 10525 10524 30859 10524 10522 30860 10522 10527 30861 10527 10524 30862 10524 10525 30863 10525 10527 30864 10527 10526 30865 10526 10524 30866 10524 10529 30867 10529 10526 30868 10526 10527 30869 10527 10529 30870 10529 10528 30871 10528 10526 30872 10526 10530 30873 10530 10528 30874 10528 10529 30875 10529 10532 30876 10532 10528 30877 10528 10530 30878 10530 10532 30879 10532 10531 30880 10531 10528 30881 10528 10534 30882 10534 10531 30883 10531 10532 30884 10532 10534 30885 10534 10533 30886 10533 10531 30887 10531 10536 30888 10536 10533 30889 10533 10534 30890 10534 10536 30891 10536 10535 30892 10535 10533 30893 10533 10518 30894 10518 10535 30895 10535 10536 30896 10536 10518 30897 10518 10537 30898 10537 10535 30899 10535 10556 30900 10556 10538 30901 10538 10539 30902 10539 10542 30903 10542 10540 30904 10540 10541 30905 10541 10544 30906 10544 10540 30907 10540 10542 30908 10542 10544 30909 10544 10543 30910 10543 10540 30911 10540 10546 30912 10546 10543 30913 10543 10544 30914 10544 10546 30915 10546 10545 30916 10545 10543 30917 10543 10548 30918 10548 10545 30919 10545 10546 30920 10546 10548 30921 10548 10547 30922 10547 10545 30923 10545 10551 30924 10551 10547 30925 10547 10548 30926 10548 10551 30927 10551 10549 30928 10549 10547 30929 10547 10551 30930 10551 10550 30931 10550 10549 30932 10549 10553 30933 10553 10550 30934 10550 10551 30935 10551 10553 30936 10553 10552 30937 10552 10550 30938 10550 10555 30939 10555 10552 30940 10552 10553 30941 10553 10555 30942 10555 10554 30943 10554 10552 30944 10552 10557 30945 10557 10554 30946 10554 10555 30947 10555 10557 30948 10557 10556 30949 10556 10554 30950 10554 10538 30951 10538 10556 30952 10556 10557 30953 10557 10575 30954 10575 10558 30955 10558 10559 30956 10559 10562 30957 10562 10560 30958 10560 10561 30959 10561 10563 30960 10563 10560 30961 10560 10562 30962 10562 10565 30963 10565 10560 30964 10560 10563 30965 10563 10565 30966 10565 10564 30967 10564 10560 30968 10560 10568 30969 10568 10564 30970 10564 10565 30971 10565 10568 30972 10568 10566 30973 10566 10564 30974 10564 10568 30975 10568 10567 30976 10567 10566 30977 10566 10569 30978 10569 10567 30979 10567 10568 30980 10568 10572 30981 10572 10567 30982 10567 10569 30983 10569 10572 30984 10572 10570 30985 10570 10567 30986 10567 10572 30987 10572 10571 30988 10571 10570 30989 10570 10574 30990 10574 10571 30991 10571 10572 30992 10572 10574 30993 10574 10573 30994 10573 10571 30995 10571 10558 30996 10558 10573 30997 10573 10574 30998 10574 10558 30999 10558 10575 31000 10575 10573 31001 10573 10592 31002 10592 10576 31003 10576 10577 31004 10577 10580 31005 10580 10578 31006 10578 10579 31007 10579 10581 31008 10581 10578 31009 10578 10580 31010 10580 10584 31011 10584 10578 31012 10578 10581 31013 10581 10584 31014 10584 10582 31015 10582 10578 31016 10578 10584 31017 10584 10583 31018 10583 10582 31019 10582 10585 31020 10585 10583 31021 10583 10584 31022 10584 10588 31023 10588 10583 31024 10583 10585 31025 10585 10588 31026 10588 10586 31027 10586 10583 31028 10583 10588 31029 10588 10587 31030 10587 10586 31031 10586 10589 31032 10589 10587 31033 10587 10588 31034 10588 10591 31035 10591 10587 31036 10587 10589 31037 10589 10591 31038 10591 10590 31039 10590 10587 31040 10587 10593 31041 10593 10590 31042 10590 10591 31043 10591 10593 31044 10593 10592 31045 10592 10590 31046 10590 10576 31047 10576 10592 31048 10592 10593 31049 10593 10613 31050 10613 10594 31051 10594 10595 31052 10595 10599 31053 10599 10596 31054 10596 10597 31055 10597 10599 31056 10599 10598 31057 10598 10596 31058 10596 10601 31059 10601 10598 31060 10598 10599 31061 10599 10601 31062 10601 10600 31063 10600 10598 31064 10598 10603 31065 10603 10600 31066 10600 10601 31067 10601 10603 31068 10603 10602 31069 10602 10600 31070 10600 10605 31071 10605 10602 31072 10602 10603 31073 10603 10605 31074 10605 10604 31075 10604 10602 31076 10602 10606 31077 10606 10604 31078 10604 10605 31079 10605 10608 31080 10608 10604 31081 10604 10606 31082 10606 10608 31083 10608 10607 31084 10607 10604 31085 10604 10610 31086 10610 10607 31087 10607 10608 31088 10608 10610 31089 10610 10609 31090 10609 10607 31091 10607 10612 31092 10612 10609 31093 10609 10610 31094 10610 10612 31095 10612 10611 31096 10611 10609 31097 10609 10594 31098 10594 10611 31099 10611 10612 31100 10612 10594 31101 10594 10613 31102 10613 10611 31103 10611 10623 31104 10623 10614 31105 10614 10615 31106 10615 10618 31107 10618 10616 31108 10616 10617 31109 10617 10619 31110 10619 10616 31111 10616 10618 31112 10618 10622 31113 10622 10616 31114 10616 10619 31115 10619 10622 31116 10622 10620 31117 10620 10616 31118 10616 10622 31119 10622 10621 31120 10621 10620 31121 10620 10614 31122 10614 10621 31123 10621 10622 31124 10622 10614 31125 10614 10623 31126 10623 10621 31127 10621 10640 31128 10640 10624 31129 10624 10625 31130 10625 10628 31131 10628 10626 31132 10626 10627 31133 10627 10629 31134 10629 10626 31135 10626 10628 31136 10628 10631 31137 10631 10626 31138 10626 10629 31139 10629 10631 31140 10631 10630 31141 10630 10626 31142 10626 10634 31143 10634 10630 31144 10630 10631 31145 10631 10634 31146 10634 10632 31147 10632 10630 31148 10630 10634 31149 10634 10633 31150 10633 10632 31151 10632 10636 31152 10636 10633 31153 10633 10634 31154 10634 10636 31155 10636 10635 31156 10635 10633 31157 10633 10637 31158 10637 10635 31159 10635 10636 31160 10636 10639 31161 10639 10635 31162 10635 10637 31163 10637 10639 31164 10639 10638 31165 10638 10635 31166 10635 10641 31167 10641 10638 31168 10638 10639 31169 10639 10641 31170 10641 10640 31171 10640 10638 31172 10638 10624 31173 10624 10640 31174 10640 10641 31175 10641 10659 31176 10659 10642 31177 10642 10650 31178 10650 10647 31179 10647 10643 31180 10643 10644 31181 10644 10647 31182 10647 10645 31183 10645 10643 31184 10643 10647 31185 10647 10646 31186 10646 10645 31187 10645 10649 31188 10649 10646 31189 10646 10647 31190 10647 10649 31191 10649 10648 31192 10648 10646 31193 10646 10651 31194 10651 10648 31195 10648 10649 31196 10649 10651 31197 10651 10650 31198 10650 10648 31199 10648 10659 31200 10659 10650 31201 10650 10651 31202 10651 10655 31203 10655 10652 31204 10652 10653 31205 10653 10655 31206 10655 10654 31207 10654 10652 31208 10652 10658 31209 10658 10654 31210 10654 10655 31211 10655 10658 31212 10658 10656 31213 10656 10654 31214 10654 10658 31215 10658 10657 31216 10657 10656 31217 10656 10642 31218 10642 10657 31219 10657 10658 31220 10658 10642 31221 10642 10659 31222 10659 10657 31223 10657 10675 31224 10675 10660 31225 10660 10668 31226 10668 10665 31227 10665 10661 31228 10661 10662 31229 10662 10665 31230 10665 10663 31231 10663 10661 31232 10661 10665 31233 10665 10664 31234 10664 10663 31235 10663 10667 31236 10667 10664 31237 10664 10665 31238 10665 10667 31239 10667 10666 31240 10666 10664 31241 10664 10675 31242 10675 10666 31243 10666 10667 31244 10667 10675 31245 10675 10668 31246 10668 10666 31247 10666 10672 31248 10672 10669 31249 10669 10670 31250 10670 10672 31251 10672 10671 31252 10671 10669 31253 10669 10674 31254 10674 10671 31255 10671 10672 31256 10672 10674 31257 10674 10673 31258 10673 10671 31259 10671 10660 31260 10660 10673 31261 10673 10674 31262 10674 10660 31263 10660 10675 31264 10675 10673 31265 10673 10694 31266 10694 10676 31267 10676 10677 31268 10677 10680 31269 10680 10678 31270 10678 10679 31271 10679 10682 31272 10682 10678 31273 10678 10680 31274 10680 10682 31275 10682 10681 31276 10681 10678 31277 10678 10684 31278 10684 10681 31279 10681 10682 31280 10682 10684 31281 10684 10683 31282 10683 10681 31283 10681 10686 31284 10686 10683 31285 10683 10684 31286 10684 10686 31287 10686 10685 31288 10685 10683 31289 10683 10689 31290 10689 10685 31291 10685 10686 31292 10686 10689 31293 10689 10687 31294 10687 10685 31295 10685 10689 31296 10689 10688 31297 10688 10687 31298 10687 10691 31299 10691 10688 31300 10688 10689 31301 10689 10691 31302 10691 10690 31303 10690 10688 31304 10688 10693 31305 10693 10690 31306 10690 10691 31307 10691 10693 31308 10693 10692 31309 10692 10690 31310 10690 10695 31311 10695 10692 31312 10692 10693 31313 10693 10695 31314 10695 10694 31315 10694 10692 31316 10692 10676 31317 10676 10694 31318 10694 10695 31319 10695 10713 31320 10713 10696 31321 10696 10697 31322 10697 10701 31323 10701 10698 31324 10698 10699 31325 10699 10701 31326 10701 10700 31327 10700 10698 31328 10698 10704 31329 10704 10700 31330 10700 10701 31331 10701 10704 31332 10704 10702 31333 10702 10700 31334 10700 10704 31335 10704 10703 31336 10703 10702 31337 10702 10705 31338 10705 10703 31339 10703 10704 31340 10704 10707 31341 10707 10703 31342 10703 10705 31343 10705 10707 31344 10707 10706 31345 10706 10703 31346 10703 10709 31347 10709 10706 31348 10706 10707 31349 10707 10709 31350 10709 10708 31351 10708 10706 31352 10706 10712 31353 10712 10708 31354 10708 10709 31355 10709 10712 31356 10712 10710 31357 10710 10708 31358 10708 10712 31359 10712 10711 31360 10711 10710 31361 10710 10696 31362 10696 10711 31363 10711 10712 31364 10712 10696 31365 10696 10713 31366 10713 10711 31367 10711 10730 31368 10730 10718 31369 10718 10714 31370 10714 10717 31371 10717 10715 31372 10715 10716 31373 10716 10719 31374 10719 10715 31375 10715 10717 31376 10717 10719 31377 10719 10718 31378 10718 10715 31379 10715 10714 31380 10714 10718 31381 10718 10719 31382 10719 10724 31383 10724 10720 31384 10720 10721 31385 10721 10724 31386 10724 10722 31387 10722 10720 31388 10720 10724 31389 10724 10723 31390 10723 10722 31391 10722 10726 31392 10726 10723 31393 10723 10724 31394 10724 10726 31395 10726 10725 31396 10725 10723 31397 10723 10727 31398 10727 10725 31399 10725 10726 31400 10726 10729 31401 10729 10725 31402 10725 10727 31403 10727 10729 31404 10729 10728 31405 10728 10725 31406 10725 10731 31407 10731 10728 31408 10728 10729 31409 10729 10731 31410 10731 10730 31411 10730 10728 31412 10728 10718 31413 10718 10730 31414 10730 10731 31415 10731 10795 31416 10795 10732 31417 10732 10734 31418 10734 10734 31419 10734 10733 31420 10733 10795 31421 10795 10736 31422 10736 10733 31423 10733 10734 31424 10734 10736 31425 10736 10735 31426 10735 10733 31427 10733 10738 31428 10738 10735 31429 10735 10736 31430 10736 10738 31431 10738 10737 31432 10737 10735 31433 10735 10740 31434 10740 10737 31435 10737 10738 31436 10738 10740 31437 10740 10739 31438 10739 10737 31439 10737 10742 31440 10742 10739 31441 10739 10740 31442 10740 10742 31443 10742 10741 31444 10741 10739 31445 10739 10744 31446 10744 10741 31447 10741 10742 31448 10742 10744 31449 10744 10743 31450 10743 10741 31451 10741 10746 31452 10746 10743 31453 10743 10744 31454 10744 10746 31455 10746 10745 31456 10745 10743 31457 10743 10748 31458 10748 10745 31459 10745 10746 31460 10746 10748 31461 10748 10747 31462 10747 10745 31463 10745 10750 31464 10750 10747 31465 10747 10748 31466 10748 10750 31467 10750 10749 31468 10749 10747 31469 10747 10752 31470 10752 10749 31471 10749 10750 31472 10750 10752 31473 10752 10751 31474 10751 10749 31475 10749 10754 31476 10754 10751 31477 10751 10752 31478 10752 10754 31479 10754 10753 31480 10753 10751 31481 10751 10756 31482 10756 10753 31483 10753 10754 31484 10754 10756 31485 10756 10755 31486 10755 10753 31487 10753 10758 31488 10758 10755 31489 10755 10756 31490 10756 10758 31491 10758 10757 31492 10757 10755 31493 10755 10760 31494 10760 10757 31495 10757 10758 31496 10758 10760 31497 10760 10759 31498 10759 10757 31499 10757 10762 31500 10762 10759 31501 10759 10760 31502 10760 10762 31503 10762 10761 31504 10761 10759 31505 10759 10764 31506 10764 10761 31507 10761 10762 31508 10762 10764 31509 10764 10763 31510 10763 10761 31511 10761 10766 31512 10766 10763 31513 10763 10764 31514 10764 10766 31515 10766 10765 31516 10765 10763 31517 10763 10768 31518 10768 10765 31519 10765 10766 31520 10766 10768 31521 10768 10767 31522 10767 10765 31523 10765 10770 31524 10770 10767 31525 10767 10768 31526 10768 10770 31527 10770 10769 31528 10769 10767 31529 10767 10772 31530 10772 10769 31531 10769 10770 31532 10770 10772 31533 10772 10771 31534 10771 10769 31535 10769 10774 31536 10774 10771 31537 10771 10772 31538 10772 10774 31539 10774 10773 31540 10773 10771 31541 10771 10776 31542 10776 10773 31543 10773 10774 31544 10774 10776 31545 10776 10775 31546 10775 10773 31547 10773 10778 31548 10778 10775 31549 10775 10776 31550 10776 10778 31551 10778 10777 31552 10777 10775 31553 10775 10780 31554 10780 10777 31555 10777 10778 31556 10778 10780 31557 10780 10779 31558 10779 10777 31559 10777 10782 31560 10782 10779 31561 10779 10780 31562 10780 10782 31563 10782 10781 31564 10781 10779 31565 10779 10784 31566 10784 10781 31567 10781 10782 31568 10782 10784 31569 10784 10783 31570 10783 10781 31571 10781 10786 31572 10786 10783 31573 10783 10784 31574 10784 10786 31575 10786 10785 31576 10785 10783 31577 10783 10788 31578 10788 10785 31579 10785 10786 31580 10786 10788 31581 10788 10787 31582 10787 10785 31583 10785 10790 31584 10790 10787 31585 10787 10788 31586 10788 10790 31587 10790 10789 31588 10789 10787 31589 10787 10792 31590 10792 10789 31591 10789 10790 31592 10790 10792 31593 10792 10791 31594 10791 10789 31595 10789 10794 31596 10794 10791 31597 10791 10792 31598 10792 10794 31599 10794 10793 31600 10793 10791 31601 10791 10732 31602 10732 10793 31603 10793 10794 31604 10794 10732 31605 10732 10795 31606 10795 10793 31607 10793 10828 31608 10828 10796 31609 10796 10797 31610 10797 10801 31611 10801 10798 31612 10798 10799 31613 10799 10801 31614 10801 10800 31615 10800 10798 31616 10798 10803 31617 10803 10800 31618 10800 10801 31619 10801 10803 31620 10803 10802 31621 10802 10800 31622 10800 10806 31623 10806 10802 31624 10802 10803 31625 10803 10806 31626 10806 10804 31627 10804 10802 31628 10802 10806 31629 10806 10805 31630 10805 10804 31631 10804 10807 31632 10807 10805 31633 10805 10806 31634 10806 10809 31635 10809 10805 31636 10805 10807 31637 10807 10809 31638 10809 10808 31639 10808 10805 31640 10805 10811 31641 10811 10808 31642 10808 10809 31643 10809 10811 31644 10811 10810 31645 10810 10808 31646 10808 10813 31647 10813 10810 31648 10810 10811 31649 10811 10813 31650 10813 10812 31651 10812 10810 31652 10810 10815 31653 10815 10812 31654 10812 10813 31655 10813 10815 31656 10815 10814 31657 10814 10812 31658 10812 10817 31659 10817 10814 31660 10814 10815 31661 10815 10817 31662 10817 10816 31663 10816 10814 31664 10814 10819 31665 10819 10816 31666 10816 10817 31667 10817 10819 31668 10819 10818 31669 10818 10816 31670 10816 10821 31671 10821 10818 31672 10818 10819 31673 10819 10821 31674 10821 10820 31675 10820 10818 31676 10818 10823 31677 10823 10820 31678 10820 10821 31679 10821 10823 31680 10823 10822 31681 10822 10820 31682 10820 10825 31683 10825 10822 31684 10822 10823 31685 10823 10825 31686 10825 10824 31687 10824 10822 31688 10822 10827 31689 10827 10824 31690 10824 10825 31691 10825 10827 31692 10827 10826 31693 10826 10824 31694 10824 10829 31695 10829 10826 31696 10826 10827 31697 10827 10829 31698 10829 10828 31699 10828 10826 31700 10826 10796 31701 10796 10828 31702 10828 10829 31703 10829 10832 31704 10832 10830 31705 10830 10831 31706 10831 10830 31707 10830 10832 31708 10832 10833 31709 10833 10836 31710 10836 10834 31711 10834 10835 31712 10835 10834 31713 10834 10836 31714 10836 10837 31715 10837 10840 31716 10840 10838 31717 10838 10839 31718 10839 10838 31719 10838 10840 31720 10840 10841 31721 10841 10844 31722 10844 10842 31723 10842 10843 31724 10843 10842 31725 10842 10844 31726 10844 10845 31727 10845 10848 31728 10848 10846 31729 10846 10847 31730 10847 10846 31731 10846 10848 31732 10848 10849 31733 10849 10852 31734 10852 10850 31735 10850 10851 31736 10851 10850 31737 10850 10852 31738 10852 10853 31739 10853 10856 31740 10856 10854 31741 10854 10855 31742 10855 10854 31743 10854 10856 31744 10856 10857 31745 10857 10860 31746 10860 10858 31747 10858 10859 31748 10859 10858 31749 10858 10860 31750 10860 10861 31751 10861 10864 31752 10864 10862 31753 10862 10863 31754 10863 10862 31755 10862 10864 31756 10864 10865 31757 10865 10868 31758 10868 10866 31759 10866 10867 31760 10867 10866 31761 10866 10868 31762 10868 10869 31763 10869 10872 31764 10872 10870 31765 10870 10871 31766 10871 10870 31767 10870 10872 31768 10872 10873 31769 10873 10876 31770 10876 10874 31771 10874 10875 31772 10875 10874 31773 10874 10876 31774 10876 10877 31775 10877 10880 31776 10880 10878 31777 10878 10879 31778 10879 10878 31779 10878 10880 31780 10880 10881 31781 10881 10884 31782 10884 10882 31783 10882 10883 31784 10883 10882 31785 10882 10884 31786 10884 10885 31787 10885 10888 31788 10888 10886 31789 10886 10887 31790 10887 10886 31791 10886 10888 31792 10888 10889 31793 10889 10892 31794 10892 10890 31795 10890 10891 31796 10891 10890 31797 10890 10892 31798 10892 10893 31799 10893 10896 31800 10896 10894 31801 10894 10895 31802 10895 10894 31803 10894 10896 31804 10896 10897 31805 10897 10900 31806 10900 10898 31807 10898 10899 31808 10899 10898 31809 10898 10900 31810 10900 10901 31811 10901 10904 31812 10904 10902 31813 10902 10903 31814 10903 10902 31815 10902 10904 31816 10904 10905 31817 10905 10918 31818 10918 10906 31819 10906 10907 31820 10907 10906 31821 10906 10908 31822 10908 10909 31823 10909 10906 31824 10906 10910 31825 10910 10908 31826 10908 10906 31827 10906 10911 31828 10911 10910 31829 10910 10906 31830 10906 10912 31831 10912 10911 31832 10911 10906 31833 10906 10913 31834 10913 10912 31835 10912 10906 31836 10906 10914 31837 10914 10913 31838 10913 10906 31839 10906 10915 31840 10915 10914 31841 10914 10906 31842 10906 10916 31843 10916 10915 31844 10915 10906 31845 10906 10917 31846 10917 10916 31847 10916 10906 31848 10906 10918 31849 10918 10917 31850 10917 10923 31851 10923 10919 31852 10919 10920 31853 10920 10924 31854 10924 10921 31855 10921 10922 31856 10922 10924 31857 10924 10923 31858 10923 10921 31859 10921 10919 31860 10919 10923 31861 10923 10924 31862 10924 10927 31863 10927 10925 31864 10925 10926 31865 10926 10931 31866 10931 10927 31867 10927 10928 31868 10928 10934 31869 10934 10929 31870 10929 10930 31871 10930 10933 31872 10933 10931 31873 10931 10932 31874 10932 10929 31875 10929 10931 31876 10931 10933 31877 10933 10929 31878 10929 10927 31879 10927 10931 31880 10931 10934 31881 10934 10927 31882 10927 10929 31883 10929 10935 31884 10935 10927 31885 10927 10934 31886 10934 10936 31887 10936 10927 31888 10927 10935 31889 10935 10937 31890 10937 10927 31891 10927 10936 31892 10936 10938 31893 10938 10927 31894 10927 10937 31895 10937 10939 31896 10939 10927 31897 10927 10938 31898 10938 10925 31899 10925 10927 31900 10927 10939 31901 10939 10940 31902 10940 10941 31903 10941 10942 31904 10942 10945 31905 10945 10943 31906 10943 10944 31907 10944 10943 31908 10943 10945 31909 10945 10946 31910 10946 10949 31911 10949 10947 31912 10947 10948 31913 10948 10947 31914 10947 10949 31915 10949 10950 31916 10950 10951 31917 10951 10952 31918 10952 10953 31919 10953 10956 31920 10956 10954 31921 10954 10955 31922 10955 10960 31923 10960 10956 31924 10956 10957 31925 10957 10961 31926 10961 10958 31927 10958 10959 31928 10959 10961 31929 10961 10960 31930 10960 10958 31931 10958 10961 31932 10961 10956 31933 10956 10960 31934 10960 10962 31935 10962 10956 31936 10956 10961 31937 10961 10963 31938 10963 10956 31939 10956 10962 31940 10962 10964 31941 10964 10956 31942 10956 10963 31943 10963 10965 31944 10965 10956 31945 10956 10964 31946 10964 10966 31947 10966 10956 31948 10956 10965 31949 10965 10954 31950 10954 10956 31951 10956 10966 31952 10966 10972 31953 10972 10967 31954 10967 10968 31955 10968 10971 31956 10971 10969 31957 10969 10970 31958 10970 10967 31959 10967 10969 31960 10969 10971 31961 10971 10967 31962 10967 10972 31963 10972 10969 31964 10969 10975 31965 10975 10973 31966 10973 10974 31967 10974 10981 31968 10981 10975 31969 10975 10976 31970 10976 10982 31971 10982 10977 31972 10977 10978 31973 10978 10977 31974 10977 10979 31975 10979 10980 31976 10980 10977 31977 10977 10981 31978 10981 10979 31979 10979 10982 31980 10982 10981 31981 10981 10977 31982 10977 10982 31983 10982 10975 31984 10975 10981 31985 10981 10983 31986 10983 10975 31987 10975 10982 31988 10982 10984 31989 10984 10975 31990 10975 10983 31991 10983 10985 31992 10985 10975 31993 10975 10984 31994 10984 10986 31995 10986 10975 31996 10975 10985 31997 10985 10987 31998 10987 10975 31999 10975 10986 32000 10986 10973 32001 10973 10975 32002 10975 10987 32003 10987 10990 32004 10990 10988 32005 10988 10989 32006 10989 10988 32007 10988 10990 32008 10990 10991 32009 10991 10994 32010 10994 10992 32011 10992 10993 32012 10993 10992 32013 10992 10994 32014 10994 10995 32015 10995 10998 32016 10998 10996 32017 10996 10997 32018 10997 10996 32019 10996 10998 32020 10998 10999 32021 10999 11002 32022 11002 11000 32023 11000 11001 32024 11001 11004 32025 11004 11002 32026 11002 11003 32027 11003 11000 32028 11000 11002 32029 11002 11004 32030 11004 11007 32031 11007 11005 32032 11005 11006 32033 11006 11005 32034 11005 11007 32035 11007 11008 32036 11008 11011 32037 11011 11009 32038 11009 11010 32039 11010 11009 32040 11009 11011 32041 11011 11012 32042 11012 11015 32043 11015 11013 32044 11013 11014 32045 11014 11013 32046 11013 11015 32047 11015 11016 32048 11016 11019 32049 11019 11017 32050 11017 11018 32051 11018 11017 32052 11017 11019 32053 11019 11020 32054 11020 11023 32055 11023 11021 32056 11021 11022 32057 11022 11021 32058 11021 11023 32059 11023 11024 32060 11024 11031 32061 11031 11025 32062 11025 11026 32063 11026 11029 32064 11029 11027 32065 11027 11028 32066 11028 11032 32067 11032 11027 32068 11027 11029 32069 11029 11032 32070 11032 11030 32071 11030 11027 32072 11027 11032 32073 11032 11031 32074 11031 11030 32075 11030 11025 32076 11025 11031 32077 11031 11032 32078 11032 11037 32079 11037 11033 32080 11033 11034 32081 11034 11038 32082 11038 11035 32083 11035 11036 32084 11036 11038 32085 11038 11037 32086 11037 11035 32087 11035 11039 32088 11039 11037 32089 11037 11038 32090 11038 11040 32091 11040 11037 32092 11037 11039 32093 11039 11033 32094 11033 11037 32095 11037 11040 32096 11040 11047 32097 11047 11041 32098 11041 11042 32099 11042 11045 32100 11045 11043 32101 11043 11044 32102 11044 11048 32103 11048 11043 32104 11043 11045 32105 11045 11048 32106 11048 11046 32107 11046 11043 32108 11043 11048 32109 11048 11047 32110 11047 11046 32111 11046 11041 32112 11041 11047 32113 11047 11048 32114 11048 11053 32115 11053 11049 32116 11049 11050 32117 11050 11054 32118 11054 11051 32119 11051 11052 32120 11052 11054 32121 11054 11053 32122 11053 11051 32123 11051 11055 32124 11055 11053 32125 11053 11054 32126 11054 11056 32127 11056 11053 32128 11053 11055 32129 11055 11049 32130 11049 11053 32131 11053 11056 32132 11056 11059 32133 11059 11057 32134 11057 11058 32135 11058 11057 32136 11057 11059 32137 11059 11060 32138 11060 11063 32139 11063 11061 32140 11061 11062 32141 11062 11061 32142 11061 11063 32143 11063 11064 32144 11064 11067 32145 11067 11065 32146 11065 11066 32147 11066 11065 32148 11065 11067 32149 11067 11068 32150 11068 11071 32151 11071 11069 32152 11069 11070 32153 11070 11069 32154 11069 11071 32155 11071 11072 32156 11072 11075 32157 11075 11073 32158 11073 11074 32159 11074 11073 32160 11073 11075 32161 11075 11076 32162 11076 11079 32163 11079 11077 32164 11077 11078 32165 11078 11077 32166 11077 11079 32167 11079 11080 32168 11080 11087 32169 11087 11081 32170 11081 11082 32171 11082 11085 32172 11085 11083 32173 11083 11084 32174 11084 11088 32175 11088 11083 32176 11083 11085 32177 11085 11088 32178 11088 11086 32179 11086 11083 32180 11083 11088 32181 11088 11087 32182 11087 11086 32183 11086 11081 32184 11081 11087 32185 11087 11088 32186 11088 11096 32187 11096 11089 32188 11089 11090 32189 11090 11094 32190 11094 11091 32191 11091 11092 32192 11092 11094 32193 11094 11093 32194 11093 11091 32195 11091 11095 32196 11095 11093 32197 11093 11094 32198 11094 11089 32199 11089 11093 32200 11093 11095 32201 11095 11089 32202 11089 11096 32203 11096 11093 32204 11093 11103 32205 11103 11097 32206 11097 11098 32207 11098 11101 32208 11101 11099 32209 11099 11100 32210 11100 11104 32211 11104 11099 32212 11099 11101 32213 11101 11104 32214 11104 11102 32215 11102 11099 32216 11099 11104 32217 11104 11103 32218 11103 11102 32219 11102 11097 32220 11097 11103 32221 11103 11104 32222 11104 11112 32223 11112 11105 32224 11105 11106 32225 11106 11110 32226 11110 11107 32227 11107 11108 32228 11108 11110 32229 11110 11109 32230 11109 11107 32231 11107 11111 32232 11111 11109 32233 11109 11110 32234 11110 11105 32235 11105 11109 32236 11109 11111 32237 11111 11105 32238 11105 11112 32239 11112 11109 32240 11109 11115 32241 11115 11113 32242 11113 11114 32243 11114 11113 32244 11113 11115 32245 11115 11116 32246 11116 11119 32247 11119 11117 32248 11117 11118 32249 11118 11117 32250 11117 11119 32251 11119 11120 32252 11120 11123 32253 11123 11121 32254 11121 11122 32255 11122 11121 32256 11121 11123 32257 11123 11124 32258 11124 11127 32259 11127 11125 32260 11125 11126 32261 11126 11125 32262 11125 11127 32263 11127 11128 32264 11128 11131 32265 11131 11129 32266 11129 11130 32267 11130 11129 32268 11129 11131 32269 11131 11132 32270 11132 11135 32271 11135 11133 32272 11133 11134 32273 11134 11133 32274 11133 11135 32275 11135 11136 32276 11136 11141 32277 11141 11137 32278 11137 11138 32279 11138 11142 32280 11142 11139 32281 11139 11140 32282 11140 11142 32283 11142 11141 32284 11141 11139 32285 11139 11143 32286 11143 11141 32287 11141 11142 32288 11142 11144 32289 11144 11141 32290 11141 11143 32291 11143 11137 32292 11137 11141 32293 11141 11144 32294 11144 11151 32295 11151 11145 32296 11145 11146 32297 11146 11149 32298 11149 11147 32299 11147 11148 32300 11148 11152 32301 11152 11147 32302 11147 11149 32303 11149 11152 32304 11152 11150 32305 11150 11147 32306 11147 11152 32307 11152 11151 32308 11151 11150 32309 11150 11145 32310 11145 11151 32311 11151 11152 32312 11152 11157 32313 11157 11153 32314 11153 11154 32315 11154 11158 32316 11158 11155 32317 11155 11156 32318 11156 11158 32319 11158 11157 32320 11157 11155 32321 11155 11159 32322 11159 11157 32323 11157 11158 32324 11158 11160 32325 11160 11157 32326 11157 11159 32327 11159 11153 32328 11153 11157 32329 11157 11160 32330 11160 11167 32331 11167 11161 32332 11161 11162 32333 11162 11165 32334 11165 11163 32335 11163 11164 32336 11164 11168 32337 11168 11163 32338 11163 11165 32339 11165 11168 32340 11168 11166 32341 11166 11163 32342 11163 11168 32343 11168 11167 32344 11167 11166 32345 11166 11161 32346 11161 11167 32347 11167 11168 32348 11168 11173 32349 11173 11169 32350 11169 11170 32351 11170 11174 32352 11174 11171 32353 11171 11172 32354 11172 11174 32355 11174 11173 32356 11173 11171 32357 11171 11175 32358 11175 11173 32359 11173 11174 32360 11174 11176 32361 11176 11173 32362 11173 11175 32363 11175 11169 32364 11169 11173 32365 11173 11176 32366 11176 11183 32367 11183 11177 32368 11177 11178 32369 11178 11181 32370 11181 11179 32371 11179 11180 32372 11180 11184 32373 11184 11179 32374 11179 11181 32375 11181 11184 32376 11184 11182 32377 11182 11179 32378 11179 11184 32379 11184 11183 32380 11183 11182 32381 11182 11177 32382 11177 11183 32383 11183 11184 32384 11184 11189 32385 11189 11185 32386 11185 11186 32387 11186 11190 32388 11190 11187 32389 11187 11188 32390 11188 11190 32391 11190 11189 32392 11189 11187 32393 11187 11191 32394 11191 11189 32395 11189 11190 32396 11190 11192 32397 11192 11189 32398 11189 11191 32399 11191 11185 32400 11185 11189 32401 11189 11192 32402 11192 11199 32403 11199 11193 32404 11193 11194 32405 11194 11197 32406 11197 11195 32407 11195 11196 32408 11196 11200 32409 11200 11195 32410 11195 11197 32411 11197 11200 32412 11200 11198 32413 11198 11195 32414 11195 11200 32415 11200 11199 32416 11199 11198 32417 11198 11193 32418 11193 11199 32419 11199 11200 32420 11200 11203 32421 11203 11201 32422 11201 11202 32423 11202 11201 32424 11201 11203 32425 11203 11204 32426 11204 11207 32427 11207 11205 32428 11205 11206 32429 11206 11205 32430 11205 11207 32431 11207 11208 32432 11208 11211 32433 11211 11209 32434 11209 11210 32435 11210 11209 32436 11209 11211 32437 11211 11212 32438 11212 11215 32439 11215 11213 32440 11213 11214 32441 11214 11213 32442 11213 11215 32443 11215 11216 32444 11216 11219 32445 11219 11217 32446 11217 11218 32447 11218 11217 32448 11217 11219 32449 11219 11220 32450 11220 11223 32451 11223 11221 32452 11221 11222 32453 11222 11221 32454 11221 11223 32455 11223 11224 32456 11224 11227 32457 11227 11225 32458 11225 11226 32459 11226 11225 32460 11225 11227 32461 11227 11228 32462 11228 11231 32463 11231 11229 32464 11229 11230 32465 11230 11229 32466 11229 11231 32467 11231 11232 32468 11232 11235 32469 11235 11233 32470 11233 11234 32471 11234 11233 32472 11233 11235 32473 11235 11236 32474 11236 11239 32475 11239 11237 32476 11237 11238 32477 11238 11237 32478 11237 11239 32479 11239 11240 32480 11240 11243 32481 11243 11241 32482 11241 11242 32483 11242 11241 32484 11241 11243 32485 11243 11244 32486 11244 11247 32487 11247 11245 32488 11245 11246 32489 11246 11245 32490 11245 11247 32491 11247 11248 32492 11248 11251 32493 11251 11249 32494 11249 11250 32495 11250 11249 32496 11249 11251 32497 11251 11252 32498 11252 11255 32499 11255 11253 32500 11253 11254 32501 11254 11253 32502 11253 11255 32503 11255 11256 32504 11256 11259 32505 11259 11257 32506 11257 11258 32507 11258 11257 32508 11257 11259 32509 11259 11260 32510 11260 11263 32511 11263 11261 32512 11261 11262 32513 11262 11261 32514 11261 11263 32515 11263 11264 32516 11264 11267 32517 11267 11265 32518 11265 11266 32519 11266 11265 32520 11265 11267 32521 11267 11268 32522 11268 11271 32523 11271 11269 32524 11269 11270 32525 11270 11269 32526 11269 11271 32527 11271 11272 32528 11272 11275 32529 11275 11273 32530 11273 11274 32531 11274 11273 32532 11273 11275 32533 11275 11276 32534 11276 11279 32535 11279 11277 32536 11277 11278 32537 11278 11277 32538 11277 11279 32539 11279 11280 32540 11280 11283 32541 11283 11281 32542 11281 11282 32543 11282 11281 32544 11281 11283 32545 11283 11284 32546 11284 11287 32547 11287 11285 32548 11285 11286 32549 11286 11285 32550 11285 11287 32551 11287 11288 32552 11288 11291 32553 11291 11289 32554 11289 11290 32555 11290 11289 32556 11289 11291 32557 11291 11292 32558 11292 11295 32559 11295 11293 32560 11293 11294 32561 11294 11293 32562 11293 11295 32563 11295 11296 32564 11296 11299 32565 11299 11297 32566 11297 11298 32567 11298 11297 32568 11297 11299 32569 11299 11300 32570 11300 11303 32571 11303 11301 32572 11301 11302 32573 11302 11301 32574 11301 11303 32575 11303 11304 32576 11304 11322 32577 11322 11305 32578 11305 11314 32579 11314 11343 32580 11343 11306 32581 11306 11307 32582 11307 11340 32583 11340 11308 32584 11308 11309 32585 11309 11319 32586 11319 11310 32587 11310 11311 32588 11311 11327 32589 11327 11312 32590 11312 11313 32591 11313 11357 32592 11357 11314 32593 11314 11315 32594 11315 11323 32595 11323 11316 32596 11316 11317 32597 11317 11319 32598 11319 11318 32599 11318 11310 32600 11310 11329 32601 11329 11318 32602 11318 11319 32603 11319 11329 32604 11329 11320 32605 11320 11318 32606 11318 11323 32607 11323 11321 32608 11321 11316 32609 11316 11323 32610 11323 11322 32611 11322 11321 32612 11321 11361 32613 11361 11322 32614 11322 11323 32615 11323 11320 32616 11320 11324 32617 11324 11325 32618 11325 11320 32619 11320 11326 32620 11326 11324 32621 11324 11329 32622 11329 11326 32623 11326 11320 32624 11320 11329 32625 11329 11327 32626 11327 11326 32627 11326 11329 32628 11329 11312 32629 11312 11327 32630 11327 11329 32631 11329 11328 32632 11328 11312 32633 11312 11331 32634 11331 11328 32635 11328 11329 32636 11329 11331 32637 11331 11330 32638 11330 11328 32639 11328 11333 32640 11333 11330 32641 11330 11331 32642 11331 11333 32643 11333 11332 32644 11332 11330 32645 11330 11335 32646 11335 11332 32647 11332 11333 32648 11333 11335 32649 11335 11334 32650 11334 11332 32651 11332 11337 32652 11337 11334 32653 11334 11335 32654 11335 11337 32655 11337 11336 32656 11336 11334 32657 11334 11339 32658 11339 11336 32659 11336 11337 32660 11337 11339 32661 11339 11338 32662 11338 11336 32663 11336 11341 32664 11341 11338 32665 11338 11339 32666 11339 11341 32667 11341 11340 32668 11340 11338 32669 11338 11342 32670 11342 11340 32671 11340 11341 32672 11341 11342 32673 11342 11308 32674 11308 11340 32675 11340 11344 32676 11344 11308 32677 11308 11342 32678 11342 11344 32679 11344 11343 32680 11343 11308 32681 11308 11345 32682 11345 11343 32683 11343 11344 32684 11344 11345 32685 11345 11306 32686 11306 11343 32687 11343 11347 32688 11347 11306 32689 11306 11345 32690 11345 11347 32691 11347 11346 32692 11346 11306 32693 11306 11349 32694 11349 11346 32695 11346 11347 32696 11347 11349 32697 11349 11348 32698 11348 11346 32699 11346 11351 32700 11351 11348 32701 11348 11349 32702 11349 11351 32703 11351 11350 32704 11350 11348 32705 11348 11353 32706 11353 11350 32707 11350 11351 32708 11351 11353 32709 11353 11352 32710 11352 11350 32711 11350 11356 32712 11356 11352 32713 11352 11353 32714 11353 11356 32715 11356 11354 32716 11354 11352 32717 11352 11356 32718 11356 11355 32719 11355 11354 32720 11354 11358 32721 11358 11355 32722 11355 11356 32723 11356 11358 32724 11358 11357 32725 11357 11355 32726 11355 11322 32727 11322 11357 32728 11357 11358 32729 11358 11322 32730 11322 11314 32731 11314 11357 32732 11357 11305 32733 11305 11359 32734 11359 11360 32735 11360 11305 32736 11305 11361 32737 11361 11359 32738 11359 11305 32739 11305 11322 32740 11322 11361 32741 11361 11363 32742 11363 11362 32743 11362 11367 32744 11367 11368 32745 11368 11363 32746 11363 11364 32747 11364 11363 32748 11363 11365 32749 11365 11366 32750 11366 11363 32751 11363 11367 32752 11367 11365 32753 11365 11362 32754 11362 11368 32755 11368 11369 32756 11369 11362 32757 11362 11363 32758 11363 11368 32759 11368 11371 32760 11371 11370 32761 11370 11375 32762 11375 11376 32763 11376 11371 32764 11371 11372 32765 11372 11371 32766 11371 11373 32767 11373 11374 32768 11374 11371 32769 11371 11375 32770 11375 11373 32771 11373 11370 32772 11370 11376 32773 11376 11377 32774 11377 11370 32775 11370 11371 32776 11371 11376 32777 11376 11384 32778 11384 11378 32779 11378 11379 32780 11379 11385 32781 11385 11380 32782 11380 11381 32783 11381 11380 32784 11380 11382 32785 11382 11383 32786 11383 11385 32787 11385 11382 32788 11382 11380 32789 11380 11385 32790 11385 11384 32791 11384 11382 32792 11382 11378 32793 11378 11384 32794 11384 11385 32795 11385 11442 32796 11442 11432 32797 11432 11386 32798 11386 11420 32799 11420 11387 32800 11387 11388 32801 11388 11417 32802 11417 11389 32803 11389 11390 32804 11390 11393 32805 11393 11391 32806 11391 11392 32807 11392 11401 32808 11401 11391 32809 11391 11393 32810 11393 11402 32811 11402 11394 32812 11394 11395 32813 11395 11400 32814 11400 11396 32815 11396 11397 32816 11397 11400 32817 11400 11398 32818 11398 11396 32819 11396 11400 32820 11400 11399 32821 11399 11398 32822 11398 11391 32823 11391 11399 32824 11399 11400 32825 11400 11401 32826 11401 11399 32827 11399 11391 32828 11391 11394 32829 11394 11399 32830 11399 11401 32831 11401 11402 32832 11402 11399 32833 11399 11394 32834 11394 11404 32835 11404 11399 32836 11399 11402 32837 11402 11404 32838 11404 11403 32839 11403 11399 32840 11399 11406 32841 11406 11403 32842 11403 11404 32843 11404 11406 32844 11406 11405 32845 11405 11403 32846 11403 11408 32847 11408 11405 32848 11405 11406 32849 11406 11408 32850 11408 11407 32851 11407 11405 32852 11405 11410 32853 11410 11407 32854 11407 11408 32855 11408 11410 32856 11410 11409 32857 11409 11407 32858 11407 11412 32859 11412 11409 32860 11409 11410 32861 11410 11412 32862 11412 11411 32863 11411 11409 32864 11409 11414 32865 11414 11411 32866 11411 11412 32867 11412 11414 32868 11414 11413 32869 11413 11411 32870 11411 11389 32871 11389 11413 32872 11413 11414 32873 11414 11389 32874 11389 11415 32875 11415 11413 32876 11413 11417 32877 11417 11415 32878 11415 11389 32879 11389 11417 32880 11417 11416 32881 11416 11415 32882 11415 11387 32883 11387 11416 32884 11416 11417 32885 11417 11387 32886 11387 11418 32887 11418 11416 32888 11416 11420 32889 11420 11418 32890 11418 11387 32891 11387 11420 32892 11420 11419 32893 11419 11418 32894 11418 11422 32895 11422 11419 32896 11419 11420 32897 11420 11422 32898 11422 11421 32899 11421 11419 32900 11419 11424 32901 11424 11421 32902 11421 11422 32903 11422 11424 32904 11424 11423 32905 11423 11421 32906 11421 11426 32907 11426 11423 32908 11423 11424 32909 11424 11426 32910 11426 11425 32911 11425 11423 32912 11423 11428 32913 11428 11425 32914 11425 11426 32915 11426 11428 32916 11428 11427 32917 11427 11425 32918 11425 11429 32919 11429 11427 32920 11427 11428 32921 11428 11431 32922 11431 11427 32923 11427 11429 32924 11429 11431 32925 11431 11430 32926 11430 11427 32927 11427 11438 32928 11438 11430 32929 11430 11431 32930 11431 11438 32931 11438 11432 32932 11432 11430 32933 11430 11436 32934 11436 11433 32935 11433 11434 32936 11434 11436 32937 11436 11435 32938 11435 11433 32939 11433 11432 32940 11432 11435 32941 11435 11436 32942 11436 11432 32943 11432 11437 32944 11437 11435 32945 11435 11439 32946 11439 11432 32947 11432 11438 32948 11438 11386 32949 11386 11432 32950 11432 11439 32951 11439 11437 32952 11437 11440 32953 11440 11441 32954 11441 11437 32955 11437 11442 32956 11442 11440 32957 11440 11432 32958 11432 11442 32959 11442 11437 32960 11437 11447 32961 11447 11443 32962 11443 11451 32963 11451 11446 32964 11446 11444 32965 11444 11445 32966 11445 11448 32967 11448 11444 32968 11444 11446 32969 11446 11448 32970 11448 11447 32971 11447 11444 32972 11444 11457 32973 11457 11447 32974 11447 11448 32975 11448 11447 32976 11447 11449 32977 11449 11450 32978 11450 11447 32979 11447 11451 32980 11451 11449 32981 11449 11443 32982 11443 11452 32983 11452 11453 32984 11453 11443 32985 11443 11454 32986 11454 11452 32987 11452 11458 32988 11458 11455 32989 11455 11456 32990 11456 11458 32991 11458 11457 32992 11457 11455 32993 11455 11458 32994 11458 11447 32995 11447 11457 32996 11457 11454 32997 11454 11447 32998 11447 11458 32999 11458 11443 33000 11443 11447 33001 11447 11454 33002 11454 11463 33003 11463 11459 33004 11459 11467 33005 11467 11464 33006 11464 11460 33007 11460 11461 33008 11461 11464 33009 11464 11462 33010 11462 11460 33011 11460 11464 33012 11464 11463 33013 11463 11462 33014 11462 11470 33015 11470 11463 33016 11463 11464 33017 11464 11463 33018 11463 11465 33019 11465 11466 33020 11466 11463 33021 11463 11467 33022 11467 11465 33023 11465 11459 33024 11459 11468 33025 11468 11469 33026 11469 11459 33027 11459 11470 33028 11470 11468 33029 11468 11459 33030 11459 11463 33031 11463 11470 33032 11470 11482 33033 11482 11479 33034 11479 11471 33035 11471 11474 33036 11474 11472 33037 11472 11473 33038 11473 11475 33039 11475 11472 33040 11472 11474 33041 11474 11479 33042 11479 11472 33043 11472 11475 33044 11475 11479 33045 11479 11476 33046 11476 11472 33047 11472 11476 33048 11476 11477 33049 11477 11478 33050 11478 11481 33051 11481 11479 33052 11479 11480 33053 11480 11471 33054 11471 11479 33055 11479 11481 33056 11481 11476 33057 11476 11482 33058 11482 11477 33059 11477 11479 33060 11479 11482 33061 11482 11476 33062 11476 11515 33063 11515 11483 33064 11483 11484 33065 11484 11487 33066 11487 11485 33067 11485 11486 33068 11486 11488 33069 11488 11485 33070 11485 11487 33071 11487 11490 33072 11490 11485 33073 11485 11488 33074 11488 11490 33075 11490 11489 33076 11489 11485 33077 11485 11492 33078 11492 11489 33079 11489 11490 33080 11490 11492 33081 11492 11491 33082 11491 11489 33083 11489 11494 33084 11494 11491 33085 11491 11492 33086 11492 11494 33087 11494 11493 33088 11493 11491 33089 11491 11497 33090 11497 11493 33091 11493 11494 33092 11494 11497 33093 11497 11495 33094 11495 11493 33095 11493 11497 33096 11497 11496 33097 11496 11495 33098 11495 11498 33099 11498 11496 33100 11496 11497 33101 11497 11500 33102 11500 11496 33103 11496 11498 33104 11498 11500 33105 11500 11499 33106 11499 11496 33107 11496 11503 33108 11503 11499 33109 11499 11500 33110 11500 11503 33111 11503 11501 33112 11501 11499 33113 11499 11503 33114 11503 11502 33115 11502 11501 33116 11501 11504 33117 11504 11502 33118 11502 11503 33119 11503 11506 33120 11506 11502 33121 11502 11504 33122 11504 11506 33123 11506 11505 33124 11505 11502 33125 11502 11508 33126 11508 11505 33127 11505 11506 33128 11506 11508 33129 11508 11507 33130 11507 11505 33131 11505 11510 33132 11510 11507 33133 11507 11508 33134 11508 11510 33135 11510 11509 33136 11509 11507 33137 11507 11512 33138 11512 11509 33139 11509 11510 33140 11510 11512 33141 11512 11511 33142 11511 11509 33143 11509 11514 33144 11514 11511 33145 11511 11512 33146 11512 11514 33147 11514 11513 33148 11513 11511 33149 11511 11516 33150 11516 11513 33151 11513 11514 33152 11514 11516 33153 11516 11515 33154 11515 11513 33155 11513 11483 33156 11483 11515 33157 11515 11516 33158 11516 11549 33159 11549 11517 33160 11517 11518 33161 11518 11521 33162 11521 11519 33163 11519 11520 33164 11520 11522 33165 11522 11519 33166 11519 11521 33167 11521 11524 33168 11524 11519 33169 11519 11522 33170 11522 11524 33171 11524 11523 33172 11523 11519 33173 11519 11526 33174 11526 11523 33175 11523 11524 33176 11524 11526 33177 11526 11525 33178 11525 11523 33179 11523 11528 33180 11528 11525 33181 11525 11526 33182 11526 11528 33183 11528 11527 33184 11527 11525 33185 11525 11531 33186 11531 11527 33187 11527 11528 33188 11528 11531 33189 11531 11529 33190 11529 11527 33191 11527 11531 33192 11531 11530 33193 11530 11529 33194 11529 11532 33195 11532 11530 33196 11530 11531 33197 11531 11534 33198 11534 11530 33199 11530 11532 33200 11532 11534 33201 11534 11533 33202 11533 11530 33203 11530 11537 33204 11537 11533 33205 11533 11534 33206 11534 11537 33207 11537 11535 33208 11535 11533 33209 11533 11537 33210 11537 11536 33211 11536 11535 33212 11535 11538 33213 11538 11536 33214 11536 11537 33215 11537 11540 33216 11540 11536 33217 11536 11538 33218 11538 11540 33219 11540 11539 33220 11539 11536 33221 11536 11542 33222 11542 11539 33223 11539 11540 33224 11540 11542 33225 11542 11541 33226 11541 11539 33227 11539 11544 33228 11544 11541 33229 11541 11542 33230 11542 11544 33231 11544 11543 33232 11543 11541 33233 11541 11546 33234 11546 11543 33235 11543 11544 33236 11544 11546 33237 11546 11545 33238 11545 11543 33239 11543 11548 33240 11548 11545 33241 11545 11546 33242 11546 11548 33243 11548 11547 33244 11547 11545 33245 11545 11550 33246 11550 11547 33247 11547 11548 33248 11548 11550 33249 11550 11549 33250 11549 11547 33251 11547 11517 33252 11517 11549 33253 11549 11550 33254 11550 11583 33255 11583 11551 33256 11551 11552 33257 11552 11555 33258 11555 11553 33259 11553 11554 33260 11554 11556 33261 11556 11553 33262 11553 11555 33263 11555 11558 33264 11558 11553 33265 11553 11556 33266 11556 11558 33267 11558 11557 33268 11557 11553 33269 11553 11560 33270 11560 11557 33271 11557 11558 33272 11558 11560 33273 11560 11559 33274 11559 11557 33275 11557 11562 33276 11562 11559 33277 11559 11560 33278 11560 11562 33279 11562 11561 33280 11561 11559 33281 11559 11565 33282 11565 11561 33283 11561 11562 33284 11562 11565 33285 11565 11563 33286 11563 11561 33287 11561 11565 33288 11565 11564 33289 11564 11563 33290 11563 11566 33291 11566 11564 33292 11564 11565 33293 11565 11568 33294 11568 11564 33295 11564 11566 33296 11566 11568 33297 11568 11567 33298 11567 11564 33299 11564 11571 33300 11571 11567 33301 11567 11568 33302 11568 11571 33303 11571 11569 33304 11569 11567 33305 11567 11571 33306 11571 11570 33307 11570 11569 33308 11569 11572 33309 11572 11570 33310 11570 11571 33311 11571 11574 33312 11574 11570 33313 11570 11572 33314 11572 11574 33315 11574 11573 33316 11573 11570 33317 11570 11576 33318 11576 11573 33319 11573 11574 33320 11574 11576 33321 11576 11575 33322 11575 11573 33323 11573 11578 33324 11578 11575 33325 11575 11576 33326 11576 11578 33327 11578 11577 33328 11577 11575 33329 11575 11580 33330 11580 11577 33331 11577 11578 33332 11578 11580 33333 11580 11579 33334 11579 11577 33335 11577 11582 33336 11582 11579 33337 11579 11580 33338 11580 11582 33339 11582 11581 33340 11581 11579 33341 11579 11584 33342 11584 11581 33343 11581 11582 33344 11582 11584 33345 11584 11583 33346 11583 11581 33347 11581 11551 33348 11551 11583 33349 11583 11584 33350 11584 11616 33351 11616 11594 33352 11594 11585 33353 11585 11588 33354 11588 11586 33355 11586 11587 33356 11587 11590 33357 11590 11586 33358 11586 11588 33359 11588 11590 33360 11590 11589 33361 11589 11586 33362 11586 11592 33363 11592 11589 33364 11589 11590 33365 11590 11592 33366 11592 11591 33367 11591 11589 33368 11589 11593 33369 11593 11591 33370 11591 11592 33371 11592 11585 33372 11585 11591 33373 11591 11593 33374 11593 11585 33375 11585 11594 33376 11594 11591 33377 11591 11597 33378 11597 11595 33379 11595 11596 33380 11596 11598 33381 11598 11595 33382 11595 11597 33383 11597 11600 33384 11600 11595 33385 11595 11598 33386 11598 11600 33387 11600 11599 33388 11599 11595 33389 11595 11602 33390 11602 11599 33391 11599 11600 33392 11600 11602 33393 11602 11601 33394 11601 11599 33395 11599 11604 33396 11604 11601 33397 11601 11602 33398 11602 11604 33399 11604 11603 33400 11603 11601 33401 11601 11606 33402 11606 11603 33403 11603 11604 33404 11604 11606 33405 11606 11605 33406 11605 11603 33407 11603 11608 33408 11608 11605 33409 11605 11606 33410 11606 11608 33411 11608 11607 33412 11607 11605 33413 11605 11610 33414 11610 11607 33415 11607 11608 33416 11608 11610 33417 11610 11609 33418 11609 11607 33419 11607 11612 33420 11612 11609 33421 11609 11610 33422 11610 11612 33423 11612 11611 33424 11611 11609 33425 11609 11614 33426 11614 11611 33427 11611 11612 33428 11612 11614 33429 11614 11613 33430 11613 11611 33431 11611 11617 33432 11617 11613 33433 11613 11614 33434 11614 11617 33435 11617 11615 33436 11615 11613 33437 11613 11617 33438 11617 11616 33439 11616 11615 33440 11615 11618 33441 11618 11616 33442 11616 11617 33443 11617 11594 33444 11594 11616 33445 11616 11618 33446 11618 11651 33447 11651 11619 33448 11619 11620 33449 11620 11625 33450 11625 11621 33451 11621 11622 33452 11622 11625 33453 11625 11623 33454 11623 11621 33455 11621 11625 33456 11625 11624 33457 11624 11623 33458 11623 11627 33459 11627 11624 33460 11624 11625 33461 11625 11627 33462 11627 11626 33463 11626 11624 33464 11624 11628 33465 11628 11626 33466 11626 11627 33467 11627 11630 33468 11630 11626 33469 11626 11628 33470 11628 11630 33471 11630 11629 33472 11629 11626 33473 11626 11633 33474 11633 11629 33475 11629 11630 33476 11630 11633 33477 11633 11631 33478 11631 11629 33479 11629 11633 33480 11633 11632 33481 11632 11631 33482 11631 11634 33483 11634 11632 33484 11632 11633 33485 11633 11636 33486 11636 11632 33487 11632 11634 33488 11634 11636 33489 11636 11635 33490 11635 11632 33491 11632 11639 33492 11639 11635 33493 11635 11636 33494 11636 11639 33495 11639 11637 33496 11637 11635 33497 11635 11639 33498 11639 11638 33499 11638 11637 33500 11637 11640 33501 11640 11638 33502 11638 11639 33503 11639 11642 33504 11642 11638 33505 11638 11640 33506 11640 11642 33507 11642 11641 33508 11641 11638 33509 11638 11644 33510 11644 11641 33511 11641 11642 33512 11642 11644 33513 11644 11643 33514 11643 11641 33515 11641 11646 33516 11646 11643 33517 11643 11644 33518 11644 11646 33519 11646 11645 33520 11645 11643 33521 11643 11648 33522 11648 11645 33523 11645 11646 33524 11646 11648 33525 11648 11647 33526 11647 11645 33527 11645 11650 33528 11650 11647 33529 11647 11648 33530 11648 11650 33531 11650 11649 33532 11649 11647 33533 11647 11652 33534 11652 11649 33535 11649 11650 33536 11650 11652 33537 11652 11651 33538 11651 11649 33539 11649 11619 33540 11619 11651 33541 11651 11652 33542 11652 11685 33543 11685 11653 33544 11653 11654 33545 11654 11657 33546 11657 11655 33547 11655 11656 33548 11656 11658 33549 11658 11655 33550 11655 11657 33551 11657 11660 33552 11660 11655 33553 11655 11658 33554 11658 11660 33555 11660 11659 33556 11659 11655 33557 11655 11662 33558 11662 11659 33559 11659 11660 33560 11660 11662 33561 11662 11661 33562 11661 11659 33563 11659 11665 33564 11665 11661 33565 11661 11662 33566 11662 11665 33567 11665 11663 33568 11663 11661 33569 11661 11665 33570 11665 11664 33571 11664 11663 33572 11663 11666 33573 11666 11664 33574 11664 11665 33575 11665 11668 33576 11668 11664 33577 11664 11666 33578 11666 11668 33579 11668 11667 33580 11667 11664 33581 11664 11670 33582 11670 11667 33583 11667 11668 33584 11668 11670 33585 11670 11669 33586 11669 11667 33587 11667 11673 33588 11673 11669 33589 11669 11670 33590 11670 11673 33591 11673 11671 33592 11671 11669 33593 11669 11673 33594 11673 11672 33595 11672 11671 33596 11671 11675 33597 11675 11672 33598 11672 11673 33599 11673 11675 33600 11675 11674 33601 11674 11672 33602 11672 11676 33603 11676 11674 33604 11674 11675 33605 11675 11679 33606 11679 11674 33607 11674 11676 33608 11676 11679 33609 11679 11677 33610 11677 11674 33611 11674 11679 33612 11679 11678 33613 11678 11677 33614 11677 11680 33615 11680 11678 33616 11678 11679 33617 11679 11682 33618 11682 11678 33619 11678 11680 33620 11680 11682 33621 11682 11681 33622 11681 11678 33623 11678 11684 33624 11684 11681 33625 11681 11682 33626 11682 11684 33627 11684 11683 33628 11683 11681 33629 11681 11686 33630 11686 11683 33631 11683 11684 33632 11684 11686 33633 11686 11685 33634 11685 11683 33635 11683 11653 33636 11653 11685 33637 11685 11686 33638 11686 11719 33639 11719 11687 33640 11687 11688 33641 11688 11692 33642 11692 11689 33643 11689 11690 33644 11690 11692 33645 11692 11691 33646 11691 11689 33647 11689 11694 33648 11694 11691 33649 11691 11692 33650 11692 11694 33651 11694 11693 33652 11693 11691 33653 11691 11696 33654 11696 11693 33655 11693 11694 33656 11694 11696 33657 11696 11695 33658 11695 11693 33659 11693 11698 33660 11698 11695 33661 11695 11696 33662 11696 11698 33663 11698 11697 33664 11697 11695 33665 11695 11700 33666 11700 11697 33667 11697 11698 33668 11698 11700 33669 11700 11699 33670 11699 11697 33671 11697 11702 33672 11702 11699 33673 11699 11700 33674 11700 11702 33675 11702 11701 33676 11701 11699 33677 11699 11704 33678 11704 11701 33679 11701 11702 33680 11702 11704 33681 11704 11703 33682 11703 11701 33683 11701 11706 33684 11706 11703 33685 11703 11704 33686 11704 11706 33687 11706 11705 33688 11705 11703 33689 11703 11708 33690 11708 11705 33691 11705 11706 33692 11706 11708 33693 11708 11707 33694 11707 11705 33695 11705 11710 33696 11710 11707 33697 11707 11708 33698 11708 11710 33699 11710 11709 33700 11709 11707 33701 11707 11712 33702 11712 11709 33703 11709 11710 33704 11710 11712 33705 11712 11711 33706 11711 11709 33707 11709 11714 33708 11714 11711 33709 11711 11712 33710 11712 11714 33711 11714 11713 33712 11713 11711 33713 11711 11716 33714 11716 11713 33715 11713 11714 33716 11714 11716 33717 11716 11715 33718 11715 11713 33719 11713 11718 33720 11718 11715 33721 11715 11716 33722 11716 11718 33723 11718 11717 33724 11717 11715 33725 11715 11720 33726 11720 11717 33727 11717 11718 33728 11718 11720 33729 11720 11719 33730 11719 11717 33731 11717 11687 33732 11687 11719 33733 11719 11720 33734 11720 11754 33735 11754 11721 33736 11721 11722 33737 11722 11725 33738 11725 11723 33739 11723 11724 33740 11724 11726 33741 11726 11723 33742 11723 11725 33743 11725 11728 33744 11728 11723 33745 11723 11726 33746 11726 11728 33747 11728 11727 33748 11727 11723 33749 11723 11730 33750 11730 11727 33751 11727 11728 33752 11728 11730 33753 11730 11729 33754 11729 11727 33755 11727 11732 33756 11732 11729 33757 11729 11730 33758 11730 11732 33759 11732 11731 33760 11731 11729 33761 11729 11734 33762 11734 11731 33763 11731 11732 33764 11732 11734 33765 11734 11733 33766 11733 11731 33767 11731 11736 33768 11736 11733 33769 11733 11734 33770 11734 11736 33771 11736 11735 33772 11735 11733 33773 11733 11738 33774 11738 11735 33775 11735 11736 33776 11736 11738 33777 11738 11737 33778 11737 11735 33779 11735 11741 33780 11741 11737 33781 11737 11738 33782 11738 11741 33783 11741 11739 33784 11739 11737 33785 11737 11741 33786 11741 11740 33787 11740 11739 33788 11739 11743 33789 11743 11740 33790 11740 11741 33791 11741 11743 33792 11743 11742 33793 11742 11740 33794 11740 11745 33795 11745 11742 33796 11742 11743 33797 11743 11745 33798 11745 11744 33799 11744 11742 33800 11742 11746 33801 11746 11744 33802 11744 11745 33803 11745 11748 33804 11748 11744 33805 11744 11746 33806 11746 11748 33807 11748 11747 33808 11747 11744 33809 11744 11750 33810 11750 11747 33811 11747 11748 33812 11748 11750 33813 11750 11749 33814 11749 11747 33815 11747 11753 33816 11753 11749 33817 11749 11750 33818 11750 11753 33819 11753 11751 33820 11751 11749 33821 11749 11753 33822 11753 11752 33823 11752 11751 33824 11751 11721 33825 11721 11752 33826 11752 11753 33827 11753 11721 33828 11721 11754 33829 11754 11752 33830 11752 11787 33831 11787 11755 33832 11755 11756 33833 11756 11759 33834 11759 11757 33835 11757 11758 33836 11758 11760 33837 11760 11757 33838 11757 11759 33839 11759 11762 33840 11762 11757 33841 11757 11760 33842 11760 11762 33843 11762 11761 33844 11761 11757 33845 11757 11764 33846 11764 11761 33847 11761 11762 33848 11762 11764 33849 11764 11763 33850 11763 11761 33851 11761 11766 33852 11766 11763 33853 11763 11764 33854 11764 11766 33855 11766 11765 33856 11765 11763 33857 11763 11768 33858 11768 11765 33859 11765 11766 33860 11766 11768 33861 11768 11767 33862 11767 11765 33863 11765 11770 33864 11770 11767 33865 11767 11768 33866 11768 11770 33867 11770 11769 33868 11769 11767 33869 11767 11772 33870 11772 11769 33871 11769 11770 33872 11770 11772 33873 11772 11771 33874 11771 11769 33875 11769 11774 33876 11774 11771 33877 11771 11772 33878 11772 11774 33879 11774 11773 33880 11773 11771 33881 11771 11777 33882 11777 11773 33883 11773 11774 33884 11774 11777 33885 11777 11775 33886 11775 11773 33887 11773 11777 33888 11777 11776 33889 11776 11775 33890 11775 11778 33891 11778 11776 33892 11776 11777 33893 11777 11780 33894 11780 11776 33895 11776 11778 33896 11778 11780 33897 11780 11779 33898 11779 11776 33899 11776 11782 33900 11782 11779 33901 11779 11780 33902 11780 11782 33903 11782 11781 33904 11781 11779 33905 11779 11784 33906 11784 11781 33907 11781 11782 33908 11782 11784 33909 11784 11783 33910 11783 11781 33911 11781 11786 33912 11786 11783 33913 11783 11784 33914 11784 11786 33915 11786 11785 33916 11785 11783 33917 11783 11788 33918 11788 11785 33919 11785 11786 33920 11786 11788 33921 11788 11787 33922 11787 11785 33923 11785 11755 33924 11755 11787 33925 11787 11788 33926 11788 11821 33927 11821 11789 33928 11789 11790 33929 11790 11793 33930 11793 11791 33931 11791 11792 33932 11792 11794 33933 11794 11791 33934 11791 11793 33935 11793 11796 33936 11796 11791 33937 11791 11794 33938 11794 11796 33939 11796 11795 33940 11795 11791 33941 11791 11798 33942 11798 11795 33943 11795 11796 33944 11796 11798 33945 11798 11797 33946 11797 11795 33947 11795 11800 33948 11800 11797 33949 11797 11798 33950 11798 11800 33951 11800 11799 33952 11799 11797 33953 11797 11802 33954 11802 11799 33955 11799 11800 33956 11800 11802 33957 11802 11801 33958 11801 11799 33959 11799 11804 33960 11804 11801 33961 11801 11802 33962 11802 11804 33963 11804 11803 33964 11803 11801 33965 11801 11806 33966 11806 11803 33967 11803 11804 33968 11804 11806 33969 11806 11805 33970 11805 11803 33971 11803 11808 33972 11808 11805 33973 11805 11806 33974 11806 11808 33975 11808 11807 33976 11807 11805 33977 11805 11811 33978 11811 11807 33979 11807 11808 33980 11808 11811 33981 11811 11809 33982 11809 11807 33983 11807 11811 33984 11811 11810 33985 11810 11809 33986 11809 11812 33987 11812 11810 33988 11810 11811 33989 11811 11814 33990 11814 11810 33991 11810 11812 33992 11812 11814 33993 11814 11813 33994 11813 11810 33995 11810 11816 33996 11816 11813 33997 11813 11814 33998 11814 11816 33999 11816 11815 34000 11815 11813 34001 11813 11818 34002 11818 11815 34003 11815 11816 34004 11816 11818 34005 11818 11817 34006 11817 11815 34007 11815 11820 34008 11820 11817 34009 11817 11818 34010 11818 11820 34011 11820 11819 34012 11819 11817 34013 11817 11822 34014 11822 11819 34015 11819 11820 34016 11820 11822 34017 11822 11821 34018 11821 11819 34019 11819 11789 34020 11789 11821 34021 11821 11822 34022 11822 11855 34023 11855 11823 34024 11823 11824 34025 11824 11827 34026 11827 11825 34027 11825 11826 34028 11826 11828 34029 11828 11825 34030 11825 11827 34031 11827 11830 34032 11830 11825 34033 11825 11828 34034 11828 11830 34035 11830 11829 34036 11829 11825 34037 11825 11832 34038 11832 11829 34039 11829 11830 34040 11830 11832 34041 11832 11831 34042 11831 11829 34043 11829 11834 34044 11834 11831 34045 11831 11832 34046 11832 11834 34047 11834 11833 34048 11833 11831 34049 11831 11837 34050 11837 11833 34051 11833 11834 34052 11834 11837 34053 11837 11835 34054 11835 11833 34055 11833 11837 34056 11837 11836 34057 11836 11835 34058 11835 11838 34059 11838 11836 34060 11836 11837 34061 11837 11840 34062 11840 11836 34063 11836 11838 34064 11838 11840 34065 11840 11839 34066 11839 11836 34067 11836 11843 34068 11843 11839 34069 11839 11840 34070 11840 11843 34071 11843 11841 34072 11841 11839 34073 11839 11843 34074 11843 11842 34075 11842 11841 34076 11841 11844 34077 11844 11842 34078 11842 11843 34079 11843 11846 34080 11846 11842 34081 11842 11844 34082 11844 11846 34083 11846 11845 34084 11845 11842 34085 11842 11848 34086 11848 11845 34087 11845 11846 34088 11846 11848 34089 11848 11847 34090 11847 11845 34091 11845 11850 34092 11850 11847 34093 11847 11848 34094 11848 11850 34095 11850 11849 34096 11849 11847 34097 11847 11852 34098 11852 11849 34099 11849 11850 34100 11850 11852 34101 11852 11851 34102 11851 11849 34103 11849 11854 34104 11854 11851 34105 11851 11852 34106 11852 11854 34107 11854 11853 34108 11853 11851 34109 11851 11856 34110 11856 11853 34111 11853 11854 34112 11854 11856 34113 11856 11855 34114 11855 11853 34115 11853 11823 34116 11823 11855 34117 11855 11856 34118 11856 11873 34119 11873 11857 34120 11857 11858 34121 11858 11861 34122 11861 11859 34123 11859 11860 34124 11860 11863 34125 11863 11859 34126 11859 11861 34127 11861 11863 34128 11863 11862 34129 11862 11859 34130 11859 11864 34131 11864 11862 34132 11862 11863 34133 11863 11866 34134 11866 11862 34135 11862 11864 34136 11864 11866 34137 11866 11865 34138 11865 11862 34139 11862 11868 34140 11868 11865 34141 11865 11866 34142 11866 11868 34143 11868 11867 34144 11867 11865 34145 11865 11870 34146 11870 11867 34147 11867 11868 34148 11868 11870 34149 11870 11869 34150 11869 11867 34151 11867 11872 34152 11872 11869 34153 11869 11870 34154 11870 11872 34155 11872 11871 34156 11871 11869 34157 11869 11874 34158 11874 11871 34159 11871 11872 34160 11872 11874 34161 11874 11873 34162 11873 11871 34163 11871 11857 34164 11857 11873 34165 11873 11874 34166 11874 11891 34167 11891 11880 34168 11880 11875 34169 11875 11878 34170 11878 11876 34171 11876 11877 34172 11877 11879 34173 11879 11876 34174 11876 11878 34175 11878 11875 34176 11875 11876 34177 11876 11879 34178 11879 11875 34179 11875 11880 34180 11880 11876 34181 11876 11884 34182 11884 11881 34183 11881 11882 34184 11882 11884 34185 11884 11883 34186 11883 11881 34187 11881 11886 34188 11886 11883 34189 11883 11884 34190 11884 11886 34191 11886 11885 34192 11885 11883 34193 11883 11888 34194 11888 11885 34195 11885 11886 34196 11886 11888 34197 11888 11887 34198 11887 11885 34199 11885 11890 34200 11890 11887 34201 11887 11888 34202 11888 11890 34203 11890 11889 34204 11889 11887 34205 11887 11892 34206 11892 11889 34207 11889 11890 34208 11890 11892 34209 11892 11891 34210 11891 11889 34211 11889 11880 34212 11880 11891 34213 11891 11892 34214 11892 11910 34215 11910 11893 34216 11893 11894 34217 11894 11899 34218 11899 11895 34219 11895 11896 34220 11896 11899 34221 11899 11897 34222 11897 11895 34223 11895 11899 34224 11899 11898 34225 11898 11897 34226 11897 11901 34227 11901 11898 34228 11898 11899 34229 11899 11901 34230 11901 11900 34231 11900 11898 34232 11898 11902 34233 11902 11900 34234 11900 11901 34235 11901 11905 34236 11905 11900 34237 11900 11902 34238 11902 11905 34239 11905 11903 34240 11903 11900 34241 11900 11905 34242 11905 11904 34243 11904 11903 34244 11903 11906 34245 11906 11904 34246 11904 11905 34247 11905 11909 34248 11909 11904 34249 11904 11906 34250 11906 11909 34251 11909 11907 34252 11907 11904 34253 11904 11909 34254 11909 11908 34255 11908 11907 34256 11907 11893 34257 11893 11908 34258 11908 11909 34259 11909 11893 34260 11893 11910 34261 11910 11908 34262 11908 11928 34263 11928 11911 34264 11911 11912 34265 11912 11915 34266 11915 11913 34267 11913 11914 34268 11914 11916 34269 11916 11913 34270 11913 11915 34271 11915 11918 34272 11918 11913 34273 11913 11916 34274 11916 11918 34275 11918 11917 34276 11917 11913 34277 11913 11920 34278 11920 11917 34279 11917 11918 34280 11918 11920 34281 11920 11919 34282 11919 11917 34283 11917 11922 34284 11922 11919 34285 11919 11920 34286 11920 11922 34287 11922 11921 34288 11921 11919 34289 11919 11924 34290 11924 11921 34291 11921 11922 34292 11922 11924 34293 11924 11923 34294 11923 11921 34295 11921 11927 34296 11927 11923 34297 11923 11924 34298 11924 11927 34299 11927 11925 34300 11925 11923 34301 11923 11927 34302 11927 11926 34303 11926 11925 34304 11925 11911 34305 11911 11926 34306 11926 11927 34307 11927 11911 34308 11911 11928 34309 11928 11926 34310 11926 11946 34311 11946 11929 34312 11929 11930 34313 11930 11935 34314 11935 11931 34315 11931 11932 34316 11932 11935 34317 11935 11933 34318 11933 11931 34319 11931 11935 34320 11935 11934 34321 11934 11933 34322 11933 11937 34323 11937 11934 34324 11934 11935 34325 11935 11937 34326 11937 11936 34327 11936 11934 34328 11934 11938 34329 11938 11936 34330 11936 11937 34331 11937 11941 34332 11941 11936 34333 11936 11938 34334 11938 11941 34335 11941 11939 34336 11939 11936 34337 11936 11941 34338 11941 11940 34339 11940 11939 34340 11939 11943 34341 11943 11940 34342 11940 11941 34343 11941 11943 34344 11943 11942 34345 11942 11940 34346 11940 11944 34347 11944 11942 34348 11942 11943 34349 11943 11929 34350 11929 11942 34351 11942 11944 34352 11944 11929 34353 11929 11945 34354 11945 11942 34355 11942 11929 34356 11929 11946 34357 11946 11945 34358 11945 11964 34359 11964 11947 34360 11947 11952 34361 11952 11951 34362 11951 11948 34363 11948 11949 34364 11949 11951 34365 11951 11950 34366 11950 11948 34367 11948 11964 34368 11964 11950 34369 11950 11951 34370 11951 11964 34371 11964 11952 34372 11952 11950 34373 11950 11955 34374 11955 11953 34375 11953 11954 34376 11954 11956 34377 11956 11953 34378 11953 11955 34379 11955 11958 34380 11958 11953 34381 11953 11956 34382 11956 11958 34383 11958 11957 34384 11957 11953 34385 11953 11961 34386 11961 11957 34387 11957 11958 34388 11958 11961 34389 11961 11959 34390 11959 11957 34391 11957 11961 34392 11961 11960 34393 11960 11959 34394 11959 11963 34395 11963 11960 34396 11960 11961 34397 11961 11963 34398 11963 11962 34399 11962 11960 34400 11960 11947 34401 11947 11962 34402 11962 11963 34403 11963 11947 34404 11947 11964 34405 11964 11962 34406 11962 11981 34407 11981 11965 34408 11965 11966 34409 11966 11970 34410 11970 11967 34411 11967 11968 34412 11968 11970 34413 11970 11969 34414 11969 11967 34415 11967 11973 34416 11973 11969 34417 11969 11970 34418 11970 11973 34419 11973 11971 34420 11971 11969 34421 11969 11973 34422 11973 11972 34423 11972 11971 34424 11971 11974 34425 11974 11972 34426 11972 11973 34427 11973 11977 34428 11977 11972 34429 11972 11974 34430 11974 11977 34431 11977 11975 34432 11975 11972 34433 11972 11977 34434 11977 11976 34435 11976 11975 34436 11975 11979 34437 11979 11976 34438 11976 11977 34439 11977 11979 34440 11979 11978 34441 11978 11976 34442 11976 11980 34443 11980 11978 34444 11978 11979 34445 11979 11982 34446 11982 11978 34447 11978 11980 34448 11980 11982 34449 11982 11981 34450 11981 11978 34451 11978 11965 34452 11965 11981 34453 11981 11982 34454 11982 12000 34455 12000 11983 34456 11983 11984 34457 11984 11987 34458 11987 11985 34459 11985 11986 34460 11986 11988 34461 11988 11985 34462 11985 11987 34463 11987 11991 34464 11991 11985 34465 11985 11988 34466 11988 11991 34467 11991 11989 34468 11989 11985 34469 11985 11991 34470 11991 11990 34471 11990 11989 34472 11989 11993 34473 11993 11990 34474 11990 11991 34475 11991 11993 34476 11993 11992 34477 11992 11990 34478 11990 11995 34479 11995 11992 34480 11992 11993 34481 11993 11995 34482 11995 11994 34483 11994 11992 34484 11992 11996 34485 11996 11994 34486 11994 11995 34487 11995 11998 34488 11998 11994 34489 11994 11996 34490 11996 11998 34491 11998 11997 34492 11997 11994 34493 11994 11983 34494 11983 11997 34495 11997 11998 34496 11998 11983 34497 11983 11999 34498 11999 11997 34499 11997 11983 34500 11983 12000 34501 12000 11999 34502 11999 12017 34503 12017 12001 34504 12001 12002 34505 12002 12005 34506 12005 12003 34507 12003 12004 34508 12004 12007 34509 12007 12003 34510 12003 12005 34511 12005 12007 34512 12007 12006 34513 12006 12003 34514 12003 12009 34515 12009 12006 34516 12006 12007 34517 12007 12009 34518 12009 12008 34519 12008 12006 34520 12006 12011 34521 12011 12008 34522 12008 12009 34523 12009 12011 34524 12011 12010 34525 12010 12008 34526 12008 12013 34527 12013 12010 34528 12010 12011 34529 12011 12013 34530 12013 12012 34531 12012 12010 34532 12010 12014 34533 12014 12012 34534 12012 12013 34535 12013 12016 34536 12016 12012 34537 12012 12014 34538 12014 12016 34539 12016 12015 34540 12015 12012 34541 12012 12018 34542 12018 12015 34543 12015 12016 34544 12016 12018 34545 12018 12017 34546 12017 12015 34547 12015 12001 34548 12001 12017 34549 12017 12018 34550 12018 12035 34551 12035 12019 34552 12019 12020 34553 12020 12023 34554 12023 12021 34555 12021 12022 34556 12022 12024 34557 12024 12021 34558 12021 12023 34559 12023 12027 34560 12027 12021 34561 12021 12024 34562 12024 12027 34563 12027 12025 34564 12025 12021 34565 12021 12027 34566 12027 12026 34567 12026 12025 34568 12025 12028 34569 12028 12026 34570 12026 12027 34571 12027 12031 34572 12031 12026 34573 12026 12028 34574 12028 12031 34575 12031 12029 34576 12029 12026 34577 12026 12031 34578 12031 12030 34579 12030 12029 34580 12029 12033 34581 12033 12030 34582 12030 12031 34583 12031 12033 34584 12033 12032 34585 12032 12030 34586 12030 12034 34587 12034 12032 34588 12032 12033 34589 12033 12036 34590 12036 12032 34591 12032 12034 34592 12034 12036 34593 12036 12035 34594 12035 12032 34595 12032 12019 34596 12019 12035 34597 12035 12036 34598 12036 12052 34599 12052 12037 34600 12037 12038 34601 12038 12041 34602 12041 12039 34603 12039 12040 34604 12040 12043 34605 12043 12039 34606 12039 12041 34607 12041 12043 34608 12043 12042 34609 12042 12039 34610 12039 12044 34611 12044 12042 34612 12042 12043 34613 12043 12046 34614 12046 12042 34615 12042 12044 34616 12044 12046 34617 12046 12045 34618 12045 12042 34619 12042 12049 34620 12049 12045 34621 12045 12046 34622 12046 12049 34623 12049 12047 34624 12047 12045 34625 12045 12049 34626 12049 12048 34627 12048 12047 34628 12047 12050 34629 12050 12048 34630 12048 12049 34631 12049 12053 34632 12053 12048 34633 12048 12050 34634 12050 12053 34635 12053 12051 34636 12051 12048 34637 12048 12053 34638 12053 12052 34639 12052 12051 34640 12051 12054 34641 12054 12052 34642 12052 12053 34643 12053 12037 34644 12037 12052 34645 12052 12054 34646 12054 12072 34647 12072 12055 34648 12055 12056 34649 12056 12059 34650 12059 12057 34651 12057 12058 34652 12058 12061 34653 12061 12057 34654 12057 12059 34655 12059 12061 34656 12061 12060 34657 12060 12057 34658 12057 12063 34659 12063 12060 34660 12060 12061 34661 12061 12063 34662 12063 12062 34663 12062 12060 34664 12060 12065 34665 12065 12062 34666 12062 12063 34667 12063 12065 34668 12065 12064 34669 12064 12062 34670 12062 12067 34671 12067 12064 34672 12064 12065 34673 12065 12067 34674 12067 12066 34675 12066 12064 34676 12064 12069 34677 12069 12066 34678 12066 12067 34679 12067 12069 34680 12069 12068 34681 12068 12066 34682 12066 12070 34683 12070 12068 34684 12068 12069 34685 12069 12055 34686 12055 12068 34687 12068 12070 34688 12070 12055 34689 12055 12071 34690 12071 12068 34691 12068 12055 34692 12055 12072 34693 12072 12071 34694 12071 12090 34695 12090 12073 34696 12073 12074 34697 12074 12077 34698 12077 12075 34699 12075 12076 34700 12076 12079 34701 12079 12075 34702 12075 12077 34703 12077 12079 34704 12079 12078 34705 12078 12075 34706 12075 12081 34707 12081 12078 34708 12078 12079 34709 12079 12081 34710 12081 12080 34711 12080 12078 34712 12078 12083 34713 12083 12080 34714 12080 12081 34715 12081 12083 34716 12083 12082 34717 12082 12080 34718 12080 12085 34719 12085 12082 34720 12082 12083 34721 12083 12085 34722 12085 12084 34723 12084 12082 34724 12082 12087 34725 12087 12084 34726 12084 12085 34727 12085 12087 34728 12087 12086 34729 12086 12084 34730 12084 12089 34731 12089 12086 34732 12086 12087 34733 12087 12089 34734 12089 12088 34735 12088 12086 34736 12086 12073 34737 12073 12088 34738 12088 12089 34739 12089 12073 34740 12073 12090 34741 12090 12088 34742 12088 12107 34743 12107 12091 34744 12091 12092 34745 12092 12096 34746 12096 12093 34747 12093 12094 34748 12094 12096 34749 12096 12095 34750 12095 12093 34751 12093 12099 34752 12099 12095 34753 12095 12096 34754 12096 12099 34755 12099 12097 34756 12097 12095 34757 12095 12099 34758 12099 12098 34759 12098 12097 34760 12097 12100 34761 12100 12098 34762 12098 12099 34763 12099 12102 34764 12102 12098 34765 12098 12100 34766 12100 12102 34767 12102 12101 34768 12101 12098 34769 12098 12104 34770 12104 12101 34771 12101 12102 34772 12102 12104 34773 12104 12103 34774 12103 12101 34775 12101 12106 34776 12106 12103 34777 12103 12104 34778 12104 12106 34779 12106 12105 34780 12105 12103 34781 12103 12108 34782 12108 12105 34783 12105 12106 34784 12106 12108 34785 12108 12107 34786 12107 12105 34787 12105 12091 34788 12091 12107 34789 12107 12108 34790 12108 12126 34791 12126 12109 34792 12109 12110 34793 12110 12113 34794 12113 12111 34795 12111 12112 34796 12112 12115 34797 12115 12111 34798 12111 12113 34799 12113 12115 34800 12115 12114 34801 12114 12111 34802 12111 12117 34803 12117 12114 34804 12114 12115 34805 12115 12117 34806 12117 12116 34807 12116 12114 34808 12114 12119 34809 12119 12116 34810 12116 12117 34811 12117 12119 34812 12119 12118 34813 12118 12116 34814 12116 12121 34815 12121 12118 34816 12118 12119 34817 12119 12121 34818 12121 12120 34819 12120 12118 34820 12118 12123 34821 12123 12120 34822 12120 12121 34823 12121 12123 34824 12123 12122 34825 12122 12120 34826 12120 12124 34827 12124 12122 34828 12122 12123 34829 12123 12109 34830 12109 12122 34831 12122 12124 34832 12124 12109 34833 12109 12125 34834 12125 12122 34835 12122 12109 34836 12109 12126 34837 12126 12125 34838 12125 12142 34839 12142 12127 34840 12127 12128 34841 12128 12131 34842 12131 12129 34843 12129 12130 34844 12130 12133 34845 12133 12129 34846 12129 12131 34847 12131 12133 34848 12133 12132 34849 12132 12129 34850 12129 12135 34851 12135 12132 34852 12132 12133 34853 12133 12135 34854 12135 12134 34855 12134 12132 34856 12132 12136 34857 12136 12134 34858 12134 12135 34859 12135 12138 34860 12138 12134 34861 12134 12136 34862 12136 12138 34863 12138 12137 34864 12137 12134 34865 12134 12141 34866 12141 12137 34867 12137 12138 34868 12138 12141 34869 12141 12139 34870 12139 12137 34871 12137 12141 34872 12141 12140 34873 12140 12139 34874 12139 12143 34875 12143 12140 34876 12140 12141 34877 12141 12143 34878 12143 12142 34879 12142 12140 34880 12140 12144 34881 12144 12142 34882 12142 12143 34883 12143 12127 34884 12127 12142 34885 12142 12144 34886 12144 12160 34887 12160 12145 34888 12145 12146 34889 12146 12149 34890 12149 12147 34891 12147 12148 34892 12148 12150 34893 12150 12147 34894 12147 12149 34895 12149 12152 34896 12152 12147 34897 12147 12150 34898 12150 12152 34899 12152 12151 34900 12151 12147 34901 12147 12154 34902 12154 12151 34903 12151 12152 34904 12152 12154 34905 12154 12153 34906 12153 12151 34907 12151 12156 34908 12156 12153 34909 12153 12154 34910 12154 12156 34911 12156 12155 34912 12155 12153 34913 12153 12159 34914 12159 12155 34915 12155 12156 34916 12156 12159 34917 12159 12157 34918 12157 12155 34919 12155 12159 34920 12159 12158 34921 12158 12157 34922 12157 12161 34923 12161 12158 34924 12158 12159 34925 12159 12161 34926 12161 12160 34927 12160 12158 34928 12158 12162 34929 12162 12160 34930 12160 12161 34931 12161 12145 34932 12145 12160 34933 12160 12162 34934 12162 12179 34935 12179 12163 34936 12163 12164 34937 12164 12169 34938 12169 12165 34939 12165 12166 34940 12166 12169 34941 12169 12167 34942 12167 12165 34943 12165 12169 34944 12169 12168 34945 12168 12167 34946 12167 12171 34947 12171 12168 34948 12168 12169 34949 12169 12171 34950 12171 12170 34951 12170 12168 34952 12168 12172 34953 12172 12170 34954 12170 12171 34955 12171 12174 34956 12174 12170 34957 12170 12172 34958 12172 12174 34959 12174 12173 34960 12173 12170 34961 12170 12177 34962 12177 12173 34963 12173 12174 34964 12174 12177 34965 12177 12175 34966 12175 12173 34967 12173 12177 34968 12177 12176 34969 12176 12175 34970 12175 12178 34971 12178 12176 34972 12176 12177 34973 12177 12180 34974 12180 12176 34975 12176 12178 34976 12178 12180 34977 12180 12179 34978 12179 12176 34979 12176 12163 34980 12163 12179 34981 12179 12180 34982 12180 12198 34983 12198 12181 34984 12181 12186 34985 12186 12185 34986 12185 12182 34987 12182 12183 34988 12183 12185 34989 12185 12184 34990 12184 12182 34991 12182 12198 34992 12198 12184 34993 12184 12185 34994 12185 12198 34995 12198 12186 34996 12186 12184 34997 12184 12190 34998 12190 12187 34999 12187 12188 35000 12188 12190 35001 12190 12189 35002 12189 12187 35003 12187 12193 35004 12193 12189 35005 12189 12190 35006 12190 12193 35007 12193 12191 35008 12191 12189 35009 12189 12193 35010 12193 12192 35011 12192 12191 35012 12191 12195 35013 12195 12192 35014 12192 12193 35015 12193 12195 35016 12195 12194 35017 12194 12192 35018 12192 12197 35019 12197 12194 35020 12194 12195 35021 12195 12197 35022 12197 12196 35023 12196 12194 35024 12194 12181 35025 12181 12196 35026 12196 12197 35027 12197 12181 35028 12181 12198 35029 12198 12196 35030 12196 12216 35031 12216 12199 35032 12199 12200 35033 12200 12204 35034 12204 12201 35035 12201 12202 35036 12202 12204 35037 12204 12203 35038 12203 12201 35039 12201 12207 35040 12207 12203 35041 12203 12204 35042 12204 12207 35043 12207 12205 35044 12205 12203 35045 12203 12207 35046 12207 12206 35047 12206 12205 35048 12205 12208 35049 12208 12206 35050 12206 12207 35051 12207 12211 35052 12211 12206 35053 12206 12208 35054 12208 12211 35055 12211 12209 35056 12209 12206 35057 12206 12211 35058 12211 12210 35059 12210 12209 35060 12209 12213 35061 12213 12210 35062 12210 12211 35063 12211 12213 35064 12213 12212 35065 12212 12210 35066 12210 12215 35067 12215 12212 35068 12212 12213 35069 12213 12215 35070 12215 12214 35071 12214 12212 35072 12212 12199 35073 12199 12214 35074 12214 12215 35075 12215 12199 35076 12199 12216 35077 12216 12214 35078 12214 12219 35079 12219 12217 35080 12217 12218 35081 12218 12217 35082 12217 12219 35083 12219 12220 35084 12220 12223 35085 12223 12221 35086 12221 12222 35087 12222 12221 35088 12221 12223 35089 12223 12224 35090 12224 12227 35091 12227 12225 35092 12225 12226 35093 12226 12225 35094 12225 12227 35095 12227 12228 35096 12228 12231 35097 12231 12229 35098 12229 12230 35099 12230 12229 35100 12229 12231 35101 12231 12232 35102 12232 12235 35103 12235 12233 35104 12233 12234 35105 12234 12233 35106 12233 12235 35107 12235 12236 35108 12236 12239 35109 12239 12237 35110 12237 12238 35111 12238 12237 35112 12237 12239 35113 12239 12240 35114 12240 12243 35115 12243 12241 35116 12241 12242 35117 12242 12241 35118 12241 12243 35119 12243 12244 35120 12244 12247 35121 12247 12245 35122 12245 12246 35123 12246 12245 35124 12245 12247 35125 12247 12248 35126 12248 12251 35127 12251 12249 35128 12249 12250 35129 12250 12249 35130 12249 12251 35131 12251 12252 35132 12252 12255 35133 12255 12253 35134 12253 12254 35135 12254 12253 35136 12253 12255 35137 12255 12256 35138 12256 12259 35139 12259 12257 35140 12257 12258 35141 12258 12257 35142 12257 12259 35143 12259 12260 35144 12260 12263 35145 12263 12261 35146 12261 12262 35147 12262 12261 35148 12261 12263 35149 12263 12264 35150 12264 12267 35151 12267 12265 35152 12265 12266 35153 12266 12265 35154 12265 12267 35155 12267 12268 35156 12268 12271 35157 12271 12269 35158 12269 12270 35159 12270 12269 35160 12269 12271 35161 12271 12272 35162 12272 12275 35163 12275 12273 35164 12273 12274 35165 12274 12273 35166 12273 12275 35167 12275 12276 35168 12276 12279 35169 12279 12277 35170 12277 12278 35171 12278 12277 35172 12277 12279 35173 12279 12280 35174 12280 12297 35175 12297 12281 35176 12281 12282 35177 12282 12285 35178 12285 12283 35179 12283 12284 35180 12284 12286 35181 12286 12283 35182 12283 12285 35183 12285 12289 35184 12289 12283 35185 12283 12286 35186 12286 12289 35187 12289 12287 35188 12287 12283 35189 12283 12289 35190 12289 12288 35191 12288 12287 35192 12287 12290 35193 12290 12288 35194 12288 12289 35195 12289 12293 35196 12293 12288 35197 12288 12290 35198 12290 12293 35199 12293 12291 35200 12291 12288 35201 12288 12293 35202 12293 12292 35203 12292 12291 35204 12291 12295 35205 12295 12292 35206 12292 12293 35207 12293 12295 35208 12295 12294 35209 12294 12292 35210 12292 12296 35211 12296 12294 35212 12294 12295 35213 12295 12298 35214 12298 12294 35215 12294 12296 35216 12296 12298 35217 12298 12297 35218 12297 12294 35219 12294 12281 35220 12281 12297 35221 12297 12298 35222 12298 12316 35223 12316 12299 35224 12299 12312 35225 12312 12302 35226 12302 12300 35227 12300 12301 35228 12301 12303 35229 12303 12300 35230 12300 12302 35231 12302 12306 35232 12306 12300 35233 12300 12303 35234 12303 12306 35235 12306 12304 35236 12304 12300 35237 12300 12306 35238 12306 12305 35239 12305 12304 35240 12304 12307 35241 12307 12305 35242 12305 12306 35243 12306 12310 35244 12310 12305 35245 12305 12307 35246 12307 12310 35247 12310 12308 35248 12308 12305 35249 12305 12310 35250 12310 12309 35251 12309 12308 35252 12308 12311 35253 12311 12309 35254 12309 12310 35255 12310 12316 35256 12316 12309 35257 12309 12311 35258 12311 12316 35259 12316 12312 35260 12312 12309 35261 12309 12299 35262 12299 12313 35263 12313 12314 35264 12314 12299 35265 12299 12315 35266 12315 12313 35267 12313 12299 35268 12299 12316 35269 12316 12315 35270 12315 12333 35271 12333 12317 35272 12317 12318 35273 12318 12322 35274 12322 12319 35275 12319 12320 35276 12320 12322 35277 12322 12321 35278 12321 12319 35279 12319 12325 35280 12325 12321 35281 12321 12322 35282 12322 12325 35283 12325 12323 35284 12323 12321 35285 12321 12325 35286 12325 12324 35287 12324 12323 35288 12323 12327 35289 12327 12324 35290 12324 12325 35291 12325 12327 35292 12327 12326 35293 12326 12324 35294 12324 12329 35295 12329 12326 35296 12326 12327 35297 12327 12329 35298 12329 12328 35299 12328 12326 35300 12326 12330 35301 12330 12328 35302 12328 12329 35303 12329 12332 35304 12332 12328 35305 12328 12330 35306 12330 12332 35307 12332 12331 35308 12331 12328 35309 12328 12334 35310 12334 12331 35311 12331 12332 35312 12332 12334 35313 12334 12333 35314 12333 12331 35315 12331 12317 35316 12317 12333 35317 12333 12334 35318 12334 12351 35319 12351 12335 35320 12335 12336 35321 12336 12339 35322 12339 12337 35323 12337 12338 35324 12338 12340 35325 12340 12337 35326 12337 12339 35327 12339 12343 35328 12343 12337 35329 12337 12340 35330 12340 12343 35331 12343 12341 35332 12341 12337 35333 12337 12343 35334 12343 12342 35335 12342 12341 35336 12341 12344 35337 12344 12342 35338 12342 12343 35339 12343 12347 35340 12347 12342 35341 12342 12344 35342 12344 12347 35343 12347 12345 35344 12345 12342 35345 12342 12347 35346 12347 12346 35347 12346 12345 35348 12345 12348 35349 12348 12346 35350 12346 12347 35351 12347 12350 35352 12350 12346 35353 12346 12348 35354 12348 12350 35355 12350 12349 35356 12349 12346 35357 12346 12352 35358 12352 12349 35359 12349 12350 35360 12350 12352 35361 12352 12351 35362 12351 12349 35363 12349 12335 35364 12335 12351 35365 12351 12352 35366 12352 12370 35367 12370 12353 35368 12353 12354 35369 12354 12358 35370 12358 12355 35371 12355 12356 35372 12356 12358 35373 12358 12357 35374 12357 12355 35375 12355 12360 35376 12360 12357 35377 12357 12358 35378 12358 12360 35379 12360 12359 35380 12359 12357 35381 12357 12363 35382 12363 12359 35383 12359 12360 35384 12360 12363 35385 12363 12361 35386 12361 12359 35387 12359 12363 35388 12363 12362 35389 12362 12361 35390 12361 12364 35391 12364 12362 35392 12362 12363 35393 12363 12366 35394 12366 12362 35395 12362 12364 35396 12364 12366 35397 12366 12365 35398 12365 12362 35399 12362 12368 35400 12368 12365 35401 12365 12366 35402 12366 12368 35403 12368 12367 35404 12367 12365 35405 12365 12353 35406 12353 12367 35407 12367 12368 35408 12368 12353 35409 12353 12369 35410 12369 12367 35411 12367 12353 35412 12353 12370 35413 12370 12369 35414 12369 12387 35415 12387 12371 35416 12371 12372 35417 12372 12376 35418 12376 12373 35419 12373 12374 35420 12374 12376 35421 12376 12375 35422 12375 12373 35423 12373 12378 35424 12378 12375 35425 12375 12376 35426 12376 12378 35427 12378 12377 35428 12377 12375 35429 12375 12380 35430 12380 12377 35431 12377 12378 35432 12378 12380 35433 12380 12379 35434 12379 12377 35435 12377 12382 35436 12382 12379 35437 12379 12380 35438 12380 12382 35439 12382 12381 35440 12381 12379 35441 12379 12385 35442 12385 12381 35443 12381 12382 35444 12382 12385 35445 12385 12383 35446 12383 12381 35447 12381 12385 35448 12385 12384 35449 12384 12383 35450 12383 12386 35451 12386 12384 35452 12384 12385 35453 12385 12388 35454 12388 12384 35455 12384 12386 35456 12386 12388 35457 12388 12387 35458 12387 12384 35459 12384 12371 35460 12371 12387 35461 12387 12388 35462 12388 12406 35463 12406 12389 35464 12389 12390 35465 12390 12393 35466 12393 12391 35467 12391 12392 35468 12392 12395 35469 12395 12391 35470 12391 12393 35471 12393 12395 35472 12395 12394 35473 12394 12391 35474 12391 12396 35475 12396 12394 35476 12394 12395 35477 12395 12398 35478 12398 12394 35479 12394 12396 35480 12396 12398 35481 12398 12397 35482 12397 12394 35483 12394 12401 35484 12401 12397 35485 12397 12398 35486 12398 12401 35487 12401 12399 35488 12399 12397 35489 12397 12401 35490 12401 12400 35491 12400 12399 35492 12399 12402 35493 12402 12400 35494 12400 12401 35495 12401 12404 35496 12404 12400 35497 12400 12402 35498 12402 12404 35499 12404 12403 35500 12403 12400 35501 12400 12389 35502 12389 12403 35503 12403 12404 35504 12404 12389 35505 12389 12405 35506 12405 12403 35507 12403 12389 35508 12389 12406 35509 12406 12405 35510 12405 12422 35511 12422 12408 35512 12408 12407 35513 12407 12410 35514 12410 12408 35515 12408 12409 35516 12409 12407 35517 12407 12408 35518 12408 12410 35519 12410 12414 35520 12414 12411 35521 12411 12412 35522 12412 12414 35523 12414 12413 35524 12413 12411 35525 12411 12417 35526 12417 12413 35527 12413 12414 35528 12414 12417 35529 12417 12415 35530 12415 12413 35531 12413 12417 35532 12417 12416 35533 12416 12415 35534 12415 12418 35535 12418 12416 35536 12416 12417 35537 12417 12420 35538 12420 12416 35539 12416 12418 35540 12418 12420 35541 12420 12419 35542 12419 12416 35543 12416 12423 35544 12423 12419 35545 12419 12420 35546 12420 12423 35547 12423 12421 35548 12421 12419 35549 12419 12423 35550 12423 12422 35551 12422 12421 35552 12421 12424 35553 12424 12422 35554 12422 12423 35555 12423 12408 35556 12408 12422 35557 12422 12424 35558 12424 12442 35559 12442 12425 35560 12425 12426 35561 12426 12429 35562 12429 12427 35563 12427 12428 35564 12428 12431 35565 12431 12427 35566 12427 12429 35567 12429 12431 35568 12431 12430 35569 12430 12427 35570 12427 12432 35571 12432 12430 35572 12430 12431 35573 12431 12435 35574 12435 12430 35575 12430 12432 35576 12432 12435 35577 12435 12433 35578 12433 12430 35579 12430 12435 35580 12435 12434 35581 12434 12433 35582 12433 12436 35583 12436 12434 35584 12434 12435 35585 12435 12439 35586 12439 12434 35587 12434 12436 35588 12436 12439 35589 12439 12437 35590 12437 12434 35591 12434 12439 35592 12439 12438 35593 12438 12437 35594 12437 12440 35595 12440 12438 35596 12438 12439 35597 12439 12425 35598 12425 12438 35599 12438 12440 35600 12440 12425 35601 12425 12441 35602 12441 12438 35603 12438 12425 35604 12425 12442 35605 12442 12441 35606 12441 12460 35607 12460 12443 35608 12443 12444 35609 12444 12447 35610 12447 12445 35611 12445 12446 35612 12446 12448 35613 12448 12445 35614 12445 12447 35615 12447 12451 35616 12451 12445 35617 12445 12448 35618 12448 12451 35619 12451 12449 35620 12449 12445 35621 12445 12451 35622 12451 12450 35623 12450 12449 35624 12449 12452 35625 12452 12450 35626 12450 12451 35627 12451 12455 35628 12455 12450 35629 12450 12452 35630 12452 12455 35631 12455 12453 35632 12453 12450 35633 12450 12455 35634 12455 12454 35635 12454 12453 35636 12453 12457 35637 12457 12454 35638 12454 12455 35639 12455 12457 35640 12457 12456 35641 12456 12454 35642 12454 12458 35643 12458 12456 35644 12456 12457 35645 12457 12443 35646 12443 12456 35647 12456 12458 35648 12458 12443 35649 12443 12459 35650 12459 12456 35651 12456 12443 35652 12443 12460 35653 12460 12459 35654 12459 12477 35655 12477 12461 35656 12461 12462 35657 12462 12465 35658 12465 12463 35659 12463 12464 35660 12464 12466 35661 12466 12463 35662 12463 12465 35663 12465 12469 35664 12469 12463 35665 12463 12466 35666 12466 12469 35667 12469 12467 35668 12467 12463 35669 12463 12469 35670 12469 12468 35671 12468 12467 35672 12467 12471 35673 12471 12468 35674 12468 12469 35675 12469 12471 35676 12471 12470 35677 12470 12468 35678 12468 12473 35679 12473 12470 35680 12470 12471 35681 12471 12473 35682 12473 12472 35683 12472 12470 35684 12470 12475 35685 12475 12472 35686 12472 12473 35687 12473 12475 35688 12475 12474 35689 12474 12472 35690 12472 12476 35691 12476 12474 35692 12474 12475 35693 12475 12478 35694 12478 12474 35695 12474 12476 35696 12476 12478 35697 12478 12477 35698 12477 12474 35699 12474 12461 35700 12461 12477 35701 12477 12478 35702 12478 12495 35703 12495 12479 35704 12479 12493 35705 12493 12484 35706 12484 12480 35707 12480 12481 35708 12481 12484 35709 12484 12482 35710 12482 12480 35711 12480 12484 35712 12484 12483 35713 12483 12482 35714 12482 12485 35715 12485 12483 35716 12483 12484 35717 12484 12487 35718 12487 12483 35719 12483 12485 35720 12485 12487 35721 12487 12486 35722 12486 12483 35723 12483 12489 35724 12489 12486 35725 12486 12487 35726 12487 12489 35727 12489 12488 35728 12488 12486 35729 12486 12492 35730 12492 12488 35731 12488 12489 35732 12489 12492 35733 12492 12490 35734 12490 12488 35735 12488 12492 35736 12492 12491 35737 12491 12490 35738 12490 12494 35739 12494 12491 35740 12491 12492 35741 12492 12494 35742 12494 12493 35743 12493 12491 35744 12491 12495 35745 12495 12493 35746 12493 12494 35747 12494 12479 35748 12479 12495 35749 12495 12496 35750 12496 12514 35751 12514 12497 35752 12497 12503 35753 12503 12501 35754 12501 12498 35755 12498 12499 35756 12499 12501 35757 12501 12500 35758 12500 12498 35759 12498 12504 35760 12504 12500 35761 12500 12501 35762 12501 12504 35763 12504 12502 35764 12502 12500 35765 12500 12504 35766 12504 12503 35767 12503 12502 35768 12502 12514 35769 12514 12503 35770 12503 12504 35771 12504 12507 35772 12507 12505 35773 12505 12506 35774 12506 12508 35775 12508 12505 35776 12505 12507 35777 12507 12510 35778 12510 12505 35779 12505 12508 35780 12508 12510 35781 12510 12509 35782 12509 12505 35783 12505 12512 35784 12512 12509 35785 12509 12510 35786 12510 12512 35787 12512 12511 35788 12511 12509 35789 12509 12497 35790 12497 12511 35791 12511 12512 35792 12512 12497 35793 12497 12513 35794 12513 12511 35795 12511 12497 35796 12497 12514 35797 12514 12513 35798 12513 12532 35799 12532 12515 35800 12515 12522 35801 12522 12518 35802 12518 12516 35803 12516 12517 35804 12517 12520 35805 12520 12516 35806 12516 12518 35807 12518 12520 35808 12520 12519 35809 12519 12516 35810 12516 12521 35811 12521 12519 35812 12519 12520 35813 12520 12532 35814 12532 12519 35815 12519 12521 35816 12521 12532 35817 12532 12522 35818 12522 12519 35819 12519 12525 35820 12525 12523 35821 12523 12524 35822 12524 12526 35823 12526 12523 35824 12523 12525 35825 12525 12528 35826 12528 12523 35827 12523 12526 35828 12526 12528 35829 12528 12527 35830 12527 12523 35831 12523 12530 35832 12530 12527 35833 12527 12528 35834 12528 12530 35835 12530 12529 35836 12529 12527 35837 12527 12515 35838 12515 12529 35839 12529 12530 35840 12530 12515 35841 12515 12531 35842 12531 12529 35843 12529 12515 35844 12515 12532 35845 12532 12531 35846 12531 12550 35847 12550 12533 35848 12533 12534 35849 12534 12537 35850 12537 12535 35851 12535 12536 35852 12536 12539 35853 12539 12535 35854 12535 12537 35855 12537 12539 35856 12539 12538 35857 12538 12535 35858 12535 12541 35859 12541 12538 35860 12538 12539 35861 12539 12541 35862 12541 12540 35863 12540 12538 35864 12538 12543 35865 12543 12540 35866 12540 12541 35867 12541 12543 35868 12543 12542 35869 12542 12540 35870 12540 12544 35871 12544 12542 35872 12542 12543 35873 12543 12547 35874 12547 12542 35875 12542 12544 35876 12544 12547 35877 12547 12545 35878 12545 12542 35879 12542 12547 35880 12547 12546 35881 12546 12545 35882 12545 12548 35883 12548 12546 35884 12546 12547 35885 12547 12533 35886 12533 12546 35887 12546 12548 35888 12548 12533 35889 12533 12549 35890 12549 12546 35891 12546 12533 35892 12533 12550 35893 12550 12549 35894 12549 12566 35895 12566 12558 35896 12558 12551 35897 12551 12555 35898 12555 12552 35899 12552 12553 35900 12553 12555 35901 12555 12554 35902 12554 12552 35903 12552 12557 35904 12557 12554 35905 12554 12555 35906 12555 12557 35907 12557 12556 35908 12556 12554 35909 12554 12551 35910 12551 12556 35911 12556 12557 35912 12557 12551 35913 12551 12558 35914 12558 12556 35915 12556 12561 35916 12561 12559 35917 12559 12560 35918 12560 12562 35919 12562 12559 35920 12559 12561 35921 12561 12565 35922 12565 12559 35923 12559 12562 35924 12562 12565 35925 12565 12563 35926 12563 12559 35927 12559 12565 35928 12565 12564 35929 12564 12563 35930 12563 12567 35931 12567 12564 35932 12564 12565 35933 12565 12567 35934 12567 12566 35935 12566 12564 35936 12564 12568 35937 12568 12566 35938 12566 12567 35939 12567 12558 35940 12558 12566 35941 12566 12568 35942 12568 12585 35943 12585 12577 35944 12577 12569 35945 12569 12573 35946 12573 12570 35947 12570 12571 35948 12571 12573 35949 12573 12572 35950 12572 12570 35951 12570 12575 35952 12575 12572 35953 12572 12573 35954 12573 12575 35955 12575 12574 35956 12574 12572 35957 12572 12578 35958 12578 12574 35959 12574 12575 35960 12575 12578 35961 12578 12576 35962 12576 12574 35963 12574 12578 35964 12578 12577 35965 12577 12576 35966 12576 12569 35967 12569 12577 35968 12577 12578 35969 12578 12581 35970 12581 12579 35971 12579 12580 35972 12580 12583 35973 12583 12579 35974 12579 12581 35975 12581 12583 35976 12583 12582 35977 12582 12579 35978 12579 12584 35979 12584 12582 35980 12582 12583 35981 12583 12586 35982 12586 12582 35983 12582 12584 35984 12584 12586 35985 12586 12585 35986 12585 12582 35987 12582 12577 35988 12577 12585 35989 12585 12586 35990 12586 12603 35991 12603 12587 35992 12587 12588 35993 12588 12591 35994 12591 12589 35995 12589 12590 35996 12590 12593 35997 12593 12589 35998 12589 12591 35999 12591 12593 36000 12593 12592 36001 12592 12589 36002 12589 12594 36003 12594 12592 36004 12592 12593 36005 12593 12596 36006 12596 12592 36007 12592 12594 36008 12594 12596 36009 12596 12595 36010 12595 12592 36011 12592 12599 36012 12599 12595 36013 12595 12596 36014 12596 12599 36015 12599 12597 36016 12597 12595 36017 12595 12599 36018 12599 12598 36019 12598 12597 36020 12597 12600 36021 12600 12598 36022 12598 12599 36023 12599 12602 36024 12602 12598 36025 12598 12600 36026 12600 12602 36027 12602 12601 36028 12601 12598 36029 12598 12604 36030 12604 12601 36031 12601 12602 36032 12602 12604 36033 12604 12603 36034 12603 12601 36035 12601 12587 36036 12587 12603 36037 12603 12604 36038 12604 12622 36039 12622 12605 36040 12605 12611 36041 12611 12608 36042 12608 12606 36043 12606 12607 36044 12607 12610 36045 12610 12606 36046 12606 12608 36047 12608 12610 36048 12610 12609 36049 12609 12606 36050 12606 12612 36051 12612 12609 36052 12609 12610 36053 12610 12612 36054 12612 12611 36055 12611 12609 36056 12609 12622 36057 12622 12611 36058 12611 12612 36059 12612 12615 36060 12615 12613 36061 12613 12614 36062 12614 12616 36063 12616 12613 36064 12613 12615 36065 12615 12618 36066 12618 12613 36067 12613 12616 36068 12616 12618 36069 12618 12617 36070 12617 12613 36071 12613 12620 36072 12620 12617 36073 12617 12618 36074 12618 12620 36075 12620 12619 36076 12619 12617 36077 12617 12605 36078 12605 12619 36079 12619 12620 36080 12620 12605 36081 12605 12621 36082 12621 12619 36083 12619 12605 36084 12605 12622 36085 12622 12621 36086 12621 12639 36087 12639 12623 36088 12623 12624 36089 12624 12627 36090 12627 12625 36091 12625 12626 36092 12626 12628 36093 12628 12625 36094 12625 12627 36095 12627 12631 36096 12631 12625 36097 12625 12628 36098 12628 12631 36099 12631 12629 36100 12629 12625 36101 12625 12631 36102 12631 12630 36103 12630 12629 36104 12629 12633 36105 12633 12630 36106 12630 12631 36107 12631 12633 36108 12633 12632 36109 12632 12630 36110 12630 12634 36111 12634 12632 36112 12632 12633 36113 12633 12637 36114 12637 12632 36115 12632 12634 36116 12634 12637 36117 12637 12635 36118 12635 12632 36119 12632 12637 36120 12637 12636 36121 12636 12635 36122 12635 12638 36123 12638 12636 36124 12636 12637 36125 12637 12640 36126 12640 12636 36127 12636 12638 36128 12638 12640 36129 12640 12639 36130 12639 12636 36131 12636 12623 36132 12623 12639 36133 12639 12640 36134 12640 12658 36135 12658 12641 36136 12641 12642 36137 12642 12645 36138 12645 12643 36139 12643 12644 36140 12644 12646 36141 12646 12643 36142 12643 12645 36143 12645 12648 36144 12648 12643 36145 12643 12646 36146 12646 12648 36147 12648 12647 36148 12647 12643 36149 12643 12650 36150 12650 12647 36151 12647 12648 36152 12648 12650 36153 12650 12649 36154 12649 12647 36155 12647 12653 36156 12653 12649 36157 12649 12650 36158 12650 12653 36159 12653 12651 36160 12651 12649 36161 12649 12653 36162 12653 12652 36163 12652 12651 36164 12651 12654 36165 12654 12652 36166 12652 12653 36167 12653 12657 36168 12657 12652 36169 12652 12654 36170 12654 12657 36171 12657 12655 36172 12655 12652 36173 12652 12657 36174 12657 12656 36175 12656 12655 36176 12655 12641 36177 12641 12656 36178 12656 12657 36179 12657 12641 36180 12641 12658 36181 12658 12656 36182 12656 12676 36183 12676 12659 36184 12659 12660 36185 12660 12665 36186 12665 12661 36187 12661 12662 36188 12662 12665 36189 12665 12663 36190 12663 12661 36191 12661 12665 36192 12665 12664 36193 12664 12663 36194 12663 12667 36195 12667 12664 36196 12664 12665 36197 12665 12667 36198 12667 12666 36199 12666 12664 36200 12664 12669 36201 12669 12666 36202 12666 12667 36203 12667 12669 36204 12669 12668 36205 12668 12666 36206 12666 12670 36207 12670 12668 36208 12668 12669 36209 12669 12673 36210 12673 12668 36211 12668 12670 36212 12670 12673 36213 12673 12671 36214 12671 12668 36215 12668 12673 36216 12673 12672 36217 12672 12671 36218 12671 12675 36219 12675 12672 36220 12672 12673 36221 12673 12675 36222 12675 12674 36223 12674 12672 36224 12672 12659 36225 12659 12674 36226 12674 12675 36227 12675 12659 36228 12659 12676 36229 12676 12674 36230 12674 12693 36231 12693 12677 36232 12677 12678 36233 12678 12682 36234 12682 12679 36235 12679 12680 36236 12680 12682 36237 12682 12681 36238 12681 12679 36239 12679 12684 36240 12684 12681 36241 12681 12682 36242 12682 12684 36243 12684 12683 36244 12683 12681 36245 12681 12687 36246 12687 12683 36247 12683 12684 36248 12684 12687 36249 12687 12685 36250 12685 12683 36251 12683 12687 36252 12687 12686 36253 12686 12685 36254 12685 12689 36255 12689 12686 36256 12686 12687 36257 12687 12689 36258 12689 12688 36259 12688 12686 36260 12686 12690 36261 12690 12688 36262 12688 12689 36263 12689 12692 36264 12692 12688 36265 12688 12690 36266 12690 12692 36267 12692 12691 36268 12691 12688 36269 12688 12694 36270 12694 12691 36271 12691 12692 36272 12692 12694 36273 12694 12693 36274 12693 12691 36275 12691 12677 36276 12677 12693 36277 12693 12694 36278 12694 12712 36279 12712 12695 36280 12695 12699 36281 12699 12700 36282 12700 12696 36283 12696 12697 36284 12697 12700 36285 12700 12698 36286 12698 12696 36287 12696 12700 36288 12700 12699 36289 12699 12698 36290 12698 12712 36291 12712 12699 36292 12699 12700 36293 12700 12703 36294 12703 12701 36295 12701 12702 36296 12702 12704 36297 12704 12701 36298 12701 12703 36299 12703 12707 36300 12707 12701 36301 12701 12704 36302 12704 12707 36303 12707 12705 36304 12705 12701 36305 12701 12707 36306 12707 12706 36307 12706 12705 36308 12705 12708 36309 12708 12706 36310 12706 12707 36311 12707 12710 36312 12710 12706 36313 12706 12708 36314 12708 12710 36315 12710 12709 36316 12709 12706 36317 12706 12695 36318 12695 12709 36319 12709 12710 36320 12710 12695 36321 12695 12711 36322 12711 12709 36323 12709 12695 36324 12695 12712 36325 12712 12711 36326 12711 12729 36327 12729 12713 36328 12713 12714 36329 12714 12718 36330 12718 12715 36331 12715 12716 36332 12716 12718 36333 12718 12717 36334 12717 12715 36335 12715 12720 36336 12720 12717 36337 12717 12718 36338 12718 12720 36339 12720 12719 36340 12719 12717 36341 12717 12723 36342 12723 12719 36343 12719 12720 36344 12720 12723 36345 12723 12721 36346 12721 12719 36347 12719 12723 36348 12723 12722 36349 12722 12721 36350 12721 12724 36351 12724 12722 36352 12722 12723 36353 12723 12726 36354 12726 12722 36355 12722 12724 36356 12724 12726 36357 12726 12725 36358 12725 12722 36359 12722 12728 36360 12728 12725 36361 12725 12726 36362 12726 12728 36363 12728 12727 36364 12727 12725 36365 12725 12730 36366 12730 12727 36367 12727 12728 36368 12728 12730 36369 12730 12729 36370 12729 12727 36371 12727 12713 36372 12713 12729 36373 12729 12730 36374 12730 12748 36375 12748 12731 36376 12731 12732 36377 12732 12734 36378 12734 12732 36379 12732 12733 36380 12733 12748 36381 12748 12732 36382 12732 12734 36383 12734 12737 36384 12737 12735 36385 12735 12736 36386 12736 12739 36387 12739 12735 36388 12735 12737 36389 12737 12739 36390 12739 12738 36391 12738 12735 36392 12735 12740 36393 12740 12738 36394 12738 12739 36395 12739 12742 36396 12742 12738 36397 12738 12740 36398 12740 12742 36399 12742 12741 36400 12741 12738 36401 12738 12745 36402 12745 12741 36403 12741 12742 36404 12742 12745 36405 12745 12743 36406 12743 12741 36407 12741 12745 36408 12745 12744 36409 12744 12743 36410 12743 12746 36411 12746 12744 36412 12744 12745 36413 12745 12731 36414 12731 12744 36415 12744 12746 36416 12746 12731 36417 12731 12747 36418 12747 12744 36419 12744 12731 36420 12731 12748 36421 12748 12747 36422 12747 12765 36423 12765 12749 36424 12749 12764 36425 12764 12752 36426 12752 12750 36427 12750 12751 36428 12751 12753 36429 12753 12750 36430 12750 12752 36431 12752 12755 36432 12755 12750 36433 12750 12753 36434 12753 12755 36435 12755 12754 36436 12754 12750 36437 12750 12758 36438 12758 12754 36439 12754 12755 36440 12755 12758 36441 12758 12756 36442 12756 12754 36443 12754 12758 36444 12758 12757 36445 12757 12756 36446 12756 12760 36447 12760 12757 36448 12757 12758 36449 12758 12760 36450 12760 12759 36451 12759 12757 36452 12757 12761 36453 12761 12759 36454 12759 12760 36455 12760 12763 36456 12763 12759 36457 12759 12761 36458 12761 12763 36459 12763 12762 36460 12762 12759 36461 12759 12765 36462 12765 12762 36463 12762 12763 36464 12763 12765 36465 12765 12764 36466 12764 12762 36467 12762 12749 36468 12749 12765 36469 12765 12766 36470 12766 12783 36471 12783 12770 36472 12770 12767 36473 12767 12767 36474 12767 12768 36475 12768 12769 36476 12769 12767 36477 12767 12770 36478 12770 12768 36479 12768 12773 36480 12773 12771 36481 12771 12772 36482 12772 12774 36483 12774 12771 36484 12771 12773 36485 12773 12777 36486 12777 12771 36487 12771 12774 36488 12774 12777 36489 12777 12775 36490 12775 12771 36491 12771 12777 36492 12777 12776 36493 12776 12775 36494 12775 12779 36495 12779 12776 36496 12776 12777 36497 12777 12779 36498 12779 12778 36499 12778 12776 36500 12776 12780 36501 12780 12778 36502 12778 12779 36503 12779 12782 36504 12782 12778 36505 12778 12780 36506 12780 12782 36507 12782 12781 36508 12781 12778 36509 12778 12784 36510 12784 12781 36511 12781 12782 36512 12782 12784 36513 12784 12783 36514 12783 12781 36515 12781 12770 36516 12770 12783 36517 12783 12784 36518 12784 12802 36519 12802 12785 36520 12785 12790 36521 12790 12788 36522 12788 12786 36523 12786 12787 36524 12787 12789 36525 12789 12786 36526 12786 12788 36527 12788 12802 36528 12802 12786 36529 12786 12789 36530 12789 12802 36531 12802 12790 36532 12790 12786 36533 12786 12794 36534 12794 12791 36535 12791 12792 36536 12792 12794 36537 12794 12793 36538 12793 12791 36539 12791 12796 36540 12796 12793 36541 12793 12794 36542 12794 12796 36543 12796 12795 36544 12795 12793 36545 12793 12798 36546 12798 12795 36547 12795 12796 36548 12796 12798 36549 12798 12797 36550 12797 12795 36551 12795 12801 36552 12801 12797 36553 12797 12798 36554 12798 12801 36555 12801 12799 36556 12799 12797 36557 12797 12801 36558 12801 12800 36559 12800 12799 36560 12799 12785 36561 12785 12800 36562 12800 12801 36563 12801 12785 36564 12785 12802 36565 12802 12800 36566 12800 12818 36567 12818 12807 36568 12807 12803 36569 12803 12808 36570 12808 12804 36571 12804 12805 36572 12805 12808 36573 12808 12806 36574 12806 12804 36575 12804 12808 36576 12808 12807 36577 12807 12806 36578 12806 12803 36579 12803 12807 36580 12807 12808 36581 12808 12813 36582 12813 12809 36583 12809 12810 36584 12810 12813 36585 12813 12811 36586 12811 12809 36587 12809 12813 36588 12813 12812 36589 12812 12811 36590 12811 12814 36591 12814 12812 36592 12812 12813 36593 12813 12816 36594 12816 12812 36595 12812 12814 36596 12814 12816 36597 12816 12815 36598 12815 12812 36599 12812 12819 36600 12819 12815 36601 12815 12816 36602 12816 12819 36603 12819 12817 36604 12817 12815 36605 12815 12819 36606 12819 12818 36607 12818 12817 36608 12817 12820 36609 12820 12818 36610 12818 12819 36611 12819 12807 36612 12807 12818 36613 12818 12820 36614 12820 12838 36615 12838 12821 36616 12821 12824 36617 12824 12838 36618 12838 12822 36619 12822 12823 36620 12823 12838 36621 12838 12824 36622 12824 12822 36623 12822 12827 36624 12827 12825 36625 12825 12826 36626 12826 12828 36627 12828 12825 36628 12825 12827 36629 12827 12830 36630 12830 12825 36631 12825 12828 36632 12828 12830 36633 12830 12829 36634 12829 12825 36635 12825 12832 36636 12832 12829 36637 12829 12830 36638 12830 12832 36639 12832 12831 36640 12831 12829 36641 12829 12834 36642 12834 12831 36643 12831 12832 36644 12832 12834 36645 12834 12833 36646 12833 12831 36647 12831 12837 36648 12837 12833 36649 12833 12834 36650 12834 12837 36651 12837 12835 36652 12835 12833 36653 12833 12837 36654 12837 12836 36655 12836 12835 36656 12835 12821 36657 12821 12836 36658 12836 12837 36659 12837 12821 36660 12821 12838 36661 12838 12836 36662 12836 12856 36663 12856 12839 36664 12839 12843 36665 12843 12842 36666 12842 12840 36667 12840 12841 36668 12841 12844 36669 12844 12840 36670 12840 12842 36671 12842 12844 36672 12844 12843 36673 12843 12840 36674 12840 12856 36675 12856 12843 36676 12843 12844 36677 12844 12847 36678 12847 12845 36679 12845 12846 36680 12846 12848 36681 12848 12845 36682 12845 12847 36683 12847 12851 36684 12851 12845 36685 12845 12848 36686 12848 12851 36687 12851 12849 36688 12849 12845 36689 12845 12851 36690 12851 12850 36691 12850 12849 36692 12849 12853 36693 12853 12850 36694 12850 12851 36695 12851 12853 36696 12853 12852 36697 12852 12850 36698 12850 12855 36699 12855 12852 36700 12852 12853 36701 12853 12855 36702 12855 12854 36703 12854 12852 36704 12852 12839 36705 12839 12854 36706 12854 12855 36707 12855 12839 36708 12839 12856 36709 12856 12854 36710 12854

+
+
+ + + + +7.500000 0.000000 1.500000 +7.500000 0.000000 0.000000 +-7.469662 0.673908 0.000000 +-7.500000 0.000000 0.000000 +-7.500000 0.000000 1.500000 +-7.469662 0.673908 1.500000 +-7.374790 1.364723 0.000000 +-7.374790 1.364723 1.500000 +-7.210492 2.063687 0.000000 +-7.210492 2.063687 1.500000 +-6.973412 2.760710 0.000000 +-6.973412 2.760710 1.500000 +-6.662130 3.444710 0.000000 +-6.662130 3.444710 1.500000 +-6.277466 4.104073 0.000000 +-6.277466 4.104073 1.500000 +-5.822649 4.727236 0.000000 +-5.822649 4.727236 1.500000 +-5.303301 5.303301 0.000000 +-5.303301 5.303301 1.500000 +-4.727236 5.822649 0.000000 +-4.727236 5.822649 1.500000 +-4.104073 6.277466 0.000000 +-4.104073 6.277466 1.500000 +-3.444710 6.662130 0.000000 +-3.444710 6.662130 1.500000 +-2.760710 6.973412 0.000000 +-2.760710 6.973412 1.500000 +-2.063687 7.210492 0.000000 +-2.063687 7.210492 1.500000 +-1.364723 7.374790 0.000000 +-1.364723 7.374790 1.500000 +-0.673908 7.469662 0.000000 +-0.673908 7.469662 1.500000 +0.000000 7.500000 0.000000 +0.000000 7.500000 1.500000 +0.673908 7.469662 0.000000 +0.673908 7.469662 1.500000 +1.364723 7.374790 0.000000 +1.364723 7.374790 1.500000 +2.063687 7.210492 0.000000 +2.063687 7.210492 1.500000 +2.760710 6.973412 0.000000 +2.760710 6.973412 1.500000 +3.444710 6.662130 0.000000 +3.444710 6.662130 1.500000 +4.104073 6.277466 0.000000 +4.104073 6.277466 1.500000 +4.727236 5.822649 0.000000 +4.727236 5.822649 1.500000 +5.303301 5.303301 0.000000 +5.303301 5.303301 1.500000 +5.822649 4.727236 0.000000 +5.822649 4.727236 1.500000 +6.277466 4.104073 0.000000 +6.277466 4.104073 1.500000 +6.662130 3.444710 0.000000 +6.662130 3.444710 1.500000 +6.973412 2.760710 0.000000 +6.973412 2.760710 1.500000 +7.210492 2.063687 0.000000 +7.210492 2.063687 1.500000 +7.374790 1.364723 0.000000 +7.374790 1.364723 1.500000 +7.469662 0.673908 0.000000 +7.469662 0.673908 1.500000 +7.500000 0.000000 0.000000 +7.500000 0.000000 1.500000 +-7.500000 0.000000 1.500000 +-7.500000 0.000000 0.000000 +-7.469662 -0.673908 1.500000 +-7.469662 -0.673908 0.000000 +-7.374790 -1.364723 1.500000 +-7.374790 -1.364723 0.000000 +-7.210492 -2.063687 1.500000 +-7.210492 -2.063687 0.000000 +-6.973412 -2.760710 1.500000 +-6.973412 -2.760710 0.000000 +-6.662130 -3.444710 1.500000 +-6.662130 -3.444710 0.000000 +-6.277466 -4.104073 1.500000 +-6.277466 -4.104073 0.000000 +-5.822649 -4.727236 1.500000 +-5.822649 -4.727236 0.000000 +-5.303301 -5.303301 1.500000 +-5.303301 -5.303301 0.000000 +-4.727236 -5.822649 1.500000 +-4.727236 -5.822649 0.000000 +-4.104073 -6.277466 1.500000 +-4.104073 -6.277466 0.000000 +-3.444710 -6.662130 1.500000 +-3.444710 -6.662130 0.000000 +-2.760710 -6.973412 1.500000 +-2.760710 -6.973412 0.000000 +-2.063687 -7.210492 1.500000 +-2.063687 -7.210492 0.000000 +-1.364723 -7.374790 1.500000 +-1.364723 -7.374790 0.000000 +-0.673908 -7.469662 1.500000 +-0.673908 -7.469662 0.000000 +0.000000 -7.500000 1.500000 +0.000000 -7.500000 0.000000 +0.673908 -7.469662 1.500000 +0.673908 -7.469662 0.000000 +1.364723 -7.374790 1.500000 +1.364723 -7.374790 0.000000 +2.063687 -7.210492 1.500000 +2.063687 -7.210492 0.000000 +2.760710 -6.973412 1.500000 +2.760710 -6.973412 0.000000 +3.444710 -6.662130 1.500000 +3.444710 -6.662130 0.000000 +4.104073 -6.277466 1.500000 +4.104073 -6.277466 0.000000 +4.727236 -5.822649 1.500000 +4.727236 -5.822649 0.000000 +5.303301 -5.303301 1.500000 +5.303301 -5.303301 0.000000 +5.822649 -4.727236 1.500000 +5.822649 -4.727236 0.000000 +6.277466 -4.104073 1.500000 +6.277466 -4.104073 0.000000 +6.662130 -3.444710 1.500000 +6.662130 -3.444710 0.000000 +6.973412 -2.760710 1.500000 +6.973412 -2.760710 0.000000 +7.210492 -2.063687 1.500000 +7.210492 -2.063687 0.000000 +7.374790 -1.364723 1.500000 +7.374790 -1.364723 0.000000 +7.469662 -0.673908 1.500000 +7.469662 -0.673908 0.000000 +2.063687 7.210492 1.500000 +1.364723 7.374790 1.500000 +0.673908 7.469662 1.500000 +-0.673908 7.469662 1.500000 +-1.364723 7.374790 1.500000 +-2.063687 7.210492 1.500000 +-2.760710 6.973412 1.500000 +-3.444710 6.662130 1.500000 +-4.104073 6.277466 1.500000 +-4.727236 5.822649 1.500000 +-5.303301 5.303301 1.500000 +-5.822649 4.727236 1.500000 +-6.277466 4.104073 1.500000 +-6.662130 3.444710 1.500000 +-6.973412 2.760710 1.500000 +-7.210492 2.063687 1.500000 +-7.374790 1.364723 1.500000 +-7.469662 0.673908 1.500000 +-7.500000 0.000000 1.500000 +-7.469662 -0.673908 1.500000 +-7.374790 -1.364723 1.500000 +-7.210492 -2.063687 1.500000 +-6.973412 -2.760710 1.500000 +-6.662130 -3.444710 1.500000 +-6.277466 -4.104073 1.500000 +-5.822649 -4.727236 1.500000 +-5.303301 -5.303301 1.500000 +-4.727236 -5.822649 1.500000 +-4.104073 -6.277466 1.500000 +-3.444710 -6.662130 1.500000 +-2.760710 -6.973412 1.500000 +-2.063687 -7.210492 1.500000 +-1.364723 -7.374790 1.500000 +-0.673908 -7.469662 1.500000 +0.673908 -7.469662 1.500000 +1.364723 -7.374790 1.500000 +2.063687 -7.210492 1.500000 +2.760710 -6.973412 1.500000 +3.444710 -6.662130 1.500000 +4.104073 -6.277466 1.500000 +4.727236 -5.822649 1.500000 +5.303301 -5.303301 1.500000 +5.822649 -4.727236 1.500000 +6.277466 -4.104073 1.500000 +6.662130 -3.444710 1.500000 +6.973412 -2.760710 1.500000 +7.210492 -2.063687 1.500000 +7.374790 -1.364723 1.500000 +7.469662 -0.673908 1.500000 +7.500000 0.000000 1.500000 +7.469662 0.673908 1.500000 +7.374790 1.364723 1.500000 +7.210492 2.063687 1.500000 +6.973412 2.760710 1.500000 +6.662130 3.444710 1.500000 +6.277466 4.104073 1.500000 +5.822649 4.727236 1.500000 +5.303301 5.303301 1.500000 +4.727236 5.822649 1.500000 +4.104073 6.277466 1.500000 +3.444710 6.662130 1.500000 +2.760710 6.973412 1.500000 +2.063687 -7.210492 0.000000 +1.364723 -7.374790 0.000000 +0.673908 -7.469662 0.000000 +-0.673908 -7.469662 0.000000 +-1.364723 -7.374790 0.000000 +-2.063687 -7.210492 0.000000 +-2.760710 -6.973412 0.000000 +-3.444710 -6.662130 0.000000 +-4.104073 -6.277466 0.000000 +-4.727236 -5.822649 0.000000 +-5.303301 -5.303301 0.000000 +-5.822649 -4.727236 0.000000 +-6.277466 -4.104073 0.000000 +-6.662130 -3.444710 0.000000 +-6.973412 -2.760710 0.000000 +-7.210492 -2.063687 0.000000 +-7.374790 -1.364723 0.000000 +-7.469662 -0.673908 0.000000 +-7.500000 0.000000 0.000000 +-7.469662 0.673908 0.000000 +-7.374790 1.364723 0.000000 +-7.210492 2.063687 0.000000 +-6.973412 2.760710 0.000000 +-6.662130 3.444710 0.000000 +-6.277466 4.104073 0.000000 +-5.822649 4.727236 0.000000 +-5.303301 5.303301 0.000000 +-4.727236 5.822649 0.000000 +-4.104073 6.277466 0.000000 +-3.444710 6.662130 0.000000 +-2.760710 6.973412 0.000000 +-2.063687 7.210492 0.000000 +-1.364723 7.374790 0.000000 +-0.673908 7.469662 0.000000 +0.673908 7.469662 0.000000 +1.364723 7.374790 0.000000 +2.063687 7.210492 0.000000 +2.760710 6.973412 0.000000 +3.444710 6.662130 0.000000 +4.104073 6.277466 0.000000 +4.727236 5.822649 0.000000 +5.303301 5.303301 0.000000 +5.822649 4.727236 0.000000 +6.277466 4.104073 0.000000 +6.662130 3.444710 0.000000 +6.973412 2.760710 0.000000 +7.210492 2.063687 0.000000 +7.374790 1.364723 0.000000 +7.469662 0.673908 0.000000 +7.500000 0.000000 0.000000 +7.469662 -0.673908 0.000000 +7.374790 -1.364723 0.000000 +7.210492 -2.063687 0.000000 +6.973412 -2.760710 0.000000 +6.662130 -3.444710 0.000000 +6.277466 -4.104073 0.000000 +5.822649 -4.727236 0.000000 +5.303301 -5.303301 0.000000 +4.727236 -5.822649 0.000000 +4.104073 -6.277466 0.000000 +3.444710 -6.662130 0.000000 +2.760710 -6.973412 0.000000 + + + + + + + + + + + +0.995955 0.089854 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.995955 0.089854 0.000000 +-1.000000 0.000000 0.000000 +-0.995955 0.089854 0.000000 +-0.995955 0.089854 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.995955 0.089854 0.000000 +-0.995955 0.089854 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.995955 0.089854 0.000000 +-0.961399 0.275158 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.961399 0.275158 0.000000 +-0.961399 0.275158 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.961399 0.275158 0.000000 +-0.961399 0.275158 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.961399 0.275158 0.000000 +-0.888284 0.459295 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.888284 0.459295 0.000000 +-0.888284 0.459295 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.888284 0.459295 0.000000 +-0.888284 0.459295 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.888284 0.459295 0.000000 +-0.776353 0.630298 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.776353 0.630298 0.000000 +-0.776353 0.630298 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.776353 0.630298 0.000000 +-0.776353 0.630298 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.776353 0.630298 0.000000 +-0.630298 0.776353 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.630298 0.776353 0.000000 +-0.630298 0.776353 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.630298 0.776353 0.000000 +-0.630298 0.776353 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.630298 0.776353 0.000000 +-0.459295 0.888284 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.459295 0.888284 0.000000 +-0.459295 0.888284 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.459295 0.888284 0.000000 +-0.459295 0.888284 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.459295 0.888284 0.000000 +-0.275158 0.961399 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.275158 0.961399 0.000000 +-0.275158 0.961399 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.275158 0.961399 0.000000 +-0.275158 0.961399 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.275158 0.961399 0.000000 +-0.089854 0.995955 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.089854 0.995955 0.000000 +-0.089854 0.995955 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.089854 0.995955 0.000000 +-0.089854 0.995955 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.089854 0.995955 0.000000 +0.089854 0.995955 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.089854 0.995955 0.000000 +0.089854 0.995955 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.089854 0.995955 0.000000 +0.089854 0.995955 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.089854 0.995955 0.000000 +0.275158 0.961399 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.275158 0.961399 0.000000 +0.275158 0.961399 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.275158 0.961399 0.000000 +0.275158 0.961399 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.275158 0.961399 0.000000 +0.459295 0.888284 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.459295 0.888284 0.000000 +0.459295 0.888284 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.459295 0.888284 0.000000 +0.459295 0.888284 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.459295 0.888284 0.000000 +0.630298 0.776353 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.630298 0.776353 0.000000 +0.630298 0.776353 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.630298 0.776353 0.000000 +0.630298 0.776353 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.630298 0.776353 0.000000 +0.776353 0.630298 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.776353 0.630298 0.000000 +0.776353 0.630298 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.776353 0.630298 0.000000 +0.776353 0.630298 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.776353 0.630298 0.000000 +0.888284 0.459295 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.888284 0.459295 0.000000 +0.888284 0.459295 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.888284 0.459295 0.000000 +0.888284 0.459295 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.888284 0.459295 0.000000 +0.961399 0.275158 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.961399 0.275158 0.000000 +0.961399 0.275158 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.961399 0.275158 0.000000 +0.961399 0.275158 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.961399 0.275158 0.000000 +0.995955 0.089854 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.995955 0.089854 0.000000 +0.995955 0.089854 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.995955 0.089854 0.000000 +0.995955 0.089854 0.000000 +0.995955 -0.089854 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.995955 -0.089854 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.995955 -0.089854 0.000000 +-0.995955 -0.089854 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.995955 -0.089854 0.000000 +-0.995955 -0.089854 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.995955 -0.089854 0.000000 +-0.961399 -0.275158 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.961399 -0.275158 0.000000 +-0.961399 -0.275158 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.961399 -0.275158 0.000000 +-0.961399 -0.275158 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.961399 -0.275158 0.000000 +-0.888284 -0.459295 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.888284 -0.459295 0.000000 +-0.888284 -0.459295 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.888284 -0.459295 0.000000 +-0.888284 -0.459295 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.888284 -0.459295 0.000000 +-0.776353 -0.630298 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.776353 -0.630298 0.000000 +-0.776353 -0.630298 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.776353 -0.630298 0.000000 +-0.776353 -0.630298 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.776353 -0.630298 0.000000 +-0.630298 -0.776353 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.630298 -0.776353 0.000000 +-0.630298 -0.776353 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.630298 -0.776353 0.000000 +-0.630298 -0.776353 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.630298 -0.776353 0.000000 +-0.459295 -0.888284 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.459295 -0.888284 0.000000 +-0.459295 -0.888284 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.459295 -0.888284 0.000000 +-0.459295 -0.888284 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.459295 -0.888284 0.000000 +-0.275158 -0.961399 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.275158 -0.961399 0.000000 +-0.275158 -0.961399 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.275158 -0.961399 0.000000 +-0.275158 -0.961399 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.275158 -0.961399 0.000000 +-0.089854 -0.995955 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.089854 -0.995955 0.000000 +-0.089854 -0.995955 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +-0.089854 -0.995955 0.000000 +-0.089854 -0.995955 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.089854 -0.995955 0.000000 +0.089854 -0.995955 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.089854 -0.995955 0.000000 +0.089854 -0.995955 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.089854 -0.995955 0.000000 +0.089854 -0.995955 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.089854 -0.995955 0.000000 +0.275158 -0.961399 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.275158 -0.961399 0.000000 +0.275158 -0.961399 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.275158 -0.961399 0.000000 +0.275158 -0.961399 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.275158 -0.961399 0.000000 +0.459295 -0.888284 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.459295 -0.888284 0.000000 +0.459295 -0.888284 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.459295 -0.888284 0.000000 +0.459295 -0.888284 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.459295 -0.888284 0.000000 +0.630298 -0.776353 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.630298 -0.776353 0.000000 +0.630298 -0.776353 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.630298 -0.776353 0.000000 +0.630298 -0.776353 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.630298 -0.776353 0.000000 +0.776353 -0.630298 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.776353 -0.630298 0.000000 +0.776353 -0.630298 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.776353 -0.630298 0.000000 +0.776353 -0.630298 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.776353 -0.630298 0.000000 +0.888284 -0.459295 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.888284 -0.459295 0.000000 +0.888284 -0.459295 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.888284 -0.459295 0.000000 +0.888284 -0.459295 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.888284 -0.459295 0.000000 +0.961399 -0.275158 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.961399 -0.275158 0.000000 +0.961399 -0.275158 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.961399 -0.275158 0.000000 +0.961399 -0.275158 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.961399 -0.275158 0.000000 +0.995955 -0.089854 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.995955 -0.089854 0.000000 +0.995955 -0.089854 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.995955 -0.089854 0.000000 +0.995955 -0.089854 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 + + + + + + + + + + + +0.487883 0.824049 +0.487883 0.823997 +0.423506 0.850005 +0.422343 0.847088 +0.422343 0.847139 +0.423506 0.850057 +0.424977 0.852898 +0.424977 0.852949 +0.426763 0.855719 +0.426763 0.855770 +0.428865 0.858420 +0.428865 0.858471 +0.431271 0.860949 +0.431271 0.861000 +0.433960 0.863257 +0.433960 0.863308 +0.436901 0.865298 +0.436901 0.865349 +0.440051 0.867032 +0.440051 0.867083 +0.443362 0.868429 +0.443362 0.868481 +0.446780 0.869471 +0.446780 0.869522 +0.450249 0.870147 +0.450249 0.870199 +0.453714 0.870464 +0.453714 0.870515 +0.457122 0.870433 +0.457122 0.870485 +0.460427 0.870080 +0.460427 0.870131 +0.463591 0.869434 +0.463591 0.869485 +0.466582 0.868530 +0.466582 0.868581 +0.469480 0.867359 +0.469480 0.867410 +0.472353 0.865878 +0.472353 0.865930 +0.475156 0.864080 +0.475156 0.864131 +0.477839 0.861964 +0.477839 0.862015 +0.480352 0.859542 +0.480352 0.859593 +0.482644 0.856835 +0.482644 0.856886 +0.484672 0.853875 +0.484672 0.853927 +0.486394 0.850704 +0.486394 0.850756 +0.487783 0.847371 +0.487783 0.847422 +0.488817 0.843930 +0.488817 0.843981 +0.489489 0.840438 +0.489489 0.840489 +0.489803 0.836950 +0.489803 0.837002 +0.489773 0.833520 +0.489773 0.833571 +0.489422 0.830192 +0.489422 0.830244 +0.488781 0.827008 +0.488781 0.827059 +0.487883 0.823997 +0.487883 0.824049 +0.422343 0.847139 +0.422343 0.847088 +0.421445 0.844128 +0.421445 0.844077 +0.420803 0.840944 +0.420803 0.840893 +0.420452 0.837617 +0.420452 0.837566 +0.420422 0.834186 +0.420422 0.834135 +0.420736 0.830699 +0.420736 0.830647 +0.421408 0.827206 +0.421408 0.827155 +0.422442 0.823765 +0.422442 0.823714 +0.423831 0.820432 +0.423831 0.820381 +0.425554 0.817261 +0.425554 0.817210 +0.427581 0.814301 +0.427581 0.814250 +0.429874 0.811594 +0.429874 0.811543 +0.432386 0.809172 +0.432386 0.809121 +0.435069 0.807057 +0.435069 0.807005 +0.437872 0.805258 +0.437872 0.805207 +0.440745 0.803777 +0.440745 0.803726 +0.443643 0.802607 +0.443643 0.802555 +0.446634 0.801703 +0.446634 0.801651 +0.449798 0.801056 +0.449798 0.801005 +0.453103 0.800703 +0.453103 0.800652 +0.456511 0.800673 +0.456511 0.800621 +0.459976 0.800989 +0.459976 0.800938 +0.463445 0.801666 +0.463445 0.801615 +0.466863 0.802707 +0.466863 0.802656 +0.470174 0.804105 +0.470174 0.804053 +0.473325 0.805839 +0.473325 0.805787 +0.476265 0.807879 +0.476265 0.807828 +0.478954 0.810187 +0.478954 0.810136 +0.481360 0.812717 +0.481360 0.812665 +0.483462 0.815417 +0.483462 0.815366 +0.485248 0.818239 +0.485248 0.818187 +0.486719 0.821131 +0.486719 0.821080 +0.475156 0.864131 +0.472353 0.865930 +0.469480 0.867410 +0.463591 0.869485 +0.460427 0.870131 +0.457122 0.870485 +0.453714 0.870515 +0.450249 0.870199 +0.446780 0.869522 +0.443362 0.868481 +0.440051 0.867083 +0.436901 0.865349 +0.433960 0.863308 +0.431271 0.861000 +0.428865 0.858471 +0.426763 0.855770 +0.424977 0.852949 +0.423506 0.850057 +0.422343 0.847139 +0.421445 0.844128 +0.420803 0.840944 +0.420452 0.837617 +0.420422 0.834186 +0.420736 0.830699 +0.421408 0.827206 +0.422442 0.823765 +0.423831 0.820432 +0.425554 0.817261 +0.427581 0.814301 +0.429874 0.811594 +0.432386 0.809172 +0.435069 0.807057 +0.437872 0.805258 +0.440745 0.803777 +0.446634 0.801703 +0.449798 0.801056 +0.453103 0.800703 +0.456511 0.800673 +0.459976 0.800989 +0.463445 0.801666 +0.466863 0.802707 +0.470174 0.804105 +0.473325 0.805839 +0.476265 0.807879 +0.478954 0.810187 +0.481360 0.812717 +0.483462 0.815417 +0.485248 0.818239 +0.486719 0.821131 +0.487883 0.824049 +0.488781 0.827059 +0.489422 0.830244 +0.489773 0.833571 +0.489803 0.837002 +0.489489 0.840489 +0.488817 0.843981 +0.487783 0.847422 +0.486394 0.850756 +0.484672 0.853927 +0.482644 0.856886 +0.480352 0.859593 +0.477839 0.862015 +0.453103 0.800652 +0.449798 0.801005 +0.446634 0.801651 +0.440745 0.803726 +0.437872 0.805207 +0.435069 0.807005 +0.432386 0.809121 +0.429874 0.811543 +0.427581 0.814250 +0.425554 0.817210 +0.423831 0.820381 +0.422442 0.823714 +0.421408 0.827155 +0.420736 0.830647 +0.420422 0.834135 +0.420452 0.837566 +0.420803 0.840893 +0.421445 0.844077 +0.422343 0.847088 +0.423506 0.850005 +0.424977 0.852898 +0.426763 0.855719 +0.428865 0.858420 +0.431271 0.860949 +0.433960 0.863257 +0.436901 0.865298 +0.440051 0.867032 +0.443362 0.868429 +0.446780 0.869471 +0.450249 0.870147 +0.453714 0.870464 +0.457122 0.870433 +0.460427 0.870080 +0.463591 0.869434 +0.469480 0.867359 +0.472353 0.865878 +0.475156 0.864080 +0.477839 0.861964 +0.480352 0.859542 +0.482644 0.856835 +0.484672 0.853875 +0.486394 0.850704 +0.487783 0.847371 +0.488817 0.843930 +0.489489 0.840438 +0.489803 0.836950 +0.489773 0.833520 +0.489422 0.830192 +0.488781 0.827008 +0.487883 0.823997 +0.486719 0.821080 +0.485248 0.818187 +0.483462 0.815366 +0.481360 0.812665 +0.478954 0.810136 +0.476265 0.807828 +0.473325 0.805787 +0.470174 0.804053 +0.466863 0.802656 +0.463445 0.801615 +0.459976 0.800938 +0.456511 0.800621 + + + + + + + + + + + +

64 0 64 0 1 0 1 2 1 4 3 4 2 4 2 3 5 3 5 6 5 2 7 2 4 8 4 7 9 7 2 10 2 5 11 5 7 12 7 6 13 6 2 14 2 9 15 9 6 16 6 7 17 7 9 18 9 8 19 8 6 20 6 11 21 11 8 22 8 9 23 9 11 24 11 10 25 10 8 26 8 13 27 13 10 28 10 11 29 11 13 30 13 12 31 12 10 32 10 15 33 15 12 34 12 13 35 13 15 36 15 14 37 14 12 38 12 17 39 17 14 40 14 15 41 15 17 42 17 16 43 16 14 44 14 19 45 19 16 46 16 17 47 17 19 48 19 18 49 18 16 50 16 21 51 21 18 52 18 19 53 19 21 54 21 20 55 20 18 56 18 23 57 23 20 58 20 21 59 21 23 60 23 22 61 22 20 62 20 25 63 25 22 64 22 23 65 23 25 66 25 24 67 24 22 68 22 27 69 27 24 70 24 25 71 25 27 72 27 26 73 26 24 74 24 29 75 29 26 76 26 27 77 27 29 78 29 28 79 28 26 80 26 31 81 31 28 82 28 29 83 29 31 84 31 30 85 30 28 86 28 33 87 33 30 88 30 31 89 31 33 90 33 32 91 32 30 92 30 35 93 35 32 94 32 33 95 33 35 96 35 34 97 34 32 98 32 37 99 37 34 100 34 35 101 35 37 102 37 36 103 36 34 104 34 39 105 39 36 106 36 37 107 37 39 108 39 38 109 38 36 110 36 41 111 41 38 112 38 39 113 39 41 114 41 40 115 40 38 116 38 43 117 43 40 118 40 41 119 41 43 120 43 42 121 42 40 122 40 45 123 45 42 124 42 43 125 43 45 126 45 44 127 44 42 128 42 47 129 47 44 130 44 45 131 45 47 132 47 46 133 46 44 134 44 49 135 49 46 136 46 47 137 47 49 138 49 48 139 48 46 140 46 51 141 51 48 142 48 49 143 49 51 144 51 50 145 50 48 146 48 53 147 53 50 148 50 51 149 51 53 150 53 52 151 52 50 152 50 55 153 55 52 154 52 53 155 53 55 156 55 54 157 54 52 158 52 57 159 57 54 160 54 55 161 55 57 162 57 56 163 56 54 164 54 59 165 59 56 166 56 57 167 57 59 168 59 58 169 58 56 170 56 61 171 61 58 172 58 59 173 59 61 174 61 60 175 60 58 176 58 63 177 63 60 178 60 61 179 61 63 180 63 62 181 62 60 182 60 65 183 65 62 184 62 63 185 63 65 186 65 64 187 64 62 188 62 0 189 0 64 190 64 65 191 65 130 192 130 66 193 66 67 194 67 71 195 71 68 196 68 69 197 69 71 198 71 70 199 70 68 200 68 73 201 73 70 202 70 71 203 71 73 204 73 72 205 72 70 206 70 75 207 75 72 208 72 73 209 73 75 210 75 74 211 74 72 212 72 77 213 77 74 214 74 75 215 75 77 216 77 76 217 76 74 218 74 79 219 79 76 220 76 77 221 77 79 222 79 78 223 78 76 224 76 81 225 81 78 226 78 79 227 79 81 228 81 80 229 80 78 230 78 83 231 83 80 232 80 81 233 81 83 234 83 82 235 82 80 236 80 85 237 85 82 238 82 83 239 83 85 240 85 84 241 84 82 242 82 87 243 87 84 244 84 85 245 85 87 246 87 86 247 86 84 248 84 89 249 89 86 250 86 87 251 87 89 252 89 88 253 88 86 254 86 91 255 91 88 256 88 89 257 89 91 258 91 90 259 90 88 260 88 93 261 93 90 262 90 91 263 91 93 264 93 92 265 92 90 266 90 95 267 95 92 268 92 93 269 93 95 270 95 94 271 94 92 272 92 97 273 97 94 274 94 95 275 95 97 276 97 96 277 96 94 278 94 99 279 99 96 280 96 97 281 97 99 282 99 98 283 98 96 284 96 101 285 101 98 286 98 99 287 99 101 288 101 100 289 100 98 290 98 103 291 103 100 292 100 101 293 101 103 294 103 102 295 102 100 296 100 105 297 105 102 298 102 103 299 103 105 300 105 104 301 104 102 302 102 107 303 107 104 304 104 105 305 105 107 306 107 106 307 106 104 308 104 109 309 109 106 310 106 107 311 107 109 312 109 108 313 108 106 314 106 111 315 111 108 316 108 109 317 109 111 318 111 110 319 110 108 320 108 113 321 113 110 322 110 111 323 111 113 324 113 112 325 112 110 326 110 115 327 115 112 328 112 113 329 113 115 330 115 114 331 114 112 332 112 117 333 117 114 334 114 115 335 115 117 336 117 116 337 116 114 338 114 119 339 119 116 340 116 117 341 117 119 342 119 118 343 118 116 344 116 121 345 121 118 346 118 119 347 119 121 348 121 120 349 120 118 350 118 123 351 123 120 352 120 121 353 121 123 354 123 122 355 122 120 356 120 125 357 125 122 358 122 123 359 123 125 360 125 124 361 124 122 362 122 127 363 127 124 364 124 125 365 125 127 366 127 126 367 126 124 368 124 129 369 129 126 370 126 127 371 127 129 372 129 128 373 128 126 374 126 131 375 131 128 376 128 129 377 129 131 378 131 130 379 130 128 380 128 66 381 66 130 382 130 131 383 131 134 384 134 132 385 132 133 386 133 136 387 136 134 388 134 135 389 135 137 390 137 134 391 134 136 392 136 138 393 138 134 394 134 137 395 137 139 396 139 134 397 134 138 398 138 140 399 140 134 400 134 139 401 139 141 402 141 134 403 134 140 404 140 142 405 142 134 406 134 141 407 141 143 408 143 134 409 134 142 410 142 144 411 144 134 412 134 143 413 143 145 414 145 134 415 134 144 416 144 146 417 146 134 418 134 145 419 145 147 420 147 134 421 134 146 422 146 148 423 148 134 424 134 147 425 147 149 426 149 134 427 134 148 428 148 150 429 150 134 430 134 149 431 149 151 432 151 134 433 134 150 434 150 152 435 152 134 436 134 151 437 151 153 438 153 134 439 134 152 440 152 154 441 154 134 442 134 153 443 153 155 444 155 134 445 134 154 446 154 156 447 156 134 448 134 155 449 155 157 450 157 134 451 134 156 452 156 158 453 158 134 454 134 157 455 157 159 456 159 134 457 134 158 458 158 160 459 160 134 460 134 159 461 159 161 462 161 134 463 134 160 464 160 162 465 162 134 466 134 161 467 161 163 468 163 134 469 134 162 470 162 164 471 164 134 472 134 163 473 163 165 474 165 134 475 134 164 476 164 166 477 166 134 478 134 165 479 165 167 480 167 134 481 134 166 482 166 168 483 168 134 484 134 167 485 167 169 486 169 134 487 134 168 488 168 170 489 170 134 490 134 169 491 169 171 492 171 134 493 134 170 494 170 172 495 172 134 496 134 171 497 171 173 498 173 134 499 134 172 500 172 174 501 174 134 502 134 173 503 173 175 504 175 134 505 134 174 506 174 176 507 176 134 508 134 175 509 175 177 510 177 134 511 134 176 512 176 178 513 178 134 514 134 177 515 177 179 516 179 134 517 134 178 518 178 180 519 180 134 520 134 179 521 179 181 522 181 134 523 134 180 524 180 182 525 182 134 526 134 181 527 181 183 528 183 134 529 134 182 530 182 184 531 184 134 532 134 183 533 183 185 534 185 134 535 134 184 536 184 186 537 186 134 538 134 185 539 185 187 540 187 134 541 134 186 542 186 188 543 188 134 544 134 187 545 187 189 546 189 134 547 134 188 548 188 190 549 190 134 550 134 189 551 189 191 552 191 134 553 134 190 554 190 192 555 192 134 556 134 191 557 191 193 558 193 134 559 134 192 560 192 132 561 132 134 562 134 193 563 193 196 564 196 194 565 194 195 566 195 198 567 198 196 568 196 197 569 197 199 570 199 196 571 196 198 572 198 200 573 200 196 574 196 199 575 199 201 576 201 196 577 196 200 578 200 202 579 202 196 580 196 201 581 201 203 582 203 196 583 196 202 584 202 204 585 204 196 586 196 203 587 203 205 588 205 196 589 196 204 590 204 206 591 206 196 592 196 205 593 205 207 594 207 196 595 196 206 596 206 208 597 208 196 598 196 207 599 207 209 600 209 196 601 196 208 602 208 210 603 210 196 604 196 209 605 209 211 606 211 196 607 196 210 608 210 212 609 212 196 610 196 211 611 211 213 612 213 196 613 196 212 614 212 214 615 214 196 616 196 213 617 213 215 618 215 196 619 196 214 620 214 216 621 216 196 622 196 215 623 215 217 624 217 196 625 196 216 626 216 218 627 218 196 628 196 217 629 217 219 630 219 196 631 196 218 632 218 220 633 220 196 634 196 219 635 219 221 636 221 196 637 196 220 638 220 222 639 222 196 640 196 221 641 221 223 642 223 196 643 196 222 644 222 224 645 224 196 646 196 223 647 223 225 648 225 196 649 196 224 650 224 226 651 226 196 652 196 225 653 225 227 654 227 196 655 196 226 656 226 228 657 228 196 658 196 227 659 227 229 660 229 196 661 196 228 662 228 230 663 230 196 664 196 229 665 229 231 666 231 196 667 196 230 668 230 232 669 232 196 670 196 231 671 231 233 672 233 196 673 196 232 674 232 234 675 234 196 676 196 233 677 233 235 678 235 196 679 196 234 680 234 236 681 236 196 682 196 235 683 235 237 684 237 196 685 196 236 686 236 238 687 238 196 688 196 237 689 237 239 690 239 196 691 196 238 692 238 240 693 240 196 694 196 239 695 239 241 696 241 196 697 196 240 698 240 242 699 242 196 700 196 241 701 241 243 702 243 196 703 196 242 704 242 244 705 244 196 706 196 243 707 243 245 708 245 196 709 196 244 710 244 246 711 246 196 712 196 245 713 245 247 714 247 196 715 196 246 716 246 248 717 248 196 718 196 247 719 247 249 720 249 196 721 196 248 722 248 250 723 250 196 724 196 249 725 249 251 726 251 196 727 196 250 728 250 252 729 252 196 730 196 251 731 251 253 732 253 196 733 196 252 734 252 254 735 254 196 736 196 253 737 253 255 738 255 196 739 196 254 740 254 194 741 194 196 742 196 255 743 255

+
+
+ + + + +37.200001 1.450000 0.120000 +37.200001 1.450000 0.000000 +36.500000 1.450000 0.000000 +36.500000 1.450000 0.120000 +36.505844 1.386313 0.000000 +36.505844 1.386313 0.120000 +36.524574 1.321167 0.000000 +36.524574 1.321167 0.120000 +36.557053 1.258477 0.000000 +36.557053 1.258477 0.120000 +36.602512 1.202513 0.000000 +36.602512 1.202513 0.120000 +36.658478 1.157052 0.000000 +36.658478 1.157052 0.120000 +36.721169 1.124574 0.000000 +36.721169 1.124574 0.120000 +36.786312 1.105843 0.000000 +36.786312 1.105843 0.120000 +36.849998 1.100000 0.000000 +36.849998 1.100000 0.120000 +36.913689 1.105843 0.000000 +36.913689 1.105843 0.120000 +36.978832 1.124574 0.000000 +36.978832 1.124574 0.120000 +37.041523 1.157052 0.000000 +37.041523 1.157052 0.120000 +37.097488 1.202513 0.000000 +37.097488 1.202513 0.120000 +37.142948 1.258477 0.000000 +37.142948 1.258477 0.120000 +37.175426 1.321167 0.000000 +37.175426 1.321167 0.120000 +37.194157 1.386313 0.000000 +37.194157 1.386313 0.120000 +35.200001 1.450000 0.120000 +35.200001 1.450000 0.000000 +34.500000 1.450000 0.000000 +34.500000 1.450000 0.120000 +34.505844 1.386313 0.000000 +34.524574 1.321167 0.000000 +34.505844 1.386313 0.120000 +34.524574 1.321167 0.120000 +34.557053 1.258477 0.000000 +34.557053 1.258477 0.120000 +34.602512 1.202513 0.000000 +34.602512 1.202513 0.120000 +34.658478 1.157052 0.000000 +34.658478 1.157052 0.120000 +34.721169 1.124574 0.000000 +34.786312 1.105843 0.000000 +34.721169 1.124574 0.120000 +34.786312 1.105843 0.120000 +34.849998 1.100000 0.000000 +34.849998 1.100000 0.120000 +34.913689 1.105843 0.000000 +34.913689 1.105843 0.120000 +34.978832 1.124574 0.000000 +34.978832 1.124574 0.120000 +35.041523 1.157052 0.000000 +35.041523 1.157052 0.120000 +35.097488 1.202513 0.000000 +35.097488 1.202513 0.120000 +35.142948 1.258477 0.000000 +35.142948 1.258477 0.120000 +35.175426 1.321167 0.000000 +35.175426 1.321167 0.120000 +35.194157 1.386313 0.000000 +35.194157 1.386313 0.120000 +32.500000 1.450000 0.000000 +32.500000 1.450000 0.120000 +33.200001 1.450000 0.120000 +33.200001 1.450000 0.000000 +33.194157 1.386313 0.120000 +33.194157 1.386313 0.000000 +33.175426 1.321167 0.120000 +33.175426 1.321167 0.000000 +33.142948 1.258477 0.120000 +33.097488 1.202513 0.120000 +33.142948 1.258477 0.000000 +33.041523 1.157052 0.120000 +33.097488 1.202513 0.000000 +32.978832 1.124574 0.120000 +33.041523 1.157052 0.000000 +32.978832 1.124574 0.000000 +32.913689 1.105843 0.120000 +32.913689 1.105843 0.000000 +32.849998 1.100000 0.120000 +32.849998 1.100000 0.000000 +32.786312 1.105843 0.120000 +32.786312 1.105843 0.000000 +32.721169 1.124574 0.120000 +32.721169 1.124574 0.000000 +32.658478 1.157052 0.120000 +32.658478 1.157052 0.000000 +32.602512 1.202513 0.120000 +32.602512 1.202513 0.000000 +32.557053 1.258477 0.120000 +32.524574 1.321167 0.120000 +32.557053 1.258477 0.000000 +32.524574 1.321167 0.000000 +32.505844 1.386313 0.120000 +32.505844 1.386313 0.000000 +31.200001 1.450000 0.120000 +31.200001 1.450000 0.000000 +30.500000 1.450000 0.000000 +30.500000 1.450000 0.120000 +30.505842 1.386313 0.000000 +30.505842 1.386313 0.120000 +30.524574 1.321167 0.000000 +30.524574 1.321167 0.120000 +30.557051 1.258477 0.000000 +30.557051 1.258477 0.120000 +30.602512 1.202513 0.000000 +30.602512 1.202513 0.120000 +30.658476 1.157052 0.000000 +30.658476 1.157052 0.120000 +30.721167 1.124574 0.000000 +30.721167 1.124574 0.120000 +30.786312 1.105843 0.000000 +30.786312 1.105843 0.120000 +30.850000 1.100000 0.000000 +30.850000 1.100000 0.120000 +30.913687 1.105843 0.000000 +30.913687 1.105843 0.120000 +30.978832 1.124574 0.000000 +30.978832 1.124574 0.120000 +31.041523 1.157052 0.000000 +31.041523 1.157052 0.120000 +31.097486 1.202513 0.000000 +31.097486 1.202513 0.120000 +31.142948 1.258477 0.000000 +31.142948 1.258477 0.120000 +31.175426 1.321167 0.000000 +31.175426 1.321167 0.120000 +31.194157 1.386313 0.000000 +31.194157 1.386313 0.120000 +29.200001 1.450000 0.120000 +29.200001 1.450000 0.000000 +28.500000 1.450000 0.000000 +28.500000 1.450000 0.120000 +28.505842 1.386313 0.000000 +28.505842 1.386313 0.120000 +28.524574 1.321167 0.000000 +28.524574 1.321167 0.120000 +28.557051 1.258477 0.000000 +28.557051 1.258477 0.120000 +28.602512 1.202513 0.000000 +28.602512 1.202513 0.120000 +28.658476 1.157052 0.000000 +28.658476 1.157052 0.120000 +28.721167 1.124574 0.000000 +28.721167 1.124574 0.120000 +28.786312 1.105843 0.000000 +28.786312 1.105843 0.120000 +28.850000 1.100000 0.000000 +28.850000 1.100000 0.120000 +28.913687 1.105843 0.000000 +28.913687 1.105843 0.120000 +28.978832 1.124574 0.000000 +28.978832 1.124574 0.120000 +29.041523 1.157052 0.000000 +29.041523 1.157052 0.120000 +29.097486 1.202513 0.000000 +29.097486 1.202513 0.120000 +29.142948 1.258477 0.000000 +29.142948 1.258477 0.120000 +29.175426 1.321167 0.000000 +29.175426 1.321167 0.120000 +29.194157 1.386313 0.000000 +29.194157 1.386313 0.120000 +27.200001 1.450000 0.120000 +27.200001 1.450000 0.000000 +26.500000 1.450000 0.000000 +26.500000 1.450000 0.120000 +26.505842 1.386313 0.000000 +26.505842 1.386313 0.120000 +26.524574 1.321167 0.000000 +26.524574 1.321167 0.120000 +26.557051 1.258477 0.000000 +26.557051 1.258477 0.120000 +26.602512 1.202513 0.000000 +26.602512 1.202513 0.120000 +26.658476 1.157052 0.000000 +26.658476 1.157052 0.120000 +26.721167 1.124574 0.000000 +26.721167 1.124574 0.120000 +26.786312 1.105843 0.000000 +26.786312 1.105843 0.120000 +26.850000 1.100000 0.000000 +26.850000 1.100000 0.120000 +26.913687 1.105843 0.000000 +26.913687 1.105843 0.120000 +26.978832 1.124574 0.000000 +26.978832 1.124574 0.120000 +27.041523 1.157052 0.000000 +27.041523 1.157052 0.120000 +27.097486 1.202513 0.000000 +27.142948 1.258477 0.000000 +27.097486 1.202513 0.120000 +27.175426 1.321167 0.000000 +27.142948 1.258477 0.120000 +27.175426 1.321167 0.120000 +27.194157 1.386313 0.000000 +27.194157 1.386313 0.120000 +25.200001 1.450000 0.120000 +25.200001 1.450000 0.000000 +24.500000 1.450000 0.000000 +24.500000 1.450000 0.120000 +24.505842 1.386313 0.000000 +24.505842 1.386313 0.120000 +24.524574 1.321167 0.000000 +24.524574 1.321167 0.120000 +24.557051 1.258477 0.000000 +24.557051 1.258477 0.120000 +24.602512 1.202513 0.000000 +24.602512 1.202513 0.120000 +24.658476 1.157052 0.000000 +24.658476 1.157052 0.120000 +24.721167 1.124574 0.000000 +24.721167 1.124574 0.120000 +24.786312 1.105843 0.000000 +24.786312 1.105843 0.120000 +24.850000 1.100000 0.000000 +24.850000 1.100000 0.120000 +24.913687 1.105843 0.000000 +24.913687 1.105843 0.120000 +24.978832 1.124574 0.000000 +24.978832 1.124574 0.120000 +25.041523 1.157052 0.000000 +25.041523 1.157052 0.120000 +25.097486 1.202513 0.000000 +25.097486 1.202513 0.120000 +25.142948 1.258477 0.000000 +25.142948 1.258477 0.120000 +25.175426 1.321167 0.000000 +25.175426 1.321167 0.120000 +25.194157 1.386313 0.000000 +25.194157 1.386313 0.120000 +23.200001 1.450000 0.120000 +23.200001 1.450000 0.000000 +22.500000 1.450000 0.000000 +22.500000 1.450000 0.120000 +22.505842 1.386313 0.000000 +22.505842 1.386313 0.120000 +22.524574 1.321167 0.000000 +22.524574 1.321167 0.120000 +22.557051 1.258477 0.000000 +22.557051 1.258477 0.120000 +22.602512 1.202513 0.000000 +22.602512 1.202513 0.120000 +22.658476 1.157052 0.000000 +22.658476 1.157052 0.120000 +22.721167 1.124574 0.000000 +22.721167 1.124574 0.120000 +22.786312 1.105843 0.000000 +22.786312 1.105843 0.120000 +22.850000 1.100000 0.000000 +22.850000 1.100000 0.120000 +22.913687 1.105843 0.000000 +22.913687 1.105843 0.120000 +22.978832 1.124574 0.000000 +22.978832 1.124574 0.120000 +23.041523 1.157052 0.000000 +23.041523 1.157052 0.120000 +23.097486 1.202513 0.000000 +23.097486 1.202513 0.120000 +23.142948 1.258477 0.000000 +23.142948 1.258477 0.120000 +23.175426 1.321167 0.000000 +23.175426 1.321167 0.120000 +23.194157 1.386313 0.000000 +23.194157 1.386313 0.120000 +21.200001 1.450000 0.120000 +21.200001 1.450000 0.000000 +20.500000 1.450000 0.000000 +20.500000 1.450000 0.120000 +20.505842 1.386313 0.000000 +20.505842 1.386313 0.120000 +20.524574 1.321167 0.000000 +20.524574 1.321167 0.120000 +20.557051 1.258477 0.000000 +20.557051 1.258477 0.120000 +20.602512 1.202513 0.000000 +20.602512 1.202513 0.120000 +20.658476 1.157052 0.000000 +20.658476 1.157052 0.120000 +20.721167 1.124574 0.000000 +20.721167 1.124574 0.120000 +20.786312 1.105843 0.000000 +20.786312 1.105843 0.120000 +20.850000 1.100000 0.000000 +20.850000 1.100000 0.120000 +20.913687 1.105843 0.000000 +20.913687 1.105843 0.120000 +20.978832 1.124574 0.000000 +20.978832 1.124574 0.120000 +21.041523 1.157052 0.000000 +21.041523 1.157052 0.120000 +21.097486 1.202513 0.000000 +21.097486 1.202513 0.120000 +21.142948 1.258477 0.000000 +21.142948 1.258477 0.120000 +21.175426 1.321167 0.000000 +21.175426 1.321167 0.120000 +21.194157 1.386313 0.000000 +21.194157 1.386313 0.120000 +19.200001 1.450000 0.120000 +19.200001 1.450000 0.000000 +18.500000 1.450000 0.000000 +18.500000 1.450000 0.120000 +18.505842 1.386313 0.000000 +18.505842 1.386313 0.120000 +18.524574 1.321167 0.000000 +18.524574 1.321167 0.120000 +18.557051 1.258477 0.000000 +18.602512 1.202513 0.000000 +18.557051 1.258477 0.120000 +18.602512 1.202513 0.120000 +18.658476 1.157052 0.000000 +18.658476 1.157052 0.120000 +18.721167 1.124574 0.000000 +18.721167 1.124574 0.120000 +18.786312 1.105843 0.000000 +18.786312 1.105843 0.120000 +18.850000 1.100000 0.000000 +18.850000 1.100000 0.120000 +18.913687 1.105843 0.000000 +18.913687 1.105843 0.120000 +18.978832 1.124574 0.000000 +18.978832 1.124574 0.120000 +19.041523 1.157052 0.000000 +19.041523 1.157052 0.120000 +19.097486 1.202513 0.000000 +19.097486 1.202513 0.120000 +19.142948 1.258477 0.000000 +19.142948 1.258477 0.120000 +19.175426 1.321167 0.000000 +19.194157 1.386313 0.000000 +19.175426 1.321167 0.120000 +19.194157 1.386313 0.120000 +17.200001 1.450000 0.120000 +17.200001 1.450000 0.000000 +16.505842 1.386313 0.000000 +16.500000 1.450000 0.000000 +16.500000 1.450000 0.120000 +16.505842 1.386313 0.120000 +16.524574 1.321167 0.000000 +16.557051 1.258477 0.000000 +16.524574 1.321167 0.120000 +16.557051 1.258477 0.120000 +16.602512 1.202513 0.000000 +16.602512 1.202513 0.120000 +16.658476 1.157052 0.000000 +16.658476 1.157052 0.120000 +16.721167 1.124574 0.000000 +16.721167 1.124574 0.120000 +16.786312 1.105843 0.000000 +16.786312 1.105843 0.120000 +16.850000 1.100000 0.000000 +16.850000 1.100000 0.120000 +16.913687 1.105843 0.000000 +16.913687 1.105843 0.120000 +16.978832 1.124574 0.000000 +16.978832 1.124574 0.120000 +17.041523 1.157052 0.000000 +17.041523 1.157052 0.120000 +17.097486 1.202513 0.000000 +17.097486 1.202513 0.120000 +17.142948 1.258477 0.000000 +17.175426 1.321167 0.000000 +17.142948 1.258477 0.120000 +17.175426 1.321167 0.120000 +17.194157 1.386313 0.000000 +17.194157 1.386313 0.120000 +15.200000 1.450000 0.120000 +15.200000 1.450000 0.000000 +14.500000 1.450000 0.000000 +14.500000 1.450000 0.120000 +14.505843 1.386313 0.000000 +14.505843 1.386313 0.120000 +14.524574 1.321167 0.000000 +14.524574 1.321167 0.120000 +14.557052 1.258477 0.000000 +14.557052 1.258477 0.120000 +14.602512 1.202513 0.000000 +14.602512 1.202513 0.120000 +14.658477 1.157052 0.000000 +14.658477 1.157052 0.120000 +14.721167 1.124574 0.000000 +14.786313 1.105843 0.000000 +14.721167 1.124574 0.120000 +14.786313 1.105843 0.120000 +14.850000 1.100000 0.000000 +14.850000 1.100000 0.120000 +14.913687 1.105843 0.000000 +14.913687 1.105843 0.120000 +14.978833 1.124574 0.000000 +14.978833 1.124574 0.120000 +15.041523 1.157052 0.000000 +15.041523 1.157052 0.120000 +15.097487 1.202513 0.000000 +15.097487 1.202513 0.120000 +15.142948 1.258477 0.000000 +15.142948 1.258477 0.120000 +15.175426 1.321167 0.000000 +15.175426 1.321167 0.120000 +15.194157 1.386313 0.000000 +15.194157 1.386313 0.120000 +13.200000 1.450000 0.120000 +13.200000 1.450000 0.000000 +12.500000 1.450000 0.000000 +12.500000 1.450000 0.120000 +12.505843 1.386313 0.000000 +12.505843 1.386313 0.120000 +12.524574 1.321167 0.000000 +12.524574 1.321167 0.120000 +12.557052 1.258477 0.000000 +12.557052 1.258477 0.120000 +12.602512 1.202513 0.000000 +12.602512 1.202513 0.120000 +12.658477 1.157052 0.000000 +12.658477 1.157052 0.120000 +12.721167 1.124574 0.000000 +12.721167 1.124574 0.120000 +12.786313 1.105843 0.000000 +12.786313 1.105843 0.120000 +12.850000 1.100000 0.000000 +12.913687 1.105843 0.000000 +12.850000 1.100000 0.120000 +12.913687 1.105843 0.120000 +12.978833 1.124574 0.000000 +12.978833 1.124574 0.120000 +13.041523 1.157052 0.000000 +13.041523 1.157052 0.120000 +13.097487 1.202513 0.000000 +13.097487 1.202513 0.120000 +13.142948 1.258477 0.000000 +13.142948 1.258477 0.120000 +13.175426 1.321167 0.000000 +13.194157 1.386313 0.000000 +13.175426 1.321167 0.120000 +13.194157 1.386313 0.120000 +11.200000 1.450000 0.120000 +11.200000 1.450000 0.000000 +10.500000 1.450000 0.000000 +10.500000 1.450000 0.120000 +10.505843 1.386313 0.000000 +10.505843 1.386313 0.120000 +10.524574 1.321167 0.000000 +10.524574 1.321167 0.120000 +10.557052 1.258477 0.000000 +10.557052 1.258477 0.120000 +10.602512 1.202513 0.000000 +10.602512 1.202513 0.120000 +10.658477 1.157052 0.000000 +10.658477 1.157052 0.120000 +10.721167 1.124574 0.000000 +10.721167 1.124574 0.120000 +10.786313 1.105843 0.000000 +10.786313 1.105843 0.120000 +10.850000 1.100000 0.000000 +10.850000 1.100000 0.120000 +10.913687 1.105843 0.000000 +10.913687 1.105843 0.120000 +10.978833 1.124574 0.000000 +10.978833 1.124574 0.120000 +11.041523 1.157052 0.000000 +11.041523 1.157052 0.120000 +11.097487 1.202513 0.000000 +11.097487 1.202513 0.120000 +11.142948 1.258477 0.000000 +11.142948 1.258477 0.120000 +11.175426 1.321167 0.000000 +11.175426 1.321167 0.120000 +11.194157 1.386313 0.000000 +11.194157 1.386313 0.120000 +9.200000 1.450000 0.120000 +9.200000 1.450000 0.000000 +8.500000 1.450000 0.000000 +8.500000 1.450000 0.120000 +8.505843 1.386313 0.000000 +8.505843 1.386313 0.120000 +8.524574 1.321167 0.000000 +8.524574 1.321167 0.120000 +8.557052 1.258477 0.000000 +8.557052 1.258477 0.120000 +8.602512 1.202513 0.000000 +8.602512 1.202513 0.120000 +8.658477 1.157052 0.000000 +8.658477 1.157052 0.120000 +8.721167 1.124574 0.000000 +8.721167 1.124574 0.120000 +8.786313 1.105843 0.000000 +8.786313 1.105843 0.120000 +8.850000 1.100000 0.000000 +8.850000 1.100000 0.120000 +8.913687 1.105843 0.000000 +8.913687 1.105843 0.120000 +8.978833 1.124574 0.000000 +8.978833 1.124574 0.120000 +9.041523 1.157052 0.000000 +9.041523 1.157052 0.120000 +9.097487 1.202513 0.000000 +9.097487 1.202513 0.120000 +9.142948 1.258477 0.000000 +9.142948 1.258477 0.120000 +9.175426 1.321167 0.000000 +9.194157 1.386313 0.000000 +9.175426 1.321167 0.120000 +9.194157 1.386313 0.120000 +7.200000 1.450000 0.120000 +7.200000 1.450000 0.000000 +6.500000 1.450000 0.000000 +6.500000 1.450000 0.120000 +6.505843 1.386313 0.000000 +6.505843 1.386313 0.120000 +6.524574 1.321167 0.000000 +6.557052 1.258477 0.000000 +6.524574 1.321167 0.120000 +6.557052 1.258477 0.120000 +6.602513 1.202513 0.000000 +6.602513 1.202513 0.120000 +6.658476 1.157052 0.000000 +6.658476 1.157052 0.120000 +6.721167 1.124574 0.000000 +6.721167 1.124574 0.120000 +6.786313 1.105843 0.000000 +6.786313 1.105843 0.120000 +6.850000 1.100000 0.000000 +6.850000 1.100000 0.120000 +6.913687 1.105843 0.000000 +6.913687 1.105843 0.120000 +6.978833 1.124574 0.000000 +6.978833 1.124574 0.120000 +7.041523 1.157052 0.000000 +7.097487 1.202513 0.000000 +7.041523 1.157052 0.120000 +7.097487 1.202513 0.120000 +7.142949 1.258477 0.000000 +7.142949 1.258477 0.120000 +7.175426 1.321167 0.000000 +7.175426 1.321167 0.120000 +7.194157 1.386313 0.000000 +7.194157 1.386313 0.120000 +5.200000 1.450000 0.120000 +5.200000 1.450000 0.000000 +4.500000 1.450000 0.000000 +4.500000 1.450000 0.120000 +4.505843 1.386313 0.000000 +4.505843 1.386313 0.120000 +4.524574 1.321167 0.000000 +4.557052 1.258477 0.000000 +4.524574 1.321167 0.120000 +4.557052 1.258477 0.120000 +4.602513 1.202513 0.000000 +4.602513 1.202513 0.120000 +4.658476 1.157052 0.000000 +4.658476 1.157052 0.120000 +4.721167 1.124574 0.000000 +4.721167 1.124574 0.120000 +4.786313 1.105843 0.000000 +4.786313 1.105843 0.120000 +4.850000 1.100000 0.000000 +4.850000 1.100000 0.120000 +4.913687 1.105843 0.000000 +4.913687 1.105843 0.120000 +4.978833 1.124574 0.000000 +4.978833 1.124574 0.120000 +5.041523 1.157052 0.000000 +5.041523 1.157052 0.120000 +5.097487 1.202513 0.000000 +5.097487 1.202513 0.120000 +5.142949 1.258477 0.000000 +5.142949 1.258477 0.120000 +5.175426 1.321167 0.000000 +5.175426 1.321167 0.120000 +5.194157 1.386313 0.000000 +5.194157 1.386313 0.120000 +3.200000 1.450000 0.120000 +3.200000 1.450000 0.000000 +2.500000 1.450000 0.000000 +2.500000 1.450000 0.120000 +2.505843 1.386313 0.000000 +2.505843 1.386313 0.120000 +2.524574 1.321167 0.000000 +2.524574 1.321167 0.120000 +2.557052 1.258477 0.000000 +2.557052 1.258477 0.120000 +2.602513 1.202513 0.000000 +2.602513 1.202513 0.120000 +2.658477 1.157052 0.000000 +2.658477 1.157052 0.120000 +2.721167 1.124574 0.000000 +2.721167 1.124574 0.120000 +2.786313 1.105843 0.000000 +2.786313 1.105843 0.120000 +2.850000 1.100000 0.000000 +2.850000 1.100000 0.120000 +2.913687 1.105843 0.000000 +2.913687 1.105843 0.120000 +2.978833 1.124574 0.000000 +2.978833 1.124574 0.120000 +3.041523 1.157052 0.000000 +3.041523 1.157052 0.120000 +3.097487 1.202513 0.000000 +3.097487 1.202513 0.120000 +3.142948 1.258477 0.000000 +3.142948 1.258477 0.120000 +3.175426 1.321167 0.000000 +3.175426 1.321167 0.120000 +3.194157 1.386313 0.000000 +3.194157 1.386313 0.120000 +38.194157 0.636313 0.120000 +38.200001 0.700000 0.120000 +37.500000 0.700000 0.000000 +37.500000 0.700000 0.120000 +37.505844 0.636313 0.000000 +37.505844 0.636313 0.120000 +37.524574 0.571167 0.000000 +37.524574 0.571167 0.120000 +37.557053 0.508477 0.000000 +37.602512 0.452513 0.000000 +37.557053 0.508477 0.120000 +37.602512 0.452513 0.120000 +37.658478 0.407052 0.000000 +37.658478 0.407052 0.120000 +37.721169 0.374574 0.000000 +37.721169 0.374574 0.120000 +37.786312 0.355843 0.000000 +37.786312 0.355843 0.120000 +37.849998 0.350000 0.000000 +37.849998 0.350000 0.120000 +37.913689 0.355843 0.000000 +37.913689 0.355843 0.120000 +37.978832 0.374574 0.000000 +38.041523 0.407052 0.000000 +37.978832 0.374574 0.120000 +38.041523 0.407052 0.120000 +38.097488 0.452513 0.000000 +38.142948 0.508477 0.000000 +38.097488 0.452513 0.120000 +38.142948 0.508477 0.120000 +38.175426 0.571167 0.000000 +38.175426 0.571167 0.120000 +38.194157 0.636313 0.000000 +38.200001 0.700000 0.000000 +37.505844 2.136313 0.120000 +37.500000 2.200000 0.000000 +37.500000 2.200000 0.120000 +37.505844 2.136313 0.000000 +38.194157 2.136313 0.120000 +38.200001 2.200000 0.120000 +38.200001 2.200000 0.000000 +38.194157 2.136313 0.000000 +38.175426 2.071167 0.120000 +38.142948 2.008476 0.120000 +38.175426 2.071167 0.000000 +38.142948 2.008476 0.000000 +38.097488 1.952513 0.120000 +38.097488 1.952513 0.000000 +38.041523 1.907052 0.120000 +38.041523 1.907052 0.000000 +37.978832 1.874574 0.120000 +37.978832 1.874574 0.000000 +37.913689 1.855843 0.120000 +37.913689 1.855843 0.000000 +37.849998 1.850000 0.120000 +37.849998 1.850000 0.000000 +37.786312 1.855843 0.120000 +37.786312 1.855843 0.000000 +37.721169 1.874574 0.120000 +37.721169 1.874574 0.000000 +37.658478 1.907052 0.120000 +37.658478 1.907052 0.000000 +37.602512 1.952513 0.120000 +37.557053 2.008476 0.120000 +37.602512 1.952513 0.000000 +37.557053 2.008476 0.000000 +37.524574 2.071167 0.120000 +37.524574 2.071167 0.000000 +36.194157 0.636313 0.120000 +36.200001 0.700000 0.120000 +35.500000 0.700000 0.000000 +35.500000 0.700000 0.120000 +35.505844 0.636313 0.000000 +35.505844 0.636313 0.120000 +35.524574 0.571167 0.000000 +35.557053 0.508477 0.000000 +35.524574 0.571167 0.120000 +35.557053 0.508477 0.120000 +35.602512 0.452513 0.000000 +35.602512 0.452513 0.120000 +35.658478 0.407052 0.000000 +35.658478 0.407052 0.120000 +35.721169 0.374574 0.000000 +35.721169 0.374574 0.120000 +35.786312 0.355843 0.000000 +35.786312 0.355843 0.120000 +35.849998 0.350000 0.000000 +35.849998 0.350000 0.120000 +35.913689 0.355843 0.000000 +35.913689 0.355843 0.120000 +35.978832 0.374574 0.000000 +35.978832 0.374574 0.120000 +36.041523 0.407052 0.000000 +36.041523 0.407052 0.120000 +36.097488 0.452513 0.000000 +36.142948 0.508477 0.000000 +36.097488 0.452513 0.120000 +36.142948 0.508477 0.120000 +36.175426 0.571167 0.000000 +36.175426 0.571167 0.120000 +36.194157 0.636313 0.000000 +36.200001 0.700000 0.000000 +35.500000 2.200000 0.000000 +35.500000 2.200000 0.120000 +36.194157 2.136313 0.120000 +36.200001 2.200000 0.120000 +36.200001 2.200000 0.000000 +36.175426 2.071167 0.120000 +36.194157 2.136313 0.000000 +36.175426 2.071167 0.000000 +36.142948 2.008476 0.120000 +36.097488 1.952513 0.120000 +36.142948 2.008476 0.000000 +36.097488 1.952513 0.000000 +36.041523 1.907052 0.120000 +36.041523 1.907052 0.000000 +35.978832 1.874574 0.120000 +35.978832 1.874574 0.000000 +35.913689 1.855843 0.120000 +35.913689 1.855843 0.000000 +35.849998 1.850000 0.120000 +35.786312 1.855843 0.120000 +35.849998 1.850000 0.000000 +35.786312 1.855843 0.000000 +35.721169 1.874574 0.120000 +35.721169 1.874574 0.000000 +35.658478 1.907052 0.120000 +35.658478 1.907052 0.000000 +35.602512 1.952513 0.120000 +35.602512 1.952513 0.000000 +35.557053 2.008476 0.120000 +35.557053 2.008476 0.000000 +35.524574 2.071167 0.120000 +35.524574 2.071167 0.000000 +35.505844 2.136313 0.120000 +35.505844 2.136313 0.000000 +34.194157 0.636313 0.120000 +34.200001 0.700000 0.120000 +33.500000 0.700000 0.000000 +33.500000 0.700000 0.120000 +33.505844 0.636313 0.000000 +33.505844 0.636313 0.120000 +33.524574 0.571167 0.000000 +33.524574 0.571167 0.120000 +33.557053 0.508477 0.000000 +33.602512 0.452513 0.000000 +33.557053 0.508477 0.120000 +33.602512 0.452513 0.120000 +33.658478 0.407052 0.000000 +33.658478 0.407052 0.120000 +33.721169 0.374574 0.000000 +33.721169 0.374574 0.120000 +33.786312 0.355843 0.000000 +33.786312 0.355843 0.120000 +33.849998 0.350000 0.000000 +33.849998 0.350000 0.120000 +33.913689 0.355843 0.000000 +33.913689 0.355843 0.120000 +33.978832 0.374574 0.000000 +34.041523 0.407052 0.000000 +33.978832 0.374574 0.120000 +34.041523 0.407052 0.120000 +34.097488 0.452513 0.000000 +34.142948 0.508477 0.000000 +34.097488 0.452513 0.120000 +34.142948 0.508477 0.120000 +34.175426 0.571167 0.000000 +34.175426 0.571167 0.120000 +34.194157 0.636313 0.000000 +34.200001 0.700000 0.000000 +33.500000 2.200000 0.000000 +33.500000 2.200000 0.120000 +34.194157 2.136313 0.120000 +34.200001 2.200000 0.120000 +34.200001 2.200000 0.000000 +34.175426 2.071167 0.120000 +34.194157 2.136313 0.000000 +34.175426 2.071167 0.000000 +34.142948 2.008476 0.120000 +34.142948 2.008476 0.000000 +34.097488 1.952513 0.120000 +34.097488 1.952513 0.000000 +34.041523 1.907052 0.120000 +34.041523 1.907052 0.000000 +33.978832 1.874574 0.120000 +33.978832 1.874574 0.000000 +33.913689 1.855843 0.120000 +33.913689 1.855843 0.000000 +33.849998 1.850000 0.120000 +33.849998 1.850000 0.000000 +33.786312 1.855843 0.120000 +33.786312 1.855843 0.000000 +33.721169 1.874574 0.120000 +33.721169 1.874574 0.000000 +33.658478 1.907052 0.120000 +33.658478 1.907052 0.000000 +33.602512 1.952513 0.120000 +33.602512 1.952513 0.000000 +33.557053 2.008476 0.120000 +33.557053 2.008476 0.000000 +33.524574 2.071167 0.120000 +33.524574 2.071167 0.000000 +33.505844 2.136313 0.120000 +33.505844 2.136313 0.000000 +31.500000 0.700000 0.000000 +31.500000 0.700000 0.120000 +32.200001 0.700000 0.120000 +32.200001 0.700000 0.000000 +32.194157 0.636313 0.120000 +32.194157 0.636313 0.000000 +32.175426 0.571167 0.120000 +32.175426 0.571167 0.000000 +32.142948 0.508477 0.120000 +32.142948 0.508477 0.000000 +32.097488 0.452513 0.120000 +32.097488 0.452513 0.000000 +32.041523 0.407052 0.120000 +32.041523 0.407052 0.000000 +31.978832 0.374574 0.120000 +31.978832 0.374574 0.000000 +31.913687 0.355843 0.120000 +31.913687 0.355843 0.000000 +31.850000 0.350000 0.120000 +31.850000 0.350000 0.000000 +31.786312 0.355843 0.120000 +31.786312 0.355843 0.000000 +31.721167 0.374574 0.120000 +31.721167 0.374574 0.000000 +31.658476 0.407052 0.120000 +31.658476 0.407052 0.000000 +31.602512 0.452513 0.120000 +31.602512 0.452513 0.000000 +31.557051 0.508477 0.120000 +31.557051 0.508477 0.000000 +31.524574 0.571167 0.120000 +31.505842 0.636313 0.120000 +31.524574 0.571167 0.000000 +31.505842 0.636313 0.000000 +31.524574 2.071167 0.000000 +31.505842 2.136313 0.000000 +31.500000 2.200000 0.000000 +31.500000 2.200000 0.120000 +32.194157 2.136313 0.120000 +32.200001 2.200000 0.120000 +32.200001 2.200000 0.000000 +32.194157 2.136313 0.000000 +32.175426 2.071167 0.120000 +32.175426 2.071167 0.000000 +32.142948 2.008476 0.120000 +32.142948 2.008476 0.000000 +32.097488 1.952513 0.120000 +32.041523 1.907052 0.120000 +32.097488 1.952513 0.000000 +32.041523 1.907052 0.000000 +31.978832 1.874574 0.120000 +31.978832 1.874574 0.000000 +31.913687 1.855843 0.120000 +31.850000 1.850000 0.120000 +31.913687 1.855843 0.000000 +31.786312 1.855843 0.120000 +31.850000 1.850000 0.000000 +31.786312 1.855843 0.000000 +31.721167 1.874574 0.120000 +31.721167 1.874574 0.000000 +31.658476 1.907052 0.120000 +31.658476 1.907052 0.000000 +31.602512 1.952513 0.120000 +31.602512 1.952513 0.000000 +31.557051 2.008476 0.120000 +31.524574 2.071167 0.120000 +31.557051 2.008476 0.000000 +31.505842 2.136313 0.120000 +30.200001 0.700000 0.120000 +30.200001 0.700000 0.000000 +29.500000 0.700000 0.000000 +29.500000 0.700000 0.120000 +29.505842 0.636313 0.000000 +29.505842 0.636313 0.120000 +29.524574 0.571167 0.000000 +29.524574 0.571167 0.120000 +29.557051 0.508477 0.000000 +29.557051 0.508477 0.120000 +29.602512 0.452513 0.000000 +29.602512 0.452513 0.120000 +29.658476 0.407052 0.000000 +29.721167 0.374574 0.000000 +29.658476 0.407052 0.120000 +29.721167 0.374574 0.120000 +29.786312 0.355843 0.000000 +29.786312 0.355843 0.120000 +29.850000 0.350000 0.000000 +29.850000 0.350000 0.120000 +29.913687 0.355843 0.000000 +29.913687 0.355843 0.120000 +29.978832 0.374574 0.000000 +29.978832 0.374574 0.120000 +30.041523 0.407052 0.000000 +30.041523 0.407052 0.120000 +30.097486 0.452513 0.000000 +30.097486 0.452513 0.120000 +30.142948 0.508477 0.000000 +30.142948 0.508477 0.120000 +30.175426 0.571167 0.000000 +30.175426 0.571167 0.120000 +30.194157 0.636313 0.000000 +30.194157 0.636313 0.120000 +29.602512 1.952513 0.120000 +29.505842 2.136313 0.000000 +29.500000 2.200000 0.000000 +29.500000 2.200000 0.120000 +29.505842 2.136313 0.120000 +29.524574 2.071167 0.000000 +29.524574 2.071167 0.120000 +29.557051 2.008476 0.000000 +29.602512 1.952513 0.000000 +29.557051 2.008476 0.120000 +30.200001 2.200000 0.120000 +30.200001 2.200000 0.000000 +30.194157 2.136313 0.120000 +30.194157 2.136313 0.000000 +30.175426 2.071167 0.120000 +30.142948 2.008476 0.120000 +30.175426 2.071167 0.000000 +30.142948 2.008476 0.000000 +30.097486 1.952513 0.120000 +30.097486 1.952513 0.000000 +30.041523 1.907052 0.120000 +30.041523 1.907052 0.000000 +29.978832 1.874574 0.120000 +29.978832 1.874574 0.000000 +29.913687 1.855843 0.120000 +29.913687 1.855843 0.000000 +29.850000 1.850000 0.120000 +29.850000 1.850000 0.000000 +29.786312 1.855843 0.120000 +29.786312 1.855843 0.000000 +29.721167 1.874574 0.120000 +29.658476 1.907052 0.120000 +29.721167 1.874574 0.000000 +29.658476 1.907052 0.000000 +27.500000 0.700000 0.000000 +27.500000 0.700000 0.120000 +28.200001 0.700000 0.120000 +28.200001 0.700000 0.000000 +28.194157 0.636313 0.120000 +28.194157 0.636313 0.000000 +28.175426 0.571167 0.120000 +28.175426 0.571167 0.000000 +28.142948 0.508477 0.120000 +28.142948 0.508477 0.000000 +28.097486 0.452513 0.120000 +28.097486 0.452513 0.000000 +28.041523 0.407052 0.120000 +28.041523 0.407052 0.000000 +27.978832 0.374574 0.120000 +27.978832 0.374574 0.000000 +27.913687 0.355843 0.120000 +27.913687 0.355843 0.000000 +27.850000 0.350000 0.120000 +27.850000 0.350000 0.000000 +27.786312 0.355843 0.120000 +27.786312 0.355843 0.000000 +27.721167 0.374574 0.120000 +27.658476 0.407052 0.120000 +27.721167 0.374574 0.000000 +27.658476 0.407052 0.000000 +27.602512 0.452513 0.120000 +27.602512 0.452513 0.000000 +27.557051 0.508477 0.120000 +27.557051 0.508477 0.000000 +27.524574 0.571167 0.120000 +27.505842 0.636313 0.120000 +27.524574 0.571167 0.000000 +27.505842 0.636313 0.000000 +28.200001 2.200000 0.120000 +28.200001 2.200000 0.000000 +27.505842 2.136313 0.000000 +27.500000 2.200000 0.000000 +27.500000 2.200000 0.120000 +27.505842 2.136313 0.120000 +27.524574 2.071167 0.000000 +27.557051 2.008476 0.000000 +27.524574 2.071167 0.120000 +27.602512 1.952513 0.000000 +27.557051 2.008476 0.120000 +27.658476 1.907052 0.000000 +27.602512 1.952513 0.120000 +27.658476 1.907052 0.120000 +27.721167 1.874574 0.000000 +27.786312 1.855843 0.000000 +27.721167 1.874574 0.120000 +27.786312 1.855843 0.120000 +27.850000 1.850000 0.000000 +27.850000 1.850000 0.120000 +27.913687 1.855843 0.000000 +27.913687 1.855843 0.120000 +27.978832 1.874574 0.000000 +27.978832 1.874574 0.120000 +28.041523 1.907052 0.000000 +28.041523 1.907052 0.120000 +28.097486 1.952513 0.000000 +28.097486 1.952513 0.120000 +28.142948 2.008476 0.000000 +28.142948 2.008476 0.120000 +28.175426 2.071167 0.000000 +28.175426 2.071167 0.120000 +28.194157 2.136313 0.000000 +28.194157 2.136313 0.120000 +26.200001 0.700000 0.120000 +26.200001 0.700000 0.000000 +25.500000 0.700000 0.000000 +25.500000 0.700000 0.120000 +25.505842 0.636313 0.000000 +25.505842 0.636313 0.120000 +25.524574 0.571167 0.000000 +25.557051 0.508477 0.000000 +25.524574 0.571167 0.120000 +25.557051 0.508477 0.120000 +25.602512 0.452513 0.000000 +25.602512 0.452513 0.120000 +25.658476 0.407052 0.000000 +25.658476 0.407052 0.120000 +25.721167 0.374574 0.000000 +25.721167 0.374574 0.120000 +25.786312 0.355843 0.000000 +25.786312 0.355843 0.120000 +25.850000 0.350000 0.000000 +25.850000 0.350000 0.120000 +25.913687 0.355843 0.000000 +25.913687 0.355843 0.120000 +25.978832 0.374574 0.000000 +25.978832 0.374574 0.120000 +26.041523 0.407052 0.000000 +26.097486 0.452513 0.000000 +26.041523 0.407052 0.120000 +26.097486 0.452513 0.120000 +26.142948 0.508477 0.000000 +26.142948 0.508477 0.120000 +26.175426 0.571167 0.000000 +26.175426 0.571167 0.120000 +26.194157 0.636313 0.000000 +26.194157 0.636313 0.120000 +25.557051 2.008476 0.000000 +25.500000 2.200000 0.000000 +25.500000 2.200000 0.120000 +25.505842 2.136313 0.000000 +25.505842 2.136313 0.120000 +25.524574 2.071167 0.000000 +26.200001 2.200000 0.120000 +26.200001 2.200000 0.000000 +26.194157 2.136313 0.120000 +26.194157 2.136313 0.000000 +26.175426 2.071167 0.120000 +26.142948 2.008476 0.120000 +26.175426 2.071167 0.000000 +26.142948 2.008476 0.000000 +26.097486 1.952513 0.120000 +26.097486 1.952513 0.000000 +26.041523 1.907052 0.120000 +26.041523 1.907052 0.000000 +25.978832 1.874574 0.120000 +25.978832 1.874574 0.000000 +25.913687 1.855843 0.120000 +25.850000 1.850000 0.120000 +25.913687 1.855843 0.000000 +25.850000 1.850000 0.000000 +25.786312 1.855843 0.120000 +25.786312 1.855843 0.000000 +25.721167 1.874574 0.120000 +25.721167 1.874574 0.000000 +25.658476 1.907052 0.120000 +25.658476 1.907052 0.000000 +25.602512 1.952513 0.120000 +25.602512 1.952513 0.000000 +25.557051 2.008476 0.120000 +25.524574 2.071167 0.120000 +23.500000 0.700000 0.000000 +23.500000 0.700000 0.120000 +24.200001 0.700000 0.120000 +24.200001 0.700000 0.000000 +24.194157 0.636313 0.120000 +24.194157 0.636313 0.000000 +24.175426 0.571167 0.120000 +24.142948 0.508477 0.120000 +24.175426 0.571167 0.000000 +24.142948 0.508477 0.000000 +24.097486 0.452513 0.120000 +24.097486 0.452513 0.000000 +24.041523 0.407052 0.120000 +24.041523 0.407052 0.000000 +23.978832 0.374574 0.120000 +23.978832 0.374574 0.000000 +23.913687 0.355843 0.120000 +23.850000 0.350000 0.120000 +23.913687 0.355843 0.000000 +23.850000 0.350000 0.000000 +23.786312 0.355843 0.120000 +23.786312 0.355843 0.000000 +23.721167 0.374574 0.120000 +23.721167 0.374574 0.000000 +23.658476 0.407052 0.120000 +23.658476 0.407052 0.000000 +23.602512 0.452513 0.120000 +23.602512 0.452513 0.000000 +23.557051 0.508477 0.120000 +23.557051 0.508477 0.000000 +23.524574 0.571167 0.120000 +23.524574 0.571167 0.000000 +23.505842 0.636313 0.120000 +23.505842 0.636313 0.000000 +23.524574 2.071167 0.000000 +23.500000 2.200000 0.000000 +23.500000 2.200000 0.120000 +23.505842 2.136313 0.000000 +24.200001 2.200000 0.120000 +24.200001 2.200000 0.000000 +24.194157 2.136313 0.120000 +24.194157 2.136313 0.000000 +24.175426 2.071167 0.120000 +24.142948 2.008476 0.120000 +24.175426 2.071167 0.000000 +24.142948 2.008476 0.000000 +24.097486 1.952513 0.120000 +24.097486 1.952513 0.000000 +24.041523 1.907052 0.120000 +24.041523 1.907052 0.000000 +23.978832 1.874574 0.120000 +23.913687 1.855843 0.120000 +23.978832 1.874574 0.000000 +23.913687 1.855843 0.000000 +23.850000 1.850000 0.120000 +23.850000 1.850000 0.000000 +23.786312 1.855843 0.120000 +23.786312 1.855843 0.000000 +23.721167 1.874574 0.120000 +23.721167 1.874574 0.000000 +23.658476 1.907052 0.120000 +23.658476 1.907052 0.000000 +23.602512 1.952513 0.120000 +23.602512 1.952513 0.000000 +23.557051 2.008476 0.120000 +23.557051 2.008476 0.000000 +23.524574 2.071167 0.120000 +23.505842 2.136313 0.120000 +22.200001 0.700000 0.120000 +22.200001 0.700000 0.000000 +21.500000 0.700000 0.000000 +21.500000 0.700000 0.120000 +21.505842 0.636313 0.000000 +21.524574 0.571167 0.000000 +21.505842 0.636313 0.120000 +21.524574 0.571167 0.120000 +21.557051 0.508477 0.000000 +21.557051 0.508477 0.120000 +21.602512 0.452513 0.000000 +21.602512 0.452513 0.120000 +21.658476 0.407052 0.000000 +21.658476 0.407052 0.120000 +21.721167 0.374574 0.000000 +21.721167 0.374574 0.120000 +21.786312 0.355843 0.000000 +21.786312 0.355843 0.120000 +21.850000 0.350000 0.000000 +21.850000 0.350000 0.120000 +21.913687 0.355843 0.000000 +21.913687 0.355843 0.120000 +21.978832 0.374574 0.000000 +21.978832 0.374574 0.120000 +22.041523 0.407052 0.000000 +22.097486 0.452513 0.000000 +22.041523 0.407052 0.120000 +22.097486 0.452513 0.120000 +22.142948 0.508477 0.000000 +22.142948 0.508477 0.120000 +22.175426 0.571167 0.000000 +22.194157 0.636313 0.000000 +22.175426 0.571167 0.120000 +22.194157 0.636313 0.120000 +22.200001 2.200000 0.120000 +22.200001 2.200000 0.000000 +21.505842 2.136313 0.000000 +21.500000 2.200000 0.000000 +21.500000 2.200000 0.120000 +21.505842 2.136313 0.120000 +21.524574 2.071167 0.000000 +21.524574 2.071167 0.120000 +21.557051 2.008476 0.000000 +21.557051 2.008476 0.120000 +21.602512 1.952513 0.000000 +21.602512 1.952513 0.120000 +21.658476 1.907052 0.000000 +21.658476 1.907052 0.120000 +21.721167 1.874574 0.000000 +21.721167 1.874574 0.120000 +21.786312 1.855843 0.000000 +21.786312 1.855843 0.120000 +21.850000 1.850000 0.000000 +21.850000 1.850000 0.120000 +21.913687 1.855843 0.000000 +21.913687 1.855843 0.120000 +21.978832 1.874574 0.000000 +21.978832 1.874574 0.120000 +22.041523 1.907052 0.000000 +22.097486 1.952513 0.000000 +22.041523 1.907052 0.120000 +22.097486 1.952513 0.120000 +22.142948 2.008476 0.000000 +22.142948 2.008476 0.120000 +22.175426 2.071167 0.000000 +22.194157 2.136313 0.000000 +22.175426 2.071167 0.120000 +22.194157 2.136313 0.120000 +1.500000 0.700000 0.000000 +1.500000 0.700000 0.120000 +2.200000 0.700000 0.120000 +2.200000 0.700000 0.000000 +2.194157 0.636313 0.120000 +2.194157 0.636313 0.000000 +2.175426 0.571167 0.120000 +2.175426 0.571167 0.000000 +2.142948 0.508477 0.120000 +2.142948 0.508477 0.000000 +2.097487 0.452513 0.120000 +2.097487 0.452513 0.000000 +2.041523 0.407052 0.120000 +2.041523 0.407052 0.000000 +1.978833 0.374574 0.120000 +1.978833 0.374574 0.000000 +1.913687 0.355843 0.120000 +1.913687 0.355843 0.000000 +1.850000 0.350000 0.120000 +1.850000 0.350000 0.000000 +1.786313 0.355843 0.120000 +1.786313 0.355843 0.000000 +1.721167 0.374574 0.120000 +1.721167 0.374574 0.000000 +1.658477 0.407052 0.120000 +1.658477 0.407052 0.000000 +1.602513 0.452513 0.120000 +1.602513 0.452513 0.000000 +1.557052 0.508477 0.120000 +1.557052 0.508477 0.000000 +1.524574 0.571167 0.120000 +1.524574 0.571167 0.000000 +1.505843 0.636313 0.120000 +1.505843 0.636313 0.000000 +2.200000 2.200000 0.120000 +2.200000 2.200000 0.000000 +1.500000 2.200000 0.000000 +1.500000 2.200000 0.120000 +1.505843 2.136313 0.000000 +1.505843 2.136313 0.120000 +1.524574 2.071167 0.000000 +1.524574 2.071167 0.120000 +1.557052 2.008476 0.000000 +1.557052 2.008476 0.120000 +1.602513 1.952513 0.000000 +1.602513 1.952513 0.120000 +1.658477 1.907052 0.000000 +1.658477 1.907052 0.120000 +1.721167 1.874574 0.000000 +1.721167 1.874574 0.120000 +1.786313 1.855843 0.000000 +1.786313 1.855843 0.120000 +1.850000 1.850000 0.000000 +1.850000 1.850000 0.120000 +1.913687 1.855843 0.000000 +1.913687 1.855843 0.120000 +1.978833 1.874574 0.000000 +1.978833 1.874574 0.120000 +2.041523 1.907052 0.000000 +2.041523 1.907052 0.120000 +2.097487 1.952513 0.000000 +2.142948 2.008476 0.000000 +2.097487 1.952513 0.120000 +2.142948 2.008476 0.120000 +2.175426 2.071167 0.000000 +2.175426 2.071167 0.120000 +2.194157 2.136313 0.000000 +2.194157 2.136313 0.120000 +4.200000 0.700000 0.120000 +4.200000 0.700000 0.000000 +3.500000 0.700000 0.000000 +3.500000 0.700000 0.120000 +3.505843 0.636313 0.000000 +3.505843 0.636313 0.120000 +3.524574 0.571167 0.000000 +3.524574 0.571167 0.120000 +3.557052 0.508477 0.000000 +3.557052 0.508477 0.120000 +3.602513 0.452513 0.000000 +3.602513 0.452513 0.120000 +3.658477 0.407052 0.000000 +3.658477 0.407052 0.120000 +3.721167 0.374574 0.000000 +3.721167 0.374574 0.120000 +3.786313 0.355843 0.000000 +3.786313 0.355843 0.120000 +3.850000 0.350000 0.000000 +3.850000 0.350000 0.120000 +3.913687 0.355843 0.000000 +3.913687 0.355843 0.120000 +3.978833 0.374574 0.000000 +3.978833 0.374574 0.120000 +4.041523 0.407052 0.000000 +4.041523 0.407052 0.120000 +4.097487 0.452513 0.000000 +4.097487 0.452513 0.120000 +4.142949 0.508477 0.000000 +4.142949 0.508477 0.120000 +4.175426 0.571167 0.000000 +4.175426 0.571167 0.120000 +4.194157 0.636313 0.000000 +4.194157 0.636313 0.120000 +4.200000 2.200000 0.120000 +4.200000 2.200000 0.000000 +3.500000 2.200000 0.000000 +3.500000 2.200000 0.120000 +3.505843 2.136313 0.000000 +3.505843 2.136313 0.120000 +3.524574 2.071167 0.000000 +3.524574 2.071167 0.120000 +3.557052 2.008476 0.000000 +3.602513 1.952513 0.000000 +3.557052 2.008476 0.120000 +3.602513 1.952513 0.120000 +3.658477 1.907052 0.000000 +3.658477 1.907052 0.120000 +3.721167 1.874574 0.000000 +3.721167 1.874574 0.120000 +3.786313 1.855843 0.000000 +3.786313 1.855843 0.120000 +3.850000 1.850000 0.000000 +3.850000 1.850000 0.120000 +3.913687 1.855843 0.000000 +3.913687 1.855843 0.120000 +3.978833 1.874574 0.000000 +4.041523 1.907052 0.000000 +3.978833 1.874574 0.120000 +4.041523 1.907052 0.120000 +4.097487 1.952513 0.000000 +4.142949 2.008476 0.000000 +4.097487 1.952513 0.120000 +4.175426 2.071167 0.000000 +4.142949 2.008476 0.120000 +4.194157 2.136313 0.000000 +4.175426 2.071167 0.120000 +4.194157 2.136313 0.120000 +5.505843 0.636313 0.000000 +5.500000 0.700000 0.000000 +6.200000 0.700000 0.120000 +6.200000 0.700000 0.000000 +6.194157 0.636313 0.120000 +6.194157 0.636313 0.000000 +6.175426 0.571167 0.120000 +6.175426 0.571167 0.000000 +6.142949 0.508477 0.120000 +6.142949 0.508477 0.000000 +6.097487 0.452513 0.120000 +6.097487 0.452513 0.000000 +6.041523 0.407052 0.120000 +6.041523 0.407052 0.000000 +5.978833 0.374574 0.120000 +5.978833 0.374574 0.000000 +5.913687 0.355843 0.120000 +5.913687 0.355843 0.000000 +5.850000 0.350000 0.120000 +5.850000 0.350000 0.000000 +5.786313 0.355843 0.120000 +5.786313 0.355843 0.000000 +5.721167 0.374574 0.120000 +5.721167 0.374574 0.000000 +5.658476 0.407052 0.120000 +5.658476 0.407052 0.000000 +5.602513 0.452513 0.120000 +5.602513 0.452513 0.000000 +5.557052 0.508477 0.120000 +5.557052 0.508477 0.000000 +5.524574 0.571167 0.120000 +5.524574 0.571167 0.000000 +5.505843 0.636313 0.120000 +5.500000 0.700000 0.120000 +6.200000 2.200000 0.120000 +6.200000 2.200000 0.000000 +5.500000 2.200000 0.000000 +5.500000 2.200000 0.120000 +5.505843 2.136313 0.000000 +5.505843 2.136313 0.120000 +5.524574 2.071167 0.000000 +5.524574 2.071167 0.120000 +5.557052 2.008476 0.000000 +5.557052 2.008476 0.120000 +5.602513 1.952513 0.000000 +5.602513 1.952513 0.120000 +5.658476 1.907052 0.000000 +5.658476 1.907052 0.120000 +5.721167 1.874574 0.000000 +5.721167 1.874574 0.120000 +5.786313 1.855843 0.000000 +5.786313 1.855843 0.120000 +5.850000 1.850000 0.000000 +5.850000 1.850000 0.120000 +5.913687 1.855843 0.000000 +5.913687 1.855843 0.120000 +5.978833 1.874574 0.000000 +5.978833 1.874574 0.120000 +6.041523 1.907052 0.000000 +6.041523 1.907052 0.120000 +6.097487 1.952513 0.000000 +6.142949 2.008476 0.000000 +6.097487 1.952513 0.120000 +6.175426 2.071167 0.000000 +6.142949 2.008476 0.120000 +6.194157 2.136313 0.000000 +6.175426 2.071167 0.120000 +6.194157 2.136313 0.120000 +7.500000 0.700000 0.000000 +7.500000 0.700000 0.120000 +8.200000 0.700000 0.120000 +8.200000 0.700000 0.000000 +8.194157 0.636313 0.120000 +8.194157 0.636313 0.000000 +8.175426 0.571167 0.120000 +8.175426 0.571167 0.000000 +8.142948 0.508477 0.120000 +8.142948 0.508477 0.000000 +8.097487 0.452513 0.120000 +8.041523 0.407052 0.120000 +8.097487 0.452513 0.000000 +8.041523 0.407052 0.000000 +7.978833 0.374574 0.120000 +7.978833 0.374574 0.000000 +7.913687 0.355843 0.120000 +7.913687 0.355843 0.000000 +7.850000 0.350000 0.120000 +7.850000 0.350000 0.000000 +7.786313 0.355843 0.120000 +7.786313 0.355843 0.000000 +7.721167 0.374574 0.120000 +7.658476 0.407052 0.120000 +7.721167 0.374574 0.000000 +7.658476 0.407052 0.000000 +7.602513 0.452513 0.120000 +7.602513 0.452513 0.000000 +7.557052 0.508477 0.120000 +7.557052 0.508477 0.000000 +7.524574 0.571167 0.120000 +7.505843 0.636313 0.120000 +7.524574 0.571167 0.000000 +7.505843 0.636313 0.000000 +7.500000 2.200000 0.000000 +7.500000 2.200000 0.120000 +8.200000 2.200000 0.120000 +8.200000 2.200000 0.000000 +8.194157 2.136313 0.120000 +8.194157 2.136313 0.000000 +8.175426 2.071167 0.120000 +8.175426 2.071167 0.000000 +8.142948 2.008476 0.120000 +8.142948 2.008476 0.000000 +8.097487 1.952513 0.120000 +8.097487 1.952513 0.000000 +8.041523 1.907052 0.120000 +8.041523 1.907052 0.000000 +7.978833 1.874574 0.120000 +7.978833 1.874574 0.000000 +7.913687 1.855843 0.120000 +7.913687 1.855843 0.000000 +7.850000 1.850000 0.120000 +7.786313 1.855843 0.120000 +7.850000 1.850000 0.000000 +7.786313 1.855843 0.000000 +7.721167 1.874574 0.120000 +7.658476 1.907052 0.120000 +7.721167 1.874574 0.000000 +7.658476 1.907052 0.000000 +7.602513 1.952513 0.120000 +7.602513 1.952513 0.000000 +7.557052 2.008476 0.120000 +7.557052 2.008476 0.000000 +7.524574 2.071167 0.120000 +7.524574 2.071167 0.000000 +7.505843 2.136313 0.120000 +7.505843 2.136313 0.000000 +9.505843 0.636313 0.120000 +9.500000 0.700000 0.000000 +9.500000 0.700000 0.120000 +9.505843 0.636313 0.000000 +10.200000 0.700000 0.120000 +10.200000 0.700000 0.000000 +10.194157 0.636313 0.120000 +10.194157 0.636313 0.000000 +10.175426 0.571167 0.120000 +10.175426 0.571167 0.000000 +10.142948 0.508477 0.120000 +10.097487 0.452513 0.120000 +10.142948 0.508477 0.000000 +10.097487 0.452513 0.000000 +10.041523 0.407052 0.120000 +10.041523 0.407052 0.000000 +9.978833 0.374574 0.120000 +9.978833 0.374574 0.000000 +9.913687 0.355843 0.120000 +9.913687 0.355843 0.000000 +9.850000 0.350000 0.120000 +9.850000 0.350000 0.000000 +9.786313 0.355843 0.120000 +9.786313 0.355843 0.000000 +9.721167 0.374574 0.120000 +9.721167 0.374574 0.000000 +9.658477 0.407052 0.120000 +9.658477 0.407052 0.000000 +9.602512 0.452513 0.120000 +9.602512 0.452513 0.000000 +9.557052 0.508477 0.120000 +9.557052 0.508477 0.000000 +9.524574 0.571167 0.120000 +9.524574 0.571167 0.000000 +9.500000 2.200000 0.000000 +9.500000 2.200000 0.120000 +10.200000 2.200000 0.120000 +10.200000 2.200000 0.000000 +10.194157 2.136313 0.120000 +10.194157 2.136313 0.000000 +10.175426 2.071167 0.120000 +10.175426 2.071167 0.000000 +10.142948 2.008476 0.120000 +10.142948 2.008476 0.000000 +10.097487 1.952513 0.120000 +10.041523 1.907052 0.120000 +10.097487 1.952513 0.000000 +10.041523 1.907052 0.000000 +9.978833 1.874574 0.120000 +9.978833 1.874574 0.000000 +9.913687 1.855843 0.120000 +9.913687 1.855843 0.000000 +9.850000 1.850000 0.120000 +9.850000 1.850000 0.000000 +9.786313 1.855843 0.120000 +9.721167 1.874574 0.120000 +9.786313 1.855843 0.000000 +9.658477 1.907052 0.120000 +9.721167 1.874574 0.000000 +9.658477 1.907052 0.000000 +9.602512 1.952513 0.120000 +9.602512 1.952513 0.000000 +9.557052 2.008476 0.120000 +9.557052 2.008476 0.000000 +9.524574 2.071167 0.120000 +9.505843 2.136313 0.120000 +9.524574 2.071167 0.000000 +9.505843 2.136313 0.000000 +12.200000 0.700000 0.120000 +12.200000 0.700000 0.000000 +11.500000 0.700000 0.000000 +11.500000 0.700000 0.120000 +11.505843 0.636313 0.000000 +11.505843 0.636313 0.120000 +11.524574 0.571167 0.000000 +11.524574 0.571167 0.120000 +11.557052 0.508477 0.000000 +11.557052 0.508477 0.120000 +11.602512 0.452513 0.000000 +11.602512 0.452513 0.120000 +11.658477 0.407052 0.000000 +11.658477 0.407052 0.120000 +11.721167 0.374574 0.000000 +11.721167 0.374574 0.120000 +11.786313 0.355843 0.000000 +11.786313 0.355843 0.120000 +11.850000 0.350000 0.000000 +11.850000 0.350000 0.120000 +11.913687 0.355843 0.000000 +11.913687 0.355843 0.120000 +11.978833 0.374574 0.000000 +11.978833 0.374574 0.120000 +12.041523 0.407052 0.000000 +12.041523 0.407052 0.120000 +12.097487 0.452513 0.000000 +12.097487 0.452513 0.120000 +12.142948 0.508477 0.000000 +12.175426 0.571167 0.000000 +12.142948 0.508477 0.120000 +12.175426 0.571167 0.120000 +12.194157 0.636313 0.000000 +12.194157 0.636313 0.120000 +12.200000 2.200000 0.120000 +12.200000 2.200000 0.000000 +11.500000 2.200000 0.000000 +11.500000 2.200000 0.120000 +11.505843 2.136313 0.000000 +11.505843 2.136313 0.120000 +11.524574 2.071167 0.000000 +11.524574 2.071167 0.120000 +11.557052 2.008476 0.000000 +11.602512 1.952513 0.000000 +11.557052 2.008476 0.120000 +11.602512 1.952513 0.120000 +11.658477 1.907052 0.000000 +11.658477 1.907052 0.120000 +11.721167 1.874574 0.000000 +11.786313 1.855843 0.000000 +11.721167 1.874574 0.120000 +11.786313 1.855843 0.120000 +11.850000 1.850000 0.000000 +11.913687 1.855843 0.000000 +11.850000 1.850000 0.120000 +11.913687 1.855843 0.120000 +11.978833 1.874574 0.000000 +11.978833 1.874574 0.120000 +12.041523 1.907052 0.000000 +12.041523 1.907052 0.120000 +12.097487 1.952513 0.000000 +12.142948 2.008476 0.000000 +12.097487 1.952513 0.120000 +12.142948 2.008476 0.120000 +12.175426 2.071167 0.000000 +12.175426 2.071167 0.120000 +12.194157 2.136313 0.000000 +12.194157 2.136313 0.120000 +13.505843 0.636313 0.120000 +13.500000 0.700000 0.000000 +13.500000 0.700000 0.120000 +13.505843 0.636313 0.000000 +14.200000 0.700000 0.120000 +14.200000 0.700000 0.000000 +14.194157 0.636313 0.120000 +14.194157 0.636313 0.000000 +14.175426 0.571167 0.120000 +14.175426 0.571167 0.000000 +14.142948 0.508477 0.120000 +14.097487 0.452513 0.120000 +14.142948 0.508477 0.000000 +14.097487 0.452513 0.000000 +14.041523 0.407052 0.120000 +14.041523 0.407052 0.000000 +13.978833 0.374574 0.120000 +13.978833 0.374574 0.000000 +13.913687 0.355843 0.120000 +13.913687 0.355843 0.000000 +13.850000 0.350000 0.120000 +13.850000 0.350000 0.000000 +13.786313 0.355843 0.120000 +13.786313 0.355843 0.000000 +13.721167 0.374574 0.120000 +13.721167 0.374574 0.000000 +13.658477 0.407052 0.120000 +13.658477 0.407052 0.000000 +13.602512 0.452513 0.120000 +13.602512 0.452513 0.000000 +13.557052 0.508477 0.120000 +13.557052 0.508477 0.000000 +13.524574 0.571167 0.120000 +13.524574 0.571167 0.000000 +13.505843 2.136313 0.120000 +13.505843 2.136313 0.000000 +13.500000 2.200000 0.000000 +13.500000 2.200000 0.120000 +14.200000 2.200000 0.120000 +14.200000 2.200000 0.000000 +14.194157 2.136313 0.120000 +14.194157 2.136313 0.000000 +14.175426 2.071167 0.120000 +14.175426 2.071167 0.000000 +14.142948 2.008476 0.120000 +14.142948 2.008476 0.000000 +14.097487 1.952513 0.120000 +14.097487 1.952513 0.000000 +14.041523 1.907052 0.120000 +14.041523 1.907052 0.000000 +13.978833 1.874574 0.120000 +13.978833 1.874574 0.000000 +13.913687 1.855843 0.120000 +13.850000 1.850000 0.120000 +13.913687 1.855843 0.000000 +13.786313 1.855843 0.120000 +13.850000 1.850000 0.000000 +13.786313 1.855843 0.000000 +13.721167 1.874574 0.120000 +13.721167 1.874574 0.000000 +13.658477 1.907052 0.120000 +13.658477 1.907052 0.000000 +13.602512 1.952513 0.120000 +13.602512 1.952513 0.000000 +13.557052 2.008476 0.120000 +13.557052 2.008476 0.000000 +13.524574 2.071167 0.120000 +13.524574 2.071167 0.000000 +15.524574 0.571167 0.120000 +15.500000 0.700000 0.000000 +15.500000 0.700000 0.120000 +15.505843 0.636313 0.000000 +15.505843 0.636313 0.120000 +15.524574 0.571167 0.000000 +16.200001 0.700000 0.120000 +16.200001 0.700000 0.000000 +16.194157 0.636313 0.120000 +16.194157 0.636313 0.000000 +16.175426 0.571167 0.120000 +16.175426 0.571167 0.000000 +16.142948 0.508477 0.120000 +16.097486 0.452513 0.120000 +16.142948 0.508477 0.000000 +16.097486 0.452513 0.000000 +16.041523 0.407052 0.120000 +16.041523 0.407052 0.000000 +15.978833 0.374574 0.120000 +15.978833 0.374574 0.000000 +15.913687 0.355843 0.120000 +15.913687 0.355843 0.000000 +15.850000 0.350000 0.120000 +15.850000 0.350000 0.000000 +15.786313 0.355843 0.120000 +15.786313 0.355843 0.000000 +15.721167 0.374574 0.120000 +15.721167 0.374574 0.000000 +15.658477 0.407052 0.120000 +15.658477 0.407052 0.000000 +15.602512 0.452513 0.120000 +15.557052 0.508477 0.120000 +15.602512 0.452513 0.000000 +15.557052 0.508477 0.000000 +15.524574 2.071167 0.120000 +15.500000 2.200000 0.000000 +15.500000 2.200000 0.120000 +15.505843 2.136313 0.000000 +15.505843 2.136313 0.120000 +15.524574 2.071167 0.000000 +16.194157 2.136313 0.120000 +16.200001 2.200000 0.120000 +16.200001 2.200000 0.000000 +16.194157 2.136313 0.000000 +16.175426 2.071167 0.120000 +16.175426 2.071167 0.000000 +16.142948 2.008476 0.120000 +16.142948 2.008476 0.000000 +16.097486 1.952513 0.120000 +16.097486 1.952513 0.000000 +16.041523 1.907052 0.120000 +16.041523 1.907052 0.000000 +15.978833 1.874574 0.120000 +15.978833 1.874574 0.000000 +15.913687 1.855843 0.120000 +15.913687 1.855843 0.000000 +15.850000 1.850000 0.120000 +15.850000 1.850000 0.000000 +15.786313 1.855843 0.120000 +15.786313 1.855843 0.000000 +15.721167 1.874574 0.120000 +15.658477 1.907052 0.120000 +15.721167 1.874574 0.000000 +15.658477 1.907052 0.000000 +15.602512 1.952513 0.120000 +15.557052 2.008476 0.120000 +15.602512 1.952513 0.000000 +15.557052 2.008476 0.000000 +17.500000 0.700000 0.000000 +17.500000 0.700000 0.120000 +18.200001 0.700000 0.120000 +18.200001 0.700000 0.000000 +18.194157 0.636313 0.120000 +18.194157 0.636313 0.000000 +18.175426 0.571167 0.120000 +18.175426 0.571167 0.000000 +18.142948 0.508477 0.120000 +18.142948 0.508477 0.000000 +18.097486 0.452513 0.120000 +18.097486 0.452513 0.000000 +18.041523 0.407052 0.120000 +18.041523 0.407052 0.000000 +17.978832 0.374574 0.120000 +17.978832 0.374574 0.000000 +17.913687 0.355843 0.120000 +17.850000 0.350000 0.120000 +17.913687 0.355843 0.000000 +17.850000 0.350000 0.000000 +17.786312 0.355843 0.120000 +17.786312 0.355843 0.000000 +17.721167 0.374574 0.120000 +17.721167 0.374574 0.000000 +17.658476 0.407052 0.120000 +17.658476 0.407052 0.000000 +17.602512 0.452513 0.120000 +17.602512 0.452513 0.000000 +17.557051 0.508477 0.120000 +17.524574 0.571167 0.120000 +17.557051 0.508477 0.000000 +17.524574 0.571167 0.000000 +17.505842 0.636313 0.120000 +17.505842 0.636313 0.000000 +18.200001 2.200000 0.120000 +18.200001 2.200000 0.000000 +17.500000 2.200000 0.000000 +17.500000 2.200000 0.120000 +17.505842 2.136313 0.000000 +17.505842 2.136313 0.120000 +17.524574 2.071167 0.000000 +17.557051 2.008476 0.000000 +17.524574 2.071167 0.120000 +17.557051 2.008476 0.120000 +17.602512 1.952513 0.000000 +17.602512 1.952513 0.120000 +17.658476 1.907052 0.000000 +17.658476 1.907052 0.120000 +17.721167 1.874574 0.000000 +17.721167 1.874574 0.120000 +17.786312 1.855843 0.000000 +17.786312 1.855843 0.120000 +17.850000 1.850000 0.000000 +17.850000 1.850000 0.120000 +17.913687 1.855843 0.000000 +17.913687 1.855843 0.120000 +17.978832 1.874574 0.000000 +17.978832 1.874574 0.120000 +18.041523 1.907052 0.000000 +18.041523 1.907052 0.120000 +18.097486 1.952513 0.000000 +18.097486 1.952513 0.120000 +18.142948 2.008476 0.000000 +18.142948 2.008476 0.120000 +18.175426 2.071167 0.000000 +18.175426 2.071167 0.120000 +18.194157 2.136313 0.000000 +18.194157 2.136313 0.120000 +19.500000 0.700000 0.000000 +19.500000 0.700000 0.120000 +20.200001 0.700000 0.120000 +20.200001 0.700000 0.000000 +20.194157 0.636313 0.120000 +20.194157 0.636313 0.000000 +20.175426 0.571167 0.120000 +20.142948 0.508477 0.120000 +20.175426 0.571167 0.000000 +20.142948 0.508477 0.000000 +20.097486 0.452513 0.120000 +20.097486 0.452513 0.000000 +20.041523 0.407052 0.120000 +20.041523 0.407052 0.000000 +19.978832 0.374574 0.120000 +19.978832 0.374574 0.000000 +19.913687 0.355843 0.120000 +19.850000 0.350000 0.120000 +19.913687 0.355843 0.000000 +19.850000 0.350000 0.000000 +19.786312 0.355843 0.120000 +19.786312 0.355843 0.000000 +19.721167 0.374574 0.120000 +19.721167 0.374574 0.000000 +19.658476 0.407052 0.120000 +19.658476 0.407052 0.000000 +19.602512 0.452513 0.120000 +19.602512 0.452513 0.000000 +19.557051 0.508477 0.120000 +19.557051 0.508477 0.000000 +19.524574 0.571167 0.120000 +19.524574 0.571167 0.000000 +19.505842 0.636313 0.120000 +19.505842 0.636313 0.000000 +19.500000 2.200000 0.000000 +19.500000 2.200000 0.120000 +20.200001 2.200000 0.120000 +20.200001 2.200000 0.000000 +20.194157 2.136313 0.120000 +20.194157 2.136313 0.000000 +20.175426 2.071167 0.120000 +20.142948 2.008476 0.120000 +20.175426 2.071167 0.000000 +20.142948 2.008476 0.000000 +20.097486 1.952513 0.120000 +20.097486 1.952513 0.000000 +20.041523 1.907052 0.120000 +20.041523 1.907052 0.000000 +19.978832 1.874574 0.120000 +19.978832 1.874574 0.000000 +19.913687 1.855843 0.120000 +19.913687 1.855843 0.000000 +19.850000 1.850000 0.120000 +19.850000 1.850000 0.000000 +19.786312 1.855843 0.120000 +19.786312 1.855843 0.000000 +19.721167 1.874574 0.120000 +19.658476 1.907052 0.120000 +19.721167 1.874574 0.000000 +19.658476 1.907052 0.000000 +19.602512 1.952513 0.120000 +19.602512 1.952513 0.000000 +19.557051 2.008476 0.120000 +19.557051 2.008476 0.000000 +19.524574 2.071167 0.120000 +19.524574 2.071167 0.000000 +19.505842 2.136313 0.120000 +19.505842 2.136313 0.000000 +0.000000 0.000000 0.120000 +0.000000 2.900000 0.120000 +0.000000 2.900000 0.000000 +0.000000 0.000000 0.000000 +39.700001 0.000000 0.120000 +0.000000 0.000000 0.120000 +0.000000 0.000000 0.000000 +39.700001 0.000000 0.000000 +39.700001 2.900000 0.120000 +39.700001 0.000000 0.120000 +39.700001 0.000000 0.000000 +39.700001 2.900000 0.000000 +0.000000 2.900000 0.120000 +39.700001 2.900000 0.120000 +39.700001 2.900000 0.000000 +0.000000 2.900000 0.000000 +0.000000 2.900000 0.120000 +1.524574 0.571167 0.120000 +1.505843 0.636313 0.120000 +1.500000 0.700000 0.120000 +1.505843 0.763687 0.120000 +1.524574 0.828833 0.120000 +1.557052 0.891523 0.120000 +2.602513 1.202513 0.120000 +3.142948 1.258477 0.120000 +4.602513 1.202513 0.120000 +5.142949 1.258477 0.120000 +6.602513 1.202513 0.120000 +7.142949 1.258477 0.120000 +8.602512 1.202513 0.120000 +9.142948 1.258477 0.120000 +10.602512 1.202513 0.120000 +11.602512 1.952513 0.120000 +12.142948 2.008476 0.120000 +12.097487 0.947487 0.120000 +12.602512 1.202513 0.120000 +13.142948 1.258477 0.120000 +14.602512 1.202513 0.120000 +15.142948 1.258477 0.120000 +15.557052 0.891523 0.120000 +15.602512 1.952513 0.120000 +16.142948 2.008476 0.120000 +17.142948 1.258477 0.120000 +18.602512 1.202513 0.120000 +19.142948 1.258477 0.120000 +20.602512 1.202513 0.120000 +21.142948 1.258477 0.120000 +22.602512 1.202513 0.120000 +23.142948 1.258477 0.120000 +24.602512 1.202513 0.120000 +25.142948 1.258477 0.120000 +26.602512 1.202513 0.120000 +27.142948 1.258477 0.120000 +27.557051 0.891523 0.120000 +27.602512 1.952513 0.120000 +28.142948 2.008476 0.120000 +29.142948 1.258477 0.120000 +30.602512 1.202513 0.120000 +31.602512 1.952513 0.120000 +32.142948 2.008476 0.120000 +32.097488 0.947487 0.120000 +32.602512 1.202513 0.120000 +33.142948 1.258477 0.120000 +34.602512 1.202513 0.120000 +35.602512 1.952513 0.120000 +36.142948 2.008476 0.120000 +36.097488 0.947487 0.120000 +36.602512 1.202513 0.120000 +37.142948 1.258477 0.120000 +37.557053 0.891523 0.120000 +37.602512 1.952513 0.120000 +37.097488 1.697487 0.120000 +36.557053 1.641523 0.120000 +35.097488 1.697487 0.120000 +34.557053 1.641523 0.120000 +34.142948 2.008476 0.120000 +34.097488 0.947487 0.120000 +33.557053 0.891523 0.120000 +32.557053 1.641523 0.120000 +31.097486 1.697487 0.120000 +30.097486 0.947487 0.120000 +29.557051 0.891523 0.120000 +29.602512 1.952513 0.120000 +29.097486 1.697487 0.120000 +28.557051 1.641523 0.120000 +27.097486 1.697487 0.120000 +26.557051 1.641523 0.120000 +26.142948 2.008476 0.120000 +26.097486 0.947487 0.120000 +25.557051 0.891523 0.120000 +24.097486 0.947487 0.120000 +23.557051 0.891523 0.120000 +23.602512 1.952513 0.120000 +23.097486 1.697487 0.120000 +22.557051 1.641523 0.120000 +22.142948 2.008476 0.120000 +22.097486 0.947487 0.120000 +21.557051 0.891523 0.120000 +20.097486 0.947487 0.120000 +19.557051 0.891523 0.120000 +19.602512 1.952513 0.120000 +19.097486 1.697487 0.120000 +18.557051 1.641523 0.120000 +18.142948 2.008476 0.120000 +18.097486 0.947487 0.120000 +17.557051 0.891523 0.120000 +16.557051 1.641523 0.120000 +15.097487 1.697487 0.120000 +14.557052 1.641523 0.120000 +14.142948 2.008476 0.120000 +14.097487 0.947487 0.120000 +13.557052 0.891523 0.120000 +12.557052 1.641523 0.120000 +11.097487 1.697487 0.120000 +10.557052 1.641523 0.120000 +10.142948 2.008476 0.120000 +10.097487 0.947487 0.120000 +9.557052 0.891523 0.120000 +8.557052 1.641523 0.120000 +8.142948 2.008476 0.120000 +8.097487 0.947487 0.120000 +7.557052 0.891523 0.120000 +6.557052 1.641523 0.120000 +6.142949 2.008476 0.120000 +6.097487 0.947487 0.120000 +5.557052 0.891523 0.120000 +4.097487 0.947487 0.120000 +3.557052 0.891523 0.120000 +3.602513 1.952513 0.120000 +3.097487 1.697487 0.120000 +2.557052 1.641523 0.120000 +2.142948 2.008476 0.120000 +2.097487 0.947487 0.120000 +1.602513 0.947487 0.120000 +2.142948 0.891523 0.120000 +3.524574 0.828833 0.120000 +4.142949 0.891523 0.120000 +5.524574 0.828833 0.120000 +6.142949 0.891523 0.120000 +7.524574 0.828833 0.120000 +8.142948 0.891523 0.120000 +9.524574 0.828833 0.120000 +10.142948 0.891523 0.120000 +11.142948 1.641523 0.120000 +12.524574 1.578833 0.120000 +12.557052 1.258477 0.120000 +12.142948 0.891523 0.120000 +13.524574 0.828833 0.120000 +14.142948 0.891523 0.120000 +15.524574 0.828833 0.120000 +15.175426 1.321167 0.120000 +15.142948 1.641523 0.120000 +16.524574 1.578833 0.120000 +17.524574 0.828833 0.120000 +18.142948 0.891523 0.120000 +19.524574 0.828833 0.120000 +20.142948 0.891523 0.120000 +21.524574 0.828833 0.120000 +22.142948 0.891523 0.120000 +23.524574 0.828833 0.120000 +24.142948 0.891523 0.120000 +25.524574 0.828833 0.120000 +26.142948 0.891523 0.120000 +27.524574 0.828833 0.120000 +27.175426 1.321167 0.120000 +27.142948 1.641523 0.120000 +28.524574 1.578833 0.120000 +29.524574 0.828833 0.120000 +30.142948 0.891523 0.120000 +31.142948 1.641523 0.120000 +32.524574 1.578833 0.120000 +32.557053 1.258477 0.120000 +32.142948 0.891523 0.120000 +33.524574 0.828833 0.120000 +34.142948 0.891523 0.120000 +35.142948 1.641523 0.120000 +36.524574 1.578833 0.120000 +36.557053 1.258477 0.120000 +36.142948 0.891523 0.120000 +37.524574 0.828833 0.120000 +37.175426 1.321167 0.120000 +37.142948 1.641523 0.120000 +37.557053 2.008476 0.120000 +36.175426 2.071167 0.120000 +35.557053 2.008476 0.120000 +34.175426 2.071167 0.120000 +34.524574 1.578833 0.120000 +34.557053 1.258477 0.120000 +33.175426 1.321167 0.120000 +32.175426 2.071167 0.120000 +31.557051 2.008476 0.120000 +30.557051 1.258477 0.120000 +29.175426 1.321167 0.120000 +29.142948 1.641523 0.120000 +29.557051 2.008476 0.120000 +28.175426 2.071167 0.120000 +27.557051 2.008476 0.120000 +26.175426 2.071167 0.120000 +26.524574 1.578833 0.120000 +26.557051 1.258477 0.120000 +25.175426 1.321167 0.120000 +24.557051 1.258477 0.120000 +23.175426 1.321167 0.120000 +23.142948 1.641523 0.120000 +23.557051 2.008476 0.120000 +22.175426 2.071167 0.120000 +22.524574 1.578833 0.120000 +22.557051 1.258477 0.120000 +21.175426 1.321167 0.120000 +20.557051 1.258477 0.120000 +19.175426 1.321167 0.120000 +19.142948 1.641523 0.120000 +19.557051 2.008476 0.120000 +18.175426 2.071167 0.120000 +18.524574 1.578833 0.120000 +18.557051 1.258477 0.120000 +17.175426 1.321167 0.120000 +16.175426 2.071167 0.120000 +15.557052 2.008476 0.120000 +14.175426 2.071167 0.120000 +14.524574 1.578833 0.120000 +14.557052 1.258477 0.120000 +13.175426 1.321167 0.120000 +12.175426 2.071167 0.120000 +11.557052 2.008476 0.120000 +10.175426 2.071167 0.120000 +10.524574 1.578833 0.120000 +10.557052 1.258477 0.120000 +9.175426 1.321167 0.120000 +8.175426 2.071167 0.120000 +8.524574 1.578833 0.120000 +8.557052 1.258477 0.120000 +7.175426 1.321167 0.120000 +6.175426 2.071167 0.120000 +6.524574 1.578833 0.120000 +6.557052 1.258477 0.120000 +5.175426 1.321167 0.120000 +4.557052 1.258477 0.120000 +3.175426 1.321167 0.120000 +3.142948 1.641523 0.120000 +3.557052 2.008476 0.120000 +2.175426 2.071167 0.120000 +2.524574 1.578833 0.120000 +2.557052 1.258477 0.120000 +1.557052 0.508477 0.120000 +2.658477 1.157052 0.120000 +3.097487 1.202513 0.120000 +4.658476 1.157052 0.120000 +5.097487 1.202513 0.120000 +6.658476 1.157052 0.120000 +7.097487 1.202513 0.120000 +8.658477 1.157052 0.120000 +9.097487 1.202513 0.120000 +10.658477 1.157052 0.120000 +11.658477 1.907052 0.120000 +12.097487 1.952513 0.120000 +12.041523 0.992948 0.120000 +12.658477 1.157052 0.120000 +13.097487 1.202513 0.120000 +14.658477 1.157052 0.120000 +15.097487 1.202513 0.120000 +15.602512 0.947487 0.120000 +15.658477 1.907052 0.120000 +16.097486 1.952513 0.120000 +17.097486 1.202513 0.120000 +18.658476 1.157052 0.120000 +19.097486 1.202513 0.120000 +20.658476 1.157052 0.120000 +21.097486 1.202513 0.120000 +22.658476 1.157052 0.120000 +23.097486 1.202513 0.120000 +24.658476 1.157052 0.120000 +25.097486 1.202513 0.120000 +26.658476 1.157052 0.120000 +27.097486 1.202513 0.120000 +27.602512 0.947487 0.120000 +27.658476 1.907052 0.120000 +28.097486 1.952513 0.120000 +29.097486 1.202513 0.120000 +30.658476 1.157052 0.120000 +31.658476 1.907052 0.120000 +32.097488 1.952513 0.120000 +32.041523 0.992948 0.120000 +32.658478 1.157052 0.120000 +33.097488 1.202513 0.120000 +34.658478 1.157052 0.120000 +35.658478 1.907052 0.120000 +36.097488 1.952513 0.120000 +36.041523 0.992948 0.120000 +36.658478 1.157052 0.120000 +37.097488 1.202513 0.120000 +37.602512 0.947487 0.120000 +37.658478 1.907052 0.120000 +37.041523 1.742948 0.120000 +36.602512 1.697487 0.120000 +35.041523 1.742948 0.120000 +34.602512 1.697487 0.120000 +34.097488 1.952513 0.120000 +34.041523 0.992948 0.120000 +33.602512 0.947487 0.120000 +32.602512 1.697487 0.120000 +31.041523 1.742948 0.120000 +30.041523 0.992948 0.120000 +29.602512 0.947487 0.120000 +29.658476 1.907052 0.120000 +29.041523 1.742948 0.120000 +28.602512 1.697487 0.120000 +27.041523 1.742948 0.120000 +26.602512 1.697487 0.120000 +26.097486 1.952513 0.120000 +26.041523 0.992948 0.120000 +25.602512 0.947487 0.120000 +24.041523 0.992948 0.120000 +23.602512 0.947487 0.120000 +23.658476 1.907052 0.120000 +23.041523 1.742948 0.120000 +22.602512 1.697487 0.120000 +22.097486 1.952513 0.120000 +22.041523 0.992948 0.120000 +21.602512 0.947487 0.120000 +20.041523 0.992948 0.120000 +19.602512 0.947487 0.120000 +19.658476 1.907052 0.120000 +19.041523 1.742948 0.120000 +18.602512 1.697487 0.120000 +18.097486 1.952513 0.120000 +18.041523 0.992948 0.120000 +17.602512 0.947487 0.120000 +16.602512 1.697487 0.120000 +15.041523 1.742948 0.120000 +14.602512 1.697487 0.120000 +14.097487 1.952513 0.120000 +14.041523 0.992948 0.120000 +13.602512 0.947487 0.120000 +12.602512 1.697487 0.120000 +11.041523 1.742948 0.120000 +10.602512 1.697487 0.120000 +10.097487 1.952513 0.120000 +10.041523 0.992948 0.120000 +9.602512 0.947487 0.120000 +8.602512 1.697487 0.120000 +8.097487 1.952513 0.120000 +8.041523 0.992948 0.120000 +7.602513 0.947487 0.120000 +6.602513 1.697487 0.120000 +6.097487 1.952513 0.120000 +6.041523 0.992948 0.120000 +5.602513 0.947487 0.120000 +4.041523 0.992948 0.120000 +3.602513 0.947487 0.120000 +3.658477 1.907052 0.120000 +3.041523 1.742948 0.120000 +2.602513 1.697487 0.120000 +2.097487 1.952513 0.120000 +2.041523 0.992948 0.120000 +1.658477 0.992948 0.120000 +2.175426 0.828833 0.120000 +3.505843 0.763687 0.120000 +4.175426 0.828833 0.120000 +5.505843 0.763687 0.120000 +6.175426 0.828833 0.120000 +7.505843 0.763687 0.120000 +8.175426 0.828833 0.120000 +9.505843 0.763687 0.120000 +10.175426 0.828833 0.120000 +11.175426 1.578833 0.120000 +12.505843 1.513687 0.120000 +12.524574 1.321167 0.120000 +12.175426 0.828833 0.120000 +13.505843 0.763687 0.120000 +14.175426 0.828833 0.120000 +15.505843 0.763687 0.120000 +15.194157 1.386313 0.120000 +15.175426 1.578833 0.120000 +16.505842 1.513687 0.120000 +17.505842 0.763687 0.120000 +18.175426 0.828833 0.120000 +19.505842 0.763687 0.120000 +20.175426 0.828833 0.120000 +21.505842 0.763687 0.120000 +22.175426 0.828833 0.120000 +23.505842 0.763687 0.120000 +24.175426 0.828833 0.120000 +25.505842 0.763687 0.120000 +26.175426 0.828833 0.120000 +27.505842 0.763687 0.120000 +27.194157 1.386313 0.120000 +27.175426 1.578833 0.120000 +28.505842 1.513687 0.120000 +29.505842 0.763687 0.120000 +30.175426 0.828833 0.120000 +31.175426 1.578833 0.120000 +32.505844 1.513687 0.120000 +32.524574 1.321167 0.120000 +32.175426 0.828833 0.120000 +33.505844 0.763687 0.120000 +34.175426 0.828833 0.120000 +35.175426 1.578833 0.120000 +36.505844 1.513687 0.120000 +36.524574 1.321167 0.120000 +36.175426 0.828833 0.120000 +37.505844 0.763687 0.120000 +37.194157 1.386313 0.120000 +37.175426 1.578833 0.120000 +37.524574 2.071167 0.120000 +36.194157 2.136313 0.120000 +35.524574 2.071167 0.120000 +34.194157 2.136313 0.120000 +34.505844 1.513687 0.120000 +34.524574 1.321167 0.120000 +33.194157 1.386313 0.120000 +32.194157 2.136313 0.120000 +31.524574 2.071167 0.120000 +30.524574 1.321167 0.120000 +29.194157 1.386313 0.120000 +29.175426 1.578833 0.120000 +29.524574 2.071167 0.120000 +28.194157 2.136313 0.120000 +27.524574 2.071167 0.120000 +26.194157 2.136313 0.120000 +26.505842 1.513687 0.120000 +26.524574 1.321167 0.120000 +25.194157 1.386313 0.120000 +24.524574 1.321167 0.120000 +23.194157 1.386313 0.120000 +23.175426 1.578833 0.120000 +23.524574 2.071167 0.120000 +22.194157 2.136313 0.120000 +22.505842 1.513687 0.120000 +22.524574 1.321167 0.120000 +21.194157 1.386313 0.120000 +20.524574 1.321167 0.120000 +19.194157 1.386313 0.120000 +19.175426 1.578833 0.120000 +19.524574 2.071167 0.120000 +18.194157 2.136313 0.120000 +18.505842 1.513687 0.120000 +18.524574 1.321167 0.120000 +17.194157 1.386313 0.120000 +16.194157 2.136313 0.120000 +15.524574 2.071167 0.120000 +14.194157 2.136313 0.120000 +14.505843 1.513687 0.120000 +14.524574 1.321167 0.120000 +13.194157 1.386313 0.120000 +12.194157 2.136313 0.120000 +11.524574 2.071167 0.120000 +10.194157 2.136313 0.120000 +10.505843 1.513687 0.120000 +10.524574 1.321167 0.120000 +9.194157 1.386313 0.120000 +8.194157 2.136313 0.120000 +8.505843 1.513687 0.120000 +8.524574 1.321167 0.120000 +7.194157 1.386313 0.120000 +6.194157 2.136313 0.120000 +6.505843 1.513687 0.120000 +6.524574 1.321167 0.120000 +5.194157 1.386313 0.120000 +4.524574 1.321167 0.120000 +3.194157 1.386313 0.120000 +3.175426 1.578833 0.120000 +3.524574 2.071167 0.120000 +2.194157 2.136313 0.120000 +2.505843 1.513687 0.120000 +2.524574 1.321167 0.120000 +1.602513 0.452513 0.120000 +2.721167 1.124574 0.120000 +3.041523 1.157052 0.120000 +4.721167 1.124574 0.120000 +5.041523 1.157052 0.120000 +6.721167 1.124574 0.120000 +7.041523 1.157052 0.120000 +8.721167 1.124574 0.120000 +9.041523 1.157052 0.120000 +10.721167 1.124574 0.120000 +11.721167 1.874574 0.120000 +12.041523 1.907052 0.120000 +11.978833 1.025426 0.120000 +12.721167 1.124574 0.120000 +13.041523 1.157052 0.120000 +14.721167 1.124574 0.120000 +15.041523 1.157052 0.120000 +15.658477 0.992948 0.120000 +15.721167 1.874574 0.120000 +16.041523 1.907052 0.120000 +17.041523 1.157052 0.120000 +18.721167 1.124574 0.120000 +19.041523 1.157052 0.120000 +20.721167 1.124574 0.120000 +21.041523 1.157052 0.120000 +22.721167 1.124574 0.120000 +23.041523 1.157052 0.120000 +24.721167 1.124574 0.120000 +25.041523 1.157052 0.120000 +26.721167 1.124574 0.120000 +27.041523 1.157052 0.120000 +27.658476 0.992948 0.120000 +27.721167 1.874574 0.120000 +28.041523 1.907052 0.120000 +29.041523 1.157052 0.120000 +30.721167 1.124574 0.120000 +31.721167 1.874574 0.120000 +32.041523 1.907052 0.120000 +31.978832 1.025426 0.120000 +32.721169 1.124574 0.120000 +33.041523 1.157052 0.120000 +34.721169 1.124574 0.120000 +35.721169 1.874574 0.120000 +36.041523 1.907052 0.120000 +35.978832 1.025426 0.120000 +36.721169 1.124574 0.120000 +37.041523 1.157052 0.120000 +37.658478 0.992948 0.120000 +37.721169 1.874574 0.120000 +36.978832 1.775426 0.120000 +36.658478 1.742948 0.120000 +34.978832 1.775426 0.120000 +34.658478 1.742948 0.120000 +34.041523 1.907052 0.120000 +33.978832 1.025426 0.120000 +33.658478 0.992948 0.120000 +32.658478 1.742948 0.120000 +30.978832 1.775426 0.120000 +29.978832 1.025426 0.120000 +29.658476 0.992948 0.120000 +29.721167 1.874574 0.120000 +28.978832 1.775426 0.120000 +28.658476 1.742948 0.120000 +26.978832 1.775426 0.120000 +26.658476 1.742948 0.120000 +26.041523 1.907052 0.120000 +25.978832 1.025426 0.120000 +25.658476 0.992948 0.120000 +23.978832 1.025426 0.120000 +23.658476 0.992948 0.120000 +23.721167 1.874574 0.120000 +22.978832 1.775426 0.120000 +22.658476 1.742948 0.120000 +22.041523 1.907052 0.120000 +21.978832 1.025426 0.120000 +21.658476 0.992948 0.120000 +19.978832 1.025426 0.120000 +19.658476 0.992948 0.120000 +19.721167 1.874574 0.120000 +18.978832 1.775426 0.120000 +18.658476 1.742948 0.120000 +18.041523 1.907052 0.120000 +17.978832 1.025426 0.120000 +17.658476 0.992948 0.120000 +16.658476 1.742948 0.120000 +14.978833 1.775426 0.120000 +14.658477 1.742948 0.120000 +14.041523 1.907052 0.120000 +13.978833 1.025426 0.120000 +13.658477 0.992948 0.120000 +12.658477 1.742948 0.120000 +10.978833 1.775426 0.120000 +10.658477 1.742948 0.120000 +10.041523 1.907052 0.120000 +9.978833 1.025426 0.120000 +9.658477 0.992948 0.120000 +8.658477 1.742948 0.120000 +8.041523 1.907052 0.120000 +7.978833 1.025426 0.120000 +7.658476 0.992948 0.120000 +6.658476 1.742948 0.120000 +6.041523 1.907052 0.120000 +5.978833 1.025426 0.120000 +5.658476 0.992948 0.120000 +3.978833 1.025426 0.120000 +3.658477 0.992948 0.120000 +3.721167 1.874574 0.120000 +2.978833 1.775426 0.120000 +2.658477 1.742948 0.120000 +2.041523 1.907052 0.120000 +1.978833 1.025426 0.120000 +1.721167 1.025426 0.120000 +2.194157 0.763687 0.120000 +3.500000 0.700000 0.120000 +4.194157 0.763687 0.120000 +5.500000 0.700000 0.120000 +6.194157 0.763687 0.120000 +7.500000 0.700000 0.120000 +8.194157 0.763687 0.120000 +9.500000 0.700000 0.120000 +10.194157 0.763687 0.120000 +11.194157 1.513687 0.120000 +12.500000 1.450000 0.120000 +12.505843 1.386313 0.120000 +11.978833 1.874574 0.120000 +11.913687 1.044157 0.120000 +11.913687 1.855843 0.120000 +11.850000 1.050000 0.120000 +11.850000 1.850000 0.120000 +11.786313 1.044157 0.120000 +11.786313 1.855843 0.120000 +11.721167 1.025426 0.120000 +11.200000 1.450000 0.120000 +11.658477 0.992948 0.120000 +11.194157 1.386313 0.120000 +11.602512 0.947487 0.120000 +11.175426 1.321167 0.120000 +11.557052 0.891523 0.120000 +11.142948 1.258477 0.120000 +11.524574 0.828833 0.120000 +11.097487 1.202513 0.120000 +11.505843 0.763687 0.120000 +11.041523 1.157052 0.120000 +12.194157 0.763687 0.120000 +13.500000 0.700000 0.120000 +14.194157 0.763687 0.120000 +15.500000 0.700000 0.120000 +15.200000 1.450000 0.120000 +15.194157 1.513687 0.120000 +15.721167 1.025426 0.120000 +15.786313 1.855843 0.120000 +15.786313 1.044157 0.120000 +15.850000 1.850000 0.120000 +15.850000 1.050000 0.120000 +15.913687 1.855843 0.120000 +15.913687 1.044157 0.120000 +15.978833 1.874574 0.120000 +16.500000 1.450000 0.120000 +16.505842 1.386313 0.120000 +15.978833 1.025426 0.120000 +16.524574 1.321167 0.120000 +16.041523 0.992948 0.120000 +16.557051 1.258477 0.120000 +16.097486 0.947487 0.120000 +16.602512 1.202513 0.120000 +16.142948 0.891523 0.120000 +16.658476 1.157052 0.120000 +16.175426 0.828833 0.120000 +16.721167 1.124574 0.120000 +17.500000 0.700000 0.120000 +11.500000 0.700000 0.120000 +16.194157 0.763687 0.120000 +18.194157 0.763687 0.120000 +19.500000 0.700000 0.120000 +20.194157 0.763687 0.120000 +21.500000 0.700000 0.120000 +22.194157 0.763687 0.120000 +23.500000 0.700000 0.120000 +24.194157 0.763687 0.120000 +25.500000 0.700000 0.120000 +26.194157 0.763687 0.120000 +27.500000 0.700000 0.120000 +27.200001 1.450000 0.120000 +27.194157 1.513687 0.120000 +27.721167 1.025426 0.120000 +27.786312 1.855843 0.120000 +27.786312 1.044157 0.120000 +27.850000 1.850000 0.120000 +27.850000 1.050000 0.120000 +27.913687 1.855843 0.120000 +27.913687 1.044157 0.120000 +27.978832 1.874574 0.120000 +28.500000 1.450000 0.120000 +28.505842 1.386313 0.120000 +27.978832 1.025426 0.120000 +28.524574 1.321167 0.120000 +28.041523 0.992948 0.120000 +28.557051 1.258477 0.120000 +28.097486 0.947487 0.120000 +28.602512 1.202513 0.120000 +28.142948 0.891523 0.120000 +28.658476 1.157052 0.120000 +28.175426 0.828833 0.120000 +28.721167 1.124574 0.120000 +29.500000 0.700000 0.120000 +30.194157 0.763687 0.120000 +31.194157 1.513687 0.120000 +32.500000 1.450000 0.120000 +32.505844 1.386313 0.120000 +31.978832 1.874574 0.120000 +31.913687 1.044157 0.120000 +31.913687 1.855843 0.120000 +31.850000 1.050000 0.120000 +31.850000 1.850000 0.120000 +31.786312 1.044157 0.120000 +31.786312 1.855843 0.120000 +31.721167 1.025426 0.120000 +31.200001 1.450000 0.120000 +31.658476 0.992948 0.120000 +31.194157 1.386313 0.120000 +31.602512 0.947487 0.120000 +31.175426 1.321167 0.120000 +31.557051 0.891523 0.120000 +31.142948 1.258477 0.120000 +31.524574 0.828833 0.120000 +31.097486 1.202513 0.120000 +31.505842 0.763687 0.120000 +31.041523 1.157052 0.120000 +28.194157 0.763687 0.120000 +31.500000 0.700000 0.120000 +32.194157 0.763687 0.120000 +33.500000 0.700000 0.120000 +34.194157 0.763687 0.120000 +35.194157 1.513687 0.120000 +36.500000 1.450000 0.120000 +36.505844 1.386313 0.120000 +35.978832 1.874574 0.120000 +35.913689 1.044157 0.120000 +35.913689 1.855843 0.120000 +35.849998 1.050000 0.120000 +35.849998 1.850000 0.120000 +35.786312 1.044157 0.120000 +35.786312 1.855843 0.120000 +35.721169 1.025426 0.120000 +35.200001 1.450000 0.120000 +35.658478 0.992948 0.120000 +35.194157 1.386313 0.120000 +35.602512 0.947487 0.120000 +35.175426 1.321167 0.120000 +35.557053 0.891523 0.120000 +35.142948 1.258477 0.120000 +35.524574 0.828833 0.120000 +35.097488 1.202513 0.120000 +35.505844 0.763687 0.120000 +35.041523 1.157052 0.120000 +36.194157 0.763687 0.120000 +37.500000 0.700000 0.120000 +35.500000 0.700000 0.120000 +37.200001 1.450000 0.120000 +37.194157 1.513687 0.120000 +37.721169 1.025426 0.120000 +37.786312 1.855843 0.120000 +37.786312 1.044157 0.120000 +37.849998 1.850000 0.120000 +37.849998 1.050000 0.120000 +37.913689 1.855843 0.120000 +37.913689 1.044157 0.120000 +37.978832 1.874574 0.120000 +37.978832 1.025426 0.120000 +38.041523 1.907052 0.120000 +37.505844 2.136313 0.120000 +36.200001 2.200000 0.120000 +35.505844 2.136313 0.120000 +34.200001 2.200000 0.120000 +34.500000 1.450000 0.120000 +34.505844 1.386313 0.120000 +33.978832 1.874574 0.120000 +33.913689 1.044157 0.120000 +33.913689 1.855843 0.120000 +33.849998 1.050000 0.120000 +33.849998 1.850000 0.120000 +33.786312 1.044157 0.120000 +33.786312 1.855843 0.120000 +33.721169 1.025426 0.120000 +33.200001 1.450000 0.120000 +33.194157 1.513687 0.120000 +33.721169 1.874574 0.120000 +33.175426 1.578833 0.120000 +33.658478 1.907052 0.120000 +33.142948 1.641523 0.120000 +33.602512 1.952513 0.120000 +33.097488 1.697487 0.120000 +33.557053 2.008476 0.120000 +33.041523 1.742948 0.120000 +33.524574 2.071167 0.120000 +32.978832 1.775426 0.120000 +33.505844 2.136313 0.120000 +32.200001 2.200000 0.120000 +31.505842 2.136313 0.120000 +30.505842 1.386313 0.120000 +29.200001 1.450000 0.120000 +29.194157 1.513687 0.120000 +29.721167 1.025426 0.120000 +29.786312 1.855843 0.120000 +29.786312 1.044157 0.120000 +29.850000 1.850000 0.120000 +29.850000 1.050000 0.120000 +29.913687 1.855843 0.120000 +29.913687 1.044157 0.120000 +29.978832 1.874574 0.120000 +30.500000 1.450000 0.120000 +30.041523 1.907052 0.120000 +30.505842 1.513687 0.120000 +30.097486 1.952513 0.120000 +30.524574 1.578833 0.120000 +30.142948 2.008476 0.120000 +30.557051 1.641523 0.120000 +30.175426 2.071167 0.120000 +30.602512 1.697487 0.120000 +30.194157 2.136313 0.120000 +30.658476 1.742948 0.120000 +29.505842 2.136313 0.120000 +28.200001 2.200000 0.120000 +27.505842 2.136313 0.120000 +26.200001 2.200000 0.120000 +30.200001 2.200000 0.120000 +26.500000 1.450000 0.120000 +26.505842 1.386313 0.120000 +25.978832 1.874574 0.120000 +25.913687 1.044157 0.120000 +25.913687 1.855843 0.120000 +25.850000 1.050000 0.120000 +25.850000 1.850000 0.120000 +25.786312 1.044157 0.120000 +25.786312 1.855843 0.120000 +25.721167 1.025426 0.120000 +25.200001 1.450000 0.120000 +25.194157 1.513687 0.120000 +25.721167 1.874574 0.120000 +25.175426 1.578833 0.120000 +25.658476 1.907052 0.120000 +25.142948 1.641523 0.120000 +25.602512 1.952513 0.120000 +25.097486 1.697487 0.120000 +25.557051 2.008476 0.120000 +25.041523 1.742948 0.120000 +25.524574 2.071167 0.120000 +24.978832 1.775426 0.120000 +24.505842 1.386313 0.120000 +23.200001 1.450000 0.120000 +23.194157 1.513687 0.120000 +23.721167 1.025426 0.120000 +23.786312 1.855843 0.120000 +23.786312 1.044157 0.120000 +23.850000 1.850000 0.120000 +23.850000 1.050000 0.120000 +23.913687 1.855843 0.120000 +23.913687 1.044157 0.120000 +23.978832 1.874574 0.120000 +24.500000 1.450000 0.120000 +24.041523 1.907052 0.120000 +24.505842 1.513687 0.120000 +24.097486 1.952513 0.120000 +24.524574 1.578833 0.120000 +24.142948 2.008476 0.120000 +24.557051 1.641523 0.120000 +24.175426 2.071167 0.120000 +24.602512 1.697487 0.120000 +24.194157 2.136313 0.120000 +24.658476 1.742948 0.120000 +23.505842 2.136313 0.120000 +22.200001 2.200000 0.120000 +22.500000 1.450000 0.120000 +25.505842 2.136313 0.120000 +24.200001 2.200000 0.120000 +22.505842 1.386313 0.120000 +21.978832 1.874574 0.120000 +21.913687 1.044157 0.120000 +21.913687 1.855843 0.120000 +21.850000 1.050000 0.120000 +21.850000 1.850000 0.120000 +21.786312 1.044157 0.120000 +21.786312 1.855843 0.120000 +21.721167 1.025426 0.120000 +21.200001 1.450000 0.120000 +21.194157 1.513687 0.120000 +21.721167 1.874574 0.120000 +21.175426 1.578833 0.120000 +21.658476 1.907052 0.120000 +21.142948 1.641523 0.120000 +21.602512 1.952513 0.120000 +21.097486 1.697487 0.120000 +21.557051 2.008476 0.120000 +21.041523 1.742948 0.120000 +21.524574 2.071167 0.120000 +20.978832 1.775426 0.120000 +20.505842 1.386313 0.120000 +19.200001 1.450000 0.120000 +19.194157 1.513687 0.120000 +19.721167 1.025426 0.120000 +19.786312 1.855843 0.120000 +19.786312 1.044157 0.120000 +19.850000 1.850000 0.120000 +19.850000 1.050000 0.120000 +19.913687 1.855843 0.120000 +19.913687 1.044157 0.120000 +19.978832 1.874574 0.120000 +20.500000 1.450000 0.120000 +20.041523 1.907052 0.120000 +20.505842 1.513687 0.120000 +20.097486 1.952513 0.120000 +20.524574 1.578833 0.120000 +20.142948 2.008476 0.120000 +20.557051 1.641523 0.120000 +20.175426 2.071167 0.120000 +20.602512 1.697487 0.120000 +20.194157 2.136313 0.120000 +20.658476 1.742948 0.120000 +19.505842 2.136313 0.120000 +18.200001 2.200000 0.120000 +18.500000 1.450000 0.120000 +21.505842 2.136313 0.120000 +20.200001 2.200000 0.120000 +18.505842 1.386313 0.120000 +17.978832 1.874574 0.120000 +17.913687 1.044157 0.120000 +17.913687 1.855843 0.120000 +17.850000 1.050000 0.120000 +17.850000 1.850000 0.120000 +17.786312 1.044157 0.120000 +17.786312 1.855843 0.120000 +17.721167 1.025426 0.120000 +17.200001 1.450000 0.120000 +17.194157 1.513687 0.120000 +17.721167 1.874574 0.120000 +17.175426 1.578833 0.120000 +17.658476 1.907052 0.120000 +17.142948 1.641523 0.120000 +17.602512 1.952513 0.120000 +17.097486 1.697487 0.120000 +17.557051 2.008476 0.120000 +17.041523 1.742948 0.120000 +17.524574 2.071167 0.120000 +16.978832 1.775426 0.120000 +16.200001 2.200000 0.120000 +15.505843 2.136313 0.120000 +14.200000 2.200000 0.120000 +14.500000 1.450000 0.120000 +14.505843 1.386313 0.120000 +13.978833 1.874574 0.120000 +13.913687 1.044157 0.120000 +13.913687 1.855843 0.120000 +13.850000 1.050000 0.120000 +13.850000 1.850000 0.120000 +13.786313 1.044157 0.120000 +13.786313 1.855843 0.120000 +13.721167 1.025426 0.120000 +13.200000 1.450000 0.120000 +13.194157 1.513687 0.120000 +13.721167 1.874574 0.120000 +13.175426 1.578833 0.120000 +13.658477 1.907052 0.120000 +13.142948 1.641523 0.120000 +13.602512 1.952513 0.120000 +13.097487 1.697487 0.120000 +13.557052 2.008476 0.120000 +13.041523 1.742948 0.120000 +13.524574 2.071167 0.120000 +12.978833 1.775426 0.120000 +17.505842 2.136313 0.120000 +13.505843 2.136313 0.120000 +12.200000 2.200000 0.120000 +11.505843 2.136313 0.120000 +10.200000 2.200000 0.120000 +10.500000 1.450000 0.120000 +10.505843 1.386313 0.120000 +9.978833 1.874574 0.120000 +9.913687 1.044157 0.120000 +9.913687 1.855843 0.120000 +9.850000 1.050000 0.120000 +9.850000 1.850000 0.120000 +9.786313 1.044157 0.120000 +9.786313 1.855843 0.120000 +9.721167 1.025426 0.120000 +9.200000 1.450000 0.120000 +9.194157 1.513687 0.120000 +9.721167 1.874574 0.120000 +9.175426 1.578833 0.120000 +9.658477 1.907052 0.120000 +9.142948 1.641523 0.120000 +9.602512 1.952513 0.120000 +9.097487 1.697487 0.120000 +9.557052 2.008476 0.120000 +9.041523 1.742948 0.120000 +9.524574 2.071167 0.120000 +8.978833 1.775426 0.120000 +8.200000 2.200000 0.120000 +8.500000 1.450000 0.120000 +9.505843 2.136313 0.120000 +8.505843 1.386313 0.120000 +7.978833 1.874574 0.120000 +7.913687 1.044157 0.120000 +7.913687 1.855843 0.120000 +7.850000 1.050000 0.120000 +7.850000 1.850000 0.120000 +7.786313 1.044157 0.120000 +7.786313 1.855843 0.120000 +7.721167 1.025426 0.120000 +7.200000 1.450000 0.120000 +7.194157 1.513687 0.120000 +7.721167 1.874574 0.120000 +7.175426 1.578833 0.120000 +7.658476 1.907052 0.120000 +7.142949 1.641523 0.120000 +7.602513 1.952513 0.120000 +7.097487 1.697487 0.120000 +7.557052 2.008476 0.120000 +7.041523 1.742948 0.120000 +7.524574 2.071167 0.120000 +6.978833 1.775426 0.120000 +6.200000 2.200000 0.120000 +6.500000 1.450000 0.120000 +6.505843 1.386313 0.120000 +5.978833 1.874574 0.120000 +5.913687 1.044157 0.120000 +5.913687 1.855843 0.120000 +5.850000 1.050000 0.120000 +5.850000 1.850000 0.120000 +5.786313 1.044157 0.120000 +5.786313 1.855843 0.120000 +5.721167 1.025426 0.120000 +5.200000 1.450000 0.120000 +5.194157 1.513687 0.120000 +5.721167 1.874574 0.120000 +5.175426 1.578833 0.120000 +5.658476 1.907052 0.120000 +5.142949 1.641523 0.120000 +5.602513 1.952513 0.120000 +5.097487 1.697487 0.120000 +5.557052 2.008476 0.120000 +5.041523 1.742948 0.120000 +5.524574 2.071167 0.120000 +4.978833 1.775426 0.120000 +4.505843 1.386313 0.120000 +3.200000 1.450000 0.120000 +3.194157 1.513687 0.120000 +3.721167 1.025426 0.120000 +3.786313 1.855843 0.120000 +3.786313 1.044157 0.120000 +3.850000 1.850000 0.120000 +3.850000 1.050000 0.120000 +3.913687 1.855843 0.120000 +3.913687 1.044157 0.120000 +3.978833 1.874574 0.120000 +4.500000 1.450000 0.120000 +4.041523 1.907052 0.120000 +4.505843 1.513687 0.120000 +4.097487 1.952513 0.120000 +4.524574 1.578833 0.120000 +4.142949 2.008476 0.120000 +4.557052 1.641523 0.120000 +4.175426 2.071167 0.120000 +4.602513 1.697487 0.120000 +4.194157 2.136313 0.120000 +4.658476 1.742948 0.120000 +7.505843 2.136313 0.120000 +5.505843 2.136313 0.120000 +4.200000 2.200000 0.120000 +3.505843 2.136313 0.120000 +2.200000 2.200000 0.120000 +2.500000 1.450000 0.120000 +2.505843 1.386313 0.120000 +1.978833 1.874574 0.120000 +1.913687 1.044157 0.120000 +1.913687 1.855843 0.120000 +1.850000 1.050000 0.120000 +1.850000 1.850000 0.120000 +1.786313 1.044157 0.120000 +1.786313 1.855843 0.120000 +1.721167 1.874574 0.120000 +1.658477 1.907052 0.120000 +1.602513 1.952513 0.120000 +1.557052 2.008476 0.120000 +1.524574 2.071167 0.120000 +1.505843 2.136313 0.120000 +1.500000 2.200000 0.120000 +1.505843 2.263687 0.120000 +1.524574 2.328833 0.120000 +1.557052 2.391523 0.120000 +2.786313 1.105843 0.120000 +2.978833 1.124574 0.120000 +4.786313 1.105843 0.120000 +4.978833 1.124574 0.120000 +6.786313 1.105843 0.120000 +6.978833 1.124574 0.120000 +8.786313 1.105843 0.120000 +8.978833 1.124574 0.120000 +10.786313 1.105843 0.120000 +10.978833 1.124574 0.120000 +12.786313 1.105843 0.120000 +12.978833 1.124574 0.120000 +14.786313 1.105843 0.120000 +14.978833 1.124574 0.120000 +16.786312 1.105843 0.120000 +16.978832 1.124574 0.120000 +18.786312 1.105843 0.120000 +18.978832 1.124574 0.120000 +20.786312 1.105843 0.120000 +20.978832 1.124574 0.120000 +22.786312 1.105843 0.120000 +22.978832 1.124574 0.120000 +24.786312 1.105843 0.120000 +24.978832 1.124574 0.120000 +26.786312 1.105843 0.120000 +26.978832 1.124574 0.120000 +28.786312 1.105843 0.120000 +28.978832 1.124574 0.120000 +30.786312 1.105843 0.120000 +30.978832 1.124574 0.120000 +32.786312 1.105843 0.120000 +32.978832 1.124574 0.120000 +34.786312 1.105843 0.120000 +34.978832 1.124574 0.120000 +36.786312 1.105843 0.120000 +36.978832 1.124574 0.120000 +36.913689 1.794157 0.120000 +36.721169 1.775426 0.120000 +34.913689 1.794157 0.120000 +34.721169 1.775426 0.120000 +32.913689 1.794157 0.120000 +32.721169 1.775426 0.120000 +30.913687 1.794157 0.120000 +30.721167 1.775426 0.120000 +28.913687 1.794157 0.120000 +28.721167 1.775426 0.120000 +26.913687 1.794157 0.120000 +26.721167 1.775426 0.120000 +24.913687 1.794157 0.120000 +24.721167 1.775426 0.120000 +22.913687 1.794157 0.120000 +22.721167 1.775426 0.120000 +20.913687 1.794157 0.120000 +20.721167 1.775426 0.120000 +18.913687 1.794157 0.120000 +18.721167 1.775426 0.120000 +16.913687 1.794157 0.120000 +16.721167 1.775426 0.120000 +14.913687 1.794157 0.120000 +14.721167 1.775426 0.120000 +12.913687 1.794157 0.120000 +12.721167 1.775426 0.120000 +10.913687 1.794157 0.120000 +10.721167 1.775426 0.120000 +8.913687 1.794157 0.120000 +8.721167 1.775426 0.120000 +6.913687 1.794157 0.120000 +6.721167 1.775426 0.120000 +4.913687 1.794157 0.120000 +4.721167 1.775426 0.120000 +2.913687 1.794157 0.120000 +2.721167 1.775426 0.120000 +1.602513 2.447487 0.120000 +1.658477 0.407052 0.120000 +2.200000 0.700000 0.120000 +3.505843 0.636313 0.120000 +4.200000 0.700000 0.120000 +5.505843 0.636313 0.120000 +6.200000 0.700000 0.120000 +7.505843 0.636313 0.120000 +8.200000 0.700000 0.120000 +9.505843 0.636313 0.120000 +10.200000 0.700000 0.120000 +11.505843 0.636313 0.120000 +12.200000 0.700000 0.120000 +13.505843 0.636313 0.120000 +14.200000 0.700000 0.120000 +15.505843 0.636313 0.120000 +16.200001 0.700000 0.120000 +17.505842 0.636313 0.120000 +18.200001 0.700000 0.120000 +19.505842 0.636313 0.120000 +20.200001 0.700000 0.120000 +21.505842 0.636313 0.120000 +22.200001 0.700000 0.120000 +23.505842 0.636313 0.120000 +24.200001 0.700000 0.120000 +25.505842 0.636313 0.120000 +26.200001 0.700000 0.120000 +27.505842 0.636313 0.120000 +28.200001 0.700000 0.120000 +29.505842 0.636313 0.120000 +30.200001 0.700000 0.120000 +31.505842 0.636313 0.120000 +32.200001 0.700000 0.120000 +33.505844 0.636313 0.120000 +34.200001 0.700000 0.120000 +35.505844 0.636313 0.120000 +36.200001 0.700000 0.120000 +37.505844 0.636313 0.120000 +38.041523 0.992948 0.120000 +38.097488 1.952513 0.120000 +37.500000 2.200000 0.120000 +36.194157 2.263687 0.120000 +35.500000 2.200000 0.120000 +34.194157 2.263687 0.120000 +33.500000 2.200000 0.120000 +32.194157 2.263687 0.120000 +31.500000 2.200000 0.120000 +30.194157 2.263687 0.120000 +29.500000 2.200000 0.120000 +28.194157 2.263687 0.120000 +27.500000 2.200000 0.120000 +26.194157 2.263687 0.120000 +25.500000 2.200000 0.120000 +24.194157 2.263687 0.120000 +23.500000 2.200000 0.120000 +22.194157 2.263687 0.120000 +21.500000 2.200000 0.120000 +20.194157 2.263687 0.120000 +19.500000 2.200000 0.120000 +18.194157 2.263687 0.120000 +17.500000 2.200000 0.120000 +16.194157 2.263687 0.120000 +15.500000 2.200000 0.120000 +14.194157 2.263687 0.120000 +13.500000 2.200000 0.120000 +12.194157 2.263687 0.120000 +11.500000 2.200000 0.120000 +10.194157 2.263687 0.120000 +9.500000 2.200000 0.120000 +8.194157 2.263687 0.120000 +7.500000 2.200000 0.120000 +6.194157 2.263687 0.120000 +5.500000 2.200000 0.120000 +4.194157 2.263687 0.120000 +3.500000 2.200000 0.120000 +2.194157 2.263687 0.120000 +2.850000 1.100000 0.120000 +2.913687 1.105843 0.120000 +2.194157 0.636313 0.120000 +3.524574 0.571167 0.120000 +2.175426 0.571167 0.120000 +3.557052 0.508477 0.120000 +2.142948 0.508477 0.120000 +3.602513 0.452513 0.120000 +4.850000 1.100000 0.120000 +4.913687 1.105843 0.120000 +4.194157 0.636313 0.120000 +5.524574 0.571167 0.120000 +4.175426 0.571167 0.120000 +5.557052 0.508477 0.120000 +4.142949 0.508477 0.120000 +5.602513 0.452513 0.120000 +6.850000 1.100000 0.120000 +6.913687 1.105843 0.120000 +6.194157 0.636313 0.120000 +7.524574 0.571167 0.120000 +6.175426 0.571167 0.120000 +7.557052 0.508477 0.120000 +6.142949 0.508477 0.120000 +7.602513 0.452513 0.120000 +8.850000 1.100000 0.120000 +8.913687 1.105843 0.120000 +8.194157 0.636313 0.120000 +9.524574 0.571167 0.120000 +8.175426 0.571167 0.120000 +9.557052 0.508477 0.120000 +8.142948 0.508477 0.120000 +9.602512 0.452513 0.120000 +10.850000 1.100000 0.120000 +10.913687 1.105843 0.120000 +10.194157 0.636313 0.120000 +11.524574 0.571167 0.120000 +10.175426 0.571167 0.120000 +11.557052 0.508477 0.120000 +10.142948 0.508477 0.120000 +11.602512 0.452513 0.120000 +12.850000 1.100000 0.120000 +12.913687 1.105843 0.120000 +12.194157 0.636313 0.120000 +13.524574 0.571167 0.120000 +12.175426 0.571167 0.120000 +13.557052 0.508477 0.120000 +12.142948 0.508477 0.120000 +13.602512 0.452513 0.120000 +14.850000 1.100000 0.120000 +14.913687 1.105843 0.120000 +14.194157 0.636313 0.120000 +15.524574 0.571167 0.120000 +14.175426 0.571167 0.120000 +15.557052 0.508477 0.120000 +14.142948 0.508477 0.120000 +15.602512 0.452513 0.120000 +16.850000 1.100000 0.120000 +16.913687 1.105843 0.120000 +16.194157 0.636313 0.120000 +17.524574 0.571167 0.120000 +16.175426 0.571167 0.120000 +17.557051 0.508477 0.120000 +16.142948 0.508477 0.120000 +17.602512 0.452513 0.120000 +18.850000 1.100000 0.120000 +18.913687 1.105843 0.120000 +18.194157 0.636313 0.120000 +19.524574 0.571167 0.120000 +18.175426 0.571167 0.120000 +19.557051 0.508477 0.120000 +18.142948 0.508477 0.120000 +19.602512 0.452513 0.120000 +20.850000 1.100000 0.120000 +20.913687 1.105843 0.120000 +20.194157 0.636313 0.120000 +21.524574 0.571167 0.120000 +20.175426 0.571167 0.120000 +21.557051 0.508477 0.120000 +20.142948 0.508477 0.120000 +21.602512 0.452513 0.120000 +22.850000 1.100000 0.120000 +22.913687 1.105843 0.120000 +22.194157 0.636313 0.120000 +23.524574 0.571167 0.120000 +22.175426 0.571167 0.120000 +23.557051 0.508477 0.120000 +22.142948 0.508477 0.120000 +23.602512 0.452513 0.120000 +24.850000 1.100000 0.120000 +24.913687 1.105843 0.120000 +24.194157 0.636313 0.120000 +25.524574 0.571167 0.120000 +24.175426 0.571167 0.120000 +25.557051 0.508477 0.120000 +24.142948 0.508477 0.120000 +25.602512 0.452513 0.120000 +26.850000 1.100000 0.120000 +26.913687 1.105843 0.120000 +26.194157 0.636313 0.120000 +27.524574 0.571167 0.120000 +26.175426 0.571167 0.120000 +27.557051 0.508477 0.120000 +26.142948 0.508477 0.120000 +27.602512 0.452513 0.120000 +28.850000 1.100000 0.120000 +28.913687 1.105843 0.120000 +28.194157 0.636313 0.120000 +29.524574 0.571167 0.120000 +28.175426 0.571167 0.120000 +29.557051 0.508477 0.120000 +28.142948 0.508477 0.120000 +29.602512 0.452513 0.120000 +30.850000 1.100000 0.120000 +30.913687 1.105843 0.120000 +30.194157 0.636313 0.120000 +31.524574 0.571167 0.120000 +30.175426 0.571167 0.120000 +31.557051 0.508477 0.120000 +30.142948 0.508477 0.120000 +31.602512 0.452513 0.120000 +32.849998 1.100000 0.120000 +32.913689 1.105843 0.120000 +32.194157 0.636313 0.120000 +33.524574 0.571167 0.120000 +32.175426 0.571167 0.120000 +33.557053 0.508477 0.120000 +32.142948 0.508477 0.120000 +33.602512 0.452513 0.120000 +34.849998 1.100000 0.120000 +34.913689 1.105843 0.120000 +34.194157 0.636313 0.120000 +35.524574 0.571167 0.120000 +34.175426 0.571167 0.120000 +35.557053 0.508477 0.120000 +34.142948 0.508477 0.120000 +35.602512 0.452513 0.120000 +36.849998 1.100000 0.120000 +36.913689 1.105843 0.120000 +36.194157 0.636313 0.120000 +37.524574 0.571167 0.120000 +36.175426 0.571167 0.120000 +37.557053 0.508477 0.120000 +36.142948 0.508477 0.120000 +37.602512 0.452513 0.120000 +36.849998 1.800000 0.120000 +36.786312 1.794157 0.120000 +37.505844 2.263687 0.120000 +36.175426 2.328833 0.120000 +37.524574 2.328833 0.120000 +36.142948 2.391523 0.120000 +37.557053 2.391523 0.120000 +36.097488 2.447487 0.120000 +34.849998 1.800000 0.120000 +34.786312 1.794157 0.120000 +35.505844 2.263687 0.120000 +34.175426 2.328833 0.120000 +35.524574 2.328833 0.120000 +34.142948 2.391523 0.120000 +35.557053 2.391523 0.120000 +34.097488 2.447487 0.120000 +32.849998 1.800000 0.120000 +32.786312 1.794157 0.120000 +33.505844 2.263687 0.120000 +32.175426 2.328833 0.120000 +33.524574 2.328833 0.120000 +32.142948 2.391523 0.120000 +33.557053 2.391523 0.120000 +32.097488 2.447487 0.120000 +30.850000 1.800000 0.120000 +30.786312 1.794157 0.120000 +31.505842 2.263687 0.120000 +30.175426 2.328833 0.120000 +31.524574 2.328833 0.120000 +30.142948 2.391523 0.120000 +31.557051 2.391523 0.120000 +30.097486 2.447487 0.120000 +28.850000 1.800000 0.120000 +28.786312 1.794157 0.120000 +29.505842 2.263687 0.120000 +28.175426 2.328833 0.120000 +29.524574 2.328833 0.120000 +28.142948 2.391523 0.120000 +29.557051 2.391523 0.120000 +28.097486 2.447487 0.120000 +26.850000 1.800000 0.120000 +26.786312 1.794157 0.120000 +27.505842 2.263687 0.120000 +26.175426 2.328833 0.120000 +27.524574 2.328833 0.120000 +26.142948 2.391523 0.120000 +27.557051 2.391523 0.120000 +26.097486 2.447487 0.120000 +24.850000 1.800000 0.120000 +24.786312 1.794157 0.120000 +25.505842 2.263687 0.120000 +24.175426 2.328833 0.120000 +25.524574 2.328833 0.120000 +24.142948 2.391523 0.120000 +25.557051 2.391523 0.120000 +24.097486 2.447487 0.120000 +22.850000 1.800000 0.120000 +22.786312 1.794157 0.120000 +23.505842 2.263687 0.120000 +22.175426 2.328833 0.120000 +23.524574 2.328833 0.120000 +22.142948 2.391523 0.120000 +23.557051 2.391523 0.120000 +22.097486 2.447487 0.120000 +20.850000 1.800000 0.120000 +20.786312 1.794157 0.120000 +21.505842 2.263687 0.120000 +20.175426 2.328833 0.120000 +21.524574 2.328833 0.120000 +20.142948 2.391523 0.120000 +21.557051 2.391523 0.120000 +20.097486 2.447487 0.120000 +18.850000 1.800000 0.120000 +18.786312 1.794157 0.120000 +19.505842 2.263687 0.120000 +18.175426 2.328833 0.120000 +19.524574 2.328833 0.120000 +18.142948 2.391523 0.120000 +19.557051 2.391523 0.120000 +18.097486 2.447487 0.120000 +16.850000 1.800000 0.120000 +16.786312 1.794157 0.120000 +17.505842 2.263687 0.120000 +16.175426 2.328833 0.120000 +17.524574 2.328833 0.120000 +16.142948 2.391523 0.120000 +17.557051 2.391523 0.120000 +16.097486 2.447487 0.120000 +14.850000 1.800000 0.120000 +14.786313 1.794157 0.120000 +15.505843 2.263687 0.120000 +14.175426 2.328833 0.120000 +15.524574 2.328833 0.120000 +14.142948 2.391523 0.120000 +15.557052 2.391523 0.120000 +14.097487 2.447487 0.120000 +12.850000 1.800000 0.120000 +12.786313 1.794157 0.120000 +13.505843 2.263687 0.120000 +12.175426 2.328833 0.120000 +13.524574 2.328833 0.120000 +12.142948 2.391523 0.120000 +13.557052 2.391523 0.120000 +12.097487 2.447487 0.120000 +10.850000 1.800000 0.120000 +10.786313 1.794157 0.120000 +11.505843 2.263687 0.120000 +10.175426 2.328833 0.120000 +11.524574 2.328833 0.120000 +10.142948 2.391523 0.120000 +11.557052 2.391523 0.120000 +10.097487 2.447487 0.120000 +8.850000 1.800000 0.120000 +8.786313 1.794157 0.120000 +9.505843 2.263687 0.120000 +8.175426 2.328833 0.120000 +9.524574 2.328833 0.120000 +8.142948 2.391523 0.120000 +9.557052 2.391523 0.120000 +8.097487 2.447487 0.120000 +6.850000 1.800000 0.120000 +6.786313 1.794157 0.120000 +7.505843 2.263687 0.120000 +6.175426 2.328833 0.120000 +7.524574 2.328833 0.120000 +6.142949 2.391523 0.120000 +7.557052 2.391523 0.120000 +6.097487 2.447487 0.120000 +4.850000 1.800000 0.120000 +4.786313 1.794157 0.120000 +5.505843 2.263687 0.120000 +4.175426 2.328833 0.120000 +5.524574 2.328833 0.120000 +4.142949 2.391523 0.120000 +5.557052 2.391523 0.120000 +4.097487 2.447487 0.120000 +2.850000 1.800000 0.120000 +2.786313 1.794157 0.120000 +3.505843 2.263687 0.120000 +2.175426 2.328833 0.120000 +3.524574 2.328833 0.120000 +2.142948 2.391523 0.120000 +3.557052 2.391523 0.120000 +2.097487 2.447487 0.120000 +1.658477 2.492949 0.120000 +1.721167 0.374574 0.120000 +2.097487 0.452513 0.120000 +3.658477 0.407052 0.120000 +4.097487 0.452513 0.120000 +5.658476 0.407052 0.120000 +6.097487 0.452513 0.120000 +7.658476 0.407052 0.120000 +8.097487 0.452513 0.120000 +9.658477 0.407052 0.120000 +10.097487 0.452513 0.120000 +11.658477 0.407052 0.120000 +12.097487 0.452513 0.120000 +13.658477 0.407052 0.120000 +14.097487 0.452513 0.120000 +15.658477 0.407052 0.120000 +16.097486 0.452513 0.120000 +17.658476 0.407052 0.120000 +18.097486 0.452513 0.120000 +19.658476 0.407052 0.120000 +20.097486 0.452513 0.120000 +21.658476 0.407052 0.120000 +22.097486 0.452513 0.120000 +23.658476 0.407052 0.120000 +24.097486 0.452513 0.120000 +25.658476 0.407052 0.120000 +26.097486 0.452513 0.120000 +27.658476 0.407052 0.120000 +28.097486 0.452513 0.120000 +29.658476 0.407052 0.120000 +30.097486 0.452513 0.120000 +31.658476 0.407052 0.120000 +32.097488 0.452513 0.120000 +33.658478 0.407052 0.120000 +34.097488 0.452513 0.120000 +35.658478 0.407052 0.120000 +36.097488 0.452513 0.120000 +37.658478 0.407052 0.120000 +38.097488 0.947487 0.120000 +38.142948 2.008476 0.120000 +37.602512 2.447487 0.120000 +36.041523 2.492949 0.120000 +35.602512 2.447487 0.120000 +34.041523 2.492949 0.120000 +33.602512 2.447487 0.120000 +32.041523 2.492949 0.120000 +31.602512 2.447487 0.120000 +30.041523 2.492949 0.120000 +29.602512 2.447487 0.120000 +28.041523 2.492949 0.120000 +27.602512 2.447487 0.120000 +26.041523 2.492949 0.120000 +25.602512 2.447487 0.120000 +24.041523 2.492949 0.120000 +23.602512 2.447487 0.120000 +22.041523 2.492949 0.120000 +21.602512 2.447487 0.120000 +20.041523 2.492949 0.120000 +19.602512 2.447487 0.120000 +18.041523 2.492949 0.120000 +17.602512 2.447487 0.120000 +16.041523 2.492949 0.120000 +15.602512 2.447487 0.120000 +14.041523 2.492949 0.120000 +13.602512 2.447487 0.120000 +12.041523 2.492949 0.120000 +11.602512 2.447487 0.120000 +10.041523 2.492949 0.120000 +9.602512 2.447487 0.120000 +8.041523 2.492949 0.120000 +7.602513 2.447487 0.120000 +6.041523 2.492949 0.120000 +5.602513 2.447487 0.120000 +4.041523 2.492949 0.120000 +3.602513 2.447487 0.120000 +2.041523 2.492949 0.120000 +1.721167 2.525426 0.120000 +1.786313 0.355843 0.120000 +2.041523 0.407052 0.120000 +3.721167 0.374574 0.120000 +4.041523 0.407052 0.120000 +5.721167 0.374574 0.120000 +6.041523 0.407052 0.120000 +7.721167 0.374574 0.120000 +8.041523 0.407052 0.120000 +9.721167 0.374574 0.120000 +10.041523 0.407052 0.120000 +11.721167 0.374574 0.120000 +12.041523 0.407052 0.120000 +13.721167 0.374574 0.120000 +14.041523 0.407052 0.120000 +15.721167 0.374574 0.120000 +16.041523 0.407052 0.120000 +17.721167 0.374574 0.120000 +18.041523 0.407052 0.120000 +19.721167 0.374574 0.120000 +20.041523 0.407052 0.120000 +21.721167 0.374574 0.120000 +22.041523 0.407052 0.120000 +23.721167 0.374574 0.120000 +24.041523 0.407052 0.120000 +25.721167 0.374574 0.120000 +26.041523 0.407052 0.120000 +27.721167 0.374574 0.120000 +28.041523 0.407052 0.120000 +29.721167 0.374574 0.120000 +30.041523 0.407052 0.120000 +31.721167 0.374574 0.120000 +32.041523 0.407052 0.120000 +33.721169 0.374574 0.120000 +34.041523 0.407052 0.120000 +35.721169 0.374574 0.120000 +36.041523 0.407052 0.120000 +37.721169 0.374574 0.120000 +38.142948 0.891523 0.120000 +38.175426 2.071167 0.120000 +37.658478 2.492949 0.120000 +35.978832 2.525426 0.120000 +35.658478 2.492949 0.120000 +33.978832 2.525426 0.120000 +33.658478 2.492949 0.120000 +31.978832 2.525426 0.120000 +31.658476 2.492949 0.120000 +29.978832 2.525426 0.120000 +29.658476 2.492949 0.120000 +27.978832 2.525426 0.120000 +27.658476 2.492949 0.120000 +25.978832 2.525426 0.120000 +25.658476 2.492949 0.120000 +23.978832 2.525426 0.120000 +23.658476 2.492949 0.120000 +21.978832 2.525426 0.120000 +21.658476 2.492949 0.120000 +19.978832 2.525426 0.120000 +19.658476 2.492949 0.120000 +17.978832 2.525426 0.120000 +17.658476 2.492949 0.120000 +15.978833 2.525426 0.120000 +15.658477 2.492949 0.120000 +13.978833 2.525426 0.120000 +13.658477 2.492949 0.120000 +11.978833 2.525426 0.120000 +11.658477 2.492949 0.120000 +9.978833 2.525426 0.120000 +9.658477 2.492949 0.120000 +7.978833 2.525426 0.120000 +7.658476 2.492949 0.120000 +5.978833 2.525426 0.120000 +5.658476 2.492949 0.120000 +3.978833 2.525426 0.120000 +3.658477 2.492949 0.120000 +1.978833 2.525426 0.120000 +1.978833 0.374574 0.120000 +3.978833 0.374574 0.120000 +5.978833 0.374574 0.120000 +7.978833 0.374574 0.120000 +9.978833 0.374574 0.120000 +3.786313 0.355843 0.120000 +5.786313 0.355843 0.120000 +7.786313 0.355843 0.120000 +9.786313 0.355843 0.120000 +11.786313 0.355843 0.120000 +11.978833 0.374574 0.120000 +13.978833 0.374574 0.120000 +15.978833 0.374574 0.120000 +13.786313 0.355843 0.120000 +15.786313 0.355843 0.120000 +17.786312 0.355843 0.120000 +17.978832 0.374574 0.120000 +19.978832 0.374574 0.120000 +21.978832 0.374574 0.120000 +23.978832 0.374574 0.120000 +19.786312 0.355843 0.120000 +21.786312 0.355843 0.120000 +23.786312 0.355843 0.120000 +25.786312 0.355843 0.120000 +25.978832 0.374574 0.120000 +27.978832 0.374574 0.120000 +29.978832 0.374574 0.120000 +27.786312 0.355843 0.120000 +29.786312 0.355843 0.120000 +31.786312 0.355843 0.120000 +31.978832 0.374574 0.120000 +33.978832 0.374574 0.120000 +35.978832 0.374574 0.120000 +38.175426 0.828833 0.120000 +33.786312 0.355843 0.120000 +35.786312 0.355843 0.120000 +37.786312 0.355843 0.120000 +38.194157 2.136313 0.120000 +37.721169 2.525426 0.120000 +35.721169 2.525426 0.120000 +33.721169 2.525426 0.120000 +35.913689 2.544157 0.120000 +33.913689 2.544157 0.120000 +31.913687 2.544157 0.120000 +31.721167 2.525426 0.120000 +29.721167 2.525426 0.120000 +27.721167 2.525426 0.120000 +25.721167 2.525426 0.120000 +29.913687 2.544157 0.120000 +27.913687 2.544157 0.120000 +25.913687 2.544157 0.120000 +23.913687 2.544157 0.120000 +23.721167 2.525426 0.120000 +21.721167 2.525426 0.120000 +19.721167 2.525426 0.120000 +21.913687 2.544157 0.120000 +19.913687 2.544157 0.120000 +17.913687 2.544157 0.120000 +17.721167 2.525426 0.120000 +15.721167 2.525426 0.120000 +13.721167 2.525426 0.120000 +11.721167 2.525426 0.120000 +15.913687 2.544157 0.120000 +13.913687 2.544157 0.120000 +11.913687 2.544157 0.120000 +9.913687 2.544157 0.120000 +9.721167 2.525426 0.120000 +7.721167 2.525426 0.120000 +5.721167 2.525426 0.120000 +7.913687 2.544157 0.120000 +5.913687 2.544157 0.120000 +3.913687 2.544157 0.120000 +3.721167 2.525426 0.120000 +1.913687 2.544157 0.120000 +1.786313 2.544157 0.120000 +39.700001 2.900000 0.120000 +1.850000 2.550000 0.120000 +1.850000 0.350000 0.120000 +0.000000 0.000000 0.120000 +1.913687 0.355843 0.120000 +3.850000 0.350000 0.120000 +3.913687 0.355843 0.120000 +5.850000 0.350000 0.120000 +5.913687 0.355843 0.120000 +7.850000 0.350000 0.120000 +7.913687 0.355843 0.120000 +9.850000 0.350000 0.120000 +9.913687 0.355843 0.120000 +11.850000 0.350000 0.120000 +11.913687 0.355843 0.120000 +13.850000 0.350000 0.120000 +13.913687 0.355843 0.120000 +15.850000 0.350000 0.120000 +15.913687 0.355843 0.120000 +17.850000 0.350000 0.120000 +17.913687 0.355843 0.120000 +19.850000 0.350000 0.120000 +19.913687 0.355843 0.120000 +21.850000 0.350000 0.120000 +21.913687 0.355843 0.120000 +23.850000 0.350000 0.120000 +23.913687 0.355843 0.120000 +25.850000 0.350000 0.120000 +25.913687 0.355843 0.120000 +27.850000 0.350000 0.120000 +27.913687 0.355843 0.120000 +29.850000 0.350000 0.120000 +29.913687 0.355843 0.120000 +31.850000 0.350000 0.120000 +31.913687 0.355843 0.120000 +33.849998 0.350000 0.120000 +33.913689 0.355843 0.120000 +35.849998 0.350000 0.120000 +35.913689 0.355843 0.120000 +37.849998 0.350000 0.120000 +37.913689 0.355843 0.120000 +37.978832 0.374574 0.120000 +38.041523 0.407052 0.120000 +38.097488 0.452513 0.120000 +38.142948 0.508477 0.120000 +39.700001 0.000000 0.120000 +38.175426 0.571167 0.120000 +38.194157 0.636313 0.120000 +38.200001 0.700000 0.120000 +38.194157 0.763687 0.120000 +38.200001 2.200000 0.120000 +38.194157 2.263687 0.120000 +38.175426 2.328833 0.120000 +38.142948 2.391523 0.120000 +38.097488 2.447487 0.120000 +38.041523 2.492949 0.120000 +37.978832 2.525426 0.120000 +37.913689 2.544157 0.120000 +37.849998 2.550000 0.120000 +37.786312 2.544157 0.120000 +35.849998 2.550000 0.120000 +35.786312 2.544157 0.120000 +33.849998 2.550000 0.120000 +33.786312 2.544157 0.120000 +31.786312 2.544157 0.120000 +29.786312 2.544157 0.120000 +27.786312 2.544157 0.120000 +25.786312 2.544157 0.120000 +31.850000 2.550000 0.120000 +29.850000 2.550000 0.120000 +27.850000 2.550000 0.120000 +25.850000 2.550000 0.120000 +23.850000 2.550000 0.120000 +23.786312 2.544157 0.120000 +21.786312 2.544157 0.120000 +19.786312 2.544157 0.120000 +21.850000 2.550000 0.120000 +19.850000 2.550000 0.120000 +17.850000 2.550000 0.120000 +17.786312 2.544157 0.120000 +15.786313 2.544157 0.120000 +13.786313 2.544157 0.120000 +11.786313 2.544157 0.120000 +15.850000 2.550000 0.120000 +13.850000 2.550000 0.120000 +11.850000 2.550000 0.120000 +9.850000 2.550000 0.120000 +9.786313 2.544157 0.120000 +7.786313 2.544157 0.120000 +5.786313 2.544157 0.120000 +7.850000 2.550000 0.120000 +5.850000 2.550000 0.120000 +3.850000 2.550000 0.120000 +3.786313 2.544157 0.120000 +0.000000 0.000000 0.000000 +1.505843 0.636313 0.000000 +1.500000 0.700000 0.000000 +1.505843 0.763687 0.000000 +1.524574 0.828833 0.000000 +1.557052 0.891523 0.000000 +1.602513 0.947487 0.000000 +2.142948 0.891523 0.000000 +2.097487 1.952513 0.000000 +2.602513 1.697487 0.000000 +3.142948 1.641523 0.000000 +3.557052 2.008476 0.000000 +3.602513 0.947487 0.000000 +4.142949 0.891523 0.000000 +5.602513 0.947487 0.000000 +6.142949 0.891523 0.000000 +6.097487 1.952513 0.000000 +6.602513 1.697487 0.000000 +7.602513 0.947487 0.000000 +8.142948 0.891523 0.000000 +8.097487 1.952513 0.000000 +8.602512 1.697487 0.000000 +9.602512 0.947487 0.000000 +10.142948 0.891523 0.000000 +10.097487 1.952513 0.000000 +10.602512 1.697487 0.000000 +11.602512 0.947487 0.000000 +12.142948 0.891523 0.000000 +12.097487 1.952513 0.000000 +12.602512 1.697487 0.000000 +13.602512 0.947487 0.000000 +14.142948 0.891523 0.000000 +14.097487 1.952513 0.000000 +14.602512 1.697487 0.000000 +15.142948 1.641523 0.000000 +15.557052 2.008476 0.000000 +15.602512 0.947487 0.000000 +16.142948 0.891523 0.000000 +17.142948 1.641523 0.000000 +18.602512 1.697487 0.000000 +19.142948 1.641523 0.000000 +20.602512 1.697487 0.000000 +21.142948 1.641523 0.000000 +21.557051 2.008476 0.000000 +21.602512 0.947487 0.000000 +22.142948 0.891523 0.000000 +23.142948 1.641523 0.000000 +24.602512 1.697487 0.000000 +25.142948 1.641523 0.000000 +26.602512 1.697487 0.000000 +27.602512 0.947487 0.000000 +28.142948 0.891523 0.000000 +28.097486 1.952513 0.000000 +28.602512 1.697487 0.000000 +29.142948 1.641523 0.000000 +29.557051 2.008476 0.000000 +29.602512 0.947487 0.000000 +30.142948 0.891523 0.000000 +31.602512 0.947487 0.000000 +32.142948 0.891523 0.000000 +32.097488 1.952513 0.000000 +32.602512 1.697487 0.000000 +33.602512 0.947487 0.000000 +34.142948 0.891523 0.000000 +34.097488 1.952513 0.000000 +34.602512 1.697487 0.000000 +35.602512 0.947487 0.000000 +36.142948 0.891523 0.000000 +36.097488 1.952513 0.000000 +36.602512 1.697487 0.000000 +37.142948 1.641523 0.000000 +37.557053 2.008476 0.000000 +37.602512 0.947487 0.000000 +37.097488 1.202513 0.000000 +36.557053 1.258477 0.000000 +35.097488 1.202513 0.000000 +34.557053 1.258477 0.000000 +33.097488 1.202513 0.000000 +32.557053 1.258477 0.000000 +31.097486 1.202513 0.000000 +30.557051 1.258477 0.000000 +29.097486 1.202513 0.000000 +28.557051 1.258477 0.000000 +27.097486 1.202513 0.000000 +26.557051 1.258477 0.000000 +26.142948 0.891523 0.000000 +26.097486 1.952513 0.000000 +25.557051 2.008476 0.000000 +24.097486 1.952513 0.000000 +23.557051 2.008476 0.000000 +23.602512 0.947487 0.000000 +23.097486 1.202513 0.000000 +22.557051 1.258477 0.000000 +21.097486 1.202513 0.000000 +20.097486 1.952513 0.000000 +19.557051 2.008476 0.000000 +19.602512 0.947487 0.000000 +19.097486 1.202513 0.000000 +18.557051 1.258477 0.000000 +18.142948 0.891523 0.000000 +18.097486 1.952513 0.000000 +17.557051 2.008476 0.000000 +16.557051 1.258477 0.000000 +15.097487 1.202513 0.000000 +14.557052 1.258477 0.000000 +13.097487 1.202513 0.000000 +12.557052 1.258477 0.000000 +11.097487 1.202513 0.000000 +10.557052 1.258477 0.000000 +9.097487 1.202513 0.000000 +8.557052 1.258477 0.000000 +7.097487 1.202513 0.000000 +6.557052 1.258477 0.000000 +5.097487 1.202513 0.000000 +4.557052 1.258477 0.000000 +3.097487 1.202513 0.000000 +2.557052 1.258477 0.000000 +1.658477 0.992948 0.000000 +2.524574 1.321167 0.000000 +2.557052 1.641523 0.000000 +2.142948 2.008476 0.000000 +3.524574 2.071167 0.000000 +3.175426 1.578833 0.000000 +3.142948 1.258477 0.000000 +4.524574 1.321167 0.000000 +5.142949 1.258477 0.000000 +6.524574 1.321167 0.000000 +6.557052 1.641523 0.000000 +6.142949 2.008476 0.000000 +7.142949 1.258477 0.000000 +8.524574 1.321167 0.000000 +8.557052 1.641523 0.000000 +8.142948 2.008476 0.000000 +9.142948 1.258477 0.000000 +10.524574 1.321167 0.000000 +10.557052 1.641523 0.000000 +10.142948 2.008476 0.000000 +11.142948 1.258477 0.000000 +12.524574 1.321167 0.000000 +12.557052 1.641523 0.000000 +12.142948 2.008476 0.000000 +13.142948 1.258477 0.000000 +14.524574 1.321167 0.000000 +14.557052 1.641523 0.000000 +14.142948 2.008476 0.000000 +15.524574 2.071167 0.000000 +15.175426 1.578833 0.000000 +15.142948 1.258477 0.000000 +16.524574 1.321167 0.000000 +17.524574 2.071167 0.000000 +18.142948 2.008476 0.000000 +19.524574 2.071167 0.000000 +20.142948 2.008476 0.000000 +21.524574 2.071167 0.000000 +21.175426 1.578833 0.000000 +21.142948 1.258477 0.000000 +22.524574 1.321167 0.000000 +23.524574 2.071167 0.000000 +24.142948 2.008476 0.000000 +25.524574 2.071167 0.000000 +26.142948 2.008476 0.000000 +27.142948 1.258477 0.000000 +28.524574 1.321167 0.000000 +28.557051 1.641523 0.000000 +28.142948 2.008476 0.000000 +29.524574 2.071167 0.000000 +29.175426 1.578833 0.000000 +29.142948 1.258477 0.000000 +30.524574 1.321167 0.000000 +31.142948 1.258477 0.000000 +32.524574 1.321167 0.000000 +32.557053 1.641523 0.000000 +32.142948 2.008476 0.000000 +33.142948 1.258477 0.000000 +34.524574 1.321167 0.000000 +34.557053 1.641523 0.000000 +34.142948 2.008476 0.000000 +35.142948 1.258477 0.000000 +36.524574 1.321167 0.000000 +36.557053 1.641523 0.000000 +36.142948 2.008476 0.000000 +37.524574 2.071167 0.000000 +37.175426 1.578833 0.000000 +37.142948 1.258477 0.000000 +37.557053 0.891523 0.000000 +36.175426 0.828833 0.000000 +35.557053 0.891523 0.000000 +34.175426 0.828833 0.000000 +33.557053 0.891523 0.000000 +32.175426 0.828833 0.000000 +31.557051 0.891523 0.000000 +30.175426 0.828833 0.000000 +29.557051 0.891523 0.000000 +28.175426 0.828833 0.000000 +27.557051 0.891523 0.000000 +26.175426 0.828833 0.000000 +26.524574 1.321167 0.000000 +26.557051 1.641523 0.000000 +25.175426 1.578833 0.000000 +24.557051 1.641523 0.000000 +23.175426 1.578833 0.000000 +23.142948 1.258477 0.000000 +23.557051 0.891523 0.000000 +22.175426 0.828833 0.000000 +21.557051 0.891523 0.000000 +20.557051 1.641523 0.000000 +19.175426 1.578833 0.000000 +19.142948 1.258477 0.000000 +19.557051 0.891523 0.000000 +18.175426 0.828833 0.000000 +18.524574 1.321167 0.000000 +18.557051 1.641523 0.000000 +17.175426 1.578833 0.000000 +16.175426 0.828833 0.000000 +15.557052 0.891523 0.000000 +14.175426 0.828833 0.000000 +13.557052 0.891523 0.000000 +12.175426 0.828833 0.000000 +11.557052 0.891523 0.000000 +10.175426 0.828833 0.000000 +9.557052 0.891523 0.000000 +8.175426 0.828833 0.000000 +7.557052 0.891523 0.000000 +6.175426 0.828833 0.000000 +5.557052 0.891523 0.000000 +4.175426 0.828833 0.000000 +3.557052 0.891523 0.000000 +2.175426 0.828833 0.000000 +1.524574 0.571167 0.000000 +2.097487 0.947487 0.000000 +2.041523 1.907052 0.000000 +2.658477 1.742948 0.000000 +3.097487 1.697487 0.000000 +3.602513 1.952513 0.000000 +3.658477 0.992948 0.000000 +4.097487 0.947487 0.000000 +5.658476 0.992948 0.000000 +6.097487 0.947487 0.000000 +6.041523 1.907052 0.000000 +6.658476 1.742948 0.000000 +7.658476 0.992948 0.000000 +8.097487 0.947487 0.000000 +8.041523 1.907052 0.000000 +8.658477 1.742948 0.000000 +9.658477 0.992948 0.000000 +10.097487 0.947487 0.000000 +10.041523 1.907052 0.000000 +10.658477 1.742948 0.000000 +11.658477 0.992948 0.000000 +12.097487 0.947487 0.000000 +12.041523 1.907052 0.000000 +12.658477 1.742948 0.000000 +13.658477 0.992948 0.000000 +14.097487 0.947487 0.000000 +14.041523 1.907052 0.000000 +14.658477 1.742948 0.000000 +15.097487 1.697487 0.000000 +15.602512 1.952513 0.000000 +15.658477 0.992948 0.000000 +16.097486 0.947487 0.000000 +17.097486 1.697487 0.000000 +18.658476 1.742948 0.000000 +19.097486 1.697487 0.000000 +20.658476 1.742948 0.000000 +21.097486 1.697487 0.000000 +21.602512 1.952513 0.000000 +21.658476 0.992948 0.000000 +22.097486 0.947487 0.000000 +23.097486 1.697487 0.000000 +24.658476 1.742948 0.000000 +25.097486 1.697487 0.000000 +26.658476 1.742948 0.000000 +27.658476 0.992948 0.000000 +28.097486 0.947487 0.000000 +28.041523 1.907052 0.000000 +28.658476 1.742948 0.000000 +29.097486 1.697487 0.000000 +29.602512 1.952513 0.000000 +29.658476 0.992948 0.000000 +30.097486 0.947487 0.000000 +31.658476 0.992948 0.000000 +32.097488 0.947487 0.000000 +32.041523 1.907052 0.000000 +32.658478 1.742948 0.000000 +33.658478 0.992948 0.000000 +34.097488 0.947487 0.000000 +34.041523 1.907052 0.000000 +34.658478 1.742948 0.000000 +35.658478 0.992948 0.000000 +36.097488 0.947487 0.000000 +36.041523 1.907052 0.000000 +36.658478 1.742948 0.000000 +37.097488 1.697487 0.000000 +37.602512 1.952513 0.000000 +37.658478 0.992948 0.000000 +37.041523 1.157052 0.000000 +36.602512 1.202513 0.000000 +35.041523 1.157052 0.000000 +34.602512 1.202513 0.000000 +33.041523 1.157052 0.000000 +32.602512 1.202513 0.000000 +31.041523 1.157052 0.000000 +30.602512 1.202513 0.000000 +29.041523 1.157052 0.000000 +28.602512 1.202513 0.000000 +27.041523 1.157052 0.000000 +26.602512 1.202513 0.000000 +26.097486 0.947487 0.000000 +26.041523 1.907052 0.000000 +25.602512 1.952513 0.000000 +24.041523 1.907052 0.000000 +23.602512 1.952513 0.000000 +23.658476 0.992948 0.000000 +23.041523 1.157052 0.000000 +22.602512 1.202513 0.000000 +21.041523 1.157052 0.000000 +20.041523 1.907052 0.000000 +19.602512 1.952513 0.000000 +19.658476 0.992948 0.000000 +19.041523 1.157052 0.000000 +18.602512 1.202513 0.000000 +18.097486 0.947487 0.000000 +18.041523 1.907052 0.000000 +17.602512 1.952513 0.000000 +16.602512 1.202513 0.000000 +15.041523 1.157052 0.000000 +14.602512 1.202513 0.000000 +13.041523 1.157052 0.000000 +12.602512 1.202513 0.000000 +11.041523 1.157052 0.000000 +10.602512 1.202513 0.000000 +9.041523 1.157052 0.000000 +8.602512 1.202513 0.000000 +7.041523 1.157052 0.000000 +6.602513 1.202513 0.000000 +5.041523 1.157052 0.000000 +4.602513 1.202513 0.000000 +3.041523 1.157052 0.000000 +2.602513 1.202513 0.000000 +1.721167 1.025426 0.000000 +2.505843 1.386313 0.000000 +2.524574 1.578833 0.000000 +2.175426 2.071167 0.000000 +3.505843 2.136313 0.000000 +3.194157 1.513687 0.000000 +3.175426 1.321167 0.000000 +4.505843 1.386313 0.000000 +5.175426 1.321167 0.000000 +6.505843 1.386313 0.000000 +6.524574 1.578833 0.000000 +6.175426 2.071167 0.000000 +7.175426 1.321167 0.000000 +8.505843 1.386313 0.000000 +8.524574 1.578833 0.000000 +8.175426 2.071167 0.000000 +9.175426 1.321167 0.000000 +10.505843 1.386313 0.000000 +10.524574 1.578833 0.000000 +10.175426 2.071167 0.000000 +11.175426 1.321167 0.000000 +12.505843 1.386313 0.000000 +12.524574 1.578833 0.000000 +12.175426 2.071167 0.000000 +13.175426 1.321167 0.000000 +14.505843 1.386313 0.000000 +14.524574 1.578833 0.000000 +14.175426 2.071167 0.000000 +15.505843 2.136313 0.000000 +15.194157 1.513687 0.000000 +15.175426 1.321167 0.000000 +16.505842 1.386313 0.000000 +17.505842 2.136313 0.000000 +18.175426 2.071167 0.000000 +19.505842 2.136313 0.000000 +20.175426 2.071167 0.000000 +21.505842 2.136313 0.000000 +21.194157 1.513687 0.000000 +21.175426 1.321167 0.000000 +22.505842 1.386313 0.000000 +23.505842 2.136313 0.000000 +24.175426 2.071167 0.000000 +25.505842 2.136313 0.000000 +26.175426 2.071167 0.000000 +27.175426 1.321167 0.000000 +28.505842 1.386313 0.000000 +28.524574 1.578833 0.000000 +28.175426 2.071167 0.000000 +29.505842 2.136313 0.000000 +29.194157 1.513687 0.000000 +29.175426 1.321167 0.000000 +30.505842 1.386313 0.000000 +31.175426 1.321167 0.000000 +32.505844 1.386313 0.000000 +32.524574 1.578833 0.000000 +32.175426 2.071167 0.000000 +33.175426 1.321167 0.000000 +34.505844 1.386313 0.000000 +34.524574 1.578833 0.000000 +34.175426 2.071167 0.000000 +35.175426 1.321167 0.000000 +36.505844 1.386313 0.000000 +36.524574 1.578833 0.000000 +36.175426 2.071167 0.000000 +37.505844 2.136313 0.000000 +37.194157 1.513687 0.000000 +37.175426 1.321167 0.000000 +37.524574 0.828833 0.000000 +36.194157 0.763687 0.000000 +35.524574 0.828833 0.000000 +34.194157 0.763687 0.000000 +33.524574 0.828833 0.000000 +32.194157 0.763687 0.000000 +31.524574 0.828833 0.000000 +30.194157 0.763687 0.000000 +29.524574 0.828833 0.000000 +28.194157 0.763687 0.000000 +27.524574 0.828833 0.000000 +26.194157 0.763687 0.000000 +26.505842 1.386313 0.000000 +26.524574 1.578833 0.000000 +25.194157 1.513687 0.000000 +24.524574 1.578833 0.000000 +23.194157 1.513687 0.000000 +23.175426 1.321167 0.000000 +23.524574 0.828833 0.000000 +22.194157 0.763687 0.000000 +21.524574 0.828833 0.000000 +20.524574 1.578833 0.000000 +19.194157 1.513687 0.000000 +19.175426 1.321167 0.000000 +19.524574 0.828833 0.000000 +18.194157 0.763687 0.000000 +18.505842 1.386313 0.000000 +18.524574 1.578833 0.000000 +17.194157 1.513687 0.000000 +16.194157 0.763687 0.000000 +15.524574 0.828833 0.000000 +14.194157 0.763687 0.000000 +13.524574 0.828833 0.000000 +12.194157 0.763687 0.000000 +11.524574 0.828833 0.000000 +10.194157 0.763687 0.000000 +9.524574 0.828833 0.000000 +8.194157 0.763687 0.000000 +7.524574 0.828833 0.000000 +6.194157 0.763687 0.000000 +5.524574 0.828833 0.000000 +4.194157 0.763687 0.000000 +3.524574 0.828833 0.000000 +2.194157 0.763687 0.000000 +1.557052 0.508477 0.000000 +2.041523 0.992948 0.000000 +1.978833 1.874574 0.000000 +2.721167 1.775426 0.000000 +3.041523 1.742948 0.000000 +3.658477 1.907052 0.000000 +3.721167 1.025426 0.000000 +4.041523 0.992948 0.000000 +5.721167 1.025426 0.000000 +6.041523 0.992948 0.000000 +5.978833 1.874574 0.000000 +6.721167 1.775426 0.000000 +7.721167 1.025426 0.000000 +8.041523 0.992948 0.000000 +7.978833 1.874574 0.000000 +8.721167 1.775426 0.000000 +9.721167 1.025426 0.000000 +10.041523 0.992948 0.000000 +9.978833 1.874574 0.000000 +10.721167 1.775426 0.000000 +11.721167 1.025426 0.000000 +12.041523 0.992948 0.000000 +11.978833 1.874574 0.000000 +12.721167 1.775426 0.000000 +13.721167 1.025426 0.000000 +14.041523 0.992948 0.000000 +13.978833 1.874574 0.000000 +14.721167 1.775426 0.000000 +15.041523 1.742948 0.000000 +15.658477 1.907052 0.000000 +15.721167 1.025426 0.000000 +16.041523 0.992948 0.000000 +17.041523 1.742948 0.000000 +18.721167 1.775426 0.000000 +19.041523 1.742948 0.000000 +20.721167 1.775426 0.000000 +21.041523 1.742948 0.000000 +21.658476 1.907052 0.000000 +21.721167 1.025426 0.000000 +22.041523 0.992948 0.000000 +23.041523 1.742948 0.000000 +24.721167 1.775426 0.000000 +25.041523 1.742948 0.000000 +26.721167 1.775426 0.000000 +27.721167 1.025426 0.000000 +28.041523 0.992948 0.000000 +27.978832 1.874574 0.000000 +28.721167 1.775426 0.000000 +29.041523 1.742948 0.000000 +29.658476 1.907052 0.000000 +29.721167 1.025426 0.000000 +30.041523 0.992948 0.000000 +31.721167 1.025426 0.000000 +32.041523 0.992948 0.000000 +31.978832 1.874574 0.000000 +32.721169 1.775426 0.000000 +33.721169 1.025426 0.000000 +34.041523 0.992948 0.000000 +33.978832 1.874574 0.000000 +34.721169 1.775426 0.000000 +35.721169 1.025426 0.000000 +36.041523 0.992948 0.000000 +35.978832 1.874574 0.000000 +36.721169 1.775426 0.000000 +37.041523 1.742948 0.000000 +37.658478 1.907052 0.000000 +37.721169 1.025426 0.000000 +36.978832 1.124574 0.000000 +36.658478 1.157052 0.000000 +34.978832 1.124574 0.000000 +34.658478 1.157052 0.000000 +32.978832 1.124574 0.000000 +32.658478 1.157052 0.000000 +30.978832 1.124574 0.000000 +30.658476 1.157052 0.000000 +28.978832 1.124574 0.000000 +28.658476 1.157052 0.000000 +26.978832 1.124574 0.000000 +26.658476 1.157052 0.000000 +26.041523 0.992948 0.000000 +25.978832 1.874574 0.000000 +25.658476 1.907052 0.000000 +23.978832 1.874574 0.000000 +23.658476 1.907052 0.000000 +23.721167 1.025426 0.000000 +22.978832 1.124574 0.000000 +22.658476 1.157052 0.000000 +20.978832 1.124574 0.000000 +19.978832 1.874574 0.000000 +19.658476 1.907052 0.000000 +19.721167 1.025426 0.000000 +18.978832 1.124574 0.000000 +18.658476 1.157052 0.000000 +18.041523 0.992948 0.000000 +17.978832 1.874574 0.000000 +17.658476 1.907052 0.000000 +16.658476 1.157052 0.000000 +14.978833 1.124574 0.000000 +14.658477 1.157052 0.000000 +12.978833 1.124574 0.000000 +12.658477 1.157052 0.000000 +10.978833 1.124574 0.000000 +10.658477 1.157052 0.000000 +8.978833 1.124574 0.000000 +8.658477 1.157052 0.000000 +6.978833 1.124574 0.000000 +6.658476 1.157052 0.000000 +4.978833 1.124574 0.000000 +4.658476 1.157052 0.000000 +2.978833 1.124574 0.000000 +2.658477 1.157052 0.000000 +1.786313 1.044157 0.000000 +2.500000 1.450000 0.000000 +2.505843 1.513687 0.000000 +1.978833 1.025426 0.000000 +1.913687 1.855843 0.000000 +1.913687 1.044157 0.000000 +1.850000 1.850000 0.000000 +1.850000 1.050000 0.000000 +1.786313 1.855843 0.000000 +1.721167 1.874574 0.000000 +2.194157 2.136313 0.000000 +3.500000 2.200000 0.000000 +3.200000 1.450000 0.000000 +3.194157 1.386313 0.000000 +3.721167 1.874574 0.000000 +3.786313 1.044157 0.000000 +3.786313 1.855843 0.000000 +3.850000 1.050000 0.000000 +3.850000 1.850000 0.000000 +3.913687 1.044157 0.000000 +3.913687 1.855843 0.000000 +3.978833 1.025426 0.000000 +4.500000 1.450000 0.000000 +4.505843 1.513687 0.000000 +3.978833 1.874574 0.000000 +4.524574 1.578833 0.000000 +4.041523 1.907052 0.000000 +4.557052 1.641523 0.000000 +4.097487 1.952513 0.000000 +4.602513 1.697487 0.000000 +4.142949 2.008476 0.000000 +4.658476 1.742948 0.000000 +4.175426 2.071167 0.000000 +4.721167 1.775426 0.000000 +5.194157 1.386313 0.000000 +6.500000 1.450000 0.000000 +6.505843 1.513687 0.000000 +5.978833 1.025426 0.000000 +5.913687 1.855843 0.000000 +5.913687 1.044157 0.000000 +5.850000 1.850000 0.000000 +5.850000 1.050000 0.000000 +5.786313 1.855843 0.000000 +5.786313 1.044157 0.000000 +5.721167 1.874574 0.000000 +5.200000 1.450000 0.000000 +5.658476 1.907052 0.000000 +5.194157 1.513687 0.000000 +5.602513 1.952513 0.000000 +5.175426 1.578833 0.000000 +5.557052 2.008476 0.000000 +5.142949 1.641523 0.000000 +5.524574 2.071167 0.000000 +5.097487 1.697487 0.000000 +5.505843 2.136313 0.000000 +5.041523 1.742948 0.000000 +4.194157 2.136313 0.000000 +5.500000 2.200000 0.000000 +6.194157 2.136313 0.000000 +7.194157 1.386313 0.000000 +8.500000 1.450000 0.000000 +8.505843 1.513687 0.000000 +7.978833 1.025426 0.000000 +7.913687 1.855843 0.000000 +7.913687 1.044157 0.000000 +7.850000 1.850000 0.000000 +7.850000 1.050000 0.000000 +7.786313 1.855843 0.000000 +7.786313 1.044157 0.000000 +7.721167 1.874574 0.000000 +7.200000 1.450000 0.000000 +7.658476 1.907052 0.000000 +7.194157 1.513687 0.000000 +7.602513 1.952513 0.000000 +7.175426 1.578833 0.000000 +7.557052 2.008476 0.000000 +7.142949 1.641523 0.000000 +7.524574 2.071167 0.000000 +7.097487 1.697487 0.000000 +7.505843 2.136313 0.000000 +7.041523 1.742948 0.000000 +8.194157 2.136313 0.000000 +9.194157 1.386313 0.000000 +10.500000 1.450000 0.000000 +10.505843 1.513687 0.000000 +9.978833 1.025426 0.000000 +9.913687 1.855843 0.000000 +9.913687 1.044157 0.000000 +9.850000 1.850000 0.000000 +9.850000 1.050000 0.000000 +9.786313 1.855843 0.000000 +9.786313 1.044157 0.000000 +9.721167 1.874574 0.000000 +9.200000 1.450000 0.000000 +9.658477 1.907052 0.000000 +9.194157 1.513687 0.000000 +9.602512 1.952513 0.000000 +9.175426 1.578833 0.000000 +9.557052 2.008476 0.000000 +9.142948 1.641523 0.000000 +9.524574 2.071167 0.000000 +9.097487 1.697487 0.000000 +9.505843 2.136313 0.000000 +9.041523 1.742948 0.000000 +7.500000 2.200000 0.000000 +9.500000 2.200000 0.000000 +10.194157 2.136313 0.000000 +11.194157 1.386313 0.000000 +12.500000 1.450000 0.000000 +12.505843 1.513687 0.000000 +11.978833 1.025426 0.000000 +11.913687 1.855843 0.000000 +11.913687 1.044157 0.000000 +11.850000 1.850000 0.000000 +11.850000 1.050000 0.000000 +11.786313 1.855843 0.000000 +11.786313 1.044157 0.000000 +11.721167 1.874574 0.000000 +11.200000 1.450000 0.000000 +11.658477 1.907052 0.000000 +11.194157 1.513687 0.000000 +11.602512 1.952513 0.000000 +11.175426 1.578833 0.000000 +11.557052 2.008476 0.000000 +11.142948 1.641523 0.000000 +11.524574 2.071167 0.000000 +11.097487 1.697487 0.000000 +11.505843 2.136313 0.000000 +11.041523 1.742948 0.000000 +12.194157 2.136313 0.000000 +13.194157 1.386313 0.000000 +14.500000 1.450000 0.000000 +14.505843 1.513687 0.000000 +13.978833 1.025426 0.000000 +13.913687 1.855843 0.000000 +13.913687 1.044157 0.000000 +13.850000 1.850000 0.000000 +13.850000 1.050000 0.000000 +13.786313 1.855843 0.000000 +13.786313 1.044157 0.000000 +13.721167 1.874574 0.000000 +13.200000 1.450000 0.000000 +13.658477 1.907052 0.000000 +13.194157 1.513687 0.000000 +13.602512 1.952513 0.000000 +13.175426 1.578833 0.000000 +13.557052 2.008476 0.000000 +13.142948 1.641523 0.000000 +13.524574 2.071167 0.000000 +13.097487 1.697487 0.000000 +13.505843 2.136313 0.000000 +13.041523 1.742948 0.000000 +11.500000 2.200000 0.000000 +13.500000 2.200000 0.000000 +14.194157 2.136313 0.000000 +15.500000 2.200000 0.000000 +15.200000 1.450000 0.000000 +15.194157 1.386313 0.000000 +15.721167 1.874574 0.000000 +15.786313 1.044157 0.000000 +15.786313 1.855843 0.000000 +15.850000 1.050000 0.000000 +15.850000 1.850000 0.000000 +15.913687 1.044157 0.000000 +15.913687 1.855843 0.000000 +15.978833 1.025426 0.000000 +16.500000 1.450000 0.000000 +16.505842 1.513687 0.000000 +15.978833 1.874574 0.000000 +16.524574 1.578833 0.000000 +16.041523 1.907052 0.000000 +16.557051 1.641523 0.000000 +16.097486 1.952513 0.000000 +16.602512 1.697487 0.000000 +16.142948 2.008476 0.000000 +16.658476 1.742948 0.000000 +16.175426 2.071167 0.000000 +16.721167 1.775426 0.000000 +17.500000 2.200000 0.000000 +18.194157 2.136313 0.000000 +19.500000 2.200000 0.000000 +16.194157 2.136313 0.000000 +20.194157 2.136313 0.000000 +21.500000 2.200000 0.000000 +21.200001 1.450000 0.000000 +21.194157 1.386313 0.000000 +21.721167 1.874574 0.000000 +21.786312 1.044157 0.000000 +21.786312 1.855843 0.000000 +21.850000 1.050000 0.000000 +21.850000 1.850000 0.000000 +21.913687 1.044157 0.000000 +21.913687 1.855843 0.000000 +21.978832 1.025426 0.000000 +22.500000 1.450000 0.000000 +22.505842 1.513687 0.000000 +21.978832 1.874574 0.000000 +22.524574 1.578833 0.000000 +22.041523 1.907052 0.000000 +22.557051 1.641523 0.000000 +22.097486 1.952513 0.000000 +22.602512 1.697487 0.000000 +22.142948 2.008476 0.000000 +22.658476 1.742948 0.000000 +22.175426 2.071167 0.000000 +22.721167 1.775426 0.000000 +23.500000 2.200000 0.000000 +24.194157 2.136313 0.000000 +25.500000 2.200000 0.000000 +26.194157 2.136313 0.000000 +22.194157 2.136313 0.000000 +27.194157 1.386313 0.000000 +28.500000 1.450000 0.000000 +28.505842 1.513687 0.000000 +27.978832 1.025426 0.000000 +27.913687 1.855843 0.000000 +27.913687 1.044157 0.000000 +27.850000 1.850000 0.000000 +27.850000 1.050000 0.000000 +27.786312 1.855843 0.000000 +27.786312 1.044157 0.000000 +27.721167 1.874574 0.000000 +27.200001 1.450000 0.000000 +27.658476 1.907052 0.000000 +27.194157 1.513687 0.000000 +27.602512 1.952513 0.000000 +27.175426 1.578833 0.000000 +27.557051 2.008476 0.000000 +27.142948 1.641523 0.000000 +27.524574 2.071167 0.000000 +27.097486 1.697487 0.000000 +27.505842 2.136313 0.000000 +27.041523 1.742948 0.000000 +28.194157 2.136313 0.000000 +29.500000 2.200000 0.000000 +29.200001 1.450000 0.000000 +29.194157 1.386313 0.000000 +29.721167 1.874574 0.000000 +29.786312 1.044157 0.000000 +29.786312 1.855843 0.000000 +29.850000 1.050000 0.000000 +29.850000 1.850000 0.000000 +29.913687 1.044157 0.000000 +29.913687 1.855843 0.000000 +29.978832 1.025426 0.000000 +30.500000 1.450000 0.000000 +30.505842 1.513687 0.000000 +29.978832 1.874574 0.000000 +30.524574 1.578833 0.000000 +30.041523 1.907052 0.000000 +30.557051 1.641523 0.000000 +30.097486 1.952513 0.000000 +30.602512 1.697487 0.000000 +30.142948 2.008476 0.000000 +30.658476 1.742948 0.000000 +30.175426 2.071167 0.000000 +30.721167 1.775426 0.000000 +31.194157 1.386313 0.000000 +27.500000 2.200000 0.000000 +30.194157 2.136313 0.000000 +32.500000 1.450000 0.000000 +32.505844 1.513687 0.000000 +31.978832 1.025426 0.000000 +31.913687 1.855843 0.000000 +31.913687 1.044157 0.000000 +31.850000 1.850000 0.000000 +31.850000 1.050000 0.000000 +31.786312 1.855843 0.000000 +31.786312 1.044157 0.000000 +31.721167 1.874574 0.000000 +31.200001 1.450000 0.000000 +31.658476 1.907052 0.000000 +31.194157 1.513687 0.000000 +31.602512 1.952513 0.000000 +31.175426 1.578833 0.000000 +31.557051 2.008476 0.000000 +31.142948 1.641523 0.000000 +31.524574 2.071167 0.000000 +31.097486 1.697487 0.000000 +31.505842 2.136313 0.000000 +31.041523 1.742948 0.000000 +32.194157 2.136313 0.000000 +33.194157 1.386313 0.000000 +34.500000 1.450000 0.000000 +34.505844 1.513687 0.000000 +33.978832 1.025426 0.000000 +33.913689 1.855843 0.000000 +33.913689 1.044157 0.000000 +33.849998 1.850000 0.000000 +33.849998 1.050000 0.000000 +33.786312 1.855843 0.000000 +33.786312 1.044157 0.000000 +33.721169 1.874574 0.000000 +33.200001 1.450000 0.000000 +33.658478 1.907052 0.000000 +33.194157 1.513687 0.000000 +33.602512 1.952513 0.000000 +33.175426 1.578833 0.000000 +33.557053 2.008476 0.000000 +33.142948 1.641523 0.000000 +33.524574 2.071167 0.000000 +33.097488 1.697487 0.000000 +33.505844 2.136313 0.000000 +33.041523 1.742948 0.000000 +34.194157 2.136313 0.000000 +35.194157 1.386313 0.000000 +31.500000 2.200000 0.000000 +33.500000 2.200000 0.000000 +36.500000 1.450000 0.000000 +36.505844 1.513687 0.000000 +35.978832 1.025426 0.000000 +35.913689 1.855843 0.000000 +35.913689 1.044157 0.000000 +35.849998 1.850000 0.000000 +35.849998 1.050000 0.000000 +35.786312 1.855843 0.000000 +35.786312 1.044157 0.000000 +35.721169 1.874574 0.000000 +35.200001 1.450000 0.000000 +35.658478 1.907052 0.000000 +35.194157 1.513687 0.000000 +35.602512 1.952513 0.000000 +35.175426 1.578833 0.000000 +35.557053 2.008476 0.000000 +35.142948 1.641523 0.000000 +35.524574 2.071167 0.000000 +35.097488 1.697487 0.000000 +35.505844 2.136313 0.000000 +35.041523 1.742948 0.000000 +36.194157 2.136313 0.000000 +37.500000 2.200000 0.000000 +37.200001 1.450000 0.000000 +37.194157 1.386313 0.000000 +37.721169 1.874574 0.000000 +37.786312 1.044157 0.000000 +37.786312 1.855843 0.000000 +37.849998 1.050000 0.000000 +37.849998 1.850000 0.000000 +37.913689 1.044157 0.000000 +37.913689 1.855843 0.000000 +37.978832 1.025426 0.000000 +37.978832 1.874574 0.000000 +38.041523 0.992948 0.000000 +37.505844 0.763687 0.000000 +36.200001 0.700000 0.000000 +35.500000 2.200000 0.000000 +35.505844 0.763687 0.000000 +34.200001 0.700000 0.000000 +33.505844 0.763687 0.000000 +32.200001 0.700000 0.000000 +31.505842 0.763687 0.000000 +30.200001 0.700000 0.000000 +29.505842 0.763687 0.000000 +28.200001 0.700000 0.000000 +27.505842 0.763687 0.000000 +26.200001 0.700000 0.000000 +26.500000 1.450000 0.000000 +26.505842 1.513687 0.000000 +25.978832 1.025426 0.000000 +25.913687 1.855843 0.000000 +25.913687 1.044157 0.000000 +25.850000 1.850000 0.000000 +25.850000 1.050000 0.000000 +25.786312 1.855843 0.000000 +25.786312 1.044157 0.000000 +25.721167 1.874574 0.000000 +25.200001 1.450000 0.000000 +25.194157 1.386313 0.000000 +25.721167 1.025426 0.000000 +25.175426 1.321167 0.000000 +25.658476 0.992948 0.000000 +25.142948 1.258477 0.000000 +25.602512 0.947487 0.000000 +25.097486 1.202513 0.000000 +25.557051 0.891523 0.000000 +25.041523 1.157052 0.000000 +25.524574 0.828833 0.000000 +24.978832 1.124574 0.000000 +24.505842 1.513687 0.000000 +23.200001 1.450000 0.000000 +23.194157 1.386313 0.000000 +23.721167 1.874574 0.000000 +23.786312 1.044157 0.000000 +23.786312 1.855843 0.000000 +23.850000 1.050000 0.000000 +23.850000 1.850000 0.000000 +23.913687 1.044157 0.000000 +23.913687 1.855843 0.000000 +23.978832 1.025426 0.000000 +24.500000 1.450000 0.000000 +24.041523 0.992948 0.000000 +24.505842 1.386313 0.000000 +24.097486 0.947487 0.000000 +24.524574 1.321167 0.000000 +24.142948 0.891523 0.000000 +24.557051 1.258477 0.000000 +24.175426 0.828833 0.000000 +24.602512 1.202513 0.000000 +24.194157 0.763687 0.000000 +24.658476 1.157052 0.000000 +23.505842 0.763687 0.000000 +22.200001 0.700000 0.000000 +21.505842 0.763687 0.000000 +25.505842 0.763687 0.000000 +24.200001 0.700000 0.000000 +20.505842 1.513687 0.000000 +19.200001 1.450000 0.000000 +19.194157 1.386313 0.000000 +19.721167 1.874574 0.000000 +19.786312 1.044157 0.000000 +19.786312 1.855843 0.000000 +19.850000 1.050000 0.000000 +19.850000 1.850000 0.000000 +19.913687 1.044157 0.000000 +19.913687 1.855843 0.000000 +19.978832 1.025426 0.000000 +20.500000 1.450000 0.000000 +20.041523 0.992948 0.000000 +20.505842 1.386313 0.000000 +20.097486 0.947487 0.000000 +20.524574 1.321167 0.000000 +20.142948 0.891523 0.000000 +20.557051 1.258477 0.000000 +20.175426 0.828833 0.000000 +20.602512 1.202513 0.000000 +20.194157 0.763687 0.000000 +20.658476 1.157052 0.000000 +19.505842 0.763687 0.000000 +18.200001 0.700000 0.000000 +18.500000 1.450000 0.000000 +18.505842 1.513687 0.000000 +17.978832 1.025426 0.000000 +17.913687 1.855843 0.000000 +17.913687 1.044157 0.000000 +17.850000 1.850000 0.000000 +17.850000 1.050000 0.000000 +17.786312 1.855843 0.000000 +17.786312 1.044157 0.000000 +17.721167 1.874574 0.000000 +17.200001 1.450000 0.000000 +17.194157 1.386313 0.000000 +17.721167 1.025426 0.000000 +17.175426 1.321167 0.000000 +17.658476 0.992948 0.000000 +17.142948 1.258477 0.000000 +17.602512 0.947487 0.000000 +17.097486 1.202513 0.000000 +17.557051 0.891523 0.000000 +17.041523 1.157052 0.000000 +17.524574 0.828833 0.000000 +16.978832 1.124574 0.000000 +20.200001 0.700000 0.000000 +17.505842 0.763687 0.000000 +16.200001 0.700000 0.000000 +15.505843 0.763687 0.000000 +14.200000 0.700000 0.000000 +13.505843 0.763687 0.000000 +12.200000 0.700000 0.000000 +11.505843 0.763687 0.000000 +10.200000 0.700000 0.000000 +9.505843 0.763687 0.000000 +8.200000 0.700000 0.000000 +7.505843 0.763687 0.000000 +6.200000 0.700000 0.000000 +5.505843 0.763687 0.000000 +4.200000 0.700000 0.000000 +3.505843 0.763687 0.000000 +2.200000 0.700000 0.000000 +1.658477 1.907052 0.000000 +1.602513 1.952513 0.000000 +1.557052 2.008476 0.000000 +1.524574 2.071167 0.000000 +1.505843 2.136313 0.000000 +1.500000 2.200000 0.000000 +1.505843 2.263687 0.000000 +1.524574 2.328833 0.000000 +1.557052 2.391523 0.000000 +1.602513 2.447487 0.000000 +2.786313 1.794157 0.000000 +2.978833 1.775426 0.000000 +4.786313 1.794157 0.000000 +4.978833 1.775426 0.000000 +6.786313 1.794157 0.000000 +6.978833 1.775426 0.000000 +8.786313 1.794157 0.000000 +8.978833 1.775426 0.000000 +10.786313 1.794157 0.000000 +10.978833 1.775426 0.000000 +12.786313 1.794157 0.000000 +12.978833 1.775426 0.000000 +14.786313 1.794157 0.000000 +14.978833 1.775426 0.000000 +16.786312 1.794157 0.000000 +16.978832 1.775426 0.000000 +18.786312 1.794157 0.000000 +18.978832 1.775426 0.000000 +20.786312 1.794157 0.000000 +20.978832 1.775426 0.000000 +22.786312 1.794157 0.000000 +22.978832 1.775426 0.000000 +24.786312 1.794157 0.000000 +24.978832 1.775426 0.000000 +26.786312 1.794157 0.000000 +26.978832 1.775426 0.000000 +28.786312 1.794157 0.000000 +28.978832 1.775426 0.000000 +30.786312 1.794157 0.000000 +30.978832 1.775426 0.000000 +32.786312 1.794157 0.000000 +32.978832 1.775426 0.000000 +34.786312 1.794157 0.000000 +34.978832 1.775426 0.000000 +36.786312 1.794157 0.000000 +36.978832 1.775426 0.000000 +36.913689 1.105843 0.000000 +36.721169 1.124574 0.000000 +34.913689 1.105843 0.000000 +34.721169 1.124574 0.000000 +32.913689 1.105843 0.000000 +32.721169 1.124574 0.000000 +30.913687 1.105843 0.000000 +30.721167 1.124574 0.000000 +28.913687 1.105843 0.000000 +28.721167 1.124574 0.000000 +26.913687 1.105843 0.000000 +26.721167 1.124574 0.000000 +24.913687 1.105843 0.000000 +24.721167 1.124574 0.000000 +22.913687 1.105843 0.000000 +22.721167 1.124574 0.000000 +20.913687 1.105843 0.000000 +20.721167 1.124574 0.000000 +18.913687 1.105843 0.000000 +18.721167 1.124574 0.000000 +16.913687 1.105843 0.000000 +16.721167 1.124574 0.000000 +14.913687 1.105843 0.000000 +14.721167 1.124574 0.000000 +12.913687 1.105843 0.000000 +12.721167 1.124574 0.000000 +10.913687 1.105843 0.000000 +10.721167 1.124574 0.000000 +8.913687 1.105843 0.000000 +8.721167 1.124574 0.000000 +6.913687 1.105843 0.000000 +6.721167 1.124574 0.000000 +4.913687 1.105843 0.000000 +4.721167 1.124574 0.000000 +2.913687 1.105843 0.000000 +2.721167 1.124574 0.000000 +1.602513 0.452513 0.000000 +1.658477 2.492949 0.000000 +2.200000 2.200000 0.000000 +3.505843 2.263687 0.000000 +4.200000 2.200000 0.000000 +5.505843 2.263687 0.000000 +6.200000 2.200000 0.000000 +7.505843 2.263687 0.000000 +8.200000 2.200000 0.000000 +9.505843 2.263687 0.000000 +10.200000 2.200000 0.000000 +11.505843 2.263687 0.000000 +12.200000 2.200000 0.000000 +13.505843 2.263687 0.000000 +14.200000 2.200000 0.000000 +15.505843 2.263687 0.000000 +16.200001 2.200000 0.000000 +17.505842 2.263687 0.000000 +18.200001 2.200000 0.000000 +19.505842 2.263687 0.000000 +20.200001 2.200000 0.000000 +21.505842 2.263687 0.000000 +22.200001 2.200000 0.000000 +23.505842 2.263687 0.000000 +24.200001 2.200000 0.000000 +25.505842 2.263687 0.000000 +26.200001 2.200000 0.000000 +27.505842 2.263687 0.000000 +28.200001 2.200000 0.000000 +29.505842 2.263687 0.000000 +30.200001 2.200000 0.000000 +31.505842 2.263687 0.000000 +32.200001 2.200000 0.000000 +33.505844 2.263687 0.000000 +34.200001 2.200000 0.000000 +35.505844 2.263687 0.000000 +36.200001 2.200000 0.000000 +37.505844 2.263687 0.000000 +38.041523 1.907052 0.000000 +38.097488 0.947487 0.000000 +37.500000 0.700000 0.000000 +36.194157 0.636313 0.000000 +35.500000 0.700000 0.000000 +34.194157 0.636313 0.000000 +33.500000 0.700000 0.000000 +32.194157 0.636313 0.000000 +31.500000 0.700000 0.000000 +30.194157 0.636313 0.000000 +29.500000 0.700000 0.000000 +28.194157 0.636313 0.000000 +27.500000 0.700000 0.000000 +26.194157 0.636313 0.000000 +25.500000 0.700000 0.000000 +24.194157 0.636313 0.000000 +23.500000 0.700000 0.000000 +22.194157 0.636313 0.000000 +21.500000 0.700000 0.000000 +20.194157 0.636313 0.000000 +19.500000 0.700000 0.000000 +18.194157 0.636313 0.000000 +17.500000 0.700000 0.000000 +16.194157 0.636313 0.000000 +15.500000 0.700000 0.000000 +14.194157 0.636313 0.000000 +13.500000 0.700000 0.000000 +12.194157 0.636313 0.000000 +11.500000 0.700000 0.000000 +10.194157 0.636313 0.000000 +9.500000 0.700000 0.000000 +8.194157 0.636313 0.000000 +7.500000 0.700000 0.000000 +6.194157 0.636313 0.000000 +5.500000 0.700000 0.000000 +4.194157 0.636313 0.000000 +3.500000 0.700000 0.000000 +2.194157 0.636313 0.000000 +2.850000 1.800000 0.000000 +2.913687 1.794157 0.000000 +2.194157 2.263687 0.000000 +3.524574 2.328833 0.000000 +2.175426 2.328833 0.000000 +3.557052 2.391523 0.000000 +2.142948 2.391523 0.000000 +3.602513 2.447487 0.000000 +4.850000 1.800000 0.000000 +4.913687 1.794157 0.000000 +4.194157 2.263687 0.000000 +5.524574 2.328833 0.000000 +4.175426 2.328833 0.000000 +5.557052 2.391523 0.000000 +4.142949 2.391523 0.000000 +5.602513 2.447487 0.000000 +6.850000 1.800000 0.000000 +6.913687 1.794157 0.000000 +6.194157 2.263687 0.000000 +7.524574 2.328833 0.000000 +6.175426 2.328833 0.000000 +7.557052 2.391523 0.000000 +6.142949 2.391523 0.000000 +7.602513 2.447487 0.000000 +8.850000 1.800000 0.000000 +8.913687 1.794157 0.000000 +8.194157 2.263687 0.000000 +9.524574 2.328833 0.000000 +8.175426 2.328833 0.000000 +9.557052 2.391523 0.000000 +8.142948 2.391523 0.000000 +9.602512 2.447487 0.000000 +10.850000 1.800000 0.000000 +10.913687 1.794157 0.000000 +10.194157 2.263687 0.000000 +11.524574 2.328833 0.000000 +10.175426 2.328833 0.000000 +11.557052 2.391523 0.000000 +10.142948 2.391523 0.000000 +11.602512 2.447487 0.000000 +12.850000 1.800000 0.000000 +12.913687 1.794157 0.000000 +12.194157 2.263687 0.000000 +13.524574 2.328833 0.000000 +12.175426 2.328833 0.000000 +13.557052 2.391523 0.000000 +12.142948 2.391523 0.000000 +13.602512 2.447487 0.000000 +14.850000 1.800000 0.000000 +14.913687 1.794157 0.000000 +14.194157 2.263687 0.000000 +15.524574 2.328833 0.000000 +14.175426 2.328833 0.000000 +15.557052 2.391523 0.000000 +14.142948 2.391523 0.000000 +15.602512 2.447487 0.000000 +16.850000 1.800000 0.000000 +16.913687 1.794157 0.000000 +16.194157 2.263687 0.000000 +17.524574 2.328833 0.000000 +16.175426 2.328833 0.000000 +17.557051 2.391523 0.000000 +16.142948 2.391523 0.000000 +17.602512 2.447487 0.000000 +18.850000 1.800000 0.000000 +18.913687 1.794157 0.000000 +18.194157 2.263687 0.000000 +19.524574 2.328833 0.000000 +18.175426 2.328833 0.000000 +19.557051 2.391523 0.000000 +18.142948 2.391523 0.000000 +19.602512 2.447487 0.000000 +20.850000 1.800000 0.000000 +20.913687 1.794157 0.000000 +20.194157 2.263687 0.000000 +21.524574 2.328833 0.000000 +20.175426 2.328833 0.000000 +21.557051 2.391523 0.000000 +20.142948 2.391523 0.000000 +21.602512 2.447487 0.000000 +22.850000 1.800000 0.000000 +22.913687 1.794157 0.000000 +22.194157 2.263687 0.000000 +23.524574 2.328833 0.000000 +22.175426 2.328833 0.000000 +23.557051 2.391523 0.000000 +22.142948 2.391523 0.000000 +23.602512 2.447487 0.000000 +24.850000 1.800000 0.000000 +24.913687 1.794157 0.000000 +24.194157 2.263687 0.000000 +25.524574 2.328833 0.000000 +24.175426 2.328833 0.000000 +25.557051 2.391523 0.000000 +24.142948 2.391523 0.000000 +25.602512 2.447487 0.000000 +26.850000 1.800000 0.000000 +26.913687 1.794157 0.000000 +26.194157 2.263687 0.000000 +27.524574 2.328833 0.000000 +26.175426 2.328833 0.000000 +27.557051 2.391523 0.000000 +26.142948 2.391523 0.000000 +27.602512 2.447487 0.000000 +28.850000 1.800000 0.000000 +28.913687 1.794157 0.000000 +28.194157 2.263687 0.000000 +29.524574 2.328833 0.000000 +28.175426 2.328833 0.000000 +29.557051 2.391523 0.000000 +28.142948 2.391523 0.000000 +29.602512 2.447487 0.000000 +30.850000 1.800000 0.000000 +30.913687 1.794157 0.000000 +30.194157 2.263687 0.000000 +31.524574 2.328833 0.000000 +30.175426 2.328833 0.000000 +31.557051 2.391523 0.000000 +30.142948 2.391523 0.000000 +31.602512 2.447487 0.000000 +32.849998 1.800000 0.000000 +32.913689 1.794157 0.000000 +32.194157 2.263687 0.000000 +33.524574 2.328833 0.000000 +32.175426 2.328833 0.000000 +33.557053 2.391523 0.000000 +32.142948 2.391523 0.000000 +33.602512 2.447487 0.000000 +34.849998 1.800000 0.000000 +34.913689 1.794157 0.000000 +34.194157 2.263687 0.000000 +35.524574 2.328833 0.000000 +34.175426 2.328833 0.000000 +35.557053 2.391523 0.000000 +34.142948 2.391523 0.000000 +35.602512 2.447487 0.000000 +36.849998 1.800000 0.000000 +36.913689 1.794157 0.000000 +36.194157 2.263687 0.000000 +37.524574 2.328833 0.000000 +36.175426 2.328833 0.000000 +37.557053 2.391523 0.000000 +36.142948 2.391523 0.000000 +37.602512 2.447487 0.000000 +36.849998 1.100000 0.000000 +36.786312 1.105843 0.000000 +37.505844 0.636313 0.000000 +36.175426 0.571167 0.000000 +37.524574 0.571167 0.000000 +36.142948 0.508477 0.000000 +37.557053 0.508477 0.000000 +36.097488 0.452513 0.000000 +34.849998 1.100000 0.000000 +34.786312 1.105843 0.000000 +35.505844 0.636313 0.000000 +34.175426 0.571167 0.000000 +35.524574 0.571167 0.000000 +34.142948 0.508477 0.000000 +35.557053 0.508477 0.000000 +34.097488 0.452513 0.000000 +32.849998 1.100000 0.000000 +32.786312 1.105843 0.000000 +33.505844 0.636313 0.000000 +32.175426 0.571167 0.000000 +33.524574 0.571167 0.000000 +32.142948 0.508477 0.000000 +33.557053 0.508477 0.000000 +32.097488 0.452513 0.000000 +30.850000 1.100000 0.000000 +30.786312 1.105843 0.000000 +31.505842 0.636313 0.000000 +30.175426 0.571167 0.000000 +31.524574 0.571167 0.000000 +30.142948 0.508477 0.000000 +31.557051 0.508477 0.000000 +30.097486 0.452513 0.000000 +28.850000 1.100000 0.000000 +28.786312 1.105843 0.000000 +29.505842 0.636313 0.000000 +28.175426 0.571167 0.000000 +29.524574 0.571167 0.000000 +28.142948 0.508477 0.000000 +29.557051 0.508477 0.000000 +28.097486 0.452513 0.000000 +26.850000 1.100000 0.000000 +26.786312 1.105843 0.000000 +27.505842 0.636313 0.000000 +26.175426 0.571167 0.000000 +27.524574 0.571167 0.000000 +26.142948 0.508477 0.000000 +27.557051 0.508477 0.000000 +26.097486 0.452513 0.000000 +24.850000 1.100000 0.000000 +24.786312 1.105843 0.000000 +25.505842 0.636313 0.000000 +24.175426 0.571167 0.000000 +25.524574 0.571167 0.000000 +24.142948 0.508477 0.000000 +25.557051 0.508477 0.000000 +24.097486 0.452513 0.000000 +22.850000 1.100000 0.000000 +22.786312 1.105843 0.000000 +23.505842 0.636313 0.000000 +22.175426 0.571167 0.000000 +23.524574 0.571167 0.000000 +22.142948 0.508477 0.000000 +23.557051 0.508477 0.000000 +22.097486 0.452513 0.000000 +20.850000 1.100000 0.000000 +20.786312 1.105843 0.000000 +21.505842 0.636313 0.000000 +20.175426 0.571167 0.000000 +21.524574 0.571167 0.000000 +20.142948 0.508477 0.000000 +21.557051 0.508477 0.000000 +20.097486 0.452513 0.000000 +18.850000 1.100000 0.000000 +18.786312 1.105843 0.000000 +19.505842 0.636313 0.000000 +18.175426 0.571167 0.000000 +19.524574 0.571167 0.000000 +18.142948 0.508477 0.000000 +19.557051 0.508477 0.000000 +18.097486 0.452513 0.000000 +16.850000 1.100000 0.000000 +16.786312 1.105843 0.000000 +17.505842 0.636313 0.000000 +16.175426 0.571167 0.000000 +17.524574 0.571167 0.000000 +16.142948 0.508477 0.000000 +17.557051 0.508477 0.000000 +16.097486 0.452513 0.000000 +14.850000 1.100000 0.000000 +14.786313 1.105843 0.000000 +15.505843 0.636313 0.000000 +14.175426 0.571167 0.000000 +15.524574 0.571167 0.000000 +14.142948 0.508477 0.000000 +15.557052 0.508477 0.000000 +14.097487 0.452513 0.000000 +12.850000 1.100000 0.000000 +12.786313 1.105843 0.000000 +13.505843 0.636313 0.000000 +12.175426 0.571167 0.000000 +13.524574 0.571167 0.000000 +12.142948 0.508477 0.000000 +13.557052 0.508477 0.000000 +12.097487 0.452513 0.000000 +10.850000 1.100000 0.000000 +10.786313 1.105843 0.000000 +11.505843 0.636313 0.000000 +10.175426 0.571167 0.000000 +11.524574 0.571167 0.000000 +10.142948 0.508477 0.000000 +11.557052 0.508477 0.000000 +10.097487 0.452513 0.000000 +8.850000 1.100000 0.000000 +8.786313 1.105843 0.000000 +9.505843 0.636313 0.000000 +8.175426 0.571167 0.000000 +9.524574 0.571167 0.000000 +8.142948 0.508477 0.000000 +9.557052 0.508477 0.000000 +8.097487 0.452513 0.000000 +6.850000 1.100000 0.000000 +6.786313 1.105843 0.000000 +7.505843 0.636313 0.000000 +6.175426 0.571167 0.000000 +7.524574 0.571167 0.000000 +6.142949 0.508477 0.000000 +7.557052 0.508477 0.000000 +6.097487 0.452513 0.000000 +4.850000 1.100000 0.000000 +4.786313 1.105843 0.000000 +5.505843 0.636313 0.000000 +4.175426 0.571167 0.000000 +5.524574 0.571167 0.000000 +4.142949 0.508477 0.000000 +5.557052 0.508477 0.000000 +4.097487 0.452513 0.000000 +2.850000 1.100000 0.000000 +2.786313 1.105843 0.000000 +3.505843 0.636313 0.000000 +2.175426 0.571167 0.000000 +3.524574 0.571167 0.000000 +2.142948 0.508477 0.000000 +3.557052 0.508477 0.000000 +2.097487 0.452513 0.000000 +1.658477 0.407052 0.000000 +1.721167 2.525426 0.000000 +2.097487 2.447487 0.000000 +3.658477 2.492949 0.000000 +4.097487 2.447487 0.000000 +5.658476 2.492949 0.000000 +6.097487 2.447487 0.000000 +7.658476 2.492949 0.000000 +8.097487 2.447487 0.000000 +9.658477 2.492949 0.000000 +10.097487 2.447487 0.000000 +11.658477 2.492949 0.000000 +12.097487 2.447487 0.000000 +13.658477 2.492949 0.000000 +14.097487 2.447487 0.000000 +15.658477 2.492949 0.000000 +16.097486 2.447487 0.000000 +17.658476 2.492949 0.000000 +18.097486 2.447487 0.000000 +19.658476 2.492949 0.000000 +20.097486 2.447487 0.000000 +21.658476 2.492949 0.000000 +22.097486 2.447487 0.000000 +23.658476 2.492949 0.000000 +24.097486 2.447487 0.000000 +25.658476 2.492949 0.000000 +26.097486 2.447487 0.000000 +27.658476 2.492949 0.000000 +28.097486 2.447487 0.000000 +29.658476 2.492949 0.000000 +30.097486 2.447487 0.000000 +31.658476 2.492949 0.000000 +32.097488 2.447487 0.000000 +33.658478 2.492949 0.000000 +34.097488 2.447487 0.000000 +35.658478 2.492949 0.000000 +36.097488 2.447487 0.000000 +37.658478 2.492949 0.000000 +38.097488 1.952513 0.000000 +38.142948 0.891523 0.000000 +37.602512 0.452513 0.000000 +36.041523 0.407052 0.000000 +35.602512 0.452513 0.000000 +34.041523 0.407052 0.000000 +33.602512 0.452513 0.000000 +32.041523 0.407052 0.000000 +31.602512 0.452513 0.000000 +30.041523 0.407052 0.000000 +29.602512 0.452513 0.000000 +28.041523 0.407052 0.000000 +27.602512 0.452513 0.000000 +26.041523 0.407052 0.000000 +25.602512 0.452513 0.000000 +24.041523 0.407052 0.000000 +23.602512 0.452513 0.000000 +22.041523 0.407052 0.000000 +21.602512 0.452513 0.000000 +20.041523 0.407052 0.000000 +19.602512 0.452513 0.000000 +18.041523 0.407052 0.000000 +17.602512 0.452513 0.000000 +16.041523 0.407052 0.000000 +15.602512 0.452513 0.000000 +14.041523 0.407052 0.000000 +13.602512 0.452513 0.000000 +12.041523 0.407052 0.000000 +11.602512 0.452513 0.000000 +10.041523 0.407052 0.000000 +9.602512 0.452513 0.000000 +8.041523 0.407052 0.000000 +7.602513 0.452513 0.000000 +6.041523 0.407052 0.000000 +5.602513 0.452513 0.000000 +4.041523 0.407052 0.000000 +3.602513 0.452513 0.000000 +2.041523 0.407052 0.000000 +1.721167 0.374574 0.000000 +1.786313 2.544157 0.000000 +2.041523 2.492949 0.000000 +3.721167 2.525426 0.000000 +4.041523 2.492949 0.000000 +5.721167 2.525426 0.000000 +6.041523 2.492949 0.000000 +7.721167 2.525426 0.000000 +8.041523 2.492949 0.000000 +9.721167 2.525426 0.000000 +10.041523 2.492949 0.000000 +11.721167 2.525426 0.000000 +12.041523 2.492949 0.000000 +13.721167 2.525426 0.000000 +14.041523 2.492949 0.000000 +15.721167 2.525426 0.000000 +16.041523 2.492949 0.000000 +17.721167 2.525426 0.000000 +18.041523 2.492949 0.000000 +19.721167 2.525426 0.000000 +20.041523 2.492949 0.000000 +21.721167 2.525426 0.000000 +22.041523 2.492949 0.000000 +23.721167 2.525426 0.000000 +24.041523 2.492949 0.000000 +25.721167 2.525426 0.000000 +26.041523 2.492949 0.000000 +27.721167 2.525426 0.000000 +28.041523 2.492949 0.000000 +29.721167 2.525426 0.000000 +30.041523 2.492949 0.000000 +31.721167 2.525426 0.000000 +32.041523 2.492949 0.000000 +33.721169 2.525426 0.000000 +34.041523 2.492949 0.000000 +35.721169 2.525426 0.000000 +36.041523 2.492949 0.000000 +37.721169 2.525426 0.000000 +38.142948 2.008476 0.000000 +38.175426 0.828833 0.000000 +37.658478 0.407052 0.000000 +35.978832 0.374574 0.000000 +35.658478 0.407052 0.000000 +33.978832 0.374574 0.000000 +33.658478 0.407052 0.000000 +31.978832 0.374574 0.000000 +31.658476 0.407052 0.000000 +29.978832 0.374574 0.000000 +29.658476 0.407052 0.000000 +27.978832 0.374574 0.000000 +27.658476 0.407052 0.000000 +25.978832 0.374574 0.000000 +25.658476 0.407052 0.000000 +23.978832 0.374574 0.000000 +23.658476 0.407052 0.000000 +21.978832 0.374574 0.000000 +21.658476 0.407052 0.000000 +19.978832 0.374574 0.000000 +19.658476 0.407052 0.000000 +17.978832 0.374574 0.000000 +17.658476 0.407052 0.000000 +15.978833 0.374574 0.000000 +15.658477 0.407052 0.000000 +13.978833 0.374574 0.000000 +13.658477 0.407052 0.000000 +11.978833 0.374574 0.000000 +11.658477 0.407052 0.000000 +9.978833 0.374574 0.000000 +9.658477 0.407052 0.000000 +7.978833 0.374574 0.000000 +7.658476 0.407052 0.000000 +5.978833 0.374574 0.000000 +5.658476 0.407052 0.000000 +3.978833 0.374574 0.000000 +3.658477 0.407052 0.000000 +1.978833 0.374574 0.000000 +1.978833 2.525426 0.000000 +3.978833 2.525426 0.000000 +5.978833 2.525426 0.000000 +7.978833 2.525426 0.000000 +9.978833 2.525426 0.000000 +3.786313 2.544157 0.000000 +5.786313 2.544157 0.000000 +7.786313 2.544157 0.000000 +9.786313 2.544157 0.000000 +11.786313 2.544157 0.000000 +11.978833 2.525426 0.000000 +13.978833 2.525426 0.000000 +15.978833 2.525426 0.000000 +13.786313 2.544157 0.000000 +15.786313 2.544157 0.000000 +17.786312 2.544157 0.000000 +17.978832 2.525426 0.000000 +19.978832 2.525426 0.000000 +21.978832 2.525426 0.000000 +23.978832 2.525426 0.000000 +19.786312 2.544157 0.000000 +21.786312 2.544157 0.000000 +23.786312 2.544157 0.000000 +25.786312 2.544157 0.000000 +25.978832 2.525426 0.000000 +27.978832 2.525426 0.000000 +29.978832 2.525426 0.000000 +27.786312 2.544157 0.000000 +29.786312 2.544157 0.000000 +31.786312 2.544157 0.000000 +31.978832 2.525426 0.000000 +33.978832 2.525426 0.000000 +35.978832 2.525426 0.000000 +38.175426 2.071167 0.000000 +33.786312 2.544157 0.000000 +35.786312 2.544157 0.000000 +37.786312 2.544157 0.000000 +38.194157 0.763687 0.000000 +37.721169 0.374574 0.000000 +35.721169 0.374574 0.000000 +33.721169 0.374574 0.000000 +35.913689 0.355843 0.000000 +33.913689 0.355843 0.000000 +31.913687 0.355843 0.000000 +31.721167 0.374574 0.000000 +29.721167 0.374574 0.000000 +27.721167 0.374574 0.000000 +25.721167 0.374574 0.000000 +29.913687 0.355843 0.000000 +27.913687 0.355843 0.000000 +25.913687 0.355843 0.000000 +23.913687 0.355843 0.000000 +23.721167 0.374574 0.000000 +21.721167 0.374574 0.000000 +19.721167 0.374574 0.000000 +21.913687 0.355843 0.000000 +19.913687 0.355843 0.000000 +17.913687 0.355843 0.000000 +17.721167 0.374574 0.000000 +15.721167 0.374574 0.000000 +13.721167 0.374574 0.000000 +11.721167 0.374574 0.000000 +15.913687 0.355843 0.000000 +13.913687 0.355843 0.000000 +11.913687 0.355843 0.000000 +9.913687 0.355843 0.000000 +9.721167 0.374574 0.000000 +7.721167 0.374574 0.000000 +5.721167 0.374574 0.000000 +7.913687 0.355843 0.000000 +5.913687 0.355843 0.000000 +3.913687 0.355843 0.000000 +3.721167 0.374574 0.000000 +1.913687 0.355843 0.000000 +1.786313 0.355843 0.000000 +39.700001 0.000000 0.000000 +1.850000 0.350000 0.000000 +1.850000 2.550000 0.000000 +0.000000 2.900000 0.000000 +1.913687 2.544157 0.000000 +3.850000 2.550000 0.000000 +3.913687 2.544157 0.000000 +5.850000 2.550000 0.000000 +5.913687 2.544157 0.000000 +7.850000 2.550000 0.000000 +7.913687 2.544157 0.000000 +9.850000 2.550000 0.000000 +9.913687 2.544157 0.000000 +11.850000 2.550000 0.000000 +11.913687 2.544157 0.000000 +13.850000 2.550000 0.000000 +13.913687 2.544157 0.000000 +15.850000 2.550000 0.000000 +15.913687 2.544157 0.000000 +17.850000 2.550000 0.000000 +17.913687 2.544157 0.000000 +19.850000 2.550000 0.000000 +19.913687 2.544157 0.000000 +21.850000 2.550000 0.000000 +21.913687 2.544157 0.000000 +23.850000 2.550000 0.000000 +23.913687 2.544157 0.000000 +25.850000 2.550000 0.000000 +25.913687 2.544157 0.000000 +27.850000 2.550000 0.000000 +27.913687 2.544157 0.000000 +29.850000 2.550000 0.000000 +29.913687 2.544157 0.000000 +31.850000 2.550000 0.000000 +31.913687 2.544157 0.000000 +33.849998 2.550000 0.000000 +33.913689 2.544157 0.000000 +35.849998 2.550000 0.000000 +35.913689 2.544157 0.000000 +37.849998 2.550000 0.000000 +37.913689 2.544157 0.000000 +37.978832 2.525426 0.000000 +38.041523 2.492949 0.000000 +38.097488 2.447487 0.000000 +38.142948 2.391523 0.000000 +39.700001 2.900000 0.000000 +38.175426 2.328833 0.000000 +38.194157 2.263687 0.000000 +38.200001 2.200000 0.000000 +38.194157 2.136313 0.000000 +38.200001 0.700000 0.000000 +38.194157 0.636313 0.000000 +38.175426 0.571167 0.000000 +38.142948 0.508477 0.000000 +38.097488 0.452513 0.000000 +38.041523 0.407052 0.000000 +37.978832 0.374574 0.000000 +37.913689 0.355843 0.000000 +37.849998 0.350000 0.000000 +37.786312 0.355843 0.000000 +35.849998 0.350000 0.000000 +35.786312 0.355843 0.000000 +33.849998 0.350000 0.000000 +33.786312 0.355843 0.000000 +31.786312 0.355843 0.000000 +29.786312 0.355843 0.000000 +27.786312 0.355843 0.000000 +25.786312 0.355843 0.000000 +31.850000 0.350000 0.000000 +29.850000 0.350000 0.000000 +27.850000 0.350000 0.000000 +25.850000 0.350000 0.000000 +23.850000 0.350000 0.000000 +23.786312 0.355843 0.000000 +21.786312 0.355843 0.000000 +19.786312 0.355843 0.000000 +21.850000 0.350000 0.000000 +19.850000 0.350000 0.000000 +17.850000 0.350000 0.000000 +17.786312 0.355843 0.000000 +15.786313 0.355843 0.000000 +13.786313 0.355843 0.000000 +11.786313 0.355843 0.000000 +15.850000 0.350000 0.000000 +13.850000 0.350000 0.000000 +11.850000 0.350000 0.000000 +9.850000 0.350000 0.000000 +9.786313 0.355843 0.000000 +7.786313 0.355843 0.000000 +5.786313 0.355843 0.000000 +7.850000 0.350000 0.000000 +5.850000 0.350000 0.000000 +3.850000 0.350000 0.000000 +3.786313 0.355843 0.000000 +19.505842 2.263687 0.000000 +19.500000 2.200000 0.120000 +19.500000 2.200000 0.000000 +19.505842 2.263687 0.120000 +20.200001 2.200000 0.000000 +20.200001 2.200000 0.120000 +20.194157 2.263687 0.000000 +20.175426 2.328833 0.000000 +20.194157 2.263687 0.120000 +20.142948 2.391523 0.000000 +20.175426 2.328833 0.120000 +20.097486 2.447487 0.000000 +20.142948 2.391523 0.120000 +20.041523 2.492949 0.000000 +20.097486 2.447487 0.120000 +20.041523 2.492949 0.120000 +19.978832 2.525426 0.000000 +19.913687 2.544157 0.000000 +19.978832 2.525426 0.120000 +19.850000 2.550000 0.000000 +19.913687 2.544157 0.120000 +19.850000 2.550000 0.120000 +19.786312 2.544157 0.000000 +19.786312 2.544157 0.120000 +19.721167 2.525426 0.000000 +19.721167 2.525426 0.120000 +19.658476 2.492949 0.000000 +19.658476 2.492949 0.120000 +19.602512 2.447487 0.000000 +19.602512 2.447487 0.120000 +19.557051 2.391523 0.000000 +19.524574 2.328833 0.000000 +19.557051 2.391523 0.120000 +19.524574 2.328833 0.120000 +19.505842 0.763687 0.000000 +19.505842 0.763687 0.120000 +19.500000 0.700000 0.120000 +19.500000 0.700000 0.000000 +20.200001 0.700000 0.000000 +20.200001 0.700000 0.120000 +20.194157 0.763687 0.000000 +20.175426 0.828833 0.000000 +20.194157 0.763687 0.120000 +20.142948 0.891523 0.000000 +20.175426 0.828833 0.120000 +20.097486 0.947487 0.000000 +20.142948 0.891523 0.120000 +20.041523 0.992948 0.000000 +20.097486 0.947487 0.120000 +19.978832 1.025426 0.000000 +20.041523 0.992948 0.120000 +19.978832 1.025426 0.120000 +19.913687 1.044157 0.000000 +19.913687 1.044157 0.120000 +19.850000 1.050000 0.000000 +19.850000 1.050000 0.120000 +19.786312 1.044157 0.000000 +19.786312 1.044157 0.120000 +19.721167 1.025426 0.000000 +19.721167 1.025426 0.120000 +19.658476 0.992948 0.000000 +19.658476 0.992948 0.120000 +19.602512 0.947487 0.000000 +19.602512 0.947487 0.120000 +19.557051 0.891523 0.000000 +19.524574 0.828833 0.000000 +19.557051 0.891523 0.120000 +19.524574 0.828833 0.120000 +17.505842 2.263687 0.000000 +17.505842 2.263687 0.120000 +17.500000 2.200000 0.120000 +17.500000 2.200000 0.000000 +18.200001 2.200000 0.000000 +18.200001 2.200000 0.120000 +18.194157 2.263687 0.000000 +18.194157 2.263687 0.120000 +18.175426 2.328833 0.000000 +18.142948 2.391523 0.000000 +18.175426 2.328833 0.120000 +18.142948 2.391523 0.120000 +18.097486 2.447487 0.000000 +18.097486 2.447487 0.120000 +18.041523 2.492949 0.000000 +17.978832 2.525426 0.000000 +18.041523 2.492949 0.120000 +17.978832 2.525426 0.120000 +17.913687 2.544157 0.000000 +17.913687 2.544157 0.120000 +17.850000 2.550000 0.000000 +17.850000 2.550000 0.120000 +17.786312 2.544157 0.000000 +17.786312 2.544157 0.120000 +17.721167 2.525426 0.000000 +17.721167 2.525426 0.120000 +17.658476 2.492949 0.000000 +17.658476 2.492949 0.120000 +17.602512 2.447487 0.000000 +17.602512 2.447487 0.120000 +17.557051 2.391523 0.000000 +17.557051 2.391523 0.120000 +17.524574 2.328833 0.000000 +17.524574 2.328833 0.120000 +17.505842 0.763687 0.000000 +17.505842 0.763687 0.120000 +17.500000 0.700000 0.120000 +17.500000 0.700000 0.000000 +18.200001 0.700000 0.000000 +18.200001 0.700000 0.120000 +18.194157 0.763687 0.000000 +18.175426 0.828833 0.000000 +18.194157 0.763687 0.120000 +18.175426 0.828833 0.120000 +18.142948 0.891523 0.000000 +18.097486 0.947487 0.000000 +18.142948 0.891523 0.120000 +18.097486 0.947487 0.120000 +18.041523 0.992948 0.000000 +18.041523 0.992948 0.120000 +17.978832 1.025426 0.000000 +17.913687 1.044157 0.000000 +17.978832 1.025426 0.120000 +17.850000 1.050000 0.000000 +17.913687 1.044157 0.120000 +17.786312 1.044157 0.000000 +17.850000 1.050000 0.120000 +17.786312 1.044157 0.120000 +17.721167 1.025426 0.000000 +17.721167 1.025426 0.120000 +17.658476 0.992948 0.000000 +17.602512 0.947487 0.000000 +17.658476 0.992948 0.120000 +17.602512 0.947487 0.120000 +17.557051 0.891523 0.000000 +17.557051 0.891523 0.120000 +17.524574 0.828833 0.000000 +17.524574 0.828833 0.120000 +15.602512 2.447487 0.000000 +15.505843 2.263687 0.120000 +15.500000 2.200000 0.120000 +15.500000 2.200000 0.000000 +15.524574 2.328833 0.120000 +15.505843 2.263687 0.000000 +15.524574 2.328833 0.000000 +15.557052 2.391523 0.120000 +15.557052 2.391523 0.000000 +15.602512 2.447487 0.120000 +16.200001 2.200000 0.000000 +16.200001 2.200000 0.120000 +16.194157 2.263687 0.000000 +16.175426 2.328833 0.000000 +16.194157 2.263687 0.120000 +16.175426 2.328833 0.120000 +16.142948 2.391523 0.000000 +16.142948 2.391523 0.120000 +16.097486 2.447487 0.000000 +16.041523 2.492949 0.000000 +16.097486 2.447487 0.120000 +16.041523 2.492949 0.120000 +15.978833 2.525426 0.000000 +15.913687 2.544157 0.000000 +15.978833 2.525426 0.120000 +15.913687 2.544157 0.120000 +15.850000 2.550000 0.000000 +15.850000 2.550000 0.120000 +15.786313 2.544157 0.000000 +15.786313 2.544157 0.120000 +15.721167 2.525426 0.000000 +15.721167 2.525426 0.120000 +15.658477 2.492949 0.000000 +15.658477 2.492949 0.120000 +16.175426 0.828833 0.120000 +16.194157 0.763687 0.000000 +16.200001 0.700000 0.000000 +16.200001 0.700000 0.120000 +16.175426 0.828833 0.000000 +16.194157 0.763687 0.120000 +15.500000 0.700000 0.120000 +15.500000 0.700000 0.000000 +15.505843 0.763687 0.120000 +15.524574 0.828833 0.120000 +15.505843 0.763687 0.000000 +15.557052 0.891523 0.120000 +15.524574 0.828833 0.000000 +15.557052 0.891523 0.000000 +15.602512 0.947487 0.120000 +15.602512 0.947487 0.000000 +15.658477 0.992948 0.120000 +15.658477 0.992948 0.000000 +15.721167 1.025426 0.120000 +15.721167 1.025426 0.000000 +15.786313 1.044157 0.120000 +15.786313 1.044157 0.000000 +15.850000 1.050000 0.120000 +15.850000 1.050000 0.000000 +15.913687 1.044157 0.120000 +15.913687 1.044157 0.000000 +15.978833 1.025426 0.120000 +15.978833 1.025426 0.000000 +16.041523 0.992948 0.120000 +16.041523 0.992948 0.000000 +16.097486 0.947487 0.120000 +16.097486 0.947487 0.000000 +16.142948 0.891523 0.120000 +16.142948 0.891523 0.000000 +14.175426 2.328833 0.120000 +14.194157 2.263687 0.000000 +14.200000 2.200000 0.000000 +14.200000 2.200000 0.120000 +14.175426 2.328833 0.000000 +14.194157 2.263687 0.120000 +13.505843 2.263687 0.120000 +13.500000 2.200000 0.120000 +13.500000 2.200000 0.000000 +13.524574 2.328833 0.120000 +13.505843 2.263687 0.000000 +13.524574 2.328833 0.000000 +13.557052 2.391523 0.120000 +13.557052 2.391523 0.000000 +13.602512 2.447487 0.120000 +13.602512 2.447487 0.000000 +13.658477 2.492949 0.120000 +13.658477 2.492949 0.000000 +13.721167 2.525426 0.120000 +13.786313 2.544157 0.120000 +13.721167 2.525426 0.000000 +13.786313 2.544157 0.000000 +13.850000 2.550000 0.120000 +13.850000 2.550000 0.000000 +13.913687 2.544157 0.120000 +13.913687 2.544157 0.000000 +13.978833 2.525426 0.120000 +13.978833 2.525426 0.000000 +14.041523 2.492949 0.120000 +14.041523 2.492949 0.000000 +14.097487 2.447487 0.120000 +14.097487 2.447487 0.000000 +14.142948 2.391523 0.120000 +14.142948 2.391523 0.000000 +13.500000 0.700000 0.120000 +13.500000 0.700000 0.000000 +14.194157 0.763687 0.000000 +14.200000 0.700000 0.000000 +14.200000 0.700000 0.120000 +14.194157 0.763687 0.120000 +14.175426 0.828833 0.000000 +14.175426 0.828833 0.120000 +14.142948 0.891523 0.000000 +14.097487 0.947487 0.000000 +14.142948 0.891523 0.120000 +14.041523 0.992948 0.000000 +14.097487 0.947487 0.120000 +13.978833 1.025426 0.000000 +14.041523 0.992948 0.120000 +13.913687 1.044157 0.000000 +13.978833 1.025426 0.120000 +13.850000 1.050000 0.000000 +13.913687 1.044157 0.120000 +13.786313 1.044157 0.000000 +13.850000 1.050000 0.120000 +13.786313 1.044157 0.120000 +13.721167 1.025426 0.000000 +13.658477 0.992948 0.000000 +13.721167 1.025426 0.120000 +13.602512 0.947487 0.000000 +13.658477 0.992948 0.120000 +13.557052 0.891523 0.000000 +13.602512 0.947487 0.120000 +13.557052 0.891523 0.120000 +13.524574 0.828833 0.000000 +13.524574 0.828833 0.120000 +13.505843 0.763687 0.000000 +13.505843 0.763687 0.120000 +11.786313 2.544157 0.000000 +12.194157 2.263687 0.000000 +12.200000 2.200000 0.000000 +12.200000 2.200000 0.120000 +12.194157 2.263687 0.120000 +12.175426 2.328833 0.000000 +12.142948 2.391523 0.000000 +12.175426 2.328833 0.120000 +12.142948 2.391523 0.120000 +12.097487 2.447487 0.000000 +12.041523 2.492949 0.000000 +12.097487 2.447487 0.120000 +11.978833 2.525426 0.000000 +12.041523 2.492949 0.120000 +11.913687 2.544157 0.000000 +11.978833 2.525426 0.120000 +11.850000 2.550000 0.000000 +11.913687 2.544157 0.120000 +11.505843 2.263687 0.120000 +11.500000 2.200000 0.120000 +11.500000 2.200000 0.000000 +11.524574 2.328833 0.120000 +11.505843 2.263687 0.000000 +11.557052 2.391523 0.120000 +11.524574 2.328833 0.000000 +11.557052 2.391523 0.000000 +11.602512 2.447487 0.120000 +11.602512 2.447487 0.000000 +11.658477 2.492949 0.120000 +11.721167 2.525426 0.120000 +11.658477 2.492949 0.000000 +11.721167 2.525426 0.000000 +11.786313 2.544157 0.120000 +11.850000 2.550000 0.120000 +11.500000 0.700000 0.120000 +11.500000 0.700000 0.000000 +12.200000 0.700000 0.000000 +12.200000 0.700000 0.120000 +12.194157 0.763687 0.000000 +12.194157 0.763687 0.120000 +12.175426 0.828833 0.000000 +12.175426 0.828833 0.120000 +12.142948 0.891523 0.000000 +12.097487 0.947487 0.000000 +12.142948 0.891523 0.120000 +12.041523 0.992948 0.000000 +12.097487 0.947487 0.120000 +11.978833 1.025426 0.000000 +12.041523 0.992948 0.120000 +11.913687 1.044157 0.000000 +11.978833 1.025426 0.120000 +11.913687 1.044157 0.120000 +11.850000 1.050000 0.000000 +11.786313 1.044157 0.000000 +11.850000 1.050000 0.120000 +11.721167 1.025426 0.000000 +11.786313 1.044157 0.120000 +11.658477 0.992948 0.000000 +11.721167 1.025426 0.120000 +11.602512 0.947487 0.000000 +11.658477 0.992948 0.120000 +11.602512 0.947487 0.120000 +11.557052 0.891523 0.000000 +11.557052 0.891523 0.120000 +11.524574 0.828833 0.000000 +11.524574 0.828833 0.120000 +11.505843 0.763687 0.000000 +11.505843 0.763687 0.120000 +9.505843 2.263687 0.000000 +9.500000 2.200000 0.120000 +9.500000 2.200000 0.000000 +9.505843 2.263687 0.120000 +10.200000 2.200000 0.000000 +10.200000 2.200000 0.120000 +10.194157 2.263687 0.000000 +10.194157 2.263687 0.120000 +10.175426 2.328833 0.000000 +10.175426 2.328833 0.120000 +10.142948 2.391523 0.000000 +10.097487 2.447487 0.000000 +10.142948 2.391523 0.120000 +10.041523 2.492949 0.000000 +10.097487 2.447487 0.120000 +9.978833 2.525426 0.000000 +10.041523 2.492949 0.120000 +9.978833 2.525426 0.120000 +9.913687 2.544157 0.000000 +9.913687 2.544157 0.120000 +9.850000 2.550000 0.000000 +9.786313 2.544157 0.000000 +9.850000 2.550000 0.120000 +9.721167 2.525426 0.000000 +9.786313 2.544157 0.120000 +9.658477 2.492949 0.000000 +9.721167 2.525426 0.120000 +9.658477 2.492949 0.120000 +9.602512 2.447487 0.000000 +9.557052 2.391523 0.000000 +9.602512 2.447487 0.120000 +9.557052 2.391523 0.120000 +9.524574 2.328833 0.000000 +9.524574 2.328833 0.120000 +9.500000 0.700000 0.120000 +9.500000 0.700000 0.000000 +10.200000 0.700000 0.000000 +10.200000 0.700000 0.120000 +10.194157 0.763687 0.000000 +10.194157 0.763687 0.120000 +10.175426 0.828833 0.000000 +10.175426 0.828833 0.120000 +10.142948 0.891523 0.000000 +10.097487 0.947487 0.000000 +10.142948 0.891523 0.120000 +10.041523 0.992948 0.000000 +10.097487 0.947487 0.120000 +9.978833 1.025426 0.000000 +10.041523 0.992948 0.120000 +9.913687 1.044157 0.000000 +9.978833 1.025426 0.120000 +9.850000 1.050000 0.000000 +9.913687 1.044157 0.120000 +9.786313 1.044157 0.000000 +9.850000 1.050000 0.120000 +9.786313 1.044157 0.120000 +9.721167 1.025426 0.000000 +9.658477 0.992948 0.000000 +9.721167 1.025426 0.120000 +9.658477 0.992948 0.120000 +9.602512 0.947487 0.000000 +9.602512 0.947487 0.120000 +9.557052 0.891523 0.000000 +9.557052 0.891523 0.120000 +9.524574 0.828833 0.000000 +9.524574 0.828833 0.120000 +9.505843 0.763687 0.000000 +9.505843 0.763687 0.120000 +7.500000 2.200000 0.120000 +7.500000 2.200000 0.000000 +8.194157 2.263687 0.000000 +8.200000 2.200000 0.000000 +8.200000 2.200000 0.120000 +8.194157 2.263687 0.120000 +8.175426 2.328833 0.000000 +8.175426 2.328833 0.120000 +8.142948 2.391523 0.000000 +8.097487 2.447487 0.000000 +8.142948 2.391523 0.120000 +8.041523 2.492949 0.000000 +8.097487 2.447487 0.120000 +7.978833 2.525426 0.000000 +8.041523 2.492949 0.120000 +7.913687 2.544157 0.000000 +7.978833 2.525426 0.120000 +7.913687 2.544157 0.120000 +7.850000 2.550000 0.000000 +7.786313 2.544157 0.000000 +7.850000 2.550000 0.120000 +7.786313 2.544157 0.120000 +7.721167 2.525426 0.000000 +7.658476 2.492949 0.000000 +7.721167 2.525426 0.120000 +7.658476 2.492949 0.120000 +7.602513 2.447487 0.000000 +7.602513 2.447487 0.120000 +7.557052 2.391523 0.000000 +7.557052 2.391523 0.120000 +7.524574 2.328833 0.000000 +7.524574 2.328833 0.120000 +7.505843 2.263687 0.000000 +7.505843 2.263687 0.120000 +7.500000 0.700000 0.120000 +7.500000 0.700000 0.000000 +8.194157 0.763687 0.000000 +8.200000 0.700000 0.000000 +8.200000 0.700000 0.120000 +8.175426 0.828833 0.000000 +8.194157 0.763687 0.120000 +8.142948 0.891523 0.000000 +8.175426 0.828833 0.120000 +8.097487 0.947487 0.000000 +8.142948 0.891523 0.120000 +8.041523 0.992948 0.000000 +8.097487 0.947487 0.120000 +8.041523 0.992948 0.120000 +7.978833 1.025426 0.000000 +7.978833 1.025426 0.120000 +7.913687 1.044157 0.000000 +7.913687 1.044157 0.120000 +7.850000 1.050000 0.000000 +7.850000 1.050000 0.120000 +7.786313 1.044157 0.000000 +7.786313 1.044157 0.120000 +7.721167 1.025426 0.000000 +7.721167 1.025426 0.120000 +7.658476 0.992948 0.000000 +7.602513 0.947487 0.000000 +7.658476 0.992948 0.120000 +7.602513 0.947487 0.120000 +7.557052 0.891523 0.000000 +7.557052 0.891523 0.120000 +7.524574 0.828833 0.000000 +7.524574 0.828833 0.120000 +7.505843 0.763687 0.000000 +7.505843 0.763687 0.120000 +5.524574 2.328833 0.120000 +5.505843 2.263687 0.120000 +5.500000 2.200000 0.120000 +5.500000 2.200000 0.000000 +6.200000 2.200000 0.000000 +6.200000 2.200000 0.120000 +6.194157 2.263687 0.000000 +6.175426 2.328833 0.000000 +6.194157 2.263687 0.120000 +6.142949 2.391523 0.000000 +6.175426 2.328833 0.120000 +6.097487 2.447487 0.000000 +6.142949 2.391523 0.120000 +6.097487 2.447487 0.120000 +6.041523 2.492949 0.000000 +6.041523 2.492949 0.120000 +5.978833 2.525426 0.000000 +5.978833 2.525426 0.120000 +5.913687 2.544157 0.000000 +5.913687 2.544157 0.120000 +5.850000 2.550000 0.000000 +5.786313 2.544157 0.000000 +5.850000 2.550000 0.120000 +5.721167 2.525426 0.000000 +5.786313 2.544157 0.120000 +5.658476 2.492949 0.000000 +5.721167 2.525426 0.120000 +5.602513 2.447487 0.000000 +5.658476 2.492949 0.120000 +5.602513 2.447487 0.120000 +5.557052 2.391523 0.000000 +5.524574 2.328833 0.000000 +5.557052 2.391523 0.120000 +5.505843 2.263687 0.000000 +5.505843 0.763687 0.000000 +5.500000 0.700000 0.120000 +5.500000 0.700000 0.000000 +5.505843 0.763687 0.120000 +6.200000 0.700000 0.000000 +6.200000 0.700000 0.120000 +6.194157 0.763687 0.000000 +6.194157 0.763687 0.120000 +6.175426 0.828833 0.000000 +6.175426 0.828833 0.120000 +6.142949 0.891523 0.000000 +6.097487 0.947487 0.000000 +6.142949 0.891523 0.120000 +6.097487 0.947487 0.120000 +6.041523 0.992948 0.000000 +5.978833 1.025426 0.000000 +6.041523 0.992948 0.120000 +5.913687 1.044157 0.000000 +5.978833 1.025426 0.120000 +5.850000 1.050000 0.000000 +5.913687 1.044157 0.120000 +5.850000 1.050000 0.120000 +5.786313 1.044157 0.000000 +5.721167 1.025426 0.000000 +5.786313 1.044157 0.120000 +5.721167 1.025426 0.120000 +5.658476 0.992948 0.000000 +5.658476 0.992948 0.120000 +5.602513 0.947487 0.000000 +5.602513 0.947487 0.120000 +5.557052 0.891523 0.000000 +5.557052 0.891523 0.120000 +5.524574 0.828833 0.000000 +5.524574 0.828833 0.120000 +3.505843 2.263687 0.000000 +3.500000 2.200000 0.120000 +3.500000 2.200000 0.000000 +3.505843 2.263687 0.120000 +4.200000 2.200000 0.000000 +4.200000 2.200000 0.120000 +4.194157 2.263687 0.000000 +4.175426 2.328833 0.000000 +4.194157 2.263687 0.120000 +4.142949 2.391523 0.000000 +4.175426 2.328833 0.120000 +4.142949 2.391523 0.120000 +4.097487 2.447487 0.000000 +4.097487 2.447487 0.120000 +4.041523 2.492949 0.000000 +4.041523 2.492949 0.120000 +3.978833 2.525426 0.000000 +3.978833 2.525426 0.120000 +3.913687 2.544157 0.000000 +3.913687 2.544157 0.120000 +3.850000 2.550000 0.000000 +3.850000 2.550000 0.120000 +3.786313 2.544157 0.000000 +3.786313 2.544157 0.120000 +3.721167 2.525426 0.000000 +3.721167 2.525426 0.120000 +3.658477 2.492949 0.000000 +3.658477 2.492949 0.120000 +3.602513 2.447487 0.000000 +3.557052 2.391523 0.000000 +3.602513 2.447487 0.120000 +3.557052 2.391523 0.120000 +3.524574 2.328833 0.000000 +3.524574 2.328833 0.120000 +3.500000 0.700000 0.120000 +3.500000 0.700000 0.000000 +4.194157 0.763687 0.000000 +4.200000 0.700000 0.000000 +4.200000 0.700000 0.120000 +4.194157 0.763687 0.120000 +4.175426 0.828833 0.000000 +4.175426 0.828833 0.120000 +4.142949 0.891523 0.000000 +4.142949 0.891523 0.120000 +4.097487 0.947487 0.000000 +4.097487 0.947487 0.120000 +4.041523 0.992948 0.000000 +4.041523 0.992948 0.120000 +3.978833 1.025426 0.000000 +3.978833 1.025426 0.120000 +3.913687 1.044157 0.000000 +3.913687 1.044157 0.120000 +3.850000 1.050000 0.000000 +3.850000 1.050000 0.120000 +3.786313 1.044157 0.000000 +3.786313 1.044157 0.120000 +3.721167 1.025426 0.000000 +3.721167 1.025426 0.120000 +3.658477 0.992948 0.000000 +3.658477 0.992948 0.120000 +3.602513 0.947487 0.000000 +3.602513 0.947487 0.120000 +3.557052 0.891523 0.000000 +3.557052 0.891523 0.120000 +3.524574 0.828833 0.000000 +3.524574 0.828833 0.120000 +3.505843 0.763687 0.000000 +3.505843 0.763687 0.120000 +1.500000 2.200000 0.120000 +1.500000 2.200000 0.000000 +2.200000 2.200000 0.000000 +2.200000 2.200000 0.120000 +2.194157 2.263687 0.000000 +2.175426 2.328833 0.000000 +2.194157 2.263687 0.120000 +2.142948 2.391523 0.000000 +2.175426 2.328833 0.120000 +2.097487 2.447487 0.000000 +2.142948 2.391523 0.120000 +2.041523 2.492949 0.000000 +2.097487 2.447487 0.120000 +2.041523 2.492949 0.120000 +1.978833 2.525426 0.000000 +1.978833 2.525426 0.120000 +1.913687 2.544157 0.000000 +1.913687 2.544157 0.120000 +1.850000 2.550000 0.000000 +1.786313 2.544157 0.000000 +1.850000 2.550000 0.120000 +1.786313 2.544157 0.120000 +1.721167 2.525426 0.000000 +1.658477 2.492949 0.000000 +1.721167 2.525426 0.120000 +1.602513 2.447487 0.000000 +1.658477 2.492949 0.120000 +1.557052 2.391523 0.000000 +1.602513 2.447487 0.120000 +1.524574 2.328833 0.000000 +1.557052 2.391523 0.120000 +1.524574 2.328833 0.120000 +1.505843 2.263687 0.000000 +1.505843 2.263687 0.120000 +2.194157 0.763687 0.000000 +2.200000 0.700000 0.000000 +1.505843 0.763687 0.120000 +1.500000 0.700000 0.120000 +1.500000 0.700000 0.000000 +1.505843 0.763687 0.000000 +1.524574 0.828833 0.120000 +1.524574 0.828833 0.000000 +1.557052 0.891523 0.120000 +1.557052 0.891523 0.000000 +1.602513 0.947487 0.120000 +1.602513 0.947487 0.000000 +1.658477 0.992948 0.120000 +1.658477 0.992948 0.000000 +1.721167 1.025426 0.120000 +1.786313 1.044157 0.120000 +1.721167 1.025426 0.000000 +1.786313 1.044157 0.000000 +1.850000 1.050000 0.120000 +1.850000 1.050000 0.000000 +1.913687 1.044157 0.120000 +1.913687 1.044157 0.000000 +1.978833 1.025426 0.120000 +1.978833 1.025426 0.000000 +2.041523 0.992948 0.120000 +2.097487 0.947487 0.120000 +2.041523 0.992948 0.000000 +2.142948 0.891523 0.120000 +2.097487 0.947487 0.000000 +2.175426 0.828833 0.120000 +2.142948 0.891523 0.000000 +2.194157 0.763687 0.120000 +2.175426 0.828833 0.000000 +2.200000 0.700000 0.120000 +21.505842 2.263687 0.000000 +21.500000 2.200000 0.120000 +21.500000 2.200000 0.000000 +21.505842 2.263687 0.120000 +22.200001 2.200000 0.000000 +22.200001 2.200000 0.120000 +22.194157 2.263687 0.000000 +22.194157 2.263687 0.120000 +22.175426 2.328833 0.000000 +22.175426 2.328833 0.120000 +22.142948 2.391523 0.000000 +22.097486 2.447487 0.000000 +22.142948 2.391523 0.120000 +22.097486 2.447487 0.120000 +22.041523 2.492949 0.000000 +22.041523 2.492949 0.120000 +21.978832 2.525426 0.000000 +21.978832 2.525426 0.120000 +21.913687 2.544157 0.000000 +21.913687 2.544157 0.120000 +21.850000 2.550000 0.000000 +21.850000 2.550000 0.120000 +21.786312 2.544157 0.000000 +21.786312 2.544157 0.120000 +21.721167 2.525426 0.000000 +21.721167 2.525426 0.120000 +21.658476 2.492949 0.000000 +21.658476 2.492949 0.120000 +21.602512 2.447487 0.000000 +21.602512 2.447487 0.120000 +21.557051 2.391523 0.000000 +21.557051 2.391523 0.120000 +21.524574 2.328833 0.000000 +21.524574 2.328833 0.120000 +21.557051 0.891523 0.000000 +21.505842 0.763687 0.120000 +21.500000 0.700000 0.120000 +21.500000 0.700000 0.000000 +21.505842 0.763687 0.000000 +21.524574 0.828833 0.120000 +21.557051 0.891523 0.120000 +21.524574 0.828833 0.000000 +22.200001 0.700000 0.000000 +22.200001 0.700000 0.120000 +22.194157 0.763687 0.000000 +22.175426 0.828833 0.000000 +22.194157 0.763687 0.120000 +22.175426 0.828833 0.120000 +22.142948 0.891523 0.000000 +22.097486 0.947487 0.000000 +22.142948 0.891523 0.120000 +22.041523 0.992948 0.000000 +22.097486 0.947487 0.120000 +22.041523 0.992948 0.120000 +21.978832 1.025426 0.000000 +21.978832 1.025426 0.120000 +21.913687 1.044157 0.000000 +21.913687 1.044157 0.120000 +21.850000 1.050000 0.000000 +21.850000 1.050000 0.120000 +21.786312 1.044157 0.000000 +21.786312 1.044157 0.120000 +21.721167 1.025426 0.000000 +21.721167 1.025426 0.120000 +21.658476 0.992948 0.000000 +21.658476 0.992948 0.120000 +21.602512 0.947487 0.000000 +21.602512 0.947487 0.120000 +23.524574 2.328833 0.000000 +23.500000 2.200000 0.120000 +23.500000 2.200000 0.000000 +23.505842 2.263687 0.120000 +23.505842 2.263687 0.000000 +23.524574 2.328833 0.120000 +24.200001 2.200000 0.000000 +24.200001 2.200000 0.120000 +24.194157 2.263687 0.000000 +24.194157 2.263687 0.120000 +24.175426 2.328833 0.000000 +24.175426 2.328833 0.120000 +24.142948 2.391523 0.000000 +24.097486 2.447487 0.000000 +24.142948 2.391523 0.120000 +24.097486 2.447487 0.120000 +24.041523 2.492949 0.000000 +24.041523 2.492949 0.120000 +23.978832 2.525426 0.000000 +23.978832 2.525426 0.120000 +23.913687 2.544157 0.000000 +23.850000 2.550000 0.000000 +23.913687 2.544157 0.120000 +23.786312 2.544157 0.000000 +23.850000 2.550000 0.120000 +23.721167 2.525426 0.000000 +23.786312 2.544157 0.120000 +23.658476 2.492949 0.000000 +23.721167 2.525426 0.120000 +23.658476 2.492949 0.120000 +23.602512 2.447487 0.000000 +23.602512 2.447487 0.120000 +23.557051 2.391523 0.000000 +23.557051 2.391523 0.120000 +23.505842 0.763687 0.000000 +23.505842 0.763687 0.120000 +23.500000 0.700000 0.120000 +23.500000 0.700000 0.000000 +24.200001 0.700000 0.000000 +24.200001 0.700000 0.120000 +24.194157 0.763687 0.000000 +24.175426 0.828833 0.000000 +24.194157 0.763687 0.120000 +24.142948 0.891523 0.000000 +24.175426 0.828833 0.120000 +24.097486 0.947487 0.000000 +24.142948 0.891523 0.120000 +24.041523 0.992948 0.000000 +24.097486 0.947487 0.120000 +23.978832 1.025426 0.000000 +24.041523 0.992948 0.120000 +23.978832 1.025426 0.120000 +23.913687 1.044157 0.000000 +23.913687 1.044157 0.120000 +23.850000 1.050000 0.000000 +23.850000 1.050000 0.120000 +23.786312 1.044157 0.000000 +23.786312 1.044157 0.120000 +23.721167 1.025426 0.000000 +23.721167 1.025426 0.120000 +23.658476 0.992948 0.000000 +23.658476 0.992948 0.120000 +23.602512 0.947487 0.000000 +23.602512 0.947487 0.120000 +23.557051 0.891523 0.000000 +23.524574 0.828833 0.000000 +23.557051 0.891523 0.120000 +23.524574 0.828833 0.120000 +25.505842 2.263687 0.000000 +25.500000 2.200000 0.120000 +25.500000 2.200000 0.000000 +25.505842 2.263687 0.120000 +26.200001 2.200000 0.000000 +26.200001 2.200000 0.120000 +26.194157 2.263687 0.000000 +26.175426 2.328833 0.000000 +26.194157 2.263687 0.120000 +26.175426 2.328833 0.120000 +26.142948 2.391523 0.000000 +26.142948 2.391523 0.120000 +26.097486 2.447487 0.000000 +26.097486 2.447487 0.120000 +26.041523 2.492949 0.000000 +26.041523 2.492949 0.120000 +25.978832 2.525426 0.000000 +25.913687 2.544157 0.000000 +25.978832 2.525426 0.120000 +25.913687 2.544157 0.120000 +25.850000 2.550000 0.000000 +25.850000 2.550000 0.120000 +25.786312 2.544157 0.000000 +25.721167 2.525426 0.000000 +25.786312 2.544157 0.120000 +25.721167 2.525426 0.120000 +25.658476 2.492949 0.000000 +25.658476 2.492949 0.120000 +25.602512 2.447487 0.000000 +25.602512 2.447487 0.120000 +25.557051 2.391523 0.000000 +25.524574 2.328833 0.000000 +25.557051 2.391523 0.120000 +25.524574 2.328833 0.120000 +25.505842 0.763687 0.000000 +25.505842 0.763687 0.120000 +25.500000 0.700000 0.120000 +25.500000 0.700000 0.000000 +26.200001 0.700000 0.000000 +26.200001 0.700000 0.120000 +26.194157 0.763687 0.000000 +26.175426 0.828833 0.000000 +26.194157 0.763687 0.120000 +26.175426 0.828833 0.120000 +26.142948 0.891523 0.000000 +26.097486 0.947487 0.000000 +26.142948 0.891523 0.120000 +26.097486 0.947487 0.120000 +26.041523 0.992948 0.000000 +26.041523 0.992948 0.120000 +25.978832 1.025426 0.000000 +25.913687 1.044157 0.000000 +25.978832 1.025426 0.120000 +25.913687 1.044157 0.120000 +25.850000 1.050000 0.000000 +25.850000 1.050000 0.120000 +25.786312 1.044157 0.000000 +25.786312 1.044157 0.120000 +25.721167 1.025426 0.000000 +25.721167 1.025426 0.120000 +25.658476 0.992948 0.000000 +25.658476 0.992948 0.120000 +25.602512 0.947487 0.000000 +25.557051 0.891523 0.000000 +25.602512 0.947487 0.120000 +25.557051 0.891523 0.120000 +25.524574 0.828833 0.000000 +25.524574 0.828833 0.120000 +28.097486 2.447487 0.120000 +28.194157 2.263687 0.000000 +28.200001 2.200000 0.000000 +28.200001 2.200000 0.120000 +28.175426 2.328833 0.000000 +28.194157 2.263687 0.120000 +28.175426 2.328833 0.120000 +28.142948 2.391523 0.000000 +28.142948 2.391523 0.120000 +28.097486 2.447487 0.000000 +27.500000 2.200000 0.120000 +27.500000 2.200000 0.000000 +27.505842 2.263687 0.120000 +27.505842 2.263687 0.000000 +27.524574 2.328833 0.120000 +27.524574 2.328833 0.000000 +27.557051 2.391523 0.120000 +27.557051 2.391523 0.000000 +27.602512 2.447487 0.120000 +27.658476 2.492949 0.120000 +27.602512 2.447487 0.000000 +27.658476 2.492949 0.000000 +27.721167 2.525426 0.120000 +27.721167 2.525426 0.000000 +27.786312 2.544157 0.120000 +27.786312 2.544157 0.000000 +27.850000 2.550000 0.120000 +27.850000 2.550000 0.000000 +27.913687 2.544157 0.120000 +27.913687 2.544157 0.000000 +27.978832 2.525426 0.120000 +27.978832 2.525426 0.000000 +28.041523 2.492949 0.120000 +28.041523 2.492949 0.000000 +27.505842 0.763687 0.000000 +27.505842 0.763687 0.120000 +27.500000 0.700000 0.120000 +27.500000 0.700000 0.000000 +28.200001 0.700000 0.000000 +28.200001 0.700000 0.120000 +28.194157 0.763687 0.000000 +28.175426 0.828833 0.000000 +28.194157 0.763687 0.120000 +28.142948 0.891523 0.000000 +28.175426 0.828833 0.120000 +28.097486 0.947487 0.000000 +28.142948 0.891523 0.120000 +28.041523 0.992948 0.000000 +28.097486 0.947487 0.120000 +27.978832 1.025426 0.000000 +28.041523 0.992948 0.120000 +27.978832 1.025426 0.120000 +27.913687 1.044157 0.000000 +27.913687 1.044157 0.120000 +27.850000 1.050000 0.000000 +27.850000 1.050000 0.120000 +27.786312 1.044157 0.000000 +27.721167 1.025426 0.000000 +27.786312 1.044157 0.120000 +27.721167 1.025426 0.120000 +27.658476 0.992948 0.000000 +27.658476 0.992948 0.120000 +27.602512 0.947487 0.000000 +27.602512 0.947487 0.120000 +27.557051 0.891523 0.000000 +27.524574 0.828833 0.000000 +27.557051 0.891523 0.120000 +27.524574 0.828833 0.120000 +30.142948 2.391523 0.000000 +30.194157 2.263687 0.000000 +30.200001 2.200000 0.000000 +30.200001 2.200000 0.120000 +30.194157 2.263687 0.120000 +30.175426 2.328833 0.000000 +29.505842 2.263687 0.120000 +29.500000 2.200000 0.120000 +29.500000 2.200000 0.000000 +29.524574 2.328833 0.120000 +29.505842 2.263687 0.000000 +29.524574 2.328833 0.000000 +29.557051 2.391523 0.120000 +29.602512 2.447487 0.120000 +29.557051 2.391523 0.000000 +29.602512 2.447487 0.000000 +29.658476 2.492949 0.120000 +29.658476 2.492949 0.000000 +29.721167 2.525426 0.120000 +29.721167 2.525426 0.000000 +29.786312 2.544157 0.120000 +29.786312 2.544157 0.000000 +29.850000 2.550000 0.120000 +29.850000 2.550000 0.000000 +29.913687 2.544157 0.120000 +29.913687 2.544157 0.000000 +29.978832 2.525426 0.120000 +29.978832 2.525426 0.000000 +30.041523 2.492949 0.120000 +30.041523 2.492949 0.000000 +30.097486 2.447487 0.120000 +30.142948 2.391523 0.120000 +30.097486 2.447487 0.000000 +30.175426 2.328833 0.120000 +29.557051 0.891523 0.120000 +29.505842 0.763687 0.120000 +29.500000 0.700000 0.120000 +29.500000 0.700000 0.000000 +29.505842 0.763687 0.000000 +29.524574 0.828833 0.120000 +30.200001 0.700000 0.000000 +30.200001 0.700000 0.120000 +30.194157 0.763687 0.000000 +30.175426 0.828833 0.000000 +30.194157 0.763687 0.120000 +30.142948 0.891523 0.000000 +30.175426 0.828833 0.120000 +30.097486 0.947487 0.000000 +30.142948 0.891523 0.120000 +30.041523 0.992948 0.000000 +30.097486 0.947487 0.120000 +30.041523 0.992948 0.120000 +29.978832 1.025426 0.000000 +29.978832 1.025426 0.120000 +29.913687 1.044157 0.000000 +29.850000 1.050000 0.000000 +29.913687 1.044157 0.120000 +29.786312 1.044157 0.000000 +29.850000 1.050000 0.120000 +29.721167 1.025426 0.000000 +29.786312 1.044157 0.120000 +29.658476 0.992948 0.000000 +29.721167 1.025426 0.120000 +29.658476 0.992948 0.120000 +29.602512 0.947487 0.000000 +29.602512 0.947487 0.120000 +29.557051 0.891523 0.000000 +29.524574 0.828833 0.000000 +31.913687 2.544157 0.120000 +32.194157 2.263687 0.000000 +32.200001 2.200000 0.000000 +32.200001 2.200000 0.120000 +32.194157 2.263687 0.120000 +32.175426 2.328833 0.000000 +32.142948 2.391523 0.000000 +32.175426 2.328833 0.120000 +32.142948 2.391523 0.120000 +32.097488 2.447487 0.000000 +32.097488 2.447487 0.120000 +32.041523 2.492949 0.000000 +31.978832 2.525426 0.000000 +32.041523 2.492949 0.120000 +31.913687 2.544157 0.000000 +31.978832 2.525426 0.120000 +31.500000 2.200000 0.120000 +31.500000 2.200000 0.000000 +31.505842 2.263687 0.120000 +31.505842 2.263687 0.000000 +31.524574 2.328833 0.120000 +31.524574 2.328833 0.000000 +31.557051 2.391523 0.120000 +31.557051 2.391523 0.000000 +31.602512 2.447487 0.120000 +31.658476 2.492949 0.120000 +31.602512 2.447487 0.000000 +31.658476 2.492949 0.000000 +31.721167 2.525426 0.120000 +31.721167 2.525426 0.000000 +31.786312 2.544157 0.120000 +31.786312 2.544157 0.000000 +31.850000 2.550000 0.120000 +31.850000 2.550000 0.000000 +31.524574 0.828833 0.000000 +31.505842 0.763687 0.120000 +31.500000 0.700000 0.120000 +31.500000 0.700000 0.000000 +31.524574 0.828833 0.120000 +31.505842 0.763687 0.000000 +32.200001 0.700000 0.000000 +32.200001 0.700000 0.120000 +32.194157 0.763687 0.000000 +32.194157 0.763687 0.120000 +32.175426 0.828833 0.000000 +32.175426 0.828833 0.120000 +32.142948 0.891523 0.000000 +32.142948 0.891523 0.120000 +32.097488 0.947487 0.000000 +32.041523 0.992948 0.000000 +32.097488 0.947487 0.120000 +32.041523 0.992948 0.120000 +31.978832 1.025426 0.000000 +31.978832 1.025426 0.120000 +31.913687 1.044157 0.000000 +31.913687 1.044157 0.120000 +31.850000 1.050000 0.000000 +31.850000 1.050000 0.120000 +31.786312 1.044157 0.000000 +31.721167 1.025426 0.000000 +31.786312 1.044157 0.120000 +31.721167 1.025426 0.120000 +31.658476 0.992948 0.000000 +31.602512 0.947487 0.000000 +31.658476 0.992948 0.120000 +31.602512 0.947487 0.120000 +31.557051 0.891523 0.000000 +31.557051 0.891523 0.120000 +33.500000 2.200000 0.120000 +33.500000 2.200000 0.000000 +34.194157 2.263687 0.000000 +34.200001 2.200000 0.000000 +34.200001 2.200000 0.120000 +34.175426 2.328833 0.000000 +34.194157 2.263687 0.120000 +34.142948 2.391523 0.000000 +34.175426 2.328833 0.120000 +34.097488 2.447487 0.000000 +34.142948 2.391523 0.120000 +34.097488 2.447487 0.120000 +34.041523 2.492949 0.000000 +34.041523 2.492949 0.120000 +33.978832 2.525426 0.000000 +33.978832 2.525426 0.120000 +33.913689 2.544157 0.000000 +33.913689 2.544157 0.120000 +33.849998 2.550000 0.000000 +33.849998 2.550000 0.120000 +33.786312 2.544157 0.000000 +33.786312 2.544157 0.120000 +33.721169 2.525426 0.000000 +33.721169 2.525426 0.120000 +33.658478 2.492949 0.000000 +33.658478 2.492949 0.120000 +33.602512 2.447487 0.000000 +33.557053 2.391523 0.000000 +33.602512 2.447487 0.120000 +33.557053 2.391523 0.120000 +33.524574 2.328833 0.000000 +33.505844 2.263687 0.000000 +33.524574 2.328833 0.120000 +33.505844 2.263687 0.120000 +33.505844 0.763687 0.120000 +33.500000 0.700000 0.120000 +34.200001 0.700000 0.000000 +34.200001 0.700000 0.120000 +34.194157 0.763687 0.000000 +34.194157 0.763687 0.120000 +34.175426 0.828833 0.000000 +34.175426 0.828833 0.120000 +34.142948 0.891523 0.000000 +34.142948 0.891523 0.120000 +34.097488 0.947487 0.000000 +34.041523 0.992948 0.000000 +34.097488 0.947487 0.120000 +34.041523 0.992948 0.120000 +33.978832 1.025426 0.000000 +33.978832 1.025426 0.120000 +33.913689 1.044157 0.000000 +33.913689 1.044157 0.120000 +33.849998 1.050000 0.000000 +33.786312 1.044157 0.000000 +33.849998 1.050000 0.120000 +33.721169 1.025426 0.000000 +33.786312 1.044157 0.120000 +33.658478 0.992948 0.000000 +33.721169 1.025426 0.120000 +33.602512 0.947487 0.000000 +33.658478 0.992948 0.120000 +33.602512 0.947487 0.120000 +33.557053 0.891523 0.000000 +33.557053 0.891523 0.120000 +33.524574 0.828833 0.000000 +33.524574 0.828833 0.120000 +33.505844 0.763687 0.000000 +33.500000 0.700000 0.000000 +35.500000 2.200000 0.120000 +35.500000 2.200000 0.000000 +36.194157 2.263687 0.000000 +36.200001 2.200000 0.000000 +36.200001 2.200000 0.120000 +36.194157 2.263687 0.120000 +36.175426 2.328833 0.000000 +36.142948 2.391523 0.000000 +36.175426 2.328833 0.120000 +36.097488 2.447487 0.000000 +36.142948 2.391523 0.120000 +36.097488 2.447487 0.120000 +36.041523 2.492949 0.000000 +35.978832 2.525426 0.000000 +36.041523 2.492949 0.120000 +35.978832 2.525426 0.120000 +35.913689 2.544157 0.000000 +35.913689 2.544157 0.120000 +35.849998 2.550000 0.000000 +35.786312 2.544157 0.000000 +35.849998 2.550000 0.120000 +35.786312 2.544157 0.120000 +35.721169 2.525426 0.000000 +35.658478 2.492949 0.000000 +35.721169 2.525426 0.120000 +35.658478 2.492949 0.120000 +35.602512 2.447487 0.000000 +35.602512 2.447487 0.120000 +35.557053 2.391523 0.000000 +35.557053 2.391523 0.120000 +35.524574 2.328833 0.000000 +35.505844 2.263687 0.000000 +35.524574 2.328833 0.120000 +35.505844 2.263687 0.120000 +35.500000 0.700000 0.120000 +35.500000 0.700000 0.000000 +36.200001 0.700000 0.000000 +36.200001 0.700000 0.120000 +36.194157 0.763687 0.000000 +36.194157 0.763687 0.120000 +36.175426 0.828833 0.000000 +36.175426 0.828833 0.120000 +36.142948 0.891523 0.000000 +36.097488 0.947487 0.000000 +36.142948 0.891523 0.120000 +36.097488 0.947487 0.120000 +36.041523 0.992948 0.000000 +36.041523 0.992948 0.120000 +35.978832 1.025426 0.000000 +35.913689 1.044157 0.000000 +35.978832 1.025426 0.120000 +35.849998 1.050000 0.000000 +35.913689 1.044157 0.120000 +35.786312 1.044157 0.000000 +35.849998 1.050000 0.120000 +35.721169 1.025426 0.000000 +35.786312 1.044157 0.120000 +35.721169 1.025426 0.120000 +35.658478 0.992948 0.000000 +35.602512 0.947487 0.000000 +35.658478 0.992948 0.120000 +35.602512 0.947487 0.120000 +35.557053 0.891523 0.000000 +35.557053 0.891523 0.120000 +35.524574 0.828833 0.000000 +35.524574 0.828833 0.120000 +35.505844 0.763687 0.000000 +35.505844 0.763687 0.120000 +37.500000 2.200000 0.120000 +37.500000 2.200000 0.000000 +38.194157 2.263687 0.000000 +38.200001 2.200000 0.000000 +38.200001 2.200000 0.120000 +38.194157 2.263687 0.120000 +38.175426 2.328833 0.000000 +38.142948 2.391523 0.000000 +38.175426 2.328833 0.120000 +38.097488 2.447487 0.000000 +38.142948 2.391523 0.120000 +38.097488 2.447487 0.120000 +38.041523 2.492949 0.000000 +37.978832 2.525426 0.000000 +38.041523 2.492949 0.120000 +37.978832 2.525426 0.120000 +37.913689 2.544157 0.000000 +37.913689 2.544157 0.120000 +37.849998 2.550000 0.000000 +37.849998 2.550000 0.120000 +37.786312 2.544157 0.000000 +37.786312 2.544157 0.120000 +37.721169 2.525426 0.000000 +37.721169 2.525426 0.120000 +37.658478 2.492949 0.000000 +37.658478 2.492949 0.120000 +37.602512 2.447487 0.000000 +37.602512 2.447487 0.120000 +37.557053 2.391523 0.000000 +37.557053 2.391523 0.120000 +37.524574 2.328833 0.000000 +37.505844 2.263687 0.000000 +37.524574 2.328833 0.120000 +37.505844 2.263687 0.120000 +37.500000 0.700000 0.120000 +37.500000 0.700000 0.000000 +38.200001 0.700000 0.000000 +38.200001 0.700000 0.120000 +38.194157 0.763687 0.000000 +38.175426 0.828833 0.000000 +38.194157 0.763687 0.120000 +38.175426 0.828833 0.120000 +38.142948 0.891523 0.000000 +38.097488 0.947487 0.000000 +38.142948 0.891523 0.120000 +38.097488 0.947487 0.120000 +38.041523 0.992948 0.000000 +38.041523 0.992948 0.120000 +37.978832 1.025426 0.000000 +37.913689 1.044157 0.000000 +37.978832 1.025426 0.120000 +37.913689 1.044157 0.120000 +37.849998 1.050000 0.000000 +37.849998 1.050000 0.120000 +37.786312 1.044157 0.000000 +37.721169 1.025426 0.000000 +37.786312 1.044157 0.120000 +37.721169 1.025426 0.120000 +37.658478 0.992948 0.000000 +37.602512 0.947487 0.000000 +37.658478 0.992948 0.120000 +37.602512 0.947487 0.120000 +37.557053 0.891523 0.000000 +37.557053 0.891523 0.120000 +37.524574 0.828833 0.000000 +37.524574 0.828833 0.120000 +37.505844 0.763687 0.000000 +37.505844 0.763687 0.120000 +2.500000 1.450000 0.120000 +2.500000 1.450000 0.000000 +3.200000 1.450000 0.000000 +3.200000 1.450000 0.120000 +3.194157 1.513687 0.000000 +3.175426 1.578833 0.000000 +3.194157 1.513687 0.120000 +3.142948 1.641523 0.000000 +3.175426 1.578833 0.120000 +3.142948 1.641523 0.120000 +3.097487 1.697487 0.000000 +3.097487 1.697487 0.120000 +3.041523 1.742948 0.000000 +3.041523 1.742948 0.120000 +2.978833 1.775426 0.000000 +2.978833 1.775426 0.120000 +2.913687 1.794157 0.000000 +2.913687 1.794157 0.120000 +2.850000 1.800000 0.000000 +2.850000 1.800000 0.120000 +2.786313 1.794157 0.000000 +2.786313 1.794157 0.120000 +2.721167 1.775426 0.000000 +2.721167 1.775426 0.120000 +2.658477 1.742948 0.000000 +2.602513 1.697487 0.000000 +2.658477 1.742948 0.120000 +2.602513 1.697487 0.120000 +2.557052 1.641523 0.000000 +2.557052 1.641523 0.120000 +2.524574 1.578833 0.000000 +2.524574 1.578833 0.120000 +2.505843 1.513687 0.000000 +2.505843 1.513687 0.120000 +4.500000 1.450000 0.120000 +4.500000 1.450000 0.000000 +5.200000 1.450000 0.000000 +5.200000 1.450000 0.120000 +5.194157 1.513687 0.000000 +5.175426 1.578833 0.000000 +5.194157 1.513687 0.120000 +5.175426 1.578833 0.120000 +5.142949 1.641523 0.000000 +5.142949 1.641523 0.120000 +5.097487 1.697487 0.000000 +5.097487 1.697487 0.120000 +5.041523 1.742948 0.000000 +5.041523 1.742948 0.120000 +4.978833 1.775426 0.000000 +4.978833 1.775426 0.120000 +4.913687 1.794157 0.000000 +4.913687 1.794157 0.120000 +4.850000 1.800000 0.000000 +4.850000 1.800000 0.120000 +4.786313 1.794157 0.000000 +4.786313 1.794157 0.120000 +4.721167 1.775426 0.000000 +4.721167 1.775426 0.120000 +4.658476 1.742948 0.000000 +4.658476 1.742948 0.120000 +4.602513 1.697487 0.000000 +4.602513 1.697487 0.120000 +4.557052 1.641523 0.000000 +4.524574 1.578833 0.000000 +4.557052 1.641523 0.120000 +4.505843 1.513687 0.000000 +4.524574 1.578833 0.120000 +4.505843 1.513687 0.120000 +6.500000 1.450000 0.120000 +6.500000 1.450000 0.000000 +7.194157 1.513687 0.000000 +7.200000 1.450000 0.000000 +7.200000 1.450000 0.120000 +7.194157 1.513687 0.120000 +7.175426 1.578833 0.000000 +7.175426 1.578833 0.120000 +7.142949 1.641523 0.000000 +7.142949 1.641523 0.120000 +7.097487 1.697487 0.000000 +7.097487 1.697487 0.120000 +7.041523 1.742948 0.000000 +7.041523 1.742948 0.120000 +6.978833 1.775426 0.000000 +6.978833 1.775426 0.120000 +6.913687 1.794157 0.000000 +6.913687 1.794157 0.120000 +6.850000 1.800000 0.000000 +6.850000 1.800000 0.120000 +6.786313 1.794157 0.000000 +6.786313 1.794157 0.120000 +6.721167 1.775426 0.000000 +6.721167 1.775426 0.120000 +6.658476 1.742948 0.000000 +6.602513 1.697487 0.000000 +6.658476 1.742948 0.120000 +6.602513 1.697487 0.120000 +6.557052 1.641523 0.000000 +6.557052 1.641523 0.120000 +6.524574 1.578833 0.000000 +6.524574 1.578833 0.120000 +6.505843 1.513687 0.000000 +6.505843 1.513687 0.120000 +8.978833 1.775426 0.120000 +9.194157 1.513687 0.000000 +9.200000 1.450000 0.000000 +9.200000 1.450000 0.120000 +9.175426 1.578833 0.000000 +9.194157 1.513687 0.120000 +9.142948 1.641523 0.000000 +9.175426 1.578833 0.120000 +9.097487 1.697487 0.000000 +9.142948 1.641523 0.120000 +9.097487 1.697487 0.120000 +9.041523 1.742948 0.000000 +9.041523 1.742948 0.120000 +8.978833 1.775426 0.000000 +8.505843 1.513687 0.120000 +8.500000 1.450000 0.120000 +8.500000 1.450000 0.000000 +8.505843 1.513687 0.000000 +8.524574 1.578833 0.120000 +8.557052 1.641523 0.120000 +8.524574 1.578833 0.000000 +8.557052 1.641523 0.000000 +8.602512 1.697487 0.120000 +8.658477 1.742948 0.120000 +8.602512 1.697487 0.000000 +8.658477 1.742948 0.000000 +8.721167 1.775426 0.120000 +8.721167 1.775426 0.000000 +8.786313 1.794157 0.120000 +8.786313 1.794157 0.000000 +8.850000 1.800000 0.120000 +8.850000 1.800000 0.000000 +8.913687 1.794157 0.120000 +8.913687 1.794157 0.000000 +10.500000 1.450000 0.120000 +10.500000 1.450000 0.000000 +11.200000 1.450000 0.000000 +11.200000 1.450000 0.120000 +11.194157 1.513687 0.000000 +11.175426 1.578833 0.000000 +11.194157 1.513687 0.120000 +11.175426 1.578833 0.120000 +11.142948 1.641523 0.000000 +11.097487 1.697487 0.000000 +11.142948 1.641523 0.120000 +11.041523 1.742948 0.000000 +11.097487 1.697487 0.120000 +11.041523 1.742948 0.120000 +10.978833 1.775426 0.000000 +10.978833 1.775426 0.120000 +10.913687 1.794157 0.000000 +10.850000 1.800000 0.000000 +10.913687 1.794157 0.120000 +10.786313 1.794157 0.000000 +10.850000 1.800000 0.120000 +10.786313 1.794157 0.120000 +10.721167 1.775426 0.000000 +10.658477 1.742948 0.000000 +10.721167 1.775426 0.120000 +10.602512 1.697487 0.000000 +10.658477 1.742948 0.120000 +10.602512 1.697487 0.120000 +10.557052 1.641523 0.000000 +10.557052 1.641523 0.120000 +10.524574 1.578833 0.000000 +10.524574 1.578833 0.120000 +10.505843 1.513687 0.000000 +10.505843 1.513687 0.120000 +12.500000 1.450000 0.120000 +12.500000 1.450000 0.000000 +13.194157 1.513687 0.000000 +13.200000 1.450000 0.000000 +13.200000 1.450000 0.120000 +13.175426 1.578833 0.000000 +13.194157 1.513687 0.120000 +13.142948 1.641523 0.000000 +13.175426 1.578833 0.120000 +13.142948 1.641523 0.120000 +13.097487 1.697487 0.000000 +13.041523 1.742948 0.000000 +13.097487 1.697487 0.120000 +12.978833 1.775426 0.000000 +13.041523 1.742948 0.120000 +12.913687 1.794157 0.000000 +12.978833 1.775426 0.120000 +12.913687 1.794157 0.120000 +12.850000 1.800000 0.000000 +12.850000 1.800000 0.120000 +12.786313 1.794157 0.000000 +12.721167 1.775426 0.000000 +12.786313 1.794157 0.120000 +12.721167 1.775426 0.120000 +12.658477 1.742948 0.000000 +12.658477 1.742948 0.120000 +12.602512 1.697487 0.000000 +12.602512 1.697487 0.120000 +12.557052 1.641523 0.000000 +12.524574 1.578833 0.000000 +12.557052 1.641523 0.120000 +12.524574 1.578833 0.120000 +12.505843 1.513687 0.000000 +12.505843 1.513687 0.120000 +14.500000 1.450000 0.120000 +14.500000 1.450000 0.000000 +15.194157 1.513687 0.000000 +15.200000 1.450000 0.000000 +15.200000 1.450000 0.120000 +15.175426 1.578833 0.000000 +15.194157 1.513687 0.120000 +15.175426 1.578833 0.120000 +15.142948 1.641523 0.000000 +15.097487 1.697487 0.000000 +15.142948 1.641523 0.120000 +15.041523 1.742948 0.000000 +15.097487 1.697487 0.120000 +15.041523 1.742948 0.120000 +14.978833 1.775426 0.000000 +14.978833 1.775426 0.120000 +14.913687 1.794157 0.000000 +14.913687 1.794157 0.120000 +14.850000 1.800000 0.000000 +14.850000 1.800000 0.120000 +14.786313 1.794157 0.000000 +14.786313 1.794157 0.120000 +14.721167 1.775426 0.000000 +14.721167 1.775426 0.120000 +14.658477 1.742948 0.000000 +14.658477 1.742948 0.120000 +14.602512 1.697487 0.000000 +14.602512 1.697487 0.120000 +14.557052 1.641523 0.000000 +14.557052 1.641523 0.120000 +14.524574 1.578833 0.000000 +14.524574 1.578833 0.120000 +14.505843 1.513687 0.000000 +14.505843 1.513687 0.120000 +16.500000 1.450000 0.120000 +16.500000 1.450000 0.000000 +17.194157 1.513687 0.000000 +17.200001 1.450000 0.000000 +17.200001 1.450000 0.120000 +17.175426 1.578833 0.000000 +17.194157 1.513687 0.120000 +17.175426 1.578833 0.120000 +17.142948 1.641523 0.000000 +17.097486 1.697487 0.000000 +17.142948 1.641523 0.120000 +17.097486 1.697487 0.120000 +17.041523 1.742948 0.000000 +17.041523 1.742948 0.120000 +16.978832 1.775426 0.000000 +16.978832 1.775426 0.120000 +16.913687 1.794157 0.000000 +16.913687 1.794157 0.120000 +16.850000 1.800000 0.000000 +16.850000 1.800000 0.120000 +16.786312 1.794157 0.000000 +16.786312 1.794157 0.120000 +16.721167 1.775426 0.000000 +16.721167 1.775426 0.120000 +16.658476 1.742948 0.000000 +16.658476 1.742948 0.120000 +16.602512 1.697487 0.000000 +16.602512 1.697487 0.120000 +16.557051 1.641523 0.000000 +16.557051 1.641523 0.120000 +16.524574 1.578833 0.000000 +16.524574 1.578833 0.120000 +16.505842 1.513687 0.000000 +16.505842 1.513687 0.120000 +18.500000 1.450000 0.120000 +18.500000 1.450000 0.000000 +19.194157 1.513687 0.000000 +19.200001 1.450000 0.000000 +19.200001 1.450000 0.120000 +19.175426 1.578833 0.000000 +19.194157 1.513687 0.120000 +19.142948 1.641523 0.000000 +19.175426 1.578833 0.120000 +19.142948 1.641523 0.120000 +19.097486 1.697487 0.000000 +19.097486 1.697487 0.120000 +19.041523 1.742948 0.000000 +18.978832 1.775426 0.000000 +19.041523 1.742948 0.120000 +18.913687 1.794157 0.000000 +18.978832 1.775426 0.120000 +18.913687 1.794157 0.120000 +18.850000 1.800000 0.000000 +18.786312 1.794157 0.000000 +18.850000 1.800000 0.120000 +18.721167 1.775426 0.000000 +18.786312 1.794157 0.120000 +18.721167 1.775426 0.120000 +18.658476 1.742948 0.000000 +18.602512 1.697487 0.000000 +18.658476 1.742948 0.120000 +18.602512 1.697487 0.120000 +18.557051 1.641523 0.000000 +18.557051 1.641523 0.120000 +18.524574 1.578833 0.000000 +18.524574 1.578833 0.120000 +18.505842 1.513687 0.000000 +18.505842 1.513687 0.120000 +20.500000 1.450000 0.120000 +20.500000 1.450000 0.000000 +21.200001 1.450000 0.000000 +21.200001 1.450000 0.120000 +21.194157 1.513687 0.000000 +21.175426 1.578833 0.000000 +21.194157 1.513687 0.120000 +21.175426 1.578833 0.120000 +21.142948 1.641523 0.000000 +21.142948 1.641523 0.120000 +21.097486 1.697487 0.000000 +21.097486 1.697487 0.120000 +21.041523 1.742948 0.000000 +21.041523 1.742948 0.120000 +20.978832 1.775426 0.000000 +20.978832 1.775426 0.120000 +20.913687 1.794157 0.000000 +20.913687 1.794157 0.120000 +20.850000 1.800000 0.000000 +20.850000 1.800000 0.120000 +20.786312 1.794157 0.000000 +20.721167 1.775426 0.000000 +20.786312 1.794157 0.120000 +20.721167 1.775426 0.120000 +20.658476 1.742948 0.000000 +20.658476 1.742948 0.120000 +20.602512 1.697487 0.000000 +20.602512 1.697487 0.120000 +20.557051 1.641523 0.000000 +20.557051 1.641523 0.120000 +20.524574 1.578833 0.000000 +20.524574 1.578833 0.120000 +20.505842 1.513687 0.000000 +20.505842 1.513687 0.120000 +22.500000 1.450000 0.120000 +22.500000 1.450000 0.000000 +23.200001 1.450000 0.000000 +23.200001 1.450000 0.120000 +23.194157 1.513687 0.000000 +23.175426 1.578833 0.000000 +23.194157 1.513687 0.120000 +23.175426 1.578833 0.120000 +23.142948 1.641523 0.000000 +23.142948 1.641523 0.120000 +23.097486 1.697487 0.000000 +23.097486 1.697487 0.120000 +23.041523 1.742948 0.000000 +23.041523 1.742948 0.120000 +22.978832 1.775426 0.000000 +22.978832 1.775426 0.120000 +22.913687 1.794157 0.000000 +22.913687 1.794157 0.120000 +22.850000 1.800000 0.000000 +22.850000 1.800000 0.120000 +22.786312 1.794157 0.000000 +22.721167 1.775426 0.000000 +22.786312 1.794157 0.120000 +22.721167 1.775426 0.120000 +22.658476 1.742948 0.000000 +22.658476 1.742948 0.120000 +22.602512 1.697487 0.000000 +22.602512 1.697487 0.120000 +22.557051 1.641523 0.000000 +22.557051 1.641523 0.120000 +22.524574 1.578833 0.000000 +22.524574 1.578833 0.120000 +22.505842 1.513687 0.000000 +22.505842 1.513687 0.120000 +24.978832 1.775426 0.120000 +25.194157 1.513687 0.000000 +25.200001 1.450000 0.000000 +25.200001 1.450000 0.120000 +25.175426 1.578833 0.000000 +25.194157 1.513687 0.120000 +25.142948 1.641523 0.000000 +25.175426 1.578833 0.120000 +25.142948 1.641523 0.120000 +25.097486 1.697487 0.000000 +25.041523 1.742948 0.000000 +25.097486 1.697487 0.120000 +24.978832 1.775426 0.000000 +25.041523 1.742948 0.120000 +24.505842 1.513687 0.120000 +24.500000 1.450000 0.120000 +24.500000 1.450000 0.000000 +24.505842 1.513687 0.000000 +24.524574 1.578833 0.120000 +24.557051 1.641523 0.120000 +24.524574 1.578833 0.000000 +24.557051 1.641523 0.000000 +24.602512 1.697487 0.120000 +24.658476 1.742948 0.120000 +24.602512 1.697487 0.000000 +24.658476 1.742948 0.000000 +24.721167 1.775426 0.120000 +24.721167 1.775426 0.000000 +24.786312 1.794157 0.120000 +24.786312 1.794157 0.000000 +24.850000 1.800000 0.120000 +24.850000 1.800000 0.000000 +24.913687 1.794157 0.120000 +24.913687 1.794157 0.000000 +26.500000 1.450000 0.120000 +26.500000 1.450000 0.000000 +27.194157 1.513687 0.000000 +27.200001 1.450000 0.000000 +27.200001 1.450000 0.120000 +27.175426 1.578833 0.000000 +27.194157 1.513687 0.120000 +27.142948 1.641523 0.000000 +27.175426 1.578833 0.120000 +27.142948 1.641523 0.120000 +27.097486 1.697487 0.000000 +27.041523 1.742948 0.000000 +27.097486 1.697487 0.120000 +26.978832 1.775426 0.000000 +27.041523 1.742948 0.120000 +26.978832 1.775426 0.120000 +26.913687 1.794157 0.000000 +26.913687 1.794157 0.120000 +26.850000 1.800000 0.000000 +26.850000 1.800000 0.120000 +26.786312 1.794157 0.000000 +26.786312 1.794157 0.120000 +26.721167 1.775426 0.000000 +26.721167 1.775426 0.120000 +26.658476 1.742948 0.000000 +26.658476 1.742948 0.120000 +26.602512 1.697487 0.000000 +26.557051 1.641523 0.000000 +26.602512 1.697487 0.120000 +26.557051 1.641523 0.120000 +26.524574 1.578833 0.000000 +26.524574 1.578833 0.120000 +26.505842 1.513687 0.000000 +26.505842 1.513687 0.120000 +28.500000 1.450000 0.120000 +28.500000 1.450000 0.000000 +29.194157 1.513687 0.000000 +29.200001 1.450000 0.000000 +29.200001 1.450000 0.120000 +29.175426 1.578833 0.000000 +29.194157 1.513687 0.120000 +29.142948 1.641523 0.000000 +29.175426 1.578833 0.120000 +29.097486 1.697487 0.000000 +29.142948 1.641523 0.120000 +29.097486 1.697487 0.120000 +29.041523 1.742948 0.000000 +29.041523 1.742948 0.120000 +28.978832 1.775426 0.000000 +28.913687 1.794157 0.000000 +28.978832 1.775426 0.120000 +28.850000 1.800000 0.000000 +28.913687 1.794157 0.120000 +28.786312 1.794157 0.000000 +28.850000 1.800000 0.120000 +28.786312 1.794157 0.120000 +28.721167 1.775426 0.000000 +28.658476 1.742948 0.000000 +28.721167 1.775426 0.120000 +28.602512 1.697487 0.000000 +28.658476 1.742948 0.120000 +28.602512 1.697487 0.120000 +28.557051 1.641523 0.000000 +28.557051 1.641523 0.120000 +28.524574 1.578833 0.000000 +28.524574 1.578833 0.120000 +28.505842 1.513687 0.000000 +28.505842 1.513687 0.120000 +30.505842 1.513687 0.000000 +30.500000 1.450000 0.120000 +30.500000 1.450000 0.000000 +30.505842 1.513687 0.120000 +31.200001 1.450000 0.000000 +31.200001 1.450000 0.120000 +31.194157 1.513687 0.000000 +31.175426 1.578833 0.000000 +31.194157 1.513687 0.120000 +31.175426 1.578833 0.120000 +31.142948 1.641523 0.000000 +31.142948 1.641523 0.120000 +31.097486 1.697487 0.000000 +31.097486 1.697487 0.120000 +31.041523 1.742948 0.000000 +30.978832 1.775426 0.000000 +31.041523 1.742948 0.120000 +30.978832 1.775426 0.120000 +30.913687 1.794157 0.000000 +30.913687 1.794157 0.120000 +30.850000 1.800000 0.000000 +30.786312 1.794157 0.000000 +30.850000 1.800000 0.120000 +30.721167 1.775426 0.000000 +30.786312 1.794157 0.120000 +30.658476 1.742948 0.000000 +30.721167 1.775426 0.120000 +30.658476 1.742948 0.120000 +30.602512 1.697487 0.000000 +30.602512 1.697487 0.120000 +30.557051 1.641523 0.000000 +30.557051 1.641523 0.120000 +30.524574 1.578833 0.000000 +30.524574 1.578833 0.120000 +32.505844 1.513687 0.000000 +32.500000 1.450000 0.120000 +32.500000 1.450000 0.000000 +32.505844 1.513687 0.120000 +33.200001 1.450000 0.000000 +33.200001 1.450000 0.120000 +33.194157 1.513687 0.000000 +33.175426 1.578833 0.000000 +33.194157 1.513687 0.120000 +33.175426 1.578833 0.120000 +33.142948 1.641523 0.000000 +33.097488 1.697487 0.000000 +33.142948 1.641523 0.120000 +33.097488 1.697487 0.120000 +33.041523 1.742948 0.000000 +33.041523 1.742948 0.120000 +32.978832 1.775426 0.000000 +32.978832 1.775426 0.120000 +32.913689 1.794157 0.000000 +32.913689 1.794157 0.120000 +32.849998 1.800000 0.000000 +32.786312 1.794157 0.000000 +32.849998 1.800000 0.120000 +32.721169 1.775426 0.000000 +32.786312 1.794157 0.120000 +32.658478 1.742948 0.000000 +32.721169 1.775426 0.120000 +32.658478 1.742948 0.120000 +32.602512 1.697487 0.000000 +32.602512 1.697487 0.120000 +32.557053 1.641523 0.000000 +32.557053 1.641523 0.120000 +32.524574 1.578833 0.000000 +32.524574 1.578833 0.120000 +34.500000 1.450000 0.120000 +34.500000 1.450000 0.000000 +35.200001 1.450000 0.000000 +35.200001 1.450000 0.120000 +35.194157 1.513687 0.000000 +35.175426 1.578833 0.000000 +35.194157 1.513687 0.120000 +35.175426 1.578833 0.120000 +35.142948 1.641523 0.000000 +35.097488 1.697487 0.000000 +35.142948 1.641523 0.120000 +35.097488 1.697487 0.120000 +35.041523 1.742948 0.000000 +35.041523 1.742948 0.120000 +34.978832 1.775426 0.000000 +34.978832 1.775426 0.120000 +34.913689 1.794157 0.000000 +34.849998 1.800000 0.000000 +34.913689 1.794157 0.120000 +34.786312 1.794157 0.000000 +34.849998 1.800000 0.120000 +34.721169 1.775426 0.000000 +34.786312 1.794157 0.120000 +34.658478 1.742948 0.000000 +34.721169 1.775426 0.120000 +34.602512 1.697487 0.000000 +34.658478 1.742948 0.120000 +34.602512 1.697487 0.120000 +34.557053 1.641523 0.000000 +34.557053 1.641523 0.120000 +34.524574 1.578833 0.000000 +34.524574 1.578833 0.120000 +34.505844 1.513687 0.000000 +34.505844 1.513687 0.120000 +36.500000 1.450000 0.120000 +36.500000 1.450000 0.000000 +37.194157 1.513687 0.000000 +37.200001 1.450000 0.000000 +37.200001 1.450000 0.120000 +37.175426 1.578833 0.000000 +37.194157 1.513687 0.120000 +37.142948 1.641523 0.000000 +37.175426 1.578833 0.120000 +37.142948 1.641523 0.120000 +37.097488 1.697487 0.000000 +37.041523 1.742948 0.000000 +37.097488 1.697487 0.120000 +36.978832 1.775426 0.000000 +37.041523 1.742948 0.120000 +36.978832 1.775426 0.120000 +36.913689 1.794157 0.000000 +36.913689 1.794157 0.120000 +36.849998 1.800000 0.000000 +36.786312 1.794157 0.000000 +36.849998 1.800000 0.120000 +36.786312 1.794157 0.120000 +36.721169 1.775426 0.000000 +36.721169 1.775426 0.120000 +36.658478 1.742948 0.000000 +36.658478 1.742948 0.120000 +36.602512 1.697487 0.000000 +36.602512 1.697487 0.120000 +36.557053 1.641523 0.000000 +36.557053 1.641523 0.120000 +36.524574 1.578833 0.000000 +36.524574 1.578833 0.120000 +36.505844 1.513687 0.000000 +36.505844 1.513687 0.120000 + + + + + + + + + + + +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 + + + + + + + + + + + +0.175331 0.644281 +0.175331 0.644281 +0.189164 0.644410 +0.189164 0.644410 +0.189089 0.642168 +0.189089 0.642168 +0.188761 0.639873 +0.188761 0.639873 +0.188159 0.637662 +0.188159 0.637662 +0.187297 0.635684 +0.187297 0.635684 +0.186220 0.634075 +0.186220 0.634075 +0.185002 0.632920 +0.185002 0.632920 +0.183727 0.632249 +0.183727 0.632249 +0.182472 0.632032 +0.182472 0.632032 +0.181210 0.632226 +0.181210 0.632226 +0.179911 0.632873 +0.179911 0.632873 +0.178651 0.634004 +0.178651 0.634004 +0.177516 0.635593 +0.177516 0.635593 +0.176582 0.637554 +0.176582 0.637554 +0.175899 0.639753 +0.175899 0.639753 +0.175487 0.642042 +0.175487 0.642042 +0.214853 0.644649 +0.214853 0.644649 +0.228686 0.644778 +0.228686 0.644778 +0.228611 0.642537 +0.228283 0.640241 +0.228611 0.642537 +0.228283 0.640241 +0.227681 0.638030 +0.227681 0.638030 +0.226819 0.636052 +0.226819 0.636052 +0.225742 0.634443 +0.225742 0.634443 +0.224524 0.633289 +0.223249 0.632618 +0.224524 0.633289 +0.223249 0.632618 +0.221994 0.632400 +0.221994 0.632400 +0.220732 0.632594 +0.220732 0.632594 +0.219433 0.633241 +0.219433 0.633241 +0.218173 0.634372 +0.218173 0.634372 +0.217038 0.635961 +0.217038 0.635961 +0.216103 0.637922 +0.216103 0.637922 +0.215421 0.640121 +0.215421 0.640121 +0.215009 0.642410 +0.215009 0.642410 +0.268207 0.645146 +0.268207 0.645146 +0.254375 0.645018 +0.254375 0.645018 +0.254531 0.642778 +0.254531 0.642778 +0.254943 0.640490 +0.254943 0.640490 +0.255625 0.638290 +0.256560 0.636330 +0.255625 0.638290 +0.257695 0.634740 +0.256560 0.636330 +0.258955 0.633609 +0.257695 0.634740 +0.258955 0.633609 +0.260254 0.632962 +0.260254 0.632962 +0.261516 0.632769 +0.261516 0.632769 +0.262771 0.632986 +0.262771 0.632986 +0.264046 0.633657 +0.264046 0.633657 +0.265264 0.634811 +0.265264 0.634811 +0.266341 0.636421 +0.266341 0.636421 +0.267203 0.638398 +0.267805 0.640609 +0.267203 0.638398 +0.267805 0.640609 +0.268133 0.642905 +0.268133 0.642905 +0.293897 0.645386 +0.293897 0.645386 +0.307729 0.645515 +0.307729 0.645515 +0.307655 0.643273 +0.307655 0.643273 +0.307327 0.640978 +0.307327 0.640978 +0.306725 0.638766 +0.306725 0.638766 +0.305863 0.636789 +0.305863 0.636789 +0.304786 0.635179 +0.304786 0.635179 +0.303568 0.634025 +0.303568 0.634025 +0.302293 0.633354 +0.302293 0.633354 +0.301038 0.633137 +0.301038 0.633137 +0.299776 0.633331 +0.299776 0.633331 +0.298477 0.633978 +0.298477 0.633978 +0.297217 0.635109 +0.297217 0.635109 +0.296082 0.636698 +0.296082 0.636698 +0.295147 0.638658 +0.295147 0.638658 +0.294465 0.640858 +0.294465 0.640858 +0.294053 0.643146 +0.294053 0.643146 +0.333419 0.645754 +0.333419 0.645754 +0.347251 0.645883 +0.347251 0.645883 +0.347177 0.643641 +0.347177 0.643641 +0.346849 0.641346 +0.346849 0.641346 +0.346247 0.639134 +0.346247 0.639134 +0.345385 0.637157 +0.345385 0.637157 +0.344308 0.635547 +0.344308 0.635547 +0.343090 0.634393 +0.343090 0.634393 +0.341815 0.633722 +0.341815 0.633722 +0.340560 0.633505 +0.340560 0.633505 +0.339298 0.633699 +0.339298 0.633699 +0.337998 0.634346 +0.337998 0.634346 +0.336739 0.635477 +0.336739 0.635477 +0.335604 0.637066 +0.335604 0.637066 +0.334669 0.639026 +0.334669 0.639026 +0.333987 0.641226 +0.333987 0.641226 +0.333575 0.643514 +0.333575 0.643514 +0.372941 0.646122 +0.372941 0.646122 +0.386773 0.646251 +0.386773 0.646251 +0.386699 0.644009 +0.386699 0.644009 +0.386371 0.641714 +0.386371 0.641714 +0.385769 0.639502 +0.385769 0.639502 +0.384907 0.637525 +0.384907 0.637525 +0.383830 0.635915 +0.383830 0.635915 +0.382612 0.634761 +0.382612 0.634761 +0.381337 0.634090 +0.381337 0.634090 +0.380082 0.633873 +0.380082 0.633873 +0.378820 0.634067 +0.378820 0.634067 +0.377520 0.634714 +0.377520 0.634714 +0.376261 0.635845 +0.376261 0.635845 +0.375126 0.637434 +0.374191 0.639395 +0.375126 0.637434 +0.373509 0.641594 +0.374191 0.639395 +0.373509 0.641594 +0.373097 0.643882 +0.373097 0.643882 +0.412463 0.646490 +0.412463 0.646490 +0.426295 0.646619 +0.426295 0.646619 +0.426221 0.644377 +0.426221 0.644377 +0.425892 0.642082 +0.425892 0.642082 +0.425291 0.639871 +0.425291 0.639871 +0.424429 0.637893 +0.424429 0.637893 +0.423352 0.636284 +0.423352 0.636284 +0.422134 0.635130 +0.422134 0.635130 +0.420859 0.634459 +0.420859 0.634459 +0.419604 0.634241 +0.419604 0.634241 +0.418342 0.634435 +0.418342 0.634435 +0.417042 0.635082 +0.417042 0.635082 +0.415783 0.636213 +0.415783 0.636213 +0.414647 0.637802 +0.414647 0.637802 +0.413713 0.639763 +0.413713 0.639763 +0.413031 0.641962 +0.413031 0.641962 +0.412619 0.644251 +0.412619 0.644251 +0.451984 0.646858 +0.451984 0.646858 +0.465817 0.646987 +0.465817 0.646987 +0.465743 0.644746 +0.465743 0.644746 +0.465414 0.642450 +0.465414 0.642450 +0.464813 0.640239 +0.464813 0.640239 +0.463951 0.638261 +0.463951 0.638261 +0.462874 0.636652 +0.462874 0.636652 +0.461656 0.635498 +0.461656 0.635498 +0.460381 0.634827 +0.460381 0.634827 +0.459126 0.634609 +0.459126 0.634609 +0.457864 0.634803 +0.457864 0.634803 +0.456564 0.635450 +0.456564 0.635450 +0.455304 0.636581 +0.455304 0.636581 +0.454169 0.638170 +0.454169 0.638170 +0.453235 0.640131 +0.453235 0.640131 +0.452553 0.642330 +0.452553 0.642330 +0.452141 0.644619 +0.452141 0.644619 +0.491506 0.647227 +0.491506 0.647227 +0.505339 0.647355 +0.505339 0.647355 +0.505265 0.645114 +0.505265 0.645114 +0.504936 0.642818 +0.504936 0.642818 +0.504335 0.640607 +0.504335 0.640607 +0.503472 0.638630 +0.503472 0.638630 +0.502396 0.637020 +0.502396 0.637020 +0.501178 0.635866 +0.501178 0.635866 +0.499902 0.635195 +0.499902 0.635195 +0.498648 0.634978 +0.498648 0.634978 +0.497385 0.635171 +0.497385 0.635171 +0.496086 0.635818 +0.496086 0.635818 +0.494826 0.636949 +0.494826 0.636949 +0.493691 0.638539 +0.493691 0.638539 +0.492757 0.640499 +0.492757 0.640499 +0.492075 0.642699 +0.492075 0.642699 +0.491663 0.644987 +0.491663 0.644987 +0.531028 0.647595 +0.531028 0.647595 +0.544861 0.647724 +0.544861 0.647724 +0.544786 0.645482 +0.544786 0.645482 +0.544458 0.643187 +0.544458 0.643187 +0.543857 0.640975 +0.542994 0.638998 +0.543857 0.640975 +0.542994 0.638998 +0.541918 0.637388 +0.541918 0.637388 +0.540700 0.636234 +0.540700 0.636234 +0.539424 0.635563 +0.539424 0.635563 +0.538170 0.635346 +0.538170 0.635346 +0.536907 0.635540 +0.536907 0.635540 +0.535608 0.636187 +0.535608 0.636187 +0.534348 0.637318 +0.534348 0.637318 +0.533213 0.638907 +0.533213 0.638907 +0.532279 0.640867 +0.532279 0.640867 +0.531597 0.643067 +0.531185 0.645355 +0.531597 0.643067 +0.531185 0.645355 +0.570550 0.647963 +0.570550 0.647963 +0.584308 0.645850 +0.584383 0.648092 +0.584383 0.648092 +0.584308 0.645850 +0.583980 0.643555 +0.583379 0.641343 +0.583980 0.643555 +0.583379 0.641343 +0.582516 0.639366 +0.582516 0.639366 +0.581440 0.637756 +0.581440 0.637756 +0.580222 0.636602 +0.580222 0.636602 +0.578946 0.635931 +0.578946 0.635931 +0.577692 0.635714 +0.577692 0.635714 +0.576429 0.635908 +0.576429 0.635908 +0.575130 0.636555 +0.575130 0.636555 +0.573870 0.637686 +0.573870 0.637686 +0.572735 0.639275 +0.572735 0.639275 +0.571801 0.641235 +0.571119 0.643435 +0.571801 0.641235 +0.571119 0.643435 +0.570707 0.645723 +0.570707 0.645723 +0.610072 0.648331 +0.610072 0.648331 +0.623905 0.648460 +0.623905 0.648460 +0.623830 0.646218 +0.623830 0.646218 +0.623502 0.643923 +0.623502 0.643923 +0.622901 0.641711 +0.622901 0.641711 +0.622038 0.639734 +0.622038 0.639734 +0.620962 0.638125 +0.620962 0.638125 +0.619744 0.636970 +0.618468 0.636299 +0.619744 0.636970 +0.618468 0.636299 +0.617213 0.636082 +0.617213 0.636082 +0.615951 0.636276 +0.615951 0.636276 +0.614652 0.636923 +0.614652 0.636923 +0.613392 0.638054 +0.613392 0.638054 +0.612257 0.639643 +0.612257 0.639643 +0.611323 0.641604 +0.611323 0.641604 +0.610641 0.643803 +0.610641 0.643803 +0.610228 0.646092 +0.610228 0.646092 +0.649594 0.648699 +0.649594 0.648699 +0.663427 0.648828 +0.663427 0.648828 +0.663352 0.646586 +0.663352 0.646586 +0.663024 0.644291 +0.663024 0.644291 +0.662422 0.642080 +0.662422 0.642080 +0.661560 0.640102 +0.661560 0.640102 +0.660483 0.638493 +0.660483 0.638493 +0.659266 0.637339 +0.659266 0.637339 +0.657990 0.636668 +0.657990 0.636668 +0.656735 0.636450 +0.655473 0.636644 +0.656735 0.636450 +0.655473 0.636644 +0.654174 0.637291 +0.654174 0.637291 +0.652914 0.638422 +0.652914 0.638422 +0.651779 0.640011 +0.651779 0.640011 +0.650845 0.641972 +0.650845 0.641972 +0.650162 0.644171 +0.649750 0.646460 +0.650162 0.644171 +0.649750 0.646460 +0.689116 0.649067 +0.689116 0.649067 +0.702949 0.649196 +0.702949 0.649196 +0.702874 0.646955 +0.702874 0.646955 +0.702546 0.644659 +0.702546 0.644659 +0.701944 0.642448 +0.701944 0.642448 +0.701082 0.640471 +0.701082 0.640471 +0.700005 0.638861 +0.700005 0.638861 +0.698787 0.637707 +0.698787 0.637707 +0.697512 0.637036 +0.697512 0.637036 +0.696257 0.636818 +0.696257 0.636818 +0.694995 0.637012 +0.694995 0.637012 +0.693696 0.637659 +0.693696 0.637659 +0.692436 0.638790 +0.692436 0.638790 +0.691301 0.640379 +0.691301 0.640379 +0.690366 0.642340 +0.690366 0.642340 +0.689684 0.644539 +0.689684 0.644539 +0.689273 0.646828 +0.689273 0.646828 +0.728638 0.649436 +0.728638 0.649436 +0.742471 0.649565 +0.742471 0.649565 +0.742396 0.647323 +0.742396 0.647323 +0.742068 0.645027 +0.742068 0.645027 +0.741466 0.642816 +0.741466 0.642816 +0.740604 0.640839 +0.740604 0.640839 +0.739527 0.639229 +0.739527 0.639229 +0.738309 0.638075 +0.738309 0.638075 +0.737034 0.637404 +0.737034 0.637404 +0.735779 0.637187 +0.735779 0.637187 +0.734517 0.637380 +0.734517 0.637380 +0.733217 0.638027 +0.733217 0.638027 +0.731958 0.639158 +0.731958 0.639158 +0.730823 0.640748 +0.730823 0.640748 +0.729888 0.642708 +0.729888 0.642708 +0.729206 0.644908 +0.728794 0.647196 +0.729206 0.644908 +0.728794 0.647196 +0.768160 0.649804 +0.768160 0.649804 +0.781992 0.649933 +0.781992 0.649933 +0.781918 0.647691 +0.781918 0.647691 +0.781590 0.645396 +0.780988 0.643184 +0.781590 0.645396 +0.780988 0.643184 +0.780126 0.641207 +0.780126 0.641207 +0.779049 0.639597 +0.779049 0.639597 +0.777831 0.638443 +0.777831 0.638443 +0.776556 0.637772 +0.776556 0.637772 +0.775301 0.637555 +0.775301 0.637555 +0.774039 0.637749 +0.774039 0.637749 +0.772740 0.638396 +0.772740 0.638396 +0.771480 0.639527 +0.770345 0.641116 +0.771480 0.639527 +0.770345 0.641116 +0.769410 0.643076 +0.769410 0.643076 +0.768728 0.645276 +0.768728 0.645276 +0.768316 0.647564 +0.768316 0.647564 +0.807682 0.650172 +0.807682 0.650172 +0.821514 0.650301 +0.821514 0.650301 +0.821440 0.648059 +0.821440 0.648059 +0.821112 0.645764 +0.820510 0.643552 +0.821112 0.645764 +0.820510 0.643552 +0.819648 0.641575 +0.819648 0.641575 +0.818571 0.639965 +0.818571 0.639965 +0.817353 0.638811 +0.817353 0.638811 +0.816078 0.638140 +0.816078 0.638140 +0.814823 0.637923 +0.814823 0.637923 +0.813561 0.638117 +0.813561 0.638117 +0.812261 0.638764 +0.812261 0.638764 +0.811002 0.639895 +0.811002 0.639895 +0.809867 0.641484 +0.809867 0.641484 +0.808932 0.643444 +0.808932 0.643444 +0.808250 0.645644 +0.808250 0.645644 +0.807838 0.647932 +0.807838 0.647932 +0.847204 0.650540 +0.847204 0.650540 +0.861036 0.650669 +0.861036 0.650669 +0.860962 0.648427 +0.860962 0.648427 +0.860634 0.646132 +0.860634 0.646132 +0.860032 0.643920 +0.860032 0.643920 +0.859170 0.641943 +0.859170 0.641943 +0.858093 0.640334 +0.858093 0.640334 +0.856875 0.639179 +0.856875 0.639179 +0.855600 0.638508 +0.855600 0.638508 +0.854345 0.638291 +0.854345 0.638291 +0.853083 0.638485 +0.853083 0.638485 +0.851783 0.639132 +0.851783 0.639132 +0.850524 0.640263 +0.850524 0.640263 +0.849388 0.641852 +0.849388 0.641852 +0.848454 0.643813 +0.848454 0.643813 +0.847772 0.646012 +0.847772 0.646012 +0.847360 0.648301 +0.847360 0.648301 +0.156209 0.615472 +0.156052 0.617711 +0.169885 0.617840 +0.169885 0.617840 +0.169810 0.615598 +0.169810 0.615598 +0.169482 0.613303 +0.169482 0.613303 +0.168881 0.611092 +0.168018 0.609114 +0.168881 0.611092 +0.168018 0.609114 +0.166941 0.607505 +0.166941 0.607505 +0.165723 0.606351 +0.165723 0.606351 +0.164448 0.605680 +0.164448 0.605680 +0.163194 0.605462 +0.163194 0.605462 +0.161931 0.605656 +0.161931 0.605656 +0.160632 0.606303 +0.159372 0.607434 +0.160632 0.606303 +0.159372 0.607434 +0.158237 0.609023 +0.157303 0.610984 +0.158237 0.609023 +0.157303 0.610984 +0.156621 0.613183 +0.156621 0.613183 +0.156209 0.615472 +0.156052 0.617711 +0.168846 0.668370 +0.168921 0.670612 +0.168921 0.670612 +0.168846 0.668370 +0.155244 0.668243 +0.155088 0.670483 +0.155088 0.670483 +0.155244 0.668243 +0.155656 0.665955 +0.156338 0.663755 +0.155656 0.665955 +0.156338 0.663755 +0.157273 0.661795 +0.157273 0.661795 +0.158408 0.660206 +0.158408 0.660206 +0.159668 0.659075 +0.159668 0.659075 +0.160967 0.658428 +0.160967 0.658428 +0.162229 0.658234 +0.162229 0.658234 +0.163484 0.658451 +0.163484 0.658451 +0.164759 0.659122 +0.164759 0.659122 +0.165977 0.660276 +0.165977 0.660276 +0.167054 0.661886 +0.167916 0.663863 +0.167054 0.661886 +0.167916 0.663863 +0.168518 0.666075 +0.168518 0.666075 +0.195730 0.615840 +0.195574 0.618079 +0.209407 0.618208 +0.209407 0.618208 +0.209332 0.615967 +0.209332 0.615967 +0.209004 0.613671 +0.208402 0.611460 +0.209004 0.613671 +0.208402 0.611460 +0.207540 0.609483 +0.207540 0.609483 +0.206463 0.607873 +0.206463 0.607873 +0.205245 0.606719 +0.205245 0.606719 +0.203970 0.606048 +0.203970 0.606048 +0.202715 0.605831 +0.202715 0.605831 +0.201453 0.606024 +0.201453 0.606024 +0.200154 0.606671 +0.200154 0.606671 +0.198894 0.607802 +0.198894 0.607802 +0.197759 0.609392 +0.196825 0.611352 +0.197759 0.609392 +0.196825 0.611352 +0.196142 0.613551 +0.196142 0.613551 +0.195730 0.615840 +0.195574 0.618079 +0.208442 0.670980 +0.208442 0.670980 +0.194766 0.668612 +0.194610 0.670851 +0.194610 0.670851 +0.195178 0.666323 +0.194766 0.668612 +0.195178 0.666323 +0.195860 0.664124 +0.196795 0.662163 +0.195860 0.664124 +0.196795 0.662163 +0.197930 0.660574 +0.197930 0.660574 +0.199189 0.659443 +0.199189 0.659443 +0.200489 0.658796 +0.200489 0.658796 +0.201751 0.658602 +0.203006 0.658819 +0.201751 0.658602 +0.203006 0.658819 +0.204281 0.659490 +0.204281 0.659490 +0.205499 0.660644 +0.205499 0.660644 +0.206576 0.662254 +0.206576 0.662254 +0.207438 0.664231 +0.207438 0.664231 +0.208040 0.666443 +0.208040 0.666443 +0.208368 0.668738 +0.208368 0.668738 +0.235252 0.616208 +0.235096 0.618448 +0.248929 0.618577 +0.248929 0.618577 +0.248854 0.616335 +0.248854 0.616335 +0.248526 0.614039 +0.248526 0.614039 +0.247924 0.611828 +0.247062 0.609851 +0.247924 0.611828 +0.247062 0.609851 +0.245985 0.608241 +0.245985 0.608241 +0.244767 0.607087 +0.244767 0.607087 +0.243492 0.606416 +0.243492 0.606416 +0.242237 0.606199 +0.242237 0.606199 +0.240975 0.606393 +0.240975 0.606393 +0.239676 0.607040 +0.238416 0.608171 +0.239676 0.607040 +0.238416 0.608171 +0.237281 0.609760 +0.236346 0.611720 +0.237281 0.609760 +0.236346 0.611720 +0.235664 0.613920 +0.235664 0.613920 +0.235252 0.616208 +0.235096 0.618448 +0.247964 0.671348 +0.247964 0.671348 +0.234288 0.668980 +0.234132 0.671219 +0.234132 0.671219 +0.234700 0.666691 +0.234288 0.668980 +0.234700 0.666691 +0.235382 0.664492 +0.235382 0.664492 +0.236317 0.662531 +0.236317 0.662531 +0.237452 0.660942 +0.237452 0.660942 +0.238711 0.659811 +0.238711 0.659811 +0.240011 0.659164 +0.240011 0.659164 +0.241273 0.658970 +0.241273 0.658970 +0.242528 0.659187 +0.242528 0.659187 +0.243803 0.659859 +0.243803 0.659859 +0.245021 0.661013 +0.245021 0.661013 +0.246098 0.662622 +0.246098 0.662622 +0.246960 0.664600 +0.246960 0.664600 +0.247562 0.666811 +0.247562 0.666811 +0.247890 0.669106 +0.247890 0.669106 +0.288451 0.618945 +0.288451 0.618945 +0.274618 0.618816 +0.274618 0.618816 +0.274774 0.616576 +0.274774 0.616576 +0.275186 0.614288 +0.275186 0.614288 +0.275868 0.612088 +0.275868 0.612088 +0.276803 0.610128 +0.276803 0.610128 +0.277938 0.608539 +0.277938 0.608539 +0.279198 0.607408 +0.279198 0.607408 +0.280497 0.606761 +0.280497 0.606761 +0.281759 0.606567 +0.281759 0.606567 +0.283014 0.606784 +0.283014 0.606784 +0.284289 0.607455 +0.284289 0.607455 +0.285507 0.608609 +0.285507 0.608609 +0.286584 0.610219 +0.286584 0.610219 +0.287446 0.612196 +0.287446 0.612196 +0.288048 0.614408 +0.288376 0.616703 +0.288048 0.614408 +0.288376 0.616703 +0.287084 0.667179 +0.287412 0.669475 +0.287486 0.671716 +0.287486 0.671716 +0.273810 0.669348 +0.273654 0.671587 +0.273654 0.671587 +0.273810 0.669348 +0.274222 0.667059 +0.274222 0.667059 +0.274904 0.664860 +0.274904 0.664860 +0.275839 0.662899 +0.276974 0.661310 +0.275839 0.662899 +0.276974 0.661310 +0.278233 0.660179 +0.278233 0.660179 +0.279533 0.659532 +0.280795 0.659338 +0.279533 0.659532 +0.282050 0.659556 +0.280795 0.659338 +0.282050 0.659556 +0.283325 0.660227 +0.283325 0.660227 +0.284543 0.661381 +0.284543 0.661381 +0.285620 0.662991 +0.285620 0.662991 +0.286482 0.664968 +0.287084 0.667179 +0.286482 0.664968 +0.287412 0.669475 +0.314140 0.619184 +0.314140 0.619184 +0.327973 0.619313 +0.327973 0.619313 +0.327898 0.617071 +0.327898 0.617071 +0.327570 0.614776 +0.327570 0.614776 +0.326968 0.612564 +0.326968 0.612564 +0.326106 0.610587 +0.326106 0.610587 +0.325029 0.608977 +0.323811 0.607823 +0.325029 0.608977 +0.323811 0.607823 +0.322536 0.607152 +0.322536 0.607152 +0.321281 0.606935 +0.321281 0.606935 +0.320019 0.607129 +0.320019 0.607129 +0.318720 0.607776 +0.318720 0.607776 +0.317460 0.608907 +0.317460 0.608907 +0.316325 0.610496 +0.316325 0.610496 +0.315390 0.612457 +0.315390 0.612457 +0.314708 0.614656 +0.314708 0.614656 +0.314296 0.616944 +0.314296 0.616944 +0.325142 0.663359 +0.326934 0.669843 +0.327008 0.672084 +0.327008 0.672084 +0.326934 0.669843 +0.326605 0.667547 +0.326605 0.667547 +0.326004 0.665336 +0.325142 0.663359 +0.326004 0.665336 +0.313176 0.671956 +0.313176 0.671956 +0.313332 0.669716 +0.313332 0.669716 +0.313744 0.667427 +0.314426 0.665228 +0.313744 0.667427 +0.314426 0.665228 +0.315360 0.663268 +0.315360 0.663268 +0.316496 0.661678 +0.316496 0.661678 +0.317755 0.660547 +0.317755 0.660547 +0.319055 0.659900 +0.319055 0.659900 +0.320317 0.659707 +0.320317 0.659707 +0.321572 0.659924 +0.321572 0.659924 +0.322847 0.660595 +0.324065 0.661749 +0.322847 0.660595 +0.324065 0.661749 +0.367494 0.619681 +0.367494 0.619681 +0.353662 0.619552 +0.353662 0.619552 +0.353818 0.617313 +0.353818 0.617313 +0.354230 0.615024 +0.354230 0.615024 +0.354912 0.612825 +0.354912 0.612825 +0.355847 0.610864 +0.355847 0.610864 +0.356982 0.609275 +0.356982 0.609275 +0.358241 0.608144 +0.358241 0.608144 +0.359541 0.607497 +0.359541 0.607497 +0.360803 0.607303 +0.360803 0.607303 +0.362058 0.607521 +0.362058 0.607521 +0.363333 0.608191 +0.364551 0.609346 +0.363333 0.608191 +0.364551 0.609346 +0.365628 0.610955 +0.365628 0.610955 +0.366490 0.612933 +0.366490 0.612933 +0.367092 0.615144 +0.367420 0.617439 +0.367092 0.615144 +0.367420 0.617439 +0.352698 0.672324 +0.352698 0.672324 +0.366456 0.670211 +0.366530 0.672453 +0.366530 0.672453 +0.366456 0.670211 +0.366127 0.667916 +0.365526 0.665704 +0.366127 0.667916 +0.364664 0.663727 +0.365526 0.665704 +0.363587 0.662117 +0.364664 0.663727 +0.363587 0.662117 +0.362369 0.660963 +0.361094 0.660292 +0.362369 0.660963 +0.361094 0.660292 +0.359839 0.660075 +0.359839 0.660075 +0.358577 0.660269 +0.358577 0.660269 +0.357277 0.660916 +0.357277 0.660916 +0.356017 0.662047 +0.356017 0.662047 +0.354882 0.663636 +0.354882 0.663636 +0.353948 0.665596 +0.353948 0.665596 +0.353266 0.667796 +0.353266 0.667796 +0.352854 0.670084 +0.352854 0.670084 +0.393184 0.619920 +0.393184 0.619920 +0.407016 0.620049 +0.407016 0.620049 +0.406942 0.617808 +0.406942 0.617808 +0.406614 0.615512 +0.406012 0.613301 +0.406614 0.615512 +0.406012 0.613301 +0.405150 0.611323 +0.405150 0.611323 +0.404073 0.609714 +0.404073 0.609714 +0.402855 0.608560 +0.402855 0.608560 +0.401580 0.607889 +0.401580 0.607889 +0.400325 0.607671 +0.400325 0.607671 +0.399063 0.607865 +0.399063 0.607865 +0.397763 0.608512 +0.397763 0.608512 +0.396504 0.609643 +0.395369 0.611232 +0.396504 0.609643 +0.395369 0.611232 +0.394434 0.613193 +0.394434 0.613193 +0.393752 0.615392 +0.393752 0.615392 +0.393340 0.617681 +0.393340 0.617681 +0.405048 0.666072 +0.406052 0.672821 +0.406052 0.672821 +0.405978 0.670579 +0.405978 0.670579 +0.405649 0.668284 +0.392219 0.672692 +0.392219 0.672692 +0.392376 0.670452 +0.392376 0.670452 +0.392788 0.668164 +0.393470 0.665964 +0.392788 0.668164 +0.393470 0.665964 +0.394404 0.664004 +0.394404 0.664004 +0.395539 0.662415 +0.395539 0.662415 +0.396799 0.661284 +0.396799 0.661284 +0.398099 0.660637 +0.399361 0.660443 +0.398099 0.660637 +0.399361 0.660443 +0.400616 0.660660 +0.400616 0.660660 +0.401891 0.661331 +0.401891 0.661331 +0.403109 0.662485 +0.403109 0.662485 +0.404185 0.664095 +0.404185 0.664095 +0.405048 0.666072 +0.405649 0.668284 +0.446538 0.620417 +0.446538 0.620417 +0.432706 0.620288 +0.432706 0.620288 +0.432862 0.618049 +0.432862 0.618049 +0.433274 0.615761 +0.433956 0.613561 +0.433274 0.615761 +0.433956 0.613561 +0.434891 0.611600 +0.434891 0.611600 +0.436026 0.610011 +0.436026 0.610011 +0.437285 0.608880 +0.437285 0.608880 +0.438585 0.608233 +0.439847 0.608039 +0.438585 0.608233 +0.439847 0.608039 +0.441102 0.608257 +0.441102 0.608257 +0.442377 0.608928 +0.442377 0.608928 +0.443595 0.610082 +0.443595 0.610082 +0.444672 0.611692 +0.444672 0.611692 +0.445534 0.613669 +0.445534 0.613669 +0.446136 0.615880 +0.446136 0.615880 +0.446464 0.618176 +0.446464 0.618176 +0.445171 0.668652 +0.445574 0.673189 +0.445574 0.673189 +0.445500 0.670947 +0.431741 0.673060 +0.431741 0.673060 +0.431898 0.670821 +0.431898 0.670821 +0.432310 0.668532 +0.432992 0.666333 +0.432310 0.668532 +0.432992 0.666333 +0.433926 0.664372 +0.433926 0.664372 +0.435061 0.662783 +0.435061 0.662783 +0.436321 0.661652 +0.437620 0.661005 +0.436321 0.661652 +0.437620 0.661005 +0.438883 0.660811 +0.438883 0.660811 +0.440137 0.661028 +0.440137 0.661028 +0.441413 0.661699 +0.441413 0.661699 +0.442631 0.662853 +0.442631 0.662853 +0.443707 0.664463 +0.443707 0.664463 +0.444570 0.666440 +0.444570 0.666440 +0.445171 0.668652 +0.445500 0.670947 +0.472228 0.620657 +0.472228 0.620657 +0.486060 0.620786 +0.486060 0.620786 +0.485986 0.618544 +0.485657 0.616248 +0.485986 0.618544 +0.485657 0.616248 +0.485056 0.614037 +0.485056 0.614037 +0.484194 0.612060 +0.484194 0.612060 +0.483117 0.610450 +0.483117 0.610450 +0.481899 0.609296 +0.481899 0.609296 +0.480624 0.608625 +0.480624 0.608625 +0.479369 0.608408 +0.479369 0.608408 +0.478107 0.608602 +0.478107 0.608602 +0.476807 0.609249 +0.476807 0.609249 +0.475548 0.610380 +0.474412 0.611969 +0.475548 0.610380 +0.474412 0.611969 +0.473478 0.613929 +0.473478 0.613929 +0.472796 0.616129 +0.472384 0.618417 +0.472796 0.616129 +0.472384 0.618417 +0.471263 0.673428 +0.471263 0.673428 +0.485021 0.671315 +0.485096 0.673557 +0.485096 0.673557 +0.485021 0.671315 +0.484693 0.669020 +0.484693 0.669020 +0.484092 0.666809 +0.484092 0.666809 +0.483229 0.664831 +0.483229 0.664831 +0.482153 0.663222 +0.482153 0.663222 +0.480935 0.662068 +0.480935 0.662068 +0.479659 0.661397 +0.479659 0.661397 +0.478405 0.661179 +0.478405 0.661179 +0.477142 0.661373 +0.477142 0.661373 +0.475843 0.662020 +0.475843 0.662020 +0.474583 0.663151 +0.473448 0.664740 +0.474583 0.663151 +0.473448 0.664740 +0.472514 0.666701 +0.472514 0.666701 +0.471832 0.668900 +0.471420 0.671189 +0.471832 0.668900 +0.471420 0.671189 +0.881279 0.624467 +0.881279 0.624467 +0.867447 0.624338 +0.867447 0.624338 +0.867603 0.622099 +0.867603 0.622099 +0.868015 0.619810 +0.868015 0.619810 +0.868697 0.617611 +0.868697 0.617611 +0.869632 0.615650 +0.869632 0.615650 +0.870767 0.614061 +0.870767 0.614061 +0.872026 0.612930 +0.872026 0.612930 +0.873326 0.612283 +0.873326 0.612283 +0.874588 0.612089 +0.874588 0.612089 +0.875843 0.612307 +0.875843 0.612307 +0.877118 0.612978 +0.877118 0.612978 +0.878336 0.614132 +0.878336 0.614132 +0.879413 0.615742 +0.879413 0.615742 +0.880275 0.617719 +0.880275 0.617719 +0.880877 0.619930 +0.880877 0.619930 +0.881205 0.622226 +0.881205 0.622226 +0.866483 0.677110 +0.866483 0.677110 +0.880315 0.677239 +0.880315 0.677239 +0.880241 0.674997 +0.880241 0.674997 +0.879912 0.672702 +0.879912 0.672702 +0.879311 0.670490 +0.879311 0.670490 +0.878449 0.668513 +0.878449 0.668513 +0.877372 0.666903 +0.877372 0.666903 +0.876154 0.665749 +0.876154 0.665749 +0.874879 0.665078 +0.874879 0.665078 +0.873624 0.664861 +0.873624 0.664861 +0.872362 0.665055 +0.872362 0.665055 +0.871062 0.665702 +0.871062 0.665702 +0.869802 0.666833 +0.869802 0.666833 +0.868667 0.668422 +0.867733 0.670382 +0.868667 0.668422 +0.867733 0.670382 +0.867051 0.672582 +0.867051 0.672582 +0.866639 0.674870 +0.866639 0.674870 +0.827925 0.623970 +0.827925 0.623970 +0.841758 0.624099 +0.841758 0.624099 +0.841683 0.621857 +0.841683 0.621857 +0.841355 0.619562 +0.841355 0.619562 +0.840753 0.617351 +0.840753 0.617351 +0.839891 0.615373 +0.839891 0.615373 +0.838814 0.613764 +0.838814 0.613764 +0.837596 0.612610 +0.837596 0.612610 +0.836321 0.611938 +0.836321 0.611938 +0.835066 0.611721 +0.835066 0.611721 +0.833804 0.611915 +0.833804 0.611915 +0.832505 0.612562 +0.832505 0.612562 +0.831245 0.613693 +0.831245 0.613693 +0.830110 0.615282 +0.830110 0.615282 +0.829175 0.617243 +0.829175 0.617243 +0.828493 0.619442 +0.828493 0.619442 +0.828081 0.621731 +0.828081 0.621731 +0.826961 0.676742 +0.826961 0.676742 +0.840793 0.676871 +0.840793 0.676871 +0.840719 0.674629 +0.840719 0.674629 +0.840390 0.672334 +0.840390 0.672334 +0.839789 0.670122 +0.838927 0.668145 +0.839789 0.670122 +0.838927 0.668145 +0.837850 0.666535 +0.837850 0.666535 +0.836632 0.665381 +0.836632 0.665381 +0.835357 0.664710 +0.835357 0.664710 +0.834102 0.664493 +0.834102 0.664493 +0.832840 0.664687 +0.832840 0.664687 +0.831540 0.665334 +0.830281 0.666465 +0.831540 0.665334 +0.830281 0.666465 +0.829145 0.668054 +0.828211 0.670014 +0.829145 0.668054 +0.827529 0.672214 +0.828211 0.670014 +0.827117 0.674502 +0.827529 0.672214 +0.827117 0.674502 +0.802161 0.621489 +0.802236 0.623731 +0.788403 0.623602 +0.788403 0.623602 +0.788559 0.621363 +0.788559 0.621363 +0.788971 0.619074 +0.788971 0.619074 +0.789653 0.616875 +0.789653 0.616875 +0.790588 0.614914 +0.790588 0.614914 +0.791723 0.613325 +0.791723 0.613325 +0.792983 0.612194 +0.792983 0.612194 +0.794282 0.611547 +0.794282 0.611547 +0.795544 0.611353 +0.795544 0.611353 +0.796799 0.611570 +0.796799 0.611570 +0.798074 0.612241 +0.798074 0.612241 +0.799292 0.613396 +0.799292 0.613396 +0.800369 0.615005 +0.800369 0.615005 +0.801231 0.616982 +0.801231 0.616982 +0.801833 0.619194 +0.801833 0.619194 +0.802161 0.621489 +0.802236 0.623731 +0.787439 0.676374 +0.787439 0.676374 +0.801271 0.676503 +0.801271 0.676503 +0.801197 0.674261 +0.801197 0.674261 +0.800869 0.671965 +0.800869 0.671965 +0.800267 0.669754 +0.800267 0.669754 +0.799405 0.667777 +0.799405 0.667777 +0.798328 0.666167 +0.798328 0.666167 +0.797110 0.665013 +0.797110 0.665013 +0.795835 0.664342 +0.795835 0.664342 +0.794580 0.664125 +0.794580 0.664125 +0.793318 0.664319 +0.793318 0.664319 +0.792018 0.664965 +0.792018 0.664965 +0.790759 0.666097 +0.790759 0.666097 +0.789623 0.667686 +0.788689 0.669646 +0.789623 0.667686 +0.788007 0.671846 +0.788689 0.669646 +0.787595 0.674134 +0.788007 0.671846 +0.787595 0.674134 +0.762714 0.623363 +0.762714 0.623363 +0.748881 0.623234 +0.748881 0.623234 +0.749038 0.620994 +0.749038 0.620994 +0.749449 0.618706 +0.749449 0.618706 +0.750132 0.616506 +0.750132 0.616506 +0.751066 0.614546 +0.752201 0.612957 +0.751066 0.614546 +0.752201 0.612957 +0.753461 0.611826 +0.753461 0.611826 +0.754760 0.611179 +0.754760 0.611179 +0.756022 0.610985 +0.756022 0.610985 +0.757277 0.611202 +0.757277 0.611202 +0.758552 0.611873 +0.759770 0.613027 +0.758552 0.611873 +0.759770 0.613027 +0.760847 0.614637 +0.760847 0.614637 +0.761709 0.616614 +0.761709 0.616614 +0.762311 0.618826 +0.762639 0.621121 +0.762311 0.618826 +0.762639 0.621121 +0.761750 0.676134 +0.761750 0.676134 +0.747917 0.676005 +0.747917 0.676005 +0.748073 0.673766 +0.748073 0.673766 +0.748485 0.671477 +0.748485 0.671477 +0.749167 0.669278 +0.749167 0.669278 +0.750102 0.667317 +0.750102 0.667317 +0.751237 0.665728 +0.751237 0.665728 +0.752496 0.664597 +0.752496 0.664597 +0.753796 0.663950 +0.753796 0.663950 +0.755058 0.663757 +0.756313 0.663974 +0.755058 0.663757 +0.756313 0.663974 +0.757588 0.664645 +0.758806 0.665799 +0.757588 0.664645 +0.758806 0.665799 +0.759883 0.667409 +0.759883 0.667409 +0.760745 0.669386 +0.760745 0.669386 +0.761347 0.671597 +0.761347 0.671597 +0.761675 0.673893 +0.761675 0.673893 +0.723117 0.620753 +0.723192 0.622995 +0.723192 0.622995 +0.723117 0.620753 +0.709359 0.622866 +0.709359 0.622866 +0.709515 0.620626 +0.709515 0.620626 +0.709928 0.618338 +0.709928 0.618338 +0.710610 0.616138 +0.711544 0.614178 +0.710610 0.616138 +0.711544 0.614178 +0.712679 0.612589 +0.712679 0.612589 +0.713939 0.611458 +0.713939 0.611458 +0.715238 0.610811 +0.715238 0.610811 +0.716501 0.610617 +0.716501 0.610617 +0.717755 0.610834 +0.717755 0.610834 +0.719030 0.611505 +0.719030 0.611505 +0.720248 0.612659 +0.720248 0.612659 +0.721325 0.614269 +0.721325 0.614269 +0.722188 0.616246 +0.722188 0.616246 +0.722789 0.618458 +0.722789 0.618458 +0.722228 0.675766 +0.722228 0.675766 +0.708395 0.675637 +0.708395 0.675637 +0.708551 0.673398 +0.708551 0.673398 +0.708963 0.671109 +0.708963 0.671109 +0.709645 0.668910 +0.709645 0.668910 +0.710580 0.666949 +0.711715 0.665360 +0.710580 0.666949 +0.711715 0.665360 +0.712974 0.664229 +0.712974 0.664229 +0.714274 0.663582 +0.714274 0.663582 +0.715536 0.663388 +0.715536 0.663388 +0.716791 0.663606 +0.718066 0.664277 +0.716791 0.663606 +0.719284 0.665431 +0.718066 0.664277 +0.719284 0.665431 +0.720361 0.667040 +0.720361 0.667040 +0.721223 0.669018 +0.721223 0.669018 +0.721825 0.671229 +0.722153 0.673524 +0.721825 0.671229 +0.722153 0.673524 +0.669837 0.622498 +0.669837 0.622498 +0.683670 0.622626 +0.683670 0.622626 +0.683595 0.620385 +0.683595 0.620385 +0.683267 0.618089 +0.683267 0.618089 +0.682666 0.615878 +0.682666 0.615878 +0.681803 0.613901 +0.681803 0.613901 +0.680727 0.612291 +0.680727 0.612291 +0.679509 0.611137 +0.679509 0.611137 +0.678233 0.610466 +0.678233 0.610466 +0.676978 0.610249 +0.676978 0.610249 +0.675716 0.610442 +0.675716 0.610442 +0.674417 0.611089 +0.674417 0.611089 +0.673157 0.612221 +0.673157 0.612221 +0.672022 0.613810 +0.672022 0.613810 +0.671088 0.615770 +0.670406 0.617970 +0.671088 0.615770 +0.670406 0.617970 +0.669994 0.620258 +0.669994 0.620258 +0.668873 0.675269 +0.668873 0.675269 +0.682706 0.675398 +0.682706 0.675398 +0.682631 0.673156 +0.682631 0.673156 +0.682303 0.670861 +0.682303 0.670861 +0.681701 0.668649 +0.680839 0.666672 +0.681701 0.668649 +0.680839 0.666672 +0.679762 0.665063 +0.679762 0.665063 +0.678544 0.663908 +0.677269 0.663238 +0.678544 0.663908 +0.677269 0.663238 +0.676014 0.663020 +0.674752 0.663214 +0.676014 0.663020 +0.674752 0.663214 +0.673452 0.663861 +0.673452 0.663861 +0.672193 0.664992 +0.672193 0.664992 +0.671058 0.666581 +0.670123 0.668542 +0.671058 0.666581 +0.670123 0.668542 +0.669441 0.670741 +0.669441 0.670741 +0.669029 0.673030 +0.669029 0.673030 +0.644073 0.620017 +0.644148 0.622258 +0.644148 0.622258 +0.644073 0.620017 +0.630315 0.622129 +0.630315 0.622129 +0.630472 0.619890 +0.630472 0.619890 +0.630884 0.617601 +0.630884 0.617601 +0.631566 0.615402 +0.632500 0.613441 +0.631566 0.615402 +0.632500 0.613441 +0.633635 0.611852 +0.633635 0.611852 +0.634895 0.610721 +0.634895 0.610721 +0.636194 0.610074 +0.636194 0.610074 +0.637457 0.609880 +0.637457 0.609880 +0.638711 0.610098 +0.638711 0.610098 +0.639987 0.610769 +0.639987 0.610769 +0.641204 0.611923 +0.641204 0.611923 +0.642281 0.613532 +0.642281 0.613532 +0.643144 0.615510 +0.643144 0.615510 +0.643745 0.617721 +0.643745 0.617721 +0.643109 0.672788 +0.643109 0.672788 +0.643184 0.675030 +0.643184 0.675030 +0.629351 0.674901 +0.629351 0.674901 +0.629507 0.672661 +0.629507 0.672661 +0.629919 0.670373 +0.629919 0.670373 +0.630602 0.668173 +0.630602 0.668173 +0.631536 0.666213 +0.631536 0.666213 +0.632671 0.664624 +0.632671 0.664624 +0.633931 0.663493 +0.633931 0.663493 +0.635230 0.662846 +0.636492 0.662652 +0.635230 0.662846 +0.637747 0.662869 +0.636492 0.662652 +0.637747 0.662869 +0.639022 0.663540 +0.639022 0.663540 +0.640240 0.664694 +0.640240 0.664694 +0.641317 0.666304 +0.641317 0.666304 +0.642179 0.668281 +0.642179 0.668281 +0.642781 0.670493 +0.642781 0.670493 +0.604223 0.617353 +0.604626 0.621890 +0.604626 0.621890 +0.604551 0.619648 +0.604551 0.619648 +0.604223 0.617353 +0.590793 0.621761 +0.590793 0.621761 +0.590950 0.619522 +0.590950 0.619522 +0.591362 0.617233 +0.591362 0.617233 +0.592044 0.615034 +0.592978 0.613073 +0.592044 0.615034 +0.592978 0.613073 +0.594113 0.611484 +0.594113 0.611484 +0.595373 0.610353 +0.595373 0.610353 +0.596672 0.609706 +0.596672 0.609706 +0.597935 0.609512 +0.597935 0.609512 +0.599189 0.609730 +0.599189 0.609730 +0.600465 0.610400 +0.600465 0.610400 +0.601683 0.611555 +0.601683 0.611555 +0.602759 0.613164 +0.603622 0.615141 +0.602759 0.613164 +0.603622 0.615141 +0.603259 0.670125 +0.603662 0.674662 +0.603662 0.674662 +0.603587 0.672420 +0.603587 0.672420 +0.603259 0.670125 +0.589985 0.672293 +0.589829 0.674533 +0.589829 0.674533 +0.589985 0.672293 +0.590397 0.670005 +0.590397 0.670005 +0.591080 0.667805 +0.591080 0.667805 +0.592014 0.665845 +0.592014 0.665845 +0.593149 0.664256 +0.593149 0.664256 +0.594409 0.663125 +0.594409 0.663125 +0.595708 0.662478 +0.595708 0.662478 +0.596970 0.662284 +0.596970 0.662284 +0.598225 0.662501 +0.598225 0.662501 +0.599501 0.663172 +0.600718 0.664326 +0.599501 0.663172 +0.600718 0.664326 +0.601795 0.665936 +0.602657 0.667913 +0.601795 0.665936 +0.602657 0.667913 +0.565104 0.621522 +0.565104 0.621522 +0.551271 0.621393 +0.551271 0.621393 +0.551428 0.619153 +0.551428 0.619153 +0.551840 0.616865 +0.551840 0.616865 +0.552522 0.614665 +0.552522 0.614665 +0.553456 0.612705 +0.553456 0.612705 +0.554591 0.611116 +0.554591 0.611116 +0.555851 0.609985 +0.555851 0.609985 +0.557150 0.609338 +0.558413 0.609144 +0.557150 0.609338 +0.558413 0.609144 +0.559667 0.609361 +0.559667 0.609361 +0.560943 0.610032 +0.560943 0.610032 +0.562161 0.611186 +0.562161 0.611186 +0.563237 0.612796 +0.563237 0.612796 +0.564100 0.614773 +0.564701 0.616985 +0.564100 0.614773 +0.564701 0.616985 +0.565030 0.619280 +0.565030 0.619280 +0.550307 0.674165 +0.550307 0.674165 +0.564140 0.674293 +0.564140 0.674293 +0.564065 0.672052 +0.564065 0.672052 +0.563737 0.669756 +0.563136 0.667545 +0.563737 0.669756 +0.563136 0.667545 +0.562273 0.665568 +0.562273 0.665568 +0.561197 0.663958 +0.561197 0.663958 +0.559979 0.662804 +0.559979 0.662804 +0.558703 0.662133 +0.558703 0.662133 +0.557449 0.661916 +0.557449 0.661916 +0.556186 0.662109 +0.556186 0.662109 +0.554887 0.662756 +0.554887 0.662756 +0.553627 0.663888 +0.553627 0.663888 +0.552492 0.665477 +0.552492 0.665477 +0.551558 0.667437 +0.551558 0.667437 +0.550876 0.669637 +0.550876 0.669637 +0.550463 0.671925 +0.550463 0.671925 +0.525582 0.621154 +0.525582 0.621154 +0.511750 0.621025 +0.511750 0.621025 +0.511906 0.618785 +0.511906 0.618785 +0.512318 0.616497 +0.513000 0.614297 +0.512318 0.616497 +0.513000 0.614297 +0.513934 0.612337 +0.513934 0.612337 +0.515069 0.610748 +0.515069 0.610748 +0.516329 0.609617 +0.516329 0.609617 +0.517628 0.608970 +0.518891 0.608776 +0.517628 0.608970 +0.518891 0.608776 +0.520146 0.608993 +0.520146 0.608993 +0.521421 0.609664 +0.521421 0.609664 +0.522639 0.610818 +0.522639 0.610818 +0.523715 0.612428 +0.523715 0.612428 +0.524578 0.614405 +0.524578 0.614405 +0.525179 0.616617 +0.525179 0.616617 +0.525508 0.618912 +0.525508 0.618912 +0.524618 0.673925 +0.524618 0.673925 +0.510785 0.673796 +0.510785 0.673796 +0.510942 0.671557 +0.510942 0.671557 +0.511354 0.669268 +0.512036 0.667069 +0.511354 0.669268 +0.512036 0.667069 +0.512970 0.665108 +0.512970 0.665108 +0.514105 0.663519 +0.514105 0.663519 +0.515365 0.662388 +0.515365 0.662388 +0.516664 0.661741 +0.516664 0.661741 +0.517927 0.661548 +0.517927 0.661548 +0.519181 0.661765 +0.519181 0.661765 +0.520457 0.662436 +0.521675 0.663590 +0.520457 0.662436 +0.521675 0.663590 +0.522751 0.665200 +0.522751 0.665200 +0.523614 0.667177 +0.523614 0.667177 +0.524215 0.669388 +0.524215 0.669388 +0.524543 0.671684 +0.524543 0.671684 +0.911371 0.600117 +0.909507 0.702142 +0.909507 0.702142 +0.911371 0.600117 +0.126861 0.592808 +0.911371 0.600117 +0.911371 0.600117 +0.126861 0.592808 +0.124996 0.694833 +0.126861 0.592808 +0.126861 0.592808 +0.124996 0.694833 +0.909507 0.702142 +0.124996 0.694833 +0.124996 0.694833 +0.909507 0.702142 +0.909507 0.702142 +0.880877 0.619930 +0.881205 0.622226 +0.881279 0.624467 +0.881123 0.626707 +0.880711 0.628995 +0.880029 0.631195 +0.859170 0.641943 +0.848454 0.643813 +0.819648 0.641575 +0.808932 0.643444 +0.780126 0.641207 +0.769410 0.643076 +0.740604 0.640839 +0.729888 0.642708 +0.701082 0.640471 +0.680839 0.666672 +0.670123 0.668542 +0.671704 0.631223 +0.661560 0.640102 +0.650845 0.641972 +0.622038 0.639734 +0.611323 0.641604 +0.603375 0.628618 +0.601795 0.665936 +0.591080 0.667805 +0.571801 0.641235 +0.542994 0.638998 +0.532279 0.640867 +0.503472 0.638630 +0.492757 0.640499 +0.463951 0.638261 +0.453235 0.640131 +0.424429 0.637893 +0.413713 0.639763 +0.384907 0.637525 +0.374191 0.639395 +0.366244 0.626409 +0.364664 0.663727 +0.353948 0.665596 +0.334669 0.639026 +0.305863 0.636789 +0.285620 0.662991 +0.274904 0.664860 +0.276485 0.627541 +0.266341 0.636421 +0.255625 0.638290 +0.226819 0.636052 +0.206576 0.662254 +0.195860 0.664124 +0.197441 0.626805 +0.187297 0.635684 +0.176582 0.637554 +0.168634 0.624568 +0.167054 0.661886 +0.177198 0.653007 +0.187913 0.651137 +0.216720 0.653375 +0.227435 0.651506 +0.235382 0.664492 +0.236963 0.627173 +0.247678 0.625304 +0.266957 0.651874 +0.295763 0.654111 +0.316006 0.627910 +0.326722 0.626040 +0.325142 0.663359 +0.335285 0.654480 +0.346001 0.652610 +0.374807 0.654848 +0.385523 0.652978 +0.393470 0.665964 +0.395050 0.628646 +0.405766 0.626777 +0.434572 0.629014 +0.445288 0.627145 +0.443707 0.664463 +0.453851 0.655584 +0.464567 0.653715 +0.472514 0.666701 +0.474094 0.629382 +0.484810 0.627513 +0.513616 0.629751 +0.524332 0.627881 +0.522751 0.665200 +0.532895 0.656320 +0.543610 0.654451 +0.551558 0.667437 +0.553138 0.630119 +0.563854 0.628249 +0.583132 0.654819 +0.611939 0.657057 +0.622654 0.655187 +0.630602 0.668173 +0.632182 0.630855 +0.642897 0.628986 +0.662176 0.655556 +0.690983 0.657793 +0.701698 0.655924 +0.709645 0.668910 +0.711226 0.631591 +0.721941 0.629722 +0.741220 0.656292 +0.749167 0.669278 +0.750748 0.631960 +0.761463 0.630090 +0.780742 0.656660 +0.788689 0.669646 +0.790270 0.632328 +0.800985 0.630458 +0.829792 0.632696 +0.840507 0.630827 +0.838927 0.668145 +0.849070 0.659266 +0.859786 0.657396 +0.867733 0.670382 +0.869313 0.633064 +0.879095 0.633155 +0.868451 0.631087 +0.841189 0.628627 +0.828929 0.630719 +0.801667 0.628259 +0.789407 0.630351 +0.762145 0.627891 +0.749885 0.629982 +0.722623 0.627522 +0.710363 0.629614 +0.690120 0.655816 +0.662858 0.653356 +0.662422 0.642080 +0.670841 0.629246 +0.643579 0.626786 +0.631320 0.628878 +0.604058 0.626418 +0.610641 0.643803 +0.611076 0.655079 +0.583815 0.652620 +0.564536 0.626050 +0.552276 0.628141 +0.525014 0.625682 +0.512754 0.627773 +0.485492 0.625313 +0.473232 0.627405 +0.445970 0.624945 +0.433710 0.627037 +0.406448 0.624577 +0.394188 0.626669 +0.366926 0.624209 +0.373509 0.641594 +0.373945 0.652870 +0.346683 0.650411 +0.327404 0.623841 +0.315144 0.625932 +0.294901 0.652134 +0.267639 0.649674 +0.267203 0.638398 +0.275622 0.625564 +0.248360 0.623104 +0.236100 0.625196 +0.215857 0.651398 +0.188595 0.648938 +0.188159 0.637662 +0.196578 0.624828 +0.169316 0.622368 +0.175899 0.639753 +0.176335 0.651030 +0.167916 0.663863 +0.195178 0.666323 +0.207438 0.664231 +0.234700 0.666691 +0.228117 0.649306 +0.227681 0.638030 +0.254943 0.640490 +0.274222 0.667059 +0.286482 0.664968 +0.306725 0.638766 +0.333987 0.641226 +0.334423 0.652502 +0.326004 0.665336 +0.353266 0.667796 +0.365526 0.665704 +0.392788 0.668164 +0.386205 0.650779 +0.385769 0.639502 +0.413031 0.641962 +0.425291 0.639871 +0.452553 0.642330 +0.452989 0.653607 +0.444570 0.666440 +0.471832 0.668900 +0.465249 0.651515 +0.464813 0.640239 +0.492075 0.642699 +0.504335 0.640607 +0.531597 0.643067 +0.532033 0.654343 +0.523614 0.667177 +0.550876 0.669637 +0.544293 0.652252 +0.543857 0.640975 +0.571119 0.643435 +0.590397 0.670005 +0.602657 0.667913 +0.629919 0.670373 +0.623336 0.652988 +0.622901 0.641711 +0.650162 0.644171 +0.669441 0.670741 +0.681701 0.668649 +0.708963 0.671109 +0.702380 0.653724 +0.701944 0.642448 +0.729206 0.644908 +0.748485 0.671477 +0.741902 0.654092 +0.741466 0.642816 +0.768728 0.645276 +0.788007 0.671846 +0.781424 0.654461 +0.780988 0.643184 +0.808250 0.645644 +0.820510 0.643552 +0.847772 0.646012 +0.848208 0.657289 +0.839789 0.670122 +0.867051 0.672582 +0.860468 0.655197 +0.860032 0.643920 +0.880275 0.617719 +0.858093 0.640334 +0.849388 0.641852 +0.818571 0.639965 +0.809867 0.641484 +0.779049 0.639597 +0.770345 0.641116 +0.739527 0.639229 +0.730823 0.640748 +0.700005 0.638861 +0.679762 0.665063 +0.671058 0.666581 +0.672780 0.632833 +0.660483 0.638493 +0.651779 0.640011 +0.620962 0.638125 +0.612257 0.639643 +0.602441 0.630578 +0.600718 0.664326 +0.592014 0.665845 +0.572735 0.639275 +0.541918 0.637388 +0.533213 0.638907 +0.502396 0.637020 +0.493691 0.638539 +0.462874 0.636652 +0.454169 0.638170 +0.423352 0.636284 +0.414647 0.637802 +0.383830 0.635915 +0.375126 0.637434 +0.365310 0.628369 +0.363587 0.662117 +0.354882 0.663636 +0.335604 0.637066 +0.304786 0.635179 +0.284543 0.661381 +0.275839 0.662899 +0.277561 0.629151 +0.265264 0.634811 +0.256560 0.636330 +0.225742 0.634443 +0.205499 0.660644 +0.196795 0.662163 +0.198517 0.628415 +0.186220 0.634075 +0.177516 0.635593 +0.167700 0.626528 +0.165977 0.660276 +0.178274 0.654617 +0.186979 0.653098 +0.217796 0.654985 +0.226501 0.653466 +0.236317 0.662531 +0.238039 0.628783 +0.246744 0.627264 +0.266023 0.653834 +0.296840 0.655721 +0.317083 0.629519 +0.325788 0.628001 +0.324065 0.661749 +0.336362 0.656089 +0.345067 0.654571 +0.375884 0.656457 +0.384588 0.654939 +0.394404 0.664004 +0.396127 0.630256 +0.404831 0.628737 +0.435649 0.630624 +0.444353 0.629105 +0.442631 0.662853 +0.454928 0.657194 +0.463632 0.655675 +0.473448 0.664740 +0.475171 0.630992 +0.483875 0.629474 +0.514693 0.631360 +0.523397 0.629842 +0.521675 0.663590 +0.533972 0.657930 +0.542676 0.656412 +0.552492 0.665477 +0.554215 0.631728 +0.562919 0.630210 +0.582198 0.656780 +0.613015 0.658667 +0.621720 0.657148 +0.631536 0.666213 +0.633259 0.632465 +0.641963 0.630946 +0.661242 0.657516 +0.692059 0.659403 +0.700764 0.657884 +0.710580 0.666949 +0.712302 0.633201 +0.721007 0.631683 +0.740286 0.658252 +0.750102 0.667317 +0.751824 0.633569 +0.760529 0.632051 +0.779808 0.658621 +0.789623 0.667686 +0.791346 0.633937 +0.800051 0.632419 +0.830868 0.634306 +0.839573 0.632787 +0.837850 0.666535 +0.850147 0.660875 +0.858851 0.659357 +0.868667 0.668422 +0.870390 0.634674 +0.877959 0.634744 +0.867849 0.628875 +0.841601 0.626339 +0.828328 0.628507 +0.802079 0.625970 +0.788806 0.628139 +0.762557 0.625602 +0.749284 0.627771 +0.723035 0.625234 +0.709762 0.627403 +0.689519 0.653604 +0.663270 0.651068 +0.663024 0.644291 +0.670240 0.627035 +0.643991 0.624498 +0.630718 0.626666 +0.604470 0.624130 +0.610228 0.646092 +0.610475 0.652868 +0.584226 0.650331 +0.564948 0.623761 +0.551674 0.625930 +0.525426 0.623393 +0.512152 0.625562 +0.485904 0.623025 +0.472630 0.625194 +0.446382 0.622657 +0.433108 0.624825 +0.406860 0.622289 +0.393586 0.624457 +0.367338 0.621921 +0.373097 0.643882 +0.373343 0.650659 +0.347095 0.648122 +0.327816 0.621552 +0.314543 0.623721 +0.294300 0.649923 +0.268051 0.647386 +0.267805 0.640609 +0.275021 0.623353 +0.248772 0.620816 +0.235499 0.622985 +0.215256 0.649186 +0.189007 0.646650 +0.188761 0.639873 +0.195977 0.622616 +0.169728 0.620080 +0.175487 0.642042 +0.175734 0.648818 +0.168518 0.666075 +0.194766 0.668612 +0.208040 0.666443 +0.234288 0.668980 +0.228529 0.647018 +0.228283 0.640241 +0.254531 0.642778 +0.273810 0.669348 +0.287084 0.667179 +0.307327 0.640978 +0.333575 0.643514 +0.333821 0.650291 +0.326605 0.667547 +0.352854 0.670084 +0.366127 0.667916 +0.392376 0.670452 +0.386617 0.648490 +0.386371 0.641714 +0.412619 0.644251 +0.425892 0.642082 +0.452141 0.644619 +0.452387 0.651395 +0.445171 0.668652 +0.471420 0.671189 +0.465661 0.649227 +0.465414 0.642450 +0.491663 0.644987 +0.504936 0.642818 +0.531185 0.645355 +0.531431 0.652132 +0.524215 0.669388 +0.550463 0.671925 +0.544705 0.649963 +0.544458 0.643187 +0.570707 0.645723 +0.589985 0.672293 +0.603259 0.670125 +0.629507 0.672661 +0.623748 0.650699 +0.623502 0.643923 +0.649750 0.646460 +0.669029 0.673030 +0.682303 0.670861 +0.708551 0.673398 +0.702792 0.651436 +0.702546 0.644659 +0.728794 0.647196 +0.748073 0.673766 +0.742314 0.651804 +0.742068 0.645027 +0.768316 0.647564 +0.787595 0.674134 +0.781836 0.652172 +0.781590 0.645396 +0.807838 0.647932 +0.821112 0.645764 +0.847360 0.648301 +0.847607 0.655077 +0.840390 0.672334 +0.866639 0.674870 +0.860880 0.652909 +0.860634 0.646132 +0.879413 0.615742 +0.856875 0.639179 +0.850524 0.640263 +0.817353 0.638811 +0.811002 0.639895 +0.777831 0.638443 +0.771480 0.639527 +0.738309 0.638075 +0.731958 0.639158 +0.698787 0.637707 +0.678544 0.663908 +0.672193 0.664992 +0.673998 0.633987 +0.659266 0.637339 +0.652914 0.638422 +0.619744 0.636970 +0.613392 0.638054 +0.601306 0.632167 +0.599501 0.663172 +0.593149 0.664256 +0.573870 0.637686 +0.540700 0.636234 +0.534348 0.637318 +0.501178 0.635866 +0.494826 0.636949 +0.461656 0.635498 +0.455304 0.636581 +0.422134 0.635130 +0.415783 0.636213 +0.382612 0.634761 +0.376261 0.635845 +0.364175 0.629958 +0.362369 0.660963 +0.356017 0.662047 +0.336739 0.635477 +0.303568 0.634025 +0.283325 0.660227 +0.276974 0.661310 +0.278779 0.630305 +0.264046 0.633657 +0.257695 0.634740 +0.224524 0.633289 +0.204281 0.659490 +0.197930 0.660574 +0.199735 0.629569 +0.185002 0.632920 +0.178651 0.634004 +0.166565 0.628117 +0.164759 0.659122 +0.179492 0.655771 +0.185844 0.654687 +0.219014 0.656139 +0.225366 0.655055 +0.237452 0.660942 +0.239257 0.629937 +0.245609 0.628853 +0.264888 0.655423 +0.298058 0.656875 +0.318301 0.630673 +0.324653 0.629590 +0.322847 0.660595 +0.337580 0.657243 +0.343931 0.656160 +0.377102 0.657612 +0.383453 0.656528 +0.395539 0.662415 +0.397345 0.631410 +0.403696 0.630326 +0.436867 0.631778 +0.443218 0.630694 +0.441413 0.661699 +0.456146 0.658348 +0.462497 0.657264 +0.474583 0.663151 +0.476389 0.632146 +0.482740 0.631063 +0.515911 0.632514 +0.522262 0.631431 +0.520457 0.662436 +0.535190 0.659084 +0.541541 0.658001 +0.553627 0.663888 +0.555433 0.632883 +0.561784 0.631799 +0.581063 0.658369 +0.614233 0.659821 +0.620585 0.658737 +0.632671 0.664624 +0.634476 0.633619 +0.640828 0.632535 +0.660107 0.659105 +0.693277 0.660557 +0.699629 0.659473 +0.711715 0.665360 +0.713520 0.634355 +0.719872 0.633272 +0.739151 0.659841 +0.751237 0.665728 +0.753042 0.634723 +0.759394 0.633640 +0.778673 0.660210 +0.790759 0.666097 +0.792564 0.635092 +0.798916 0.634008 +0.832086 0.635460 +0.838438 0.634376 +0.836632 0.665381 +0.851365 0.662030 +0.857716 0.660946 +0.869802 0.666833 +0.871608 0.635828 +0.876700 0.635875 +0.867521 0.626580 +0.841758 0.624099 +0.827999 0.626212 +0.802236 0.623731 +0.788478 0.625844 +0.762714 0.623363 +0.748955 0.625476 +0.723192 0.622995 +0.709434 0.625107 +0.689191 0.651309 +0.663427 0.648828 +0.663352 0.646586 +0.673452 0.663861 +0.675274 0.634658 +0.674752 0.663214 +0.676528 0.634875 +0.676014 0.663020 +0.677791 0.634681 +0.677269 0.663238 +0.679090 0.634034 +0.689116 0.649067 +0.680350 0.632903 +0.689273 0.646828 +0.681485 0.631314 +0.689684 0.644539 +0.682419 0.629354 +0.690366 0.642340 +0.683101 0.627154 +0.691301 0.640379 +0.683514 0.624866 +0.692436 0.638790 +0.669912 0.624739 +0.644148 0.622258 +0.630390 0.624371 +0.604626 0.621890 +0.610072 0.648331 +0.610147 0.650573 +0.600046 0.633298 +0.598225 0.662501 +0.598747 0.633945 +0.596970 0.662284 +0.597485 0.634139 +0.595708 0.662478 +0.596230 0.633922 +0.594409 0.663125 +0.584383 0.648092 +0.584308 0.645850 +0.594955 0.633251 +0.583980 0.643555 +0.593737 0.632097 +0.583379 0.641343 +0.592660 0.630487 +0.582516 0.639366 +0.591797 0.628510 +0.581440 0.637756 +0.591196 0.626298 +0.580222 0.636602 +0.565104 0.621522 +0.683670 0.622626 +0.590868 0.624003 +0.551346 0.623635 +0.525582 0.621154 +0.511824 0.623266 +0.486060 0.620786 +0.472302 0.622898 +0.446538 0.620417 +0.432780 0.622530 +0.407016 0.620049 +0.393258 0.622162 +0.367494 0.619681 +0.372941 0.646122 +0.373015 0.648364 +0.362915 0.631089 +0.361094 0.660292 +0.361615 0.631736 +0.359839 0.660075 +0.360353 0.631930 +0.358577 0.660269 +0.359098 0.631713 +0.357277 0.660916 +0.347251 0.645883 +0.347177 0.643641 +0.357823 0.631042 +0.346849 0.641346 +0.356605 0.629888 +0.346247 0.639134 +0.355528 0.628278 +0.345385 0.637157 +0.354666 0.626301 +0.344308 0.635547 +0.354065 0.624089 +0.343090 0.634393 +0.327973 0.619313 +0.314214 0.621426 +0.293971 0.647627 +0.268207 0.645146 +0.268133 0.642905 +0.278233 0.660179 +0.280055 0.630976 +0.279533 0.659532 +0.281309 0.631194 +0.280795 0.659338 +0.282572 0.631000 +0.282050 0.659556 +0.283871 0.630353 +0.293897 0.645386 +0.285131 0.629222 +0.294053 0.643146 +0.286266 0.627633 +0.294465 0.640858 +0.287200 0.625672 +0.295147 0.638658 +0.287882 0.623473 +0.296082 0.636698 +0.288294 0.621184 +0.297217 0.635109 +0.353736 0.621794 +0.288451 0.618945 +0.274692 0.621057 +0.248929 0.618577 +0.235171 0.620689 +0.214927 0.646891 +0.189164 0.644410 +0.189089 0.642168 +0.199189 0.659443 +0.201011 0.630240 +0.200489 0.658796 +0.202265 0.630457 +0.201751 0.658602 +0.203528 0.630263 +0.203006 0.658819 +0.204827 0.629616 +0.214853 0.644649 +0.206087 0.628485 +0.215009 0.642410 +0.207222 0.626896 +0.215421 0.640121 +0.208156 0.624936 +0.216103 0.637922 +0.208838 0.622736 +0.217038 0.635961 +0.209250 0.620448 +0.218173 0.634372 +0.195649 0.620321 +0.169885 0.617840 +0.209407 0.618208 +0.175331 0.644281 +0.175405 0.646523 +0.165305 0.629248 +0.163484 0.658451 +0.164006 0.629895 +0.162229 0.658234 +0.162744 0.630089 +0.160967 0.658428 +0.161489 0.629872 +0.159668 0.659075 +0.160213 0.629201 +0.158408 0.660206 +0.168846 0.668370 +0.194610 0.670851 +0.208368 0.668738 +0.234132 0.671219 +0.228686 0.644778 +0.228611 0.642537 +0.238711 0.659811 +0.240533 0.630608 +0.240011 0.659164 +0.241787 0.630825 +0.241273 0.658970 +0.243050 0.630632 +0.242528 0.659187 +0.244349 0.629985 +0.254375 0.645018 +0.254449 0.647259 +0.243803 0.659859 +0.254778 0.649554 +0.245021 0.661013 +0.255379 0.651766 +0.246098 0.662622 +0.256241 0.653743 +0.246960 0.664600 +0.257318 0.655353 +0.247562 0.666811 +0.258536 0.656507 +0.247890 0.669106 +0.273654 0.671587 +0.287412 0.669475 +0.307655 0.643273 +0.333419 0.645754 +0.333493 0.647996 +0.323393 0.630721 +0.321572 0.659924 +0.322093 0.631368 +0.320317 0.659707 +0.320831 0.631562 +0.319055 0.659900 +0.319577 0.631344 +0.317755 0.660547 +0.307729 0.645515 +0.316496 0.661678 +0.307573 0.647754 +0.315360 0.663268 +0.307161 0.650042 +0.314426 0.665228 +0.306479 0.652242 +0.313744 0.667427 +0.305545 0.654202 +0.313332 0.669716 +0.304409 0.655792 +0.326934 0.669843 +0.352698 0.672324 +0.366456 0.670211 +0.392219 0.672692 +0.313176 0.671956 +0.386773 0.646251 +0.386699 0.644009 +0.396799 0.661284 +0.398620 0.632081 +0.398099 0.660637 +0.399875 0.632298 +0.399361 0.660443 +0.401137 0.632104 +0.400616 0.660660 +0.402437 0.631457 +0.412463 0.646490 +0.412537 0.648732 +0.401891 0.661331 +0.412865 0.651027 +0.403109 0.662485 +0.413467 0.653239 +0.404185 0.664095 +0.414329 0.655216 +0.405048 0.666072 +0.415406 0.656826 +0.405649 0.668284 +0.416624 0.657980 +0.426221 0.644377 +0.451984 0.646858 +0.452059 0.649100 +0.441959 0.631826 +0.440137 0.661028 +0.440659 0.632472 +0.438883 0.660811 +0.439397 0.632666 +0.437620 0.661005 +0.438142 0.632449 +0.436321 0.661652 +0.426295 0.646619 +0.435061 0.662783 +0.426139 0.648859 +0.433926 0.664372 +0.425727 0.651147 +0.432992 0.666333 +0.425045 0.653347 +0.432310 0.668532 +0.424110 0.655307 +0.431898 0.670821 +0.422975 0.656896 +0.445500 0.670947 +0.471263 0.673428 +0.465817 0.646987 +0.405978 0.670579 +0.431741 0.673060 +0.465743 0.644746 +0.475843 0.662020 +0.477664 0.632817 +0.477142 0.661373 +0.478919 0.633034 +0.478405 0.661179 +0.480181 0.632841 +0.479659 0.661397 +0.481481 0.632194 +0.491506 0.647227 +0.491581 0.649468 +0.480935 0.662068 +0.491909 0.651764 +0.482153 0.663222 +0.492511 0.653975 +0.483229 0.664831 +0.493373 0.655952 +0.484092 0.666809 +0.494450 0.657562 +0.484693 0.669020 +0.495668 0.658716 +0.505265 0.645114 +0.531028 0.647595 +0.531103 0.649836 +0.521002 0.632562 +0.519181 0.661765 +0.519703 0.633209 +0.517927 0.661548 +0.518441 0.633403 +0.516664 0.661741 +0.517186 0.633185 +0.515365 0.662388 +0.505339 0.647355 +0.514105 0.663519 +0.505183 0.649595 +0.512970 0.665108 +0.504771 0.651883 +0.512036 0.667069 +0.504089 0.654083 +0.511354 0.669268 +0.503154 0.656043 +0.510942 0.671557 +0.502019 0.657632 +0.524543 0.671684 +0.550307 0.674165 +0.544861 0.647724 +0.485021 0.671315 +0.510785 0.673796 +0.544786 0.645482 +0.554887 0.662756 +0.556708 0.633554 +0.556186 0.662109 +0.557963 0.633771 +0.557449 0.661916 +0.559225 0.633577 +0.558703 0.662133 +0.560524 0.632930 +0.570550 0.647963 +0.570625 0.650205 +0.559979 0.662804 +0.570953 0.652500 +0.561197 0.663958 +0.571555 0.654711 +0.562273 0.665568 +0.572417 0.656689 +0.563136 0.667545 +0.573494 0.658298 +0.563737 0.669756 +0.574711 0.659452 +0.589829 0.674533 +0.603587 0.672420 +0.629351 0.674901 +0.623905 0.648460 +0.623830 0.646218 +0.633931 0.663493 +0.635752 0.634290 +0.635230 0.662846 +0.637007 0.634507 +0.636492 0.662652 +0.638269 0.634313 +0.637747 0.662869 +0.639568 0.633666 +0.649594 0.648699 +0.649669 0.650941 +0.639022 0.663540 +0.649997 0.653236 +0.640240 0.664694 +0.650598 0.655448 +0.641317 0.666304 +0.651461 0.657425 +0.642179 0.668281 +0.652537 0.659035 +0.642781 0.670493 +0.653755 0.660189 +0.564065 0.672052 +0.643109 0.672788 +0.668873 0.675269 +0.682631 0.673156 +0.708395 0.675637 +0.702949 0.649196 +0.702874 0.646955 +0.712974 0.664229 +0.714796 0.635026 +0.714274 0.663582 +0.716050 0.635243 +0.715536 0.663388 +0.717313 0.635050 +0.716791 0.663606 +0.718612 0.634403 +0.728638 0.649436 +0.728712 0.651677 +0.718066 0.664277 +0.729041 0.653973 +0.719284 0.665431 +0.729642 0.656184 +0.720361 0.667040 +0.730505 0.658161 +0.721223 0.669018 +0.731581 0.659771 +0.721825 0.671229 +0.732799 0.660925 +0.747917 0.676005 +0.742471 0.649565 +0.722153 0.673524 +0.742396 0.647323 +0.752496 0.664597 +0.754318 0.635394 +0.753796 0.663950 +0.755572 0.635612 +0.755058 0.663757 +0.756835 0.635418 +0.756313 0.663974 +0.758134 0.634771 +0.768160 0.649804 +0.768234 0.652045 +0.757588 0.664645 +0.768563 0.654341 +0.758806 0.665799 +0.769164 0.656552 +0.759883 0.667409 +0.770027 0.658529 +0.760745 0.669386 +0.771103 0.660139 +0.761347 0.671597 +0.772321 0.661293 +0.787439 0.676374 +0.781992 0.649933 +0.781918 0.647691 +0.792018 0.664965 +0.793839 0.635763 +0.793318 0.664319 +0.795094 0.635980 +0.794580 0.664125 +0.796357 0.635786 +0.795835 0.664342 +0.797656 0.635139 +0.807682 0.650172 +0.807756 0.652414 +0.797110 0.665013 +0.808084 0.654709 +0.798328 0.666167 +0.808686 0.656920 +0.799405 0.667777 +0.809548 0.658898 +0.800267 0.669754 +0.810625 0.660507 +0.800869 0.671965 +0.811843 0.661661 +0.821440 0.648059 +0.847204 0.650540 +0.847278 0.652782 +0.837178 0.635507 +0.835357 0.664710 +0.835878 0.636154 +0.834102 0.664493 +0.834616 0.636348 +0.832840 0.664687 +0.833361 0.636131 +0.831540 0.665334 +0.821514 0.650301 +0.830281 0.666465 +0.821358 0.652540 +0.829145 0.668054 +0.820946 0.654829 +0.828211 0.670014 +0.820264 0.657028 +0.827529 0.672214 +0.819330 0.658989 +0.827117 0.674502 +0.818195 0.660578 +0.761675 0.673893 +0.801197 0.674261 +0.826961 0.676742 +0.840719 0.674629 +0.866483 0.677110 +0.861036 0.650669 +0.860962 0.648427 +0.871062 0.665702 +0.872883 0.636499 +0.872362 0.665055 +0.874138 0.636716 +0.873624 0.664861 +0.875400 0.636522 +0.874879 0.665078 +0.876154 0.665749 +0.877372 0.666903 +0.878449 0.668513 +0.879311 0.670490 +0.879912 0.672702 +0.880241 0.674997 +0.880315 0.677239 +0.880159 0.679478 +0.879747 0.681767 +0.879065 0.683966 +0.855600 0.638508 +0.851783 0.639132 +0.816078 0.638140 +0.812261 0.638764 +0.776556 0.637772 +0.772740 0.638396 +0.737034 0.637404 +0.733217 0.638027 +0.697512 0.637036 +0.693696 0.637659 +0.657990 0.636668 +0.654174 0.637291 +0.618468 0.636299 +0.614652 0.636923 +0.578946 0.635931 +0.575130 0.636555 +0.539424 0.635563 +0.535608 0.636187 +0.499902 0.635195 +0.496086 0.635818 +0.460381 0.634827 +0.456564 0.635450 +0.420859 0.634459 +0.417042 0.635082 +0.381337 0.634090 +0.377520 0.634714 +0.341815 0.633722 +0.337998 0.634346 +0.302293 0.633354 +0.298477 0.633978 +0.262771 0.632986 +0.258955 0.633609 +0.223249 0.632618 +0.219433 0.633241 +0.183727 0.632249 +0.179911 0.632873 +0.180768 0.656442 +0.184584 0.655818 +0.220289 0.656810 +0.224106 0.656186 +0.259811 0.657178 +0.263628 0.656554 +0.299333 0.657546 +0.303150 0.656923 +0.338855 0.657914 +0.342672 0.657291 +0.378377 0.658282 +0.382194 0.657659 +0.417899 0.658651 +0.421716 0.658027 +0.457421 0.659019 +0.461237 0.658395 +0.496943 0.659387 +0.500759 0.658764 +0.536465 0.659755 +0.540281 0.659132 +0.575987 0.660123 +0.579803 0.659500 +0.615509 0.660492 +0.619325 0.659868 +0.655031 0.660860 +0.658847 0.660236 +0.694553 0.661228 +0.698369 0.660604 +0.734074 0.661596 +0.737891 0.660972 +0.773596 0.661964 +0.777413 0.661341 +0.813118 0.662332 +0.816935 0.661709 +0.852640 0.662701 +0.856457 0.662077 +0.878130 0.685927 +0.878336 0.614132 +0.867447 0.624338 +0.841683 0.621857 +0.827925 0.623970 +0.802161 0.621489 +0.788403 0.623602 +0.762639 0.621121 +0.748881 0.623234 +0.723117 0.620753 +0.709359 0.622866 +0.683595 0.620385 +0.669837 0.622498 +0.644073 0.620017 +0.630315 0.622129 +0.604551 0.619648 +0.590793 0.621761 +0.565030 0.619280 +0.551271 0.621393 +0.525508 0.618912 +0.511750 0.621025 +0.485986 0.618544 +0.472228 0.620657 +0.446464 0.618176 +0.432706 0.620288 +0.406942 0.617808 +0.393184 0.619920 +0.367420 0.617439 +0.353662 0.619552 +0.327898 0.617071 +0.314140 0.619184 +0.288376 0.616703 +0.274618 0.618816 +0.248854 0.616335 +0.235096 0.618448 +0.209332 0.615967 +0.195574 0.618079 +0.169810 0.615598 +0.158995 0.628047 +0.157273 0.661795 +0.168921 0.670612 +0.194684 0.673093 +0.208442 0.670980 +0.234206 0.673461 +0.247964 0.671348 +0.273728 0.673829 +0.287486 0.671716 +0.313250 0.674197 +0.327008 0.672084 +0.352772 0.674565 +0.366530 0.672453 +0.392294 0.674934 +0.406052 0.672821 +0.431816 0.675302 +0.445574 0.673189 +0.471338 0.675670 +0.485096 0.673557 +0.510860 0.676038 +0.524618 0.673925 +0.550382 0.676406 +0.564140 0.674293 +0.589904 0.676774 +0.603662 0.674662 +0.629426 0.677143 +0.643184 0.675030 +0.668947 0.677511 +0.682706 0.675398 +0.708469 0.677879 +0.722228 0.675766 +0.747991 0.678247 +0.761750 0.676134 +0.787513 0.678615 +0.801271 0.676503 +0.827035 0.678983 +0.840793 0.676871 +0.866557 0.679352 +0.854345 0.638291 +0.853083 0.638485 +0.867603 0.622099 +0.841355 0.619562 +0.868015 0.619810 +0.840753 0.617351 +0.868697 0.617611 +0.839891 0.615373 +0.814823 0.637923 +0.813561 0.638117 +0.828081 0.621731 +0.801833 0.619194 +0.828493 0.619442 +0.801231 0.616982 +0.829175 0.617243 +0.800369 0.615005 +0.775301 0.637555 +0.774039 0.637749 +0.788559 0.621363 +0.762311 0.618826 +0.788971 0.619074 +0.761709 0.616614 +0.789653 0.616875 +0.760847 0.614637 +0.735779 0.637187 +0.734517 0.637380 +0.749038 0.620994 +0.722789 0.618458 +0.749449 0.618706 +0.722188 0.616246 +0.750132 0.616506 +0.721325 0.614269 +0.696257 0.636818 +0.694995 0.637012 +0.709515 0.620626 +0.683267 0.618089 +0.709928 0.618338 +0.682666 0.615878 +0.710610 0.616138 +0.681803 0.613901 +0.656735 0.636450 +0.655473 0.636644 +0.669994 0.620258 +0.643745 0.617721 +0.670406 0.617970 +0.643144 0.615510 +0.671088 0.615770 +0.642281 0.613532 +0.617213 0.636082 +0.615951 0.636276 +0.630472 0.619890 +0.604223 0.617353 +0.630884 0.617601 +0.603622 0.615141 +0.631566 0.615402 +0.602759 0.613164 +0.577692 0.635714 +0.576429 0.635908 +0.590950 0.619522 +0.564701 0.616985 +0.591362 0.617233 +0.564100 0.614773 +0.592044 0.615034 +0.563237 0.612796 +0.538170 0.635346 +0.536907 0.635540 +0.551428 0.619153 +0.525179 0.616617 +0.551840 0.616865 +0.524578 0.614405 +0.552522 0.614665 +0.523715 0.612428 +0.498648 0.634978 +0.497385 0.635171 +0.511906 0.618785 +0.485657 0.616248 +0.512318 0.616497 +0.485056 0.614037 +0.513000 0.614297 +0.484194 0.612060 +0.459126 0.634609 +0.457864 0.634803 +0.472384 0.618417 +0.446136 0.615880 +0.472796 0.616129 +0.445534 0.613669 +0.473478 0.613929 +0.444672 0.611692 +0.419604 0.634241 +0.418342 0.634435 +0.432862 0.618049 +0.406614 0.615512 +0.433274 0.615761 +0.406012 0.613301 +0.433956 0.613561 +0.405150 0.611323 +0.380082 0.633873 +0.378820 0.634067 +0.393340 0.617681 +0.367092 0.615144 +0.393752 0.615392 +0.366490 0.612933 +0.394434 0.613193 +0.365628 0.610955 +0.340560 0.633505 +0.339298 0.633699 +0.353818 0.617313 +0.327570 0.614776 +0.354230 0.615024 +0.326968 0.612564 +0.354912 0.612825 +0.326106 0.610587 +0.301038 0.633137 +0.299776 0.633331 +0.314296 0.616944 +0.288048 0.614408 +0.314708 0.614656 +0.287446 0.612196 +0.315390 0.612457 +0.286584 0.610219 +0.261516 0.632769 +0.260254 0.632962 +0.274774 0.616576 +0.248526 0.614039 +0.275186 0.614288 +0.247924 0.611828 +0.275868 0.612088 +0.247062 0.609851 +0.221994 0.632400 +0.220732 0.632594 +0.235252 0.616208 +0.209004 0.613671 +0.235664 0.613920 +0.208402 0.611460 +0.236346 0.611720 +0.207540 0.609483 +0.182472 0.632032 +0.181210 0.632226 +0.195730 0.615840 +0.169482 0.613303 +0.196142 0.613551 +0.168881 0.611092 +0.196825 0.611352 +0.168018 0.609114 +0.182022 0.656659 +0.183285 0.656465 +0.168764 0.672851 +0.195013 0.675388 +0.168352 0.675140 +0.195614 0.677600 +0.167670 0.677339 +0.196476 0.679577 +0.221544 0.657027 +0.222807 0.656833 +0.208286 0.673219 +0.234535 0.675756 +0.207874 0.675508 +0.235136 0.677968 +0.207192 0.677707 +0.235998 0.679945 +0.261066 0.657395 +0.262328 0.657201 +0.247808 0.673588 +0.274057 0.676124 +0.247396 0.675876 +0.274658 0.678336 +0.246714 0.678076 +0.275520 0.680313 +0.300588 0.657763 +0.301850 0.657570 +0.287330 0.673956 +0.313578 0.676493 +0.286918 0.676244 +0.314180 0.678704 +0.286236 0.678444 +0.315042 0.680681 +0.340110 0.658132 +0.341372 0.657938 +0.326852 0.674324 +0.353100 0.676861 +0.326440 0.676612 +0.353702 0.679072 +0.325758 0.678812 +0.354564 0.681049 +0.379632 0.658500 +0.380894 0.658306 +0.366374 0.674692 +0.392622 0.677229 +0.365962 0.676981 +0.393224 0.679440 +0.365280 0.679180 +0.394086 0.681418 +0.419154 0.658868 +0.420416 0.658674 +0.405896 0.675060 +0.432144 0.677597 +0.405484 0.677349 +0.432746 0.679808 +0.404802 0.679548 +0.433608 0.681786 +0.458676 0.659236 +0.459938 0.659042 +0.445418 0.675428 +0.471666 0.677965 +0.445006 0.677717 +0.472268 0.680177 +0.444324 0.679916 +0.473130 0.682154 +0.498198 0.659604 +0.499460 0.659410 +0.484940 0.675797 +0.511188 0.678333 +0.484528 0.678085 +0.511790 0.680545 +0.483846 0.680285 +0.512652 0.682522 +0.537720 0.659972 +0.538982 0.659779 +0.524462 0.676165 +0.550710 0.678702 +0.524049 0.678453 +0.551311 0.680913 +0.523367 0.680653 +0.552174 0.682890 +0.577242 0.660341 +0.578504 0.660147 +0.563983 0.676533 +0.590232 0.679070 +0.563571 0.678821 +0.590833 0.681281 +0.562889 0.681021 +0.591696 0.683258 +0.616763 0.660709 +0.618026 0.660515 +0.603505 0.676901 +0.629754 0.679438 +0.603093 0.679190 +0.630355 0.681649 +0.602411 0.681389 +0.631218 0.683627 +0.656285 0.661077 +0.657548 0.660883 +0.643027 0.677269 +0.669276 0.679806 +0.642615 0.679558 +0.669877 0.682018 +0.641933 0.681757 +0.670740 0.683995 +0.695807 0.661445 +0.697070 0.661251 +0.682549 0.677637 +0.708798 0.680174 +0.682137 0.679926 +0.709399 0.682386 +0.681455 0.682125 +0.710261 0.684363 +0.735329 0.661813 +0.736592 0.661619 +0.722071 0.678006 +0.748320 0.680542 +0.721659 0.680294 +0.748921 0.682754 +0.720977 0.682494 +0.749783 0.684731 +0.774851 0.662182 +0.776113 0.661988 +0.761593 0.678374 +0.787841 0.680911 +0.761181 0.680662 +0.788443 0.683122 +0.760499 0.682862 +0.789305 0.685099 +0.814373 0.662550 +0.815635 0.662356 +0.801115 0.678742 +0.827363 0.681279 +0.800703 0.681030 +0.827965 0.683490 +0.800021 0.683230 +0.828827 0.685468 +0.853895 0.662918 +0.855157 0.662724 +0.840637 0.679110 +0.866885 0.681647 +0.840225 0.681399 +0.867487 0.683858 +0.839543 0.683598 +0.868349 0.685836 +0.876995 0.687516 +0.877118 0.612978 +0.869632 0.615650 +0.838814 0.613764 +0.830110 0.615282 +0.799292 0.613396 +0.790588 0.614914 +0.759770 0.613027 +0.751066 0.614546 +0.720248 0.612659 +0.711544 0.614178 +0.680727 0.612291 +0.672022 0.613810 +0.641204 0.611923 +0.632500 0.613441 +0.601683 0.611555 +0.592978 0.613073 +0.562161 0.611186 +0.553456 0.612705 +0.522639 0.610818 +0.513934 0.612337 +0.483117 0.610450 +0.474412 0.611969 +0.443595 0.610082 +0.434891 0.611600 +0.404073 0.609714 +0.395369 0.611232 +0.364551 0.609346 +0.355847 0.610864 +0.325029 0.608977 +0.316325 0.610496 +0.285507 0.608609 +0.276803 0.610128 +0.245985 0.608241 +0.237281 0.609760 +0.206463 0.607873 +0.197759 0.609392 +0.166941 0.607505 +0.157919 0.626437 +0.156338 0.663755 +0.166736 0.679300 +0.197553 0.681186 +0.206258 0.679668 +0.237075 0.681555 +0.245780 0.680036 +0.276597 0.681923 +0.285302 0.680404 +0.316119 0.682291 +0.324823 0.680772 +0.355641 0.682659 +0.364345 0.681141 +0.395163 0.683027 +0.403867 0.681509 +0.434685 0.683396 +0.443389 0.681877 +0.474207 0.683764 +0.482911 0.682245 +0.513729 0.684132 +0.522433 0.682613 +0.553251 0.684500 +0.561955 0.682981 +0.592772 0.684868 +0.601477 0.683350 +0.632294 0.685236 +0.640999 0.683718 +0.671816 0.685604 +0.680521 0.684086 +0.711338 0.685973 +0.720043 0.684454 +0.750860 0.686341 +0.759565 0.684822 +0.790382 0.686709 +0.799086 0.685190 +0.829904 0.687077 +0.838608 0.685559 +0.869426 0.687445 +0.875736 0.688647 +0.875843 0.612307 +0.870767 0.614061 +0.837596 0.612610 +0.831245 0.613693 +0.798074 0.612241 +0.791723 0.613325 +0.758552 0.611873 +0.752201 0.612957 +0.719030 0.611505 +0.712679 0.612589 +0.679509 0.611137 +0.673157 0.612221 +0.639987 0.610769 +0.633635 0.611852 +0.600465 0.610400 +0.594113 0.611484 +0.560943 0.610032 +0.554591 0.611116 +0.521421 0.609664 +0.515069 0.610748 +0.481899 0.609296 +0.475548 0.610380 +0.442377 0.608928 +0.436026 0.610011 +0.402855 0.608560 +0.396504 0.609643 +0.363333 0.608191 +0.356982 0.609275 +0.323811 0.607823 +0.317460 0.608907 +0.284289 0.607455 +0.277938 0.608539 +0.244767 0.607087 +0.238416 0.608171 +0.205245 0.606719 +0.198894 0.607802 +0.165723 0.606351 +0.157056 0.624460 +0.155656 0.665955 +0.165601 0.680889 +0.198771 0.682341 +0.205122 0.681257 +0.238293 0.682709 +0.244644 0.681625 +0.277815 0.683077 +0.284166 0.681993 +0.317337 0.683445 +0.323688 0.682361 +0.356859 0.683813 +0.363210 0.682730 +0.396381 0.684181 +0.402732 0.683098 +0.435903 0.684550 +0.442254 0.683466 +0.475425 0.684918 +0.481776 0.683834 +0.514946 0.685286 +0.521298 0.684202 +0.554469 0.685654 +0.560820 0.684570 +0.593990 0.686022 +0.600342 0.684939 +0.633512 0.686390 +0.639864 0.685307 +0.673034 0.686759 +0.679386 0.685675 +0.712556 0.687127 +0.718907 0.686043 +0.752078 0.687495 +0.758430 0.686411 +0.791600 0.687863 +0.797951 0.686780 +0.831122 0.688231 +0.837473 0.687148 +0.870644 0.688599 +0.872026 0.612930 +0.832505 0.612562 +0.792983 0.612194 +0.753461 0.611826 +0.713939 0.611458 +0.836321 0.611938 +0.796799 0.611570 +0.757277 0.611202 +0.717755 0.610834 +0.678233 0.610466 +0.674417 0.611089 +0.634895 0.610721 +0.595373 0.610353 +0.638711 0.610098 +0.599189 0.609730 +0.559667 0.609361 +0.555851 0.609985 +0.516329 0.609617 +0.476807 0.609249 +0.437285 0.608880 +0.520146 0.608993 +0.480624 0.608625 +0.441102 0.608257 +0.401580 0.607889 +0.397763 0.608512 +0.358241 0.608144 +0.318720 0.607776 +0.362058 0.607521 +0.322536 0.607152 +0.283014 0.606784 +0.279198 0.607408 +0.239676 0.607040 +0.200154 0.606671 +0.156455 0.622248 +0.243492 0.606416 +0.203970 0.606048 +0.164448 0.605680 +0.155244 0.668243 +0.164341 0.682020 +0.203863 0.682388 +0.243385 0.682756 +0.200046 0.683011 +0.239568 0.683380 +0.279090 0.683748 +0.282907 0.683124 +0.322429 0.683492 +0.361951 0.683861 +0.401472 0.684229 +0.318612 0.684116 +0.358134 0.684484 +0.397656 0.684852 +0.437178 0.685221 +0.440994 0.684597 +0.480516 0.684965 +0.520038 0.685333 +0.476700 0.685589 +0.516222 0.685957 +0.555744 0.686325 +0.559560 0.685702 +0.599082 0.686070 +0.638604 0.686438 +0.678126 0.686806 +0.595266 0.686693 +0.634788 0.687061 +0.674309 0.687430 +0.713831 0.687798 +0.717648 0.687174 +0.757170 0.687542 +0.796692 0.687911 +0.753353 0.688166 +0.792875 0.688534 +0.832397 0.688902 +0.836214 0.688279 +0.871919 0.689270 +0.874436 0.689294 +0.124996 0.694833 +0.873174 0.689488 +0.874588 0.612089 +0.911371 0.600117 +0.873326 0.612283 +0.835066 0.611721 +0.833804 0.611915 +0.795544 0.611353 +0.794282 0.611547 +0.756022 0.610985 +0.754760 0.611179 +0.716501 0.610617 +0.715238 0.610811 +0.676978 0.610249 +0.675716 0.610442 +0.637457 0.609880 +0.636194 0.610074 +0.597935 0.609512 +0.596672 0.609706 +0.558413 0.609144 +0.557150 0.609338 +0.518891 0.608776 +0.517628 0.608970 +0.479369 0.608408 +0.478107 0.608602 +0.439847 0.608039 +0.438585 0.608233 +0.400325 0.607671 +0.399063 0.607865 +0.360803 0.607303 +0.359541 0.607497 +0.321281 0.606935 +0.320019 0.607129 +0.281759 0.606567 +0.280497 0.606761 +0.242237 0.606199 +0.240975 0.606393 +0.202715 0.605831 +0.201453 0.606024 +0.163194 0.605462 +0.161931 0.605656 +0.160632 0.606303 +0.159372 0.607434 +0.158237 0.609023 +0.157303 0.610984 +0.126861 0.592808 +0.156621 0.613183 +0.156209 0.615472 +0.156052 0.617711 +0.156127 0.619953 +0.155088 0.670483 +0.155162 0.672724 +0.155491 0.675020 +0.156092 0.677231 +0.156955 0.679209 +0.158031 0.680818 +0.159249 0.681972 +0.160524 0.682643 +0.161779 0.682861 +0.163042 0.682667 +0.201301 0.683229 +0.202563 0.683035 +0.240823 0.683597 +0.242085 0.683403 +0.281607 0.683771 +0.321129 0.684140 +0.360651 0.684508 +0.400173 0.684876 +0.280345 0.683965 +0.319867 0.684333 +0.359389 0.684702 +0.398911 0.685070 +0.438433 0.685438 +0.439695 0.685244 +0.479217 0.685612 +0.518739 0.685980 +0.477955 0.685806 +0.517477 0.686174 +0.556998 0.686542 +0.558261 0.686349 +0.597783 0.686717 +0.637305 0.687085 +0.676827 0.687453 +0.596520 0.686911 +0.636042 0.687279 +0.675564 0.687647 +0.715086 0.688015 +0.716348 0.687821 +0.755870 0.688189 +0.795392 0.688558 +0.754608 0.688383 +0.794130 0.688751 +0.833652 0.689120 +0.834914 0.688926 +0.911371 0.600117 +0.881205 0.622226 +0.881279 0.624467 +0.881123 0.626707 +0.880711 0.628995 +0.880029 0.631195 +0.879095 0.633155 +0.868451 0.631087 +0.868667 0.668422 +0.858851 0.659357 +0.848208 0.657289 +0.839789 0.670122 +0.839573 0.632787 +0.828929 0.630719 +0.800051 0.632419 +0.789407 0.630351 +0.789623 0.667686 +0.779808 0.658621 +0.760529 0.632051 +0.749885 0.629982 +0.750102 0.667317 +0.740286 0.658252 +0.721007 0.631683 +0.710363 0.629614 +0.710580 0.666949 +0.700764 0.657884 +0.681485 0.631314 +0.670841 0.629246 +0.671058 0.666581 +0.661242 0.657516 +0.641963 0.630946 +0.631320 0.628878 +0.631536 0.666213 +0.621720 0.657148 +0.611076 0.655079 +0.602657 0.667913 +0.602441 0.630578 +0.591797 0.628510 +0.571555 0.654711 +0.542676 0.656412 +0.532033 0.654343 +0.503154 0.656043 +0.492511 0.653975 +0.484092 0.666809 +0.483875 0.629474 +0.473232 0.627405 +0.452989 0.653607 +0.424110 0.655307 +0.413467 0.653239 +0.384588 0.654939 +0.365310 0.628369 +0.354666 0.626301 +0.354882 0.663636 +0.345067 0.654571 +0.334423 0.652502 +0.326004 0.665336 +0.325788 0.628001 +0.315144 0.625932 +0.286266 0.627633 +0.275622 0.625564 +0.275839 0.662899 +0.266023 0.653834 +0.246744 0.627264 +0.236100 0.625196 +0.236317 0.662531 +0.226501 0.653466 +0.207222 0.626896 +0.196578 0.624828 +0.196795 0.662163 +0.186979 0.653098 +0.176335 0.651030 +0.167916 0.663863 +0.167700 0.626528 +0.177516 0.635593 +0.188159 0.637662 +0.217038 0.635961 +0.227681 0.638030 +0.256560 0.636330 +0.267203 0.638398 +0.296082 0.636698 +0.306725 0.638766 +0.335604 0.637066 +0.346247 0.639134 +0.375126 0.637434 +0.385769 0.639502 +0.394188 0.626669 +0.394404 0.664004 +0.405048 0.666072 +0.433926 0.664372 +0.444570 0.666440 +0.444353 0.629105 +0.454169 0.638170 +0.464813 0.640239 +0.493691 0.638539 +0.512970 0.665108 +0.523614 0.667177 +0.523397 0.629842 +0.533213 0.638907 +0.543857 0.640975 +0.552276 0.628141 +0.552492 0.665477 +0.563136 0.667545 +0.583379 0.641343 +0.612257 0.639643 +0.622901 0.641711 +0.651779 0.640011 +0.662422 0.642080 +0.691301 0.640379 +0.701944 0.642448 +0.730823 0.640748 +0.741466 0.642816 +0.770345 0.641116 +0.780988 0.643184 +0.809867 0.641484 +0.820510 0.643552 +0.849388 0.641852 +0.860032 0.643920 +0.877959 0.634744 +0.860634 0.646132 +0.859786 0.657396 +0.867733 0.670382 +0.840390 0.672334 +0.847607 0.655077 +0.848454 0.643813 +0.821112 0.645764 +0.808932 0.643444 +0.781590 0.645396 +0.780742 0.656660 +0.788689 0.669646 +0.769410 0.643076 +0.742068 0.645027 +0.741220 0.656292 +0.749167 0.669278 +0.729888 0.642708 +0.702546 0.644659 +0.701698 0.655924 +0.709645 0.668910 +0.690366 0.642340 +0.663024 0.644291 +0.662176 0.655556 +0.670123 0.668542 +0.650845 0.641972 +0.623502 0.643923 +0.622654 0.655187 +0.630602 0.668173 +0.603259 0.670125 +0.610475 0.652868 +0.611323 0.641604 +0.583980 0.643555 +0.563737 0.669756 +0.551558 0.667437 +0.524215 0.669388 +0.512036 0.667069 +0.484693 0.669020 +0.491909 0.651764 +0.492757 0.640499 +0.465414 0.642450 +0.445171 0.668652 +0.432992 0.666333 +0.405649 0.668284 +0.393470 0.665964 +0.374191 0.639395 +0.346849 0.641346 +0.346001 0.652610 +0.353948 0.665596 +0.326605 0.667547 +0.333821 0.650291 +0.334669 0.639026 +0.307327 0.640978 +0.295147 0.638658 +0.267805 0.640609 +0.266957 0.651874 +0.274904 0.664860 +0.255625 0.638290 +0.228283 0.640241 +0.227435 0.651506 +0.235382 0.664492 +0.216103 0.637922 +0.188761 0.639873 +0.187913 0.651137 +0.195860 0.664124 +0.168518 0.666075 +0.175734 0.648818 +0.176582 0.637554 +0.168634 0.624568 +0.195977 0.622616 +0.208156 0.624936 +0.235499 0.622985 +0.247678 0.625304 +0.275021 0.623353 +0.287200 0.625672 +0.314543 0.623721 +0.326722 0.626040 +0.354065 0.624089 +0.366244 0.626409 +0.393586 0.624457 +0.386371 0.641714 +0.385523 0.652978 +0.412865 0.651027 +0.425045 0.653347 +0.452387 0.651395 +0.453235 0.640131 +0.445288 0.627145 +0.472630 0.625194 +0.484810 0.627513 +0.504089 0.654083 +0.531431 0.652132 +0.532279 0.640867 +0.524332 0.627881 +0.551674 0.625930 +0.544458 0.643187 +0.543610 0.654451 +0.570953 0.652500 +0.591196 0.626298 +0.603375 0.628618 +0.630718 0.626666 +0.642897 0.628986 +0.670240 0.627035 +0.682419 0.629354 +0.709762 0.627403 +0.721941 0.629722 +0.749284 0.627771 +0.761463 0.630090 +0.788806 0.628139 +0.800985 0.630458 +0.828328 0.628507 +0.840507 0.630827 +0.867849 0.628875 +0.880877 0.619930 +0.869313 0.633064 +0.869802 0.666833 +0.857716 0.660946 +0.849070 0.659266 +0.838927 0.668145 +0.838438 0.634376 +0.829792 0.632696 +0.798916 0.634008 +0.790270 0.632328 +0.790759 0.666097 +0.778673 0.660210 +0.759394 0.633640 +0.750748 0.631960 +0.751237 0.665728 +0.739151 0.659841 +0.719872 0.633272 +0.711226 0.631591 +0.711715 0.665360 +0.699629 0.659473 +0.680350 0.632903 +0.671704 0.631223 +0.672193 0.664992 +0.660107 0.659105 +0.640828 0.632535 +0.632182 0.630855 +0.632671 0.664624 +0.620585 0.658737 +0.611939 0.657057 +0.601795 0.665936 +0.601306 0.632167 +0.592660 0.630487 +0.572417 0.656689 +0.541541 0.658001 +0.532895 0.656320 +0.502019 0.657632 +0.493373 0.655952 +0.483229 0.664831 +0.482740 0.631063 +0.474094 0.629382 +0.453851 0.655584 +0.422975 0.656896 +0.414329 0.655216 +0.383453 0.656528 +0.364175 0.629958 +0.355528 0.628278 +0.356017 0.662047 +0.343931 0.656160 +0.335285 0.654480 +0.325142 0.663359 +0.324653 0.629590 +0.316006 0.627910 +0.285131 0.629222 +0.276485 0.627541 +0.276974 0.661310 +0.264888 0.655423 +0.245609 0.628853 +0.236963 0.627173 +0.237452 0.660942 +0.225366 0.655055 +0.206087 0.628485 +0.197441 0.626805 +0.197930 0.660574 +0.185844 0.654687 +0.177198 0.653007 +0.167054 0.661886 +0.166565 0.628117 +0.178651 0.634004 +0.187297 0.635684 +0.218173 0.634372 +0.226819 0.636052 +0.257695 0.634740 +0.266341 0.636421 +0.297217 0.635109 +0.305863 0.636789 +0.336739 0.635477 +0.345385 0.637157 +0.376261 0.635845 +0.384907 0.637525 +0.395050 0.628646 +0.395539 0.662415 +0.404185 0.664095 +0.435061 0.662783 +0.443707 0.664463 +0.443218 0.630694 +0.455304 0.636581 +0.463951 0.638261 +0.494826 0.636949 +0.514105 0.663519 +0.522751 0.665200 +0.522262 0.631431 +0.534348 0.637318 +0.542994 0.638998 +0.553138 0.630119 +0.553627 0.663888 +0.562273 0.665568 +0.582516 0.639366 +0.613392 0.638054 +0.622038 0.639734 +0.652914 0.638422 +0.661560 0.640102 +0.692436 0.638790 +0.701082 0.640471 +0.731958 0.639158 +0.740604 0.640839 +0.771480 0.639527 +0.780126 0.641207 +0.811002 0.639895 +0.819648 0.641575 +0.850524 0.640263 +0.859170 0.641943 +0.876700 0.635875 +0.860962 0.648427 +0.860468 0.655197 +0.867051 0.672582 +0.840719 0.674629 +0.847278 0.652782 +0.847772 0.646012 +0.821440 0.648059 +0.808250 0.645644 +0.781918 0.647691 +0.781424 0.654461 +0.788007 0.671846 +0.768728 0.645276 +0.742396 0.647323 +0.741902 0.654092 +0.748485 0.671477 +0.729206 0.644908 +0.702874 0.646955 +0.702380 0.653724 +0.708963 0.671109 +0.689684 0.644539 +0.663352 0.646586 +0.662858 0.653356 +0.669441 0.670741 +0.650162 0.644171 +0.623830 0.646218 +0.623336 0.652988 +0.629919 0.670373 +0.603587 0.672420 +0.610147 0.650573 +0.610641 0.643803 +0.584308 0.645850 +0.564065 0.672052 +0.550876 0.669637 +0.524543 0.671684 +0.511354 0.669268 +0.485021 0.671315 +0.491581 0.649468 +0.492075 0.642699 +0.465743 0.644746 +0.445500 0.670947 +0.432310 0.668532 +0.405978 0.670579 +0.392788 0.668164 +0.373509 0.641594 +0.347177 0.643641 +0.346683 0.650411 +0.353266 0.667796 +0.326934 0.669843 +0.333493 0.647996 +0.333987 0.641226 +0.307655 0.643273 +0.294465 0.640858 +0.268133 0.642905 +0.267639 0.649674 +0.274222 0.667059 +0.254943 0.640490 +0.228611 0.642537 +0.228117 0.649306 +0.234700 0.666691 +0.215421 0.640121 +0.189089 0.642168 +0.188595 0.648938 +0.195178 0.666323 +0.168846 0.668370 +0.175405 0.646523 +0.175899 0.639753 +0.169316 0.622368 +0.195649 0.620321 +0.208838 0.622736 +0.235171 0.620689 +0.248360 0.623104 +0.274692 0.621057 +0.287882 0.623473 +0.314214 0.621426 +0.327404 0.623841 +0.353736 0.621794 +0.366926 0.624209 +0.393258 0.622162 +0.386699 0.644009 +0.386205 0.650779 +0.412537 0.648732 +0.425727 0.651147 +0.452059 0.649100 +0.452553 0.642330 +0.445970 0.624945 +0.472302 0.622898 +0.485492 0.625313 +0.504771 0.651883 +0.531103 0.649836 +0.531597 0.643067 +0.525014 0.625682 +0.551346 0.623635 +0.544786 0.645482 +0.544293 0.652252 +0.570625 0.650205 +0.590868 0.624003 +0.604058 0.626418 +0.630390 0.624371 +0.643579 0.626786 +0.669912 0.624739 +0.683101 0.627154 +0.709434 0.625107 +0.722623 0.627522 +0.748955 0.625476 +0.762145 0.627891 +0.788478 0.625844 +0.801667 0.628259 +0.827999 0.626212 +0.841189 0.628627 +0.867521 0.626580 +0.880275 0.617719 +0.870390 0.634674 +0.871062 0.665702 +0.856457 0.662077 +0.850147 0.660875 +0.837850 0.666535 +0.837178 0.635507 +0.830868 0.634306 +0.797656 0.635139 +0.791346 0.633937 +0.792018 0.664965 +0.777413 0.661341 +0.758134 0.634771 +0.751824 0.633569 +0.752496 0.664597 +0.737891 0.660972 +0.718612 0.634403 +0.712302 0.633201 +0.712974 0.664229 +0.698369 0.660604 +0.679090 0.634034 +0.672780 0.632833 +0.673452 0.663861 +0.658847 0.660236 +0.639568 0.633666 +0.633259 0.632465 +0.633931 0.663493 +0.619325 0.659868 +0.613015 0.658667 +0.600718 0.664326 +0.600046 0.633298 +0.593737 0.632097 +0.573494 0.658298 +0.540281 0.659132 +0.533972 0.657930 +0.500759 0.658764 +0.494450 0.657562 +0.482153 0.663222 +0.481481 0.632194 +0.475171 0.630992 +0.454928 0.657194 +0.421716 0.658027 +0.415406 0.656826 +0.382194 0.657659 +0.362915 0.631089 +0.356605 0.629888 +0.357277 0.660916 +0.342672 0.657291 +0.336362 0.656089 +0.324065 0.661749 +0.323393 0.630721 +0.317083 0.629519 +0.283871 0.630353 +0.277561 0.629151 +0.278233 0.660179 +0.263628 0.656554 +0.244349 0.629985 +0.238039 0.628783 +0.238711 0.659811 +0.224106 0.656186 +0.204827 0.629616 +0.198517 0.628415 +0.199189 0.659443 +0.184584 0.655818 +0.178274 0.654617 +0.165977 0.660276 +0.165305 0.629248 +0.179911 0.632873 +0.186220 0.634075 +0.219433 0.633241 +0.225742 0.634443 +0.258955 0.633609 +0.265264 0.634811 +0.298477 0.633978 +0.304786 0.635179 +0.337998 0.634346 +0.344308 0.635547 +0.377520 0.634714 +0.383830 0.635915 +0.396127 0.630256 +0.396799 0.661284 +0.403109 0.662485 +0.436321 0.661652 +0.442631 0.662853 +0.441959 0.631826 +0.456564 0.635450 +0.462874 0.636652 +0.496086 0.635818 +0.515365 0.662388 +0.521675 0.663590 +0.521002 0.632562 +0.535608 0.636187 +0.541918 0.637388 +0.554215 0.631728 +0.554887 0.662756 +0.561197 0.663958 +0.581440 0.637756 +0.614652 0.636923 +0.620962 0.638125 +0.654174 0.637291 +0.660483 0.638493 +0.693696 0.637659 +0.700005 0.638861 +0.733217 0.638027 +0.739527 0.639229 +0.772740 0.638396 +0.779049 0.639597 +0.812261 0.638764 +0.818571 0.639965 +0.851783 0.639132 +0.858093 0.640334 +0.875400 0.636522 +0.861036 0.650669 +0.860880 0.652909 +0.871608 0.635828 +0.872362 0.665055 +0.872883 0.636499 +0.873624 0.664861 +0.874138 0.636716 +0.874879 0.665078 +0.876154 0.665749 +0.866639 0.674870 +0.840793 0.676871 +0.847204 0.650540 +0.847360 0.648301 +0.836632 0.665381 +0.835878 0.636154 +0.835357 0.664710 +0.834616 0.636348 +0.834102 0.664493 +0.833361 0.636131 +0.832840 0.664687 +0.832086 0.635460 +0.821514 0.650301 +0.821358 0.652540 +0.831540 0.665334 +0.820946 0.654829 +0.830281 0.666465 +0.820264 0.657028 +0.829145 0.668054 +0.819330 0.658989 +0.828211 0.670014 +0.818195 0.660578 +0.827529 0.672214 +0.816935 0.661709 +0.807838 0.647932 +0.781992 0.649933 +0.781836 0.652172 +0.792564 0.635092 +0.793318 0.664319 +0.793839 0.635763 +0.794580 0.664125 +0.795094 0.635980 +0.795835 0.664342 +0.796357 0.635786 +0.797110 0.665013 +0.807682 0.650172 +0.798328 0.666167 +0.807756 0.652414 +0.799405 0.667777 +0.808084 0.654709 +0.800267 0.669754 +0.808686 0.656920 +0.800869 0.671965 +0.809548 0.658898 +0.801197 0.674261 +0.810625 0.660507 +0.827117 0.674502 +0.801271 0.676503 +0.787595 0.674134 +0.768316 0.647564 +0.742471 0.649565 +0.742314 0.651804 +0.753042 0.634723 +0.753796 0.663950 +0.754318 0.635394 +0.755058 0.663757 +0.755572 0.635612 +0.756313 0.663974 +0.756835 0.635418 +0.757588 0.664645 +0.768160 0.649804 +0.758806 0.665799 +0.768234 0.652045 +0.759883 0.667409 +0.768563 0.654341 +0.760745 0.669386 +0.769164 0.656552 +0.761347 0.671597 +0.770027 0.658529 +0.761675 0.673893 +0.771103 0.660139 +0.748073 0.673766 +0.728794 0.647196 +0.702949 0.649196 +0.702792 0.651436 +0.713520 0.634355 +0.714274 0.663582 +0.714796 0.635026 +0.715536 0.663388 +0.716050 0.635243 +0.716791 0.663606 +0.717313 0.635050 +0.718066 0.664277 +0.728638 0.649436 +0.719284 0.665431 +0.728712 0.651677 +0.720361 0.667040 +0.729041 0.653973 +0.721223 0.669018 +0.729642 0.656184 +0.721825 0.671229 +0.730505 0.658161 +0.722153 0.673524 +0.731581 0.659771 +0.761750 0.676134 +0.722228 0.675766 +0.708551 0.673398 +0.689273 0.646828 +0.663427 0.648828 +0.663270 0.651068 +0.673998 0.633987 +0.674752 0.663214 +0.675274 0.634658 +0.676014 0.663020 +0.676528 0.634875 +0.677269 0.663238 +0.677791 0.634681 +0.678544 0.663908 +0.689116 0.649067 +0.679762 0.665063 +0.689191 0.651309 +0.680839 0.666672 +0.689519 0.653604 +0.681701 0.668649 +0.690120 0.655816 +0.682303 0.670861 +0.690983 0.657793 +0.682631 0.673156 +0.692059 0.659403 +0.669029 0.673030 +0.649750 0.646460 +0.623905 0.648460 +0.623748 0.650699 +0.634476 0.633619 +0.635230 0.662846 +0.635752 0.634290 +0.636492 0.662652 +0.637007 0.634507 +0.637747 0.662869 +0.638269 0.634313 +0.639022 0.663540 +0.649594 0.648699 +0.640240 0.664694 +0.649669 0.650941 +0.641317 0.666304 +0.649997 0.653236 +0.642179 0.668281 +0.650598 0.655448 +0.642781 0.670493 +0.651461 0.657425 +0.643109 0.672788 +0.652537 0.659035 +0.682706 0.675398 +0.643184 0.675030 +0.629507 0.672661 +0.603662 0.674662 +0.610072 0.648331 +0.610228 0.646092 +0.599501 0.663172 +0.598747 0.633945 +0.598225 0.662501 +0.597485 0.634139 +0.596970 0.662284 +0.596230 0.633922 +0.595708 0.662478 +0.594955 0.633251 +0.584383 0.648092 +0.584226 0.650331 +0.594409 0.663125 +0.583815 0.652620 +0.593149 0.664256 +0.583132 0.654819 +0.592014 0.665845 +0.582198 0.656780 +0.591080 0.667805 +0.581063 0.658369 +0.590397 0.670005 +0.579803 0.659500 +0.564140 0.674293 +0.550463 0.671925 +0.524618 0.673925 +0.589985 0.672293 +0.510942 0.671557 +0.485096 0.673557 +0.491506 0.647227 +0.491663 0.644987 +0.480935 0.662068 +0.480181 0.632841 +0.479659 0.661397 +0.478919 0.633034 +0.478405 0.661179 +0.477664 0.632817 +0.477142 0.661373 +0.476389 0.632146 +0.465817 0.646987 +0.465661 0.649227 +0.475843 0.662020 +0.465249 0.651515 +0.474583 0.663151 +0.464567 0.653715 +0.473448 0.664740 +0.463632 0.655675 +0.472514 0.666701 +0.462497 0.657264 +0.471832 0.668900 +0.461237 0.658395 +0.445574 0.673189 +0.431898 0.670821 +0.406052 0.672821 +0.392376 0.670452 +0.471420 0.671189 +0.373097 0.643882 +0.347251 0.645883 +0.347095 0.648122 +0.357823 0.631042 +0.358577 0.660269 +0.359098 0.631713 +0.359839 0.660075 +0.360353 0.631930 +0.361094 0.660292 +0.361615 0.631736 +0.362369 0.660963 +0.372941 0.646122 +0.363587 0.662117 +0.373015 0.648364 +0.364664 0.663727 +0.373343 0.650659 +0.365526 0.665704 +0.373945 0.652870 +0.366127 0.667916 +0.374807 0.654848 +0.366456 0.670211 +0.375884 0.656457 +0.352854 0.670084 +0.327008 0.672084 +0.333419 0.645754 +0.333575 0.643514 +0.322847 0.660595 +0.322093 0.631368 +0.321572 0.659924 +0.320831 0.631562 +0.320317 0.659707 +0.319577 0.631344 +0.319055 0.659900 +0.318301 0.630673 +0.307729 0.645515 +0.307573 0.647754 +0.317755 0.660547 +0.307161 0.650042 +0.316496 0.661678 +0.306479 0.652242 +0.315360 0.663268 +0.305545 0.654202 +0.314426 0.665228 +0.304409 0.655792 +0.313744 0.667427 +0.303150 0.656923 +0.294053 0.643146 +0.366530 0.672453 +0.313332 0.669716 +0.268207 0.645146 +0.268051 0.647386 +0.278779 0.630305 +0.279533 0.659532 +0.280055 0.630976 +0.280795 0.659338 +0.281309 0.631194 +0.282050 0.659556 +0.282572 0.631000 +0.283325 0.660227 +0.293897 0.645386 +0.284543 0.661381 +0.293971 0.647627 +0.285620 0.662991 +0.294300 0.649923 +0.286482 0.664968 +0.294901 0.652134 +0.287084 0.667179 +0.295763 0.654111 +0.287412 0.669475 +0.296840 0.655721 +0.273810 0.669348 +0.254531 0.642778 +0.228686 0.644778 +0.228529 0.647018 +0.239257 0.629937 +0.240011 0.659164 +0.240533 0.630608 +0.241273 0.658970 +0.241787 0.630825 +0.242528 0.659187 +0.243050 0.630632 +0.243803 0.659859 +0.254375 0.645018 +0.245021 0.661013 +0.254449 0.647259 +0.246098 0.662622 +0.254778 0.649554 +0.246960 0.664600 +0.255379 0.651766 +0.247562 0.666811 +0.256241 0.653743 +0.247890 0.669106 +0.257318 0.655353 +0.234288 0.668980 +0.215009 0.642410 +0.287486 0.671716 +0.247964 0.671348 +0.189164 0.644410 +0.189007 0.646650 +0.199735 0.629569 +0.200489 0.658796 +0.201011 0.630240 +0.201751 0.658602 +0.202265 0.630457 +0.203006 0.658819 +0.203528 0.630263 +0.204281 0.659490 +0.214853 0.644649 +0.205499 0.660644 +0.214927 0.646891 +0.206576 0.662254 +0.215256 0.649186 +0.207438 0.664231 +0.215857 0.651398 +0.208040 0.666443 +0.216720 0.653375 +0.208368 0.668738 +0.217796 0.654985 +0.194766 0.668612 +0.168921 0.670612 +0.175331 0.644281 +0.175487 0.642042 +0.164759 0.659122 +0.164006 0.629895 +0.163484 0.658451 +0.162744 0.630089 +0.162229 0.658234 +0.161489 0.629872 +0.160967 0.658428 +0.160213 0.629201 +0.159668 0.659075 +0.158995 0.628047 +0.169728 0.620080 +0.195574 0.618079 +0.208442 0.670980 +0.209250 0.620448 +0.235096 0.618448 +0.248772 0.620816 +0.274618 0.618816 +0.288294 0.621184 +0.314140 0.619184 +0.327816 0.621552 +0.353662 0.619552 +0.367338 0.621921 +0.393184 0.619920 +0.386773 0.646251 +0.386617 0.648490 +0.397345 0.631410 +0.398099 0.660637 +0.398620 0.632081 +0.399361 0.660443 +0.399875 0.632298 +0.400616 0.660660 +0.401137 0.632104 +0.401891 0.661331 +0.412463 0.646490 +0.412619 0.644251 +0.402437 0.631457 +0.413031 0.641962 +0.403696 0.630326 +0.413713 0.639763 +0.404831 0.628737 +0.414647 0.637802 +0.405766 0.626777 +0.415783 0.636213 +0.406448 0.624577 +0.417042 0.635082 +0.426139 0.648859 +0.451984 0.646858 +0.452141 0.644619 +0.441413 0.661699 +0.440659 0.632472 +0.440137 0.661028 +0.439397 0.632666 +0.438883 0.660811 +0.438142 0.632449 +0.437620 0.661005 +0.436867 0.631778 +0.426295 0.646619 +0.435649 0.630624 +0.426221 0.644377 +0.434572 0.629014 +0.425892 0.642082 +0.433710 0.627037 +0.425291 0.639871 +0.433108 0.624825 +0.424429 0.637893 +0.432780 0.622530 +0.423352 0.636284 +0.446382 0.622657 +0.472228 0.620657 +0.485904 0.623025 +0.406860 0.622289 +0.432706 0.620288 +0.505183 0.649595 +0.531028 0.647595 +0.531185 0.645355 +0.520457 0.662436 +0.519703 0.633209 +0.519181 0.661765 +0.518441 0.633403 +0.517927 0.661548 +0.517186 0.633185 +0.516664 0.661741 +0.515911 0.632514 +0.505339 0.647355 +0.514693 0.631360 +0.505265 0.645114 +0.513616 0.629751 +0.504936 0.642818 +0.512754 0.627773 +0.504335 0.640607 +0.512152 0.625562 +0.503472 0.638630 +0.511824 0.623266 +0.502396 0.637020 +0.525426 0.623393 +0.551271 0.621393 +0.544861 0.647724 +0.544705 0.649963 +0.555433 0.632883 +0.556186 0.662109 +0.556708 0.633554 +0.557449 0.661916 +0.557963 0.633771 +0.558703 0.662133 +0.559225 0.633577 +0.559979 0.662804 +0.570550 0.647963 +0.570707 0.645723 +0.560524 0.632930 +0.571119 0.643435 +0.561784 0.631799 +0.571801 0.641235 +0.562919 0.630210 +0.572735 0.639275 +0.563854 0.628249 +0.573870 0.637686 +0.564536 0.626050 +0.575130 0.636555 +0.511750 0.621025 +0.564948 0.623761 +0.590793 0.621761 +0.604470 0.624130 +0.630315 0.622129 +0.643991 0.624498 +0.669837 0.622498 +0.683514 0.624866 +0.709359 0.622866 +0.723035 0.625234 +0.748881 0.623234 +0.762557 0.625602 +0.788403 0.623602 +0.802079 0.625970 +0.827925 0.623970 +0.841601 0.626339 +0.867447 0.624338 +0.877372 0.666903 +0.878449 0.668513 +0.879311 0.670490 +0.879912 0.672702 +0.880241 0.674997 +0.880315 0.677239 +0.880159 0.679478 +0.879747 0.681767 +0.879065 0.683966 +0.878130 0.685927 +0.855157 0.662724 +0.851365 0.662030 +0.815635 0.662356 +0.811843 0.661661 +0.776113 0.661988 +0.772321 0.661293 +0.736592 0.661619 +0.732799 0.660925 +0.697070 0.661251 +0.693277 0.660557 +0.657548 0.660883 +0.653755 0.660189 +0.618026 0.660515 +0.614233 0.659821 +0.578504 0.660147 +0.574711 0.659452 +0.538982 0.659779 +0.535190 0.659084 +0.499460 0.659410 +0.495668 0.658716 +0.459938 0.659042 +0.456146 0.658348 +0.420416 0.658674 +0.416624 0.657980 +0.380894 0.658306 +0.377102 0.657612 +0.341372 0.657938 +0.337580 0.657243 +0.301850 0.657570 +0.298058 0.656875 +0.262328 0.657201 +0.258536 0.656507 +0.222807 0.656833 +0.219014 0.656139 +0.183285 0.656465 +0.179492 0.655771 +0.181210 0.632226 +0.185002 0.632920 +0.220732 0.632594 +0.224524 0.633289 +0.260254 0.632962 +0.264046 0.633657 +0.299776 0.633331 +0.303568 0.634025 +0.339298 0.633699 +0.343090 0.634393 +0.378820 0.634067 +0.382612 0.634761 +0.418342 0.634435 +0.422134 0.635130 +0.457864 0.634803 +0.461656 0.635498 +0.497385 0.635171 +0.501178 0.635866 +0.536907 0.635540 +0.540700 0.636234 +0.576429 0.635908 +0.580222 0.636602 +0.615951 0.636276 +0.619744 0.636970 +0.655473 0.636644 +0.659266 0.637339 +0.694995 0.637012 +0.698787 0.637707 +0.734517 0.637380 +0.738309 0.638075 +0.774039 0.637749 +0.777831 0.638443 +0.813561 0.638117 +0.817353 0.638811 +0.853083 0.638485 +0.856875 0.639179 +0.879413 0.615742 +0.876995 0.687516 +0.866483 0.677110 +0.840637 0.679110 +0.826961 0.676742 +0.801115 0.678742 +0.787439 0.676374 +0.761593 0.678374 +0.747917 0.676005 +0.722071 0.678006 +0.708395 0.675637 +0.682549 0.677637 +0.668873 0.675269 +0.643027 0.677269 +0.629351 0.674901 +0.603505 0.676901 +0.589829 0.674533 +0.563983 0.676533 +0.550307 0.674165 +0.524462 0.676165 +0.510785 0.673796 +0.484940 0.675797 +0.471263 0.673428 +0.445418 0.675428 +0.431741 0.673060 +0.405896 0.675060 +0.392219 0.672692 +0.366374 0.674692 +0.352698 0.672324 +0.326852 0.674324 +0.313176 0.671956 +0.287330 0.673956 +0.273654 0.671587 +0.247808 0.673588 +0.234132 0.671219 +0.208286 0.673219 +0.194610 0.670851 +0.168764 0.672851 +0.158408 0.660206 +0.157919 0.626437 +0.169885 0.617840 +0.195730 0.615840 +0.209407 0.618208 +0.235252 0.616208 +0.248929 0.618577 +0.274774 0.616576 +0.288451 0.618945 +0.314296 0.616944 +0.327973 0.619313 +0.353818 0.617313 +0.367494 0.619681 +0.393340 0.617681 +0.407016 0.620049 +0.432862 0.618049 +0.446538 0.620417 +0.472384 0.618417 +0.486060 0.620786 +0.511906 0.618785 +0.525582 0.621154 +0.551428 0.619153 +0.565104 0.621522 +0.590950 0.619522 +0.604626 0.621890 +0.630472 0.619890 +0.644148 0.622258 +0.669994 0.620258 +0.683670 0.622626 +0.709515 0.620626 +0.723192 0.622995 +0.749038 0.620994 +0.762714 0.623363 +0.788559 0.621363 +0.802236 0.623731 +0.828081 0.621731 +0.841758 0.624099 +0.867603 0.622099 +0.853895 0.662918 +0.852640 0.662701 +0.866557 0.679352 +0.840225 0.681399 +0.866885 0.681647 +0.839543 0.683598 +0.867487 0.683858 +0.838608 0.685559 +0.814373 0.662550 +0.813118 0.662332 +0.827035 0.678983 +0.800703 0.681030 +0.827363 0.681279 +0.800021 0.683230 +0.827965 0.683490 +0.799086 0.685190 +0.774851 0.662182 +0.773596 0.661964 +0.787513 0.678615 +0.761181 0.680662 +0.787841 0.680911 +0.760499 0.682862 +0.788443 0.683122 +0.759565 0.684822 +0.735329 0.661813 +0.734074 0.661596 +0.747991 0.678247 +0.721659 0.680294 +0.748320 0.680542 +0.720977 0.682494 +0.748921 0.682754 +0.720043 0.684454 +0.695807 0.661445 +0.694553 0.661228 +0.708469 0.677879 +0.682137 0.679926 +0.708798 0.680174 +0.681455 0.682125 +0.709399 0.682386 +0.680521 0.684086 +0.656285 0.661077 +0.655031 0.660860 +0.668947 0.677511 +0.642615 0.679558 +0.669276 0.679806 +0.641933 0.681757 +0.669877 0.682018 +0.640999 0.683718 +0.616763 0.660709 +0.615509 0.660492 +0.629426 0.677143 +0.603093 0.679190 +0.629754 0.679438 +0.602411 0.681389 +0.630355 0.681649 +0.601477 0.683350 +0.577242 0.660341 +0.575987 0.660123 +0.589904 0.676774 +0.563571 0.678821 +0.590232 0.679070 +0.562889 0.681021 +0.590833 0.681281 +0.561955 0.682981 +0.537720 0.659972 +0.536465 0.659755 +0.550382 0.676406 +0.524049 0.678453 +0.550710 0.678702 +0.523367 0.680653 +0.551311 0.680913 +0.522433 0.682613 +0.498198 0.659604 +0.496943 0.659387 +0.510860 0.676038 +0.484528 0.678085 +0.511188 0.678333 +0.483846 0.680285 +0.511790 0.680545 +0.482911 0.682245 +0.458676 0.659236 +0.457421 0.659019 +0.471338 0.675670 +0.445006 0.677717 +0.471666 0.677965 +0.444324 0.679916 +0.472268 0.680177 +0.443389 0.681877 +0.419154 0.658868 +0.417899 0.658651 +0.431816 0.675302 +0.405484 0.677349 +0.432144 0.677597 +0.404802 0.679548 +0.432746 0.679808 +0.403867 0.681509 +0.379632 0.658500 +0.378377 0.658282 +0.392294 0.674934 +0.365962 0.676981 +0.392622 0.677229 +0.365280 0.679180 +0.393224 0.679440 +0.364345 0.681141 +0.340110 0.658132 +0.338855 0.657914 +0.352772 0.674565 +0.326440 0.676612 +0.353100 0.676861 +0.325758 0.678812 +0.353702 0.679072 +0.324823 0.680772 +0.300588 0.657763 +0.299333 0.657546 +0.313250 0.674197 +0.286918 0.676244 +0.313578 0.676493 +0.286236 0.678444 +0.314180 0.678704 +0.285302 0.680404 +0.261066 0.657395 +0.259811 0.657178 +0.273728 0.673829 +0.247396 0.675876 +0.274057 0.676124 +0.246714 0.678076 +0.274658 0.678336 +0.245780 0.680036 +0.221544 0.657027 +0.220289 0.656810 +0.234206 0.673461 +0.207874 0.675508 +0.234535 0.675756 +0.207192 0.677707 +0.235136 0.677968 +0.206258 0.679668 +0.182022 0.656659 +0.180768 0.656442 +0.194684 0.673093 +0.168352 0.675140 +0.195013 0.675388 +0.167670 0.677339 +0.195614 0.677600 +0.166736 0.679300 +0.182472 0.632032 +0.183727 0.632249 +0.169810 0.615598 +0.196142 0.613551 +0.169482 0.613303 +0.196825 0.611352 +0.168881 0.611092 +0.197759 0.609392 +0.221994 0.632400 +0.223249 0.632618 +0.209332 0.615967 +0.235664 0.613920 +0.209004 0.613671 +0.236346 0.611720 +0.208402 0.611460 +0.237281 0.609760 +0.261516 0.632769 +0.262771 0.632986 +0.248854 0.616335 +0.275186 0.614288 +0.248526 0.614039 +0.275868 0.612088 +0.247924 0.611828 +0.276803 0.610128 +0.301038 0.633137 +0.302293 0.633354 +0.288376 0.616703 +0.314708 0.614656 +0.288048 0.614408 +0.315390 0.612457 +0.287446 0.612196 +0.316325 0.610496 +0.340560 0.633505 +0.341815 0.633722 +0.327898 0.617071 +0.354230 0.615024 +0.327570 0.614776 +0.354912 0.612825 +0.326968 0.612564 +0.355847 0.610864 +0.380082 0.633873 +0.381337 0.634090 +0.367420 0.617439 +0.393752 0.615392 +0.367092 0.615144 +0.394434 0.613193 +0.366490 0.612933 +0.395369 0.611232 +0.419604 0.634241 +0.420859 0.634459 +0.406942 0.617808 +0.433274 0.615761 +0.406614 0.615512 +0.433956 0.613561 +0.406012 0.613301 +0.434891 0.611600 +0.459126 0.634609 +0.460381 0.634827 +0.446464 0.618176 +0.472796 0.616129 +0.446136 0.615880 +0.473478 0.613929 +0.445534 0.613669 +0.474412 0.611969 +0.498648 0.634978 +0.499902 0.635195 +0.485986 0.618544 +0.512318 0.616497 +0.485657 0.616248 +0.513000 0.614297 +0.485056 0.614037 +0.513934 0.612337 +0.538170 0.635346 +0.539424 0.635563 +0.525508 0.618912 +0.551840 0.616865 +0.525179 0.616617 +0.552522 0.614665 +0.524578 0.614405 +0.553456 0.612705 +0.577692 0.635714 +0.578946 0.635931 +0.565030 0.619280 +0.591362 0.617233 +0.564701 0.616985 +0.592044 0.615034 +0.564100 0.614773 +0.592978 0.613073 +0.617213 0.636082 +0.618468 0.636299 +0.604551 0.619648 +0.630884 0.617601 +0.604223 0.617353 +0.631566 0.615402 +0.603622 0.615141 +0.632500 0.613441 +0.656735 0.636450 +0.657990 0.636668 +0.644073 0.620017 +0.670406 0.617970 +0.643745 0.617721 +0.671088 0.615770 +0.643144 0.615510 +0.672022 0.613810 +0.696257 0.636818 +0.697512 0.637036 +0.683595 0.620385 +0.709928 0.618338 +0.683267 0.618089 +0.710610 0.616138 +0.682666 0.615878 +0.711544 0.614178 +0.735779 0.637187 +0.737034 0.637404 +0.723117 0.620753 +0.749449 0.618706 +0.722789 0.618458 +0.750132 0.616506 +0.722188 0.616246 +0.751066 0.614546 +0.775301 0.637555 +0.776556 0.637772 +0.762639 0.621121 +0.788971 0.619074 +0.762311 0.618826 +0.789653 0.616875 +0.761709 0.616614 +0.790588 0.614914 +0.814823 0.637923 +0.816078 0.638140 +0.802161 0.621489 +0.828493 0.619442 +0.801833 0.619194 +0.829175 0.617243 +0.801231 0.616982 +0.830110 0.615282 +0.854345 0.638291 +0.855600 0.638508 +0.841683 0.621857 +0.868015 0.619810 +0.841355 0.619562 +0.868697 0.617611 +0.840753 0.617351 +0.869632 0.615650 +0.878336 0.614132 +0.875736 0.688647 +0.868349 0.685836 +0.837473 0.687148 +0.828827 0.685468 +0.797951 0.686780 +0.789305 0.685099 +0.758430 0.686411 +0.749783 0.684731 +0.718907 0.686043 +0.710261 0.684363 +0.679386 0.685675 +0.670740 0.683995 +0.639864 0.685307 +0.631218 0.683627 +0.600342 0.684939 +0.591696 0.683258 +0.560820 0.684570 +0.552174 0.682890 +0.521298 0.684202 +0.512652 0.682522 +0.481776 0.683834 +0.473130 0.682154 +0.442254 0.683466 +0.433608 0.681786 +0.402732 0.683098 +0.394086 0.681418 +0.363210 0.682730 +0.354564 0.681049 +0.323688 0.682361 +0.315042 0.680681 +0.284166 0.681993 +0.275520 0.680313 +0.244644 0.681625 +0.235998 0.679945 +0.205122 0.681257 +0.196476 0.679577 +0.165601 0.680889 +0.157273 0.661795 +0.157056 0.624460 +0.168018 0.609114 +0.198894 0.607802 +0.207540 0.609483 +0.238416 0.608171 +0.247062 0.609851 +0.277938 0.608539 +0.286584 0.610219 +0.317460 0.608907 +0.326106 0.610587 +0.356982 0.609275 +0.365628 0.610955 +0.396504 0.609643 +0.405150 0.611323 +0.436026 0.610011 +0.444672 0.611692 +0.475548 0.610380 +0.484194 0.612060 +0.515069 0.610748 +0.523715 0.612428 +0.554591 0.611116 +0.563237 0.612796 +0.594113 0.611484 +0.602759 0.613164 +0.633635 0.611852 +0.642281 0.613532 +0.673157 0.612221 +0.681803 0.613901 +0.712679 0.612589 +0.721325 0.614269 +0.752201 0.612957 +0.760847 0.614637 +0.791723 0.613325 +0.800369 0.615005 +0.831245 0.613693 +0.839891 0.615373 +0.870767 0.614061 +0.877118 0.612978 +0.874436 0.689294 +0.869426 0.687445 +0.836214 0.688279 +0.829904 0.687077 +0.796692 0.687911 +0.790382 0.686709 +0.757170 0.687542 +0.750860 0.686341 +0.717648 0.687174 +0.711338 0.685973 +0.678126 0.686806 +0.671816 0.685604 +0.638604 0.686438 +0.632294 0.685236 +0.599082 0.686070 +0.592772 0.684868 +0.559560 0.685702 +0.553251 0.684500 +0.520038 0.685333 +0.513729 0.684132 +0.480516 0.684965 +0.474207 0.683764 +0.440994 0.684597 +0.434685 0.683396 +0.401472 0.684229 +0.395163 0.683027 +0.361951 0.683861 +0.355641 0.682659 +0.322429 0.683492 +0.316119 0.682291 +0.282907 0.683124 +0.276597 0.681923 +0.243385 0.682756 +0.237075 0.681555 +0.203863 0.682388 +0.197553 0.681186 +0.164341 0.682020 +0.156338 0.663755 +0.156455 0.622248 +0.166941 0.607505 +0.200154 0.606671 +0.206463 0.607873 +0.239676 0.607040 +0.245985 0.608241 +0.279198 0.607408 +0.285507 0.608609 +0.318720 0.607776 +0.325029 0.608977 +0.358241 0.608144 +0.364551 0.609346 +0.397763 0.608512 +0.404073 0.609714 +0.437285 0.608880 +0.443595 0.610082 +0.476807 0.609249 +0.483117 0.610450 +0.516329 0.609617 +0.522639 0.610818 +0.555851 0.609985 +0.562161 0.611186 +0.595373 0.610353 +0.601683 0.611555 +0.634895 0.610721 +0.641204 0.611923 +0.674417 0.611089 +0.680727 0.612291 +0.713939 0.611458 +0.720248 0.612659 +0.753461 0.611826 +0.759770 0.613027 +0.792983 0.612194 +0.799292 0.613396 +0.832505 0.612562 +0.838814 0.613764 +0.872026 0.612930 +0.870644 0.688599 +0.831122 0.688231 +0.791600 0.687863 +0.752078 0.687495 +0.712556 0.687127 +0.834914 0.688926 +0.795392 0.688558 +0.755870 0.688189 +0.716348 0.687821 +0.676827 0.687453 +0.673034 0.686759 +0.633512 0.686390 +0.593990 0.686022 +0.637305 0.687085 +0.597783 0.686717 +0.558261 0.686349 +0.554469 0.685654 +0.514946 0.685286 +0.475425 0.684918 +0.435903 0.684550 +0.518739 0.685980 +0.479217 0.685612 +0.439695 0.685244 +0.400173 0.684876 +0.396381 0.684181 +0.356859 0.683813 +0.317337 0.683445 +0.360651 0.684508 +0.321129 0.684140 +0.281607 0.683771 +0.277815 0.683077 +0.238293 0.682709 +0.198771 0.682341 +0.155656 0.665955 +0.242085 0.683403 +0.202563 0.683035 +0.163042 0.682667 +0.156127 0.619953 +0.165723 0.606351 +0.205245 0.606719 +0.244767 0.607087 +0.201453 0.606024 +0.240975 0.606393 +0.280497 0.606761 +0.284289 0.607455 +0.323811 0.607823 +0.363333 0.608191 +0.402855 0.608560 +0.320019 0.607129 +0.359541 0.607497 +0.399063 0.607865 +0.438585 0.608233 +0.442377 0.608928 +0.481899 0.609296 +0.521421 0.609664 +0.478107 0.608602 +0.517628 0.608970 +0.557150 0.609338 +0.560943 0.610032 +0.600465 0.610400 +0.639987 0.610769 +0.679509 0.611137 +0.596672 0.609706 +0.636194 0.610074 +0.675716 0.610442 +0.715238 0.610811 +0.719030 0.611505 +0.758552 0.611873 +0.798074 0.612241 +0.754760 0.611179 +0.794282 0.611547 +0.833804 0.611915 +0.837596 0.612610 +0.873326 0.612283 +0.875843 0.612307 +0.126861 0.592808 +0.874588 0.612089 +0.873174 0.689488 +0.909507 0.702142 +0.871919 0.689270 +0.833652 0.689120 +0.832397 0.688902 +0.794130 0.688751 +0.792875 0.688534 +0.754608 0.688383 +0.753353 0.688166 +0.715086 0.688015 +0.713831 0.687798 +0.675564 0.687647 +0.674309 0.687430 +0.636042 0.687279 +0.634788 0.687061 +0.596520 0.686911 +0.595266 0.686693 +0.556998 0.686542 +0.555744 0.686325 +0.517477 0.686174 +0.516222 0.685957 +0.477955 0.685806 +0.476700 0.685589 +0.438433 0.685438 +0.437178 0.685221 +0.398911 0.685070 +0.397656 0.684852 +0.359389 0.684702 +0.358134 0.684484 +0.319867 0.684333 +0.318612 0.684116 +0.280345 0.683965 +0.279090 0.683748 +0.240823 0.683597 +0.239568 0.683380 +0.201301 0.683229 +0.200046 0.683011 +0.161779 0.682861 +0.160524 0.682643 +0.159249 0.681972 +0.158031 0.680818 +0.156955 0.679209 +0.156092 0.677231 +0.124996 0.694833 +0.155491 0.675020 +0.155162 0.672724 +0.155088 0.670483 +0.155244 0.668243 +0.156052 0.617711 +0.156209 0.615472 +0.156621 0.613183 +0.157303 0.610984 +0.158237 0.609023 +0.159372 0.607434 +0.160632 0.606303 +0.161931 0.605656 +0.163194 0.605462 +0.164448 0.605680 +0.202715 0.605831 +0.203970 0.606048 +0.242237 0.606199 +0.243492 0.606416 +0.283014 0.606784 +0.322536 0.607152 +0.362058 0.607521 +0.401580 0.607889 +0.281759 0.606567 +0.321281 0.606935 +0.360803 0.607303 +0.400325 0.607671 +0.439847 0.608039 +0.441102 0.608257 +0.480624 0.608625 +0.520146 0.608993 +0.479369 0.608408 +0.518891 0.608776 +0.558413 0.609144 +0.559667 0.609361 +0.599189 0.609730 +0.638711 0.610098 +0.678233 0.610466 +0.597935 0.609512 +0.637457 0.609880 +0.676978 0.610249 +0.716501 0.610617 +0.717755 0.610834 +0.757277 0.611202 +0.796799 0.611570 +0.756022 0.610985 +0.795544 0.611353 +0.835066 0.611721 +0.836321 0.611938 +0.524462 0.676165 +0.524618 0.673925 +0.524618 0.673925 +0.524462 0.676165 +0.510785 0.673796 +0.510785 0.673796 +0.510860 0.676038 +0.511188 0.678333 +0.510860 0.676038 +0.511790 0.680545 +0.511188 0.678333 +0.512652 0.682522 +0.511790 0.680545 +0.513729 0.684132 +0.512652 0.682522 +0.513729 0.684132 +0.514946 0.685286 +0.516222 0.685957 +0.514946 0.685286 +0.517477 0.686174 +0.516222 0.685957 +0.517477 0.686174 +0.518739 0.685980 +0.518739 0.685980 +0.520038 0.685333 +0.520038 0.685333 +0.521298 0.684202 +0.521298 0.684202 +0.522433 0.682613 +0.522433 0.682613 +0.523367 0.680653 +0.524049 0.678453 +0.523367 0.680653 +0.524049 0.678453 +0.525426 0.623393 +0.525426 0.623393 +0.525582 0.621154 +0.525582 0.621154 +0.511750 0.621025 +0.511750 0.621025 +0.511824 0.623266 +0.512152 0.625562 +0.511824 0.623266 +0.512754 0.627773 +0.512152 0.625562 +0.513616 0.629751 +0.512754 0.627773 +0.514693 0.631360 +0.513616 0.629751 +0.515911 0.632514 +0.514693 0.631360 +0.515911 0.632514 +0.517186 0.633185 +0.517186 0.633185 +0.518441 0.633403 +0.518441 0.633403 +0.519703 0.633209 +0.519703 0.633209 +0.521002 0.632562 +0.521002 0.632562 +0.522262 0.631431 +0.522262 0.631431 +0.523397 0.629842 +0.523397 0.629842 +0.524332 0.627881 +0.525014 0.625682 +0.524332 0.627881 +0.525014 0.625682 +0.563983 0.676533 +0.563983 0.676533 +0.564140 0.674293 +0.564140 0.674293 +0.550307 0.674165 +0.550307 0.674165 +0.550382 0.676406 +0.550382 0.676406 +0.550710 0.678702 +0.551311 0.680913 +0.550710 0.678702 +0.551311 0.680913 +0.552174 0.682890 +0.552174 0.682890 +0.553251 0.684500 +0.554469 0.685654 +0.553251 0.684500 +0.554469 0.685654 +0.555744 0.686325 +0.555744 0.686325 +0.556998 0.686542 +0.556998 0.686542 +0.558261 0.686349 +0.558261 0.686349 +0.559560 0.685702 +0.559560 0.685702 +0.560820 0.684570 +0.560820 0.684570 +0.561955 0.682981 +0.561955 0.682981 +0.562889 0.681021 +0.562889 0.681021 +0.563571 0.678821 +0.563571 0.678821 +0.564948 0.623761 +0.564948 0.623761 +0.565104 0.621522 +0.565104 0.621522 +0.551271 0.621393 +0.551271 0.621393 +0.551346 0.623635 +0.551674 0.625930 +0.551346 0.623635 +0.551674 0.625930 +0.552276 0.628141 +0.553138 0.630119 +0.552276 0.628141 +0.553138 0.630119 +0.554215 0.631728 +0.554215 0.631728 +0.555433 0.632883 +0.556708 0.633554 +0.555433 0.632883 +0.557963 0.633771 +0.556708 0.633554 +0.559225 0.633577 +0.557963 0.633771 +0.559225 0.633577 +0.560524 0.632930 +0.560524 0.632930 +0.561784 0.631799 +0.562919 0.630210 +0.561784 0.631799 +0.562919 0.630210 +0.563854 0.628249 +0.563854 0.628249 +0.564536 0.626050 +0.564536 0.626050 +0.601477 0.683350 +0.603505 0.676901 +0.603662 0.674662 +0.603662 0.674662 +0.603093 0.679190 +0.603505 0.676901 +0.603093 0.679190 +0.602411 0.681389 +0.602411 0.681389 +0.601477 0.683350 +0.589829 0.674533 +0.589829 0.674533 +0.589904 0.676774 +0.590232 0.679070 +0.589904 0.676774 +0.590232 0.679070 +0.590833 0.681281 +0.590833 0.681281 +0.591696 0.683258 +0.592772 0.684868 +0.591696 0.683258 +0.592772 0.684868 +0.593990 0.686022 +0.595266 0.686693 +0.593990 0.686022 +0.595266 0.686693 +0.596520 0.686911 +0.596520 0.686911 +0.597783 0.686717 +0.597783 0.686717 +0.599082 0.686070 +0.599082 0.686070 +0.600342 0.684939 +0.600342 0.684939 +0.591196 0.626298 +0.590868 0.624003 +0.590793 0.621761 +0.590793 0.621761 +0.591196 0.626298 +0.590868 0.624003 +0.604626 0.621890 +0.604626 0.621890 +0.604470 0.624130 +0.604058 0.626418 +0.604470 0.624130 +0.603375 0.628618 +0.604058 0.626418 +0.603375 0.628618 +0.602441 0.630578 +0.602441 0.630578 +0.601306 0.632167 +0.601306 0.632167 +0.600046 0.633298 +0.600046 0.633298 +0.598747 0.633945 +0.598747 0.633945 +0.597485 0.634139 +0.597485 0.634139 +0.596230 0.633922 +0.596230 0.633922 +0.594955 0.633251 +0.594955 0.633251 +0.593737 0.632097 +0.593737 0.632097 +0.592660 0.630487 +0.592660 0.630487 +0.591797 0.628510 +0.591797 0.628510 +0.629754 0.679438 +0.629426 0.677143 +0.629351 0.674901 +0.629351 0.674901 +0.629754 0.679438 +0.629426 0.677143 +0.643027 0.677269 +0.643184 0.675030 +0.643184 0.675030 +0.642615 0.679558 +0.643027 0.677269 +0.642615 0.679558 +0.641933 0.681757 +0.641933 0.681757 +0.640999 0.683718 +0.640999 0.683718 +0.639864 0.685307 +0.639864 0.685307 +0.638604 0.686438 +0.637305 0.687085 +0.638604 0.686438 +0.637305 0.687085 +0.636042 0.687279 +0.636042 0.687279 +0.634788 0.687061 +0.634788 0.687061 +0.633512 0.686390 +0.633512 0.686390 +0.632294 0.685236 +0.632294 0.685236 +0.631218 0.683627 +0.631218 0.683627 +0.630355 0.681649 +0.630355 0.681649 +0.644148 0.622258 +0.644148 0.622258 +0.630390 0.624371 +0.630315 0.622129 +0.630315 0.622129 +0.630390 0.624371 +0.630718 0.626666 +0.630718 0.626666 +0.631320 0.628878 +0.632182 0.630855 +0.631320 0.628878 +0.633259 0.632465 +0.632182 0.630855 +0.634476 0.633619 +0.633259 0.632465 +0.635752 0.634290 +0.634476 0.633619 +0.637007 0.634507 +0.635752 0.634290 +0.638269 0.634313 +0.637007 0.634507 +0.638269 0.634313 +0.639568 0.633666 +0.640828 0.632535 +0.639568 0.633666 +0.641963 0.630946 +0.640828 0.632535 +0.642897 0.628986 +0.641963 0.630946 +0.642897 0.628986 +0.643579 0.626786 +0.643579 0.626786 +0.643991 0.624498 +0.643991 0.624498 +0.676827 0.687453 +0.668947 0.677511 +0.668873 0.675269 +0.668873 0.675269 +0.668947 0.677511 +0.669276 0.679806 +0.669877 0.682018 +0.669276 0.679806 +0.669877 0.682018 +0.670740 0.683995 +0.671816 0.685604 +0.670740 0.683995 +0.673034 0.686759 +0.671816 0.685604 +0.674309 0.687430 +0.673034 0.686759 +0.675564 0.687647 +0.674309 0.687430 +0.682549 0.677637 +0.682706 0.675398 +0.682706 0.675398 +0.682137 0.679926 +0.682549 0.677637 +0.681455 0.682125 +0.682137 0.679926 +0.681455 0.682125 +0.680521 0.684086 +0.680521 0.684086 +0.679386 0.685675 +0.678126 0.686806 +0.679386 0.685675 +0.678126 0.686806 +0.676827 0.687453 +0.675564 0.687647 +0.683670 0.622626 +0.683670 0.622626 +0.669837 0.622498 +0.669837 0.622498 +0.669912 0.624739 +0.669912 0.624739 +0.670240 0.627035 +0.670240 0.627035 +0.670841 0.629246 +0.671704 0.631223 +0.670841 0.629246 +0.672780 0.632833 +0.671704 0.631223 +0.673998 0.633987 +0.672780 0.632833 +0.675274 0.634658 +0.673998 0.633987 +0.675274 0.634658 +0.676528 0.634875 +0.677791 0.634681 +0.676528 0.634875 +0.679090 0.634034 +0.677791 0.634681 +0.680350 0.632903 +0.679090 0.634034 +0.681485 0.631314 +0.680350 0.632903 +0.681485 0.631314 +0.682419 0.629354 +0.682419 0.629354 +0.683101 0.627154 +0.683101 0.627154 +0.683514 0.624866 +0.683514 0.624866 +0.722071 0.678006 +0.722228 0.675766 +0.722228 0.675766 +0.722071 0.678006 +0.708395 0.675637 +0.708395 0.675637 +0.708469 0.677879 +0.708469 0.677879 +0.708798 0.680174 +0.708798 0.680174 +0.709399 0.682386 +0.710261 0.684363 +0.709399 0.682386 +0.711338 0.685973 +0.710261 0.684363 +0.712556 0.687127 +0.711338 0.685973 +0.712556 0.687127 +0.713831 0.687798 +0.713831 0.687798 +0.715086 0.688015 +0.716348 0.687821 +0.715086 0.688015 +0.717648 0.687174 +0.716348 0.687821 +0.718907 0.686043 +0.717648 0.687174 +0.718907 0.686043 +0.720043 0.684454 +0.720977 0.682494 +0.720043 0.684454 +0.720977 0.682494 +0.721659 0.680294 +0.721659 0.680294 +0.723192 0.622995 +0.723192 0.622995 +0.709359 0.622866 +0.709359 0.622866 +0.709434 0.625107 +0.709434 0.625107 +0.709762 0.627403 +0.709762 0.627403 +0.710363 0.629614 +0.711226 0.631591 +0.710363 0.629614 +0.712302 0.633201 +0.711226 0.631591 +0.713520 0.634355 +0.712302 0.633201 +0.714796 0.635026 +0.713520 0.634355 +0.716050 0.635243 +0.714796 0.635026 +0.717313 0.635050 +0.716050 0.635243 +0.717313 0.635050 +0.718612 0.634403 +0.719872 0.633272 +0.718612 0.634403 +0.719872 0.633272 +0.721007 0.631683 +0.721007 0.631683 +0.721941 0.629722 +0.721941 0.629722 +0.722623 0.627522 +0.722623 0.627522 +0.723035 0.625234 +0.723035 0.625234 +0.761750 0.676134 +0.761750 0.676134 +0.747991 0.678247 +0.747917 0.676005 +0.747917 0.676005 +0.747991 0.678247 +0.748320 0.680542 +0.748320 0.680542 +0.748921 0.682754 +0.749783 0.684731 +0.748921 0.682754 +0.750860 0.686341 +0.749783 0.684731 +0.752078 0.687495 +0.750860 0.686341 +0.753353 0.688166 +0.752078 0.687495 +0.753353 0.688166 +0.754608 0.688383 +0.755870 0.688189 +0.754608 0.688383 +0.755870 0.688189 +0.757170 0.687542 +0.758430 0.686411 +0.757170 0.687542 +0.758430 0.686411 +0.759565 0.684822 +0.759565 0.684822 +0.760499 0.682862 +0.760499 0.682862 +0.761181 0.680662 +0.761181 0.680662 +0.761593 0.678374 +0.761593 0.678374 +0.762714 0.623363 +0.762714 0.623363 +0.748955 0.625476 +0.748881 0.623234 +0.748881 0.623234 +0.749284 0.627771 +0.748955 0.625476 +0.749885 0.629982 +0.749284 0.627771 +0.750748 0.631960 +0.749885 0.629982 +0.751824 0.633569 +0.750748 0.631960 +0.751824 0.633569 +0.753042 0.634723 +0.753042 0.634723 +0.754318 0.635394 +0.754318 0.635394 +0.755572 0.635612 +0.755572 0.635612 +0.756835 0.635418 +0.756835 0.635418 +0.758134 0.634771 +0.758134 0.634771 +0.759394 0.633640 +0.760529 0.632051 +0.759394 0.633640 +0.760529 0.632051 +0.761463 0.630090 +0.761463 0.630090 +0.762145 0.627891 +0.762145 0.627891 +0.762557 0.625602 +0.762557 0.625602 +0.800703 0.681030 +0.801115 0.678742 +0.801271 0.676503 +0.801271 0.676503 +0.787439 0.676374 +0.787439 0.676374 +0.787513 0.678615 +0.787841 0.680911 +0.787513 0.678615 +0.788443 0.683122 +0.787841 0.680911 +0.789305 0.685099 +0.788443 0.683122 +0.789305 0.685099 +0.790382 0.686709 +0.790382 0.686709 +0.791600 0.687863 +0.791600 0.687863 +0.792875 0.688534 +0.792875 0.688534 +0.794130 0.688751 +0.795392 0.688558 +0.794130 0.688751 +0.796692 0.687911 +0.795392 0.688558 +0.797951 0.686780 +0.796692 0.687911 +0.799086 0.685190 +0.797951 0.686780 +0.799086 0.685190 +0.800021 0.683230 +0.800703 0.681030 +0.800021 0.683230 +0.801115 0.678742 +0.802079 0.625970 +0.802236 0.623731 +0.802236 0.623731 +0.802079 0.625970 +0.788403 0.623602 +0.788403 0.623602 +0.788478 0.625844 +0.788478 0.625844 +0.788806 0.628139 +0.788806 0.628139 +0.789407 0.630351 +0.790270 0.632328 +0.789407 0.630351 +0.790270 0.632328 +0.791346 0.633937 +0.792564 0.635092 +0.791346 0.633937 +0.793839 0.635763 +0.792564 0.635092 +0.795094 0.635980 +0.793839 0.635763 +0.795094 0.635980 +0.796357 0.635786 +0.797656 0.635139 +0.796357 0.635786 +0.797656 0.635139 +0.798916 0.634008 +0.798916 0.634008 +0.800051 0.632419 +0.800051 0.632419 +0.800985 0.630458 +0.800985 0.630458 +0.801667 0.628259 +0.801667 0.628259 +0.840637 0.679110 +0.840793 0.676871 +0.840793 0.676871 +0.840637 0.679110 +0.826961 0.676742 +0.826961 0.676742 +0.827035 0.678983 +0.827363 0.681279 +0.827035 0.678983 +0.827965 0.683490 +0.827363 0.681279 +0.827965 0.683490 +0.828827 0.685468 +0.828827 0.685468 +0.829904 0.687077 +0.829904 0.687077 +0.831122 0.688231 +0.831122 0.688231 +0.832397 0.688902 +0.832397 0.688902 +0.833652 0.689120 +0.833652 0.689120 +0.834914 0.688926 +0.834914 0.688926 +0.836214 0.688279 +0.836214 0.688279 +0.837473 0.687148 +0.837473 0.687148 +0.838608 0.685559 +0.839543 0.683598 +0.838608 0.685559 +0.839543 0.683598 +0.840225 0.681399 +0.840225 0.681399 +0.841758 0.624099 +0.841758 0.624099 +0.827999 0.626212 +0.827925 0.623970 +0.827925 0.623970 +0.827999 0.626212 +0.828328 0.628507 +0.828328 0.628507 +0.828929 0.630719 +0.828929 0.630719 +0.829792 0.632696 +0.829792 0.632696 +0.830868 0.634306 +0.830868 0.634306 +0.832086 0.635460 +0.832086 0.635460 +0.833361 0.636131 +0.833361 0.636131 +0.834616 0.636348 +0.834616 0.636348 +0.835878 0.636154 +0.835878 0.636154 +0.837178 0.635507 +0.837178 0.635507 +0.838438 0.634376 +0.838438 0.634376 +0.839573 0.632787 +0.839573 0.632787 +0.840507 0.630827 +0.840507 0.630827 +0.841189 0.628627 +0.841189 0.628627 +0.841601 0.626339 +0.841601 0.626339 +0.880315 0.677239 +0.880315 0.677239 +0.866483 0.677110 +0.866483 0.677110 +0.866557 0.679352 +0.866885 0.681647 +0.866557 0.679352 +0.867487 0.683858 +0.866885 0.681647 +0.868349 0.685836 +0.867487 0.683858 +0.869426 0.687445 +0.868349 0.685836 +0.869426 0.687445 +0.870644 0.688599 +0.870644 0.688599 +0.871919 0.689270 +0.871919 0.689270 +0.873174 0.689488 +0.874436 0.689294 +0.873174 0.689488 +0.874436 0.689294 +0.875736 0.688647 +0.876995 0.687516 +0.875736 0.688647 +0.878130 0.685927 +0.876995 0.687516 +0.879065 0.683966 +0.878130 0.685927 +0.879747 0.681767 +0.879065 0.683966 +0.879747 0.681767 +0.880159 0.679478 +0.880159 0.679478 +0.867521 0.626580 +0.867447 0.624338 +0.881123 0.626707 +0.881279 0.624467 +0.881279 0.624467 +0.881123 0.626707 +0.880711 0.628995 +0.880711 0.628995 +0.880029 0.631195 +0.880029 0.631195 +0.879095 0.633155 +0.879095 0.633155 +0.877959 0.634744 +0.877959 0.634744 +0.876700 0.635875 +0.875400 0.636522 +0.876700 0.635875 +0.875400 0.636522 +0.874138 0.636716 +0.874138 0.636716 +0.872883 0.636499 +0.872883 0.636499 +0.871608 0.635828 +0.871608 0.635828 +0.870390 0.634674 +0.869313 0.633064 +0.870390 0.634674 +0.868451 0.631087 +0.869313 0.633064 +0.867849 0.628875 +0.868451 0.631087 +0.867521 0.626580 +0.867849 0.628875 +0.867447 0.624338 +0.484940 0.675797 +0.485096 0.673557 +0.485096 0.673557 +0.484940 0.675797 +0.471263 0.673428 +0.471263 0.673428 +0.471338 0.675670 +0.471338 0.675670 +0.471666 0.677965 +0.471666 0.677965 +0.472268 0.680177 +0.473130 0.682154 +0.472268 0.680177 +0.473130 0.682154 +0.474207 0.683764 +0.474207 0.683764 +0.475425 0.684918 +0.475425 0.684918 +0.476700 0.685589 +0.476700 0.685589 +0.477955 0.685806 +0.477955 0.685806 +0.479217 0.685612 +0.479217 0.685612 +0.480516 0.684965 +0.480516 0.684965 +0.481776 0.683834 +0.481776 0.683834 +0.482911 0.682245 +0.482911 0.682245 +0.483846 0.680285 +0.483846 0.680285 +0.484528 0.678085 +0.484528 0.678085 +0.484810 0.627513 +0.485904 0.623025 +0.486060 0.620786 +0.486060 0.620786 +0.485904 0.623025 +0.485492 0.625313 +0.484810 0.627513 +0.485492 0.625313 +0.472228 0.620657 +0.472228 0.620657 +0.472302 0.622898 +0.472630 0.625194 +0.472302 0.622898 +0.472630 0.625194 +0.473232 0.627405 +0.474094 0.629382 +0.473232 0.627405 +0.475171 0.630992 +0.474094 0.629382 +0.475171 0.630992 +0.476389 0.632146 +0.476389 0.632146 +0.477664 0.632817 +0.477664 0.632817 +0.478919 0.633034 +0.478919 0.633034 +0.480181 0.632841 +0.480181 0.632841 +0.481481 0.632194 +0.481481 0.632194 +0.482740 0.631063 +0.482740 0.631063 +0.483875 0.629474 +0.483875 0.629474 +0.445006 0.677717 +0.445574 0.673189 +0.445574 0.673189 +0.445418 0.675428 +0.445418 0.675428 +0.445006 0.677717 +0.431741 0.673060 +0.431741 0.673060 +0.431816 0.675302 +0.431816 0.675302 +0.432144 0.677597 +0.432144 0.677597 +0.432746 0.679808 +0.433608 0.681786 +0.432746 0.679808 +0.433608 0.681786 +0.434685 0.683396 +0.434685 0.683396 +0.435903 0.684550 +0.435903 0.684550 +0.437178 0.685221 +0.438433 0.685438 +0.437178 0.685221 +0.439695 0.685244 +0.438433 0.685438 +0.440994 0.684597 +0.439695 0.685244 +0.442254 0.683466 +0.440994 0.684597 +0.442254 0.683466 +0.443389 0.681877 +0.443389 0.681877 +0.444324 0.679916 +0.444324 0.679916 +0.446382 0.622657 +0.446382 0.622657 +0.446538 0.620417 +0.446538 0.620417 +0.432706 0.620288 +0.432706 0.620288 +0.432780 0.622530 +0.433108 0.624825 +0.432780 0.622530 +0.433710 0.627037 +0.433108 0.624825 +0.434572 0.629014 +0.433710 0.627037 +0.435649 0.630624 +0.434572 0.629014 +0.436867 0.631778 +0.435649 0.630624 +0.436867 0.631778 +0.438142 0.632449 +0.438142 0.632449 +0.439397 0.632666 +0.439397 0.632666 +0.440659 0.632472 +0.440659 0.632472 +0.441959 0.631826 +0.441959 0.631826 +0.443218 0.630694 +0.443218 0.630694 +0.444353 0.629105 +0.444353 0.629105 +0.445288 0.627145 +0.445970 0.624945 +0.445288 0.627145 +0.445970 0.624945 +0.405896 0.675060 +0.406052 0.672821 +0.406052 0.672821 +0.405896 0.675060 +0.392219 0.672692 +0.392219 0.672692 +0.392294 0.674934 +0.392622 0.677229 +0.392294 0.674934 +0.392622 0.677229 +0.393224 0.679440 +0.393224 0.679440 +0.394086 0.681418 +0.394086 0.681418 +0.395163 0.683027 +0.395163 0.683027 +0.396381 0.684181 +0.397656 0.684852 +0.396381 0.684181 +0.397656 0.684852 +0.398911 0.685070 +0.398911 0.685070 +0.400173 0.684876 +0.401472 0.684229 +0.400173 0.684876 +0.401472 0.684229 +0.402732 0.683098 +0.402732 0.683098 +0.403867 0.681509 +0.403867 0.681509 +0.404802 0.679548 +0.405484 0.677349 +0.404802 0.679548 +0.405484 0.677349 +0.406860 0.622289 +0.406860 0.622289 +0.407016 0.620049 +0.407016 0.620049 +0.393184 0.619920 +0.393184 0.619920 +0.393258 0.622162 +0.393586 0.624457 +0.393258 0.622162 +0.393586 0.624457 +0.394188 0.626669 +0.395050 0.628646 +0.394188 0.626669 +0.395050 0.628646 +0.396127 0.630256 +0.396127 0.630256 +0.397345 0.631410 +0.398620 0.632081 +0.397345 0.631410 +0.398620 0.632081 +0.399875 0.632298 +0.399875 0.632298 +0.401137 0.632104 +0.401137 0.632104 +0.402437 0.631457 +0.402437 0.631457 +0.403696 0.630326 +0.403696 0.630326 +0.404831 0.628737 +0.405766 0.626777 +0.404831 0.628737 +0.405766 0.626777 +0.406448 0.624577 +0.406448 0.624577 +0.354564 0.681049 +0.352772 0.674565 +0.352698 0.672324 +0.352698 0.672324 +0.353100 0.676861 +0.352772 0.674565 +0.353100 0.676861 +0.353702 0.679072 +0.353702 0.679072 +0.354564 0.681049 +0.366530 0.672453 +0.366530 0.672453 +0.366374 0.674692 +0.366374 0.674692 +0.365962 0.676981 +0.365962 0.676981 +0.365280 0.679180 +0.365280 0.679180 +0.364345 0.681141 +0.363210 0.682730 +0.364345 0.681141 +0.363210 0.682730 +0.361951 0.683861 +0.361951 0.683861 +0.360651 0.684508 +0.360651 0.684508 +0.359389 0.684702 +0.359389 0.684702 +0.358134 0.684484 +0.358134 0.684484 +0.356859 0.683813 +0.356859 0.683813 +0.355641 0.682659 +0.355641 0.682659 +0.367338 0.621921 +0.367338 0.621921 +0.367494 0.619681 +0.367494 0.619681 +0.353662 0.619552 +0.353662 0.619552 +0.353736 0.621794 +0.354065 0.624089 +0.353736 0.621794 +0.354666 0.626301 +0.354065 0.624089 +0.355528 0.628278 +0.354666 0.626301 +0.356605 0.629888 +0.355528 0.628278 +0.357823 0.631042 +0.356605 0.629888 +0.357823 0.631042 +0.359098 0.631713 +0.359098 0.631713 +0.360353 0.631930 +0.360353 0.631930 +0.361615 0.631736 +0.362915 0.631089 +0.361615 0.631736 +0.362915 0.631089 +0.364175 0.629958 +0.364175 0.629958 +0.365310 0.628369 +0.365310 0.628369 +0.366244 0.626409 +0.366926 0.624209 +0.366244 0.626409 +0.366926 0.624209 +0.314180 0.678704 +0.313250 0.674197 +0.313176 0.671956 +0.313176 0.671956 +0.313250 0.674197 +0.313578 0.676493 +0.326852 0.674324 +0.327008 0.672084 +0.327008 0.672084 +0.326440 0.676612 +0.326852 0.674324 +0.326440 0.676612 +0.325758 0.678812 +0.324823 0.680772 +0.325758 0.678812 +0.324823 0.680772 +0.323688 0.682361 +0.323688 0.682361 +0.322429 0.683492 +0.322429 0.683492 +0.321129 0.684140 +0.321129 0.684140 +0.319867 0.684333 +0.319867 0.684333 +0.318612 0.684116 +0.318612 0.684116 +0.317337 0.683445 +0.317337 0.683445 +0.316119 0.682291 +0.316119 0.682291 +0.315042 0.680681 +0.314180 0.678704 +0.315042 0.680681 +0.313578 0.676493 +0.326722 0.626040 +0.327816 0.621552 +0.327973 0.619313 +0.327973 0.619313 +0.327816 0.621552 +0.327404 0.623841 +0.314140 0.619184 +0.314140 0.619184 +0.314214 0.621426 +0.314543 0.623721 +0.314214 0.621426 +0.315144 0.625932 +0.314543 0.623721 +0.316006 0.627910 +0.315144 0.625932 +0.317083 0.629519 +0.316006 0.627910 +0.317083 0.629519 +0.318301 0.630673 +0.318301 0.630673 +0.319577 0.631344 +0.320831 0.631562 +0.319577 0.631344 +0.322093 0.631368 +0.320831 0.631562 +0.323393 0.630721 +0.322093 0.631368 +0.324653 0.629590 +0.323393 0.630721 +0.324653 0.629590 +0.325788 0.628001 +0.325788 0.628001 +0.326722 0.626040 +0.327404 0.623841 +0.279090 0.683748 +0.273728 0.673829 +0.273654 0.671587 +0.273654 0.671587 +0.273728 0.673829 +0.274057 0.676124 +0.274658 0.678336 +0.274057 0.676124 +0.274658 0.678336 +0.275520 0.680313 +0.275520 0.680313 +0.276597 0.681923 +0.277815 0.683077 +0.276597 0.681923 +0.279090 0.683748 +0.277815 0.683077 +0.287486 0.671716 +0.287486 0.671716 +0.287330 0.673956 +0.287330 0.673956 +0.286918 0.676244 +0.286918 0.676244 +0.286236 0.678444 +0.286236 0.678444 +0.285302 0.680404 +0.284166 0.681993 +0.285302 0.680404 +0.284166 0.681993 +0.282907 0.683124 +0.282907 0.683124 +0.281607 0.683771 +0.281607 0.683771 +0.280345 0.683965 +0.280345 0.683965 +0.287882 0.623473 +0.288294 0.621184 +0.288451 0.618945 +0.288451 0.618945 +0.287882 0.623473 +0.288294 0.621184 +0.274618 0.618816 +0.274618 0.618816 +0.274692 0.621057 +0.274692 0.621057 +0.275021 0.623353 +0.275021 0.623353 +0.275622 0.625564 +0.275622 0.625564 +0.276485 0.627541 +0.277561 0.629151 +0.276485 0.627541 +0.277561 0.629151 +0.278779 0.630305 +0.278779 0.630305 +0.280055 0.630976 +0.280055 0.630976 +0.281309 0.631194 +0.281309 0.631194 +0.282572 0.631000 +0.283871 0.630353 +0.282572 0.631000 +0.283871 0.630353 +0.285131 0.629222 +0.286266 0.627633 +0.285131 0.629222 +0.286266 0.627633 +0.287200 0.625672 +0.287200 0.625672 +0.247964 0.671348 +0.247964 0.671348 +0.234206 0.673461 +0.234132 0.671219 +0.234132 0.671219 +0.234535 0.675756 +0.234206 0.673461 +0.235136 0.677968 +0.234535 0.675756 +0.235998 0.679945 +0.235136 0.677968 +0.235998 0.679945 +0.237075 0.681555 +0.237075 0.681555 +0.238293 0.682709 +0.238293 0.682709 +0.239568 0.683380 +0.239568 0.683380 +0.240823 0.683597 +0.240823 0.683597 +0.242085 0.683403 +0.242085 0.683403 +0.243385 0.682756 +0.243385 0.682756 +0.244644 0.681625 +0.244644 0.681625 +0.245780 0.680036 +0.246714 0.678076 +0.245780 0.680036 +0.246714 0.678076 +0.247396 0.675876 +0.247808 0.673588 +0.247396 0.675876 +0.247808 0.673588 +0.248772 0.620816 +0.248929 0.618577 +0.235096 0.618448 +0.235096 0.618448 +0.235171 0.620689 +0.235171 0.620689 +0.235499 0.622985 +0.235499 0.622985 +0.236100 0.625196 +0.236100 0.625196 +0.236963 0.627173 +0.238039 0.628783 +0.236963 0.627173 +0.238039 0.628783 +0.239257 0.629937 +0.239257 0.629937 +0.240533 0.630608 +0.240533 0.630608 +0.241787 0.630825 +0.243050 0.630632 +0.241787 0.630825 +0.244349 0.629985 +0.243050 0.630632 +0.245609 0.628853 +0.244349 0.629985 +0.246744 0.627264 +0.245609 0.628853 +0.246744 0.627264 +0.247678 0.625304 +0.247678 0.625304 +0.248360 0.623104 +0.248360 0.623104 +0.248772 0.620816 +0.248929 0.618577 +0.208442 0.670980 +0.208442 0.670980 +0.194684 0.673093 +0.194610 0.670851 +0.194610 0.670851 +0.194684 0.673093 +0.195013 0.675388 +0.195614 0.677600 +0.195013 0.675388 +0.196476 0.679577 +0.195614 0.677600 +0.196476 0.679577 +0.197553 0.681186 +0.198771 0.682341 +0.197553 0.681186 +0.198771 0.682341 +0.200046 0.683011 +0.200046 0.683011 +0.201301 0.683229 +0.202563 0.683035 +0.201301 0.683229 +0.202563 0.683035 +0.203863 0.682388 +0.205122 0.681257 +0.203863 0.682388 +0.205122 0.681257 +0.206258 0.679668 +0.206258 0.679668 +0.207192 0.677707 +0.207192 0.677707 +0.207874 0.675508 +0.208286 0.673219 +0.207874 0.675508 +0.208286 0.673219 +0.209407 0.618208 +0.209407 0.618208 +0.195574 0.618079 +0.195574 0.618079 +0.195649 0.620321 +0.195649 0.620321 +0.195977 0.622616 +0.195977 0.622616 +0.196578 0.624828 +0.197441 0.626805 +0.196578 0.624828 +0.197441 0.626805 +0.198517 0.628415 +0.198517 0.628415 +0.199735 0.629569 +0.201011 0.630240 +0.199735 0.629569 +0.202265 0.630457 +0.201011 0.630240 +0.203528 0.630263 +0.202265 0.630457 +0.204827 0.629616 +0.203528 0.630263 +0.204827 0.629616 +0.206087 0.628485 +0.207222 0.626896 +0.206087 0.628485 +0.207222 0.626896 +0.208156 0.624936 +0.208156 0.624936 +0.208838 0.622736 +0.208838 0.622736 +0.209250 0.620448 +0.209250 0.620448 +0.168921 0.670612 +0.168921 0.670612 +0.155162 0.672724 +0.155088 0.670483 +0.155088 0.670483 +0.155162 0.672724 +0.155491 0.675020 +0.156092 0.677231 +0.155491 0.675020 +0.156955 0.679209 +0.156092 0.677231 +0.156955 0.679209 +0.158031 0.680818 +0.159249 0.681972 +0.158031 0.680818 +0.159249 0.681972 +0.160524 0.682643 +0.160524 0.682643 +0.161779 0.682861 +0.161779 0.682861 +0.163042 0.682667 +0.163042 0.682667 +0.164341 0.682020 +0.164341 0.682020 +0.165601 0.680889 +0.165601 0.680889 +0.166736 0.679300 +0.166736 0.679300 +0.167670 0.677339 +0.167670 0.677339 +0.168352 0.675140 +0.168764 0.672851 +0.168352 0.675140 +0.168764 0.672851 +0.169885 0.617840 +0.169885 0.617840 +0.156052 0.617711 +0.156052 0.617711 +0.156127 0.619953 +0.156455 0.622248 +0.156127 0.619953 +0.156455 0.622248 +0.157056 0.624460 +0.157919 0.626437 +0.157056 0.624460 +0.157919 0.626437 +0.158995 0.628047 +0.158995 0.628047 +0.160213 0.629201 +0.161489 0.629872 +0.160213 0.629201 +0.161489 0.629872 +0.162744 0.630089 +0.162744 0.630089 +0.164006 0.629895 +0.165305 0.629248 +0.164006 0.629895 +0.165305 0.629248 +0.166565 0.628117 +0.167700 0.626528 +0.166565 0.628117 +0.167700 0.626528 +0.168634 0.624568 +0.168634 0.624568 +0.169316 0.622368 +0.169316 0.622368 +0.169728 0.620080 +0.169728 0.620080 +0.861036 0.650669 +0.861036 0.650669 +0.847204 0.650540 +0.847204 0.650540 +0.847278 0.652782 +0.847607 0.655077 +0.847278 0.652782 +0.848208 0.657289 +0.847607 0.655077 +0.848208 0.657289 +0.849070 0.659266 +0.849070 0.659266 +0.850147 0.660875 +0.850147 0.660875 +0.851365 0.662030 +0.851365 0.662030 +0.852640 0.662701 +0.852640 0.662701 +0.853895 0.662918 +0.853895 0.662918 +0.855157 0.662724 +0.855157 0.662724 +0.856457 0.662077 +0.856457 0.662077 +0.857716 0.660946 +0.858851 0.659357 +0.857716 0.660946 +0.858851 0.659357 +0.859786 0.657396 +0.859786 0.657396 +0.860468 0.655197 +0.860468 0.655197 +0.860880 0.652909 +0.860880 0.652909 +0.821514 0.650301 +0.821514 0.650301 +0.807682 0.650172 +0.807682 0.650172 +0.807756 0.652414 +0.808084 0.654709 +0.807756 0.652414 +0.808084 0.654709 +0.808686 0.656920 +0.808686 0.656920 +0.809548 0.658898 +0.809548 0.658898 +0.810625 0.660507 +0.810625 0.660507 +0.811843 0.661661 +0.811843 0.661661 +0.813118 0.662332 +0.813118 0.662332 +0.814373 0.662550 +0.814373 0.662550 +0.815635 0.662356 +0.815635 0.662356 +0.816935 0.661709 +0.816935 0.661709 +0.818195 0.660578 +0.818195 0.660578 +0.819330 0.658989 +0.819330 0.658989 +0.820264 0.657028 +0.820946 0.654829 +0.820264 0.657028 +0.821358 0.652540 +0.820946 0.654829 +0.821358 0.652540 +0.781992 0.649933 +0.781992 0.649933 +0.768234 0.652045 +0.768160 0.649804 +0.768160 0.649804 +0.768234 0.652045 +0.768563 0.654341 +0.768563 0.654341 +0.769164 0.656552 +0.769164 0.656552 +0.770027 0.658529 +0.770027 0.658529 +0.771103 0.660139 +0.771103 0.660139 +0.772321 0.661293 +0.772321 0.661293 +0.773596 0.661964 +0.773596 0.661964 +0.774851 0.662182 +0.774851 0.662182 +0.776113 0.661988 +0.776113 0.661988 +0.777413 0.661341 +0.777413 0.661341 +0.778673 0.660210 +0.779808 0.658621 +0.778673 0.660210 +0.779808 0.658621 +0.780742 0.656660 +0.780742 0.656660 +0.781424 0.654461 +0.781424 0.654461 +0.781836 0.652172 +0.781836 0.652172 +0.732799 0.660925 +0.728712 0.651677 +0.728638 0.649436 +0.728638 0.649436 +0.729041 0.653973 +0.728712 0.651677 +0.729642 0.656184 +0.729041 0.653973 +0.730505 0.658161 +0.729642 0.656184 +0.730505 0.658161 +0.731581 0.659771 +0.731581 0.659771 +0.732799 0.660925 +0.742314 0.651804 +0.742471 0.649565 +0.742471 0.649565 +0.742314 0.651804 +0.741902 0.654092 +0.741220 0.656292 +0.741902 0.654092 +0.741220 0.656292 +0.740286 0.658252 +0.739151 0.659841 +0.740286 0.658252 +0.739151 0.659841 +0.737891 0.660972 +0.737891 0.660972 +0.736592 0.661619 +0.736592 0.661619 +0.735329 0.661813 +0.735329 0.661813 +0.734074 0.661596 +0.734074 0.661596 +0.702949 0.649196 +0.702949 0.649196 +0.689116 0.649067 +0.689116 0.649067 +0.689191 0.651309 +0.689519 0.653604 +0.689191 0.651309 +0.689519 0.653604 +0.690120 0.655816 +0.690983 0.657793 +0.690120 0.655816 +0.692059 0.659403 +0.690983 0.657793 +0.692059 0.659403 +0.693277 0.660557 +0.693277 0.660557 +0.694553 0.661228 +0.695807 0.661445 +0.694553 0.661228 +0.697070 0.661251 +0.695807 0.661445 +0.697070 0.661251 +0.698369 0.660604 +0.699629 0.659473 +0.698369 0.660604 +0.700764 0.657884 +0.699629 0.659473 +0.700764 0.657884 +0.701698 0.655924 +0.701698 0.655924 +0.702380 0.653724 +0.702380 0.653724 +0.702792 0.651436 +0.702792 0.651436 +0.663427 0.648828 +0.663427 0.648828 +0.649669 0.650941 +0.649594 0.648699 +0.649594 0.648699 +0.649997 0.653236 +0.649669 0.650941 +0.650598 0.655448 +0.649997 0.653236 +0.650598 0.655448 +0.651461 0.657425 +0.652537 0.659035 +0.651461 0.657425 +0.653755 0.660189 +0.652537 0.659035 +0.655031 0.660860 +0.653755 0.660189 +0.655031 0.660860 +0.656285 0.661077 +0.656285 0.661077 +0.657548 0.660883 +0.658847 0.660236 +0.657548 0.660883 +0.658847 0.660236 +0.660107 0.659105 +0.660107 0.659105 +0.661242 0.657516 +0.661242 0.657516 +0.662176 0.655556 +0.662858 0.653356 +0.662176 0.655556 +0.662858 0.653356 +0.663270 0.651068 +0.663270 0.651068 +0.623905 0.648460 +0.623905 0.648460 +0.610147 0.650573 +0.610072 0.648331 +0.610072 0.648331 +0.610475 0.652868 +0.610147 0.650573 +0.610475 0.652868 +0.611076 0.655079 +0.611939 0.657057 +0.611076 0.655079 +0.613015 0.658667 +0.611939 0.657057 +0.613015 0.658667 +0.614233 0.659821 +0.614233 0.659821 +0.615509 0.660492 +0.615509 0.660492 +0.616763 0.660709 +0.616763 0.660709 +0.618026 0.660515 +0.618026 0.660515 +0.619325 0.659868 +0.619325 0.659868 +0.620585 0.658737 +0.620585 0.658737 +0.621720 0.657148 +0.621720 0.657148 +0.622654 0.655187 +0.622654 0.655187 +0.623336 0.652988 +0.623336 0.652988 +0.623748 0.650699 +0.623748 0.650699 +0.584383 0.648092 +0.584383 0.648092 +0.570625 0.650205 +0.570550 0.647963 +0.570550 0.647963 +0.570953 0.652500 +0.570625 0.650205 +0.570953 0.652500 +0.571555 0.654711 +0.572417 0.656689 +0.571555 0.654711 +0.572417 0.656689 +0.573494 0.658298 +0.573494 0.658298 +0.574711 0.659452 +0.574711 0.659452 +0.575987 0.660123 +0.575987 0.660123 +0.577242 0.660341 +0.577242 0.660341 +0.578504 0.660147 +0.578504 0.660147 +0.579803 0.659500 +0.579803 0.659500 +0.581063 0.658369 +0.581063 0.658369 +0.582198 0.656780 +0.582198 0.656780 +0.583132 0.654819 +0.583132 0.654819 +0.583815 0.652620 +0.583815 0.652620 +0.584226 0.650331 +0.584226 0.650331 +0.544861 0.647724 +0.544861 0.647724 +0.531103 0.649836 +0.531028 0.647595 +0.531028 0.647595 +0.531431 0.652132 +0.531103 0.649836 +0.532033 0.654343 +0.531431 0.652132 +0.532033 0.654343 +0.532895 0.656320 +0.532895 0.656320 +0.533972 0.657930 +0.535190 0.659084 +0.533972 0.657930 +0.536465 0.659755 +0.535190 0.659084 +0.536465 0.659755 +0.537720 0.659972 +0.538982 0.659779 +0.537720 0.659972 +0.540281 0.659132 +0.538982 0.659779 +0.540281 0.659132 +0.541541 0.658001 +0.542676 0.656412 +0.541541 0.658001 +0.542676 0.656412 +0.543610 0.654451 +0.543610 0.654451 +0.544293 0.652252 +0.544293 0.652252 +0.544705 0.649963 +0.544705 0.649963 +0.505339 0.647355 +0.505339 0.647355 +0.491506 0.647227 +0.491506 0.647227 +0.491581 0.649468 +0.491909 0.651764 +0.491581 0.649468 +0.491909 0.651764 +0.492511 0.653975 +0.492511 0.653975 +0.493373 0.655952 +0.493373 0.655952 +0.494450 0.657562 +0.494450 0.657562 +0.495668 0.658716 +0.495668 0.658716 +0.496943 0.659387 +0.496943 0.659387 +0.498198 0.659604 +0.498198 0.659604 +0.499460 0.659410 +0.500759 0.658764 +0.499460 0.659410 +0.500759 0.658764 +0.502019 0.657632 +0.502019 0.657632 +0.503154 0.656043 +0.503154 0.656043 +0.504089 0.654083 +0.504089 0.654083 +0.504771 0.651883 +0.504771 0.651883 +0.505183 0.649595 +0.505183 0.649595 +0.465817 0.646987 +0.465817 0.646987 +0.451984 0.646858 +0.451984 0.646858 +0.452059 0.649100 +0.452387 0.651395 +0.452059 0.649100 +0.452387 0.651395 +0.452989 0.653607 +0.452989 0.653607 +0.453851 0.655584 +0.453851 0.655584 +0.454928 0.657194 +0.454928 0.657194 +0.456146 0.658348 +0.456146 0.658348 +0.457421 0.659019 +0.457421 0.659019 +0.458676 0.659236 +0.458676 0.659236 +0.459938 0.659042 +0.461237 0.658395 +0.459938 0.659042 +0.461237 0.658395 +0.462497 0.657264 +0.462497 0.657264 +0.463632 0.655675 +0.463632 0.655675 +0.464567 0.653715 +0.464567 0.653715 +0.465249 0.651515 +0.465249 0.651515 +0.465661 0.649227 +0.465661 0.649227 +0.416624 0.657980 +0.412537 0.648732 +0.412463 0.646490 +0.412463 0.646490 +0.412865 0.651027 +0.412537 0.648732 +0.413467 0.653239 +0.412865 0.651027 +0.413467 0.653239 +0.414329 0.655216 +0.415406 0.656826 +0.414329 0.655216 +0.416624 0.657980 +0.415406 0.656826 +0.426139 0.648859 +0.426295 0.646619 +0.426295 0.646619 +0.426139 0.648859 +0.425727 0.651147 +0.425045 0.653347 +0.425727 0.651147 +0.425045 0.653347 +0.424110 0.655307 +0.422975 0.656896 +0.424110 0.655307 +0.422975 0.656896 +0.421716 0.658027 +0.421716 0.658027 +0.420416 0.658674 +0.420416 0.658674 +0.419154 0.658868 +0.419154 0.658868 +0.417899 0.658651 +0.417899 0.658651 +0.386773 0.646251 +0.386773 0.646251 +0.373015 0.648364 +0.372941 0.646122 +0.372941 0.646122 +0.373343 0.650659 +0.373015 0.648364 +0.373945 0.652870 +0.373343 0.650659 +0.373945 0.652870 +0.374807 0.654848 +0.375884 0.656457 +0.374807 0.654848 +0.377102 0.657612 +0.375884 0.656457 +0.377102 0.657612 +0.378377 0.658282 +0.378377 0.658282 +0.379632 0.658500 +0.379632 0.658500 +0.380894 0.658306 +0.380894 0.658306 +0.382194 0.657659 +0.382194 0.657659 +0.383453 0.656528 +0.383453 0.656528 +0.384588 0.654939 +0.385523 0.652978 +0.384588 0.654939 +0.385523 0.652978 +0.386205 0.650779 +0.386205 0.650779 +0.386617 0.648490 +0.386617 0.648490 +0.347251 0.645883 +0.347251 0.645883 +0.333493 0.647996 +0.333419 0.645754 +0.333419 0.645754 +0.333821 0.650291 +0.333493 0.647996 +0.334423 0.652502 +0.333821 0.650291 +0.335285 0.654480 +0.334423 0.652502 +0.335285 0.654480 +0.336362 0.656089 +0.336362 0.656089 +0.337580 0.657243 +0.338855 0.657914 +0.337580 0.657243 +0.340110 0.658132 +0.338855 0.657914 +0.341372 0.657938 +0.340110 0.658132 +0.341372 0.657938 +0.342672 0.657291 +0.343931 0.656160 +0.342672 0.657291 +0.345067 0.654571 +0.343931 0.656160 +0.345067 0.654571 +0.346001 0.652610 +0.346001 0.652610 +0.346683 0.650411 +0.346683 0.650411 +0.347095 0.648122 +0.347095 0.648122 +0.307573 0.647754 +0.307729 0.645515 +0.307729 0.645515 +0.307573 0.647754 +0.293897 0.645386 +0.293897 0.645386 +0.293971 0.647627 +0.294300 0.649923 +0.293971 0.647627 +0.294300 0.649923 +0.294901 0.652134 +0.294901 0.652134 +0.295763 0.654111 +0.295763 0.654111 +0.296840 0.655721 +0.298058 0.656875 +0.296840 0.655721 +0.298058 0.656875 +0.299333 0.657546 +0.299333 0.657546 +0.300588 0.657763 +0.301850 0.657570 +0.300588 0.657763 +0.303150 0.656923 +0.301850 0.657570 +0.304409 0.655792 +0.303150 0.656923 +0.304409 0.655792 +0.305545 0.654202 +0.305545 0.654202 +0.306479 0.652242 +0.306479 0.652242 +0.307161 0.650042 +0.307161 0.650042 +0.268051 0.647386 +0.268207 0.645146 +0.268207 0.645146 +0.268051 0.647386 +0.254375 0.645018 +0.254375 0.645018 +0.254449 0.647259 +0.254778 0.649554 +0.254449 0.647259 +0.254778 0.649554 +0.255379 0.651766 +0.256241 0.653743 +0.255379 0.651766 +0.256241 0.653743 +0.257318 0.655353 +0.257318 0.655353 +0.258536 0.656507 +0.258536 0.656507 +0.259811 0.657178 +0.259811 0.657178 +0.261066 0.657395 +0.262328 0.657201 +0.261066 0.657395 +0.263628 0.656554 +0.262328 0.657201 +0.264888 0.655423 +0.263628 0.656554 +0.264888 0.655423 +0.266023 0.653834 +0.266023 0.653834 +0.266957 0.651874 +0.266957 0.651874 +0.267639 0.649674 +0.267639 0.649674 +0.228686 0.644778 +0.228686 0.644778 +0.214853 0.644649 +0.214853 0.644649 +0.214927 0.646891 +0.215256 0.649186 +0.214927 0.646891 +0.215256 0.649186 +0.215857 0.651398 +0.216720 0.653375 +0.215857 0.651398 +0.216720 0.653375 +0.217796 0.654985 +0.217796 0.654985 +0.219014 0.656139 +0.219014 0.656139 +0.220289 0.656810 +0.221544 0.657027 +0.220289 0.656810 +0.222807 0.656833 +0.221544 0.657027 +0.224106 0.656186 +0.222807 0.656833 +0.225366 0.655055 +0.224106 0.656186 +0.226501 0.653466 +0.225366 0.655055 +0.226501 0.653466 +0.227435 0.651506 +0.227435 0.651506 +0.228117 0.649306 +0.228117 0.649306 +0.228529 0.647018 +0.228529 0.647018 +0.189164 0.644410 +0.189164 0.644410 +0.175405 0.646523 +0.175331 0.644281 +0.175331 0.644281 +0.175734 0.648818 +0.175405 0.646523 +0.176335 0.651030 +0.175734 0.648818 +0.176335 0.651030 +0.177198 0.653007 +0.178274 0.654617 +0.177198 0.653007 +0.179492 0.655771 +0.178274 0.654617 +0.179492 0.655771 +0.180768 0.656442 +0.180768 0.656442 +0.182022 0.656659 +0.183285 0.656465 +0.182022 0.656659 +0.183285 0.656465 +0.184584 0.655818 +0.184584 0.655818 +0.185844 0.654687 +0.185844 0.654687 +0.186979 0.653098 +0.186979 0.653098 +0.187913 0.651137 +0.187913 0.651137 +0.188595 0.648938 +0.188595 0.648938 +0.189007 0.646650 +0.189007 0.646650 + + + + + + + + + + + +

32 0 32 0 1 0 1 2 1 5 3 5 2 4 2 3 5 3 5 6 5 4 7 4 2 8 2 7 9 7 4 10 4 5 11 5 7 12 7 6 13 6 4 14 4 9 15 9 6 16 6 7 17 7 9 18 9 8 19 8 6 20 6 11 21 11 8 22 8 9 23 9 11 24 11 10 25 10 8 26 8 13 27 13 10 28 10 11 29 11 13 30 13 12 31 12 10 32 10 15 33 15 12 34 12 13 35 13 15 36 15 14 37 14 12 38 12 17 39 17 14 40 14 15 41 15 17 42 17 16 43 16 14 44 14 19 45 19 16 46 16 17 47 17 19 48 19 18 49 18 16 50 16 21 51 21 18 52 18 19 53 19 21 54 21 20 55 20 18 56 18 23 57 23 20 58 20 21 59 21 23 60 23 22 61 22 20 62 20 25 63 25 22 64 22 23 65 23 25 66 25 24 67 24 22 68 22 27 69 27 24 70 24 25 71 25 27 72 27 26 73 26 24 74 24 29 75 29 26 76 26 27 77 27 29 78 29 28 79 28 26 80 26 31 81 31 28 82 28 29 83 29 31 84 31 30 85 30 28 86 28 33 87 33 30 88 30 31 89 31 33 90 33 32 91 32 30 92 30 0 93 0 32 94 32 33 95 33 66 96 66 34 97 34 35 98 35 40 99 40 36 100 36 37 101 37 40 102 40 38 103 38 36 104 36 40 105 40 39 106 39 38 107 38 41 108 41 39 109 39 40 110 40 43 111 43 39 112 39 41 113 41 43 114 43 42 115 42 39 116 39 45 117 45 42 118 42 43 119 43 45 120 45 44 121 44 42 122 42 47 123 47 44 124 44 45 125 45 47 126 47 46 127 46 44 128 44 50 129 50 46 130 46 47 131 47 50 132 50 48 133 48 46 134 46 50 135 50 49 136 49 48 137 48 51 138 51 49 139 49 50 140 50 53 141 53 49 142 49 51 143 51 53 144 53 52 145 52 49 146 49 55 147 55 52 148 52 53 149 53 55 150 55 54 151 54 52 152 52 57 153 57 54 154 54 55 155 55 57 156 57 56 157 56 54 158 54 59 159 59 56 160 56 57 161 57 59 162 59 58 163 58 56 164 56 61 165 61 58 166 58 59 167 59 61 168 61 60 169 60 58 170 58 63 171 63 60 172 60 61 173 61 63 174 63 62 175 62 60 176 60 65 177 65 62 178 62 63 179 63 65 180 65 64 181 64 62 182 62 67 183 67 64 184 64 65 185 65 67 186 67 66 187 66 64 188 64 34 189 34 66 190 66 67 191 67 100 192 100 68 193 68 69 194 69 73 195 73 70 196 70 71 197 71 73 198 73 72 199 72 70 200 70 75 201 75 72 202 72 73 203 73 75 204 75 74 205 74 72 206 72 78 207 78 74 208 74 75 209 75 78 210 78 76 211 76 74 212 74 78 213 78 77 214 77 76 215 76 80 216 80 77 217 77 78 218 78 80 219 80 79 220 79 77 221 77 82 222 82 79 223 79 80 224 80 82 225 82 81 226 81 79 227 79 83 228 83 81 229 81 82 230 82 85 231 85 81 232 81 83 233 83 85 234 85 84 235 84 81 236 81 87 237 87 84 238 84 85 239 85 87 240 87 86 241 86 84 242 84 89 243 89 86 244 86 87 245 87 89 246 89 88 247 88 86 248 86 91 249 91 88 250 88 89 251 89 91 252 91 90 253 90 88 254 88 93 255 93 90 256 90 91 257 91 93 258 93 92 259 92 90 260 90 95 261 95 92 262 92 93 263 93 95 264 95 94 265 94 92 266 92 98 267 98 94 268 94 95 269 95 98 270 98 96 271 96 94 272 94 98 273 98 97 274 97 96 275 96 99 276 99 97 277 97 98 278 98 101 279 101 97 280 97 99 281 99 101 282 101 100 283 100 97 284 97 68 285 68 100 286 100 101 287 101 134 288 134 102 289 102 103 290 103 107 291 107 104 292 104 105 293 105 107 294 107 106 295 106 104 296 104 109 297 109 106 298 106 107 299 107 109 300 109 108 301 108 106 302 106 111 303 111 108 304 108 109 305 109 111 306 111 110 307 110 108 308 108 113 309 113 110 310 110 111 311 111 113 312 113 112 313 112 110 314 110 115 315 115 112 316 112 113 317 113 115 318 115 114 319 114 112 320 112 117 321 117 114 322 114 115 323 115 117 324 117 116 325 116 114 326 114 119 327 119 116 328 116 117 329 117 119 330 119 118 331 118 116 332 116 121 333 121 118 334 118 119 335 119 121 336 121 120 337 120 118 338 118 123 339 123 120 340 120 121 341 121 123 342 123 122 343 122 120 344 120 125 345 125 122 346 122 123 347 123 125 348 125 124 349 124 122 350 122 127 351 127 124 352 124 125 353 125 127 354 127 126 355 126 124 356 124 129 357 129 126 358 126 127 359 127 129 360 129 128 361 128 126 362 126 131 363 131 128 364 128 129 365 129 131 366 131 130 367 130 128 368 128 133 369 133 130 370 130 131 371 131 133 372 133 132 373 132 130 374 130 135 375 135 132 376 132 133 377 133 135 378 135 134 379 134 132 380 132 102 381 102 134 382 134 135 383 135 168 384 168 136 385 136 137 386 137 141 387 141 138 388 138 139 389 139 141 390 141 140 391 140 138 392 138 143 393 143 140 394 140 141 395 141 143 396 143 142 397 142 140 398 140 145 399 145 142 400 142 143 401 143 145 402 145 144 403 144 142 404 142 147 405 147 144 406 144 145 407 145 147 408 147 146 409 146 144 410 144 149 411 149 146 412 146 147 413 147 149 414 149 148 415 148 146 416 146 151 417 151 148 418 148 149 419 149 151 420 151 150 421 150 148 422 148 153 423 153 150 424 150 151 425 151 153 426 153 152 427 152 150 428 150 155 429 155 152 430 152 153 431 153 155 432 155 154 433 154 152 434 152 157 435 157 154 436 154 155 437 155 157 438 157 156 439 156 154 440 154 159 441 159 156 442 156 157 443 157 159 444 159 158 445 158 156 446 156 161 447 161 158 448 158 159 449 159 161 450 161 160 451 160 158 452 158 163 453 163 160 454 160 161 455 161 163 456 163 162 457 162 160 458 160 165 459 165 162 460 162 163 461 163 165 462 165 164 463 164 162 464 162 167 465 167 164 466 164 165 467 165 167 468 167 166 469 166 164 470 164 169 471 169 166 472 166 167 473 167 169 474 169 168 475 168 166 476 166 136 477 136 168 478 168 169 479 169 202 480 202 170 481 170 171 482 171 175 483 175 172 484 172 173 485 173 175 486 175 174 487 174 172 488 172 177 489 177 174 490 174 175 491 175 177 492 177 176 493 176 174 494 174 179 495 179 176 496 176 177 497 177 179 498 179 178 499 178 176 500 176 181 501 181 178 502 178 179 503 179 181 504 181 180 505 180 178 506 178 183 507 183 180 508 180 181 509 181 183 510 183 182 511 182 180 512 180 185 513 185 182 514 182 183 515 183 185 516 185 184 517 184 182 518 182 187 519 187 184 520 184 185 521 185 187 522 187 186 523 186 184 524 184 189 525 189 186 526 186 187 527 187 189 528 189 188 529 188 186 530 186 191 531 191 188 532 188 189 533 189 191 534 191 190 535 190 188 536 188 193 537 193 190 538 190 191 539 191 193 540 193 192 541 192 190 542 190 195 543 195 192 544 192 193 545 193 195 546 195 194 547 194 192 548 192 198 549 198 194 550 194 195 551 195 198 552 198 196 553 196 194 554 194 198 555 198 197 556 197 196 557 196 200 558 200 197 559 197 198 560 198 200 561 200 199 562 199 197 563 197 201 564 201 199 565 199 200 566 200 203 567 203 199 568 199 201 569 201 203 570 203 202 571 202 199 572 199 170 573 170 202 574 202 203 575 203 236 576 236 204 577 204 205 578 205 209 579 209 206 580 206 207 581 207 209 582 209 208 583 208 206 584 206 211 585 211 208 586 208 209 587 209 211 588 211 210 589 210 208 590 208 213 591 213 210 592 210 211 593 211 213 594 213 212 595 212 210 596 210 215 597 215 212 598 212 213 599 213 215 600 215 214 601 214 212 602 212 217 603 217 214 604 214 215 605 215 217 606 217 216 607 216 214 608 214 219 609 219 216 610 216 217 611 217 219 612 219 218 613 218 216 614 216 221 615 221 218 616 218 219 617 219 221 618 221 220 619 220 218 620 218 223 621 223 220 622 220 221 623 221 223 624 223 222 625 222 220 626 220 225 627 225 222 628 222 223 629 223 225 630 225 224 631 224 222 632 222 227 633 227 224 634 224 225 635 225 227 636 227 226 637 226 224 638 224 229 639 229 226 640 226 227 641 227 229 642 229 228 643 228 226 644 226 231 645 231 228 646 228 229 647 229 231 648 231 230 649 230 228 650 228 233 651 233 230 652 230 231 653 231 233 654 233 232 655 232 230 656 230 235 657 235 232 658 232 233 659 233 235 660 235 234 661 234 232 662 232 237 663 237 234 664 234 235 665 235 237 666 237 236 667 236 234 668 234 204 669 204 236 670 236 237 671 237 270 672 270 238 673 238 239 674 239 243 675 243 240 676 240 241 677 241 243 678 243 242 679 242 240 680 240 245 681 245 242 682 242 243 683 243 245 684 245 244 685 244 242 686 242 247 687 247 244 688 244 245 689 245 247 690 247 246 691 246 244 692 244 249 693 249 246 694 246 247 695 247 249 696 249 248 697 248 246 698 246 251 699 251 248 700 248 249 701 249 251 702 251 250 703 250 248 704 248 253 705 253 250 706 250 251 707 251 253 708 253 252 709 252 250 710 250 255 711 255 252 712 252 253 713 253 255 714 255 254 715 254 252 716 252 257 717 257 254 718 254 255 719 255 257 720 257 256 721 256 254 722 254 259 723 259 256 724 256 257 725 257 259 726 259 258 727 258 256 728 256 261 729 261 258 730 258 259 731 259 261 732 261 260 733 260 258 734 258 263 735 263 260 736 260 261 737 261 263 738 263 262 739 262 260 740 260 265 741 265 262 742 262 263 743 263 265 744 265 264 745 264 262 746 262 267 747 267 264 748 264 265 749 265 267 750 267 266 751 266 264 752 264 269 753 269 266 754 266 267 755 267 269 756 269 268 757 268 266 758 266 271 759 271 268 760 268 269 761 269 271 762 271 270 763 270 268 764 268 238 765 238 270 766 270 271 767 271 304 768 304 272 769 272 273 770 273 277 771 277 274 772 274 275 773 275 277 774 277 276 775 276 274 776 274 279 777 279 276 778 276 277 779 277 279 780 279 278 781 278 276 782 276 281 783 281 278 784 278 279 785 279 281 786 281 280 787 280 278 788 278 283 789 283 280 790 280 281 791 281 283 792 283 282 793 282 280 794 280 285 795 285 282 796 282 283 797 283 285 798 285 284 799 284 282 800 282 287 801 287 284 802 284 285 803 285 287 804 287 286 805 286 284 806 284 289 807 289 286 808 286 287 809 287 289 810 289 288 811 288 286 812 286 291 813 291 288 814 288 289 815 289 291 816 291 290 817 290 288 818 288 293 819 293 290 820 290 291 821 291 293 822 293 292 823 292 290 824 290 295 825 295 292 826 292 293 827 293 295 828 295 294 829 294 292 830 292 297 831 297 294 832 294 295 833 295 297 834 297 296 835 296 294 836 294 299 837 299 296 838 296 297 839 297 299 840 299 298 841 298 296 842 296 301 843 301 298 844 298 299 845 299 301 846 301 300 847 300 298 848 298 303 849 303 300 850 300 301 851 301 303 852 303 302 853 302 300 854 300 305 855 305 302 856 302 303 857 303 305 858 305 304 859 304 302 860 302 272 861 272 304 862 304 305 863 305 337 864 337 306 865 306 307 866 307 311 867 311 308 868 308 309 869 309 311 870 311 310 871 310 308 872 308 313 873 313 310 874 310 311 875 311 313 876 313 312 877 312 310 878 310 316 879 316 312 880 312 313 881 313 316 882 316 314 883 314 312 884 312 316 885 316 315 886 315 314 887 314 317 888 317 315 889 315 316 890 316 319 891 319 315 892 315 317 893 317 319 894 319 318 895 318 315 896 315 321 897 321 318 898 318 319 899 319 321 900 321 320 901 320 318 902 318 323 903 323 320 904 320 321 905 321 323 906 323 322 907 322 320 908 320 325 909 325 322 910 322 323 911 323 325 912 325 324 913 324 322 914 322 327 915 327 324 916 324 325 917 325 327 918 327 326 919 326 324 920 324 329 921 329 326 922 326 327 923 327 329 924 329 328 925 328 326 926 326 331 927 331 328 928 328 329 929 329 331 930 331 330 931 330 328 932 328 333 933 333 330 934 330 331 935 331 333 936 333 332 937 332 330 938 330 335 939 335 332 940 332 333 941 333 335 942 335 334 943 334 332 944 332 338 945 338 334 946 334 335 947 335 338 948 338 336 949 336 334 950 334 338 951 338 337 952 337 336 953 336 339 954 339 337 955 337 338 956 338 306 957 306 337 958 337 339 959 339 372 960 372 340 961 340 341 962 341 344 963 344 342 964 342 343 965 343 345 966 345 342 967 342 344 968 344 348 969 348 342 970 342 345 971 345 348 972 348 346 973 346 342 974 342 348 975 348 347 976 347 346 977 346 349 978 349 347 979 347 348 980 348 351 981 351 347 982 347 349 983 349 351 984 351 350 985 350 347 986 347 353 987 353 350 988 350 351 989 351 353 990 353 352 991 352 350 992 350 355 993 355 352 994 352 353 995 353 355 996 355 354 997 354 352 998 352 357 999 357 354 1000 354 355 1001 355 357 1002 357 356 1003 356 354 1004 354 359 1005 359 356 1006 356 357 1007 357 359 1008 359 358 1009 358 356 1010 356 361 1011 361 358 1012 358 359 1013 359 361 1014 361 360 1015 360 358 1016 358 363 1017 363 360 1018 360 361 1019 361 363 1020 363 362 1021 362 360 1022 360 365 1023 365 362 1024 362 363 1025 363 365 1026 365 364 1027 364 362 1028 362 367 1029 367 364 1030 364 365 1031 365 367 1032 367 366 1033 366 364 1034 364 370 1035 370 366 1036 366 367 1037 367 370 1038 370 368 1039 368 366 1040 366 370 1041 370 369 1042 369 368 1043 368 371 1044 371 369 1045 369 370 1046 370 373 1047 373 369 1048 369 371 1049 371 373 1050 373 372 1051 372 369 1052 369 340 1053 340 372 1054 372 373 1055 373 406 1056 406 374 1057 374 375 1058 375 379 1059 379 376 1060 376 377 1061 377 379 1062 379 378 1063 378 376 1064 376 381 1065 381 378 1066 378 379 1067 379 381 1068 381 380 1069 380 378 1070 378 383 1071 383 380 1072 380 381 1073 381 383 1074 383 382 1075 382 380 1076 380 385 1077 385 382 1078 382 383 1079 383 385 1080 385 384 1081 384 382 1082 382 387 1083 387 384 1084 384 385 1085 385 387 1086 387 386 1087 386 384 1088 384 390 1089 390 386 1090 386 387 1091 387 390 1092 390 388 1093 388 386 1094 386 390 1095 390 389 1096 389 388 1097 388 391 1098 391 389 1099 389 390 1100 390 393 1101 393 389 1102 389 391 1103 391 393 1104 393 392 1105 392 389 1106 389 395 1107 395 392 1108 392 393 1109 393 395 1110 395 394 1111 394 392 1112 392 397 1113 397 394 1114 394 395 1115 395 397 1116 397 396 1117 396 394 1118 394 399 1119 399 396 1120 396 397 1121 397 399 1122 399 398 1123 398 396 1124 396 401 1125 401 398 1126 398 399 1127 399 401 1128 401 400 1129 400 398 1130 398 403 1131 403 400 1132 400 401 1133 401 403 1134 403 402 1135 402 400 1136 400 405 1137 405 402 1138 402 403 1139 403 405 1140 405 404 1141 404 402 1142 402 407 1143 407 404 1144 404 405 1145 405 407 1146 407 406 1147 406 404 1148 404 374 1149 374 406 1150 406 407 1151 407 439 1152 439 408 1153 408 409 1154 409 413 1155 413 410 1156 410 411 1157 411 413 1158 413 412 1159 412 410 1160 410 415 1161 415 412 1162 412 413 1163 413 415 1164 415 414 1165 414 412 1166 412 417 1167 417 414 1168 414 415 1169 415 417 1170 417 416 1171 416 414 1172 414 419 1173 419 416 1174 416 417 1175 417 419 1176 419 418 1177 418 416 1178 416 421 1179 421 418 1180 418 419 1181 419 421 1182 421 420 1183 420 418 1184 418 423 1185 423 420 1186 420 421 1187 421 423 1188 423 422 1189 422 420 1190 420 425 1191 425 422 1192 422 423 1193 423 425 1194 425 424 1195 424 422 1196 422 428 1197 428 424 1198 424 425 1199 425 428 1200 428 426 1201 426 424 1202 424 428 1203 428 427 1204 427 426 1205 426 429 1206 429 427 1207 427 428 1208 428 431 1209 431 427 1210 427 429 1211 429 431 1212 431 430 1213 430 427 1214 427 433 1215 433 430 1216 430 431 1217 431 433 1218 433 432 1219 432 430 1220 430 435 1221 435 432 1222 432 433 1223 433 435 1224 435 434 1225 434 432 1226 432 437 1227 437 434 1228 434 435 1229 435 437 1230 437 436 1231 436 434 1232 434 440 1233 440 436 1234 436 437 1235 437 440 1236 440 438 1237 438 436 1238 436 440 1239 440 439 1240 439 438 1241 438 441 1242 441 439 1243 439 440 1244 440 408 1245 408 439 1246 439 441 1247 441 474 1248 474 442 1249 442 443 1250 443 447 1251 447 444 1252 444 445 1253 445 447 1254 447 446 1255 446 444 1256 444 449 1257 449 446 1258 446 447 1259 447 449 1260 449 448 1261 448 446 1262 446 451 1263 451 448 1264 448 449 1265 449 451 1266 451 450 1267 450 448 1268 448 453 1269 453 450 1270 450 451 1271 451 453 1272 453 452 1273 452 450 1274 450 455 1275 455 452 1276 452 453 1277 453 455 1278 455 454 1279 454 452 1280 452 457 1281 457 454 1282 454 455 1283 455 457 1284 457 456 1285 456 454 1286 454 459 1287 459 456 1288 456 457 1289 457 459 1290 459 458 1291 458 456 1292 456 461 1293 461 458 1294 458 459 1295 459 461 1296 461 460 1297 460 458 1298 458 463 1299 463 460 1300 460 461 1301 461 463 1302 463 462 1303 462 460 1304 460 465 1305 465 462 1306 462 463 1307 463 465 1308 465 464 1309 464 462 1310 462 467 1311 467 464 1312 464 465 1313 465 467 1314 467 466 1315 466 464 1316 464 469 1317 469 466 1318 466 467 1319 467 469 1320 469 468 1321 468 466 1322 466 471 1323 471 468 1324 468 469 1325 469 471 1326 471 470 1327 470 468 1328 468 473 1329 473 470 1330 470 471 1331 471 473 1332 473 472 1333 472 470 1334 470 475 1335 475 472 1336 472 473 1337 473 475 1338 475 474 1339 474 472 1340 472 442 1341 442 474 1342 474 475 1343 475 507 1344 507 476 1345 476 477 1346 477 481 1347 481 478 1348 478 479 1349 479 481 1350 481 480 1351 480 478 1352 478 483 1353 483 480 1354 480 481 1355 481 483 1356 483 482 1357 482 480 1358 480 485 1359 485 482 1360 482 483 1361 483 485 1362 485 484 1363 484 482 1364 482 487 1365 487 484 1366 484 485 1367 485 487 1368 487 486 1369 486 484 1370 484 489 1371 489 486 1372 486 487 1373 487 489 1374 489 488 1375 488 486 1376 486 491 1377 491 488 1378 488 489 1379 489 491 1380 491 490 1381 490 488 1382 488 493 1383 493 490 1384 490 491 1385 491 493 1386 493 492 1387 492 490 1388 490 495 1389 495 492 1390 492 493 1391 493 495 1392 495 494 1393 494 492 1394 492 497 1395 497 494 1396 494 495 1397 495 497 1398 497 496 1399 496 494 1400 494 499 1401 499 496 1402 496 497 1403 497 499 1404 499 498 1405 498 496 1406 496 501 1407 501 498 1408 498 499 1409 499 501 1410 501 500 1411 500 498 1412 498 503 1413 503 500 1414 500 501 1415 501 503 1416 503 502 1417 502 500 1418 500 505 1419 505 502 1420 502 503 1421 503 505 1422 505 504 1423 504 502 1424 502 508 1425 508 504 1426 504 505 1427 505 508 1428 508 506 1429 506 504 1430 504 508 1431 508 507 1432 507 506 1433 506 509 1434 509 507 1435 507 508 1436 508 476 1437 476 507 1438 507 509 1439 509 542 1440 542 510 1441 510 511 1442 511 515 1443 515 512 1444 512 513 1445 513 515 1446 515 514 1447 514 512 1448 512 518 1449 518 514 1450 514 515 1451 515 518 1452 518 516 1453 516 514 1454 514 518 1455 518 517 1456 517 516 1457 516 519 1458 519 517 1459 517 518 1460 518 521 1461 521 517 1462 517 519 1463 519 521 1464 521 520 1465 520 517 1466 517 523 1467 523 520 1468 520 521 1469 521 523 1470 523 522 1471 522 520 1472 520 525 1473 525 522 1474 522 523 1475 523 525 1476 525 524 1477 524 522 1478 522 527 1479 527 524 1480 524 525 1481 525 527 1482 527 526 1483 526 524 1484 524 529 1485 529 526 1486 526 527 1487 527 529 1488 529 528 1489 528 526 1490 526 531 1491 531 528 1492 528 529 1493 529 531 1494 531 530 1495 530 528 1496 528 533 1497 533 530 1498 530 531 1499 531 533 1500 533 532 1501 532 530 1502 530 536 1503 536 532 1504 532 533 1505 533 536 1506 536 534 1507 534 532 1508 532 536 1509 536 535 1510 535 534 1511 534 537 1512 537 535 1513 535 536 1514 536 539 1515 539 535 1516 535 537 1517 537 539 1518 539 538 1519 538 535 1520 535 541 1521 541 538 1522 538 539 1523 539 541 1524 541 540 1525 540 538 1526 538 543 1527 543 540 1528 540 541 1529 541 543 1530 543 542 1531 542 540 1532 540 510 1533 510 542 1534 542 543 1535 543 576 1536 576 544 1537 544 545 1538 545 549 1539 549 546 1540 546 547 1541 547 549 1542 549 548 1543 548 546 1544 546 552 1545 552 548 1546 548 549 1547 549 552 1548 552 550 1549 550 548 1550 548 552 1551 552 551 1552 551 550 1553 550 553 1554 553 551 1555 551 552 1556 552 555 1557 555 551 1558 551 553 1559 553 555 1560 555 554 1561 554 551 1562 551 557 1563 557 554 1564 554 555 1565 555 557 1566 557 556 1567 556 554 1568 554 559 1569 559 556 1570 556 557 1571 557 559 1572 559 558 1573 558 556 1574 556 561 1575 561 558 1576 558 559 1577 559 561 1578 561 560 1579 560 558 1580 558 563 1581 563 560 1582 560 561 1583 561 563 1584 563 562 1585 562 560 1586 560 565 1587 565 562 1588 562 563 1589 563 565 1590 565 564 1591 564 562 1592 562 567 1593 567 564 1594 564 565 1595 565 567 1596 567 566 1597 566 564 1598 564 569 1599 569 566 1600 566 567 1601 567 569 1602 569 568 1603 568 566 1604 566 571 1605 571 568 1606 568 569 1607 569 571 1608 571 570 1609 570 568 1610 568 573 1611 573 570 1612 570 571 1613 571 573 1614 573 572 1615 572 570 1616 570 575 1617 575 572 1618 572 573 1619 573 575 1620 575 574 1621 574 572 1622 572 577 1623 577 574 1624 574 575 1625 575 577 1626 577 576 1627 576 574 1628 574 544 1629 544 576 1630 576 577 1631 577 610 1632 610 578 1633 578 579 1634 579 583 1635 583 580 1636 580 581 1637 581 583 1638 583 582 1639 582 580 1640 580 585 1641 585 582 1642 582 583 1643 583 585 1644 585 584 1645 584 582 1646 582 587 1647 587 584 1648 584 585 1649 585 587 1650 587 586 1651 586 584 1652 584 589 1653 589 586 1654 586 587 1655 587 589 1656 589 588 1657 588 586 1658 586 591 1659 591 588 1660 588 589 1661 589 591 1662 591 590 1663 590 588 1664 588 593 1665 593 590 1666 590 591 1667 591 593 1668 593 592 1669 592 590 1670 590 595 1671 595 592 1672 592 593 1673 593 595 1674 595 594 1675 594 592 1676 592 597 1677 597 594 1678 594 595 1679 595 597 1680 597 596 1681 596 594 1682 594 599 1683 599 596 1684 596 597 1685 597 599 1686 599 598 1687 598 596 1688 596 601 1689 601 598 1690 598 599 1691 599 601 1692 601 600 1693 600 598 1694 598 603 1695 603 600 1696 600 601 1697 601 603 1698 603 602 1699 602 600 1700 600 605 1701 605 602 1702 602 603 1703 603 605 1704 605 604 1705 604 602 1706 602 607 1707 607 604 1708 604 605 1709 605 607 1710 607 606 1711 606 604 1712 604 609 1713 609 606 1714 606 607 1715 607 609 1716 609 608 1717 608 606 1718 606 611 1719 611 608 1720 608 609 1721 609 611 1722 611 610 1723 610 608 1724 608 578 1725 578 610 1726 610 611 1727 611 645 1728 645 612 1729 612 613 1730 613 617 1731 617 614 1732 614 615 1733 615 617 1734 617 616 1735 616 614 1736 614 619 1737 619 616 1738 616 617 1739 617 619 1740 619 618 1741 618 616 1742 616 622 1743 622 618 1744 618 619 1745 619 622 1746 622 620 1747 620 618 1748 618 622 1749 622 621 1750 621 620 1751 620 623 1752 623 621 1753 621 622 1754 622 625 1755 625 621 1756 621 623 1757 623 625 1758 625 624 1759 624 621 1760 621 627 1761 627 624 1762 624 625 1763 625 627 1764 627 626 1765 626 624 1766 624 629 1767 629 626 1768 626 627 1769 627 629 1770 629 628 1771 628 626 1772 626 631 1773 631 628 1774 628 629 1775 629 631 1776 631 630 1777 630 628 1778 628 633 1779 633 630 1780 630 631 1781 631 633 1782 633 632 1783 632 630 1784 630 636 1785 636 632 1786 632 633 1787 633 636 1788 636 634 1789 634 632 1790 632 636 1791 636 635 1792 635 634 1793 634 637 1794 637 635 1795 635 636 1796 636 640 1797 640 635 1798 635 637 1799 637 640 1800 640 638 1801 638 635 1802 635 640 1803 640 639 1804 639 638 1805 638 641 1806 641 639 1807 639 640 1808 640 643 1809 643 639 1810 639 641 1811 641 643 1812 643 642 1813 642 639 1814 639 612 1815 612 642 1816 642 643 1817 643 612 1818 612 644 1819 644 642 1820 642 612 1821 612 645 1822 645 644 1823 644 678 1824 678 649 1825 649 646 1826 646 646 1827 646 647 1828 647 648 1829 648 646 1830 646 649 1831 649 647 1832 647 652 1833 652 650 1834 650 651 1835 651 653 1836 653 650 1837 650 652 1838 652 656 1839 656 650 1840 650 653 1841 653 656 1842 656 654 1843 654 650 1844 650 656 1845 656 655 1846 655 654 1847 654 657 1848 657 655 1849 655 656 1850 656 659 1851 659 655 1852 655 657 1853 657 659 1854 659 658 1855 658 655 1856 655 661 1857 661 658 1858 658 659 1859 659 661 1860 661 660 1861 660 658 1862 658 663 1863 663 660 1864 660 661 1865 661 663 1866 663 662 1867 662 660 1868 660 665 1869 665 662 1870 662 663 1871 663 665 1872 665 664 1873 664 662 1874 662 667 1875 667 664 1876 664 665 1877 665 667 1878 667 666 1879 666 664 1880 664 669 1881 669 666 1882 666 667 1883 667 669 1884 669 668 1885 668 666 1886 666 671 1887 671 668 1888 668 669 1889 669 671 1890 671 670 1891 670 668 1892 668 673 1893 673 670 1894 670 671 1895 671 673 1896 673 672 1897 672 670 1898 670 676 1899 676 672 1900 672 673 1901 673 676 1902 676 674 1903 674 672 1904 672 676 1905 676 675 1906 675 674 1907 674 677 1908 677 675 1909 675 676 1910 676 679 1911 679 675 1912 675 677 1913 677 679 1914 679 678 1915 678 675 1916 675 649 1917 649 678 1918 678 679 1919 679 713 1920 713 680 1921 680 681 1922 681 685 1923 685 682 1924 682 683 1925 683 685 1926 685 684 1927 684 682 1928 682 688 1929 688 684 1930 684 685 1931 685 688 1932 688 686 1933 686 684 1934 684 688 1935 688 687 1936 687 686 1937 686 689 1938 689 687 1939 687 688 1940 688 691 1941 691 687 1942 687 689 1943 689 691 1944 691 690 1945 690 687 1946 687 693 1947 693 690 1948 690 691 1949 691 693 1950 693 692 1951 692 690 1952 690 695 1953 695 692 1954 692 693 1955 693 695 1956 695 694 1957 694 692 1958 692 697 1959 697 694 1960 694 695 1961 695 697 1962 697 696 1963 696 694 1964 694 699 1965 699 696 1966 696 697 1967 697 699 1968 699 698 1969 698 696 1970 696 701 1971 701 698 1972 698 699 1973 699 701 1974 701 700 1975 700 698 1976 698 703 1977 703 700 1978 700 701 1979 701 703 1980 703 702 1981 702 700 1982 700 705 1983 705 702 1984 702 703 1985 703 705 1986 705 704 1987 704 702 1988 702 708 1989 708 704 1990 704 705 1991 705 708 1992 708 706 1993 706 704 1994 704 708 1995 708 707 1996 707 706 1997 706 709 1998 709 707 1999 707 708 2000 708 711 2001 711 707 2002 707 709 2003 709 711 2004 711 710 2005 710 707 2006 707 680 2007 680 710 2008 710 711 2009 711 680 2010 680 712 2011 712 710 2012 710 680 2013 680 713 2014 713 712 2015 712 746 2016 746 714 2017 714 715 2018 715 718 2019 718 716 2020 716 717 2021 717 720 2022 720 716 2023 716 718 2024 718 720 2025 720 719 2026 719 716 2027 716 721 2028 721 719 2029 719 720 2030 720 724 2031 724 719 2032 719 721 2033 721 724 2034 724 722 2035 722 719 2036 719 724 2037 724 723 2038 723 722 2039 722 725 2040 725 723 2041 723 724 2042 724 727 2043 727 723 2044 723 725 2045 725 727 2046 727 726 2047 726 723 2048 723 729 2049 729 726 2050 726 727 2051 727 729 2052 729 728 2053 728 726 2054 726 731 2055 731 728 2056 728 729 2057 729 731 2058 731 730 2059 730 728 2060 728 734 2061 734 730 2062 730 731 2063 731 734 2064 734 732 2065 732 730 2066 730 734 2067 734 733 2068 733 732 2069 732 735 2070 735 733 2071 733 734 2072 734 737 2073 737 733 2074 733 735 2075 735 737 2076 737 736 2077 736 733 2078 733 739 2079 739 736 2080 736 737 2081 737 739 2082 739 738 2083 738 736 2084 736 741 2085 741 738 2086 738 739 2087 739 741 2088 741 740 2089 740 738 2090 738 743 2091 743 740 2092 740 741 2093 741 743 2094 743 742 2095 742 740 2096 740 745 2097 745 742 2098 742 743 2099 743 745 2100 745 744 2101 744 742 2102 742 747 2103 747 744 2104 744 745 2105 745 747 2106 747 746 2107 746 744 2108 744 714 2109 714 746 2110 746 747 2111 747 781 2112 781 748 2113 748 749 2114 749 753 2115 753 750 2116 750 751 2117 751 753 2118 753 752 2119 752 750 2120 750 755 2121 755 752 2122 752 753 2123 753 755 2124 755 754 2125 754 752 2126 752 758 2127 758 754 2128 754 755 2129 755 758 2130 758 756 2131 756 754 2132 754 758 2133 758 757 2134 757 756 2135 756 759 2136 759 757 2137 757 758 2138 758 761 2139 761 757 2140 757 759 2141 759 761 2142 761 760 2143 760 757 2144 757 763 2145 763 760 2146 760 761 2147 761 763 2148 763 762 2149 762 760 2150 760 765 2151 765 762 2152 762 763 2153 763 765 2154 765 764 2155 764 762 2156 762 767 2157 767 764 2158 764 765 2159 765 767 2160 767 766 2161 766 764 2162 764 769 2163 769 766 2164 766 767 2165 767 769 2166 769 768 2167 768 766 2168 766 772 2169 772 768 2170 768 769 2171 769 772 2172 772 770 2173 770 768 2174 768 772 2175 772 771 2176 771 770 2177 770 773 2178 773 771 2179 771 772 2180 772 776 2181 776 771 2182 771 773 2183 773 776 2184 776 774 2185 774 771 2186 771 776 2187 776 775 2188 775 774 2189 774 777 2190 777 775 2191 775 776 2192 776 779 2193 779 775 2194 775 777 2195 777 779 2196 779 778 2197 778 775 2198 775 748 2199 748 778 2200 778 779 2201 779 748 2202 748 780 2203 780 778 2204 778 748 2205 748 781 2206 781 780 2207 780 814 2208 814 782 2209 782 783 2210 783 786 2211 786 784 2212 784 785 2213 785 788 2214 788 784 2215 784 786 2216 786 788 2217 788 787 2218 787 784 2219 784 789 2220 789 787 2221 787 788 2222 788 791 2223 791 787 2224 787 789 2225 789 791 2226 791 790 2227 790 787 2228 787 793 2229 793 790 2230 790 791 2231 791 793 2232 793 792 2233 792 790 2234 790 795 2235 795 792 2236 792 793 2237 793 795 2238 795 794 2239 794 792 2240 792 797 2241 797 794 2242 794 795 2243 795 797 2244 797 796 2245 796 794 2246 794 799 2247 799 796 2248 796 797 2249 797 799 2250 799 798 2251 798 796 2252 796 801 2253 801 798 2254 798 799 2255 799 801 2256 801 800 2257 800 798 2258 798 803 2259 803 800 2260 800 801 2261 801 803 2262 803 802 2263 802 800 2264 800 805 2265 805 802 2266 802 803 2267 803 805 2268 805 804 2269 804 802 2270 802 807 2271 807 804 2272 804 805 2273 805 807 2274 807 806 2275 806 804 2276 804 809 2277 809 806 2278 806 807 2279 807 809 2280 809 808 2281 808 806 2282 806 811 2283 811 808 2284 808 809 2285 809 811 2286 811 810 2287 810 808 2288 808 813 2289 813 810 2290 810 811 2291 811 813 2292 813 812 2293 812 810 2294 810 815 2295 815 812 2296 812 813 2297 813 815 2298 815 814 2299 814 812 2300 812 782 2301 782 814 2302 814 815 2303 815 847 2304 847 816 2305 816 817 2306 817 821 2307 821 818 2308 818 819 2309 819 821 2310 821 820 2311 820 818 2312 818 823 2313 823 820 2314 820 821 2315 821 823 2316 823 822 2317 822 820 2318 820 825 2319 825 822 2320 822 823 2321 823 825 2322 825 824 2323 824 822 2324 822 827 2325 827 824 2326 824 825 2327 825 827 2328 827 826 2329 826 824 2330 824 829 2331 829 826 2332 826 827 2333 827 829 2334 829 828 2335 828 826 2336 826 831 2337 831 828 2338 828 829 2339 829 831 2340 831 830 2341 830 828 2342 828 833 2343 833 830 2344 830 831 2345 831 833 2346 833 832 2347 832 830 2348 830 835 2349 835 832 2350 832 833 2351 833 835 2352 835 834 2353 834 832 2354 832 837 2355 837 834 2356 834 835 2357 835 837 2358 837 836 2359 836 834 2360 834 839 2361 839 836 2362 836 837 2363 837 839 2364 839 838 2365 838 836 2366 836 841 2367 841 838 2368 838 839 2369 839 841 2370 841 840 2371 840 838 2372 838 843 2373 843 840 2374 840 841 2375 841 843 2376 843 842 2377 842 840 2378 840 845 2379 845 842 2380 842 843 2381 843 845 2382 845 844 2383 844 842 2384 842 848 2385 848 844 2386 844 845 2387 845 848 2388 848 846 2389 846 844 2390 844 848 2391 848 847 2392 847 846 2393 846 849 2394 849 847 2395 847 848 2396 848 816 2397 816 847 2398 847 849 2399 849 883 2400 883 850 2401 850 851 2402 851 853 2403 853 851 2404 851 852 2405 852 883 2406 883 851 2407 851 853 2408 853 856 2409 856 854 2410 854 855 2411 855 857 2412 857 854 2413 854 856 2414 856 859 2415 859 854 2416 854 857 2417 857 859 2418 859 858 2419 858 854 2420 854 861 2421 861 858 2422 858 859 2423 859 861 2424 861 860 2425 860 858 2426 858 864 2427 864 860 2428 860 861 2429 861 864 2430 864 862 2431 862 860 2432 860 864 2433 864 863 2434 863 862 2435 862 865 2436 865 863 2437 863 864 2438 864 867 2439 867 863 2440 863 865 2441 865 867 2442 867 866 2443 866 863 2444 863 870 2445 870 866 2446 866 867 2447 867 870 2448 870 868 2449 868 866 2450 866 870 2451 870 869 2452 869 868 2453 868 872 2454 872 869 2455 869 870 2456 870 872 2457 872 871 2458 871 869 2459 869 873 2460 873 871 2461 871 872 2462 872 875 2463 875 871 2464 871 873 2465 873 875 2466 875 874 2467 874 871 2468 871 877 2469 877 874 2470 874 875 2471 875 877 2472 877 876 2473 876 874 2474 874 879 2475 879 876 2476 876 877 2477 877 879 2478 879 878 2479 878 876 2480 876 882 2481 882 878 2482 878 879 2483 879 882 2484 882 880 2485 880 878 2486 878 882 2487 882 881 2488 881 880 2489 880 850 2490 850 881 2491 881 882 2492 882 850 2493 850 883 2494 883 881 2495 881 916 2496 916 884 2497 884 885 2498 885 889 2499 889 886 2500 886 887 2501 887 889 2502 889 888 2503 888 886 2504 886 891 2505 891 888 2506 888 889 2507 889 891 2508 891 890 2509 890 888 2510 888 893 2511 893 890 2512 890 891 2513 891 893 2514 893 892 2515 892 890 2516 890 895 2517 895 892 2518 892 893 2519 893 895 2520 895 894 2521 894 892 2522 892 898 2523 898 894 2524 894 895 2525 895 898 2526 898 896 2527 896 894 2528 894 898 2529 898 897 2530 897 896 2531 896 899 2532 899 897 2533 897 898 2534 898 901 2535 901 897 2536 897 899 2537 899 901 2538 901 900 2539 900 897 2540 897 903 2541 903 900 2542 900 901 2543 901 903 2544 903 902 2545 902 900 2546 900 905 2547 905 902 2548 902 903 2549 903 905 2550 905 904 2551 904 902 2552 902 907 2553 907 904 2554 904 905 2555 905 907 2556 907 906 2557 906 904 2558 904 909 2559 909 906 2560 906 907 2561 907 909 2562 909 908 2563 908 906 2564 906 911 2565 911 908 2566 908 909 2567 909 911 2568 911 910 2569 910 908 2570 908 913 2571 913 910 2572 910 911 2573 911 913 2574 913 912 2575 912 910 2576 910 915 2577 915 912 2578 912 913 2579 913 915 2580 915 914 2581 914 912 2582 912 917 2583 917 914 2584 914 915 2585 915 917 2586 917 916 2587 916 914 2588 914 884 2589 884 916 2590 916 917 2591 917 949 2592 949 926 2593 926 918 2594 918 921 2595 921 919 2596 919 920 2597 920 922 2598 922 919 2599 919 921 2600 921 924 2601 924 919 2602 919 922 2603 922 924 2604 924 923 2605 923 919 2606 919 927 2607 927 923 2608 923 924 2609 924 927 2610 927 925 2611 925 923 2612 923 927 2613 927 926 2614 926 925 2615 925 918 2616 918 926 2617 926 927 2618 927 931 2619 931 928 2620 928 929 2621 929 931 2622 931 930 2623 930 928 2624 928 934 2625 934 930 2626 930 931 2627 931 934 2628 934 932 2629 932 930 2630 930 934 2631 934 933 2632 933 932 2633 932 935 2634 935 933 2635 933 934 2636 934 937 2637 937 933 2638 933 935 2639 935 937 2640 937 936 2641 936 933 2642 933 939 2643 939 936 2644 936 937 2645 937 939 2646 939 938 2647 938 936 2648 936 941 2649 941 938 2650 938 939 2651 939 941 2652 941 940 2653 940 938 2654 938 943 2655 943 940 2656 940 941 2657 941 943 2658 943 942 2659 942 940 2660 940 945 2661 945 942 2662 942 943 2663 943 945 2664 945 944 2665 944 942 2666 942 947 2667 947 944 2668 944 945 2669 945 947 2670 947 946 2671 946 944 2672 944 950 2673 950 946 2674 946 947 2675 947 950 2676 950 948 2677 948 946 2678 946 950 2679 950 949 2680 949 948 2681 948 951 2682 951 949 2683 949 950 2684 950 926 2685 926 949 2686 949 951 2687 951 983 2688 983 952 2689 952 953 2690 953 957 2691 957 954 2692 954 955 2693 955 957 2694 957 956 2695 956 954 2696 954 959 2697 959 956 2698 956 957 2699 957 959 2700 959 958 2701 958 956 2702 956 961 2703 961 958 2704 958 959 2705 959 961 2706 961 960 2707 960 958 2708 958 963 2709 963 960 2710 960 961 2711 961 963 2712 963 962 2713 962 960 2714 960 965 2715 965 962 2716 962 963 2717 963 965 2718 965 964 2719 964 962 2720 962 967 2721 967 964 2722 964 965 2723 965 967 2724 967 966 2725 966 964 2726 964 969 2727 969 966 2728 966 967 2729 967 969 2730 969 968 2731 968 966 2732 966 971 2733 971 968 2734 968 969 2735 969 971 2736 971 970 2737 970 968 2738 968 973 2739 973 970 2740 970 971 2741 971 973 2742 973 972 2743 972 970 2744 970 976 2745 976 972 2746 972 973 2747 973 976 2748 976 974 2749 974 972 2750 972 976 2751 976 975 2752 975 974 2753 974 977 2754 977 975 2755 975 976 2756 976 979 2757 979 975 2758 975 977 2759 977 979 2760 979 978 2761 978 975 2762 975 981 2763 981 978 2764 978 979 2765 979 981 2766 981 980 2767 980 978 2768 978 984 2769 984 980 2770 980 981 2771 981 984 2772 984 982 2773 982 980 2774 980 984 2775 984 983 2776 983 982 2777 982 985 2778 985 983 2779 983 984 2780 984 952 2781 952 983 2782 983 985 2783 985 1018 2784 1018 986 2785 986 987 2786 987 990 2787 990 988 2788 988 989 2789 989 991 2790 991 988 2791 988 990 2792 990 994 2793 994 988 2794 988 991 2795 991 994 2796 994 992 2797 992 988 2798 988 994 2799 994 993 2800 993 992 2801 992 996 2802 996 993 2803 993 994 2804 994 996 2805 996 995 2806 995 993 2807 993 998 2808 998 995 2809 995 996 2810 996 998 2811 998 997 2812 997 995 2813 995 999 2814 999 997 2815 997 998 2816 998 1002 2817 1002 997 2818 997 999 2819 999 1002 2820 1002 1000 2821 1000 997 2822 997 1002 2823 1002 1001 2824 1001 1000 2825 1000 1003 2826 1003 1001 2827 1001 1002 2828 1002 1005 2829 1005 1001 2830 1001 1003 2831 1003 1005 2832 1005 1004 2833 1004 1001 2834 1001 1007 2835 1007 1004 2836 1004 1005 2837 1005 1007 2838 1007 1006 2839 1006 1004 2840 1004 1009 2841 1009 1006 2842 1006 1007 2843 1007 1009 2844 1009 1008 2845 1008 1006 2846 1006 1011 2847 1011 1008 2848 1008 1009 2849 1009 1011 2850 1011 1010 2851 1010 1008 2852 1008 1013 2853 1013 1010 2854 1010 1011 2855 1011 1013 2856 1013 1012 2857 1012 1010 2858 1010 1015 2859 1015 1012 2860 1012 1013 2861 1013 1015 2862 1015 1014 2863 1014 1012 2864 1012 1017 2865 1017 1014 2866 1014 1015 2867 1015 1017 2868 1017 1016 2869 1016 1014 2870 1014 1019 2871 1019 1016 2872 1016 1017 2873 1017 1019 2874 1019 1018 2875 1018 1016 2876 1016 986 2877 986 1018 2878 1018 1019 2879 1019 1052 2880 1052 1020 2881 1020 1021 2882 1021 1025 2883 1025 1022 2884 1022 1023 2885 1023 1025 2886 1025 1024 2887 1024 1022 2888 1022 1028 2889 1028 1024 2890 1024 1025 2891 1025 1028 2892 1028 1026 2893 1026 1024 2894 1024 1028 2895 1028 1027 2896 1027 1026 2897 1026 1029 2898 1029 1027 2899 1027 1028 2900 1028 1031 2901 1031 1027 2902 1027 1029 2903 1029 1031 2904 1031 1030 2905 1030 1027 2906 1027 1033 2907 1033 1030 2908 1030 1031 2909 1031 1033 2910 1033 1032 2911 1032 1030 2912 1030 1035 2913 1035 1032 2914 1032 1033 2915 1033 1035 2916 1035 1034 2917 1034 1032 2918 1032 1037 2919 1037 1034 2920 1034 1035 2921 1035 1037 2922 1037 1036 2923 1036 1034 2924 1034 1039 2925 1039 1036 2926 1036 1037 2927 1037 1039 2928 1039 1038 2929 1038 1036 2930 1036 1041 2931 1041 1038 2932 1038 1039 2933 1039 1041 2934 1041 1040 2935 1040 1038 2936 1038 1043 2937 1043 1040 2938 1040 1041 2939 1041 1043 2940 1043 1042 2941 1042 1040 2942 1040 1046 2943 1046 1042 2944 1042 1043 2945 1043 1046 2946 1046 1044 2947 1044 1042 2948 1042 1046 2949 1046 1045 2950 1045 1044 2951 1044 1047 2952 1047 1045 2953 1045 1046 2954 1046 1049 2955 1049 1045 2956 1045 1047 2957 1047 1049 2958 1049 1048 2959 1048 1045 2960 1045 1051 2961 1051 1048 2962 1048 1049 2963 1049 1051 2964 1051 1050 2965 1050 1048 2966 1048 1053 2967 1053 1050 2968 1050 1051 2969 1051 1053 2970 1053 1052 2971 1052 1050 2972 1050 1020 2973 1020 1052 2974 1052 1053 2975 1053 1087 2976 1087 1054 2977 1054 1059 2978 1059 1058 2979 1058 1055 2980 1055 1056 2981 1056 1058 2982 1058 1057 2983 1057 1055 2984 1055 1087 2985 1087 1057 2986 1057 1058 2987 1058 1087 2988 1087 1059 2989 1059 1057 2990 1057 1063 2991 1063 1060 2992 1060 1061 2993 1061 1063 2994 1063 1062 2995 1062 1060 2996 1060 1066 2997 1066 1062 2998 1062 1063 2999 1063 1066 3000 1066 1064 3001 1064 1062 3002 1062 1066 3003 1066 1065 3004 1065 1064 3005 1064 1067 3006 1067 1065 3007 1065 1066 3008 1066 1069 3009 1069 1065 3010 1065 1067 3011 1067 1069 3012 1069 1068 3013 1068 1065 3014 1065 1071 3015 1071 1068 3016 1068 1069 3017 1069 1071 3018 1071 1070 3019 1070 1068 3020 1068 1073 3021 1073 1070 3022 1070 1071 3023 1071 1073 3024 1073 1072 3025 1072 1070 3026 1070 1076 3027 1076 1072 3028 1072 1073 3029 1073 1076 3030 1076 1074 3031 1074 1072 3032 1072 1076 3033 1076 1075 3034 1075 1074 3035 1074 1077 3036 1077 1075 3037 1075 1076 3038 1076 1079 3039 1079 1075 3040 1075 1077 3041 1077 1079 3042 1079 1078 3043 1078 1075 3044 1075 1081 3045 1081 1078 3046 1078 1079 3047 1079 1081 3048 1081 1080 3049 1080 1078 3050 1078 1083 3051 1083 1080 3052 1080 1081 3053 1081 1083 3054 1083 1082 3055 1082 1080 3056 1080 1085 3057 1085 1082 3058 1082 1083 3059 1083 1085 3060 1085 1084 3061 1084 1082 3062 1082 1054 3063 1054 1084 3064 1084 1085 3065 1085 1054 3066 1054 1086 3067 1086 1084 3068 1084 1054 3069 1054 1087 3070 1087 1086 3071 1086 1120 3072 1120 1088 3073 1088 1089 3074 1089 1093 3075 1093 1090 3076 1090 1091 3077 1091 1093 3078 1093 1092 3079 1092 1090 3080 1090 1096 3081 1096 1092 3082 1092 1093 3083 1093 1096 3084 1096 1094 3085 1094 1092 3086 1092 1096 3087 1096 1095 3088 1095 1094 3089 1094 1097 3090 1097 1095 3091 1095 1096 3092 1096 1099 3093 1099 1095 3094 1095 1097 3095 1097 1099 3096 1099 1098 3097 1098 1095 3098 1095 1101 3099 1101 1098 3100 1098 1099 3101 1099 1101 3102 1101 1100 3103 1100 1098 3104 1098 1103 3105 1103 1100 3106 1100 1101 3107 1101 1103 3108 1103 1102 3109 1102 1100 3110 1100 1106 3111 1106 1102 3112 1102 1103 3113 1103 1106 3114 1106 1104 3115 1104 1102 3116 1102 1106 3117 1106 1105 3118 1105 1104 3119 1104 1107 3120 1107 1105 3121 1105 1106 3122 1106 1109 3123 1109 1105 3124 1105 1107 3125 1107 1109 3126 1109 1108 3127 1108 1105 3128 1105 1111 3129 1111 1108 3130 1108 1109 3131 1109 1111 3132 1111 1110 3133 1110 1108 3134 1108 1113 3135 1113 1110 3136 1110 1111 3137 1111 1113 3138 1113 1112 3139 1112 1110 3140 1110 1115 3141 1115 1112 3142 1112 1113 3143 1113 1115 3144 1115 1114 3145 1114 1112 3146 1112 1117 3147 1117 1114 3148 1114 1115 3149 1115 1117 3150 1117 1116 3151 1116 1114 3152 1114 1119 3153 1119 1116 3154 1116 1117 3155 1117 1119 3156 1119 1118 3157 1118 1116 3158 1116 1121 3159 1121 1118 3160 1118 1119 3161 1119 1121 3162 1121 1120 3163 1120 1118 3164 1118 1088 3165 1088 1120 3166 1120 1121 3167 1121 1155 3168 1155 1122 3169 1122 1125 3170 1125 1155 3171 1155 1123 3172 1123 1124 3173 1124 1155 3174 1155 1125 3175 1125 1123 3176 1123 1129 3177 1129 1126 3178 1126 1127 3179 1127 1129 3180 1129 1128 3181 1128 1126 3182 1126 1132 3183 1132 1128 3184 1128 1129 3185 1129 1132 3186 1132 1130 3187 1130 1128 3188 1128 1132 3189 1132 1131 3190 1131 1130 3191 1130 1133 3192 1133 1131 3193 1131 1132 3194 1132 1135 3195 1135 1131 3196 1131 1133 3197 1133 1135 3198 1135 1134 3199 1134 1131 3200 1131 1137 3201 1137 1134 3202 1134 1135 3203 1135 1137 3204 1137 1136 3205 1136 1134 3206 1134 1140 3207 1140 1136 3208 1136 1137 3209 1137 1140 3210 1140 1138 3211 1138 1136 3212 1136 1140 3213 1140 1139 3214 1139 1138 3215 1138 1141 3216 1141 1139 3217 1139 1140 3218 1140 1143 3219 1143 1139 3220 1139 1141 3221 1141 1143 3222 1143 1142 3223 1142 1139 3224 1139 1145 3225 1145 1142 3226 1142 1143 3227 1143 1145 3228 1145 1144 3229 1144 1142 3230 1142 1147 3231 1147 1144 3232 1144 1145 3233 1145 1147 3234 1147 1146 3235 1146 1144 3236 1144 1149 3237 1149 1146 3238 1146 1147 3239 1147 1149 3240 1149 1148 3241 1148 1146 3242 1146 1151 3243 1151 1148 3244 1148 1149 3245 1149 1151 3246 1151 1150 3247 1150 1148 3248 1148 1153 3249 1153 1150 3250 1150 1151 3251 1151 1153 3252 1153 1152 3253 1152 1150 3254 1150 1122 3255 1122 1152 3256 1152 1153 3257 1153 1122 3258 1122 1154 3259 1154 1152 3260 1152 1122 3261 1122 1155 3262 1155 1154 3263 1154 1187 3264 1187 1156 3265 1156 1157 3266 1157 1162 3267 1162 1158 3268 1158 1159 3269 1159 1162 3270 1162 1160 3271 1160 1158 3272 1158 1162 3273 1162 1161 3274 1161 1160 3275 1160 1163 3276 1163 1161 3277 1161 1162 3278 1162 1165 3279 1165 1161 3280 1161 1163 3281 1163 1165 3282 1165 1164 3283 1164 1161 3284 1161 1167 3285 1167 1164 3286 1164 1165 3287 1165 1167 3288 1167 1166 3289 1166 1164 3290 1164 1169 3291 1169 1166 3292 1166 1167 3293 1167 1169 3294 1169 1168 3295 1168 1166 3296 1166 1171 3297 1171 1168 3298 1168 1169 3299 1169 1171 3300 1171 1170 3301 1170 1168 3302 1168 1173 3303 1173 1170 3304 1170 1171 3305 1171 1173 3306 1173 1172 3307 1172 1170 3308 1170 1175 3309 1175 1172 3310 1172 1173 3311 1173 1175 3312 1175 1174 3313 1174 1172 3314 1172 1177 3315 1177 1174 3316 1174 1175 3317 1175 1177 3318 1177 1176 3319 1176 1174 3320 1174 1179 3321 1179 1176 3322 1176 1177 3323 1177 1179 3324 1179 1178 3325 1178 1176 3326 1176 1182 3327 1182 1178 3328 1178 1179 3329 1179 1182 3330 1182 1180 3331 1180 1178 3332 1178 1182 3333 1182 1181 3334 1181 1180 3335 1180 1183 3336 1183 1181 3337 1181 1182 3338 1182 1185 3339 1185 1181 3340 1181 1183 3341 1183 1185 3342 1185 1184 3343 1184 1181 3344 1181 1188 3345 1188 1184 3346 1184 1185 3347 1185 1188 3348 1188 1186 3349 1186 1184 3350 1184 1188 3351 1188 1187 3352 1187 1186 3353 1186 1189 3354 1189 1187 3355 1187 1188 3356 1188 1156 3357 1156 1187 3358 1187 1189 3359 1189 1221 3360 1221 1190 3361 1190 1191 3362 1191 1194 3363 1194 1192 3364 1192 1193 3365 1193 1195 3366 1195 1192 3367 1192 1194 3368 1194 1197 3369 1197 1192 3370 1192 1195 3371 1195 1197 3372 1197 1196 3373 1196 1192 3374 1192 1199 3375 1199 1196 3376 1196 1197 3377 1197 1199 3378 1199 1198 3379 1198 1196 3380 1196 1201 3381 1201 1198 3382 1198 1199 3383 1199 1201 3384 1201 1200 3385 1200 1198 3386 1198 1203 3387 1203 1200 3388 1200 1201 3389 1201 1203 3390 1203 1202 3391 1202 1200 3392 1200 1205 3393 1205 1202 3394 1202 1203 3395 1203 1205 3396 1205 1204 3397 1204 1202 3398 1202 1207 3399 1207 1204 3400 1204 1205 3401 1205 1207 3402 1207 1206 3403 1206 1204 3404 1204 1209 3405 1209 1206 3406 1206 1207 3407 1207 1209 3408 1209 1208 3409 1208 1206 3410 1206 1211 3411 1211 1208 3412 1208 1209 3413 1209 1211 3414 1211 1210 3415 1210 1208 3416 1208 1213 3417 1213 1210 3418 1210 1211 3419 1211 1213 3420 1213 1212 3421 1212 1210 3422 1210 1216 3423 1216 1212 3424 1212 1213 3425 1213 1216 3426 1216 1214 3427 1214 1212 3428 1212 1216 3429 1216 1215 3430 1215 1214 3431 1214 1217 3432 1217 1215 3433 1215 1216 3434 1216 1219 3435 1219 1215 3436 1215 1217 3437 1217 1219 3438 1219 1218 3439 1218 1215 3440 1215 1222 3441 1222 1218 3442 1218 1219 3443 1219 1222 3444 1222 1220 3445 1220 1218 3446 1218 1222 3447 1222 1221 3448 1221 1220 3449 1220 1223 3450 1223 1221 3451 1221 1222 3452 1222 1190 3453 1190 1221 3454 1221 1223 3455 1223 1256 3456 1256 1224 3457 1224 1225 3458 1225 1229 3459 1229 1226 3460 1226 1227 3461 1227 1229 3462 1229 1228 3463 1228 1226 3464 1226 1231 3465 1231 1228 3466 1228 1229 3467 1229 1231 3468 1231 1230 3469 1230 1228 3470 1228 1233 3471 1233 1230 3472 1230 1231 3473 1231 1233 3474 1233 1232 3475 1232 1230 3476 1230 1235 3477 1235 1232 3478 1232 1233 3479 1233 1235 3480 1235 1234 3481 1234 1232 3482 1232 1237 3483 1237 1234 3484 1234 1235 3485 1235 1237 3486 1237 1236 3487 1236 1234 3488 1234 1239 3489 1239 1236 3490 1236 1237 3491 1237 1239 3492 1239 1238 3493 1238 1236 3494 1236 1241 3495 1241 1238 3496 1238 1239 3497 1239 1241 3498 1241 1240 3499 1240 1238 3500 1238 1243 3501 1243 1240 3502 1240 1241 3503 1241 1243 3504 1243 1242 3505 1242 1240 3506 1240 1245 3507 1245 1242 3508 1242 1243 3509 1243 1245 3510 1245 1244 3511 1244 1242 3512 1242 1247 3513 1247 1244 3514 1244 1245 3515 1245 1247 3516 1247 1246 3517 1246 1244 3518 1244 1249 3519 1249 1246 3520 1246 1247 3521 1247 1249 3522 1249 1248 3523 1248 1246 3524 1246 1251 3525 1251 1248 3526 1248 1249 3527 1249 1251 3528 1251 1250 3529 1250 1248 3530 1248 1253 3531 1253 1250 3532 1250 1251 3533 1251 1253 3534 1253 1252 3535 1252 1250 3536 1250 1255 3537 1255 1252 3538 1252 1253 3539 1253 1255 3540 1255 1254 3541 1254 1252 3542 1252 1257 3543 1257 1254 3544 1254 1255 3545 1255 1257 3546 1257 1256 3547 1256 1254 3548 1254 1224 3549 1224 1256 3550 1256 1257 3551 1257 1290 3552 1290 1258 3553 1258 1259 3554 1259 1263 3555 1263 1260 3556 1260 1261 3557 1261 1263 3558 1263 1262 3559 1262 1260 3560 1260 1265 3561 1265 1262 3562 1262 1263 3563 1263 1265 3564 1265 1264 3565 1264 1262 3566 1262 1267 3567 1267 1264 3568 1264 1265 3569 1265 1267 3570 1267 1266 3571 1266 1264 3572 1264 1269 3573 1269 1266 3574 1266 1267 3575 1267 1269 3576 1269 1268 3577 1268 1266 3578 1266 1271 3579 1271 1268 3580 1268 1269 3581 1269 1271 3582 1271 1270 3583 1270 1268 3584 1268 1273 3585 1273 1270 3586 1270 1271 3587 1271 1273 3588 1273 1272 3589 1272 1270 3590 1270 1275 3591 1275 1272 3592 1272 1273 3593 1273 1275 3594 1275 1274 3595 1274 1272 3596 1272 1277 3597 1277 1274 3598 1274 1275 3599 1275 1277 3600 1277 1276 3601 1276 1274 3602 1274 1279 3603 1279 1276 3604 1276 1277 3605 1277 1279 3606 1279 1278 3607 1278 1276 3608 1276 1281 3609 1281 1278 3610 1278 1279 3611 1279 1281 3612 1281 1280 3613 1280 1278 3614 1278 1283 3615 1283 1280 3616 1280 1281 3617 1281 1283 3618 1283 1282 3619 1282 1280 3620 1280 1286 3621 1286 1282 3622 1282 1283 3623 1283 1286 3624 1286 1284 3625 1284 1282 3626 1282 1286 3627 1286 1285 3628 1285 1284 3629 1284 1287 3630 1287 1285 3631 1285 1286 3632 1286 1289 3633 1289 1285 3634 1285 1287 3635 1287 1289 3636 1289 1288 3637 1288 1285 3638 1285 1291 3639 1291 1288 3640 1288 1289 3641 1289 1291 3642 1291 1290 3643 1290 1288 3644 1288 1258 3645 1258 1290 3646 1290 1291 3647 1291 1324 3648 1324 1292 3649 1292 1293 3650 1293 1297 3651 1297 1294 3652 1294 1295 3653 1295 1297 3654 1297 1296 3655 1296 1294 3656 1294 1299 3657 1299 1296 3658 1296 1297 3659 1297 1299 3660 1299 1298 3661 1298 1296 3662 1296 1301 3663 1301 1298 3664 1298 1299 3665 1299 1301 3666 1301 1300 3667 1300 1298 3668 1298 1303 3669 1303 1300 3670 1300 1301 3671 1301 1303 3672 1303 1302 3673 1302 1300 3674 1300 1305 3675 1305 1302 3676 1302 1303 3677 1303 1305 3678 1305 1304 3679 1304 1302 3680 1302 1307 3681 1307 1304 3682 1304 1305 3683 1305 1307 3684 1307 1306 3685 1306 1304 3686 1304 1309 3687 1309 1306 3688 1306 1307 3689 1307 1309 3690 1309 1308 3691 1308 1306 3692 1306 1311 3693 1311 1308 3694 1308 1309 3695 1309 1311 3696 1311 1310 3697 1310 1308 3698 1308 1313 3699 1313 1310 3700 1310 1311 3701 1311 1313 3702 1313 1312 3703 1312 1310 3704 1310 1315 3705 1315 1312 3706 1312 1313 3707 1313 1315 3708 1315 1314 3709 1314 1312 3710 1312 1317 3711 1317 1314 3712 1314 1315 3713 1315 1317 3714 1317 1316 3715 1316 1314 3716 1314 1319 3717 1319 1316 3718 1316 1317 3719 1317 1319 3720 1319 1318 3721 1318 1316 3722 1316 1321 3723 1321 1318 3724 1318 1319 3725 1319 1321 3726 1321 1320 3727 1320 1318 3728 1318 1323 3729 1323 1320 3730 1320 1321 3731 1321 1323 3732 1323 1322 3733 1322 1320 3734 1320 1325 3735 1325 1322 3736 1322 1323 3737 1323 1325 3738 1325 1324 3739 1324 1322 3740 1322 1292 3741 1292 1324 3742 1324 1325 3743 1325 1357 3744 1357 1326 3745 1326 1327 3746 1327 1331 3747 1331 1328 3748 1328 1329 3749 1329 1331 3750 1331 1330 3751 1330 1328 3752 1328 1333 3753 1333 1330 3754 1330 1331 3755 1331 1333 3756 1333 1332 3757 1332 1330 3758 1330 1336 3759 1336 1332 3760 1332 1333 3761 1333 1336 3762 1336 1334 3763 1334 1332 3764 1332 1336 3765 1336 1335 3766 1335 1334 3767 1334 1337 3768 1337 1335 3769 1335 1336 3770 1336 1339 3771 1339 1335 3772 1335 1337 3773 1337 1339 3774 1339 1338 3775 1338 1335 3776 1335 1341 3777 1341 1338 3778 1338 1339 3779 1339 1341 3780 1341 1340 3781 1340 1338 3782 1338 1343 3783 1343 1340 3784 1340 1341 3785 1341 1343 3786 1343 1342 3787 1342 1340 3788 1340 1345 3789 1345 1342 3790 1342 1343 3791 1343 1345 3792 1345 1344 3793 1344 1342 3794 1342 1347 3795 1347 1344 3796 1344 1345 3797 1345 1347 3798 1347 1346 3799 1346 1344 3800 1344 1350 3801 1350 1346 3802 1346 1347 3803 1347 1350 3804 1350 1348 3805 1348 1346 3806 1346 1350 3807 1350 1349 3808 1349 1348 3809 1348 1351 3810 1351 1349 3811 1349 1350 3812 1350 1354 3813 1354 1349 3814 1349 1351 3815 1351 1354 3816 1354 1352 3817 1352 1349 3818 1349 1354 3819 1354 1353 3820 1353 1352 3821 1352 1356 3822 1356 1353 3823 1353 1354 3824 1354 1356 3825 1356 1355 3826 1355 1353 3827 1353 1358 3828 1358 1355 3829 1355 1356 3830 1356 1358 3831 1358 1357 3832 1357 1355 3833 1355 1359 3834 1359 1357 3835 1357 1358 3836 1358 1326 3837 1326 1357 3838 1357 1359 3839 1359 1393 3840 1393 1360 3841 1360 1361 3842 1361 1365 3843 1365 1362 3844 1362 1363 3845 1363 1365 3846 1365 1364 3847 1364 1362 3848 1362 1367 3849 1367 1364 3850 1364 1365 3851 1365 1367 3852 1367 1366 3853 1366 1364 3854 1364 1369 3855 1369 1366 3856 1366 1367 3857 1367 1369 3858 1369 1368 3859 1368 1366 3860 1366 1371 3861 1371 1368 3862 1368 1369 3863 1369 1371 3864 1371 1370 3865 1370 1368 3866 1368 1373 3867 1373 1370 3868 1370 1371 3869 1371 1373 3870 1373 1372 3871 1372 1370 3872 1370 1375 3873 1375 1372 3874 1372 1373 3875 1373 1375 3876 1375 1374 3877 1374 1372 3878 1372 1377 3879 1377 1374 3880 1374 1375 3881 1375 1377 3882 1377 1376 3883 1376 1374 3884 1374 1379 3885 1379 1376 3886 1376 1377 3887 1377 1379 3888 1379 1378 3889 1378 1376 3890 1376 1381 3891 1381 1378 3892 1378 1379 3893 1379 1381 3894 1381 1380 3895 1380 1378 3896 1378 1383 3897 1383 1380 3898 1380 1381 3899 1381 1383 3900 1383 1382 3901 1382 1380 3902 1380 1385 3903 1385 1382 3904 1382 1383 3905 1383 1385 3906 1385 1384 3907 1384 1382 3908 1382 1387 3909 1387 1384 3910 1384 1385 3911 1385 1387 3912 1387 1386 3913 1386 1384 3914 1384 1389 3915 1389 1386 3916 1386 1387 3917 1387 1389 3918 1389 1388 3919 1388 1386 3920 1386 1391 3921 1391 1388 3922 1388 1389 3923 1389 1391 3924 1391 1390 3925 1390 1388 3926 1388 1360 3927 1360 1390 3928 1390 1391 3929 1391 1360 3930 1360 1392 3931 1392 1390 3932 1390 1360 3933 1360 1393 3934 1393 1392 3935 1392 1425 3936 1425 1394 3937 1394 1395 3938 1395 1399 3939 1399 1396 3940 1396 1397 3941 1397 1399 3942 1399 1398 3943 1398 1396 3944 1396 1401 3945 1401 1398 3946 1398 1399 3947 1399 1401 3948 1401 1400 3949 1400 1398 3950 1398 1403 3951 1403 1400 3952 1400 1401 3953 1401 1403 3954 1403 1402 3955 1402 1400 3956 1400 1405 3957 1405 1402 3958 1402 1403 3959 1403 1405 3960 1405 1404 3961 1404 1402 3962 1402 1407 3963 1407 1404 3964 1404 1405 3965 1405 1407 3966 1407 1406 3967 1406 1404 3968 1404 1409 3969 1409 1406 3970 1406 1407 3971 1407 1409 3972 1409 1408 3973 1408 1406 3974 1406 1411 3975 1411 1408 3976 1408 1409 3977 1409 1411 3978 1411 1410 3979 1410 1408 3980 1408 1413 3981 1413 1410 3982 1410 1411 3983 1411 1413 3984 1413 1412 3985 1412 1410 3986 1410 1415 3987 1415 1412 3988 1412 1413 3989 1413 1415 3990 1415 1414 3991 1414 1412 3992 1412 1417 3993 1417 1414 3994 1414 1415 3995 1415 1417 3996 1417 1416 3997 1416 1414 3998 1414 1419 3999 1419 1416 4000 1416 1417 4001 1417 1419 4002 1419 1418 4003 1418 1416 4004 1416 1422 4005 1422 1418 4006 1418 1419 4007 1419 1422 4008 1422 1420 4009 1420 1418 4010 1418 1422 4011 1422 1421 4012 1421 1420 4013 1420 1424 4014 1424 1421 4015 1421 1422 4016 1422 1424 4017 1424 1423 4018 1423 1421 4019 1421 1426 4020 1426 1423 4021 1423 1424 4022 1424 1426 4023 1426 1425 4024 1425 1423 4025 1423 1427 4026 1427 1425 4027 1425 1426 4028 1426 1394 4029 1394 1425 4030 1425 1427 4031 1427 1459 4032 1459 1428 4033 1428 1429 4034 1429 1433 4035 1433 1430 4036 1430 1431 4037 1431 1433 4038 1433 1432 4039 1432 1430 4040 1430 1435 4041 1435 1432 4042 1432 1433 4043 1433 1435 4044 1435 1434 4045 1434 1432 4046 1432 1437 4047 1437 1434 4048 1434 1435 4049 1435 1437 4050 1437 1436 4051 1436 1434 4052 1434 1440 4053 1440 1436 4054 1436 1437 4055 1437 1440 4056 1440 1438 4057 1438 1436 4058 1436 1440 4059 1440 1439 4060 1439 1438 4061 1438 1441 4062 1441 1439 4063 1439 1440 4064 1440 1443 4065 1443 1439 4066 1439 1441 4067 1441 1443 4068 1443 1442 4069 1442 1439 4070 1439 1445 4071 1445 1442 4072 1442 1443 4073 1443 1445 4074 1445 1444 4075 1444 1442 4076 1442 1447 4077 1447 1444 4078 1444 1445 4079 1445 1447 4080 1447 1446 4081 1446 1444 4082 1444 1449 4083 1449 1446 4084 1446 1447 4085 1447 1449 4086 1449 1448 4087 1448 1446 4088 1446 1452 4089 1452 1448 4090 1448 1449 4091 1449 1452 4092 1452 1450 4093 1450 1448 4094 1448 1452 4095 1452 1451 4096 1451 1450 4097 1450 1453 4098 1453 1451 4099 1451 1452 4100 1452 1455 4101 1455 1451 4102 1451 1453 4103 1453 1455 4104 1455 1454 4105 1454 1451 4106 1451 1457 4107 1457 1454 4108 1454 1455 4109 1455 1457 4110 1457 1456 4111 1456 1454 4112 1454 1460 4113 1460 1456 4114 1456 1457 4115 1457 1460 4116 1460 1458 4117 1458 1456 4118 1456 1460 4119 1460 1459 4120 1459 1458 4121 1458 1461 4122 1461 1459 4123 1459 1460 4124 1460 1428 4125 1428 1459 4126 1459 1461 4127 1461 1494 4128 1494 1462 4129 1462 1463 4130 1463 1467 4131 1467 1464 4132 1464 1465 4133 1465 1467 4134 1467 1466 4135 1466 1464 4136 1464 1469 4137 1469 1466 4138 1466 1467 4139 1467 1469 4140 1469 1468 4141 1468 1466 4142 1466 1471 4143 1471 1468 4144 1468 1469 4145 1469 1471 4146 1471 1470 4147 1470 1468 4148 1468 1473 4149 1473 1470 4150 1470 1471 4151 1471 1473 4152 1473 1472 4153 1472 1470 4154 1470 1475 4155 1475 1472 4156 1472 1473 4157 1473 1475 4158 1475 1474 4159 1474 1472 4160 1472 1477 4161 1477 1474 4162 1474 1475 4163 1475 1477 4164 1477 1476 4165 1476 1474 4166 1474 1479 4167 1479 1476 4168 1476 1477 4169 1477 1479 4170 1479 1478 4171 1478 1476 4172 1476 1482 4173 1482 1478 4174 1478 1479 4175 1479 1482 4176 1482 1480 4177 1480 1478 4178 1478 1482 4179 1482 1481 4180 1481 1480 4181 1480 1483 4182 1483 1481 4183 1481 1482 4184 1482 1486 4185 1486 1481 4186 1481 1483 4187 1483 1486 4188 1486 1484 4189 1484 1481 4190 1481 1486 4191 1486 1485 4192 1485 1484 4193 1484 1487 4194 1487 1485 4195 1485 1486 4196 1486 1489 4197 1489 1485 4198 1485 1487 4199 1487 1489 4200 1489 1488 4201 1488 1485 4202 1485 1491 4203 1491 1488 4204 1488 1489 4205 1489 1491 4206 1491 1490 4207 1490 1488 4208 1488 1493 4209 1493 1490 4210 1490 1491 4211 1491 1493 4212 1493 1492 4213 1492 1490 4214 1490 1495 4215 1495 1492 4216 1492 1493 4217 1493 1495 4218 1495 1494 4219 1494 1492 4220 1492 1462 4221 1462 1494 4222 1494 1495 4223 1495 1528 4224 1528 1499 4225 1499 1496 4226 1496 1496 4227 1496 1497 4228 1497 1498 4229 1498 1496 4230 1496 1499 4231 1499 1497 4232 1497 1503 4233 1503 1500 4234 1500 1501 4235 1501 1503 4236 1503 1502 4237 1502 1500 4238 1500 1505 4239 1505 1502 4240 1502 1503 4241 1503 1505 4242 1505 1504 4243 1504 1502 4244 1502 1508 4245 1508 1504 4246 1504 1505 4247 1505 1508 4248 1508 1506 4249 1506 1504 4250 1504 1508 4251 1508 1507 4252 1507 1506 4253 1506 1509 4254 1509 1507 4255 1507 1508 4256 1508 1511 4257 1511 1507 4258 1507 1509 4259 1509 1511 4260 1511 1510 4261 1510 1507 4262 1507 1513 4263 1513 1510 4264 1510 1511 4265 1511 1513 4266 1513 1512 4267 1512 1510 4268 1510 1515 4269 1515 1512 4270 1512 1513 4271 1513 1515 4272 1515 1514 4273 1514 1512 4274 1512 1517 4275 1517 1514 4276 1514 1515 4277 1515 1517 4278 1517 1516 4279 1516 1514 4280 1514 1519 4281 1519 1516 4282 1516 1517 4283 1517 1519 4284 1519 1518 4285 1518 1516 4286 1516 1521 4287 1521 1518 4288 1518 1519 4289 1519 1521 4290 1521 1520 4291 1520 1518 4292 1518 1523 4293 1523 1520 4294 1520 1521 4295 1521 1523 4296 1523 1522 4297 1522 1520 4298 1520 1525 4299 1525 1522 4300 1522 1523 4301 1523 1525 4302 1525 1524 4303 1524 1522 4304 1522 1527 4305 1527 1524 4306 1524 1525 4307 1525 1527 4308 1527 1526 4309 1526 1524 4310 1524 1529 4311 1529 1526 4312 1526 1527 4313 1527 1529 4314 1529 1528 4315 1528 1526 4316 1526 1499 4317 1499 1528 4318 1528 1529 4319 1529 1561 4320 1561 1530 4321 1530 1531 4322 1531 1535 4323 1535 1532 4324 1532 1533 4325 1533 1535 4326 1535 1534 4327 1534 1532 4328 1532 1537 4329 1537 1534 4330 1534 1535 4331 1535 1537 4332 1537 1536 4333 1536 1534 4334 1534 1539 4335 1539 1536 4336 1536 1537 4337 1537 1539 4338 1539 1538 4339 1538 1536 4340 1536 1542 4341 1542 1538 4342 1538 1539 4343 1539 1542 4344 1542 1540 4345 1540 1538 4346 1538 1542 4347 1542 1541 4348 1541 1540 4349 1540 1543 4350 1543 1541 4351 1541 1542 4352 1542 1545 4353 1545 1541 4354 1541 1543 4355 1543 1545 4356 1545 1544 4357 1544 1541 4358 1541 1547 4359 1547 1544 4360 1544 1545 4361 1545 1547 4362 1547 1546 4363 1546 1544 4364 1544 1549 4365 1549 1546 4366 1546 1547 4367 1547 1549 4368 1549 1548 4369 1548 1546 4370 1546 1552 4371 1552 1548 4372 1548 1549 4373 1549 1552 4374 1552 1550 4375 1550 1548 4376 1548 1552 4377 1552 1551 4378 1551 1550 4379 1550 1554 4380 1554 1551 4381 1551 1552 4382 1552 1554 4383 1554 1553 4384 1553 1551 4385 1551 1555 4386 1555 1553 4387 1553 1554 4388 1554 1557 4389 1557 1553 4390 1553 1555 4391 1555 1557 4392 1557 1556 4393 1556 1553 4394 1553 1559 4395 1559 1556 4396 1556 1557 4397 1557 1559 4398 1559 1558 4399 1558 1556 4400 1556 1562 4401 1562 1558 4402 1558 1559 4403 1559 1562 4404 1562 1560 4405 1560 1558 4406 1558 1562 4407 1562 1561 4408 1561 1560 4409 1560 1563 4410 1563 1561 4411 1561 1562 4412 1562 1530 4413 1530 1561 4414 1561 1563 4415 1563 1596 4416 1596 1564 4417 1564 1565 4418 1565 1569 4419 1569 1566 4420 1566 1567 4421 1567 1569 4422 1569 1568 4423 1568 1566 4424 1566 1571 4425 1571 1568 4426 1568 1569 4427 1569 1571 4428 1571 1570 4429 1570 1568 4430 1568 1573 4431 1573 1570 4432 1570 1571 4433 1571 1573 4434 1573 1572 4435 1572 1570 4436 1570 1575 4437 1575 1572 4438 1572 1573 4439 1573 1575 4440 1575 1574 4441 1574 1572 4442 1572 1577 4443 1577 1574 4444 1574 1575 4445 1575 1577 4446 1577 1576 4447 1576 1574 4448 1574 1579 4449 1579 1576 4450 1576 1577 4451 1577 1579 4452 1579 1578 4453 1578 1576 4454 1576 1581 4455 1581 1578 4456 1578 1579 4457 1579 1581 4458 1581 1580 4459 1580 1578 4460 1578 1583 4461 1583 1580 4462 1580 1581 4463 1581 1583 4464 1583 1582 4465 1582 1580 4466 1580 1585 4467 1585 1582 4468 1582 1583 4469 1583 1585 4470 1585 1584 4471 1584 1582 4472 1582 1587 4473 1587 1584 4474 1584 1585 4475 1585 1587 4476 1587 1586 4477 1586 1584 4478 1584 1589 4479 1589 1586 4480 1586 1587 4481 1587 1589 4482 1589 1588 4483 1588 1586 4484 1586 1591 4485 1591 1588 4486 1588 1589 4487 1589 1591 4488 1591 1590 4489 1590 1588 4490 1588 1594 4491 1594 1590 4492 1590 1591 4493 1591 1594 4494 1594 1592 4495 1592 1590 4496 1590 1594 4497 1594 1593 4498 1593 1592 4499 1592 1595 4500 1595 1593 4501 1593 1594 4502 1594 1597 4503 1597 1593 4504 1593 1595 4505 1595 1597 4506 1597 1596 4507 1596 1593 4508 1593 1564 4509 1564 1596 4510 1596 1597 4511 1597 1630 4512 1630 1598 4513 1598 1599 4514 1599 1603 4515 1603 1600 4516 1600 1601 4517 1601 1603 4518 1603 1602 4519 1602 1600 4520 1600 1605 4521 1605 1602 4522 1602 1603 4523 1603 1605 4524 1605 1604 4525 1604 1602 4526 1602 1608 4527 1608 1604 4528 1604 1605 4529 1605 1608 4530 1608 1606 4531 1606 1604 4532 1604 1608 4533 1608 1607 4534 1607 1606 4535 1606 1609 4536 1609 1607 4537 1607 1608 4538 1608 1611 4539 1611 1607 4540 1607 1609 4541 1609 1611 4542 1611 1610 4543 1610 1607 4544 1607 1614 4545 1614 1610 4546 1610 1611 4547 1611 1614 4548 1614 1612 4549 1612 1610 4550 1610 1614 4551 1614 1613 4552 1613 1612 4553 1612 1615 4554 1615 1613 4555 1613 1614 4556 1614 1618 4557 1618 1613 4558 1613 1615 4559 1615 1618 4560 1618 1616 4561 1616 1613 4562 1613 1618 4563 1618 1617 4564 1617 1616 4565 1616 1619 4566 1619 1617 4567 1617 1618 4568 1618 1621 4569 1621 1617 4570 1617 1619 4571 1619 1621 4572 1621 1620 4573 1620 1617 4574 1617 1623 4575 1623 1620 4576 1620 1621 4577 1621 1623 4578 1623 1622 4579 1622 1620 4580 1620 1626 4581 1626 1622 4582 1622 1623 4583 1623 1626 4584 1626 1624 4585 1624 1622 4586 1622 1626 4587 1626 1625 4588 1625 1624 4589 1624 1627 4590 1627 1625 4591 1625 1626 4592 1626 1629 4593 1629 1625 4594 1625 1627 4595 1627 1629 4596 1629 1628 4597 1628 1625 4598 1625 1631 4599 1631 1628 4600 1628 1629 4601 1629 1631 4602 1631 1630 4603 1630 1628 4604 1628 1598 4605 1598 1630 4606 1630 1631 4607 1631 1664 4608 1664 1635 4609 1635 1632 4610 1632 1632 4611 1632 1633 4612 1633 1634 4613 1634 1632 4614 1632 1635 4615 1635 1633 4616 1633 1639 4617 1639 1636 4618 1636 1637 4619 1637 1639 4620 1639 1638 4621 1638 1636 4622 1636 1641 4623 1641 1638 4624 1638 1639 4625 1639 1641 4626 1641 1640 4627 1640 1638 4628 1638 1644 4629 1644 1640 4630 1640 1641 4631 1641 1644 4632 1644 1642 4633 1642 1640 4634 1640 1644 4635 1644 1643 4636 1643 1642 4637 1642 1645 4638 1645 1643 4639 1643 1644 4640 1644 1647 4641 1647 1643 4642 1643 1645 4643 1645 1647 4644 1647 1646 4645 1646 1643 4646 1643 1649 4647 1649 1646 4648 1646 1647 4649 1647 1649 4650 1649 1648 4651 1648 1646 4652 1646 1651 4653 1651 1648 4654 1648 1649 4655 1649 1651 4656 1651 1650 4657 1650 1648 4658 1648 1653 4659 1653 1650 4660 1650 1651 4661 1651 1653 4662 1653 1652 4663 1652 1650 4664 1650 1655 4665 1655 1652 4666 1652 1653 4667 1653 1655 4668 1655 1654 4669 1654 1652 4670 1652 1657 4671 1657 1654 4672 1654 1655 4673 1655 1657 4674 1657 1656 4675 1656 1654 4676 1654 1659 4677 1659 1656 4678 1656 1657 4679 1657 1659 4680 1659 1658 4681 1658 1656 4682 1656 1661 4683 1661 1658 4684 1658 1659 4685 1659 1661 4686 1661 1660 4687 1660 1658 4688 1658 1663 4689 1663 1660 4690 1660 1661 4691 1661 1663 4692 1663 1662 4693 1662 1660 4694 1660 1665 4695 1665 1662 4696 1662 1663 4697 1663 1665 4698 1665 1664 4699 1664 1662 4700 1662 1635 4701 1635 1664 4702 1664 1665 4703 1665 1698 4704 1698 1667 4705 1667 1666 4706 1666 1669 4707 1669 1667 4708 1667 1668 4709 1668 1666 4710 1666 1667 4711 1667 1669 4712 1669 1673 4713 1673 1670 4714 1670 1671 4715 1671 1673 4716 1673 1672 4717 1672 1670 4718 1670 1675 4719 1675 1672 4720 1672 1673 4721 1673 1675 4722 1675 1674 4723 1674 1672 4724 1672 1677 4725 1677 1674 4726 1674 1675 4727 1675 1677 4728 1677 1676 4729 1676 1674 4730 1674 1679 4731 1679 1676 4732 1676 1677 4733 1677 1679 4734 1679 1678 4735 1678 1676 4736 1676 1681 4737 1681 1678 4738 1678 1679 4739 1679 1681 4740 1681 1680 4741 1680 1678 4742 1678 1683 4743 1683 1680 4744 1680 1681 4745 1681 1683 4746 1683 1682 4747 1682 1680 4748 1680 1686 4749 1686 1682 4750 1682 1683 4751 1683 1686 4752 1686 1684 4753 1684 1682 4754 1682 1686 4755 1686 1685 4756 1685 1684 4757 1684 1688 4758 1688 1685 4759 1685 1686 4760 1686 1688 4761 1688 1687 4762 1687 1685 4763 1685 1689 4764 1689 1687 4765 1687 1688 4766 1688 1691 4767 1691 1687 4768 1687 1689 4769 1689 1691 4770 1691 1690 4771 1690 1687 4772 1687 1693 4773 1693 1690 4774 1690 1691 4775 1691 1693 4776 1693 1692 4777 1692 1690 4778 1690 1695 4779 1695 1692 4780 1692 1693 4781 1693 1695 4782 1695 1694 4783 1694 1692 4784 1692 1697 4785 1697 1694 4786 1694 1695 4787 1695 1697 4788 1697 1696 4789 1696 1694 4790 1694 1699 4791 1699 1696 4792 1696 1697 4793 1697 1699 4794 1699 1698 4795 1698 1696 4796 1696 1667 4797 1667 1698 4798 1698 1699 4799 1699 1731 4800 1731 1705 4801 1705 1700 4802 1700 1704 4803 1704 1701 4804 1701 1702 4805 1702 1704 4806 1704 1703 4807 1703 1701 4808 1701 1700 4809 1700 1703 4810 1703 1704 4811 1704 1700 4812 1700 1705 4813 1705 1703 4814 1703 1709 4815 1709 1706 4816 1706 1707 4817 1707 1709 4818 1709 1708 4819 1708 1706 4820 1706 1711 4821 1711 1708 4822 1708 1709 4823 1709 1711 4824 1711 1710 4825 1710 1708 4826 1708 1714 4827 1714 1710 4828 1710 1711 4829 1711 1714 4830 1714 1712 4831 1712 1710 4832 1710 1714 4833 1714 1713 4834 1713 1712 4835 1712 1715 4836 1715 1713 4837 1713 1714 4838 1714 1717 4839 1717 1713 4840 1713 1715 4841 1715 1717 4842 1717 1716 4843 1716 1713 4844 1713 1719 4845 1719 1716 4846 1716 1717 4847 1717 1719 4848 1719 1718 4849 1718 1716 4850 1716 1721 4851 1721 1718 4852 1718 1719 4853 1719 1721 4854 1721 1720 4855 1720 1718 4856 1718 1723 4857 1723 1720 4858 1720 1721 4859 1721 1723 4860 1723 1722 4861 1722 1720 4862 1720 1725 4863 1725 1722 4864 1722 1723 4865 1723 1725 4866 1725 1724 4867 1724 1722 4868 1722 1727 4869 1727 1724 4870 1724 1725 4871 1725 1727 4872 1727 1726 4873 1726 1724 4874 1724 1729 4875 1729 1726 4876 1726 1727 4877 1727 1729 4878 1729 1728 4879 1728 1726 4880 1726 1732 4881 1732 1728 4882 1728 1729 4883 1729 1732 4884 1732 1730 4885 1730 1728 4886 1728 1732 4887 1732 1731 4888 1731 1730 4889 1730 1733 4890 1733 1731 4891 1731 1732 4892 1732 1705 4893 1705 1731 4894 1731 1733 4895 1733 1765 4896 1765 1739 4897 1739 1734 4898 1734 1738 4899 1738 1735 4900 1735 1736 4901 1736 1738 4902 1738 1737 4903 1737 1735 4904 1735 1734 4905 1734 1737 4906 1737 1738 4907 1738 1734 4908 1734 1739 4909 1739 1737 4910 1737 1742 4911 1742 1740 4912 1740 1741 4913 1741 1743 4914 1743 1740 4915 1740 1742 4916 1742 1745 4917 1745 1740 4918 1740 1743 4919 1743 1745 4920 1745 1744 4921 1744 1740 4922 1740 1747 4923 1747 1744 4924 1744 1745 4925 1745 1747 4926 1747 1746 4927 1746 1744 4928 1744 1749 4929 1749 1746 4930 1746 1747 4931 1747 1749 4932 1749 1748 4933 1748 1746 4934 1746 1751 4935 1751 1748 4936 1748 1749 4937 1749 1751 4938 1751 1750 4939 1750 1748 4940 1748 1753 4941 1753 1750 4942 1750 1751 4943 1751 1753 4944 1753 1752 4945 1752 1750 4946 1750 1755 4947 1755 1752 4948 1752 1753 4949 1753 1755 4950 1755 1754 4951 1754 1752 4952 1752 1757 4953 1757 1754 4954 1754 1755 4955 1755 1757 4956 1757 1756 4957 1756 1754 4958 1754 1759 4959 1759 1756 4960 1756 1757 4961 1757 1759 4962 1759 1758 4963 1758 1756 4964 1756 1762 4965 1762 1758 4966 1758 1759 4967 1759 1762 4968 1762 1760 4969 1760 1758 4970 1758 1762 4971 1762 1761 4972 1761 1760 4973 1760 1763 4974 1763 1761 4975 1761 1762 4976 1762 1766 4977 1766 1761 4978 1761 1763 4979 1763 1766 4980 1766 1764 4981 1764 1761 4982 1761 1766 4983 1766 1765 4984 1765 1764 4985 1764 1767 4986 1767 1765 4987 1765 1766 4988 1766 1739 4989 1739 1765 4990 1765 1767 4991 1767 1800 4992 1800 1768 4993 1768 1769 4994 1769 1773 4995 1773 1770 4996 1770 1771 4997 1771 1773 4998 1773 1772 4999 1772 1770 5000 1770 1775 5001 1775 1772 5002 1772 1773 5003 1773 1775 5004 1775 1774 5005 1774 1772 5006 1772 1777 5007 1777 1774 5008 1774 1775 5009 1775 1777 5010 1777 1776 5011 1776 1774 5012 1774 1779 5013 1779 1776 5014 1776 1777 5015 1777 1779 5016 1779 1778 5017 1778 1776 5018 1776 1781 5019 1781 1778 5020 1778 1779 5021 1779 1781 5022 1781 1780 5023 1780 1778 5024 1778 1783 5025 1783 1780 5026 1780 1781 5027 1781 1783 5028 1783 1782 5029 1782 1780 5030 1780 1786 5031 1786 1782 5032 1782 1783 5033 1783 1786 5034 1786 1784 5035 1784 1782 5036 1782 1786 5037 1786 1785 5038 1785 1784 5039 1784 1787 5040 1787 1785 5041 1785 1786 5042 1786 1789 5043 1789 1785 5044 1785 1787 5045 1787 1789 5046 1789 1788 5047 1788 1785 5048 1785 1791 5049 1791 1788 5050 1788 1789 5051 1789 1791 5052 1791 1790 5053 1790 1788 5054 1788 1793 5055 1793 1790 5056 1790 1791 5057 1791 1793 5058 1793 1792 5059 1792 1790 5060 1790 1795 5061 1795 1792 5062 1792 1793 5063 1793 1795 5064 1795 1794 5065 1794 1792 5066 1792 1798 5067 1798 1794 5068 1794 1795 5069 1795 1798 5070 1798 1796 5071 1796 1794 5072 1794 1798 5073 1798 1797 5074 1797 1796 5075 1796 1799 5076 1799 1797 5077 1797 1798 5078 1798 1801 5079 1801 1797 5080 1797 1799 5081 1799 1801 5082 1801 1800 5083 1800 1797 5084 1797 1768 5085 1768 1800 5086 1800 1801 5087 1801 1834 5088 1834 1802 5089 1802 1803 5090 1803 1807 5091 1807 1804 5092 1804 1805 5093 1805 1807 5094 1807 1806 5095 1806 1804 5096 1804 1810 5097 1810 1806 5098 1806 1807 5099 1807 1810 5100 1810 1808 5101 1808 1806 5102 1806 1810 5103 1810 1809 5104 1809 1808 5105 1808 1811 5106 1811 1809 5107 1809 1810 5108 1810 1813 5109 1813 1809 5110 1809 1811 5111 1811 1813 5112 1813 1812 5113 1812 1809 5114 1809 1815 5115 1815 1812 5116 1812 1813 5117 1813 1815 5118 1815 1814 5119 1814 1812 5120 1812 1817 5121 1817 1814 5122 1814 1815 5123 1815 1817 5124 1817 1816 5125 1816 1814 5126 1814 1819 5127 1819 1816 5128 1816 1817 5129 1817 1819 5130 1819 1818 5131 1818 1816 5132 1816 1821 5133 1821 1818 5134 1818 1819 5135 1819 1821 5136 1821 1820 5137 1820 1818 5138 1818 1823 5139 1823 1820 5140 1820 1821 5141 1821 1823 5142 1823 1822 5143 1822 1820 5144 1820 1825 5145 1825 1822 5146 1822 1823 5147 1823 1825 5148 1825 1824 5149 1824 1822 5150 1822 1827 5151 1827 1824 5152 1824 1825 5153 1825 1827 5154 1827 1826 5155 1826 1824 5156 1824 1829 5157 1829 1826 5158 1826 1827 5159 1827 1829 5160 1829 1828 5161 1828 1826 5162 1826 1831 5163 1831 1828 5164 1828 1829 5165 1829 1831 5166 1831 1830 5167 1830 1828 5168 1828 1833 5169 1833 1830 5170 1830 1831 5171 1831 1833 5172 1833 1832 5173 1832 1830 5174 1830 1835 5175 1835 1832 5176 1832 1833 5177 1833 1835 5178 1835 1834 5179 1834 1832 5180 1832 1802 5181 1802 1834 5182 1834 1835 5183 1835 1868 5184 1868 1836 5185 1836 1837 5186 1837 1841 5187 1841 1838 5188 1838 1839 5189 1839 1841 5190 1841 1840 5191 1840 1838 5192 1838 1844 5193 1844 1840 5194 1840 1841 5195 1841 1844 5196 1844 1842 5197 1842 1840 5198 1840 1844 5199 1844 1843 5200 1843 1842 5201 1842 1845 5202 1845 1843 5203 1843 1844 5204 1844 1847 5205 1847 1843 5206 1843 1845 5207 1845 1847 5208 1847 1846 5209 1846 1843 5210 1843 1849 5211 1849 1846 5212 1846 1847 5213 1847 1849 5214 1849 1848 5215 1848 1846 5216 1846 1851 5217 1851 1848 5218 1848 1849 5219 1849 1851 5220 1851 1850 5221 1850 1848 5222 1848 1854 5223 1854 1850 5224 1850 1851 5225 1851 1854 5226 1854 1852 5227 1852 1850 5228 1850 1854 5229 1854 1853 5230 1853 1852 5231 1852 1855 5232 1855 1853 5233 1853 1854 5234 1854 1857 5235 1857 1853 5236 1853 1855 5237 1855 1857 5238 1857 1856 5239 1856 1853 5240 1853 1859 5241 1859 1856 5242 1856 1857 5243 1857 1859 5244 1859 1858 5245 1858 1856 5246 1856 1861 5247 1861 1858 5248 1858 1859 5249 1859 1861 5250 1861 1860 5251 1860 1858 5252 1858 1863 5253 1863 1860 5254 1860 1861 5255 1861 1863 5256 1863 1862 5257 1862 1860 5258 1860 1865 5259 1865 1862 5260 1862 1863 5261 1863 1865 5262 1865 1864 5263 1864 1862 5264 1862 1867 5265 1867 1864 5266 1864 1865 5267 1865 1867 5268 1867 1866 5269 1866 1864 5270 1864 1869 5271 1869 1866 5272 1866 1867 5273 1867 1869 5274 1869 1868 5275 1868 1866 5276 1866 1836 5277 1836 1868 5278 1868 1869 5279 1869 1902 5280 1902 1870 5281 1870 1871 5282 1871 1875 5283 1875 1872 5284 1872 1873 5285 1873 1875 5286 1875 1874 5287 1874 1872 5288 1872 1878 5289 1878 1874 5290 1874 1875 5291 1875 1878 5292 1878 1876 5293 1876 1874 5294 1874 1878 5295 1878 1877 5296 1877 1876 5297 1876 1879 5298 1879 1877 5299 1877 1878 5300 1878 1881 5301 1881 1877 5302 1877 1879 5303 1879 1881 5304 1881 1880 5305 1880 1877 5306 1877 1883 5307 1883 1880 5308 1880 1881 5309 1881 1883 5310 1883 1882 5311 1882 1880 5312 1880 1885 5313 1885 1882 5314 1882 1883 5315 1883 1885 5316 1885 1884 5317 1884 1882 5318 1882 1887 5319 1887 1884 5320 1884 1885 5321 1885 1887 5322 1887 1886 5323 1886 1884 5324 1884 1889 5325 1889 1886 5326 1886 1887 5327 1887 1889 5328 1889 1888 5329 1888 1886 5330 1886 1891 5331 1891 1888 5332 1888 1889 5333 1889 1891 5334 1891 1890 5335 1890 1888 5336 1888 1894 5337 1894 1890 5338 1890 1891 5339 1891 1894 5340 1894 1892 5341 1892 1890 5342 1890 1894 5343 1894 1893 5344 1893 1892 5345 1892 1895 5346 1895 1893 5347 1893 1894 5348 1894 1897 5349 1897 1893 5350 1893 1895 5351 1895 1897 5352 1897 1896 5353 1896 1893 5354 1893 1899 5355 1899 1896 5356 1896 1897 5357 1897 1899 5358 1899 1898 5359 1898 1896 5360 1896 1901 5361 1901 1898 5362 1898 1899 5363 1899 1901 5364 1901 1900 5365 1900 1898 5366 1898 1903 5367 1903 1900 5368 1900 1901 5369 1901 1903 5370 1903 1902 5371 1902 1900 5372 1900 1870 5373 1870 1902 5374 1902 1903 5375 1903 1906 5376 1906 1904 5377 1904 1905 5378 1905 1904 5379 1904 1906 5380 1906 1907 5381 1907 1910 5382 1910 1908 5383 1908 1909 5384 1909 1908 5385 1908 1910 5386 1910 1911 5387 1911 1914 5388 1914 1912 5389 1912 1913 5390 1913 1912 5391 1912 1914 5392 1914 1915 5393 1915 1918 5394 1918 1916 5395 1916 1917 5396 1917 1916 5397 1916 1918 5398 1918 1919 5399 1919 3622 5400 3622 3684 5401 3684 3682 5402 3682 1921 5403 1921 1920 5404 1920 3625 5405 3625 1922 5406 1922 1920 5407 1920 1921 5408 1921 1923 5409 1923 1920 5410 1920 1922 5411 1922 1924 5412 1924 1920 5413 1920 1923 5414 1923 1925 5415 1925 1920 5416 1920 1924 5417 1924 1926 5418 1926 1920 5419 1920 1925 5420 1925 2037 5421 2037 1920 5422 1920 1926 5423 1926 2038 5424 2038 1927 5425 1927 2147 5426 2147 2150 5427 2150 2031 5428 2031 1928 5429 1928 2040 5430 2040 1929 5431 1929 2141 5432 2141 2152 5433 2152 2029 5434 2029 1930 5435 1930 2042 5436 2042 1931 5437 1931 2139 5438 2139 2154 5439 2154 2025 5440 2025 1932 5441 1932 2044 5442 2044 1933 5443 1933 2135 5444 2135 2156 5445 2156 2021 5446 2021 1934 5447 1934 2046 5448 2046 1935 5449 1935 2131 5450 2131 2047 5451 2047 1936 5452 1936 2128 5453 2128 2159 5454 2159 2016 5455 2016 1937 5456 1937 2049 5457 2049 1938 5458 1938 2050 5459 2050 2050 5460 2050 1939 5461 1939 2049 5462 2049 2162 5463 2162 2015 5464 2015 1940 5465 1940 2052 5466 2052 1941 5467 1941 2125 5468 2125 2164 5469 2164 1943 5470 1943 1942 5471 1942 2165 5472 2165 1942 5473 1942 1943 5474 1943 2055 5475 2055 1944 5476 1944 2122 5477 2122 2167 5478 2167 2010 5479 2010 1945 5480 1945 2168 5481 2168 2009 5482 2009 1946 5483 1946 2058 5484 2058 1947 5485 1947 2119 5486 2119 2170 5487 2170 2003 5488 2003 1948 5489 1948 2060 5490 2060 1949 5491 1949 2113 5492 2113 2172 5493 2172 2001 5494 2001 1950 5495 1950 2062 5496 2062 1951 5497 1951 2111 5498 2111 2174 5499 2174 1995 5500 1995 1952 5501 1952 2064 5502 2064 1953 5503 1953 2105 5504 2105 2176 5505 2176 1993 5506 1993 1954 5507 1954 2066 5508 2066 1955 5509 1955 2103 5510 2103 2178 5511 2178 1957 5512 1957 1956 5513 1956 2179 5514 2179 1956 5515 1956 1957 5516 1957 2069 5517 2069 1958 5518 1958 2100 5519 2100 2181 5520 2181 1988 5521 1988 1959 5522 1959 2182 5523 2182 1985 5524 1985 1960 5525 1960 2072 5526 2072 1961 5527 1961 2095 5528 2095 2073 5529 2073 1962 5530 1962 2094 5531 2094 2185 5532 2185 1982 5533 1982 1963 5534 1963 2075 5535 2075 1964 5536 1964 2076 5537 2076 2076 5538 2076 1965 5539 1965 2075 5540 2075 2188 5541 2188 1981 5542 1981 1966 5543 1966 2078 5544 2078 1967 5545 1967 2091 5546 2091 2079 5547 2079 1968 5548 1968 2088 5549 2088 2191 5550 2191 1976 5551 1976 1969 5552 1969 2081 5553 2081 1970 5554 1970 2082 5555 2082 2082 5556 2082 1971 5557 1971 2081 5558 2081 2194 5559 2194 1973 5560 1973 1972 5561 1972 2195 5562 2195 1972 5563 1972 1973 5564 1973 2085 5565 2085 1974 5566 1974 2086 5567 2086 2086 5568 2086 1975 5569 1975 2085 5570 2085 2198 5571 2198 1969 5572 1969 1976 5573 1976 2088 5574 2088 1977 5575 1977 2079 5576 2079 2200 5577 2200 1979 5578 1979 1978 5579 1978 2201 5580 2201 1978 5581 1978 1979 5582 1979 2091 5583 2091 1980 5584 1980 2078 5585 2078 2203 5586 2203 1966 5587 1966 1981 5588 1981 2204 5589 2204 1963 5590 1963 1982 5591 1982 2094 5592 2094 1983 5593 1983 2073 5594 2073 2095 5595 2095 1984 5596 1984 2072 5597 2072 2207 5598 2207 1960 5599 1960 1985 5600 1985 2097 5601 2097 1986 5602 1986 2098 5603 2098 2098 5604 2098 1987 5605 1987 2097 5606 2097 2210 5607 2210 1959 5608 1959 1988 5609 1988 2100 5610 2100 1989 5611 1989 2069 5612 2069 2212 5613 2212 1991 5614 1991 1990 5615 1990 2213 5616 2213 1990 5617 1990 1991 5618 1991 2103 5619 2103 1992 5620 1992 2066 5621 2066 2215 5622 2215 1954 5623 1954 1993 5624 1993 2105 5625 2105 1994 5626 1994 2064 5627 2064 2217 5628 2217 1952 5629 1952 1995 5630 1995 2107 5631 2107 1996 5632 1996 2108 5633 2108 2108 5634 2108 1997 5635 1997 2107 5636 2107 2220 5637 2220 1999 5638 1999 1998 5639 1998 2221 5640 2221 1998 5641 1998 1999 5642 1999 2111 5643 2111 2000 5644 2000 2062 5645 2062 2223 5646 2223 1950 5647 1950 2001 5648 2001 2113 5649 2113 2002 5650 2002 2060 5651 2060 2225 5652 2225 1948 5653 1948 2003 5654 2003 2115 5655 2115 2004 5656 2004 2116 5657 2116 2116 5658 2116 2005 5659 2005 2115 5660 2115 2228 5661 2228 2007 5662 2007 2006 5663 2006 2229 5664 2229 2006 5665 2006 2007 5666 2007 2119 5667 2119 2008 5668 2008 2058 5669 2058 2231 5670 2231 1946 5671 1946 2009 5672 2009 2232 5673 2232 1945 5674 1945 2010 5675 2010 2122 5676 2122 2011 5677 2011 2055 5678 2055 2234 5679 2234 2013 5680 2013 2012 5681 2012 2235 5682 2235 2012 5683 2012 2013 5684 2013 2125 5685 2125 2014 5686 2014 2052 5687 2052 2237 5688 2237 1940 5689 1940 2015 5690 2015 2238 5691 2238 1937 5692 1937 2016 5693 2016 2128 5694 2128 2017 5695 2017 2047 5696 2047 2240 5697 2240 2019 5698 2019 2018 5699 2018 2241 5700 2241 2018 5701 2018 2019 5702 2019 2131 5703 2131 2020 5704 2020 2046 5705 2046 2243 5706 2243 1934 5707 1934 2021 5708 2021 2244 5709 2244 2023 5710 2023 2022 5711 2022 2245 5712 2245 2022 5713 2022 2023 5714 2023 2135 5715 2135 2024 5716 2024 2044 5717 2044 2247 5718 2247 1932 5719 1932 2025 5720 2025 2248 5721 2248 2027 5722 2027 2026 5723 2026 2249 5724 2249 2026 5725 2026 2027 5726 2027 2139 5727 2139 2028 5728 2028 2042 5729 2042 2251 5730 2251 1930 5731 1930 2029 5732 2029 2141 5733 2141 2030 5734 2030 2040 5735 2040 2253 5736 2253 1928 5737 1928 2031 5738 2031 2143 5739 2143 2032 5740 2032 2144 5741 2144 2144 5742 2144 2033 5743 2033 2143 5744 2143 2256 5745 2256 2035 5746 2035 2034 5747 2034 2257 5748 2257 2034 5749 2034 2035 5750 2035 2147 5751 2147 2036 5752 2036 2038 5753 2038 2259 5754 2259 1920 5755 1920 2037 5756 2037 2260 5757 2260 1927 5758 1927 2038 5759 2038 2150 5760 2150 2039 5761 2039 2031 5762 2031 2262 5763 2262 1929 5764 1929 2040 5765 2040 2152 5766 2152 2041 5767 2041 2029 5768 2029 2264 5769 2264 1931 5770 1931 2042 5771 2042 2154 5772 2154 2043 5773 2043 2025 5774 2025 2266 5775 2266 1933 5776 1933 2044 5777 2044 2156 5778 2156 2045 5779 2045 2021 5780 2021 2268 5781 2268 1935 5782 1935 2046 5783 2046 2269 5784 2269 1936 5785 1936 2047 5786 2047 2159 5787 2159 2048 5788 2048 2016 5789 2016 2271 5790 2271 1938 5791 1938 2049 5792 2049 2272 5793 2272 1939 5794 1939 2050 5795 2050 2162 5796 2162 2051 5797 2051 2015 5798 2015 2274 5799 2274 1941 5800 1941 2052 5801 2052 2164 5802 2164 2053 5803 2053 1943 5804 1943 2165 5805 2165 2054 5806 2054 1942 5807 1942 2277 5808 2277 1944 5809 1944 2055 5810 2055 2167 5811 2167 2056 5812 2056 2010 5813 2010 2168 5814 2168 2057 5815 2057 2009 5816 2009 2280 5817 2280 1947 5818 1947 2058 5819 2058 2170 5820 2170 2059 5821 2059 2003 5822 2003 2282 5823 2282 1949 5824 1949 2060 5825 2060 2172 5826 2172 2061 5827 2061 2001 5828 2001 2284 5829 2284 1951 5830 1951 2062 5831 2062 2174 5832 2174 2063 5833 2063 1995 5834 1995 2286 5835 2286 1953 5836 1953 2064 5837 2064 2176 5838 2176 2065 5839 2065 1993 5840 1993 2288 5841 2288 1955 5842 1955 2066 5843 2066 2178 5844 2178 2067 5845 2067 1957 5846 1957 2179 5847 2179 2068 5848 2068 1956 5849 1956 2291 5850 2291 1958 5851 1958 2069 5852 2069 2181 5853 2181 2070 5854 2070 1988 5855 1988 2182 5856 2182 2071 5857 2071 1985 5858 1985 2294 5859 2294 1961 5860 1961 2072 5861 2072 2295 5862 2295 1962 5863 1962 2073 5864 2073 2185 5865 2185 2074 5866 2074 1982 5867 1982 2297 5868 2297 1964 5869 1964 2075 5870 2075 2298 5871 2298 1965 5872 1965 2076 5873 2076 2188 5874 2188 2077 5875 2077 1981 5876 1981 2300 5877 2300 1967 5878 1967 2078 5879 2078 2301 5880 2301 1968 5881 1968 2079 5882 2079 2191 5883 2191 2080 5884 2080 1976 5885 1976 2303 5886 2303 1970 5887 1970 2081 5888 2081 2304 5889 2304 1971 5890 1971 2082 5891 2082 2194 5892 2194 2083 5893 2083 1973 5894 1973 2195 5895 2195 2084 5896 2084 1972 5897 1972 2307 5898 2307 1974 5899 1974 2085 5900 2085 2308 5901 2308 1975 5902 1975 2086 5903 2086 2198 5904 2198 2087 5905 2087 1969 5906 1969 2310 5907 2310 1977 5908 1977 2088 5909 2088 2200 5910 2200 2089 5911 2089 1979 5912 1979 2201 5913 2201 2090 5914 2090 1978 5915 1978 2313 5916 2313 1980 5917 1980 2091 5918 2091 2203 5919 2203 2092 5920 2092 1966 5921 1966 2204 5922 2204 2093 5923 2093 1963 5924 1963 2316 5925 2316 1983 5926 1983 2094 5927 2094 2317 5928 2317 1984 5929 1984 2095 5930 2095 2207 5931 2207 2096 5932 2096 1960 5933 1960 2319 5934 2319 1986 5935 1986 2097 5936 2097 2320 5937 2320 1987 5938 1987 2098 5939 2098 2210 5940 2210 2099 5941 2099 1959 5942 1959 2322 5943 2322 1989 5944 1989 2100 5945 2100 2212 5946 2212 2101 5947 2101 1991 5948 1991 2213 5949 2213 2102 5950 2102 1990 5951 1990 2325 5952 2325 1992 5953 1992 2103 5954 2103 2215 5955 2215 2104 5956 2104 1954 5957 1954 2327 5958 2327 1994 5959 1994 2105 5960 2105 2217 5961 2217 2106 5962 2106 1952 5963 1952 2329 5964 2329 1996 5965 1996 2107 5966 2107 2330 5967 2330 1997 5968 1997 2108 5969 2108 2220 5970 2220 2109 5971 2109 1999 5972 1999 2221 5973 2221 2110 5974 2110 1998 5975 1998 2333 5976 2333 2000 5977 2000 2111 5978 2111 2223 5979 2223 2112 5980 2112 1950 5981 1950 2335 5982 2335 2002 5983 2002 2113 5984 2113 2225 5985 2225 2114 5986 2114 1948 5987 1948 2337 5988 2337 2004 5989 2004 2115 5990 2115 2338 5991 2338 2005 5992 2005 2116 5993 2116 2228 5994 2228 2117 5995 2117 2007 5996 2007 2229 5997 2229 2118 5998 2118 2006 5999 2006 2341 6000 2341 2008 6001 2008 2119 6002 2119 2231 6003 2231 2120 6004 2120 1946 6005 1946 2232 6006 2232 2121 6007 2121 1945 6008 1945 2344 6009 2344 2011 6010 2011 2122 6011 2122 2234 6012 2234 2123 6013 2123 2013 6014 2013 2235 6015 2235 2124 6016 2124 2012 6017 2012 2347 6018 2347 2014 6019 2014 2125 6020 2125 2237 6021 2237 2126 6022 2126 1940 6023 1940 2238 6024 2238 2127 6025 2127 1937 6026 1937 2350 6027 2350 2017 6028 2017 2128 6029 2128 2240 6030 2240 2129 6031 2129 2019 6032 2019 2241 6033 2241 2130 6034 2130 2018 6035 2018 2353 6036 2353 2020 6037 2020 2131 6038 2131 2243 6039 2243 2132 6040 2132 1934 6041 1934 2244 6042 2244 2133 6043 2133 2023 6044 2023 2245 6045 2245 2134 6046 2134 2022 6047 2022 2357 6048 2357 2024 6049 2024 2135 6050 2135 2247 6051 2247 2136 6052 2136 1932 6053 1932 2248 6054 2248 2137 6055 2137 2027 6056 2027 2249 6057 2249 2138 6058 2138 2026 6059 2026 2361 6060 2361 2028 6061 2028 2139 6062 2139 2251 6063 2251 2140 6064 2140 1930 6065 1930 2363 6066 2363 2030 6067 2030 2141 6068 2141 2253 6069 2253 2142 6070 2142 1928 6071 1928 2365 6072 2365 2032 6073 2032 2143 6074 2143 2366 6075 2366 2033 6076 2033 2144 6077 2144 2256 6078 2256 2145 6079 2145 2035 6080 2035 2257 6081 2257 2146 6082 2146 2034 6083 2034 2369 6084 2369 2036 6085 2036 2147 6086 2147 3625 6087 3625 2148 6088 2148 1921 6089 1921 2260 6090 2260 2149 6091 2149 1927 6092 1927 2372 6093 2372 2039 6094 2039 2150 6095 2150 2262 6096 2262 2151 6097 2151 1929 6098 1929 2374 6099 2374 2041 6100 2041 2152 6101 2152 2264 6102 2264 2153 6103 2153 1931 6104 1931 2376 6105 2376 2043 6106 2043 2154 6107 2154 2266 6108 2266 2155 6109 2155 1933 6110 1933 2378 6111 2378 2045 6112 2045 2156 6113 2156 2268 6114 2268 2157 6115 2157 1935 6116 1935 2269 6117 2269 2158 6118 2158 1936 6119 1936 2381 6120 2381 2048 6121 2048 2159 6122 2159 2271 6123 2271 2160 6124 2160 1938 6125 1938 2272 6126 2272 2161 6127 2161 1939 6128 1939 2384 6129 2384 2051 6130 2051 2162 6131 2162 2274 6132 2274 2163 6133 2163 1941 6134 1941 2386 6135 2386 2053 6136 2053 2164 6137 2164 2387 6138 2387 2054 6139 2054 2165 6140 2165 2277 6141 2277 2166 6142 2166 1944 6143 1944 2389 6144 2389 2056 6145 2056 2167 6146 2167 2390 6147 2390 2057 6148 2057 2168 6149 2168 2280 6150 2280 2169 6151 2169 1947 6152 1947 2392 6153 2392 2059 6154 2059 2170 6155 2170 2282 6156 2282 2171 6157 2171 1949 6158 1949 2394 6159 2394 2061 6160 2061 2172 6161 2172 2284 6162 2284 2173 6163 2173 1951 6164 1951 2396 6165 2396 2063 6166 2063 2174 6167 2174 2286 6168 2286 2175 6169 2175 1953 6170 1953 2398 6171 2398 2065 6172 2065 2176 6173 2176 2288 6174 2288 2177 6175 2177 1955 6176 1955 2400 6177 2400 2067 6178 2067 2178 6179 2178 2401 6180 2401 2068 6181 2068 2179 6182 2179 2291 6183 2291 2180 6184 2180 1958 6185 1958 2403 6186 2403 2070 6187 2070 2181 6188 2181 2404 6189 2404 2071 6190 2071 2182 6191 2182 2294 6192 2294 2183 6193 2183 1961 6194 1961 2295 6195 2295 2184 6196 2184 1962 6197 1962 2407 6198 2407 2074 6199 2074 2185 6200 2185 2297 6201 2297 2186 6202 2186 1964 6203 1964 2298 6204 2298 2187 6205 2187 1965 6206 1965 2410 6207 2410 2077 6208 2077 2188 6209 2188 2300 6210 2300 2189 6211 2189 1967 6212 1967 2301 6213 2301 2190 6214 2190 1968 6215 1968 2413 6216 2413 2080 6217 2080 2191 6218 2191 2303 6219 2303 2192 6220 2192 1970 6221 1970 2304 6222 2304 2193 6223 2193 1971 6224 1971 2416 6225 2416 2083 6226 2083 2194 6227 2194 2417 6228 2417 2084 6229 2084 2195 6230 2195 2307 6231 2307 2196 6232 2196 1974 6233 1974 2308 6234 2308 2197 6235 2197 1975 6236 1975 2420 6237 2420 2087 6238 2087 2198 6239 2198 2310 6240 2310 2199 6241 2199 1977 6242 1977 2422 6243 2422 2089 6244 2089 2200 6245 2200 2423 6246 2423 2090 6247 2090 2201 6248 2201 2313 6249 2313 2202 6250 2202 1980 6251 1980 2425 6252 2425 2092 6253 2092 2203 6254 2203 2426 6255 2426 2093 6256 2093 2204 6257 2204 2316 6258 2316 2205 6259 2205 1983 6260 1983 2317 6261 2317 2206 6262 2206 1984 6263 1984 2429 6264 2429 2096 6265 2096 2207 6266 2207 2319 6267 2319 2208 6268 2208 1986 6269 1986 2320 6270 2320 2209 6271 2209 1987 6272 1987 2432 6273 2432 2099 6274 2099 2210 6275 2210 2322 6276 2322 2211 6277 2211 1989 6278 1989 2434 6279 2434 2101 6280 2101 2212 6281 2212 2435 6282 2435 2102 6283 2102 2213 6284 2213 2325 6285 2325 2214 6286 2214 1992 6287 1992 2437 6288 2437 2104 6289 2104 2215 6290 2215 2327 6291 2327 2216 6292 2216 1994 6293 1994 2439 6294 2439 2106 6295 2106 2217 6296 2217 2329 6297 2329 2218 6298 2218 1996 6299 1996 2330 6300 2330 2219 6301 2219 1997 6302 1997 2442 6303 2442 2109 6304 2109 2220 6305 2220 2443 6306 2443 2110 6307 2110 2221 6308 2221 2333 6309 2333 2222 6310 2222 2000 6311 2000 2445 6312 2445 2112 6313 2112 2223 6314 2223 2335 6315 2335 2224 6316 2224 2002 6317 2002 2447 6318 2447 2114 6319 2114 2225 6320 2225 2337 6321 2337 2226 6322 2226 2004 6323 2004 2338 6324 2338 2227 6325 2227 2005 6326 2005 2450 6327 2450 2117 6328 2117 2228 6329 2228 2451 6330 2451 2118 6331 2118 2229 6332 2229 2341 6333 2341 2230 6334 2230 2008 6335 2008 2453 6336 2453 2120 6337 2120 2231 6338 2231 2454 6339 2454 2121 6340 2121 2232 6341 2232 2344 6342 2344 2233 6343 2233 2011 6344 2011 2456 6345 2456 2123 6346 2123 2234 6347 2234 2457 6348 2457 2124 6349 2124 2235 6350 2235 2347 6351 2347 2236 6352 2236 2014 6353 2014 2459 6354 2459 2126 6355 2126 2237 6356 2237 2460 6357 2460 2127 6358 2127 2238 6359 2238 2350 6360 2350 2239 6361 2239 2017 6362 2017 2462 6363 2462 2129 6364 2129 2240 6365 2240 2463 6366 2463 2130 6367 2130 2241 6368 2241 2353 6369 2353 2242 6370 2242 2020 6371 2020 2465 6372 2465 2132 6373 2132 2243 6374 2243 2466 6375 2466 2133 6376 2133 2244 6377 2244 2467 6378 2467 2134 6379 2134 2245 6380 2245 2357 6381 2357 2246 6382 2246 2024 6383 2024 2469 6384 2469 2136 6385 2136 2247 6386 2247 2470 6387 2470 2137 6388 2137 2248 6389 2248 2471 6390 2471 2138 6391 2138 2249 6392 2249 2361 6393 2361 2250 6394 2250 2028 6395 2028 2473 6396 2473 2140 6397 2140 2251 6398 2251 2363 6399 2363 2252 6400 2252 2030 6401 2030 2475 6402 2475 2142 6403 2142 2253 6404 2253 2365 6405 2365 2254 6406 2254 2032 6407 2032 2366 6408 2366 2255 6409 2255 2033 6410 2033 2478 6411 2478 2145 6412 2145 2256 6413 2256 2479 6414 2479 2146 6415 2146 2257 6416 2257 2369 6417 2369 2258 6418 2258 2036 6419 2036 2481 6420 2481 1920 6421 1920 2259 6422 2259 2482 6423 2482 2149 6424 2149 2260 6425 2260 2372 6426 2372 2261 6427 2261 2039 6428 2039 2484 6429 2484 2151 6430 2151 2262 6431 2262 2374 6432 2374 2263 6433 2263 2041 6434 2041 2486 6435 2486 2153 6436 2153 2264 6437 2264 2376 6438 2376 2265 6439 2265 2043 6440 2043 2488 6441 2488 2155 6442 2155 2266 6443 2266 2378 6444 2378 2267 6445 2267 2045 6446 2045 2490 6447 2490 2157 6448 2157 2268 6449 2268 2491 6450 2491 2158 6451 2158 2269 6452 2269 2381 6453 2381 2270 6454 2270 2048 6455 2048 2493 6456 2493 2160 6457 2160 2271 6458 2271 2513 6459 2513 2161 6460 2161 2272 6461 2272 2384 6462 2384 2273 6463 2273 2051 6464 2051 2515 6465 2515 2163 6466 2163 2274 6467 2274 2386 6468 2386 2275 6469 2275 2053 6470 2053 2387 6471 2387 2276 6472 2276 2054 6473 2054 2518 6474 2518 2166 6475 2166 2277 6476 2277 2389 6477 2389 2278 6478 2278 2056 6479 2056 2390 6480 2390 2279 6481 2279 2057 6482 2057 2542 6483 2542 2169 6484 2169 2280 6485 2280 2392 6486 2392 2281 6487 2281 2059 6488 2059 2544 6489 2544 2171 6490 2171 2282 6491 2282 2394 6492 2394 2283 6493 2283 2061 6494 2061 2546 6495 2546 2173 6496 2173 2284 6497 2284 2396 6498 2396 2285 6499 2285 2063 6500 2063 2548 6501 2548 2175 6502 2175 2286 6503 2286 2398 6504 2398 2287 6505 2287 2065 6506 2065 2550 6507 2550 2177 6508 2177 2288 6509 2288 2400 6510 2400 2289 6511 2289 2067 6512 2067 2401 6513 2401 2290 6514 2290 2068 6515 2068 2553 6516 2553 2180 6517 2180 2291 6518 2291 2403 6519 2403 2292 6520 2292 2070 6521 2070 2404 6522 2404 2293 6523 2293 2071 6524 2071 2575 6525 2575 2183 6526 2183 2294 6527 2294 2576 6528 2576 2184 6529 2184 2295 6530 2295 2407 6531 2407 2296 6532 2296 2074 6533 2074 2578 6534 2578 2186 6535 2186 2297 6536 2297 2600 6537 2600 2187 6538 2187 2298 6539 2298 2410 6540 2410 2299 6541 2299 2077 6542 2077 2602 6543 2602 2189 6544 2189 2300 6545 2300 2603 6546 2603 2190 6547 2190 2301 6548 2301 2413 6549 2413 2302 6550 2302 2080 6551 2080 2605 6552 2605 2192 6553 2192 2303 6554 2303 2625 6555 2625 2193 6556 2193 2304 6557 2304 2416 6558 2416 2305 6559 2305 2083 6560 2083 2417 6561 2417 2306 6562 2306 2084 6563 2084 2629 6564 2629 2196 6565 2196 2307 6566 2307 2640 6567 2640 2197 6568 2197 2308 6569 2308 2420 6570 2420 2309 6571 2309 2087 6572 2087 2642 6573 2642 2199 6574 2199 2310 6575 2310 2422 6576 2422 2311 6577 2311 2089 6578 2089 2423 6579 2423 2312 6580 2312 2090 6581 2090 2645 6582 2645 2202 6583 2202 2313 6584 2313 2425 6585 2425 2314 6586 2314 2092 6587 2092 2426 6588 2426 2315 6589 2315 2093 6590 2093 2668 6591 2668 2205 6592 2205 2316 6593 2316 2669 6594 2669 2206 6595 2206 2317 6596 2317 2429 6597 2429 2318 6598 2318 2096 6599 2096 2671 6600 2671 2208 6601 2208 2319 6602 2319 2691 6603 2691 2209 6604 2209 2320 6605 2320 2432 6606 2432 2321 6607 2321 2099 6608 2099 2693 6609 2693 2211 6610 2211 2322 6611 2322 2434 6612 2434 2323 6613 2323 2101 6614 2101 2435 6615 2435 2324 6616 2324 2102 6617 2102 2697 6618 2697 2214 6619 2214 2325 6620 2325 2437 6621 2437 2326 6622 2326 2104 6623 2104 2718 6624 2718 2216 6625 2216 2327 6626 2327 2439 6627 2439 2328 6628 2328 2106 6629 2106 2720 6630 2720 2218 6631 2218 2329 6632 2329 2740 6633 2740 2219 6634 2219 2330 6635 2330 2442 6636 2442 2331 6637 2331 2109 6638 2109 2443 6639 2443 2332 6640 2332 2110 6641 2110 2745 6642 2745 2222 6643 2222 2333 6644 2333 2445 6645 2445 2334 6646 2334 2112 6647 2112 2766 6648 2766 2224 6649 2224 2335 6650 2335 2447 6651 2447 2336 6652 2336 2114 6653 2114 2768 6654 2768 2226 6655 2226 2337 6656 2337 2788 6657 2788 2227 6658 2227 2338 6659 2338 2450 6660 2450 2339 6661 2339 2117 6662 2117 2451 6663 2451 2340 6664 2340 2118 6665 2118 2793 6666 2793 2230 6667 2230 2341 6668 2341 2453 6669 2453 2342 6670 2342 2120 6671 2120 2454 6672 2454 2343 6673 2343 2121 6674 2121 2815 6675 2815 2233 6676 2233 2344 6677 2344 2456 6678 2456 2345 6679 2345 2123 6680 2123 2457 6681 2457 2346 6682 2346 2124 6683 2124 2818 6684 2818 2236 6685 2236 2347 6686 2347 2459 6687 2459 2348 6688 2348 2126 6689 2126 2460 6690 2460 2349 6691 2349 2127 6692 2127 2842 6693 2842 2239 6694 2239 2350 6695 2350 2462 6696 2462 2351 6697 2351 2129 6698 2129 2463 6699 2463 2352 6700 2352 2130 6701 2130 2845 6702 2845 2242 6703 2242 2353 6704 2353 2465 6705 2465 2354 6706 2354 2132 6707 2132 2466 6708 2466 2355 6709 2355 2133 6710 2133 2467 6711 2467 2356 6712 2356 2134 6713 2134 2869 6714 2869 2246 6715 2246 2357 6716 2357 2469 6717 2469 2358 6718 2358 2136 6719 2136 2470 6720 2470 2359 6721 2359 2137 6722 2137 2471 6723 2471 2360 6724 2360 2138 6725 2138 2892 6726 2892 2250 6727 2250 2361 6728 2361 2473 6729 2473 2362 6730 2362 2140 6731 2140 2913 6732 2913 2252 6733 2252 2363 6734 2363 2475 6735 2475 2364 6736 2364 2142 6737 2142 2915 6738 2915 2254 6739 2254 2365 6740 2365 2938 6741 2938 2255 6742 2255 2366 6743 2366 2478 6744 2478 2367 6745 2367 2145 6746 2145 2479 6747 2479 2368 6748 2368 2146 6749 2146 2941 6750 2941 2258 6751 2258 2369 6752 2369 3625 6753 3625 2370 6754 2370 2148 6755 2148 2482 6756 2482 2371 6757 2371 2149 6758 2149 2960 6759 2960 2261 6760 2261 2372 6761 2372 2484 6762 2484 2373 6763 2373 2151 6764 2151 2962 6765 2962 2263 6766 2263 2374 6767 2374 2486 6768 2486 2375 6769 2375 2153 6770 2153 2964 6771 2964 2265 6772 2265 2376 6773 2376 2488 6774 2488 2377 6775 2377 2155 6776 2155 2966 6777 2966 2267 6778 2267 2378 6779 2378 2490 6780 2490 2379 6781 2379 2157 6782 2157 2491 6783 2491 2380 6784 2380 2158 6785 2158 2494 6786 2494 2270 6787 2270 2381 6788 2381 2493 6789 2493 2382 6790 2382 2160 6791 2160 2513 6792 2513 2383 6793 2383 2161 6794 2161 2970 6795 2970 2273 6796 2273 2384 6797 2384 2515 6798 2515 2385 6799 2385 2163 6800 2163 2972 6801 2972 2275 6802 2275 2386 6803 2386 2519 6804 2519 2276 6805 2276 2387 6806 2387 2518 6807 2518 2388 6808 2388 2166 6809 2166 2526 6810 2526 2278 6811 2278 2389 6812 2389 2974 6813 2974 2279 6814 2279 2390 6815 2390 2542 6816 2542 2391 6817 2391 2169 6818 2169 2976 6819 2976 2281 6820 2281 2392 6821 2392 2544 6822 2544 2393 6823 2393 2171 6824 2171 2978 6825 2978 2283 6826 2283 2394 6827 2394 2546 6828 2546 2395 6829 2395 2173 6830 2173 2980 6831 2980 2285 6832 2285 2396 6833 2396 2548 6834 2548 2397 6835 2397 2175 6836 2175 2982 6837 2982 2287 6838 2287 2398 6839 2398 2550 6840 2550 2399 6841 2399 2177 6842 2177 2984 6843 2984 2289 6844 2289 2400 6845 2400 2554 6846 2554 2290 6847 2290 2401 6848 2401 2553 6849 2553 2402 6850 2402 2180 6851 2180 2561 6852 2561 2292 6853 2292 2403 6854 2403 2986 6855 2986 2293 6856 2293 2404 6857 2404 2575 6858 2575 2405 6859 2405 2183 6860 2183 2576 6861 2576 2406 6862 2406 2184 6863 2184 2579 6864 2579 2296 6865 2296 2407 6866 2407 2578 6867 2578 2408 6868 2408 2186 6869 2186 2600 6870 2600 2409 6871 2409 2187 6872 2187 2990 6873 2990 2299 6874 2299 2410 6875 2410 2602 6876 2602 2411 6877 2411 2189 6878 2189 2603 6879 2603 2412 6880 2412 2190 6881 2190 2606 6882 2606 2302 6883 2302 2413 6884 2413 2605 6885 2605 2414 6886 2414 2192 6887 2192 2625 6888 2625 2415 6889 2415 2193 6890 2193 2994 6891 2994 2305 6892 2305 2416 6893 2416 2630 6894 2630 2306 6895 2306 2417 6896 2417 2629 6897 2629 2418 6898 2418 2196 6899 2196 2640 6900 2640 2419 6901 2419 2197 6902 2197 2996 6903 2996 2309 6904 2309 2420 6905 2420 2642 6906 2642 2421 6907 2421 2199 6908 2199 2998 6909 2998 2311 6910 2311 2422 6911 2422 2646 6912 2646 2312 6913 2312 2423 6914 2423 2645 6915 2645 2424 6916 2424 2202 6917 2202 2653 6918 2653 2314 6919 2314 2425 6920 2425 3000 6921 3000 2315 6922 2315 2426 6923 2426 2668 6924 2668 2427 6925 2427 2205 6926 2205 2669 6927 2669 2428 6928 2428 2206 6929 2206 2672 6930 2672 2318 6931 2318 2429 6932 2429 2671 6933 2671 2430 6934 2430 2208 6935 2208 2691 6936 2691 2431 6937 2431 2209 6938 2209 3004 6939 3004 2321 6940 2321 2432 6941 2432 2693 6942 2693 2433 6943 2433 2211 6944 2211 3006 6945 3006 2323 6946 2323 2434 6947 2434 2698 6948 2698 2324 6949 2324 2435 6950 2435 2697 6951 2697 2436 6952 2436 2214 6953 2214 2705 6954 2705 2326 6955 2326 2437 6956 2437 2718 6957 2718 2438 6958 2438 2216 6959 2216 2721 6960 2721 2328 6961 2328 2439 6962 2439 2720 6963 2720 2440 6964 2440 2218 6965 2218 2740 6966 2740 2441 6967 2441 2219 6968 2219 3010 6969 3010 2331 6970 2331 2442 6971 2442 2746 6972 2746 2332 6973 2332 2443 6974 2443 2745 6975 2745 2444 6976 2444 2222 6977 2222 2753 6978 2753 2334 6979 2334 2445 6980 2445 2766 6981 2766 2446 6982 2446 2224 6983 2224 2769 6984 2769 2336 6985 2336 2447 6986 2447 2768 6987 2768 2448 6988 2448 2226 6989 2226 2788 6990 2788 2449 6991 2449 2227 6992 2227 3014 6993 3014 2339 6994 2339 2450 6995 2450 2794 6996 2794 2340 6997 2340 2451 6998 2451 2793 6999 2793 2452 7000 2452 2230 7001 2230 2801 7002 2801 2342 7003 2342 2453 7004 2453 3016 7005 3016 2343 7006 2343 2454 7007 2454 2815 7008 2815 2455 7009 2455 2233 7010 2233 3018 7011 3018 2345 7012 2345 2456 7013 2456 2819 7014 2819 2346 7015 2346 2457 7016 2457 2818 7017 2818 2458 7018 2458 2236 7019 2236 2826 7020 2826 2348 7021 2348 2459 7022 2459 3020 7023 3020 2349 7024 2349 2460 7025 2460 2842 7026 2842 2461 7027 2461 2239 7028 2239 3022 7029 3022 2351 7030 2351 2462 7031 2462 2846 7032 2846 2352 7033 2352 2463 7034 2463 2845 7035 2845 2464 7036 2464 2242 7037 2242 2853 7038 2853 2354 7039 2354 2465 7040 2465 3024 7041 3024 2355 7042 2355 2466 7043 2466 2870 7044 2870 2356 7045 2356 2467 7046 2467 2869 7047 2869 2468 7048 2468 2246 7049 2246 2877 7050 2877 2358 7051 2358 2469 7052 2469 3026 7053 3026 2359 7054 2359 2470 7055 2470 2893 7056 2893 2360 7057 2360 2471 7058 2471 2892 7059 2892 2472 7060 2472 2250 7061 2250 2900 7062 2900 2362 7063 2362 2473 7064 2473 2913 7065 2913 2474 7066 2474 2252 7067 2252 2916 7068 2916 2364 7069 2364 2475 7070 2475 2915 7071 2915 2476 7072 2476 2254 7073 2254 2938 7074 2938 2477 7075 2477 2255 7076 2255 3030 7077 3030 2367 7078 2367 2478 7079 2478 2942 7080 2942 2368 7081 2368 2479 7082 2479 2941 7083 2941 2480 7084 2480 2258 7085 2258 2947 7086 2947 1920 7087 1920 2481 7088 2481 3033 7089 3033 2371 7090 2371 2482 7091 2482 2960 7092 2960 2483 7093 2483 2261 7094 2261 3035 7095 3035 2373 7096 2373 2484 7097 2484 2962 7098 2962 2485 7099 2485 2263 7100 2263 3037 7101 3037 2375 7102 2375 2486 7103 2486 2964 7104 2964 2487 7105 2487 2265 7106 2265 3039 7107 3039 2377 7108 2377 2488 7109 2488 2966 7110 2966 2489 7111 2489 2267 7112 2267 3041 7113 3041 2379 7114 2379 2490 7115 2490 2502 7116 2502 2380 7117 2380 2491 7118 2491 2494 7119 2494 2492 7120 2492 2270 7121 2270 2492 7122 2492 2382 7123 2382 2493 7124 2493 2494 7125 2494 2382 7126 2382 2492 7127 2492 2496 7128 2496 2382 7129 2382 2494 7130 2494 2496 7131 2496 2495 7132 2495 2382 7133 2382 2498 7134 2498 2495 7135 2495 2496 7136 2496 2498 7137 2498 2497 7138 2497 2495 7139 2495 2500 7140 2500 2497 7141 2497 2498 7142 2498 2500 7143 2500 2499 7144 2499 2497 7145 2497 2380 7146 2380 2499 7147 2499 2500 7148 2500 2502 7149 2502 2499 7150 2499 2380 7151 2380 2502 7152 2502 2501 7153 2501 2499 7154 2499 2504 7155 2504 2501 7156 2501 2502 7157 2502 2504 7158 2504 2503 7159 2503 2501 7160 2501 2506 7161 2506 2503 7162 2503 2504 7163 2504 2506 7164 2506 2505 7165 2505 2503 7166 2503 2508 7167 2508 2505 7168 2505 2506 7169 2506 2508 7170 2508 2507 7171 2507 2505 7172 2505 2510 7173 2510 2507 7174 2507 2508 7175 2508 2510 7176 2510 2509 7177 2509 2507 7178 2507 2512 7179 2512 2509 7180 2509 2510 7181 2510 2512 7182 2512 2511 7183 2511 2509 7184 2509 2968 7185 2968 2511 7186 2511 2512 7187 2512 3043 7188 3043 2383 7189 2383 2513 7190 2513 2970 7191 2970 2514 7192 2514 2273 7193 2273 3045 7194 3045 2385 7195 2385 2515 7196 2515 2972 7197 2972 2516 7198 2516 2275 7199 2275 2519 7200 2519 2517 7201 2517 2276 7202 2276 2517 7203 2517 2388 7204 2388 2518 7205 2518 2519 7206 2519 2388 7207 2388 2517 7208 2517 2521 7209 2521 2388 7210 2388 2519 7211 2519 2521 7212 2521 2520 7213 2520 2388 7214 2388 2523 7215 2523 2520 7216 2520 2521 7217 2521 2523 7218 2523 2522 7219 2522 2520 7220 2520 2525 7221 2525 2522 7222 2522 2523 7223 2523 2525 7224 2525 2524 7225 2524 2522 7226 2522 2529 7227 2529 2524 7228 2524 2525 7229 2525 2529 7230 2529 2526 7231 2526 2524 7232 2524 2529 7233 2529 2278 7234 2278 2526 7235 2526 2529 7236 2529 2527 7237 2527 2278 7238 2278 2529 7239 2529 2528 7240 2528 2527 7241 2527 2531 7242 2531 2528 7243 2528 2529 7244 2529 2531 7245 2531 2530 7246 2530 2528 7247 2528 2533 7248 2533 2530 7249 2530 2531 7250 2531 2533 7251 2533 2532 7252 2532 2530 7253 2530 2535 7254 2535 2532 7255 2532 2533 7256 2533 2535 7257 2535 2534 7258 2534 2532 7259 2532 2537 7260 2537 2534 7261 2534 2535 7262 2535 2537 7263 2537 2536 7264 2536 2534 7265 2534 2541 7266 2541 2536 7267 2536 2537 7268 2537 2541 7269 2541 2538 7270 2538 2536 7271 2536 2974 7272 2974 2539 7273 2539 2279 7274 2279 2968 7275 2968 2540 7276 2540 2511 7277 2511 3047 7278 3047 2538 7279 2538 2541 7280 2541 3049 7281 3049 2391 7282 2391 2542 7283 2542 2976 7284 2976 2543 7285 2543 2281 7286 2281 3051 7287 3051 2393 7288 2393 2544 7289 2544 2978 7290 2978 2545 7291 2545 2283 7292 2283 3053 7293 3053 2395 7294 2395 2546 7295 2546 2980 7296 2980 2547 7297 2547 2285 7298 2285 3055 7299 3055 2397 7300 2397 2548 7301 2548 2982 7302 2982 2549 7303 2549 2287 7304 2287 3057 7305 3057 2399 7306 2399 2550 7307 2550 2984 7308 2984 2551 7309 2551 2289 7310 2289 2554 7311 2554 2552 7312 2552 2290 7313 2290 2552 7314 2552 2402 7315 2402 2553 7316 2553 2554 7317 2554 2402 7318 2402 2552 7319 2552 2556 7320 2556 2402 7321 2402 2554 7322 2554 2556 7323 2556 2555 7324 2555 2402 7325 2402 2558 7326 2558 2555 7327 2555 2556 7328 2556 2558 7329 2558 2557 7330 2557 2555 7331 2555 2560 7332 2560 2557 7333 2557 2558 7334 2558 2560 7335 2560 2559 7336 2559 2557 7337 2557 2564 7338 2564 2559 7339 2559 2560 7340 2560 2564 7341 2564 2561 7342 2561 2559 7343 2559 2564 7344 2564 2292 7345 2292 2561 7346 2561 2564 7347 2564 2562 7348 2562 2292 7349 2292 2564 7350 2564 2563 7351 2563 2562 7352 2562 2566 7353 2566 2563 7354 2563 2564 7355 2564 2566 7356 2566 2565 7357 2565 2563 7358 2563 2568 7359 2568 2565 7360 2565 2566 7361 2566 2568 7362 2568 2567 7363 2567 2565 7364 2565 2570 7365 2570 2567 7366 2567 2568 7367 2568 2570 7368 2570 2569 7369 2569 2567 7370 2567 2572 7371 2572 2569 7372 2569 2570 7373 2570 2572 7374 2572 2571 7375 2571 2569 7376 2569 2598 7377 2598 2571 7378 2571 2572 7379 2572 2598 7380 2598 2573 7381 2573 2571 7382 2571 2986 7383 2986 2574 7384 2574 2293 7385 2293 3061 7386 3061 2405 7387 2405 2575 7388 2575 2587 7389 2587 2406 7390 2406 2576 7391 2576 2579 7392 2579 2577 7393 2577 2296 7394 2296 2577 7395 2577 2408 7396 2408 2578 7397 2578 2579 7398 2579 2408 7399 2408 2577 7400 2577 2581 7401 2581 2408 7402 2408 2579 7403 2579 2581 7404 2581 2580 7405 2580 2408 7406 2408 2583 7407 2583 2580 7408 2580 2581 7409 2581 2583 7410 2583 2582 7411 2582 2580 7412 2580 2585 7413 2585 2582 7414 2582 2583 7415 2583 2585 7416 2585 2584 7417 2584 2582 7418 2582 2406 7419 2406 2584 7420 2584 2585 7421 2585 2587 7422 2587 2584 7423 2584 2406 7424 2406 2587 7425 2587 2586 7426 2586 2584 7427 2584 2589 7428 2589 2586 7429 2586 2587 7430 2587 2589 7431 2589 2588 7432 2588 2586 7433 2586 2591 7434 2591 2588 7435 2588 2589 7436 2589 2591 7437 2591 2590 7438 2590 2588 7439 2588 2593 7440 2593 2590 7441 2590 2591 7442 2591 2593 7443 2593 2592 7444 2592 2590 7445 2590 2595 7446 2595 2592 7447 2592 2593 7448 2593 2595 7449 2595 2594 7450 2594 2592 7451 2592 2597 7452 2597 2594 7453 2594 2595 7454 2595 2597 7455 2597 2596 7456 2596 2594 7457 2594 2988 7458 2988 2596 7459 2596 2597 7460 2597 3059 7461 3059 2573 7462 2573 2598 7463 2598 2988 7464 2988 2599 7465 2599 2596 7466 2596 3063 7467 3063 2409 7468 2409 2600 7469 2600 2990 7470 2990 2601 7471 2601 2299 7472 2299 3065 7473 3065 2411 7474 2411 2602 7475 2602 2614 7476 2614 2412 7477 2412 2603 7478 2603 2606 7479 2606 2604 7480 2604 2302 7481 2302 2604 7482 2604 2414 7483 2414 2605 7484 2605 2606 7485 2606 2414 7486 2414 2604 7487 2604 2608 7488 2608 2414 7489 2414 2606 7490 2606 2608 7491 2608 2607 7492 2607 2414 7493 2414 2610 7494 2610 2607 7495 2607 2608 7496 2608 2610 7497 2610 2609 7498 2609 2607 7499 2607 2612 7500 2612 2609 7501 2609 2610 7502 2610 2612 7503 2612 2611 7504 2611 2609 7505 2609 2412 7506 2412 2611 7507 2611 2612 7508 2612 2614 7509 2614 2611 7510 2611 2412 7511 2412 2614 7512 2614 2613 7513 2613 2611 7514 2611 2616 7515 2616 2613 7516 2613 2614 7517 2614 2616 7518 2616 2615 7519 2615 2613 7520 2613 2618 7521 2618 2615 7522 2615 2616 7523 2616 2618 7524 2618 2617 7525 2617 2615 7526 2615 2620 7527 2620 2617 7528 2617 2618 7529 2618 2620 7530 2620 2619 7531 2619 2617 7532 2617 2622 7533 2622 2619 7534 2619 2620 7535 2620 2622 7536 2622 2621 7537 2621 2619 7538 2619 2624 7539 2624 2621 7540 2621 2622 7541 2622 2624 7542 2624 2623 7543 2623 2621 7544 2621 2992 7545 2992 2623 7546 2623 2624 7547 2624 3067 7548 3067 2415 7549 2415 2625 7550 2625 2994 7551 2994 2626 7552 2626 2305 7553 2305 2992 7554 2992 2627 7555 2627 2623 7556 2623 2630 7557 2630 2628 7558 2628 2306 7559 2306 2628 7560 2628 2418 7561 2418 2629 7562 2629 2630 7563 2630 2418 7564 2418 2628 7565 2628 2632 7566 2632 2418 7567 2418 2630 7568 2630 2632 7569 2632 2631 7570 2631 2418 7571 2418 2634 7572 2634 2631 7573 2631 2632 7574 2632 2634 7575 2634 2633 7576 2633 2631 7577 2631 2636 7578 2636 2633 7579 2633 2634 7580 2634 2636 7581 2636 2635 7582 2635 2633 7583 2633 2638 7584 2638 2635 7585 2635 2636 7586 2636 2638 7587 2638 2637 7588 2637 2635 7589 2635 3069 7590 3069 2637 7591 2637 2638 7592 2638 3069 7593 3069 2639 7594 2639 2637 7595 2637 3071 7596 3071 2419 7597 2419 2640 7598 2640 2996 7599 2996 2641 7600 2641 2309 7601 2309 3073 7602 3073 2421 7603 2421 2642 7604 2642 2998 7605 2998 2643 7606 2643 2311 7607 2311 2646 7608 2646 2644 7609 2644 2312 7610 2312 2644 7611 2644 2424 7612 2424 2645 7613 2645 2646 7614 2646 2424 7615 2424 2644 7616 2644 2648 7617 2648 2424 7618 2424 2646 7619 2646 2648 7620 2648 2647 7621 2647 2424 7622 2424 2650 7623 2650 2647 7624 2647 2648 7625 2648 2650 7626 2650 2649 7627 2649 2647 7628 2647 2652 7629 2652 2649 7630 2649 2650 7631 2650 2652 7632 2652 2651 7633 2651 2649 7634 2649 2656 7635 2656 2651 7636 2651 2652 7637 2652 2656 7638 2656 2653 7639 2653 2651 7640 2651 2656 7641 2656 2314 7642 2314 2653 7643 2653 2656 7644 2656 2654 7645 2654 2314 7646 2314 2656 7647 2656 2655 7648 2655 2654 7649 2654 2658 7650 2658 2655 7651 2655 2656 7652 2656 2658 7653 2658 2657 7654 2657 2655 7655 2655 2660 7656 2660 2657 7657 2657 2658 7658 2658 2660 7659 2660 2659 7660 2659 2657 7661 2657 2662 7662 2662 2659 7663 2659 2660 7664 2660 2662 7665 2662 2661 7666 2661 2659 7667 2659 2664 7668 2664 2661 7669 2661 2662 7670 2662 2664 7671 2664 2663 7672 2663 2661 7673 2661 2666 7674 2666 2663 7675 2663 2664 7676 2664 2666 7677 2666 2665 7678 2665 2663 7679 2663 3075 7680 3075 2665 7681 2665 2666 7682 2666 3000 7683 3000 2667 7684 2667 2315 7685 2315 3077 7686 3077 2427 7687 2427 2668 7688 2668 2680 7689 2680 2428 7690 2428 2669 7691 2669 2672 7692 2672 2670 7693 2670 2318 7694 2318 2670 7695 2670 2430 7696 2430 2671 7697 2671 2672 7698 2672 2430 7699 2430 2670 7700 2670 2674 7701 2674 2430 7702 2430 2672 7703 2672 2674 7704 2674 2673 7705 2673 2430 7706 2430 2676 7707 2676 2673 7708 2673 2674 7709 2674 2676 7710 2676 2675 7711 2675 2673 7712 2673 2678 7713 2678 2675 7714 2675 2676 7715 2676 2678 7716 2678 2677 7717 2677 2675 7718 2675 2428 7719 2428 2677 7720 2677 2678 7721 2678 2680 7722 2680 2677 7723 2677 2428 7724 2428 2680 7725 2680 2679 7726 2679 2677 7727 2677 2682 7728 2682 2679 7729 2679 2680 7730 2680 2682 7731 2682 2681 7732 2681 2679 7733 2679 2684 7734 2684 2681 7735 2681 2682 7736 2682 2684 7737 2684 2683 7738 2683 2681 7739 2681 2686 7740 2686 2683 7741 2683 2684 7742 2684 2686 7743 2686 2685 7744 2685 2683 7745 2683 2688 7746 2688 2685 7747 2685 2686 7748 2686 2688 7749 2688 2687 7750 2687 2685 7751 2685 2690 7752 2690 2687 7753 2687 2688 7754 2688 2690 7755 2690 2689 7756 2689 2687 7757 2687 3002 7758 3002 2689 7759 2689 2690 7760 2690 3079 7761 3079 2431 7762 2431 2691 7763 2691 3004 7764 3004 2692 7765 2692 2321 7766 2321 3081 7767 3081 2433 7768 2433 2693 7769 2693 3006 7770 3006 2694 7771 2694 2323 7772 2323 3002 7773 3002 2695 7774 2695 2689 7775 2689 2698 7776 2698 2696 7777 2696 2324 7778 2324 2696 7779 2696 2436 7780 2436 2697 7781 2697 2698 7782 2698 2436 7783 2436 2696 7784 2696 2700 7785 2700 2436 7786 2436 2698 7787 2698 2700 7788 2700 2699 7789 2699 2436 7790 2436 2702 7791 2702 2699 7792 2699 2700 7793 2700 2702 7794 2702 2701 7795 2701 2699 7796 2699 2704 7797 2704 2701 7798 2701 2702 7799 2702 2704 7800 2704 2703 7801 2703 2701 7802 2701 2708 7803 2708 2703 7804 2703 2704 7805 2704 2708 7806 2708 2705 7807 2705 2703 7808 2703 2708 7809 2708 2326 7810 2326 2705 7811 2705 2708 7812 2708 2706 7813 2706 2326 7814 2326 2708 7815 2708 2707 7816 2707 2706 7817 2706 2710 7818 2710 2707 7819 2707 2708 7820 2708 2710 7821 2710 2709 7822 2709 2707 7823 2707 2712 7824 2712 2709 7825 2709 2710 7826 2710 2712 7827 2712 2711 7828 2711 2709 7829 2709 2714 7830 2714 2711 7831 2711 2712 7832 2712 2714 7833 2714 2713 7834 2713 2711 7835 2711 2716 7836 2716 2713 7837 2713 2714 7838 2714 2716 7839 2716 2715 7840 2715 2713 7841 2713 2743 7842 2743 2715 7843 2715 2716 7844 2716 2743 7845 2743 2717 7846 2717 2715 7847 2715 2729 7848 2729 2438 7849 2438 2718 7850 2718 2721 7851 2721 2719 7852 2719 2328 7853 2328 2719 7854 2719 2440 7855 2440 2720 7856 2720 2721 7857 2721 2440 7858 2440 2719 7859 2719 2723 7860 2723 2440 7861 2440 2721 7862 2721 2723 7863 2723 2722 7864 2722 2440 7865 2440 2725 7866 2725 2722 7867 2722 2723 7868 2723 2725 7869 2725 2724 7870 2724 2722 7871 2722 2727 7872 2727 2724 7873 2724 2725 7874 2725 2727 7875 2727 2726 7876 2726 2724 7877 2724 2438 7878 2438 2726 7879 2726 2727 7880 2727 2729 7881 2729 2726 7882 2726 2438 7883 2438 2729 7884 2729 2728 7885 2728 2726 7886 2726 2731 7887 2731 2728 7888 2728 2729 7889 2729 2731 7890 2731 2730 7891 2730 2728 7892 2728 2733 7893 2733 2730 7894 2730 2731 7895 2731 2733 7896 2733 2732 7897 2732 2730 7898 2730 2735 7899 2735 2732 7900 2732 2733 7901 2733 2735 7902 2735 2734 7903 2734 2732 7904 2732 2737 7905 2737 2734 7906 2734 2735 7907 2735 2737 7908 2737 2736 7909 2736 2734 7910 2734 2739 7911 2739 2736 7912 2736 2737 7913 2737 2739 7914 2739 2738 7915 2738 2736 7916 2736 3008 7917 3008 2738 7918 2738 2739 7919 2739 3085 7920 3085 2441 7921 2441 2740 7922 2740 3010 7923 3010 2741 7924 2741 2331 7925 2331 2746 7926 2746 2742 7927 2742 2332 7928 2332 3083 7929 3083 2717 7930 2717 2743 7931 2743 3008 7932 3008 2744 7933 2744 2738 7934 2738 2742 7935 2742 2444 7936 2444 2745 7937 2745 2746 7938 2746 2444 7939 2444 2742 7940 2742 2748 7941 2748 2444 7942 2444 2746 7943 2746 2748 7944 2748 2747 7945 2747 2444 7946 2444 2750 7947 2750 2747 7948 2747 2748 7949 2748 2750 7950 2750 2749 7951 2749 2747 7952 2747 2752 7953 2752 2749 7954 2749 2750 7955 2750 2752 7956 2752 2751 7957 2751 2749 7958 2749 2756 7959 2756 2751 7960 2751 2752 7961 2752 2756 7962 2756 2753 7963 2753 2751 7964 2751 2756 7965 2756 2334 7966 2334 2753 7967 2753 2756 7968 2756 2754 7969 2754 2334 7970 2334 2756 7971 2756 2755 7972 2755 2754 7973 2754 2758 7974 2758 2755 7975 2755 2756 7976 2756 2758 7977 2758 2757 7978 2757 2755 7979 2755 2760 7980 2760 2757 7981 2757 2758 7982 2758 2760 7983 2760 2759 7984 2759 2757 7985 2757 2762 7986 2762 2759 7987 2759 2760 7988 2760 2762 7989 2762 2761 7990 2761 2759 7991 2759 2764 7992 2764 2761 7993 2761 2762 7994 2762 2764 7995 2764 2763 7996 2763 2761 7997 2761 2791 7998 2791 2763 7999 2763 2764 8000 2764 2791 8001 2791 2765 8002 2765 2763 8003 2763 2777 8004 2777 2446 8005 2446 2766 8006 2766 2769 8007 2769 2767 8008 2767 2336 8009 2336 2767 8010 2767 2448 8011 2448 2768 8012 2768 2769 8013 2769 2448 8014 2448 2767 8015 2767 2771 8016 2771 2448 8017 2448 2769 8018 2769 2771 8019 2771 2770 8020 2770 2448 8021 2448 2773 8022 2773 2770 8023 2770 2771 8024 2771 2773 8025 2773 2772 8026 2772 2770 8027 2770 2775 8028 2775 2772 8029 2772 2773 8030 2773 2775 8031 2775 2774 8032 2774 2772 8033 2772 2446 8034 2446 2774 8035 2774 2775 8036 2775 2777 8037 2777 2774 8038 2774 2446 8039 2446 2777 8040 2777 2776 8041 2776 2774 8042 2774 2779 8043 2779 2776 8044 2776 2777 8045 2777 2779 8046 2779 2778 8047 2778 2776 8048 2776 2781 8049 2781 2778 8050 2778 2779 8051 2779 2781 8052 2781 2780 8053 2780 2778 8054 2778 2783 8055 2783 2780 8056 2780 2781 8057 2781 2783 8058 2783 2782 8059 2782 2780 8060 2780 2785 8061 2785 2782 8062 2782 2783 8063 2783 2785 8064 2785 2784 8065 2784 2782 8066 2782 2787 8067 2787 2784 8068 2784 2785 8069 2785 2787 8070 2787 2786 8071 2786 2784 8072 2784 3012 8073 3012 2786 8074 2786 2787 8075 2787 3089 8076 3089 2449 8077 2449 2788 8078 2788 3014 8079 3014 2789 8080 2789 2339 8081 2339 2794 8082 2794 2790 8083 2790 2340 8084 2340 3087 8085 3087 2765 8086 2765 2791 8087 2791 3012 8088 3012 2792 8089 2792 2786 8090 2786 2790 8091 2790 2452 8092 2452 2793 8093 2793 2794 8094 2794 2452 8095 2452 2790 8096 2790 2796 8097 2796 2452 8098 2452 2794 8099 2794 2796 8100 2796 2795 8101 2795 2452 8102 2452 2798 8103 2798 2795 8104 2795 2796 8105 2796 2798 8106 2798 2797 8107 2797 2795 8108 2795 2800 8109 2800 2797 8110 2797 2798 8111 2798 2800 8112 2800 2799 8113 2799 2797 8114 2797 2804 8115 2804 2799 8116 2799 2800 8117 2800 2804 8118 2804 2801 8119 2801 2799 8120 2799 2804 8121 2804 2342 8122 2342 2801 8123 2801 2804 8124 2804 2802 8125 2802 2342 8126 2342 2804 8127 2804 2803 8128 2803 2802 8129 2802 2806 8130 2806 2803 8131 2803 2804 8132 2804 2806 8133 2806 2805 8134 2805 2803 8135 2803 2808 8136 2808 2805 8137 2805 2806 8138 2806 2808 8139 2808 2807 8140 2807 2805 8141 2805 2810 8142 2810 2807 8143 2807 2808 8144 2808 2810 8145 2810 2809 8146 2809 2807 8147 2807 2812 8148 2812 2809 8149 2809 2810 8150 2810 2812 8151 2812 2811 8152 2811 2809 8153 2809 2839 8154 2839 2811 8155 2811 2812 8156 2812 2839 8157 2839 2813 8158 2813 2811 8159 2811 3016 8160 3016 2814 8161 2814 2343 8162 2343 3093 8163 3093 2455 8164 2455 2815 8165 2815 3018 8166 3018 2816 8167 2816 2345 8168 2345 2819 8169 2819 2817 8170 2817 2346 8171 2346 2817 8172 2817 2458 8173 2458 2818 8174 2818 2819 8175 2819 2458 8176 2458 2817 8177 2817 2821 8178 2821 2458 8179 2458 2819 8180 2819 2821 8181 2821 2820 8182 2820 2458 8183 2458 2823 8184 2823 2820 8185 2820 2821 8186 2821 2823 8187 2823 2822 8188 2822 2820 8189 2820 2825 8190 2825 2822 8191 2822 2823 8192 2823 2825 8193 2825 2824 8194 2824 2822 8195 2822 2829 8196 2829 2824 8197 2824 2825 8198 2825 2829 8199 2829 2826 8200 2826 2824 8201 2824 2829 8202 2829 2348 8203 2348 2826 8204 2826 2829 8205 2829 2827 8206 2827 2348 8207 2348 2829 8208 2829 2828 8209 2828 2827 8210 2827 2831 8211 2831 2828 8212 2828 2829 8213 2829 2831 8214 2831 2830 8215 2830 2828 8216 2828 2833 8217 2833 2830 8218 2830 2831 8219 2831 2833 8220 2833 2832 8221 2832 2830 8222 2830 2835 8223 2835 2832 8224 2832 2833 8225 2833 2835 8226 2835 2834 8227 2834 2832 8228 2832 2837 8229 2837 2834 8230 2834 2835 8231 2835 2837 8232 2837 2836 8233 2836 2834 8234 2834 2840 8235 2840 2836 8236 2836 2837 8237 2837 2840 8238 2840 2838 8239 2838 2836 8240 2836 3091 8241 3091 2813 8242 2813 2839 8243 2839 3095 8244 3095 2838 8245 2838 2840 8246 2840 3020 8247 3020 2841 8248 2841 2349 8249 2349 3097 8250 3097 2461 8251 2461 2842 8252 2842 3022 8253 3022 2843 8254 2843 2351 8255 2351 2846 8256 2846 2844 8257 2844 2352 8258 2352 2844 8259 2844 2464 8260 2464 2845 8261 2845 2846 8262 2846 2464 8263 2464 2844 8264 2844 2848 8265 2848 2464 8266 2464 2846 8267 2846 2848 8268 2848 2847 8269 2847 2464 8270 2464 2850 8271 2850 2847 8272 2847 2848 8273 2848 2850 8274 2850 2849 8275 2849 2847 8276 2847 2852 8277 2852 2849 8278 2849 2850 8279 2850 2852 8280 2852 2851 8281 2851 2849 8282 2849 2856 8283 2856 2851 8284 2851 2852 8285 2852 2856 8286 2856 2853 8287 2853 2851 8288 2851 2856 8289 2856 2354 8290 2354 2853 8291 2853 2856 8292 2856 2854 8293 2854 2354 8294 2354 2856 8295 2856 2855 8296 2855 2854 8297 2854 2858 8298 2858 2855 8299 2855 2856 8300 2856 2858 8301 2858 2857 8302 2857 2855 8303 2855 2860 8304 2860 2857 8305 2857 2858 8306 2858 2860 8307 2860 2859 8308 2859 2857 8309 2857 2862 8310 2862 2859 8311 2859 2860 8312 2860 2862 8313 2862 2861 8314 2861 2859 8315 2859 2864 8316 2864 2861 8317 2861 2862 8318 2862 2864 8319 2864 2863 8320 2863 2861 8321 2861 2868 8322 2868 2863 8323 2863 2864 8324 2864 2868 8325 2868 2865 8326 2865 2863 8327 2863 3024 8328 3024 2866 8329 2866 2355 8330 2355 2870 8331 2870 2867 8332 2867 2356 8333 2356 3099 8334 3099 2865 8335 2865 2868 8336 2868 2867 8337 2867 2468 8338 2468 2869 8339 2869 2870 8340 2870 2468 8341 2468 2867 8342 2867 2872 8343 2872 2468 8344 2468 2870 8345 2870 2872 8346 2872 2871 8347 2871 2468 8348 2468 2874 8349 2874 2871 8350 2871 2872 8351 2872 2874 8352 2874 2873 8353 2873 2871 8354 2871 2876 8355 2876 2873 8356 2873 2874 8357 2874 2876 8358 2876 2875 8359 2875 2873 8360 2873 2880 8361 2880 2875 8362 2875 2876 8363 2876 2880 8364 2880 2877 8365 2877 2875 8366 2875 2880 8367 2880 2358 8368 2358 2877 8369 2877 2880 8370 2880 2878 8371 2878 2358 8372 2358 2880 8373 2880 2879 8374 2879 2878 8375 2878 2882 8376 2882 2879 8377 2879 2880 8378 2880 2882 8379 2882 2881 8380 2881 2879 8381 2879 2884 8382 2884 2881 8383 2881 2882 8384 2882 2884 8385 2884 2883 8386 2883 2881 8387 2881 2886 8388 2886 2883 8389 2883 2884 8390 2884 2886 8391 2886 2885 8392 2885 2883 8393 2883 2888 8394 2888 2885 8395 2885 2886 8396 2886 2888 8397 2888 2887 8398 2887 2885 8399 2885 2935 8400 2935 2887 8401 2887 2888 8402 2888 2935 8403 2935 2889 8404 2889 2887 8405 2887 3026 8406 3026 2890 8407 2890 2359 8408 2359 2893 8409 2893 2891 8410 2891 2360 8411 2360 2891 8412 2891 2472 8413 2472 2892 8414 2892 2893 8415 2893 2472 8416 2472 2891 8417 2891 2895 8418 2895 2472 8419 2472 2893 8420 2893 2895 8421 2895 2894 8422 2894 2472 8423 2472 2897 8424 2897 2894 8425 2894 2895 8426 2895 2897 8427 2897 2896 8428 2896 2894 8429 2894 2899 8430 2899 2896 8431 2896 2897 8432 2897 2899 8433 2899 2898 8434 2898 2896 8435 2896 2903 8436 2903 2898 8437 2898 2899 8438 2899 2903 8439 2903 2900 8440 2900 2898 8441 2898 2903 8442 2903 2362 8443 2362 2900 8444 2900 2903 8445 2903 2901 8446 2901 2362 8447 2362 2903 8448 2903 2902 8449 2902 2901 8450 2901 2905 8451 2905 2902 8452 2902 2903 8453 2903 2905 8454 2905 2904 8455 2904 2902 8456 2902 2907 8457 2907 2904 8458 2904 2905 8459 2905 2907 8460 2907 2906 8461 2906 2904 8462 2904 2909 8463 2909 2906 8464 2906 2907 8465 2907 2909 8466 2909 2908 8467 2908 2906 8468 2906 2911 8469 2911 2908 8470 2908 2909 8471 2909 2911 8472 2911 2910 8473 2910 2908 8474 2908 2936 8475 2936 2910 8476 2910 2911 8477 2911 2936 8478 2936 2912 8479 2912 2910 8480 2910 2924 8481 2924 2474 8482 2474 2913 8483 2913 2916 8484 2916 2914 8485 2914 2364 8486 2364 2914 8487 2914 2476 8488 2476 2915 8489 2915 2916 8490 2916 2476 8491 2476 2914 8492 2914 2918 8493 2918 2476 8494 2476 2916 8495 2916 2918 8496 2918 2917 8497 2917 2476 8498 2476 2920 8499 2920 2917 8500 2917 2918 8501 2918 2920 8502 2920 2919 8503 2919 2917 8504 2917 2922 8505 2922 2919 8506 2919 2920 8507 2920 2922 8508 2922 2921 8509 2921 2919 8510 2919 2474 8511 2474 2921 8512 2921 2922 8513 2922 2924 8514 2924 2921 8515 2921 2474 8516 2474 2924 8517 2924 2923 8518 2923 2921 8519 2921 2926 8520 2926 2923 8521 2923 2924 8522 2924 2926 8523 2926 2925 8524 2925 2923 8525 2923 2928 8526 2928 2925 8527 2925 2926 8528 2926 2928 8529 2928 2927 8530 2927 2925 8531 2925 2930 8532 2930 2927 8533 2927 2928 8534 2928 2930 8535 2930 2929 8536 2929 2927 8537 2927 2932 8538 2932 2929 8539 2929 2930 8540 2930 2932 8541 2932 2931 8542 2931 2929 8543 2929 2934 8544 2934 2931 8545 2931 2932 8546 2932 2934 8547 2934 2933 8548 2933 2931 8549 2931 3028 8550 3028 2933 8551 2933 2934 8552 2934 3101 8553 3101 2889 8554 2889 2935 8555 2935 3103 8556 3103 2912 8557 2912 2936 8558 2936 3028 8559 3028 2937 8560 2937 2933 8561 2933 3105 8562 3105 2477 8563 2477 2938 8564 2938 3030 8565 3030 2939 8566 2939 2367 8567 2367 2942 8568 2942 2940 8569 2940 2368 8570 2368 2940 8571 2940 2480 8572 2480 2941 8573 2941 2942 8574 2942 2480 8575 2480 2940 8576 2940 2944 8577 2944 2480 8578 2480 2942 8579 2942 2944 8580 2944 2943 8581 2943 2480 8582 2480 2946 8583 2946 2943 8584 2943 2944 8585 2944 2946 8586 2946 2945 8587 2945 2943 8588 2943 2948 8589 2948 2945 8590 2945 2946 8591 2946 2948 8592 2948 2947 8593 2947 2945 8594 2945 2949 8595 2949 2947 8596 2947 2948 8597 2948 2950 8598 2950 2947 8599 2947 2949 8600 2949 2950 8601 2950 1920 8602 1920 2947 8603 2947 2951 8604 2951 1920 8605 1920 2950 8606 2950 2952 8607 2952 1920 8608 1920 2951 8609 2951 2953 8610 2953 1920 8611 1920 2952 8612 2952 2954 8613 2954 1920 8614 1920 2953 8615 2953 2955 8616 2955 1920 8617 1920 2954 8618 2954 2956 8619 2956 1920 8620 1920 2955 8621 2955 2957 8622 2957 1920 8623 1920 2956 8624 2956 2958 8625 2958 1920 8626 1920 2957 8627 2957 3031 8628 3031 1920 8629 1920 2958 8630 2958 3033 8631 3033 2959 8632 2959 2371 8633 2371 3108 8634 3108 2483 8635 2483 2960 8636 2960 3035 8637 3035 2961 8638 2961 2373 8639 2373 3116 8640 3116 2485 8641 2485 2962 8642 2962 3037 8643 3037 2963 8644 2963 2375 8645 2375 3124 8646 3124 2487 8647 2487 2964 8648 2964 3039 8649 3039 2965 8650 2965 2377 8651 2377 3132 8652 3132 2489 8653 2489 2966 8654 2966 3041 8655 3041 2967 8656 2967 2379 8657 2379 3140 8658 3140 2540 8659 2540 2968 8660 2968 3043 8661 3043 2969 8662 2969 2383 8663 2383 3148 8664 3148 2514 8665 2514 2970 8666 2970 3045 8667 3045 2971 8668 2971 2385 8669 2385 3156 8670 3156 2516 8671 2516 2972 8672 2972 3047 8673 3047 2973 8674 2973 2538 8675 2538 3164 8676 3164 2539 8677 2539 2974 8678 2974 3049 8679 3049 2975 8680 2975 2391 8681 2391 3172 8682 3172 2543 8683 2543 2976 8684 2976 3051 8685 3051 2977 8686 2977 2393 8687 2393 3180 8688 3180 2545 8689 2545 2978 8690 2978 3053 8691 3053 2979 8692 2979 2395 8693 2395 3188 8694 3188 2547 8695 2547 2980 8696 2980 3055 8697 3055 2981 8698 2981 2397 8699 2397 3196 8700 3196 2549 8701 2549 2982 8702 2982 3057 8703 3057 2983 8704 2983 2399 8705 2399 3204 8706 3204 2551 8707 2551 2984 8708 2984 3059 8709 3059 2985 8710 2985 2573 8711 2573 3212 8712 3212 2574 8713 2574 2986 8714 2986 3061 8715 3061 2987 8716 2987 2405 8717 2405 3220 8718 3220 2599 8719 2599 2988 8720 2988 3063 8721 3063 2989 8722 2989 2409 8723 2409 3228 8724 3228 2601 8725 2601 2990 8726 2990 3065 8727 3065 2991 8728 2991 2411 8729 2411 3236 8730 3236 2627 8731 2627 2992 8732 2992 3067 8733 3067 2993 8734 2993 2415 8735 2415 3244 8736 3244 2626 8737 2626 2994 8738 2994 3071 8739 3071 2995 8740 2995 2419 8741 2419 3252 8742 3252 2641 8743 2641 2996 8744 2996 3073 8745 3073 2997 8746 2997 2421 8747 2421 3260 8748 3260 2643 8749 2643 2998 8750 2998 3075 8751 3075 2999 8752 2999 2665 8753 2665 3268 8754 3268 2667 8755 2667 3000 8756 3000 3077 8757 3077 3001 8758 3001 2427 8759 2427 3276 8760 3276 2695 8761 2695 3002 8762 3002 3079 8763 3079 3003 8764 3003 2431 8765 2431 3284 8766 3284 2692 8767 2692 3004 8768 3004 3081 8769 3081 3005 8770 3005 2433 8771 2433 3292 8772 3292 2694 8773 2694 3006 8774 3006 3083 8775 3083 3007 8776 3007 2717 8777 2717 3300 8778 3300 2744 8779 2744 3008 8780 3008 3085 8781 3085 3009 8782 3009 2441 8783 2441 3308 8784 3308 2741 8785 2741 3010 8786 3010 3087 8787 3087 3011 8788 3011 2765 8789 2765 3316 8790 3316 2792 8791 2792 3012 8792 3012 3089 8793 3089 3013 8794 3013 2449 8795 2449 3324 8796 3324 2789 8797 2789 3014 8798 3014 3091 8799 3091 3015 8800 3015 2813 8801 2813 3332 8802 3332 2814 8803 2814 3016 8804 3016 3093 8805 3093 3017 8806 3017 2455 8807 2455 3340 8808 3340 2816 8809 2816 3018 8810 3018 3095 8811 3095 3019 8812 3019 2838 8813 2838 3348 8814 3348 2841 8815 2841 3020 8816 3020 3097 8817 3097 3021 8818 3021 2461 8819 2461 3356 8820 3356 2843 8821 2843 3022 8822 3022 3099 8823 3099 3023 8824 3023 2865 8825 2865 3364 8826 3364 2866 8827 2866 3024 8828 3024 3101 8829 3101 3025 8830 3025 2889 8831 2889 3372 8832 3372 2890 8833 2890 3026 8834 3026 3103 8835 3103 3027 8836 3027 2912 8837 2912 3380 8838 3380 2937 8839 2937 3028 8840 3028 3105 8841 3105 3029 8842 3029 2477 8843 2477 3388 8844 3388 2939 8845 2939 3030 8846 3030 3395 8847 3395 1920 8848 1920 3031 8849 3031 3625 8850 3625 3032 8851 3032 2370 8852 2370 3109 8853 3109 2959 8854 2959 3033 8855 3033 3108 8856 3108 3034 8857 3034 2483 8858 2483 3117 8859 3117 2961 8860 2961 3035 8861 3035 3116 8862 3116 3036 8863 3036 2485 8864 2485 3125 8865 3125 2963 8866 2963 3037 8867 3037 3124 8868 3124 3038 8869 3038 2487 8870 2487 3133 8871 3133 2965 8872 2965 3039 8873 3039 3132 8874 3132 3040 8875 3040 2489 8876 2489 3141 8877 3141 2967 8878 2967 3041 8879 3041 3140 8880 3140 3042 8881 3042 2540 8882 2540 3149 8883 3149 2969 8884 2969 3043 8885 3043 3148 8886 3148 3044 8887 3044 2514 8888 2514 3157 8889 3157 2971 8890 2971 3045 8891 3045 3156 8892 3156 3046 8893 3046 2516 8894 2516 3165 8895 3165 2973 8896 2973 3047 8897 3047 3164 8898 3164 3048 8899 3048 2539 8900 2539 3173 8901 3173 2975 8902 2975 3049 8903 3049 3172 8904 3172 3050 8905 3050 2543 8906 2543 3181 8907 3181 2977 8908 2977 3051 8909 3051 3180 8910 3180 3052 8911 3052 2545 8912 2545 3189 8913 3189 2979 8914 2979 3053 8915 3053 3188 8916 3188 3054 8917 3054 2547 8918 2547 3197 8919 3197 2981 8920 2981 3055 8921 3055 3196 8922 3196 3056 8923 3056 2549 8924 2549 3205 8925 3205 2983 8926 2983 3057 8927 3057 3204 8928 3204 3058 8929 3058 2551 8930 2551 3213 8931 3213 2985 8932 2985 3059 8933 3059 3212 8934 3212 3060 8935 3060 2574 8936 2574 3221 8937 3221 2987 8938 2987 3061 8939 3061 3220 8940 3220 3062 8941 3062 2599 8942 2599 3229 8943 3229 2989 8944 2989 3063 8945 3063 3228 8946 3228 3064 8947 3064 2601 8948 2601 3237 8949 3237 2991 8950 2991 3065 8951 3065 3236 8952 3236 3066 8953 3066 2627 8954 2627 3245 8955 3245 2993 8956 2993 3067 8957 3067 3244 8958 3244 3068 8959 3068 2626 8960 2626 3433 8961 3433 2639 8962 2639 3069 8963 3069 3433 8964 3433 3070 8965 3070 2639 8966 2639 3253 8967 3253 2995 8968 2995 3071 8969 3071 3252 8970 3252 3072 8971 3072 2641 8972 2641 3261 8973 3261 2997 8974 2997 3073 8975 3073 3260 8976 3260 3074 8977 3074 2643 8978 2643 3269 8979 3269 2999 8980 2999 3075 8981 3075 3268 8982 3268 3076 8983 3076 2667 8984 2667 3277 8985 3277 3001 8986 3001 3077 8987 3077 3276 8988 3276 3078 8989 3078 2695 8990 2695 3285 8991 3285 3003 8992 3003 3079 8993 3079 3284 8994 3284 3080 8995 3080 2692 8996 2692 3293 8997 3293 3005 8998 3005 3081 8999 3081 3292 9000 3292 3082 9001 3082 2694 9002 2694 3301 9003 3301 3007 9004 3007 3083 9005 3083 3300 9006 3300 3084 9007 3084 2744 9008 2744 3309 9009 3309 3009 9010 3009 3085 9011 3085 3308 9012 3308 3086 9013 3086 2741 9014 2741 3317 9015 3317 3011 9016 3011 3087 9017 3087 3316 9018 3316 3088 9019 3088 2792 9020 2792 3325 9021 3325 3013 9022 3013 3089 9023 3089 3324 9024 3324 3090 9025 3090 2789 9026 2789 3333 9027 3333 3015 9028 3015 3091 9029 3091 3332 9030 3332 3092 9031 3092 2814 9032 2814 3341 9033 3341 3017 9034 3017 3093 9035 3093 3340 9036 3340 3094 9037 3094 2816 9038 2816 3349 9039 3349 3019 9040 3019 3095 9041 3095 3348 9042 3348 3096 9043 3096 2841 9044 2841 3357 9045 3357 3021 9046 3021 3097 9047 3097 3356 9048 3356 3098 9049 3098 2843 9050 2843 3365 9051 3365 3023 9052 3023 3099 9053 3099 3364 9054 3364 3100 9055 3100 2866 9056 2866 3373 9057 3373 3025 9058 3025 3101 9059 3101 3372 9060 3372 3102 9061 3102 2890 9062 2890 3381 9063 3381 3027 9064 3027 3103 9065 3103 3380 9066 3380 3104 9067 3104 2937 9068 2937 3389 9069 3389 3029 9070 3029 3105 9071 3105 3388 9072 3388 3106 9073 3106 2939 9074 2939 3109 9075 3109 3107 9076 3107 2959 9077 2959 3107 9078 3107 3034 9079 3034 3108 9080 3108 3109 9081 3109 3034 9082 3034 3107 9083 3107 3111 9084 3111 3034 9085 3034 3109 9086 3109 3111 9087 3111 3110 9088 3110 3034 9089 3034 3113 9090 3113 3110 9091 3110 3111 9092 3111 3113 9093 3113 3112 9094 3112 3110 9095 3110 3397 9096 3397 3112 9097 3112 3113 9098 3113 3397 9099 3397 3114 9100 3114 3112 9101 3112 3117 9102 3117 3115 9103 3115 2961 9104 2961 3115 9105 3115 3036 9106 3036 3116 9107 3116 3117 9108 3117 3036 9109 3036 3115 9110 3115 3119 9111 3119 3036 9112 3036 3117 9113 3117 3119 9114 3119 3118 9115 3118 3036 9116 3036 3121 9117 3121 3118 9118 3118 3119 9119 3119 3121 9120 3121 3120 9121 3120 3118 9122 3118 3399 9123 3399 3120 9124 3120 3121 9125 3121 3399 9126 3399 3122 9127 3122 3120 9128 3120 3125 9129 3125 3123 9130 3123 2963 9131 2963 3123 9132 3123 3038 9133 3038 3124 9134 3124 3125 9135 3125 3038 9136 3038 3123 9137 3123 3127 9138 3127 3038 9139 3038 3125 9140 3125 3127 9141 3127 3126 9142 3126 3038 9143 3038 3129 9144 3129 3126 9145 3126 3127 9146 3127 3129 9147 3129 3128 9148 3128 3126 9149 3126 3401 9150 3401 3128 9151 3128 3129 9152 3129 3401 9153 3401 3130 9154 3130 3128 9155 3128 3133 9156 3133 3131 9157 3131 2965 9158 2965 3131 9159 3131 3040 9160 3040 3132 9161 3132 3133 9162 3133 3040 9163 3040 3131 9164 3131 3135 9165 3135 3040 9166 3040 3133 9167 3133 3135 9168 3135 3134 9169 3134 3040 9170 3040 3137 9171 3137 3134 9172 3134 3135 9173 3135 3137 9174 3137 3136 9175 3136 3134 9176 3134 3403 9177 3403 3136 9178 3136 3137 9179 3137 3403 9180 3403 3138 9181 3138 3136 9182 3136 3141 9183 3141 3139 9184 3139 2967 9185 2967 3139 9186 3139 3042 9187 3042 3140 9188 3140 3141 9189 3141 3042 9190 3042 3139 9191 3139 3143 9192 3143 3042 9193 3042 3141 9194 3141 3143 9195 3143 3142 9196 3142 3042 9197 3042 3145 9198 3145 3142 9199 3142 3143 9200 3143 3145 9201 3145 3144 9202 3144 3142 9203 3142 3405 9204 3405 3144 9205 3144 3145 9206 3145 3405 9207 3405 3146 9208 3146 3144 9209 3144 3149 9210 3149 3147 9211 3147 2969 9212 2969 3147 9213 3147 3044 9214 3044 3148 9215 3148 3149 9216 3149 3044 9217 3044 3147 9218 3147 3151 9219 3151 3044 9220 3044 3149 9221 3149 3151 9222 3151 3150 9223 3150 3044 9224 3044 3153 9225 3153 3150 9226 3150 3151 9227 3151 3153 9228 3153 3152 9229 3152 3150 9230 3150 3407 9231 3407 3152 9232 3152 3153 9233 3153 3407 9234 3407 3154 9235 3154 3152 9236 3152 3157 9237 3157 3155 9238 3155 2971 9239 2971 3155 9240 3155 3046 9241 3046 3156 9242 3156 3157 9243 3157 3046 9244 3046 3155 9245 3155 3159 9246 3159 3046 9247 3046 3157 9248 3157 3159 9249 3159 3158 9250 3158 3046 9251 3046 3161 9252 3161 3158 9253 3158 3159 9254 3159 3161 9255 3161 3160 9256 3160 3158 9257 3158 3409 9258 3409 3160 9259 3160 3161 9260 3161 3409 9261 3409 3162 9262 3162 3160 9263 3160 3165 9264 3165 3163 9265 3163 2973 9266 2973 3163 9267 3163 3048 9268 3048 3164 9269 3164 3165 9270 3165 3048 9271 3048 3163 9272 3163 3167 9273 3167 3048 9274 3048 3165 9275 3165 3167 9276 3167 3166 9277 3166 3048 9278 3048 3169 9279 3169 3166 9280 3166 3167 9281 3167 3169 9282 3169 3168 9283 3168 3166 9284 3166 3411 9285 3411 3168 9286 3168 3169 9287 3169 3411 9288 3411 3170 9289 3170 3168 9290 3168 3173 9291 3173 3171 9292 3171 2975 9293 2975 3171 9294 3171 3050 9295 3050 3172 9296 3172 3173 9297 3173 3050 9298 3050 3171 9299 3171 3175 9300 3175 3050 9301 3050 3173 9302 3173 3175 9303 3175 3174 9304 3174 3050 9305 3050 3177 9306 3177 3174 9307 3174 3175 9308 3175 3177 9309 3177 3176 9310 3176 3174 9311 3174 3413 9312 3413 3176 9313 3176 3177 9314 3177 3413 9315 3413 3178 9316 3178 3176 9317 3176 3181 9318 3181 3179 9319 3179 2977 9320 2977 3179 9321 3179 3052 9322 3052 3180 9323 3180 3181 9324 3181 3052 9325 3052 3179 9326 3179 3183 9327 3183 3052 9328 3052 3181 9329 3181 3183 9330 3183 3182 9331 3182 3052 9332 3052 3185 9333 3185 3182 9334 3182 3183 9335 3183 3185 9336 3185 3184 9337 3184 3182 9338 3182 3415 9339 3415 3184 9340 3184 3185 9341 3185 3415 9342 3415 3186 9343 3186 3184 9344 3184 3189 9345 3189 3187 9346 3187 2979 9347 2979 3187 9348 3187 3054 9349 3054 3188 9350 3188 3189 9351 3189 3054 9352 3054 3187 9353 3187 3191 9354 3191 3054 9355 3054 3189 9356 3189 3191 9357 3191 3190 9358 3190 3054 9359 3054 3193 9360 3193 3190 9361 3190 3191 9362 3191 3193 9363 3193 3192 9364 3192 3190 9365 3190 3417 9366 3417 3192 9367 3192 3193 9368 3193 3417 9369 3417 3194 9370 3194 3192 9371 3192 3197 9372 3197 3195 9373 3195 2981 9374 2981 3195 9375 3195 3056 9376 3056 3196 9377 3196 3197 9378 3197 3056 9379 3056 3195 9380 3195 3199 9381 3199 3056 9382 3056 3197 9383 3197 3199 9384 3199 3198 9385 3198 3056 9386 3056 3201 9387 3201 3198 9388 3198 3199 9389 3199 3201 9390 3201 3200 9391 3200 3198 9392 3198 3419 9393 3419 3200 9394 3200 3201 9395 3201 3419 9396 3419 3202 9397 3202 3200 9398 3200 3205 9399 3205 3203 9400 3203 2983 9401 2983 3203 9402 3203 3058 9403 3058 3204 9404 3204 3205 9405 3205 3058 9406 3058 3203 9407 3203 3207 9408 3207 3058 9409 3058 3205 9410 3205 3207 9411 3207 3206 9412 3206 3058 9413 3058 3209 9414 3209 3206 9415 3206 3207 9416 3207 3209 9417 3209 3208 9418 3208 3206 9419 3206 3421 9420 3421 3208 9421 3208 3209 9422 3209 3421 9423 3421 3210 9424 3210 3208 9425 3208 3213 9426 3213 3211 9427 3211 2985 9428 2985 3211 9429 3211 3060 9430 3060 3212 9431 3212 3213 9432 3213 3060 9433 3060 3211 9434 3211 3215 9435 3215 3060 9436 3060 3213 9437 3213 3215 9438 3215 3214 9439 3214 3060 9440 3060 3217 9441 3217 3214 9442 3214 3215 9443 3215 3217 9444 3217 3216 9445 3216 3214 9446 3214 3423 9447 3423 3216 9448 3216 3217 9449 3217 3423 9450 3423 3218 9451 3218 3216 9452 3216 3221 9453 3221 3219 9454 3219 2987 9455 2987 3219 9456 3219 3062 9457 3062 3220 9458 3220 3221 9459 3221 3062 9460 3062 3219 9461 3219 3223 9462 3223 3062 9463 3062 3221 9464 3221 3223 9465 3223 3222 9466 3222 3062 9467 3062 3225 9468 3225 3222 9469 3222 3223 9470 3223 3225 9471 3225 3224 9472 3224 3222 9473 3222 3425 9474 3425 3224 9475 3224 3225 9476 3225 3425 9477 3425 3226 9478 3226 3224 9479 3224 3229 9480 3229 3227 9481 3227 2989 9482 2989 3227 9483 3227 3064 9484 3064 3228 9485 3228 3229 9486 3229 3064 9487 3064 3227 9488 3227 3231 9489 3231 3064 9490 3064 3229 9491 3229 3231 9492 3231 3230 9493 3230 3064 9494 3064 3233 9495 3233 3230 9496 3230 3231 9497 3231 3233 9498 3233 3232 9499 3232 3230 9500 3230 3427 9501 3427 3232 9502 3232 3233 9503 3233 3427 9504 3427 3234 9505 3234 3232 9506 3232 3237 9507 3237 3235 9508 3235 2991 9509 2991 3235 9510 3235 3066 9511 3066 3236 9512 3236 3237 9513 3237 3066 9514 3066 3235 9515 3235 3239 9516 3239 3066 9517 3066 3237 9518 3237 3239 9519 3239 3238 9520 3238 3066 9521 3066 3241 9522 3241 3238 9523 3238 3239 9524 3239 3241 9525 3241 3240 9526 3240 3238 9527 3238 3429 9528 3429 3240 9529 3240 3241 9530 3241 3429 9531 3429 3242 9532 3242 3240 9533 3240 3245 9534 3245 3243 9535 3243 2993 9536 2993 3243 9537 3243 3068 9538 3068 3244 9539 3244 3245 9540 3245 3068 9541 3068 3243 9542 3243 3247 9543 3247 3068 9544 3068 3245 9545 3245 3247 9546 3247 3246 9547 3246 3068 9548 3068 3249 9549 3249 3246 9550 3246 3247 9551 3247 3249 9552 3249 3248 9553 3248 3246 9554 3246 3431 9555 3431 3248 9556 3248 3249 9557 3249 3431 9558 3431 3250 9559 3250 3248 9560 3248 3253 9561 3253 3251 9562 3251 2995 9563 2995 3251 9564 3251 3072 9565 3072 3252 9566 3252 3253 9567 3253 3072 9568 3072 3251 9569 3251 3255 9570 3255 3072 9571 3072 3253 9572 3253 3255 9573 3255 3254 9574 3254 3072 9575 3072 3257 9576 3257 3254 9577 3254 3255 9578 3255 3257 9579 3257 3256 9580 3256 3254 9581 3254 3435 9582 3435 3256 9583 3256 3257 9584 3257 3435 9585 3435 3258 9586 3258 3256 9587 3256 3261 9588 3261 3259 9589 3259 2997 9590 2997 3259 9591 3259 3074 9592 3074 3260 9593 3260 3261 9594 3261 3074 9595 3074 3259 9596 3259 3263 9597 3263 3074 9598 3074 3261 9599 3261 3263 9600 3263 3262 9601 3262 3074 9602 3074 3265 9603 3265 3262 9604 3262 3263 9605 3263 3265 9606 3265 3264 9607 3264 3262 9608 3262 3437 9609 3437 3264 9610 3264 3265 9611 3265 3437 9612 3437 3266 9613 3266 3264 9614 3264 3269 9615 3269 3267 9616 3267 2999 9617 2999 3267 9618 3267 3076 9619 3076 3268 9620 3268 3269 9621 3269 3076 9622 3076 3267 9623 3267 3271 9624 3271 3076 9625 3076 3269 9626 3269 3271 9627 3271 3270 9628 3270 3076 9629 3076 3273 9630 3273 3270 9631 3270 3271 9632 3271 3273 9633 3273 3272 9634 3272 3270 9635 3270 3439 9636 3439 3272 9637 3272 3273 9638 3273 3439 9639 3439 3274 9640 3274 3272 9641 3272 3277 9642 3277 3275 9643 3275 3001 9644 3001 3275 9645 3275 3078 9646 3078 3276 9647 3276 3277 9648 3277 3078 9649 3078 3275 9650 3275 3279 9651 3279 3078 9652 3078 3277 9653 3277 3279 9654 3279 3278 9655 3278 3078 9656 3078 3281 9657 3281 3278 9658 3278 3279 9659 3279 3281 9660 3281 3280 9661 3280 3278 9662 3278 3441 9663 3441 3280 9664 3280 3281 9665 3281 3441 9666 3441 3282 9667 3282 3280 9668 3280 3285 9669 3285 3283 9670 3283 3003 9671 3003 3283 9672 3283 3080 9673 3080 3284 9674 3284 3285 9675 3285 3080 9676 3080 3283 9677 3283 3287 9678 3287 3080 9679 3080 3285 9680 3285 3287 9681 3287 3286 9682 3286 3080 9683 3080 3289 9684 3289 3286 9685 3286 3287 9686 3287 3289 9687 3289 3288 9688 3288 3286 9689 3286 3443 9690 3443 3288 9691 3288 3289 9692 3289 3443 9693 3443 3290 9694 3290 3288 9695 3288 3293 9696 3293 3291 9697 3291 3005 9698 3005 3291 9699 3291 3082 9700 3082 3292 9701 3292 3293 9702 3293 3082 9703 3082 3291 9704 3291 3295 9705 3295 3082 9706 3082 3293 9707 3293 3295 9708 3295 3294 9709 3294 3082 9710 3082 3297 9711 3297 3294 9712 3294 3295 9713 3295 3297 9714 3297 3296 9715 3296 3294 9716 3294 3445 9717 3445 3296 9718 3296 3297 9719 3297 3445 9720 3445 3298 9721 3298 3296 9722 3296 3301 9723 3301 3299 9724 3299 3007 9725 3007 3299 9726 3299 3084 9727 3084 3300 9728 3300 3301 9729 3301 3084 9730 3084 3299 9731 3299 3303 9732 3303 3084 9733 3084 3301 9734 3301 3303 9735 3303 3302 9736 3302 3084 9737 3084 3305 9738 3305 3302 9739 3302 3303 9740 3303 3305 9741 3305 3304 9742 3304 3302 9743 3302 3447 9744 3447 3304 9745 3304 3305 9746 3305 3447 9747 3447 3306 9748 3306 3304 9749 3304 3309 9750 3309 3307 9751 3307 3009 9752 3009 3307 9753 3307 3086 9754 3086 3308 9755 3308 3309 9756 3309 3086 9757 3086 3307 9758 3307 3311 9759 3311 3086 9760 3086 3309 9761 3309 3311 9762 3311 3310 9763 3310 3086 9764 3086 3313 9765 3313 3310 9766 3310 3311 9767 3311 3313 9768 3313 3312 9769 3312 3310 9770 3310 3449 9771 3449 3312 9772 3312 3313 9773 3313 3449 9774 3449 3314 9775 3314 3312 9776 3312 3317 9777 3317 3315 9778 3315 3011 9779 3011 3315 9780 3315 3088 9781 3088 3316 9782 3316 3317 9783 3317 3088 9784 3088 3315 9785 3315 3319 9786 3319 3088 9787 3088 3317 9788 3317 3319 9789 3319 3318 9790 3318 3088 9791 3088 3321 9792 3321 3318 9793 3318 3319 9794 3319 3321 9795 3321 3320 9796 3320 3318 9797 3318 3451 9798 3451 3320 9799 3320 3321 9800 3321 3451 9801 3451 3322 9802 3322 3320 9803 3320 3325 9804 3325 3323 9805 3323 3013 9806 3013 3323 9807 3323 3090 9808 3090 3324 9809 3324 3325 9810 3325 3090 9811 3090 3323 9812 3323 3327 9813 3327 3090 9814 3090 3325 9815 3325 3327 9816 3327 3326 9817 3326 3090 9818 3090 3329 9819 3329 3326 9820 3326 3327 9821 3327 3329 9822 3329 3328 9823 3328 3326 9824 3326 3453 9825 3453 3328 9826 3328 3329 9827 3329 3453 9828 3453 3330 9829 3330 3328 9830 3328 3333 9831 3333 3331 9832 3331 3015 9833 3015 3331 9834 3331 3092 9835 3092 3332 9836 3332 3333 9837 3333 3092 9838 3092 3331 9839 3331 3335 9840 3335 3092 9841 3092 3333 9842 3333 3335 9843 3335 3334 9844 3334 3092 9845 3092 3337 9846 3337 3334 9847 3334 3335 9848 3335 3337 9849 3337 3336 9850 3336 3334 9851 3334 3455 9852 3455 3336 9853 3336 3337 9854 3337 3455 9855 3455 3338 9856 3338 3336 9857 3336 3341 9858 3341 3339 9859 3339 3017 9860 3017 3339 9861 3339 3094 9862 3094 3340 9863 3340 3341 9864 3341 3094 9865 3094 3339 9866 3339 3343 9867 3343 3094 9868 3094 3341 9869 3341 3343 9870 3343 3342 9871 3342 3094 9872 3094 3345 9873 3345 3342 9874 3342 3343 9875 3343 3345 9876 3345 3344 9877 3344 3342 9878 3342 3457 9879 3457 3344 9880 3344 3345 9881 3345 3457 9882 3457 3346 9883 3346 3344 9884 3344 3349 9885 3349 3347 9886 3347 3019 9887 3019 3347 9888 3347 3096 9889 3096 3348 9890 3348 3349 9891 3349 3096 9892 3096 3347 9893 3347 3351 9894 3351 3096 9895 3096 3349 9896 3349 3351 9897 3351 3350 9898 3350 3096 9899 3096 3353 9900 3353 3350 9901 3350 3351 9902 3351 3353 9903 3353 3352 9904 3352 3350 9905 3350 3459 9906 3459 3352 9907 3352 3353 9908 3353 3459 9909 3459 3354 9910 3354 3352 9911 3352 3357 9912 3357 3355 9913 3355 3021 9914 3021 3355 9915 3355 3098 9916 3098 3356 9917 3356 3357 9918 3357 3098 9919 3098 3355 9920 3355 3359 9921 3359 3098 9922 3098 3357 9923 3357 3359 9924 3359 3358 9925 3358 3098 9926 3098 3361 9927 3361 3358 9928 3358 3359 9929 3359 3361 9930 3361 3360 9931 3360 3358 9932 3358 3461 9933 3461 3360 9934 3360 3361 9935 3361 3461 9936 3461 3362 9937 3362 3360 9938 3360 3365 9939 3365 3363 9940 3363 3023 9941 3023 3363 9942 3363 3100 9943 3100 3364 9944 3364 3365 9945 3365 3100 9946 3100 3363 9947 3363 3367 9948 3367 3100 9949 3100 3365 9950 3365 3367 9951 3367 3366 9952 3366 3100 9953 3100 3369 9954 3369 3366 9955 3366 3367 9956 3367 3369 9957 3369 3368 9958 3368 3366 9959 3366 3463 9960 3463 3368 9961 3368 3369 9962 3369 3463 9963 3463 3370 9964 3370 3368 9965 3368 3373 9966 3373 3371 9967 3371 3025 9968 3025 3371 9969 3371 3102 9970 3102 3372 9971 3372 3373 9972 3373 3102 9973 3102 3371 9974 3371 3375 9975 3375 3102 9976 3102 3373 9977 3373 3375 9978 3375 3374 9979 3374 3102 9980 3102 3377 9981 3377 3374 9982 3374 3375 9983 3375 3377 9984 3377 3376 9985 3376 3374 9986 3374 3465 9987 3465 3376 9988 3376 3377 9989 3377 3465 9990 3465 3378 9991 3378 3376 9992 3376 3381 9993 3381 3379 9994 3379 3027 9995 3027 3379 9996 3379 3104 9997 3104 3380 9998 3380 3381 9999 3381 3104 10000 3104 3379 10001 3379 3383 10002 3383 3104 10003 3104 3381 10004 3381 3383 10005 3383 3382 10006 3382 3104 10007 3104 3385 10008 3385 3382 10009 3382 3383 10010 3383 3385 10011 3385 3384 10012 3384 3382 10013 3382 3467 10014 3467 3384 10015 3384 3385 10016 3385 3467 10017 3467 3386 10018 3386 3384 10019 3384 3389 10020 3389 3387 10021 3387 3029 10022 3029 3387 10023 3387 3106 10024 3106 3388 10025 3388 3389 10026 3389 3106 10027 3106 3387 10028 3387 3391 10029 3391 3106 10030 3106 3389 10031 3389 3391 10032 3391 3390 10033 3390 3106 10034 3106 3393 10035 3393 3390 10036 3390 3391 10037 3391 3393 10038 3393 3392 10039 3392 3390 10040 3390 3469 10041 3469 3392 10042 3392 3393 10043 3393 3469 10044 3469 3394 10045 3394 3392 10046 3392 3471 10047 3471 1920 10048 1920 3395 10049 3395 3625 10050 3625 3396 10051 3396 3032 10052 3032 3473 10053 3473 3114 10054 3114 3397 10055 3397 3473 10056 3473 3398 10057 3398 3114 10058 3114 3475 10059 3475 3122 10060 3122 3399 10061 3399 3475 10062 3475 3400 10063 3400 3122 10064 3122 3477 10065 3477 3130 10066 3130 3401 10067 3401 3477 10068 3477 3402 10069 3402 3130 10070 3130 3479 10071 3479 3138 10072 3138 3403 10073 3403 3479 10074 3479 3404 10075 3404 3138 10076 3138 3481 10077 3481 3146 10078 3146 3405 10079 3405 3481 10080 3481 3406 10081 3406 3146 10082 3146 3483 10083 3483 3154 10084 3154 3407 10085 3407 3483 10086 3483 3408 10087 3408 3154 10088 3154 3485 10089 3485 3162 10090 3162 3409 10091 3409 3485 10092 3485 3410 10093 3410 3162 10094 3162 3487 10095 3487 3170 10096 3170 3411 10097 3411 3487 10098 3487 3412 10099 3412 3170 10100 3170 3489 10101 3489 3178 10102 3178 3413 10103 3413 3489 10104 3489 3414 10105 3414 3178 10106 3178 3491 10107 3491 3186 10108 3186 3415 10109 3415 3491 10110 3491 3416 10111 3416 3186 10112 3186 3493 10113 3493 3194 10114 3194 3417 10115 3417 3493 10116 3493 3418 10117 3418 3194 10118 3194 3495 10119 3495 3202 10120 3202 3419 10121 3419 3495 10122 3495 3420 10123 3420 3202 10124 3202 3497 10125 3497 3210 10126 3210 3421 10127 3421 3497 10128 3497 3422 10129 3422 3210 10130 3210 3499 10131 3499 3218 10132 3218 3423 10133 3423 3499 10134 3499 3424 10135 3424 3218 10136 3218 3501 10137 3501 3226 10138 3226 3425 10139 3425 3501 10140 3501 3426 10141 3426 3226 10142 3226 3503 10143 3503 3234 10144 3234 3427 10145 3427 3503 10146 3503 3428 10147 3428 3234 10148 3234 3505 10149 3505 3242 10150 3242 3429 10151 3429 3505 10152 3505 3430 10153 3430 3242 10154 3242 3507 10155 3507 3250 10156 3250 3431 10157 3431 3507 10158 3507 3432 10159 3432 3250 10160 3250 3509 10161 3509 3070 10162 3070 3433 10163 3433 3509 10164 3509 3434 10165 3434 3070 10166 3070 3511 10167 3511 3258 10168 3258 3435 10169 3435 3511 10170 3511 3436 10171 3436 3258 10172 3258 3513 10173 3513 3266 10174 3266 3437 10175 3437 3513 10176 3513 3438 10177 3438 3266 10178 3266 3515 10179 3515 3274 10180 3274 3439 10181 3439 3515 10182 3515 3440 10183 3440 3274 10184 3274 3517 10185 3517 3282 10186 3282 3441 10187 3441 3517 10188 3517 3442 10189 3442 3282 10190 3282 3519 10191 3519 3290 10192 3290 3443 10193 3443 3519 10194 3519 3444 10195 3444 3290 10196 3290 3521 10197 3521 3298 10198 3298 3445 10199 3445 3521 10200 3521 3446 10201 3446 3298 10202 3298 3523 10203 3523 3306 10204 3306 3447 10205 3447 3523 10206 3523 3448 10207 3448 3306 10208 3306 3525 10209 3525 3314 10210 3314 3449 10211 3449 3525 10212 3525 3450 10213 3450 3314 10214 3314 3527 10215 3527 3322 10216 3322 3451 10217 3451 3527 10218 3527 3452 10219 3452 3322 10220 3322 3529 10221 3529 3330 10222 3330 3453 10223 3453 3529 10224 3529 3454 10225 3454 3330 10226 3330 3531 10227 3531 3338 10228 3338 3455 10229 3455 3531 10230 3531 3456 10231 3456 3338 10232 3338 3533 10233 3533 3346 10234 3346 3457 10235 3457 3533 10236 3533 3458 10237 3458 3346 10238 3346 3535 10239 3535 3354 10240 3354 3459 10241 3459 3535 10242 3535 3460 10243 3460 3354 10244 3354 3537 10245 3537 3362 10246 3362 3461 10247 3461 3537 10248 3537 3462 10249 3462 3362 10250 3362 3539 10251 3539 3370 10252 3370 3463 10253 3463 3539 10254 3539 3464 10255 3464 3370 10256 3370 3541 10257 3541 3378 10258 3378 3465 10259 3465 3541 10260 3541 3466 10261 3466 3378 10262 3378 3543 10263 3543 3386 10264 3386 3467 10265 3467 3543 10266 3543 3468 10267 3468 3386 10268 3386 3545 10269 3545 3394 10270 3394 3469 10271 3469 3545 10272 3545 3470 10273 3470 3394 10274 3394 3621 10275 3621 1920 10276 1920 3471 10277 3471 3625 10278 3625 3472 10279 3472 3396 10280 3396 3547 10281 3547 3398 10282 3398 3473 10283 3473 3547 10284 3547 3474 10285 3474 3398 10286 3398 3548 10287 3548 3400 10288 3400 3475 10289 3475 3548 10290 3548 3476 10291 3476 3400 10292 3400 3549 10293 3549 3402 10294 3402 3477 10295 3477 3549 10296 3549 3478 10297 3478 3402 10298 3402 3550 10299 3550 3404 10300 3404 3479 10301 3479 3550 10302 3550 3480 10303 3480 3404 10304 3404 3551 10305 3551 3406 10306 3406 3481 10307 3481 3551 10308 3551 3482 10309 3482 3406 10310 3406 3557 10311 3557 3408 10312 3408 3483 10313 3483 3557 10314 3557 3484 10315 3484 3408 10316 3408 3558 10317 3558 3410 10318 3410 3485 10319 3485 3558 10320 3558 3486 10321 3486 3410 10322 3410 3559 10323 3559 3412 10324 3412 3487 10325 3487 3559 10326 3559 3488 10327 3488 3412 10328 3412 3563 10329 3563 3414 10330 3414 3489 10331 3489 3563 10332 3563 3490 10333 3490 3414 10334 3414 3564 10335 3564 3416 10336 3416 3491 10337 3491 3564 10338 3564 3492 10339 3492 3416 10340 3416 3565 10341 3565 3418 10342 3418 3493 10343 3493 3565 10344 3565 3494 10345 3494 3418 10346 3418 3566 10347 3566 3420 10348 3420 3495 10349 3495 3566 10350 3566 3496 10351 3496 3420 10352 3420 3571 10353 3571 3422 10354 3422 3497 10355 3497 3571 10356 3571 3498 10357 3498 3422 10358 3422 3572 10359 3572 3424 10360 3424 3499 10361 3499 3572 10362 3572 3500 10363 3500 3424 10364 3424 3573 10365 3573 3426 10366 3426 3501 10367 3501 3573 10368 3573 3502 10369 3502 3426 10370 3426 3577 10371 3577 3428 10372 3428 3503 10373 3503 3577 10374 3577 3504 10375 3504 3428 10376 3428 3578 10377 3578 3430 10378 3430 3505 10379 3505 3578 10380 3578 3506 10381 3506 3430 10382 3430 3579 10383 3579 3432 10384 3432 3507 10385 3507 3579 10386 3579 3508 10387 3508 3432 10388 3432 3580 10389 3580 3434 10390 3434 3509 10391 3509 3580 10392 3580 3510 10393 3510 3434 10394 3434 3585 10395 3585 3436 10396 3436 3511 10397 3511 3585 10398 3585 3512 10399 3512 3436 10400 3436 3586 10401 3586 3438 10402 3438 3513 10403 3513 3586 10404 3586 3514 10405 3514 3438 10406 3438 3587 10407 3587 3440 10408 3440 3515 10409 3515 3587 10410 3587 3516 10411 3516 3440 10412 3440 3591 10413 3591 3442 10414 3442 3517 10415 3517 3591 10416 3591 3518 10417 3518 3442 10418 3442 3592 10419 3592 3444 10420 3444 3519 10421 3519 3592 10422 3592 3520 10423 3520 3444 10424 3444 3593 10425 3593 3446 10426 3446 3521 10427 3521 3593 10428 3593 3522 10429 3522 3446 10430 3446 3594 10431 3594 3448 10432 3448 3523 10433 3523 3594 10434 3594 3524 10435 3524 3448 10436 3448 3599 10437 3599 3450 10438 3450 3525 10439 3525 3599 10440 3599 3526 10441 3526 3450 10442 3450 3600 10443 3600 3452 10444 3452 3527 10445 3527 3600 10446 3600 3528 10447 3528 3452 10448 3452 3601 10449 3601 3454 10450 3454 3529 10451 3529 3601 10452 3601 3530 10453 3530 3454 10454 3454 3605 10455 3605 3456 10456 3456 3531 10457 3531 3605 10458 3605 3532 10459 3532 3456 10460 3456 3606 10461 3606 3458 10462 3458 3533 10463 3533 3606 10464 3606 3534 10465 3534 3458 10466 3458 3607 10467 3607 3460 10468 3460 3535 10469 3535 3607 10470 3607 3536 10471 3536 3460 10472 3460 3608 10473 3608 3462 10474 3462 3537 10475 3537 3608 10476 3608 3538 10477 3538 3462 10478 3462 3613 10479 3613 3464 10480 3464 3539 10481 3539 3613 10482 3613 3540 10483 3540 3464 10484 3464 3614 10485 3614 3466 10486 3466 3541 10487 3541 3614 10488 3614 3542 10489 3542 3466 10490 3466 3615 10491 3615 3468 10492 3468 3543 10493 3543 3615 10494 3615 3544 10495 3544 3468 10496 3468 3619 10497 3619 3470 10498 3470 3545 10499 3545 3619 10500 3619 3546 10501 3546 3470 10502 3470 3626 10503 3626 3474 10504 3474 3547 10505 3547 3628 10506 3628 3476 10507 3476 3548 10508 3548 3630 10509 3630 3478 10510 3478 3549 10511 3549 3632 10512 3632 3480 10513 3480 3550 10514 3550 3634 10515 3634 3482 10516 3482 3551 10517 3551 3626 10518 3626 3552 10519 3552 3474 10520 3474 3628 10521 3628 3553 10522 3553 3476 10523 3476 3630 10524 3630 3554 10525 3554 3478 10526 3478 3632 10527 3632 3555 10528 3555 3480 10529 3480 3634 10530 3634 3556 10531 3556 3482 10532 3482 3636 10533 3636 3484 10534 3484 3557 10535 3557 3638 10536 3638 3486 10537 3486 3558 10538 3558 3640 10539 3640 3488 10540 3488 3559 10541 3559 3636 10542 3636 3560 10543 3560 3484 10544 3484 3638 10545 3638 3561 10546 3561 3486 10547 3486 3640 10548 3640 3562 10549 3562 3488 10550 3488 3642 10551 3642 3490 10552 3490 3563 10553 3563 3644 10554 3644 3492 10555 3492 3564 10556 3564 3646 10557 3646 3494 10558 3494 3565 10559 3565 3648 10560 3648 3496 10561 3496 3566 10562 3566 3642 10563 3642 3567 10564 3567 3490 10565 3490 3644 10566 3644 3568 10567 3568 3492 10568 3492 3646 10569 3646 3569 10570 3569 3494 10571 3494 3648 10572 3648 3570 10573 3570 3496 10574 3496 3650 10575 3650 3498 10576 3498 3571 10577 3571 3652 10578 3652 3500 10579 3500 3572 10580 3572 3654 10581 3654 3502 10582 3502 3573 10583 3573 3650 10584 3650 3574 10585 3574 3498 10586 3498 3652 10587 3652 3575 10588 3575 3500 10589 3500 3654 10590 3654 3576 10591 3576 3502 10592 3502 3656 10593 3656 3504 10594 3504 3577 10595 3577 3658 10596 3658 3506 10597 3506 3578 10598 3578 3660 10599 3660 3508 10600 3508 3579 10601 3579 3671 10602 3671 3510 10603 3510 3580 10604 3580 3656 10605 3656 3581 10606 3581 3504 10607 3504 3658 10608 3658 3582 10609 3582 3506 10610 3506 3660 10611 3660 3583 10612 3583 3508 10613 3508 3671 10614 3671 3584 10615 3584 3510 10616 3510 3681 10617 3681 3512 10618 3512 3585 10619 3585 3683 10620 3683 3514 10621 3514 3586 10622 3586 3685 10623 3685 3516 10624 3516 3587 10625 3587 3681 10626 3681 3588 10627 3588 3512 10628 3512 3683 10629 3683 3589 10630 3589 3514 10631 3514 3685 10632 3685 3590 10633 3590 3516 10634 3516 3686 10635 3686 3518 10636 3518 3591 10637 3591 3687 10638 3687 3520 10639 3520 3592 10640 3592 3688 10641 3688 3522 10642 3522 3593 10643 3593 3689 10644 3689 3524 10645 3524 3594 10646 3594 3686 10647 3686 3595 10648 3595 3518 10649 3518 3687 10650 3687 3596 10651 3596 3520 10652 3520 3688 10653 3688 3597 10654 3597 3522 10655 3522 3689 10656 3689 3598 10657 3598 3524 10658 3524 3695 10659 3695 3526 10660 3526 3599 10661 3599 3696 10662 3696 3528 10663 3528 3600 10664 3600 3697 10665 3697 3530 10666 3530 3601 10667 3601 3695 10668 3695 3602 10669 3602 3526 10670 3526 3696 10671 3696 3603 10672 3603 3528 10673 3528 3697 10674 3697 3604 10675 3604 3530 10676 3530 3701 10677 3701 3532 10678 3532 3605 10679 3605 3702 10680 3702 3534 10681 3534 3606 10682 3606 3703 10683 3703 3536 10684 3536 3607 10685 3607 3704 10686 3704 3538 10687 3538 3608 10688 3608 3701 10689 3701 3609 10690 3609 3532 10691 3532 3702 10692 3702 3610 10693 3610 3534 10694 3534 3703 10695 3703 3611 10696 3611 3536 10697 3536 3704 10698 3704 3612 10699 3612 3538 10700 3538 3709 10701 3709 3540 10702 3540 3613 10703 3613 3710 10704 3710 3542 10705 3542 3614 10706 3614 3711 10707 3711 3544 10708 3544 3615 10709 3615 3709 10710 3709 3616 10711 3616 3540 10712 3540 3710 10713 3710 3617 10714 3617 3542 10715 3542 3711 10716 3711 3618 10717 3618 3544 10718 3544 3715 10719 3715 3546 10720 3546 3619 10721 3619 3715 10722 3715 3620 10723 3620 3546 10724 3546 3623 10725 3623 1920 10726 1920 3621 10727 3621 3623 10728 3623 3622 10729 3622 1920 10730 1920 3620 10731 3620 3622 10732 3622 3623 10733 3623 3625 10734 3625 3624 10735 3624 3472 10736 3472 3667 10737 3667 3624 10738 3624 3625 10739 3625 3667 10740 3667 3626 10741 3626 3624 10742 3624 3626 10743 3626 3627 10744 3627 3552 10745 3552 3667 10746 3667 3627 10747 3627 3626 10748 3626 3667 10749 3667 3628 10750 3628 3627 10751 3627 3628 10752 3628 3629 10753 3629 3553 10754 3553 3667 10755 3667 3629 10756 3629 3628 10757 3628 3667 10758 3667 3630 10759 3630 3629 10760 3629 3630 10761 3630 3631 10762 3631 3554 10763 3554 3667 10764 3667 3631 10765 3631 3630 10766 3630 3667 10767 3667 3632 10768 3632 3631 10769 3631 3632 10770 3632 3633 10771 3633 3555 10772 3555 3667 10773 3667 3633 10774 3633 3632 10775 3632 3667 10776 3667 3634 10777 3634 3633 10778 3633 3634 10779 3634 3635 10780 3635 3556 10781 3556 3667 10782 3667 3635 10783 3635 3634 10784 3634 3667 10785 3667 3636 10786 3636 3635 10787 3635 3636 10788 3636 3637 10789 3637 3560 10790 3560 3667 10791 3667 3637 10792 3637 3636 10793 3636 3667 10794 3667 3638 10795 3638 3637 10796 3637 3638 10797 3638 3639 10798 3639 3561 10799 3561 3667 10800 3667 3639 10801 3639 3638 10802 3638 3667 10803 3667 3640 10804 3640 3639 10805 3639 3640 10806 3640 3641 10807 3641 3562 10808 3562 3667 10809 3667 3641 10810 3641 3640 10811 3640 3667 10812 3667 3642 10813 3642 3641 10814 3641 3642 10815 3642 3643 10816 3643 3567 10817 3567 3667 10818 3667 3643 10819 3643 3642 10820 3642 3667 10821 3667 3644 10822 3644 3643 10823 3643 3644 10824 3644 3645 10825 3645 3568 10826 3568 3667 10827 3667 3645 10828 3645 3644 10829 3644 3667 10830 3667 3646 10831 3646 3645 10832 3645 3646 10833 3646 3647 10834 3647 3569 10835 3569 3667 10836 3667 3647 10837 3647 3646 10838 3646 3667 10839 3667 3648 10840 3648 3647 10841 3647 3648 10842 3648 3649 10843 3649 3570 10844 3570 3667 10845 3667 3649 10846 3649 3648 10847 3648 3667 10848 3667 3650 10849 3650 3649 10850 3649 3650 10851 3650 3651 10852 3651 3574 10853 3574 3667 10854 3667 3651 10855 3651 3650 10856 3650 3667 10857 3667 3652 10858 3652 3651 10859 3651 3652 10860 3652 3653 10861 3653 3575 10862 3575 3667 10863 3667 3653 10864 3653 3652 10865 3652 3667 10866 3667 3654 10867 3654 3653 10868 3653 3654 10869 3654 3655 10870 3655 3576 10871 3576 3667 10872 3667 3655 10873 3655 3654 10874 3654 3667 10875 3667 3656 10876 3656 3655 10877 3655 3656 10878 3656 3657 10879 3657 3581 10880 3581 3667 10881 3667 3657 10882 3657 3656 10883 3656 3667 10884 3667 3658 10885 3658 3657 10886 3657 3658 10887 3658 3659 10888 3659 3582 10889 3582 3667 10890 3667 3659 10891 3659 3658 10892 3658 3667 10893 3667 3660 10894 3660 3659 10895 3659 3667 10896 3667 3583 10897 3583 3660 10898 3660 3667 10899 3667 3661 10900 3661 3583 10901 3583 3667 10902 3667 3662 10903 3662 3661 10904 3661 3667 10905 3667 3663 10906 3663 3662 10907 3662 3667 10908 3667 3664 10909 3664 3663 10910 3663 3667 10911 3667 3665 10912 3665 3664 10913 3664 3667 10914 3667 3666 10915 3666 3665 10916 3665 3622 10917 3622 3666 10918 3666 3667 10919 3667 3622 10920 3622 3668 10921 3668 3666 10922 3666 3622 10923 3622 3669 10924 3669 3668 10925 3668 3622 10926 3622 3670 10927 3670 3669 10928 3669 3622 10929 3622 3671 10930 3671 3670 10931 3670 3622 10932 3622 3584 10933 3584 3671 10934 3671 3622 10935 3622 3672 10936 3672 3584 10937 3584 3622 10938 3622 3673 10939 3673 3672 10940 3672 3622 10941 3622 3674 10942 3674 3673 10943 3673 3622 10944 3622 3675 10945 3675 3674 10946 3674 3622 10947 3622 3676 10948 3676 3675 10949 3675 3622 10950 3622 3677 10951 3677 3676 10952 3676 3622 10953 3622 3678 10954 3678 3677 10955 3677 3622 10956 3622 3679 10957 3679 3678 10958 3678 3622 10959 3622 3680 10960 3680 3679 10961 3679 3680 10962 3680 3588 10963 3588 3681 10964 3681 3622 10965 3622 3588 10966 3588 3680 10967 3680 3622 10968 3622 3682 10969 3682 3588 10970 3588 3682 10971 3682 3589 10972 3589 3683 10973 3683 3682 10974 3682 3684 10975 3684 3589 10976 3589 3684 10977 3684 3590 10978 3590 3685 10979 3685 3690 10980 3690 3595 10981 3595 3686 10982 3686 3691 10983 3691 3596 10984 3596 3687 10985 3687 3692 10986 3692 3597 10987 3597 3688 10988 3688 3693 10989 3693 3598 10990 3598 3689 10991 3689 3684 10992 3684 3690 10993 3690 3590 10994 3590 3690 10995 3690 3691 10996 3691 3595 10997 3595 3691 10998 3691 3692 10999 3692 3596 11000 3596 3692 11001 3692 3693 11002 3693 3597 11003 3597 3693 11004 3693 3694 11005 3694 3598 11006 3598 3694 11007 3694 3602 11008 3602 3695 11009 3695 3698 11010 3698 3603 11011 3603 3696 11012 3696 3699 11013 3699 3604 11014 3604 3697 11015 3697 3694 11016 3694 3698 11017 3698 3602 11018 3602 3698 11019 3698 3699 11020 3699 3603 11021 3603 3699 11022 3699 3700 11023 3700 3604 11024 3604 3700 11025 3700 3609 11026 3609 3701 11027 3701 3705 11028 3705 3610 11029 3610 3702 11030 3702 3706 11031 3706 3611 11032 3611 3703 11033 3703 3707 11034 3707 3612 11035 3612 3704 11036 3704 3700 11037 3700 3705 11038 3705 3609 11039 3609 3705 11040 3705 3706 11041 3706 3610 11042 3610 3706 11043 3706 3707 11044 3707 3611 11045 3611 3707 11046 3707 3708 11047 3708 3612 11048 3612 3708 11049 3708 3616 11050 3616 3709 11051 3709 3712 11052 3712 3617 11053 3617 3710 11054 3710 3713 11055 3713 3618 11056 3618 3711 11057 3711 3708 11058 3708 3712 11059 3712 3616 11060 3616 3712 11061 3712 3713 11062 3713 3617 11063 3617 3713 11064 3713 3714 11065 3714 3618 11066 3618 3714 11067 3714 3620 11068 3620 3715 11069 3715 3714 11070 3714 3622 11071 3622 3620 11072 3620 3713 11073 3713 3622 11074 3622 3714 11075 3714 3712 11076 3712 3622 11077 3622 3713 11078 3713 3708 11079 3708 3622 11080 3622 3712 11081 3712 3707 11082 3707 3622 11083 3622 3708 11084 3708 3706 11085 3706 3622 11086 3622 3707 11087 3707 3705 11088 3705 3622 11089 3622 3706 11090 3706 3700 11091 3700 3622 11092 3622 3705 11093 3705 3699 11094 3699 3622 11095 3622 3700 11096 3700 3698 11097 3698 3622 11098 3622 3699 11099 3699 3694 11100 3694 3622 11101 3622 3698 11102 3698 3693 11103 3693 3622 11104 3622 3694 11105 3694 3692 11106 3692 3622 11107 3622 3693 11108 3693 3691 11109 3691 3622 11110 3622 3692 11111 3692 3690 11112 3690 3622 11113 3622 3691 11114 3691 3684 11115 3684 3622 11116 3622 3690 11117 3690 5418 11118 5418 5480 11119 5480 5478 11120 5478 5421 11121 5421 3944 11122 3944 3716 11123 3716 5421 11124 5421 3717 11125 3717 3944 11126 3944 5421 11127 5421 3718 11128 3718 3717 11129 3717 5421 11130 5421 3719 11131 3719 3718 11132 3718 5421 11133 5421 3720 11134 3720 3719 11135 3719 5421 11136 5421 3721 11137 3721 3720 11138 3720 5421 11139 5421 3722 11140 3722 3721 11141 3721 3945 11142 3945 3832 11143 3832 3723 11144 3723 3835 11145 3835 3724 11146 3724 3836 11147 3836 3836 11148 3836 3725 11149 3725 3835 11150 3835 3948 11151 3948 3727 11152 3727 3726 11153 3726 3949 11154 3949 3726 11155 3726 3727 11156 3727 3839 11157 3839 3728 11158 3728 3942 11159 3942 3951 11160 3951 3830 11161 3830 3729 11162 3729 3841 11163 3841 3730 11164 3730 3940 11165 3940 3953 11166 3953 3828 11167 3828 3731 11168 3731 3843 11169 3843 3732 11170 3732 3844 11171 3844 3844 11172 3844 3733 11173 3733 3843 11174 3843 3845 11175 3845 3734 11176 3734 3938 11177 3938 3957 11178 3957 3826 11179 3826 3735 11180 3735 3847 11181 3847 3736 11182 3736 3848 11183 3848 3848 11184 3848 3737 11185 3737 3847 11186 3847 3849 11187 3849 3738 11188 3738 3936 11189 3936 3961 11190 3961 3824 11191 3824 3739 11192 3739 3851 11193 3851 3740 11194 3740 3852 11195 3852 3852 11196 3852 3741 11197 3741 3851 11198 3851 3853 11199 3853 3742 11200 3742 3934 11201 3934 3965 11202 3965 3822 11203 3822 3743 11204 3743 3855 11205 3855 3744 11206 3744 3856 11207 3856 3856 11208 3856 3745 11209 3745 3855 11210 3855 3857 11211 3857 3746 11212 3746 3932 11213 3932 3969 11214 3969 3820 11215 3820 3747 11216 3747 3859 11217 3859 3748 11218 3748 3860 11219 3860 3860 11220 3860 3749 11221 3749 3859 11222 3859 3972 11223 3972 3751 11224 3751 3750 11225 3750 3973 11226 3973 3750 11227 3750 3751 11228 3751 3863 11229 3863 3752 11230 3752 3930 11231 3930 3975 11232 3975 3818 11233 3818 3753 11234 3753 3976 11235 3976 3817 11236 3817 3754 11237 3754 3866 11238 3866 3755 11239 3755 3927 11240 3927 3978 11241 3978 3811 11242 3811 3756 11243 3756 3868 11244 3868 3757 11245 3757 3921 11246 3921 3980 11247 3980 3759 11248 3759 3758 11249 3758 3981 11250 3981 3758 11251 3758 3759 11252 3759 3871 11253 3871 3760 11254 3760 3920 11255 3920 3983 11256 3983 3808 11257 3808 3761 11258 3761 3984 11259 3984 3805 11260 3805 3762 11261 3762 3874 11262 3874 3763 11263 3763 3915 11264 3915 3986 11265 3986 3803 11266 3803 3764 11267 3764 3876 11268 3876 3765 11269 3765 3913 11270 3913 3877 11271 3877 3766 11272 3766 3910 11273 3910 3989 11274 3989 3798 11275 3798 3767 11276 3767 3879 11277 3879 3768 11278 3768 3880 11279 3880 3880 11280 3880 3769 11281 3769 3879 11282 3879 3992 11283 3992 3771 11284 3771 3770 11285 3770 3993 11286 3993 3770 11287 3770 3771 11288 3771 3883 11289 3883 3772 11290 3772 3908 11291 3908 3995 11292 3995 3796 11293 3796 3773 11294 3773 3885 11295 3885 3774 11296 3774 3906 11297 3906 3997 11298 3997 3794 11299 3794 3775 11300 3775 3887 11301 3887 3776 11302 3776 3888 11303 3888 3888 11304 3888 3777 11305 3777 3887 11306 3887 3889 11307 3889 3778 11308 3778 3904 11309 3904 4001 11310 4001 3792 11311 3792 3779 11312 3779 3891 11313 3891 3780 11314 3780 3892 11315 3892 3892 11316 3892 3781 11317 3781 3891 11318 3891 3893 11319 3893 3782 11320 3782 3902 11321 3902 4005 11322 4005 3790 11323 3790 3783 11324 3783 3895 11325 3895 3784 11326 3784 3896 11327 3896 3896 11328 3896 3785 11329 3785 3895 11330 3895 4008 11331 4008 3787 11332 3787 3786 11333 3786 4009 11334 4009 3786 11335 3786 3787 11336 3787 3899 11337 3899 3788 11338 3788 3900 11339 3900 3900 11340 3900 3789 11341 3789 3899 11342 3899 4012 11343 4012 3783 11344 3783 3790 11345 3790 3902 11346 3902 3791 11347 3791 3893 11348 3893 4014 11349 4014 3779 11350 3779 3792 11351 3792 3904 11352 3904 3793 11353 3793 3889 11354 3889 4016 11355 4016 3775 11356 3775 3794 11357 3794 3906 11358 3906 3795 11359 3795 3885 11360 3885 4018 11361 4018 3773 11362 3773 3796 11363 3796 3908 11364 3908 3797 11365 3797 3883 11366 3883 4020 11367 4020 3767 11368 3767 3798 11369 3798 3910 11370 3910 3799 11371 3799 3877 11372 3877 4022 11373 4022 3801 11374 3801 3800 11375 3800 4023 11376 4023 3800 11377 3800 3801 11378 3801 3913 11379 3913 3802 11380 3802 3876 11381 3876 4025 11382 4025 3764 11383 3764 3803 11384 3803 3915 11385 3915 3804 11386 3804 3874 11387 3874 4027 11388 4027 3762 11389 3762 3805 11390 3805 3917 11391 3917 3806 11392 3806 3918 11393 3918 3918 11394 3918 3807 11395 3807 3917 11396 3917 4030 11397 4030 3761 11398 3761 3808 11399 3808 3920 11400 3920 3809 11401 3809 3871 11402 3871 3921 11403 3921 3810 11404 3810 3868 11405 3868 4033 11406 4033 3756 11407 3756 3811 11408 3811 3923 11409 3923 3812 11410 3812 3924 11411 3924 3924 11412 3924 3813 11413 3813 3923 11414 3923 4036 11415 4036 3815 11416 3815 3814 11417 3814 4037 11418 4037 3814 11419 3814 3815 11420 3815 3927 11421 3927 3816 11422 3816 3866 11423 3866 4039 11424 4039 3754 11425 3754 3817 11426 3817 4040 11427 4040 3753 11428 3753 3818 11429 3818 3930 11430 3930 3819 11431 3819 3863 11432 3863 4042 11433 4042 3747 11434 3747 3820 11435 3820 3932 11436 3932 3821 11437 3821 3857 11438 3857 4044 11439 4044 3743 11440 3743 3822 11441 3822 3934 11442 3934 3823 11443 3823 3853 11444 3853 4046 11445 4046 3739 11446 3739 3824 11447 3824 3936 11448 3936 3825 11449 3825 3849 11450 3849 4048 11451 4048 3735 11452 3735 3826 11453 3826 3938 11454 3938 3827 11455 3827 3845 11456 3845 4050 11457 4050 3731 11458 3731 3828 11459 3828 3940 11460 3940 3829 11461 3829 3841 11462 3841 4052 11463 4052 3729 11464 3729 3830 11465 3830 3942 11466 3942 3831 11467 3831 3839 11468 3839 4054 11469 4054 3723 11470 3723 3832 11471 3832 5421 11472 5421 3833 11473 3833 3722 11474 3722 3945 11475 3945 3834 11476 3834 3832 11477 3832 4057 11478 4057 3724 11479 3724 3835 11480 3835 4058 11481 4058 3725 11482 3725 3836 11483 3836 3948 11484 3948 3837 11485 3837 3727 11486 3727 3949 11487 3949 3838 11488 3838 3726 11489 3726 4061 11490 4061 3728 11491 3728 3839 11492 3839 3951 11493 3951 3840 11494 3840 3830 11495 3830 4063 11496 4063 3730 11497 3730 3841 11498 3841 3953 11499 3953 3842 11500 3842 3828 11501 3828 4065 11502 4065 3732 11503 3732 3843 11504 3843 4066 11505 4066 3733 11506 3733 3844 11507 3844 4067 11508 4067 3734 11509 3734 3845 11510 3845 3957 11511 3957 3846 11512 3846 3826 11513 3826 4069 11514 4069 3736 11515 3736 3847 11516 3847 4070 11517 4070 3737 11518 3737 3848 11519 3848 4071 11520 4071 3738 11521 3738 3849 11522 3849 3961 11523 3961 3850 11524 3850 3824 11525 3824 4073 11526 4073 3740 11527 3740 3851 11528 3851 4074 11529 4074 3741 11530 3741 3852 11531 3852 4075 11532 4075 3742 11533 3742 3853 11534 3853 3965 11535 3965 3854 11536 3854 3822 11537 3822 4077 11538 4077 3744 11539 3744 3855 11540 3855 4078 11541 4078 3745 11542 3745 3856 11543 3856 4079 11544 4079 3746 11545 3746 3857 11546 3857 3969 11547 3969 3858 11548 3858 3820 11549 3820 4081 11550 4081 3748 11551 3748 3859 11552 3859 4082 11553 4082 3749 11554 3749 3860 11555 3860 3972 11556 3972 3861 11557 3861 3751 11558 3751 3973 11559 3973 3862 11560 3862 3750 11561 3750 4085 11562 4085 3752 11563 3752 3863 11564 3863 3975 11565 3975 3864 11566 3864 3818 11567 3818 3976 11568 3976 3865 11569 3865 3817 11570 3817 4088 11571 4088 3755 11572 3755 3866 11573 3866 3978 11574 3978 3867 11575 3867 3811 11576 3811 4090 11577 4090 3757 11578 3757 3868 11579 3868 3980 11580 3980 3869 11581 3869 3759 11582 3759 3981 11583 3981 3870 11584 3870 3758 11585 3758 4093 11586 4093 3760 11587 3760 3871 11588 3871 3983 11589 3983 3872 11590 3872 3808 11591 3808 3984 11592 3984 3873 11593 3873 3805 11594 3805 4096 11595 4096 3763 11596 3763 3874 11597 3874 3986 11598 3986 3875 11599 3875 3803 11600 3803 4098 11601 4098 3765 11602 3765 3876 11603 3876 4099 11604 4099 3766 11605 3766 3877 11606 3877 3989 11607 3989 3878 11608 3878 3798 11609 3798 4101 11610 4101 3768 11611 3768 3879 11612 3879 4102 11613 4102 3769 11614 3769 3880 11615 3880 3992 11616 3992 3881 11617 3881 3771 11618 3771 3993 11619 3993 3882 11620 3882 3770 11621 3770 4105 11622 4105 3772 11623 3772 3883 11624 3883 3995 11625 3995 3884 11626 3884 3796 11627 3796 4107 11628 4107 3774 11629 3774 3885 11630 3885 3997 11631 3997 3886 11632 3886 3794 11633 3794 4109 11634 4109 3776 11635 3776 3887 11636 3887 4110 11637 4110 3777 11638 3777 3888 11639 3888 4111 11640 4111 3778 11641 3778 3889 11642 3889 4001 11643 4001 3890 11644 3890 3792 11645 3792 4113 11646 4113 3780 11647 3780 3891 11648 3891 4114 11649 4114 3781 11650 3781 3892 11651 3892 4115 11652 4115 3782 11653 3782 3893 11654 3893 4005 11655 4005 3894 11656 3894 3790 11657 3790 4117 11658 4117 3784 11659 3784 3895 11660 3895 4118 11661 4118 3785 11662 3785 3896 11663 3896 4008 11664 4008 3897 11665 3897 3787 11666 3787 4009 11667 4009 3898 11668 3898 3786 11669 3786 4121 11670 4121 3788 11671 3788 3899 11672 3899 4122 11673 4122 3789 11674 3789 3900 11675 3900 4012 11676 4012 3901 11677 3901 3783 11678 3783 4124 11679 4124 3791 11680 3791 3902 11681 3902 4014 11682 4014 3903 11683 3903 3779 11684 3779 4126 11685 4126 3793 11686 3793 3904 11687 3904 4016 11688 4016 3905 11689 3905 3775 11690 3775 4128 11691 4128 3795 11692 3795 3906 11693 3906 4018 11694 4018 3907 11695 3907 3773 11696 3773 4130 11697 4130 3797 11698 3797 3908 11699 3908 4020 11700 4020 3909 11701 3909 3767 11702 3767 4132 11703 4132 3799 11704 3799 3910 11705 3910 4022 11706 4022 3911 11707 3911 3801 11708 3801 4023 11709 4023 3912 11710 3912 3800 11711 3800 4135 11712 4135 3802 11713 3802 3913 11714 3913 4025 11715 4025 3914 11716 3914 3764 11717 3764 4137 11718 4137 3804 11719 3804 3915 11720 3915 4027 11721 4027 3916 11722 3916 3762 11723 3762 4139 11724 4139 3806 11725 3806 3917 11726 3917 4140 11727 4140 3807 11728 3807 3918 11729 3918 4030 11730 4030 3919 11731 3919 3761 11732 3761 4142 11733 4142 3809 11734 3809 3920 11735 3920 4143 11736 4143 3810 11737 3810 3921 11738 3921 4033 11739 4033 3922 11740 3922 3756 11741 3756 4145 11742 4145 3812 11743 3812 3923 11744 3923 4146 11745 4146 3813 11746 3813 3924 11747 3924 4036 11748 4036 3925 11749 3925 3815 11750 3815 4037 11751 4037 3926 11752 3926 3814 11753 3814 4149 11754 4149 3816 11755 3816 3927 11756 3927 4039 11757 4039 3928 11758 3928 3754 11759 3754 4040 11760 4040 3929 11761 3929 3753 11762 3753 4152 11763 4152 3819 11764 3819 3930 11765 3930 4042 11766 4042 3931 11767 3931 3747 11768 3747 4154 11769 4154 3821 11770 3821 3932 11771 3932 4044 11772 4044 3933 11773 3933 3743 11774 3743 4156 11775 4156 3823 11776 3823 3934 11777 3934 4046 11778 4046 3935 11779 3935 3739 11780 3739 4158 11781 4158 3825 11782 3825 3936 11783 3936 4048 11784 4048 3937 11785 3937 3735 11786 3735 4160 11787 4160 3827 11788 3827 3938 11789 3938 4050 11790 4050 3939 11791 3939 3731 11792 3731 4162 11793 4162 3829 11794 3829 3940 11795 3940 4052 11796 4052 3941 11797 3941 3729 11798 3729 4164 11799 4164 3831 11800 3831 3942 11801 3942 4054 11802 4054 3943 11803 3943 3723 11804 3723 4166 11805 4166 3716 11806 3716 3944 11807 3944 4167 11808 4167 3834 11809 3834 3945 11810 3945 4057 11811 4057 3946 11812 3946 3724 11813 3724 4058 11814 4058 3947 11815 3947 3725 11816 3725 4170 11817 4170 3837 11818 3837 3948 11819 3948 4171 11820 4171 3838 11821 3838 3949 11822 3949 4061 11823 4061 3950 11824 3950 3728 11825 3728 4173 11826 4173 3840 11827 3840 3951 11828 3951 4063 11829 4063 3952 11830 3952 3730 11831 3730 4175 11832 4175 3842 11833 3842 3953 11834 3953 4065 11835 4065 3954 11836 3954 3732 11837 3732 4066 11838 4066 3955 11839 3955 3733 11840 3733 4067 11841 4067 3956 11842 3956 3734 11843 3734 4179 11844 4179 3846 11845 3846 3957 11846 3957 4069 11847 4069 3958 11848 3958 3736 11849 3736 4070 11850 4070 3959 11851 3959 3737 11852 3737 4071 11853 4071 3960 11854 3960 3738 11855 3738 4183 11856 4183 3850 11857 3850 3961 11858 3961 4073 11859 4073 3962 11860 3962 3740 11861 3740 4074 11862 4074 3963 11863 3963 3741 11864 3741 4075 11865 4075 3964 11866 3964 3742 11867 3742 4187 11868 4187 3854 11869 3854 3965 11870 3965 4077 11871 4077 3966 11872 3966 3744 11873 3744 4078 11874 4078 3967 11875 3967 3745 11876 3745 4079 11877 4079 3968 11878 3968 3746 11879 3746 4191 11880 4191 3858 11881 3858 3969 11882 3969 4081 11883 4081 3970 11884 3970 3748 11885 3748 4082 11886 4082 3971 11887 3971 3749 11888 3749 4194 11889 4194 3861 11890 3861 3972 11891 3972 4195 11892 4195 3862 11893 3862 3973 11894 3973 4085 11895 4085 3974 11896 3974 3752 11897 3752 4197 11898 4197 3864 11899 3864 3975 11900 3975 4198 11901 4198 3865 11902 3865 3976 11903 3976 4088 11904 4088 3977 11905 3977 3755 11906 3755 4200 11907 4200 3867 11908 3867 3978 11909 3978 4090 11910 4090 3979 11911 3979 3757 11912 3757 4202 11913 4202 3869 11914 3869 3980 11915 3980 4203 11916 4203 3870 11917 3870 3981 11918 3981 4093 11919 4093 3982 11920 3982 3760 11921 3760 4205 11922 4205 3872 11923 3872 3983 11924 3983 4206 11925 4206 3873 11926 3873 3984 11927 3984 4096 11928 4096 3985 11929 3985 3763 11930 3763 4208 11931 4208 3875 11932 3875 3986 11933 3986 4098 11934 4098 3987 11935 3987 3765 11936 3765 4099 11937 4099 3988 11938 3988 3766 11939 3766 4211 11940 4211 3878 11941 3878 3989 11942 3989 4101 11943 4101 3990 11944 3990 3768 11945 3768 4102 11946 4102 3991 11947 3991 3769 11948 3769 4214 11949 4214 3881 11950 3881 3992 11951 3992 4215 11952 4215 3882 11953 3882 3993 11954 3993 4105 11955 4105 3994 11956 3994 3772 11957 3772 4217 11958 4217 3884 11959 3884 3995 11960 3995 4107 11961 4107 3996 11962 3996 3774 11963 3774 4219 11964 4219 3886 11965 3886 3997 11966 3997 4109 11967 4109 3998 11968 3998 3776 11969 3776 4110 11970 4110 3999 11971 3999 3777 11972 3777 4111 11973 4111 4000 11974 4000 3778 11975 3778 4223 11976 4223 3890 11977 3890 4001 11978 4001 4113 11979 4113 4002 11980 4002 3780 11981 3780 4114 11982 4114 4003 11983 4003 3781 11984 3781 4115 11985 4115 4004 11986 4004 3782 11987 3782 4227 11988 4227 3894 11989 3894 4005 11990 4005 4117 11991 4117 4006 11992 4006 3784 11993 3784 4118 11994 4118 4007 11995 4007 3785 11996 3785 4230 11997 4230 3897 11998 3897 4008 11999 4008 4231 12000 4231 3898 12001 3898 4009 12002 4009 4121 12003 4121 4010 12004 4010 3788 12005 3788 4122 12006 4122 4011 12007 4011 3789 12008 3789 4234 12009 4234 3901 12010 3901 4012 12011 4012 4124 12012 4124 4013 12013 4013 3791 12014 3791 4236 12015 4236 3903 12016 3903 4014 12017 4014 4126 12018 4126 4015 12019 4015 3793 12020 3793 4238 12021 4238 3905 12022 3905 4016 12023 4016 4128 12024 4128 4017 12025 4017 3795 12026 3795 4240 12027 4240 3907 12028 3907 4018 12029 4018 4130 12030 4130 4019 12031 4019 3797 12032 3797 4242 12033 4242 3909 12034 3909 4020 12035 4020 4132 12036 4132 4021 12037 4021 3799 12038 3799 4244 12039 4244 3911 12040 3911 4022 12041 4022 4245 12042 4245 3912 12043 3912 4023 12044 4023 4135 12045 4135 4024 12046 4024 3802 12047 3802 4247 12048 4247 3914 12049 3914 4025 12050 4025 4137 12051 4137 4026 12052 4026 3804 12053 3804 4249 12054 4249 3916 12055 3916 4027 12056 4027 4139 12057 4139 4028 12058 4028 3806 12059 3806 4140 12060 4140 4029 12061 4029 3807 12062 3807 4252 12063 4252 3919 12064 3919 4030 12065 4030 4142 12066 4142 4031 12067 4031 3809 12068 3809 4143 12069 4143 4032 12070 4032 3810 12071 3810 4255 12072 4255 3922 12073 3922 4033 12074 4033 4145 12075 4145 4034 12076 4034 3812 12077 3812 4146 12078 4146 4035 12079 4035 3813 12080 3813 4258 12081 4258 3925 12082 3925 4036 12083 4036 4259 12084 4259 3926 12085 3926 4037 12086 4037 4149 12087 4149 4038 12088 4038 3816 12089 3816 4261 12090 4261 3928 12091 3928 4039 12092 4039 4262 12093 4262 3929 12094 3929 4040 12095 4040 4152 12096 4152 4041 12097 4041 3819 12098 3819 4264 12099 4264 3931 12100 3931 4042 12101 4042 4154 12102 4154 4043 12103 4043 3821 12104 3821 4266 12105 4266 3933 12106 3933 4044 12107 4044 4156 12108 4156 4045 12109 4045 3823 12110 3823 4268 12111 4268 3935 12112 3935 4046 12113 4046 4158 12114 4158 4047 12115 4047 3825 12116 3825 4270 12117 4270 3937 12118 3937 4048 12119 4048 4160 12120 4160 4049 12121 4049 3827 12122 3827 4272 12123 4272 3939 12124 3939 4050 12125 4050 4162 12126 4162 4051 12127 4051 3829 12128 3829 4274 12129 4274 3941 12130 3941 4052 12131 4052 4164 12132 4164 4053 12133 4053 3831 12134 3831 4276 12135 4276 3943 12136 3943 4054 12137 4054 5421 12138 5421 4055 12139 4055 3833 12140 3833 4167 12141 4167 4056 12142 4056 3834 12143 3834 4279 12144 4279 3946 12145 3946 4057 12146 4057 4287 12147 4287 3947 12148 3947 4058 12149 4058 4170 12150 4170 4059 12151 4059 3837 12152 3837 4171 12153 4171 4060 12154 4060 3838 12155 3838 4290 12156 4290 3950 12157 3950 4061 12158 4061 4173 12159 4173 4062 12160 4062 3840 12161 3840 4311 12162 4311 3952 12163 3952 4063 12164 4063 4175 12165 4175 4064 12166 4064 3842 12167 3842 4313 12168 4313 3954 12169 3954 4065 12170 4065 4335 12171 4335 3955 12172 3955 4066 12173 4066 4336 12174 4336 3956 12175 3956 4067 12176 4067 4179 12177 4179 4068 12178 4068 3846 12179 3846 4338 12180 4338 3958 12181 3958 4069 12182 4069 4358 12183 4358 3959 12184 3959 4070 12185 4070 4359 12186 4359 3960 12187 3960 4071 12188 4071 4183 12189 4183 4072 12190 4072 3850 12191 3850 4361 12192 4361 3962 12193 3962 4073 12194 4073 4383 12195 4383 3963 12196 3963 4074 12197 4074 4384 12198 4384 3964 12199 3964 4075 12200 4075 4187 12201 4187 4076 12202 4076 3854 12203 3854 4386 12204 4386 3966 12205 3966 4077 12206 4077 4406 12207 4406 3967 12208 3967 4078 12209 4078 4407 12210 4407 3968 12211 3968 4079 12212 4079 4191 12213 4191 4080 12214 4080 3858 12215 3858 4409 12216 4409 3970 12217 3970 4081 12218 4081 4431 12219 4431 3971 12220 3971 4082 12221 4082 4194 12222 4194 4083 12223 4083 3861 12224 3861 4195 12225 4195 4084 12226 4084 3862 12227 3862 4434 12228 4434 3974 12229 3974 4085 12230 4085 4197 12231 4197 4086 12232 4086 3864 12233 3864 4198 12234 4198 4087 12235 4087 3865 12236 3865 4456 12237 4456 3977 12238 3977 4088 12239 4088 4200 12240 4200 4089 12241 4089 3867 12242 3867 4459 12243 4459 3979 12244 3979 4090 12245 4090 4202 12246 4202 4091 12247 4091 3869 12248 3869 4203 12249 4203 4092 12250 4092 3870 12251 3870 4462 12252 4462 3982 12253 3982 4093 12254 4093 4205 12255 4205 4094 12256 4094 3872 12257 3872 4206 12258 4206 4095 12259 4095 3873 12260 3873 4484 12261 4484 3985 12262 3985 4096 12263 4096 4208 12264 4208 4097 12265 4097 3875 12266 3875 4486 12267 4486 3987 12268 3987 4098 12269 4098 4488 12270 4488 3988 12271 3988 4099 12272 4099 4211 12273 4211 4100 12274 4100 3878 12275 3878 4490 12276 4490 3990 12277 3990 4101 12278 4101 4510 12279 4510 3991 12280 3991 4102 12281 4102 4214 12282 4214 4103 12283 4103 3881 12284 3881 4215 12285 4215 4104 12286 4104 3882 12287 3882 4513 12288 4513 3994 12289 3994 4105 12290 4105 4217 12291 4217 4106 12292 4106 3884 12293 3884 4534 12294 4534 3996 12295 3996 4107 12296 4107 4219 12297 4219 4108 12298 4108 3886 12299 3886 4538 12300 4538 3998 12301 3998 4109 12302 4109 4558 12303 4558 3999 12304 3999 4110 12305 4110 4559 12306 4559 4000 12307 4000 4111 12308 4111 4223 12309 4223 4112 12310 4112 3890 12311 3890 4561 12312 4561 4002 12313 4002 4113 12314 4113 4581 12315 4581 4003 12316 4003 4114 12317 4114 4582 12318 4582 4004 12319 4004 4115 12320 4115 4227 12321 4227 4116 12322 4116 3894 12323 3894 4586 12324 4586 4006 12325 4006 4117 12326 4117 4606 12327 4606 4007 12328 4007 4118 12329 4118 4230 12330 4230 4119 12331 4119 3897 12332 3897 4231 12333 4231 4120 12334 4120 3898 12335 3898 4609 12336 4609 4010 12337 4010 4121 12338 4121 4620 12339 4620 4011 12340 4011 4122 12341 4122 4234 12342 4234 4123 12343 4123 3901 12344 3901 4623 12345 4623 4013 12346 4013 4124 12347 4124 4236 12348 4236 4125 12349 4125 3903 12350 3903 4625 12351 4625 4015 12352 4015 4126 12353 4126 4238 12354 4238 4127 12355 4127 3905 12356 3905 4627 12357 4627 4017 12358 4017 4128 12359 4128 4240 12360 4240 4129 12361 4129 3907 12362 3907 4629 12363 4629 4019 12364 4019 4130 12365 4130 4242 12366 4242 4131 12367 4131 3909 12368 3909 4631 12369 4631 4021 12370 4021 4132 12371 4132 4244 12372 4244 4133 12373 4133 3911 12374 3911 4245 12375 4245 4134 12376 4134 3912 12377 3912 4634 12378 4634 4024 12379 4024 4135 12380 4135 4247 12381 4247 4136 12382 4136 3914 12383 3914 4655 12384 4655 4026 12385 4026 4137 12386 4137 4249 12387 4249 4138 12388 4138 3916 12389 3916 4657 12390 4657 4028 12391 4028 4139 12392 4139 4677 12393 4677 4029 12394 4029 4140 12395 4140 4252 12396 4252 4141 12397 4141 3919 12398 3919 4679 12399 4679 4031 12400 4031 4142 12401 4142 4682 12402 4682 4032 12403 4032 4143 12404 4143 4255 12405 4255 4144 12406 4144 3922 12407 3922 4684 12408 4684 4034 12409 4034 4145 12410 4145 4704 12411 4704 4035 12412 4035 4146 12413 4146 4258 12414 4258 4147 12415 4147 3925 12416 3925 4259 12417 4259 4148 12418 4148 3926 12419 3926 4707 12420 4707 4038 12421 4038 4149 12422 4149 4261 12423 4261 4150 12424 4150 3928 12425 3928 4262 12426 4262 4151 12427 4151 3929 12428 3929 4731 12429 4731 4041 12430 4041 4152 12431 4152 4264 12432 4264 4153 12433 4153 3931 12434 3931 4733 12435 4733 4043 12436 4043 4154 12437 4154 4266 12438 4266 4155 12439 4155 3933 12440 3933 4735 12441 4735 4045 12442 4045 4156 12443 4156 4268 12444 4268 4157 12445 4157 3935 12446 3935 4737 12447 4737 4047 12448 4047 4158 12449 4158 4270 12450 4270 4159 12451 4159 3937 12452 3937 4739 12453 4739 4049 12454 4049 4160 12455 4160 4272 12456 4272 4161 12457 4161 3939 12458 3939 4741 12459 4741 4051 12460 4051 4162 12461 4162 4274 12462 4274 4163 12463 4163 3941 12464 3941 4743 12465 4743 4053 12466 4053 4164 12467 4164 4276 12468 4276 4165 12469 4165 3943 12470 3943 4827 12471 4827 3716 12472 3716 4166 12473 4166 4280 12474 4280 4056 12475 4056 4167 12476 4167 4279 12477 4279 4168 12478 4168 3946 12479 3946 4287 12480 4287 4169 12481 4169 3947 12482 3947 4756 12483 4756 4059 12484 4059 4170 12485 4170 4291 12486 4291 4060 12487 4060 4171 12488 4171 4290 12489 4290 4172 12490 4172 3950 12491 3950 4298 12492 4298 4062 12493 4062 4173 12494 4173 4311 12495 4311 4174 12496 4174 3952 12497 3952 4314 12498 4314 4064 12499 4064 4175 12500 4175 4313 12501 4313 4176 12502 4176 3954 12503 3954 4335 12504 4335 4177 12505 4177 3955 12506 3955 4336 12507 4336 4178 12508 4178 3956 12509 3956 4339 12510 4339 4068 12511 4068 4179 12512 4179 4338 12513 4338 4180 12514 4180 3958 12515 3958 4358 12516 4358 4181 12517 4181 3959 12518 3959 4359 12519 4359 4182 12520 4182 3960 12521 3960 4362 12522 4362 4072 12523 4072 4183 12524 4183 4361 12525 4361 4184 12526 4184 3962 12527 3962 4383 12528 4383 4185 12529 4185 3963 12530 3963 4384 12531 4384 4186 12532 4186 3964 12533 3964 4387 12534 4387 4076 12535 4076 4187 12536 4187 4386 12537 4386 4188 12538 4188 3966 12539 3966 4406 12540 4406 4189 12541 4189 3967 12542 3967 4407 12543 4407 4190 12544 4190 3968 12545 3968 4410 12546 4410 4080 12547 4080 4191 12548 4191 4409 12549 4409 4192 12550 4192 3970 12551 3970 4431 12552 4431 4193 12553 4193 3971 12554 3971 4768 12555 4768 4083 12556 4083 4194 12557 4194 4435 12558 4435 4084 12559 4084 4195 12560 4195 4434 12561 4434 4196 12562 4196 3974 12563 3974 4442 12564 4442 4086 12565 4086 4197 12566 4197 4770 12567 4770 4087 12568 4087 4198 12569 4198 4456 12570 4456 4199 12571 4199 3977 12572 3977 4772 12573 4772 4089 12574 4089 4200 12575 4200 4459 12576 4459 4201 12577 4201 3979 12578 3979 4774 12579 4774 4091 12580 4091 4202 12581 4202 4463 12582 4463 4092 12583 4092 4203 12584 4203 4462 12585 4462 4204 12586 4204 3982 12587 3982 4470 12588 4470 4094 12589 4094 4205 12590 4205 4776 12591 4776 4095 12592 4095 4206 12593 4206 4484 12594 4484 4207 12595 4207 3985 12596 3985 4778 12597 4778 4097 12598 4097 4208 12599 4208 4486 12600 4486 4209 12601 4209 3987 12602 3987 4488 12603 4488 4210 12604 4210 3988 12605 3988 4491 12606 4491 4100 12607 4100 4211 12608 4211 4490 12609 4490 4212 12610 4212 3990 12611 3990 4510 12612 4510 4213 12613 4213 3991 12614 3991 4782 12615 4782 4103 12616 4103 4214 12617 4214 4514 12618 4514 4104 12619 4104 4215 12620 4215 4513 12621 4513 4216 12622 4216 3994 12623 3994 4521 12624 4521 4106 12625 4106 4217 12626 4217 4534 12627 4534 4218 12628 4218 3996 12629 3996 4539 12630 4539 4108 12631 4108 4219 12632 4219 4538 12633 4538 4220 12634 4220 3998 12635 3998 4558 12636 4558 4221 12637 4221 3999 12638 3999 4559 12639 4559 4222 12640 4222 4000 12641 4000 4562 12642 4562 4112 12643 4112 4223 12644 4223 4561 12645 4561 4224 12646 4224 4002 12647 4002 4581 12648 4581 4225 12649 4225 4003 12650 4003 4582 12651 4582 4226 12652 4226 4004 12653 4004 4587 12654 4587 4116 12655 4116 4227 12656 4227 4586 12657 4586 4228 12658 4228 4006 12659 4006 4606 12660 4606 4229 12661 4229 4007 12662 4007 4790 12663 4790 4119 12664 4119 4230 12665 4230 4610 12666 4610 4120 12667 4120 4231 12668 4231 4609 12669 4609 4232 12670 4232 4010 12671 4010 4620 12672 4620 4233 12673 4233 4011 12674 4011 4792 12675 4792 4123 12676 4123 4234 12677 4234 4623 12678 4623 4235 12679 4235 4013 12680 4013 4794 12681 4794 4125 12682 4125 4236 12683 4236 4625 12684 4625 4237 12685 4237 4015 12686 4015 4796 12687 4796 4127 12688 4127 4238 12689 4238 4627 12690 4627 4239 12691 4239 4017 12692 4017 4798 12693 4798 4129 12694 4129 4240 12695 4240 4629 12696 4629 4241 12697 4241 4019 12698 4019 4800 12699 4800 4131 12700 4131 4242 12701 4242 4631 12702 4631 4243 12703 4243 4021 12704 4021 4802 12705 4802 4133 12706 4133 4244 12707 4244 4635 12708 4635 4134 12709 4134 4245 12710 4245 4634 12711 4634 4246 12712 4246 4024 12713 4024 4642 12714 4642 4136 12715 4136 4247 12716 4247 4655 12717 4655 4248 12718 4248 4026 12719 4026 4658 12720 4658 4138 12721 4138 4249 12722 4249 4657 12723 4657 4250 12724 4250 4028 12725 4028 4677 12726 4677 4251 12727 4251 4029 12728 4029 4806 12729 4806 4141 12730 4141 4252 12731 4252 4679 12732 4679 4253 12733 4253 4031 12734 4031 4682 12735 4682 4254 12736 4254 4032 12737 4032 4685 12738 4685 4144 12739 4144 4255 12740 4255 4684 12741 4684 4256 12742 4256 4034 12743 4034 4704 12744 4704 4257 12745 4257 4035 12746 4035 4810 12747 4810 4147 12748 4147 4258 12749 4258 4708 12750 4708 4148 12751 4148 4259 12752 4259 4707 12753 4707 4260 12754 4260 4038 12755 4038 4715 12756 4715 4150 12757 4150 4261 12758 4261 4812 12759 4812 4151 12760 4151 4262 12761 4262 4731 12762 4731 4263 12763 4263 4041 12764 4041 4814 12765 4814 4153 12766 4153 4264 12767 4264 4733 12768 4733 4265 12769 4265 4043 12770 4043 4816 12771 4816 4155 12772 4155 4266 12773 4266 4735 12774 4735 4267 12775 4267 4045 12776 4045 4818 12777 4818 4157 12778 4157 4268 12779 4268 4737 12780 4737 4269 12781 4269 4047 12782 4047 4820 12783 4820 4159 12784 4159 4270 12785 4270 4739 12786 4739 4271 12787 4271 4049 12788 4049 4822 12789 4822 4161 12790 4161 4272 12791 4272 4741 12792 4741 4273 12793 4273 4051 12794 4051 4824 12795 4824 4163 12796 4163 4274 12797 4274 4743 12798 4743 4275 12799 4275 4053 12800 4053 4826 12801 4826 4165 12802 4165 4276 12803 4276 5421 12804 5421 4277 12805 4277 4055 12806 4055 4280 12807 4280 4278 12808 4278 4056 12809 4056 4278 12810 4278 4168 12811 4168 4279 12812 4279 4280 12813 4280 4168 12814 4168 4278 12815 4278 4282 12816 4282 4168 12817 4168 4280 12818 4280 4282 12819 4282 4281 12820 4281 4168 12821 4168 4284 12822 4284 4281 12823 4281 4282 12824 4282 4284 12825 4284 4283 12826 4283 4281 12827 4281 4277 12828 4277 4283 12829 4283 4284 12830 4284 4277 12831 4277 4285 12832 4285 4283 12833 4283 4277 12834 4277 4286 12835 4286 4285 12836 4285 4829 12837 4829 4169 12838 4169 4287 12839 4287 4756 12840 4756 4288 12841 4288 4059 12842 4059 4291 12843 4291 4289 12844 4289 4060 12845 4060 4289 12846 4289 4172 12847 4172 4290 12848 4290 4291 12849 4291 4172 12850 4172 4289 12851 4289 4293 12852 4293 4172 12853 4172 4291 12854 4291 4293 12855 4293 4292 12856 4292 4172 12857 4172 4295 12858 4295 4292 12859 4292 4293 12860 4293 4295 12861 4295 4294 12862 4294 4292 12863 4292 4297 12864 4297 4294 12865 4294 4295 12866 4295 4297 12867 4297 4296 12868 4296 4294 12869 4294 4301 12870 4301 4296 12871 4296 4297 12872 4297 4301 12873 4301 4298 12874 4298 4296 12875 4296 4301 12876 4301 4062 12877 4062 4298 12878 4298 4301 12879 4301 4299 12880 4299 4062 12881 4062 4301 12882 4301 4300 12883 4300 4299 12884 4299 4303 12885 4303 4300 12886 4300 4301 12887 4301 4303 12888 4303 4302 12889 4302 4300 12890 4300 4305 12891 4305 4302 12892 4302 4303 12893 4303 4305 12894 4305 4304 12895 4304 4302 12896 4302 4307 12897 4307 4304 12898 4304 4305 12899 4305 4307 12900 4307 4306 12901 4306 4304 12902 4304 4309 12903 4309 4306 12904 4306 4307 12905 4307 4309 12906 4309 4308 12907 4308 4306 12908 4306 4333 12909 4333 4308 12910 4308 4309 12911 4309 4333 12912 4333 4310 12913 4310 4308 12914 4308 4322 12915 4322 4174 12916 4174 4311 12917 4311 4314 12918 4314 4312 12919 4312 4064 12920 4064 4312 12921 4312 4176 12922 4176 4313 12923 4313 4314 12924 4314 4176 12925 4176 4312 12926 4312 4316 12927 4316 4176 12928 4176 4314 12929 4314 4316 12930 4316 4315 12931 4315 4176 12932 4176 4318 12933 4318 4315 12934 4315 4316 12935 4316 4318 12936 4318 4317 12937 4317 4315 12938 4315 4320 12939 4320 4317 12940 4317 4318 12941 4318 4320 12942 4320 4319 12943 4319 4317 12944 4317 4174 12945 4174 4319 12946 4319 4320 12947 4320 4322 12948 4322 4319 12949 4319 4174 12950 4174 4322 12951 4322 4321 12952 4321 4319 12953 4319 4324 12954 4324 4321 12955 4321 4322 12956 4322 4324 12957 4324 4323 12958 4323 4321 12959 4321 4326 12960 4326 4323 12961 4323 4324 12962 4324 4326 12963 4326 4325 12964 4325 4323 12965 4323 4328 12966 4328 4325 12967 4325 4326 12968 4326 4328 12969 4328 4327 12970 4327 4325 12971 4325 4330 12972 4330 4327 12973 4327 4328 12974 4328 4330 12975 4330 4329 12976 4329 4327 12977 4327 4332 12978 4332 4329 12979 4329 4330 12980 4330 4332 12981 4332 4331 12982 4331 4329 12983 4329 4758 12984 4758 4331 12985 4331 4332 12986 4332 4831 12987 4831 4310 12988 4310 4333 12989 4333 4758 12990 4758 4334 12991 4334 4331 12992 4331 4833 12993 4833 4177 12994 4177 4335 12995 4335 4347 12996 4347 4178 12997 4178 4336 12998 4336 4339 12999 4339 4337 13000 4337 4068 13001 4068 4337 13002 4337 4180 13003 4180 4338 13004 4338 4339 13005 4339 4180 13006 4180 4337 13007 4337 4341 13008 4341 4180 13009 4180 4339 13010 4339 4341 13011 4341 4340 13012 4340 4180 13013 4180 4343 13014 4343 4340 13015 4340 4341 13016 4341 4343 13017 4343 4342 13018 4342 4340 13019 4340 4345 13020 4345 4342 13021 4342 4343 13022 4343 4345 13023 4345 4344 13024 4344 4342 13025 4342 4178 13026 4178 4344 13027 4344 4345 13028 4345 4347 13029 4347 4344 13030 4344 4178 13031 4178 4347 13032 4347 4346 13033 4346 4344 13034 4344 4349 13035 4349 4346 13036 4346 4347 13037 4347 4349 13038 4349 4348 13039 4348 4346 13040 4346 4351 13041 4351 4348 13042 4348 4349 13043 4349 4351 13044 4351 4350 13045 4350 4348 13046 4348 4353 13047 4353 4350 13048 4350 4351 13049 4351 4353 13050 4353 4352 13051 4352 4350 13052 4350 4355 13053 4355 4352 13054 4352 4353 13055 4353 4355 13056 4355 4354 13057 4354 4352 13058 4352 4357 13059 4357 4354 13060 4354 4355 13061 4355 4357 13062 4357 4356 13063 4356 4354 13064 4354 4760 13065 4760 4356 13066 4356 4357 13067 4357 4835 13068 4835 4181 13069 4181 4358 13070 4358 4370 13071 4370 4182 13072 4182 4359 13073 4359 4362 13074 4362 4360 13075 4360 4072 13076 4072 4360 13077 4360 4184 13078 4184 4361 13079 4361 4362 13080 4362 4184 13081 4184 4360 13082 4360 4364 13083 4364 4184 13084 4184 4362 13085 4362 4364 13086 4364 4363 13087 4363 4184 13088 4184 4366 13089 4366 4363 13090 4363 4364 13091 4364 4366 13092 4366 4365 13093 4365 4363 13094 4363 4368 13095 4368 4365 13096 4365 4366 13097 4366 4368 13098 4368 4367 13099 4367 4365 13100 4365 4182 13101 4182 4367 13102 4367 4368 13103 4368 4370 13104 4370 4367 13105 4367 4182 13106 4182 4370 13107 4370 4369 13108 4369 4367 13109 4367 4372 13110 4372 4369 13111 4369 4370 13112 4370 4372 13113 4372 4371 13114 4371 4369 13115 4369 4374 13116 4374 4371 13117 4371 4372 13118 4372 4374 13119 4374 4373 13120 4373 4371 13121 4371 4376 13122 4376 4373 13123 4373 4374 13124 4374 4376 13125 4376 4375 13126 4375 4373 13127 4373 4378 13128 4378 4375 13129 4375 4376 13130 4376 4378 13131 4378 4377 13132 4377 4375 13133 4375 4380 13134 4380 4377 13135 4377 4378 13136 4378 4380 13137 4380 4379 13138 4379 4377 13139 4377 4762 13140 4762 4379 13141 4379 4380 13142 4380 4760 13143 4760 4381 13144 4381 4356 13145 4356 4762 13146 4762 4382 13147 4382 4379 13148 4379 4837 13149 4837 4185 13150 4185 4383 13151 4383 4395 13152 4395 4186 13153 4186 4384 13154 4384 4387 13155 4387 4385 13156 4385 4076 13157 4076 4385 13158 4385 4188 13159 4188 4386 13160 4386 4387 13161 4387 4188 13162 4188 4385 13163 4385 4389 13164 4389 4188 13165 4188 4387 13166 4387 4389 13167 4389 4388 13168 4388 4188 13169 4188 4391 13170 4391 4388 13171 4388 4389 13172 4389 4391 13173 4391 4390 13174 4390 4388 13175 4388 4393 13176 4393 4390 13177 4390 4391 13178 4391 4393 13179 4393 4392 13180 4392 4390 13181 4390 4186 13182 4186 4392 13183 4392 4393 13184 4393 4395 13185 4395 4392 13186 4392 4186 13187 4186 4395 13188 4395 4394 13189 4394 4392 13190 4392 4397 13191 4397 4394 13192 4394 4395 13193 4395 4397 13194 4397 4396 13195 4396 4394 13196 4394 4399 13197 4399 4396 13198 4396 4397 13199 4397 4399 13200 4399 4398 13201 4398 4396 13202 4396 4401 13203 4401 4398 13204 4398 4399 13205 4399 4401 13206 4401 4400 13207 4400 4398 13208 4398 4403 13209 4403 4400 13210 4400 4401 13211 4401 4403 13212 4403 4402 13213 4402 4400 13214 4400 4405 13215 4405 4402 13216 4402 4403 13217 4403 4405 13218 4405 4404 13219 4404 4402 13220 4402 4764 13221 4764 4404 13222 4404 4405 13223 4405 4839 13224 4839 4189 13225 4189 4406 13226 4406 4418 13227 4418 4190 13228 4190 4407 13229 4407 4410 13230 4410 4408 13231 4408 4080 13232 4080 4408 13233 4408 4192 13234 4192 4409 13235 4409 4410 13236 4410 4192 13237 4192 4408 13238 4408 4412 13239 4412 4192 13240 4192 4410 13241 4410 4412 13242 4412 4411 13243 4411 4192 13244 4192 4414 13245 4414 4411 13246 4411 4412 13247 4412 4414 13248 4414 4413 13249 4413 4411 13250 4411 4416 13251 4416 4413 13252 4413 4414 13253 4414 4416 13254 4416 4415 13255 4415 4413 13256 4413 4190 13257 4190 4415 13258 4415 4416 13259 4416 4418 13260 4418 4415 13261 4415 4190 13262 4190 4418 13263 4418 4417 13264 4417 4415 13265 4415 4420 13266 4420 4417 13267 4417 4418 13268 4418 4420 13269 4420 4419 13270 4419 4417 13271 4417 4422 13272 4422 4419 13273 4419 4420 13274 4420 4422 13275 4422 4421 13276 4421 4419 13277 4419 4424 13278 4424 4421 13279 4421 4422 13280 4422 4424 13281 4424 4423 13282 4423 4421 13283 4421 4426 13284 4426 4423 13285 4423 4424 13286 4424 4426 13287 4426 4425 13288 4425 4423 13289 4423 4428 13290 4428 4425 13291 4425 4426 13292 4426 4428 13293 4428 4427 13294 4427 4425 13295 4425 4766 13296 4766 4427 13297 4427 4428 13298 4428 4764 13299 4764 4429 13300 4429 4404 13301 4404 4766 13302 4766 4430 13303 4430 4427 13304 4427 4841 13305 4841 4193 13306 4193 4431 13307 4431 4768 13308 4768 4432 13309 4432 4083 13310 4083 4435 13311 4435 4433 13312 4433 4084 13313 4084 4433 13314 4433 4196 13315 4196 4434 13316 4434 4435 13317 4435 4196 13318 4196 4433 13319 4433 4437 13320 4437 4196 13321 4196 4435 13322 4435 4437 13323 4437 4436 13324 4436 4196 13325 4196 4439 13326 4439 4436 13327 4436 4437 13328 4437 4439 13329 4439 4438 13330 4438 4436 13331 4436 4441 13332 4441 4438 13333 4438 4439 13334 4439 4441 13335 4441 4440 13336 4440 4438 13337 4438 4445 13338 4445 4440 13339 4440 4441 13340 4441 4445 13341 4445 4442 13342 4442 4440 13343 4440 4445 13344 4445 4086 13345 4086 4442 13346 4442 4445 13347 4445 4443 13348 4443 4086 13349 4086 4445 13350 4445 4444 13351 4444 4443 13352 4443 4447 13353 4447 4444 13354 4444 4445 13355 4445 4447 13356 4447 4446 13357 4446 4444 13358 4444 4449 13359 4449 4446 13360 4446 4447 13361 4447 4449 13362 4449 4448 13363 4448 4446 13364 4446 4451 13365 4451 4448 13366 4448 4449 13367 4449 4451 13368 4451 4450 13369 4450 4448 13370 4448 4453 13371 4453 4450 13372 4450 4451 13373 4451 4453 13374 4453 4452 13375 4452 4450 13376 4450 4458 13377 4458 4452 13378 4452 4453 13379 4453 4458 13380 4458 4454 13381 4454 4452 13382 4452 4770 13383 4770 4455 13384 4455 4087 13385 4087 4845 13386 4845 4199 13387 4199 4456 13388 4456 4772 13389 4772 4457 13390 4457 4089 13391 4089 4843 13392 4843 4454 13393 4454 4458 13394 4458 4847 13395 4847 4201 13396 4201 4459 13397 4459 4774 13398 4774 4460 13399 4460 4091 13400 4091 4463 13401 4463 4461 13402 4461 4092 13403 4092 4461 13404 4461 4204 13405 4204 4462 13406 4462 4463 13407 4463 4204 13408 4204 4461 13409 4461 4465 13410 4465 4204 13411 4204 4463 13412 4463 4465 13413 4465 4464 13414 4464 4204 13415 4204 4467 13416 4467 4464 13417 4464 4465 13418 4465 4467 13419 4467 4466 13420 4466 4464 13421 4464 4469 13422 4469 4466 13423 4466 4467 13424 4467 4469 13425 4469 4468 13426 4468 4466 13427 4466 4473 13428 4473 4468 13429 4468 4469 13430 4469 4473 13431 4473 4470 13432 4470 4468 13433 4468 4473 13434 4473 4094 13435 4094 4470 13436 4470 4473 13437 4473 4471 13438 4471 4094 13439 4094 4473 13440 4473 4472 13441 4472 4471 13442 4471 4475 13443 4475 4472 13444 4472 4473 13445 4473 4475 13446 4475 4474 13447 4474 4472 13448 4472 4477 13449 4477 4474 13450 4474 4475 13451 4475 4477 13452 4477 4476 13453 4476 4474 13454 4474 4479 13455 4479 4476 13456 4476 4477 13457 4477 4479 13458 4479 4478 13459 4478 4476 13460 4476 4481 13461 4481 4478 13462 4478 4479 13463 4479 4481 13464 4481 4480 13465 4480 4478 13466 4478 4487 13467 4487 4480 13468 4480 4481 13469 4481 4487 13470 4487 4482 13471 4482 4480 13472 4480 4776 13473 4776 4483 13474 4483 4095 13475 4095 4851 13476 4851 4207 13477 4207 4484 13478 4484 4778 13479 4778 4485 13480 4485 4097 13481 4097 4853 13482 4853 4209 13483 4209 4486 13484 4486 4849 13485 4849 4482 13486 4482 4487 13487 4487 4499 13488 4499 4210 13489 4210 4488 13490 4488 4491 13491 4491 4489 13492 4489 4100 13493 4100 4489 13494 4489 4212 13495 4212 4490 13496 4490 4491 13497 4491 4212 13498 4212 4489 13499 4489 4493 13500 4493 4212 13501 4212 4491 13502 4491 4493 13503 4493 4492 13504 4492 4212 13505 4212 4495 13506 4495 4492 13507 4492 4493 13508 4493 4495 13509 4495 4494 13510 4494 4492 13511 4492 4497 13512 4497 4494 13513 4494 4495 13514 4495 4497 13515 4497 4496 13516 4496 4494 13517 4494 4210 13518 4210 4496 13519 4496 4497 13520 4497 4499 13521 4499 4496 13522 4496 4210 13523 4210 4499 13524 4499 4498 13525 4498 4496 13526 4496 4501 13527 4501 4498 13528 4498 4499 13529 4499 4501 13530 4501 4500 13531 4500 4498 13532 4498 4503 13533 4503 4500 13534 4500 4501 13535 4501 4503 13536 4503 4502 13537 4502 4500 13538 4500 4505 13539 4505 4502 13540 4502 4503 13541 4503 4505 13542 4505 4504 13543 4504 4502 13544 4502 4507 13545 4507 4504 13546 4504 4505 13547 4505 4507 13548 4507 4506 13549 4506 4504 13550 4504 4509 13551 4509 4506 13552 4506 4507 13553 4507 4509 13554 4509 4508 13555 4508 4506 13556 4506 4780 13557 4780 4508 13558 4508 4509 13559 4509 4855 13560 4855 4213 13561 4213 4510 13562 4510 4782 13563 4782 4511 13564 4511 4103 13565 4103 4514 13566 4514 4512 13567 4512 4104 13568 4104 4512 13569 4512 4216 13570 4216 4513 13571 4513 4514 13572 4514 4216 13573 4216 4512 13574 4512 4516 13575 4516 4216 13576 4216 4514 13577 4514 4516 13578 4516 4515 13579 4515 4216 13580 4216 4518 13581 4518 4515 13582 4515 4516 13583 4516 4518 13584 4518 4517 13585 4517 4515 13586 4515 4520 13587 4520 4517 13588 4517 4518 13589 4518 4520 13590 4520 4519 13591 4519 4517 13592 4517 4524 13593 4524 4519 13594 4519 4520 13595 4520 4524 13596 4524 4521 13597 4521 4519 13598 4519 4524 13599 4524 4106 13600 4106 4521 13601 4521 4524 13602 4524 4522 13603 4522 4106 13604 4106 4524 13605 4524 4523 13606 4523 4522 13607 4522 4526 13608 4526 4523 13609 4523 4524 13610 4524 4526 13611 4526 4525 13612 4525 4523 13613 4523 4528 13614 4528 4525 13615 4525 4526 13616 4526 4528 13617 4528 4527 13618 4527 4525 13619 4525 4530 13620 4530 4527 13621 4527 4528 13622 4528 4530 13623 4530 4529 13624 4529 4527 13625 4527 4532 13626 4532 4529 13627 4529 4530 13628 4530 4532 13629 4532 4531 13630 4531 4529 13631 4529 4536 13632 4536 4531 13633 4531 4532 13634 4532 4536 13635 4536 4533 13636 4533 4531 13637 4531 4547 13638 4547 4218 13639 4218 4534 13640 4534 4780 13641 4780 4535 13642 4535 4508 13643 4508 4857 13644 4857 4533 13645 4533 4536 13646 4536 4539 13647 4539 4537 13648 4537 4108 13649 4108 4537 13650 4537 4220 13651 4220 4538 13652 4538 4539 13653 4539 4220 13654 4220 4537 13655 4537 4541 13656 4541 4220 13657 4220 4539 13658 4539 4541 13659 4541 4540 13660 4540 4220 13661 4220 4543 13662 4543 4540 13663 4540 4541 13664 4541 4543 13665 4543 4542 13666 4542 4540 13667 4540 4545 13668 4545 4542 13669 4542 4543 13670 4543 4545 13671 4545 4544 13672 4544 4542 13673 4542 4218 13674 4218 4544 13675 4544 4545 13676 4545 4547 13677 4547 4544 13678 4544 4218 13679 4218 4547 13680 4547 4546 13681 4546 4544 13682 4544 4549 13683 4549 4546 13684 4546 4547 13685 4547 4549 13686 4549 4548 13687 4548 4546 13688 4546 4551 13689 4551 4548 13690 4548 4549 13691 4549 4551 13692 4551 4550 13693 4550 4548 13694 4548 4553 13695 4553 4550 13696 4550 4551 13697 4551 4553 13698 4553 4552 13699 4552 4550 13700 4550 4555 13701 4555 4552 13702 4552 4553 13703 4553 4555 13704 4555 4554 13705 4554 4552 13706 4552 4557 13707 4557 4554 13708 4554 4555 13709 4555 4557 13710 4557 4556 13711 4556 4554 13712 4554 4784 13713 4784 4556 13714 4556 4557 13715 4557 4859 13716 4859 4221 13717 4221 4558 13718 4558 4570 13719 4570 4222 13720 4222 4559 13721 4559 4562 13722 4562 4560 13723 4560 4112 13724 4112 4560 13725 4560 4224 13726 4224 4561 13727 4561 4562 13728 4562 4224 13729 4224 4560 13730 4560 4564 13731 4564 4224 13732 4224 4562 13733 4562 4564 13734 4564 4563 13735 4563 4224 13736 4224 4566 13737 4566 4563 13738 4563 4564 13739 4564 4566 13740 4566 4565 13741 4565 4563 13742 4563 4568 13743 4568 4565 13744 4565 4566 13745 4566 4568 13746 4568 4567 13747 4567 4565 13748 4565 4222 13749 4222 4567 13750 4567 4568 13751 4568 4570 13752 4570 4567 13753 4567 4222 13754 4222 4570 13755 4570 4569 13756 4569 4567 13757 4567 4572 13758 4572 4569 13759 4569 4570 13760 4570 4572 13761 4572 4571 13762 4571 4569 13763 4569 4574 13764 4574 4571 13765 4571 4572 13766 4572 4574 13767 4574 4573 13768 4573 4571 13769 4571 4576 13770 4576 4573 13771 4573 4574 13772 4574 4576 13773 4576 4575 13774 4575 4573 13775 4573 4578 13776 4578 4575 13777 4575 4576 13778 4576 4578 13779 4578 4577 13780 4577 4575 13781 4575 4580 13782 4580 4577 13783 4577 4578 13784 4578 4580 13785 4580 4579 13786 4579 4577 13787 4577 4786 13788 4786 4579 13789 4579 4580 13790 4580 4861 13791 4861 4225 13792 4225 4581 13793 4581 4595 13794 4595 4226 13795 4226 4582 13796 4582 4784 13797 4784 4583 13798 4583 4556 13799 4556 4786 13800 4786 4584 13801 4584 4579 13802 4579 4587 13803 4587 4585 13804 4585 4116 13805 4116 4585 13806 4585 4228 13807 4228 4586 13808 4586 4587 13809 4587 4228 13810 4228 4585 13811 4585 4589 13812 4589 4228 13813 4228 4587 13814 4587 4589 13815 4589 4588 13816 4588 4228 13817 4228 4591 13818 4591 4588 13819 4588 4589 13820 4589 4591 13821 4591 4590 13822 4590 4588 13823 4588 4593 13824 4593 4590 13825 4590 4591 13826 4591 4593 13827 4593 4592 13828 4592 4590 13829 4590 4226 13830 4226 4592 13831 4592 4593 13832 4593 4595 13833 4595 4592 13834 4592 4226 13835 4226 4595 13836 4595 4594 13837 4594 4592 13838 4592 4597 13839 4597 4594 13840 4594 4595 13841 4595 4597 13842 4597 4596 13843 4596 4594 13844 4594 4599 13845 4599 4596 13846 4596 4597 13847 4597 4599 13848 4599 4598 13849 4598 4596 13850 4596 4601 13851 4601 4598 13852 4598 4599 13853 4599 4601 13854 4601 4600 13855 4600 4598 13856 4598 4603 13857 4603 4600 13858 4600 4601 13859 4601 4603 13860 4603 4602 13861 4602 4600 13862 4600 4605 13863 4605 4602 13864 4602 4603 13865 4603 4605 13866 4605 4604 13867 4604 4602 13868 4602 4788 13869 4788 4604 13870 4604 4605 13871 4605 4863 13872 4863 4229 13873 4229 4606 13874 4606 4790 13875 4790 4607 13876 4607 4119 13877 4119 4610 13878 4610 4608 13879 4608 4120 13880 4120 4608 13881 4608 4232 13882 4232 4609 13883 4609 4610 13884 4610 4232 13885 4232 4608 13886 4608 4612 13887 4612 4232 13888 4232 4610 13889 4610 4612 13890 4612 4611 13891 4611 4232 13892 4232 4614 13893 4614 4611 13894 4611 4612 13895 4612 4614 13896 4614 4613 13897 4613 4611 13898 4611 4616 13899 4616 4613 13900 4613 4614 13901 4614 4616 13902 4616 4615 13903 4615 4613 13904 4613 4618 13905 4618 4615 13906 4615 4616 13907 4616 4618 13908 4618 4617 13909 4617 4615 13910 4615 4865 13911 4865 4617 13912 4617 4618 13913 4618 4865 13914 4865 4619 13915 4619 4617 13916 4617 4867 13917 4867 4233 13918 4233 4620 13919 4620 4792 13920 4792 4621 13921 4621 4123 13922 4123 4788 13923 4788 4622 13924 4622 4604 13925 4604 4869 13926 4869 4235 13927 4235 4623 13928 4623 4794 13929 4794 4624 13930 4624 4125 13931 4125 4871 13932 4871 4237 13933 4237 4625 13934 4625 4796 13935 4796 4626 13936 4626 4127 13937 4127 4873 13938 4873 4239 13939 4239 4627 13940 4627 4798 13941 4798 4628 13942 4628 4129 13943 4129 4875 13944 4875 4241 13945 4241 4629 13946 4629 4800 13947 4800 4630 13948 4630 4131 13949 4131 4877 13950 4877 4243 13951 4243 4631 13952 4631 4802 13953 4802 4632 13954 4632 4133 13955 4133 4635 13956 4635 4633 13957 4633 4134 13958 4134 4633 13959 4633 4246 13960 4246 4634 13961 4634 4635 13962 4635 4246 13963 4246 4633 13964 4633 4637 13965 4637 4246 13966 4246 4635 13967 4635 4637 13968 4637 4636 13969 4636 4246 13970 4246 4639 13971 4639 4636 13972 4636 4637 13973 4637 4639 13974 4639 4638 13975 4638 4636 13976 4636 4641 13977 4641 4638 13978 4638 4639 13979 4639 4641 13980 4641 4640 13981 4640 4638 13982 4638 4645 13983 4645 4640 13984 4640 4641 13985 4641 4645 13986 4645 4642 13987 4642 4640 13988 4640 4645 13989 4645 4136 13990 4136 4642 13991 4642 4645 13992 4645 4643 13993 4643 4136 13994 4136 4645 13995 4645 4644 13996 4644 4643 13997 4643 4647 13998 4647 4644 13999 4644 4645 14000 4645 4647 14001 4647 4646 14002 4646 4644 14003 4644 4649 14004 4649 4646 14005 4646 4647 14006 4647 4649 14007 4649 4648 14008 4648 4646 14009 4646 4651 14010 4651 4648 14011 4648 4649 14012 4649 4651 14013 4651 4650 14014 4650 4648 14015 4648 4653 14016 4653 4650 14017 4650 4651 14018 4651 4653 14019 4653 4652 14020 4652 4650 14021 4650 4680 14022 4680 4652 14023 4652 4653 14024 4653 4680 14025 4680 4654 14026 4654 4652 14027 4652 4666 14028 4666 4248 14029 4248 4655 14030 4655 4658 14031 4658 4656 14032 4656 4138 14033 4138 4656 14034 4656 4250 14035 4250 4657 14036 4657 4658 14037 4658 4250 14038 4250 4656 14039 4656 4660 14040 4660 4250 14041 4250 4658 14042 4658 4660 14043 4660 4659 14044 4659 4250 14045 4250 4662 14046 4662 4659 14047 4659 4660 14048 4660 4662 14049 4662 4661 14050 4661 4659 14051 4659 4664 14052 4664 4661 14053 4661 4662 14054 4662 4664 14055 4664 4663 14056 4663 4661 14057 4661 4248 14058 4248 4663 14059 4663 4664 14060 4664 4666 14061 4666 4663 14062 4663 4248 14063 4248 4666 14064 4666 4665 14065 4665 4663 14066 4663 4668 14067 4668 4665 14068 4665 4666 14069 4666 4668 14070 4668 4667 14071 4667 4665 14072 4665 4670 14073 4670 4667 14074 4667 4668 14075 4668 4670 14076 4670 4669 14077 4669 4667 14078 4667 4672 14079 4672 4669 14080 4669 4670 14081 4670 4672 14082 4672 4671 14083 4671 4669 14084 4669 4674 14085 4674 4671 14086 4671 4672 14087 4672 4674 14088 4674 4673 14089 4673 4671 14090 4671 4676 14091 4676 4673 14092 4673 4674 14093 4674 4676 14094 4676 4675 14095 4675 4673 14096 4673 4804 14097 4804 4675 14098 4675 4676 14099 4676 4881 14100 4881 4251 14101 4251 4677 14102 4677 4806 14103 4806 4678 14104 4678 4141 14105 4141 4883 14106 4883 4253 14107 4253 4679 14108 4679 4879 14109 4879 4654 14110 4654 4680 14111 4680 4804 14112 4804 4681 14113 4681 4675 14114 4675 4693 14115 4693 4254 14116 4254 4682 14117 4682 4685 14118 4685 4683 14119 4683 4144 14120 4144 4683 14121 4683 4256 14122 4256 4684 14123 4684 4685 14124 4685 4256 14125 4256 4683 14126 4683 4687 14127 4687 4256 14128 4256 4685 14129 4685 4687 14130 4687 4686 14131 4686 4256 14132 4256 4689 14133 4689 4686 14134 4686 4687 14135 4687 4689 14136 4689 4688 14137 4688 4686 14138 4686 4691 14139 4691 4688 14140 4688 4689 14141 4689 4691 14142 4691 4690 14143 4690 4688 14144 4688 4254 14145 4254 4690 14146 4690 4691 14147 4691 4693 14148 4693 4690 14149 4690 4254 14150 4254 4693 14151 4693 4692 14152 4692 4690 14153 4690 4695 14154 4695 4692 14155 4692 4693 14156 4693 4695 14157 4695 4694 14158 4694 4692 14159 4692 4697 14160 4697 4694 14161 4694 4695 14162 4695 4697 14163 4697 4696 14164 4696 4694 14165 4694 4699 14166 4699 4696 14167 4696 4697 14168 4697 4699 14169 4699 4698 14170 4698 4696 14171 4696 4701 14172 4701 4698 14173 4698 4699 14174 4699 4701 14175 4701 4700 14176 4700 4698 14177 4698 4703 14178 4703 4700 14179 4700 4701 14180 4701 4703 14181 4703 4702 14182 4702 4700 14183 4700 4808 14184 4808 4702 14185 4702 4703 14186 4703 4885 14187 4885 4257 14188 4257 4704 14189 4704 4810 14190 4810 4705 14191 4705 4147 14192 4147 4708 14193 4708 4706 14194 4706 4148 14195 4148 4706 14196 4706 4260 14197 4260 4707 14198 4707 4708 14199 4708 4260 14200 4260 4706 14201 4706 4710 14202 4710 4260 14203 4260 4708 14204 4708 4710 14205 4710 4709 14206 4709 4260 14207 4260 4712 14208 4712 4709 14209 4709 4710 14210 4710 4712 14211 4712 4711 14212 4711 4709 14213 4709 4714 14214 4714 4711 14215 4711 4712 14216 4712 4714 14217 4714 4713 14218 4713 4711 14219 4711 4718 14220 4718 4713 14221 4713 4714 14222 4714 4718 14223 4718 4715 14224 4715 4713 14225 4713 4718 14226 4718 4150 14227 4150 4715 14228 4715 4718 14229 4718 4716 14230 4716 4150 14231 4150 4718 14232 4718 4717 14233 4717 4716 14234 4716 4720 14235 4720 4717 14236 4717 4718 14237 4718 4720 14238 4720 4719 14239 4719 4717 14240 4717 4722 14241 4722 4719 14242 4719 4720 14243 4720 4722 14244 4722 4721 14245 4721 4719 14246 4719 4724 14247 4724 4721 14248 4721 4722 14249 4722 4724 14250 4724 4723 14251 4723 4721 14252 4721 4726 14253 4726 4723 14254 4723 4724 14255 4724 4726 14256 4726 4725 14257 4725 4723 14258 4723 4729 14259 4729 4725 14260 4725 4726 14261 4726 4729 14262 4729 4727 14263 4727 4725 14264 4725 4808 14265 4808 4728 14266 4728 4702 14267 4702 4887 14268 4887 4727 14269 4727 4729 14270 4729 4812 14271 4812 4730 14272 4730 4151 14273 4151 4889 14274 4889 4263 14275 4263 4731 14276 4731 4814 14277 4814 4732 14278 4732 4153 14279 4153 4891 14280 4891 4265 14281 4265 4733 14282 4733 4816 14283 4816 4734 14284 4734 4155 14285 4155 4893 14286 4893 4267 14287 4267 4735 14288 4735 4818 14289 4818 4736 14290 4736 4157 14291 4157 4895 14292 4895 4269 14293 4269 4737 14294 4737 4820 14295 4820 4738 14296 4738 4159 14297 4159 4897 14298 4897 4271 14299 4271 4739 14300 4739 4822 14301 4822 4740 14302 4740 4161 14303 4161 4899 14304 4899 4273 14305 4273 4741 14306 4741 4824 14307 4824 4742 14308 4742 4163 14309 4163 4901 14310 4901 4275 14311 4275 4743 14312 4743 4826 14313 4826 4744 14314 4744 4165 14315 4165 4277 14316 4277 4745 14317 4745 4286 14318 4286 5421 14319 5421 4745 14320 4745 4277 14321 4277 5421 14322 5421 4746 14323 4746 4745 14324 4745 5421 14325 5421 4747 14326 4747 4746 14327 4746 5421 14328 5421 4748 14329 4748 4747 14330 4747 5421 14331 5421 4749 14332 4749 4748 14333 4748 5421 14334 5421 4750 14335 4750 4749 14336 4749 5421 14337 5421 4751 14338 4751 4750 14339 4750 5421 14340 5421 4752 14341 4752 4751 14342 4751 5421 14343 5421 4753 14344 4753 4752 14345 4752 5421 14346 5421 4754 14347 4754 4753 14348 4753 4829 14349 4829 4755 14350 4755 4169 14351 4169 4904 14352 4904 4288 14353 4288 4756 14354 4756 4831 14355 4831 4757 14356 4757 4310 14357 4310 4912 14358 4912 4334 14359 4334 4758 14360 4758 4833 14361 4833 4759 14362 4759 4177 14363 4177 4920 14364 4920 4381 14365 4381 4760 14366 4760 4835 14367 4835 4761 14368 4761 4181 14369 4181 4928 14370 4928 4382 14371 4382 4762 14372 4762 4837 14373 4837 4763 14374 4763 4185 14375 4185 4936 14376 4936 4429 14377 4429 4764 14378 4764 4839 14379 4839 4765 14380 4765 4189 14381 4189 4944 14382 4944 4430 14383 4430 4766 14384 4766 4841 14385 4841 4767 14386 4767 4193 14387 4193 4952 14388 4952 4432 14389 4432 4768 14390 4768 4843 14391 4843 4769 14392 4769 4454 14393 4454 4960 14394 4960 4455 14395 4455 4770 14396 4770 4845 14397 4845 4771 14398 4771 4199 14399 4199 4968 14400 4968 4457 14401 4457 4772 14402 4772 4847 14403 4847 4773 14404 4773 4201 14405 4201 4976 14406 4976 4460 14407 4460 4774 14408 4774 4849 14409 4849 4775 14410 4775 4482 14411 4482 4984 14412 4984 4483 14413 4483 4776 14414 4776 4851 14415 4851 4777 14416 4777 4207 14417 4207 4992 14418 4992 4485 14419 4485 4778 14420 4778 4853 14421 4853 4779 14422 4779 4209 14423 4209 5000 14424 5000 4535 14425 4535 4780 14426 4780 4855 14427 4855 4781 14428 4781 4213 14429 4213 5008 14430 5008 4511 14431 4511 4782 14432 4782 4857 14433 4857 4783 14434 4783 4533 14435 4533 5016 14436 5016 4583 14437 4583 4784 14438 4784 4859 14439 4859 4785 14440 4785 4221 14441 4221 5024 14442 5024 4584 14443 4584 4786 14444 4786 4861 14445 4861 4787 14446 4787 4225 14447 4225 5032 14448 5032 4622 14449 4622 4788 14450 4788 4863 14451 4863 4789 14452 4789 4229 14453 4229 5040 14454 5040 4607 14455 4607 4790 14456 4790 4867 14457 4867 4791 14458 4791 4233 14459 4233 5048 14460 5048 4621 14461 4621 4792 14462 4792 4869 14463 4869 4793 14464 4793 4235 14465 4235 5056 14466 5056 4624 14467 4624 4794 14468 4794 4871 14469 4871 4795 14470 4795 4237 14471 4237 5064 14472 5064 4626 14473 4626 4796 14474 4796 4873 14475 4873 4797 14476 4797 4239 14477 4239 5072 14478 5072 4628 14479 4628 4798 14480 4798 4875 14481 4875 4799 14482 4799 4241 14483 4241 5080 14484 5080 4630 14485 4630 4800 14486 4800 4877 14487 4877 4801 14488 4801 4243 14489 4243 5088 14490 5088 4632 14491 4632 4802 14492 4802 4879 14493 4879 4803 14494 4803 4654 14495 4654 5096 14496 5096 4681 14497 4681 4804 14498 4804 4881 14499 4881 4805 14500 4805 4251 14501 4251 5104 14502 5104 4678 14503 4678 4806 14504 4806 4883 14505 4883 4807 14506 4807 4253 14507 4253 5112 14508 5112 4728 14509 4728 4808 14510 4808 4885 14511 4885 4809 14512 4809 4257 14513 4257 5120 14514 5120 4705 14515 4705 4810 14516 4810 4887 14517 4887 4811 14518 4811 4727 14519 4727 5128 14520 5128 4730 14521 4730 4812 14522 4812 4889 14523 4889 4813 14524 4813 4263 14525 4263 5136 14526 5136 4732 14527 4732 4814 14528 4814 4891 14529 4891 4815 14530 4815 4265 14531 4265 5144 14532 5144 4734 14533 4734 4816 14534 4816 4893 14535 4893 4817 14536 4817 4267 14537 4267 5152 14538 5152 4736 14539 4736 4818 14540 4818 4895 14541 4895 4819 14542 4819 4269 14543 4269 5160 14544 5160 4738 14545 4738 4820 14546 4820 4897 14547 4897 4821 14548 4821 4271 14549 4271 5168 14550 5168 4740 14551 4740 4822 14552 4822 4899 14553 4899 4823 14554 4823 4273 14555 4273 5176 14556 5176 4742 14557 4742 4824 14558 4824 4901 14559 4901 4825 14560 4825 4275 14561 4275 5184 14562 5184 4744 14563 4744 4826 14564 4826 5191 14565 5191 3716 14566 3716 4827 14567 4827 5421 14568 5421 4828 14569 4828 4754 14570 4754 4905 14571 4905 4755 14572 4755 4829 14573 4829 4904 14574 4904 4830 14575 4830 4288 14576 4288 4913 14577 4913 4757 14578 4757 4831 14579 4831 4912 14580 4912 4832 14581 4832 4334 14582 4334 4921 14583 4921 4759 14584 4759 4833 14585 4833 4920 14586 4920 4834 14587 4834 4381 14588 4381 4929 14589 4929 4761 14590 4761 4835 14591 4835 4928 14592 4928 4836 14593 4836 4382 14594 4382 4937 14595 4937 4763 14596 4763 4837 14597 4837 4936 14598 4936 4838 14599 4838 4429 14600 4429 4945 14601 4945 4765 14602 4765 4839 14603 4839 4944 14604 4944 4840 14605 4840 4430 14606 4430 4953 14607 4953 4767 14608 4767 4841 14609 4841 4952 14610 4952 4842 14611 4842 4432 14612 4432 4961 14613 4961 4769 14614 4769 4843 14615 4843 4960 14616 4960 4844 14617 4844 4455 14618 4455 4969 14619 4969 4771 14620 4771 4845 14621 4845 4968 14622 4968 4846 14623 4846 4457 14624 4457 4977 14625 4977 4773 14626 4773 4847 14627 4847 4976 14628 4976 4848 14629 4848 4460 14630 4460 4985 14631 4985 4775 14632 4775 4849 14633 4849 4984 14634 4984 4850 14635 4850 4483 14636 4483 4993 14637 4993 4777 14638 4777 4851 14639 4851 4992 14640 4992 4852 14641 4852 4485 14642 4485 5001 14643 5001 4779 14644 4779 4853 14645 4853 5000 14646 5000 4854 14647 4854 4535 14648 4535 5009 14649 5009 4781 14650 4781 4855 14651 4855 5008 14652 5008 4856 14653 4856 4511 14654 4511 5017 14655 5017 4783 14656 4783 4857 14657 4857 5016 14658 5016 4858 14659 4858 4583 14660 4583 5025 14661 5025 4785 14662 4785 4859 14663 4859 5024 14664 5024 4860 14665 4860 4584 14666 4584 5033 14667 5033 4787 14668 4787 4861 14669 4861 5032 14670 5032 4862 14671 4862 4622 14672 4622 5041 14673 5041 4789 14674 4789 4863 14675 4863 5040 14676 5040 4864 14677 4864 4607 14678 4607 5229 14679 5229 4619 14680 4619 4865 14681 4865 5229 14682 5229 4866 14683 4866 4619 14684 4619 5049 14685 5049 4791 14686 4791 4867 14687 4867 5048 14688 5048 4868 14689 4868 4621 14690 4621 5057 14691 5057 4793 14692 4793 4869 14693 4869 5056 14694 5056 4870 14695 4870 4624 14696 4624 5065 14697 5065 4795 14698 4795 4871 14699 4871 5064 14700 5064 4872 14701 4872 4626 14702 4626 5073 14703 5073 4797 14704 4797 4873 14705 4873 5072 14706 5072 4874 14707 4874 4628 14708 4628 5081 14709 5081 4799 14710 4799 4875 14711 4875 5080 14712 5080 4876 14713 4876 4630 14714 4630 5089 14715 5089 4801 14716 4801 4877 14717 4877 5088 14718 5088 4878 14719 4878 4632 14720 4632 5097 14721 5097 4803 14722 4803 4879 14723 4879 5096 14724 5096 4880 14725 4880 4681 14726 4681 5105 14727 5105 4805 14728 4805 4881 14729 4881 5104 14730 5104 4882 14731 4882 4678 14732 4678 5113 14733 5113 4807 14734 4807 4883 14735 4883 5112 14736 5112 4884 14737 4884 4728 14738 4728 5121 14739 5121 4809 14740 4809 4885 14741 4885 5120 14742 5120 4886 14743 4886 4705 14744 4705 5129 14745 5129 4811 14746 4811 4887 14747 4887 5128 14748 5128 4888 14749 4888 4730 14750 4730 5137 14751 5137 4813 14752 4813 4889 14753 4889 5136 14754 5136 4890 14755 4890 4732 14756 4732 5145 14757 5145 4815 14758 4815 4891 14759 4891 5144 14760 5144 4892 14761 4892 4734 14762 4734 5153 14763 5153 4817 14764 4817 4893 14765 4893 5152 14766 5152 4894 14767 4894 4736 14768 4736 5161 14769 5161 4819 14770 4819 4895 14771 4895 5160 14772 5160 4896 14773 4896 4738 14774 4738 5169 14775 5169 4821 14776 4821 4897 14777 4897 5168 14778 5168 4898 14779 4898 4740 14780 4740 5177 14781 5177 4823 14782 4823 4899 14783 4899 5176 14784 5176 4900 14785 4900 4742 14786 4742 5185 14787 5185 4825 14788 4825 4901 14789 4901 5184 14790 5184 4902 14791 4902 4744 14792 4744 4905 14793 4905 4903 14794 4903 4755 14795 4755 4903 14796 4903 4830 14797 4830 4904 14798 4904 4905 14799 4905 4830 14800 4830 4903 14801 4903 4907 14802 4907 4830 14803 4830 4905 14804 4905 4907 14805 4907 4906 14806 4906 4830 14807 4830 4909 14808 4909 4906 14809 4906 4907 14810 4907 4909 14811 4909 4908 14812 4908 4906 14813 4906 5193 14814 5193 4908 14815 4908 4909 14816 4909 5193 14817 5193 4910 14818 4910 4908 14819 4908 4913 14820 4913 4911 14821 4911 4757 14822 4757 4911 14823 4911 4832 14824 4832 4912 14825 4912 4913 14826 4913 4832 14827 4832 4911 14828 4911 4915 14829 4915 4832 14830 4832 4913 14831 4913 4915 14832 4915 4914 14833 4914 4832 14834 4832 4917 14835 4917 4914 14836 4914 4915 14837 4915 4917 14838 4917 4916 14839 4916 4914 14840 4914 5195 14841 5195 4916 14842 4916 4917 14843 4917 5195 14844 5195 4918 14845 4918 4916 14846 4916 4921 14847 4921 4919 14848 4919 4759 14849 4759 4919 14850 4919 4834 14851 4834 4920 14852 4920 4921 14853 4921 4834 14854 4834 4919 14855 4919 4923 14856 4923 4834 14857 4834 4921 14858 4921 4923 14859 4923 4922 14860 4922 4834 14861 4834 4925 14862 4925 4922 14863 4922 4923 14864 4923 4925 14865 4925 4924 14866 4924 4922 14867 4922 5197 14868 5197 4924 14869 4924 4925 14870 4925 5197 14871 5197 4926 14872 4926 4924 14873 4924 4929 14874 4929 4927 14875 4927 4761 14876 4761 4927 14877 4927 4836 14878 4836 4928 14879 4928 4929 14880 4929 4836 14881 4836 4927 14882 4927 4931 14883 4931 4836 14884 4836 4929 14885 4929 4931 14886 4931 4930 14887 4930 4836 14888 4836 4933 14889 4933 4930 14890 4930 4931 14891 4931 4933 14892 4933 4932 14893 4932 4930 14894 4930 5199 14895 5199 4932 14896 4932 4933 14897 4933 5199 14898 5199 4934 14899 4934 4932 14900 4932 4937 14901 4937 4935 14902 4935 4763 14903 4763 4935 14904 4935 4838 14905 4838 4936 14906 4936 4937 14907 4937 4838 14908 4838 4935 14909 4935 4939 14910 4939 4838 14911 4838 4937 14912 4937 4939 14913 4939 4938 14914 4938 4838 14915 4838 4941 14916 4941 4938 14917 4938 4939 14918 4939 4941 14919 4941 4940 14920 4940 4938 14921 4938 5201 14922 5201 4940 14923 4940 4941 14924 4941 5201 14925 5201 4942 14926 4942 4940 14927 4940 4945 14928 4945 4943 14929 4943 4765 14930 4765 4943 14931 4943 4840 14932 4840 4944 14933 4944 4945 14934 4945 4840 14935 4840 4943 14936 4943 4947 14937 4947 4840 14938 4840 4945 14939 4945 4947 14940 4947 4946 14941 4946 4840 14942 4840 4949 14943 4949 4946 14944 4946 4947 14945 4947 4949 14946 4949 4948 14947 4948 4946 14948 4946 5203 14949 5203 4948 14950 4948 4949 14951 4949 5203 14952 5203 4950 14953 4950 4948 14954 4948 4953 14955 4953 4951 14956 4951 4767 14957 4767 4951 14958 4951 4842 14959 4842 4952 14960 4952 4953 14961 4953 4842 14962 4842 4951 14963 4951 4955 14964 4955 4842 14965 4842 4953 14966 4953 4955 14967 4955 4954 14968 4954 4842 14969 4842 4957 14970 4957 4954 14971 4954 4955 14972 4955 4957 14973 4957 4956 14974 4956 4954 14975 4954 5205 14976 5205 4956 14977 4956 4957 14978 4957 5205 14979 5205 4958 14980 4958 4956 14981 4956 4961 14982 4961 4959 14983 4959 4769 14984 4769 4959 14985 4959 4844 14986 4844 4960 14987 4960 4961 14988 4961 4844 14989 4844 4959 14990 4959 4963 14991 4963 4844 14992 4844 4961 14993 4961 4963 14994 4963 4962 14995 4962 4844 14996 4844 4965 14997 4965 4962 14998 4962 4963 14999 4963 4965 15000 4965 4964 15001 4964 4962 15002 4962 5207 15003 5207 4964 15004 4964 4965 15005 4965 5207 15006 5207 4966 15007 4966 4964 15008 4964 4969 15009 4969 4967 15010 4967 4771 15011 4771 4967 15012 4967 4846 15013 4846 4968 15014 4968 4969 15015 4969 4846 15016 4846 4967 15017 4967 4971 15018 4971 4846 15019 4846 4969 15020 4969 4971 15021 4971 4970 15022 4970 4846 15023 4846 4973 15024 4973 4970 15025 4970 4971 15026 4971 4973 15027 4973 4972 15028 4972 4970 15029 4970 5209 15030 5209 4972 15031 4972 4973 15032 4973 5209 15033 5209 4974 15034 4974 4972 15035 4972 4977 15036 4977 4975 15037 4975 4773 15038 4773 4975 15039 4975 4848 15040 4848 4976 15041 4976 4977 15042 4977 4848 15043 4848 4975 15044 4975 4979 15045 4979 4848 15046 4848 4977 15047 4977 4979 15048 4979 4978 15049 4978 4848 15050 4848 4981 15051 4981 4978 15052 4978 4979 15053 4979 4981 15054 4981 4980 15055 4980 4978 15056 4978 5211 15057 5211 4980 15058 4980 4981 15059 4981 5211 15060 5211 4982 15061 4982 4980 15062 4980 4985 15063 4985 4983 15064 4983 4775 15065 4775 4983 15066 4983 4850 15067 4850 4984 15068 4984 4985 15069 4985 4850 15070 4850 4983 15071 4983 4987 15072 4987 4850 15073 4850 4985 15074 4985 4987 15075 4987 4986 15076 4986 4850 15077 4850 4989 15078 4989 4986 15079 4986 4987 15080 4987 4989 15081 4989 4988 15082 4988 4986 15083 4986 5213 15084 5213 4988 15085 4988 4989 15086 4989 5213 15087 5213 4990 15088 4990 4988 15089 4988 4993 15090 4993 4991 15091 4991 4777 15092 4777 4991 15093 4991 4852 15094 4852 4992 15095 4992 4993 15096 4993 4852 15097 4852 4991 15098 4991 4995 15099 4995 4852 15100 4852 4993 15101 4993 4995 15102 4995 4994 15103 4994 4852 15104 4852 4997 15105 4997 4994 15106 4994 4995 15107 4995 4997 15108 4997 4996 15109 4996 4994 15110 4994 5215 15111 5215 4996 15112 4996 4997 15113 4997 5215 15114 5215 4998 15115 4998 4996 15116 4996 5001 15117 5001 4999 15118 4999 4779 15119 4779 4999 15120 4999 4854 15121 4854 5000 15122 5000 5001 15123 5001 4854 15124 4854 4999 15125 4999 5003 15126 5003 4854 15127 4854 5001 15128 5001 5003 15129 5003 5002 15130 5002 4854 15131 4854 5005 15132 5005 5002 15133 5002 5003 15134 5003 5005 15135 5005 5004 15136 5004 5002 15137 5002 5217 15138 5217 5004 15139 5004 5005 15140 5005 5217 15141 5217 5006 15142 5006 5004 15143 5004 5009 15144 5009 5007 15145 5007 4781 15146 4781 5007 15147 5007 4856 15148 4856 5008 15149 5008 5009 15150 5009 4856 15151 4856 5007 15152 5007 5011 15153 5011 4856 15154 4856 5009 15155 5009 5011 15156 5011 5010 15157 5010 4856 15158 4856 5013 15159 5013 5010 15160 5010 5011 15161 5011 5013 15162 5013 5012 15163 5012 5010 15164 5010 5219 15165 5219 5012 15166 5012 5013 15167 5013 5219 15168 5219 5014 15169 5014 5012 15170 5012 5017 15171 5017 5015 15172 5015 4783 15173 4783 5015 15174 5015 4858 15175 4858 5016 15176 5016 5017 15177 5017 4858 15178 4858 5015 15179 5015 5019 15180 5019 4858 15181 4858 5017 15182 5017 5019 15183 5019 5018 15184 5018 4858 15185 4858 5021 15186 5021 5018 15187 5018 5019 15188 5019 5021 15189 5021 5020 15190 5020 5018 15191 5018 5221 15192 5221 5020 15193 5020 5021 15194 5021 5221 15195 5221 5022 15196 5022 5020 15197 5020 5025 15198 5025 5023 15199 5023 4785 15200 4785 5023 15201 5023 4860 15202 4860 5024 15203 5024 5025 15204 5025 4860 15205 4860 5023 15206 5023 5027 15207 5027 4860 15208 4860 5025 15209 5025 5027 15210 5027 5026 15211 5026 4860 15212 4860 5029 15213 5029 5026 15214 5026 5027 15215 5027 5029 15216 5029 5028 15217 5028 5026 15218 5026 5223 15219 5223 5028 15220 5028 5029 15221 5029 5223 15222 5223 5030 15223 5030 5028 15224 5028 5033 15225 5033 5031 15226 5031 4787 15227 4787 5031 15228 5031 4862 15229 4862 5032 15230 5032 5033 15231 5033 4862 15232 4862 5031 15233 5031 5035 15234 5035 4862 15235 4862 5033 15236 5033 5035 15237 5035 5034 15238 5034 4862 15239 4862 5037 15240 5037 5034 15241 5034 5035 15242 5035 5037 15243 5037 5036 15244 5036 5034 15245 5034 5225 15246 5225 5036 15247 5036 5037 15248 5037 5225 15249 5225 5038 15250 5038 5036 15251 5036 5041 15252 5041 5039 15253 5039 4789 15254 4789 5039 15255 5039 4864 15256 4864 5040 15257 5040 5041 15258 5041 4864 15259 4864 5039 15260 5039 5043 15261 5043 4864 15262 4864 5041 15263 5041 5043 15264 5043 5042 15265 5042 4864 15266 4864 5045 15267 5045 5042 15268 5042 5043 15269 5043 5045 15270 5045 5044 15271 5044 5042 15272 5042 5227 15273 5227 5044 15274 5044 5045 15275 5045 5227 15276 5227 5046 15277 5046 5044 15278 5044 5049 15279 5049 5047 15280 5047 4791 15281 4791 5047 15282 5047 4868 15283 4868 5048 15284 5048 5049 15285 5049 4868 15286 4868 5047 15287 5047 5051 15288 5051 4868 15289 4868 5049 15290 5049 5051 15291 5051 5050 15292 5050 4868 15293 4868 5053 15294 5053 5050 15295 5050 5051 15296 5051 5053 15297 5053 5052 15298 5052 5050 15299 5050 5231 15300 5231 5052 15301 5052 5053 15302 5053 5231 15303 5231 5054 15304 5054 5052 15305 5052 5057 15306 5057 5055 15307 5055 4793 15308 4793 5055 15309 5055 4870 15310 4870 5056 15311 5056 5057 15312 5057 4870 15313 4870 5055 15314 5055 5059 15315 5059 4870 15316 4870 5057 15317 5057 5059 15318 5059 5058 15319 5058 4870 15320 4870 5061 15321 5061 5058 15322 5058 5059 15323 5059 5061 15324 5061 5060 15325 5060 5058 15326 5058 5233 15327 5233 5060 15328 5060 5061 15329 5061 5233 15330 5233 5062 15331 5062 5060 15332 5060 5065 15333 5065 5063 15334 5063 4795 15335 4795 5063 15336 5063 4872 15337 4872 5064 15338 5064 5065 15339 5065 4872 15340 4872 5063 15341 5063 5067 15342 5067 4872 15343 4872 5065 15344 5065 5067 15345 5067 5066 15346 5066 4872 15347 4872 5069 15348 5069 5066 15349 5066 5067 15350 5067 5069 15351 5069 5068 15352 5068 5066 15353 5066 5235 15354 5235 5068 15355 5068 5069 15356 5069 5235 15357 5235 5070 15358 5070 5068 15359 5068 5073 15360 5073 5071 15361 5071 4797 15362 4797 5071 15363 5071 4874 15364 4874 5072 15365 5072 5073 15366 5073 4874 15367 4874 5071 15368 5071 5075 15369 5075 4874 15370 4874 5073 15371 5073 5075 15372 5075 5074 15373 5074 4874 15374 4874 5077 15375 5077 5074 15376 5074 5075 15377 5075 5077 15378 5077 5076 15379 5076 5074 15380 5074 5237 15381 5237 5076 15382 5076 5077 15383 5077 5237 15384 5237 5078 15385 5078 5076 15386 5076 5081 15387 5081 5079 15388 5079 4799 15389 4799 5079 15390 5079 4876 15391 4876 5080 15392 5080 5081 15393 5081 4876 15394 4876 5079 15395 5079 5083 15396 5083 4876 15397 4876 5081 15398 5081 5083 15399 5083 5082 15400 5082 4876 15401 4876 5085 15402 5085 5082 15403 5082 5083 15404 5083 5085 15405 5085 5084 15406 5084 5082 15407 5082 5239 15408 5239 5084 15409 5084 5085 15410 5085 5239 15411 5239 5086 15412 5086 5084 15413 5084 5089 15414 5089 5087 15415 5087 4801 15416 4801 5087 15417 5087 4878 15418 4878 5088 15419 5088 5089 15420 5089 4878 15421 4878 5087 15422 5087 5091 15423 5091 4878 15424 4878 5089 15425 5089 5091 15426 5091 5090 15427 5090 4878 15428 4878 5093 15429 5093 5090 15430 5090 5091 15431 5091 5093 15432 5093 5092 15433 5092 5090 15434 5090 5241 15435 5241 5092 15436 5092 5093 15437 5093 5241 15438 5241 5094 15439 5094 5092 15440 5092 5097 15441 5097 5095 15442 5095 4803 15443 4803 5095 15444 5095 4880 15445 4880 5096 15446 5096 5097 15447 5097 4880 15448 4880 5095 15449 5095 5099 15450 5099 4880 15451 4880 5097 15452 5097 5099 15453 5099 5098 15454 5098 4880 15455 4880 5101 15456 5101 5098 15457 5098 5099 15458 5099 5101 15459 5101 5100 15460 5100 5098 15461 5098 5243 15462 5243 5100 15463 5100 5101 15464 5101 5243 15465 5243 5102 15466 5102 5100 15467 5100 5105 15468 5105 5103 15469 5103 4805 15470 4805 5103 15471 5103 4882 15472 4882 5104 15473 5104 5105 15474 5105 4882 15475 4882 5103 15476 5103 5107 15477 5107 4882 15478 4882 5105 15479 5105 5107 15480 5107 5106 15481 5106 4882 15482 4882 5109 15483 5109 5106 15484 5106 5107 15485 5107 5109 15486 5109 5108 15487 5108 5106 15488 5106 5245 15489 5245 5108 15490 5108 5109 15491 5109 5245 15492 5245 5110 15493 5110 5108 15494 5108 5113 15495 5113 5111 15496 5111 4807 15497 4807 5111 15498 5111 4884 15499 4884 5112 15500 5112 5113 15501 5113 4884 15502 4884 5111 15503 5111 5115 15504 5115 4884 15505 4884 5113 15506 5113 5115 15507 5115 5114 15508 5114 4884 15509 4884 5117 15510 5117 5114 15511 5114 5115 15512 5115 5117 15513 5117 5116 15514 5116 5114 15515 5114 5247 15516 5247 5116 15517 5116 5117 15518 5117 5247 15519 5247 5118 15520 5118 5116 15521 5116 5121 15522 5121 5119 15523 5119 4809 15524 4809 5119 15525 5119 4886 15526 4886 5120 15527 5120 5121 15528 5121 4886 15529 4886 5119 15530 5119 5123 15531 5123 4886 15532 4886 5121 15533 5121 5123 15534 5123 5122 15535 5122 4886 15536 4886 5125 15537 5125 5122 15538 5122 5123 15539 5123 5125 15540 5125 5124 15541 5124 5122 15542 5122 5249 15543 5249 5124 15544 5124 5125 15545 5125 5249 15546 5249 5126 15547 5126 5124 15548 5124 5129 15549 5129 5127 15550 5127 4811 15551 4811 5127 15552 5127 4888 15553 4888 5128 15554 5128 5129 15555 5129 4888 15556 4888 5127 15557 5127 5131 15558 5131 4888 15559 4888 5129 15560 5129 5131 15561 5131 5130 15562 5130 4888 15563 4888 5133 15564 5133 5130 15565 5130 5131 15566 5131 5133 15567 5133 5132 15568 5132 5130 15569 5130 5251 15570 5251 5132 15571 5132 5133 15572 5133 5251 15573 5251 5134 15574 5134 5132 15575 5132 5137 15576 5137 5135 15577 5135 4813 15578 4813 5135 15579 5135 4890 15580 4890 5136 15581 5136 5137 15582 5137 4890 15583 4890 5135 15584 5135 5139 15585 5139 4890 15586 4890 5137 15587 5137 5139 15588 5139 5138 15589 5138 4890 15590 4890 5141 15591 5141 5138 15592 5138 5139 15593 5139 5141 15594 5141 5140 15595 5140 5138 15596 5138 5253 15597 5253 5140 15598 5140 5141 15599 5141 5253 15600 5253 5142 15601 5142 5140 15602 5140 5145 15603 5145 5143 15604 5143 4815 15605 4815 5143 15606 5143 4892 15607 4892 5144 15608 5144 5145 15609 5145 4892 15610 4892 5143 15611 5143 5147 15612 5147 4892 15613 4892 5145 15614 5145 5147 15615 5147 5146 15616 5146 4892 15617 4892 5149 15618 5149 5146 15619 5146 5147 15620 5147 5149 15621 5149 5148 15622 5148 5146 15623 5146 5255 15624 5255 5148 15625 5148 5149 15626 5149 5255 15627 5255 5150 15628 5150 5148 15629 5148 5153 15630 5153 5151 15631 5151 4817 15632 4817 5151 15633 5151 4894 15634 4894 5152 15635 5152 5153 15636 5153 4894 15637 4894 5151 15638 5151 5155 15639 5155 4894 15640 4894 5153 15641 5153 5155 15642 5155 5154 15643 5154 4894 15644 4894 5157 15645 5157 5154 15646 5154 5155 15647 5155 5157 15648 5157 5156 15649 5156 5154 15650 5154 5257 15651 5257 5156 15652 5156 5157 15653 5157 5257 15654 5257 5158 15655 5158 5156 15656 5156 5161 15657 5161 5159 15658 5159 4819 15659 4819 5159 15660 5159 4896 15661 4896 5160 15662 5160 5161 15663 5161 4896 15664 4896 5159 15665 5159 5163 15666 5163 4896 15667 4896 5161 15668 5161 5163 15669 5163 5162 15670 5162 4896 15671 4896 5165 15672 5165 5162 15673 5162 5163 15674 5163 5165 15675 5165 5164 15676 5164 5162 15677 5162 5259 15678 5259 5164 15679 5164 5165 15680 5165 5259 15681 5259 5166 15682 5166 5164 15683 5164 5169 15684 5169 5167 15685 5167 4821 15686 4821 5167 15687 5167 4898 15688 4898 5168 15689 5168 5169 15690 5169 4898 15691 4898 5167 15692 5167 5171 15693 5171 4898 15694 4898 5169 15695 5169 5171 15696 5171 5170 15697 5170 4898 15698 4898 5173 15699 5173 5170 15700 5170 5171 15701 5171 5173 15702 5173 5172 15703 5172 5170 15704 5170 5261 15705 5261 5172 15706 5172 5173 15707 5173 5261 15708 5261 5174 15709 5174 5172 15710 5172 5177 15711 5177 5175 15712 5175 4823 15713 4823 5175 15714 5175 4900 15715 4900 5176 15716 5176 5177 15717 5177 4900 15718 4900 5175 15719 5175 5179 15720 5179 4900 15721 4900 5177 15722 5177 5179 15723 5179 5178 15724 5178 4900 15725 4900 5181 15726 5181 5178 15727 5178 5179 15728 5179 5181 15729 5181 5180 15730 5180 5178 15731 5178 5263 15732 5263 5180 15733 5180 5181 15734 5181 5263 15735 5263 5182 15736 5182 5180 15737 5180 5185 15738 5185 5183 15739 5183 4825 15740 4825 5183 15741 5183 4902 15742 4902 5184 15743 5184 5185 15744 5185 4902 15745 4902 5183 15746 5183 5187 15747 5187 4902 15748 4902 5185 15749 5185 5187 15750 5187 5186 15751 5186 4902 15752 4902 5189 15753 5189 5186 15754 5186 5187 15755 5187 5189 15756 5189 5188 15757 5188 5186 15758 5186 5265 15759 5265 5188 15760 5188 5189 15761 5189 5265 15762 5265 5190 15763 5190 5188 15764 5188 5267 15765 5267 3716 15766 3716 5191 15767 5191 5421 15768 5421 5192 15769 5192 4828 15770 4828 5269 15771 5269 4910 15772 4910 5193 15773 5193 5269 15774 5269 5194 15775 5194 4910 15776 4910 5271 15777 5271 4918 15778 4918 5195 15779 5195 5271 15780 5271 5196 15781 5196 4918 15782 4918 5273 15783 5273 4926 15784 4926 5197 15785 5197 5273 15786 5273 5198 15787 5198 4926 15788 4926 5275 15789 5275 4934 15790 4934 5199 15791 5199 5275 15792 5275 5200 15793 5200 4934 15794 4934 5277 15795 5277 4942 15796 4942 5201 15797 5201 5277 15798 5277 5202 15799 5202 4942 15800 4942 5279 15801 5279 4950 15802 4950 5203 15803 5203 5279 15804 5279 5204 15805 5204 4950 15806 4950 5281 15807 5281 4958 15808 4958 5205 15809 5205 5281 15810 5281 5206 15811 5206 4958 15812 4958 5283 15813 5283 4966 15814 4966 5207 15815 5207 5283 15816 5283 5208 15817 5208 4966 15818 4966 5285 15819 5285 4974 15820 4974 5209 15821 5209 5285 15822 5285 5210 15823 5210 4974 15824 4974 5287 15825 5287 4982 15826 4982 5211 15827 5211 5287 15828 5287 5212 15829 5212 4982 15830 4982 5289 15831 5289 4990 15832 4990 5213 15833 5213 5289 15834 5289 5214 15835 5214 4990 15836 4990 5291 15837 5291 4998 15838 4998 5215 15839 5215 5291 15840 5291 5216 15841 5216 4998 15842 4998 5293 15843 5293 5006 15844 5006 5217 15845 5217 5293 15846 5293 5218 15847 5218 5006 15848 5006 5295 15849 5295 5014 15850 5014 5219 15851 5219 5295 15852 5295 5220 15853 5220 5014 15854 5014 5297 15855 5297 5022 15856 5022 5221 15857 5221 5297 15858 5297 5222 15859 5222 5022 15860 5022 5299 15861 5299 5030 15862 5030 5223 15863 5223 5299 15864 5299 5224 15865 5224 5030 15866 5030 5301 15867 5301 5038 15868 5038 5225 15869 5225 5301 15870 5301 5226 15871 5226 5038 15872 5038 5303 15873 5303 5046 15874 5046 5227 15875 5227 5303 15876 5303 5228 15877 5228 5046 15878 5046 5305 15879 5305 4866 15880 4866 5229 15881 5229 5305 15882 5305 5230 15883 5230 4866 15884 4866 5307 15885 5307 5054 15886 5054 5231 15887 5231 5307 15888 5307 5232 15889 5232 5054 15890 5054 5309 15891 5309 5062 15892 5062 5233 15893 5233 5309 15894 5309 5234 15895 5234 5062 15896 5062 5311 15897 5311 5070 15898 5070 5235 15899 5235 5311 15900 5311 5236 15901 5236 5070 15902 5070 5313 15903 5313 5078 15904 5078 5237 15905 5237 5313 15906 5313 5238 15907 5238 5078 15908 5078 5315 15909 5315 5086 15910 5086 5239 15911 5239 5315 15912 5315 5240 15913 5240 5086 15914 5086 5317 15915 5317 5094 15916 5094 5241 15917 5241 5317 15918 5317 5242 15919 5242 5094 15920 5094 5319 15921 5319 5102 15922 5102 5243 15923 5243 5319 15924 5319 5244 15925 5244 5102 15926 5102 5321 15927 5321 5110 15928 5110 5245 15929 5245 5321 15930 5321 5246 15931 5246 5110 15932 5110 5323 15933 5323 5118 15934 5118 5247 15935 5247 5323 15936 5323 5248 15937 5248 5118 15938 5118 5325 15939 5325 5126 15940 5126 5249 15941 5249 5325 15942 5325 5250 15943 5250 5126 15944 5126 5327 15945 5327 5134 15946 5134 5251 15947 5251 5327 15948 5327 5252 15949 5252 5134 15950 5134 5329 15951 5329 5142 15952 5142 5253 15953 5253 5329 15954 5329 5254 15955 5254 5142 15956 5142 5331 15957 5331 5150 15958 5150 5255 15959 5255 5331 15960 5331 5256 15961 5256 5150 15962 5150 5333 15963 5333 5158 15964 5158 5257 15965 5257 5333 15966 5333 5258 15967 5258 5158 15968 5158 5335 15969 5335 5166 15970 5166 5259 15971 5259 5335 15972 5335 5260 15973 5260 5166 15974 5166 5337 15975 5337 5174 15976 5174 5261 15977 5261 5337 15978 5337 5262 15979 5262 5174 15980 5174 5339 15981 5339 5182 15982 5182 5263 15983 5263 5339 15984 5339 5264 15985 5264 5182 15986 5182 5341 15987 5341 5190 15988 5190 5265 15989 5265 5341 15990 5341 5266 15991 5266 5190 15992 5190 5417 15993 5417 3716 15994 3716 5267 15995 5267 5421 15996 5421 5268 15997 5268 5192 15998 5192 5343 15999 5343 5194 16000 5194 5269 16001 5269 5343 16002 5343 5270 16003 5270 5194 16004 5194 5344 16005 5344 5196 16006 5196 5271 16007 5271 5344 16008 5344 5272 16009 5272 5196 16010 5196 5345 16011 5345 5198 16012 5198 5273 16013 5273 5345 16014 5345 5274 16015 5274 5198 16016 5198 5346 16017 5346 5200 16018 5200 5275 16019 5275 5346 16020 5346 5276 16021 5276 5200 16022 5200 5347 16023 5347 5202 16024 5202 5277 16025 5277 5347 16026 5347 5278 16027 5278 5202 16028 5202 5353 16029 5353 5204 16030 5204 5279 16031 5279 5353 16032 5353 5280 16033 5280 5204 16034 5204 5354 16035 5354 5206 16036 5206 5281 16037 5281 5354 16038 5354 5282 16039 5282 5206 16040 5206 5355 16041 5355 5208 16042 5208 5283 16043 5283 5355 16044 5355 5284 16045 5284 5208 16046 5208 5359 16047 5359 5210 16048 5210 5285 16049 5285 5359 16050 5359 5286 16051 5286 5210 16052 5210 5360 16053 5360 5212 16054 5212 5287 16055 5287 5360 16056 5360 5288 16057 5288 5212 16058 5212 5361 16059 5361 5214 16060 5214 5289 16061 5289 5361 16062 5361 5290 16063 5290 5214 16064 5214 5362 16065 5362 5216 16066 5216 5291 16067 5291 5362 16068 5362 5292 16069 5292 5216 16070 5216 5367 16071 5367 5218 16072 5218 5293 16073 5293 5367 16074 5367 5294 16075 5294 5218 16076 5218 5368 16077 5368 5220 16078 5220 5295 16079 5295 5368 16080 5368 5296 16081 5296 5220 16082 5220 5369 16083 5369 5222 16084 5222 5297 16085 5297 5369 16086 5369 5298 16087 5298 5222 16088 5222 5373 16089 5373 5224 16090 5224 5299 16091 5299 5373 16092 5373 5300 16093 5300 5224 16094 5224 5374 16095 5374 5226 16096 5226 5301 16097 5301 5374 16098 5374 5302 16099 5302 5226 16100 5226 5375 16101 5375 5228 16102 5228 5303 16103 5303 5375 16104 5375 5304 16105 5304 5228 16106 5228 5376 16107 5376 5230 16108 5230 5305 16109 5305 5376 16110 5376 5306 16111 5306 5230 16112 5230 5381 16113 5381 5232 16114 5232 5307 16115 5307 5381 16116 5381 5308 16117 5308 5232 16118 5232 5382 16119 5382 5234 16120 5234 5309 16121 5309 5382 16122 5382 5310 16123 5310 5234 16124 5234 5383 16125 5383 5236 16126 5236 5311 16127 5311 5383 16128 5383 5312 16129 5312 5236 16130 5236 5387 16131 5387 5238 16132 5238 5313 16133 5313 5387 16134 5387 5314 16135 5314 5238 16136 5238 5388 16137 5388 5240 16138 5240 5315 16139 5315 5388 16140 5388 5316 16141 5316 5240 16142 5240 5389 16143 5389 5242 16144 5242 5317 16145 5317 5389 16146 5389 5318 16147 5318 5242 16148 5242 5390 16149 5390 5244 16150 5244 5319 16151 5319 5390 16152 5390 5320 16153 5320 5244 16154 5244 5395 16155 5395 5246 16156 5246 5321 16157 5321 5395 16158 5395 5322 16159 5322 5246 16160 5246 5396 16161 5396 5248 16162 5248 5323 16163 5323 5396 16164 5396 5324 16165 5324 5248 16166 5248 5397 16167 5397 5250 16168 5250 5325 16169 5325 5397 16170 5397 5326 16171 5326 5250 16172 5250 5401 16173 5401 5252 16174 5252 5327 16175 5327 5401 16176 5401 5328 16177 5328 5252 16178 5252 5402 16179 5402 5254 16180 5254 5329 16181 5329 5402 16182 5402 5330 16183 5330 5254 16184 5254 5403 16185 5403 5256 16186 5256 5331 16187 5331 5403 16188 5403 5332 16189 5332 5256 16190 5256 5404 16191 5404 5258 16192 5258 5333 16193 5333 5404 16194 5404 5334 16195 5334 5258 16196 5258 5409 16197 5409 5260 16198 5260 5335 16199 5335 5409 16200 5409 5336 16201 5336 5260 16202 5260 5410 16203 5410 5262 16204 5262 5337 16205 5337 5410 16206 5410 5338 16207 5338 5262 16208 5262 5411 16209 5411 5264 16210 5264 5339 16211 5339 5411 16212 5411 5340 16213 5340 5264 16214 5264 5415 16215 5415 5266 16216 5266 5341 16217 5341 5415 16218 5415 5342 16219 5342 5266 16220 5266 5422 16221 5422 5270 16222 5270 5343 16223 5343 5424 16224 5424 5272 16225 5272 5344 16226 5344 5426 16227 5426 5274 16228 5274 5345 16229 5345 5428 16230 5428 5276 16231 5276 5346 16232 5346 5430 16233 5430 5278 16234 5278 5347 16235 5347 5422 16236 5422 5348 16237 5348 5270 16238 5270 5424 16239 5424 5349 16240 5349 5272 16241 5272 5426 16242 5426 5350 16243 5350 5274 16244 5274 5428 16245 5428 5351 16246 5351 5276 16247 5276 5430 16248 5430 5352 16249 5352 5278 16250 5278 5432 16251 5432 5280 16252 5280 5353 16253 5353 5434 16254 5434 5282 16255 5282 5354 16256 5354 5436 16257 5436 5284 16258 5284 5355 16259 5355 5432 16260 5432 5356 16261 5356 5280 16262 5280 5434 16263 5434 5357 16264 5357 5282 16265 5282 5436 16266 5436 5358 16267 5358 5284 16268 5284 5438 16269 5438 5286 16270 5286 5359 16271 5359 5440 16272 5440 5288 16273 5288 5360 16274 5360 5442 16275 5442 5290 16276 5290 5361 16277 5361 5444 16278 5444 5292 16279 5292 5362 16280 5362 5438 16281 5438 5363 16282 5363 5286 16283 5286 5440 16284 5440 5364 16285 5364 5288 16286 5288 5442 16287 5442 5365 16288 5365 5290 16289 5290 5444 16290 5444 5366 16291 5366 5292 16292 5292 5446 16293 5446 5294 16294 5294 5367 16295 5367 5448 16296 5448 5296 16297 5296 5368 16298 5368 5450 16299 5450 5298 16300 5298 5369 16301 5369 5446 16302 5446 5370 16303 5370 5294 16304 5294 5448 16305 5448 5371 16306 5371 5296 16307 5296 5450 16308 5450 5372 16309 5372 5298 16310 5298 5452 16311 5452 5300 16312 5300 5373 16313 5373 5454 16314 5454 5302 16315 5302 5374 16316 5374 5456 16317 5456 5304 16318 5304 5375 16319 5375 5467 16320 5467 5306 16321 5306 5376 16322 5376 5452 16323 5452 5377 16324 5377 5300 16325 5300 5454 16326 5454 5378 16327 5378 5302 16328 5302 5456 16329 5456 5379 16330 5379 5304 16331 5304 5467 16332 5467 5380 16333 5380 5306 16334 5306 5477 16335 5477 5308 16336 5308 5381 16337 5381 5479 16338 5479 5310 16339 5310 5382 16340 5382 5481 16341 5481 5312 16342 5312 5383 16343 5383 5477 16344 5477 5384 16345 5384 5308 16346 5308 5479 16347 5479 5385 16348 5385 5310 16349 5310 5481 16350 5481 5386 16351 5386 5312 16352 5312 5482 16353 5482 5314 16354 5314 5387 16355 5387 5483 16356 5483 5316 16357 5316 5388 16358 5388 5484 16359 5484 5318 16360 5318 5389 16361 5389 5485 16362 5485 5320 16363 5320 5390 16364 5390 5482 16365 5482 5391 16366 5391 5314 16367 5314 5483 16368 5483 5392 16369 5392 5316 16370 5316 5484 16371 5484 5393 16372 5393 5318 16373 5318 5485 16374 5485 5394 16375 5394 5320 16376 5320 5491 16377 5491 5322 16378 5322 5395 16379 5395 5492 16380 5492 5324 16381 5324 5396 16382 5396 5493 16383 5493 5326 16384 5326 5397 16385 5397 5491 16386 5491 5398 16387 5398 5322 16388 5322 5492 16389 5492 5399 16390 5399 5324 16391 5324 5493 16392 5493 5400 16393 5400 5326 16394 5326 5497 16395 5497 5328 16396 5328 5401 16397 5401 5498 16398 5498 5330 16399 5330 5402 16400 5402 5499 16401 5499 5332 16402 5332 5403 16403 5403 5500 16404 5500 5334 16405 5334 5404 16406 5404 5497 16407 5497 5405 16408 5405 5328 16409 5328 5498 16410 5498 5406 16411 5406 5330 16412 5330 5499 16413 5499 5407 16414 5407 5332 16415 5332 5500 16416 5500 5408 16417 5408 5334 16418 5334 5505 16419 5505 5336 16420 5336 5409 16421 5409 5506 16422 5506 5338 16423 5338 5410 16424 5410 5507 16425 5507 5340 16426 5340 5411 16427 5411 5505 16428 5505 5412 16429 5412 5336 16430 5336 5506 16431 5506 5413 16432 5413 5338 16433 5338 5507 16434 5507 5414 16435 5414 5340 16436 5340 5511 16437 5511 5342 16438 5342 5415 16439 5415 5511 16440 5511 5416 16441 5416 5342 16442 5342 5419 16443 5419 3716 16444 3716 5417 16445 5417 5419 16446 5419 5418 16447 5418 3716 16448 3716 5416 16449 5416 5418 16450 5418 5419 16451 5419 5421 16452 5421 5420 16453 5420 5268 16454 5268 5463 16455 5463 5420 16456 5420 5421 16457 5421 5463 16458 5463 5422 16459 5422 5420 16460 5420 5422 16461 5422 5423 16462 5423 5348 16463 5348 5463 16464 5463 5423 16465 5423 5422 16466 5422 5463 16467 5463 5424 16468 5424 5423 16469 5423 5424 16470 5424 5425 16471 5425 5349 16472 5349 5463 16473 5463 5425 16474 5425 5424 16475 5424 5463 16476 5463 5426 16477 5426 5425 16478 5425 5426 16479 5426 5427 16480 5427 5350 16481 5350 5463 16482 5463 5427 16483 5427 5426 16484 5426 5463 16485 5463 5428 16486 5428 5427 16487 5427 5428 16488 5428 5429 16489 5429 5351 16490 5351 5463 16491 5463 5429 16492 5429 5428 16493 5428 5463 16494 5463 5430 16495 5430 5429 16496 5429 5430 16497 5430 5431 16498 5431 5352 16499 5352 5463 16500 5463 5431 16501 5431 5430 16502 5430 5463 16503 5463 5432 16504 5432 5431 16505 5431 5432 16506 5432 5433 16507 5433 5356 16508 5356 5463 16509 5463 5433 16510 5433 5432 16511 5432 5463 16512 5463 5434 16513 5434 5433 16514 5433 5434 16515 5434 5435 16516 5435 5357 16517 5357 5463 16518 5463 5435 16519 5435 5434 16520 5434 5463 16521 5463 5436 16522 5436 5435 16523 5435 5436 16524 5436 5437 16525 5437 5358 16526 5358 5463 16527 5463 5437 16528 5437 5436 16529 5436 5463 16530 5463 5438 16531 5438 5437 16532 5437 5438 16533 5438 5439 16534 5439 5363 16535 5363 5463 16536 5463 5439 16537 5439 5438 16538 5438 5463 16539 5463 5440 16540 5440 5439 16541 5439 5440 16542 5440 5441 16543 5441 5364 16544 5364 5463 16545 5463 5441 16546 5441 5440 16547 5440 5463 16548 5463 5442 16549 5442 5441 16550 5441 5442 16551 5442 5443 16552 5443 5365 16553 5365 5463 16554 5463 5443 16555 5443 5442 16556 5442 5463 16557 5463 5444 16558 5444 5443 16559 5443 5444 16560 5444 5445 16561 5445 5366 16562 5366 5463 16563 5463 5445 16564 5445 5444 16565 5444 5463 16566 5463 5446 16567 5446 5445 16568 5445 5446 16569 5446 5447 16570 5447 5370 16571 5370 5463 16572 5463 5447 16573 5447 5446 16574 5446 5463 16575 5463 5448 16576 5448 5447 16577 5447 5448 16578 5448 5449 16579 5449 5371 16580 5371 5463 16581 5463 5449 16582 5449 5448 16583 5448 5463 16584 5463 5450 16585 5450 5449 16586 5449 5450 16587 5450 5451 16588 5451 5372 16589 5372 5463 16590 5463 5451 16591 5451 5450 16592 5450 5463 16593 5463 5452 16594 5452 5451 16595 5451 5452 16596 5452 5453 16597 5453 5377 16598 5377 5463 16599 5463 5453 16600 5453 5452 16601 5452 5463 16602 5463 5454 16603 5454 5453 16604 5453 5454 16605 5454 5455 16606 5455 5378 16607 5378 5463 16608 5463 5455 16609 5455 5454 16610 5454 5463 16611 5463 5456 16612 5456 5455 16613 5455 5463 16614 5463 5379 16615 5379 5456 16616 5456 5463 16617 5463 5457 16618 5457 5379 16619 5379 5463 16620 5463 5458 16621 5458 5457 16622 5457 5463 16623 5463 5459 16624 5459 5458 16625 5458 5463 16626 5463 5460 16627 5460 5459 16628 5459 5463 16629 5463 5461 16630 5461 5460 16631 5460 5463 16632 5463 5462 16633 5462 5461 16634 5461 5418 16635 5418 5462 16636 5462 5463 16637 5463 5418 16638 5418 5464 16639 5464 5462 16640 5462 5418 16641 5418 5465 16642 5465 5464 16643 5464 5418 16644 5418 5466 16645 5466 5465 16646 5465 5418 16647 5418 5467 16648 5467 5466 16649 5466 5418 16650 5418 5380 16651 5380 5467 16652 5467 5418 16653 5418 5468 16654 5468 5380 16655 5380 5418 16656 5418 5469 16657 5469 5468 16658 5468 5418 16659 5418 5470 16660 5470 5469 16661 5469 5418 16662 5418 5471 16663 5471 5470 16664 5470 5418 16665 5418 5472 16666 5472 5471 16667 5471 5418 16668 5418 5473 16669 5473 5472 16670 5472 5418 16671 5418 5474 16672 5474 5473 16673 5473 5418 16674 5418 5475 16675 5475 5474 16676 5474 5418 16677 5418 5476 16678 5476 5475 16679 5475 5476 16680 5476 5384 16681 5384 5477 16682 5477 5418 16683 5418 5384 16684 5384 5476 16685 5476 5418 16686 5418 5478 16687 5478 5384 16688 5384 5478 16689 5478 5385 16690 5385 5479 16691 5479 5478 16692 5478 5480 16693 5480 5385 16694 5385 5480 16695 5480 5386 16696 5386 5481 16697 5481 5486 16698 5486 5391 16699 5391 5482 16700 5482 5487 16701 5487 5392 16702 5392 5483 16703 5483 5488 16704 5488 5393 16705 5393 5484 16706 5484 5489 16707 5489 5394 16708 5394 5485 16709 5485 5480 16710 5480 5486 16711 5486 5386 16712 5386 5486 16713 5486 5487 16714 5487 5391 16715 5391 5487 16716 5487 5488 16717 5488 5392 16718 5392 5488 16719 5488 5489 16720 5489 5393 16721 5393 5489 16722 5489 5490 16723 5490 5394 16724 5394 5490 16725 5490 5398 16726 5398 5491 16727 5491 5494 16728 5494 5399 16729 5399 5492 16730 5492 5495 16731 5495 5400 16732 5400 5493 16733 5493 5490 16734 5490 5494 16735 5494 5398 16736 5398 5494 16737 5494 5495 16738 5495 5399 16739 5399 5495 16740 5495 5496 16741 5496 5400 16742 5400 5496 16743 5496 5405 16744 5405 5497 16745 5497 5501 16746 5501 5406 16747 5406 5498 16748 5498 5502 16749 5502 5407 16750 5407 5499 16751 5499 5503 16752 5503 5408 16753 5408 5500 16754 5500 5496 16755 5496 5501 16756 5501 5405 16757 5405 5501 16758 5501 5502 16759 5502 5406 16760 5406 5502 16761 5502 5503 16762 5503 5407 16763 5407 5503 16764 5503 5504 16765 5504 5408 16766 5408 5504 16767 5504 5412 16768 5412 5505 16769 5505 5508 16770 5508 5413 16771 5413 5506 16772 5506 5509 16773 5509 5414 16774 5414 5507 16775 5507 5504 16776 5504 5508 16777 5508 5412 16778 5412 5508 16779 5508 5509 16780 5509 5413 16781 5413 5509 16782 5509 5510 16783 5510 5414 16784 5414 5510 16785 5510 5416 16786 5416 5511 16787 5511 5510 16788 5510 5418 16789 5418 5416 16790 5416 5509 16791 5509 5418 16792 5418 5510 16793 5510 5508 16794 5508 5418 16795 5418 5509 16796 5509 5504 16797 5504 5418 16798 5418 5508 16799 5508 5503 16800 5503 5418 16801 5418 5504 16802 5504 5502 16803 5502 5418 16804 5418 5503 16805 5503 5501 16806 5501 5418 16807 5418 5502 16808 5502 5496 16809 5496 5418 16810 5418 5501 16811 5501 5495 16812 5495 5418 16813 5418 5496 16814 5496 5494 16815 5494 5418 16816 5418 5495 16817 5495 5490 16818 5490 5418 16819 5418 5494 16820 5494 5489 16821 5489 5418 16822 5418 5490 16823 5490 5488 16824 5488 5418 16825 5418 5489 16826 5489 5487 16827 5487 5418 16828 5418 5488 16829 5488 5486 16830 5486 5418 16831 5418 5487 16832 5487 5480 16833 5480 5418 16834 5418 5486 16835 5486 5543 16836 5543 5515 16837 5515 5512 16838 5512 5512 16839 5512 5513 16840 5513 5514 16841 5514 5512 16842 5512 5515 16843 5515 5513 16844 5513 5520 16845 5520 5516 16846 5516 5517 16847 5517 5520 16848 5520 5518 16849 5518 5516 16850 5516 5520 16851 5520 5519 16852 5519 5518 16853 5518 5522 16854 5522 5519 16855 5519 5520 16856 5520 5522 16857 5522 5521 16858 5521 5519 16859 5519 5524 16860 5524 5521 16861 5521 5522 16862 5522 5524 16863 5524 5523 16864 5523 5521 16865 5521 5526 16866 5526 5523 16867 5523 5524 16868 5524 5526 16869 5526 5525 16870 5525 5523 16871 5523 5527 16872 5527 5525 16873 5525 5526 16874 5526 5530 16875 5530 5525 16876 5525 5527 16877 5527 5530 16878 5530 5528 16879 5528 5525 16880 5525 5530 16881 5530 5529 16882 5529 5528 16883 5528 5532 16884 5532 5529 16885 5529 5530 16886 5530 5532 16887 5532 5531 16888 5531 5529 16889 5529 5533 16890 5533 5531 16891 5531 5532 16892 5532 5535 16893 5535 5531 16894 5531 5533 16895 5533 5535 16896 5535 5534 16897 5534 5531 16898 5531 5537 16899 5537 5534 16900 5534 5535 16901 5535 5537 16902 5537 5536 16903 5536 5534 16904 5534 5539 16905 5539 5536 16906 5536 5537 16907 5537 5539 16908 5539 5538 16909 5538 5536 16910 5536 5541 16911 5541 5538 16912 5538 5539 16913 5539 5541 16914 5541 5540 16915 5540 5538 16916 5538 5544 16917 5544 5540 16918 5540 5541 16919 5541 5544 16920 5544 5542 16921 5542 5540 16922 5540 5544 16923 5544 5543 16924 5543 5542 16925 5542 5545 16926 5545 5543 16927 5543 5544 16928 5544 5515 16929 5515 5543 16930 5543 5545 16931 5545 5577 16932 5577 5547 16933 5547 5546 16934 5546 5549 16935 5549 5547 16936 5547 5548 16937 5548 5546 16938 5546 5547 16939 5547 5549 16940 5549 5554 16941 5554 5550 16942 5550 5551 16943 5551 5554 16944 5554 5552 16945 5552 5550 16946 5550 5554 16947 5554 5553 16948 5553 5552 16949 5552 5556 16950 5556 5553 16951 5553 5554 16952 5554 5556 16953 5556 5555 16954 5555 5553 16955 5553 5558 16956 5558 5555 16957 5555 5556 16958 5556 5558 16959 5558 5557 16960 5557 5555 16961 5555 5560 16962 5560 5557 16963 5557 5558 16964 5558 5560 16965 5560 5559 16966 5559 5557 16967 5557 5562 16968 5562 5559 16969 5559 5560 16970 5560 5562 16971 5562 5561 16972 5561 5559 16973 5559 5563 16974 5563 5561 16975 5561 5562 16976 5562 5565 16977 5565 5561 16978 5561 5563 16979 5563 5565 16980 5565 5564 16981 5564 5561 16982 5561 5567 16983 5567 5564 16984 5564 5565 16985 5565 5567 16986 5567 5566 16987 5566 5564 16988 5564 5569 16989 5569 5566 16990 5566 5567 16991 5567 5569 16992 5569 5568 16993 5568 5566 16994 5566 5571 16995 5571 5568 16996 5568 5569 16997 5569 5571 16998 5571 5570 16999 5570 5568 17000 5568 5573 17001 5573 5570 17002 5570 5571 17003 5571 5573 17004 5573 5572 17005 5572 5570 17006 5570 5575 17007 5575 5572 17008 5572 5573 17009 5573 5575 17010 5575 5574 17011 5574 5572 17012 5572 5578 17013 5578 5574 17014 5574 5575 17015 5575 5578 17016 5578 5576 17017 5576 5574 17018 5574 5578 17019 5578 5577 17020 5577 5576 17021 5576 5579 17022 5579 5577 17023 5577 5578 17024 5578 5547 17025 5547 5577 17026 5577 5579 17027 5579 5612 17028 5612 5581 17029 5581 5580 17030 5580 5583 17031 5583 5581 17032 5581 5582 17033 5582 5580 17034 5580 5581 17035 5581 5583 17036 5583 5587 17037 5587 5584 17038 5584 5585 17039 5585 5587 17040 5587 5586 17041 5586 5584 17042 5584 5590 17043 5590 5586 17044 5586 5587 17045 5587 5590 17046 5590 5588 17047 5588 5586 17048 5586 5590 17049 5590 5589 17050 5589 5588 17051 5588 5591 17052 5591 5589 17053 5589 5590 17054 5590 5593 17055 5593 5589 17056 5589 5591 17057 5591 5593 17058 5593 5592 17059 5592 5589 17060 5589 5596 17061 5596 5592 17062 5592 5593 17063 5593 5596 17064 5596 5594 17065 5594 5592 17066 5592 5596 17067 5596 5595 17068 5595 5594 17069 5594 5597 17070 5597 5595 17071 5595 5596 17072 5596 5599 17073 5599 5595 17074 5595 5597 17075 5597 5599 17076 5599 5598 17077 5598 5595 17078 5595 5601 17079 5601 5598 17080 5598 5599 17081 5599 5601 17082 5601 5600 17083 5600 5598 17084 5598 5603 17085 5603 5600 17086 5600 5601 17087 5601 5603 17088 5603 5602 17089 5602 5600 17090 5600 5605 17091 5605 5602 17092 5602 5603 17093 5603 5605 17094 5605 5604 17095 5604 5602 17096 5602 5607 17097 5607 5604 17098 5604 5605 17099 5605 5607 17100 5607 5606 17101 5606 5604 17102 5604 5609 17103 5609 5606 17104 5606 5607 17105 5607 5609 17106 5609 5608 17107 5608 5606 17108 5606 5611 17109 5611 5608 17110 5608 5609 17111 5609 5611 17112 5611 5610 17113 5610 5608 17114 5608 5613 17115 5613 5610 17116 5610 5611 17117 5611 5613 17118 5613 5612 17119 5612 5610 17120 5610 5581 17121 5581 5612 17122 5612 5613 17123 5613 5646 17124 5646 5615 17125 5615 5614 17126 5614 5617 17127 5617 5615 17128 5615 5616 17129 5616 5614 17130 5614 5615 17131 5615 5617 17132 5617 5622 17133 5622 5618 17134 5618 5619 17135 5619 5622 17136 5622 5620 17137 5620 5618 17138 5618 5622 17139 5622 5621 17140 5621 5620 17141 5620 5623 17142 5623 5621 17143 5621 5622 17144 5622 5626 17145 5626 5621 17146 5621 5623 17147 5623 5626 17148 5626 5624 17149 5624 5621 17150 5621 5626 17151 5626 5625 17152 5625 5624 17153 5624 5627 17154 5627 5625 17155 5625 5626 17156 5626 5629 17157 5629 5625 17158 5625 5627 17159 5627 5629 17160 5629 5628 17161 5628 5625 17162 5625 5632 17163 5632 5628 17164 5628 5629 17165 5629 5632 17166 5632 5630 17167 5630 5628 17168 5628 5632 17169 5632 5631 17170 5631 5630 17171 5630 5634 17172 5634 5631 17173 5631 5632 17174 5632 5634 17175 5634 5633 17176 5633 5631 17177 5631 5636 17178 5636 5633 17179 5633 5634 17180 5634 5636 17181 5636 5635 17182 5635 5633 17183 5633 5637 17184 5637 5635 17185 5635 5636 17186 5636 5639 17187 5639 5635 17188 5635 5637 17189 5637 5639 17190 5639 5638 17191 5638 5635 17192 5635 5642 17193 5642 5638 17194 5638 5639 17195 5639 5642 17196 5642 5640 17197 5640 5638 17198 5638 5642 17199 5642 5641 17200 5641 5640 17201 5640 5643 17202 5643 5641 17203 5641 5642 17204 5642 5645 17205 5645 5641 17206 5641 5643 17207 5643 5645 17208 5645 5644 17209 5644 5641 17210 5641 5647 17211 5647 5644 17212 5644 5645 17213 5645 5647 17214 5647 5646 17215 5646 5644 17216 5644 5615 17217 5615 5646 17218 5646 5647 17219 5647 5680 17220 5680 5657 17221 5657 5648 17222 5648 5651 17223 5651 5649 17224 5649 5650 17225 5650 5653 17226 5653 5649 17227 5649 5651 17228 5651 5653 17229 5653 5652 17230 5652 5649 17231 5649 5654 17232 5654 5652 17233 5652 5653 17234 5653 5656 17235 5656 5652 17236 5652 5654 17237 5654 5656 17238 5656 5655 17239 5655 5652 17240 5652 5648 17241 5648 5655 17242 5655 5656 17243 5656 5648 17244 5648 5657 17245 5657 5655 17246 5655 5662 17247 5662 5658 17248 5658 5659 17249 5659 5662 17250 5662 5660 17251 5660 5658 17252 5658 5662 17253 5662 5661 17254 5661 5660 17255 5660 5663 17256 5663 5661 17257 5661 5662 17258 5662 5665 17259 5665 5661 17260 5661 5663 17261 5663 5665 17262 5665 5664 17263 5664 5661 17264 5661 5668 17265 5668 5664 17266 5664 5665 17267 5665 5668 17268 5668 5666 17269 5666 5664 17270 5664 5668 17271 5668 5667 17272 5667 5666 17273 5666 5669 17274 5669 5667 17275 5667 5668 17276 5668 5672 17277 5672 5667 17278 5667 5669 17279 5669 5672 17280 5672 5670 17281 5670 5667 17282 5667 5672 17283 5672 5671 17284 5671 5670 17285 5670 5673 17286 5673 5671 17287 5671 5672 17288 5672 5675 17289 5675 5671 17290 5671 5673 17291 5673 5675 17292 5675 5674 17293 5674 5671 17294 5671 5677 17295 5677 5674 17296 5674 5675 17297 5675 5677 17298 5677 5676 17299 5676 5674 17300 5674 5679 17301 5679 5676 17302 5676 5677 17303 5677 5679 17304 5679 5678 17305 5678 5676 17306 5676 5681 17307 5681 5678 17308 5678 5679 17309 5679 5681 17310 5681 5680 17311 5680 5678 17312 5678 5657 17313 5657 5680 17314 5680 5681 17315 5681 5714 17316 5714 5686 17317 5686 5682 17318 5682 5685 17319 5685 5683 17320 5683 5684 17321 5684 5687 17322 5687 5683 17323 5683 5685 17324 5685 5687 17325 5687 5686 17326 5686 5683 17327 5683 5682 17328 5682 5686 17329 5686 5687 17330 5687 5692 17331 5692 5688 17332 5688 5689 17333 5689 5692 17334 5692 5690 17335 5690 5688 17336 5688 5692 17337 5692 5691 17338 5691 5690 17339 5690 5694 17340 5694 5691 17341 5691 5692 17342 5692 5694 17343 5694 5693 17344 5693 5691 17345 5691 5695 17346 5695 5693 17347 5693 5694 17348 5694 5697 17349 5697 5693 17350 5693 5695 17351 5695 5697 17352 5697 5696 17353 5696 5693 17354 5693 5699 17355 5699 5696 17356 5696 5697 17357 5697 5699 17358 5699 5698 17359 5698 5696 17360 5696 5701 17361 5701 5698 17362 5698 5699 17363 5699 5701 17364 5701 5700 17365 5700 5698 17366 5698 5703 17367 5703 5700 17368 5700 5701 17369 5701 5703 17370 5703 5702 17371 5702 5700 17372 5700 5705 17373 5705 5702 17374 5702 5703 17375 5703 5705 17376 5705 5704 17377 5704 5702 17378 5702 5707 17379 5707 5704 17380 5704 5705 17381 5705 5707 17382 5707 5706 17383 5706 5704 17384 5704 5709 17385 5709 5706 17386 5706 5707 17387 5707 5709 17388 5709 5708 17389 5708 5706 17390 5706 5711 17391 5711 5708 17392 5708 5709 17393 5709 5711 17394 5711 5710 17395 5710 5708 17396 5708 5713 17397 5713 5710 17398 5710 5711 17399 5711 5713 17400 5713 5712 17401 5712 5710 17402 5710 5715 17403 5715 5712 17404 5712 5713 17405 5713 5715 17406 5715 5714 17407 5714 5712 17408 5712 5686 17409 5686 5714 17410 5714 5715 17411 5715 5748 17412 5748 5720 17413 5720 5716 17414 5716 5719 17415 5719 5717 17416 5717 5718 17417 5718 5721 17418 5721 5717 17419 5717 5719 17420 5719 5721 17421 5721 5720 17422 5720 5717 17423 5717 5716 17424 5716 5720 17425 5720 5721 17426 5721 5724 17427 5724 5722 17428 5722 5723 17429 5723 5726 17430 5726 5722 17431 5722 5724 17432 5724 5726 17433 5726 5725 17434 5725 5722 17435 5722 5727 17436 5727 5725 17437 5725 5726 17438 5726 5729 17439 5729 5725 17440 5725 5727 17441 5727 5729 17442 5729 5728 17443 5728 5725 17444 5725 5731 17445 5731 5728 17446 5728 5729 17447 5729 5731 17448 5731 5730 17449 5730 5728 17450 5728 5733 17451 5733 5730 17452 5730 5731 17453 5731 5733 17454 5733 5732 17455 5732 5730 17456 5730 5736 17457 5736 5732 17458 5732 5733 17459 5733 5736 17460 5736 5734 17461 5734 5732 17462 5732 5736 17463 5736 5735 17464 5735 5734 17465 5734 5737 17466 5737 5735 17467 5735 5736 17468 5736 5739 17469 5739 5735 17470 5735 5737 17471 5737 5739 17472 5739 5738 17473 5738 5735 17474 5735 5741 17475 5741 5738 17476 5738 5739 17477 5739 5741 17478 5741 5740 17479 5740 5738 17480 5738 5743 17481 5743 5740 17482 5740 5741 17483 5741 5743 17484 5743 5742 17485 5742 5740 17486 5740 5745 17487 5745 5742 17488 5742 5743 17489 5743 5745 17490 5745 5744 17491 5744 5742 17492 5742 5747 17493 5747 5744 17494 5744 5745 17495 5745 5747 17496 5747 5746 17497 5746 5744 17498 5744 5749 17499 5749 5746 17500 5746 5747 17501 5747 5749 17502 5749 5748 17503 5748 5746 17504 5746 5720 17505 5720 5748 17506 5748 5749 17507 5749 5782 17508 5782 5750 17509 5750 5751 17510 5751 5754 17511 5754 5752 17512 5752 5753 17513 5753 5755 17514 5755 5752 17515 5752 5754 17516 5754 5757 17517 5757 5752 17518 5752 5755 17519 5755 5757 17520 5757 5756 17521 5756 5752 17522 5752 5760 17523 5760 5756 17524 5756 5757 17525 5757 5760 17526 5760 5758 17527 5758 5756 17528 5756 5760 17529 5760 5759 17530 5759 5758 17531 5758 5762 17532 5762 5759 17533 5759 5760 17534 5760 5762 17535 5762 5761 17536 5761 5759 17537 5759 5764 17538 5764 5761 17539 5761 5762 17540 5762 5764 17541 5764 5763 17542 5763 5761 17543 5761 5766 17544 5766 5763 17545 5763 5764 17546 5764 5766 17547 5766 5765 17548 5765 5763 17549 5763 5768 17550 5768 5765 17551 5765 5766 17552 5766 5768 17553 5768 5767 17554 5767 5765 17555 5765 5770 17556 5770 5767 17557 5767 5768 17558 5768 5770 17559 5770 5769 17560 5769 5767 17561 5767 5771 17562 5771 5769 17563 5769 5770 17564 5770 5774 17565 5774 5769 17566 5769 5771 17567 5771 5774 17568 5774 5772 17569 5772 5769 17570 5769 5774 17571 5774 5773 17572 5773 5772 17573 5772 5776 17574 5776 5773 17575 5773 5774 17576 5774 5776 17577 5776 5775 17578 5775 5773 17579 5773 5778 17580 5778 5775 17581 5775 5776 17582 5776 5778 17583 5778 5777 17584 5777 5775 17585 5775 5779 17586 5779 5777 17587 5777 5778 17588 5778 5781 17589 5781 5777 17590 5777 5779 17591 5779 5781 17592 5781 5780 17593 5780 5777 17594 5777 5783 17595 5783 5780 17596 5780 5781 17597 5781 5783 17598 5783 5782 17599 5782 5780 17600 5780 5750 17601 5750 5782 17602 5782 5783 17603 5783 5817 17604 5817 5784 17605 5784 5800 17606 5800 5787 17607 5787 5785 17608 5785 5786 17609 5786 5788 17610 5788 5785 17611 5785 5787 17612 5787 5791 17613 5791 5785 17614 5785 5788 17615 5788 5791 17616 5791 5789 17617 5789 5785 17618 5785 5791 17619 5791 5790 17620 5790 5789 17621 5789 5792 17622 5792 5790 17623 5790 5791 17624 5791 5795 17625 5795 5790 17626 5790 5792 17627 5792 5795 17628 5795 5793 17629 5793 5790 17630 5790 5795 17631 5795 5794 17632 5794 5793 17633 5793 5797 17634 5797 5794 17635 5794 5795 17636 5795 5797 17637 5797 5796 17638 5796 5794 17639 5794 5799 17640 5799 5796 17641 5796 5797 17642 5797 5799 17643 5799 5798 17644 5798 5796 17645 5796 5801 17646 5801 5798 17647 5798 5799 17648 5799 5801 17649 5801 5800 17650 5800 5798 17651 5798 5817 17652 5817 5800 17653 5800 5801 17654 5801 5804 17655 5804 5802 17656 5802 5803 17657 5803 5806 17658 5806 5802 17659 5802 5804 17660 5804 5806 17661 5806 5805 17662 5805 5802 17663 5802 5808 17664 5808 5805 17665 5805 5806 17666 5806 5808 17667 5808 5807 17668 5807 5805 17669 5805 5809 17670 5809 5807 17671 5807 5808 17672 5808 5811 17673 5811 5807 17674 5807 5809 17675 5809 5811 17676 5811 5810 17677 5810 5807 17678 5807 5814 17679 5814 5810 17680 5810 5811 17681 5811 5814 17682 5814 5812 17683 5812 5810 17684 5810 5814 17685 5814 5813 17686 5813 5812 17687 5812 5815 17688 5815 5813 17689 5813 5814 17690 5814 5784 17691 5784 5813 17692 5813 5815 17693 5815 5784 17694 5784 5816 17695 5816 5813 17696 5813 5784 17697 5784 5817 17698 5817 5816 17699 5816 5850 17700 5850 5818 17701 5818 5819 17702 5819 5823 17703 5823 5820 17704 5820 5821 17705 5821 5823 17706 5823 5822 17707 5822 5820 17708 5820 5825 17709 5825 5822 17710 5822 5823 17711 5823 5825 17712 5825 5824 17713 5824 5822 17714 5822 5828 17715 5828 5824 17716 5824 5825 17717 5825 5828 17718 5828 5826 17719 5826 5824 17720 5824 5828 17721 5828 5827 17722 5827 5826 17723 5826 5830 17724 5830 5827 17725 5827 5828 17726 5828 5830 17727 5830 5829 17728 5829 5827 17729 5827 5832 17730 5832 5829 17731 5829 5830 17732 5830 5832 17733 5832 5831 17734 5831 5829 17735 5829 5834 17736 5834 5831 17737 5831 5832 17738 5832 5834 17739 5834 5833 17740 5833 5831 17741 5831 5835 17742 5835 5833 17743 5833 5834 17744 5834 5838 17745 5838 5833 17746 5833 5835 17747 5835 5838 17748 5838 5836 17749 5836 5833 17750 5833 5838 17751 5838 5837 17752 5837 5836 17753 5836 5840 17754 5840 5837 17755 5837 5838 17756 5838 5840 17757 5840 5839 17758 5839 5837 17759 5837 5842 17760 5842 5839 17761 5839 5840 17762 5840 5842 17763 5842 5841 17764 5841 5839 17765 5839 5844 17766 5844 5841 17767 5841 5842 17768 5842 5844 17769 5844 5843 17770 5843 5841 17771 5841 5845 17772 5845 5843 17773 5843 5844 17774 5844 5847 17775 5847 5843 17776 5843 5845 17777 5845 5847 17778 5847 5846 17779 5846 5843 17780 5843 5849 17781 5849 5846 17782 5846 5847 17783 5847 5849 17784 5849 5848 17785 5848 5846 17786 5846 5851 17787 5851 5848 17788 5848 5849 17789 5849 5851 17790 5851 5850 17791 5850 5848 17792 5848 5818 17793 5818 5850 17794 5850 5851 17795 5851 5884 17796 5884 5855 17797 5855 5852 17798 5852 5852 17799 5852 5853 17800 5853 5854 17801 5854 5852 17802 5852 5855 17803 5855 5853 17804 5853 5859 17805 5859 5856 17806 5856 5857 17807 5857 5859 17808 5859 5858 17809 5858 5856 17810 5856 5861 17811 5861 5858 17812 5858 5859 17813 5859 5861 17814 5861 5860 17815 5860 5858 17816 5858 5864 17817 5864 5860 17818 5860 5861 17819 5861 5864 17820 5864 5862 17821 5862 5860 17822 5860 5864 17823 5864 5863 17824 5863 5862 17825 5862 5866 17826 5866 5863 17827 5863 5864 17828 5864 5866 17829 5866 5865 17830 5865 5863 17831 5863 5868 17832 5868 5865 17833 5865 5866 17834 5866 5868 17835 5868 5867 17836 5867 5865 17837 5865 5869 17838 5869 5867 17839 5867 5868 17840 5868 5871 17841 5871 5867 17842 5867 5869 17843 5869 5871 17844 5871 5870 17845 5870 5867 17846 5867 5874 17847 5874 5870 17848 5870 5871 17849 5871 5874 17850 5874 5872 17851 5872 5870 17852 5870 5874 17853 5874 5873 17854 5873 5872 17855 5872 5876 17856 5876 5873 17857 5873 5874 17858 5874 5876 17859 5876 5875 17860 5875 5873 17861 5873 5878 17862 5878 5875 17863 5875 5876 17864 5876 5878 17865 5878 5877 17866 5877 5875 17867 5875 5879 17868 5879 5877 17869 5877 5878 17870 5878 5882 17871 5882 5877 17872 5877 5879 17873 5879 5882 17874 5882 5880 17875 5880 5877 17876 5877 5882 17877 5882 5881 17878 5881 5880 17879 5880 5883 17880 5883 5881 17881 5881 5882 17882 5882 5885 17883 5885 5881 17884 5881 5883 17885 5883 5885 17886 5885 5884 17887 5884 5881 17888 5881 5855 17889 5855 5884 17890 5884 5885 17891 5885 5918 17892 5918 5886 17893 5886 5887 17894 5887 5891 17895 5891 5888 17896 5888 5889 17897 5889 5891 17898 5891 5890 17899 5890 5888 17900 5888 5893 17901 5893 5890 17902 5890 5891 17903 5891 5893 17904 5893 5892 17905 5892 5890 17906 5890 5896 17907 5896 5892 17908 5892 5893 17909 5893 5896 17910 5896 5894 17911 5894 5892 17912 5892 5896 17913 5896 5895 17914 5895 5894 17915 5894 5898 17916 5898 5895 17917 5895 5896 17918 5896 5898 17919 5898 5897 17920 5897 5895 17921 5895 5900 17922 5900 5897 17923 5897 5898 17924 5898 5900 17925 5900 5899 17926 5899 5897 17927 5897 5902 17928 5902 5899 17929 5899 5900 17930 5900 5902 17931 5902 5901 17932 5901 5899 17933 5899 5904 17934 5904 5901 17935 5901 5902 17936 5902 5904 17937 5904 5903 17938 5903 5901 17939 5901 5906 17940 5906 5903 17941 5903 5904 17942 5904 5906 17943 5906 5905 17944 5905 5903 17945 5903 5907 17946 5907 5905 17947 5905 5906 17948 5906 5910 17949 5910 5905 17950 5905 5907 17951 5907 5910 17952 5910 5908 17953 5908 5905 17954 5905 5910 17955 5910 5909 17956 5909 5908 17957 5908 5911 17958 5911 5909 17959 5909 5910 17960 5910 5913 17961 5913 5909 17962 5909 5911 17963 5911 5913 17964 5913 5912 17965 5912 5909 17966 5909 5915 17967 5915 5912 17968 5912 5913 17969 5913 5915 17970 5915 5914 17971 5914 5912 17972 5912 5917 17973 5917 5914 17974 5914 5915 17975 5915 5917 17976 5917 5916 17977 5916 5914 17978 5914 5919 17979 5919 5916 17980 5916 5917 17981 5917 5919 17982 5919 5918 17983 5918 5916 17984 5916 5886 17985 5886 5918 17986 5918 5919 17987 5919 5952 17988 5952 5920 17989 5920 5921 17990 5921 5924 17991 5924 5922 17992 5922 5923 17993 5923 5925 17994 5925 5922 17995 5922 5924 17996 5924 5927 17997 5927 5922 17998 5922 5925 17999 5925 5927 18000 5927 5926 18001 5926 5922 18002 5922 5930 18003 5930 5926 18004 5926 5927 18005 5927 5930 18006 5930 5928 18007 5928 5926 18008 5926 5930 18009 5930 5929 18010 5929 5928 18011 5928 5932 18012 5932 5929 18013 5929 5930 18014 5930 5932 18015 5932 5931 18016 5931 5929 18017 5929 5934 18018 5934 5931 18019 5931 5932 18020 5932 5934 18021 5934 5933 18022 5933 5931 18023 5931 5936 18024 5936 5933 18025 5933 5934 18026 5934 5936 18027 5936 5935 18028 5935 5933 18029 5933 5937 18030 5937 5935 18031 5935 5936 18032 5936 5940 18033 5940 5935 18034 5935 5937 18035 5937 5940 18036 5940 5938 18037 5938 5935 18038 5935 5940 18039 5940 5939 18040 5939 5938 18041 5938 5941 18042 5941 5939 18043 5939 5940 18044 5940 5944 18045 5944 5939 18046 5939 5941 18047 5941 5944 18048 5944 5942 18049 5942 5939 18050 5939 5944 18051 5944 5943 18052 5943 5942 18053 5942 5945 18054 5945 5943 18055 5943 5944 18056 5944 5947 18057 5947 5943 18058 5943 5945 18059 5945 5947 18060 5947 5946 18061 5946 5943 18062 5943 5949 18063 5949 5946 18064 5946 5947 18065 5947 5949 18066 5949 5948 18067 5948 5946 18068 5946 5951 18069 5951 5948 18070 5948 5949 18071 5949 5951 18072 5951 5950 18073 5950 5948 18074 5948 5953 18075 5953 5950 18076 5950 5951 18077 5951 5953 18078 5953 5952 18079 5952 5950 18080 5950 5920 18081 5920 5952 18082 5952 5953 18083 5953 5986 18084 5986 5954 18085 5954 5955 18086 5955 5958 18087 5958 5956 18088 5956 5957 18089 5957 5960 18090 5960 5956 18091 5956 5958 18092 5958 5960 18093 5960 5959 18094 5959 5956 18095 5956 5962 18096 5962 5959 18097 5959 5960 18098 5960 5962 18099 5962 5961 18100 5961 5959 18101 5959 5964 18102 5964 5961 18103 5961 5962 18104 5962 5964 18105 5964 5963 18106 5963 5961 18107 5961 5966 18108 5966 5963 18109 5963 5964 18110 5964 5966 18111 5966 5965 18112 5965 5963 18113 5963 5967 18114 5967 5965 18115 5965 5966 18116 5966 5969 18117 5969 5965 18118 5965 5967 18119 5967 5969 18120 5969 5968 18121 5968 5965 18122 5965 5971 18123 5971 5968 18124 5968 5969 18125 5969 5971 18126 5971 5970 18127 5970 5968 18128 5968 5973 18129 5973 5970 18130 5970 5971 18131 5971 5973 18132 5973 5972 18133 5972 5970 18134 5970 5975 18135 5975 5972 18136 5972 5973 18137 5973 5975 18138 5975 5974 18139 5974 5972 18140 5972 5977 18141 5977 5974 18142 5974 5975 18143 5975 5977 18144 5977 5976 18145 5976 5974 18146 5974 5980 18147 5980 5976 18148 5976 5977 18149 5977 5980 18150 5980 5978 18151 5978 5976 18152 5976 5980 18153 5980 5979 18154 5979 5978 18155 5978 5981 18156 5981 5979 18157 5979 5980 18158 5980 5983 18159 5983 5979 18160 5979 5981 18161 5981 5983 18162 5983 5982 18163 5982 5979 18164 5979 5985 18165 5985 5982 18166 5982 5983 18167 5983 5985 18168 5985 5984 18169 5984 5982 18170 5982 5987 18171 5987 5984 18172 5984 5985 18173 5985 5987 18174 5987 5986 18175 5986 5984 18176 5984 5954 18177 5954 5986 18178 5986 5987 18179 5987 6021 18180 6021 5988 18181 5988 5989 18182 5989 5991 18183 5991 5989 18184 5989 5990 18185 5990 6021 18186 6021 5989 18187 5989 5991 18188 5991 5996 18189 5996 5992 18190 5992 5993 18191 5993 5996 18192 5996 5994 18193 5994 5992 18194 5992 5996 18195 5996 5995 18196 5995 5994 18197 5994 5998 18198 5998 5995 18199 5995 5996 18200 5996 5998 18201 5998 5997 18202 5997 5995 18203 5995 6000 18204 6000 5997 18205 5997 5998 18206 5998 6000 18207 6000 5999 18208 5999 5997 18209 5997 6001 18210 6001 5999 18211 5999 6000 18212 6000 6003 18213 6003 5999 18214 5999 6001 18215 6001 6003 18216 6003 6002 18217 6002 5999 18218 5999 6005 18219 6005 6002 18220 6002 6003 18221 6003 6005 18222 6005 6004 18223 6004 6002 18224 6002 6007 18225 6007 6004 18226 6004 6005 18227 6005 6007 18228 6007 6006 18229 6006 6004 18230 6004 6010 18231 6010 6006 18232 6006 6007 18233 6007 6010 18234 6010 6008 18235 6008 6006 18236 6006 6010 18237 6010 6009 18238 6009 6008 18239 6008 6012 18240 6012 6009 18241 6009 6010 18242 6010 6012 18243 6012 6011 18244 6011 6009 18245 6009 6014 18246 6014 6011 18247 6011 6012 18248 6012 6014 18249 6014 6013 18250 6013 6011 18251 6011 6016 18252 6016 6013 18253 6013 6014 18254 6014 6016 18255 6016 6015 18256 6015 6013 18257 6013 6017 18258 6017 6015 18259 6015 6016 18260 6016 6020 18261 6020 6015 18262 6015 6017 18263 6017 6020 18264 6020 6018 18265 6018 6015 18266 6015 6020 18267 6020 6019 18268 6019 6018 18269 6018 5988 18270 5988 6019 18271 6019 6020 18272 6020 5988 18273 5988 6021 18274 6021 6019 18275 6019 6054 18276 6054 6025 18277 6025 6022 18278 6022 6022 18279 6022 6023 18280 6023 6024 18281 6024 6022 18282 6022 6025 18283 6025 6023 18284 6023 6029 18285 6029 6026 18286 6026 6027 18287 6027 6029 18288 6029 6028 18289 6028 6026 18290 6026 6031 18291 6031 6028 18292 6028 6029 18293 6029 6031 18294 6031 6030 18295 6030 6028 18296 6028 6034 18297 6034 6030 18298 6030 6031 18299 6031 6034 18300 6034 6032 18301 6032 6030 18302 6030 6034 18303 6034 6033 18304 6033 6032 18305 6032 6035 18306 6035 6033 18307 6033 6034 18308 6034 6038 18309 6038 6033 18310 6033 6035 18311 6035 6038 18312 6038 6036 18313 6036 6033 18314 6033 6038 18315 6038 6037 18316 6037 6036 18317 6036 6040 18318 6040 6037 18319 6037 6038 18320 6038 6040 18321 6040 6039 18322 6039 6037 18323 6037 6042 18324 6042 6039 18325 6039 6040 18326 6040 6042 18327 6042 6041 18328 6041 6039 18329 6039 6043 18330 6043 6041 18331 6041 6042 18332 6042 6046 18333 6046 6041 18334 6041 6043 18335 6043 6046 18336 6046 6044 18337 6044 6041 18338 6041 6046 18339 6046 6045 18340 6045 6044 18341 6044 6047 18342 6047 6045 18343 6045 6046 18344 6046 6049 18345 6049 6045 18346 6045 6047 18347 6047 6049 18348 6049 6048 18349 6048 6045 18350 6045 6051 18351 6051 6048 18352 6048 6049 18353 6049 6051 18354 6051 6050 18355 6050 6048 18356 6048 6053 18357 6053 6050 18358 6050 6051 18359 6051 6053 18360 6053 6052 18361 6052 6050 18362 6050 6055 18363 6055 6052 18364 6052 6053 18365 6053 6055 18366 6055 6054 18367 6054 6052 18368 6052 6025 18369 6025 6054 18370 6054 6055 18371 6055 6088 18372 6088 6059 18373 6059 6056 18374 6056 6056 18375 6056 6057 18376 6057 6058 18377 6058 6056 18378 6056 6059 18379 6059 6057 18380 6057 6064 18381 6064 6060 18382 6060 6061 18383 6061 6064 18384 6064 6062 18385 6062 6060 18386 6060 6064 18387 6064 6063 18388 6063 6062 18389 6062 6066 18390 6066 6063 18391 6063 6064 18392 6064 6066 18393 6066 6065 18394 6065 6063 18395 6063 6067 18396 6067 6065 18397 6065 6066 18398 6066 6069 18399 6069 6065 18400 6065 6067 18401 6067 6069 18402 6069 6068 18403 6068 6065 18404 6065 6071 18405 6071 6068 18406 6068 6069 18407 6069 6071 18408 6071 6070 18409 6070 6068 18410 6068 6073 18411 6073 6070 18412 6070 6071 18413 6071 6073 18414 6073 6072 18415 6072 6070 18416 6070 6075 18417 6075 6072 18418 6072 6073 18419 6073 6075 18420 6075 6074 18421 6074 6072 18422 6072 6077 18423 6077 6074 18424 6074 6075 18425 6075 6077 18426 6077 6076 18427 6076 6074 18428 6074 6079 18429 6079 6076 18430 6076 6077 18431 6077 6079 18432 6079 6078 18433 6078 6076 18434 6076 6081 18435 6081 6078 18436 6078 6079 18437 6079 6081 18438 6081 6080 18439 6080 6078 18440 6078 6083 18441 6083 6080 18442 6080 6081 18443 6081 6083 18444 6083 6082 18445 6082 6080 18446 6080 6086 18447 6086 6082 18448 6082 6083 18449 6083 6086 18450 6086 6084 18451 6084 6082 18452 6082 6086 18453 6086 6085 18454 6085 6084 18455 6084 6087 18456 6087 6085 18457 6085 6086 18458 6086 6089 18459 6089 6085 18460 6085 6087 18461 6087 6089 18462 6089 6088 18463 6088 6085 18464 6085 6059 18465 6059 6088 18466 6088 6089 18467 6089 6122 18468 6122 6090 18469 6090 6091 18470 6091 6094 18471 6094 6092 18472 6092 6093 18473 6093 6095 18474 6095 6092 18475 6092 6094 18476 6094 6097 18477 6097 6092 18478 6092 6095 18479 6095 6097 18480 6097 6096 18481 6096 6092 18482 6092 6099 18483 6099 6096 18484 6096 6097 18485 6097 6099 18486 6099 6098 18487 6098 6096 18488 6096 6101 18489 6101 6098 18490 6098 6099 18491 6099 6101 18492 6101 6100 18493 6100 6098 18494 6098 6103 18495 6103 6100 18496 6100 6101 18497 6101 6103 18498 6103 6102 18499 6102 6100 18500 6100 6105 18501 6105 6102 18502 6102 6103 18503 6103 6105 18504 6105 6104 18505 6104 6102 18506 6102 6107 18507 6107 6104 18508 6104 6105 18509 6105 6107 18510 6107 6106 18511 6106 6104 18512 6104 6109 18513 6109 6106 18514 6106 6107 18515 6107 6109 18516 6109 6108 18517 6108 6106 18518 6106 6111 18519 6111 6108 18520 6108 6109 18521 6109 6111 18522 6111 6110 18523 6110 6108 18524 6108 6113 18525 6113 6110 18526 6110 6111 18527 6111 6113 18528 6113 6112 18529 6112 6110 18530 6110 6115 18531 6115 6112 18532 6112 6113 18533 6113 6115 18534 6115 6114 18535 6114 6112 18536 6112 6117 18537 6117 6114 18538 6114 6115 18539 6115 6117 18540 6117 6116 18541 6116 6114 18542 6114 6119 18543 6119 6116 18544 6116 6117 18545 6117 6119 18546 6119 6118 18547 6118 6116 18548 6116 6121 18549 6121 6118 18550 6118 6119 18551 6119 6121 18552 6121 6120 18553 6120 6118 18554 6118 6123 18555 6123 6120 18556 6120 6121 18557 6121 6123 18558 6123 6122 18559 6122 6120 18560 6120 6090 18561 6090 6122 18562 6122 6123 18563 6123 6156 18564 6156 6124 18565 6124 6125 18566 6125 6130 18567 6130 6126 18568 6126 6127 18569 6127 6130 18570 6130 6128 18571 6128 6126 18572 6126 6130 18573 6130 6129 18574 6129 6128 18575 6128 6132 18576 6132 6129 18577 6129 6130 18578 6130 6132 18579 6132 6131 18580 6131 6129 18581 6129 6134 18582 6134 6131 18583 6131 6132 18584 6132 6134 18585 6134 6133 18586 6133 6131 18587 6131 6136 18588 6136 6133 18589 6133 6134 18590 6134 6136 18591 6136 6135 18592 6135 6133 18593 6133 6137 18594 6137 6135 18595 6135 6136 18596 6136 6139 18597 6139 6135 18598 6135 6137 18599 6137 6139 18600 6139 6138 18601 6138 6135 18602 6135 6141 18603 6141 6138 18604 6138 6139 18605 6139 6141 18606 6141 6140 18607 6140 6138 18608 6138 6144 18609 6144 6140 18610 6140 6141 18611 6141 6144 18612 6144 6142 18613 6142 6140 18614 6140 6144 18615 6144 6143 18616 6143 6142 18617 6142 6145 18618 6145 6143 18619 6143 6144 18620 6144 6148 18621 6148 6143 18622 6143 6145 18623 6145 6148 18624 6148 6146 18625 6146 6143 18626 6143 6148 18627 6148 6147 18628 6147 6146 18629 6146 6150 18630 6150 6147 18631 6147 6148 18632 6148 6150 18633 6150 6149 18634 6149 6147 18635 6147 6152 18636 6152 6149 18637 6149 6150 18638 6150 6152 18639 6152 6151 18640 6151 6149 18641 6149 6154 18642 6154 6151 18643 6151 6152 18644 6152 6154 18645 6154 6153 18646 6153 6151 18647 6151 6155 18648 6155 6153 18649 6153 6154 18650 6154 6157 18651 6157 6153 18652 6153 6155 18653 6155 6157 18654 6157 6156 18655 6156 6153 18656 6153 6124 18657 6124 6156 18658 6156 6157 18659 6157 6191 18660 6191 6158 18661 6158 6159 18662 6159 6162 18663 6162 6160 18664 6160 6161 18665 6161 6163 18666 6163 6160 18667 6160 6162 18668 6162 6165 18669 6165 6160 18670 6160 6163 18671 6163 6165 18672 6165 6164 18673 6164 6160 18674 6160 6167 18675 6167 6164 18676 6164 6165 18677 6165 6167 18678 6167 6166 18679 6166 6164 18680 6164 6169 18681 6169 6166 18682 6166 6167 18683 6167 6169 18684 6169 6168 18685 6168 6166 18686 6166 6171 18687 6171 6168 18688 6168 6169 18689 6169 6171 18690 6171 6170 18691 6170 6168 18692 6168 6174 18693 6174 6170 18694 6170 6171 18695 6171 6174 18696 6174 6172 18697 6172 6170 18698 6170 6174 18699 6174 6173 18700 6173 6172 18701 6172 6175 18702 6175 6173 18703 6173 6174 18704 6174 6177 18705 6177 6173 18706 6173 6175 18707 6175 6177 18708 6177 6176 18709 6176 6173 18710 6173 6179 18711 6179 6176 18712 6176 6177 18713 6177 6179 18714 6179 6178 18715 6178 6176 18716 6176 6181 18717 6181 6178 18718 6178 6179 18719 6179 6181 18720 6181 6180 18721 6180 6178 18722 6178 6184 18723 6184 6180 18724 6180 6181 18725 6181 6184 18726 6184 6182 18727 6182 6180 18728 6180 6184 18729 6184 6183 18730 6183 6182 18731 6182 6186 18732 6186 6183 18733 6183 6184 18734 6184 6186 18735 6186 6185 18736 6185 6183 18737 6183 6188 18738 6188 6185 18739 6185 6186 18740 6186 6188 18741 6188 6187 18742 6187 6185 18743 6185 6190 18744 6190 6187 18745 6187 6188 18746 6188 6190 18747 6190 6189 18748 6189 6187 18749 6187 6158 18750 6158 6189 18751 6189 6190 18752 6190 6158 18753 6158 6191 18754 6191 6189 18755 6189 6224 18756 6224 6195 18757 6195 6192 18758 6192 6192 18759 6192 6193 18760 6193 6194 18761 6194 6192 18762 6192 6195 18763 6195 6193 18764 6193 6199 18765 6199 6196 18766 6196 6197 18767 6197 6199 18768 6199 6198 18769 6198 6196 18770 6196 6201 18771 6201 6198 18772 6198 6199 18773 6199 6201 18774 6201 6200 18775 6200 6198 18776 6198 6204 18777 6204 6200 18778 6200 6201 18779 6201 6204 18780 6204 6202 18781 6202 6200 18782 6200 6204 18783 6204 6203 18784 6203 6202 18785 6202 6205 18786 6205 6203 18787 6203 6204 18788 6204 6207 18789 6207 6203 18790 6203 6205 18791 6205 6207 18792 6207 6206 18793 6206 6203 18794 6203 6209 18795 6209 6206 18796 6206 6207 18797 6207 6209 18798 6209 6208 18799 6208 6206 18800 6206 6211 18801 6211 6208 18802 6208 6209 18803 6209 6211 18804 6211 6210 18805 6210 6208 18806 6208 6213 18807 6213 6210 18808 6210 6211 18809 6211 6213 18810 6213 6212 18811 6212 6210 18812 6210 6215 18813 6215 6212 18814 6212 6213 18815 6213 6215 18816 6215 6214 18817 6214 6212 18818 6212 6217 18819 6217 6214 18820 6214 6215 18821 6215 6217 18822 6217 6216 18823 6216 6214 18824 6214 6219 18825 6219 6216 18826 6216 6217 18827 6217 6219 18828 6219 6218 18829 6218 6216 18830 6216 6221 18831 6221 6218 18832 6218 6219 18833 6219 6221 18834 6221 6220 18835 6220 6218 18836 6218 6223 18837 6223 6220 18838 6220 6221 18839 6221 6223 18840 6223 6222 18841 6222 6220 18842 6220 6225 18843 6225 6222 18844 6222 6223 18845 6223 6225 18846 6225 6224 18847 6224 6222 18848 6222 6195 18849 6195 6224 18850 6224 6225 18851 6225 6258 18852 6258 6232 18853 6232 6226 18854 6226 6229 18855 6229 6227 18856 6227 6228 18857 6228 6230 18858 6230 6227 18859 6227 6229 18860 6229 6233 18861 6233 6227 18862 6227 6230 18863 6230 6233 18864 6233 6231 18865 6231 6227 18866 6227 6233 18867 6233 6232 18868 6232 6231 18869 6231 6226 18870 6226 6232 18871 6232 6233 18872 6233 6238 18873 6238 6234 18874 6234 6235 18875 6235 6238 18876 6238 6236 18877 6236 6234 18878 6234 6238 18879 6238 6237 18880 6237 6236 18881 6236 6239 18882 6239 6237 18883 6237 6238 18884 6238 6242 18885 6242 6237 18886 6237 6239 18887 6239 6242 18888 6242 6240 18889 6240 6237 18890 6237 6242 18891 6242 6241 18892 6241 6240 18893 6240 6244 18894 6244 6241 18895 6241 6242 18896 6242 6244 18897 6244 6243 18898 6243 6241 18899 6241 6245 18900 6245 6243 18901 6243 6244 18902 6244 6247 18903 6247 6243 18904 6243 6245 18905 6245 6247 18906 6247 6246 18907 6246 6243 18908 6243 6249 18909 6249 6246 18910 6246 6247 18911 6247 6249 18912 6249 6248 18913 6248 6246 18914 6246 6251 18915 6251 6248 18916 6248 6249 18917 6249 6251 18918 6251 6250 18919 6250 6248 18920 6248 6253 18921 6253 6250 18922 6250 6251 18923 6251 6253 18924 6253 6252 18925 6252 6250 18926 6250 6255 18927 6255 6252 18928 6252 6253 18929 6253 6255 18930 6255 6254 18931 6254 6252 18932 6252 6257 18933 6257 6254 18934 6254 6255 18935 6255 6257 18936 6257 6256 18937 6256 6254 18938 6254 6259 18939 6259 6256 18940 6256 6257 18941 6257 6259 18942 6259 6258 18943 6258 6256 18944 6256 6232 18945 6232 6258 18946 6258 6259 18947 6259 6292 18948 6292 6265 18949 6265 6260 18950 6260 6264 18951 6264 6261 18952 6261 6262 18953 6262 6264 18954 6264 6263 18955 6263 6261 18956 6261 6260 18957 6260 6263 18958 6263 6264 18959 6264 6260 18960 6260 6265 18961 6265 6263 18962 6263 6269 18963 6269 6266 18964 6266 6267 18965 6267 6269 18966 6269 6268 18967 6268 6266 18968 6266 6271 18969 6271 6268 18970 6268 6269 18971 6269 6271 18972 6271 6270 18973 6270 6268 18974 6268 6274 18975 6274 6270 18976 6270 6271 18977 6271 6274 18978 6274 6272 18979 6272 6270 18980 6270 6274 18981 6274 6273 18982 6273 6272 18983 6272 6275 18984 6275 6273 18985 6273 6274 18986 6274 6277 18987 6277 6273 18988 6273 6275 18989 6275 6277 18990 6277 6276 18991 6276 6273 18992 6273 6279 18993 6279 6276 18994 6276 6277 18995 6277 6279 18996 6279 6278 18997 6278 6276 18998 6276 6282 18999 6282 6278 19000 6278 6279 19001 6279 6282 19002 6282 6280 19003 6280 6278 19004 6278 6282 19005 6282 6281 19006 6281 6280 19007 6280 6284 19008 6284 6281 19009 6281 6282 19010 6282 6284 19011 6284 6283 19012 6283 6281 19013 6281 6286 19014 6286 6283 19015 6283 6284 19016 6284 6286 19017 6286 6285 19018 6285 6283 19019 6283 6288 19020 6288 6285 19021 6285 6286 19022 6286 6288 19023 6288 6287 19024 6287 6285 19025 6285 6289 19026 6289 6287 19027 6287 6288 19028 6288 6291 19029 6291 6287 19030 6287 6289 19031 6289 6291 19032 6291 6290 19033 6290 6287 19034 6287 6293 19035 6293 6290 19036 6290 6291 19037 6291 6293 19038 6293 6292 19039 6292 6290 19040 6290 6265 19041 6265 6292 19042 6292 6293 19043 6293 6325 19044 6325 6295 19045 6295 6294 19046 6294 6297 19047 6297 6295 19048 6295 6296 19049 6296 6294 19050 6294 6295 19051 6295 6297 19052 6297 6302 19053 6302 6298 19054 6298 6299 19055 6299 6302 19056 6302 6300 19057 6300 6298 19058 6298 6302 19059 6302 6301 19060 6301 6300 19061 6300 6304 19062 6304 6301 19063 6301 6302 19064 6302 6304 19065 6304 6303 19066 6303 6301 19067 6301 6306 19068 6306 6303 19069 6303 6304 19070 6304 6306 19071 6306 6305 19072 6305 6303 19073 6303 6308 19074 6308 6305 19075 6305 6306 19076 6306 6308 19077 6308 6307 19078 6307 6305 19079 6305 6310 19080 6310 6307 19081 6307 6308 19082 6308 6310 19083 6310 6309 19084 6309 6307 19085 6307 6311 19086 6311 6309 19087 6309 6310 19088 6310 6313 19089 6313 6309 19090 6309 6311 19091 6311 6313 19092 6313 6312 19093 6312 6309 19094 6309 6315 19095 6315 6312 19096 6312 6313 19097 6313 6315 19098 6315 6314 19099 6314 6312 19100 6312 6317 19101 6317 6314 19102 6314 6315 19103 6315 6317 19104 6317 6316 19105 6316 6314 19106 6314 6319 19107 6319 6316 19108 6316 6317 19109 6317 6319 19110 6319 6318 19111 6318 6316 19112 6316 6321 19113 6321 6318 19114 6318 6319 19115 6319 6321 19116 6321 6320 19117 6320 6318 19118 6318 6323 19119 6323 6320 19120 6320 6321 19121 6321 6323 19122 6323 6322 19123 6322 6320 19124 6320 6326 19125 6326 6322 19126 6322 6323 19127 6323 6326 19128 6326 6324 19129 6324 6322 19130 6322 6326 19131 6326 6325 19132 6325 6324 19133 6324 6327 19134 6327 6325 19135 6325 6326 19136 6326 6295 19137 6295 6325 19138 6325 6327 19139 6327 6359 19140 6359 6331 19141 6331 6328 19142 6328 6328 19143 6328 6329 19144 6329 6330 19145 6330 6328 19146 6328 6331 19147 6331 6329 19148 6329 6336 19149 6336 6332 19150 6332 6333 19151 6333 6336 19152 6336 6334 19153 6334 6332 19154 6332 6336 19155 6336 6335 19156 6335 6334 19157 6334 6337 19158 6337 6335 19159 6335 6336 19160 6336 6339 19161 6339 6335 19162 6335 6337 19163 6337 6339 19164 6339 6338 19165 6338 6335 19166 6335 6341 19167 6341 6338 19168 6338 6339 19169 6339 6341 19170 6341 6340 19171 6340 6338 19172 6338 6343 19173 6343 6340 19174 6340 6341 19175 6341 6343 19176 6343 6342 19177 6342 6340 19178 6340 6346 19179 6346 6342 19180 6342 6343 19181 6343 6346 19182 6346 6344 19183 6344 6342 19184 6342 6346 19185 6346 6345 19186 6345 6344 19187 6344 6347 19188 6347 6345 19189 6345 6346 19190 6346 6349 19191 6349 6345 19192 6345 6347 19193 6347 6349 19194 6349 6348 19195 6348 6345 19196 6345 6352 19197 6352 6348 19198 6348 6349 19199 6349 6352 19200 6352 6350 19201 6350 6348 19202 6348 6352 19203 6352 6351 19204 6351 6350 19205 6350 6353 19206 6353 6351 19207 6351 6352 19208 6352 6355 19209 6355 6351 19210 6351 6353 19211 6353 6355 19212 6355 6354 19213 6354 6351 19214 6351 6357 19215 6357 6354 19216 6354 6355 19217 6355 6357 19218 6357 6356 19219 6356 6354 19220 6354 6360 19221 6360 6356 19222 6356 6357 19223 6357 6360 19224 6360 6358 19225 6358 6356 19226 6356 6360 19227 6360 6359 19228 6359 6358 19229 6358 6361 19230 6361 6359 19231 6359 6360 19232 6360 6331 19233 6331 6359 19234 6359 6361 19235 6361 6394 19236 6394 6363 19237 6363 6362 19238 6362 6365 19239 6365 6363 19240 6363 6364 19241 6364 6362 19242 6362 6363 19243 6363 6365 19244 6365 6370 19245 6370 6366 19246 6366 6367 19247 6367 6370 19248 6370 6368 19249 6368 6366 19250 6366 6370 19251 6370 6369 19252 6369 6368 19253 6368 6371 19254 6371 6369 19255 6369 6370 19256 6370 6374 19257 6374 6369 19258 6369 6371 19259 6371 6374 19260 6374 6372 19261 6372 6369 19262 6369 6374 19263 6374 6373 19264 6373 6372 19265 6372 6375 19266 6375 6373 19267 6373 6374 19268 6374 6377 19269 6377 6373 19270 6373 6375 19271 6375 6377 19272 6377 6376 19273 6376 6373 19274 6373 6380 19275 6380 6376 19276 6376 6377 19277 6377 6380 19278 6380 6378 19279 6378 6376 19280 6376 6380 19281 6380 6379 19282 6379 6378 19283 6378 6381 19284 6381 6379 19285 6379 6380 19286 6380 6383 19287 6383 6379 19288 6379 6381 19289 6381 6383 19290 6383 6382 19291 6382 6379 19292 6379 6385 19293 6385 6382 19294 6382 6383 19295 6383 6385 19296 6385 6384 19297 6384 6382 19298 6382 6387 19299 6387 6384 19300 6384 6385 19301 6385 6387 19302 6387 6386 19303 6386 6384 19304 6384 6389 19305 6389 6386 19306 6386 6387 19307 6387 6389 19308 6389 6388 19309 6388 6386 19310 6386 6392 19311 6392 6388 19312 6388 6389 19313 6389 6392 19314 6392 6390 19315 6390 6388 19316 6388 6392 19317 6392 6391 19318 6391 6390 19319 6390 6393 19320 6393 6391 19321 6391 6392 19322 6392 6395 19323 6395 6391 19324 6391 6393 19325 6393 6395 19326 6395 6394 19327 6394 6391 19328 6391 6363 19329 6363 6394 19330 6394 6395 19331 6395 6428 19332 6428 6405 19333 6405 6396 19334 6396 6399 19335 6399 6397 19336 6397 6398 19337 6398 6401 19338 6401 6397 19339 6397 6399 19340 6399 6401 19341 6401 6400 19342 6400 6397 19343 6397 6402 19344 6402 6400 19345 6400 6401 19346 6401 6404 19347 6404 6400 19348 6400 6402 19349 6402 6404 19350 6404 6403 19351 6403 6400 19352 6400 6396 19353 6396 6403 19354 6403 6404 19355 6404 6396 19356 6396 6405 19357 6405 6403 19358 6403 6409 19359 6409 6406 19360 6406 6407 19361 6407 6409 19362 6409 6408 19363 6408 6406 19364 6406 6411 19365 6411 6408 19366 6408 6409 19367 6409 6411 19368 6411 6410 19369 6410 6408 19370 6408 6413 19371 6413 6410 19372 6410 6411 19373 6411 6413 19374 6413 6412 19375 6412 6410 19376 6410 6416 19377 6416 6412 19378 6412 6413 19379 6413 6416 19380 6416 6414 19381 6414 6412 19382 6412 6416 19383 6416 6415 19384 6415 6414 19385 6414 6417 19386 6417 6415 19387 6415 6416 19388 6416 6419 19389 6419 6415 19390 6415 6417 19391 6417 6419 19392 6419 6418 19393 6418 6415 19394 6415 6421 19395 6421 6418 19396 6418 6419 19397 6419 6421 19398 6421 6420 19399 6420 6418 19400 6418 6423 19401 6423 6420 19402 6420 6421 19403 6421 6423 19404 6423 6422 19405 6422 6420 19406 6420 6425 19407 6425 6422 19408 6422 6423 19409 6423 6425 19410 6425 6424 19411 6424 6422 19412 6422 6427 19413 6427 6424 19414 6424 6425 19415 6425 6427 19416 6427 6426 19417 6426 6424 19418 6424 6429 19419 6429 6426 19420 6426 6427 19421 6427 6429 19422 6429 6428 19423 6428 6426 19424 6426 6405 19425 6405 6428 19426 6428 6429 19427 6429 6461 19428 6461 6431 19429 6431 6430 19430 6430 6433 19431 6433 6431 19432 6431 6432 19433 6432 6430 19434 6430 6431 19435 6431 6433 19436 6433 6438 19437 6438 6434 19438 6434 6435 19439 6435 6438 19440 6438 6436 19441 6436 6434 19442 6434 6438 19443 6438 6437 19444 6437 6436 19445 6436 6440 19446 6440 6437 19447 6437 6438 19448 6438 6440 19449 6440 6439 19450 6439 6437 19451 6437 6442 19452 6442 6439 19453 6439 6440 19454 6440 6442 19455 6442 6441 19456 6441 6439 19457 6439 6444 19458 6444 6441 19459 6441 6442 19460 6442 6444 19461 6444 6443 19462 6443 6441 19463 6441 6446 19464 6446 6443 19465 6443 6444 19466 6444 6446 19467 6446 6445 19468 6445 6443 19469 6443 6447 19470 6447 6445 19471 6445 6446 19472 6446 6449 19473 6449 6445 19474 6445 6447 19475 6447 6449 19476 6449 6448 19477 6448 6445 19478 6445 6451 19479 6451 6448 19480 6448 6449 19481 6449 6451 19482 6451 6450 19483 6450 6448 19484 6448 6454 19485 6454 6450 19486 6450 6451 19487 6451 6454 19488 6454 6452 19489 6452 6450 19490 6450 6454 19491 6454 6453 19492 6453 6452 19493 6452 6455 19494 6455 6453 19495 6453 6454 19496 6454 6457 19497 6457 6453 19498 6453 6455 19499 6455 6457 19500 6457 6456 19501 6456 6453 19502 6453 6459 19503 6459 6456 19504 6456 6457 19505 6457 6459 19506 6459 6458 19507 6458 6456 19508 6456 6462 19509 6462 6458 19510 6458 6459 19511 6459 6462 19512 6462 6460 19513 6460 6458 19514 6458 6462 19515 6462 6461 19516 6461 6460 19517 6460 6463 19518 6463 6461 19519 6461 6462 19520 6462 6431 19521 6431 6461 19522 6461 6463 19523 6463 6497 19524 6497 6464 19525 6464 6469 19526 6469 6467 19527 6467 6465 19528 6465 6466 19529 6466 6468 19530 6468 6465 19531 6465 6467 19532 6467 6497 19533 6497 6465 19534 6465 6468 19535 6468 6497 19536 6497 6469 19537 6469 6465 19538 6465 6472 19539 6472 6470 19540 6470 6471 19541 6471 6474 19542 6474 6470 19543 6470 6472 19544 6472 6474 19545 6474 6473 19546 6473 6470 19547 6470 6475 19548 6475 6473 19549 6473 6474 19550 6474 6478 19551 6478 6473 19552 6473 6475 19553 6475 6478 19554 6478 6476 19555 6476 6473 19556 6473 6478 19557 6478 6477 19558 6477 6476 19559 6476 6479 19560 6479 6477 19561 6477 6478 19562 6478 6481 19563 6481 6477 19564 6477 6479 19565 6479 6481 19566 6481 6480 19567 6480 6477 19568 6477 6483 19569 6483 6480 19570 6480 6481 19571 6481 6483 19572 6483 6482 19573 6482 6480 19574 6480 6485 19575 6485 6482 19576 6482 6483 19577 6483 6485 19578 6485 6484 19579 6484 6482 19580 6482 6487 19581 6487 6484 19582 6484 6485 19583 6485 6487 19584 6487 6486 19585 6486 6484 19586 6484 6489 19587 6489 6486 19588 6486 6487 19589 6487 6489 19590 6489 6488 19591 6488 6486 19592 6486 6491 19593 6491 6488 19594 6488 6489 19595 6489 6491 19596 6491 6490 19597 6490 6488 19598 6488 6493 19599 6493 6490 19600 6490 6491 19601 6491 6493 19602 6493 6492 19603 6492 6490 19604 6490 6496 19605 6496 6492 19606 6492 6493 19607 6493 6496 19608 6496 6494 19609 6494 6492 19610 6492 6496 19611 6496 6495 19612 6495 6494 19613 6494 6464 19614 6464 6495 19615 6495 6496 19616 6496 6464 19617 6464 6497 19618 6497 6495 19619 6495 6531 19620 6531 6498 19621 6498 6503 19622 6503 6501 19623 6501 6499 19624 6499 6500 19625 6500 6502 19626 6502 6499 19627 6499 6501 19628 6501 6531 19629 6531 6499 19630 6499 6502 19631 6502 6531 19632 6531 6503 19633 6503 6499 19634 6499 6508 19635 6508 6504 19636 6504 6505 19637 6505 6508 19638 6508 6506 19639 6506 6504 19640 6504 6508 19641 6508 6507 19642 6507 6506 19643 6506 6510 19644 6510 6507 19645 6507 6508 19646 6508 6510 19647 6510 6509 19648 6509 6507 19649 6507 6512 19650 6512 6509 19651 6509 6510 19652 6510 6512 19653 6512 6511 19654 6511 6509 19655 6509 6514 19656 6514 6511 19657 6511 6512 19658 6512 6514 19659 6514 6513 19660 6513 6511 19661 6511 6515 19662 6515 6513 19663 6513 6514 19664 6514 6517 19665 6517 6513 19666 6513 6515 19667 6515 6517 19668 6517 6516 19669 6516 6513 19670 6513 6520 19671 6520 6516 19672 6516 6517 19673 6517 6520 19674 6520 6518 19675 6518 6516 19676 6516 6520 19677 6520 6519 19678 6519 6518 19679 6518 6522 19680 6522 6519 19681 6519 6520 19682 6520 6522 19683 6522 6521 19684 6521 6519 19685 6519 6524 19686 6524 6521 19687 6521 6522 19688 6522 6524 19689 6524 6523 19690 6523 6521 19691 6521 6526 19692 6526 6523 19693 6523 6524 19694 6524 6526 19695 6526 6525 19696 6525 6523 19697 6523 6527 19698 6527 6525 19699 6525 6526 19700 6526 6529 19701 6529 6525 19702 6525 6527 19703 6527 6529 19704 6529 6528 19705 6528 6525 19706 6525 6498 19707 6498 6528 19708 6528 6529 19709 6529 6498 19710 6498 6530 19711 6530 6528 19712 6528 6498 19713 6498 6531 19714 6531 6530 19715 6530 6564 19716 6564 6546 19717 6546 6532 19718 6532 6535 19719 6535 6533 19720 6533 6534 19721 6534 6536 19722 6536 6533 19723 6533 6535 19724 6535 6539 19725 6539 6533 19726 6533 6536 19727 6536 6539 19728 6539 6537 19729 6537 6533 19730 6533 6539 19731 6539 6538 19732 6538 6537 19733 6537 6540 19734 6540 6538 19735 6538 6539 19736 6539 6542 19737 6542 6538 19738 6538 6540 19739 6540 6542 19740 6542 6541 19741 6541 6538 19742 6538 6545 19743 6545 6541 19744 6541 6542 19745 6542 6545 19746 6545 6543 19747 6543 6541 19748 6541 6545 19749 6545 6544 19750 6544 6543 19751 6543 6547 19752 6547 6544 19753 6544 6545 19754 6545 6547 19755 6547 6546 19756 6546 6544 19757 6544 6532 19758 6532 6546 19759 6546 6547 19760 6547 6551 19761 6551 6548 19762 6548 6549 19763 6549 6551 19764 6551 6550 19765 6550 6548 19766 6548 6553 19767 6553 6550 19768 6550 6551 19769 6551 6553 19770 6553 6552 19771 6552 6550 19772 6550 6555 19773 6555 6552 19774 6552 6553 19775 6553 6555 19776 6555 6554 19777 6554 6552 19778 6552 6558 19779 6558 6554 19780 6554 6555 19781 6555 6558 19782 6558 6556 19783 6556 6554 19784 6554 6558 19785 6558 6557 19786 6557 6556 19787 6556 6559 19788 6559 6557 19789 6557 6558 19790 6558 6561 19791 6561 6557 19792 6557 6559 19793 6559 6561 19794 6561 6560 19795 6560 6557 19796 6557 6563 19797 6563 6560 19798 6560 6561 19799 6561 6563 19800 6563 6562 19801 6562 6560 19802 6560 6565 19803 6565 6562 19804 6562 6563 19805 6563 6565 19806 6565 6564 19807 6564 6562 19808 6562 6546 19809 6546 6564 19810 6564 6565 19811 6565 6598 19812 6598 6570 19813 6570 6566 19814 6566 6569 19815 6569 6567 19816 6567 6568 19817 6568 6571 19818 6571 6567 19819 6567 6569 19820 6569 6571 19821 6571 6570 19822 6570 6567 19823 6567 6566 19824 6566 6570 19825 6570 6571 19826 6571 6575 19827 6575 6572 19828 6572 6573 19829 6573 6575 19830 6575 6574 19831 6574 6572 19832 6572 6577 19833 6577 6574 19834 6574 6575 19835 6575 6577 19836 6577 6576 19837 6576 6574 19838 6574 6579 19839 6579 6576 19840 6576 6577 19841 6577 6579 19842 6579 6578 19843 6578 6576 19844 6576 6582 19845 6582 6578 19846 6578 6579 19847 6579 6582 19848 6582 6580 19849 6580 6578 19850 6578 6582 19851 6582 6581 19852 6581 6580 19853 6580 6583 19854 6583 6581 19855 6581 6582 19856 6582 6585 19857 6585 6581 19858 6581 6583 19859 6583 6585 19860 6585 6584 19861 6584 6581 19862 6581 6587 19863 6587 6584 19864 6584 6585 19865 6585 6587 19866 6587 6586 19867 6586 6584 19868 6584 6589 19869 6589 6586 19870 6586 6587 19871 6587 6589 19872 6589 6588 19873 6588 6586 19874 6586 6592 19875 6592 6588 19876 6588 6589 19877 6589 6592 19878 6592 6590 19879 6590 6588 19880 6588 6592 19881 6592 6591 19882 6591 6590 19883 6590 6593 19884 6593 6591 19885 6591 6592 19886 6592 6596 19887 6596 6591 19888 6591 6593 19889 6593 6596 19890 6596 6594 19891 6594 6591 19892 6591 6596 19893 6596 6595 19894 6595 6594 19895 6594 6597 19896 6597 6595 19897 6595 6596 19898 6596 6599 19899 6599 6595 19900 6595 6597 19901 6597 6599 19902 6599 6598 19903 6598 6595 19904 6595 6570 19905 6570 6598 19906 6598 6599 19907 6599 6631 19908 6631 6600 19909 6600 6601 19910 6601 6604 19911 6604 6602 19912 6602 6603 19913 6603 6606 19914 6606 6602 19915 6602 6604 19916 6604 6606 19917 6606 6605 19918 6605 6602 19919 6602 6608 19920 6608 6605 19921 6605 6606 19922 6606 6608 19923 6608 6607 19924 6607 6605 19925 6605 6610 19926 6610 6607 19927 6607 6608 19928 6608 6610 19929 6610 6609 19930 6609 6607 19931 6607 6611 19932 6611 6609 19933 6609 6610 19934 6610 6613 19935 6613 6609 19936 6609 6611 19937 6611 6613 19938 6613 6612 19939 6612 6609 19940 6609 6615 19941 6615 6612 19942 6612 6613 19943 6613 6615 19944 6615 6614 19945 6614 6612 19946 6612 6617 19947 6617 6614 19948 6614 6615 19949 6615 6617 19950 6617 6616 19951 6616 6614 19952 6614 6619 19953 6619 6616 19954 6616 6617 19955 6617 6619 19956 6619 6618 19957 6618 6616 19958 6616 6621 19959 6621 6618 19960 6618 6619 19961 6619 6621 19962 6621 6620 19963 6620 6618 19964 6618 6623 19965 6623 6620 19966 6620 6621 19967 6621 6623 19968 6623 6622 19969 6622 6620 19970 6620 6625 19971 6625 6622 19972 6622 6623 19973 6623 6625 19974 6625 6624 19975 6624 6622 19976 6622 6628 19977 6628 6624 19978 6624 6625 19979 6625 6628 19980 6628 6626 19981 6626 6624 19982 6624 6628 19983 6628 6627 19984 6627 6626 19985 6626 6629 19986 6629 6627 19987 6627 6628 19988 6628 6632 19989 6632 6627 19990 6627 6629 19991 6629 6632 19992 6632 6630 19993 6630 6627 19994 6627 6632 19995 6632 6631 19996 6631 6630 19997 6630 6633 19998 6633 6631 19999 6631 6632 20000 6632 6600 20001 6600 6631 20002 6631 6633 20003 6633 6667 20004 6667 6634 20005 6634 6635 20006 6635 6639 20007 6639 6636 20008 6636 6637 20009 6637 6639 20010 6639 6638 20011 6638 6636 20012 6636 6641 20013 6641 6638 20014 6638 6639 20015 6639 6641 20016 6641 6640 20017 6640 6638 20018 6638 6643 20019 6643 6640 20020 6640 6641 20021 6641 6643 20022 6643 6642 20023 6642 6640 20024 6640 6646 20025 6646 6642 20026 6642 6643 20027 6643 6646 20028 6646 6644 20029 6644 6642 20030 6642 6646 20031 6646 6645 20032 6645 6644 20033 6644 6647 20034 6647 6645 20035 6645 6646 20036 6646 6649 20037 6649 6645 20038 6645 6647 20039 6647 6649 20040 6649 6648 20041 6648 6645 20042 6645 6651 20043 6651 6648 20044 6648 6649 20045 6649 6651 20046 6651 6650 20047 6650 6648 20048 6648 6654 20049 6654 6650 20050 6650 6651 20051 6651 6654 20052 6654 6652 20053 6652 6650 20054 6650 6654 20055 6654 6653 20056 6653 6652 20057 6652 6656 20058 6656 6653 20059 6653 6654 20060 6654 6656 20061 6656 6655 20062 6655 6653 20063 6653 6658 20064 6658 6655 20065 6655 6656 20066 6656 6658 20067 6658 6657 20068 6657 6655 20069 6655 6660 20070 6660 6657 20071 6657 6658 20072 6658 6660 20073 6660 6659 20074 6659 6657 20075 6657 6661 20076 6661 6659 20077 6659 6660 20078 6660 6663 20079 6663 6659 20080 6659 6661 20081 6661 6663 20082 6663 6662 20083 6662 6659 20084 6659 6665 20085 6665 6662 20086 6662 6663 20087 6663 6665 20088 6665 6664 20089 6664 6662 20090 6662 6634 20091 6634 6664 20092 6664 6665 20093 6665 6634 20094 6634 6666 20095 6666 6664 20096 6664 6634 20097 6634 6667 20098 6667 6666 20099 6666 6699 20100 6699 6668 20101 6668 6669 20102 6669 6672 20103 6672 6670 20104 6670 6671 20105 6671 6673 20106 6673 6670 20107 6670 6672 20108 6672 6676 20109 6676 6670 20110 6670 6673 20111 6673 6676 20112 6676 6674 20113 6674 6670 20114 6670 6676 20115 6676 6675 20116 6675 6674 20117 6674 6678 20118 6678 6675 20119 6675 6676 20120 6676 6678 20121 6678 6677 20122 6677 6675 20123 6675 6679 20124 6679 6677 20125 6677 6678 20126 6678 6682 20127 6682 6677 20128 6677 6679 20129 6679 6682 20130 6682 6680 20131 6680 6677 20132 6677 6682 20133 6682 6681 20134 6681 6680 20135 6680 6683 20136 6683 6681 20137 6681 6682 20138 6682 6685 20139 6685 6681 20140 6681 6683 20141 6683 6685 20142 6685 6684 20143 6684 6681 20144 6681 6688 20145 6688 6684 20146 6684 6685 20147 6685 6688 20148 6688 6686 20149 6686 6684 20150 6684 6688 20151 6688 6687 20152 6687 6686 20153 6686 6689 20154 6689 6687 20155 6687 6688 20156 6688 6692 20157 6692 6687 20158 6687 6689 20159 6689 6692 20160 6692 6690 20161 6690 6687 20162 6687 6692 20163 6692 6691 20164 6691 6690 20165 6690 6693 20166 6693 6691 20167 6691 6692 20168 6692 6695 20169 6695 6691 20170 6691 6693 20171 6693 6695 20172 6695 6694 20173 6694 6691 20174 6691 6697 20175 6697 6694 20176 6694 6695 20177 6695 6697 20178 6697 6696 20179 6696 6694 20180 6694 6700 20181 6700 6696 20182 6696 6697 20183 6697 6700 20184 6700 6698 20185 6698 6696 20186 6696 6700 20187 6700 6699 20188 6699 6698 20189 6698 6701 20190 6701 6699 20191 6699 6700 20192 6700 6668 20193 6668 6699 20194 6699 6701 20195 6701 6734 20196 6734 6702 20197 6702 6703 20198 6703 6707 20199 6707 6704 20200 6704 6705 20201 6705 6707 20202 6707 6706 20203 6706 6704 20204 6704 6709 20205 6709 6706 20206 6706 6707 20207 6707 6709 20208 6709 6708 20209 6708 6706 20210 6706 6712 20211 6712 6708 20212 6708 6709 20213 6709 6712 20214 6712 6710 20215 6710 6708 20216 6708 6712 20217 6712 6711 20218 6711 6710 20219 6710 6713 20220 6713 6711 20221 6711 6712 20222 6712 6715 20223 6715 6711 20224 6711 6713 20225 6713 6715 20226 6715 6714 20227 6714 6711 20228 6711 6718 20229 6718 6714 20230 6714 6715 20231 6715 6718 20232 6718 6716 20233 6716 6714 20234 6714 6718 20235 6718 6717 20236 6717 6716 20237 6716 6720 20238 6720 6717 20239 6717 6718 20240 6718 6720 20241 6720 6719 20242 6719 6717 20243 6717 6722 20244 6722 6719 20245 6719 6720 20246 6720 6722 20247 6722 6721 20248 6721 6719 20249 6719 6724 20250 6724 6721 20251 6721 6722 20252 6722 6724 20253 6724 6723 20254 6723 6721 20255 6721 6725 20256 6725 6723 20257 6723 6724 20258 6724 6728 20259 6728 6723 20260 6723 6725 20261 6725 6728 20262 6728 6726 20263 6726 6723 20264 6723 6728 20265 6728 6727 20266 6727 6726 20267 6726 6729 20268 6729 6727 20269 6727 6728 20270 6728 6731 20271 6731 6727 20272 6727 6729 20273 6729 6731 20274 6731 6730 20275 6730 6727 20276 6727 6733 20277 6733 6730 20278 6730 6731 20279 6731 6733 20280 6733 6732 20281 6732 6730 20282 6730 6735 20283 6735 6732 20284 6732 6733 20285 6733 6735 20286 6735 6734 20287 6734 6732 20288 6732 6702 20289 6702 6734 20290 6734 6735 20291 6735 6767 20292 6767 6736 20293 6736 6737 20294 6737 6740 20295 6740 6738 20296 6738 6739 20297 6739 6741 20298 6741 6738 20299 6738 6740 20300 6740 6744 20301 6744 6738 20302 6738 6741 20303 6741 6744 20304 6744 6742 20305 6742 6738 20306 6738 6744 20307 6744 6743 20308 6743 6742 20309 6742 6746 20310 6746 6743 20311 6743 6744 20312 6744 6746 20313 6746 6745 20314 6745 6743 20315 6743 6747 20316 6747 6745 20317 6745 6746 20318 6746 6750 20319 6750 6745 20320 6745 6747 20321 6747 6750 20322 6750 6748 20323 6748 6745 20324 6745 6750 20325 6750 6749 20326 6749 6748 20327 6748 6751 20328 6751 6749 20329 6749 6750 20330 6750 6753 20331 6753 6749 20332 6749 6751 20333 6751 6753 20334 6753 6752 20335 6752 6749 20336 6749 6755 20337 6755 6752 20338 6752 6753 20339 6753 6755 20340 6755 6754 20341 6754 6752 20342 6752 6757 20343 6757 6754 20344 6754 6755 20345 6755 6757 20346 6757 6756 20347 6756 6754 20348 6754 6759 20349 6759 6756 20350 6756 6757 20351 6757 6759 20352 6759 6758 20353 6758 6756 20354 6756 6761 20355 6761 6758 20356 6758 6759 20357 6759 6761 20358 6761 6760 20359 6760 6758 20360 6758 6763 20361 6763 6760 20362 6760 6761 20363 6761 6763 20364 6763 6762 20365 6762 6760 20366 6760 6765 20367 6765 6762 20368 6762 6763 20369 6763 6765 20370 6765 6764 20371 6764 6762 20372 6762 6768 20373 6768 6764 20374 6764 6765 20375 6765 6768 20376 6768 6766 20377 6766 6764 20378 6764 6768 20379 6768 6767 20380 6767 6766 20381 6766 6769 20382 6769 6767 20383 6767 6768 20384 6768 6736 20385 6736 6767 20386 6767 6769 20387 6769 6802 20388 6802 6770 20389 6770 6771 20390 6771 6776 20391 6776 6772 20392 6772 6773 20393 6773 6776 20394 6776 6774 20395 6774 6772 20396 6772 6776 20397 6776 6775 20398 6775 6774 20399 6774 6777 20400 6777 6775 20401 6775 6776 20402 6776 6780 20403 6780 6775 20404 6775 6777 20405 6777 6780 20406 6780 6778 20407 6778 6775 20408 6775 6780 20409 6780 6779 20410 6779 6778 20411 6778 6781 20412 6781 6779 20413 6779 6780 20414 6780 6783 20415 6783 6779 20416 6779 6781 20417 6781 6783 20418 6783 6782 20419 6782 6779 20420 6779 6786 20421 6786 6782 20422 6782 6783 20423 6783 6786 20424 6786 6784 20425 6784 6782 20426 6782 6786 20427 6786 6785 20428 6785 6784 20429 6784 6787 20430 6787 6785 20431 6785 6786 20432 6786 6789 20433 6789 6785 20434 6785 6787 20435 6787 6789 20436 6789 6788 20437 6788 6785 20438 6785 6792 20439 6792 6788 20440 6788 6789 20441 6789 6792 20442 6792 6790 20443 6790 6788 20444 6788 6792 20445 6792 6791 20446 6791 6790 20447 6790 6793 20448 6793 6791 20449 6791 6792 20450 6792 6796 20451 6796 6791 20452 6791 6793 20453 6793 6796 20454 6796 6794 20455 6794 6791 20456 6791 6796 20457 6796 6795 20458 6795 6794 20459 6794 6797 20460 6797 6795 20461 6795 6796 20462 6796 6799 20463 6799 6795 20464 6795 6797 20465 6797 6799 20466 6799 6798 20467 6798 6795 20468 6795 6801 20469 6801 6798 20470 6798 6799 20471 6799 6801 20472 6801 6800 20473 6800 6798 20474 6798 6803 20475 6803 6800 20476 6800 6801 20477 6801 6803 20478 6803 6802 20479 6802 6800 20480 6800 6770 20481 6770 6802 20482 6802 6803 20483 6803 6836 20484 6836 6804 20485 6804 6805 20486 6805 6810 20487 6810 6806 20488 6806 6807 20489 6807 6810 20490 6810 6808 20491 6808 6806 20492 6806 6810 20493 6810 6809 20494 6809 6808 20495 6808 6812 20496 6812 6809 20497 6809 6810 20498 6810 6812 20499 6812 6811 20500 6811 6809 20501 6809 6813 20502 6813 6811 20503 6811 6812 20504 6812 6815 20505 6815 6811 20506 6811 6813 20507 6813 6815 20508 6815 6814 20509 6814 6811 20510 6811 6817 20511 6817 6814 20512 6814 6815 20513 6815 6817 20514 6817 6816 20515 6816 6814 20516 6814 6819 20517 6819 6816 20518 6816 6817 20519 6817 6819 20520 6819 6818 20521 6818 6816 20522 6816 6821 20523 6821 6818 20524 6818 6819 20525 6819 6821 20526 6821 6820 20527 6820 6818 20528 6818 6823 20529 6823 6820 20530 6820 6821 20531 6821 6823 20532 6823 6822 20533 6822 6820 20534 6820 6825 20535 6825 6822 20536 6822 6823 20537 6823 6825 20538 6825 6824 20539 6824 6822 20540 6822 6827 20541 6827 6824 20542 6824 6825 20543 6825 6827 20544 6827 6826 20545 6826 6824 20546 6824 6830 20547 6830 6826 20548 6826 6827 20549 6827 6830 20550 6830 6828 20551 6828 6826 20552 6826 6830 20553 6830 6829 20554 6829 6828 20555 6828 6831 20556 6831 6829 20557 6829 6830 20558 6830 6833 20559 6833 6829 20560 6829 6831 20561 6831 6833 20562 6833 6832 20563 6832 6829 20564 6829 6835 20565 6835 6832 20566 6832 6833 20567 6833 6835 20568 6835 6834 20569 6834 6832 20570 6832 6837 20571 6837 6834 20572 6834 6835 20573 6835 6837 20574 6837 6836 20575 6836 6834 20576 6834 6804 20577 6804 6836 20578 6836 6837 20579 6837 6869 20580 6869 6838 20581 6838 6839 20582 6839 6844 20583 6844 6840 20584 6840 6841 20585 6841 6844 20586 6844 6842 20587 6842 6840 20588 6840 6844 20589 6844 6843 20590 6843 6842 20591 6842 6845 20592 6845 6843 20593 6843 6844 20594 6844 6847 20595 6847 6843 20596 6843 6845 20597 6845 6847 20598 6847 6846 20599 6846 6843 20600 6843 6849 20601 6849 6846 20602 6846 6847 20603 6847 6849 20604 6849 6848 20605 6848 6846 20606 6846 6851 20607 6851 6848 20608 6848 6849 20609 6849 6851 20610 6851 6850 20611 6850 6848 20612 6848 6853 20613 6853 6850 20614 6850 6851 20615 6851 6853 20616 6853 6852 20617 6852 6850 20618 6850 6855 20619 6855 6852 20620 6852 6853 20621 6853 6855 20622 6855 6854 20623 6854 6852 20624 6852 6857 20625 6857 6854 20626 6854 6855 20627 6855 6857 20628 6857 6856 20629 6856 6854 20630 6854 6859 20631 6859 6856 20632 6856 6857 20633 6857 6859 20634 6859 6858 20635 6858 6856 20636 6856 6861 20637 6861 6858 20638 6858 6859 20639 6859 6861 20640 6861 6860 20641 6860 6858 20642 6858 6863 20643 6863 6860 20644 6860 6861 20645 6861 6863 20646 6863 6862 20647 6862 6860 20648 6860 6865 20649 6865 6862 20650 6862 6863 20651 6863 6865 20652 6865 6864 20653 6864 6862 20654 6862 6868 20655 6868 6864 20656 6864 6865 20657 6865 6868 20658 6868 6866 20659 6866 6864 20660 6864 6868 20661 6868 6867 20662 6867 6866 20663 6866 6870 20664 6870 6867 20665 6867 6868 20666 6868 6870 20667 6870 6869 20668 6869 6867 20669 6867 6871 20670 6871 6869 20671 6869 6870 20672 6870 6838 20673 6838 6869 20674 6869 6871 20675 6871 6904 20676 6904 6872 20677 6872 6873 20678 6873 6876 20679 6876 6874 20680 6874 6875 20681 6875 6877 20682 6877 6874 20683 6874 6876 20684 6876 6879 20685 6879 6874 20686 6874 6877 20687 6877 6879 20688 6879 6878 20689 6878 6874 20690 6874 6881 20691 6881 6878 20692 6878 6879 20693 6879 6881 20694 6881 6880 20695 6880 6878 20696 6878 6883 20697 6883 6880 20698 6880 6881 20699 6881 6883 20700 6883 6882 20701 6882 6880 20702 6880 6885 20703 6885 6882 20704 6882 6883 20705 6883 6885 20706 6885 6884 20707 6884 6882 20708 6882 6887 20709 6887 6884 20710 6884 6885 20711 6885 6887 20712 6887 6886 20713 6886 6884 20714 6884 6889 20715 6889 6886 20716 6886 6887 20717 6887 6889 20718 6889 6888 20719 6888 6886 20720 6886 6891 20721 6891 6888 20722 6888 6889 20723 6889 6891 20724 6891 6890 20725 6890 6888 20726 6888 6893 20727 6893 6890 20728 6890 6891 20729 6891 6893 20730 6893 6892 20731 6892 6890 20732 6890 6895 20733 6895 6892 20734 6892 6893 20735 6893 6895 20736 6895 6894 20737 6894 6892 20738 6892 6898 20739 6898 6894 20740 6894 6895 20741 6895 6898 20742 6898 6896 20743 6896 6894 20744 6894 6898 20745 6898 6897 20746 6897 6896 20747 6896 6899 20748 6899 6897 20749 6897 6898 20750 6898 6901 20751 6901 6897 20752 6897 6899 20753 6899 6901 20754 6901 6900 20755 6900 6897 20756 6897 6903 20757 6903 6900 20758 6900 6901 20759 6901 6903 20760 6903 6902 20761 6902 6900 20762 6900 6905 20763 6905 6902 20764 6902 6903 20765 6903 6905 20766 6905 6904 20767 6904 6902 20768 6902 6872 20769 6872 6904 20770 6904 6905 20771 6905 6938 20772 6938 6919 20773 6919 6906 20774 6906 6909 20775 6909 6907 20776 6907 6908 20777 6908 6911 20778 6911 6907 20779 6907 6909 20780 6909 6911 20781 6911 6910 20782 6910 6907 20783 6907 6913 20784 6913 6910 20785 6910 6911 20786 6911 6913 20787 6913 6912 20788 6912 6910 20789 6910 6915 20790 6915 6912 20791 6912 6913 20792 6913 6915 20793 6915 6914 20794 6914 6912 20795 6912 6916 20796 6916 6914 20797 6914 6915 20798 6915 6918 20799 6918 6914 20800 6914 6916 20801 6916 6918 20802 6918 6917 20803 6917 6914 20804 6914 6906 20805 6906 6917 20806 6917 6918 20807 6918 6906 20808 6906 6919 20809 6919 6917 20810 6917 6922 20811 6922 6920 20812 6920 6921 20813 6921 6923 20814 6923 6920 20815 6920 6922 20816 6922 6926 20817 6926 6920 20818 6920 6923 20819 6923 6926 20820 6926 6924 20821 6924 6920 20822 6920 6926 20823 6926 6925 20824 6925 6924 20825 6924 6927 20826 6927 6925 20827 6925 6926 20828 6926 6930 20829 6930 6925 20830 6925 6927 20831 6927 6930 20832 6930 6928 20833 6928 6925 20834 6925 6930 20835 6930 6929 20836 6929 6928 20837 6928 6931 20838 6931 6929 20839 6929 6930 20840 6930 6933 20841 6933 6929 20842 6929 6931 20843 6931 6933 20844 6933 6932 20845 6932 6929 20846 6929 6935 20847 6935 6932 20848 6932 6933 20849 6933 6935 20850 6935 6934 20851 6934 6932 20852 6932 6937 20853 6937 6934 20854 6934 6935 20855 6935 6937 20856 6937 6936 20857 6936 6934 20858 6934 6939 20859 6939 6936 20860 6936 6937 20861 6937 6939 20862 6939 6938 20863 6938 6936 20864 6936 6919 20865 6919 6938 20866 6938 6939 20867 6939 6972 20868 6972 6940 20869 6940 6941 20870 6941 6946 20871 6946 6942 20872 6942 6943 20873 6943 6946 20874 6946 6944 20875 6944 6942 20876 6942 6946 20877 6946 6945 20878 6945 6944 20879 6944 6947 20880 6947 6945 20881 6945 6946 20882 6946 6950 20883 6950 6945 20884 6945 6947 20885 6947 6950 20886 6950 6948 20887 6948 6945 20888 6945 6950 20889 6950 6949 20890 6949 6948 20891 6948 6952 20892 6952 6949 20893 6949 6950 20894 6950 6952 20895 6952 6951 20896 6951 6949 20897 6949 6953 20898 6953 6951 20899 6951 6952 20900 6952 6955 20901 6955 6951 20902 6951 6953 20903 6953 6955 20904 6955 6954 20905 6954 6951 20906 6951 6958 20907 6958 6954 20908 6954 6955 20909 6955 6958 20910 6958 6956 20911 6956 6954 20912 6954 6958 20913 6958 6957 20914 6957 6956 20915 6956 6960 20916 6960 6957 20917 6957 6958 20918 6958 6960 20919 6960 6959 20920 6959 6957 20921 6957 6961 20922 6961 6959 20923 6959 6960 20924 6960 6964 20925 6964 6959 20926 6959 6961 20927 6961 6964 20928 6964 6962 20929 6962 6959 20930 6959 6964 20931 6964 6963 20932 6963 6962 20933 6962 6966 20934 6966 6963 20935 6963 6964 20936 6964 6966 20937 6966 6965 20938 6965 6963 20939 6963 6967 20940 6967 6965 20941 6965 6966 20942 6966 6969 20943 6969 6965 20944 6965 6967 20945 6967 6969 20946 6969 6968 20947 6968 6965 20948 6965 6971 20949 6971 6968 20950 6968 6969 20951 6969 6971 20952 6971 6970 20953 6970 6968 20954 6968 6973 20955 6973 6970 20956 6970 6971 20957 6971 6973 20958 6973 6972 20959 6972 6970 20960 6970 6940 20961 6940 6972 20962 6972 6973 20963 6973 7006 20964 7006 6974 20965 6974 6975 20966 6975 6978 20967 6978 6976 20968 6976 6977 20969 6977 6980 20970 6980 6976 20971 6976 6978 20972 6978 6980 20973 6980 6979 20974 6979 6976 20975 6976 6982 20976 6982 6979 20977 6979 6980 20978 6980 6982 20979 6982 6981 20980 6981 6979 20981 6979 6983 20982 6983 6981 20983 6981 6982 20984 6982 6986 20985 6986 6981 20986 6981 6983 20987 6983 6986 20988 6986 6984 20989 6984 6981 20990 6981 6986 20991 6986 6985 20992 6985 6984 20993 6984 6988 20994 6988 6985 20995 6985 6986 20996 6986 6988 20997 6988 6987 20998 6987 6985 20999 6985 6990 21000 6990 6987 21001 6987 6988 21002 6988 6990 21003 6990 6989 21004 6989 6987 21005 6987 6991 21006 6991 6989 21007 6989 6990 21008 6990 6993 21009 6993 6989 21010 6989 6991 21011 6991 6993 21012 6993 6992 21013 6992 6989 21014 6989 6996 21015 6996 6992 21016 6992 6993 21017 6993 6996 21018 6996 6994 21019 6994 6992 21020 6992 6996 21021 6996 6995 21022 6995 6994 21023 6994 6997 21024 6997 6995 21025 6995 6996 21026 6996 6999 21027 6999 6995 21028 6995 6997 21029 6997 6999 21030 6999 6998 21031 6998 6995 21032 6995 7001 21033 7001 6998 21034 6998 6999 21035 6999 7001 21036 7001 7000 21037 7000 6998 21038 6998 7004 21039 7004 7000 21040 7000 7001 21041 7001 7004 21042 7004 7002 21043 7002 7000 21044 7000 7004 21045 7004 7003 21046 7003 7002 21047 7002 7005 21048 7005 7003 21049 7003 7004 21050 7004 7007 21051 7007 7003 21052 7003 7005 21053 7005 7007 21054 7007 7006 21055 7006 7003 21056 7003 6974 21057 6974 7006 21058 7006 7007 21059 7007 7040 21060 7040 7008 21061 7008 7009 21062 7009 7012 21063 7012 7010 21064 7010 7011 21065 7011 7014 21066 7014 7010 21067 7010 7012 21068 7012 7014 21069 7014 7013 21070 7013 7010 21071 7010 7015 21072 7015 7013 21073 7013 7014 21074 7014 7018 21075 7018 7013 21076 7013 7015 21077 7015 7018 21078 7018 7016 21079 7016 7013 21080 7013 7018 21081 7018 7017 21082 7017 7016 21083 7016 7020 21084 7020 7017 21085 7017 7018 21086 7018 7020 21087 7020 7019 21088 7019 7017 21089 7017 7021 21090 7021 7019 21091 7019 7020 21092 7020 7023 21093 7023 7019 21094 7019 7021 21095 7021 7023 21096 7023 7022 21097 7022 7019 21098 7019 7025 21099 7025 7022 21100 7022 7023 21101 7023 7025 21102 7025 7024 21103 7024 7022 21104 7022 7027 21105 7027 7024 21106 7024 7025 21107 7025 7027 21108 7027 7026 21109 7026 7024 21110 7024 7029 21111 7029 7026 21112 7026 7027 21113 7027 7029 21114 7029 7028 21115 7028 7026 21116 7026 7031 21117 7031 7028 21118 7028 7029 21119 7029 7031 21120 7031 7030 21121 7030 7028 21122 7028 7033 21123 7033 7030 21124 7030 7031 21125 7031 7033 21126 7033 7032 21127 7032 7030 21128 7030 7035 21129 7035 7032 21130 7032 7033 21131 7033 7035 21132 7035 7034 21133 7034 7032 21134 7032 7037 21135 7037 7034 21136 7034 7035 21137 7035 7037 21138 7037 7036 21139 7036 7034 21140 7034 7039 21141 7039 7036 21142 7036 7037 21143 7037 7039 21144 7039 7038 21145 7038 7036 21146 7036 7041 21147 7041 7038 21148 7038 7039 21149 7039 7041 21150 7041 7040 21151 7040 7038 21152 7038 7008 21153 7008 7040 21154 7040 7041 21155 7041 7074 21156 7074 7042 21157 7042 7043 21158 7043 7046 21159 7046 7044 21160 7044 7045 21161 7045 7048 21162 7048 7044 21163 7044 7046 21164 7046 7048 21165 7048 7047 21166 7047 7044 21167 7044 7049 21168 7049 7047 21169 7047 7048 21170 7048 7052 21171 7052 7047 21172 7047 7049 21173 7049 7052 21174 7052 7050 21175 7050 7047 21176 7047 7052 21177 7052 7051 21178 7051 7050 21179 7050 7053 21180 7053 7051 21181 7051 7052 21182 7052 7055 21183 7055 7051 21184 7051 7053 21185 7053 7055 21186 7055 7054 21187 7054 7051 21188 7051 7057 21189 7057 7054 21190 7054 7055 21191 7055 7057 21192 7057 7056 21193 7056 7054 21194 7054 7059 21195 7059 7056 21196 7056 7057 21197 7057 7059 21198 7059 7058 21199 7058 7056 21200 7056 7061 21201 7061 7058 21202 7058 7059 21203 7059 7061 21204 7061 7060 21205 7060 7058 21206 7058 7063 21207 7063 7060 21208 7060 7061 21209 7061 7063 21210 7063 7062 21211 7062 7060 21212 7060 7065 21213 7065 7062 21214 7062 7063 21215 7063 7065 21216 7065 7064 21217 7064 7062 21218 7062 7067 21219 7067 7064 21220 7064 7065 21221 7065 7067 21222 7067 7066 21223 7066 7064 21224 7064 7069 21225 7069 7066 21226 7066 7067 21227 7067 7069 21228 7069 7068 21229 7068 7066 21230 7066 7071 21231 7071 7068 21232 7068 7069 21233 7069 7071 21234 7071 7070 21235 7070 7068 21236 7068 7073 21237 7073 7070 21238 7070 7071 21239 7071 7073 21240 7073 7072 21241 7072 7070 21242 7070 7075 21243 7075 7072 21244 7072 7073 21245 7073 7075 21246 7075 7074 21247 7074 7072 21248 7072 7042 21249 7042 7074 21250 7074 7075 21251 7075 7108 21252 7108 7076 21253 7076 7077 21254 7077 7080 21255 7080 7078 21256 7078 7079 21257 7079 7082 21258 7082 7078 21259 7078 7080 21260 7080 7082 21261 7082 7081 21262 7081 7078 21263 7078 7084 21264 7084 7081 21265 7081 7082 21266 7082 7084 21267 7084 7083 21268 7083 7081 21269 7081 7085 21270 7085 7083 21271 7083 7084 21272 7084 7087 21273 7087 7083 21274 7083 7085 21275 7085 7087 21276 7087 7086 21277 7086 7083 21278 7083 7090 21279 7090 7086 21280 7086 7087 21281 7087 7090 21282 7090 7088 21283 7088 7086 21284 7086 7090 21285 7090 7089 21286 7089 7088 21287 7088 7092 21288 7092 7089 21289 7089 7090 21290 7090 7092 21291 7092 7091 21292 7091 7089 21293 7089 7093 21294 7093 7091 21295 7091 7092 21296 7092 7096 21297 7096 7091 21298 7091 7093 21299 7093 7096 21300 7096 7094 21301 7094 7091 21302 7091 7096 21303 7096 7095 21304 7095 7094 21305 7094 7098 21306 7098 7095 21307 7095 7096 21308 7096 7098 21309 7098 7097 21310 7097 7095 21311 7095 7099 21312 7099 7097 21313 7097 7098 21314 7098 7102 21315 7102 7097 21316 7097 7099 21317 7099 7102 21318 7102 7100 21319 7100 7097 21320 7097 7102 21321 7102 7101 21322 7101 7100 21323 7100 7103 21324 7103 7101 21325 7101 7102 21326 7102 7105 21327 7105 7101 21328 7101 7103 21329 7103 7105 21330 7105 7104 21331 7104 7101 21332 7101 7107 21333 7107 7104 21334 7104 7105 21335 7105 7107 21336 7107 7106 21337 7106 7104 21338 7104 7109 21339 7109 7106 21340 7106 7107 21341 7107 7109 21342 7109 7108 21343 7108 7106 21344 7106 7076 21345 7076 7108 21346 7108 7109 21347 7109 7142 21348 7142 7110 21349 7110 7111 21350 7111 7116 21351 7116 7112 21352 7112 7113 21353 7113 7116 21354 7116 7114 21355 7114 7112 21356 7112 7116 21357 7116 7115 21358 7115 7114 21359 7114 7117 21360 7117 7115 21361 7115 7116 21362 7116 7119 21363 7119 7115 21364 7115 7117 21365 7117 7119 21366 7119 7118 21367 7118 7115 21368 7115 7121 21369 7121 7118 21370 7118 7119 21371 7119 7121 21372 7121 7120 21373 7120 7118 21374 7118 7123 21375 7123 7120 21376 7120 7121 21377 7121 7123 21378 7123 7122 21379 7122 7120 21380 7120 7125 21381 7125 7122 21382 7122 7123 21383 7123 7125 21384 7125 7124 21385 7124 7122 21386 7122 7127 21387 7127 7124 21388 7124 7125 21389 7125 7127 21390 7127 7126 21391 7126 7124 21392 7124 7129 21393 7129 7126 21394 7126 7127 21395 7127 7129 21396 7129 7128 21397 7128 7126 21398 7126 7132 21399 7132 7128 21400 7128 7129 21401 7129 7132 21402 7132 7130 21403 7130 7128 21404 7128 7132 21405 7132 7131 21406 7131 7130 21407 7130 7133 21408 7133 7131 21409 7131 7132 21410 7132 7135 21411 7135 7131 21412 7131 7133 21413 7133 7135 21414 7135 7134 21415 7134 7131 21416 7131 7137 21417 7137 7134 21418 7134 7135 21419 7135 7137 21420 7137 7136 21421 7136 7134 21422 7134 7139 21423 7139 7136 21424 7136 7137 21425 7137 7139 21426 7139 7138 21427 7138 7136 21428 7136 7141 21429 7141 7138 21430 7138 7139 21431 7139 7141 21432 7141 7140 21433 7140 7138 21434 7138 7143 21435 7143 7140 21436 7140 7141 21437 7141 7143 21438 7143 7142 21439 7142 7140 21440 7140 7110 21441 7110 7142 21442 7142 7143 21443 7143 7176 21444 7176 7144 21445 7144 7145 21446 7145 7150 21447 7150 7146 21448 7146 7147 21449 7147 7150 21450 7150 7148 21451 7148 7146 21452 7146 7150 21453 7150 7149 21454 7149 7148 21455 7148 7151 21456 7151 7149 21457 7149 7150 21458 7150 7153 21459 7153 7149 21460 7149 7151 21461 7151 7153 21462 7153 7152 21463 7152 7149 21464 7149 7155 21465 7155 7152 21466 7152 7153 21467 7153 7155 21468 7155 7154 21469 7154 7152 21470 7152 7157 21471 7157 7154 21472 7154 7155 21473 7155 7157 21474 7157 7156 21475 7156 7154 21476 7154 7159 21477 7159 7156 21478 7156 7157 21479 7157 7159 21480 7159 7158 21481 7158 7156 21482 7156 7161 21483 7161 7158 21484 7158 7159 21485 7159 7161 21486 7161 7160 21487 7160 7158 21488 7158 7163 21489 7163 7160 21490 7160 7161 21491 7161 7163 21492 7163 7162 21493 7162 7160 21494 7160 7166 21495 7166 7162 21496 7162 7163 21497 7163 7166 21498 7166 7164 21499 7164 7162 21500 7162 7166 21501 7166 7165 21502 7165 7164 21503 7164 7167 21504 7167 7165 21505 7165 7166 21506 7166 7169 21507 7169 7165 21508 7165 7167 21509 7167 7169 21510 7169 7168 21511 7168 7165 21512 7165 7171 21513 7171 7168 21514 7168 7169 21515 7169 7171 21516 7171 7170 21517 7170 7168 21518 7168 7173 21519 7173 7170 21520 7170 7171 21521 7171 7173 21522 7173 7172 21523 7172 7170 21524 7170 7175 21525 7175 7172 21526 7172 7173 21527 7173 7175 21528 7175 7174 21529 7174 7172 21530 7172 7177 21531 7177 7174 21532 7174 7175 21533 7175 7177 21534 7177 7176 21535 7176 7174 21536 7174 7144 21537 7144 7176 21538 7176 7177 21539 7177 7210 21540 7210 7190 21541 7190 7178 21542 7178 7181 21543 7181 7179 21544 7179 7180 21545 7180 7183 21546 7183 7179 21547 7179 7181 21548 7181 7183 21549 7183 7182 21550 7182 7179 21551 7179 7185 21552 7185 7182 21553 7182 7183 21554 7183 7185 21555 7185 7184 21556 7184 7182 21557 7182 7186 21558 7186 7184 21559 7184 7185 21560 7185 7189 21561 7189 7184 21562 7184 7186 21563 7186 7189 21564 7189 7187 21565 7187 7184 21566 7184 7189 21567 7189 7188 21568 7188 7187 21569 7187 7191 21570 7191 7188 21571 7188 7189 21572 7189 7191 21573 7191 7190 21574 7190 7188 21575 7188 7178 21576 7178 7190 21577 7190 7191 21578 7191 7194 21579 7194 7192 21580 7192 7193 21581 7193 7195 21582 7195 7192 21583 7192 7194 21584 7194 7198 21585 7198 7192 21586 7192 7195 21587 7195 7198 21588 7198 7196 21589 7196 7192 21590 7192 7198 21591 7198 7197 21592 7197 7196 21593 7196 7199 21594 7199 7197 21595 7197 7198 21596 7198 7202 21597 7202 7197 21598 7197 7199 21599 7199 7202 21600 7202 7200 21601 7200 7197 21602 7197 7202 21603 7202 7201 21604 7201 7200 21605 7200 7203 21606 7203 7201 21607 7201 7202 21608 7202 7205 21609 7205 7201 21610 7201 7203 21611 7203 7205 21612 7205 7204 21613 7204 7201 21614 7201 7207 21615 7207 7204 21616 7204 7205 21617 7205 7207 21618 7207 7206 21619 7206 7204 21620 7204 7209 21621 7209 7206 21622 7206 7207 21623 7207 7209 21624 7209 7208 21625 7208 7206 21626 7206 7211 21627 7211 7208 21628 7208 7209 21629 7209 7211 21630 7211 7210 21631 7210 7208 21632 7208 7190 21633 7190 7210 21634 7210 7211 21635 7211 7244 21636 7244 7212 21637 7212 7213 21638 7213 7216 21639 7216 7214 21640 7214 7215 21641 7215 7218 21642 7218 7214 21643 7214 7216 21644 7216 7218 21645 7218 7217 21646 7217 7214 21647 7214 7220 21648 7220 7217 21649 7217 7218 21650 7218 7220 21651 7220 7219 21652 7219 7217 21653 7217 7221 21654 7221 7219 21655 7219 7220 21656 7220 7224 21657 7224 7219 21658 7219 7221 21659 7221 7224 21660 7224 7222 21661 7222 7219 21662 7219 7224 21663 7224 7223 21664 7223 7222 21665 7222 7226 21666 7226 7223 21667 7223 7224 21668 7224 7226 21669 7226 7225 21670 7225 7223 21671 7223 7227 21672 7227 7225 21673 7225 7226 21674 7226 7229 21675 7229 7225 21676 7225 7227 21677 7227 7229 21678 7229 7228 21679 7228 7225 21680 7225 7231 21681 7231 7228 21682 7228 7229 21683 7229 7231 21684 7231 7230 21685 7230 7228 21686 7228 7233 21687 7233 7230 21688 7230 7231 21689 7231 7233 21690 7233 7232 21691 7232 7230 21692 7230 7235 21693 7235 7232 21694 7232 7233 21695 7233 7235 21696 7235 7234 21697 7234 7232 21698 7232 7237 21699 7237 7234 21700 7234 7235 21701 7235 7237 21702 7237 7236 21703 7236 7234 21704 7234 7240 21705 7240 7236 21706 7236 7237 21707 7237 7240 21708 7240 7238 21709 7238 7236 21710 7236 7240 21711 7240 7239 21712 7239 7238 21713 7238 7241 21714 7241 7239 21715 7239 7240 21716 7240 7243 21717 7243 7239 21718 7239 7241 21719 7241 7243 21720 7243 7242 21721 7242 7239 21722 7239 7245 21723 7245 7242 21724 7242 7243 21725 7243 7245 21726 7245 7244 21727 7244 7242 21728 7242 7212 21729 7212 7244 21730 7244 7245 21731 7245 7278 21732 7278 7246 21733 7246 7247 21734 7247 7250 21735 7250 7248 21736 7248 7249 21737 7249 7252 21738 7252 7248 21739 7248 7250 21740 7250 7252 21741 7252 7251 21742 7251 7248 21743 7248 7254 21744 7254 7251 21745 7251 7252 21746 7252 7254 21747 7254 7253 21748 7253 7251 21749 7251 7256 21750 7256 7253 21751 7253 7254 21752 7254 7256 21753 7256 7255 21754 7255 7253 21755 7253 7257 21756 7257 7255 21757 7255 7256 21758 7256 7259 21759 7259 7255 21760 7255 7257 21761 7257 7259 21762 7259 7258 21763 7258 7255 21764 7255 7262 21765 7262 7258 21766 7258 7259 21767 7259 7262 21768 7262 7260 21769 7260 7258 21770 7258 7262 21771 7262 7261 21772 7261 7260 21773 7260 7264 21774 7264 7261 21775 7261 7262 21776 7262 7264 21777 7264 7263 21778 7263 7261 21779 7261 7266 21780 7266 7263 21781 7263 7264 21782 7264 7266 21783 7266 7265 21784 7265 7263 21785 7263 7267 21786 7267 7265 21787 7265 7266 21788 7266 7270 21789 7270 7265 21790 7265 7267 21791 7267 7270 21792 7270 7268 21793 7268 7265 21794 7265 7270 21795 7270 7269 21796 7269 7268 21797 7268 7272 21798 7272 7269 21799 7269 7270 21800 7270 7272 21801 7272 7271 21802 7271 7269 21803 7269 7273 21804 7273 7271 21805 7271 7272 21806 7272 7275 21807 7275 7271 21808 7271 7273 21809 7273 7275 21810 7275 7274 21811 7274 7271 21812 7271 7277 21813 7277 7274 21814 7274 7275 21815 7275 7277 21816 7277 7276 21817 7276 7274 21818 7274 7279 21819 7279 7276 21820 7276 7277 21821 7277 7279 21822 7279 7278 21823 7278 7276 21824 7276 7246 21825 7246 7278 21826 7278 7279 21827 7279 7312 21828 7312 7283 21829 7283 7280 21830 7280 7280 21831 7280 7281 21832 7281 7282 21833 7282 7280 21834 7280 7283 21835 7283 7281 21836 7281 7288 21837 7288 7284 21838 7284 7285 21839 7285 7288 21840 7288 7286 21841 7286 7284 21842 7284 7288 21843 7288 7287 21844 7287 7286 21845 7286 7289 21846 7289 7287 21847 7287 7288 21848 7288 7291 21849 7291 7287 21850 7287 7289 21851 7289 7291 21852 7291 7290 21853 7290 7287 21854 7287 7293 21855 7293 7290 21856 7290 7291 21857 7291 7293 21858 7293 7292 21859 7292 7290 21860 7290 7296 21861 7296 7292 21862 7292 7293 21863 7293 7296 21864 7296 7294 21865 7294 7292 21866 7292 7296 21867 7296 7295 21868 7295 7294 21869 7294 7297 21870 7297 7295 21871 7295 7296 21872 7296 7299 21873 7299 7295 21874 7295 7297 21875 7297 7299 21876 7299 7298 21877 7298 7295 21878 7295 7302 21879 7302 7298 21880 7298 7299 21881 7299 7302 21882 7302 7300 21883 7300 7298 21884 7298 7302 21885 7302 7301 21886 7301 7300 21887 7300 7304 21888 7304 7301 21889 7301 7302 21890 7302 7304 21891 7304 7303 21892 7303 7301 21893 7301 7306 21894 7306 7303 21895 7303 7304 21896 7304 7306 21897 7306 7305 21898 7305 7303 21899 7303 7307 21900 7307 7305 21901 7305 7306 21902 7306 7309 21903 7309 7305 21904 7305 7307 21905 7307 7309 21906 7309 7308 21907 7308 7305 21908 7305 7311 21909 7311 7308 21910 7308 7309 21911 7309 7311 21912 7311 7310 21913 7310 7308 21914 7308 7313 21915 7313 7310 21916 7310 7311 21917 7311 7313 21918 7313 7312 21919 7312 7310 21920 7310 7283 21921 7283 7312 21922 7312 7313 21923 7313 7346 21924 7346 7317 21925 7317 7314 21926 7314 7314 21927 7314 7315 21928 7315 7316 21929 7316 7314 21930 7314 7317 21931 7317 7315 21932 7315 7322 21933 7322 7318 21934 7318 7319 21935 7319 7322 21936 7322 7320 21937 7320 7318 21938 7318 7322 21939 7322 7321 21940 7321 7320 21941 7320 7323 21942 7323 7321 21943 7321 7322 21944 7322 7326 21945 7326 7321 21946 7321 7323 21947 7323 7326 21948 7326 7324 21949 7324 7321 21950 7321 7326 21951 7326 7325 21952 7325 7324 21953 7324 7327 21954 7327 7325 21955 7325 7326 21956 7326 7329 21957 7329 7325 21958 7325 7327 21959 7327 7329 21960 7329 7328 21961 7328 7325 21962 7325 7331 21963 7331 7328 21964 7328 7329 21965 7329 7331 21966 7331 7330 21967 7330 7328 21968 7328 7333 21969 7333 7330 21970 7330 7331 21971 7331 7333 21972 7333 7332 21973 7332 7330 21974 7330 7336 21975 7336 7332 21976 7332 7333 21977 7333 7336 21978 7336 7334 21979 7334 7332 21980 7332 7336 21981 7336 7335 21982 7335 7334 21983 7334 7338 21984 7338 7335 21985 7335 7336 21986 7336 7338 21987 7338 7337 21988 7337 7335 21989 7335 7340 21990 7340 7337 21991 7337 7338 21992 7338 7340 21993 7340 7339 21994 7339 7337 21995 7337 7341 21996 7341 7339 21997 7339 7340 21998 7340 7343 21999 7343 7339 22000 7339 7341 22001 7341 7343 22002 7343 7342 22003 7342 7339 22004 7339 7345 22005 7345 7342 22006 7342 7343 22007 7343 7345 22008 7345 7344 22009 7344 7342 22010 7342 7347 22011 7347 7344 22012 7344 7345 22013 7345 7347 22014 7347 7346 22015 7346 7344 22016 7344 7317 22017 7317 7346 22018 7346 7347 22019 7347 7380 22020 7380 7348 22021 7348 7349 22022 7349 7354 22023 7354 7350 22024 7350 7351 22025 7351 7354 22026 7354 7352 22027 7352 7350 22028 7350 7354 22029 7354 7353 22030 7353 7352 22031 7352 7355 22032 7355 7353 22033 7353 7354 22034 7354 7358 22035 7358 7353 22036 7353 7355 22037 7355 7358 22038 7358 7356 22039 7356 7353 22040 7353 7358 22041 7358 7357 22042 7357 7356 22043 7356 7359 22044 7359 7357 22045 7357 7358 22046 7358 7361 22047 7361 7357 22048 7357 7359 22049 7359 7361 22050 7361 7360 22051 7360 7357 22052 7357 7363 22053 7363 7360 22054 7360 7361 22055 7361 7363 22056 7363 7362 22057 7362 7360 22058 7360 7366 22059 7366 7362 22060 7362 7363 22061 7363 7366 22062 7366 7364 22063 7364 7362 22064 7362 7366 22065 7366 7365 22066 7365 7364 22067 7364 7368 22068 7368 7365 22069 7365 7366 22070 7366 7368 22071 7368 7367 22072 7367 7365 22073 7365 7370 22074 7370 7367 22075 7367 7368 22076 7368 7370 22077 7370 7369 22078 7369 7367 22079 7367 7372 22080 7372 7369 22081 7369 7370 22082 7370 7372 22083 7372 7371 22084 7371 7369 22085 7369 7374 22086 7374 7371 22087 7371 7372 22088 7372 7374 22089 7374 7373 22090 7373 7371 22091 7371 7375 22092 7375 7373 22093 7373 7374 22094 7374 7377 22095 7377 7373 22096 7373 7375 22097 7375 7377 22098 7377 7376 22099 7376 7373 22100 7373 7379 22101 7379 7376 22102 7376 7377 22103 7377 7379 22104 7379 7378 22105 7378 7376 22106 7376 7381 22107 7381 7378 22108 7378 7379 22109 7379 7381 22110 7381 7380 22111 7380 7378 22112 7378 7348 22113 7348 7380 22114 7380 7381 22115 7381 7414 22116 7414 7382 22117 7382 7383 22118 7383 7386 22119 7386 7384 22120 7384 7385 22121 7385 7388 22122 7388 7384 22123 7384 7386 22124 7386 7388 22125 7388 7387 22126 7387 7384 22127 7384 7390 22128 7390 7387 22129 7387 7388 22130 7388 7390 22131 7390 7389 22132 7389 7387 22133 7387 7391 22134 7391 7389 22135 7389 7390 22136 7390 7394 22137 7394 7389 22138 7389 7391 22139 7391 7394 22140 7394 7392 22141 7392 7389 22142 7389 7394 22143 7394 7393 22144 7393 7392 22145 7392 7396 22146 7396 7393 22147 7393 7394 22148 7394 7396 22149 7396 7395 22150 7395 7393 22151 7393 7397 22152 7397 7395 22153 7395 7396 22154 7396 7399 22155 7399 7395 22156 7395 7397 22157 7397 7399 22158 7399 7398 22159 7398 7395 22160 7395 7402 22161 7402 7398 22162 7398 7399 22163 7399 7402 22164 7402 7400 22165 7400 7398 22166 7398 7402 22167 7402 7401 22168 7401 7400 22169 7400 7403 22170 7403 7401 22171 7401 7402 22172 7402 7405 22173 7405 7401 22174 7401 7403 22175 7403 7405 22176 7405 7404 22177 7404 7401 22178 7401 7407 22179 7407 7404 22180 7404 7405 22181 7405 7407 22182 7407 7406 22183 7406 7404 22184 7404 7409 22185 7409 7406 22186 7406 7407 22187 7407 7409 22188 7409 7408 22189 7408 7406 22190 7406 7411 22191 7411 7408 22192 7408 7409 22193 7409 7411 22194 7411 7410 22195 7410 7408 22196 7408 7413 22197 7413 7410 22198 7410 7411 22199 7411 7413 22200 7413 7412 22201 7412 7410 22202 7410 7415 22203 7415 7412 22204 7412 7413 22205 7413 7415 22206 7415 7414 22207 7414 7412 22208 7412 7382 22209 7382 7414 22210 7414 7415 22211 7415

+
+
+ + + + +28.874426 -27.017475 9.800000 +28.873993 -26.996658 9.800000 +28.881271 -27.003639 9.000000 +28.881704 -27.024456 9.000000 +22.640167 19.500000 9.000000 +22.647154 19.500000 9.800000 +22.147135 19.000000 9.800000 +22.140148 19.000000 9.000000 +22.155483 19.090982 9.800000 +22.148495 19.090982 9.000000 +22.182241 19.184048 9.800000 +22.175255 19.184048 9.000000 +22.228640 19.273605 9.800000 +22.221653 19.273605 9.000000 +22.258963 19.315149 9.800000 +22.251974 19.315149 9.000000 +22.293587 19.353554 9.800000 +22.286600 19.353554 9.000000 +22.331993 19.388176 9.800000 +22.325005 19.388176 9.000000 +22.373539 19.418497 9.800000 +22.366550 19.418497 9.000000 +22.463100 19.464893 9.800000 +22.456112 19.464893 9.000000 +22.556170 19.491653 9.800000 +22.549181 19.491653 9.000000 +13.000000 -18.062500 12.733338 +18.000000 -18.062500 12.733338 +18.000000 -17.027000 14.172479 +18.000000 -17.000000 14.500000 +13.000000 -17.000000 14.500000 +13.000000 -17.027000 14.172479 +18.000000 -17.127136 13.798301 +18.000000 -17.286087 13.469224 +13.000000 -17.127136 13.798301 +13.000000 -17.286087 13.469224 +18.000000 -17.502262 13.174563 +18.000000 -17.785847 12.910713 +13.000000 -17.502262 13.174563 +13.000000 -17.785847 12.910713 +18.000000 -17.033390 14.863926 +13.000000 -17.000000 14.500000 +18.000000 -17.000000 14.500000 +13.000000 -17.033390 14.863926 +18.000000 -21.000000 14.500000 +13.000000 -21.000000 14.500000 +18.000000 -20.966610 14.863926 +18.000000 -20.859577 15.236190 +13.000000 -20.966610 14.863926 +18.000000 -20.673990 15.594419 +13.000000 -20.859577 15.236190 +18.000000 -20.414213 15.914213 +13.000000 -20.673990 15.594419 +18.000000 -20.094419 16.173990 +13.000000 -20.414213 15.914213 +13.000000 -20.094419 16.173990 +18.000000 -19.736189 16.359577 +13.000000 -19.736189 16.359577 +18.000000 -19.363926 16.466610 +13.000000 -19.363926 16.466610 +18.000000 -19.000000 16.500000 +13.000000 -19.000000 16.500000 +18.000000 -18.636074 16.466610 +13.000000 -18.636074 16.466610 +18.000000 -18.263811 16.359577 +13.000000 -18.263811 16.359577 +18.000000 -17.905581 16.173990 +13.000000 -17.905581 16.173990 +18.000000 -17.585787 15.914213 +13.000000 -17.585787 15.914213 +18.000000 -17.326010 15.594419 +13.000000 -17.326010 15.594419 +18.000000 -17.140423 15.236190 +13.000000 -17.140423 15.236190 +-21.000000 27.078939 1.884419 +-24.500000 25.931183 1.500243 +-24.500000 25.900000 1.500000 +-21.000000 25.900000 1.500000 +-24.500000 26.331890 1.547189 +-21.000000 25.931183 1.500243 +-24.500000 26.722876 1.677124 +-21.000000 26.331890 1.547189 +-24.500000 27.078939 1.884419 +-21.000000 26.722876 1.677124 +-21.000000 27.246101 4.979192 +-21.000000 27.222876 5.000000 +-24.500000 27.222876 5.000000 +-21.000000 27.515581 4.678939 +-24.500000 27.246101 4.979192 +-21.000000 27.722876 4.322875 +-24.500000 27.515581 4.678939 +-21.000000 27.852812 3.931890 +-24.500000 27.722876 4.322875 +-24.500000 27.852812 3.931890 +-21.000000 27.899757 3.531183 +-21.000000 27.868263 3.145120 +-24.500000 27.899757 3.531183 +-24.500000 27.868263 3.145120 +-21.000000 27.770828 2.792893 +-24.500000 27.770828 2.792893 +-21.000000 27.610929 2.464276 +-21.000000 27.379192 2.153898 +-24.500000 27.610929 2.464276 +-24.500000 27.379192 2.153898 +-13.000000 -19.937500 12.733338 +-18.000000 -19.937500 12.733338 +-18.000000 -21.000000 14.500000 +-13.000000 -21.000000 14.500000 +-18.000000 -20.973000 14.172479 +-13.000000 -20.973000 14.172479 +-18.000000 -20.872864 13.798301 +-13.000000 -20.872864 13.798301 +-18.000000 -20.713913 13.469224 +-13.000000 -20.713913 13.469224 +-18.000000 -20.497738 13.174563 +-18.000000 -20.214153 12.910713 +-13.000000 -20.497738 13.174563 +-13.000000 -20.214153 12.910713 +-18.000000 -19.736189 16.359577 +-13.000000 -21.000000 14.500000 +-18.000000 -21.000000 14.500000 +-13.000000 -20.966610 14.863926 +-13.000000 -20.859577 15.236190 +-18.000000 -20.966610 14.863926 +-13.000000 -20.673990 15.594419 +-18.000000 -20.859577 15.236190 +-18.000000 -20.673990 15.594419 +-13.000000 -20.414213 15.914213 +-18.000000 -20.414213 15.914213 +-13.000000 -20.094419 16.173990 +-18.000000 -20.094419 16.173990 +-13.000000 -19.736189 16.359577 +-18.000000 -17.000000 14.500000 +-13.000000 -17.000000 14.500000 +-18.000000 -17.033390 14.863926 +-18.000000 -17.140423 15.236190 +-13.000000 -17.033390 14.863926 +-13.000000 -17.140423 15.236190 +-18.000000 -17.326010 15.594419 +-18.000000 -17.585787 15.914213 +-13.000000 -17.326010 15.594419 +-13.000000 -17.585787 15.914213 +-18.000000 -17.905581 16.173990 +-13.000000 -17.905581 16.173990 +-18.000000 -18.263811 16.359577 +-18.000000 -18.636074 16.466610 +-13.000000 -18.263811 16.359577 +-18.000000 -19.000000 16.500000 +-13.000000 -18.636074 16.466610 +-13.000000 -19.000000 16.500000 +-18.000000 -19.363926 16.466610 +-13.000000 -19.363926 16.466610 +-10.754363 -23.250000 12.000000 +-10.769199 -23.250000 10.300000 +-11.730801 -23.250000 10.300000 +-11.745637 -23.250000 12.000000 +-8.254363 -23.250000 12.000000 +-8.269199 -23.250000 10.300000 +-9.230801 -23.250000 10.300000 +-9.245637 -23.250000 12.000000 +-5.754364 -23.250000 12.000000 +-5.769199 -23.250000 10.300000 +-6.730801 -23.250000 10.300000 +-6.745636 -23.250000 12.000000 +-3.254364 -23.250000 12.000000 +-3.269199 -23.250000 10.300000 +-4.230801 -23.250000 10.300000 +-4.245636 -23.250000 12.000000 +-0.754363 -23.250000 12.000000 +-0.769199 -23.250000 10.300000 +-1.730801 -23.250000 10.300000 +-1.745637 -23.250000 12.000000 +1.745637 -23.250000 12.000000 +1.730801 -23.250000 10.300000 +0.769199 -23.250000 10.300000 +0.754363 -23.250000 12.000000 +4.245636 -23.250000 12.000000 +4.230801 -23.250000 10.300000 +3.269199 -23.250000 10.300000 +3.254364 -23.250000 12.000000 +6.745636 -23.250000 12.000000 +6.730801 -23.250000 10.300000 +5.769199 -23.250000 10.300000 +5.754364 -23.250000 12.000000 +9.245637 -23.250000 12.000000 +9.230801 -23.250000 10.300000 +8.269199 -23.250000 10.300000 +8.254363 -23.250000 12.000000 +10.754363 -14.750000 12.000000 +10.769199 -14.750000 10.300000 +11.730801 -14.750000 10.300000 +11.745637 -14.750000 12.000000 +9.245637 -14.750000 12.000000 +8.254363 -14.750000 12.000000 +8.269199 -14.750000 10.300000 +9.230801 -14.750000 10.300000 +5.754364 -14.750000 12.000000 +5.769199 -14.750000 10.300000 +6.730801 -14.750000 10.300000 +6.745636 -14.750000 12.000000 +3.254364 -14.750000 12.000000 +3.269199 -14.750000 10.300000 +4.230801 -14.750000 10.300000 +4.245636 -14.750000 12.000000 +0.754363 -14.750000 12.000000 +0.769199 -14.750000 10.300000 +1.730801 -14.750000 10.300000 +1.745637 -14.750000 12.000000 +-0.754363 -14.750000 12.000000 +-1.745637 -14.750000 12.000000 +-1.730801 -14.750000 10.300000 +-0.769199 -14.750000 10.300000 +-3.254364 -14.750000 12.000000 +-4.245636 -14.750000 12.000000 +-4.230801 -14.750000 10.300000 +-3.269199 -14.750000 10.300000 +-5.754364 -14.750000 12.000000 +-6.745636 -14.750000 12.000000 +-6.730801 -14.750000 10.300000 +-5.769199 -14.750000 10.300000 +-8.254363 -14.750000 12.000000 +-9.245637 -14.750000 12.000000 +-9.230801 -14.750000 10.300000 +-8.269199 -14.750000 10.300000 +13.000000 -19.000000 16.500000 +13.000000 -19.937500 12.733338 +13.000000 -19.630152 12.500000 +13.000000 -14.625000 12.500000 +13.000000 -18.369848 12.500000 +13.000000 -18.062500 12.733338 +13.000000 -20.368467 13.041474 +13.000000 -20.713913 13.469224 +13.000000 -17.631533 13.041474 +13.000000 -15.000000 14.000000 +13.000000 -14.250000 14.000000 +13.000000 -17.286087 13.469224 +13.000000 -23.375000 12.500000 +13.000000 -23.750000 14.000000 +13.000000 -20.929831 13.974874 +13.000000 -21.000000 14.500000 +13.000000 -23.000000 14.000000 +13.000000 -22.933222 14.727852 +13.000000 -20.966610 14.863926 +13.000000 -22.719152 15.472379 +13.000000 -20.859577 15.236190 +13.000000 -17.070169 13.974874 +13.000000 -15.066778 14.727852 +13.000000 -15.280847 15.472379 +13.000000 -17.000000 14.500000 +13.000000 -15.652018 16.188839 +13.000000 -17.033390 14.863926 +13.000000 -16.171574 16.828426 +13.000000 -17.140423 15.236190 +13.000000 -17.326010 15.594419 +13.000000 -16.811161 17.347982 +13.000000 -17.585787 15.914213 +13.000000 -17.527620 17.719152 +13.000000 -17.905581 16.173990 +13.000000 -18.272148 17.933222 +13.000000 -18.263811 16.359577 +13.000000 -19.000000 18.000000 +13.000000 -18.636074 16.466610 +13.000000 -22.347982 16.188839 +13.000000 -20.673990 15.594419 +13.000000 -20.414213 15.914213 +13.000000 -21.828426 16.828426 +13.000000 -20.094419 16.173990 +13.000000 -21.188839 17.347982 +13.000000 -19.736189 16.359577 +13.000000 -20.472380 17.719152 +13.000000 -19.363926 16.466610 +13.000000 -19.727852 17.933222 +-13.000000 -19.000000 16.500000 +-13.000000 -23.375000 12.500000 +-13.000000 -19.630152 12.500000 +-13.000000 -18.062500 12.733338 +-13.000000 -18.369848 12.500000 +-13.000000 -17.631533 13.041474 +-13.000000 -19.937500 12.733338 +-13.000000 -20.368467 13.041474 +-13.000000 -17.286087 13.469224 +-13.000000 -23.000000 14.000000 +-13.000000 -23.750000 14.000000 +-13.000000 -20.713913 13.469224 +-13.000000 -14.625000 12.500000 +-13.000000 -14.250000 14.000000 +-13.000000 -17.070169 13.974874 +-13.000000 -17.000000 14.500000 +-13.000000 -15.000000 14.000000 +-13.000000 -15.066778 14.727852 +-13.000000 -17.033390 14.863926 +-13.000000 -15.280847 15.472379 +-13.000000 -17.140423 15.236190 +-13.000000 -20.929831 13.974874 +-13.000000 -22.933222 14.727852 +-13.000000 -22.719152 15.472379 +-13.000000 -21.000000 14.500000 +-13.000000 -22.347982 16.188839 +-13.000000 -20.966610 14.863926 +-13.000000 -21.828426 16.828426 +-13.000000 -20.859577 15.236190 +-13.000000 -20.673990 15.594419 +-13.000000 -21.188839 17.347982 +-13.000000 -20.414213 15.914213 +-13.000000 -20.472380 17.719152 +-13.000000 -20.094419 16.173990 +-13.000000 -19.727852 17.933222 +-13.000000 -19.736189 16.359577 +-13.000000 -19.000000 18.000000 +-13.000000 -19.363926 16.466610 +-13.000000 -15.652018 16.188839 +-13.000000 -17.326010 15.594419 +-13.000000 -17.585787 15.914213 +-13.000000 -16.171574 16.828426 +-13.000000 -17.905581 16.173990 +-13.000000 -16.811161 17.347982 +-13.000000 -18.263811 16.359577 +-13.000000 -17.527620 17.719152 +-13.000000 -18.636074 16.466610 +-13.000000 -18.272148 17.933222 +-13.003330 -18.614410 12.118416 +-13.005255 -18.678799 11.897917 +-13.019199 -13.730801 10.300000 +-13.000000 -13.750000 12.500000 +-13.000000 -23.375000 12.500000 +-13.000000 -24.250000 12.500000 +-13.000000 -19.630152 12.500000 +-13.001548 -19.490814 12.322605 +-13.003330 -19.385590 12.118416 +-13.005255 -19.321201 11.897917 +-13.007215 -19.299999 11.673341 +-13.014835 -19.299999 10.800000 +-13.019199 -24.269199 10.300000 +-13.014835 -18.700001 10.800000 +-13.000000 -14.625000 12.500000 +-13.007215 -18.700001 11.673341 +-13.000000 -18.369848 12.500000 +-13.001548 -18.509186 12.322605 +11.745637 -23.250000 12.000000 +11.730801 -23.250000 10.300000 +10.769199 -23.250000 10.300000 +10.754363 -23.250000 12.000000 +13.003330 -19.385590 12.118416 +13.005255 -19.321201 11.897917 +13.019199 -24.269199 10.300000 +13.000000 -24.250000 12.500000 +13.000000 -14.625000 12.500000 +13.000000 -13.750000 12.500000 +13.000000 -18.369848 12.500000 +13.001548 -18.509186 12.322605 +13.003330 -18.614410 12.118416 +13.005255 -18.678799 11.897917 +13.007215 -18.700001 11.673341 +13.014835 -18.700001 10.800000 +13.019199 -13.730801 10.300000 +13.014835 -19.299999 10.800000 +13.000000 -23.375000 12.500000 +13.007215 -19.299999 11.673341 +13.000000 -19.630152 12.500000 +13.001548 -19.490814 12.322605 +-10.754363 -14.750000 12.000000 +-11.745637 -14.750000 12.000000 +-11.730801 -14.750000 10.300000 +-10.769199 -14.750000 10.300000 +0.754363 -14.750000 12.000000 +0.750000 -14.625000 12.500000 +0.750000 -13.750000 12.500000 +0.769199 -13.730801 10.300000 +0.769199 -14.750000 10.300000 +-0.750000 -13.750000 12.500000 +-0.769199 -13.730801 10.300000 +0.769199 -13.730801 10.300000 +0.750000 -13.750000 12.500000 +-0.750000 -13.750000 12.500000 +-0.750000 -14.625000 12.500000 +-0.769199 -14.750000 10.300000 +-0.769199 -13.730801 10.300000 +-0.754363 -14.750000 12.000000 +10.754363 -14.750000 12.000000 +10.750000 -14.625000 12.500000 +10.750000 -13.750000 12.500000 +10.769199 -13.730801 10.300000 +10.769199 -14.750000 10.300000 +10.750000 -13.750000 12.500000 +9.250000 -13.750000 12.500000 +9.230801 -13.730801 10.300000 +10.769199 -13.730801 10.300000 +9.250000 -13.750000 12.500000 +9.250000 -14.625000 12.500000 +9.230801 -14.750000 10.300000 +9.230801 -13.730801 10.300000 +9.245637 -14.750000 12.000000 +-1.745637 -14.750000 12.000000 +-1.750000 -14.625000 12.500000 +-1.750000 -13.750000 12.500000 +-1.730801 -13.730801 10.300000 +-1.730801 -14.750000 10.300000 +-3.250000 -13.750000 12.500000 +-3.269199 -13.730801 10.300000 +-1.730801 -13.730801 10.300000 +-1.750000 -13.750000 12.500000 +-3.250000 -13.750000 12.500000 +-3.250000 -14.625000 12.500000 +-3.269199 -14.750000 10.300000 +-3.269199 -13.730801 10.300000 +-3.254364 -14.750000 12.000000 +8.254363 -14.750000 12.000000 +8.250000 -14.625000 12.500000 +8.250000 -13.750000 12.500000 +8.269199 -13.730801 10.300000 +8.269199 -14.750000 10.300000 +8.250000 -13.750000 12.500000 +6.750000 -13.750000 12.500000 +6.730801 -13.730801 10.300000 +8.269199 -13.730801 10.300000 +6.750000 -13.750000 12.500000 +6.750000 -14.625000 12.500000 +6.730801 -14.750000 10.300000 +6.730801 -13.730801 10.300000 +6.745636 -14.750000 12.000000 +-4.245636 -14.750000 12.000000 +-4.250000 -14.625000 12.500000 +-4.250000 -13.750000 12.500000 +-4.230801 -13.730801 10.300000 +-4.230801 -14.750000 10.300000 +-5.750000 -13.750000 12.500000 +-5.769199 -13.730801 10.300000 +-4.230801 -13.730801 10.300000 +-4.250000 -13.750000 12.500000 +-5.750000 -13.750000 12.500000 +-5.750000 -14.625000 12.500000 +-5.769199 -14.750000 10.300000 +-5.769199 -13.730801 10.300000 +-5.754364 -14.750000 12.000000 +5.754364 -14.750000 12.000000 +5.750000 -14.625000 12.500000 +5.750000 -13.750000 12.500000 +5.769199 -13.730801 10.300000 +5.769199 -14.750000 10.300000 +4.250000 -13.750000 12.500000 +4.230801 -13.730801 10.300000 +5.769199 -13.730801 10.300000 +5.750000 -13.750000 12.500000 +4.250000 -13.750000 12.500000 +4.250000 -14.625000 12.500000 +4.230801 -14.750000 10.300000 +4.230801 -13.730801 10.300000 +4.245636 -14.750000 12.000000 +-6.745636 -14.750000 12.000000 +-6.750000 -14.625000 12.500000 +-6.750000 -13.750000 12.500000 +-6.730801 -13.730801 10.300000 +-6.730801 -14.750000 10.300000 +-6.750000 -13.750000 12.500000 +-8.250000 -13.750000 12.500000 +-8.269199 -13.730801 10.300000 +-6.730801 -13.730801 10.300000 +-8.250000 -13.750000 12.500000 +-8.250000 -14.625000 12.500000 +-8.269199 -14.750000 10.300000 +-8.269199 -13.730801 10.300000 +-8.254363 -14.750000 12.000000 +3.254364 -14.750000 12.000000 +3.250000 -14.625000 12.500000 +3.250000 -13.750000 12.500000 +3.269199 -13.730801 10.300000 +3.269199 -14.750000 10.300000 +3.250000 -13.750000 12.500000 +1.750000 -13.750000 12.500000 +1.730801 -13.730801 10.300000 +3.269199 -13.730801 10.300000 +1.750000 -13.750000 12.500000 +1.750000 -14.625000 12.500000 +1.730801 -14.750000 10.300000 +1.730801 -13.730801 10.300000 +1.745637 -14.750000 12.000000 +-9.245637 -14.750000 12.000000 +-9.250000 -14.625000 12.500000 +-9.250000 -13.750000 12.500000 +-9.230801 -13.730801 10.300000 +-9.230801 -14.750000 10.300000 +-10.750000 -13.750000 12.500000 +-10.769199 -13.730801 10.300000 +-9.230801 -13.730801 10.300000 +-9.250000 -13.750000 12.500000 +-10.750000 -13.750000 12.500000 +-10.750000 -14.625000 12.500000 +-10.769199 -14.750000 10.300000 +-10.769199 -13.730801 10.300000 +-10.754363 -14.750000 12.000000 +11.750000 -13.750000 12.500000 +11.730801 -13.730801 10.300000 +13.019199 -13.730801 10.300000 +13.000000 -13.750000 12.500000 +11.750000 -13.750000 12.500000 +11.750000 -14.625000 12.500000 +11.730801 -14.750000 10.300000 +11.730801 -13.730801 10.300000 +11.745637 -14.750000 12.000000 +-11.745637 -14.750000 12.000000 +-11.750000 -14.625000 12.500000 +-11.750000 -13.750000 12.500000 +-11.730801 -13.730801 10.300000 +-11.730801 -14.750000 10.300000 +-13.000000 -13.750000 12.500000 +-13.019199 -13.730801 10.300000 +-11.730801 -13.730801 10.300000 +-11.750000 -13.750000 12.500000 +-0.750000 -24.250000 12.500000 +0.750000 -24.250000 12.500000 +0.769199 -24.269199 10.300000 +-0.769199 -24.269199 10.300000 +-0.754363 -23.250000 12.000000 +-0.750000 -23.375000 12.500000 +-0.750000 -24.250000 12.500000 +-0.769199 -24.269199 10.300000 +-0.769199 -23.250000 10.300000 +0.750000 -24.250000 12.500000 +0.750000 -23.375000 12.500000 +0.769199 -23.250000 10.300000 +0.769199 -24.269199 10.300000 +0.754363 -23.250000 12.000000 +9.250000 -24.250000 12.500000 +10.750000 -24.250000 12.500000 +10.769199 -24.269199 10.300000 +9.230801 -24.269199 10.300000 +9.245637 -23.250000 12.000000 +9.250000 -23.375000 12.500000 +9.250000 -24.250000 12.500000 +9.230801 -24.269199 10.300000 +9.230801 -23.250000 10.300000 +10.750000 -24.250000 12.500000 +10.750000 -23.375000 12.500000 +10.769199 -23.250000 10.300000 +10.769199 -24.269199 10.300000 +10.754363 -23.250000 12.000000 +-3.250000 -24.250000 12.500000 +-1.750000 -24.250000 12.500000 +-1.730801 -24.269199 10.300000 +-3.269199 -24.269199 10.300000 +-3.254364 -23.250000 12.000000 +-3.250000 -23.375000 12.500000 +-3.250000 -24.250000 12.500000 +-3.269199 -24.269199 10.300000 +-3.269199 -23.250000 10.300000 +-1.750000 -24.250000 12.500000 +-1.750000 -23.375000 12.500000 +-1.730801 -23.250000 10.300000 +-1.730801 -24.269199 10.300000 +-1.745637 -23.250000 12.000000 +6.750000 -24.250000 12.500000 +8.250000 -24.250000 12.500000 +8.269199 -24.269199 10.300000 +6.730801 -24.269199 10.300000 +6.745636 -23.250000 12.000000 +6.750000 -23.375000 12.500000 +6.750000 -24.250000 12.500000 +6.730801 -24.269199 10.300000 +6.730801 -23.250000 10.300000 +8.250000 -24.250000 12.500000 +8.250000 -23.375000 12.500000 +8.269199 -23.250000 10.300000 +8.269199 -24.269199 10.300000 +8.254363 -23.250000 12.000000 +-5.769199 -24.269199 10.300000 +-5.750000 -24.250000 12.500000 +-4.250000 -24.250000 12.500000 +-4.230801 -24.269199 10.300000 +-5.754364 -23.250000 12.000000 +-5.750000 -23.375000 12.500000 +-5.750000 -24.250000 12.500000 +-5.769199 -24.269199 10.300000 +-5.769199 -23.250000 10.300000 +-4.250000 -24.250000 12.500000 +-4.250000 -23.375000 12.500000 +-4.230801 -23.250000 10.300000 +-4.230801 -24.269199 10.300000 +-4.245636 -23.250000 12.000000 +4.230801 -24.269199 10.300000 +4.250000 -24.250000 12.500000 +5.750000 -24.250000 12.500000 +5.769199 -24.269199 10.300000 +4.245636 -23.250000 12.000000 +4.250000 -23.375000 12.500000 +4.250000 -24.250000 12.500000 +4.230801 -24.269199 10.300000 +4.230801 -23.250000 10.300000 +5.750000 -24.250000 12.500000 +5.750000 -23.375000 12.500000 +5.769199 -23.250000 10.300000 +5.769199 -24.269199 10.300000 +5.754364 -23.250000 12.000000 +-8.250000 -24.250000 12.500000 +-6.750000 -24.250000 12.500000 +-6.730801 -24.269199 10.300000 +-8.269199 -24.269199 10.300000 +-8.254363 -23.250000 12.000000 +-8.250000 -23.375000 12.500000 +-8.250000 -24.250000 12.500000 +-8.269199 -24.269199 10.300000 +-8.269199 -23.250000 10.300000 +-6.750000 -24.250000 12.500000 +-6.750000 -23.375000 12.500000 +-6.730801 -23.250000 10.300000 +-6.730801 -24.269199 10.300000 +-6.745636 -23.250000 12.000000 +1.750000 -24.250000 12.500000 +3.250000 -24.250000 12.500000 +3.269199 -24.269199 10.300000 +1.730801 -24.269199 10.300000 +1.745637 -23.250000 12.000000 +1.750000 -23.375000 12.500000 +1.750000 -24.250000 12.500000 +1.730801 -24.269199 10.300000 +1.730801 -23.250000 10.300000 +3.250000 -24.250000 12.500000 +3.250000 -23.375000 12.500000 +3.269199 -23.250000 10.300000 +3.269199 -24.269199 10.300000 +3.254364 -23.250000 12.000000 +-10.769199 -24.269199 10.300000 +-10.750000 -24.250000 12.500000 +-9.250000 -24.250000 12.500000 +-9.230801 -24.269199 10.300000 +-10.754363 -23.250000 12.000000 +-10.750000 -23.375000 12.500000 +-10.750000 -24.250000 12.500000 +-10.769199 -24.269199 10.300000 +-10.769199 -23.250000 10.300000 +-9.250000 -24.250000 12.500000 +-9.250000 -23.375000 12.500000 +-9.230801 -23.250000 10.300000 +-9.230801 -24.269199 10.300000 +-9.245637 -23.250000 12.000000 +11.750000 -24.250000 12.500000 +13.000000 -24.250000 12.500000 +13.019199 -24.269199 10.300000 +11.730801 -24.269199 10.300000 +11.745637 -23.250000 12.000000 +11.750000 -23.375000 12.500000 +11.750000 -24.250000 12.500000 +11.730801 -24.269199 10.300000 +11.730801 -23.250000 10.300000 +-11.750000 -24.250000 12.500000 +-11.750000 -23.375000 12.500000 +-11.730801 -23.250000 10.300000 +-11.730801 -24.269199 10.300000 +-11.745637 -23.250000 12.000000 +-13.000000 -24.250000 12.500000 +-11.750000 -24.250000 12.500000 +-11.730801 -24.269199 10.300000 +-13.019199 -24.269199 10.300000 +-18.291653 -13.859018 9.800000 +-17.984047 -13.485106 9.800000 +-18.073605 -13.531502 9.800000 +-18.573545 -12.775801 9.800000 +-18.666609 -12.802558 9.800000 +-18.756163 -12.848951 9.800000 +-18.836107 -12.913893 9.800000 +-18.901049 -12.993837 9.800000 +-18.947443 -13.083391 9.800000 +-18.974199 -13.176454 9.800000 +-18.982546 -13.267435 9.800000 +-18.153553 -13.596447 9.800000 +-18.218498 -13.676395 9.800000 +-18.264894 -13.765953 9.800000 +-17.890982 -13.458347 9.800000 +-17.799999 -13.450000 9.800000 +-18.482565 -12.767454 9.800000 +17.799999 -13.450000 9.800000 +17.890982 -13.458347 9.800000 +17.984047 -13.485106 9.800000 +18.073605 -13.531502 9.800000 +18.153553 -13.596447 9.800000 +18.482565 -12.767454 9.800000 +18.573545 -12.775801 9.800000 +18.666609 -12.802558 9.800000 +18.756163 -12.848951 9.800000 +18.836107 -12.913893 9.800000 +18.901049 -12.993837 9.800000 +18.947443 -13.083391 9.800000 +18.974199 -13.176454 9.800000 +18.218498 -13.676395 9.800000 +18.264894 -13.765953 9.800000 +18.291653 -13.859018 9.800000 +18.299999 -13.950000 9.800000 +18.982546 -13.267435 9.800000 +18.299999 -24.049999 9.800000 +18.291653 -24.140982 9.800000 +18.264894 -24.234047 9.800000 +18.218498 -24.323605 9.800000 +18.153553 -24.403553 9.800000 +18.982546 -24.732565 9.800000 +18.974199 -24.823545 9.800000 +18.947443 -24.916609 9.800000 +18.901049 -25.006163 9.800000 +18.836107 -25.086107 9.800000 +18.756163 -25.151049 9.800000 +18.666609 -25.197443 9.800000 +18.573545 -25.224199 9.800000 +18.073605 -24.468498 9.800000 +17.984047 -24.514894 9.800000 +17.890982 -24.541653 9.800000 +17.799999 -24.549999 9.800000 +18.482565 -25.232546 9.800000 +-17.799999 -24.549999 9.800000 +-17.890982 -24.541653 9.800000 +-17.984047 -24.514894 9.800000 +-18.073605 -24.468498 9.800000 +-18.153553 -24.403553 9.800000 +-18.482565 -25.232546 9.800000 +-18.573545 -25.224199 9.800000 +-18.666609 -25.197443 9.800000 +-18.756163 -25.151049 9.800000 +-18.836107 -25.086107 9.800000 +-18.901049 -25.006163 9.800000 +-18.947443 -24.916609 9.800000 +-18.974199 -24.823545 9.800000 +-18.218498 -24.323605 9.800000 +-18.264894 -24.234047 9.800000 +-18.291653 -24.140982 9.800000 +-18.299999 -24.049999 9.800000 +-18.982546 -24.732565 9.800000 +-18.299999 -13.950000 9.800000 +-18.918503 -12.976383 11.800000 +-21.000000 27.500000 11.800000 +21.000000 27.500000 11.800000 +-21.000000 22.500000 11.800000 +18.918503 -25.023617 11.800000 +18.853561 -25.103561 11.800000 +18.964895 -24.934063 11.800000 +18.773617 -25.168503 11.800000 +18.991653 -24.841000 11.800000 +21.000000 22.500000 11.800000 +19.000000 -24.750019 11.800000 +19.000000 -13.249981 11.800000 +18.991653 -13.159000 11.800000 +18.964895 -13.065937 11.800000 +18.918503 -12.976383 11.800000 +18.853561 -12.896439 11.800000 +18.773617 -12.831498 11.800000 +18.684063 -12.785104 11.800000 +18.591000 -12.758347 11.800000 +18.500019 -12.750000 11.800000 +-18.500019 -12.750000 11.800000 +-18.591000 -12.758347 11.800000 +-18.684063 -12.785104 11.800000 +18.684063 -25.214895 11.800000 +-18.773617 -12.831498 11.800000 +18.591000 -25.241653 11.800000 +-18.853561 -12.896439 11.800000 +18.500019 -25.250000 11.800000 +23.083334 -27.500000 11.800000 +-18.500019 -25.250000 11.800000 +-18.591000 -25.241653 11.800000 +-18.684063 -25.214895 11.800000 +-18.773617 -25.168503 11.800000 +-18.853561 -25.103561 11.800000 +-18.918503 -25.023617 11.800000 +-18.964895 -24.934063 11.800000 +-18.991653 -24.841000 11.800000 +-19.000000 -24.750019 11.800000 +-23.083334 -27.500000 11.800000 +-19.000000 -13.249981 11.800000 +-18.991653 -13.159000 11.800000 +-18.964895 -13.065937 11.800000 +21.000000 24.197859 4.550103 +21.000000 22.500000 0.000000 +21.000000 22.500000 9.354102 +21.000000 23.054502 8.759621 +21.000000 23.499334 8.062843 +21.000000 23.809200 7.296451 +21.000000 23.972136 6.500000 +21.000000 27.222876 5.000000 +21.000000 22.709627 10.800000 +21.000000 22.500000 11.800000 +21.000000 28.000000 10.800000 +21.000000 27.500000 11.800000 +21.000000 27.681963 11.783305 +21.000000 27.868095 11.729788 +21.000000 28.047211 11.636995 +21.000000 28.207108 11.507107 +21.000000 28.336996 11.347210 +21.000000 28.429789 11.168095 +21.000000 28.483305 10.981963 +21.000000 29.500000 9.500000 +21.000000 30.000000 9.500000 +21.000000 28.500000 10.800000 +21.000000 28.000000 6.500000 +21.000000 28.500000 10.500000 +21.000000 28.516695 10.318037 +21.000000 28.570211 10.131906 +21.000000 28.663004 9.952790 +21.000000 28.792892 9.792893 +21.000000 28.952789 9.663005 +21.000000 29.131905 9.570211 +21.000000 29.318037 9.516695 +21.000000 27.602140 4.550103 +21.000000 27.841074 3.981906 +21.000000 27.895636 3.367935 +21.000000 27.770828 2.792893 +21.000000 27.484079 2.279061 +21.000000 27.037054 1.854671 +21.000000 30.000000 0.501299 +21.000000 29.990131 0.403199 +21.000000 29.961508 0.309359 +21.000000 29.915611 0.222958 +21.000000 29.853920 0.147175 +21.000000 29.778349 0.085134 +21.000000 29.691999 0.038881 +21.000000 29.598131 0.009981 +21.000000 26.482027 1.586562 +21.000000 29.500000 0.000000 +21.000000 25.900000 1.500000 +21.000000 25.317972 1.586562 +21.000000 24.762945 1.854671 +21.000000 24.315920 2.279061 +21.000000 24.029171 2.792893 +21.000000 24.577124 5.000000 +21.000000 23.904366 3.367935 +21.000000 23.958927 3.981906 +21.127148 20.045889 8.949916 +21.021364 22.500000 9.354102 +21.050659 22.500000 6.000000 +21.047979 22.449917 6.545889 +21.049791 22.289366 7.104284 +21.056696 22.010986 7.641629 +21.000000 22.500000 11.800000 +21.000000 22.709627 10.800000 +23.083334 -27.500000 11.800000 +21.068743 21.621321 8.121321 +21.054670 21.565664 9.997878 +21.085327 21.141630 8.510986 +21.095671 20.500000 10.387483 +21.105284 20.604284 8.789365 +23.108809 -27.524435 9.000000 +21.149456 19.500000 9.000000 +21.092068 20.500000 10.800000 +-13.000000 -23.750000 14.000000 +-13.000000 -23.000000 14.000000 +22.993927 -30.000000 14.000000 +19.500000 -15.000000 14.000000 +-22.993927 -30.000000 14.000000 +20.514759 29.500000 14.000000 +-19.500000 -15.000000 14.000000 +-13.000000 -15.000000 14.000000 +19.500000 -23.000000 14.000000 +13.000000 -23.000000 14.000000 +13.000000 -23.750000 14.000000 +13.000000 -14.250000 14.000000 +13.000000 -15.000000 14.000000 +-13.000000 -14.250000 14.000000 +-20.514759 29.500000 14.000000 +-19.500000 -23.000000 14.000000 +-24.210815 -17.971392 12.456755 +-24.187609 -17.971392 9.800000 +-24.374910 -22.466623 9.800000 +-24.398115 -22.466623 12.456755 +-23.981846 -12.476159 12.456755 +-23.958641 -12.476159 9.800000 +-24.145943 -16.971392 9.800000 +-24.169147 -16.971392 12.456755 +-23.752878 -6.980927 12.456755 +-23.729673 -6.980927 9.800000 +-23.916975 -11.476159 9.800000 +-23.940180 -11.476159 12.456755 +-23.523911 -1.485696 12.456755 +-23.500706 -1.485696 9.800000 +-23.688007 -5.980927 9.800000 +-23.711212 -5.980927 12.456755 +-23.294943 4.009536 12.456755 +-23.271738 4.009536 9.800000 +-23.459040 -0.485696 9.800000 +-23.482244 -0.485696 12.456755 +-23.065975 9.504768 12.456755 +-23.042770 9.504768 9.800000 +-23.230070 5.009536 9.800000 +-23.253277 5.009536 12.456755 +-22.837008 15.000000 12.456755 +-22.813801 15.000000 9.800000 +-23.001102 10.504768 9.800000 +-23.024307 10.504768 12.456755 +-22.670340 19.000000 12.456755 +-22.647135 19.000000 9.800000 +-22.772135 16.000000 9.800000 +-22.795340 16.000000 12.456755 +24.374910 -22.466623 9.800000 +24.187609 -17.971392 9.800000 +24.210815 -17.971392 12.456755 +24.398115 -22.466623 12.456755 +24.563801 -27.000000 9.800000 +24.416578 -23.466623 9.800000 +24.439783 -23.466623 12.456755 +24.587008 -27.000000 12.456755 +24.145943 -16.971392 9.800000 +23.958641 -12.476159 9.800000 +23.981846 -12.476159 12.456755 +24.169147 -16.971392 12.456755 +23.916975 -11.476159 9.800000 +23.729673 -6.980927 9.800000 +23.752878 -6.980927 12.456755 +23.940180 -11.476159 12.456755 +23.688007 -5.980927 9.800000 +23.500706 -1.485696 9.800000 +23.523911 -1.485696 12.456755 +23.711212 -5.980927 12.456755 +23.459040 -0.485696 9.800000 +23.271738 4.009536 9.800000 +23.294943 4.009536 12.456755 +23.482244 -0.485696 12.456755 +23.230070 5.009536 9.800000 +23.042770 9.504768 9.800000 +23.065975 9.504768 12.456755 +23.253277 5.009536 12.456755 +23.001102 10.504768 9.800000 +22.813801 15.000000 9.800000 +22.837008 15.000000 12.456755 +23.024307 10.504768 12.456755 +22.772135 16.000000 9.800000 +22.647135 19.000000 9.800000 +22.670340 19.000000 12.456755 +22.795340 16.000000 12.456755 +-22.140581 18.979185 9.000000 +-23.108809 -27.524435 9.000000 +-24.557814 -27.524435 9.000000 +-22.547163 19.491276 9.000000 +-22.640167 19.500000 9.000000 +-24.468882 -27.516462 9.000000 +-22.451895 19.463202 9.000000 +-24.378036 -27.490997 9.000000 +-22.360403 19.414413 9.000000 +-24.290445 -27.446943 9.000000 +-22.279316 19.346117 9.000000 +-24.211710 -27.385281 9.000000 +-22.214451 19.262259 9.000000 +-24.146822 -27.309179 9.000000 +-22.169510 19.168819 9.000000 +-24.099159 -27.223497 9.000000 +-22.145428 19.072468 9.000000 +-24.069935 -27.133791 9.000000 +-21.149456 19.500000 9.000000 +-24.058266 -27.045269 9.000000 +28.873358 -27.115437 9.000000 +29.604803 -27.524435 9.000000 +28.381723 -27.524435 9.000000 +26.552937 19.492027 9.000000 +26.464001 19.500000 9.000000 +26.643787 19.466560 9.000000 +28.472704 -27.516088 9.000000 +26.731388 19.422504 9.000000 +28.565767 -27.489332 9.000000 +26.810129 19.360838 9.000000 +28.655321 -27.442938 9.000000 +26.875023 19.284733 9.000000 +28.735266 -27.377996 9.000000 +26.922689 19.199047 9.000000 +28.800207 -27.298054 9.000000 +26.951918 19.109339 9.000000 +28.846601 -27.208500 9.000000 +26.963587 19.020815 9.000000 +27.645451 19.500000 9.000000 +28.881271 -27.003639 9.000000 +28.881704 -27.024456 9.000000 +21.000000 28.500000 10.500000 +21.000000 28.500000 10.800000 +-21.000000 28.500000 10.800000 +-21.000000 28.500000 10.500000 +-28.881271 -27.003639 9.000000 +-27.645451 19.500000 9.000000 +-26.464001 19.500000 9.000000 +-28.474724 -27.515711 9.000000 +-28.381723 -27.524435 9.000000 +-28.569986 -27.487638 9.000000 +-26.552937 19.492027 9.000000 +-26.643787 19.466560 9.000000 +-28.661470 -27.438852 9.000000 +-26.731388 19.422504 9.000000 +-28.742550 -27.370560 9.000000 +-26.810129 19.360838 9.000000 +-28.807409 -27.286707 9.000000 +-26.875023 19.284733 9.000000 +-28.852345 -27.193270 9.000000 +-26.922689 19.199047 9.000000 +-28.876427 -27.096922 9.000000 +-26.951918 19.109339 9.000000 +-29.604803 -27.524435 9.000000 +-26.963587 19.020815 9.000000 +22.148495 19.090982 9.000000 +21.149456 19.500000 9.000000 +22.640167 19.500000 9.000000 +24.468882 -27.516462 9.000000 +24.557814 -27.524435 9.000000 +24.378036 -27.490997 9.000000 +22.549181 19.491653 9.000000 +22.456112 19.464893 9.000000 +24.290445 -27.446943 9.000000 +24.211710 -27.385281 9.000000 +22.366550 19.418497 9.000000 +24.146822 -27.309179 9.000000 +22.286600 19.353554 9.000000 +24.099159 -27.223497 9.000000 +22.221653 19.273605 9.000000 +24.069935 -27.133791 9.000000 +22.175255 19.184048 9.000000 +24.058266 -27.045269 9.000000 +23.108809 -27.524435 9.000000 +22.140581 18.979185 9.000000 +22.140148 19.000000 9.000000 +-21.698545 30.000000 13.391485 +-21.000000 30.000000 9.500000 +-21.000000 30.000000 0.501299 +-22.205130 30.000000 0.706587 +-23.339539 30.000000 1.128183 +-24.381807 30.000000 1.756571 +-25.283665 30.000000 2.562519 +-26.024683 30.000000 3.527889 +-26.570353 30.000000 4.608300 +-26.907141 30.000000 5.776322 +-27.020399 30.000000 6.983936 +-27.020399 30.000000 7.000000 +-26.911791 30.000000 8.182760 +-26.563627 30.000000 9.392615 +-25.959951 30.000000 10.556864 +-25.114943 30.000000 11.596194 +-24.074709 30.000000 12.440471 +-22.909451 30.000000 13.043624 +22.205130 30.000000 0.706587 +21.000000 30.000000 0.501299 +23.339539 30.000000 1.128183 +24.381807 30.000000 1.756571 +25.283665 30.000000 2.562519 +26.024683 30.000000 3.527889 +26.570353 30.000000 4.608300 +26.907141 30.000000 5.776322 +27.020399 30.000000 6.983936 +27.020399 30.000000 7.000000 +26.911791 30.000000 8.182760 +26.563627 30.000000 9.392615 +25.959951 30.000000 10.556864 +25.114943 30.000000 11.596194 +24.074709 30.000000 12.440471 +22.909451 30.000000 13.043624 +21.698545 30.000000 13.391485 +20.514759 30.000000 13.500000 +21.000000 30.000000 9.500000 +-20.514759 30.000000 13.500000 +-22.993927 -30.000000 0.000000 +-27.947969 -30.000000 2.050252 +-26.283258 -30.000000 1.978027 +-28.857979 -30.000000 3.169532 +-27.242641 -30.000000 2.757359 +-29.508091 -30.000000 4.423337 +-28.021973 -30.000000 3.716742 +-29.883036 -30.000000 5.726259 +-28.578730 -30.000000 4.791432 +-30.000000 -30.000000 7.000000 +-28.899832 -30.000000 5.908222 +-29.883036 -30.000000 8.273742 +-29.000000 -30.000000 7.000000 +-29.508091 -30.000000 9.576663 +-28.899832 -30.000000 8.091779 +-28.857979 -30.000000 10.830468 +-28.578730 -30.000000 9.208569 +-27.947969 -30.000000 11.949747 +-28.021973 -30.000000 10.283258 +-26.827719 -30.000000 12.858969 +-27.242641 -30.000000 11.242640 +-25.572824 -30.000000 13.508518 +-26.283258 -30.000000 12.021973 +-24.268772 -30.000000 13.883138 +-25.208569 -30.000000 12.578730 +-26.827719 -30.000000 1.141031 +-25.208569 -30.000000 1.421270 +-25.572824 -30.000000 0.491482 +-24.091778 -30.000000 1.100168 +-24.268772 -30.000000 0.116862 +-23.000000 -30.000000 1.000000 +-22.993927 -30.000000 14.000000 +-24.091778 -30.000000 12.899832 +-23.000000 -30.000000 13.000000 +22.993927 -30.000000 14.000000 +24.268772 -30.000000 13.883138 +23.000000 -30.000000 13.000000 +25.572824 -30.000000 13.508518 +24.091778 -30.000000 12.899832 +26.827719 -30.000000 12.858969 +25.208569 -30.000000 12.578730 +27.947969 -30.000000 11.949747 +26.283258 -30.000000 12.021973 +28.857979 -30.000000 10.830468 +27.242641 -30.000000 11.242640 +29.508091 -30.000000 9.576663 +28.021973 -30.000000 10.283258 +29.883036 -30.000000 8.273742 +28.578730 -30.000000 9.208569 +30.000000 -30.000000 7.000000 +28.899832 -30.000000 8.091779 +29.883036 -30.000000 5.726259 +29.000000 -30.000000 7.000000 +29.508091 -30.000000 4.423337 +28.899832 -30.000000 5.908222 +28.857979 -30.000000 3.169532 +28.578730 -30.000000 4.791432 +27.947969 -30.000000 2.050252 +28.021973 -30.000000 3.716742 +26.827719 -30.000000 1.141031 +27.242641 -30.000000 2.757359 +25.572824 -30.000000 0.491482 +26.283258 -30.000000 1.978027 +24.268772 -30.000000 0.116862 +25.208569 -30.000000 1.421270 +22.993927 -30.000000 0.000000 +24.091778 -30.000000 1.100168 +23.000000 -30.000000 1.000000 +22.578543 -28.000000 0.000000 +22.578543 -27.602978 0.000000 +-22.894051 -27.602978 0.000000 +-22.578543 -27.602978 0.000000 +-22.993927 -30.000000 0.000000 +22.993927 -30.000000 0.000000 +-22.578543 -28.000000 0.000000 +22.894051 -27.602978 0.000000 +-27.519966 29.520815 7.000000 +-27.519966 29.520815 6.983936 +-27.819616 22.329193 6.997829 +-27.819649 22.328426 7.000000 +27.519966 29.520815 7.000000 +27.819649 22.328426 7.000000 +27.819616 22.329193 6.997829 +27.519966 29.520815 6.983936 +-21.000000 22.500000 9.354102 +-21.021364 22.500000 9.354102 +-21.050659 22.500000 6.000000 +-27.740980 22.500000 6.000000 +-27.461208 22.500000 4.808880 +-26.977634 22.500000 3.683669 +-26.306774 22.500000 2.661841 +-25.465902 22.500000 1.770023 +-24.486139 22.500000 1.040717 +-23.389849 22.500000 0.490714 +-22.220266 22.500000 0.141402 +-21.000000 22.500000 0.000000 +21.050659 22.500000 6.000000 +21.021364 22.500000 9.354102 +27.459700 22.500000 4.804305 +27.740980 22.500000 6.000000 +26.977253 22.500000 3.682960 +26.303738 22.500000 2.657999 +25.465425 22.500000 1.769599 +24.481964 22.500000 1.038144 +23.389105 22.500000 0.490420 +22.215483 22.500000 0.140419 +21.000000 22.500000 0.000000 +21.000000 22.500000 9.354102 +22.212704 -27.526964 8.710185 +-22.508650 -27.533087 8.008726 +-22.578543 -27.602978 0.000000 +-22.894051 -27.602978 0.000000 +-24.168854 -27.601957 0.116862 +-25.472771 -27.598688 0.491482 +-26.727427 -27.593019 1.141031 +-27.847347 -27.585085 2.050252 +-28.756950 -27.575317 3.169532 +-29.406607 -27.564375 4.423337 +-29.781078 -27.553005 5.726259 +-29.897579 -27.541889 7.000000 +-29.604803 -27.524435 9.000000 +-22.490534 -27.531507 8.189685 +22.894051 -27.602978 0.000000 +22.578543 -27.602978 0.000000 +24.168854 -27.601957 0.116862 +25.472771 -27.598688 0.491482 +26.727427 -27.593019 1.141031 +27.847347 -27.585085 2.050252 +28.756950 -27.575317 3.169532 +29.406607 -27.564375 4.423337 +29.781078 -27.553005 5.726259 +29.897579 -27.541889 7.000000 +29.604803 -27.524435 9.000000 +28.381723 -27.524435 9.000000 +22.508650 -27.533087 8.008726 +24.564510 -27.517454 9.800000 +28.374445 -27.517454 9.800000 +24.557814 -27.524435 9.000000 +23.108809 -27.524435 9.000000 +22.490534 -27.531507 8.189685 +22.435947 -27.529894 8.374420 +-23.083334 -27.500000 11.800000 +23.083334 -27.500000 11.800000 +-28.374445 -27.517454 9.800000 +-24.564510 -27.517454 9.800000 +-28.381723 -27.524435 9.000000 +-24.557814 -27.524435 9.000000 +-22.435947 -27.529894 8.374420 +-22.342592 -27.528345 8.551910 +22.342592 -27.528345 8.551910 +-22.212704 -27.526964 8.710185 +-23.108809 -27.524435 9.000000 +-22.053301 -27.525843 8.838688 +-21.875004 -27.525042 8.930491 +-21.689798 -27.524580 8.983463 +-21.508688 -27.524435 9.000000 +21.508688 -27.524435 9.000000 +21.689798 -27.524580 8.983463 +21.875004 -27.525042 8.930491 +22.053301 -27.525843 8.838688 +-21.000000 23.904366 3.367935 +-21.000000 23.439899 8.174212 +-21.000000 22.500000 9.354102 +-21.000000 23.937059 6.750000 +-21.000000 23.970625 6.654294 +-21.000000 24.000851 6.609817 +-21.000000 24.039215 6.570871 +-21.000000 24.084009 6.539534 +-21.000000 27.700001 6.500000 +-21.000000 24.577124 5.000000 +-21.000000 27.500000 11.800000 +-21.000000 22.500000 11.800000 +-21.000000 22.709627 10.800000 +-21.000000 27.681963 11.783305 +-21.000000 27.868095 11.729788 +-21.000000 28.047211 11.636995 +-21.000000 27.700001 10.800000 +-21.000000 28.207108 11.507107 +-21.000000 28.336996 11.347210 +-21.000000 27.754589 10.794991 +-21.000000 28.429789 11.168095 +-21.000000 27.810429 10.778936 +-21.000000 28.483305 10.981963 +-21.000000 27.864162 10.751099 +-21.000000 28.500000 10.800000 +-21.000000 27.912132 10.712132 +-21.000000 27.951099 10.664163 +-21.000000 28.500000 10.500000 +-21.000000 27.978937 10.610429 +-21.000000 27.994991 10.554589 +-21.000000 24.132902 6.517144 +-21.000000 28.000000 10.500000 +-21.000000 28.516695 10.318037 +-21.000000 28.570211 10.131906 +-21.000000 28.663004 9.952790 +-21.000000 28.792892 9.792893 +-21.000000 28.952789 9.663005 +-21.000000 29.131905 9.570211 +-21.000000 30.000000 0.501299 +-21.000000 30.000000 9.500000 +-21.000000 24.232864 6.500000 +-21.000000 29.318037 9.516695 +-21.000000 29.500000 9.500000 +-21.000000 28.000000 6.800000 +-21.000000 27.994991 6.745411 +-21.000000 27.978937 6.689571 +-21.000000 27.951099 6.635837 +-21.000000 27.912132 6.587868 +-21.000000 27.864162 6.548902 +-21.000000 27.810429 6.521063 +-21.000000 27.754589 6.505008 +-21.000000 27.222876 5.000000 +-21.000000 27.602140 4.550103 +-21.000000 27.841074 3.981906 +-21.000000 27.895636 3.367935 +-21.000000 27.770828 2.792893 +-21.000000 27.484079 2.279061 +-21.000000 29.990097 0.403150 +-21.000000 29.961399 0.309202 +-21.000000 29.915417 0.222708 +-21.000000 29.853666 0.146921 +-21.000000 29.778114 0.084956 +-21.000000 29.691854 0.038786 +-21.000000 29.598083 0.009953 +-21.000000 29.500000 0.000000 +-21.000000 27.037054 1.854671 +-21.000000 22.500000 0.000000 +-21.000000 26.482027 1.586562 +-21.000000 25.900000 1.500000 +-21.000000 25.317972 1.586562 +-21.000000 24.762945 1.854671 +-21.000000 24.315920 2.279061 +-21.000000 24.197859 4.550103 +-21.000000 24.029171 2.792893 +-21.000000 23.958927 3.981906 +-21.092070 20.580383 10.416232 +-21.047979 22.449917 6.545889 +-21.050659 22.500000 6.000000 +-21.049791 22.289366 7.104284 +-21.056696 22.010986 7.641629 +-21.068743 21.621321 8.121321 +-21.079567 20.799999 10.800000 +-21.000000 22.709627 10.800000 +-21.000000 22.500000 11.800000 +-21.083782 20.702278 10.783638 +-21.085962 20.654432 10.762317 +-21.088058 20.610384 10.732477 +-21.089970 20.572298 10.695325 +-21.091612 20.541794 10.652741 +-21.093906 20.506123 10.560303 +-21.085327 21.141630 8.510986 +-21.021364 22.500000 9.354102 +-21.105284 20.604284 8.789365 +-21.050983 21.665281 9.944814 +-21.127148 20.045889 8.949916 +-21.087042 20.718750 10.331819 +-23.083334 -27.500000 11.800000 +-23.108809 -27.524435 9.000000 +-21.093464 20.532627 10.484550 +-21.149456 19.500000 9.000000 +-21.089832 20.645096 10.363692 +-22.640167 19.500000 9.000000 +-26.464001 19.500000 9.000000 +-27.645451 19.500000 9.000000 +-21.127148 20.045889 8.949916 +-21.149456 19.500000 9.000000 +-27.740980 22.500000 6.000000 +-21.050659 22.500000 6.000000 +-27.796915 22.457510 6.504951 +-27.819616 22.329193 6.997829 +-21.047979 22.449917 6.545889 +-27.819649 22.328426 7.000000 +-27.814631 22.140718 7.423588 +-21.049791 22.289366 7.104284 +-27.790483 21.890099 7.813128 +-21.056696 22.010986 7.641629 +-27.754364 21.585892 8.156167 +-21.062099 21.829060 7.890894 +-21.068743 21.621321 8.121321 +-27.713345 21.230772 8.450394 +-21.076529 21.390894 8.329060 +-27.675589 20.836082 8.686168 +-21.085327 21.141630 8.510986 +-27.648039 20.408684 8.859072 +-21.105284 20.604284 8.789365 +-27.636803 19.960232 8.964703 +26.464001 19.500000 9.000000 +27.636776 19.962101 8.964197 +27.645451 19.500000 9.000000 +21.050659 22.500000 6.000000 +27.740980 22.500000 6.000000 +21.047979 22.449917 6.545889 +27.796915 22.457510 6.504951 +21.049791 22.289366 7.104284 +27.819616 22.329193 6.997829 +27.819649 22.328426 7.000000 +21.056696 22.010986 7.641629 +27.814705 22.141703 7.422219 +21.062099 21.829060 7.890894 +27.790804 21.892946 7.809367 +21.068743 21.621321 8.121321 +21.076529 21.390894 8.329060 +27.754604 21.587914 8.154340 +21.085327 21.141630 8.510986 +27.713736 21.234396 8.447829 +21.105284 20.604284 8.789365 +27.675755 20.838432 8.684884 +21.127148 20.045889 8.949916 +27.648254 20.413347 8.857586 +21.149456 19.500000 9.000000 +22.640167 19.500000 9.000000 +-21.000000 30.000000 9.500000 +21.000000 30.000000 9.500000 +21.000000 29.500000 9.500000 +-21.000000 29.500000 9.500000 +26.963587 19.020815 9.000000 +28.881271 -27.003639 9.000000 +28.873993 -26.996658 9.800000 +26.956598 19.020815 9.800000 +22.640167 19.500000 9.000000 +26.464001 19.500000 9.000000 +26.457012 19.500000 9.800000 +22.647154 19.500000 9.800000 +24.064962 -27.038288 9.800000 +24.058266 -27.045269 9.000000 +22.140581 18.979185 9.000000 +22.147568 18.979185 9.800000 +27.268936 -0.485696 9.800000 +26.636801 19.466560 9.800000 +26.545950 19.492027 9.800000 +26.457012 19.500000 9.800000 +26.724400 19.422504 9.800000 +26.803143 19.360838 9.800000 +26.868036 19.284733 9.800000 +26.915703 19.199047 9.800000 +26.944929 19.109339 9.800000 +24.076632 -27.126810 9.800000 +24.105856 -27.216516 9.800000 +24.153519 -27.302198 9.800000 +24.218407 -27.378298 9.800000 +24.297142 -27.439962 9.800000 +24.384733 -27.484016 9.800000 +24.475578 -27.509481 9.800000 +24.564510 -27.517454 9.800000 +23.230070 5.009536 9.800000 +27.081635 4.009536 9.800000 +27.310602 -1.485696 9.800000 +23.459040 -0.485696 9.800000 +26.852667 9.504768 9.800000 +23.001102 10.504768 9.800000 +26.623699 15.000000 9.800000 +22.772135 16.000000 9.800000 +24.064962 -27.038288 9.800000 +24.416578 -23.466623 9.800000 +24.187609 -17.971392 9.800000 +27.997507 -17.971392 9.800000 +24.145943 -16.971392 9.800000 +23.958641 -12.476159 9.800000 +23.729673 -6.980927 9.800000 +23.916975 -11.476159 9.800000 +27.768538 -12.476159 9.800000 +24.374910 -22.466623 9.800000 +28.226475 -23.466623 9.800000 +26.457031 19.000000 9.800000 +22.647154 19.500000 9.800000 +22.556170 19.491653 9.800000 +22.463100 19.464893 9.800000 +22.373539 19.418497 9.800000 +22.293587 19.353554 9.800000 +22.228640 19.273605 9.800000 +22.182241 19.184048 9.800000 +22.155483 19.090982 9.800000 +22.147135 19.000000 9.800000 +22.147568 18.979185 9.800000 +24.563801 -27.000000 9.800000 +28.374445 -27.517454 9.800000 +28.465425 -27.509108 9.800000 +28.558489 -27.482349 9.800000 +28.648043 -27.435957 9.800000 +28.727987 -27.371016 9.800000 +28.792929 -27.291071 9.800000 +28.839323 -27.201517 9.800000 +28.866079 -27.108456 9.800000 +28.874426 -27.017475 9.800000 +28.873993 -26.996658 9.800000 +26.956598 19.020815 9.800000 +28.373699 -27.000000 9.800000 +28.184809 -22.466623 9.800000 +27.955839 -16.971392 9.800000 +27.726871 -11.476159 9.800000 +26.582031 16.000000 9.800000 +22.647135 19.000000 9.800000 +26.810999 10.504768 9.800000 +22.813801 15.000000 9.800000 +23.042770 9.504768 9.800000 +27.039968 5.009536 9.800000 +23.271738 4.009536 9.800000 +23.500706 -1.485696 9.800000 +23.688007 -5.980927 9.800000 +27.539570 -6.980927 9.800000 +27.497904 -5.980927 9.800000 +-22.140581 18.979185 9.000000 +-24.058266 -27.045269 9.000000 +-24.064962 -27.038288 9.800000 +-22.147568 18.979185 9.800000 +-22.640167 19.500000 9.000000 +-22.647154 19.500000 9.800000 +-26.457012 19.500000 9.800000 +-26.464001 19.500000 9.000000 +-28.873993 -26.996658 9.800000 +-28.881271 -27.003639 9.000000 +-26.963587 19.020815 9.000000 +-26.956598 19.020815 9.800000 +-26.724400 19.422504 9.800000 +-26.636801 19.466560 9.800000 +-26.545950 19.492027 9.800000 +-26.803143 19.360838 9.800000 +-26.868036 19.284733 9.800000 +-26.915703 19.199047 9.800000 +-26.944929 19.109339 9.800000 +-26.956598 19.020815 9.800000 +-24.064962 -27.038288 9.800000 +-24.076632 -27.126810 9.800000 +-24.105856 -27.216516 9.800000 +-24.153519 -27.302198 9.800000 +-24.218407 -27.378298 9.800000 +-24.297142 -27.439962 9.800000 +-24.384733 -27.484016 9.800000 +-24.475578 -27.509481 9.800000 +-26.810999 10.504768 9.800000 +-23.042770 9.504768 9.800000 +-23.271738 4.009536 9.800000 +-27.039968 5.009536 9.800000 +-23.500706 -1.485696 9.800000 +-27.268936 -0.485696 9.800000 +-23.729673 -6.980927 9.800000 +-27.497904 -5.980927 9.800000 +-22.147568 18.979185 9.800000 +-24.563801 -27.000000 9.800000 +-24.374910 -22.466623 9.800000 +-24.145943 -16.971392 9.800000 +-23.916975 -11.476159 9.800000 +-23.688007 -5.980927 9.800000 +-23.459040 -0.485696 9.800000 +-23.230070 5.009536 9.800000 +-23.001102 10.504768 9.800000 +-28.184809 -22.466623 9.800000 +-24.416578 -23.466623 9.800000 +-27.955839 -16.971392 9.800000 +-24.187609 -17.971392 9.800000 +-27.726871 -11.476159 9.800000 +-23.958641 -12.476159 9.800000 +-22.647135 19.000000 9.800000 +-26.457012 19.500000 9.800000 +-22.647154 19.500000 9.800000 +-22.554150 19.491276 9.800000 +-22.458881 19.463202 9.800000 +-22.367390 19.414413 9.800000 +-22.286303 19.346117 9.800000 +-22.221437 19.262259 9.800000 +-22.176498 19.168819 9.800000 +-22.152414 19.072468 9.800000 +-26.457031 19.000000 9.800000 +-28.873993 -26.996658 9.800000 +-28.373699 -27.000000 9.800000 +-24.564510 -27.517454 9.800000 +-28.374445 -27.517454 9.800000 +-28.467445 -27.508728 9.800000 +-28.562708 -27.480658 9.800000 +-28.654192 -27.431871 9.800000 +-28.735271 -27.363579 9.800000 +-28.800131 -27.279724 9.800000 +-28.845066 -27.186289 9.800000 +-28.869148 -27.089941 9.800000 +-28.226475 -23.466623 9.800000 +-22.772135 16.000000 9.800000 +-26.582031 16.000000 9.800000 +-22.813801 15.000000 9.800000 +-26.623699 15.000000 9.800000 +-26.852667 9.504768 9.800000 +-27.081635 4.009536 9.800000 +-27.310602 -1.485696 9.800000 +-27.539570 -6.980927 9.800000 +-27.768538 -12.476159 9.800000 +-27.997507 -17.971392 9.800000 +24.889462 19.000000 11.591903 +23.815733 19.000000 12.164536 +22.647135 19.000000 9.800000 +26.457031 19.000000 9.800000 +25.793076 19.000000 10.777225 +22.670340 19.000000 12.456755 +24.587008 -27.000000 12.456755 +25.732399 -27.000000 12.164536 +27.709742 -27.000000 10.777225 +28.373699 -27.000000 9.800000 +26.806128 -27.000000 11.591903 +24.563801 -27.000000 9.800000 +-22.670340 19.000000 12.456755 +-23.815733 19.000000 12.164536 +-25.793076 19.000000 10.777225 +-26.457031 19.000000 9.800000 +-24.889462 19.000000 11.591903 +-22.647135 19.000000 9.800000 +-26.806128 -27.000000 11.591903 +-25.732399 -27.000000 12.164536 +-24.563801 -27.000000 9.800000 +-28.373699 -27.000000 9.800000 +-27.709742 -27.000000 10.777225 +-24.587008 -27.000000 12.456755 +-24.439783 -23.466623 12.456755 +-24.416578 -23.466623 9.800000 +-24.563801 -27.000000 9.800000 +-24.587008 -27.000000 12.456755 +22.795340 16.000000 12.456755 +23.940733 16.000000 12.164536 +25.918076 16.000000 10.777225 +26.582031 16.000000 9.800000 +25.014462 16.000000 11.591903 +22.772135 16.000000 9.800000 +25.056128 15.000000 11.591903 +23.982399 15.000000 12.164536 +22.813801 15.000000 9.800000 +26.623699 15.000000 9.800000 +25.959742 15.000000 10.777225 +22.837008 15.000000 12.456755 +23.024307 10.504768 12.456755 +24.169701 10.504768 12.164536 +26.147043 10.504768 10.777225 +26.810999 10.504768 9.800000 +25.243429 10.504768 11.591903 +23.001102 10.504768 9.800000 +25.285095 9.504768 11.591903 +24.211369 9.504768 12.164536 +23.042770 9.504768 9.800000 +26.852667 9.504768 9.800000 +26.188711 9.504768 10.777225 +23.065975 9.504768 12.456755 +23.253277 5.009536 12.456755 +24.398668 5.009536 12.164536 +26.376011 5.009536 10.777225 +27.039968 5.009536 9.800000 +25.472397 5.009536 11.591903 +23.230070 5.009536 9.800000 +25.514065 4.009536 11.591903 +24.440336 4.009536 12.164536 +23.271738 4.009536 9.800000 +27.081635 4.009536 9.800000 +26.417679 4.009536 10.777225 +23.294943 4.009536 12.456755 +23.482244 -0.485696 12.456755 +24.627638 -0.485696 12.164536 +26.604980 -0.485696 10.777225 +27.268936 -0.485696 9.800000 +25.701365 -0.485696 11.591903 +23.459040 -0.485696 9.800000 +25.743032 -1.485696 11.591903 +24.669304 -1.485696 12.164536 +23.500706 -1.485696 9.800000 +27.310602 -1.485696 9.800000 +26.646646 -1.485696 10.777225 +23.523911 -1.485696 12.456755 +23.711212 -5.980927 12.456755 +24.856606 -5.980927 12.164536 +26.833948 -5.980927 10.777225 +27.497904 -5.980927 9.800000 +25.930334 -5.980927 11.591903 +23.688007 -5.980927 9.800000 +25.972000 -6.980927 11.591903 +24.898272 -6.980927 12.164536 +23.729673 -6.980927 9.800000 +27.539570 -6.980927 9.800000 +26.875614 -6.980927 10.777225 +23.752878 -6.980927 12.456755 +23.940180 -11.476159 12.456755 +25.085573 -11.476159 12.164536 +27.062916 -11.476159 10.777225 +27.726871 -11.476159 9.800000 +26.159302 -11.476159 11.591903 +23.916975 -11.476159 9.800000 +26.200968 -12.476159 11.591903 +25.127239 -12.476159 12.164536 +23.958641 -12.476159 9.800000 +27.768538 -12.476159 9.800000 +27.104582 -12.476159 10.777225 +23.981846 -12.476159 12.456755 +24.169147 -16.971392 12.456755 +25.314541 -16.971392 12.164536 +27.291883 -16.971392 10.777225 +27.955839 -16.971392 9.800000 +26.388269 -16.971392 11.591903 +24.145943 -16.971392 9.800000 +26.429935 -17.971392 11.591903 +25.356209 -17.971392 12.164536 +24.187609 -17.971392 9.800000 +27.997507 -17.971392 9.800000 +27.333549 -17.971392 10.777225 +24.210815 -17.971392 12.456755 +24.398115 -22.466623 12.456755 +25.543509 -22.466623 12.164536 +27.520851 -22.466623 10.777225 +28.184809 -22.466623 9.800000 +26.617237 -22.466623 11.591903 +24.374910 -22.466623 9.800000 +26.658905 -23.466623 11.591903 +25.585176 -23.466623 12.164536 +24.416578 -23.466623 9.800000 +28.226475 -23.466623 9.800000 +27.562519 -23.466623 10.777225 +24.439783 -23.466623 12.456755 +-25.014462 16.000000 11.591903 +-23.940733 16.000000 12.164536 +-22.772135 16.000000 9.800000 +-26.582031 16.000000 9.800000 +-25.918076 16.000000 10.777225 +-22.795340 16.000000 12.456755 +-22.837008 15.000000 12.456755 +-23.982399 15.000000 12.164536 +-25.959742 15.000000 10.777225 +-26.623699 15.000000 9.800000 +-25.056128 15.000000 11.591903 +-22.813801 15.000000 9.800000 +-25.243429 10.504768 11.591903 +-24.169701 10.504768 12.164536 +-23.001102 10.504768 9.800000 +-26.810999 10.504768 9.800000 +-26.147043 10.504768 10.777225 +-23.024307 10.504768 12.456755 +-23.065975 9.504768 12.456755 +-24.211369 9.504768 12.164536 +-26.188711 9.504768 10.777225 +-26.852667 9.504768 9.800000 +-25.285095 9.504768 11.591903 +-23.042770 9.504768 9.800000 +-25.472397 5.009536 11.591903 +-24.398668 5.009536 12.164536 +-23.230070 5.009536 9.800000 +-27.039968 5.009536 9.800000 +-26.376011 5.009536 10.777225 +-23.253277 5.009536 12.456755 +-23.294943 4.009536 12.456755 +-24.440336 4.009536 12.164536 +-26.417679 4.009536 10.777225 +-27.081635 4.009536 9.800000 +-25.514065 4.009536 11.591903 +-23.271738 4.009536 9.800000 +-25.701365 -0.485696 11.591903 +-24.627638 -0.485696 12.164536 +-23.459040 -0.485696 9.800000 +-27.268936 -0.485696 9.800000 +-26.604980 -0.485696 10.777225 +-23.482244 -0.485696 12.456755 +-23.523911 -1.485696 12.456755 +-24.669304 -1.485696 12.164536 +-26.646646 -1.485696 10.777225 +-27.310602 -1.485696 9.800000 +-25.743032 -1.485696 11.591903 +-23.500706 -1.485696 9.800000 +-25.930334 -5.980927 11.591903 +-24.856606 -5.980927 12.164536 +-23.688007 -5.980927 9.800000 +-27.497904 -5.980927 9.800000 +-26.833948 -5.980927 10.777225 +-23.711212 -5.980927 12.456755 +-23.752878 -6.980927 12.456755 +-24.898272 -6.980927 12.164536 +-26.875614 -6.980927 10.777225 +-27.539570 -6.980927 9.800000 +-25.972000 -6.980927 11.591903 +-23.729673 -6.980927 9.800000 +-26.159302 -11.476159 11.591903 +-25.085573 -11.476159 12.164536 +-23.916975 -11.476159 9.800000 +-27.726871 -11.476159 9.800000 +-27.062916 -11.476159 10.777225 +-23.940180 -11.476159 12.456755 +-23.981846 -12.476159 12.456755 +-25.127239 -12.476159 12.164536 +-27.104582 -12.476159 10.777225 +-27.768538 -12.476159 9.800000 +-26.200968 -12.476159 11.591903 +-23.958641 -12.476159 9.800000 +-26.388269 -16.971392 11.591903 +-25.314541 -16.971392 12.164536 +-24.145943 -16.971392 9.800000 +-27.955839 -16.971392 9.800000 +-27.291883 -16.971392 10.777225 +-24.169147 -16.971392 12.456755 +-24.210815 -17.971392 12.456755 +-25.356209 -17.971392 12.164536 +-27.333549 -17.971392 10.777225 +-27.997507 -17.971392 9.800000 +-26.429935 -17.971392 11.591903 +-24.187609 -17.971392 9.800000 +-26.617237 -22.466623 11.591903 +-25.543509 -22.466623 12.164536 +-24.374910 -22.466623 9.800000 +-28.184809 -22.466623 9.800000 +-27.520851 -22.466623 10.777225 +-24.398115 -22.466623 12.456755 +-24.439783 -23.466623 12.456755 +-25.585176 -23.466623 12.164536 +-27.562519 -23.466623 10.777225 +-28.226475 -23.466623 9.800000 +-26.658905 -23.466623 11.591903 +-24.416578 -23.466623 9.800000 +-28.074314 -27.000000 10.302947 +-28.373699 -27.000000 9.800000 +-25.014908 -23.466623 12.346143 +-24.439783 -23.466623 12.456755 +-24.587008 -27.000000 12.456755 +-25.585176 -23.466623 12.164536 +-25.162132 -27.000000 12.346143 +-26.137522 -23.466623 11.912025 +-25.732399 -27.000000 12.164536 +-26.658905 -23.466623 11.591903 +-26.284746 -27.000000 11.912025 +-27.137281 -23.466623 11.210590 +-26.806128 -27.000000 11.591903 +-27.562519 -23.466623 10.777225 +-27.284506 -27.000000 11.210590 +-27.927090 -23.466623 10.302947 +-27.709742 -27.000000 10.777225 +-28.226475 -23.466623 9.800000 +-27.885424 -22.466623 10.302947 +-28.184809 -22.466623 9.800000 +-24.785940 -17.971392 12.346143 +-24.210815 -17.971392 12.456755 +-24.398115 -22.466623 12.456755 +-25.356209 -17.971392 12.164536 +-24.973242 -22.466623 12.346143 +-25.908554 -17.971392 11.912025 +-25.543509 -22.466623 12.164536 +-26.429935 -17.971392 11.591903 +-26.095856 -22.466623 11.912025 +-26.908314 -17.971392 11.210590 +-26.617237 -22.466623 11.591903 +-27.333549 -17.971392 10.777225 +-27.095615 -22.466623 11.210590 +-27.698122 -17.971392 10.302947 +-27.520851 -22.466623 10.777225 +-27.997507 -17.971392 9.800000 +-27.656456 -16.971392 10.302947 +-27.955839 -16.971392 9.800000 +-24.556973 -12.476159 12.346143 +-23.981846 -12.476159 12.456755 +-24.169147 -16.971392 12.456755 +-25.127239 -12.476159 12.164536 +-24.744274 -16.971392 12.346143 +-25.679586 -12.476159 11.912025 +-25.314541 -16.971392 12.164536 +-26.200968 -12.476159 11.591903 +-25.866886 -16.971392 11.912025 +-26.679344 -12.476159 11.210590 +-26.388269 -16.971392 11.591903 +-27.104582 -12.476159 10.777225 +-26.866646 -16.971392 11.210590 +-27.469154 -12.476159 10.302947 +-27.291883 -16.971392 10.777225 +-27.768538 -12.476159 9.800000 +-27.427488 -11.476159 10.302947 +-27.726871 -11.476159 9.800000 +-24.328005 -6.980927 12.346143 +-23.752878 -6.980927 12.456755 +-23.940180 -11.476159 12.456755 +-24.898272 -6.980927 12.164536 +-24.515306 -11.476159 12.346143 +-25.450617 -6.980927 11.912025 +-25.085573 -11.476159 12.164536 +-25.972000 -6.980927 11.591903 +-25.637918 -11.476159 11.912025 +-26.450377 -6.980927 11.210590 +-26.159302 -11.476159 11.591903 +-26.875614 -6.980927 10.777225 +-26.637678 -11.476159 11.210590 +-27.240187 -6.980927 10.302947 +-27.062916 -11.476159 10.777225 +-27.539570 -6.980927 9.800000 +-27.198519 -5.980927 10.302947 +-27.497904 -5.980927 9.800000 +-24.099037 -1.485696 12.346143 +-23.523911 -1.485696 12.456755 +-23.711212 -5.980927 12.456755 +-24.669304 -1.485696 12.164536 +-24.286337 -5.980927 12.346143 +-25.221649 -1.485696 11.912025 +-24.856606 -5.980927 12.164536 +-25.743032 -1.485696 11.591903 +-25.408951 -5.980927 11.912025 +-26.221409 -1.485696 11.210590 +-25.930334 -5.980927 11.591903 +-26.646646 -1.485696 10.777225 +-26.408710 -5.980927 11.210590 +-27.011217 -1.485696 10.302947 +-26.833948 -5.980927 10.777225 +-27.310602 -1.485696 9.800000 +-26.969551 -0.485696 10.302947 +-27.268936 -0.485696 9.800000 +-23.870068 4.009536 12.346143 +-23.294943 4.009536 12.456755 +-23.482244 -0.485696 12.456755 +-24.440336 4.009536 12.164536 +-24.057369 -0.485696 12.346143 +-24.992682 4.009536 11.912025 +-24.627638 -0.485696 12.164536 +-25.514065 4.009536 11.591903 +-25.179983 -0.485696 11.912025 +-25.992441 4.009536 11.210590 +-25.701365 -0.485696 11.591903 +-26.417679 4.009536 10.777225 +-26.179743 -0.485696 11.210590 +-26.782249 4.009536 10.302947 +-26.604980 -0.485696 10.777225 +-27.081635 4.009536 9.800000 +-26.740583 5.009536 10.302947 +-27.039968 5.009536 9.800000 +-23.641100 9.504768 12.346143 +-23.065975 9.504768 12.456755 +-23.253277 5.009536 12.456755 +-24.211369 9.504768 12.164536 +-23.828402 5.009536 12.346143 +-24.763714 9.504768 11.912025 +-24.398668 5.009536 12.164536 +-25.285095 9.504768 11.591903 +-24.951015 5.009536 11.912025 +-25.763474 9.504768 11.210590 +-25.472397 5.009536 11.591903 +-26.188711 9.504768 10.777225 +-25.950775 5.009536 11.210590 +-26.553282 9.504768 10.302947 +-26.376011 5.009536 10.777225 +-26.852667 9.504768 9.800000 +-26.511616 10.504768 10.302947 +-26.810999 10.504768 9.800000 +-23.412132 15.000000 12.346143 +-22.837008 15.000000 12.456755 +-23.024307 10.504768 12.456755 +-23.982399 15.000000 12.164536 +-23.599434 10.504768 12.346143 +-24.534746 15.000000 11.912025 +-24.169701 10.504768 12.164536 +-25.056128 15.000000 11.591903 +-24.722048 10.504768 11.912025 +-25.534506 15.000000 11.210590 +-25.243429 10.504768 11.591903 +-25.959742 15.000000 10.777225 +-25.721806 10.504768 11.210590 +-26.324314 15.000000 10.302947 +-26.147043 10.504768 10.777225 +-26.623699 15.000000 9.800000 +-26.282648 16.000000 10.302947 +-26.582031 16.000000 9.800000 +-23.245466 19.000000 12.346143 +-22.670340 19.000000 12.456755 +-22.795340 16.000000 12.456755 +-23.815733 19.000000 12.164536 +-23.370466 16.000000 12.346143 +-24.368078 19.000000 11.912025 +-23.940733 16.000000 12.164536 +-24.889462 19.000000 11.591903 +-24.493078 16.000000 11.912025 +-25.367838 19.000000 11.210590 +-25.014462 16.000000 11.591903 +-25.793076 19.000000 10.777225 +-25.492838 16.000000 11.210590 +-26.157648 19.000000 10.302947 +-25.918076 16.000000 10.777225 +-26.457031 19.000000 9.800000 +28.226475 -23.466623 9.800000 +28.373699 -27.000000 9.800000 +24.587008 -27.000000 12.456755 +24.439783 -23.466623 12.456755 +25.162132 -27.000000 12.346143 +25.014908 -23.466623 12.346143 +25.732399 -27.000000 12.164536 +25.585176 -23.466623 12.164536 +26.284746 -27.000000 11.912025 +26.137522 -23.466623 11.912025 +26.806128 -27.000000 11.591903 +26.658905 -23.466623 11.591903 +27.284506 -27.000000 11.210590 +27.137281 -23.466623 11.210590 +27.709742 -27.000000 10.777225 +27.562519 -23.466623 10.777225 +28.074314 -27.000000 10.302947 +27.927090 -23.466623 10.302947 +27.997507 -17.971392 9.800000 +28.184809 -22.466623 9.800000 +24.398115 -22.466623 12.456755 +24.210815 -17.971392 12.456755 +24.973242 -22.466623 12.346143 +24.785940 -17.971392 12.346143 +25.543509 -22.466623 12.164536 +25.356209 -17.971392 12.164536 +26.095856 -22.466623 11.912025 +25.908554 -17.971392 11.912025 +26.617237 -22.466623 11.591903 +26.429935 -17.971392 11.591903 +27.095615 -22.466623 11.210590 +26.908314 -17.971392 11.210590 +27.520851 -22.466623 10.777225 +27.333549 -17.971392 10.777225 +27.885424 -22.466623 10.302947 +27.698122 -17.971392 10.302947 +27.768538 -12.476159 9.800000 +27.955839 -16.971392 9.800000 +24.169147 -16.971392 12.456755 +23.981846 -12.476159 12.456755 +24.744274 -16.971392 12.346143 +24.556973 -12.476159 12.346143 +25.314541 -16.971392 12.164536 +25.127239 -12.476159 12.164536 +25.866886 -16.971392 11.912025 +25.679586 -12.476159 11.912025 +26.388269 -16.971392 11.591903 +26.200968 -12.476159 11.591903 +26.866646 -16.971392 11.210590 +26.679344 -12.476159 11.210590 +27.291883 -16.971392 10.777225 +27.104582 -12.476159 10.777225 +27.656456 -16.971392 10.302947 +27.469154 -12.476159 10.302947 +27.539570 -6.980927 9.800000 +27.726871 -11.476159 9.800000 +23.940180 -11.476159 12.456755 +23.752878 -6.980927 12.456755 +24.515306 -11.476159 12.346143 +24.328005 -6.980927 12.346143 +25.085573 -11.476159 12.164536 +24.898272 -6.980927 12.164536 +25.637918 -11.476159 11.912025 +25.450617 -6.980927 11.912025 +26.159302 -11.476159 11.591903 +25.972000 -6.980927 11.591903 +26.637678 -11.476159 11.210590 +26.450377 -6.980927 11.210590 +27.062916 -11.476159 10.777225 +26.875614 -6.980927 10.777225 +27.427488 -11.476159 10.302947 +27.240187 -6.980927 10.302947 +27.310602 -1.485696 9.800000 +27.497904 -5.980927 9.800000 +23.711212 -5.980927 12.456755 +23.523911 -1.485696 12.456755 +24.286337 -5.980927 12.346143 +24.099037 -1.485696 12.346143 +24.856606 -5.980927 12.164536 +24.669304 -1.485696 12.164536 +25.408951 -5.980927 11.912025 +25.221649 -1.485696 11.912025 +25.930334 -5.980927 11.591903 +25.743032 -1.485696 11.591903 +26.408710 -5.980927 11.210590 +26.221409 -1.485696 11.210590 +26.833948 -5.980927 10.777225 +26.646646 -1.485696 10.777225 +27.198519 -5.980927 10.302947 +27.011217 -1.485696 10.302947 +27.081635 4.009536 9.800000 +27.268936 -0.485696 9.800000 +23.482244 -0.485696 12.456755 +23.294943 4.009536 12.456755 +24.057369 -0.485696 12.346143 +23.870068 4.009536 12.346143 +24.627638 -0.485696 12.164536 +24.440336 4.009536 12.164536 +25.179983 -0.485696 11.912025 +24.992682 4.009536 11.912025 +25.701365 -0.485696 11.591903 +25.514065 4.009536 11.591903 +26.179743 -0.485696 11.210590 +25.992441 4.009536 11.210590 +26.604980 -0.485696 10.777225 +26.417679 4.009536 10.777225 +26.969551 -0.485696 10.302947 +26.782249 4.009536 10.302947 +26.852667 9.504768 9.800000 +27.039968 5.009536 9.800000 +23.253277 5.009536 12.456755 +23.065975 9.504768 12.456755 +23.828402 5.009536 12.346143 +23.641100 9.504768 12.346143 +24.398668 5.009536 12.164536 +24.211369 9.504768 12.164536 +24.951015 5.009536 11.912025 +24.763714 9.504768 11.912025 +25.472397 5.009536 11.591903 +25.285095 9.504768 11.591903 +25.950775 5.009536 11.210590 +25.763474 9.504768 11.210590 +26.376011 5.009536 10.777225 +26.188711 9.504768 10.777225 +26.740583 5.009536 10.302947 +26.553282 9.504768 10.302947 +26.623699 15.000000 9.800000 +26.810999 10.504768 9.800000 +23.024307 10.504768 12.456755 +22.837008 15.000000 12.456755 +23.599434 10.504768 12.346143 +23.412132 15.000000 12.346143 +24.169701 10.504768 12.164536 +23.982399 15.000000 12.164536 +24.722048 10.504768 11.912025 +24.534746 15.000000 11.912025 +25.243429 10.504768 11.591903 +25.056128 15.000000 11.591903 +25.721806 10.504768 11.210590 +25.534506 15.000000 11.210590 +26.147043 10.504768 10.777225 +25.959742 15.000000 10.777225 +26.511616 10.504768 10.302947 +26.324314 15.000000 10.302947 +26.457031 19.000000 9.800000 +26.582031 16.000000 9.800000 +22.795340 16.000000 12.456755 +22.670340 19.000000 12.456755 +23.370466 16.000000 12.346143 +23.245466 19.000000 12.346143 +23.940733 16.000000 12.164536 +23.815733 19.000000 12.164536 +24.493078 16.000000 11.912025 +24.368078 19.000000 11.912025 +25.014462 16.000000 11.591903 +24.889462 19.000000 11.591903 +25.492838 16.000000 11.210590 +25.367838 19.000000 11.210590 +25.918076 16.000000 10.777225 +25.793076 19.000000 10.777225 +26.282648 16.000000 10.302947 +26.157648 19.000000 10.302947 +-27.796915 22.457510 6.504951 +-27.819616 22.329193 6.997829 +-22.303431 29.503923 0.215352 +-21.000000 29.500000 0.000000 +-21.000000 22.500000 0.000000 +-22.220266 22.500000 0.141402 +-23.531500 29.507671 0.665791 +-23.389849 22.500000 0.490714 +-24.660194 29.511168 1.340793 +-24.486139 22.500000 1.040717 +-25.637346 29.514252 2.208935 +-25.465902 22.500000 1.770023 +-26.440493 29.516851 3.250411 +-26.306774 22.500000 2.661841 +-27.032007 29.518847 4.416991 +-26.977634 22.500000 3.683669 +-27.397171 29.520187 5.678949 +-27.461208 22.500000 4.808880 +-27.519966 29.520815 6.983936 +-27.740980 22.500000 6.000000 +-24.168854 -27.601957 0.116862 +-22.894051 -27.602978 0.000000 +-30.000000 -30.000000 7.000000 +-29.897579 -27.541889 7.000000 +-29.883036 -30.000000 5.726259 +-29.508091 -30.000000 4.423337 +-29.781078 -27.553005 5.726259 +-28.857979 -30.000000 3.169532 +-29.406607 -27.564375 4.423337 +-28.433113 -30.000000 2.587913 +-28.756950 -27.575317 3.169532 +-27.947969 -30.000000 2.050252 +-28.332296 -27.580393 2.587913 +-27.409842 -30.000000 1.565528 +-27.847347 -27.585085 2.050252 +-26.827719 -30.000000 1.141031 +-27.309397 -27.589315 1.565528 +-25.572824 -30.000000 0.491482 +-26.727427 -27.593019 1.141031 +-24.268772 -30.000000 0.116862 +-25.472771 -27.598688 0.491482 +-22.993927 -30.000000 0.000000 +-27.519966 29.520815 7.000000 +-27.819649 22.328426 7.000000 +-29.897579 -27.541889 7.000000 +-30.000000 -30.000000 7.000000 +-29.823814 -27.533070 8.010587 +-29.604803 -27.524435 9.000000 +-29.883036 -30.000000 8.273742 +-22.993927 -30.000000 14.000000 +-20.514759 29.500000 14.000000 +-24.268772 -30.000000 13.883138 +-21.789448 29.503788 13.883138 +-25.572824 -30.000000 13.508518 +-23.093340 29.507662 13.508518 +-26.827719 -30.000000 12.858969 +-24.348078 29.511391 12.858969 +-27.409842 -30.000000 12.434472 +-24.930128 29.513121 12.434472 +-27.947969 -30.000000 11.949747 +-25.468189 29.514719 11.949747 +-28.433113 -30.000000 11.412086 +-25.953274 29.516159 11.412086 +-28.857979 -30.000000 10.830468 +-26.378086 29.517422 10.830468 +-29.508091 -30.000000 9.576663 +-27.645451 19.500000 9.000000 +-27.028118 29.519354 9.576663 +-27.648039 20.408684 8.859072 +-27.713345 21.230772 8.450394 +-27.790483 21.890099 7.813128 +-27.403017 29.520468 8.273742 +22.215483 22.500000 0.140419 +21.000000 22.500000 0.000000 +27.519966 29.520815 6.983936 +27.819616 22.329193 6.997829 +27.397171 29.520187 5.678949 +27.796915 22.457510 6.504951 +27.740980 22.500000 6.000000 +27.032007 29.518847 4.416991 +27.459700 22.500000 4.804305 +26.440493 29.516851 3.250411 +26.977253 22.500000 3.682960 +25.637346 29.514252 2.208935 +26.303738 22.500000 2.657999 +24.660194 29.511168 1.340793 +25.465425 22.500000 1.769599 +23.531500 29.507671 0.665791 +24.481964 22.500000 1.038144 +22.303431 29.503923 0.215352 +23.389105 22.500000 0.490420 +21.000000 29.500000 0.000000 +22.993927 -30.000000 0.000000 +22.894051 -27.602978 0.000000 +29.897579 -27.541889 7.000000 +30.000000 -30.000000 7.000000 +29.781078 -27.553005 5.726259 +29.883036 -30.000000 5.726259 +29.406607 -27.564375 4.423337 +29.508091 -30.000000 4.423337 +28.756950 -27.575317 3.169532 +28.857979 -30.000000 3.169532 +28.332296 -27.580393 2.587913 +28.433113 -30.000000 2.587913 +27.847347 -27.585085 2.050252 +27.947969 -30.000000 2.050252 +27.309397 -27.589315 1.565528 +27.409842 -30.000000 1.565528 +26.727427 -27.593019 1.141031 +26.827719 -30.000000 1.141031 +25.472771 -27.598688 0.491482 +25.572824 -30.000000 0.491482 +24.168854 -27.601957 0.116862 +24.268772 -30.000000 0.116862 +27.790804 21.892946 7.809367 +27.819649 22.328426 7.000000 +29.883036 -30.000000 8.273742 +30.000000 -30.000000 7.000000 +29.897579 -27.541889 7.000000 +29.823814 -27.533070 8.010587 +29.508091 -30.000000 9.576663 +21.789448 29.503788 13.883138 +20.514759 29.500000 14.000000 +22.993927 -30.000000 14.000000 +23.093340 29.507662 13.508518 +24.268772 -30.000000 13.883138 +24.348078 29.511391 12.858969 +25.572824 -30.000000 13.508518 +24.930128 29.513121 12.434472 +26.827719 -30.000000 12.858969 +25.468189 29.514719 11.949747 +27.409842 -30.000000 12.434472 +25.953274 29.516159 11.412086 +27.947969 -30.000000 11.949747 +26.378086 29.517422 10.830468 +28.433113 -30.000000 11.412086 +27.028118 29.519354 9.576663 +28.857979 -30.000000 10.830468 +29.604803 -27.524435 9.000000 +27.403017 29.520468 8.273742 +27.645451 19.500000 9.000000 +27.648254 20.413347 8.857586 +27.713736 21.234396 8.447829 +27.519966 29.520815 7.000000 +-24.598152 -29.500000 2.963150 +-23.790028 -29.500000 2.730795 +25.375814 -29.500000 10.633973 +24.598152 -29.500000 11.036850 +26.070036 -29.500000 10.070037 +26.633972 -29.500000 9.375813 +23.790028 -29.500000 11.269205 +27.036850 -29.500000 8.598152 +27.269205 -29.500000 7.790027 +27.341688 -29.500000 7.000000 +27.269205 -29.500000 6.209973 +27.036850 -29.500000 5.401848 +26.633972 -29.500000 4.624186 +26.070036 -29.500000 3.929963 +25.375814 -29.500000 3.366027 +24.598152 -29.500000 2.963150 +23.790028 -29.500000 2.730795 +23.000000 -29.500000 2.658312 +-23.000000 -29.500000 2.658312 +23.000000 -29.500000 11.341687 +-23.000000 -29.500000 11.341687 +-23.790028 -29.500000 11.269205 +-24.598152 -29.500000 11.036850 +-25.375814 -29.500000 10.633973 +-26.070036 -29.500000 10.070037 +-26.633972 -29.500000 9.375813 +-27.036850 -29.500000 8.598152 +-27.269205 -29.500000 7.790027 +-27.341688 -29.500000 7.000000 +-27.269205 -29.500000 6.209973 +-27.036850 -29.500000 5.401848 +-26.633972 -29.500000 4.624186 +-26.070036 -29.500000 3.929963 +-25.375814 -29.500000 3.366027 +-23.000000 -29.500000 11.341687 +23.000000 -29.500000 11.341687 +23.000000 -30.000000 13.000000 +-23.000000 -30.000000 13.000000 +23.000000 -29.833256 12.715904 +-23.000000 -29.833256 12.715904 +23.000000 -29.627718 12.207713 +23.000000 -29.518085 11.670606 +-23.000000 -29.627718 12.207713 +-23.000000 -29.518085 11.670606 +-23.790028 -29.500000 11.269205 +-23.000000 -29.500000 11.341687 +-24.598152 -29.500000 11.036850 +-23.000000 -29.833256 12.715904 +-23.000000 -30.000000 13.000000 +-25.375814 -29.500000 10.633973 +-26.070036 -29.500000 10.070037 +-26.633972 -29.500000 9.375813 +-27.036850 -29.500000 8.598152 +-27.269205 -29.500000 7.790027 +-27.341688 -29.500000 7.000000 +-27.269205 -29.500000 6.209973 +-27.036850 -29.500000 5.401848 +-26.633972 -29.500000 4.624186 +-26.070036 -29.500000 3.929963 +-25.375814 -29.500000 3.366027 +-24.598152 -29.500000 2.963150 +-23.790028 -29.500000 2.730795 +-23.000000 -29.500000 2.658312 +-23.000000 -29.518085 2.329394 +-23.000000 -29.627718 1.792287 +-23.000000 -29.833256 1.284096 +-23.000000 -30.000000 1.000000 +-24.091778 -30.000000 1.100168 +-25.208569 -30.000000 1.421270 +-26.283258 -30.000000 1.978027 +-27.242641 -30.000000 2.757359 +-28.021973 -30.000000 3.716742 +-28.578730 -30.000000 4.791432 +-28.899832 -30.000000 5.908222 +-29.000000 -30.000000 7.000000 +-28.899832 -30.000000 8.091779 +-28.578730 -30.000000 9.208569 +-28.021973 -30.000000 10.283258 +-27.242641 -30.000000 11.242640 +-26.283258 -30.000000 12.021973 +-25.208569 -30.000000 12.578730 +-24.091778 -30.000000 12.899832 +-23.000000 -29.627718 12.207713 +-23.000000 -29.518085 11.670606 +-23.849878 -29.518085 11.592632 +-24.719225 -29.518085 11.342675 +-25.555801 -29.518085 10.909276 +-26.302618 -29.518085 10.302617 +-26.909277 -29.518085 9.555801 +-27.342674 -29.518085 8.719225 +-27.592632 -29.518085 7.849878 +-27.670607 -29.518085 7.000000 +-27.592632 -29.518085 6.150122 +-27.342674 -29.518085 5.280775 +-26.909277 -29.518085 4.444199 +-26.302618 -29.518085 3.697383 +-25.555801 -29.518085 3.090724 +-24.719225 -29.518085 2.657325 +-23.849878 -29.518085 2.407368 +-23.947611 -29.627718 1.879228 +-24.040083 -29.833256 1.379521 +-25.103994 -29.833256 1.685419 +-26.127798 -29.833256 2.215814 +-27.041754 -29.833256 2.958246 +-27.784185 -29.833256 3.872201 +-28.314581 -29.833256 4.896006 +-28.620480 -29.833256 5.959917 +-28.715904 -29.833256 7.000000 +-28.620480 -29.833256 8.040083 +-28.314581 -29.833256 9.103994 +-27.784185 -29.833256 10.127798 +-27.041754 -29.833256 11.041755 +-26.127798 -29.833256 11.784186 +-25.103994 -29.833256 12.314581 +-24.040083 -29.833256 12.620480 +-23.947611 -29.627718 12.120772 +-24.916931 -29.627718 2.157929 +-25.849710 -29.627718 2.641168 +-26.682409 -29.627718 3.317591 +-27.358833 -29.627718 4.150289 +-27.842072 -29.627718 5.083068 +-28.120771 -29.627718 6.052389 +-28.207712 -29.627718 7.000000 +-28.120771 -29.627718 7.947611 +-27.842072 -29.627718 8.916931 +-27.358833 -29.627718 9.849711 +-26.682409 -29.627718 10.682409 +-25.849710 -29.627718 11.358832 +-24.916931 -29.627718 11.842071 +24.091778 -30.000000 1.100168 +23.000000 -30.000000 1.000000 +23.000000 -29.833256 1.284096 +23.000000 -29.627718 1.792287 +23.000000 -29.518085 2.329394 +23.000000 -29.518085 11.670606 +23.000000 -29.500000 11.341687 +23.000000 -29.500000 2.658312 +23.790028 -29.500000 2.730795 +24.598152 -29.500000 2.963150 +25.375814 -29.500000 3.366027 +26.070036 -29.500000 3.929963 +26.633972 -29.500000 4.624186 +27.036850 -29.500000 5.401848 +27.269205 -29.500000 6.209973 +27.341688 -29.500000 7.000000 +27.269205 -29.500000 7.790027 +27.036850 -29.500000 8.598152 +26.633972 -29.500000 9.375813 +26.070036 -29.500000 10.070037 +25.375814 -29.500000 10.633973 +24.598152 -29.500000 11.036850 +23.790028 -29.500000 11.269205 +23.000000 -29.627718 12.207713 +23.000000 -29.833256 12.715904 +23.000000 -30.000000 13.000000 +24.091778 -30.000000 12.899832 +25.208569 -30.000000 12.578730 +26.283258 -30.000000 12.021973 +27.242641 -30.000000 11.242640 +28.021973 -30.000000 10.283258 +28.578730 -30.000000 9.208569 +28.899832 -30.000000 8.091779 +29.000000 -30.000000 7.000000 +28.899832 -30.000000 5.908222 +28.578730 -30.000000 4.791432 +28.021973 -30.000000 3.716742 +27.242641 -30.000000 2.757359 +26.283258 -30.000000 1.978027 +25.208569 -30.000000 1.421270 +24.040083 -29.833256 1.379521 +23.947611 -29.627718 1.879228 +23.849878 -29.518085 2.407368 +24.719225 -29.518085 2.657325 +25.555801 -29.518085 3.090724 +26.302618 -29.518085 3.697383 +26.909277 -29.518085 4.444199 +27.342674 -29.518085 5.280775 +27.592632 -29.518085 6.150122 +27.670607 -29.518085 7.000000 +27.592632 -29.518085 7.849878 +27.342674 -29.518085 8.719225 +26.909277 -29.518085 9.555801 +26.302618 -29.518085 10.302617 +25.555801 -29.518085 10.909276 +24.719225 -29.518085 11.342675 +23.849878 -29.518085 11.592632 +23.947611 -29.627718 12.120772 +24.040083 -29.833256 12.620480 +25.103994 -29.833256 12.314581 +26.127798 -29.833256 11.784186 +27.041754 -29.833256 11.041755 +27.784185 -29.833256 10.127798 +28.314581 -29.833256 9.103994 +28.620480 -29.833256 8.040083 +28.715904 -29.833256 7.000000 +28.620480 -29.833256 5.959917 +28.314581 -29.833256 4.896006 +27.784185 -29.833256 3.872201 +27.041754 -29.833256 2.958246 +26.127798 -29.833256 2.215814 +25.103994 -29.833256 1.685419 +24.916931 -29.627718 11.842071 +25.849710 -29.627718 11.358832 +26.682409 -29.627718 10.682409 +27.358833 -29.627718 9.849711 +27.842072 -29.627718 8.916931 +28.120771 -29.627718 7.947611 +28.207712 -29.627718 7.000000 +28.120771 -29.627718 6.052389 +27.842072 -29.627718 5.083068 +27.358833 -29.627718 4.150289 +26.682409 -29.627718 3.317591 +25.849710 -29.627718 2.641168 +24.916931 -29.627718 2.157929 +23.000000 -29.833256 1.284096 +-23.000000 -29.833256 1.284096 +-23.000000 -30.000000 1.000000 +23.000000 -30.000000 1.000000 +23.000000 -29.518085 2.329394 +23.000000 -29.500000 2.658312 +-23.000000 -29.500000 2.658312 +-23.000000 -29.518085 2.329394 +23.000000 -29.627718 1.792287 +-23.000000 -29.627718 1.792287 +-13.000000 -15.000000 14.000000 +-19.500000 -15.000000 14.000000 +-19.495367 -22.964602 14.530973 +-19.500000 -23.000000 14.000000 +-13.000000 -23.000000 14.000000 +-19.490227 -22.840000 15.120000 +-13.000000 -22.933222 14.727852 +-19.484703 -22.595505 15.752809 +-13.000000 -22.719152 15.472379 +-19.479055 -22.200001 16.400000 +-13.000000 -22.347982 16.188839 +-19.473700 -21.630136 17.013699 +-13.000000 -21.828426 16.828426 +-19.469200 -20.882353 17.529411 +-13.000000 -21.188839 17.347982 +-19.467464 -20.449057 17.728302 +-13.000000 -20.472380 17.719152 +-19.466167 -19.984615 17.876923 +-19.465364 -19.498055 17.968872 +-13.000000 -19.727852 17.933222 +-19.465092 -19.000000 18.000000 +-13.000000 -19.000000 18.000000 +-19.465364 -18.501945 17.968872 +-19.466167 -18.015385 17.876923 +-13.000000 -18.272148 17.933222 +-19.467464 -17.550943 17.728302 +-19.469200 -17.117647 17.529411 +-13.000000 -17.527620 17.719152 +-19.473700 -16.369864 17.013699 +-13.000000 -16.811161 17.347982 +-19.479055 -15.800000 16.400000 +-13.000000 -16.171574 16.828426 +-19.484703 -15.404494 15.752809 +-13.000000 -15.652018 16.188839 +-19.490227 -15.160000 15.120000 +-13.000000 -15.280847 15.472379 +-19.495367 -15.035398 14.530973 +-13.000000 -15.066778 14.727852 +-19.479055 -15.800000 16.400000 +-19.484703 -15.404494 15.752809 +-19.490227 -15.160000 15.120000 +-19.500000 -15.000000 14.000000 +-19.500000 -23.000000 14.000000 +-19.490227 -22.840000 15.120000 +-19.484703 -22.595505 15.752809 +-19.479055 -22.200001 16.400000 +-19.473700 -21.630136 17.013699 +-19.469200 -20.882353 17.529411 +-19.466167 -19.984615 17.876923 +-19.465092 -19.000000 18.000000 +-19.466167 -18.015385 17.876923 +-19.469200 -17.117647 17.529411 +-19.473700 -16.369864 17.013699 +-13.000000 -17.000000 14.500000 +-18.000000 -17.000000 14.500000 +-18.000000 -17.785847 12.910713 +-18.000000 -18.062500 12.733338 +-13.000000 -18.062500 12.733338 +-13.000000 -17.785847 12.910713 +-18.000000 -17.502262 13.174563 +-18.000000 -17.286087 13.469224 +-13.000000 -17.502262 13.174563 +-13.000000 -17.286087 13.469224 +-18.000000 -17.127136 13.798301 +-18.000000 -17.027000 14.172479 +-13.000000 -17.127136 13.798301 +-13.000000 -17.027000 14.172479 +-18.000000 -20.859577 15.236190 +-18.000000 -20.966610 14.863926 +-18.000000 -19.299999 11.673341 +-18.000000 -19.299999 10.800000 +-18.000000 -18.700001 10.800000 +-18.000000 -18.700001 11.673341 +-18.000000 -19.342102 11.988417 +-18.000000 -18.657898 11.988417 +-18.000000 -19.471651 12.291807 +-18.000000 -18.528349 12.291807 +-18.000000 -19.678919 12.548456 +-18.000000 -18.321081 12.548456 +-18.000000 -19.937500 12.733338 +-18.000000 -18.062500 12.733338 +-18.000000 -17.631533 13.041474 +-18.000000 -17.286087 13.469224 +-18.000000 -17.070169 13.974874 +-18.000000 -20.368467 13.041474 +-18.000000 -20.713913 13.469224 +-18.000000 -20.929831 13.974874 +-18.000000 -21.000000 14.500000 +-18.000000 -17.000000 14.500000 +-18.000000 -17.033390 14.863926 +-18.000000 -17.140423 15.236190 +-18.000000 -17.326010 15.594419 +-18.000000 -17.585787 15.914213 +-18.000000 -17.905581 16.173990 +-18.000000 -18.263811 16.359577 +-18.000000 -18.636074 16.466610 +-18.000000 -19.000000 16.500000 +-18.000000 -19.363926 16.466610 +-18.000000 -19.736189 16.359577 +-18.000000 -20.094419 16.173990 +-18.000000 -20.414213 15.914213 +-18.000000 -20.673990 15.594419 +-24.500000 25.468109 1.547189 +-21.000000 25.868818 1.500243 +-21.000000 25.900000 1.500000 +-24.500000 25.900000 1.500000 +-21.000000 25.468109 1.547189 +-24.500000 25.868818 1.500243 +-24.500000 24.577124 5.000000 +-21.000000 24.577124 5.000000 +-24.500000 24.553898 4.979192 +-24.500000 24.284420 4.678939 +-21.000000 24.553898 4.979192 +-21.000000 24.284420 4.678939 +-24.500000 24.077124 4.322875 +-24.500000 23.947189 3.931890 +-21.000000 24.077124 4.322875 +-21.000000 23.947189 3.931890 +-24.500000 23.900244 3.531183 +-24.500000 23.931736 3.145120 +-21.000000 23.900244 3.531183 +-21.000000 23.931736 3.145120 +-24.500000 24.029171 2.792893 +-21.000000 24.029171 2.792893 +-24.500000 24.189072 2.464276 +-24.500000 24.420807 2.153898 +-21.000000 24.189072 2.464276 +-21.000000 24.420807 2.153898 +-24.500000 24.721060 1.884419 +-24.500000 25.077124 1.677124 +-21.000000 24.721060 1.884419 +-21.000000 25.077124 1.677124 +-21.000000 24.577124 5.000000 +-24.500000 24.577124 5.000000 +-24.500000 27.222876 5.000000 +-21.000000 27.222876 5.000000 +-24.500000 27.484079 2.279061 +-24.500000 27.770828 2.792893 +-24.500000 27.602140 4.550103 +-24.500000 27.222876 5.000000 +-24.500000 24.577124 5.000000 +-24.500000 24.197859 4.550103 +-24.500000 23.958927 3.981906 +-24.500000 23.904366 3.367935 +-24.500000 27.841074 3.981906 +-24.500000 27.895636 3.367935 +-24.500000 24.029171 2.792893 +-24.500000 24.315920 2.279061 +-24.500000 24.762945 1.854671 +-24.500000 25.317972 1.586562 +-24.500000 25.900000 1.500000 +-24.500000 26.482027 1.586562 +-24.500000 27.037054 1.854671 +-25.500000 20.718750 10.331819 +-21.087042 20.718750 10.331819 +-21.000000 23.719357 7.564300 +-21.000000 23.937059 6.750000 +-25.500000 23.937059 6.750000 +-25.500000 23.719357 7.564300 +-21.000000 23.338686 8.348295 +-25.500000 23.338686 8.348295 +-21.000000 22.847269 9.007623 +-21.000000 22.500000 9.354102 +-21.021364 22.500000 9.354102 +-25.500000 22.847298 9.007590 +-21.035215 22.100834 9.672282 +-25.500000 22.244146 9.566464 +-21.050983 21.665281 9.944814 +-21.068377 21.201502 10.165920 +-25.500000 21.505199 10.028544 +-21.000000 22.709627 10.800000 +-21.079567 20.799999 10.800000 +-25.500000 20.799999 10.800000 +-25.500000 27.700001 10.800000 +-21.000000 27.700001 10.800000 +-25.500000 28.000000 6.800000 +-21.000000 28.000000 6.800000 +-21.000000 28.000000 10.500000 +-25.500000 28.000000 10.500000 +-21.000000 24.232864 6.500000 +-21.000000 27.700001 6.500000 +-25.500000 27.700001 6.500000 +-25.500000 24.232864 6.500000 +-25.500000 27.810429 10.778936 +-25.500000 27.754589 10.794991 +-25.500000 20.541794 10.652741 +-25.500000 20.506123 10.560303 +-25.500000 20.532627 10.484550 +-25.500000 20.572298 10.695325 +-25.500000 20.580383 10.416232 +-25.500000 20.610384 10.732477 +-25.500000 20.645096 10.363692 +-25.500000 20.654432 10.762317 +-25.500000 20.702278 10.783638 +-25.500000 20.799999 10.800000 +-25.500000 27.700001 10.800000 +-25.500000 20.718750 10.331819 +-25.500000 21.855141 9.834490 +-25.500000 22.847298 9.007590 +-25.500000 23.563713 7.932933 +-25.500000 23.937059 6.750000 +-25.500000 23.970625 6.654294 +-25.500000 24.000851 6.609817 +-25.500000 24.039215 6.570871 +-25.500000 24.084009 6.539534 +-25.500000 24.132902 6.517144 +-25.500000 24.232864 6.500000 +-25.500000 27.700001 6.500000 +-25.500000 27.754589 6.505008 +-25.500000 27.810429 6.521063 +-25.500000 27.864162 6.548902 +-25.500000 27.912132 6.587868 +-25.500000 27.951099 6.635837 +-25.500000 27.978937 6.689571 +-25.500000 27.994991 6.745411 +-25.500000 28.000000 6.800000 +-25.500000 28.000000 10.500000 +-25.500000 27.994991 10.554589 +-25.500000 27.978937 10.610429 +-25.500000 27.951099 10.664163 +-25.500000 27.912132 10.712132 +-25.500000 27.864162 10.751099 +19.465364 -19.498055 17.968872 +19.495367 -15.035398 14.530973 +19.500000 -15.000000 14.000000 +13.000000 -15.000000 14.000000 +19.490227 -15.160000 15.120000 +13.000000 -15.066778 14.727852 +19.484703 -15.404494 15.752809 +13.000000 -15.280847 15.472379 +19.479055 -15.800000 16.400000 +13.000000 -15.652018 16.188839 +19.473700 -16.369864 17.013699 +13.000000 -16.171574 16.828426 +19.469200 -17.117647 17.529411 +13.000000 -16.811161 17.347982 +19.467464 -17.550943 17.728302 +13.000000 -17.527620 17.719152 +19.466167 -18.015385 17.876923 +19.465364 -18.501945 17.968872 +13.000000 -18.272148 17.933222 +19.465092 -19.000000 18.000000 +13.000000 -23.000000 14.000000 +19.500000 -23.000000 14.000000 +13.000000 -22.933222 14.727852 +19.495367 -22.964602 14.530973 +13.000000 -22.719152 15.472379 +19.490227 -22.840000 15.120000 +13.000000 -22.347982 16.188839 +19.484703 -22.595505 15.752809 +13.000000 -21.828426 16.828426 +19.479055 -22.200001 16.400000 +13.000000 -21.188839 17.347982 +19.473700 -21.630136 17.013699 +13.000000 -20.472380 17.719152 +19.469200 -20.882353 17.529411 +13.000000 -19.727852 17.933222 +19.467464 -20.449057 17.728302 +19.466167 -19.984615 17.876923 +13.000000 -19.000000 18.000000 +19.479055 -22.200001 16.400000 +19.484703 -22.595505 15.752809 +19.490227 -22.840000 15.120000 +19.500000 -23.000000 14.000000 +19.500000 -15.000000 14.000000 +19.490227 -15.160000 15.120000 +19.484703 -15.404494 15.752809 +19.479055 -15.800000 16.400000 +19.473700 -16.369864 17.013699 +19.469200 -17.117647 17.529411 +19.466167 -18.015385 17.876923 +19.465092 -19.000000 18.000000 +19.466167 -19.984615 17.876923 +19.469200 -20.882353 17.529411 +19.473700 -21.630136 17.013699 +13.000000 -20.973000 14.172479 +13.000000 -21.000000 14.500000 +18.000000 -20.214153 12.910713 +18.000000 -19.937500 12.733338 +13.000000 -19.937500 12.733338 +13.000000 -20.214153 12.910713 +18.000000 -20.497738 13.174563 +18.000000 -20.713913 13.469224 +13.000000 -20.497738 13.174563 +13.000000 -20.713913 13.469224 +18.000000 -20.872864 13.798301 +18.000000 -20.973000 14.172479 +13.000000 -20.872864 13.798301 +18.000000 -21.000000 14.500000 +18.000000 -17.140423 15.236190 +18.000000 -17.033390 14.863926 +18.000000 -18.700001 10.800000 +18.000000 -19.299999 10.800000 +18.000000 -18.700001 11.673341 +18.000000 -19.299999 11.673341 +18.000000 -18.657898 11.988417 +18.000000 -19.342102 11.988417 +18.000000 -18.528349 12.291807 +18.000000 -19.471651 12.291807 +18.000000 -18.321081 12.548456 +18.000000 -19.678919 12.548456 +18.000000 -18.062500 12.733338 +18.000000 -19.937500 12.733338 +18.000000 -20.368467 13.041474 +18.000000 -20.713913 13.469224 +18.000000 -20.929831 13.974874 +18.000000 -17.631533 13.041474 +18.000000 -17.286087 13.469224 +18.000000 -17.070169 13.974874 +18.000000 -17.000000 14.500000 +18.000000 -21.000000 14.500000 +18.000000 -20.966610 14.863926 +18.000000 -20.859577 15.236190 +18.000000 -20.673990 15.594419 +18.000000 -20.414213 15.914213 +18.000000 -20.094419 16.173990 +18.000000 -19.736189 16.359577 +18.000000 -19.363926 16.466610 +18.000000 -19.000000 16.500000 +18.000000 -18.636074 16.466610 +18.000000 -18.263811 16.359577 +18.000000 -17.905581 16.173990 +18.000000 -17.585787 15.914213 +18.000000 -17.326010 15.594419 +21.000000 24.485786 2.085786 +21.000000 24.577124 5.000000 +24.500000 24.577124 5.000000 +21.000000 24.485786 4.914214 +24.500000 24.485786 4.914214 +21.000000 24.226009 4.594419 +21.000000 24.040422 4.236189 +24.500000 24.226009 4.594419 +24.500000 24.040422 4.236189 +21.000000 23.933390 3.863926 +21.000000 23.900000 3.500151 +24.500000 23.933390 3.863926 +24.500000 23.900000 3.500151 +21.000000 23.933390 3.136075 +21.000000 24.040424 2.763811 +24.500000 23.933390 3.136075 +24.500000 24.040424 2.763811 +21.000000 24.226009 2.405581 +24.500000 27.222876 5.000000 +21.000000 27.222876 5.000000 +24.500000 27.314213 4.914214 +24.500000 27.573992 4.594419 +21.000000 27.314213 4.914214 +24.500000 27.759577 4.236189 +21.000000 27.573992 4.594419 +21.000000 27.759577 4.236189 +24.500000 27.866611 3.863926 +21.000000 27.866611 3.863926 +24.500000 27.900000 3.500151 +24.500000 27.866611 3.136075 +21.000000 27.900000 3.500151 +21.000000 27.866611 3.136075 +24.500000 27.759577 2.763811 +21.000000 27.759577 2.763811 +24.500000 27.573992 2.405581 +24.500000 27.314213 2.085786 +21.000000 27.573992 2.405581 +24.500000 26.994419 1.826009 +21.000000 27.314213 2.085786 +21.000000 26.994419 1.826009 +24.500000 26.636189 1.640423 +24.500000 26.263926 1.533389 +21.000000 26.636189 1.640423 +24.500000 25.900000 1.500000 +21.000000 26.263926 1.533389 +24.500000 25.536074 1.533389 +21.000000 25.900000 1.500000 +21.000000 25.536074 1.533389 +24.500000 25.163811 1.640423 +21.000000 25.163811 1.640423 +24.500000 24.805580 1.826009 +21.000000 24.805580 1.826009 +24.500000 24.485786 2.085786 +24.500000 24.226009 2.405581 +24.500000 27.222876 5.000000 +24.500000 24.577124 5.000000 +21.000000 24.577124 5.000000 +21.000000 27.222876 5.000000 +24.500000 24.315920 2.279061 +24.500000 24.029171 2.792893 +24.500000 24.197859 4.550103 +24.500000 24.577124 5.000000 +24.500000 27.222876 5.000000 +24.500000 27.602140 4.550103 +24.500000 27.841074 3.981906 +24.500000 27.895636 3.367935 +24.500000 23.958927 3.981906 +24.500000 23.904366 3.367935 +24.500000 27.770828 2.792893 +24.500000 27.484079 2.279061 +24.500000 27.037054 1.854671 +24.500000 26.482027 1.586562 +24.500000 25.900000 1.500000 +24.500000 25.317972 1.586562 +24.500000 24.762945 1.854671 +21.000000 22.856220 8.997629 +21.000000 22.500000 9.354102 +25.500000 23.949472 6.672450 +25.500000 23.972136 6.500000 +21.000000 23.972136 6.500000 +25.500000 23.723986 7.551758 +21.000000 23.949472 6.672450 +21.095671 20.500000 10.387483 +25.500000 20.500000 10.387483 +21.074446 21.043018 10.227185 +25.500000 20.668806 10.345560 +21.054670 21.565664 9.997878 +25.500000 21.517159 10.022570 +21.036844 22.055082 9.704262 +21.021364 22.500000 9.354102 +25.500000 22.254728 9.558296 +21.000000 23.723986 7.551758 +25.500000 23.345646 8.336881 +25.500000 22.856218 8.997633 +21.000000 23.345646 8.336881 +25.500000 20.500000 10.800000 +21.092068 20.500000 10.800000 +21.000000 22.709627 10.800000 +21.000000 28.000000 10.800000 +25.500000 28.000000 10.800000 +25.500000 20.500000 10.800000 +25.500000 20.500000 10.387483 +21.095671 20.500000 10.387483 +21.092068 20.500000 10.800000 +25.500000 28.000000 6.500000 +21.000000 28.000000 6.500000 +21.000000 23.972136 6.500000 +25.500000 23.972136 6.500000 +25.500000 28.000000 6.500000 +25.500000 28.000000 10.800000 +21.000000 28.000000 10.800000 +21.000000 28.000000 6.500000 +25.500000 23.622297 7.804625 +25.500000 20.500000 10.800000 +25.500000 28.000000 10.800000 +25.500000 28.000000 6.500000 +25.500000 23.972136 6.500000 +25.500000 21.756979 9.893077 +25.500000 20.500000 10.387483 +25.500000 22.856218 8.997633 +18.982546 -24.732565 9.800000 +18.982546 -13.267435 9.800000 +19.000000 -13.249981 11.800000 +19.000000 -24.750019 11.800000 +18.482565 -25.232546 9.800000 +18.500019 -25.250000 11.800000 +-18.500019 -25.250000 11.800000 +-18.482565 -25.232546 9.800000 +-18.982546 -24.732565 9.800000 +-19.000000 -24.750019 11.800000 +-19.000000 -13.249981 11.800000 +-18.982546 -13.267435 9.800000 +18.500019 -12.750000 11.800000 +18.482565 -12.767454 9.800000 +-18.482565 -12.767454 9.800000 +-18.500019 -12.750000 11.800000 +18.000000 -19.299999 11.673341 +18.000000 -19.299999 10.800000 +13.014835 -19.299999 10.800000 +13.007215 -19.299999 11.673341 +18.000000 -18.700001 11.673341 +13.007215 -18.700001 11.673341 +13.014835 -18.700001 10.800000 +18.000000 -18.700001 10.800000 +13.014835 -19.299999 10.800000 +18.000000 -19.299999 10.800000 +18.000000 -18.700001 10.800000 +13.014835 -18.700001 10.800000 +-18.000000 -18.700001 10.800000 +-18.000000 -19.299999 10.800000 +-13.014835 -19.299999 10.800000 +-13.014835 -18.700001 10.800000 +-18.000000 -18.700001 11.673341 +-18.000000 -18.700001 10.800000 +-13.014835 -18.700001 10.800000 +-13.007215 -18.700001 11.673341 +-18.000000 -19.299999 11.673341 +-13.007215 -19.299999 11.673341 +-13.014835 -19.299999 10.800000 +-18.000000 -19.299999 10.800000 +22.578543 -27.602978 0.000000 +22.578543 -28.000000 0.000000 +22.508650 -28.000000 8.008726 +22.508650 -27.533087 8.008726 +-21.508688 -27.524435 9.000000 +21.508688 -27.524435 9.000000 +21.508688 -28.000000 9.000000 +-21.508688 -28.000000 9.000000 +-22.508650 -28.000000 8.008726 +-22.578543 -28.000000 0.000000 +-22.578543 -27.602978 0.000000 +-22.508650 -27.533087 8.008726 +22.435947 -28.000000 8.374420 +22.490534 -28.000000 8.189685 +22.508650 -28.000000 8.008726 +22.578543 -28.000000 0.000000 +-22.578543 -28.000000 0.000000 +-22.508650 -28.000000 8.008726 +-22.490534 -28.000000 8.189685 +-22.435947 -28.000000 8.374420 +-22.342592 -28.000000 8.551910 +-22.212704 -28.000000 8.710185 +-22.053301 -28.000000 8.838688 +-21.875004 -28.000000 8.930491 +-21.689798 -28.000000 8.983463 +-21.508688 -28.000000 9.000000 +21.508688 -28.000000 9.000000 +21.689798 -28.000000 8.983463 +21.875004 -28.000000 8.930491 +22.053301 -28.000000 8.838688 +22.212704 -28.000000 8.710185 +22.342592 -28.000000 8.551910 +-0.750000 -13.750000 12.500000 +0.750000 -13.750000 12.500000 +0.750000 -14.625000 12.500000 +-0.750000 -14.625000 12.500000 +9.250000 -13.750000 12.500000 +10.750000 -13.750000 12.500000 +10.750000 -14.625000 12.500000 +9.250000 -14.625000 12.500000 +-3.250000 -14.625000 12.500000 +-3.250000 -13.750000 12.500000 +-1.750000 -13.750000 12.500000 +-1.750000 -14.625000 12.500000 +6.750000 -14.625000 12.500000 +6.750000 -13.750000 12.500000 +8.250000 -13.750000 12.500000 +8.250000 -14.625000 12.500000 +-5.750000 -13.750000 12.500000 +-4.250000 -13.750000 12.500000 +-4.250000 -14.625000 12.500000 +-5.750000 -14.625000 12.500000 +4.250000 -14.625000 12.500000 +4.250000 -13.750000 12.500000 +5.750000 -13.750000 12.500000 +5.750000 -14.625000 12.500000 +-8.250000 -14.625000 12.500000 +-8.250000 -13.750000 12.500000 +-6.750000 -13.750000 12.500000 +-6.750000 -14.625000 12.500000 +1.750000 -13.750000 12.500000 +3.250000 -13.750000 12.500000 +3.250000 -14.625000 12.500000 +1.750000 -14.625000 12.500000 +-10.750000 -13.750000 12.500000 +-9.250000 -13.750000 12.500000 +-9.250000 -14.625000 12.500000 +-10.750000 -14.625000 12.500000 +11.750000 -13.750000 12.500000 +13.000000 -13.750000 12.500000 +13.000000 -14.625000 12.500000 +11.750000 -14.625000 12.500000 +-13.000000 -13.750000 12.500000 +-11.750000 -13.750000 12.500000 +-11.750000 -14.625000 12.500000 +-13.000000 -14.625000 12.500000 +0.750000 -23.375000 12.500000 +0.750000 -24.250000 12.500000 +-0.750000 -24.250000 12.500000 +-0.750000 -23.375000 12.500000 +10.750000 -24.250000 12.500000 +9.250000 -24.250000 12.500000 +9.250000 -23.375000 12.500000 +10.750000 -23.375000 12.500000 +-1.750000 -23.375000 12.500000 +-1.750000 -24.250000 12.500000 +-3.250000 -24.250000 12.500000 +-3.250000 -23.375000 12.500000 +8.250000 -24.250000 12.500000 +6.750000 -24.250000 12.500000 +6.750000 -23.375000 12.500000 +8.250000 -23.375000 12.500000 +-4.250000 -24.250000 12.500000 +-5.750000 -24.250000 12.500000 +-5.750000 -23.375000 12.500000 +-4.250000 -23.375000 12.500000 +5.750000 -23.375000 12.500000 +5.750000 -24.250000 12.500000 +4.250000 -24.250000 12.500000 +4.250000 -23.375000 12.500000 +-6.750000 -24.250000 12.500000 +-8.250000 -24.250000 12.500000 +-8.250000 -23.375000 12.500000 +-6.750000 -23.375000 12.500000 +3.250000 -23.375000 12.500000 +3.250000 -24.250000 12.500000 +1.750000 -24.250000 12.500000 +1.750000 -23.375000 12.500000 +-9.250000 -24.250000 12.500000 +-10.750000 -24.250000 12.500000 +-10.750000 -23.375000 12.500000 +-9.250000 -23.375000 12.500000 +13.000000 -24.250000 12.500000 +11.750000 -24.250000 12.500000 +11.750000 -23.375000 12.500000 +13.000000 -23.375000 12.500000 +-11.750000 -23.375000 12.500000 +-11.750000 -24.250000 12.500000 +-13.000000 -24.250000 12.500000 +-13.000000 -23.375000 12.500000 +-18.218498 -13.676395 10.300000 +-18.153553 -24.403553 10.300000 +-18.073605 -24.468498 10.300000 +18.153553 -24.403553 10.300000 +18.218498 -24.323605 10.300000 +18.153553 -13.596447 10.300000 +18.073605 -13.531502 10.300000 +-18.153553 -13.596447 10.300000 +-3.269199 -13.730801 10.300000 +-3.269199 -14.750000 10.300000 +-4.230801 -14.750000 10.300000 +0.769199 -23.250000 10.300000 +1.730801 -23.250000 10.300000 +0.769199 -24.269199 10.300000 +-4.230801 -23.250000 10.300000 +-3.269199 -23.250000 10.300000 +-4.230801 -24.269199 10.300000 +-11.730801 -24.269199 10.300000 +-11.730801 -23.250000 10.300000 +-10.769199 -23.250000 10.300000 +-13.019199 -13.730801 10.300000 +-13.980801 -17.219198 10.300000 +15.519199 -17.219198 10.300000 +16.480801 -13.730801 10.300000 +-15.519199 -13.730801 10.300000 +-16.480801 -17.219198 10.300000 +-10.769199 -14.750000 10.300000 +-11.730801 -14.750000 10.300000 +-10.769199 -13.730801 10.300000 +-8.269199 -14.750000 10.300000 +-9.230801 -14.750000 10.300000 +-8.269199 -13.730801 10.300000 +-5.769199 -14.750000 10.300000 +-6.730801 -14.750000 10.300000 +-5.769199 -13.730801 10.300000 +-0.769199 -14.750000 10.300000 +-1.730801 -14.750000 10.300000 +-0.769199 -13.730801 10.300000 +1.730801 -14.750000 10.300000 +0.769199 -14.750000 10.300000 +1.730801 -13.730801 10.300000 +4.230801 -14.750000 10.300000 +3.269199 -14.750000 10.300000 +4.230801 -13.730801 10.300000 +6.730801 -14.750000 10.300000 +5.769199 -14.750000 10.300000 +6.730801 -13.730801 10.300000 +9.230801 -14.750000 10.300000 +8.269199 -14.750000 10.300000 +9.230801 -13.730801 10.300000 +11.730801 -14.750000 10.300000 +10.769199 -14.750000 10.300000 +11.730801 -13.730801 10.300000 +10.769199 -23.250000 10.300000 +11.730801 -23.250000 10.300000 +10.769199 -24.269199 10.300000 +8.269199 -23.250000 10.300000 +9.230801 -23.250000 10.300000 +8.269199 -24.269199 10.300000 +5.769199 -23.250000 10.300000 +6.730801 -23.250000 10.300000 +5.769199 -24.269199 10.300000 +3.269199 -23.250000 10.300000 +4.230801 -23.250000 10.300000 +3.269199 -24.269199 10.300000 +-1.730801 -23.250000 10.300000 +-0.769199 -23.250000 10.300000 +-1.730801 -24.269199 10.300000 +-6.730801 -23.250000 10.300000 +-5.769199 -23.250000 10.300000 +-6.730801 -24.269199 10.300000 +-9.230801 -23.250000 10.300000 +-8.269199 -23.250000 10.300000 +-9.230801 -24.269199 10.300000 +-16.480801 -24.269199 10.300000 +-15.519199 -20.780802 10.300000 +15.519199 -24.269199 10.300000 +16.480801 -20.780802 10.300000 +-18.264894 -13.765953 10.300000 +-18.019199 -13.730801 10.300000 +-18.291653 -13.859018 10.300000 +-18.299999 -13.950000 10.300000 +-18.299999 -24.049999 10.300000 +-18.218498 -24.323605 10.300000 +-18.019199 -20.780802 10.300000 +-18.264894 -24.234047 10.300000 +-18.291653 -24.140982 10.300000 +-16.480801 -20.780802 10.300000 +-18.019199 -17.219198 10.300000 +-15.519199 -17.219198 10.300000 +-13.980801 -20.780802 10.300000 +-13.980801 -24.269199 10.300000 +-17.984047 -24.514894 10.300000 +-18.019199 -24.269199 10.300000 +-17.890982 -24.541653 10.300000 +-17.799999 -24.549999 10.300000 +17.799999 -24.549999 10.300000 +-15.519199 -24.269199 10.300000 +-13.019199 -24.269199 10.300000 +-10.769199 -24.269199 10.300000 +-8.269199 -24.269199 10.300000 +-5.769199 -24.269199 10.300000 +-3.269199 -24.269199 10.300000 +-0.769199 -24.269199 10.300000 +1.730801 -24.269199 10.300000 +4.230801 -24.269199 10.300000 +6.730801 -24.269199 10.300000 +9.230801 -24.269199 10.300000 +11.730801 -24.269199 10.300000 +18.073605 -24.468498 10.300000 +16.480801 -24.269199 10.300000 +17.984047 -24.514894 10.300000 +17.890982 -24.541653 10.300000 +18.264894 -24.234047 10.300000 +18.019199 -24.269199 10.300000 +18.291653 -24.140982 10.300000 +18.299999 -24.049999 10.300000 +18.299999 -13.950000 10.300000 +18.218498 -13.676395 10.300000 +18.019199 -17.219198 10.300000 +18.264894 -13.765953 10.300000 +18.291653 -13.859018 10.300000 +18.019199 -20.780802 10.300000 +16.480801 -17.219198 10.300000 +15.519199 -20.780802 10.300000 +13.980801 -17.219198 10.300000 +17.984047 -13.485106 10.300000 +18.019199 -13.730801 10.300000 +17.890982 -13.458347 10.300000 +17.799999 -13.450000 10.300000 +-17.799999 -13.450000 10.300000 +15.519199 -13.730801 10.300000 +-18.073605 -13.531502 10.300000 +-16.480801 -13.730801 10.300000 +-17.984047 -13.485106 10.300000 +-17.890982 -13.458347 10.300000 +-13.980801 -13.730801 10.300000 +13.980801 -24.269199 10.300000 +13.019199 -24.269199 10.300000 +13.980801 -20.780802 10.300000 +13.980801 -13.730801 10.300000 +13.019199 -13.730801 10.300000 +10.769199 -13.730801 10.300000 +8.269199 -13.730801 10.300000 +5.769199 -13.730801 10.300000 +3.269199 -13.730801 10.300000 +0.769199 -13.730801 10.300000 +-1.730801 -13.730801 10.300000 +-4.230801 -13.730801 10.300000 +-6.730801 -13.730801 10.300000 +-9.230801 -13.730801 10.300000 +-11.730801 -13.730801 10.300000 +18.299999 -13.950000 9.800000 +18.299999 -24.049999 9.800000 +18.299999 -24.049999 10.300000 +18.299999 -13.950000 10.300000 +-17.799999 -13.450000 9.800000 +17.799999 -13.450000 9.800000 +17.799999 -13.450000 10.300000 +-17.799999 -13.450000 10.300000 +-18.299999 -13.950000 10.300000 +-18.299999 -24.049999 10.300000 +-18.299999 -24.049999 9.800000 +-18.299999 -13.950000 9.800000 +-17.799999 -24.549999 10.300000 +17.799999 -24.549999 10.300000 +17.799999 -24.549999 9.800000 +-17.799999 -24.549999 9.800000 +-16.500000 -20.799999 12.500000 +-16.500000 -24.250000 12.500000 +-18.000000 -24.250000 12.500000 +-18.000000 -20.799999 12.500000 +-18.000000 -20.799999 12.500000 +-18.019199 -20.780802 10.300000 +-16.480801 -20.780802 10.300000 +-16.500000 -20.799999 12.500000 +-16.500000 -20.799999 12.500000 +-16.480801 -20.780802 10.300000 +-16.480801 -24.269199 10.300000 +-16.500000 -24.250000 12.500000 +-18.000000 -24.250000 12.500000 +-16.500000 -24.250000 12.500000 +-16.480801 -24.269199 10.300000 +-18.019199 -24.269199 10.300000 +-18.000000 -20.799999 12.500000 +-18.000000 -24.250000 12.500000 +-18.019199 -24.269199 10.300000 +-18.019199 -20.780802 10.300000 +14.000000 -24.250000 12.500000 +14.000000 -20.799999 12.500000 +15.500000 -20.799999 12.500000 +15.500000 -24.250000 12.500000 +15.519199 -24.269199 10.300000 +15.500000 -24.250000 12.500000 +15.500000 -20.799999 12.500000 +15.519199 -20.780802 10.300000 +15.519199 -20.780802 10.300000 +15.500000 -20.799999 12.500000 +14.000000 -20.799999 12.500000 +13.980801 -20.780802 10.300000 +14.000000 -20.799999 12.500000 +14.000000 -24.250000 12.500000 +13.980801 -24.269199 10.300000 +13.980801 -20.780802 10.300000 +14.000000 -24.250000 12.500000 +15.500000 -24.250000 12.500000 +15.519199 -24.269199 10.300000 +13.980801 -24.269199 10.300000 +16.500000 -24.250000 12.500000 +16.500000 -20.799999 12.500000 +18.000000 -20.799999 12.500000 +18.000000 -24.250000 12.500000 +18.019199 -24.269199 10.300000 +18.000000 -24.250000 12.500000 +18.000000 -20.799999 12.500000 +18.019199 -20.780802 10.300000 +18.019199 -20.780802 10.300000 +18.000000 -20.799999 12.500000 +16.500000 -20.799999 12.500000 +16.480801 -20.780802 10.300000 +16.480801 -20.780802 10.300000 +16.500000 -20.799999 12.500000 +16.500000 -24.250000 12.500000 +16.480801 -24.269199 10.300000 +16.500000 -24.250000 12.500000 +18.000000 -24.250000 12.500000 +18.019199 -24.269199 10.300000 +16.480801 -24.269199 10.300000 +-14.000000 -13.750000 12.500000 +-14.000000 -17.200001 12.500000 +-15.500000 -17.200001 12.500000 +-15.500000 -13.750000 12.500000 +-15.500000 -13.750000 12.500000 +-15.500000 -17.200001 12.500000 +-15.519199 -17.219198 10.300000 +-15.519199 -13.730801 10.300000 +-15.500000 -17.200001 12.500000 +-14.000000 -17.200001 12.500000 +-13.980801 -17.219198 10.300000 +-15.519199 -17.219198 10.300000 +-14.000000 -17.200001 12.500000 +-14.000000 -13.750000 12.500000 +-13.980801 -13.730801 10.300000 +-13.980801 -17.219198 10.300000 +-14.000000 -13.750000 12.500000 +-15.500000 -13.750000 12.500000 +-15.519199 -13.730801 10.300000 +-13.980801 -13.730801 10.300000 +-18.000000 -13.750000 12.500000 +-16.500000 -13.750000 12.500000 +-16.500000 -17.200001 12.500000 +-18.000000 -17.200001 12.500000 +-18.000000 -13.750000 12.500000 +-18.000000 -17.200001 12.500000 +-18.019199 -17.219198 10.300000 +-18.019199 -13.730801 10.300000 +-18.019199 -17.219198 10.300000 +-18.000000 -17.200001 12.500000 +-16.500000 -17.200001 12.500000 +-16.480801 -17.219198 10.300000 +-16.480801 -17.219198 10.300000 +-16.500000 -17.200001 12.500000 +-16.500000 -13.750000 12.500000 +-16.480801 -13.730801 10.300000 +-16.500000 -13.750000 12.500000 +-18.000000 -13.750000 12.500000 +-18.019199 -13.730801 10.300000 +-16.480801 -13.730801 10.300000 +14.000000 -13.750000 12.500000 +15.500000 -13.750000 12.500000 +15.500000 -17.200001 12.500000 +14.000000 -17.200001 12.500000 +14.000000 -17.200001 12.500000 +15.500000 -17.200001 12.500000 +15.519199 -17.219198 10.300000 +13.980801 -17.219198 10.300000 +14.000000 -13.750000 12.500000 +14.000000 -17.200001 12.500000 +13.980801 -17.219198 10.300000 +13.980801 -13.730801 10.300000 +14.000000 -13.750000 12.500000 +13.980801 -13.730801 10.300000 +15.519199 -13.730801 10.300000 +15.500000 -13.750000 12.500000 +15.500000 -17.200001 12.500000 +15.500000 -13.750000 12.500000 +15.519199 -13.730801 10.300000 +15.519199 -17.219198 10.300000 +16.500000 -17.200001 12.500000 +16.500000 -13.750000 12.500000 +18.000000 -13.750000 12.500000 +18.000000 -17.200001 12.500000 +16.500000 -17.200001 12.500000 +18.000000 -17.200001 12.500000 +18.019199 -17.219198 10.300000 +16.480801 -17.219198 10.300000 +16.500000 -13.750000 12.500000 +16.500000 -17.200001 12.500000 +16.480801 -17.219198 10.300000 +16.480801 -13.730801 10.300000 +18.000000 -13.750000 12.500000 +16.500000 -13.750000 12.500000 +16.480801 -13.730801 10.300000 +18.019199 -13.730801 10.300000 +18.000000 -17.200001 12.500000 +18.000000 -13.750000 12.500000 +18.019199 -13.730801 10.300000 +18.019199 -17.219198 10.300000 +-14.000000 -24.250000 12.500000 +-15.500000 -24.250000 12.500000 +-15.500000 -20.799999 12.500000 +-14.000000 -20.799999 12.500000 +-14.000000 -20.799999 12.500000 +-15.500000 -20.799999 12.500000 +-15.519199 -20.780802 10.300000 +-13.980801 -20.780802 10.300000 +-14.000000 -20.799999 12.500000 +-13.980801 -20.780802 10.300000 +-13.980801 -24.269199 10.300000 +-14.000000 -24.250000 12.500000 +-15.500000 -24.250000 12.500000 +-14.000000 -24.250000 12.500000 +-13.980801 -24.269199 10.300000 +-15.519199 -24.269199 10.300000 +-15.500000 -20.799999 12.500000 +-15.500000 -24.250000 12.500000 +-15.519199 -24.269199 10.300000 +-15.519199 -20.780802 10.300000 +-18.000000 -18.683800 11.869854 +-18.000000 -18.700001 11.673341 +-13.000000 -18.062500 12.733338 +-18.000000 -18.062500 12.733338 +-13.000000 -18.228493 12.626913 +-13.000000 -18.369848 12.500000 +-18.000000 -18.228493 12.626913 +-13.001548 -18.509186 12.322605 +-18.000000 -18.398642 12.468603 +-13.003330 -18.614410 12.118416 +-18.000000 -18.528349 12.291807 +-13.005255 -18.678799 11.897917 +-18.000000 -18.623718 12.094360 +-13.007215 -18.700001 11.673341 +-13.007215 -19.299999 11.673341 +-18.000000 -19.299999 11.673341 +-18.000000 -19.771507 12.626913 +-18.000000 -19.937500 12.733338 +-13.000000 -19.937500 12.733338 +-13.000000 -19.771507 12.626913 +-18.000000 -19.601358 12.468603 +-13.000000 -19.630152 12.500000 +-18.000000 -19.471651 12.291807 +-13.001548 -19.490814 12.322605 +-18.000000 -19.376282 12.094360 +-13.003330 -19.385590 12.118416 +-18.000000 -19.316200 11.869854 +-13.005255 -19.321201 11.897917 +18.000000 -19.316200 11.869854 +18.000000 -19.299999 11.673341 +13.000000 -19.937500 12.733338 +18.000000 -19.937500 12.733338 +13.000000 -19.771507 12.626913 +18.000000 -19.771507 12.626913 +13.000000 -19.630152 12.500000 +13.001548 -19.490814 12.322605 +18.000000 -19.601358 12.468603 +13.003330 -19.385590 12.118416 +18.000000 -19.471651 12.291807 +13.005255 -19.321201 11.897917 +18.000000 -19.376282 12.094360 +13.007215 -19.299999 11.673341 +13.007215 -18.700001 11.673341 +18.000000 -18.700001 11.673341 +18.000000 -18.062500 12.733338 +13.000000 -18.062500 12.733338 +18.000000 -18.228493 12.626913 +18.000000 -18.398642 12.468603 +13.000000 -18.228493 12.626913 +13.000000 -18.369848 12.500000 +18.000000 -18.528349 12.291807 +13.001548 -18.509186 12.322605 +18.000000 -18.623718 12.094360 +13.003330 -18.614410 12.118416 +18.000000 -18.683800 11.869854 +13.005255 -18.678799 11.897917 +11.750000 -14.625000 12.500000 +13.000000 -14.625000 12.500000 +-13.000000 -14.250000 14.000000 +-13.000000 -14.625000 12.500000 +13.000000 -14.250000 14.000000 +10.754363 -14.750000 12.000000 +11.745637 -14.750000 12.000000 +10.750000 -14.625000 12.500000 +8.254363 -14.750000 12.000000 +9.245637 -14.750000 12.000000 +8.250000 -14.625000 12.500000 +5.754364 -14.750000 12.000000 +6.745636 -14.750000 12.000000 +5.750000 -14.625000 12.500000 +3.254364 -14.750000 12.000000 +4.245636 -14.750000 12.000000 +3.250000 -14.625000 12.500000 +0.754363 -14.750000 12.000000 +1.745637 -14.750000 12.000000 +0.750000 -14.625000 12.500000 +-1.745637 -14.750000 12.000000 +-0.754363 -14.750000 12.000000 +-1.750000 -14.625000 12.500000 +-4.245636 -14.750000 12.000000 +-3.254364 -14.750000 12.000000 +-4.250000 -14.625000 12.500000 +-6.745636 -14.750000 12.000000 +-5.754364 -14.750000 12.000000 +-6.750000 -14.625000 12.500000 +-9.245637 -14.750000 12.000000 +-8.254363 -14.750000 12.000000 +-9.250000 -14.625000 12.500000 +-11.745637 -14.750000 12.000000 +-10.754363 -14.750000 12.000000 +-11.750000 -14.625000 12.500000 +-10.750000 -14.625000 12.500000 +-8.250000 -14.625000 12.500000 +-5.750000 -14.625000 12.500000 +-3.250000 -14.625000 12.500000 +-0.750000 -14.625000 12.500000 +1.750000 -14.625000 12.500000 +4.250000 -14.625000 12.500000 +6.750000 -14.625000 12.500000 +9.250000 -14.625000 12.500000 +13.000000 -23.750000 14.000000 +13.000000 -23.375000 12.500000 +-13.000000 -23.750000 14.000000 +-11.750000 -23.375000 12.500000 +-13.000000 -23.375000 12.500000 +-10.754363 -23.250000 12.000000 +-11.745637 -23.250000 12.000000 +-10.750000 -23.375000 12.500000 +-8.254363 -23.250000 12.000000 +-9.245637 -23.250000 12.000000 +-8.250000 -23.375000 12.500000 +-5.754364 -23.250000 12.000000 +-6.745636 -23.250000 12.000000 +-5.750000 -23.375000 12.500000 +-3.254364 -23.250000 12.000000 +-4.245636 -23.250000 12.000000 +-3.250000 -23.375000 12.500000 +-0.754363 -23.250000 12.000000 +-1.745637 -23.250000 12.000000 +-0.750000 -23.375000 12.500000 +1.745637 -23.250000 12.000000 +0.754363 -23.250000 12.000000 +1.750000 -23.375000 12.500000 +4.245636 -23.250000 12.000000 +3.254364 -23.250000 12.000000 +4.250000 -23.375000 12.500000 +6.745636 -23.250000 12.000000 +5.754364 -23.250000 12.000000 +6.750000 -23.375000 12.500000 +9.245637 -23.250000 12.000000 +8.254363 -23.250000 12.000000 +9.250000 -23.375000 12.500000 +11.745637 -23.250000 12.000000 +10.754363 -23.250000 12.000000 +11.750000 -23.375000 12.500000 +10.750000 -23.375000 12.500000 +8.250000 -23.375000 12.500000 +5.750000 -23.375000 12.500000 +3.250000 -23.375000 12.500000 +0.750000 -23.375000 12.500000 +-1.750000 -23.375000 12.500000 +-4.250000 -23.375000 12.500000 +-6.750000 -23.375000 12.500000 +-9.250000 -23.375000 12.500000 +-22.508650 -28.000000 8.008726 +-22.508650 -27.533087 8.008726 +-21.689798 -27.524580 8.983463 +-21.508688 -27.524435 9.000000 +-21.508688 -28.000000 9.000000 +-21.875004 -27.525042 8.930491 +-21.709326 -28.000000 8.979666 +-22.053301 -27.525843 8.838688 +-21.901857 -28.000000 8.919466 +-22.212704 -27.526964 8.710185 +-22.071722 -28.000000 8.826434 +-22.342592 -27.528345 8.551910 +-22.212704 -28.000000 8.710185 +-22.330177 -28.000000 8.570225 +-22.435947 -27.529894 8.374420 +-22.424688 -28.000000 8.401178 +-22.490534 -27.531507 8.189685 +-22.486567 -28.000000 8.209178 +22.490534 -27.531507 8.189685 +22.508650 -27.533087 8.008726 +21.508688 -28.000000 9.000000 +21.508688 -27.524435 9.000000 +21.709326 -28.000000 8.979666 +21.689798 -27.524580 8.983463 +21.901857 -28.000000 8.919466 +21.875004 -27.525042 8.930491 +22.071722 -28.000000 8.826434 +22.053301 -27.525843 8.838688 +22.212704 -28.000000 8.710185 +22.212704 -27.526964 8.710185 +22.330177 -28.000000 8.570225 +22.424688 -28.000000 8.401178 +22.342592 -27.528345 8.551910 +22.486567 -28.000000 8.209178 +22.435947 -27.529894 8.374420 +22.508650 -28.000000 8.008726 +-22.145428 19.072468 9.000000 +-22.140581 18.979185 9.000000 +-22.554150 19.491276 9.800000 +-22.647154 19.500000 9.800000 +-22.640167 19.500000 9.000000 +-22.458881 19.463202 9.800000 +-22.547163 19.491276 9.000000 +-22.367390 19.414413 9.800000 +-22.451895 19.463202 9.000000 +-22.325146 19.382517 9.800000 +-22.360403 19.414413 9.000000 +-22.286303 19.346117 9.800000 +-22.318159 19.382517 9.000000 +-22.251549 19.305792 9.800000 +-22.279316 19.346117 9.000000 +-22.221437 19.262259 9.800000 +-22.244562 19.305792 9.000000 +-22.176498 19.168819 9.800000 +-22.214451 19.262259 9.000000 +-22.152414 19.072468 9.800000 +-22.169510 19.168819 9.000000 +-22.147568 18.979185 9.800000 +-26.464001 19.500000 9.000000 +-26.457012 19.500000 9.800000 +-26.956598 19.020815 9.800000 +-26.963587 19.020815 9.000000 +-26.944929 19.109339 9.800000 +-26.951918 19.109339 9.000000 +-26.915703 19.199047 9.800000 +-26.922689 19.199047 9.000000 +-26.868036 19.284733 9.800000 +-26.875023 19.284733 9.000000 +-26.803143 19.360838 9.800000 +-26.810129 19.360838 9.000000 +-26.724400 19.422504 9.800000 +-26.731388 19.422504 9.000000 +-26.636801 19.466560 9.800000 +-26.643787 19.466560 9.000000 +-26.545950 19.492027 9.800000 +-26.552937 19.492027 9.000000 +22.147135 19.000000 9.800000 +22.147568 18.979185 9.800000 +22.140581 18.979185 9.000000 +22.140148 19.000000 9.000000 +26.951918 19.109339 9.000000 +26.963587 19.020815 9.000000 +26.545950 19.492027 9.800000 +26.457012 19.500000 9.800000 +26.464001 19.500000 9.000000 +26.636801 19.466560 9.800000 +26.552937 19.492027 9.000000 +26.724400 19.422504 9.800000 +26.643787 19.466560 9.000000 +26.803143 19.360838 9.800000 +26.731388 19.422504 9.000000 +26.868036 19.284733 9.800000 +26.810129 19.360838 9.000000 +26.915703 19.199047 9.800000 +26.875023 19.284733 9.000000 +26.944929 19.109339 9.800000 +26.922689 19.199047 9.000000 +26.956598 19.020815 9.800000 +-24.557814 -27.524435 9.000000 +-24.564510 -27.517454 9.800000 +-24.076632 -27.126810 9.800000 +-24.064962 -27.038288 9.800000 +-24.058266 -27.045269 9.000000 +-24.105856 -27.216516 9.800000 +-24.069935 -27.133791 9.000000 +-24.153519 -27.302198 9.800000 +-24.099159 -27.223497 9.000000 +-24.218407 -27.378298 9.800000 +-24.146822 -27.309179 9.000000 +-24.211710 -27.385281 9.000000 +-24.297142 -27.439962 9.800000 +-24.290445 -27.446943 9.000000 +-24.384733 -27.484016 9.800000 +-24.378036 -27.490997 9.000000 +-24.475578 -27.509481 9.800000 +-24.468882 -27.516462 9.000000 +-28.881271 -27.003639 9.000000 +-28.873993 -26.996658 9.800000 +-28.467445 -27.508728 9.800000 +-28.374445 -27.517454 9.800000 +-28.381723 -27.524435 9.000000 +-28.562708 -27.480658 9.800000 +-28.474724 -27.515711 9.000000 +-28.654192 -27.431871 9.800000 +-28.569986 -27.487638 9.000000 +-28.696432 -27.399977 9.800000 +-28.661470 -27.438852 9.000000 +-28.735271 -27.363579 9.800000 +-28.703711 -27.406958 9.000000 +-28.742550 -27.370560 9.000000 +-28.770021 -27.323257 9.800000 +-28.777300 -27.330238 9.000000 +-28.800131 -27.279724 9.800000 +-28.807409 -27.286707 9.000000 +-28.845066 -27.186289 9.800000 +-28.852345 -27.193270 9.000000 +-28.869148 -27.089941 9.800000 +-28.876427 -27.096922 9.000000 +24.058266 -27.045269 9.000000 +24.064962 -27.038288 9.800000 +24.475578 -27.509481 9.800000 +24.564510 -27.517454 9.800000 +24.557814 -27.524435 9.000000 +24.384733 -27.484016 9.800000 +24.468882 -27.516462 9.000000 +24.297142 -27.439962 9.800000 +24.378036 -27.490997 9.000000 +24.218407 -27.378298 9.800000 +24.290445 -27.446943 9.000000 +24.211710 -27.385281 9.000000 +24.153519 -27.302198 9.800000 +24.146822 -27.309179 9.000000 +24.105856 -27.216516 9.800000 +24.099159 -27.223497 9.000000 +24.076632 -27.126810 9.800000 +24.069935 -27.133791 9.000000 +28.381723 -27.524435 9.000000 +28.374445 -27.517454 9.800000 +28.866079 -27.108456 9.800000 +28.874426 -27.017475 9.800000 +28.881704 -27.024456 9.000000 +28.839323 -27.201517 9.800000 +28.873358 -27.115437 9.000000 +28.792929 -27.291071 9.800000 +28.846601 -27.208500 9.000000 +28.762609 -27.332613 9.800000 +28.800207 -27.298054 9.000000 +28.727987 -27.371016 9.800000 +28.769888 -27.339596 9.000000 +28.735266 -27.377996 9.000000 +28.689585 -27.405636 9.800000 +28.696863 -27.412619 9.000000 +28.648043 -27.435957 9.800000 +28.655321 -27.442938 9.000000 +28.558489 -27.482349 9.800000 +28.565767 -27.489332 9.000000 +28.465425 -27.509108 9.800000 +28.472704 -27.516088 9.000000 +-18.500019 -12.750000 11.800000 +-18.482565 -12.767454 9.800000 +-18.974199 -13.176454 9.800000 +-18.982546 -13.267435 9.800000 +-19.000000 -13.249981 11.800000 +-18.947443 -13.083391 9.800000 +-18.991653 -13.159000 11.800000 +-18.901049 -12.993837 9.800000 +-18.964895 -13.065937 11.800000 +-18.870729 -12.952294 9.800000 +-18.918503 -12.976383 11.800000 +-18.836107 -12.913893 9.800000 +-18.888182 -12.934841 11.800000 +-18.853561 -12.896439 11.800000 +-18.797705 -12.879272 9.800000 +-18.815159 -12.861817 11.800000 +-18.756163 -12.848951 9.800000 +-18.773617 -12.831498 11.800000 +-18.666609 -12.802558 9.800000 +-18.684063 -12.785104 11.800000 +-18.573545 -12.775801 9.800000 +-18.591000 -12.758347 11.800000 +-19.000000 -24.750019 11.800000 +-18.982546 -24.732565 9.800000 +-18.573545 -25.224199 9.800000 +-18.482565 -25.232546 9.800000 +-18.500019 -25.250000 11.800000 +-18.666609 -25.197443 9.800000 +-18.591000 -25.241653 11.800000 +-18.756163 -25.151049 9.800000 +-18.684063 -25.214895 11.800000 +-18.797705 -25.120729 9.800000 +-18.773617 -25.168503 11.800000 +-18.836107 -25.086107 9.800000 +-18.815159 -25.138182 11.800000 +-18.853561 -25.103561 11.800000 +-18.870729 -25.047705 9.800000 +-18.888182 -25.065159 11.800000 +-18.901049 -25.006163 9.800000 +-18.918503 -25.023617 11.800000 +-18.947443 -24.916609 9.800000 +-18.964895 -24.934063 11.800000 +-18.974199 -24.823545 9.800000 +-18.991653 -24.841000 11.800000 +18.500019 -25.250000 11.800000 +18.482565 -25.232546 9.800000 +18.974199 -24.823545 9.800000 +18.982546 -24.732565 9.800000 +19.000000 -24.750019 11.800000 +18.947443 -24.916609 9.800000 +18.991653 -24.841000 11.800000 +18.901049 -25.006163 9.800000 +18.964895 -24.934063 11.800000 +18.870729 -25.047705 9.800000 +18.918503 -25.023617 11.800000 +18.836107 -25.086107 9.800000 +18.888182 -25.065159 11.800000 +18.853561 -25.103561 11.800000 +18.797705 -25.120729 9.800000 +18.815159 -25.138182 11.800000 +18.756163 -25.151049 9.800000 +18.773617 -25.168503 11.800000 +18.666609 -25.197443 9.800000 +18.684063 -25.214895 11.800000 +18.573545 -25.224199 9.800000 +18.591000 -25.241653 11.800000 +19.000000 -13.249981 11.800000 +18.982546 -13.267435 9.800000 +18.573545 -12.775801 9.800000 +18.482565 -12.767454 9.800000 +18.500019 -12.750000 11.800000 +18.666609 -12.802558 9.800000 +18.591000 -12.758347 11.800000 +18.756163 -12.848951 9.800000 +18.684063 -12.785104 11.800000 +18.797705 -12.879272 9.800000 +18.773617 -12.831498 11.800000 +18.836107 -12.913893 9.800000 +18.815159 -12.861817 11.800000 +18.853561 -12.896439 11.800000 +18.870729 -12.952294 9.800000 +18.888182 -12.934841 11.800000 +18.901049 -12.993837 9.800000 +18.918503 -12.976383 11.800000 +18.947443 -13.083391 9.800000 +18.964895 -13.065937 11.800000 +18.974199 -13.176454 9.800000 +18.991653 -13.159000 11.800000 +-18.299999 -13.950000 10.300000 +-18.299999 -13.950000 9.800000 +-17.902454 -13.460609 9.800000 +-17.799999 -13.450000 9.800000 +-17.799999 -13.450000 10.300000 +-17.902454 -13.460609 10.300000 +-17.998589 -13.491129 9.800000 +-17.998589 -13.491129 10.300000 +-18.083317 -13.538015 9.800000 +-18.153553 -13.596447 9.800000 +-18.083317 -13.538015 10.300000 +-18.153553 -13.596447 10.300000 +-18.211985 -13.666682 9.800000 +-18.211985 -13.666682 10.300000 +-18.258871 -13.751411 9.800000 +-18.258871 -13.751411 10.300000 +-18.289391 -13.847546 9.800000 +-18.289391 -13.847546 10.300000 +-17.799999 -24.549999 10.300000 +-17.799999 -24.549999 9.800000 +-18.289391 -24.152454 9.800000 +-18.299999 -24.049999 9.800000 +-18.299999 -24.049999 10.300000 +-18.289391 -24.152454 10.300000 +-18.258871 -24.248589 9.800000 +-18.258871 -24.248589 10.300000 +-18.211985 -24.333317 9.800000 +-18.153553 -24.403553 9.800000 +-18.211985 -24.333317 10.300000 +-18.153553 -24.403553 10.300000 +-18.083317 -24.461985 9.800000 +-18.083317 -24.461985 10.300000 +-17.998589 -24.508871 9.800000 +-17.998589 -24.508871 10.300000 +-17.902454 -24.539391 9.800000 +-17.902454 -24.539391 10.300000 +17.998589 -13.491129 9.800000 +17.799999 -13.450000 10.300000 +17.799999 -13.450000 9.800000 +17.902454 -13.460609 10.300000 +17.998589 -13.491129 10.300000 +17.902454 -13.460609 9.800000 +18.299999 -13.950000 9.800000 +18.299999 -13.950000 10.300000 +18.289391 -13.847546 9.800000 +18.258871 -13.751411 9.800000 +18.289391 -13.847546 10.300000 +18.211985 -13.666682 9.800000 +18.258871 -13.751411 10.300000 +18.211985 -13.666682 10.300000 +18.153553 -13.596447 9.800000 +18.083317 -13.538015 9.800000 +18.153553 -13.596447 10.300000 +18.083317 -13.538015 10.300000 +17.799999 -24.549999 9.800000 +17.799999 -24.549999 10.300000 +18.299999 -24.049999 10.300000 +18.299999 -24.049999 9.800000 +18.289391 -24.152454 10.300000 +18.289391 -24.152454 9.800000 +18.258871 -24.248589 10.300000 +18.211985 -24.333317 10.300000 +18.258871 -24.248589 9.800000 +18.211985 -24.333317 9.800000 +18.153553 -24.403553 10.300000 +18.083317 -24.461985 10.300000 +18.153553 -24.403553 9.800000 +17.998589 -24.508871 10.300000 +18.083317 -24.461985 9.800000 +17.998589 -24.508871 9.800000 +17.902454 -24.539391 10.300000 +17.902454 -24.539391 9.800000 +21.000000 27.897177 11.717742 +21.000000 27.500000 11.800000 +-21.000000 27.500000 11.800000 +21.000000 27.704910 11.778781 +-21.000000 28.500000 10.800000 +21.000000 28.500000 10.800000 +-21.000000 28.478781 11.004910 +-21.000000 28.417742 11.197177 +21.000000 28.478781 11.004910 +21.000000 28.417742 11.197177 +-21.000000 28.323969 11.366634 +-21.000000 28.207108 11.507107 +21.000000 28.323969 11.366634 +21.000000 28.207108 11.507107 +-21.000000 28.066635 11.623969 +-21.000000 27.897177 11.717742 +21.000000 28.066635 11.623969 +-21.000000 27.704910 11.778781 +-21.000000 29.500000 9.500000 +21.000000 29.500000 9.500000 +21.000000 28.500000 10.500000 +-21.000000 28.500000 10.500000 +21.000000 28.521219 10.295091 +21.000000 28.582258 10.102822 +-21.000000 28.521219 10.295091 +-21.000000 28.582258 10.102822 +21.000000 28.676031 9.933366 +21.000000 28.792892 9.792893 +-21.000000 28.676031 9.933366 +-21.000000 28.792892 9.792893 +21.000000 28.933365 9.676031 +-21.000000 28.933365 9.676031 +21.000000 29.102823 9.582258 +21.000000 29.295090 9.521219 +-21.000000 29.102823 9.582258 +-21.000000 29.295090 9.521219 +-22.205130 30.000000 0.706587 +-21.000000 29.915417 0.222708 +-21.000000 29.961399 0.309202 +-21.000000 29.990097 0.403150 +-21.000000 30.000000 0.501299 +-21.000000 29.853666 0.146921 +-21.000000 29.778114 0.084956 +-21.000000 29.691854 0.038786 +-21.000000 29.598083 0.009953 +-21.000000 29.500000 0.000000 +-22.303431 29.503923 0.215352 +-23.531500 29.507671 0.665791 +-24.660194 29.511168 1.340793 +-25.637346 29.514252 2.208935 +-26.440493 29.516851 3.250411 +-27.032007 29.518847 4.416991 +-27.397171 29.520187 5.678949 +-27.519966 29.520815 6.983936 +-27.508299 29.609339 6.983936 +-27.479071 29.699047 6.983936 +-27.431406 29.784735 6.983936 +-27.366516 29.860838 6.983936 +-27.287777 29.922504 6.983936 +-27.200180 29.966560 6.983936 +-27.109333 29.992027 6.983936 +-27.020399 30.000000 6.983936 +-26.907141 30.000000 5.776322 +-26.570353 30.000000 4.608300 +-26.024683 30.000000 3.527889 +-25.283665 30.000000 2.562519 +-24.381807 30.000000 1.756571 +-23.339539 30.000000 1.128183 +-22.142269 29.991720 0.596470 +-22.187128 29.919224 0.420213 +-22.206795 29.854874 0.342940 +-22.165125 29.965195 0.506664 +-22.222813 29.775621 0.280001 +-22.234316 29.686760 0.234804 +-22.241028 29.594292 0.208427 +-23.479576 29.597635 0.651851 +-24.618420 29.600750 1.322886 +-25.605328 29.603498 2.190339 +-26.416943 29.605814 3.233872 +-27.014874 29.607590 4.404571 +-27.384148 29.608782 5.672410 +-27.355513 29.698593 5.677886 +-27.308731 29.784397 5.686831 +-27.244991 29.860619 5.699020 +-27.167616 29.922382 5.713816 +-27.081520 29.966511 5.730280 +-26.992222 29.992016 5.747355 +-26.643938 29.991991 4.551992 +-26.080025 29.991955 3.448261 +-25.314623 29.991909 2.464484 +-24.383961 29.991852 1.646778 +-23.310085 29.991789 1.014310 +-26.728559 29.966402 4.518361 +-26.810139 29.922125 4.485939 +-26.883421 29.860147 4.456814 +-26.943735 29.783678 4.432844 +-26.987925 29.697622 4.415281 +-26.157032 29.966242 3.399259 +-25.381233 29.966032 2.401668 +-26.231256 29.921738 3.352029 +-25.445419 29.921234 2.341138 +-26.297888 29.859446 3.309629 +-25.502991 29.858530 2.286846 +-26.352652 29.782606 3.274781 +-25.550224 29.781206 2.242304 +-26.392672 29.696175 3.249316 +-25.584621 29.694286 2.209866 +-24.437841 29.965782 1.572343 +-23.349169 29.965500 0.930730 +-24.489748 29.920635 1.500639 +-23.386805 29.919954 0.850243 +-24.536257 29.857441 1.436390 +-23.420488 29.856203 0.778210 +-24.574331 29.779541 1.383792 +-23.447996 29.777653 0.719383 +-24.601946 29.692041 1.345644 +-23.467854 29.689495 0.676920 +-27.366516 29.860838 6.983936 +-27.112642 29.991417 7.000000 +-27.020399 30.000000 7.000000 +-27.020399 30.000000 6.983936 +-27.209391 29.962906 7.000000 +-27.112642 29.991417 6.983936 +-27.209391 29.962906 6.983936 +-27.295078 29.917793 7.000000 +-27.366516 29.860838 7.000000 +-27.295078 29.917793 6.983936 +-27.519966 29.520815 6.983936 +-27.519966 29.520815 7.000000 +-27.507551 29.612621 6.983936 +-27.475037 29.708099 6.983936 +-27.507551 29.612621 7.000000 +-27.426395 29.791834 6.983936 +-27.475037 29.708099 7.000000 +-27.426395 29.791834 7.000000 +-21.789448 29.503788 13.883138 +-20.514759 29.500000 14.000000 +-25.114943 30.000000 11.596194 +-25.959951 30.000000 10.556864 +-26.563627 30.000000 9.392615 +-24.074709 30.000000 12.440471 +-22.909451 30.000000 13.043624 +-21.698545 30.000000 13.391485 +-20.514759 29.991653 13.590981 +-20.514759 30.000000 13.500000 +-20.514759 29.964893 13.684048 +-26.911791 30.000000 8.182760 +-27.020399 30.000000 7.000000 +-27.109333 29.992027 7.000000 +-27.200180 29.966560 7.000000 +-27.287777 29.922504 7.000000 +-27.366516 29.860838 7.000000 +-27.431406 29.784735 7.000000 +-27.479071 29.699047 7.000000 +-27.508299 29.609339 7.000000 +-27.519966 29.520815 7.000000 +-27.403017 29.520468 8.273742 +-27.028118 29.519354 9.576663 +-26.378086 29.517422 10.830468 +-25.468189 29.514719 11.949747 +-24.348078 29.511391 12.858969 +-23.093340 29.507662 13.508518 +-20.514759 29.918497 13.773605 +-20.514759 29.853554 13.853554 +-20.514759 29.773605 13.918498 +-20.514759 29.684048 13.964894 +-20.514759 29.590982 13.991652 +-25.997875 29.991964 10.660604 +-25.178226 29.991919 11.659534 +-26.607485 29.991999 9.521561 +-26.982250 29.992020 8.285435 +-24.178764 29.991861 12.478931 +-23.038853 29.991796 13.088563 +-21.801594 29.991726 13.463549 +-21.819658 29.965221 13.554398 +-27.071379 29.966530 8.303178 +-27.157318 29.922428 8.320286 +-27.234560 29.860699 8.335664 +-27.298201 29.784521 8.348335 +-27.344927 29.698761 8.357639 +-27.373550 29.608988 8.363340 +-26.976175 29.607946 9.674410 +-26.329771 29.606255 10.882562 +-25.460615 29.603979 11.942168 +-24.400736 29.601198 12.811425 +-23.191851 29.598024 13.458250 +-21.879639 29.594576 13.856234 +-21.837046 29.919285 13.641857 +-21.852587 29.854986 13.720041 +-21.865246 29.775793 13.783736 +-21.874334 29.686991 13.829499 +-23.074118 29.965534 13.173773 +-23.108080 29.920040 13.255834 +-23.138477 29.856359 13.329287 +-23.163311 29.777889 13.389291 +-23.181248 29.689814 13.432630 +-24.229755 29.965822 12.555300 +-24.278877 29.920732 12.628872 +-24.322899 29.857618 12.694808 +-25.242897 29.966076 11.724261 +-25.305220 29.921339 11.786636 +-25.361128 29.858719 11.842594 +-24.358948 29.779814 12.748809 +-24.385109 29.692408 12.788004 +-25.407013 29.781496 11.888519 +-25.440454 29.694677 11.921989 +-26.073696 29.966282 10.711306 +-26.146782 29.921835 10.760179 +-26.212402 29.859619 10.804062 +-26.691563 29.966434 9.556417 +-26.772621 29.922201 9.590021 +-26.845444 29.860289 9.620213 +-26.266356 29.782873 10.840144 +-26.305809 29.696535 10.866532 +-26.905396 29.783894 9.645066 +-26.949345 29.697914 9.663286 +20.514759 30.000000 13.500000 +-20.514759 30.000000 13.500000 +-20.514759 29.602455 13.989390 +-20.514759 29.500000 14.000000 +20.514759 29.500000 14.000000 +20.514759 29.602455 13.989390 +-20.514759 29.698589 13.958871 +20.514759 29.698589 13.958871 +-20.514759 29.783318 13.911984 +-20.514759 29.853554 13.853554 +20.514759 29.783318 13.911984 +-20.514759 29.911985 13.783318 +20.514759 29.853554 13.853554 +-20.514759 29.958872 13.698588 +20.514759 29.911985 13.783318 +20.514759 29.958872 13.698588 +-20.514759 29.989391 13.602455 +20.514759 29.989391 13.602455 +27.403017 29.520468 8.273742 +27.519966 29.520815 7.000000 +26.563627 30.000000 9.392615 +26.911791 30.000000 8.182760 +25.959951 30.000000 10.556864 +25.114943 30.000000 11.596194 +24.074709 30.000000 12.440471 +22.909451 30.000000 13.043624 +27.109333 29.992027 7.000000 +27.020399 30.000000 7.000000 +27.200180 29.966560 7.000000 +27.287777 29.922504 7.000000 +27.366516 29.860838 7.000000 +21.698545 30.000000 13.391485 +20.514759 30.000000 13.500000 +20.514759 29.991653 13.590981 +20.514759 29.964893 13.684048 +20.514759 29.918497 13.773605 +20.514759 29.853554 13.853554 +20.514759 29.773605 13.918498 +20.514759 29.684048 13.964894 +20.514759 29.590982 13.991652 +20.514759 29.500000 14.000000 +21.789448 29.503788 13.883138 +23.093340 29.507662 13.508518 +24.348078 29.511391 12.858969 +25.468189 29.514719 11.949747 +26.378086 29.517422 10.830468 +27.028118 29.519354 9.576663 +27.431406 29.784735 7.000000 +27.479071 29.699047 7.000000 +27.508299 29.609339 7.000000 +26.607485 29.991999 9.521561 +25.997875 29.991964 10.660604 +26.982250 29.992020 8.285435 +25.178226 29.991919 11.659534 +24.178764 29.991861 12.478931 +23.038853 29.991796 13.088563 +21.801594 29.991726 13.463549 +27.071379 29.966530 8.303178 +27.157318 29.922428 8.320286 +27.234560 29.860699 8.335664 +21.819658 29.965221 13.554398 +21.837046 29.919285 13.641857 +21.852587 29.854986 13.720041 +21.865246 29.775793 13.783736 +21.874334 29.686991 13.829499 +21.879639 29.594576 13.856234 +23.191851 29.598024 13.458250 +24.400736 29.601198 12.811425 +25.460615 29.603979 11.942168 +26.329771 29.606255 10.882562 +26.976175 29.607946 9.674410 +27.373550 29.608988 8.363340 +27.298201 29.784521 8.348335 +27.344927 29.698761 8.357639 +26.691563 29.966434 9.556417 +26.772621 29.922201 9.590021 +26.845444 29.860289 9.620213 +26.905396 29.783894 9.645066 +26.949345 29.697914 9.663286 +26.073696 29.966282 10.711306 +26.146782 29.921835 10.760179 +26.212402 29.859619 10.804062 +25.242897 29.966076 11.724261 +25.305220 29.921339 11.786636 +25.361128 29.858719 11.842594 +26.266356 29.782873 10.840144 +26.305809 29.696535 10.866532 +25.407013 29.781496 11.888519 +25.440454 29.694677 11.921989 +24.229755 29.965822 12.555300 +24.278877 29.920732 12.628872 +24.322899 29.857618 12.694808 +23.074118 29.965534 13.173773 +23.108080 29.920040 13.255834 +23.138477 29.856359 13.329287 +24.358948 29.779814 12.748809 +24.385109 29.692408 12.788004 +23.163311 29.777889 13.389291 +23.181248 29.689814 13.432630 +27.295078 29.917793 7.000000 +27.112642 29.991417 6.983936 +27.020399 30.000000 6.983936 +27.020399 30.000000 7.000000 +27.112642 29.991417 7.000000 +27.209391 29.962906 6.983936 +27.295078 29.917793 6.983936 +27.209391 29.962906 7.000000 +27.507551 29.612621 7.000000 +27.519966 29.520815 7.000000 +27.519966 29.520815 6.983936 +27.507551 29.612621 6.983936 +27.475037 29.708099 7.000000 +27.475037 29.708099 6.983936 +27.426395 29.791834 7.000000 +27.366516 29.860838 7.000000 +27.426395 29.791834 6.983936 +27.366516 29.860838 6.983936 +22.303431 29.503923 0.215352 +21.000000 29.500000 0.000000 +27.508299 29.609339 6.983936 +27.519966 29.520815 6.983936 +27.366516 29.860838 6.983936 +27.287777 29.922504 6.983936 +27.200180 29.966560 6.983936 +27.109333 29.992027 6.983936 +27.020399 30.000000 6.983936 +26.907141 30.000000 5.776322 +26.570353 30.000000 4.608300 +26.024683 30.000000 3.527889 +25.283665 30.000000 2.562519 +24.381807 30.000000 1.756571 +23.339539 30.000000 1.128183 +22.205130 30.000000 0.706587 +21.000000 30.000000 0.501299 +21.000000 29.990131 0.403199 +21.000000 29.961508 0.309359 +21.000000 29.915611 0.222958 +21.000000 29.853920 0.147175 +21.000000 29.778349 0.085134 +21.000000 29.691999 0.038881 +21.000000 29.598131 0.009981 +23.531500 29.507671 0.665791 +24.660194 29.511168 1.340793 +25.637346 29.514252 2.208935 +26.440493 29.516851 3.250411 +27.032007 29.518847 4.416991 +27.397171 29.520187 5.678949 +27.479071 29.699047 6.983936 +27.431406 29.784735 6.983936 +27.355513 29.698593 5.677886 +27.308731 29.784397 5.686831 +27.244991 29.860619 5.699020 +27.167616 29.922382 5.713816 +27.081520 29.966511 5.730280 +26.992222 29.992016 5.747355 +26.643938 29.991991 4.551992 +26.080025 29.991955 3.448261 +25.314623 29.991909 2.464484 +24.383961 29.991852 1.646778 +23.310085 29.991789 1.014310 +22.142269 29.991720 0.596470 +22.165125 29.965195 0.506664 +22.187128 29.919224 0.420213 +22.206795 29.854874 0.342940 +22.222813 29.775621 0.280001 +22.234316 29.686760 0.234804 +22.241028 29.594292 0.208427 +23.479576 29.597635 0.651851 +24.618420 29.600750 1.322886 +25.605328 29.603498 2.190339 +26.416943 29.605814 3.233872 +27.014874 29.607590 4.404571 +27.384148 29.608782 5.672410 +26.987925 29.697622 4.415281 +26.943735 29.783678 4.432844 +26.883421 29.860147 4.456814 +26.810139 29.922125 4.485939 +26.728559 29.966402 4.518361 +26.392672 29.696175 3.249316 +25.584621 29.694286 2.209866 +26.352652 29.782606 3.274781 +25.550224 29.781206 2.242304 +26.297888 29.859446 3.309629 +25.502991 29.858530 2.286846 +26.231256 29.921738 3.352029 +25.445419 29.921234 2.341138 +26.157032 29.966242 3.399259 +25.381233 29.966032 2.401668 +24.601946 29.692041 1.345644 +23.467854 29.689495 0.676920 +24.574331 29.779541 1.383792 +23.447996 29.777653 0.719383 +24.536257 29.857441 1.436390 +23.420488 29.856203 0.778210 +24.489748 29.920635 1.500639 +23.386805 29.919954 0.850243 +24.437841 29.965782 1.572343 +23.349169 29.965500 0.930730 +-21.093906 20.506123 10.560303 +-25.500000 20.506123 10.560303 +-25.500000 20.799999 10.800000 +-21.079567 20.799999 10.800000 +-25.500000 20.768505 10.798342 +-25.500000 20.709270 10.785952 +-21.081621 20.751543 10.796061 +-25.500000 20.655851 10.763099 +-21.083782 20.702278 10.783638 +-25.500000 20.610384 10.732477 +-21.085962 20.654432 10.762317 +-21.088058 20.610384 10.732477 +-25.500000 20.571247 10.694093 +-21.089970 20.572298 10.695325 +-25.500000 20.538122 10.646358 +-21.091612 20.541794 10.652741 +-25.500000 20.514078 10.590822 +-21.092932 20.519722 10.606978 +-21.088484 20.681374 10.345057 +-21.087042 20.718750 10.331819 +-25.500000 20.520575 10.511421 +-25.500000 20.506123 10.560303 +-21.093906 20.506123 10.560303 +-21.093801 20.516644 10.522072 +-25.500000 20.546862 10.459606 +-21.093464 20.532627 10.484550 +-25.500000 20.580383 10.416232 +-21.092884 20.554005 10.448892 +-25.500000 20.621239 10.379683 +-21.092070 20.580383 10.416232 +-21.091042 20.611065 10.387575 +-25.500000 20.671032 10.349742 +-21.089832 20.645096 10.363692 +-25.500000 20.718750 10.331819 +-21.000000 23.945398 6.714187 +-25.500000 23.945398 6.714187 +-25.500000 23.937059 6.750000 +-21.000000 23.937059 6.750000 +-21.000000 24.196161 6.502254 +-21.000000 24.232864 6.500000 +-25.500000 24.232864 6.500000 +-21.000000 24.137152 6.515677 +-25.500000 24.196161 6.502254 +-25.500000 24.137152 6.515677 +-21.000000 24.084141 6.539459 +-25.500000 24.084141 6.539459 +-21.000000 24.039215 6.570871 +-21.000000 24.000755 6.609933 +-25.500000 24.039215 6.570871 +-21.000000 23.968470 6.658240 +-25.500000 24.000755 6.609933 +-25.500000 23.968470 6.658240 +-25.500000 27.869991 6.552809 +-25.500000 27.761473 6.506366 +-25.500000 27.700001 6.500000 +-21.000000 27.700001 6.500000 +-21.000000 27.761473 6.506366 +-25.500000 27.819153 6.524677 +-21.000000 28.000000 6.800000 +-25.500000 28.000000 6.800000 +-21.000000 27.993635 6.738527 +-25.500000 27.993635 6.738527 +-21.000000 27.975323 6.680847 +-21.000000 27.947191 6.630010 +-25.500000 27.975323 6.680847 +-21.000000 27.912132 6.587868 +-25.500000 27.947191 6.630010 +-21.000000 27.869991 6.552809 +-25.500000 27.912132 6.587868 +-21.000000 27.819153 6.524677 +-25.500000 27.947191 10.669991 +-25.500000 27.993635 10.561473 +-25.500000 28.000000 10.500000 +-21.000000 28.000000 10.500000 +-25.500000 27.975323 10.619153 +-21.000000 27.993635 10.561473 +-21.000000 27.761473 10.793634 +-21.000000 27.700001 10.800000 +-25.500000 27.700001 10.800000 +-25.500000 27.761473 10.793634 +-21.000000 27.819153 10.775323 +-25.500000 27.819153 10.775323 +-21.000000 27.869991 10.747190 +-25.500000 27.869991 10.747190 +-21.000000 27.912132 10.712132 +-25.500000 27.912132 10.712132 +-21.000000 27.947191 10.669991 +-21.000000 27.975323 10.619153 + + + + + + + + + + + +-0.999095 -0.041629 -0.008727 +-0.999959 0.000000 -0.009098 +-0.999095 -0.041629 -0.008727 +-0.999959 0.000000 -0.009098 +-0.999095 -0.041629 -0.008727 +-0.999959 0.000000 -0.009098 +0.181956 -0.983305 -0.001589 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.983268 -0.181963 -0.008588 +0.999962 0.000000 -0.008734 +0.999962 0.000000 -0.008734 +0.983268 -0.181963 -0.008588 +0.983268 -0.181963 -0.008588 +0.999962 0.000000 -0.008734 +0.929753 -0.368095 -0.008121 +0.983268 -0.181963 -0.008588 +0.983268 -0.181963 -0.008588 +0.929753 -0.368095 -0.008121 +0.929753 -0.368095 -0.008121 +0.983268 -0.181963 -0.008588 +0.836964 -0.547210 -0.007310 +0.929753 -0.368095 -0.008121 +0.929753 -0.368095 -0.008121 +0.836964 -0.547210 -0.007310 +0.836964 -0.547210 -0.007310 +0.929753 -0.368095 -0.008121 +0.776324 -0.630298 -0.006781 +0.836964 -0.547210 -0.007310 +0.836964 -0.547210 -0.007310 +0.776324 -0.630298 -0.006781 +0.776324 -0.630298 -0.006781 +0.836964 -0.547210 -0.007310 +0.707080 -0.707107 -0.006176 +0.776324 -0.630298 -0.006781 +0.776324 -0.630298 -0.006781 +0.707080 -0.707107 -0.006176 +0.707080 -0.707107 -0.006176 +0.776324 -0.630298 -0.006781 +0.630274 -0.776353 -0.005505 +0.707080 -0.707107 -0.006176 +0.707080 -0.707107 -0.006176 +0.630274 -0.776353 -0.005505 +0.630274 -0.776353 -0.005505 +0.707080 -0.707107 -0.006176 +0.547189 -0.836995 -0.004779 +0.630274 -0.776353 -0.005505 +0.630274 -0.776353 -0.005505 +0.547189 -0.836995 -0.004779 +0.547189 -0.836995 -0.004779 +0.630274 -0.776353 -0.005505 +0.368081 -0.929788 -0.003215 +0.547189 -0.836995 -0.004779 +0.547189 -0.836995 -0.004779 +0.368081 -0.929788 -0.003215 +0.368081 -0.929788 -0.003215 +0.547189 -0.836995 -0.004779 +0.181956 -0.983305 -0.001589 +0.368081 -0.929788 -0.003215 +0.368081 -0.929788 -0.003215 +0.181956 -0.983305 -0.001589 +0.181956 -0.983305 -0.001589 +0.368081 -0.929788 -0.003215 +0.000000 -1.000000 0.000000 +0.181956 -0.983305 -0.001589 +0.181956 -0.983305 -0.001589 +0.000000 -0.607077 0.794643 +0.000000 -0.468750 0.883331 +0.000000 -0.468750 0.883331 +0.000000 -1.000000 0.000000 +0.000000 -0.986500 0.163761 +0.000000 -1.000000 0.000000 +0.000000 -0.986500 0.163761 +0.000000 -0.986500 0.163761 +0.000000 -1.000000 0.000000 +0.000000 -0.936432 0.350850 +0.000000 -0.986500 0.163761 +0.000000 -0.986500 0.163761 +0.000000 -0.936432 0.350850 +0.000000 -0.936432 0.350850 +0.000000 -0.986500 0.163761 +0.000000 -0.936432 0.350850 +0.000000 -0.856957 0.515388 +0.000000 -0.936432 0.350850 +0.000000 -0.856957 0.515388 +0.000000 -0.856957 0.515388 +0.000000 -0.936432 0.350850 +0.000000 -0.748869 0.662718 +0.000000 -0.856957 0.515388 +0.000000 -0.856957 0.515388 +0.000000 -0.748869 0.662718 +0.000000 -0.748869 0.662718 +0.000000 -0.856957 0.515388 +0.000000 -0.748869 0.662718 +0.000000 -0.607077 0.794643 +0.000000 -0.748869 0.662718 +0.000000 -0.607077 0.794643 +0.000000 -0.607077 0.794643 +0.000000 -0.748869 0.662718 +0.000000 -0.468750 0.883331 +0.000000 -0.607077 0.794643 +0.000000 -0.607077 0.794643 +0.000000 -0.929788 -0.368095 +0.000000 -0.983305 -0.181963 +0.000000 -0.983305 -0.181963 +0.000000 -0.983305 -0.181963 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -0.983305 -0.181963 +0.000000 -0.983305 -0.181963 +0.000000 -1.000000 0.000000 +0.000000 0.983305 -0.181963 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.983305 -0.181963 +0.000000 0.983305 -0.181963 +0.000000 1.000000 0.000000 +0.000000 0.983305 -0.181963 +0.000000 0.929788 -0.368095 +0.000000 0.983305 -0.181963 +0.000000 0.929788 -0.368095 +0.000000 0.929788 -0.368095 +0.000000 0.983305 -0.181963 +0.000000 0.929788 -0.368095 +0.000000 0.836995 -0.547210 +0.000000 0.929788 -0.368095 +0.000000 0.836995 -0.547210 +0.000000 0.836995 -0.547210 +0.000000 0.929788 -0.368095 +0.000000 0.836995 -0.547210 +0.000000 0.707107 -0.707107 +0.000000 0.836995 -0.547210 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.836995 -0.547210 +0.000000 0.707107 -0.707107 +0.000000 0.547210 -0.836995 +0.000000 0.707107 -0.707107 +0.000000 0.547210 -0.836995 +0.000000 0.547210 -0.836995 +0.000000 0.707107 -0.707107 +0.000000 0.368095 -0.929788 +0.000000 0.547210 -0.836995 +0.000000 0.547210 -0.836995 +0.000000 0.368095 -0.929788 +0.000000 0.368095 -0.929788 +0.000000 0.547210 -0.836995 +0.000000 0.181963 -0.983305 +0.000000 0.368095 -0.929788 +0.000000 0.368095 -0.929788 +0.000000 0.181963 -0.983305 +0.000000 0.181963 -0.983305 +0.000000 0.368095 -0.929788 +0.000000 0.000000 -1.000000 +0.000000 0.181963 -0.983305 +0.000000 0.181963 -0.983305 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.181963 -0.983305 +0.000000 -0.181963 -0.983305 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -0.181963 -0.983305 +0.000000 -0.181963 -0.983305 +0.000000 0.000000 -1.000000 +0.000000 -0.368095 -0.929788 +0.000000 -0.181963 -0.983305 +0.000000 -0.181963 -0.983305 +0.000000 -0.368095 -0.929788 +0.000000 -0.368095 -0.929788 +0.000000 -0.181963 -0.983305 +0.000000 -0.547210 -0.836995 +0.000000 -0.368095 -0.929788 +0.000000 -0.368095 -0.929788 +0.000000 -0.547210 -0.836995 +0.000000 -0.547210 -0.836995 +0.000000 -0.368095 -0.929788 +0.000000 -0.707107 -0.707107 +0.000000 -0.547210 -0.836995 +0.000000 -0.547210 -0.836995 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.547210 -0.836995 +0.000000 -0.836995 -0.547210 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.836995 -0.547210 +0.000000 -0.836995 -0.547210 +0.000000 -0.707107 -0.707107 +0.000000 -0.929788 -0.368095 +0.000000 -0.836995 -0.547210 +0.000000 -0.836995 -0.547210 +0.000000 -0.929788 -0.368095 +0.000000 -0.929788 -0.368095 +0.000000 -0.836995 -0.547210 +0.000000 -0.983305 -0.181963 +0.000000 -0.929788 -0.368095 +0.000000 -0.929788 -0.368095 +0.000000 -0.739596 0.673051 +0.000000 -0.589470 0.807790 +0.000000 -0.589470 0.807790 +0.000000 0.000000 1.000000 +0.000000 -0.015591 0.999878 +0.000000 0.000000 1.000000 +0.000000 -0.015591 0.999878 +0.000000 -0.015591 0.999878 +0.000000 0.000000 1.000000 +0.000000 -0.015591 0.999878 +0.000000 -0.215945 0.976406 +0.000000 -0.015591 0.999878 +0.000000 -0.215945 0.976406 +0.000000 -0.215945 0.976406 +0.000000 -0.015591 0.999878 +0.000000 -0.215945 0.976406 +0.000000 -0.411438 0.911438 +0.000000 -0.215945 0.976406 +0.000000 -0.411438 0.911438 +0.000000 -0.411438 0.911438 +0.000000 -0.215945 0.976406 +0.000000 -0.411438 0.911438 +0.000000 -0.589470 0.807790 +0.000000 -0.411438 0.911438 +0.000000 -0.589470 0.807790 +0.000000 -0.589470 0.807790 +0.000000 -0.411438 0.911438 +0.000000 -0.661438 -0.750000 +0.000000 -0.673051 -0.739596 +0.000000 -0.661438 -0.750000 +0.000000 -0.673051 -0.739596 +0.000000 -0.673051 -0.739596 +0.000000 -0.661438 -0.750000 +0.000000 -0.673051 -0.739596 +0.000000 -0.807790 -0.589470 +0.000000 -0.673051 -0.739596 +0.000000 -0.807790 -0.589470 +0.000000 -0.807790 -0.589470 +0.000000 -0.673051 -0.739596 +0.000000 -0.807790 -0.589470 +0.000000 -0.911438 -0.411438 +0.000000 -0.807790 -0.589470 +0.000000 -0.911438 -0.411438 +0.000000 -0.911438 -0.411438 +0.000000 -0.807790 -0.589470 +0.000000 -0.911438 -0.411438 +0.000000 -0.976406 -0.215945 +0.000000 -0.911438 -0.411438 +0.000000 -0.976406 -0.215945 +0.000000 -0.976406 -0.215945 +0.000000 -0.911438 -0.411438 +0.000000 -0.999878 -0.015591 +0.000000 -0.976406 -0.215945 +0.000000 -0.976406 -0.215945 +0.000000 -0.999878 -0.015591 +0.000000 -0.999878 -0.015591 +0.000000 -0.976406 -0.215945 +0.000000 -0.999878 -0.015591 +0.000000 -0.984132 0.177440 +0.000000 -0.999878 -0.015591 +0.000000 -0.984132 0.177440 +0.000000 -0.984132 0.177440 +0.000000 -0.999878 -0.015591 +0.000000 -0.935414 0.353553 +0.000000 -0.984132 0.177440 +0.000000 -0.984132 0.177440 +0.000000 -0.935414 0.353553 +0.000000 -0.935414 0.353553 +0.000000 -0.984132 0.177440 +0.000000 -0.855464 0.517862 +0.000000 -0.935414 0.353553 +0.000000 -0.935414 0.353553 +0.000000 -0.855464 0.517862 +0.000000 -0.855464 0.517862 +0.000000 -0.935414 0.353553 +0.000000 -0.855464 0.517862 +0.000000 -0.739596 0.673051 +0.000000 -0.855464 0.517862 +0.000000 -0.739596 0.673051 +0.000000 -0.739596 0.673051 +0.000000 -0.855464 0.517862 +0.000000 -0.589470 0.807790 +0.000000 -0.739596 0.673051 +0.000000 -0.739596 0.673051 +0.000000 0.607077 0.794643 +0.000000 0.468750 0.883331 +0.000000 0.468750 0.883331 +0.000000 0.986500 0.163761 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.986500 0.163761 +0.000000 0.986500 0.163761 +0.000000 1.000000 0.000000 +0.000000 0.936432 0.350850 +0.000000 0.986500 0.163761 +0.000000 0.986500 0.163761 +0.000000 0.936432 0.350850 +0.000000 0.936432 0.350850 +0.000000 0.986500 0.163761 +0.000000 0.856957 0.515388 +0.000000 0.936432 0.350850 +0.000000 0.936432 0.350850 +0.000000 0.856957 0.515388 +0.000000 0.856957 0.515388 +0.000000 0.936432 0.350850 +0.000000 0.748869 0.662718 +0.000000 0.856957 0.515388 +0.000000 0.856957 0.515388 +0.000000 0.748869 0.662718 +0.000000 0.748869 0.662718 +0.000000 0.856957 0.515388 +0.000000 0.748869 0.662718 +0.000000 0.607077 0.794643 +0.000000 0.748869 0.662718 +0.000000 0.607077 0.794643 +0.000000 0.607077 0.794643 +0.000000 0.748869 0.662718 +0.000000 0.468750 0.883331 +0.000000 0.607077 0.794643 +0.000000 0.607077 0.794643 +0.000000 0.181963 -0.983305 +0.000000 0.368095 -0.929788 +0.000000 0.368095 -0.929788 +0.000000 0.983305 -0.181963 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.983305 -0.181963 +0.000000 0.983305 -0.181963 +0.000000 1.000000 0.000000 +0.000000 0.983305 -0.181963 +0.000000 0.929788 -0.368095 +0.000000 0.983305 -0.181963 +0.000000 0.929788 -0.368095 +0.000000 0.929788 -0.368095 +0.000000 0.983305 -0.181963 +0.000000 0.929788 -0.368095 +0.000000 0.836995 -0.547210 +0.000000 0.929788 -0.368095 +0.000000 0.836995 -0.547210 +0.000000 0.836995 -0.547210 +0.000000 0.929788 -0.368095 +0.000000 0.707107 -0.707107 +0.000000 0.836995 -0.547210 +0.000000 0.836995 -0.547210 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.836995 -0.547210 +0.000000 0.547210 -0.836995 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.547210 -0.836995 +0.000000 0.547210 -0.836995 +0.000000 0.707107 -0.707107 +0.000000 0.368095 -0.929788 +0.000000 0.547210 -0.836995 +0.000000 0.547210 -0.836995 +0.000000 0.368095 -0.929788 +0.000000 0.368095 -0.929788 +0.000000 0.547210 -0.836995 +0.000000 -0.983305 -0.181963 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -0.983305 -0.181963 +0.000000 -0.983305 -0.181963 +0.000000 -1.000000 0.000000 +0.000000 -0.983305 -0.181963 +0.000000 -0.929788 -0.368095 +0.000000 -0.983305 -0.181963 +0.000000 -0.929788 -0.368095 +0.000000 -0.929788 -0.368095 +0.000000 -0.983305 -0.181963 +0.000000 -0.836995 -0.547210 +0.000000 -0.929788 -0.368095 +0.000000 -0.929788 -0.368095 +0.000000 -0.836995 -0.547210 +0.000000 -0.836995 -0.547210 +0.000000 -0.929788 -0.368095 +0.000000 -0.836995 -0.547210 +0.000000 -0.707107 -0.707107 +0.000000 -0.836995 -0.547210 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.836995 -0.547210 +0.000000 -0.547210 -0.836995 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.547210 -0.836995 +0.000000 -0.547210 -0.836995 +0.000000 -0.707107 -0.707107 +0.000000 -0.368095 -0.929788 +0.000000 -0.547210 -0.836995 +0.000000 -0.547210 -0.836995 +0.000000 -0.368095 -0.929788 +0.000000 -0.368095 -0.929788 +0.000000 -0.547210 -0.836995 +0.000000 -0.368095 -0.929788 +0.000000 -0.181963 -0.983305 +0.000000 -0.368095 -0.929788 +0.000000 -0.181963 -0.983305 +0.000000 -0.181963 -0.983305 +0.000000 -0.368095 -0.929788 +0.000000 -0.181963 -0.983305 +0.000000 0.000000 -1.000000 +0.000000 -0.181963 -0.983305 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -0.181963 -0.983305 +0.000000 0.181963 -0.983305 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.181963 -0.983305 +0.000000 0.181963 -0.983305 +0.000000 0.000000 -1.000000 +0.000000 0.368095 -0.929788 +0.000000 0.181963 -0.983305 +0.000000 0.181963 -0.983305 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.999095 -0.041629 -0.008727 +-0.999095 -0.041629 -0.008727 +-0.999095 -0.041629 -0.008727 +-0.999095 -0.041629 -0.008727 +-0.999095 -0.041629 -0.008727 +-0.999095 -0.041629 -0.008727 +-0.999095 -0.041629 -0.008727 +-0.999095 -0.041629 -0.008727 +-0.999095 -0.041629 -0.008727 +-0.999095 -0.041629 -0.008727 +-0.999095 -0.041629 -0.008727 +-0.999095 -0.041629 -0.008727 +-0.999095 -0.041629 -0.008727 +-0.999095 -0.041629 -0.008727 +-0.999095 -0.041629 -0.008727 +-0.999095 -0.041629 -0.008727 +-0.999095 -0.041629 -0.008727 +-0.999095 -0.041629 -0.008727 +-0.999095 -0.041629 -0.008727 +-0.999095 -0.041629 -0.008727 +-0.999095 -0.041629 -0.008727 +-0.999095 -0.041629 -0.008727 +-0.999095 -0.041629 -0.008727 +-0.999095 -0.041629 -0.008727 +-0.999095 -0.041629 -0.008727 +-0.999095 -0.041629 -0.008727 +-0.999095 -0.041629 -0.008727 +-0.999095 -0.041629 -0.008727 +-0.999095 -0.041629 -0.008727 +-0.999095 -0.041629 -0.008727 +-0.999095 -0.041629 -0.008727 +-0.999095 -0.041629 -0.008727 +-0.999095 -0.041629 -0.008727 +-0.999095 -0.041629 -0.008727 +-0.999095 -0.041629 -0.008727 +-0.999095 -0.041629 -0.008727 +-0.999095 -0.041629 -0.008727 +-0.999095 -0.041629 -0.008727 +-0.999095 -0.041629 -0.008727 +-0.999095 -0.041629 -0.008727 +-0.999095 -0.041629 -0.008727 +-0.999095 -0.041629 -0.008727 +-0.999095 -0.041629 -0.008727 +-0.999095 -0.041629 -0.008727 +-0.999095 -0.041629 -0.008727 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999095 0.041629 -0.008727 +-0.999095 0.041629 -0.008727 +-0.999095 0.041629 -0.008727 +-0.999095 0.041629 -0.008727 +-0.999095 0.041629 -0.008727 +-0.999095 0.041629 -0.008727 +-0.999095 0.041629 -0.008727 +-0.999095 0.041629 -0.008727 +-0.999095 0.041629 -0.008727 +-0.999095 0.041629 -0.008727 +-0.999095 0.041629 -0.008727 +-0.999095 0.041629 -0.008727 +-0.999095 0.041629 -0.008727 +-0.999095 0.041629 -0.008727 +-0.999095 0.041629 -0.008727 +-0.999095 0.041629 -0.008727 +-0.999095 0.041629 -0.008727 +-0.999095 0.041629 -0.008727 +-0.999095 0.041629 -0.008727 +-0.999095 0.041629 -0.008727 +-0.999095 0.041629 -0.008727 +-0.999095 0.041629 -0.008727 +-0.999095 0.041629 -0.008727 +-0.999095 0.041629 -0.008727 +-0.999095 0.041629 -0.008727 +-0.999095 0.041629 -0.008727 +-0.999095 0.041629 -0.008727 +-0.999095 0.041629 -0.008727 +-0.999095 0.041629 -0.008727 +-0.999095 0.041629 -0.008727 +-0.999095 0.041629 -0.008727 +-0.999095 0.041629 -0.008727 +-0.999095 0.041629 -0.008727 +-0.999095 0.041629 -0.008727 +-0.999095 0.041629 -0.008727 +-0.999095 0.041629 -0.008727 +-0.999095 0.041629 -0.008727 +-0.999095 0.041629 -0.008727 +-0.999095 0.041629 -0.008727 +-0.999095 0.041629 -0.008727 +-0.999095 0.041629 -0.008727 +-0.999095 0.041629 -0.008727 +-0.999095 0.041629 -0.008727 +-0.999095 0.041629 -0.008727 +-0.999095 0.041629 -0.008727 +-0.999095 0.041629 -0.008727 +-0.999095 0.041629 -0.008727 +-0.999095 0.041629 -0.008727 +0.999095 0.041629 -0.008727 +0.999095 0.041629 -0.008727 +0.999095 0.041629 -0.008727 +0.999095 0.041629 -0.008727 +0.999095 0.041629 -0.008727 +0.999095 0.041629 -0.008727 +0.999095 0.041629 -0.008727 +0.999095 0.041629 -0.008727 +0.999095 0.041629 -0.008727 +0.999095 0.041629 -0.008727 +0.999095 0.041629 -0.008727 +0.999095 0.041629 -0.008727 +0.999095 0.041629 -0.008727 +0.999095 0.041629 -0.008727 +0.999095 0.041629 -0.008727 +0.999095 0.041629 -0.008727 +0.999095 0.041629 -0.008727 +0.999095 0.041629 -0.008727 +0.999095 0.041629 -0.008727 +0.999095 0.041629 -0.008727 +0.999095 0.041629 -0.008727 +0.999095 0.041629 -0.008727 +0.999095 0.041629 -0.008727 +0.999095 0.041629 -0.008727 +0.999095 0.041629 -0.008727 +0.999095 0.041629 -0.008727 +0.999095 0.041629 -0.008727 +0.999095 0.041629 -0.008727 +0.999095 0.041629 -0.008727 +0.999095 0.041629 -0.008727 +0.999095 0.041629 -0.008727 +0.999095 0.041629 -0.008727 +0.999095 0.041629 -0.008727 +0.999095 0.041629 -0.008727 +0.999095 0.041629 -0.008727 +0.999095 0.041629 -0.008727 +0.999095 0.041629 -0.008727 +0.999095 0.041629 -0.008727 +0.999095 0.041629 -0.008727 +0.999095 0.041629 -0.008727 +0.999095 0.041629 -0.008727 +0.999095 0.041629 -0.008727 +0.999095 0.041629 -0.008727 +0.999095 0.041629 -0.008727 +0.999095 0.041629 -0.008727 +0.999095 0.041629 -0.008727 +0.999095 0.041629 -0.008727 +0.999095 0.041629 -0.008727 +0.999095 0.041629 -0.008727 +0.999095 0.041629 -0.008727 +0.999095 0.041629 -0.008727 +0.999095 0.041629 -0.008727 +0.999095 0.041629 -0.008727 +0.999095 0.041629 -0.008727 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.999133 0.041631 0.000000 +-0.999133 0.041631 0.000000 +-0.999133 0.041631 0.000000 +-0.999133 0.041631 0.000000 +-0.999133 0.041631 0.000000 +-0.999133 0.041631 0.000000 +0.999133 0.041631 0.000000 +0.999133 0.041631 0.000000 +0.999133 0.041631 0.000000 +0.999133 0.041631 0.000000 +0.999133 0.041631 0.000000 +0.999133 0.041631 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.000000 -0.153400 -0.988164 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -0.153400 -0.988164 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -0.181963 -0.983305 +0.000000 0.000000 -1.000000 +0.000000 -0.983305 -0.181963 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -0.983305 -0.181963 +0.000000 -0.985736 -0.168300 +0.000000 -1.000000 0.000000 +0.000000 -0.983305 -0.181963 +0.000000 -0.943065 -0.332610 +0.000000 -0.985736 -0.168300 +0.000000 -0.929788 -0.368095 +0.000000 -0.943065 -0.332610 +0.000000 -0.983305 -0.181963 +0.000000 -0.929788 -0.368095 +0.000000 -0.942809 -0.333333 +0.000000 -0.943065 -0.332610 +0.000000 -0.929788 -0.368095 +0.000000 -0.880240 -0.474529 +0.000000 -0.942809 -0.333333 +0.000000 -0.836995 -0.547210 +0.000000 -0.880240 -0.474529 +0.000000 -0.929788 -0.368095 +0.000000 -0.836995 -0.547210 +0.000000 -0.796699 -0.604376 +0.000000 -0.880240 -0.474529 +0.000000 -0.776353 -0.630298 +0.000000 -0.796699 -0.604376 +0.000000 -0.836995 -0.547210 +0.000000 -0.776353 -0.630298 +0.000000 -0.695297 -0.718722 +0.000000 -0.796699 -0.604376 +0.000000 -0.707107 -0.707107 +0.000000 -0.695297 -0.718722 +0.000000 -0.776353 -0.630298 +0.000000 -0.630298 -0.776353 +0.000000 -0.695297 -0.718722 +0.000000 -0.707107 -0.707107 +0.000000 -0.630298 -0.776353 +0.000000 -0.576924 -0.816798 +0.000000 -0.695297 -0.718722 +0.000000 -0.547210 -0.836995 +0.000000 -0.576924 -0.816798 +0.000000 -0.630298 -0.776353 +0.000000 -0.547210 -0.836995 +0.000000 -0.445346 -0.895359 +0.000000 -0.576924 -0.816798 +0.000000 -0.368095 -0.929788 +0.000000 -0.445346 -0.895359 +0.000000 -0.547210 -0.836995 +0.000000 -0.368095 -0.929788 +0.000000 -0.302895 -0.953024 +0.000000 -0.445346 -0.895359 +0.000000 -0.181963 -0.983305 +0.000000 -0.302895 -0.953024 +0.000000 -0.368095 -0.929788 +0.000000 -0.181963 -0.983305 +0.000000 -0.153400 -0.988164 +0.000000 -0.302895 -0.953024 +0.000000 0.000000 -1.000000 +0.000000 -0.153400 -0.988164 +0.000000 -0.181963 -0.983305 +0.000000 0.000000 -1.000000 +0.000000 -0.154033 -0.988066 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -0.154033 -0.988066 +0.000000 0.000000 -1.000000 +0.000000 -0.985736 -0.168300 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -0.985736 -0.168300 +0.000000 -0.983305 -0.181963 +0.000000 -1.000000 0.000000 +0.000000 -0.943065 -0.332610 +0.000000 -0.983305 -0.181963 +0.000000 -0.985736 -0.168300 +0.000000 -0.943065 -0.332610 +0.000000 -0.929788 -0.368095 +0.000000 -0.983305 -0.181963 +0.000000 -0.942809 -0.333333 +0.000000 -0.929788 -0.368095 +0.000000 -0.943065 -0.332610 +0.000000 -0.880504 -0.474039 +0.000000 -0.929788 -0.368095 +0.000000 -0.942809 -0.333333 +0.000000 -0.880504 -0.474039 +0.000000 -0.836995 -0.547210 +0.000000 -0.929788 -0.368095 +0.000000 -0.797649 -0.603122 +0.000000 -0.836995 -0.547210 +0.000000 -0.880504 -0.474039 +0.000000 -0.797649 -0.603122 +0.000000 -0.776353 -0.630298 +0.000000 -0.836995 -0.547210 +0.000000 -0.695949 -0.718091 +0.000000 -0.776353 -0.630298 +0.000000 -0.797649 -0.603122 +0.000000 -0.695949 -0.718091 +0.000000 -0.707107 -0.707107 +0.000000 -0.776353 -0.630298 +0.000000 -0.695949 -0.718091 +0.000000 -0.630298 -0.776353 +0.000000 -0.707107 -0.707107 +0.000000 -0.578132 -0.815943 +0.000000 -0.630298 -0.776353 +0.000000 -0.695949 -0.718091 +0.000000 -0.578132 -0.815943 +0.000000 -0.547210 -0.836995 +0.000000 -0.630298 -0.776353 +0.000000 -0.446144 -0.894961 +0.000000 -0.547210 -0.836995 +0.000000 -0.578132 -0.815943 +0.000000 -0.446144 -0.894961 +0.000000 -0.368095 -0.929788 +0.000000 -0.547210 -0.836995 +0.000000 -0.304449 -0.952529 +0.000000 -0.368095 -0.929788 +0.000000 -0.446144 -0.894961 +0.000000 -0.304449 -0.952529 +0.000000 -0.181963 -0.983305 +0.000000 -0.368095 -0.929788 +0.000000 -0.154033 -0.988066 +0.000000 -0.181963 -0.983305 +0.000000 -0.304449 -0.952529 +0.000000 -0.154033 -0.988066 +0.000000 0.000000 -1.000000 +0.000000 -0.181963 -0.983305 +0.000000 -0.154033 -0.988066 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.999095 -0.041629 -0.008727 +-0.999095 -0.041629 -0.008727 +-0.999095 -0.041629 -0.008727 +-0.999095 -0.041629 -0.008727 +-0.999095 -0.041629 -0.008727 +-0.999095 -0.041629 -0.008727 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.999095 0.041629 -0.008727 +0.999095 0.041629 -0.008727 +0.999095 0.041629 -0.008727 +0.999095 0.041629 -0.008727 +0.999095 0.041629 -0.008727 +0.999095 0.041629 -0.008727 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.999095 0.041629 -0.008727 +-0.999095 0.041629 -0.008727 +-0.999095 0.041629 -0.008727 +-0.999095 0.041629 -0.008727 +-0.999095 0.041629 -0.008727 +-0.999095 0.041629 -0.008727 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999095 0.041629 -0.008727 +-0.999095 0.041629 -0.008727 +-0.999095 0.041629 -0.008727 +-0.999095 0.041629 -0.008727 +-0.999095 0.041629 -0.008727 +-0.999095 0.041629 -0.008727 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.887149 -0.036965 -0.460000 +0.827376 -0.034474 -0.560589 +0.887149 -0.036965 -0.460000 +0.131123 -0.005463 -0.991351 +0.245949 -0.010248 -0.969229 +0.131123 -0.005463 -0.991351 +0.245949 -0.010248 -0.969229 +0.245949 -0.010248 -0.969229 +0.131123 -0.005463 -0.991351 +0.245949 -0.010248 -0.969229 +0.359805 -0.014992 -0.932907 +0.245949 -0.010248 -0.969229 +0.359805 -0.014992 -0.932907 +0.359805 -0.014992 -0.932907 +0.245949 -0.010248 -0.969229 +0.359805 -0.014992 -0.932907 +0.470083 -0.019587 -0.882405 +0.359805 -0.014992 -0.932907 +0.470083 -0.019587 -0.882405 +0.470083 -0.019587 -0.882405 +0.359805 -0.014992 -0.932907 +0.470083 -0.019587 -0.882405 +0.574178 -0.023924 -0.818381 +0.470083 -0.019587 -0.882405 +0.574178 -0.023924 -0.818381 +0.574178 -0.023924 -0.818381 +0.470083 -0.019587 -0.882405 +0.574178 -0.023924 -0.818381 +0.669688 -0.027904 -0.742118 +0.574178 -0.023924 -0.818381 +0.669688 -0.027904 -0.742118 +0.669688 -0.027904 -0.742118 +0.574178 -0.023924 -0.818381 +0.669688 -0.027904 -0.742118 +0.754588 -0.031441 -0.655445 +0.669688 -0.027904 -0.742118 +0.754588 -0.031441 -0.655445 +0.754588 -0.031441 -0.655445 +0.669688 -0.027904 -0.742118 +0.754588 -0.031441 -0.655445 +0.827376 -0.034474 -0.560589 +0.754588 -0.031441 -0.655445 +0.827376 -0.034474 -0.560589 +0.827376 -0.034474 -0.560589 +0.754588 -0.031441 -0.655445 +0.827376 -0.034474 -0.560589 +0.887149 -0.036965 -0.460000 +0.827376 -0.034474 -0.560589 +0.887149 -0.036965 -0.460000 +0.827376 -0.034474 -0.560589 +0.887149 -0.036965 -0.460000 +0.131123 -0.005463 -0.991351 +0.245949 -0.010248 -0.969229 +0.131123 -0.005463 -0.991351 +0.245949 -0.010248 -0.969229 +0.245949 -0.010248 -0.969229 +0.131123 -0.005463 -0.991351 +0.245949 -0.010248 -0.969229 +0.359805 -0.014992 -0.932907 +0.245949 -0.010248 -0.969229 +0.359805 -0.014992 -0.932907 +0.359805 -0.014992 -0.932907 +0.245949 -0.010248 -0.969229 +0.359805 -0.014992 -0.932907 +0.470083 -0.019587 -0.882405 +0.359805 -0.014992 -0.932907 +0.470083 -0.019587 -0.882405 +0.470083 -0.019587 -0.882405 +0.359805 -0.014992 -0.932907 +0.470083 -0.019587 -0.882405 +0.574178 -0.023924 -0.818381 +0.470083 -0.019587 -0.882405 +0.574178 -0.023924 -0.818381 +0.574178 -0.023924 -0.818381 +0.470083 -0.019587 -0.882405 +0.574178 -0.023924 -0.818381 +0.669688 -0.027904 -0.742118 +0.574178 -0.023924 -0.818381 +0.669688 -0.027904 -0.742118 +0.669688 -0.027904 -0.742118 +0.574178 -0.023924 -0.818381 +0.669688 -0.027904 -0.742118 +0.754588 -0.031441 -0.655445 +0.669688 -0.027904 -0.742118 +0.754588 -0.031441 -0.655445 +0.754588 -0.031441 -0.655445 +0.669688 -0.027904 -0.742118 +0.754588 -0.031441 -0.655445 +0.827376 -0.034474 -0.560589 +0.754588 -0.031441 -0.655445 +0.827376 -0.034474 -0.560589 +0.827376 -0.034474 -0.560589 +0.754588 -0.031441 -0.655445 +0.827376 -0.034474 -0.560589 +0.887149 -0.036965 -0.460000 +0.827376 -0.034474 -0.560589 +0.887149 -0.036965 -0.460000 +0.827376 -0.034474 -0.560589 +0.887149 -0.036965 -0.460000 +0.131123 -0.005463 -0.991351 +0.245949 -0.010248 -0.969229 +0.131123 -0.005463 -0.991351 +0.245949 -0.010248 -0.969229 +0.245949 -0.010248 -0.969229 +0.131123 -0.005463 -0.991351 +0.245949 -0.010248 -0.969229 +0.359805 -0.014992 -0.932907 +0.245949 -0.010248 -0.969229 +0.359805 -0.014992 -0.932907 +0.359805 -0.014992 -0.932907 +0.245949 -0.010248 -0.969229 +0.359805 -0.014992 -0.932907 +0.470083 -0.019587 -0.882405 +0.359805 -0.014992 -0.932907 +0.470083 -0.019587 -0.882405 +0.470083 -0.019587 -0.882405 +0.359805 -0.014992 -0.932907 +0.470083 -0.019587 -0.882405 +0.574178 -0.023924 -0.818381 +0.470083 -0.019587 -0.882405 +0.574178 -0.023924 -0.818381 +0.574178 -0.023924 -0.818381 +0.470083 -0.019587 -0.882405 +0.574178 -0.023924 -0.818381 +0.669688 -0.027904 -0.742118 +0.574178 -0.023924 -0.818381 +0.669688 -0.027904 -0.742118 +0.669688 -0.027904 -0.742118 +0.574178 -0.023924 -0.818381 +0.669688 -0.027904 -0.742118 +0.754588 -0.031441 -0.655445 +0.669688 -0.027904 -0.742118 +0.754588 -0.031441 -0.655445 +0.754588 -0.031441 -0.655445 +0.669688 -0.027904 -0.742118 +0.754588 -0.031441 -0.655445 +0.827376 -0.034474 -0.560589 +0.754588 -0.031441 -0.655445 +0.827376 -0.034474 -0.560589 +0.827376 -0.034474 -0.560589 +0.754588 -0.031441 -0.655445 +0.827376 -0.034474 -0.560589 +0.887149 -0.036965 -0.460000 +0.827376 -0.034474 -0.560589 +0.887149 -0.036965 -0.460000 +0.827376 -0.034474 -0.560589 +0.887149 -0.036965 -0.460000 +0.131123 -0.005463 -0.991351 +0.245949 -0.010248 -0.969229 +0.131123 -0.005463 -0.991351 +0.245949 -0.010248 -0.969229 +0.245949 -0.010248 -0.969229 +0.131123 -0.005463 -0.991351 +0.245949 -0.010248 -0.969229 +0.359805 -0.014992 -0.932907 +0.245949 -0.010248 -0.969229 +0.359805 -0.014992 -0.932907 +0.359805 -0.014992 -0.932907 +0.245949 -0.010248 -0.969229 +0.359805 -0.014992 -0.932907 +0.470083 -0.019587 -0.882405 +0.359805 -0.014992 -0.932907 +0.470083 -0.019587 -0.882405 +0.470083 -0.019587 -0.882405 +0.359805 -0.014992 -0.932907 +0.470083 -0.019587 -0.882405 +0.574178 -0.023924 -0.818381 +0.470083 -0.019587 -0.882405 +0.574178 -0.023924 -0.818381 +0.574178 -0.023924 -0.818381 +0.470083 -0.019587 -0.882405 +0.574178 -0.023924 -0.818381 +0.669688 -0.027904 -0.742118 +0.574178 -0.023924 -0.818381 +0.669688 -0.027904 -0.742118 +0.669688 -0.027904 -0.742118 +0.574178 -0.023924 -0.818381 +0.669688 -0.027904 -0.742118 +0.754588 -0.031441 -0.655445 +0.669688 -0.027904 -0.742118 +0.754588 -0.031441 -0.655445 +0.754588 -0.031441 -0.655445 +0.669688 -0.027904 -0.742118 +0.754588 -0.031441 -0.655445 +0.827376 -0.034474 -0.560589 +0.754588 -0.031441 -0.655445 +0.827376 -0.034474 -0.560589 +0.827376 -0.034474 -0.560589 +0.754588 -0.031441 -0.655445 +0.827376 -0.034474 -0.560589 +0.887149 -0.036965 -0.460000 +0.827376 -0.034474 -0.560589 +0.887149 -0.036965 -0.460000 +0.827376 -0.034474 -0.560589 +0.887149 -0.036965 -0.460000 +0.131123 -0.005463 -0.991351 +0.245949 -0.010248 -0.969229 +0.131123 -0.005463 -0.991351 +0.245949 -0.010248 -0.969229 +0.245949 -0.010248 -0.969229 +0.131123 -0.005463 -0.991351 +0.245949 -0.010248 -0.969229 +0.359805 -0.014992 -0.932907 +0.245949 -0.010248 -0.969229 +0.359805 -0.014992 -0.932907 +0.359805 -0.014992 -0.932907 +0.245949 -0.010248 -0.969229 +0.359805 -0.014992 -0.932907 +0.470083 -0.019587 -0.882405 +0.359805 -0.014992 -0.932907 +0.470083 -0.019587 -0.882405 +0.470083 -0.019587 -0.882405 +0.359805 -0.014992 -0.932907 +0.470083 -0.019587 -0.882405 +0.574178 -0.023924 -0.818381 +0.470083 -0.019587 -0.882405 +0.574178 -0.023924 -0.818381 +0.574178 -0.023924 -0.818381 +0.470083 -0.019587 -0.882405 +0.574178 -0.023924 -0.818381 +0.669688 -0.027904 -0.742118 +0.574178 -0.023924 -0.818381 +0.669688 -0.027904 -0.742118 +0.669688 -0.027904 -0.742118 +0.574178 -0.023924 -0.818381 +0.669688 -0.027904 -0.742118 +0.754588 -0.031441 -0.655445 +0.669688 -0.027904 -0.742118 +0.754588 -0.031441 -0.655445 +0.754588 -0.031441 -0.655445 +0.669688 -0.027904 -0.742118 +0.754588 -0.031441 -0.655445 +0.827376 -0.034474 -0.560589 +0.754588 -0.031441 -0.655445 +0.827376 -0.034474 -0.560589 +0.827376 -0.034474 -0.560589 +0.754588 -0.031441 -0.655445 +0.827376 -0.034474 -0.560589 +0.887149 -0.036965 -0.460000 +0.827376 -0.034474 -0.560589 +0.887149 -0.036965 -0.460000 +0.827376 -0.034474 -0.560589 +0.887149 -0.036965 -0.460000 +0.131123 -0.005463 -0.991351 +0.245949 -0.010248 -0.969229 +0.131123 -0.005463 -0.991351 +0.245949 -0.010248 -0.969229 +0.245949 -0.010248 -0.969229 +0.131123 -0.005463 -0.991351 +0.245949 -0.010248 -0.969229 +0.359805 -0.014992 -0.932907 +0.245949 -0.010248 -0.969229 +0.359805 -0.014992 -0.932907 +0.359805 -0.014992 -0.932907 +0.245949 -0.010248 -0.969229 +0.359805 -0.014992 -0.932907 +0.470083 -0.019587 -0.882405 +0.359805 -0.014992 -0.932907 +0.470083 -0.019587 -0.882405 +0.470083 -0.019587 -0.882405 +0.359805 -0.014992 -0.932907 +0.470083 -0.019587 -0.882405 +0.574178 -0.023924 -0.818381 +0.470083 -0.019587 -0.882405 +0.574178 -0.023924 -0.818381 +0.574178 -0.023924 -0.818381 +0.470083 -0.019587 -0.882405 +0.574178 -0.023924 -0.818381 +0.669688 -0.027904 -0.742118 +0.574178 -0.023924 -0.818381 +0.669688 -0.027904 -0.742118 +0.669688 -0.027904 -0.742118 +0.574178 -0.023924 -0.818381 +0.669688 -0.027904 -0.742118 +0.754588 -0.031441 -0.655445 +0.669688 -0.027904 -0.742118 +0.754588 -0.031441 -0.655445 +0.754588 -0.031441 -0.655445 +0.669688 -0.027904 -0.742118 +0.754588 -0.031441 -0.655445 +0.827376 -0.034474 -0.560589 +0.754588 -0.031441 -0.655445 +0.827376 -0.034474 -0.560589 +0.827376 -0.034474 -0.560589 +0.754588 -0.031441 -0.655445 +0.827376 -0.034474 -0.560589 +0.887149 -0.036965 -0.460000 +0.827376 -0.034474 -0.560589 +0.887149 -0.036965 -0.460000 +0.827376 -0.034474 -0.560589 +0.887149 -0.036965 -0.460000 +0.131123 -0.005463 -0.991351 +0.245949 -0.010248 -0.969229 +0.131123 -0.005463 -0.991351 +0.245949 -0.010248 -0.969229 +0.245949 -0.010248 -0.969229 +0.131123 -0.005463 -0.991351 +0.245949 -0.010248 -0.969229 +0.359805 -0.014992 -0.932907 +0.245949 -0.010248 -0.969229 +0.359805 -0.014992 -0.932907 +0.359805 -0.014992 -0.932907 +0.245949 -0.010248 -0.969229 +0.359805 -0.014992 -0.932907 +0.470083 -0.019587 -0.882405 +0.359805 -0.014992 -0.932907 +0.470083 -0.019587 -0.882405 +0.470083 -0.019587 -0.882405 +0.359805 -0.014992 -0.932907 +0.470083 -0.019587 -0.882405 +0.574178 -0.023924 -0.818381 +0.470083 -0.019587 -0.882405 +0.574178 -0.023924 -0.818381 +0.574178 -0.023924 -0.818381 +0.470083 -0.019587 -0.882405 +0.574178 -0.023924 -0.818381 +0.669688 -0.027904 -0.742118 +0.574178 -0.023924 -0.818381 +0.669688 -0.027904 -0.742118 +0.669688 -0.027904 -0.742118 +0.574178 -0.023924 -0.818381 +0.669688 -0.027904 -0.742118 +0.754588 -0.031441 -0.655445 +0.669688 -0.027904 -0.742118 +0.754588 -0.031441 -0.655445 +0.754588 -0.031441 -0.655445 +0.669688 -0.027904 -0.742118 +0.754588 -0.031441 -0.655445 +0.827376 -0.034474 -0.560589 +0.754588 -0.031441 -0.655445 +0.827376 -0.034474 -0.560589 +0.827376 -0.034474 -0.560589 +0.754588 -0.031441 -0.655445 +0.827376 -0.034474 -0.560589 +0.887149 -0.036965 -0.460000 +0.827376 -0.034474 -0.560589 +0.887149 -0.036965 -0.460000 +0.827376 -0.034474 -0.560589 +0.887149 -0.036965 -0.460000 +0.131123 -0.005463 -0.991351 +0.245949 -0.010248 -0.969229 +0.131123 -0.005463 -0.991351 +0.245949 -0.010248 -0.969229 +0.245949 -0.010248 -0.969229 +0.131123 -0.005463 -0.991351 +0.245949 -0.010248 -0.969229 +0.359805 -0.014992 -0.932907 +0.245949 -0.010248 -0.969229 +0.359805 -0.014992 -0.932907 +0.359805 -0.014992 -0.932907 +0.245949 -0.010248 -0.969229 +0.359805 -0.014992 -0.932907 +0.470083 -0.019587 -0.882405 +0.359805 -0.014992 -0.932907 +0.470083 -0.019587 -0.882405 +0.470083 -0.019587 -0.882405 +0.359805 -0.014992 -0.932907 +0.470083 -0.019587 -0.882405 +0.574178 -0.023924 -0.818381 +0.470083 -0.019587 -0.882405 +0.574178 -0.023924 -0.818381 +0.574178 -0.023924 -0.818381 +0.470083 -0.019587 -0.882405 +0.574178 -0.023924 -0.818381 +0.669688 -0.027904 -0.742118 +0.574178 -0.023924 -0.818381 +0.669688 -0.027904 -0.742118 +0.669688 -0.027904 -0.742118 +0.574178 -0.023924 -0.818381 +0.669688 -0.027904 -0.742118 +0.754588 -0.031441 -0.655445 +0.669688 -0.027904 -0.742118 +0.754588 -0.031441 -0.655445 +0.754588 -0.031441 -0.655445 +0.669688 -0.027904 -0.742118 +0.754588 -0.031441 -0.655445 +0.827376 -0.034474 -0.560589 +0.754588 -0.031441 -0.655445 +0.827376 -0.034474 -0.560589 +0.827376 -0.034474 -0.560589 +0.754588 -0.031441 -0.655445 +0.827376 -0.034474 -0.560589 +0.887149 -0.036965 -0.460000 +0.827376 -0.034474 -0.560589 +0.887149 -0.036965 -0.460000 +0.827376 -0.034474 -0.560589 +0.887149 -0.036965 -0.460000 +0.131123 -0.005463 -0.991351 +0.245949 -0.010248 -0.969229 +0.131123 -0.005463 -0.991351 +0.245949 -0.010248 -0.969229 +0.245949 -0.010248 -0.969229 +0.131123 -0.005463 -0.991351 +0.245949 -0.010248 -0.969229 +0.359805 -0.014992 -0.932907 +0.245949 -0.010248 -0.969229 +0.359805 -0.014992 -0.932907 +0.359805 -0.014992 -0.932907 +0.245949 -0.010248 -0.969229 +0.359805 -0.014992 -0.932907 +0.470083 -0.019587 -0.882405 +0.359805 -0.014992 -0.932907 +0.470083 -0.019587 -0.882405 +0.470083 -0.019587 -0.882405 +0.359805 -0.014992 -0.932907 +0.470083 -0.019587 -0.882405 +0.574178 -0.023924 -0.818381 +0.470083 -0.019587 -0.882405 +0.574178 -0.023924 -0.818381 +0.574178 -0.023924 -0.818381 +0.470083 -0.019587 -0.882405 +0.574178 -0.023924 -0.818381 +0.669688 -0.027904 -0.742118 +0.574178 -0.023924 -0.818381 +0.669688 -0.027904 -0.742118 +0.669688 -0.027904 -0.742118 +0.574178 -0.023924 -0.818381 +0.669688 -0.027904 -0.742118 +0.754588 -0.031441 -0.655445 +0.669688 -0.027904 -0.742118 +0.754588 -0.031441 -0.655445 +0.754588 -0.031441 -0.655445 +0.669688 -0.027904 -0.742118 +0.754588 -0.031441 -0.655445 +0.827376 -0.034474 -0.560589 +0.754588 -0.031441 -0.655445 +0.827376 -0.034474 -0.560589 +0.827376 -0.034474 -0.560589 +0.754588 -0.031441 -0.655445 +0.827376 -0.034474 -0.560589 +0.887149 -0.036965 -0.460000 +0.827376 -0.034474 -0.560589 +-0.827376 -0.034474 -0.560589 +-0.887149 -0.036965 -0.460000 +-0.887149 -0.036965 -0.460000 +-0.245949 -0.010248 -0.969229 +-0.131123 -0.005463 -0.991351 +-0.131123 -0.005463 -0.991351 +-0.245949 -0.010248 -0.969229 +-0.245949 -0.010248 -0.969229 +-0.131123 -0.005463 -0.991351 +-0.359805 -0.014992 -0.932907 +-0.245949 -0.010248 -0.969229 +-0.245949 -0.010248 -0.969229 +-0.359805 -0.014992 -0.932907 +-0.359805 -0.014992 -0.932907 +-0.245949 -0.010248 -0.969229 +-0.470083 -0.019587 -0.882405 +-0.359805 -0.014992 -0.932907 +-0.359805 -0.014992 -0.932907 +-0.470083 -0.019587 -0.882405 +-0.470083 -0.019587 -0.882405 +-0.359805 -0.014992 -0.932907 +-0.574178 -0.023924 -0.818381 +-0.470083 -0.019587 -0.882405 +-0.470083 -0.019587 -0.882405 +-0.574178 -0.023924 -0.818381 +-0.574178 -0.023924 -0.818381 +-0.470083 -0.019587 -0.882405 +-0.669688 -0.027904 -0.742118 +-0.574178 -0.023924 -0.818381 +-0.574178 -0.023924 -0.818381 +-0.669688 -0.027904 -0.742118 +-0.669688 -0.027904 -0.742118 +-0.574178 -0.023924 -0.818381 +-0.754588 -0.031441 -0.655445 +-0.669688 -0.027904 -0.742118 +-0.669688 -0.027904 -0.742118 +-0.754588 -0.031441 -0.655445 +-0.754588 -0.031441 -0.655445 +-0.669688 -0.027904 -0.742118 +-0.827376 -0.034474 -0.560589 +-0.754588 -0.031441 -0.655445 +-0.754588 -0.031441 -0.655445 +-0.827376 -0.034474 -0.560589 +-0.827376 -0.034474 -0.560589 +-0.754588 -0.031441 -0.655445 +-0.887149 -0.036965 -0.460000 +-0.827376 -0.034474 -0.560589 +-0.827376 -0.034474 -0.560589 +-0.827376 -0.034474 -0.560589 +-0.887149 -0.036965 -0.460000 +-0.887149 -0.036965 -0.460000 +-0.245949 -0.010248 -0.969229 +-0.131123 -0.005463 -0.991351 +-0.131123 -0.005463 -0.991351 +-0.245949 -0.010248 -0.969229 +-0.245949 -0.010248 -0.969229 +-0.131123 -0.005463 -0.991351 +-0.359805 -0.014992 -0.932907 +-0.245949 -0.010248 -0.969229 +-0.245949 -0.010248 -0.969229 +-0.359805 -0.014992 -0.932907 +-0.359805 -0.014992 -0.932907 +-0.245949 -0.010248 -0.969229 +-0.470083 -0.019587 -0.882405 +-0.359805 -0.014992 -0.932907 +-0.359805 -0.014992 -0.932907 +-0.470083 -0.019587 -0.882405 +-0.470083 -0.019587 -0.882405 +-0.359805 -0.014992 -0.932907 +-0.574178 -0.023924 -0.818381 +-0.470083 -0.019587 -0.882405 +-0.470083 -0.019587 -0.882405 +-0.574178 -0.023924 -0.818381 +-0.574178 -0.023924 -0.818381 +-0.470083 -0.019587 -0.882405 +-0.669688 -0.027904 -0.742118 +-0.574178 -0.023924 -0.818381 +-0.574178 -0.023924 -0.818381 +-0.669688 -0.027904 -0.742118 +-0.669688 -0.027904 -0.742118 +-0.574178 -0.023924 -0.818381 +-0.754588 -0.031441 -0.655445 +-0.669688 -0.027904 -0.742118 +-0.669688 -0.027904 -0.742118 +-0.754588 -0.031441 -0.655445 +-0.754588 -0.031441 -0.655445 +-0.669688 -0.027904 -0.742118 +-0.827376 -0.034474 -0.560589 +-0.754588 -0.031441 -0.655445 +-0.754588 -0.031441 -0.655445 +-0.827376 -0.034474 -0.560589 +-0.827376 -0.034474 -0.560589 +-0.754588 -0.031441 -0.655445 +-0.887149 -0.036965 -0.460000 +-0.827376 -0.034474 -0.560589 +-0.827376 -0.034474 -0.560589 +-0.827376 -0.034474 -0.560589 +-0.887149 -0.036965 -0.460000 +-0.887149 -0.036965 -0.460000 +-0.245949 -0.010248 -0.969229 +-0.131123 -0.005463 -0.991351 +-0.131123 -0.005463 -0.991351 +-0.245949 -0.010248 -0.969229 +-0.245949 -0.010248 -0.969229 +-0.131123 -0.005463 -0.991351 +-0.359805 -0.014992 -0.932907 +-0.245949 -0.010248 -0.969229 +-0.245949 -0.010248 -0.969229 +-0.359805 -0.014992 -0.932907 +-0.359805 -0.014992 -0.932907 +-0.245949 -0.010248 -0.969229 +-0.470083 -0.019587 -0.882405 +-0.359805 -0.014992 -0.932907 +-0.359805 -0.014992 -0.932907 +-0.470083 -0.019587 -0.882405 +-0.470083 -0.019587 -0.882405 +-0.359805 -0.014992 -0.932907 +-0.574178 -0.023924 -0.818381 +-0.470083 -0.019587 -0.882405 +-0.470083 -0.019587 -0.882405 +-0.574178 -0.023924 -0.818381 +-0.574178 -0.023924 -0.818381 +-0.470083 -0.019587 -0.882405 +-0.669688 -0.027904 -0.742118 +-0.574178 -0.023924 -0.818381 +-0.574178 -0.023924 -0.818381 +-0.669688 -0.027904 -0.742118 +-0.669688 -0.027904 -0.742118 +-0.574178 -0.023924 -0.818381 +-0.754588 -0.031441 -0.655445 +-0.669688 -0.027904 -0.742118 +-0.669688 -0.027904 -0.742118 +-0.754588 -0.031441 -0.655445 +-0.754588 -0.031441 -0.655445 +-0.669688 -0.027904 -0.742118 +-0.827376 -0.034474 -0.560589 +-0.754588 -0.031441 -0.655445 +-0.754588 -0.031441 -0.655445 +-0.827376 -0.034474 -0.560589 +-0.827376 -0.034474 -0.560589 +-0.754588 -0.031441 -0.655445 +-0.887149 -0.036965 -0.460000 +-0.827376 -0.034474 -0.560589 +-0.827376 -0.034474 -0.560589 +-0.827376 -0.034474 -0.560589 +-0.887149 -0.036965 -0.460000 +-0.887149 -0.036965 -0.460000 +-0.245949 -0.010248 -0.969229 +-0.131123 -0.005463 -0.991351 +-0.131123 -0.005463 -0.991351 +-0.245949 -0.010248 -0.969229 +-0.245949 -0.010248 -0.969229 +-0.131123 -0.005463 -0.991351 +-0.359805 -0.014992 -0.932907 +-0.245949 -0.010248 -0.969229 +-0.245949 -0.010248 -0.969229 +-0.359805 -0.014992 -0.932907 +-0.359805 -0.014992 -0.932907 +-0.245949 -0.010248 -0.969229 +-0.470083 -0.019587 -0.882405 +-0.359805 -0.014992 -0.932907 +-0.359805 -0.014992 -0.932907 +-0.470083 -0.019587 -0.882405 +-0.470083 -0.019587 -0.882405 +-0.359805 -0.014992 -0.932907 +-0.574178 -0.023924 -0.818381 +-0.470083 -0.019587 -0.882405 +-0.470083 -0.019587 -0.882405 +-0.574178 -0.023924 -0.818381 +-0.574178 -0.023924 -0.818381 +-0.470083 -0.019587 -0.882405 +-0.669688 -0.027904 -0.742118 +-0.574178 -0.023924 -0.818381 +-0.574178 -0.023924 -0.818381 +-0.669688 -0.027904 -0.742118 +-0.669688 -0.027904 -0.742118 +-0.574178 -0.023924 -0.818381 +-0.754588 -0.031441 -0.655445 +-0.669688 -0.027904 -0.742118 +-0.669688 -0.027904 -0.742118 +-0.754588 -0.031441 -0.655445 +-0.754588 -0.031441 -0.655445 +-0.669688 -0.027904 -0.742118 +-0.827376 -0.034474 -0.560589 +-0.754588 -0.031441 -0.655445 +-0.754588 -0.031441 -0.655445 +-0.827376 -0.034474 -0.560589 +-0.827376 -0.034474 -0.560589 +-0.754588 -0.031441 -0.655445 +-0.887149 -0.036965 -0.460000 +-0.827376 -0.034474 -0.560589 +-0.827376 -0.034474 -0.560589 +-0.827376 -0.034474 -0.560589 +-0.887149 -0.036965 -0.460000 +-0.887149 -0.036965 -0.460000 +-0.245949 -0.010248 -0.969229 +-0.131123 -0.005463 -0.991351 +-0.131123 -0.005463 -0.991351 +-0.245949 -0.010248 -0.969229 +-0.245949 -0.010248 -0.969229 +-0.131123 -0.005463 -0.991351 +-0.359805 -0.014992 -0.932907 +-0.245949 -0.010248 -0.969229 +-0.245949 -0.010248 -0.969229 +-0.359805 -0.014992 -0.932907 +-0.359805 -0.014992 -0.932907 +-0.245949 -0.010248 -0.969229 +-0.470083 -0.019587 -0.882405 +-0.359805 -0.014992 -0.932907 +-0.359805 -0.014992 -0.932907 +-0.470083 -0.019587 -0.882405 +-0.470083 -0.019587 -0.882405 +-0.359805 -0.014992 -0.932907 +-0.574178 -0.023924 -0.818381 +-0.470083 -0.019587 -0.882405 +-0.470083 -0.019587 -0.882405 +-0.574178 -0.023924 -0.818381 +-0.574178 -0.023924 -0.818381 +-0.470083 -0.019587 -0.882405 +-0.669688 -0.027904 -0.742118 +-0.574178 -0.023924 -0.818381 +-0.574178 -0.023924 -0.818381 +-0.669688 -0.027904 -0.742118 +-0.669688 -0.027904 -0.742118 +-0.574178 -0.023924 -0.818381 +-0.754588 -0.031441 -0.655445 +-0.669688 -0.027904 -0.742118 +-0.669688 -0.027904 -0.742118 +-0.754588 -0.031441 -0.655445 +-0.754588 -0.031441 -0.655445 +-0.669688 -0.027904 -0.742118 +-0.827376 -0.034474 -0.560589 +-0.754588 -0.031441 -0.655445 +-0.754588 -0.031441 -0.655445 +-0.827376 -0.034474 -0.560589 +-0.827376 -0.034474 -0.560589 +-0.754588 -0.031441 -0.655445 +-0.887149 -0.036965 -0.460000 +-0.827376 -0.034474 -0.560589 +-0.827376 -0.034474 -0.560589 +-0.827376 -0.034474 -0.560589 +-0.887149 -0.036965 -0.460000 +-0.887149 -0.036965 -0.460000 +-0.245949 -0.010248 -0.969229 +-0.131123 -0.005463 -0.991351 +-0.131123 -0.005463 -0.991351 +-0.245949 -0.010248 -0.969229 +-0.245949 -0.010248 -0.969229 +-0.131123 -0.005463 -0.991351 +-0.359805 -0.014992 -0.932907 +-0.245949 -0.010248 -0.969229 +-0.245949 -0.010248 -0.969229 +-0.359805 -0.014992 -0.932907 +-0.359805 -0.014992 -0.932907 +-0.245949 -0.010248 -0.969229 +-0.470083 -0.019587 -0.882405 +-0.359805 -0.014992 -0.932907 +-0.359805 -0.014992 -0.932907 +-0.470083 -0.019587 -0.882405 +-0.470083 -0.019587 -0.882405 +-0.359805 -0.014992 -0.932907 +-0.574178 -0.023924 -0.818381 +-0.470083 -0.019587 -0.882405 +-0.470083 -0.019587 -0.882405 +-0.574178 -0.023924 -0.818381 +-0.574178 -0.023924 -0.818381 +-0.470083 -0.019587 -0.882405 +-0.669688 -0.027904 -0.742118 +-0.574178 -0.023924 -0.818381 +-0.574178 -0.023924 -0.818381 +-0.669688 -0.027904 -0.742118 +-0.669688 -0.027904 -0.742118 +-0.574178 -0.023924 -0.818381 +-0.754588 -0.031441 -0.655445 +-0.669688 -0.027904 -0.742118 +-0.669688 -0.027904 -0.742118 +-0.754588 -0.031441 -0.655445 +-0.754588 -0.031441 -0.655445 +-0.669688 -0.027904 -0.742118 +-0.827376 -0.034474 -0.560589 +-0.754588 -0.031441 -0.655445 +-0.754588 -0.031441 -0.655445 +-0.827376 -0.034474 -0.560589 +-0.827376 -0.034474 -0.560589 +-0.754588 -0.031441 -0.655445 +-0.887149 -0.036965 -0.460000 +-0.827376 -0.034474 -0.560589 +-0.827376 -0.034474 -0.560589 +-0.827376 -0.034474 -0.560589 +-0.887149 -0.036965 -0.460000 +-0.887149 -0.036965 -0.460000 +-0.245949 -0.010248 -0.969229 +-0.131123 -0.005463 -0.991351 +-0.131123 -0.005463 -0.991351 +-0.245949 -0.010248 -0.969229 +-0.245949 -0.010248 -0.969229 +-0.131123 -0.005463 -0.991351 +-0.359805 -0.014992 -0.932907 +-0.245949 -0.010248 -0.969229 +-0.245949 -0.010248 -0.969229 +-0.359805 -0.014992 -0.932907 +-0.359805 -0.014992 -0.932907 +-0.245949 -0.010248 -0.969229 +-0.470083 -0.019587 -0.882405 +-0.359805 -0.014992 -0.932907 +-0.359805 -0.014992 -0.932907 +-0.470083 -0.019587 -0.882405 +-0.470083 -0.019587 -0.882405 +-0.359805 -0.014992 -0.932907 +-0.574178 -0.023924 -0.818381 +-0.470083 -0.019587 -0.882405 +-0.470083 -0.019587 -0.882405 +-0.574178 -0.023924 -0.818381 +-0.574178 -0.023924 -0.818381 +-0.470083 -0.019587 -0.882405 +-0.669688 -0.027904 -0.742118 +-0.574178 -0.023924 -0.818381 +-0.574178 -0.023924 -0.818381 +-0.669688 -0.027904 -0.742118 +-0.669688 -0.027904 -0.742118 +-0.574178 -0.023924 -0.818381 +-0.754588 -0.031441 -0.655445 +-0.669688 -0.027904 -0.742118 +-0.669688 -0.027904 -0.742118 +-0.754588 -0.031441 -0.655445 +-0.754588 -0.031441 -0.655445 +-0.669688 -0.027904 -0.742118 +-0.827376 -0.034474 -0.560589 +-0.754588 -0.031441 -0.655445 +-0.754588 -0.031441 -0.655445 +-0.827376 -0.034474 -0.560589 +-0.827376 -0.034474 -0.560589 +-0.754588 -0.031441 -0.655445 +-0.887149 -0.036965 -0.460000 +-0.827376 -0.034474 -0.560589 +-0.827376 -0.034474 -0.560589 +-0.827376 -0.034474 -0.560589 +-0.887149 -0.036965 -0.460000 +-0.887149 -0.036965 -0.460000 +-0.245949 -0.010248 -0.969229 +-0.131123 -0.005463 -0.991351 +-0.131123 -0.005463 -0.991351 +-0.245949 -0.010248 -0.969229 +-0.245949 -0.010248 -0.969229 +-0.131123 -0.005463 -0.991351 +-0.359805 -0.014992 -0.932907 +-0.245949 -0.010248 -0.969229 +-0.245949 -0.010248 -0.969229 +-0.359805 -0.014992 -0.932907 +-0.359805 -0.014992 -0.932907 +-0.245949 -0.010248 -0.969229 +-0.470083 -0.019587 -0.882405 +-0.359805 -0.014992 -0.932907 +-0.359805 -0.014992 -0.932907 +-0.470083 -0.019587 -0.882405 +-0.470083 -0.019587 -0.882405 +-0.359805 -0.014992 -0.932907 +-0.574178 -0.023924 -0.818381 +-0.470083 -0.019587 -0.882405 +-0.470083 -0.019587 -0.882405 +-0.574178 -0.023924 -0.818381 +-0.574178 -0.023924 -0.818381 +-0.470083 -0.019587 -0.882405 +-0.669688 -0.027904 -0.742118 +-0.574178 -0.023924 -0.818381 +-0.574178 -0.023924 -0.818381 +-0.669688 -0.027904 -0.742118 +-0.669688 -0.027904 -0.742118 +-0.574178 -0.023924 -0.818381 +-0.754588 -0.031441 -0.655445 +-0.669688 -0.027904 -0.742118 +-0.669688 -0.027904 -0.742118 +-0.754588 -0.031441 -0.655445 +-0.754588 -0.031441 -0.655445 +-0.669688 -0.027904 -0.742118 +-0.827376 -0.034474 -0.560589 +-0.754588 -0.031441 -0.655445 +-0.754588 -0.031441 -0.655445 +-0.827376 -0.034474 -0.560589 +-0.827376 -0.034474 -0.560589 +-0.754588 -0.031441 -0.655445 +-0.887149 -0.036965 -0.460000 +-0.827376 -0.034474 -0.560589 +-0.827376 -0.034474 -0.560589 +-0.827376 -0.034474 -0.560589 +-0.887149 -0.036965 -0.460000 +-0.887149 -0.036965 -0.460000 +-0.245949 -0.010248 -0.969229 +-0.131123 -0.005463 -0.991351 +-0.131123 -0.005463 -0.991351 +-0.245949 -0.010248 -0.969229 +-0.245949 -0.010248 -0.969229 +-0.131123 -0.005463 -0.991351 +-0.359805 -0.014992 -0.932907 +-0.245949 -0.010248 -0.969229 +-0.245949 -0.010248 -0.969229 +-0.359805 -0.014992 -0.932907 +-0.359805 -0.014992 -0.932907 +-0.245949 -0.010248 -0.969229 +-0.470083 -0.019587 -0.882405 +-0.359805 -0.014992 -0.932907 +-0.359805 -0.014992 -0.932907 +-0.470083 -0.019587 -0.882405 +-0.470083 -0.019587 -0.882405 +-0.359805 -0.014992 -0.932907 +-0.574178 -0.023924 -0.818381 +-0.470083 -0.019587 -0.882405 +-0.470083 -0.019587 -0.882405 +-0.574178 -0.023924 -0.818381 +-0.574178 -0.023924 -0.818381 +-0.470083 -0.019587 -0.882405 +-0.669688 -0.027904 -0.742118 +-0.574178 -0.023924 -0.818381 +-0.574178 -0.023924 -0.818381 +-0.669688 -0.027904 -0.742118 +-0.669688 -0.027904 -0.742118 +-0.574178 -0.023924 -0.818381 +-0.754588 -0.031441 -0.655445 +-0.669688 -0.027904 -0.742118 +-0.669688 -0.027904 -0.742118 +-0.754588 -0.031441 -0.655445 +-0.754588 -0.031441 -0.655445 +-0.669688 -0.027904 -0.742118 +-0.827376 -0.034474 -0.560589 +-0.754588 -0.031441 -0.655445 +-0.754588 -0.031441 -0.655445 +-0.827376 -0.034474 -0.560589 +-0.827376 -0.034474 -0.560589 +-0.754588 -0.031441 -0.655445 +-0.887149 -0.036965 -0.460000 +-0.827376 -0.034474 -0.560589 +-0.827376 -0.034474 -0.560589 +-0.999133 0.041631 0.000000 +-0.996658 0.041452 -0.070391 +-0.999133 0.041631 0.000000 +-0.027653 0.000000 -0.999618 +-0.255221 0.007847 -0.966851 +-0.069320 0.000000 -0.997594 +-0.201674 0.007287 -0.979426 +-0.255221 0.007847 -0.966851 +-0.027653 0.000000 -0.999618 +-0.368464 0.014304 -0.929532 +-0.255221 0.007847 -0.966851 +-0.201674 0.007287 -0.979426 +-0.368464 0.014304 -0.929532 +-0.430369 0.015341 -0.902523 +-0.255221 0.007847 -0.966851 +-0.524802 0.020917 -0.850967 +-0.430369 0.015341 -0.902523 +-0.368464 0.014304 -0.929532 +-0.524802 0.020917 -0.850967 +-0.591341 0.022335 -0.806112 +-0.430369 0.015341 -0.902523 +-0.664520 0.026862 -0.746787 +-0.591341 0.022335 -0.806112 +-0.524802 0.020917 -0.850967 +-0.664520 0.026862 -0.746787 +-0.730695 0.028502 -0.682108 +-0.591341 0.022335 -0.806112 +-0.784430 0.032005 -0.619391 +-0.730695 0.028502 -0.682108 +-0.664520 0.026862 -0.746787 +-0.784430 0.032005 -0.619391 +-0.845229 0.033703 -0.533340 +-0.730695 0.028502 -0.682108 +-0.880095 0.036155 -0.473420 +-0.845229 0.033703 -0.533340 +-0.784430 0.032005 -0.619391 +-0.880095 0.036155 -0.473420 +-0.929577 0.037693 -0.366696 +-0.845229 0.033703 -0.533340 +-0.949050 0.039205 -0.312679 +-0.929577 0.037693 -0.366696 +-0.880095 0.036155 -0.473420 +-0.949050 0.039205 -0.312679 +-0.981640 0.040374 -0.186423 +-0.929577 0.037693 -0.366696 +-0.988940 0.041052 -0.142521 +-0.981640 0.040374 -0.186423 +-0.949050 0.039205 -0.312679 +-0.988940 0.041052 -0.142521 +-0.999133 0.041631 0.000000 +-0.981640 0.040374 -0.186423 +-0.996658 0.041452 -0.070391 +-0.999133 0.041631 0.000000 +-0.988940 0.041052 -0.142521 +0.000000 0.000000 -1.000000 +-0.181805 0.007575 -0.983305 +0.000000 0.000000 -1.000000 +-0.982453 0.040936 -0.181963 +-0.999133 0.041631 0.000000 +-0.999133 0.041631 0.000000 +-0.982453 0.040936 -0.181963 +-0.982453 0.040936 -0.181963 +-0.999133 0.041631 0.000000 +-0.982453 0.040936 -0.181963 +-0.928982 0.038708 -0.368095 +-0.982453 0.040936 -0.181963 +-0.928982 0.038708 -0.368095 +-0.928982 0.038708 -0.368095 +-0.982453 0.040936 -0.181963 +-0.928982 0.038708 -0.368095 +-0.836270 0.034845 -0.547210 +-0.928982 0.038708 -0.368095 +-0.836270 0.034845 -0.547210 +-0.836270 0.034845 -0.547210 +-0.928982 0.038708 -0.368095 +-0.836270 0.034845 -0.547210 +-0.775680 0.032320 -0.630298 +-0.836270 0.034845 -0.547210 +-0.775680 0.032320 -0.630298 +-0.775680 0.032320 -0.630298 +-0.836270 0.034845 -0.547210 +-0.775680 0.032320 -0.630298 +-0.706494 0.029437 -0.707107 +-0.775680 0.032320 -0.630298 +-0.706494 0.029437 -0.707107 +-0.706494 0.029437 -0.707107 +-0.775680 0.032320 -0.630298 +-0.706494 0.029437 -0.707107 +-0.629752 0.026240 -0.776353 +-0.706494 0.029437 -0.707107 +-0.629752 0.026240 -0.776353 +-0.629752 0.026240 -0.776353 +-0.706494 0.029437 -0.707107 +-0.629752 0.026240 -0.776353 +-0.546735 0.022781 -0.836995 +-0.629752 0.026240 -0.776353 +-0.546735 0.022781 -0.836995 +-0.546735 0.022781 -0.836995 +-0.629752 0.026240 -0.776353 +-0.546735 0.022781 -0.836995 +-0.367776 0.015324 -0.929788 +-0.546735 0.022781 -0.836995 +-0.367776 0.015324 -0.929788 +-0.367776 0.015324 -0.929788 +-0.546735 0.022781 -0.836995 +-0.367776 0.015324 -0.929788 +-0.181805 0.007575 -0.983305 +-0.367776 0.015324 -0.929788 +-0.181805 0.007575 -0.983305 +-0.181805 0.007575 -0.983305 +-0.367776 0.015324 -0.929788 +-0.181805 0.007575 -0.983305 +0.000000 0.000000 -1.000000 +-0.181805 0.007575 -0.983305 +-0.992369 0.041349 0.116161 +-0.999133 0.041631 0.000000 +-0.999133 0.041631 0.000000 +-0.982453 0.040936 0.181963 +-0.999133 0.041631 0.000000 +-0.999133 0.041631 0.000000 +-0.982453 0.040936 0.181963 +-0.988666 0.041194 0.144370 +-0.999133 0.041631 0.000000 +-0.982453 0.040936 0.181963 +-0.957484 0.039895 0.285714 +-0.988666 0.041194 0.144370 +-0.928982 0.038708 0.368095 +-0.957484 0.039895 0.285714 +-0.982453 0.040936 0.181963 +-0.181805 0.007575 0.983305 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.181805 0.007575 0.983305 +-0.181805 0.007575 0.983305 +0.000000 0.000000 1.000000 +-0.367776 0.015324 0.929788 +-0.181805 0.007575 0.983305 +-0.181805 0.007575 0.983305 +-0.367776 0.015324 0.929788 +-0.367776 0.015324 0.929788 +-0.181805 0.007575 0.983305 +-0.546735 0.022781 0.836995 +-0.367776 0.015324 0.929788 +-0.367776 0.015324 0.929788 +-0.546735 0.022781 0.836995 +-0.546735 0.022781 0.836995 +-0.367776 0.015324 0.929788 +-0.629752 0.026240 0.776353 +-0.546735 0.022781 0.836995 +-0.546735 0.022781 0.836995 +-0.629752 0.026240 0.776353 +-0.629752 0.026240 0.776353 +-0.546735 0.022781 0.836995 +-0.706494 0.029437 0.707107 +-0.629752 0.026240 0.776353 +-0.629752 0.026240 0.776353 +-0.706494 0.029437 0.707107 +-0.706494 0.029437 0.707107 +-0.629752 0.026240 0.776353 +-0.775680 0.032320 0.630298 +-0.706494 0.029437 0.707107 +-0.706494 0.029437 0.707107 +-0.775680 0.032320 0.630298 +-0.775680 0.032320 0.630298 +-0.706494 0.029437 0.707107 +-0.836270 0.034845 0.547210 +-0.775680 0.032320 0.630298 +-0.775680 0.032320 0.630298 +-0.836270 0.034845 0.547210 +-0.836270 0.034845 0.547210 +-0.775680 0.032320 0.630298 +-0.928982 0.038708 0.368095 +-0.836270 0.034845 0.547210 +-0.836270 0.034845 0.547210 +-0.928982 0.038708 0.368095 +-0.928982 0.038708 0.368095 +-0.836270 0.034845 0.547210 +-0.928982 0.038708 0.368095 +-0.957484 0.039895 0.285714 +-0.928982 0.038708 0.368095 +-0.928982 0.038708 0.368095 +-0.957484 0.039895 0.285714 +-0.957484 0.039895 0.285714 +-0.982453 0.040936 0.181963 +-0.957484 0.039895 0.285714 +-0.928982 0.038708 0.368095 +-0.982453 0.040936 0.181963 +-0.963253 0.040136 0.265582 +-0.957484 0.039895 0.285714 +-0.982453 0.040936 0.181963 +-0.977451 0.040727 0.207199 +-0.963253 0.040136 0.265582 +-0.982453 0.040936 0.181963 +-0.992369 0.041349 0.116161 +-0.977451 0.040727 0.207199 +-0.999133 0.041631 0.000000 +-0.992369 0.041349 0.116161 +-0.982453 0.040936 0.181963 +0.069320 0.000000 -0.997594 +0.200991 0.007258 -0.979566 +0.027653 0.000000 -0.999618 +0.996658 0.041452 -0.070391 +0.999133 0.041631 0.000000 +0.999133 0.041631 0.000000 +0.996658 0.041452 -0.070391 +0.981640 0.040374 -0.186423 +0.999133 0.041631 0.000000 +0.988940 0.041052 -0.142521 +0.981640 0.040374 -0.186423 +0.996658 0.041452 -0.070391 +0.948834 0.039195 -0.313332 +0.981640 0.040374 -0.186423 +0.988940 0.041052 -0.142521 +0.948834 0.039195 -0.313332 +0.929577 0.037693 -0.366696 +0.981640 0.040374 -0.186423 +0.880040 0.036152 -0.473521 +0.929577 0.037693 -0.366696 +0.948834 0.039195 -0.313332 +0.880040 0.036152 -0.473521 +0.845229 0.033703 -0.533340 +0.929577 0.037693 -0.366696 +0.783997 0.031986 -0.619939 +0.845229 0.033703 -0.533340 +0.880040 0.036152 -0.473521 +0.783997 0.031986 -0.619939 +0.730695 0.028502 -0.682108 +0.845229 0.033703 -0.533340 +0.664452 0.026859 -0.746848 +0.730695 0.028502 -0.682108 +0.783997 0.031986 -0.619939 +0.664452 0.026859 -0.746848 +0.591341 0.022335 -0.806112 +0.730695 0.028502 -0.682108 +0.524206 0.020892 -0.851335 +0.591341 0.022335 -0.806112 +0.664452 0.026859 -0.746848 +0.524206 0.020892 -0.851335 +0.430369 0.015341 -0.902523 +0.591341 0.022335 -0.806112 +0.368358 0.014300 -0.929574 +0.430369 0.015341 -0.902523 +0.524206 0.020892 -0.851335 +0.368358 0.014300 -0.929574 +0.255221 0.007847 -0.966851 +0.430369 0.015341 -0.902523 +0.200991 0.007258 -0.979566 +0.255221 0.007847 -0.966851 +0.368358 0.014300 -0.929574 +0.200991 0.007258 -0.979566 +0.069320 0.000000 -0.997594 +0.255221 0.007847 -0.966851 +0.181805 0.007575 -0.983305 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.982453 0.040936 -0.181963 +0.999133 0.041631 0.000000 +0.999133 0.041631 0.000000 +0.982453 0.040936 -0.181963 +0.982453 0.040936 -0.181963 +0.999133 0.041631 0.000000 +0.928982 0.038708 -0.368095 +0.982453 0.040936 -0.181963 +0.982453 0.040936 -0.181963 +0.928982 0.038708 -0.368095 +0.928982 0.038708 -0.368095 +0.982453 0.040936 -0.181963 +0.836270 0.034845 -0.547210 +0.928982 0.038708 -0.368095 +0.928982 0.038708 -0.368095 +0.836270 0.034845 -0.547210 +0.836270 0.034845 -0.547210 +0.928982 0.038708 -0.368095 +0.775680 0.032320 -0.630298 +0.836270 0.034845 -0.547210 +0.836270 0.034845 -0.547210 +0.775680 0.032320 -0.630298 +0.775680 0.032320 -0.630298 +0.836270 0.034845 -0.547210 +0.706494 0.029437 -0.707107 +0.775680 0.032320 -0.630298 +0.775680 0.032320 -0.630298 +0.706494 0.029437 -0.707107 +0.706494 0.029437 -0.707107 +0.775680 0.032320 -0.630298 +0.629752 0.026240 -0.776353 +0.706494 0.029437 -0.707107 +0.706494 0.029437 -0.707107 +0.629752 0.026240 -0.776353 +0.629752 0.026240 -0.776353 +0.706494 0.029437 -0.707107 +0.546735 0.022781 -0.836995 +0.629752 0.026240 -0.776353 +0.629752 0.026240 -0.776353 +0.546735 0.022781 -0.836995 +0.546735 0.022781 -0.836995 +0.629752 0.026240 -0.776353 +0.367776 0.015324 -0.929788 +0.546735 0.022781 -0.836995 +0.546735 0.022781 -0.836995 +0.367776 0.015324 -0.929788 +0.367776 0.015324 -0.929788 +0.546735 0.022781 -0.836995 +0.181805 0.007575 -0.983305 +0.367776 0.015324 -0.929788 +0.367776 0.015324 -0.929788 +0.181805 0.007575 -0.983305 +0.181805 0.007575 -0.983305 +0.367776 0.015324 -0.929788 +0.000000 0.000000 -1.000000 +0.181805 0.007575 -0.983305 +0.181805 0.007575 -0.983305 +0.999133 0.041631 0.000000 +0.992432 0.041351 0.115624 +0.999133 0.041631 0.000000 +0.999133 0.041631 0.000000 +0.982453 0.040936 0.181963 +0.999133 0.041631 0.000000 +0.988666 0.041194 0.144370 +0.982453 0.040936 0.181963 +0.999133 0.041631 0.000000 +0.957484 0.039895 0.285714 +0.982453 0.040936 0.181963 +0.988666 0.041194 0.144370 +0.957484 0.039895 0.285714 +0.928982 0.038708 0.368095 +0.982453 0.040936 0.181963 +0.000000 0.000000 1.000000 +0.181805 0.007575 0.983305 +0.000000 0.000000 1.000000 +0.181805 0.007575 0.983305 +0.181805 0.007575 0.983305 +0.000000 0.000000 1.000000 +0.181805 0.007575 0.983305 +0.367776 0.015324 0.929788 +0.181805 0.007575 0.983305 +0.367776 0.015324 0.929788 +0.367776 0.015324 0.929788 +0.181805 0.007575 0.983305 +0.367776 0.015324 0.929788 +0.546735 0.022781 0.836995 +0.367776 0.015324 0.929788 +0.546735 0.022781 0.836995 +0.546735 0.022781 0.836995 +0.367776 0.015324 0.929788 +0.546735 0.022781 0.836995 +0.629752 0.026240 0.776353 +0.546735 0.022781 0.836995 +0.629752 0.026240 0.776353 +0.629752 0.026240 0.776353 +0.546735 0.022781 0.836995 +0.629752 0.026240 0.776353 +0.706494 0.029437 0.707107 +0.629752 0.026240 0.776353 +0.706494 0.029437 0.707107 +0.706494 0.029437 0.707107 +0.629752 0.026240 0.776353 +0.706494 0.029437 0.707107 +0.775680 0.032320 0.630298 +0.706494 0.029437 0.707107 +0.775680 0.032320 0.630298 +0.775680 0.032320 0.630298 +0.706494 0.029437 0.707107 +0.775680 0.032320 0.630298 +0.836270 0.034845 0.547210 +0.775680 0.032320 0.630298 +0.836270 0.034845 0.547210 +0.836270 0.034845 0.547210 +0.775680 0.032320 0.630298 +0.836270 0.034845 0.547210 +0.928982 0.038708 0.368095 +0.836270 0.034845 0.547210 +0.928982 0.038708 0.368095 +0.928982 0.038708 0.368095 +0.836270 0.034845 0.547210 +0.957484 0.039895 0.285714 +0.928982 0.038708 0.368095 +0.928982 0.038708 0.368095 +0.957484 0.039895 0.285714 +0.928982 0.038708 0.368095 +0.957484 0.039895 0.285714 +0.957484 0.039895 0.285714 +0.982453 0.040936 0.181963 +0.928982 0.038708 0.368095 +0.963311 0.040138 0.265369 +0.982453 0.040936 0.181963 +0.957484 0.039895 0.285714 +0.977528 0.040730 0.206833 +0.982453 0.040936 0.181963 +0.963311 0.040138 0.265369 +0.992432 0.041351 0.115624 +0.982453 0.040936 0.181963 +0.977528 0.040730 0.206833 +0.992432 0.041351 0.115624 +0.999133 0.041631 0.000000 +0.982453 0.040936 0.181963 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -0.993971 -0.109639 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -0.888915 -0.458072 +0.000000 -0.833333 -0.552771 +0.000000 -0.833333 -0.552771 +0.000000 -0.888915 -0.458072 +0.000000 -0.888915 -0.458072 +0.000000 -0.833333 -0.552771 +0.000000 -0.957427 -0.288675 +0.000000 -0.888915 -0.458072 +0.000000 -0.888915 -0.458072 +0.000000 -0.957427 -0.288675 +0.000000 -0.957427 -0.288675 +0.000000 -0.888915 -0.458072 +0.000000 -0.957427 -0.288675 +0.000000 -0.993971 -0.109639 +0.000000 -0.957427 -0.288675 +0.000000 -0.993971 -0.109639 +0.000000 -0.993971 -0.109639 +0.000000 -0.957427 -0.288675 +0.000000 -1.000000 0.000000 +0.000000 -0.993971 -0.109639 +0.000000 -0.993971 -0.109639 +0.000000 -0.993971 -0.109639 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.019950 -0.993971 -0.107809 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.040358 -0.993971 -0.101941 +0.000000 -1.000000 0.000000 +0.019950 -0.993971 -0.107809 +0.100584 -0.833333 -0.543543 +0.000000 -0.888915 -0.458072 +0.000000 -0.833333 -0.552771 +0.059996 -0.993971 -0.091768 +0.000000 -1.000000 0.000000 +0.040358 -0.993971 -0.101941 +0.059996 -0.993971 -0.091768 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.077527 -0.993971 -0.077527 +0.000000 -1.000000 0.000000 +0.059996 -0.993971 -0.091768 +0.077527 -0.993971 -0.077527 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.091768 -0.993971 -0.059996 +0.000000 -1.000000 0.000000 +0.077527 -0.993971 -0.077527 +0.091768 -0.993971 -0.059996 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.101941 -0.993971 -0.040358 +0.000000 -1.000000 0.000000 +0.091768 -0.993971 -0.059996 +0.101941 -0.993971 -0.040358 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.107809 -0.993971 -0.019950 +0.000000 -1.000000 0.000000 +0.101941 -0.993971 -0.040358 +0.107809 -0.993971 -0.019950 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.109639 -0.993971 0.000000 +0.000000 -1.000000 0.000000 +0.107809 -0.993971 -0.019950 +0.109639 -0.993971 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.107809 -0.993971 0.019950 +0.000000 -1.000000 0.000000 +0.109639 -0.993971 0.000000 +0.107809 -0.993971 0.019950 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.101941 -0.993971 0.040358 +0.000000 -1.000000 0.000000 +0.107809 -0.993971 0.019950 +0.101941 -0.993971 0.040358 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.091768 -0.993971 0.059996 +0.000000 -1.000000 0.000000 +0.101941 -0.993971 0.040358 +0.091768 -0.993971 0.059996 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.077527 -0.993971 0.077527 +0.000000 -1.000000 0.000000 +0.091768 -0.993971 0.059996 +0.077527 -0.993971 0.077527 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.059996 -0.993971 0.091768 +0.000000 -1.000000 0.000000 +0.077527 -0.993971 0.077527 +0.059996 -0.993971 0.091768 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.059996 -0.993971 0.091768 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.040358 -0.993971 0.101941 +0.000000 -1.000000 0.000000 +0.059996 -0.993971 0.091768 +0.040358 -0.993971 0.101941 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.019950 -0.993971 0.107809 +0.000000 -1.000000 0.000000 +0.040358 -0.993971 0.101941 +0.019950 -0.993971 0.107809 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.019950 -0.993971 0.107809 +0.000000 -0.993971 0.109639 +0.000000 -1.000000 0.000000 +0.019950 -0.993971 0.107809 +0.000000 -0.957427 0.288675 +0.000000 -0.993971 0.109639 +0.052528 -0.957427 0.283856 +0.000000 -0.957427 0.288675 +0.019950 -0.993971 0.107809 +0.052528 -0.957427 0.283856 +0.000000 -0.888915 0.458072 +0.000000 -0.957427 0.288675 +0.083352 -0.888915 0.450425 +0.000000 -0.888915 0.458072 +0.052528 -0.957427 0.283856 +0.083352 -0.888915 0.450425 +0.000000 -0.833333 0.552771 +0.000000 -0.888915 0.458072 +0.083352 -0.888915 0.450425 +0.100584 -0.833333 0.543543 +0.000000 -0.833333 0.552771 +0.168614 -0.888915 0.425910 +0.100584 -0.833333 0.543543 +0.083352 -0.888915 0.450425 +0.168614 -0.888915 0.425910 +0.203472 -0.833333 0.513960 +0.100584 -0.833333 0.543543 +0.250662 -0.888915 0.383404 +0.203472 -0.833333 0.513960 +0.168614 -0.888915 0.425910 +0.250662 -0.888915 0.383404 +0.302482 -0.833333 0.462667 +0.203472 -0.833333 0.513960 +0.323906 -0.888915 0.323906 +0.302482 -0.833333 0.462667 +0.250662 -0.888915 0.383404 +0.323906 -0.888915 0.323906 +0.390868 -0.833333 0.390868 +0.302482 -0.833333 0.462667 +0.383404 -0.888915 0.250662 +0.390868 -0.833333 0.390868 +0.323906 -0.888915 0.323906 +0.383404 -0.888915 0.250662 +0.462667 -0.833333 0.302482 +0.390868 -0.833333 0.390868 +0.425910 -0.888915 0.168614 +0.462667 -0.833333 0.302482 +0.383404 -0.888915 0.250662 +0.425910 -0.888915 0.168614 +0.513960 -0.833333 0.203472 +0.462667 -0.833333 0.302482 +0.450425 -0.888915 0.083352 +0.513960 -0.833333 0.203472 +0.425910 -0.888915 0.168614 +0.450425 -0.888915 0.083352 +0.543543 -0.833333 0.100584 +0.513960 -0.833333 0.203472 +0.458072 -0.888915 0.000000 +0.543543 -0.833333 0.100584 +0.450425 -0.888915 0.083352 +0.458072 -0.888915 0.000000 +0.552771 -0.833333 0.000000 +0.543543 -0.833333 0.100584 +0.450425 -0.888915 -0.083352 +0.552771 -0.833333 0.000000 +0.458072 -0.888915 0.000000 +0.450425 -0.888915 -0.083352 +0.543543 -0.833333 -0.100584 +0.552771 -0.833333 0.000000 +0.425910 -0.888915 -0.168614 +0.543543 -0.833333 -0.100584 +0.450425 -0.888915 -0.083352 +0.425910 -0.888915 -0.168614 +0.513960 -0.833333 -0.203472 +0.543543 -0.833333 -0.100584 +0.383404 -0.888915 -0.250662 +0.513960 -0.833333 -0.203472 +0.425910 -0.888915 -0.168614 +0.383404 -0.888915 -0.250662 +0.462667 -0.833333 -0.302482 +0.513960 -0.833333 -0.203472 +0.323906 -0.888915 -0.323906 +0.462667 -0.833333 -0.302482 +0.383404 -0.888915 -0.250662 +0.323906 -0.888915 -0.323906 +0.390868 -0.833333 -0.390868 +0.462667 -0.833333 -0.302482 +0.250662 -0.888915 -0.383404 +0.390868 -0.833333 -0.390868 +0.323906 -0.888915 -0.323906 +0.250662 -0.888915 -0.383404 +0.302482 -0.833333 -0.462667 +0.390868 -0.833333 -0.390868 +0.168614 -0.888915 -0.425910 +0.302482 -0.833333 -0.462667 +0.250662 -0.888915 -0.383404 +0.168614 -0.888915 -0.425910 +0.203472 -0.833333 -0.513960 +0.302482 -0.833333 -0.462667 +0.083352 -0.888915 -0.450425 +0.203472 -0.833333 -0.513960 +0.168614 -0.888915 -0.425910 +0.083352 -0.888915 -0.450425 +0.100584 -0.833333 -0.543543 +0.203472 -0.833333 -0.513960 +0.083352 -0.888915 -0.450425 +0.000000 -0.888915 -0.458072 +0.100584 -0.833333 -0.543543 +0.083352 -0.888915 -0.450425 +0.000000 -0.957427 -0.288675 +0.000000 -0.888915 -0.458072 +0.052528 -0.957427 -0.283856 +0.000000 -0.957427 -0.288675 +0.083352 -0.888915 -0.450425 +0.019950 -0.993971 -0.107809 +0.000000 -0.957427 -0.288675 +0.052528 -0.957427 -0.283856 +0.019950 -0.993971 -0.107809 +0.000000 -0.993971 -0.109639 +0.000000 -0.957427 -0.288675 +0.000000 -1.000000 0.000000 +0.000000 -0.993971 -0.109639 +0.019950 -0.993971 -0.107809 +0.083352 -0.888915 0.450425 +0.106260 -0.957427 0.268407 +0.168614 -0.888915 0.425910 +0.106260 -0.957427 0.268407 +0.083352 -0.888915 0.450425 +0.052528 -0.957427 0.283856 +0.168614 -0.888915 0.425910 +0.157966 -0.957427 0.241620 +0.250662 -0.888915 0.383404 +0.157966 -0.957427 0.241620 +0.168614 -0.888915 0.425910 +0.106260 -0.957427 0.268407 +0.250662 -0.888915 0.383404 +0.204124 -0.957427 0.204124 +0.323906 -0.888915 0.323906 +0.204124 -0.957427 0.204124 +0.250662 -0.888915 0.383404 +0.157966 -0.957427 0.241620 +0.052528 -0.957427 0.283856 +0.040358 -0.993971 0.101941 +0.106260 -0.957427 0.268407 +0.040358 -0.993971 0.101941 +0.052528 -0.957427 0.283856 +0.019950 -0.993971 0.107809 +0.106260 -0.957427 0.268407 +0.059996 -0.993971 0.091768 +0.157966 -0.957427 0.241620 +0.059996 -0.993971 0.091768 +0.106260 -0.957427 0.268407 +0.040358 -0.993971 0.101941 +0.157966 -0.957427 0.241620 +0.077527 -0.993971 0.077527 +0.204124 -0.957427 0.204124 +0.077527 -0.993971 0.077527 +0.157966 -0.957427 0.241620 +0.059996 -0.993971 0.091768 +0.323906 -0.888915 0.323906 +0.241620 -0.957427 0.157966 +0.383404 -0.888915 0.250662 +0.241620 -0.957427 0.157966 +0.323906 -0.888915 0.323906 +0.204124 -0.957427 0.204124 +0.383404 -0.888915 0.250662 +0.268407 -0.957427 0.106260 +0.425910 -0.888915 0.168614 +0.268407 -0.957427 0.106260 +0.383404 -0.888915 0.250662 +0.241620 -0.957427 0.157966 +0.425910 -0.888915 0.168614 +0.283856 -0.957427 0.052528 +0.450425 -0.888915 0.083352 +0.283856 -0.957427 0.052528 +0.425910 -0.888915 0.168614 +0.268407 -0.957427 0.106260 +0.450425 -0.888915 0.083352 +0.288675 -0.957427 0.000000 +0.458072 -0.888915 0.000000 +0.288675 -0.957427 0.000000 +0.450425 -0.888915 0.083352 +0.283856 -0.957427 0.052528 +0.204124 -0.957427 0.204124 +0.091768 -0.993971 0.059996 +0.241620 -0.957427 0.157966 +0.091768 -0.993971 0.059996 +0.204124 -0.957427 0.204124 +0.077527 -0.993971 0.077527 +0.241620 -0.957427 0.157966 +0.101941 -0.993971 0.040358 +0.268407 -0.957427 0.106260 +0.101941 -0.993971 0.040358 +0.241620 -0.957427 0.157966 +0.091768 -0.993971 0.059996 +0.268407 -0.957427 0.106260 +0.107809 -0.993971 0.019950 +0.283856 -0.957427 0.052528 +0.107809 -0.993971 0.019950 +0.268407 -0.957427 0.106260 +0.101941 -0.993971 0.040358 +0.283856 -0.957427 0.052528 +0.109639 -0.993971 0.000000 +0.288675 -0.957427 0.000000 +0.109639 -0.993971 0.000000 +0.283856 -0.957427 0.052528 +0.107809 -0.993971 0.019950 +0.458072 -0.888915 0.000000 +0.283856 -0.957427 -0.052528 +0.450425 -0.888915 -0.083352 +0.283856 -0.957427 -0.052528 +0.458072 -0.888915 0.000000 +0.288675 -0.957427 0.000000 +0.450425 -0.888915 -0.083352 +0.268407 -0.957427 -0.106260 +0.425910 -0.888915 -0.168614 +0.268407 -0.957427 -0.106260 +0.450425 -0.888915 -0.083352 +0.283856 -0.957427 -0.052528 +0.425910 -0.888915 -0.168614 +0.241620 -0.957427 -0.157966 +0.383404 -0.888915 -0.250662 +0.241620 -0.957427 -0.157966 +0.425910 -0.888915 -0.168614 +0.268407 -0.957427 -0.106260 +0.383404 -0.888915 -0.250662 +0.204124 -0.957427 -0.204124 +0.323906 -0.888915 -0.323906 +0.204124 -0.957427 -0.204124 +0.383404 -0.888915 -0.250662 +0.241620 -0.957427 -0.157966 +0.288675 -0.957427 0.000000 +0.107809 -0.993971 -0.019950 +0.283856 -0.957427 -0.052528 +0.107809 -0.993971 -0.019950 +0.288675 -0.957427 0.000000 +0.109639 -0.993971 0.000000 +0.283856 -0.957427 -0.052528 +0.101941 -0.993971 -0.040358 +0.268407 -0.957427 -0.106260 +0.101941 -0.993971 -0.040358 +0.283856 -0.957427 -0.052528 +0.107809 -0.993971 -0.019950 +0.268407 -0.957427 -0.106260 +0.091768 -0.993971 -0.059996 +0.241620 -0.957427 -0.157966 +0.091768 -0.993971 -0.059996 +0.268407 -0.957427 -0.106260 +0.101941 -0.993971 -0.040358 +0.241620 -0.957427 -0.157966 +0.077527 -0.993971 -0.077527 +0.204124 -0.957427 -0.204124 +0.077527 -0.993971 -0.077527 +0.241620 -0.957427 -0.157966 +0.091768 -0.993971 -0.059996 +0.323906 -0.888915 -0.323906 +0.157966 -0.957427 -0.241620 +0.250662 -0.888915 -0.383404 +0.157966 -0.957427 -0.241620 +0.323906 -0.888915 -0.323906 +0.204124 -0.957427 -0.204124 +0.250662 -0.888915 -0.383404 +0.106260 -0.957427 -0.268407 +0.168614 -0.888915 -0.425910 +0.106260 -0.957427 -0.268407 +0.250662 -0.888915 -0.383404 +0.157966 -0.957427 -0.241620 +0.168614 -0.888915 -0.425910 +0.052528 -0.957427 -0.283856 +0.083352 -0.888915 -0.450425 +0.052528 -0.957427 -0.283856 +0.168614 -0.888915 -0.425910 +0.106260 -0.957427 -0.268407 +0.204124 -0.957427 -0.204124 +0.059996 -0.993971 -0.091768 +0.157966 -0.957427 -0.241620 +0.059996 -0.993971 -0.091768 +0.204124 -0.957427 -0.204124 +0.077527 -0.993971 -0.077527 +0.157966 -0.957427 -0.241620 +0.040358 -0.993971 -0.101941 +0.106260 -0.957427 -0.268407 +0.040358 -0.993971 -0.101941 +0.157966 -0.957427 -0.241620 +0.059996 -0.993971 -0.091768 +0.106260 -0.957427 -0.268407 +0.019950 -0.993971 -0.107809 +0.052528 -0.957427 -0.283856 +0.019950 -0.993971 -0.107809 +0.106260 -0.957427 -0.268407 +0.040358 -0.993971 -0.101941 +-0.203472 -0.833333 0.513960 +-0.083352 -0.888915 0.450425 +-0.100584 -0.833333 0.543543 +-0.083352 -0.888915 0.450425 +0.000000 -0.833333 0.552771 +-0.100584 -0.833333 0.543543 +-0.083352 -0.888915 0.450425 +0.000000 -0.888915 0.458072 +0.000000 -0.833333 0.552771 +-0.083352 -0.888915 0.450425 +0.000000 -0.957427 0.288675 +0.000000 -0.888915 0.458072 +-0.052528 -0.957427 0.283856 +0.000000 -0.957427 0.288675 +-0.083352 -0.888915 0.450425 +-0.052528 -0.957427 0.283856 +0.000000 -0.993971 0.109639 +0.000000 -0.957427 0.288675 +-0.019950 -0.993971 0.107809 +0.000000 -0.993971 0.109639 +-0.052528 -0.957427 0.283856 +0.000000 -1.000000 0.000000 +0.000000 -0.993971 -0.109639 +0.000000 -1.000000 0.000000 +-0.019950 -0.993971 0.107809 +0.000000 -1.000000 0.000000 +0.000000 -0.993971 0.109639 +-0.019950 -0.993971 0.107809 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.040358 -0.993971 0.101941 +0.000000 -1.000000 0.000000 +-0.019950 -0.993971 0.107809 +-0.040358 -0.993971 0.101941 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.059996 -0.993971 0.091768 +0.000000 -1.000000 0.000000 +-0.040358 -0.993971 0.101941 +-0.059996 -0.993971 0.091768 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.077527 -0.993971 0.077527 +0.000000 -1.000000 0.000000 +-0.059996 -0.993971 0.091768 +-0.077527 -0.993971 0.077527 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.091768 -0.993971 0.059996 +0.000000 -1.000000 0.000000 +-0.077527 -0.993971 0.077527 +-0.091768 -0.993971 0.059996 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.101941 -0.993971 0.040358 +0.000000 -1.000000 0.000000 +-0.091768 -0.993971 0.059996 +-0.101941 -0.993971 0.040358 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.107809 -0.993971 0.019950 +0.000000 -1.000000 0.000000 +-0.101941 -0.993971 0.040358 +-0.107809 -0.993971 0.019950 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.109639 -0.993971 0.000000 +0.000000 -1.000000 0.000000 +-0.107809 -0.993971 0.019950 +-0.109639 -0.993971 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.107809 -0.993971 -0.019950 +0.000000 -1.000000 0.000000 +-0.109639 -0.993971 0.000000 +-0.107809 -0.993971 -0.019950 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.101941 -0.993971 -0.040358 +0.000000 -1.000000 0.000000 +-0.107809 -0.993971 -0.019950 +-0.101941 -0.993971 -0.040358 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.091768 -0.993971 -0.059996 +0.000000 -1.000000 0.000000 +-0.101941 -0.993971 -0.040358 +-0.091768 -0.993971 -0.059996 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.077527 -0.993971 -0.077527 +0.000000 -1.000000 0.000000 +-0.091768 -0.993971 -0.059996 +-0.077527 -0.993971 -0.077527 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.059996 -0.993971 -0.091768 +0.000000 -1.000000 0.000000 +-0.077527 -0.993971 -0.077527 +-0.059996 -0.993971 -0.091768 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.040358 -0.993971 -0.101941 +0.000000 -1.000000 0.000000 +-0.059996 -0.993971 -0.091768 +-0.040358 -0.993971 -0.101941 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.019950 -0.993971 -0.107809 +0.000000 -1.000000 0.000000 +-0.040358 -0.993971 -0.101941 +-0.019950 -0.993971 -0.107809 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.019950 -0.993971 -0.107809 +0.000000 -0.993971 -0.109639 +0.000000 -1.000000 0.000000 +-0.019950 -0.993971 -0.107809 +0.000000 -0.957427 -0.288675 +0.000000 -0.993971 -0.109639 +-0.052528 -0.957427 -0.283856 +0.000000 -0.957427 -0.288675 +-0.019950 -0.993971 -0.107809 +-0.083352 -0.888915 -0.450425 +0.000000 -0.957427 -0.288675 +-0.052528 -0.957427 -0.283856 +-0.083352 -0.888915 -0.450425 +0.000000 -0.888915 -0.458072 +0.000000 -0.957427 -0.288675 +-0.083352 -0.888915 -0.450425 +0.000000 -0.833333 -0.552771 +0.000000 -0.888915 -0.458072 +-0.083352 -0.888915 -0.450425 +-0.100584 -0.833333 -0.543543 +0.000000 -0.833333 -0.552771 +-0.083352 -0.888915 -0.450425 +-0.203472 -0.833333 -0.513960 +-0.100584 -0.833333 -0.543543 +-0.168614 -0.888915 -0.425910 +-0.203472 -0.833333 -0.513960 +-0.083352 -0.888915 -0.450425 +-0.168614 -0.888915 -0.425910 +-0.302482 -0.833333 -0.462667 +-0.203472 -0.833333 -0.513960 +-0.250662 -0.888915 -0.383404 +-0.302482 -0.833333 -0.462667 +-0.168614 -0.888915 -0.425910 +-0.250662 -0.888915 -0.383404 +-0.390868 -0.833333 -0.390868 +-0.302482 -0.833333 -0.462667 +-0.323906 -0.888915 -0.323906 +-0.390868 -0.833333 -0.390868 +-0.250662 -0.888915 -0.383404 +-0.323906 -0.888915 -0.323906 +-0.462667 -0.833333 -0.302482 +-0.390868 -0.833333 -0.390868 +-0.383404 -0.888915 -0.250662 +-0.462667 -0.833333 -0.302482 +-0.323906 -0.888915 -0.323906 +-0.383404 -0.888915 -0.250662 +-0.513960 -0.833333 -0.203472 +-0.462667 -0.833333 -0.302482 +-0.425910 -0.888915 -0.168614 +-0.513960 -0.833333 -0.203472 +-0.383404 -0.888915 -0.250662 +-0.425910 -0.888915 -0.168614 +-0.543543 -0.833333 -0.100584 +-0.513960 -0.833333 -0.203472 +-0.450425 -0.888915 -0.083352 +-0.543543 -0.833333 -0.100584 +-0.425910 -0.888915 -0.168614 +-0.450425 -0.888915 -0.083352 +-0.552771 -0.833333 0.000000 +-0.543543 -0.833333 -0.100584 +-0.458072 -0.888915 0.000000 +-0.552771 -0.833333 0.000000 +-0.450425 -0.888915 -0.083352 +-0.458072 -0.888915 0.000000 +-0.543543 -0.833333 0.100584 +-0.552771 -0.833333 0.000000 +-0.450425 -0.888915 0.083352 +-0.543543 -0.833333 0.100584 +-0.458072 -0.888915 0.000000 +-0.425910 -0.888915 0.168614 +-0.543543 -0.833333 0.100584 +-0.450425 -0.888915 0.083352 +-0.425910 -0.888915 0.168614 +-0.513960 -0.833333 0.203472 +-0.543543 -0.833333 0.100584 +-0.383404 -0.888915 0.250662 +-0.513960 -0.833333 0.203472 +-0.425910 -0.888915 0.168614 +-0.383404 -0.888915 0.250662 +-0.462667 -0.833333 0.302482 +-0.513960 -0.833333 0.203472 +-0.383404 -0.888915 0.250662 +-0.390868 -0.833333 0.390868 +-0.462667 -0.833333 0.302482 +-0.323906 -0.888915 0.323906 +-0.390868 -0.833333 0.390868 +-0.383404 -0.888915 0.250662 +-0.323906 -0.888915 0.323906 +-0.302482 -0.833333 0.462667 +-0.390868 -0.833333 0.390868 +-0.250662 -0.888915 0.383404 +-0.302482 -0.833333 0.462667 +-0.323906 -0.888915 0.323906 +-0.250662 -0.888915 0.383404 +-0.203472 -0.833333 0.513960 +-0.302482 -0.833333 0.462667 +-0.168614 -0.888915 0.425910 +-0.203472 -0.833333 0.513960 +-0.250662 -0.888915 0.383404 +-0.083352 -0.888915 0.450425 +-0.203472 -0.833333 0.513960 +-0.168614 -0.888915 0.425910 +-0.083352 -0.888915 -0.450425 +-0.106260 -0.957427 -0.268407 +-0.168614 -0.888915 -0.425910 +-0.106260 -0.957427 -0.268407 +-0.083352 -0.888915 -0.450425 +-0.052528 -0.957427 -0.283856 +-0.168614 -0.888915 -0.425910 +-0.157966 -0.957427 -0.241620 +-0.250662 -0.888915 -0.383404 +-0.157966 -0.957427 -0.241620 +-0.168614 -0.888915 -0.425910 +-0.106260 -0.957427 -0.268407 +-0.250662 -0.888915 -0.383404 +-0.204124 -0.957427 -0.204124 +-0.323906 -0.888915 -0.323906 +-0.204124 -0.957427 -0.204124 +-0.250662 -0.888915 -0.383404 +-0.157966 -0.957427 -0.241620 +-0.052528 -0.957427 -0.283856 +-0.040358 -0.993971 -0.101941 +-0.106260 -0.957427 -0.268407 +-0.040358 -0.993971 -0.101941 +-0.052528 -0.957427 -0.283856 +-0.019950 -0.993971 -0.107809 +-0.106260 -0.957427 -0.268407 +-0.059996 -0.993971 -0.091768 +-0.157966 -0.957427 -0.241620 +-0.059996 -0.993971 -0.091768 +-0.106260 -0.957427 -0.268407 +-0.040358 -0.993971 -0.101941 +-0.157966 -0.957427 -0.241620 +-0.077527 -0.993971 -0.077527 +-0.204124 -0.957427 -0.204124 +-0.077527 -0.993971 -0.077527 +-0.157966 -0.957427 -0.241620 +-0.059996 -0.993971 -0.091768 +-0.323906 -0.888915 -0.323906 +-0.241620 -0.957427 -0.157966 +-0.383404 -0.888915 -0.250662 +-0.241620 -0.957427 -0.157966 +-0.323906 -0.888915 -0.323906 +-0.204124 -0.957427 -0.204124 +-0.383404 -0.888915 -0.250662 +-0.268407 -0.957427 -0.106260 +-0.425910 -0.888915 -0.168614 +-0.268407 -0.957427 -0.106260 +-0.383404 -0.888915 -0.250662 +-0.241620 -0.957427 -0.157966 +-0.425910 -0.888915 -0.168614 +-0.283856 -0.957427 -0.052528 +-0.450425 -0.888915 -0.083352 +-0.283856 -0.957427 -0.052528 +-0.425910 -0.888915 -0.168614 +-0.268407 -0.957427 -0.106260 +-0.450425 -0.888915 -0.083352 +-0.288675 -0.957427 0.000000 +-0.458072 -0.888915 0.000000 +-0.288675 -0.957427 0.000000 +-0.450425 -0.888915 -0.083352 +-0.283856 -0.957427 -0.052528 +-0.204124 -0.957427 -0.204124 +-0.091768 -0.993971 -0.059996 +-0.241620 -0.957427 -0.157966 +-0.091768 -0.993971 -0.059996 +-0.204124 -0.957427 -0.204124 +-0.077527 -0.993971 -0.077527 +-0.241620 -0.957427 -0.157966 +-0.101941 -0.993971 -0.040358 +-0.268407 -0.957427 -0.106260 +-0.101941 -0.993971 -0.040358 +-0.241620 -0.957427 -0.157966 +-0.091768 -0.993971 -0.059996 +-0.268407 -0.957427 -0.106260 +-0.107809 -0.993971 -0.019950 +-0.283856 -0.957427 -0.052528 +-0.107809 -0.993971 -0.019950 +-0.268407 -0.957427 -0.106260 +-0.101941 -0.993971 -0.040358 +-0.283856 -0.957427 -0.052528 +-0.109639 -0.993971 0.000000 +-0.288675 -0.957427 0.000000 +-0.109639 -0.993971 0.000000 +-0.283856 -0.957427 -0.052528 +-0.107809 -0.993971 -0.019950 +-0.458072 -0.888915 0.000000 +-0.283856 -0.957427 0.052528 +-0.450425 -0.888915 0.083352 +-0.283856 -0.957427 0.052528 +-0.458072 -0.888915 0.000000 +-0.288675 -0.957427 0.000000 +-0.450425 -0.888915 0.083352 +-0.268407 -0.957427 0.106260 +-0.425910 -0.888915 0.168614 +-0.268407 -0.957427 0.106260 +-0.450425 -0.888915 0.083352 +-0.283856 -0.957427 0.052528 +-0.425910 -0.888915 0.168614 +-0.241620 -0.957427 0.157966 +-0.383404 -0.888915 0.250662 +-0.241620 -0.957427 0.157966 +-0.425910 -0.888915 0.168614 +-0.268407 -0.957427 0.106260 +-0.383404 -0.888915 0.250662 +-0.204124 -0.957427 0.204124 +-0.323906 -0.888915 0.323906 +-0.204124 -0.957427 0.204124 +-0.383404 -0.888915 0.250662 +-0.241620 -0.957427 0.157966 +-0.288675 -0.957427 0.000000 +-0.107809 -0.993971 0.019950 +-0.283856 -0.957427 0.052528 +-0.107809 -0.993971 0.019950 +-0.288675 -0.957427 0.000000 +-0.109639 -0.993971 0.000000 +-0.283856 -0.957427 0.052528 +-0.101941 -0.993971 0.040358 +-0.268407 -0.957427 0.106260 +-0.101941 -0.993971 0.040358 +-0.283856 -0.957427 0.052528 +-0.107809 -0.993971 0.019950 +-0.268407 -0.957427 0.106260 +-0.091768 -0.993971 0.059996 +-0.241620 -0.957427 0.157966 +-0.091768 -0.993971 0.059996 +-0.268407 -0.957427 0.106260 +-0.101941 -0.993971 0.040358 +-0.241620 -0.957427 0.157966 +-0.077527 -0.993971 0.077527 +-0.204124 -0.957427 0.204124 +-0.077527 -0.993971 0.077527 +-0.241620 -0.957427 0.157966 +-0.091768 -0.993971 0.059996 +-0.323906 -0.888915 0.323906 +-0.157966 -0.957427 0.241620 +-0.250662 -0.888915 0.383404 +-0.157966 -0.957427 0.241620 +-0.323906 -0.888915 0.323906 +-0.204124 -0.957427 0.204124 +-0.250662 -0.888915 0.383404 +-0.106260 -0.957427 0.268407 +-0.168614 -0.888915 0.425910 +-0.106260 -0.957427 0.268407 +-0.250662 -0.888915 0.383404 +-0.157966 -0.957427 0.241620 +-0.168614 -0.888915 0.425910 +-0.052528 -0.957427 0.283856 +-0.083352 -0.888915 0.450425 +-0.052528 -0.957427 0.283856 +-0.168614 -0.888915 0.425910 +-0.106260 -0.957427 0.268407 +-0.204124 -0.957427 0.204124 +-0.059996 -0.993971 0.091768 +-0.157966 -0.957427 0.241620 +-0.059996 -0.993971 0.091768 +-0.204124 -0.957427 0.204124 +-0.077527 -0.993971 0.077527 +-0.157966 -0.957427 0.241620 +-0.040358 -0.993971 0.101941 +-0.106260 -0.957427 0.268407 +-0.040358 -0.993971 0.101941 +-0.157966 -0.957427 0.241620 +-0.059996 -0.993971 0.091768 +-0.106260 -0.957427 0.268407 +-0.019950 -0.993971 0.107809 +-0.052528 -0.957427 0.283856 +-0.019950 -0.993971 0.107809 +-0.106260 -0.957427 0.268407 +-0.040358 -0.993971 0.101941 +0.000000 -0.957427 0.288675 +0.000000 -0.888915 0.458072 +0.000000 -0.888915 0.458072 +0.000000 -0.833333 0.552771 +0.000000 -0.888915 0.458072 +0.000000 -0.833333 0.552771 +0.000000 -0.888915 0.458072 +0.000000 -0.888915 0.458072 +0.000000 -0.833333 0.552771 +0.000000 -1.000000 0.000000 +0.000000 -0.993971 0.109639 +0.000000 -1.000000 0.000000 +0.000000 -0.993971 0.109639 +0.000000 -0.993971 0.109639 +0.000000 -1.000000 0.000000 +0.000000 -0.957427 0.288675 +0.000000 -0.993971 0.109639 +0.000000 -0.993971 0.109639 +0.000000 -0.957427 0.288675 +0.000000 -0.957427 0.288675 +0.000000 -0.993971 0.109639 +0.000000 -0.888915 0.458072 +0.000000 -0.957427 0.288675 +0.000000 -0.957427 0.288675 +0.000000 0.991150 0.132743 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -0.991150 0.132743 +0.000000 -1.000000 0.000000 +0.000000 -0.983305 0.181963 +0.000000 -0.991150 0.132743 +0.000000 -1.000000 0.000000 +0.000000 -0.983305 0.181963 +0.000000 -0.960000 0.280000 +0.000000 -0.991150 0.132743 +0.000000 -0.929788 0.368095 +0.000000 -0.960000 0.280000 +0.000000 -0.983305 0.181963 +0.000000 -0.929788 0.368095 +0.000000 -0.898876 0.438202 +0.000000 -0.960000 0.280000 +0.000000 -0.836995 0.547210 +0.000000 -0.898876 0.438202 +0.000000 -0.929788 0.368095 +0.000000 -0.836995 0.547210 +0.000000 -0.800000 0.600000 +0.000000 -0.898876 0.438202 +0.000000 -0.707107 0.707107 +0.000000 -0.800000 0.600000 +0.000000 -0.836995 0.547210 +0.000000 -0.707107 0.707107 +0.000000 -0.657534 0.753425 +0.000000 -0.800000 0.600000 +0.000000 -0.547210 0.836995 +0.000000 -0.657534 0.753425 +0.000000 -0.707107 0.707107 +0.000000 -0.547210 0.836995 +0.000000 -0.470588 0.882353 +0.000000 -0.657534 0.753425 +0.000000 -0.368095 0.929788 +0.000000 -0.470588 0.882353 +0.000000 -0.547210 0.836995 +0.000000 -0.368095 0.929788 +0.000000 -0.362266 0.932075 +0.000000 -0.470588 0.882353 +0.000000 -0.181963 0.983305 +0.000000 -0.362266 0.932075 +0.000000 -0.368095 0.929788 +0.000000 -0.181963 0.983305 +0.000000 -0.246154 0.969231 +0.000000 -0.362266 0.932075 +0.000000 -0.181963 0.983305 +0.000000 -0.124516 0.992218 +0.000000 -0.246154 0.969231 +0.000000 0.000000 1.000000 +0.000000 -0.124516 0.992218 +0.000000 -0.181963 0.983305 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -0.124516 0.992218 +0.000000 0.181963 0.983305 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.181963 0.983305 +0.000000 0.124516 0.992218 +0.000000 0.000000 1.000000 +0.000000 0.181963 0.983305 +0.000000 0.246154 0.969231 +0.000000 0.124516 0.992218 +0.000000 0.368095 0.929788 +0.000000 0.246154 0.969231 +0.000000 0.181963 0.983305 +0.000000 0.368095 0.929788 +0.000000 0.362266 0.932075 +0.000000 0.246154 0.969231 +0.000000 0.368095 0.929788 +0.000000 0.470588 0.882353 +0.000000 0.362266 0.932075 +0.000000 0.547210 0.836995 +0.000000 0.470588 0.882353 +0.000000 0.368095 0.929788 +0.000000 0.547210 0.836995 +0.000000 0.657534 0.753425 +0.000000 0.470588 0.882353 +0.000000 0.707107 0.707107 +0.000000 0.657534 0.753425 +0.000000 0.547210 0.836995 +0.000000 0.707107 0.707107 +0.000000 0.800000 0.600000 +0.000000 0.657534 0.753425 +0.000000 0.836995 0.547210 +0.000000 0.800000 0.600000 +0.000000 0.707107 0.707107 +0.000000 0.836995 0.547210 +0.000000 0.898876 0.438202 +0.000000 0.800000 0.600000 +0.000000 0.929788 0.368095 +0.000000 0.898876 0.438202 +0.000000 0.836995 0.547210 +0.000000 0.929788 0.368095 +0.000000 0.960000 0.280000 +0.000000 0.898876 0.438202 +0.000000 0.983305 0.181963 +0.000000 0.960000 0.280000 +0.000000 0.929788 0.368095 +0.000000 0.983305 0.181963 +0.000000 0.991150 0.132743 +0.000000 0.960000 0.280000 +0.000000 1.000000 0.000000 +0.000000 0.991150 0.132743 +0.000000 0.983305 0.181963 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +0.000000 -0.986500 0.163761 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -0.468750 0.883331 +0.000000 -0.607077 0.794643 +0.000000 -0.468750 0.883331 +0.000000 -0.607077 0.794643 +0.000000 -0.607077 0.794643 +0.000000 -0.468750 0.883331 +0.000000 -0.748869 0.662718 +0.000000 -0.607077 0.794643 +0.000000 -0.607077 0.794643 +0.000000 -0.748869 0.662718 +0.000000 -0.748869 0.662718 +0.000000 -0.607077 0.794643 +0.000000 -0.748869 0.662718 +0.000000 -0.856957 0.515388 +0.000000 -0.748869 0.662718 +0.000000 -0.856957 0.515388 +0.000000 -0.856957 0.515388 +0.000000 -0.748869 0.662718 +0.000000 -0.936432 0.350850 +0.000000 -0.856957 0.515388 +0.000000 -0.856957 0.515388 +0.000000 -0.936432 0.350850 +0.000000 -0.936432 0.350850 +0.000000 -0.856957 0.515388 +0.000000 -0.936432 0.350850 +0.000000 -0.986500 0.163761 +0.000000 -0.936432 0.350850 +0.000000 -0.986500 0.163761 +0.000000 -0.986500 0.163761 +0.000000 -0.936432 0.350850 +0.000000 -1.000000 0.000000 +0.000000 -0.986500 0.163761 +0.000000 -0.986500 0.163761 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.411438 0.911438 +0.000000 0.215945 0.976406 +0.000000 0.215945 0.976406 +0.000000 0.000000 1.000000 +0.000000 0.015591 0.999878 +0.000000 0.000000 1.000000 +0.000000 0.015591 0.999878 +0.000000 0.015591 0.999878 +0.000000 0.000000 1.000000 +0.000000 0.015591 0.999878 +0.000000 0.215945 0.976406 +0.000000 0.015591 0.999878 +0.000000 0.215945 0.976406 +0.000000 0.215945 0.976406 +0.000000 0.015591 0.999878 +0.000000 0.673051 -0.739596 +0.000000 0.661438 -0.750000 +0.000000 0.661438 -0.750000 +0.000000 0.673051 -0.739596 +0.000000 0.673051 -0.739596 +0.000000 0.661438 -0.750000 +0.000000 0.673051 -0.739596 +0.000000 0.807790 -0.589470 +0.000000 0.673051 -0.739596 +0.000000 0.807790 -0.589470 +0.000000 0.807790 -0.589470 +0.000000 0.673051 -0.739596 +0.000000 0.911438 -0.411438 +0.000000 0.807790 -0.589470 +0.000000 0.807790 -0.589470 +0.000000 0.911438 -0.411438 +0.000000 0.911438 -0.411438 +0.000000 0.807790 -0.589470 +0.000000 0.911438 -0.411438 +0.000000 0.976406 -0.215945 +0.000000 0.911438 -0.411438 +0.000000 0.976406 -0.215945 +0.000000 0.976406 -0.215945 +0.000000 0.911438 -0.411438 +0.000000 0.999878 -0.015591 +0.000000 0.976406 -0.215945 +0.000000 0.976406 -0.215945 +0.000000 0.999878 -0.015591 +0.000000 0.999878 -0.015591 +0.000000 0.976406 -0.215945 +0.000000 0.999878 -0.015591 +0.000000 0.984132 0.177440 +0.000000 0.999878 -0.015591 +0.000000 0.984132 0.177440 +0.000000 0.984132 0.177440 +0.000000 0.999878 -0.015591 +0.000000 0.935414 0.353553 +0.000000 0.984132 0.177440 +0.000000 0.984132 0.177440 +0.000000 0.935414 0.353553 +0.000000 0.935414 0.353553 +0.000000 0.984132 0.177440 +0.000000 0.855464 0.517862 +0.000000 0.935414 0.353553 +0.000000 0.935414 0.353553 +0.000000 0.855464 0.517862 +0.000000 0.855464 0.517862 +0.000000 0.935414 0.353553 +0.000000 0.855464 0.517862 +0.000000 0.739596 0.673051 +0.000000 0.855464 0.517862 +0.000000 0.739596 0.673051 +0.000000 0.739596 0.673051 +0.000000 0.855464 0.517862 +0.000000 0.589470 0.807790 +0.000000 0.739596 0.673051 +0.000000 0.739596 0.673051 +0.000000 0.589470 0.807790 +0.000000 0.589470 0.807790 +0.000000 0.739596 0.673051 +0.000000 0.589470 0.807790 +0.000000 0.411438 0.911438 +0.000000 0.589470 0.807790 +0.000000 0.411438 0.911438 +0.000000 0.411438 0.911438 +0.000000 0.589470 0.807790 +0.000000 0.215945 0.976406 +0.000000 0.411438 0.911438 +0.000000 0.411438 0.911438 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.378112 0.925760 +0.000000 0.270833 0.962626 +0.000000 0.270833 0.962626 +0.000000 0.986013 0.166667 +0.000000 0.937635 0.347622 +0.000000 0.986013 0.166667 +0.000000 0.937635 0.347622 +0.000000 0.937635 0.347622 +0.000000 0.986013 0.166667 +0.000000 0.853041 0.521843 +0.000000 0.937635 0.347622 +0.000000 0.937635 0.347622 +0.000000 0.853041 0.521843 +0.000000 0.853041 0.521843 +0.000000 0.937635 0.347622 +0.000000 0.743844 0.668353 +0.000000 0.853041 0.521843 +0.000000 0.853041 0.521843 +0.000000 0.743844 0.668353 +0.000000 0.743844 0.668353 +0.000000 0.853041 0.521843 +0.000000 0.743844 0.668353 +0.000000 0.666667 0.745356 +0.000000 0.743844 0.668353 +0.000000 0.743844 0.668353 +0.000000 0.666667 0.745356 +0.000000 0.666667 0.745356 +0.000000 0.609810 0.792548 +0.000000 0.666667 0.745356 +0.000000 0.743844 0.668353 +0.000000 0.609810 0.792548 +0.000000 0.577963 0.816063 +0.000000 0.666667 0.745356 +0.000000 0.445600 0.895232 +0.000000 0.577963 0.816063 +0.000000 0.609810 0.792548 +0.000000 0.445600 0.895232 +0.000000 0.481174 0.876625 +0.000000 0.577963 0.816063 +0.000000 0.445600 0.895232 +0.000000 0.378112 0.925760 +0.000000 0.481174 0.876625 +0.000000 0.270833 0.962626 +0.000000 0.378112 0.925760 +0.000000 0.445600 0.895232 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 -0.124516 0.992218 +0.000000 0.000000 1.000000 +0.000000 1.000000 0.000000 +0.000000 0.991150 0.132743 +0.000000 1.000000 0.000000 +0.000000 0.983305 0.181963 +0.000000 0.991150 0.132743 +0.000000 1.000000 0.000000 +0.000000 0.983305 0.181963 +0.000000 0.960000 0.280000 +0.000000 0.991150 0.132743 +0.000000 0.929788 0.368095 +0.000000 0.960000 0.280000 +0.000000 0.983305 0.181963 +0.000000 0.929788 0.368095 +0.000000 0.898876 0.438202 +0.000000 0.960000 0.280000 +0.000000 0.836995 0.547210 +0.000000 0.898876 0.438202 +0.000000 0.929788 0.368095 +0.000000 0.836995 0.547210 +0.000000 0.800000 0.600000 +0.000000 0.898876 0.438202 +0.000000 0.707107 0.707107 +0.000000 0.800000 0.600000 +0.000000 0.836995 0.547210 +0.000000 0.707107 0.707107 +0.000000 0.657534 0.753425 +0.000000 0.800000 0.600000 +0.000000 0.547210 0.836995 +0.000000 0.657534 0.753425 +0.000000 0.707107 0.707107 +0.000000 0.547210 0.836995 +0.000000 0.470588 0.882353 +0.000000 0.657534 0.753425 +0.000000 0.368095 0.929788 +0.000000 0.470588 0.882353 +0.000000 0.547210 0.836995 +0.000000 0.368095 0.929788 +0.000000 0.362266 0.932075 +0.000000 0.470588 0.882353 +0.000000 0.181963 0.983305 +0.000000 0.362266 0.932075 +0.000000 0.368095 0.929788 +0.000000 0.181963 0.983305 +0.000000 0.246154 0.969231 +0.000000 0.362266 0.932075 +0.000000 0.181963 0.983305 +0.000000 0.124516 0.992218 +0.000000 0.246154 0.969231 +0.000000 0.000000 1.000000 +0.000000 0.124516 0.992218 +0.000000 0.181963 0.983305 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.124516 0.992218 +0.000000 -0.991150 0.132743 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -0.991150 0.132743 +0.000000 -0.983305 0.181963 +0.000000 -1.000000 0.000000 +0.000000 -0.960000 0.280000 +0.000000 -0.983305 0.181963 +0.000000 -0.991150 0.132743 +0.000000 -0.960000 0.280000 +0.000000 -0.929788 0.368095 +0.000000 -0.983305 0.181963 +0.000000 -0.898876 0.438202 +0.000000 -0.929788 0.368095 +0.000000 -0.960000 0.280000 +0.000000 -0.898876 0.438202 +0.000000 -0.836995 0.547210 +0.000000 -0.929788 0.368095 +0.000000 -0.800000 0.600000 +0.000000 -0.836995 0.547210 +0.000000 -0.898876 0.438202 +0.000000 -0.800000 0.600000 +0.000000 -0.707107 0.707107 +0.000000 -0.836995 0.547210 +0.000000 -0.657534 0.753425 +0.000000 -0.707107 0.707107 +0.000000 -0.800000 0.600000 +0.000000 -0.657534 0.753425 +0.000000 -0.547210 0.836995 +0.000000 -0.707107 0.707107 +0.000000 -0.470588 0.882353 +0.000000 -0.547210 0.836995 +0.000000 -0.657534 0.753425 +0.000000 -0.470588 0.882353 +0.000000 -0.368095 0.929788 +0.000000 -0.547210 0.836995 +0.000000 -0.362266 0.932075 +0.000000 -0.368095 0.929788 +0.000000 -0.470588 0.882353 +0.000000 -0.362266 0.932075 +0.000000 -0.181963 0.983305 +0.000000 -0.368095 0.929788 +0.000000 -0.246154 0.969231 +0.000000 -0.181963 0.983305 +0.000000 -0.362266 0.932075 +0.000000 -0.124516 0.992218 +0.000000 -0.181963 0.983305 +0.000000 -0.246154 0.969231 +0.000000 -0.124516 0.992218 +0.000000 0.000000 1.000000 +0.000000 -0.181963 0.983305 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.000000 1.000000 0.000000 +0.000000 0.986500 0.163761 +0.000000 1.000000 0.000000 +0.000000 0.468750 0.883331 +0.000000 0.607077 0.794643 +0.000000 0.468750 0.883331 +0.000000 0.607077 0.794643 +0.000000 0.607077 0.794643 +0.000000 0.468750 0.883331 +0.000000 0.748869 0.662718 +0.000000 0.607077 0.794643 +0.000000 0.607077 0.794643 +0.000000 0.748869 0.662718 +0.000000 0.748869 0.662718 +0.000000 0.607077 0.794643 +0.000000 0.748869 0.662718 +0.000000 0.856957 0.515388 +0.000000 0.748869 0.662718 +0.000000 0.856957 0.515388 +0.000000 0.856957 0.515388 +0.000000 0.748869 0.662718 +0.000000 0.936432 0.350850 +0.000000 0.856957 0.515388 +0.000000 0.856957 0.515388 +0.000000 0.936432 0.350850 +0.000000 0.936432 0.350850 +0.000000 0.856957 0.515388 +0.000000 0.936432 0.350850 +0.000000 0.986500 0.163761 +0.000000 0.936432 0.350850 +0.000000 0.986500 0.163761 +0.000000 0.986500 0.163761 +0.000000 0.936432 0.350850 +0.000000 0.986500 0.163761 +0.000000 1.000000 0.000000 +0.000000 0.986500 0.163761 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.836995 0.547210 +0.000000 0.707107 0.707107 +0.000000 0.836995 0.547210 +0.000000 0.707107 -0.707107 +0.000000 0.661438 -0.750000 +0.000000 0.661438 -0.750000 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.661438 -0.750000 +0.000000 0.836995 -0.547210 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.836995 -0.547210 +0.000000 0.836995 -0.547210 +0.000000 0.707107 -0.707107 +0.000000 0.836995 -0.547210 +0.000000 0.929788 -0.368095 +0.000000 0.836995 -0.547210 +0.000000 0.929788 -0.368095 +0.000000 0.929788 -0.368095 +0.000000 0.836995 -0.547210 +0.000000 0.983305 -0.181963 +0.000000 0.929788 -0.368095 +0.000000 0.929788 -0.368095 +0.000000 0.983305 -0.181963 +0.000000 0.983305 -0.181963 +0.000000 0.929788 -0.368095 +0.000000 0.983305 -0.181963 +0.000000 1.000000 0.000000 +0.000000 0.983305 -0.181963 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.983305 -0.181963 +0.000000 0.983305 0.181963 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.983305 0.181963 +0.000000 0.983305 0.181963 +0.000000 1.000000 0.000000 +0.000000 0.983305 0.181963 +0.000000 0.929788 0.368095 +0.000000 0.983305 0.181963 +0.000000 0.929788 0.368095 +0.000000 0.929788 0.368095 +0.000000 0.983305 0.181963 +0.000000 0.836995 0.547210 +0.000000 0.929788 0.368095 +0.000000 0.929788 0.368095 +0.000000 0.836995 0.547210 +0.000000 0.836995 0.547210 +0.000000 0.929788 0.368095 +0.000000 -0.707107 -0.707107 +0.000000 -0.661438 -0.750000 +0.000000 -0.661438 -0.750000 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.661438 -0.750000 +0.000000 -0.707107 -0.707107 +0.000000 -0.836995 -0.547210 +0.000000 -0.707107 -0.707107 +0.000000 -0.836995 -0.547210 +0.000000 -0.836995 -0.547210 +0.000000 -0.707107 -0.707107 +0.000000 -0.836995 -0.547210 +0.000000 -0.929788 -0.368095 +0.000000 -0.836995 -0.547210 +0.000000 -0.929788 -0.368095 +0.000000 -0.929788 -0.368095 +0.000000 -0.836995 -0.547210 +0.000000 -0.983305 -0.181963 +0.000000 -0.929788 -0.368095 +0.000000 -0.929788 -0.368095 +0.000000 -0.983305 -0.181963 +0.000000 -0.983305 -0.181963 +0.000000 -0.929788 -0.368095 +0.000000 -1.000000 0.000000 +0.000000 -0.983305 -0.181963 +0.000000 -0.983305 -0.181963 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -0.983305 -0.181963 +0.000000 -1.000000 0.000000 +0.000000 -0.983305 0.181963 +0.000000 -1.000000 0.000000 +0.000000 -0.983305 0.181963 +0.000000 -0.983305 0.181963 +0.000000 -1.000000 0.000000 +0.000000 -0.929788 0.368095 +0.000000 -0.983305 0.181963 +0.000000 -0.983305 0.181963 +0.000000 -0.929788 0.368095 +0.000000 -0.929788 0.368095 +0.000000 -0.983305 0.181963 +0.000000 -0.836995 0.547210 +0.000000 -0.929788 0.368095 +0.000000 -0.929788 0.368095 +0.000000 -0.836995 0.547210 +0.000000 -0.836995 0.547210 +0.000000 -0.929788 0.368095 +0.000000 -0.836995 0.547210 +0.000000 -0.707107 0.707107 +0.000000 -0.836995 0.547210 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.836995 0.547210 +0.000000 -0.707107 0.707107 +0.000000 -0.547210 0.836995 +0.000000 -0.707107 0.707107 +0.000000 -0.547210 0.836995 +0.000000 -0.547210 0.836995 +0.000000 -0.707107 0.707107 +0.000000 -0.368095 0.929788 +0.000000 -0.547210 0.836995 +0.000000 -0.547210 0.836995 +0.000000 -0.368095 0.929788 +0.000000 -0.368095 0.929788 +0.000000 -0.547210 0.836995 +0.000000 -0.368095 0.929788 +0.000000 -0.181963 0.983305 +0.000000 -0.368095 0.929788 +0.000000 -0.181963 0.983305 +0.000000 -0.181963 0.983305 +0.000000 -0.368095 0.929788 +0.000000 -0.181963 0.983305 +0.000000 0.000000 1.000000 +0.000000 -0.181963 0.983305 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -0.181963 0.983305 +0.000000 0.000000 1.000000 +0.000000 0.181963 0.983305 +0.000000 0.000000 1.000000 +0.000000 0.181963 0.983305 +0.000000 0.181963 0.983305 +0.000000 0.000000 1.000000 +0.000000 0.368095 0.929788 +0.000000 0.181963 0.983305 +0.000000 0.181963 0.983305 +0.000000 0.368095 0.929788 +0.000000 0.368095 0.929788 +0.000000 0.181963 0.983305 +0.000000 0.547210 0.836995 +0.000000 0.368095 0.929788 +0.000000 0.368095 0.929788 +0.000000 0.547210 0.836995 +0.000000 0.547210 0.836995 +0.000000 0.368095 0.929788 +0.000000 0.707107 0.707107 +0.000000 0.547210 0.836995 +0.000000 0.547210 0.836995 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.547210 0.836995 +0.000000 0.707107 0.707107 +0.000000 0.836995 0.547210 +0.000000 0.707107 0.707107 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.666667 0.745356 +0.000000 0.745826 0.666141 +0.000000 0.666667 0.745356 +0.000000 0.993808 0.111111 +0.000000 0.988772 0.149433 +0.000000 0.993808 0.111111 +0.000000 0.988772 0.149433 +0.000000 0.988772 0.149433 +0.000000 0.993808 0.111111 +0.000000 0.988772 0.149433 +0.000000 0.938663 0.344835 +0.000000 0.988772 0.149433 +0.000000 0.938663 0.344835 +0.000000 0.938663 0.344835 +0.000000 0.988772 0.149433 +0.000000 0.259735 0.965680 +0.000000 0.222222 0.974996 +0.000000 0.222222 0.974996 +0.000000 0.259735 0.965680 +0.000000 0.342893 0.939375 +0.000000 0.222222 0.974996 +0.000000 0.448258 0.893904 +0.000000 0.342893 0.939375 +0.000000 0.259735 0.965680 +0.000000 0.448258 0.893904 +0.000000 0.459036 0.888417 +0.000000 0.342893 0.939375 +0.000000 0.612162 0.790732 +0.000000 0.459036 0.888417 +0.000000 0.448258 0.893904 +0.000000 0.612162 0.790732 +0.000000 0.567796 0.823169 +0.000000 0.459036 0.888417 +0.000000 0.612162 0.790732 +0.000000 0.666667 0.745356 +0.000000 0.567796 0.823169 +0.000000 0.745826 0.666141 +0.000000 0.666667 0.745356 +0.000000 0.612162 0.790732 +0.000000 0.854588 0.519307 +0.000000 0.938663 0.344835 +0.000000 0.938663 0.344835 +0.000000 0.854588 0.519307 +0.000000 0.854588 0.519307 +0.000000 0.938663 0.344835 +0.000000 0.854588 0.519307 +0.000000 0.745826 0.666141 +0.000000 0.854588 0.519307 +0.000000 0.745826 0.666141 +0.000000 0.745826 0.666141 +0.000000 0.854588 0.519307 +0.000000 0.745826 0.666141 +0.000000 0.666667 0.745356 +0.000000 0.745826 0.666141 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.000000 -1.000000 0.000000 +0.000000 -0.986500 0.163761 +0.000000 -1.000000 0.000000 +0.000000 -0.607077 0.794643 +0.000000 -0.468750 0.883331 +0.000000 -0.468750 0.883331 +0.000000 -0.607077 0.794643 +0.000000 -0.607077 0.794643 +0.000000 -0.468750 0.883331 +0.000000 -0.607077 0.794643 +0.000000 -0.724873 0.688882 +0.000000 -0.607077 0.794643 +0.000000 -0.748869 0.662718 +0.000000 -0.724873 0.688882 +0.000000 -0.607077 0.794643 +0.000000 -0.748869 0.662718 +0.000000 -0.840988 0.541054 +0.000000 -0.724873 0.688882 +0.000000 -0.856957 0.515388 +0.000000 -0.840988 0.541054 +0.000000 -0.748869 0.662718 +0.000000 -0.856957 0.515388 +0.000000 -0.928675 0.370895 +0.000000 -0.840988 0.541054 +0.000000 -0.936432 0.350850 +0.000000 -0.928675 0.370895 +0.000000 -0.856957 0.515388 +0.000000 -0.936432 0.350850 +0.000000 -0.982332 0.187147 +0.000000 -0.928675 0.370895 +0.000000 -0.986500 0.163761 +0.000000 -0.982332 0.187147 +0.000000 -0.936432 0.350850 +0.000000 -0.986500 0.163761 +0.000000 -1.000000 0.000000 +0.000000 -0.982332 0.187147 +0.000000 0.986500 0.163761 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.468750 0.883331 +0.000000 0.607077 0.794643 +0.000000 0.468750 0.883331 +0.000000 0.607077 0.794643 +0.000000 0.607077 0.794643 +0.000000 0.468750 0.883331 +0.000000 0.724873 0.688882 +0.000000 0.607077 0.794643 +0.000000 0.607077 0.794643 +0.000000 0.724873 0.688882 +0.000000 0.748869 0.662718 +0.000000 0.607077 0.794643 +0.000000 0.840988 0.541054 +0.000000 0.748869 0.662718 +0.000000 0.724873 0.688882 +0.000000 0.840988 0.541054 +0.000000 0.856957 0.515388 +0.000000 0.748869 0.662718 +0.000000 0.928675 0.370895 +0.000000 0.856957 0.515388 +0.000000 0.840988 0.541054 +0.000000 0.928675 0.370895 +0.000000 0.936432 0.350850 +0.000000 0.856957 0.515388 +0.000000 0.982332 0.187147 +0.000000 0.936432 0.350850 +0.000000 0.928675 0.370895 +0.000000 0.982332 0.187147 +0.000000 0.986500 0.163761 +0.000000 0.936432 0.350850 +0.000000 1.000000 0.000000 +0.000000 0.986500 0.163761 +0.000000 0.982332 0.187147 +0.000000 1.000000 0.000000 +0.000000 0.986500 0.163761 +0.000000 1.000000 0.000000 +0.000000 0.607077 0.794643 +0.000000 0.468750 0.883331 +0.000000 0.468750 0.883331 +0.000000 0.607077 0.794643 +0.000000 0.607077 0.794643 +0.000000 0.468750 0.883331 +0.000000 0.748869 0.662718 +0.000000 0.607077 0.794643 +0.000000 0.607077 0.794643 +0.000000 0.748869 0.662718 +0.000000 0.724873 0.688882 +0.000000 0.607077 0.794643 +0.000000 0.748869 0.662718 +0.000000 0.840988 0.541054 +0.000000 0.724873 0.688882 +0.000000 0.856957 0.515388 +0.000000 0.840988 0.541054 +0.000000 0.748869 0.662718 +0.000000 0.856957 0.515388 +0.000000 0.928675 0.370895 +0.000000 0.840988 0.541054 +0.000000 0.936432 0.350850 +0.000000 0.928675 0.370895 +0.000000 0.856957 0.515388 +0.000000 0.936432 0.350850 +0.000000 0.982332 0.187147 +0.000000 0.928675 0.370895 +0.000000 0.986500 0.163761 +0.000000 0.982332 0.187147 +0.000000 0.936432 0.350850 +0.000000 0.986500 0.163761 +0.000000 1.000000 0.000000 +0.000000 0.982332 0.187147 +0.000000 -0.986500 0.163761 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -0.607077 0.794643 +0.000000 -0.468750 0.883331 +0.000000 -0.468750 0.883331 +0.000000 -0.607077 0.794643 +0.000000 -0.607077 0.794643 +0.000000 -0.468750 0.883331 +0.000000 -0.607077 0.794643 +0.000000 -0.748869 0.662718 +0.000000 -0.607077 0.794643 +0.000000 -0.724873 0.688882 +0.000000 -0.748869 0.662718 +0.000000 -0.607077 0.794643 +0.000000 -0.840988 0.541054 +0.000000 -0.748869 0.662718 +0.000000 -0.724873 0.688882 +0.000000 -0.840988 0.541054 +0.000000 -0.856957 0.515388 +0.000000 -0.748869 0.662718 +0.000000 -0.928675 0.370895 +0.000000 -0.856957 0.515388 +0.000000 -0.840988 0.541054 +0.000000 -0.928675 0.370895 +0.000000 -0.936432 0.350850 +0.000000 -0.856957 0.515388 +0.000000 -0.982332 0.187147 +0.000000 -0.936432 0.350850 +0.000000 -0.928675 0.370895 +0.000000 -0.982332 0.187147 +0.000000 -0.986500 0.163761 +0.000000 -0.936432 0.350850 +0.000000 -1.000000 0.000000 +0.000000 -0.986500 0.163761 +0.000000 -0.982332 0.187147 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 -0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.000000 0.970142 0.242536 +0.981845 0.000000 -0.189685 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.000000 0.000000 -1.000000 +0.181109 0.000000 -0.983463 +0.000000 0.000000 -1.000000 +0.200637 0.000000 -0.979666 +0.181109 0.000000 -0.983463 +0.000000 0.000000 -1.000000 +0.200637 0.000000 -0.979666 +0.366314 0.000000 -0.930491 +0.181109 0.000000 -0.983463 +0.393169 0.000000 -0.919466 +0.366314 0.000000 -0.930491 +0.200637 0.000000 -0.979666 +0.393169 0.000000 -0.919466 +0.544612 0.000000 -0.838688 +0.366314 0.000000 -0.930491 +0.563034 0.000000 -0.826434 +0.544612 0.000000 -0.838688 +0.393169 0.000000 -0.919466 +0.563034 0.000000 -0.826434 +0.704015 0.000000 -0.710185 +0.544612 0.000000 -0.838688 +0.704015 0.000000 -0.710185 +0.704015 0.000000 -0.710185 +0.563034 0.000000 -0.826434 +0.704015 0.000000 -0.710185 +0.833903 0.000000 -0.551911 +0.704015 0.000000 -0.710185 +0.821489 0.000000 -0.570224 +0.833903 0.000000 -0.551911 +0.704015 0.000000 -0.710185 +0.916000 0.000000 -0.401178 +0.833903 0.000000 -0.551911 +0.821489 0.000000 -0.570224 +0.916000 0.000000 -0.401178 +0.927259 0.000000 -0.374420 +0.833903 0.000000 -0.551911 +0.977878 0.000000 -0.209178 +0.927259 0.000000 -0.374420 +0.916000 0.000000 -0.401178 +0.977878 0.000000 -0.209178 +0.981845 0.000000 -0.189685 +0.927259 0.000000 -0.374420 +0.999962 0.000000 -0.008727 +0.981845 0.000000 -0.189685 +0.977878 0.000000 -0.209178 +-0.999962 0.000000 -0.008727 +-0.981845 0.000000 -0.189685 +-0.999962 0.000000 -0.008727 +-0.181109 0.000000 -0.983463 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.181109 0.000000 -0.983463 +-0.200637 0.000000 -0.979666 +0.000000 0.000000 -1.000000 +-0.366314 0.000000 -0.930491 +-0.200637 0.000000 -0.979666 +-0.181109 0.000000 -0.983463 +-0.366314 0.000000 -0.930491 +-0.393169 0.000000 -0.919466 +-0.200637 0.000000 -0.979666 +-0.544612 0.000000 -0.838688 +-0.393169 0.000000 -0.919466 +-0.366314 0.000000 -0.930491 +-0.544612 0.000000 -0.838688 +-0.563034 0.000000 -0.826434 +-0.393169 0.000000 -0.919466 +-0.704015 0.000000 -0.710185 +-0.563034 0.000000 -0.826434 +-0.544612 0.000000 -0.838688 +-0.704015 0.000000 -0.710185 +-0.704015 0.000000 -0.710185 +-0.563034 0.000000 -0.826434 +-0.833903 0.000000 -0.551911 +-0.704015 0.000000 -0.710185 +-0.704015 0.000000 -0.710185 +-0.833903 0.000000 -0.551911 +-0.821489 0.000000 -0.570224 +-0.704015 0.000000 -0.710185 +-0.833903 0.000000 -0.551911 +-0.916000 0.000000 -0.401178 +-0.821489 0.000000 -0.570224 +-0.927259 0.000000 -0.374420 +-0.916000 0.000000 -0.401178 +-0.833903 0.000000 -0.551911 +-0.927259 0.000000 -0.374420 +-0.977878 0.000000 -0.209178 +-0.916000 0.000000 -0.401178 +-0.981845 0.000000 -0.189685 +-0.977878 0.000000 -0.209178 +-0.927259 0.000000 -0.374420 +-0.981845 0.000000 -0.189685 +-0.999962 0.000000 -0.008727 +-0.977878 0.000000 -0.209178 +-0.999095 0.041629 -0.008727 +-0.989403 -0.144936 -0.008642 +-0.999095 0.041629 -0.008727 +0.000000 -1.000000 0.000000 +-0.185993 -0.982550 -0.001625 +0.000000 -1.000000 0.000000 +-0.185993 -0.982550 -0.001625 +-0.185993 -0.982550 -0.001625 +0.000000 -1.000000 0.000000 +-0.185993 -0.982550 -0.001625 +-0.376516 -0.926404 -0.003289 +-0.185993 -0.982550 -0.001625 +-0.376516 -0.926404 -0.003289 +-0.376516 -0.926404 -0.003289 +-0.185993 -0.982550 -0.001625 +-0.376516 -0.926404 -0.003289 +-0.559485 -0.828826 -0.004887 +-0.376516 -0.926404 -0.003289 +-0.559485 -0.828826 -0.004887 +-0.559485 -0.828826 -0.004887 +-0.376516 -0.926404 -0.003289 +-0.559485 -0.828826 -0.004887 +-0.643966 -0.765033 -0.005625 +-0.559485 -0.828826 -0.004887 +-0.643966 -0.765033 -0.005625 +-0.643966 -0.765033 -0.005625 +-0.559485 -0.828826 -0.004887 +-0.643966 -0.765033 -0.005625 +-0.721647 -0.692232 -0.006303 +-0.643966 -0.765033 -0.005625 +-0.721647 -0.692232 -0.006303 +-0.721647 -0.692232 -0.006303 +-0.643966 -0.765033 -0.005625 +-0.721647 -0.692232 -0.006303 +-0.791148 -0.611585 -0.006910 +-0.721647 -0.692232 -0.006303 +-0.791148 -0.611585 -0.006910 +-0.791148 -0.611585 -0.006910 +-0.721647 -0.692232 -0.006303 +-0.791148 -0.611585 -0.006910 +-0.851367 -0.524518 -0.007436 +-0.791148 -0.611585 -0.006910 +-0.851367 -0.524518 -0.007436 +-0.851367 -0.524518 -0.007436 +-0.791148 -0.611585 -0.006910 +-0.851367 -0.524518 -0.007436 +-0.941240 -0.337639 -0.008221 +-0.851367 -0.524518 -0.007436 +-0.941240 -0.337639 -0.008221 +-0.941240 -0.337639 -0.008221 +-0.851367 -0.524518 -0.007436 +-0.941240 -0.337639 -0.008221 +-0.989403 -0.144936 -0.008642 +-0.941240 -0.337639 -0.008221 +-0.989403 -0.144936 -0.008642 +-0.989403 -0.144936 -0.008642 +-0.941240 -0.337639 -0.008221 +-0.989403 -0.144936 -0.008642 +-0.999095 0.041629 -0.008727 +-0.989403 -0.144936 -0.008642 +0.177860 -0.984055 -0.001554 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.975760 -0.218677 -0.008523 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.975760 -0.218677 -0.008523 +0.975760 -0.218677 -0.008523 +0.999095 -0.041629 -0.008727 +0.917310 -0.398094 -0.008012 +0.975760 -0.218677 -0.008523 +0.975760 -0.218677 -0.008523 +0.917310 -0.398094 -0.008012 +0.917310 -0.398094 -0.008012 +0.975760 -0.218677 -0.008523 +0.821983 -0.569467 -0.007180 +0.917310 -0.398094 -0.008012 +0.917310 -0.398094 -0.008012 +0.821983 -0.569467 -0.007180 +0.821983 -0.569467 -0.007180 +0.917310 -0.398094 -0.008012 +0.692206 -0.721675 -0.006046 +0.821983 -0.569467 -0.007180 +0.821983 -0.569467 -0.007180 +0.692206 -0.721675 -0.006046 +0.692206 -0.721675 -0.006046 +0.821983 -0.569467 -0.007180 +0.534733 -0.845008 -0.004671 +0.692206 -0.721675 -0.006046 +0.692206 -0.721675 -0.006046 +0.534733 -0.845008 -0.004671 +0.534733 -0.845008 -0.004671 +0.692206 -0.721675 -0.006046 +0.359547 -0.933122 -0.003140 +0.534733 -0.845008 -0.004671 +0.534733 -0.845008 -0.004671 +0.359547 -0.933122 -0.003140 +0.359547 -0.933122 -0.003140 +0.534733 -0.845008 -0.004671 +0.177860 -0.984055 -0.001554 +0.359547 -0.933122 -0.003140 +0.359547 -0.933122 -0.003140 +0.177860 -0.984055 -0.001554 +0.177860 -0.984055 -0.001554 +0.359547 -0.933122 -0.003140 +0.000000 -1.000000 0.000000 +0.177860 -0.984055 -0.001554 +0.177860 -0.984055 -0.001554 +0.999095 0.041629 -0.008727 +0.999962 0.000000 -0.008734 +0.999095 0.041629 -0.008727 +0.999962 0.000000 -0.008734 +0.999095 0.041629 -0.008727 +0.999962 0.000000 -0.008734 +-0.999095 -0.041629 -0.008727 +-0.975760 -0.218677 -0.008523 +-0.999095 -0.041629 -0.008727 +0.000000 -1.000000 0.000000 +-0.177860 -0.984055 -0.001554 +0.000000 -1.000000 0.000000 +-0.177860 -0.984055 -0.001554 +-0.177860 -0.984055 -0.001554 +0.000000 -1.000000 0.000000 +-0.177860 -0.984055 -0.001554 +-0.359547 -0.933122 -0.003140 +-0.177860 -0.984055 -0.001554 +-0.359547 -0.933122 -0.003140 +-0.359547 -0.933122 -0.003140 +-0.177860 -0.984055 -0.001554 +-0.359547 -0.933122 -0.003140 +-0.534733 -0.845008 -0.004671 +-0.359547 -0.933122 -0.003140 +-0.534733 -0.845008 -0.004671 +-0.534733 -0.845008 -0.004671 +-0.359547 -0.933122 -0.003140 +-0.534733 -0.845008 -0.004671 +-0.692206 -0.721675 -0.006046 +-0.534733 -0.845008 -0.004671 +-0.692206 -0.721675 -0.006046 +-0.692206 -0.721675 -0.006046 +-0.534733 -0.845008 -0.004671 +-0.692206 -0.721675 -0.006046 +-0.821983 -0.569467 -0.007180 +-0.692206 -0.721675 -0.006046 +-0.821983 -0.569467 -0.007180 +-0.821983 -0.569467 -0.007180 +-0.692206 -0.721675 -0.006046 +-0.821983 -0.569467 -0.007180 +-0.917310 -0.398094 -0.008012 +-0.821983 -0.569467 -0.007180 +-0.917310 -0.398094 -0.008012 +-0.917310 -0.398094 -0.008012 +-0.821983 -0.569467 -0.007180 +-0.917310 -0.398094 -0.008012 +-0.975760 -0.218677 -0.008523 +-0.917310 -0.398094 -0.008012 +-0.975760 -0.218677 -0.008523 +-0.975760 -0.218677 -0.008523 +-0.917310 -0.398094 -0.008012 +-0.975760 -0.218677 -0.008523 +-0.999095 -0.041629 -0.008727 +-0.975760 -0.218677 -0.008523 +-0.177853 0.984006 -0.010076 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +-0.999095 0.041629 -0.008727 +-0.975748 0.218663 -0.010076 +-0.999095 0.041629 -0.008727 +-0.975748 0.218663 -0.010076 +-0.975748 0.218663 -0.010076 +-0.999095 0.041629 -0.008727 +-0.975748 0.218663 -0.010076 +-0.917289 0.398065 -0.011152 +-0.975748 0.218663 -0.010076 +-0.917289 0.398065 -0.011152 +-0.917289 0.398065 -0.011152 +-0.975748 0.218663 -0.010076 +-0.917289 0.398065 -0.011152 +-0.821958 0.569425 -0.011850 +-0.917289 0.398065 -0.011152 +-0.821958 0.569425 -0.011850 +-0.821958 0.569425 -0.011850 +-0.917289 0.398065 -0.011152 +-0.821958 0.569425 -0.011850 +-0.692181 0.721623 -0.012092 +-0.821958 0.569425 -0.011850 +-0.692181 0.721623 -0.012092 +-0.692181 0.721623 -0.012092 +-0.821958 0.569425 -0.011850 +-0.534712 0.844951 -0.011850 +-0.692181 0.721623 -0.012092 +-0.692181 0.721623 -0.012092 +-0.534712 0.844951 -0.011850 +-0.534712 0.844951 -0.011850 +-0.692181 0.721623 -0.012092 +-0.359533 0.933066 -0.011152 +-0.534712 0.844951 -0.011850 +-0.534712 0.844951 -0.011850 +-0.359533 0.933066 -0.011152 +-0.359533 0.933066 -0.011152 +-0.534712 0.844951 -0.011850 +-0.177853 0.984006 -0.010076 +-0.359533 0.933066 -0.011152 +-0.359533 0.933066 -0.011152 +-0.177853 0.984006 -0.010076 +-0.177853 0.984006 -0.010076 +-0.359533 0.933066 -0.011152 +0.000000 0.999962 -0.008727 +-0.177853 0.984006 -0.010076 +-0.177853 0.984006 -0.010076 +0.989390 0.144922 -0.010266 +0.999095 -0.041629 -0.008727 +0.999095 -0.041629 -0.008727 +0.000000 0.999962 -0.008727 +0.185985 0.982499 -0.010266 +0.000000 0.999962 -0.008727 +0.185985 0.982499 -0.010266 +0.185985 0.982499 -0.010266 +0.000000 0.999962 -0.008727 +0.185985 0.982499 -0.010266 +0.376499 0.926346 -0.011510 +0.185985 0.982499 -0.010266 +0.376499 0.926346 -0.011510 +0.376499 0.926346 -0.011510 +0.185985 0.982499 -0.010266 +0.376499 0.926346 -0.011510 +0.559460 0.828766 -0.012323 +0.376499 0.926346 -0.011510 +0.559460 0.828766 -0.012323 +0.559460 0.828766 -0.012323 +0.376499 0.926346 -0.011510 +0.559460 0.828766 -0.012323 +0.643939 0.764974 -0.012534 +0.559460 0.828766 -0.012323 +0.643939 0.764974 -0.012534 +0.643939 0.764974 -0.012534 +0.559460 0.828766 -0.012323 +0.643939 0.764974 -0.012534 +0.721618 0.692177 -0.012606 +0.643939 0.764974 -0.012534 +0.721618 0.692177 -0.012606 +0.721618 0.692177 -0.012606 +0.643939 0.764974 -0.012534 +0.791119 0.611534 -0.012534 +0.721618 0.692177 -0.012606 +0.721618 0.692177 -0.012606 +0.791119 0.611534 -0.012534 +0.791119 0.611534 -0.012534 +0.721618 0.692177 -0.012606 +0.851338 0.524473 -0.012323 +0.791119 0.611534 -0.012534 +0.791119 0.611534 -0.012534 +0.851338 0.524473 -0.012323 +0.851338 0.524473 -0.012323 +0.791119 0.611534 -0.012534 +0.941216 0.337608 -0.011510 +0.851338 0.524473 -0.012323 +0.851338 0.524473 -0.012323 +0.941216 0.337608 -0.011510 +0.941216 0.337608 -0.011510 +0.851338 0.524473 -0.012323 +0.989390 0.144922 -0.010266 +0.941216 0.337608 -0.011510 +0.941216 0.337608 -0.011510 +0.989390 0.144922 -0.010266 +0.989390 0.144922 -0.010266 +0.941216 0.337608 -0.011510 +0.999095 -0.041629 -0.008727 +0.989390 0.144922 -0.010266 +0.989390 0.144922 -0.010266 +0.975748 0.218663 -0.010076 +0.999095 0.041629 -0.008727 +0.999095 0.041629 -0.008727 +0.000000 0.999962 -0.008727 +0.177853 0.984006 -0.010076 +0.000000 0.999962 -0.008727 +0.177853 0.984006 -0.010076 +0.177853 0.984006 -0.010076 +0.000000 0.999962 -0.008727 +0.177853 0.984006 -0.010076 +0.359533 0.933066 -0.011152 +0.177853 0.984006 -0.010076 +0.359533 0.933066 -0.011152 +0.359533 0.933066 -0.011152 +0.177853 0.984006 -0.010076 +0.359533 0.933066 -0.011152 +0.534712 0.844951 -0.011850 +0.359533 0.933066 -0.011152 +0.534712 0.844951 -0.011850 +0.534712 0.844951 -0.011850 +0.359533 0.933066 -0.011152 +0.534712 0.844951 -0.011850 +0.692181 0.721623 -0.012092 +0.534712 0.844951 -0.011850 +0.692181 0.721623 -0.012092 +0.692181 0.721623 -0.012092 +0.534712 0.844951 -0.011850 +0.821958 0.569425 -0.011850 +0.692181 0.721623 -0.012092 +0.692181 0.721623 -0.012092 +0.821958 0.569425 -0.011850 +0.821958 0.569425 -0.011850 +0.692181 0.721623 -0.012092 +0.917289 0.398065 -0.011152 +0.821958 0.569425 -0.011850 +0.821958 0.569425 -0.011850 +0.917289 0.398065 -0.011152 +0.917289 0.398065 -0.011152 +0.821958 0.569425 -0.011850 +0.975748 0.218663 -0.010076 +0.917289 0.398065 -0.011152 +0.917289 0.398065 -0.011152 +0.975748 0.218663 -0.010076 +0.975748 0.218663 -0.010076 +0.917289 0.398065 -0.011152 +0.999095 0.041629 -0.008727 +0.975748 0.218663 -0.010076 +0.975748 0.218663 -0.010076 +-0.181948 0.983255 -0.010236 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +-0.999959 0.000000 -0.009098 +-0.983252 0.181948 -0.010534 +-0.999959 0.000000 -0.009098 +-0.983252 0.181948 -0.010534 +-0.983252 0.181948 -0.010534 +-0.999959 0.000000 -0.009098 +-0.983252 0.181948 -0.010534 +-0.929727 0.368065 -0.011671 +-0.983252 0.181948 -0.010534 +-0.929727 0.368065 -0.011671 +-0.929727 0.368065 -0.011671 +-0.983252 0.181948 -0.010534 +-0.929727 0.368065 -0.011671 +-0.836933 0.547165 -0.012390 +-0.929727 0.368065 -0.011671 +-0.836933 0.547165 -0.012390 +-0.836933 0.547165 -0.012390 +-0.929727 0.368065 -0.011671 +-0.836933 0.547165 -0.012390 +-0.776292 0.630248 -0.012563 +-0.836933 0.547165 -0.012390 +-0.776292 0.630248 -0.012563 +-0.776292 0.630248 -0.012563 +-0.836933 0.547165 -0.012390 +-0.776292 0.630248 -0.012563 +-0.707049 0.707052 -0.012603 +-0.776292 0.630248 -0.012563 +-0.707049 0.707052 -0.012603 +-0.707049 0.707052 -0.012603 +-0.776292 0.630248 -0.012563 +-0.630246 0.776295 -0.012509 +-0.707049 0.707052 -0.012603 +-0.707049 0.707052 -0.012603 +-0.630246 0.776295 -0.012509 +-0.630246 0.776295 -0.012509 +-0.707049 0.707052 -0.012603 +-0.547163 0.836936 -0.012282 +-0.630246 0.776295 -0.012509 +-0.630246 0.776295 -0.012509 +-0.547163 0.836936 -0.012282 +-0.547163 0.836936 -0.012282 +-0.630246 0.776295 -0.012509 +-0.368063 0.929730 -0.011462 +-0.547163 0.836936 -0.012282 +-0.547163 0.836936 -0.012282 +-0.368063 0.929730 -0.011462 +-0.368063 0.929730 -0.011462 +-0.547163 0.836936 -0.012282 +-0.181948 0.983255 -0.010236 +-0.368063 0.929730 -0.011462 +-0.368063 0.929730 -0.011462 +-0.181948 0.983255 -0.010236 +-0.181948 0.983255 -0.010236 +-0.368063 0.929730 -0.011462 +0.000000 0.999962 -0.008727 +-0.181948 0.983255 -0.010236 +-0.181948 0.983255 -0.010236 +-0.181949 0.983255 -0.010169 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +-0.999962 0.000000 -0.008727 +-0.983255 0.181949 -0.010169 +-0.999962 0.000000 -0.008727 +-0.983255 0.181949 -0.010169 +-0.983255 0.181949 -0.010169 +-0.999962 0.000000 -0.008727 +-0.983255 0.181949 -0.010169 +-0.929731 0.368065 -0.011326 +-0.983255 0.181949 -0.010169 +-0.929731 0.368065 -0.011326 +-0.929731 0.368065 -0.011326 +-0.983255 0.181949 -0.010169 +-0.929731 0.368065 -0.011326 +-0.836937 0.547166 -0.012079 +-0.929731 0.368065 -0.011326 +-0.836937 0.547166 -0.012079 +-0.836937 0.547166 -0.012079 +-0.929731 0.368065 -0.011326 +-0.836937 0.547166 -0.012079 +-0.776296 0.630249 -0.012275 +-0.836937 0.547166 -0.012079 +-0.776296 0.630249 -0.012275 +-0.776296 0.630249 -0.012275 +-0.836937 0.547166 -0.012079 +-0.776296 0.630249 -0.012275 +-0.707053 0.707053 -0.012341 +-0.776296 0.630249 -0.012275 +-0.707053 0.707053 -0.012341 +-0.707053 0.707053 -0.012341 +-0.776296 0.630249 -0.012275 +-0.630249 0.776296 -0.012275 +-0.707053 0.707053 -0.012341 +-0.707053 0.707053 -0.012341 +-0.630249 0.776296 -0.012275 +-0.630249 0.776296 -0.012275 +-0.707053 0.707053 -0.012341 +-0.547166 0.836937 -0.012079 +-0.630249 0.776296 -0.012275 +-0.630249 0.776296 -0.012275 +-0.547166 0.836937 -0.012079 +-0.547166 0.836937 -0.012079 +-0.630249 0.776296 -0.012275 +-0.368065 0.929731 -0.011326 +-0.547166 0.836937 -0.012079 +-0.547166 0.836937 -0.012079 +-0.368065 0.929731 -0.011326 +-0.368065 0.929731 -0.011326 +-0.547166 0.836937 -0.012079 +-0.181949 0.983255 -0.010169 +-0.368065 0.929731 -0.011326 +-0.368065 0.929731 -0.011326 +-0.181949 0.983255 -0.010169 +-0.181949 0.983255 -0.010169 +-0.368065 0.929731 -0.011326 +0.000000 0.999962 -0.008727 +-0.181949 0.983255 -0.010169 +-0.181949 0.983255 -0.010169 +-0.983255 -0.181949 -0.010169 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +0.000000 -0.999962 -0.008727 +-0.181949 -0.983255 -0.010169 +0.000000 -0.999962 -0.008727 +-0.181949 -0.983255 -0.010169 +-0.181949 -0.983255 -0.010169 +0.000000 -0.999962 -0.008727 +-0.181949 -0.983255 -0.010169 +-0.368065 -0.929731 -0.011326 +-0.181949 -0.983255 -0.010169 +-0.368065 -0.929731 -0.011326 +-0.368065 -0.929731 -0.011326 +-0.181949 -0.983255 -0.010169 +-0.368065 -0.929731 -0.011326 +-0.547166 -0.836937 -0.012079 +-0.368065 -0.929731 -0.011326 +-0.547166 -0.836937 -0.012079 +-0.547166 -0.836937 -0.012079 +-0.368065 -0.929731 -0.011326 +-0.547166 -0.836937 -0.012079 +-0.630249 -0.776296 -0.012275 +-0.547166 -0.836937 -0.012079 +-0.630249 -0.776296 -0.012275 +-0.630249 -0.776296 -0.012275 +-0.547166 -0.836937 -0.012079 +-0.630249 -0.776296 -0.012275 +-0.707053 -0.707053 -0.012341 +-0.630249 -0.776296 -0.012275 +-0.707053 -0.707053 -0.012341 +-0.707053 -0.707053 -0.012341 +-0.630249 -0.776296 -0.012275 +-0.776296 -0.630249 -0.012275 +-0.707053 -0.707053 -0.012341 +-0.707053 -0.707053 -0.012341 +-0.776296 -0.630249 -0.012275 +-0.776296 -0.630249 -0.012275 +-0.707053 -0.707053 -0.012341 +-0.836937 -0.547166 -0.012079 +-0.776296 -0.630249 -0.012275 +-0.776296 -0.630249 -0.012275 +-0.836937 -0.547166 -0.012079 +-0.836937 -0.547166 -0.012079 +-0.776296 -0.630249 -0.012275 +-0.929731 -0.368065 -0.011326 +-0.836937 -0.547166 -0.012079 +-0.836937 -0.547166 -0.012079 +-0.929731 -0.368065 -0.011326 +-0.929731 -0.368065 -0.011326 +-0.836937 -0.547166 -0.012079 +-0.983255 -0.181949 -0.010169 +-0.929731 -0.368065 -0.011326 +-0.929731 -0.368065 -0.011326 +-0.983255 -0.181949 -0.010169 +-0.983255 -0.181949 -0.010169 +-0.929731 -0.368065 -0.011326 +-0.999962 0.000000 -0.008727 +-0.983255 -0.181949 -0.010169 +-0.983255 -0.181949 -0.010169 +0.181949 -0.983255 -0.010169 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.999962 0.000000 -0.008727 +0.983255 -0.181949 -0.010169 +0.999962 0.000000 -0.008727 +0.983255 -0.181949 -0.010169 +0.983255 -0.181949 -0.010169 +0.999962 0.000000 -0.008727 +0.983255 -0.181949 -0.010169 +0.929731 -0.368065 -0.011326 +0.983255 -0.181949 -0.010169 +0.929731 -0.368065 -0.011326 +0.929731 -0.368065 -0.011326 +0.983255 -0.181949 -0.010169 +0.929731 -0.368065 -0.011326 +0.836937 -0.547166 -0.012079 +0.929731 -0.368065 -0.011326 +0.836937 -0.547166 -0.012079 +0.836937 -0.547166 -0.012079 +0.929731 -0.368065 -0.011326 +0.836937 -0.547166 -0.012079 +0.776296 -0.630249 -0.012275 +0.836937 -0.547166 -0.012079 +0.776296 -0.630249 -0.012275 +0.776296 -0.630249 -0.012275 +0.836937 -0.547166 -0.012079 +0.776296 -0.630249 -0.012275 +0.707053 -0.707053 -0.012341 +0.776296 -0.630249 -0.012275 +0.707053 -0.707053 -0.012341 +0.707053 -0.707053 -0.012341 +0.776296 -0.630249 -0.012275 +0.630249 -0.776296 -0.012275 +0.707053 -0.707053 -0.012341 +0.707053 -0.707053 -0.012341 +0.630249 -0.776296 -0.012275 +0.630249 -0.776296 -0.012275 +0.707053 -0.707053 -0.012341 +0.547166 -0.836937 -0.012079 +0.630249 -0.776296 -0.012275 +0.630249 -0.776296 -0.012275 +0.547166 -0.836937 -0.012079 +0.547166 -0.836937 -0.012079 +0.630249 -0.776296 -0.012275 +0.368065 -0.929731 -0.011326 +0.547166 -0.836937 -0.012079 +0.547166 -0.836937 -0.012079 +0.368065 -0.929731 -0.011326 +0.368065 -0.929731 -0.011326 +0.547166 -0.836937 -0.012079 +0.181949 -0.983255 -0.010169 +0.368065 -0.929731 -0.011326 +0.368065 -0.929731 -0.011326 +0.181949 -0.983255 -0.010169 +0.181949 -0.983255 -0.010169 +0.368065 -0.929731 -0.011326 +0.000000 -0.999962 -0.008727 +0.181949 -0.983255 -0.010169 +0.181949 -0.983255 -0.010169 +0.983255 0.181949 -0.010169 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.000000 0.999962 -0.008727 +0.181949 0.983255 -0.010169 +0.000000 0.999962 -0.008727 +0.181949 0.983255 -0.010169 +0.181949 0.983255 -0.010169 +0.000000 0.999962 -0.008727 +0.181949 0.983255 -0.010169 +0.368065 0.929731 -0.011326 +0.181949 0.983255 -0.010169 +0.368065 0.929731 -0.011326 +0.368065 0.929731 -0.011326 +0.181949 0.983255 -0.010169 +0.368065 0.929731 -0.011326 +0.547166 0.836937 -0.012079 +0.368065 0.929731 -0.011326 +0.547166 0.836937 -0.012079 +0.547166 0.836937 -0.012079 +0.368065 0.929731 -0.011326 +0.547166 0.836937 -0.012079 +0.630249 0.776296 -0.012275 +0.547166 0.836937 -0.012079 +0.630249 0.776296 -0.012275 +0.630249 0.776296 -0.012275 +0.547166 0.836937 -0.012079 +0.630249 0.776296 -0.012275 +0.707053 0.707053 -0.012341 +0.630249 0.776296 -0.012275 +0.707053 0.707053 -0.012341 +0.707053 0.707053 -0.012341 +0.630249 0.776296 -0.012275 +0.776296 0.630249 -0.012275 +0.707053 0.707053 -0.012341 +0.707053 0.707053 -0.012341 +0.776296 0.630249 -0.012275 +0.776296 0.630249 -0.012275 +0.707053 0.707053 -0.012341 +0.836937 0.547166 -0.012079 +0.776296 0.630249 -0.012275 +0.776296 0.630249 -0.012275 +0.836937 0.547166 -0.012079 +0.836937 0.547166 -0.012079 +0.776296 0.630249 -0.012275 +0.929731 0.368065 -0.011326 +0.836937 0.547166 -0.012079 +0.836937 0.547166 -0.012079 +0.929731 0.368065 -0.011326 +0.929731 0.368065 -0.011326 +0.836937 0.547166 -0.012079 +0.983255 0.181949 -0.010169 +0.929731 0.368065 -0.011326 +0.929731 0.368065 -0.011326 +0.983255 0.181949 -0.010169 +0.983255 0.181949 -0.010169 +0.929731 0.368065 -0.011326 +0.999962 0.000000 -0.008727 +0.983255 0.181949 -0.010169 +0.983255 0.181949 -0.010169 +0.978781 -0.204909 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.204909 -0.978781 0.000000 +0.000000 -1.000000 0.000000 +0.204909 -0.978781 0.000000 +0.204909 -0.978781 0.000000 +0.000000 -1.000000 0.000000 +0.397177 -0.917742 0.000000 +0.204909 -0.978781 0.000000 +0.204909 -0.978781 0.000000 +0.397177 -0.917742 0.000000 +0.397177 -0.917742 0.000000 +0.204909 -0.978781 0.000000 +0.566635 -0.823969 0.000000 +0.397177 -0.917742 0.000000 +0.397177 -0.917742 0.000000 +0.566635 -0.823969 0.000000 +0.566635 -0.823969 0.000000 +0.397177 -0.917742 0.000000 +0.566635 -0.823969 0.000000 +0.707107 -0.707107 0.000000 +0.566635 -0.823969 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.566635 -0.823969 0.000000 +0.823969 -0.566635 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.823969 -0.566635 0.000000 +0.823969 -0.566635 0.000000 +0.707107 -0.707107 0.000000 +0.917742 -0.397177 0.000000 +0.823969 -0.566635 0.000000 +0.823969 -0.566635 0.000000 +0.917742 -0.397177 0.000000 +0.917742 -0.397177 0.000000 +0.823969 -0.566635 0.000000 +0.978781 -0.204909 0.000000 +0.917742 -0.397177 0.000000 +0.917742 -0.397177 0.000000 +0.978781 -0.204909 0.000000 +0.978781 -0.204909 0.000000 +0.917742 -0.397177 0.000000 +1.000000 0.000000 0.000000 +0.978781 -0.204909 0.000000 +0.978781 -0.204909 0.000000 +0.204909 0.978781 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +1.000000 0.000000 0.000000 +0.978781 0.204909 0.000000 +1.000000 0.000000 0.000000 +0.978781 0.204909 0.000000 +0.978781 0.204909 0.000000 +1.000000 0.000000 0.000000 +0.917742 0.397177 0.000000 +0.978781 0.204909 0.000000 +0.978781 0.204909 0.000000 +0.917742 0.397177 0.000000 +0.917742 0.397177 0.000000 +0.978781 0.204909 0.000000 +0.823969 0.566635 0.000000 +0.917742 0.397177 0.000000 +0.917742 0.397177 0.000000 +0.823969 0.566635 0.000000 +0.823969 0.566635 0.000000 +0.917742 0.397177 0.000000 +0.823969 0.566635 0.000000 +0.707107 0.707107 0.000000 +0.823969 0.566635 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.823969 0.566635 0.000000 +0.566635 0.823969 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.566635 0.823969 0.000000 +0.566635 0.823969 0.000000 +0.707107 0.707107 0.000000 +0.397177 0.917742 0.000000 +0.566635 0.823969 0.000000 +0.566635 0.823969 0.000000 +0.397177 0.917742 0.000000 +0.397177 0.917742 0.000000 +0.566635 0.823969 0.000000 +0.204909 0.978781 0.000000 +0.397177 0.917742 0.000000 +0.397177 0.917742 0.000000 +0.204909 0.978781 0.000000 +0.204909 0.978781 0.000000 +0.397177 0.917742 0.000000 +0.000000 1.000000 0.000000 +0.204909 0.978781 0.000000 +0.204909 0.978781 0.000000 +-0.566635 -0.823969 0.000000 +-0.397177 -0.917742 0.000000 +-0.397177 -0.917742 0.000000 +-0.204909 -0.978781 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.204909 -0.978781 0.000000 +-0.204909 -0.978781 0.000000 +0.000000 -1.000000 0.000000 +-0.204909 -0.978781 0.000000 +-0.397177 -0.917742 0.000000 +-0.204909 -0.978781 0.000000 +-0.397177 -0.917742 0.000000 +-0.397177 -0.917742 0.000000 +-0.204909 -0.978781 0.000000 +-0.978781 -0.204909 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.978781 -0.204909 0.000000 +-0.978781 -0.204909 0.000000 +-1.000000 0.000000 0.000000 +-0.978781 -0.204909 0.000000 +-0.917742 -0.397177 0.000000 +-0.978781 -0.204909 0.000000 +-0.917742 -0.397177 0.000000 +-0.917742 -0.397177 0.000000 +-0.978781 -0.204909 0.000000 +-0.917742 -0.397177 0.000000 +-0.823969 -0.566635 0.000000 +-0.917742 -0.397177 0.000000 +-0.823969 -0.566635 0.000000 +-0.823969 -0.566635 0.000000 +-0.917742 -0.397177 0.000000 +-0.707107 -0.707107 0.000000 +-0.823969 -0.566635 0.000000 +-0.823969 -0.566635 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.823969 -0.566635 0.000000 +-0.707107 -0.707107 0.000000 +-0.566635 -0.823969 0.000000 +-0.707107 -0.707107 0.000000 +-0.566635 -0.823969 0.000000 +-0.566635 -0.823969 0.000000 +-0.707107 -0.707107 0.000000 +-0.397177 -0.917742 0.000000 +-0.566635 -0.823969 0.000000 +-0.566635 -0.823969 0.000000 +-0.204909 0.978781 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.978781 0.204909 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.978781 0.204909 0.000000 +-0.978781 0.204909 0.000000 +-1.000000 0.000000 0.000000 +-0.917742 0.397177 0.000000 +-0.978781 0.204909 0.000000 +-0.978781 0.204909 0.000000 +-0.917742 0.397177 0.000000 +-0.917742 0.397177 0.000000 +-0.978781 0.204909 0.000000 +-0.917742 0.397177 0.000000 +-0.823969 0.566635 0.000000 +-0.917742 0.397177 0.000000 +-0.823969 0.566635 0.000000 +-0.823969 0.566635 0.000000 +-0.917742 0.397177 0.000000 +-0.707107 0.707107 0.000000 +-0.823969 0.566635 0.000000 +-0.823969 0.566635 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.823969 0.566635 0.000000 +-0.707107 0.707107 0.000000 +-0.566635 0.823969 0.000000 +-0.707107 0.707107 0.000000 +-0.566635 0.823969 0.000000 +-0.566635 0.823969 0.000000 +-0.707107 0.707107 0.000000 +-0.566635 0.823969 0.000000 +-0.397177 0.917742 0.000000 +-0.566635 0.823969 0.000000 +-0.397177 0.917742 0.000000 +-0.397177 0.917742 0.000000 +-0.566635 0.823969 0.000000 +-0.204909 0.978781 0.000000 +-0.397177 0.917742 0.000000 +-0.397177 0.917742 0.000000 +-0.204909 0.978781 0.000000 +-0.204909 0.978781 0.000000 +-0.397177 0.917742 0.000000 +0.000000 1.000000 0.000000 +-0.204909 0.978781 0.000000 +-0.204909 0.978781 0.000000 +0.000000 -0.204909 -0.978781 +0.000000 -0.397177 -0.917742 +0.000000 -0.204909 -0.978781 +0.000000 -0.204909 -0.978781 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -0.204909 -0.978781 +0.000000 -0.204909 -0.978781 +0.000000 0.000000 -1.000000 +0.000000 -0.978781 -0.204909 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -0.978781 -0.204909 +0.000000 -0.978781 -0.204909 +0.000000 -1.000000 0.000000 +0.000000 -0.978781 -0.204909 +0.000000 -0.917742 -0.397177 +0.000000 -0.978781 -0.204909 +0.000000 -0.917742 -0.397177 +0.000000 -0.917742 -0.397177 +0.000000 -0.978781 -0.204909 +0.000000 -0.823969 -0.566635 +0.000000 -0.917742 -0.397177 +0.000000 -0.917742 -0.397177 +0.000000 -0.823969 -0.566635 +0.000000 -0.823969 -0.566635 +0.000000 -0.917742 -0.397177 +0.000000 -0.823969 -0.566635 +0.000000 -0.707107 -0.707107 +0.000000 -0.823969 -0.566635 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.823969 -0.566635 +0.000000 -0.566635 -0.823969 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.566635 -0.823969 +0.000000 -0.566635 -0.823969 +0.000000 -0.707107 -0.707107 +0.000000 -0.566635 -0.823969 +0.000000 -0.397177 -0.917742 +0.000000 -0.566635 -0.823969 +0.000000 -0.397177 -0.917742 +0.000000 -0.397177 -0.917742 +0.000000 -0.566635 -0.823969 +0.000000 -0.397177 -0.917742 +0.000000 -0.204909 -0.978781 +0.000000 -0.397177 -0.917742 +0.000000 -0.204909 -0.978781 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -0.978781 -0.204909 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -0.978781 -0.204909 +0.000000 -0.978781 -0.204909 +0.000000 -1.000000 0.000000 +0.000000 -0.978781 -0.204909 +0.000000 -0.917742 -0.397177 +0.000000 -0.978781 -0.204909 +0.000000 -0.917742 -0.397177 +0.000000 -0.917742 -0.397177 +0.000000 -0.978781 -0.204909 +0.000000 -0.823969 -0.566635 +0.000000 -0.917742 -0.397177 +0.000000 -0.917742 -0.397177 +0.000000 -0.823969 -0.566635 +0.000000 -0.823969 -0.566635 +0.000000 -0.917742 -0.397177 +0.000000 -0.823969 -0.566635 +0.000000 -0.707107 -0.707107 +0.000000 -0.823969 -0.566635 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.823969 -0.566635 +0.000000 -0.566635 -0.823969 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.566635 -0.823969 +0.000000 -0.566635 -0.823969 +0.000000 -0.707107 -0.707107 +0.000000 -0.397177 -0.917742 +0.000000 -0.566635 -0.823969 +0.000000 -0.566635 -0.823969 +0.000000 -0.397177 -0.917742 +0.000000 -0.397177 -0.917742 +0.000000 -0.566635 -0.823969 +0.000000 -0.397177 -0.917742 +0.000000 -0.204909 -0.978781 +0.000000 -0.397177 -0.917742 +0.000000 -0.204909 -0.978781 +0.000000 -0.204909 -0.978781 +0.000000 -0.397177 -0.917742 +0.000000 0.000000 -1.000000 +0.000000 -0.204909 -0.978781 +0.000000 -0.204909 -0.978781 +-0.044699 0.983441 -0.175632 +0.000000 1.000000 0.000000 +-0.000001 1.000000 -0.000019 +-0.134416 0.838447 -0.528147 +-0.050149 0.707328 -0.705105 +-0.173749 0.709747 -0.682693 +-0.134416 0.838447 -0.528147 +-0.039885 0.831212 -0.554523 +-0.050149 0.707328 -0.705105 +-0.134416 0.838447 -0.528147 +-0.027868 0.923549 -0.382465 +-0.039885 0.831212 -0.554523 +-0.090411 0.930391 -0.355244 +-0.027868 0.923549 -0.382465 +-0.134416 0.838447 -0.528147 +-0.090411 0.930391 -0.355244 +-0.014437 0.980632 -0.195329 +-0.027868 0.923549 -0.382465 +-0.044699 0.983441 -0.175632 +-0.014437 0.980632 -0.195329 +-0.090411 0.930391 -0.355244 +-0.044699 0.983441 -0.175632 +-0.000001 1.000000 -0.000019 +-0.014437 0.980632 -0.195329 +-0.058414 0.556468 -0.828813 +-0.173749 0.709747 -0.682693 +-0.050149 0.707328 -0.705105 +-0.058414 0.556468 -0.828813 +-0.205785 0.551242 -0.808570 +-0.173749 0.709747 -0.682693 +-0.064482 0.384002 -0.921078 +-0.205785 0.551242 -0.808570 +-0.058414 0.556468 -0.828813 +-0.064482 0.384002 -0.921078 +-0.228791 0.373520 -0.898965 +-0.205785 0.551242 -0.808570 +-0.068194 0.196246 -0.978180 +-0.228791 0.373520 -0.898965 +-0.064482 0.384002 -0.921078 +-0.068194 0.196246 -0.978180 +-0.242217 0.188585 -0.951718 +-0.228791 0.373520 -0.898965 +-0.069447 0.000000 -0.997586 +-0.242217 0.188585 -0.951718 +-0.068194 0.196246 -0.978180 +-0.255155 0.007847 -0.966868 +-0.242217 0.188585 -0.951718 +-0.069447 0.000000 -0.997586 +-0.255155 0.007847 -0.966868 +-0.415436 0.195269 -0.888416 +-0.242217 0.188585 -0.951718 +-0.430357 0.015341 -0.902528 +-0.415436 0.195269 -0.888416 +-0.255155 0.007847 -0.966868 +-0.430357 0.015341 -0.902528 +-0.574346 0.201501 -0.793425 +-0.415436 0.195269 -0.888416 +-0.591300 0.022335 -0.806142 +-0.574346 0.201501 -0.793425 +-0.430357 0.015341 -0.902528 +-0.591300 0.022335 -0.806142 +-0.711767 0.206997 -0.671223 +-0.574346 0.201501 -0.793425 +-0.730767 0.028502 -0.682032 +-0.711767 0.206997 -0.671223 +-0.591300 0.022335 -0.806142 +-0.730767 0.028502 -0.682032 +-0.824567 0.211628 -0.524693 +-0.711767 0.206997 -0.671223 +-0.845212 0.033703 -0.533367 +-0.824567 0.211628 -0.524693 +-0.730767 0.028502 -0.682032 +-0.845212 0.033703 -0.533367 +-0.907529 0.215179 -0.360680 +-0.824567 0.211628 -0.524693 +-0.929589 0.037693 -0.366666 +-0.907529 0.215179 -0.360680 +-0.845212 0.033703 -0.533367 +-0.929589 0.037693 -0.366666 +-0.958676 0.217563 -0.183322 +-0.907529 0.215179 -0.360680 +-0.981637 0.040374 -0.186434 +-0.958676 0.217563 -0.183322 +-0.929589 0.037693 -0.366666 +-0.975797 0.218679 0.000000 +-0.981637 0.040374 -0.186434 +-0.999133 0.041631 0.000000 +-0.975797 0.218679 0.000000 +-0.958676 0.217563 -0.183322 +-0.981637 0.040374 -0.186434 +-0.917344 0.398095 0.000000 +-0.958676 0.217563 -0.183322 +-0.975797 0.218679 0.000000 +-0.917344 0.398095 0.000000 +-0.901405 0.397187 -0.172370 +-0.958676 0.217563 -0.183322 +-0.822014 0.569468 0.000000 +-0.901405 0.397187 -0.172370 +-0.917344 0.398095 0.000000 +-0.822014 0.569468 0.000000 +-0.807842 0.568795 -0.154479 +-0.901405 0.397187 -0.172370 +-0.692232 0.721675 0.000000 +-0.807842 0.568795 -0.154479 +-0.822014 0.569468 0.000000 +-0.692232 0.721675 0.000000 +-0.680363 0.721235 -0.130102 +-0.807842 0.568795 -0.154479 +-0.534753 0.845008 0.000000 +-0.680363 0.721235 -0.130102 +-0.692232 0.721675 0.000000 +-0.534753 0.845008 0.000000 +-0.525612 0.844766 -0.100510 +-0.680363 0.721235 -0.130102 +-0.359561 0.933122 0.000000 +-0.525612 0.844766 -0.100510 +-0.534753 0.845008 0.000000 +-0.359561 0.933122 0.000000 +-0.353419 0.933021 -0.067582 +-0.525612 0.844766 -0.100510 +-0.177866 0.984055 0.000000 +-0.353419 0.933021 -0.067582 +-0.359561 0.933122 0.000000 +-0.177866 0.984055 0.000000 +-0.174824 0.984032 -0.033431 +-0.353419 0.933021 -0.067582 +0.000000 1.000000 0.000000 +-0.174824 0.984032 -0.033431 +-0.177866 0.984055 0.000000 +0.000000 1.000000 0.000000 +-0.174824 0.984032 -0.033431 +0.000000 1.000000 0.000000 +-0.000001 1.000000 0.000000 +-0.174824 0.984032 -0.033431 +0.000000 1.000000 0.000000 +-0.000001 1.000000 0.000000 +-0.165658 0.983983 -0.065837 +-0.174824 0.984032 -0.033431 +0.000000 1.000000 0.000000 +-0.165658 0.983983 -0.065837 +-0.000001 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.150732 0.983911 -0.095914 +-0.165658 0.983983 -0.065837 +-0.000006 1.000000 -0.000005 +-0.150732 0.983911 -0.095914 +0.000000 1.000000 0.000000 +-0.000006 1.000000 -0.000005 +-0.130358 0.983816 -0.122932 +-0.150732 0.983911 -0.095914 +0.000000 1.000000 0.000000 +-0.130358 0.983816 -0.122932 +-0.000006 1.000000 -0.000005 +0.000000 1.000000 0.000000 +-0.105427 0.983704 -0.145641 +-0.130358 0.983816 -0.122932 +0.000000 1.000000 0.000000 +-0.105427 0.983704 -0.145641 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.076454 0.983577 -0.163497 +-0.105427 0.983704 -0.145641 +0.000000 1.000000 0.000000 +-0.076454 0.983577 -0.163497 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.044699 0.983441 -0.175632 +-0.076454 0.983577 -0.163497 +-0.174824 0.984032 -0.033431 +-0.334902 0.932805 -0.133100 +-0.353419 0.933021 -0.067582 +-0.334902 0.932805 -0.133100 +-0.174824 0.984032 -0.033431 +-0.165658 0.983983 -0.065837 +-0.353419 0.933021 -0.067582 +-0.498059 0.844248 -0.197944 +-0.525612 0.844766 -0.100510 +-0.498059 0.844248 -0.197944 +-0.353419 0.933021 -0.067582 +-0.334902 0.932805 -0.133100 +-0.525612 0.844766 -0.100510 +-0.644625 0.720294 -0.256194 +-0.680363 0.721235 -0.130102 +-0.644625 0.720294 -0.256194 +-0.525612 0.844766 -0.100510 +-0.498059 0.844248 -0.197944 +-0.680363 0.721235 -0.130102 +-0.765251 0.567356 -0.304134 +-0.807842 0.568795 -0.154479 +-0.765251 0.567356 -0.304134 +-0.680363 0.721235 -0.130102 +-0.644625 0.720294 -0.256194 +-0.807842 0.568795 -0.154479 +-0.853631 0.395244 -0.339259 +-0.901405 0.397187 -0.172370 +-0.853631 0.395244 -0.339259 +-0.807842 0.568795 -0.154479 +-0.765251 0.567356 -0.304134 +-0.901405 0.397187 -0.172370 +-0.907529 0.215179 -0.360680 +-0.958676 0.217563 -0.183322 +-0.907529 0.215179 -0.360680 +-0.901405 0.397187 -0.172370 +-0.853631 0.395244 -0.339259 +-0.165658 0.983983 -0.065837 +-0.304747 0.932483 -0.193918 +-0.334902 0.932805 -0.133100 +-0.304747 0.932483 -0.193918 +-0.165658 0.983983 -0.065837 +-0.150732 0.983911 -0.095914 +-0.150732 0.983911 -0.095914 +-0.263578 0.932063 -0.248564 +-0.304747 0.932483 -0.193918 +-0.263578 0.932063 -0.248564 +-0.150732 0.983911 -0.095914 +-0.130358 0.983816 -0.122932 +-0.334902 0.932805 -0.133100 +-0.453195 0.843476 -0.288379 +-0.498059 0.844248 -0.197944 +-0.453195 0.843476 -0.288379 +-0.334902 0.932805 -0.133100 +-0.304747 0.932483 -0.193918 +-0.304747 0.932483 -0.193918 +-0.391951 0.842468 -0.369624 +-0.453195 0.843476 -0.288379 +-0.391951 0.842468 -0.369624 +-0.304747 0.932483 -0.193918 +-0.263578 0.932063 -0.248564 +-0.498059 0.844248 -0.197944 +-0.586458 0.718891 -0.373178 +-0.644625 0.720294 -0.256194 +-0.586458 0.718891 -0.373178 +-0.498059 0.844248 -0.197944 +-0.453195 0.843476 -0.288379 +-0.453195 0.843476 -0.288379 +-0.507093 0.717059 -0.478208 +-0.586458 0.718891 -0.373178 +-0.507093 0.717059 -0.478208 +-0.453195 0.843476 -0.288379 +-0.391951 0.842468 -0.369624 +-0.644625 0.720294 -0.256194 +-0.695987 0.565212 -0.442874 +-0.765251 0.567356 -0.304134 +-0.695987 0.565212 -0.442874 +-0.644625 0.720294 -0.256194 +-0.586458 0.718891 -0.373178 +-0.586458 0.718891 -0.373178 +-0.601559 0.562411 -0.567292 +-0.695987 0.565212 -0.442874 +-0.601559 0.562411 -0.567292 +-0.586458 0.718891 -0.373178 +-0.507093 0.717059 -0.478208 +-0.765251 0.567356 -0.304134 +-0.776027 0.392349 -0.493806 +-0.853631 0.395244 -0.339259 +-0.776027 0.392349 -0.493806 +-0.765251 0.567356 -0.304134 +-0.695987 0.565212 -0.442874 +-0.695987 0.565212 -0.442874 +-0.670355 0.388571 -0.632169 +-0.776027 0.392349 -0.493806 +-0.670355 0.388571 -0.632169 +-0.695987 0.565212 -0.442874 +-0.601559 0.562411 -0.567292 +-0.853631 0.395244 -0.339259 +-0.824567 0.211628 -0.524693 +-0.907529 0.215179 -0.360680 +-0.824567 0.211628 -0.524693 +-0.853631 0.395244 -0.339259 +-0.776027 0.392349 -0.493806 +-0.776027 0.392349 -0.493806 +-0.711767 0.206997 -0.671223 +-0.824567 0.211628 -0.524693 +-0.711767 0.206997 -0.671223 +-0.776027 0.392349 -0.493806 +-0.670355 0.388571 -0.632169 +-0.130358 0.983816 -0.122932 +-0.213191 0.931565 -0.294511 +-0.263578 0.932063 -0.248564 +-0.213191 0.931565 -0.294511 +-0.130358 0.983816 -0.122932 +-0.105427 0.983704 -0.145641 +-0.105427 0.983704 -0.145641 +-0.154620 0.930999 -0.330657 +-0.213191 0.931565 -0.294511 +-0.154620 0.930999 -0.330657 +-0.105427 0.983704 -0.145641 +-0.076454 0.983577 -0.163497 +-0.263578 0.932063 -0.248564 +-0.317003 0.841270 -0.437920 +-0.391951 0.842468 -0.369624 +-0.317003 0.841270 -0.437920 +-0.263578 0.932063 -0.248564 +-0.213191 0.931565 -0.294511 +-0.213191 0.931565 -0.294511 +-0.229894 0.839909 -0.491631 +-0.317003 0.841270 -0.437920 +-0.229894 0.839909 -0.491631 +-0.213191 0.931565 -0.294511 +-0.154620 0.930999 -0.330657 +-0.391951 0.842468 -0.369624 +-0.410020 0.714881 -0.566417 +-0.507093 0.717059 -0.478208 +-0.410020 0.714881 -0.566417 +-0.391951 0.842468 -0.369624 +-0.317003 0.841270 -0.437920 +-0.317003 0.841270 -0.437920 +-0.297261 0.712407 -0.635698 +-0.410020 0.714881 -0.566417 +-0.297261 0.712407 -0.635698 +-0.317003 0.841270 -0.437920 +-0.229894 0.839909 -0.491631 +-0.507093 0.717059 -0.478208 +-0.486169 0.559084 -0.671614 +-0.601559 0.562411 -0.567292 +-0.486169 0.559084 -0.671614 +-0.507093 0.717059 -0.478208 +-0.410020 0.714881 -0.566417 +-0.410020 0.714881 -0.566417 +-0.352278 0.555304 -0.753351 +-0.486169 0.559084 -0.671614 +-0.352278 0.555304 -0.753351 +-0.410020 0.714881 -0.566417 +-0.297261 0.712407 -0.635698 +-0.601559 0.562411 -0.567292 +-0.541398 0.384084 -0.747909 +-0.670355 0.388571 -0.632169 +-0.541398 0.384084 -0.747909 +-0.601559 0.562411 -0.567292 +-0.486169 0.559084 -0.671614 +-0.486169 0.559084 -0.671614 +-0.391991 0.378990 -0.838278 +-0.541398 0.384084 -0.747909 +-0.391991 0.378990 -0.838278 +-0.486169 0.559084 -0.671614 +-0.352278 0.555304 -0.753351 +-0.670355 0.388571 -0.632169 +-0.574346 0.201501 -0.793425 +-0.711767 0.206997 -0.671223 +-0.574346 0.201501 -0.793425 +-0.670355 0.388571 -0.632169 +-0.541398 0.384084 -0.747909 +-0.541398 0.384084 -0.747909 +-0.415436 0.195269 -0.888416 +-0.574346 0.201501 -0.793425 +-0.415436 0.195269 -0.888416 +-0.541398 0.384084 -0.747909 +-0.391991 0.378990 -0.838278 +-0.076454 0.983577 -0.163497 +-0.090411 0.930391 -0.355244 +-0.154620 0.930999 -0.330657 +-0.090411 0.930391 -0.355244 +-0.076454 0.983577 -0.163497 +-0.044699 0.983441 -0.175632 +-0.154620 0.930999 -0.330657 +-0.134416 0.838447 -0.528147 +-0.229894 0.839909 -0.491631 +-0.134416 0.838447 -0.528147 +-0.154620 0.930999 -0.330657 +-0.090411 0.930391 -0.355244 +-0.229894 0.839909 -0.491631 +-0.173749 0.709747 -0.682693 +-0.297261 0.712407 -0.635698 +-0.173749 0.709747 -0.682693 +-0.229894 0.839909 -0.491631 +-0.134416 0.838447 -0.528147 +-0.297261 0.712407 -0.635698 +-0.205785 0.551242 -0.808570 +-0.352278 0.555304 -0.753351 +-0.205785 0.551242 -0.808570 +-0.297261 0.712407 -0.635698 +-0.173749 0.709747 -0.682693 +-0.352278 0.555304 -0.753351 +-0.228791 0.373520 -0.898965 +-0.391991 0.378990 -0.838278 +-0.228791 0.373520 -0.898965 +-0.352278 0.555304 -0.753351 +-0.205785 0.551242 -0.808570 +-0.391991 0.378990 -0.838278 +-0.242217 0.188585 -0.951718 +-0.415436 0.195269 -0.888416 +-0.242217 0.188585 -0.951718 +-0.391991 0.378990 -0.838278 +-0.228791 0.373520 -0.898965 +-0.811993 0.583667 0.000000 +-0.692232 0.721675 0.000000 +-0.692232 0.721675 0.000000 +0.000000 1.000000 0.000000 +-0.184487 0.982835 0.000000 +0.000000 1.000000 0.000000 +-0.184487 0.982835 0.000000 +-0.184487 0.982835 0.000000 +0.000000 1.000000 0.000000 +-0.184487 0.982835 0.000000 +-0.377984 0.925812 0.000000 +-0.184487 0.982835 0.000000 +-0.377984 0.925812 0.000000 +-0.377984 0.925812 0.000000 +-0.184487 0.982835 0.000000 +-0.549357 0.835588 0.000000 +-0.377984 0.925812 0.000000 +-0.377984 0.925812 0.000000 +-0.549357 0.835588 0.000000 +-0.549357 0.835588 0.000000 +-0.377984 0.925812 0.000000 +-0.549357 0.835588 0.000000 +-0.692232 0.721675 0.000000 +-0.549357 0.835588 0.000000 +-0.692232 0.721675 0.000000 +-0.692232 0.721675 0.000000 +-0.549357 0.835588 0.000000 +-0.974303 0.225243 0.000000 +-0.999133 0.041631 0.000000 +-0.999133 0.041631 0.000000 +-0.974303 0.225243 0.000000 +-0.974303 0.225243 0.000000 +-0.999133 0.041631 0.000000 +-0.974303 0.225243 0.000000 +-0.909274 0.416198 0.000000 +-0.974303 0.225243 0.000000 +-0.909274 0.416198 0.000000 +-0.909274 0.416198 0.000000 +-0.974303 0.225243 0.000000 +-0.909274 0.416198 0.000000 +-0.811993 0.583667 0.000000 +-0.909274 0.416198 0.000000 +-0.811993 0.583667 0.000000 +-0.811993 0.583667 0.000000 +-0.909274 0.416198 0.000000 +-0.692232 0.721675 0.000000 +-0.811993 0.583667 0.000000 +-0.811993 0.583667 0.000000 +0.000000 0.181963 0.983305 +-0.181887 0.007592 0.983290 +0.000000 0.000000 1.000000 +-0.148446 0.983925 0.099275 +0.000000 1.000000 0.000000 +-0.000669 1.000000 0.000438 +-0.126569 0.983836 0.126678 +0.000000 1.000000 0.000000 +-0.148446 0.983925 0.099275 +-0.000669 1.000000 0.000438 +-0.164596 0.983998 0.068237 +-0.148446 0.983925 0.099275 +-0.000017 1.000000 0.000007 +-0.164596 0.983998 0.068237 +-0.000669 1.000000 0.000438 +-0.000017 1.000000 0.000007 +-0.174543 0.984036 0.034751 +-0.164596 0.983998 0.068237 +-0.000761 1.000000 0.000141 +-0.174543 0.984036 0.034751 +-0.000017 1.000000 0.000007 +-0.099783 0.983719 0.149466 +0.000000 1.000000 0.000000 +-0.126569 0.983836 0.126678 +-0.099783 0.983719 0.149466 +-0.000437 1.000000 0.000669 +0.000000 1.000000 0.000000 +-0.068986 0.983593 0.166691 +-0.000437 1.000000 0.000669 +-0.099783 0.983719 0.149466 +-0.068986 0.983593 0.166691 +-0.000007 1.000000 0.000017 +-0.000437 1.000000 0.000669 +-0.035319 0.983450 0.177706 +-0.000007 1.000000 0.000017 +-0.068986 0.983593 0.166691 +-0.035319 0.983450 0.177706 +-0.000141 1.000000 0.000761 +-0.000007 1.000000 0.000017 +-0.000141 1.000000 0.000761 +0.000000 0.983305 0.181963 +0.000000 1.000000 0.000000 +-0.035319 0.983450 0.177706 +0.000000 0.983305 0.181963 +-0.000141 1.000000 0.000761 +-0.035319 0.983450 0.177706 +0.000000 0.929788 0.368095 +0.000000 0.983305 0.181963 +-0.071437 0.930434 0.359430 +0.000000 0.929788 0.368095 +-0.035319 0.983450 0.177706 +-0.177866 0.984055 0.000000 +-0.000761 1.000000 0.000141 +0.000000 1.000000 0.000000 +-0.177866 0.984055 0.000000 +-0.174543 0.984036 0.034751 +-0.000761 1.000000 0.000141 +-0.359561 0.933122 0.000000 +-0.174543 0.984036 0.034751 +-0.177866 0.984055 0.000000 +-0.359561 0.933122 0.000000 +-0.352837 0.933044 0.070248 +-0.174543 0.984036 0.034751 +-0.534753 0.845008 0.000000 +-0.352837 0.933044 0.070248 +-0.359561 0.933122 0.000000 +-0.534753 0.845008 0.000000 +-0.524731 0.844833 0.104471 +-0.352837 0.933044 0.070248 +-0.692232 0.721675 0.000000 +-0.524731 0.844833 0.104471 +-0.534753 0.845008 0.000000 +-0.692232 0.721675 0.000000 +-0.679213 0.721376 0.135227 +-0.524731 0.844833 0.104471 +-0.822014 0.569468 0.000000 +-0.679213 0.721376 0.135227 +-0.692232 0.721675 0.000000 +-0.822014 0.569468 0.000000 +-0.806483 0.569037 0.160566 +-0.679213 0.721376 0.135227 +-0.917344 0.398095 0.000000 +-0.806483 0.569037 0.160566 +-0.822014 0.569468 0.000000 +-0.917344 0.398095 0.000000 +-0.899921 0.397544 0.179169 +-0.806483 0.569037 0.160566 +-0.975797 0.218679 0.000000 +-0.899921 0.397544 0.179169 +-0.917344 0.398095 0.000000 +-0.975797 0.218679 0.000000 +-0.957156 0.218031 0.190564 +-0.899921 0.397544 0.179169 +-0.999133 0.041631 0.000000 +-0.957156 0.218031 0.190564 +-0.975797 0.218679 0.000000 +-0.982434 0.041021 0.182045 +-0.957156 0.218031 0.190564 +-0.999133 0.041631 0.000000 +-0.929045 0.038710 0.367935 +-0.957156 0.218031 0.190564 +-0.982434 0.041021 0.182045 +-0.929045 0.038710 0.367935 +-0.901977 0.215895 0.373935 +-0.957156 0.218031 0.190564 +-0.836232 0.034916 0.547262 +-0.901977 0.215895 0.373935 +-0.929045 0.038710 0.367935 +-0.836232 0.034916 0.547262 +-0.812252 0.212557 0.543200 +-0.901977 0.215895 0.373935 +-0.706494 0.029437 0.707107 +-0.812252 0.212557 0.543200 +-0.836232 0.034916 0.547262 +-0.706494 0.029437 0.707107 +-0.691348 0.207956 0.691948 +-0.812252 0.212557 0.543200 +-0.706494 0.029437 0.707107 +-0.543743 0.202425 0.814474 +-0.691348 0.207956 0.691948 +-0.546789 0.022830 0.836959 +-0.543743 0.202425 0.814474 +-0.706494 0.029437 0.707107 +-0.546789 0.022830 0.836959 +-0.374979 0.196050 0.906066 +-0.543743 0.202425 0.814474 +-0.367616 0.015324 0.929851 +-0.374979 0.196050 0.906066 +-0.546789 0.022830 0.836959 +-0.367616 0.015324 0.929851 +-0.191418 0.189152 0.963110 +-0.374979 0.196050 0.906066 +-0.181887 0.007592 0.983290 +-0.191418 0.189152 0.963110 +-0.367616 0.015324 0.929851 +-0.106205 0.838554 0.534366 +0.000000 0.929788 0.368095 +-0.071437 0.930434 0.359430 +-0.106205 0.838554 0.534366 +0.000000 0.836995 0.547210 +0.000000 0.929788 0.368095 +-0.106205 0.838554 0.534366 +0.000000 0.707107 0.707107 +0.000000 0.836995 0.547210 +-0.137285 0.709951 0.690740 +0.000000 0.707107 0.707107 +-0.106205 0.838554 0.534366 +-0.162603 0.551566 0.818129 +0.000000 0.707107 0.707107 +-0.137285 0.709951 0.690740 +-0.162603 0.551566 0.818129 +0.000000 0.547210 0.836995 +0.000000 0.707107 0.707107 +-0.180792 0.373971 0.909648 +0.000000 0.547210 0.836995 +-0.162603 0.551566 0.818129 +-0.180792 0.373971 0.909648 +0.000000 0.368095 0.929788 +0.000000 0.547210 0.836995 +-0.191418 0.189152 0.963110 +0.000000 0.368095 0.929788 +-0.180792 0.373971 0.909648 +-0.191418 0.189152 0.963110 +0.000000 0.181963 0.983305 +0.000000 0.368095 0.929788 +-0.181887 0.007592 0.983290 +0.000000 0.181963 0.983305 +-0.191418 0.189152 0.963110 +-0.035319 0.983450 0.177706 +-0.139515 0.931070 0.337112 +-0.071437 0.930434 0.359430 +-0.139515 0.931070 0.337112 +-0.035319 0.983450 0.177706 +-0.068986 0.983593 0.166691 +-0.071437 0.930434 0.359430 +-0.207438 0.840080 0.501234 +-0.106205 0.838554 0.534366 +-0.207438 0.840080 0.501234 +-0.071437 0.930434 0.359430 +-0.139515 0.931070 0.337112 +-0.106205 0.838554 0.534366 +-0.268235 0.712717 0.648139 +-0.137285 0.709951 0.690740 +-0.268235 0.712717 0.648139 +-0.106205 0.838554 0.534366 +-0.207438 0.840080 0.501234 +-0.137285 0.709951 0.690740 +-0.317901 0.555777 0.768147 +-0.162603 0.551566 0.818129 +-0.317901 0.555777 0.768147 +-0.137285 0.709951 0.690740 +-0.268235 0.712717 0.648139 +-0.162603 0.551566 0.818129 +-0.353773 0.379628 0.854826 +-0.180792 0.373971 0.909648 +-0.353773 0.379628 0.854826 +-0.162603 0.551566 0.818129 +-0.317901 0.555777 0.768147 +-0.180792 0.373971 0.909648 +-0.374979 0.196050 0.906066 +-0.191418 0.189152 0.963110 +-0.374979 0.196050 0.906066 +-0.180792 0.373971 0.909648 +-0.353773 0.379628 0.854826 +-0.068986 0.983593 0.166691 +-0.201771 0.931635 0.302233 +-0.139515 0.931070 0.337112 +-0.201771 0.931635 0.302233 +-0.068986 0.983593 0.166691 +-0.099783 0.983719 0.149466 +-0.139515 0.931070 0.337112 +-0.300018 0.841446 0.449397 +-0.207438 0.840080 0.501234 +-0.300018 0.841446 0.449397 +-0.139515 0.931070 0.337112 +-0.201771 0.931635 0.302233 +-0.207438 0.840080 0.501234 +-0.388058 0.715215 0.581273 +-0.268235 0.712717 0.648139 +-0.388058 0.715215 0.581273 +-0.207438 0.840080 0.501234 +-0.300018 0.841446 0.449397 +-0.099783 0.983719 0.149466 +-0.255912 0.932150 0.256134 +-0.201771 0.931635 0.302233 +-0.255912 0.932150 0.256134 +-0.099783 0.983719 0.149466 +-0.126569 0.983836 0.126678 +-0.201771 0.931635 0.302233 +-0.380555 0.842677 0.380885 +-0.300018 0.841446 0.449397 +-0.380555 0.842677 0.380885 +-0.201771 0.931635 0.302233 +-0.255912 0.932150 0.256134 +-0.300018 0.841446 0.449397 +-0.492372 0.717439 0.492799 +-0.388058 0.715215 0.581273 +-0.492372 0.717439 0.492799 +-0.300018 0.841446 0.449397 +-0.380555 0.842677 0.380885 +-0.268235 0.712717 0.648139 +-0.460155 0.559613 0.689268 +-0.317901 0.555777 0.768147 +-0.460155 0.559613 0.689268 +-0.268235 0.712717 0.648139 +-0.388058 0.715215 0.581273 +-0.317901 0.555777 0.768147 +-0.512479 0.384820 0.767644 +-0.353773 0.379628 0.854826 +-0.512479 0.384820 0.767644 +-0.317901 0.555777 0.768147 +-0.460155 0.559613 0.689268 +-0.353773 0.379628 0.854826 +-0.543743 0.202425 0.814474 +-0.374979 0.196050 0.906066 +-0.543743 0.202425 0.814474 +-0.353773 0.379628 0.854826 +-0.512479 0.384820 0.767644 +-0.388058 0.715215 0.581273 +-0.584144 0.562992 0.584651 +-0.460155 0.559613 0.689268 +-0.584144 0.562992 0.584651 +-0.388058 0.715215 0.581273 +-0.492372 0.717439 0.492799 +-0.460155 0.559613 0.689268 +-0.651025 0.389354 0.651590 +-0.512479 0.384820 0.767644 +-0.651025 0.389354 0.651590 +-0.460155 0.559613 0.689268 +-0.584144 0.562992 0.584651 +-0.512479 0.384820 0.767644 +-0.691348 0.207956 0.691948 +-0.543743 0.202425 0.814474 +-0.691348 0.207956 0.691948 +-0.512479 0.384820 0.767644 +-0.651025 0.389354 0.651590 +-0.126569 0.983836 0.126678 +-0.300114 0.932550 0.200704 +-0.255912 0.932150 0.256134 +-0.300114 0.932550 0.200704 +-0.126569 0.983836 0.126678 +-0.148446 0.983925 0.099275 +-0.255912 0.932150 0.256134 +-0.446296 0.843647 0.298464 +-0.380555 0.842677 0.380885 +-0.446296 0.843647 0.298464 +-0.255912 0.932150 0.256134 +-0.300114 0.932550 0.200704 +-0.380555 0.842677 0.380885 +-0.577537 0.719219 0.386232 +-0.492372 0.717439 0.492799 +-0.577537 0.719219 0.386232 +-0.380555 0.842677 0.380885 +-0.446296 0.843647 0.298464 +-0.148446 0.983925 0.099275 +-0.332752 0.932870 0.137950 +-0.300114 0.932550 0.200704 +-0.332752 0.932870 0.137950 +-0.148446 0.983925 0.099275 +-0.164596 0.983998 0.068237 +-0.300114 0.932550 0.200704 +-0.494866 0.844404 0.205158 +-0.446296 0.843647 0.298464 +-0.494866 0.844404 0.205158 +-0.300114 0.932550 0.200704 +-0.332752 0.932870 0.137950 +-0.446296 0.843647 0.298464 +-0.640514 0.720577 0.265540 +-0.577537 0.719219 0.386232 +-0.640514 0.720577 0.265540 +-0.446296 0.843647 0.298464 +-0.494866 0.844404 0.205158 +-0.492372 0.717439 0.492799 +-0.685435 0.565736 0.458390 +-0.584144 0.562992 0.584651 +-0.685435 0.565736 0.458390 +-0.492372 0.717439 0.492799 +-0.577537 0.719219 0.386232 +-0.584144 0.562992 0.584651 +-0.764334 0.393085 0.511154 +-0.651025 0.389354 0.651590 +-0.764334 0.393085 0.511154 +-0.584144 0.562992 0.584651 +-0.685435 0.565736 0.458390 +-0.651025 0.389354 0.651590 +-0.812252 0.212557 0.543200 +-0.691348 0.207956 0.691948 +-0.812252 0.212557 0.543200 +-0.651025 0.389354 0.651590 +-0.764334 0.393085 0.511154 +-0.577537 0.719219 0.386232 +-0.760418 0.567788 0.315249 +-0.685435 0.565736 0.458390 +-0.760418 0.567788 0.315249 +-0.577537 0.719219 0.386232 +-0.640514 0.720577 0.265540 +-0.685435 0.565736 0.458390 +-0.848314 0.395827 0.351688 +-0.764334 0.393085 0.511154 +-0.848314 0.395827 0.351688 +-0.685435 0.565736 0.458390 +-0.760418 0.567788 0.315249 +-0.764334 0.393085 0.511154 +-0.901977 0.215895 0.373935 +-0.812252 0.212557 0.543200 +-0.901977 0.215895 0.373935 +-0.764334 0.393085 0.511154 +-0.848314 0.395827 0.351688 +-0.164596 0.983998 0.068237 +-0.352837 0.933044 0.070248 +-0.332752 0.932870 0.137950 +-0.352837 0.933044 0.070248 +-0.164596 0.983998 0.068237 +-0.174543 0.984036 0.034751 +-0.332752 0.932870 0.137950 +-0.524731 0.844833 0.104471 +-0.494866 0.844404 0.205158 +-0.524731 0.844833 0.104471 +-0.332752 0.932870 0.137950 +-0.352837 0.933044 0.070248 +-0.494866 0.844404 0.205158 +-0.679213 0.721376 0.135227 +-0.640514 0.720577 0.265540 +-0.679213 0.721376 0.135227 +-0.494866 0.844404 0.205158 +-0.524731 0.844833 0.104471 +-0.640514 0.720577 0.265540 +-0.806483 0.569037 0.160566 +-0.760418 0.567788 0.315249 +-0.806483 0.569037 0.160566 +-0.640514 0.720577 0.265540 +-0.679213 0.721376 0.135227 +-0.760418 0.567788 0.315249 +-0.899921 0.397544 0.179169 +-0.848314 0.395827 0.351688 +-0.899921 0.397544 0.179169 +-0.760418 0.567788 0.315249 +-0.806483 0.569037 0.160566 +-0.848314 0.395827 0.351688 +-0.957156 0.218031 0.190564 +-0.901977 0.215895 0.373935 +-0.957156 0.218031 0.190564 +-0.848314 0.395827 0.351688 +-0.899921 0.397544 0.179169 +0.000000 0.978781 0.204909 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.204909 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.204909 0.978781 +0.000000 0.204909 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.397177 0.917742 +0.000000 0.204909 0.978781 +0.000000 0.204909 0.978781 +0.000000 0.397177 0.917742 +0.000000 0.397177 0.917742 +0.000000 0.204909 0.978781 +0.000000 0.566635 0.823969 +0.000000 0.397177 0.917742 +0.000000 0.397177 0.917742 +0.000000 0.566635 0.823969 +0.000000 0.566635 0.823969 +0.000000 0.397177 0.917742 +0.000000 0.566635 0.823969 +0.000000 0.707107 0.707107 +0.000000 0.566635 0.823969 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.566635 0.823969 +0.000000 0.707107 0.707107 +0.000000 0.823969 0.566635 +0.000000 0.707107 0.707107 +0.000000 0.823969 0.566635 +0.000000 0.823969 0.566635 +0.000000 0.707107 0.707107 +0.000000 0.823969 0.566635 +0.000000 0.917742 0.397177 +0.000000 0.823969 0.566635 +0.000000 0.917742 0.397177 +0.000000 0.917742 0.397177 +0.000000 0.823969 0.566635 +0.000000 0.978781 0.204909 +0.000000 0.917742 0.397177 +0.000000 0.917742 0.397177 +0.000000 0.978781 0.204909 +0.000000 0.978781 0.204909 +0.000000 0.917742 0.397177 +0.000000 1.000000 0.000000 +0.000000 0.978781 0.204909 +0.000000 0.978781 0.204909 +0.975797 0.218679 0.000000 +0.982434 0.041021 0.182045 +0.999133 0.041631 0.000000 +0.164596 0.983998 0.068237 +0.000669 1.000000 0.000438 +0.148446 0.983925 0.099275 +0.164596 0.983998 0.068237 +0.000017 1.000000 0.000007 +0.000669 1.000000 0.000438 +0.174543 0.984036 0.034751 +0.000017 1.000000 0.000007 +0.164596 0.983998 0.068237 +0.174543 0.984036 0.034751 +0.000761 1.000000 0.000141 +0.000017 1.000000 0.000007 +0.000000 1.000000 0.000000 +0.148446 0.983925 0.099275 +0.000669 1.000000 0.000438 +0.000000 1.000000 0.000000 +0.126569 0.983836 0.126678 +0.148446 0.983925 0.099275 +0.000437 1.000000 0.000669 +0.126569 0.983836 0.126678 +0.000000 1.000000 0.000000 +0.000437 1.000000 0.000669 +0.099783 0.983719 0.149466 +0.126569 0.983836 0.126678 +0.000437 1.000000 0.000669 +0.068986 0.983593 0.166691 +0.099783 0.983719 0.149466 +0.000007 1.000000 0.000017 +0.068986 0.983593 0.166691 +0.000437 1.000000 0.000669 +0.000007 1.000000 0.000017 +0.035319 0.983450 0.177706 +0.068986 0.983593 0.166691 +0.000141 1.000000 0.000761 +0.035319 0.983450 0.177706 +0.000007 1.000000 0.000017 +0.000761 1.000000 0.000141 +0.177866 0.984055 0.000000 +0.000000 1.000000 0.000000 +0.174543 0.984036 0.034751 +0.177866 0.984055 0.000000 +0.000761 1.000000 0.000141 +0.352837 0.933044 0.070248 +0.177866 0.984055 0.000000 +0.174543 0.984036 0.034751 +0.352837 0.933044 0.070248 +0.359561 0.933122 0.000000 +0.177866 0.984055 0.000000 +0.352837 0.933044 0.070248 +0.534753 0.845008 0.000000 +0.359561 0.933122 0.000000 +0.524731 0.844833 0.104471 +0.534753 0.845008 0.000000 +0.352837 0.933044 0.070248 +0.679213 0.721376 0.135227 +0.534753 0.845008 0.000000 +0.524731 0.844833 0.104471 +0.679213 0.721376 0.135227 +0.692232 0.721675 0.000000 +0.534753 0.845008 0.000000 +0.000000 0.983305 0.181963 +0.000141 1.000000 0.000761 +0.000000 1.000000 0.000000 +0.000000 0.983305 0.181963 +0.035319 0.983450 0.177706 +0.000141 1.000000 0.000761 +0.000000 0.929788 0.368095 +0.035319 0.983450 0.177706 +0.000000 0.983305 0.181963 +0.000000 0.929788 0.368095 +0.071437 0.930434 0.359430 +0.035319 0.983450 0.177706 +0.000000 0.836995 0.547210 +0.071437 0.930434 0.359430 +0.000000 0.929788 0.368095 +0.000000 0.836995 0.547210 +0.106205 0.838554 0.534366 +0.071437 0.930434 0.359430 +0.000000 0.707107 0.707107 +0.106205 0.838554 0.534366 +0.000000 0.836995 0.547210 +0.000000 0.707107 0.707107 +0.137285 0.709951 0.690740 +0.106205 0.838554 0.534366 +0.000000 0.547210 0.836995 +0.137285 0.709951 0.690740 +0.000000 0.707107 0.707107 +0.000000 0.547210 0.836995 +0.162603 0.551566 0.818129 +0.137285 0.709951 0.690740 +0.000000 0.368095 0.929788 +0.162603 0.551566 0.818129 +0.000000 0.547210 0.836995 +0.000000 0.368095 0.929788 +0.180792 0.373971 0.909648 +0.162603 0.551566 0.818129 +0.000000 0.181963 0.983305 +0.180792 0.373971 0.909648 +0.000000 0.368095 0.929788 +0.000000 0.181963 0.983305 +0.191418 0.189152 0.963110 +0.180792 0.373971 0.909648 +0.000000 0.000000 1.000000 +0.191418 0.189152 0.963110 +0.000000 0.181963 0.983305 +0.181887 0.007592 0.983290 +0.191418 0.189152 0.963110 +0.000000 0.000000 1.000000 +0.367616 0.015324 0.929851 +0.191418 0.189152 0.963110 +0.181887 0.007592 0.983290 +0.367616 0.015324 0.929851 +0.374979 0.196050 0.906066 +0.191418 0.189152 0.963110 +0.546789 0.022830 0.836959 +0.374979 0.196050 0.906066 +0.367616 0.015324 0.929851 +0.546789 0.022830 0.836959 +0.543743 0.202425 0.814474 +0.374979 0.196050 0.906066 +0.706494 0.029437 0.707107 +0.543743 0.202425 0.814474 +0.546789 0.022830 0.836959 +0.706494 0.029437 0.707107 +0.691348 0.207956 0.691948 +0.543743 0.202425 0.814474 +0.836232 0.034916 0.547262 +0.691348 0.207956 0.691948 +0.706494 0.029437 0.707107 +0.836232 0.034916 0.547262 +0.812252 0.212557 0.543200 +0.691348 0.207956 0.691948 +0.836232 0.034916 0.547262 +0.901977 0.215895 0.373935 +0.812252 0.212557 0.543200 +0.929045 0.038710 0.367935 +0.901977 0.215895 0.373935 +0.836232 0.034916 0.547262 +0.929045 0.038710 0.367935 +0.957156 0.218031 0.190564 +0.901977 0.215895 0.373935 +0.982434 0.041021 0.182045 +0.957156 0.218031 0.190564 +0.929045 0.038710 0.367935 +0.806483 0.569037 0.160566 +0.692232 0.721675 0.000000 +0.679213 0.721376 0.135227 +0.806483 0.569037 0.160566 +0.822014 0.569468 0.000000 +0.692232 0.721675 0.000000 +0.899921 0.397544 0.179169 +0.822014 0.569468 0.000000 +0.806483 0.569037 0.160566 +0.899921 0.397544 0.179169 +0.917344 0.398095 0.000000 +0.822014 0.569468 0.000000 +0.957156 0.218031 0.190564 +0.917344 0.398095 0.000000 +0.899921 0.397544 0.179169 +0.957156 0.218031 0.190564 +0.975797 0.218679 0.000000 +0.917344 0.398095 0.000000 +0.982434 0.041021 0.182045 +0.975797 0.218679 0.000000 +0.957156 0.218031 0.190564 +0.174543 0.984036 0.034751 +0.332752 0.932870 0.137950 +0.352837 0.933044 0.070248 +0.332752 0.932870 0.137950 +0.174543 0.984036 0.034751 +0.164596 0.983998 0.068237 +0.352837 0.933044 0.070248 +0.494866 0.844404 0.205158 +0.524731 0.844833 0.104471 +0.494866 0.844404 0.205158 +0.352837 0.933044 0.070248 +0.332752 0.932870 0.137950 +0.524731 0.844833 0.104471 +0.640514 0.720577 0.265540 +0.679213 0.721376 0.135227 +0.640514 0.720577 0.265540 +0.524731 0.844833 0.104471 +0.494866 0.844404 0.205158 +0.679213 0.721376 0.135227 +0.760418 0.567788 0.315249 +0.806483 0.569037 0.160566 +0.760418 0.567788 0.315249 +0.679213 0.721376 0.135227 +0.640514 0.720577 0.265540 +0.806483 0.569037 0.160566 +0.848314 0.395827 0.351688 +0.899921 0.397544 0.179169 +0.848314 0.395827 0.351688 +0.806483 0.569037 0.160566 +0.760418 0.567788 0.315249 +0.899921 0.397544 0.179169 +0.901977 0.215895 0.373935 +0.957156 0.218031 0.190564 +0.901977 0.215895 0.373935 +0.899921 0.397544 0.179169 +0.848314 0.395827 0.351688 +0.164596 0.983998 0.068237 +0.300114 0.932550 0.200704 +0.332752 0.932870 0.137950 +0.300114 0.932550 0.200704 +0.164596 0.983998 0.068237 +0.148446 0.983925 0.099275 +0.332752 0.932870 0.137950 +0.446296 0.843647 0.298464 +0.494866 0.844404 0.205158 +0.446296 0.843647 0.298464 +0.332752 0.932870 0.137950 +0.300114 0.932550 0.200704 +0.494866 0.844404 0.205158 +0.577537 0.719219 0.386232 +0.640514 0.720577 0.265540 +0.577537 0.719219 0.386232 +0.494866 0.844404 0.205158 +0.446296 0.843647 0.298464 +0.148446 0.983925 0.099275 +0.255912 0.932150 0.256134 +0.300114 0.932550 0.200704 +0.255912 0.932150 0.256134 +0.148446 0.983925 0.099275 +0.126569 0.983836 0.126678 +0.300114 0.932550 0.200704 +0.380555 0.842677 0.380885 +0.446296 0.843647 0.298464 +0.380555 0.842677 0.380885 +0.300114 0.932550 0.200704 +0.255912 0.932150 0.256134 +0.446296 0.843647 0.298464 +0.492372 0.717439 0.492799 +0.577537 0.719219 0.386232 +0.492372 0.717439 0.492799 +0.446296 0.843647 0.298464 +0.380555 0.842677 0.380885 +0.640514 0.720577 0.265540 +0.685435 0.565736 0.458390 +0.760418 0.567788 0.315249 +0.685435 0.565736 0.458390 +0.640514 0.720577 0.265540 +0.577537 0.719219 0.386232 +0.760418 0.567788 0.315249 +0.764334 0.393085 0.511154 +0.848314 0.395827 0.351688 +0.764334 0.393085 0.511154 +0.760418 0.567788 0.315249 +0.685435 0.565736 0.458390 +0.848314 0.395827 0.351688 +0.812252 0.212557 0.543200 +0.901977 0.215895 0.373935 +0.812252 0.212557 0.543200 +0.848314 0.395827 0.351688 +0.764334 0.393085 0.511154 +0.577537 0.719219 0.386232 +0.584144 0.562992 0.584651 +0.685435 0.565736 0.458390 +0.584144 0.562992 0.584651 +0.577537 0.719219 0.386232 +0.492372 0.717439 0.492799 +0.685435 0.565736 0.458390 +0.651025 0.389354 0.651590 +0.764334 0.393085 0.511154 +0.651025 0.389354 0.651590 +0.685435 0.565736 0.458390 +0.584144 0.562992 0.584651 +0.764334 0.393085 0.511154 +0.691348 0.207956 0.691948 +0.812252 0.212557 0.543200 +0.691348 0.207956 0.691948 +0.764334 0.393085 0.511154 +0.651025 0.389354 0.651590 +0.126569 0.983836 0.126678 +0.201771 0.931635 0.302233 +0.255912 0.932150 0.256134 +0.201771 0.931635 0.302233 +0.126569 0.983836 0.126678 +0.099783 0.983719 0.149466 +0.255912 0.932150 0.256134 +0.300018 0.841446 0.449397 +0.380555 0.842677 0.380885 +0.300018 0.841446 0.449397 +0.255912 0.932150 0.256134 +0.201771 0.931635 0.302233 +0.380555 0.842677 0.380885 +0.388058 0.715215 0.581273 +0.492372 0.717439 0.492799 +0.388058 0.715215 0.581273 +0.380555 0.842677 0.380885 +0.300018 0.841446 0.449397 +0.099783 0.983719 0.149466 +0.139515 0.931070 0.337112 +0.201771 0.931635 0.302233 +0.139515 0.931070 0.337112 +0.099783 0.983719 0.149466 +0.068986 0.983593 0.166691 +0.201771 0.931635 0.302233 +0.207438 0.840080 0.501234 +0.300018 0.841446 0.449397 +0.207438 0.840080 0.501234 +0.201771 0.931635 0.302233 +0.139515 0.931070 0.337112 +0.300018 0.841446 0.449397 +0.268235 0.712717 0.648139 +0.388058 0.715215 0.581273 +0.268235 0.712717 0.648139 +0.300018 0.841446 0.449397 +0.207438 0.840080 0.501234 +0.492372 0.717439 0.492799 +0.460155 0.559613 0.689268 +0.584144 0.562992 0.584651 +0.460155 0.559613 0.689268 +0.492372 0.717439 0.492799 +0.388058 0.715215 0.581273 +0.584144 0.562992 0.584651 +0.512479 0.384820 0.767644 +0.651025 0.389354 0.651590 +0.512479 0.384820 0.767644 +0.584144 0.562992 0.584651 +0.460155 0.559613 0.689268 +0.651025 0.389354 0.651590 +0.543743 0.202425 0.814474 +0.691348 0.207956 0.691948 +0.543743 0.202425 0.814474 +0.651025 0.389354 0.651590 +0.512479 0.384820 0.767644 +0.388058 0.715215 0.581273 +0.317901 0.555777 0.768147 +0.460155 0.559613 0.689268 +0.317901 0.555777 0.768147 +0.388058 0.715215 0.581273 +0.268235 0.712717 0.648139 +0.460155 0.559613 0.689268 +0.353773 0.379628 0.854826 +0.512479 0.384820 0.767644 +0.353773 0.379628 0.854826 +0.460155 0.559613 0.689268 +0.317901 0.555777 0.768147 +0.512479 0.384820 0.767644 +0.374979 0.196050 0.906066 +0.543743 0.202425 0.814474 +0.374979 0.196050 0.906066 +0.512479 0.384820 0.767644 +0.353773 0.379628 0.854826 +0.068986 0.983593 0.166691 +0.071437 0.930434 0.359430 +0.139515 0.931070 0.337112 +0.071437 0.930434 0.359430 +0.068986 0.983593 0.166691 +0.035319 0.983450 0.177706 +0.139515 0.931070 0.337112 +0.106205 0.838554 0.534366 +0.207438 0.840080 0.501234 +0.106205 0.838554 0.534366 +0.139515 0.931070 0.337112 +0.071437 0.930434 0.359430 +0.207438 0.840080 0.501234 +0.137285 0.709951 0.690740 +0.268235 0.712717 0.648139 +0.137285 0.709951 0.690740 +0.207438 0.840080 0.501234 +0.106205 0.838554 0.534366 +0.268235 0.712717 0.648139 +0.162603 0.551566 0.818129 +0.317901 0.555777 0.768147 +0.162603 0.551566 0.818129 +0.268235 0.712717 0.648139 +0.137285 0.709951 0.690740 +0.317901 0.555777 0.768147 +0.180792 0.373971 0.909648 +0.353773 0.379628 0.854826 +0.180792 0.373971 0.909648 +0.317901 0.555777 0.768147 +0.162603 0.551566 0.818129 +0.353773 0.379628 0.854826 +0.191418 0.189152 0.963110 +0.374979 0.196050 0.906066 +0.191418 0.189152 0.963110 +0.353773 0.379628 0.854826 +0.180792 0.373971 0.909648 +0.692232 0.721675 0.000000 +0.549357 0.835588 0.000000 +0.549357 0.835588 0.000000 +0.000000 1.000000 0.000000 +0.184487 0.982835 0.000000 +0.000000 1.000000 0.000000 +0.184487 0.982835 0.000000 +0.184487 0.982835 0.000000 +0.000000 1.000000 0.000000 +0.377984 0.925812 0.000000 +0.184487 0.982835 0.000000 +0.184487 0.982835 0.000000 +0.377984 0.925812 0.000000 +0.377984 0.925812 0.000000 +0.184487 0.982835 0.000000 +0.377984 0.925812 0.000000 +0.549357 0.835588 0.000000 +0.377984 0.925812 0.000000 +0.549357 0.835588 0.000000 +0.549357 0.835588 0.000000 +0.377984 0.925812 0.000000 +0.999133 0.041631 0.000000 +0.974303 0.225243 0.000000 +0.999133 0.041631 0.000000 +0.974303 0.225243 0.000000 +0.974303 0.225243 0.000000 +0.999133 0.041631 0.000000 +0.909274 0.416198 0.000000 +0.974303 0.225243 0.000000 +0.974303 0.225243 0.000000 +0.909274 0.416198 0.000000 +0.909274 0.416198 0.000000 +0.974303 0.225243 0.000000 +0.811993 0.583667 0.000000 +0.909274 0.416198 0.000000 +0.909274 0.416198 0.000000 +0.811993 0.583667 0.000000 +0.811993 0.583667 0.000000 +0.909274 0.416198 0.000000 +0.811993 0.583667 0.000000 +0.692232 0.721675 0.000000 +0.811993 0.583667 0.000000 +0.692232 0.721675 0.000000 +0.692232 0.721675 0.000000 +0.811993 0.583667 0.000000 +0.549357 0.835588 0.000000 +0.692232 0.721675 0.000000 +0.692232 0.721675 0.000000 +0.822014 0.569468 0.000000 +0.901405 0.397187 -0.172370 +0.807842 0.568795 -0.154479 +0.068193 0.196350 -0.978160 +0.255155 0.007847 -0.966868 +0.069447 0.000000 -0.997586 +0.981637 0.040374 -0.186434 +0.975797 0.218679 0.000000 +0.999133 0.041631 0.000000 +0.680363 0.721235 -0.130102 +0.822014 0.569468 0.000000 +0.807842 0.568795 -0.154479 +0.680363 0.721235 -0.130102 +0.692232 0.721675 0.000000 +0.822014 0.569468 0.000000 +0.525612 0.844766 -0.100510 +0.692232 0.721675 0.000000 +0.680363 0.721235 -0.130102 +0.525612 0.844766 -0.100510 +0.534753 0.845008 0.000000 +0.692232 0.721675 0.000000 +0.353419 0.933021 -0.067582 +0.534753 0.845008 0.000000 +0.525612 0.844766 -0.100510 +0.353419 0.933021 -0.067582 +0.359561 0.933122 0.000000 +0.534753 0.845008 0.000000 +0.174824 0.984032 -0.033431 +0.359561 0.933122 0.000000 +0.353419 0.933021 -0.067582 +0.174824 0.984032 -0.033431 +0.177866 0.984055 0.000000 +0.359561 0.933122 0.000000 +0.174824 0.984032 -0.033431 +0.000000 1.000000 0.000000 +0.177866 0.984055 0.000000 +0.174824 0.984032 -0.033431 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.174824 0.984032 -0.033431 +0.000001 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.165658 0.983983 -0.065837 +0.000001 1.000000 0.000000 +0.174824 0.984032 -0.033431 +0.150732 0.983911 -0.095914 +0.000001 1.000000 0.000000 +0.165658 0.983983 -0.065837 +0.150732 0.983911 -0.095914 +0.000000 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.150732 0.983911 -0.095914 +0.000006 1.000000 -0.000005 +0.000000 1.000000 0.000000 +0.130358 0.983816 -0.122932 +0.000006 1.000000 -0.000005 +0.150732 0.983911 -0.095914 +0.105427 0.983704 -0.145641 +0.000006 1.000000 -0.000005 +0.130358 0.983816 -0.122932 +0.105427 0.983704 -0.145641 +0.000000 1.000000 0.000000 +0.000006 1.000000 -0.000005 +0.105427 0.983704 -0.145641 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.076454 0.983577 -0.163497 +0.000000 1.000000 0.000000 +0.105427 0.983704 -0.145641 +0.076454 0.983577 -0.163497 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.044699 0.983441 -0.175632 +0.000000 1.000000 0.000000 +0.076454 0.983577 -0.163497 +0.044699 0.983441 -0.175632 +0.000001 1.000000 -0.000019 +0.000000 1.000000 0.000000 +0.044699 0.983441 -0.175632 +0.014429 0.980653 -0.195222 +0.000001 1.000000 -0.000019 +0.090411 0.930391 -0.355244 +0.014429 0.980653 -0.195222 +0.044699 0.983441 -0.175632 +0.090411 0.930391 -0.355244 +0.027844 0.923693 -0.382121 +0.014429 0.980653 -0.195222 +0.134416 0.838447 -0.528147 +0.027844 0.923693 -0.382121 +0.090411 0.930391 -0.355244 +0.134416 0.838447 -0.528147 +0.039849 0.831562 -0.554001 +0.027844 0.923693 -0.382121 +0.173749 0.709747 -0.682693 +0.039849 0.831562 -0.554001 +0.134416 0.838447 -0.528147 +0.173749 0.709747 -0.682693 +0.050115 0.707834 -0.704599 +0.039849 0.831562 -0.554001 +0.173749 0.709747 -0.682693 +0.058393 0.556956 -0.828487 +0.050115 0.707834 -0.704599 +0.205785 0.551242 -0.808570 +0.058393 0.556956 -0.828487 +0.173749 0.709747 -0.682693 +0.205785 0.551242 -0.808570 +0.064473 0.384319 -0.920946 +0.058393 0.556956 -0.828487 +0.228791 0.373520 -0.898965 +0.064473 0.384319 -0.920946 +0.205785 0.551242 -0.808570 +0.228791 0.373520 -0.898965 +0.068193 0.196350 -0.978160 +0.064473 0.384319 -0.920946 +0.242217 0.188585 -0.951718 +0.068193 0.196350 -0.978160 +0.228791 0.373520 -0.898965 +0.242217 0.188585 -0.951718 +0.255155 0.007847 -0.966868 +0.068193 0.196350 -0.978160 +0.415436 0.195269 -0.888416 +0.255155 0.007847 -0.966868 +0.242217 0.188585 -0.951718 +0.415436 0.195269 -0.888416 +0.430357 0.015341 -0.902528 +0.255155 0.007847 -0.966868 +0.574346 0.201501 -0.793425 +0.430357 0.015341 -0.902528 +0.415436 0.195269 -0.888416 +0.574346 0.201501 -0.793425 +0.591300 0.022335 -0.806142 +0.430357 0.015341 -0.902528 +0.711767 0.206997 -0.671223 +0.591300 0.022335 -0.806142 +0.574346 0.201501 -0.793425 +0.711767 0.206997 -0.671223 +0.730767 0.028502 -0.682032 +0.591300 0.022335 -0.806142 +0.824567 0.211628 -0.524693 +0.730767 0.028502 -0.682032 +0.711767 0.206997 -0.671223 +0.824567 0.211628 -0.524693 +0.845212 0.033703 -0.533367 +0.730767 0.028502 -0.682032 +0.907529 0.215179 -0.360680 +0.845212 0.033703 -0.533367 +0.824567 0.211628 -0.524693 +0.907529 0.215179 -0.360680 +0.929589 0.037693 -0.366666 +0.845212 0.033703 -0.533367 +0.958676 0.217563 -0.183322 +0.929589 0.037693 -0.366666 +0.907529 0.215179 -0.360680 +0.958676 0.217563 -0.183322 +0.981637 0.040374 -0.186434 +0.929589 0.037693 -0.366666 +0.958676 0.217563 -0.183322 +0.975797 0.218679 0.000000 +0.981637 0.040374 -0.186434 +0.901405 0.397187 -0.172370 +0.975797 0.218679 0.000000 +0.958676 0.217563 -0.183322 +0.901405 0.397187 -0.172370 +0.917344 0.398095 0.000000 +0.975797 0.218679 0.000000 +0.901405 0.397187 -0.172370 +0.822014 0.569468 0.000000 +0.917344 0.398095 0.000000 +0.958676 0.217563 -0.183322 +0.853631 0.395244 -0.339259 +0.901405 0.397187 -0.172370 +0.853631 0.395244 -0.339259 +0.958676 0.217563 -0.183322 +0.907529 0.215179 -0.360680 +0.901405 0.397187 -0.172370 +0.765251 0.567356 -0.304134 +0.807842 0.568795 -0.154479 +0.765251 0.567356 -0.304134 +0.901405 0.397187 -0.172370 +0.853631 0.395244 -0.339259 +0.807842 0.568795 -0.154479 +0.644625 0.720294 -0.256194 +0.680363 0.721235 -0.130102 +0.644625 0.720294 -0.256194 +0.807842 0.568795 -0.154479 +0.765251 0.567356 -0.304134 +0.680363 0.721235 -0.130102 +0.498059 0.844248 -0.197944 +0.525612 0.844766 -0.100510 +0.498059 0.844248 -0.197944 +0.680363 0.721235 -0.130102 +0.644625 0.720294 -0.256194 +0.525612 0.844766 -0.100510 +0.334902 0.932805 -0.133100 +0.353419 0.933021 -0.067582 +0.334902 0.932805 -0.133100 +0.525612 0.844766 -0.100510 +0.498059 0.844248 -0.197944 +0.353419 0.933021 -0.067582 +0.165658 0.983983 -0.065837 +0.174824 0.984032 -0.033431 +0.165658 0.983983 -0.065837 +0.353419 0.933021 -0.067582 +0.334902 0.932805 -0.133100 +0.907529 0.215179 -0.360680 +0.776027 0.392349 -0.493806 +0.853631 0.395244 -0.339259 +0.776027 0.392349 -0.493806 +0.907529 0.215179 -0.360680 +0.824567 0.211628 -0.524693 +0.824567 0.211628 -0.524693 +0.670355 0.388571 -0.632169 +0.776027 0.392349 -0.493806 +0.670355 0.388571 -0.632169 +0.824567 0.211628 -0.524693 +0.711767 0.206997 -0.671223 +0.853631 0.395244 -0.339259 +0.695987 0.565212 -0.442874 +0.765251 0.567356 -0.304134 +0.695987 0.565212 -0.442874 +0.853631 0.395244 -0.339259 +0.776027 0.392349 -0.493806 +0.776027 0.392349 -0.493806 +0.601559 0.562411 -0.567292 +0.695987 0.565212 -0.442874 +0.601559 0.562411 -0.567292 +0.776027 0.392349 -0.493806 +0.670355 0.388571 -0.632169 +0.765251 0.567356 -0.304134 +0.586458 0.718891 -0.373178 +0.644625 0.720294 -0.256194 +0.586458 0.718891 -0.373178 +0.765251 0.567356 -0.304134 +0.695987 0.565212 -0.442874 +0.695987 0.565212 -0.442874 +0.507093 0.717059 -0.478208 +0.586458 0.718891 -0.373178 +0.507093 0.717059 -0.478208 +0.695987 0.565212 -0.442874 +0.601559 0.562411 -0.567292 +0.644625 0.720294 -0.256194 +0.453195 0.843476 -0.288379 +0.498059 0.844248 -0.197944 +0.453195 0.843476 -0.288379 +0.644625 0.720294 -0.256194 +0.586458 0.718891 -0.373178 +0.586458 0.718891 -0.373178 +0.391951 0.842468 -0.369624 +0.453195 0.843476 -0.288379 +0.391951 0.842468 -0.369624 +0.586458 0.718891 -0.373178 +0.507093 0.717059 -0.478208 +0.498059 0.844248 -0.197944 +0.304747 0.932483 -0.193918 +0.334902 0.932805 -0.133100 +0.304747 0.932483 -0.193918 +0.498059 0.844248 -0.197944 +0.453195 0.843476 -0.288379 +0.453195 0.843476 -0.288379 +0.263578 0.932063 -0.248564 +0.304747 0.932483 -0.193918 +0.263578 0.932063 -0.248564 +0.453195 0.843476 -0.288379 +0.391951 0.842468 -0.369624 +0.334902 0.932805 -0.133100 +0.150732 0.983911 -0.095914 +0.165658 0.983983 -0.065837 +0.150732 0.983911 -0.095914 +0.334902 0.932805 -0.133100 +0.304747 0.932483 -0.193918 +0.304747 0.932483 -0.193918 +0.130358 0.983816 -0.122932 +0.150732 0.983911 -0.095914 +0.130358 0.983816 -0.122932 +0.304747 0.932483 -0.193918 +0.263578 0.932063 -0.248564 +0.711767 0.206997 -0.671223 +0.541398 0.384084 -0.747909 +0.670355 0.388571 -0.632169 +0.541398 0.384084 -0.747909 +0.711767 0.206997 -0.671223 +0.574346 0.201501 -0.793425 +0.574346 0.201501 -0.793425 +0.391991 0.378990 -0.838278 +0.541398 0.384084 -0.747909 +0.391991 0.378990 -0.838278 +0.574346 0.201501 -0.793425 +0.415436 0.195269 -0.888416 +0.670355 0.388571 -0.632169 +0.486169 0.559084 -0.671614 +0.601559 0.562411 -0.567292 +0.486169 0.559084 -0.671614 +0.670355 0.388571 -0.632169 +0.541398 0.384084 -0.747909 +0.541398 0.384084 -0.747909 +0.352278 0.555304 -0.753351 +0.486169 0.559084 -0.671614 +0.352278 0.555304 -0.753351 +0.541398 0.384084 -0.747909 +0.391991 0.378990 -0.838278 +0.601559 0.562411 -0.567292 +0.410020 0.714881 -0.566417 +0.507093 0.717059 -0.478208 +0.410020 0.714881 -0.566417 +0.601559 0.562411 -0.567292 +0.486169 0.559084 -0.671614 +0.486169 0.559084 -0.671614 +0.297261 0.712407 -0.635698 +0.410020 0.714881 -0.566417 +0.297261 0.712407 -0.635698 +0.486169 0.559084 -0.671614 +0.352278 0.555304 -0.753351 +0.507093 0.717059 -0.478208 +0.317003 0.841270 -0.437920 +0.391951 0.842468 -0.369624 +0.317003 0.841270 -0.437920 +0.507093 0.717059 -0.478208 +0.410020 0.714881 -0.566417 +0.410020 0.714881 -0.566417 +0.229894 0.839909 -0.491631 +0.317003 0.841270 -0.437920 +0.229894 0.839909 -0.491631 +0.410020 0.714881 -0.566417 +0.297261 0.712407 -0.635698 +0.391951 0.842468 -0.369624 +0.213191 0.931565 -0.294511 +0.263578 0.932063 -0.248564 +0.213191 0.931565 -0.294511 +0.391951 0.842468 -0.369624 +0.317003 0.841270 -0.437920 +0.317003 0.841270 -0.437920 +0.154620 0.930999 -0.330657 +0.213191 0.931565 -0.294511 +0.154620 0.930999 -0.330657 +0.317003 0.841270 -0.437920 +0.229894 0.839909 -0.491631 +0.263578 0.932063 -0.248564 +0.105427 0.983704 -0.145641 +0.130358 0.983816 -0.122932 +0.105427 0.983704 -0.145641 +0.263578 0.932063 -0.248564 +0.213191 0.931565 -0.294511 +0.213191 0.931565 -0.294511 +0.076454 0.983577 -0.163497 +0.105427 0.983704 -0.145641 +0.076454 0.983577 -0.163497 +0.213191 0.931565 -0.294511 +0.154620 0.930999 -0.330657 +0.415436 0.195269 -0.888416 +0.228791 0.373520 -0.898965 +0.391991 0.378990 -0.838278 +0.228791 0.373520 -0.898965 +0.415436 0.195269 -0.888416 +0.242217 0.188585 -0.951718 +0.391991 0.378990 -0.838278 +0.205785 0.551242 -0.808570 +0.352278 0.555304 -0.753351 +0.205785 0.551242 -0.808570 +0.391991 0.378990 -0.838278 +0.228791 0.373520 -0.898965 +0.352278 0.555304 -0.753351 +0.173749 0.709747 -0.682693 +0.297261 0.712407 -0.635698 +0.173749 0.709747 -0.682693 +0.352278 0.555304 -0.753351 +0.205785 0.551242 -0.808570 +0.297261 0.712407 -0.635698 +0.134416 0.838447 -0.528147 +0.229894 0.839909 -0.491631 +0.134416 0.838447 -0.528147 +0.297261 0.712407 -0.635698 +0.173749 0.709747 -0.682693 +0.229894 0.839909 -0.491631 +0.090411 0.930391 -0.355244 +0.154620 0.930999 -0.330657 +0.090411 0.930391 -0.355244 +0.229894 0.839909 -0.491631 +0.134416 0.838447 -0.528147 +0.154620 0.930999 -0.330657 +0.044699 0.983441 -0.175632 +0.076454 0.983577 -0.163497 +0.044699 0.983441 -0.175632 +0.154620 0.930999 -0.330657 +0.090411 0.930391 -0.355244 +0.000000 0.953073 -0.302739 +0.000000 0.979589 -0.201010 +0.000000 0.979589 -0.201010 +0.000000 0.161521 -0.986869 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.161521 -0.986869 +0.000000 0.104983 -0.994474 +0.000000 0.000000 -1.000000 +0.000000 0.161521 -0.986869 +0.000000 0.302434 -0.953170 +0.000000 0.104983 -0.994474 +0.000000 0.325739 -0.945460 +0.000000 0.302434 -0.953170 +0.000000 0.161521 -0.986869 +0.000000 0.325739 -0.945460 +0.000000 0.480497 -0.876996 +0.000000 0.302434 -0.953170 +0.000000 0.485225 -0.874389 +0.000000 0.480497 -0.876996 +0.000000 0.325739 -0.945460 +0.000000 0.485225 -0.874389 +0.000000 0.632056 -0.774923 +0.000000 0.480497 -0.876996 +0.000000 0.632056 -0.774923 +0.000000 0.632056 -0.774923 +0.000000 0.485225 -0.874389 +0.000000 0.759007 -0.651082 +0.000000 0.632056 -0.774923 +0.000000 0.632056 -0.774923 +0.000000 0.759007 -0.651082 +0.000000 0.762511 -0.646975 +0.000000 0.632056 -0.774923 +0.000000 0.860685 -0.509137 +0.000000 0.762511 -0.646975 +0.000000 0.759007 -0.651082 +0.000000 0.860685 -0.509137 +0.000000 0.872923 -0.487857 +0.000000 0.762511 -0.646975 +0.000000 0.934259 -0.356595 +0.000000 0.872923 -0.487857 +0.000000 0.860685 -0.509137 +0.000000 0.934259 -0.356595 +0.000000 0.953073 -0.302739 +0.000000 0.872923 -0.487857 +0.000000 0.979589 -0.201010 +0.000000 0.953073 -0.302739 +0.000000 0.934259 -0.356595 +0.000000 0.270833 0.962626 +0.000000 0.395424 0.918499 +0.000000 0.270833 0.962626 +0.000000 0.979589 0.201010 +0.000000 0.931419 0.363949 +0.000000 0.979589 0.201010 +0.000000 0.944522 0.328448 +0.000000 0.931419 0.363949 +0.000000 0.979589 0.201010 +0.000000 0.891245 0.453521 +0.000000 0.931419 0.363949 +0.000000 0.944522 0.328448 +0.000000 0.891245 0.453521 +0.000000 0.843795 0.536666 +0.000000 0.931419 0.363949 +0.000000 0.819987 0.572382 +0.000000 0.843795 0.536666 +0.000000 0.891245 0.453521 +0.000000 0.819987 0.572382 +0.000000 0.732055 0.681246 +0.000000 0.843795 0.536666 +0.000000 0.732055 0.681246 +0.000000 0.732055 0.681246 +0.000000 0.819987 0.572382 +0.000000 0.732055 0.681246 +0.000000 0.595872 0.803080 +0.000000 0.732055 0.681246 +0.000000 0.629786 0.776769 +0.000000 0.595872 0.803080 +0.000000 0.732055 0.681246 +0.000000 0.516349 0.856378 +0.000000 0.595872 0.803080 +0.000000 0.629786 0.776769 +0.000000 0.516349 0.856378 +0.000000 0.429893 0.902880 +0.000000 0.595872 0.803080 +0.000000 0.395424 0.918499 +0.000000 0.429893 0.902880 +0.000000 0.516349 0.856378 +0.000000 0.395424 0.918499 +0.000000 0.270833 0.962626 +0.000000 0.429893 0.902880 +0.000000 0.881313 0.472533 +0.000000 0.958217 0.286043 +0.000000 0.958217 0.286043 +0.000000 0.986013 0.166667 +0.000000 0.958217 0.286043 +0.000000 0.986013 0.166667 +0.000000 0.958217 0.286043 +0.000000 0.958217 0.286043 +0.000000 0.986013 0.166667 +0.000000 0.000000 1.000000 +0.000000 0.122340 0.992488 +0.000000 0.000000 1.000000 +0.000000 0.122340 0.992488 +0.000000 0.122340 0.992488 +0.000000 0.000000 1.000000 +0.000000 0.122340 0.992488 +0.000000 0.319039 0.947742 +0.000000 0.122340 0.992488 +0.000000 0.319039 0.947742 +0.000000 0.319039 0.947742 +0.000000 0.122340 0.992488 +0.000000 0.495744 0.868469 +0.000000 0.319039 0.947742 +0.000000 0.319039 0.947742 +0.000000 0.495744 0.868469 +0.000000 0.495744 0.868469 +0.000000 0.319039 0.947742 +0.000000 0.645497 0.763763 +0.000000 0.495744 0.868469 +0.000000 0.495744 0.868469 +0.000000 0.645497 0.763763 +0.000000 0.645497 0.763763 +0.000000 0.495744 0.868469 +0.000000 0.645497 0.763763 +0.000000 0.773697 0.633555 +0.000000 0.645497 0.763763 +0.000000 0.773697 0.633555 +0.000000 0.773697 0.633555 +0.000000 0.645497 0.763763 +0.000000 0.773697 0.633555 +0.000000 0.881313 0.472533 +0.000000 0.773697 0.633555 +0.000000 0.881313 0.472533 +0.000000 0.881313 0.472533 +0.000000 0.773697 0.633555 +0.000000 0.958217 0.286043 +0.000000 0.881313 0.472533 +0.000000 0.881313 0.472533 +0.000000 -0.397177 0.917742 +0.000000 -0.566635 0.823969 +0.000000 -0.397177 0.917742 +0.000000 0.000000 1.000000 +0.000000 -0.204909 0.978781 +0.000000 0.000000 1.000000 +0.000000 -0.204909 0.978781 +0.000000 -0.204909 0.978781 +0.000000 0.000000 1.000000 +0.000000 -0.397177 0.917742 +0.000000 -0.204909 0.978781 +0.000000 -0.204909 0.978781 +0.000000 -0.397177 0.917742 +0.000000 -0.397177 0.917742 +0.000000 -0.204909 0.978781 +0.000000 -0.978781 0.204909 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -0.978781 0.204909 +0.000000 -0.978781 0.204909 +0.000000 -1.000000 0.000000 +0.000000 -0.917742 0.397177 +0.000000 -0.978781 0.204909 +0.000000 -0.978781 0.204909 +0.000000 -0.917742 0.397177 +0.000000 -0.917742 0.397177 +0.000000 -0.978781 0.204909 +0.000000 -0.917742 0.397177 +0.000000 -0.823969 0.566635 +0.000000 -0.917742 0.397177 +0.000000 -0.823969 0.566635 +0.000000 -0.823969 0.566635 +0.000000 -0.917742 0.397177 +0.000000 -0.823969 0.566635 +0.000000 -0.707107 0.707107 +0.000000 -0.823969 0.566635 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.823969 0.566635 +0.000000 -0.707107 0.707107 +0.000000 -0.566635 0.823969 +0.000000 -0.707107 0.707107 +0.000000 -0.566635 0.823969 +0.000000 -0.566635 0.823969 +0.000000 -0.707107 0.707107 +0.000000 -0.566635 0.823969 +0.000000 -0.397177 0.917742 +0.000000 -0.566635 0.823969 +0.000000 -0.917742 -0.397177 +0.000000 -0.823969 -0.566635 +0.000000 -0.917742 -0.397177 +0.000000 -1.000000 0.000000 +0.000000 -0.978781 -0.204909 +0.000000 -1.000000 0.000000 +0.000000 -0.978781 -0.204909 +0.000000 -0.978781 -0.204909 +0.000000 -1.000000 0.000000 +0.000000 -0.978781 -0.204909 +0.000000 -0.917742 -0.397177 +0.000000 -0.978781 -0.204909 +0.000000 -0.917742 -0.397177 +0.000000 -0.917742 -0.397177 +0.000000 -0.978781 -0.204909 +0.000000 0.000000 -1.000000 +0.000000 -0.204909 -0.978781 +0.000000 0.000000 -1.000000 +0.000000 -0.204909 -0.978781 +0.000000 -0.204909 -0.978781 +0.000000 0.000000 -1.000000 +0.000000 -0.397177 -0.917742 +0.000000 -0.204909 -0.978781 +0.000000 -0.204909 -0.978781 +0.000000 -0.397177 -0.917742 +0.000000 -0.397177 -0.917742 +0.000000 -0.204909 -0.978781 +0.000000 -0.566635 -0.823969 +0.000000 -0.397177 -0.917742 +0.000000 -0.397177 -0.917742 +0.000000 -0.566635 -0.823969 +0.000000 -0.566635 -0.823969 +0.000000 -0.397177 -0.917742 +0.000000 -0.707107 -0.707107 +0.000000 -0.566635 -0.823969 +0.000000 -0.566635 -0.823969 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.566635 -0.823969 +0.000000 -0.823969 -0.566635 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.823969 -0.566635 +0.000000 -0.823969 -0.566635 +0.000000 -0.707107 -0.707107 +0.000000 -0.823969 -0.566635 +0.000000 -0.917742 -0.397177 +0.000000 -0.823969 -0.566635 + + + + + + + + + + + +0.980760 0.492741 +0.980752 0.492821 +0.980874 0.492795 +0.980881 0.492715 +0.876959 0.671641 +0.877076 0.671641 +0.868750 0.669718 +0.868634 0.669718 +0.868889 0.670068 +0.868773 0.670068 +0.869335 0.670426 +0.869219 0.670426 +0.870107 0.670770 +0.869991 0.670770 +0.870612 0.670930 +0.870496 0.670930 +0.871189 0.671077 +0.871073 0.671077 +0.871828 0.671211 +0.871712 0.671211 +0.872520 0.671327 +0.872404 0.671327 +0.874011 0.671506 +0.873895 0.671506 +0.875561 0.671608 +0.875444 0.671608 +0.716450 0.527181 +0.799700 0.527181 +0.799700 0.531163 +0.799700 0.531267 +0.716450 0.531267 +0.716450 0.531163 +0.799700 0.530778 +0.799700 0.530167 +0.716450 0.530778 +0.716450 0.530167 +0.799700 0.529335 +0.799700 0.528245 +0.716450 0.529335 +0.716450 0.528245 +0.799700 0.531139 +0.716450 0.531267 +0.799700 0.531267 +0.716450 0.531139 +0.799700 0.515884 +0.716450 0.515884 +0.799700 0.516012 +0.799700 0.516424 +0.716450 0.516012 +0.799700 0.517138 +0.716450 0.516424 +0.799700 0.518137 +0.716450 0.517138 +0.799700 0.519366 +0.716450 0.518137 +0.716450 0.519366 +0.799700 0.520744 +0.716450 0.520744 +0.799700 0.522176 +0.716450 0.522176 +0.799700 0.523575 +0.716450 0.523575 +0.799700 0.524975 +0.716450 0.524975 +0.799700 0.526407 +0.716450 0.526407 +0.799700 0.527784 +0.716450 0.527784 +0.799700 0.529014 +0.716450 0.529014 +0.799700 0.530013 +0.716450 0.530013 +0.799700 0.530727 +0.716450 0.530727 +0.150350 0.700788 +0.092075 0.696374 +0.092075 0.696254 +0.150350 0.696254 +0.092075 0.697915 +0.150350 0.696374 +0.092075 0.699419 +0.150350 0.697915 +0.092075 0.700788 +0.150350 0.699419 +0.150350 0.701431 +0.150350 0.701342 +0.092075 0.701342 +0.150350 0.702467 +0.092075 0.701431 +0.150350 0.703265 +0.092075 0.702467 +0.150350 0.703764 +0.092075 0.703265 +0.092075 0.703764 +0.150350 0.703945 +0.150350 0.703824 +0.092075 0.703945 +0.092075 0.703824 +0.150350 0.703449 +0.092075 0.703449 +0.150350 0.702834 +0.150350 0.701943 +0.092075 0.702834 +0.092075 0.701943 +0.283550 0.519970 +0.200300 0.519970 +0.200300 0.515884 +0.283550 0.515884 +0.200300 0.515988 +0.283550 0.515988 +0.200300 0.516373 +0.283550 0.516373 +0.200300 0.516984 +0.283550 0.516984 +0.200300 0.517815 +0.200300 0.518906 +0.283550 0.517815 +0.283550 0.518906 +0.200300 0.520744 +0.283550 0.515884 +0.200300 0.515884 +0.283550 0.516012 +0.283550 0.516424 +0.200300 0.516012 +0.283550 0.517138 +0.200300 0.516424 +0.200300 0.517138 +0.283550 0.518137 +0.200300 0.518137 +0.283550 0.519367 +0.200300 0.519367 +0.283550 0.520744 +0.200300 0.531267 +0.283550 0.531267 +0.200300 0.531139 +0.200300 0.530727 +0.283550 0.531139 +0.283550 0.530727 +0.200300 0.530013 +0.200300 0.529014 +0.283550 0.530013 +0.283550 0.529014 +0.200300 0.527784 +0.283550 0.527784 +0.200300 0.526407 +0.200300 0.524975 +0.283550 0.526407 +0.200300 0.523575 +0.283550 0.524975 +0.283550 0.523575 +0.200300 0.522176 +0.283550 0.522176 +0.320940 0.507231 +0.320693 0.507231 +0.304682 0.507231 +0.304435 0.507231 +0.362565 0.507231 +0.362318 0.507231 +0.346307 0.507231 +0.346060 0.507231 +0.404190 0.507231 +0.403943 0.507231 +0.387932 0.507231 +0.387685 0.507231 +0.445815 0.507231 +0.445568 0.507231 +0.429557 0.507231 +0.429310 0.507231 +0.487440 0.507231 +0.487193 0.507231 +0.471182 0.507231 +0.470935 0.507231 +0.529065 0.507231 +0.528818 0.507231 +0.512807 0.507231 +0.512560 0.507231 +0.570690 0.507231 +0.570443 0.507231 +0.554432 0.507231 +0.554185 0.507231 +0.612315 0.507231 +0.612068 0.507231 +0.596057 0.507231 +0.595810 0.507231 +0.653940 0.507231 +0.653693 0.507231 +0.637682 0.507231 +0.637435 0.507231 +0.679060 0.539920 +0.679307 0.539920 +0.695318 0.539920 +0.695565 0.539920 +0.653940 0.539920 +0.637435 0.539920 +0.637682 0.539920 +0.653693 0.539920 +0.595810 0.539920 +0.596057 0.539920 +0.612068 0.539920 +0.612315 0.539920 +0.554185 0.539920 +0.554432 0.539920 +0.570443 0.539920 +0.570690 0.539920 +0.512560 0.539920 +0.512807 0.539920 +0.528818 0.539920 +0.529065 0.539920 +0.487440 0.539920 +0.470935 0.539920 +0.471182 0.539920 +0.487193 0.539920 +0.445815 0.539920 +0.429310 0.539920 +0.429557 0.539920 +0.445568 0.539920 +0.404190 0.539920 +0.387685 0.539920 +0.387932 0.539920 +0.403943 0.539920 +0.362565 0.539920 +0.346060 0.539920 +0.346307 0.539920 +0.362318 0.539920 +0.716450 0.523575 +0.716450 0.519970 +0.716450 0.521152 +0.716450 0.540401 +0.716450 0.525999 +0.716450 0.527181 +0.716450 0.518312 +0.716450 0.516984 +0.716450 0.528838 +0.716450 0.538959 +0.716450 0.541843 +0.716450 0.530167 +0.716450 0.506750 +0.716450 0.505308 +0.716450 0.516154 +0.716450 0.515884 +0.716450 0.508192 +0.716450 0.508449 +0.716450 0.516012 +0.716450 0.509272 +0.716450 0.516424 +0.716450 0.530997 +0.716450 0.538702 +0.716450 0.537879 +0.716450 0.531267 +0.716450 0.536451 +0.716450 0.531139 +0.716450 0.534453 +0.716450 0.530727 +0.716450 0.530013 +0.716450 0.531993 +0.716450 0.529014 +0.716450 0.529238 +0.716450 0.527784 +0.716450 0.526375 +0.716450 0.526407 +0.716450 0.523575 +0.716450 0.524975 +0.716450 0.510700 +0.716450 0.517138 +0.716450 0.518137 +0.716450 0.512698 +0.716450 0.519366 +0.716450 0.515157 +0.716450 0.520744 +0.716450 0.517913 +0.716450 0.522176 +0.716450 0.520776 +0.283550 0.523575 +0.283550 0.506750 +0.283550 0.521152 +0.283550 0.527181 +0.283550 0.525999 +0.283550 0.528838 +0.283550 0.519970 +0.283550 0.518313 +0.283550 0.530167 +0.283550 0.508192 +0.283550 0.505308 +0.283550 0.516984 +0.283550 0.540401 +0.283550 0.541843 +0.283550 0.530997 +0.283550 0.531267 +0.283550 0.538959 +0.283550 0.538702 +0.283550 0.531139 +0.283550 0.537879 +0.283550 0.530727 +0.283550 0.516154 +0.283550 0.508449 +0.283550 0.509272 +0.283550 0.515884 +0.283550 0.510700 +0.283550 0.516012 +0.283550 0.512698 +0.283550 0.516424 +0.283550 0.517138 +0.283550 0.515157 +0.283550 0.518137 +0.283550 0.517913 +0.283550 0.519367 +0.283550 0.520776 +0.283550 0.520744 +0.283550 0.523575 +0.283550 0.522176 +0.283550 0.536451 +0.283550 0.530013 +0.283550 0.529014 +0.283550 0.534453 +0.283550 0.527784 +0.283550 0.531993 +0.283550 0.526407 +0.283550 0.529238 +0.283550 0.524975 +0.283550 0.526375 +0.283494 0.525058 +0.283462 0.524811 +0.283230 0.543840 +0.283550 0.543766 +0.283550 0.506750 +0.283550 0.503385 +0.283550 0.521152 +0.283524 0.521688 +0.283494 0.522092 +0.283462 0.522340 +0.283430 0.522422 +0.283303 0.522422 +0.283230 0.503311 +0.283303 0.524729 +0.283550 0.540401 +0.283430 0.524729 +0.283550 0.525999 +0.283524 0.525463 +0.695565 0.507231 +0.695318 0.507231 +0.679307 0.507231 +0.679060 0.507231 +0.716506 0.522092 +0.716538 0.522340 +0.716770 0.503311 +0.716450 0.503385 +0.716450 0.540401 +0.716450 0.543766 +0.716450 0.525999 +0.716476 0.525463 +0.716506 0.525058 +0.716538 0.524811 +0.716570 0.524729 +0.716697 0.524729 +0.716770 0.543840 +0.716697 0.522422 +0.716450 0.506750 +0.716570 0.522422 +0.716450 0.521152 +0.716476 0.521688 +0.320940 0.539920 +0.304435 0.539920 +0.304682 0.539920 +0.320693 0.539920 +0.512560 0.539920 +0.512488 0.540401 +0.512488 0.543766 +0.512807 0.543840 +0.512807 0.539920 +0.487513 0.543766 +0.487193 0.543840 +0.512807 0.543840 +0.512488 0.543766 +0.487513 0.543766 +0.487513 0.540401 +0.487193 0.539920 +0.487193 0.543840 +0.487440 0.539920 +0.679060 0.539920 +0.678988 0.540401 +0.678988 0.543766 +0.679307 0.543840 +0.679307 0.539920 +0.678988 0.543766 +0.654013 0.543766 +0.653693 0.543840 +0.679307 0.543840 +0.654013 0.543766 +0.654013 0.540401 +0.653693 0.539920 +0.653693 0.543840 +0.653940 0.539920 +0.470935 0.539920 +0.470863 0.540401 +0.470863 0.543766 +0.471182 0.543840 +0.471182 0.539920 +0.445888 0.543766 +0.445568 0.543840 +0.471182 0.543840 +0.470863 0.543766 +0.445888 0.543766 +0.445888 0.540401 +0.445568 0.539920 +0.445568 0.543840 +0.445815 0.539920 +0.637435 0.539920 +0.637363 0.540401 +0.637363 0.543766 +0.637682 0.543840 +0.637682 0.539920 +0.637363 0.543766 +0.612388 0.543766 +0.612068 0.543840 +0.637682 0.543840 +0.612388 0.543766 +0.612388 0.540401 +0.612068 0.539920 +0.612068 0.543840 +0.612315 0.539920 +0.429310 0.539920 +0.429237 0.540401 +0.429237 0.543766 +0.429557 0.543840 +0.429557 0.539920 +0.404262 0.543766 +0.403943 0.543840 +0.429557 0.543840 +0.429237 0.543766 +0.404262 0.543766 +0.404262 0.540401 +0.403943 0.539920 +0.403943 0.543840 +0.404190 0.539920 +0.595810 0.539920 +0.595738 0.540401 +0.595738 0.543766 +0.596057 0.543840 +0.596057 0.539920 +0.570763 0.543766 +0.570443 0.543840 +0.596057 0.543840 +0.595738 0.543766 +0.570763 0.543766 +0.570763 0.540401 +0.570443 0.539920 +0.570443 0.543840 +0.570690 0.539920 +0.387685 0.539920 +0.387612 0.540401 +0.387612 0.543766 +0.387932 0.543840 +0.387932 0.539920 +0.387612 0.543766 +0.362637 0.543766 +0.362318 0.543840 +0.387932 0.543840 +0.362637 0.543766 +0.362637 0.540401 +0.362318 0.539920 +0.362318 0.543840 +0.362565 0.539920 +0.554185 0.539920 +0.554113 0.540401 +0.554113 0.543766 +0.554432 0.543840 +0.554432 0.539920 +0.554113 0.543766 +0.529138 0.543766 +0.528818 0.543840 +0.554432 0.543840 +0.529138 0.543766 +0.529138 0.540401 +0.528818 0.539920 +0.528818 0.543840 +0.529065 0.539920 +0.346060 0.539920 +0.345987 0.540401 +0.345987 0.543766 +0.346307 0.543840 +0.346307 0.539920 +0.321012 0.543766 +0.320693 0.543840 +0.346307 0.543840 +0.345987 0.543766 +0.321012 0.543766 +0.321012 0.540401 +0.320693 0.539920 +0.320693 0.543840 +0.320940 0.539920 +0.695638 0.543766 +0.695318 0.543840 +0.716770 0.543840 +0.716450 0.543766 +0.695638 0.543766 +0.695638 0.540401 +0.695318 0.539920 +0.695318 0.543840 +0.695565 0.539920 +0.304435 0.539920 +0.304362 0.540401 +0.304362 0.543766 +0.304682 0.543840 +0.304682 0.539920 +0.283550 0.543766 +0.283230 0.543840 +0.304682 0.543840 +0.304362 0.543766 +0.487513 0.503385 +0.512488 0.503385 +0.512807 0.503311 +0.487193 0.503311 +0.487440 0.507231 +0.487513 0.506750 +0.487513 0.503385 +0.487193 0.503311 +0.487193 0.507231 +0.512488 0.503385 +0.512488 0.506750 +0.512807 0.507231 +0.512807 0.503311 +0.512560 0.507231 +0.654013 0.503385 +0.678988 0.503385 +0.679307 0.503311 +0.653693 0.503311 +0.653940 0.507231 +0.654013 0.506750 +0.654013 0.503385 +0.653693 0.503311 +0.653693 0.507231 +0.678988 0.503385 +0.678988 0.506750 +0.679307 0.507231 +0.679307 0.503311 +0.679060 0.507231 +0.445887 0.503385 +0.470863 0.503385 +0.471182 0.503311 +0.445568 0.503311 +0.445815 0.507231 +0.445887 0.506750 +0.445887 0.503385 +0.445568 0.503311 +0.445568 0.507231 +0.470863 0.503385 +0.470863 0.506750 +0.471182 0.507231 +0.471182 0.503311 +0.470935 0.507231 +0.612388 0.503385 +0.637363 0.503385 +0.637682 0.503311 +0.612068 0.503311 +0.612315 0.507231 +0.612388 0.506750 +0.612388 0.503385 +0.612068 0.503311 +0.612068 0.507231 +0.637363 0.503385 +0.637363 0.506750 +0.637682 0.507231 +0.637682 0.503311 +0.637435 0.507231 +0.403943 0.503311 +0.404262 0.503385 +0.429237 0.503385 +0.429557 0.503311 +0.404190 0.507231 +0.404262 0.506750 +0.404262 0.503385 +0.403943 0.503311 +0.403943 0.507231 +0.429237 0.503385 +0.429237 0.506750 +0.429557 0.507231 +0.429557 0.503311 +0.429310 0.507231 +0.570443 0.503311 +0.570763 0.503385 +0.595738 0.503385 +0.596057 0.503311 +0.570690 0.507231 +0.570763 0.506750 +0.570763 0.503385 +0.570443 0.503311 +0.570443 0.507231 +0.595738 0.503385 +0.595738 0.506750 +0.596057 0.507231 +0.596057 0.503311 +0.595810 0.507231 +0.362637 0.503385 +0.387612 0.503385 +0.387932 0.503311 +0.362318 0.503311 +0.362565 0.507231 +0.362637 0.506750 +0.362637 0.503385 +0.362318 0.503311 +0.362318 0.507231 +0.387612 0.503385 +0.387612 0.506750 +0.387932 0.507231 +0.387932 0.503311 +0.387685 0.507231 +0.529138 0.503385 +0.554113 0.503385 +0.554432 0.503311 +0.528818 0.503311 +0.529065 0.507231 +0.529138 0.506750 +0.529138 0.503385 +0.528818 0.503311 +0.528818 0.507231 +0.554113 0.503385 +0.554113 0.506750 +0.554432 0.507231 +0.554432 0.503311 +0.554185 0.507231 +0.320693 0.503311 +0.321012 0.503385 +0.345987 0.503385 +0.346307 0.503311 +0.320940 0.507231 +0.321012 0.506750 +0.321012 0.503385 +0.320693 0.503311 +0.320693 0.507231 +0.345987 0.503385 +0.345987 0.506750 +0.346307 0.507231 +0.346307 0.503311 +0.346060 0.507231 +0.695638 0.503385 +0.716450 0.503385 +0.716770 0.503311 +0.695318 0.503311 +0.695565 0.507231 +0.695638 0.506750 +0.695638 0.503385 +0.695318 0.503311 +0.695318 0.507231 +0.304362 0.503385 +0.304362 0.506750 +0.304682 0.507231 +0.304682 0.503311 +0.304435 0.507231 +0.283550 0.503385 +0.304362 0.503385 +0.304682 0.503311 +0.283230 0.503311 +0.195444 0.543347 +0.200565 0.544785 +0.199074 0.544606 +0.190750 0.547513 +0.189201 0.547410 +0.187710 0.547231 +0.186379 0.546982 +0.185297 0.546674 +0.184525 0.546330 +0.184079 0.545972 +0.183940 0.545622 +0.197743 0.544357 +0.196662 0.544049 +0.195889 0.543705 +0.202115 0.544888 +0.203630 0.544920 +0.192265 0.547545 +0.796370 0.544920 +0.797885 0.544888 +0.799435 0.544785 +0.800926 0.544606 +0.802257 0.544357 +0.807735 0.547545 +0.809250 0.547513 +0.810799 0.547410 +0.812290 0.547231 +0.813622 0.546982 +0.814703 0.546674 +0.815475 0.546330 +0.815921 0.545972 +0.803338 0.544049 +0.804111 0.543705 +0.804556 0.543347 +0.804695 0.542997 +0.816060 0.545622 +0.804695 0.504154 +0.804556 0.503804 +0.804111 0.503446 +0.803338 0.503102 +0.802257 0.502794 +0.816060 0.501529 +0.815921 0.501179 +0.815475 0.500821 +0.814703 0.500477 +0.813622 0.500169 +0.812290 0.499919 +0.810799 0.499741 +0.809250 0.499638 +0.800926 0.502544 +0.799435 0.502366 +0.797885 0.502263 +0.796370 0.502231 +0.807735 0.499606 +0.203630 0.502231 +0.202115 0.502263 +0.200565 0.502366 +0.199074 0.502544 +0.197743 0.502794 +0.192265 0.499606 +0.190750 0.499638 +0.189201 0.499741 +0.187710 0.499919 +0.186379 0.500169 +0.185297 0.500477 +0.184525 0.500821 +0.184079 0.501179 +0.196662 0.503102 +0.195889 0.503446 +0.195444 0.503804 +0.195305 0.504154 +0.183940 0.501529 +0.195305 0.542997 +0.185007 0.546741 +0.150350 0.702407 +0.849651 0.702407 +0.150350 0.683178 +0.814993 0.500409 +0.813912 0.500102 +0.815766 0.500754 +0.812581 0.499852 +0.816211 0.501112 +0.849651 0.683178 +0.816350 0.501462 +0.816350 0.545689 +0.816211 0.546039 +0.815766 0.546397 +0.814994 0.546741 +0.813912 0.547049 +0.812581 0.547299 +0.811090 0.547477 +0.809541 0.547580 +0.808026 0.547612 +0.191974 0.547612 +0.190460 0.547580 +0.188910 0.547477 +0.811090 0.499674 +0.187419 0.547299 +0.809541 0.499571 +0.186088 0.547049 +0.808026 0.499539 +0.884338 0.490886 +0.191974 0.499539 +0.190460 0.499571 +0.188910 0.499674 +0.187419 0.499852 +0.186088 0.500102 +0.185007 0.500409 +0.184234 0.500754 +0.183789 0.501112 +0.183650 0.501462 +0.115662 0.490886 +0.183650 0.545689 +0.183789 0.546039 +0.184234 0.546397 +0.849651 0.689708 +0.849651 0.683178 +0.849651 0.683178 +0.849651 0.685311 +0.849651 0.687021 +0.849651 0.688213 +0.849651 0.688840 +0.849651 0.701342 +0.849651 0.683984 +0.849651 0.683178 +0.849651 0.704330 +0.849651 0.702407 +0.849651 0.703107 +0.849651 0.703823 +0.849651 0.704512 +0.849651 0.705127 +0.849651 0.705626 +0.849651 0.705983 +0.849651 0.706189 +0.849651 0.710099 +0.849651 0.712022 +0.849651 0.706253 +0.849651 0.704330 +0.849651 0.706253 +0.849651 0.706317 +0.849651 0.706523 +0.849651 0.706880 +0.849651 0.707380 +0.849651 0.707995 +0.849651 0.708683 +0.849651 0.709399 +0.849651 0.702800 +0.849651 0.703719 +0.849651 0.703929 +0.849651 0.703449 +0.849651 0.702346 +0.849651 0.700627 +0.849651 0.712022 +0.849651 0.711984 +0.849651 0.711874 +0.849651 0.711697 +0.849651 0.711460 +0.849651 0.711170 +0.849651 0.710837 +0.849651 0.710477 +0.849651 0.698492 +0.849651 0.710099 +0.849651 0.696254 +0.849651 0.694016 +0.849651 0.691881 +0.849651 0.690162 +0.849651 0.689059 +0.849651 0.691166 +0.849651 0.688579 +0.849651 0.688789 +0.851768 0.673740 +0.850006 0.683178 +0.850494 0.683178 +0.850449 0.682986 +0.850480 0.682368 +0.850595 0.681297 +0.849651 0.683178 +0.849651 0.683984 +0.884338 0.490886 +0.850795 0.679799 +0.850561 0.679585 +0.851071 0.677954 +0.851243 0.675486 +0.851404 0.675887 +0.884762 0.490792 +0.852139 0.671641 +0.851184 0.675486 +0.283550 0.505308 +0.283550 0.508192 +0.882849 0.481271 +0.824675 0.538959 +0.117151 0.481271 +0.841571 0.710099 +0.175325 0.538959 +0.283550 0.538959 +0.824675 0.508192 +0.716450 0.508192 +0.716450 0.505308 +0.716450 0.541843 +0.716450 0.538959 +0.283550 0.541843 +0.158429 0.710099 +0.175325 0.508192 +0.096890 0.527531 +0.097276 0.527531 +0.094157 0.510243 +0.093771 0.510243 +0.100702 0.548665 +0.101088 0.548665 +0.097970 0.531377 +0.097583 0.531377 +0.104514 0.569799 +0.104901 0.569799 +0.101782 0.552511 +0.101396 0.552511 +0.108327 0.590933 +0.108713 0.590933 +0.105594 0.573645 +0.105208 0.573645 +0.112139 0.612067 +0.112525 0.612067 +0.109407 0.594779 +0.109020 0.594779 +0.115951 0.633201 +0.116338 0.633201 +0.113219 0.615912 +0.112833 0.615912 +0.119764 0.654334 +0.120150 0.654334 +0.117031 0.637046 +0.116645 0.637046 +0.122539 0.669718 +0.122925 0.669718 +0.120844 0.658180 +0.120457 0.658180 +0.905843 0.510243 +0.902724 0.527531 +0.903111 0.527531 +0.906229 0.510243 +0.908988 0.492809 +0.906536 0.506397 +0.906923 0.506397 +0.909374 0.492809 +0.902030 0.531377 +0.898912 0.548665 +0.899298 0.548665 +0.902417 0.531377 +0.898218 0.552511 +0.895100 0.569799 +0.895486 0.569799 +0.898605 0.552511 +0.894406 0.573645 +0.891287 0.590933 +0.891674 0.590933 +0.894792 0.573645 +0.890594 0.594779 +0.887475 0.612067 +0.887861 0.612067 +0.890980 0.594779 +0.886781 0.615912 +0.883663 0.633200 +0.884049 0.633200 +0.887168 0.615912 +0.882969 0.637046 +0.879850 0.654334 +0.880237 0.654334 +0.883355 0.637046 +0.879157 0.658180 +0.877075 0.669718 +0.877462 0.669718 +0.879543 0.658180 +0.131359 0.669638 +0.115238 0.490792 +0.091112 0.490792 +0.124590 0.671607 +0.123041 0.671641 +0.092593 0.490822 +0.126176 0.671499 +0.094105 0.490920 +0.127699 0.671311 +0.095564 0.491090 +0.129049 0.671049 +0.096875 0.491327 +0.130129 0.670726 +0.097955 0.491620 +0.130877 0.670367 +0.098749 0.491949 +0.131278 0.669996 +0.099235 0.492294 +0.147861 0.671641 +0.099429 0.492635 +0.980742 0.492365 +0.992921 0.490792 +0.972556 0.490792 +0.942107 0.671610 +0.940626 0.671641 +0.943620 0.671512 +0.974071 0.490824 +0.945078 0.671342 +0.975621 0.490927 +0.946389 0.671105 +0.977112 0.491105 +0.947470 0.670813 +0.978443 0.491355 +0.948263 0.670483 +0.979524 0.491662 +0.948750 0.670138 +0.980296 0.492007 +0.948944 0.669798 +0.960297 0.671641 +0.980874 0.492795 +0.980881 0.492715 +0.849651 0.706253 +0.849651 0.706253 +0.150350 0.706253 +0.150350 0.706253 +0.019126 0.492795 +0.039703 0.671641 +0.059374 0.671641 +0.025895 0.490825 +0.027444 0.490792 +0.024309 0.490933 +0.057893 0.671610 +0.056381 0.671512 +0.022786 0.491121 +0.054922 0.671343 +0.021436 0.491384 +0.053611 0.671106 +0.020356 0.491706 +0.052531 0.670813 +0.019608 0.492065 +0.051737 0.670483 +0.019207 0.492436 +0.051250 0.670138 +0.007080 0.490792 +0.051056 0.669798 +0.868773 0.670068 +0.852139 0.671641 +0.876959 0.671641 +0.907407 0.490822 +0.908888 0.490792 +0.905895 0.490920 +0.875444 0.671608 +0.873895 0.671506 +0.904436 0.491090 +0.903125 0.491327 +0.872404 0.671327 +0.902045 0.491620 +0.871073 0.671077 +0.901251 0.491949 +0.869991 0.670770 +0.900765 0.492294 +0.869219 0.670426 +0.900571 0.492635 +0.884762 0.490792 +0.868641 0.669638 +0.868634 0.669718 +0.138719 0.712022 +0.150350 0.712022 +0.150350 0.712022 +0.130284 0.712022 +0.111397 0.712022 +0.094043 0.712022 +0.079027 0.712022 +0.066689 0.712022 +0.057603 0.712022 +0.051996 0.712022 +0.050110 0.712022 +0.050110 0.712022 +0.051918 0.712022 +0.057715 0.712022 +0.067767 0.712022 +0.081836 0.712022 +0.099156 0.712022 +0.118557 0.712022 +0.869716 0.712022 +0.849651 0.712022 +0.888604 0.712022 +0.905958 0.712022 +0.920974 0.712022 +0.933312 0.712022 +0.942397 0.712022 +0.948005 0.712022 +0.949890 0.712022 +0.949890 0.712022 +0.948082 0.712022 +0.942285 0.712022 +0.932234 0.712022 +0.918164 0.712022 +0.900845 0.712022 +0.881443 0.712022 +0.861281 0.712022 +0.841571 0.712022 +0.849651 0.712022 +0.158429 0.712022 +0.117151 0.481271 +0.034666 0.481271 +0.062383 0.481271 +0.019514 0.481271 +0.046410 0.481271 +0.008690 0.481271 +0.033434 0.481271 +0.002447 0.481271 +0.024164 0.481271 +0.000499 0.481271 +0.018817 0.481271 +0.002447 0.481271 +0.017150 0.481271 +0.008690 0.481271 +0.018817 0.481271 +0.019514 0.481271 +0.024164 0.481271 +0.034666 0.481271 +0.033434 0.481271 +0.053318 0.481271 +0.046410 0.481271 +0.074212 0.481271 +0.062383 0.481271 +0.095925 0.481271 +0.080277 0.481271 +0.053318 0.481271 +0.080277 0.481271 +0.074212 0.481271 +0.098871 0.481271 +0.095925 0.481271 +0.117050 0.481271 +0.117151 0.481271 +0.098871 0.481271 +0.117050 0.481271 +0.882849 0.481271 +0.904076 0.481271 +0.882950 0.481271 +0.925788 0.481271 +0.901129 0.481271 +0.946682 0.481271 +0.919723 0.481271 +0.965334 0.481271 +0.937617 0.481271 +0.980486 0.481271 +0.953590 0.481271 +0.991310 0.481271 +0.966566 0.481271 +0.997553 0.481271 +0.975836 0.481271 +0.999501 0.481271 +0.981183 0.481271 +0.997553 0.481271 +0.982850 0.481271 +0.991310 0.481271 +0.981183 0.481271 +0.980486 0.481271 +0.975836 0.481271 +0.965334 0.481271 +0.966566 0.481271 +0.946682 0.481271 +0.953590 0.481271 +0.925788 0.481271 +0.937617 0.481271 +0.904076 0.481271 +0.919723 0.481271 +0.882849 0.481271 +0.901129 0.481271 +0.882950 0.481271 +0.875933 0.488963 +0.875933 0.490490 +0.118814 0.490490 +0.124067 0.490490 +0.117151 0.481271 +0.882849 0.481271 +0.124067 0.488963 +0.881186 0.490490 +0.041792 0.710179 +0.041792 0.710179 +0.036803 0.682521 +0.036803 0.682518 +0.958208 0.710179 +0.963198 0.682518 +0.963197 0.682521 +0.958208 0.710179 +0.150350 0.683178 +0.149994 0.683178 +0.149506 0.683178 +0.038112 0.683178 +0.042771 0.683178 +0.050822 0.683178 +0.061992 0.683178 +0.075992 0.683178 +0.092306 0.683178 +0.110559 0.683178 +0.130032 0.683178 +0.150350 0.683178 +0.850494 0.683178 +0.850006 0.683178 +0.957205 0.683178 +0.961888 0.683178 +0.949172 0.683178 +0.937958 0.683178 +0.924000 0.683178 +0.907625 0.683178 +0.889429 0.683178 +0.869888 0.683178 +0.849651 0.683178 +0.849651 0.683178 +0.869842 0.490782 +0.125231 0.490758 +0.124067 0.490490 +0.118814 0.490490 +0.097588 0.490494 +0.075878 0.490506 +0.054988 0.490528 +0.036341 0.490559 +0.021196 0.490596 +0.010379 0.490638 +0.004145 0.490682 +0.002205 0.490725 +0.007080 0.490792 +0.125532 0.490765 +0.881186 0.490490 +0.875933 0.490490 +0.902412 0.490494 +0.924122 0.490506 +0.945012 0.490528 +0.963659 0.490558 +0.978804 0.490596 +0.989621 0.490638 +0.995855 0.490682 +0.997795 0.490725 +0.992921 0.490792 +0.972556 0.490792 +0.874769 0.490758 +0.909000 0.490819 +0.972435 0.490819 +0.908888 0.490792 +0.884762 0.490792 +0.874468 0.490764 +0.873559 0.490771 +0.115662 0.490886 +0.884338 0.490886 +0.027565 0.490819 +0.091000 0.490819 +0.027444 0.490792 +0.091112 0.490792 +0.126441 0.490771 +0.127995 0.490777 +0.872005 0.490777 +0.130158 0.490782 +0.115238 0.490792 +0.132812 0.490786 +0.135781 0.490789 +0.138864 0.490791 +0.141880 0.490792 +0.858120 0.490792 +0.861135 0.490791 +0.864219 0.490789 +0.867188 0.490786 +0.150350 0.688579 +0.150350 0.686793 +0.150350 0.683178 +0.150350 0.688705 +0.150350 0.688834 +0.150350 0.688950 +0.150350 0.689098 +0.150350 0.689270 +0.150350 0.703177 +0.150350 0.691167 +0.150350 0.702407 +0.150350 0.683178 +0.150350 0.683984 +0.150350 0.703107 +0.150350 0.703823 +0.150350 0.704512 +0.150350 0.703177 +0.150350 0.705127 +0.150350 0.705626 +0.150350 0.703387 +0.150350 0.705983 +0.150350 0.703601 +0.150350 0.706189 +0.150350 0.703808 +0.150350 0.706253 +0.150350 0.703992 +0.150350 0.704142 +0.150350 0.706253 +0.150350 0.704249 +0.150350 0.704311 +0.150350 0.689458 +0.150350 0.704330 +0.150350 0.706317 +0.150350 0.706523 +0.150350 0.706880 +0.150350 0.707380 +0.150350 0.707995 +0.150350 0.708683 +0.150350 0.712022 +0.150350 0.712022 +0.150350 0.689843 +0.150350 0.709399 +0.150350 0.710099 +0.150350 0.704330 +0.150350 0.704311 +0.150350 0.704249 +0.150350 0.704142 +0.150350 0.703992 +0.150350 0.703808 +0.150350 0.703601 +0.150350 0.703387 +0.150350 0.701342 +0.150350 0.702800 +0.150350 0.703719 +0.150350 0.703929 +0.150350 0.703449 +0.150350 0.702346 +0.150350 0.711984 +0.150350 0.711874 +0.150350 0.711697 +0.150350 0.711459 +0.150350 0.711169 +0.150350 0.710837 +0.150350 0.710476 +0.150350 0.710099 +0.150350 0.700627 +0.150350 0.683178 +0.150350 0.698492 +0.150350 0.696254 +0.150350 0.694016 +0.150350 0.691881 +0.150350 0.690162 +0.150350 0.689708 +0.150350 0.689059 +0.150350 0.688789 +0.148817 0.675796 +0.149551 0.682986 +0.149506 0.683178 +0.149521 0.682368 +0.149406 0.681298 +0.149205 0.679799 +0.149025 0.676640 +0.150350 0.683984 +0.150350 0.683178 +0.148955 0.676264 +0.148919 0.676080 +0.148884 0.675911 +0.148852 0.675765 +0.148825 0.675647 +0.148786 0.675510 +0.148929 0.677954 +0.149994 0.683178 +0.148597 0.675888 +0.149501 0.679968 +0.148233 0.673740 +0.148901 0.676328 +0.115662 0.490886 +0.115238 0.490792 +0.148794 0.675612 +0.147861 0.671641 +0.148854 0.676044 +0.123041 0.671641 +0.059374 0.671641 +0.039703 0.671641 +0.148233 0.673740 +0.147861 0.671641 +0.038112 0.683178 +0.149506 0.683178 +0.037181 0.683015 +0.036803 0.682521 +0.149551 0.682986 +0.036803 0.682518 +0.036886 0.681796 +0.149521 0.682368 +0.037288 0.680833 +0.149406 0.681298 +0.037890 0.679663 +0.149316 0.680598 +0.149205 0.679799 +0.038573 0.678297 +0.149076 0.678913 +0.039201 0.676779 +0.148929 0.677954 +0.039660 0.675135 +0.148597 0.675888 +0.039847 0.673411 +0.940626 0.671641 +0.960153 0.673418 +0.960297 0.671641 +0.850494 0.683178 +0.961888 0.683178 +0.850449 0.682986 +0.962819 0.683015 +0.850480 0.682368 +0.963197 0.682521 +0.963198 0.682518 +0.850595 0.681297 +0.963116 0.681800 +0.850685 0.680598 +0.962718 0.680843 +0.850795 0.679799 +0.850925 0.678913 +0.962115 0.679670 +0.851071 0.677954 +0.961434 0.678311 +0.851404 0.675887 +0.960802 0.676788 +0.851768 0.673740 +0.960344 0.675153 +0.852139 0.671641 +0.876959 0.671641 +0.150350 0.712022 +0.849651 0.712022 +0.849651 0.710099 +0.150350 0.710099 +0.948944 0.669798 +0.980874 0.492795 +0.980752 0.492821 +0.948828 0.669798 +0.876959 0.671641 +0.940626 0.671641 +0.940510 0.671641 +0.877076 0.671641 +0.900682 0.492661 +0.900571 0.492635 +0.868641 0.669638 +0.868758 0.669638 +0.954028 0.594779 +0.943503 0.671512 +0.941991 0.671610 +0.940510 0.671641 +0.944962 0.671342 +0.946273 0.671105 +0.947353 0.670813 +0.948147 0.670483 +0.948634 0.670138 +0.900876 0.492321 +0.901363 0.491976 +0.902156 0.491646 +0.903237 0.491354 +0.904548 0.491117 +0.906006 0.490947 +0.907519 0.490849 +0.909000 0.490819 +0.886781 0.615912 +0.950910 0.612067 +0.954722 0.590933 +0.890594 0.594779 +0.947098 0.633200 +0.882969 0.637046 +0.943285 0.654334 +0.879157 0.658180 +0.900682 0.492661 +0.906536 0.506397 +0.902724 0.527531 +0.966159 0.527531 +0.902030 0.531377 +0.898912 0.548665 +0.895100 0.569799 +0.898218 0.552511 +0.962347 0.548665 +0.905843 0.510243 +0.969971 0.506397 +0.940510 0.669718 +0.877076 0.671641 +0.875561 0.671608 +0.874011 0.671506 +0.872520 0.671327 +0.871189 0.671077 +0.870107 0.670770 +0.869335 0.670426 +0.868889 0.670068 +0.868750 0.669718 +0.868758 0.669638 +0.908988 0.492809 +0.972435 0.490819 +0.973950 0.490851 +0.975499 0.490954 +0.976990 0.491132 +0.978321 0.491382 +0.979403 0.491689 +0.980175 0.492034 +0.980621 0.492391 +0.980760 0.492741 +0.980752 0.492821 +0.948828 0.669798 +0.972423 0.492809 +0.969278 0.510243 +0.965465 0.531377 +0.961653 0.552511 +0.942591 0.658180 +0.877075 0.669718 +0.946404 0.637046 +0.879850 0.654334 +0.883663 0.633200 +0.950216 0.615912 +0.887475 0.612067 +0.891287 0.590933 +0.894406 0.573645 +0.958534 0.569799 +0.957841 0.573645 +0.131359 0.669638 +0.099429 0.492635 +0.099318 0.492661 +0.131243 0.669638 +0.123041 0.671641 +0.122925 0.671641 +0.059491 0.671641 +0.059374 0.671641 +0.019248 0.492821 +0.019126 0.492795 +0.051056 0.669798 +0.051172 0.669798 +0.055038 0.671343 +0.056497 0.671512 +0.058010 0.671610 +0.053727 0.671106 +0.052647 0.670813 +0.051853 0.670483 +0.051367 0.670138 +0.051172 0.669798 +0.099318 0.492661 +0.099124 0.492321 +0.098637 0.491976 +0.097843 0.491646 +0.096763 0.491354 +0.095452 0.491117 +0.093994 0.490947 +0.092481 0.490849 +0.053597 0.637046 +0.116338 0.633201 +0.112525 0.612067 +0.049784 0.615912 +0.108713 0.590933 +0.045972 0.594779 +0.104901 0.569799 +0.042160 0.573645 +0.131243 0.669638 +0.091012 0.492809 +0.094157 0.510243 +0.097970 0.531377 +0.101782 0.552511 +0.105594 0.573645 +0.109407 0.594779 +0.113219 0.615912 +0.117031 0.637046 +0.030722 0.510243 +0.093464 0.506397 +0.034535 0.531377 +0.097276 0.527531 +0.038347 0.552511 +0.101088 0.548665 +0.122925 0.669718 +0.059491 0.671641 +0.122925 0.671641 +0.124473 0.671607 +0.126059 0.671499 +0.127583 0.671311 +0.128933 0.671049 +0.130013 0.670726 +0.130761 0.670367 +0.131162 0.669996 +0.059490 0.669718 +0.019248 0.492821 +0.027577 0.492809 +0.091000 0.490819 +0.027565 0.490819 +0.026017 0.490852 +0.024430 0.490960 +0.022907 0.491148 +0.021557 0.491410 +0.020477 0.491733 +0.019729 0.492092 +0.019328 0.492463 +0.030029 0.506397 +0.120844 0.658180 +0.057409 0.658180 +0.120150 0.654334 +0.056715 0.654334 +0.052903 0.633201 +0.049090 0.612067 +0.045278 0.590933 +0.041466 0.569799 +0.037653 0.548665 +0.033841 0.527531 +0.914410 0.669718 +0.896533 0.669718 +0.877075 0.669718 +0.940510 0.669718 +0.929455 0.669718 +0.877462 0.669718 +0.909374 0.492809 +0.928445 0.492809 +0.961368 0.492809 +0.972423 0.492809 +0.946323 0.492809 +0.908988 0.492809 +0.122539 0.669718 +0.103468 0.669718 +0.070545 0.669718 +0.059490 0.669718 +0.085590 0.669718 +0.122925 0.669718 +0.053677 0.492809 +0.071555 0.492809 +0.091012 0.492809 +0.027577 0.492809 +0.038632 0.492809 +0.090626 0.492809 +0.093077 0.506397 +0.093464 0.506397 +0.091012 0.492809 +0.090626 0.492809 +0.879543 0.658180 +0.898614 0.658180 +0.931537 0.658180 +0.942591 0.658180 +0.916491 0.658180 +0.879157 0.658180 +0.917185 0.654334 +0.899308 0.654334 +0.879850 0.654334 +0.943285 0.654334 +0.932230 0.654334 +0.880237 0.654334 +0.883355 0.637046 +0.902426 0.637046 +0.935349 0.637046 +0.946404 0.637046 +0.920304 0.637046 +0.882969 0.637046 +0.920997 0.633200 +0.903120 0.633200 +0.883663 0.633200 +0.947098 0.633200 +0.936043 0.633200 +0.884049 0.633200 +0.887168 0.615912 +0.906238 0.615912 +0.939161 0.615912 +0.950216 0.615912 +0.924116 0.615912 +0.886781 0.615912 +0.924810 0.612067 +0.906932 0.612067 +0.887475 0.612067 +0.950910 0.612067 +0.939855 0.612067 +0.887861 0.612067 +0.890980 0.594779 +0.910051 0.594779 +0.942973 0.594779 +0.954028 0.594779 +0.927928 0.594779 +0.890594 0.594779 +0.928622 0.590933 +0.910744 0.590933 +0.891287 0.590933 +0.954722 0.590933 +0.943667 0.590933 +0.891674 0.590933 +0.894792 0.573645 +0.913863 0.573645 +0.946786 0.573645 +0.957841 0.573645 +0.931741 0.573645 +0.894406 0.573645 +0.932434 0.569799 +0.914557 0.569799 +0.895100 0.569799 +0.958534 0.569799 +0.947480 0.569799 +0.895486 0.569799 +0.898605 0.552511 +0.917675 0.552511 +0.950598 0.552511 +0.961653 0.552511 +0.935553 0.552511 +0.898218 0.552511 +0.936247 0.548665 +0.918369 0.548665 +0.898912 0.548665 +0.962347 0.548665 +0.951292 0.548665 +0.899298 0.548665 +0.902417 0.531377 +0.921488 0.531377 +0.954410 0.531377 +0.965465 0.531377 +0.939365 0.531377 +0.902030 0.531377 +0.940059 0.527531 +0.922181 0.527531 +0.902724 0.527531 +0.966159 0.527531 +0.955104 0.527531 +0.903111 0.527531 +0.906229 0.510243 +0.925300 0.510243 +0.958223 0.510243 +0.969278 0.510243 +0.943177 0.510243 +0.905843 0.510243 +0.943871 0.506397 +0.925994 0.506397 +0.906536 0.506397 +0.969971 0.506397 +0.958916 0.506397 +0.906923 0.506397 +0.083509 0.658180 +0.101387 0.658180 +0.120844 0.658180 +0.057409 0.658180 +0.068464 0.658180 +0.120457 0.658180 +0.119764 0.654334 +0.100693 0.654334 +0.067770 0.654334 +0.056715 0.654334 +0.082815 0.654334 +0.120150 0.654334 +0.079697 0.637046 +0.097574 0.637046 +0.117031 0.637046 +0.053597 0.637046 +0.064651 0.637046 +0.116645 0.637046 +0.115951 0.633201 +0.096880 0.633201 +0.063958 0.633201 +0.052903 0.633201 +0.079003 0.633201 +0.116338 0.633201 +0.075884 0.615912 +0.093762 0.615912 +0.113219 0.615912 +0.049784 0.615912 +0.060839 0.615912 +0.112833 0.615912 +0.112139 0.612067 +0.093068 0.612067 +0.060145 0.612067 +0.049090 0.612067 +0.075191 0.612067 +0.112525 0.612067 +0.072072 0.594779 +0.089950 0.594779 +0.109407 0.594779 +0.045972 0.594779 +0.057027 0.594779 +0.109020 0.594779 +0.108327 0.590933 +0.089256 0.590933 +0.056333 0.590933 +0.045278 0.590933 +0.071378 0.590933 +0.108713 0.590933 +0.068260 0.573645 +0.086137 0.573645 +0.105594 0.573645 +0.042160 0.573645 +0.053214 0.573645 +0.105208 0.573645 +0.104514 0.569799 +0.085443 0.569799 +0.052521 0.569799 +0.041466 0.569799 +0.067566 0.569799 +0.104901 0.569799 +0.064447 0.552511 +0.082325 0.552511 +0.101782 0.552511 +0.038347 0.552511 +0.049402 0.552511 +0.101396 0.552511 +0.100702 0.548665 +0.081631 0.548665 +0.048708 0.548665 +0.037653 0.548665 +0.063753 0.548665 +0.101088 0.548665 +0.060635 0.531377 +0.078513 0.531377 +0.097970 0.531377 +0.034535 0.531377 +0.045590 0.531377 +0.097583 0.531377 +0.096890 0.527531 +0.077819 0.527531 +0.044896 0.527531 +0.033841 0.527531 +0.059941 0.527531 +0.097276 0.527531 +0.056823 0.510243 +0.074700 0.510243 +0.094157 0.510243 +0.030722 0.510243 +0.041777 0.510243 +0.093771 0.510243 +0.093077 0.506397 +0.074006 0.506397 +0.041084 0.506397 +0.030029 0.506397 +0.056129 0.506397 +0.093464 0.506397 +0.032562 0.492809 +0.027577 0.492809 +0.083501 0.506397 +0.093077 0.506397 +0.090626 0.492809 +0.074006 0.506397 +0.081050 0.492809 +0.064810 0.506397 +0.071555 0.492809 +0.056129 0.506397 +0.062359 0.492809 +0.048164 0.506397 +0.053677 0.492809 +0.041084 0.506397 +0.045713 0.492809 +0.035013 0.506397 +0.038632 0.492809 +0.030029 0.506397 +0.035707 0.510243 +0.030722 0.510243 +0.087314 0.527531 +0.096890 0.527531 +0.093771 0.510243 +0.077819 0.527531 +0.084195 0.510243 +0.068622 0.527531 +0.074700 0.510243 +0.059941 0.527531 +0.065504 0.510243 +0.051976 0.527531 +0.056823 0.510243 +0.044896 0.527531 +0.048858 0.510243 +0.038826 0.527531 +0.041777 0.510243 +0.033841 0.527531 +0.039520 0.531377 +0.034535 0.531377 +0.091126 0.548665 +0.100702 0.548665 +0.097583 0.531377 +0.081631 0.548665 +0.088007 0.531377 +0.072435 0.548665 +0.078513 0.531377 +0.063753 0.548665 +0.069316 0.531377 +0.055789 0.548665 +0.060635 0.531377 +0.048708 0.548665 +0.052670 0.531377 +0.042638 0.548665 +0.045590 0.531377 +0.037653 0.548665 +0.043332 0.552511 +0.038347 0.552511 +0.094938 0.569799 +0.104514 0.569799 +0.101396 0.552511 +0.085443 0.569799 +0.091820 0.552511 +0.076247 0.569799 +0.082325 0.552511 +0.067566 0.569799 +0.073128 0.552511 +0.059601 0.569799 +0.064447 0.552511 +0.052521 0.569799 +0.056482 0.552511 +0.046450 0.569799 +0.049402 0.552511 +0.041466 0.569799 +0.047144 0.573645 +0.042160 0.573645 +0.098751 0.590933 +0.108327 0.590933 +0.105208 0.573645 +0.089256 0.590933 +0.095632 0.573645 +0.080059 0.590933 +0.086137 0.573645 +0.071378 0.590933 +0.076941 0.573645 +0.063413 0.590933 +0.068260 0.573645 +0.056333 0.590933 +0.060295 0.573645 +0.050263 0.590933 +0.053214 0.573645 +0.045278 0.590933 +0.050957 0.594779 +0.045972 0.594779 +0.102563 0.612067 +0.112139 0.612067 +0.109020 0.594779 +0.093068 0.612067 +0.099445 0.594779 +0.083872 0.612067 +0.089950 0.594779 +0.075191 0.612067 +0.080753 0.594779 +0.067226 0.612067 +0.072072 0.594779 +0.060145 0.612067 +0.064107 0.594779 +0.054075 0.612067 +0.057027 0.594779 +0.049090 0.612067 +0.054769 0.615912 +0.049784 0.615912 +0.106375 0.633201 +0.115951 0.633201 +0.112833 0.615912 +0.096880 0.633201 +0.103257 0.615912 +0.087684 0.633201 +0.093762 0.615912 +0.079003 0.633201 +0.084565 0.615912 +0.071038 0.633201 +0.075884 0.615912 +0.063958 0.633201 +0.067919 0.615912 +0.057888 0.633201 +0.060839 0.615912 +0.052903 0.633201 +0.058581 0.637046 +0.053597 0.637046 +0.110188 0.654334 +0.119764 0.654334 +0.116645 0.637046 +0.100693 0.654334 +0.107069 0.637046 +0.091496 0.654334 +0.097574 0.637046 +0.082815 0.654334 +0.088378 0.637046 +0.074850 0.654334 +0.079697 0.637046 +0.067770 0.654334 +0.071732 0.637046 +0.061700 0.654334 +0.064651 0.637046 +0.056715 0.654334 +0.062394 0.658180 +0.057409 0.658180 +0.112963 0.669718 +0.122539 0.669718 +0.120457 0.658180 +0.103468 0.669718 +0.110882 0.658180 +0.094271 0.669718 +0.101387 0.658180 +0.085590 0.669718 +0.092190 0.658180 +0.077625 0.669718 +0.083509 0.658180 +0.070545 0.669718 +0.075544 0.658180 +0.064475 0.669718 +0.068464 0.658180 +0.059490 0.669718 +0.969971 0.506397 +0.972423 0.492809 +0.909374 0.492809 +0.906923 0.506397 +0.918950 0.492809 +0.916499 0.506397 +0.928445 0.492809 +0.925994 0.506397 +0.937642 0.492809 +0.935190 0.506397 +0.946323 0.492809 +0.943871 0.506397 +0.954288 0.492809 +0.951836 0.506397 +0.961368 0.492809 +0.958916 0.506397 +0.967438 0.492809 +0.964987 0.506397 +0.966159 0.527531 +0.969278 0.510243 +0.906229 0.510243 +0.903111 0.527531 +0.915805 0.510243 +0.912686 0.527531 +0.925300 0.510243 +0.922181 0.527531 +0.934497 0.510243 +0.931378 0.527531 +0.943177 0.510243 +0.940059 0.527531 +0.951142 0.510243 +0.948024 0.527531 +0.958223 0.510243 +0.955104 0.527531 +0.964293 0.510243 +0.961174 0.527531 +0.962347 0.548665 +0.965465 0.531377 +0.902417 0.531377 +0.899298 0.548665 +0.911993 0.531377 +0.908874 0.548665 +0.921488 0.531377 +0.918369 0.548665 +0.930684 0.531377 +0.927566 0.548665 +0.939365 0.531377 +0.936247 0.548665 +0.947330 0.531377 +0.944212 0.548665 +0.954410 0.531377 +0.951292 0.548665 +0.960481 0.531377 +0.957362 0.548665 +0.958534 0.569799 +0.961653 0.552511 +0.898605 0.552511 +0.895486 0.569799 +0.908180 0.552511 +0.905062 0.569799 +0.917675 0.552511 +0.914557 0.569799 +0.926872 0.552511 +0.923753 0.569799 +0.935553 0.552511 +0.932434 0.569799 +0.943518 0.552511 +0.940399 0.569799 +0.950598 0.552511 +0.947480 0.569799 +0.956668 0.552511 +0.953550 0.569799 +0.954722 0.590933 +0.957841 0.573645 +0.894792 0.573645 +0.891674 0.590933 +0.904368 0.573645 +0.901250 0.590933 +0.913863 0.573645 +0.910744 0.590933 +0.923060 0.573645 +0.919941 0.590933 +0.931741 0.573645 +0.928622 0.590933 +0.939706 0.573645 +0.936587 0.590933 +0.946786 0.573645 +0.943667 0.590933 +0.952856 0.573645 +0.949737 0.590933 +0.950910 0.612067 +0.954028 0.594779 +0.890980 0.594779 +0.887861 0.612067 +0.900556 0.594779 +0.897437 0.612067 +0.910051 0.594779 +0.906932 0.612067 +0.919247 0.594779 +0.916129 0.612067 +0.927928 0.594779 +0.924810 0.612067 +0.935893 0.594779 +0.932775 0.612067 +0.942973 0.594779 +0.939855 0.612067 +0.949044 0.594779 +0.945925 0.612067 +0.947098 0.633200 +0.950216 0.615912 +0.887168 0.615912 +0.884049 0.633200 +0.896743 0.615912 +0.893625 0.633200 +0.906238 0.615912 +0.903120 0.633200 +0.915435 0.615912 +0.912316 0.633200 +0.924116 0.615912 +0.920997 0.633200 +0.932081 0.615912 +0.928962 0.633200 +0.939161 0.615912 +0.936043 0.633200 +0.945231 0.615912 +0.942113 0.633200 +0.943285 0.654334 +0.946404 0.637046 +0.883355 0.637046 +0.880237 0.654334 +0.892931 0.637046 +0.889813 0.654334 +0.902426 0.637046 +0.899308 0.654334 +0.911623 0.637046 +0.908504 0.654334 +0.920304 0.637046 +0.917185 0.654334 +0.928269 0.637046 +0.925150 0.654334 +0.935349 0.637046 +0.932230 0.654334 +0.941419 0.637046 +0.938300 0.654334 +0.940510 0.669718 +0.942591 0.658180 +0.879543 0.658180 +0.877462 0.669718 +0.889119 0.658180 +0.887038 0.669718 +0.898614 0.658180 +0.896533 0.669718 +0.907810 0.658180 +0.905729 0.669718 +0.916491 0.658180 +0.914410 0.669718 +0.924456 0.658180 +0.922375 0.669718 +0.931537 0.658180 +0.929455 0.669718 +0.937607 0.658180 +0.935526 0.669718 +0.037181 0.683015 +0.036803 0.682521 +0.128648 0.710114 +0.150350 0.710099 +0.150350 0.683178 +0.130032 0.683178 +0.108200 0.710129 +0.110559 0.683178 +0.089408 0.710142 +0.092306 0.683178 +0.073138 0.710154 +0.075992 0.683178 +0.059766 0.710164 +0.061992 0.683178 +0.049917 0.710172 +0.050822 0.683178 +0.043837 0.710177 +0.042771 0.683178 +0.041792 0.710179 +0.038112 0.683178 +0.097588 0.490494 +0.118814 0.490490 +0.000499 0.481271 +0.002205 0.490725 +0.002447 0.481271 +0.008690 0.481271 +0.004145 0.490682 +0.019514 0.481271 +0.010379 0.490638 +0.026588 0.481271 +0.021196 0.490596 +0.034666 0.481271 +0.028267 0.490577 +0.043626 0.481271 +0.036341 0.490559 +0.053318 0.481271 +0.045298 0.490542 +0.074212 0.481271 +0.054988 0.490528 +0.095925 0.481271 +0.075878 0.490506 +0.117151 0.481271 +0.041792 0.710179 +0.036803 0.682518 +0.002205 0.490725 +0.000499 0.481271 +0.003433 0.490759 +0.007080 0.490792 +0.002447 0.481271 +0.117151 0.481271 +0.158429 0.710099 +0.095925 0.481271 +0.137206 0.710114 +0.074212 0.481271 +0.115496 0.710129 +0.053318 0.481271 +0.094604 0.710143 +0.043626 0.481271 +0.084913 0.710150 +0.034666 0.481271 +0.075954 0.710156 +0.026588 0.481271 +0.067878 0.710161 +0.019514 0.481271 +0.060805 0.710166 +0.008690 0.481271 +0.039703 0.671641 +0.049982 0.710174 +0.039660 0.675135 +0.038573 0.678297 +0.037288 0.680833 +0.043740 0.710178 +0.869888 0.683178 +0.849651 0.683178 +0.958208 0.710179 +0.963197 0.682521 +0.956164 0.710177 +0.962819 0.683015 +0.961888 0.683178 +0.950084 0.710172 +0.957205 0.683178 +0.940235 0.710164 +0.949172 0.683178 +0.926862 0.710154 +0.937958 0.683178 +0.910593 0.710142 +0.924000 0.683178 +0.891800 0.710129 +0.907625 0.683178 +0.871353 0.710114 +0.889429 0.683178 +0.849651 0.710099 +0.882849 0.481271 +0.881186 0.490490 +0.997795 0.490725 +0.999501 0.481271 +0.995855 0.490682 +0.997553 0.481271 +0.989621 0.490638 +0.991310 0.481271 +0.978804 0.490596 +0.980486 0.481271 +0.971733 0.490576 +0.973412 0.481271 +0.963659 0.490558 +0.965334 0.481271 +0.954702 0.490542 +0.956374 0.481271 +0.945012 0.490528 +0.946682 0.481271 +0.924122 0.490506 +0.925788 0.481271 +0.902412 0.490494 +0.904076 0.481271 +0.962718 0.680843 +0.963198 0.682518 +0.997553 0.481271 +0.999501 0.481271 +0.997795 0.490725 +0.996567 0.490758 +0.991310 0.481271 +0.862795 0.710114 +0.841571 0.710099 +0.882849 0.481271 +0.884505 0.710129 +0.904076 0.481271 +0.905396 0.710143 +0.925788 0.481271 +0.915087 0.710150 +0.946682 0.481271 +0.924046 0.710156 +0.956374 0.481271 +0.932123 0.710161 +0.965334 0.481271 +0.939196 0.710166 +0.973412 0.481271 +0.950019 0.710173 +0.980486 0.481271 +0.992921 0.490792 +0.956261 0.710178 +0.960297 0.671641 +0.960344 0.675153 +0.961434 0.678311 +0.958208 0.710179 +0.117050 0.483194 +0.882950 0.483194 +0.882950 0.481271 +0.117050 0.481271 +0.882950 0.481912 +0.117050 0.481912 +0.882950 0.482703 +0.882950 0.483124 +0.117050 0.482703 +0.117050 0.483124 +0.103896 0.483194 +0.117050 0.483194 +0.090440 0.483194 +0.117050 0.481912 +0.117050 0.481271 +0.077492 0.483194 +0.065933 0.483194 +0.056544 0.483194 +0.049836 0.483194 +0.045967 0.483194 +0.044760 0.483194 +0.045967 0.483194 +0.049836 0.483194 +0.056544 0.483194 +0.065933 0.483194 +0.077492 0.483194 +0.090440 0.483194 +0.103896 0.483194 +0.117050 0.483194 +0.117050 0.483124 +0.117050 0.482703 +0.117050 0.481912 +0.117050 0.481271 +0.098871 0.481271 +0.080277 0.481271 +0.062383 0.481271 +0.046410 0.481271 +0.033434 0.481271 +0.024164 0.481271 +0.018817 0.481271 +0.017150 0.481271 +0.018817 0.481271 +0.024164 0.481271 +0.033434 0.481271 +0.046410 0.481271 +0.062383 0.481271 +0.080277 0.481271 +0.098871 0.481271 +0.117050 0.482703 +0.117050 0.483124 +0.102899 0.483124 +0.088424 0.483124 +0.074495 0.483124 +0.062061 0.483124 +0.051960 0.483124 +0.044744 0.483124 +0.040582 0.483124 +0.039284 0.483124 +0.040582 0.483124 +0.044744 0.483124 +0.051960 0.483124 +0.062061 0.483124 +0.074495 0.483124 +0.088424 0.483124 +0.102899 0.483124 +0.101272 0.482703 +0.099732 0.481912 +0.082018 0.481912 +0.064972 0.481912 +0.049754 0.481912 +0.037393 0.481912 +0.028562 0.481912 +0.023469 0.481912 +0.021880 0.481912 +0.023469 0.481912 +0.028562 0.481912 +0.037393 0.481912 +0.049754 0.481912 +0.064972 0.481912 +0.082018 0.481912 +0.099732 0.481912 +0.101272 0.482703 +0.085133 0.482703 +0.069602 0.482703 +0.055737 0.482703 +0.044475 0.482703 +0.036429 0.482703 +0.031789 0.482703 +0.030341 0.482703 +0.031789 0.482703 +0.036429 0.482703 +0.044475 0.482703 +0.055737 0.482703 +0.069602 0.482703 +0.085133 0.482703 +0.901129 0.481271 +0.882950 0.481271 +0.882950 0.481912 +0.882950 0.482703 +0.882950 0.483124 +0.882950 0.483124 +0.882950 0.483194 +0.882950 0.483194 +0.896104 0.483194 +0.909560 0.483194 +0.922508 0.483194 +0.934067 0.483194 +0.943456 0.483194 +0.950164 0.483194 +0.954033 0.483194 +0.955240 0.483194 +0.954033 0.483194 +0.950164 0.483194 +0.943456 0.483194 +0.934067 0.483194 +0.922508 0.483194 +0.909560 0.483194 +0.896104 0.483194 +0.882950 0.482703 +0.882950 0.481912 +0.882950 0.481271 +0.901129 0.481271 +0.919723 0.481271 +0.937617 0.481271 +0.953590 0.481271 +0.966566 0.481271 +0.975836 0.481271 +0.981183 0.481271 +0.982850 0.481271 +0.981183 0.481271 +0.975836 0.481271 +0.966566 0.481271 +0.953590 0.481271 +0.937617 0.481271 +0.919723 0.481271 +0.900268 0.481912 +0.898728 0.482703 +0.897101 0.483124 +0.911576 0.483124 +0.925505 0.483124 +0.937939 0.483124 +0.948040 0.483124 +0.955256 0.483124 +0.959418 0.483124 +0.960716 0.483124 +0.959418 0.483124 +0.955256 0.483124 +0.948040 0.483124 +0.937939 0.483124 +0.925505 0.483124 +0.911576 0.483124 +0.897101 0.483124 +0.898728 0.482703 +0.900268 0.481912 +0.917982 0.481912 +0.935028 0.481912 +0.950246 0.481912 +0.962607 0.481912 +0.971438 0.481912 +0.976532 0.481912 +0.978120 0.481912 +0.976532 0.481912 +0.971438 0.481912 +0.962607 0.481912 +0.950246 0.481912 +0.935028 0.481912 +0.917982 0.481912 +0.914867 0.482703 +0.930398 0.482703 +0.944263 0.482703 +0.955525 0.482703 +0.963571 0.482703 +0.968211 0.482703 +0.969659 0.482703 +0.968211 0.482703 +0.963571 0.482703 +0.955525 0.482703 +0.944263 0.482703 +0.930398 0.482703 +0.914867 0.482703 +0.882950 0.481912 +0.117050 0.481912 +0.117050 0.481271 +0.882950 0.481271 +0.882950 0.483124 +0.882950 0.483194 +0.117050 0.483194 +0.117050 0.483124 +0.882950 0.482703 +0.117050 0.482703 +0.283550 0.538959 +0.175325 0.538959 +0.175402 0.508328 +0.175325 0.508192 +0.283550 0.508192 +0.175487 0.508807 +0.283550 0.508449 +0.175579 0.509748 +0.283550 0.509272 +0.175673 0.511269 +0.283550 0.510700 +0.175763 0.513460 +0.283550 0.512698 +0.175838 0.516336 +0.283550 0.515157 +0.175866 0.518003 +0.283550 0.517913 +0.175888 0.519789 +0.175901 0.521660 +0.283550 0.520776 +0.175906 0.523575 +0.283550 0.523575 +0.175901 0.525491 +0.175888 0.527362 +0.283550 0.526375 +0.175866 0.529148 +0.175838 0.530815 +0.283550 0.529238 +0.175763 0.533691 +0.283550 0.531993 +0.175673 0.535882 +0.283550 0.534453 +0.175579 0.537403 +0.283550 0.536451 +0.175487 0.538343 +0.283550 0.537879 +0.175402 0.538823 +0.283550 0.538702 +0.175673 0.535882 +0.175579 0.537403 +0.175487 0.538343 +0.175325 0.538959 +0.175325 0.508192 +0.175487 0.508807 +0.175579 0.509748 +0.175673 0.511269 +0.175763 0.513460 +0.175838 0.516336 +0.175888 0.519789 +0.175906 0.523575 +0.175888 0.527362 +0.175838 0.530815 +0.175763 0.533691 +0.283550 0.531267 +0.200300 0.531267 +0.200300 0.528245 +0.200300 0.527181 +0.283550 0.527181 +0.283550 0.528245 +0.200300 0.529335 +0.200300 0.530167 +0.283550 0.529335 +0.283550 0.530167 +0.200300 0.530778 +0.200300 0.531163 +0.283550 0.530778 +0.283550 0.531163 +0.200300 0.516424 +0.200300 0.516012 +0.200300 0.522422 +0.200300 0.522422 +0.200300 0.524729 +0.200300 0.524729 +0.200300 0.522260 +0.200300 0.524891 +0.200300 0.521762 +0.200300 0.525389 +0.200300 0.520964 +0.200300 0.526186 +0.200300 0.519970 +0.200300 0.527181 +0.200300 0.528838 +0.200300 0.530167 +0.200300 0.530997 +0.200300 0.518313 +0.200300 0.516984 +0.200300 0.516154 +0.200300 0.515884 +0.200300 0.531267 +0.200300 0.531139 +0.200300 0.530727 +0.200300 0.530013 +0.200300 0.529014 +0.200300 0.527784 +0.200300 0.526407 +0.200300 0.524975 +0.200300 0.523575 +0.200300 0.522176 +0.200300 0.520744 +0.200300 0.519367 +0.200300 0.518137 +0.200300 0.517138 +0.092075 0.694593 +0.150350 0.696134 +0.150350 0.696254 +0.092075 0.696254 +0.150350 0.694593 +0.092075 0.696134 +0.092075 0.691167 +0.150350 0.691167 +0.092075 0.691077 +0.092075 0.690041 +0.150350 0.691077 +0.150350 0.690041 +0.092075 0.689244 +0.092075 0.688744 +0.150350 0.689244 +0.150350 0.688744 +0.092075 0.688563 +0.092075 0.688684 +0.150350 0.688563 +0.150350 0.688684 +0.092075 0.689059 +0.150350 0.689059 +0.092075 0.689674 +0.092075 0.690565 +0.150350 0.689674 +0.150350 0.690565 +0.092075 0.691720 +0.092075 0.693089 +0.150350 0.691720 +0.150350 0.693089 +0.150350 0.691167 +0.092075 0.691167 +0.092075 0.701342 +0.150350 0.701342 +0.092075 0.702346 +0.092075 0.703449 +0.092075 0.702800 +0.092075 0.701342 +0.092075 0.691167 +0.092075 0.689708 +0.092075 0.688789 +0.092075 0.688579 +0.092075 0.703719 +0.092075 0.703929 +0.092075 0.689059 +0.092075 0.690162 +0.092075 0.691881 +0.092075 0.694016 +0.092075 0.696254 +0.092075 0.698492 +0.092075 0.700627 +0.075425 0.676328 +0.148901 0.676328 +0.150350 0.687868 +0.150350 0.688705 +0.075425 0.688705 +0.075425 0.687868 +0.150350 0.686404 +0.075425 0.686404 +0.150350 0.684514 +0.150350 0.683178 +0.149994 0.683178 +0.075425 0.684514 +0.149763 0.681643 +0.075425 0.682194 +0.149501 0.679968 +0.149211 0.678184 +0.075425 0.679352 +0.150350 0.683984 +0.149025 0.676640 +0.075425 0.676640 +0.075425 0.703177 +0.150350 0.703177 +0.075425 0.704330 +0.150350 0.704330 +0.150350 0.704330 +0.075425 0.704330 +0.150350 0.689843 +0.150350 0.703177 +0.075425 0.703177 +0.075425 0.689843 +0.075425 0.703601 +0.075425 0.703387 +0.075425 0.675647 +0.075425 0.675510 +0.075425 0.675612 +0.075425 0.675765 +0.075425 0.675796 +0.075425 0.675911 +0.075425 0.676044 +0.075425 0.676080 +0.075425 0.676264 +0.075425 0.676640 +0.075425 0.703177 +0.075425 0.676328 +0.075425 0.680698 +0.075425 0.684514 +0.075425 0.687269 +0.075425 0.688705 +0.075425 0.688834 +0.075425 0.688950 +0.075425 0.689098 +0.075425 0.689270 +0.075425 0.689458 +0.075425 0.689843 +0.075425 0.703177 +0.075425 0.703387 +0.075425 0.703601 +0.075425 0.703808 +0.075425 0.703992 +0.075425 0.704142 +0.075425 0.704249 +0.075425 0.704311 +0.075425 0.704330 +0.075425 0.704330 +0.075425 0.704311 +0.075425 0.704249 +0.075425 0.704142 +0.075425 0.703992 +0.075425 0.703808 +0.824099 0.521660 +0.824598 0.538823 +0.824675 0.538959 +0.716450 0.538959 +0.824513 0.538343 +0.716450 0.538702 +0.824421 0.537403 +0.716450 0.537879 +0.824327 0.535882 +0.716450 0.536451 +0.824237 0.533691 +0.716450 0.534453 +0.824163 0.530815 +0.716450 0.531993 +0.824134 0.529148 +0.716450 0.529238 +0.824112 0.527362 +0.824099 0.525491 +0.716450 0.526375 +0.824094 0.523575 +0.716450 0.508192 +0.824675 0.508192 +0.716450 0.508449 +0.824598 0.508328 +0.716450 0.509272 +0.824513 0.508807 +0.716450 0.510700 +0.824421 0.509748 +0.716450 0.512698 +0.824327 0.511269 +0.716450 0.515157 +0.824237 0.513460 +0.716450 0.517913 +0.824163 0.516336 +0.716450 0.520776 +0.824134 0.518003 +0.824112 0.519789 +0.716450 0.523575 +0.824327 0.511269 +0.824421 0.509748 +0.824513 0.508807 +0.824675 0.508192 +0.824675 0.538959 +0.824513 0.538343 +0.824421 0.537403 +0.824327 0.535882 +0.824237 0.533691 +0.824163 0.530815 +0.824112 0.527362 +0.824094 0.523575 +0.824112 0.519789 +0.824163 0.516336 +0.824237 0.513460 +0.716450 0.515988 +0.716450 0.515884 +0.799700 0.518906 +0.799700 0.519970 +0.716450 0.519970 +0.716450 0.518906 +0.799700 0.517815 +0.799700 0.516984 +0.716450 0.517815 +0.716450 0.516984 +0.799700 0.516373 +0.799700 0.515988 +0.716450 0.516373 +0.799700 0.515884 +0.799700 0.530727 +0.799700 0.531139 +0.799700 0.524729 +0.799700 0.522422 +0.799700 0.524729 +0.799700 0.522422 +0.799700 0.524891 +0.799700 0.522260 +0.799700 0.525389 +0.799700 0.521762 +0.799700 0.526186 +0.799700 0.520964 +0.799700 0.527181 +0.799700 0.519970 +0.799700 0.518312 +0.799700 0.516984 +0.799700 0.516154 +0.799700 0.528838 +0.799700 0.530167 +0.799700 0.530997 +0.799700 0.531267 +0.799700 0.515884 +0.799700 0.516012 +0.799700 0.516424 +0.799700 0.517138 +0.799700 0.518137 +0.799700 0.519366 +0.799700 0.520744 +0.799700 0.522176 +0.799700 0.523575 +0.799700 0.524975 +0.799700 0.526407 +0.799700 0.527784 +0.799700 0.529014 +0.799700 0.530013 +0.849651 0.690815 +0.849651 0.691166 +0.907926 0.691166 +0.849651 0.690815 +0.907926 0.690815 +0.849651 0.689816 +0.849651 0.689102 +0.907926 0.689816 +0.907926 0.689102 +0.849651 0.688691 +0.849651 0.688562 +0.907926 0.688691 +0.907926 0.688562 +0.849651 0.688691 +0.849651 0.689102 +0.907926 0.688691 +0.907926 0.689102 +0.849651 0.689816 +0.907926 0.701342 +0.849651 0.701342 +0.907926 0.701693 +0.907926 0.702692 +0.849651 0.701693 +0.907926 0.703406 +0.849651 0.702692 +0.849651 0.703406 +0.907926 0.703817 +0.849651 0.703817 +0.907926 0.703946 +0.907926 0.703817 +0.849651 0.703946 +0.849651 0.703817 +0.907926 0.703406 +0.849651 0.703406 +0.907926 0.702692 +0.907926 0.701693 +0.849651 0.702692 +0.907926 0.700463 +0.849651 0.701693 +0.849651 0.700463 +0.907926 0.699085 +0.907926 0.697654 +0.849651 0.699085 +0.907926 0.696254 +0.849651 0.697654 +0.907926 0.694854 +0.849651 0.696254 +0.849651 0.694854 +0.907926 0.693423 +0.849651 0.693423 +0.907926 0.692045 +0.849651 0.692045 +0.907926 0.690815 +0.907926 0.689816 +0.907926 0.701342 +0.907926 0.691166 +0.849651 0.691166 +0.849651 0.701342 +0.907926 0.690162 +0.907926 0.689059 +0.907926 0.689708 +0.907926 0.691166 +0.907926 0.701342 +0.907926 0.702800 +0.907926 0.703719 +0.907926 0.703929 +0.907926 0.688789 +0.907926 0.688579 +0.907926 0.703449 +0.907926 0.702346 +0.907926 0.700627 +0.907926 0.698492 +0.907926 0.696254 +0.907926 0.694016 +0.907926 0.691881 +0.849651 0.684548 +0.849651 0.683178 +0.924576 0.688753 +0.924576 0.688840 +0.849651 0.688840 +0.924576 0.687885 +0.849651 0.688753 +0.851243 0.675486 +0.924576 0.675486 +0.850890 0.677575 +0.924576 0.676136 +0.850561 0.679585 +0.924576 0.679398 +0.850264 0.681467 +0.850006 0.683178 +0.924576 0.682235 +0.849651 0.687885 +0.924576 0.686430 +0.924576 0.684548 +0.849651 0.686430 +0.924576 0.675486 +0.851184 0.675486 +0.849651 0.683984 +0.849651 0.704330 +0.924576 0.704330 +0.924576 0.675486 +0.924576 0.675486 +0.851243 0.675486 +0.851184 0.675486 +0.924576 0.704330 +0.849651 0.704330 +0.849651 0.688840 +0.924576 0.688840 +0.924576 0.704330 +0.924576 0.704330 +0.849651 0.704330 +0.849651 0.704330 +0.924576 0.687494 +0.924576 0.675486 +0.924576 0.704330 +0.924576 0.704330 +0.924576 0.688840 +0.924576 0.680321 +0.924576 0.675486 +0.924576 0.684548 +0.816060 0.501529 +0.816060 0.545622 +0.816350 0.545689 +0.816350 0.501462 +0.807735 0.499606 +0.808026 0.499539 +0.191974 0.499539 +0.192265 0.499606 +0.183940 0.501529 +0.183650 0.501462 +0.183650 0.545689 +0.183940 0.545622 +0.808026 0.547612 +0.807735 0.547545 +0.192265 0.547545 +0.191974 0.547612 +0.799700 0.522422 +0.799700 0.522422 +0.716697 0.522422 +0.716570 0.522422 +0.799700 0.524729 +0.716570 0.524729 +0.716697 0.524729 +0.799700 0.524729 +0.716697 0.522422 +0.799700 0.522422 +0.799700 0.524729 +0.716697 0.524729 +0.200300 0.524729 +0.200300 0.522422 +0.283303 0.522422 +0.283303 0.524729 +0.200300 0.524729 +0.200300 0.524729 +0.283303 0.524729 +0.283430 0.524729 +0.200300 0.522422 +0.283430 0.522422 +0.283303 0.522422 +0.200300 0.522422 +0.875933 0.490490 +0.875933 0.488963 +0.874769 0.488963 +0.874769 0.490758 +0.141880 0.490792 +0.858120 0.490792 +0.858120 0.488963 +0.141880 0.488963 +0.125231 0.488963 +0.124067 0.488963 +0.124067 0.490490 +0.125231 0.490758 +0.873559 0.488963 +0.874468 0.488963 +0.874769 0.488963 +0.875933 0.488963 +0.124067 0.488963 +0.125231 0.488963 +0.125532 0.488963 +0.126441 0.488963 +0.127995 0.488963 +0.130158 0.488963 +0.132812 0.488963 +0.135781 0.488963 +0.138864 0.488963 +0.141880 0.488963 +0.858120 0.488963 +0.861135 0.488963 +0.864219 0.488963 +0.867188 0.488963 +0.869842 0.488963 +0.872005 0.488963 +0.487513 0.543766 +0.512488 0.543766 +0.512488 0.540401 +0.487513 0.540401 +0.654013 0.543766 +0.678988 0.543766 +0.678988 0.540401 +0.654013 0.540401 +0.445888 0.540401 +0.445888 0.543766 +0.470863 0.543766 +0.470863 0.540401 +0.612388 0.540401 +0.612388 0.543766 +0.637363 0.543766 +0.637363 0.540401 +0.404262 0.543766 +0.429237 0.543766 +0.429237 0.540401 +0.404262 0.540401 +0.570763 0.540401 +0.570763 0.543766 +0.595738 0.543766 +0.595738 0.540401 +0.362637 0.540401 +0.362637 0.543766 +0.387612 0.543766 +0.387612 0.540401 +0.529138 0.543766 +0.554113 0.543766 +0.554113 0.540401 +0.529138 0.540401 +0.321012 0.543766 +0.345987 0.543766 +0.345987 0.540401 +0.321012 0.540401 +0.695638 0.543766 +0.716450 0.543766 +0.716450 0.540401 +0.695638 0.540401 +0.283550 0.543766 +0.304362 0.543766 +0.304362 0.540401 +0.283550 0.540401 +0.512488 0.506750 +0.512488 0.503385 +0.487513 0.503385 +0.487513 0.506750 +0.678988 0.503385 +0.654013 0.503385 +0.654013 0.506750 +0.678988 0.506750 +0.470863 0.506750 +0.470863 0.503385 +0.445887 0.503385 +0.445887 0.506750 +0.637363 0.503385 +0.612388 0.503385 +0.612388 0.506750 +0.637363 0.506750 +0.429237 0.503385 +0.404262 0.503385 +0.404262 0.506750 +0.429237 0.506750 +0.595738 0.506750 +0.595738 0.503385 +0.570763 0.503385 +0.570763 0.506750 +0.387612 0.503385 +0.362637 0.503385 +0.362637 0.506750 +0.387612 0.506750 +0.554113 0.506750 +0.554113 0.503385 +0.529138 0.503385 +0.529138 0.506750 +0.345987 0.503385 +0.321012 0.503385 +0.321012 0.506750 +0.345987 0.506750 +0.716450 0.503385 +0.695638 0.503385 +0.695638 0.506750 +0.716450 0.506750 +0.304362 0.506750 +0.304362 0.503385 +0.283550 0.503385 +0.283550 0.506750 +0.196662 0.544049 +0.197743 0.502794 +0.199074 0.502544 +0.802257 0.502794 +0.803338 0.503102 +0.802257 0.544357 +0.800926 0.544606 +0.197743 0.544357 +0.445568 0.543840 +0.445568 0.539920 +0.429557 0.539920 +0.512807 0.507231 +0.528818 0.507231 +0.512807 0.503311 +0.429557 0.507231 +0.445568 0.507231 +0.429557 0.503311 +0.304682 0.503311 +0.304682 0.507231 +0.320693 0.507231 +0.283230 0.543840 +0.267219 0.530424 +0.758395 0.530424 +0.774406 0.543840 +0.241605 0.543840 +0.225594 0.530424 +0.320693 0.539920 +0.304682 0.539920 +0.320693 0.543840 +0.362318 0.539920 +0.346307 0.539920 +0.362318 0.543840 +0.403943 0.539920 +0.387932 0.539920 +0.403943 0.543840 +0.487193 0.539920 +0.471182 0.539920 +0.487193 0.543840 +0.528818 0.539920 +0.512807 0.539920 +0.528818 0.543840 +0.570443 0.539920 +0.554432 0.539920 +0.570443 0.543840 +0.612068 0.539920 +0.596057 0.539920 +0.612068 0.543840 +0.653693 0.539920 +0.637682 0.539920 +0.653693 0.543840 +0.695318 0.539920 +0.679307 0.539920 +0.695318 0.543840 +0.679307 0.507231 +0.695318 0.507231 +0.679307 0.503311 +0.637682 0.507231 +0.653693 0.507231 +0.637682 0.503311 +0.596057 0.507231 +0.612068 0.507231 +0.596057 0.503311 +0.554432 0.507231 +0.570443 0.507231 +0.554432 0.503311 +0.471182 0.507231 +0.487193 0.507231 +0.471182 0.503311 +0.387932 0.507231 +0.403943 0.507231 +0.387932 0.503311 +0.346307 0.507231 +0.362318 0.507231 +0.346307 0.503311 +0.225594 0.503311 +0.241605 0.516727 +0.758395 0.503311 +0.774406 0.516727 +0.195889 0.543705 +0.199980 0.543840 +0.195444 0.543347 +0.195305 0.542997 +0.195305 0.504154 +0.196662 0.503102 +0.199980 0.516727 +0.195889 0.503446 +0.195444 0.503804 +0.225594 0.516727 +0.199980 0.530424 +0.241605 0.530424 +0.267219 0.516727 +0.267219 0.503311 +0.200565 0.502366 +0.199980 0.503311 +0.202115 0.502263 +0.203630 0.502231 +0.796370 0.502231 +0.241605 0.503311 +0.283230 0.503311 +0.320693 0.503311 +0.362318 0.503311 +0.403943 0.503311 +0.445568 0.503311 +0.487193 0.503311 +0.528818 0.503311 +0.570443 0.503311 +0.612068 0.503311 +0.653693 0.503311 +0.695318 0.503311 +0.800926 0.502544 +0.774406 0.503311 +0.799435 0.502366 +0.797885 0.502263 +0.804111 0.503446 +0.800020 0.503311 +0.804556 0.503804 +0.804695 0.504154 +0.804695 0.542997 +0.803338 0.544049 +0.800020 0.530424 +0.804111 0.543705 +0.804556 0.543347 +0.800020 0.516727 +0.774406 0.530424 +0.758395 0.516727 +0.732781 0.530424 +0.799435 0.544785 +0.800020 0.543840 +0.797885 0.544888 +0.796370 0.544920 +0.203630 0.544920 +0.758395 0.543840 +0.199074 0.544606 +0.225594 0.543840 +0.200565 0.544785 +0.202115 0.544888 +0.267219 0.543840 +0.732781 0.503311 +0.716770 0.503311 +0.732781 0.516727 +0.732781 0.543840 +0.716770 0.543840 +0.679307 0.543840 +0.637682 0.543840 +0.596057 0.543840 +0.554432 0.543840 +0.512807 0.543840 +0.471182 0.543840 +0.429557 0.543840 +0.387932 0.543840 +0.346307 0.543840 +0.304682 0.543840 +0.804695 0.542997 +0.804695 0.504154 +0.804695 0.504154 +0.804695 0.542997 +0.203630 0.544920 +0.796370 0.544920 +0.796370 0.544920 +0.203630 0.544920 +0.195305 0.542997 +0.195305 0.504154 +0.195305 0.504154 +0.195305 0.542997 +0.203630 0.502231 +0.796370 0.502231 +0.796370 0.502231 +0.203630 0.502231 +0.225275 0.516653 +0.225275 0.503385 +0.200300 0.503385 +0.200300 0.516653 +0.200300 0.516653 +0.199980 0.516727 +0.225594 0.516727 +0.225275 0.516653 +0.225275 0.516653 +0.225594 0.516727 +0.225594 0.503311 +0.225275 0.503385 +0.200300 0.503385 +0.225275 0.503385 +0.225594 0.503311 +0.199980 0.503311 +0.200300 0.516653 +0.200300 0.503385 +0.199980 0.503311 +0.199980 0.516727 +0.733100 0.503385 +0.733100 0.516653 +0.758075 0.516653 +0.758075 0.503385 +0.758395 0.503311 +0.758075 0.503385 +0.758075 0.516653 +0.758395 0.516727 +0.758395 0.516727 +0.758075 0.516653 +0.733100 0.516653 +0.732781 0.516727 +0.733100 0.516653 +0.733100 0.503385 +0.732781 0.503311 +0.732781 0.516727 +0.733100 0.503385 +0.758075 0.503385 +0.758395 0.503311 +0.732781 0.503311 +0.774725 0.503385 +0.774725 0.516653 +0.799700 0.516653 +0.799700 0.503385 +0.800020 0.503311 +0.799700 0.503385 +0.799700 0.516653 +0.800020 0.516727 +0.800020 0.516727 +0.799700 0.516653 +0.774725 0.516653 +0.774406 0.516727 +0.774406 0.516727 +0.774725 0.516653 +0.774725 0.503385 +0.774406 0.503311 +0.774725 0.503385 +0.799700 0.503385 +0.800020 0.503311 +0.774406 0.503311 +0.266900 0.543766 +0.266900 0.530498 +0.241925 0.530498 +0.241925 0.543766 +0.241925 0.543766 +0.241925 0.530498 +0.241605 0.530424 +0.241605 0.543840 +0.241925 0.530498 +0.266900 0.530498 +0.267219 0.530424 +0.241605 0.530424 +0.266900 0.530498 +0.266900 0.543766 +0.267219 0.543840 +0.267219 0.530424 +0.266900 0.543766 +0.241925 0.543766 +0.241605 0.543840 +0.267219 0.543840 +0.200300 0.543766 +0.225275 0.543766 +0.225275 0.530498 +0.200300 0.530498 +0.200300 0.543766 +0.200300 0.530498 +0.199980 0.530424 +0.199980 0.543840 +0.199980 0.530424 +0.200300 0.530498 +0.225275 0.530498 +0.225594 0.530424 +0.225594 0.530424 +0.225275 0.530498 +0.225275 0.543766 +0.225594 0.543840 +0.225275 0.543766 +0.200300 0.543766 +0.199980 0.543840 +0.225594 0.543840 +0.733100 0.543766 +0.758075 0.543766 +0.758075 0.530498 +0.733100 0.530498 +0.733100 0.530498 +0.758075 0.530498 +0.758395 0.530424 +0.732781 0.530424 +0.733100 0.543766 +0.733100 0.530498 +0.732781 0.530424 +0.732781 0.543840 +0.733100 0.543766 +0.732781 0.543840 +0.758395 0.543840 +0.758075 0.543766 +0.758075 0.530498 +0.758075 0.543766 +0.758395 0.543840 +0.758395 0.530424 +0.774725 0.530498 +0.774725 0.543766 +0.799700 0.543766 +0.799700 0.530498 +0.774725 0.530498 +0.799700 0.530498 +0.800020 0.530424 +0.774406 0.530424 +0.774725 0.543766 +0.774725 0.530498 +0.774406 0.530424 +0.774406 0.543840 +0.799700 0.543766 +0.774725 0.543766 +0.774406 0.543840 +0.800020 0.543840 +0.799700 0.530498 +0.799700 0.543766 +0.800020 0.543840 +0.800020 0.530424 +0.266900 0.503385 +0.241925 0.503385 +0.241925 0.516653 +0.266900 0.516653 +0.266900 0.516653 +0.241925 0.516653 +0.241605 0.516727 +0.267219 0.516727 +0.266900 0.516653 +0.267219 0.516727 +0.267219 0.503311 +0.266900 0.503385 +0.241925 0.503385 +0.266900 0.503385 +0.267219 0.503311 +0.241605 0.503311 +0.241925 0.516653 +0.241925 0.503385 +0.241605 0.503311 +0.241605 0.516727 +0.200300 0.524791 +0.200300 0.524729 +0.283550 0.527181 +0.200300 0.527181 +0.283550 0.526543 +0.283550 0.525999 +0.200300 0.526543 +0.283524 0.525463 +0.200300 0.525888 +0.283494 0.525058 +0.200300 0.525389 +0.283462 0.524811 +0.200300 0.525023 +0.283430 0.524729 +0.283430 0.522422 +0.200300 0.522422 +0.200300 0.520608 +0.200300 0.519970 +0.283550 0.519970 +0.283550 0.520608 +0.200300 0.521263 +0.283550 0.521152 +0.200300 0.521762 +0.283524 0.521688 +0.200300 0.522128 +0.283494 0.522092 +0.200300 0.522359 +0.283462 0.522340 +0.799700 0.522359 +0.799700 0.522422 +0.716450 0.519970 +0.799700 0.519970 +0.716450 0.520608 +0.799700 0.520608 +0.716450 0.521152 +0.716476 0.521688 +0.799700 0.521263 +0.716506 0.522092 +0.799700 0.521762 +0.716538 0.522340 +0.799700 0.522128 +0.716570 0.522422 +0.716570 0.524729 +0.799700 0.524729 +0.799700 0.527181 +0.716450 0.527181 +0.799700 0.526543 +0.799700 0.525888 +0.716450 0.526543 +0.716450 0.525999 +0.799700 0.525389 +0.716476 0.525463 +0.799700 0.525023 +0.716506 0.525058 +0.799700 0.524791 +0.716538 0.524811 +0.695638 0.540401 +0.716450 0.540401 +0.283550 0.541843 +0.283550 0.540401 +0.716450 0.541843 +0.679060 0.539920 +0.695565 0.539920 +0.678988 0.540401 +0.637435 0.539920 +0.653940 0.539920 +0.637363 0.540401 +0.595810 0.539920 +0.612315 0.539920 +0.595738 0.540401 +0.554185 0.539920 +0.570690 0.539920 +0.554113 0.540401 +0.512560 0.539920 +0.529065 0.539920 +0.512488 0.540401 +0.470935 0.539920 +0.487440 0.539920 +0.470863 0.540401 +0.429310 0.539920 +0.445815 0.539920 +0.429237 0.540401 +0.387685 0.539920 +0.404190 0.539920 +0.387612 0.540401 +0.346060 0.539920 +0.362565 0.539920 +0.345987 0.540401 +0.304435 0.539920 +0.320940 0.539920 +0.304362 0.540401 +0.321012 0.540401 +0.362637 0.540401 +0.404262 0.540401 +0.445888 0.540401 +0.487513 0.540401 +0.529138 0.540401 +0.570763 0.540401 +0.612388 0.540401 +0.654013 0.540401 +0.716450 0.505308 +0.716450 0.506750 +0.283550 0.505308 +0.304362 0.506750 +0.283550 0.506750 +0.320940 0.507231 +0.304435 0.507231 +0.321012 0.506750 +0.362565 0.507231 +0.346060 0.507231 +0.362637 0.506750 +0.404190 0.507231 +0.387685 0.507231 +0.404262 0.506750 +0.445815 0.507231 +0.429310 0.507231 +0.445887 0.506750 +0.487440 0.507231 +0.470935 0.507231 +0.487513 0.506750 +0.529065 0.507231 +0.512560 0.507231 +0.529138 0.506750 +0.570690 0.507231 +0.554185 0.507231 +0.570763 0.506750 +0.612315 0.507231 +0.595810 0.507231 +0.612388 0.506750 +0.653940 0.507231 +0.637435 0.507231 +0.654013 0.506750 +0.695565 0.507231 +0.679060 0.507231 +0.695638 0.506750 +0.678988 0.506750 +0.637363 0.506750 +0.595738 0.506750 +0.554113 0.506750 +0.512488 0.506750 +0.470863 0.506750 +0.429237 0.506750 +0.387612 0.506750 +0.345987 0.506750 +0.125231 0.488963 +0.125231 0.490758 +0.138864 0.490791 +0.141880 0.490792 +0.141880 0.488963 +0.135781 0.490789 +0.138539 0.488963 +0.132812 0.490786 +0.135334 0.488963 +0.130158 0.490782 +0.132505 0.488963 +0.127995 0.490777 +0.130158 0.488963 +0.128202 0.488963 +0.126441 0.490771 +0.126629 0.488963 +0.125532 0.490765 +0.125598 0.488963 +0.874468 0.490764 +0.874769 0.490758 +0.858120 0.488963 +0.858120 0.490792 +0.861461 0.488963 +0.861135 0.490791 +0.864666 0.488963 +0.864219 0.490789 +0.867495 0.488963 +0.867188 0.490786 +0.869842 0.488963 +0.869842 0.490782 +0.871798 0.488963 +0.873371 0.488963 +0.872005 0.490777 +0.874402 0.488963 +0.873559 0.490771 +0.874769 0.488963 +0.131278 0.669996 +0.131359 0.669638 +0.124473 0.671607 +0.122925 0.671641 +0.123041 0.671641 +0.126059 0.671499 +0.124590 0.671607 +0.127583 0.671311 +0.126176 0.671499 +0.128286 0.671189 +0.127699 0.671311 +0.128933 0.671049 +0.128402 0.671189 +0.129512 0.670894 +0.129049 0.671049 +0.130013 0.670726 +0.129628 0.670894 +0.130761 0.670367 +0.130129 0.670726 +0.131162 0.669996 +0.130877 0.670367 +0.131243 0.669638 +0.059374 0.671641 +0.059491 0.671641 +0.051172 0.669798 +0.051056 0.669798 +0.051367 0.670138 +0.051250 0.670138 +0.051853 0.670483 +0.051737 0.670483 +0.052647 0.670813 +0.052531 0.670813 +0.053727 0.671106 +0.053611 0.671106 +0.055038 0.671343 +0.054922 0.671343 +0.056497 0.671512 +0.056381 0.671512 +0.058010 0.671610 +0.057893 0.671610 +0.868750 0.669718 +0.868758 0.669638 +0.868641 0.669638 +0.868634 0.669718 +0.948750 0.670138 +0.948944 0.669798 +0.941991 0.671610 +0.940510 0.671641 +0.940626 0.671641 +0.943503 0.671512 +0.942107 0.671610 +0.944962 0.671342 +0.943620 0.671512 +0.946273 0.671105 +0.945078 0.671342 +0.947353 0.670813 +0.946389 0.671105 +0.948147 0.670483 +0.947470 0.670813 +0.948634 0.670138 +0.948263 0.670483 +0.948828 0.669798 +0.091112 0.490792 +0.091000 0.490819 +0.099124 0.492321 +0.099318 0.492661 +0.099429 0.492635 +0.098637 0.491976 +0.099235 0.492294 +0.097843 0.491646 +0.098749 0.491949 +0.096763 0.491354 +0.097955 0.491620 +0.096875 0.491327 +0.095452 0.491117 +0.095564 0.491090 +0.093994 0.490947 +0.094105 0.490920 +0.092481 0.490849 +0.092593 0.490822 +0.019126 0.492795 +0.019248 0.492821 +0.026017 0.490852 +0.027565 0.490819 +0.027444 0.490792 +0.024430 0.490960 +0.025895 0.490825 +0.022907 0.491148 +0.024309 0.490933 +0.022204 0.491270 +0.022786 0.491121 +0.021557 0.491410 +0.022083 0.491244 +0.021436 0.491384 +0.020979 0.491565 +0.020857 0.491539 +0.020477 0.491733 +0.020356 0.491706 +0.019729 0.492092 +0.019608 0.492065 +0.019328 0.492463 +0.019207 0.492436 +0.900571 0.492635 +0.900682 0.492661 +0.907519 0.490849 +0.909000 0.490819 +0.908888 0.490792 +0.906006 0.490947 +0.907407 0.490822 +0.904548 0.491117 +0.905895 0.490920 +0.903237 0.491354 +0.904436 0.491090 +0.903125 0.491327 +0.902156 0.491646 +0.902045 0.491620 +0.901363 0.491976 +0.901251 0.491949 +0.900876 0.492321 +0.900765 0.492294 +0.972556 0.490792 +0.972435 0.490819 +0.980621 0.492391 +0.980760 0.492741 +0.980881 0.492715 +0.980175 0.492034 +0.980742 0.492365 +0.979403 0.491689 +0.980296 0.492007 +0.978898 0.491529 +0.979524 0.491662 +0.978321 0.491382 +0.979019 0.491503 +0.978443 0.491355 +0.977682 0.491249 +0.977803 0.491222 +0.976990 0.491132 +0.977112 0.491105 +0.975499 0.490954 +0.975621 0.490927 +0.973950 0.490851 +0.974071 0.490824 +0.191974 0.547612 +0.192265 0.547545 +0.184079 0.545972 +0.183940 0.545622 +0.183650 0.545689 +0.184525 0.546330 +0.183789 0.546039 +0.185297 0.546674 +0.184234 0.546397 +0.185802 0.546834 +0.185007 0.546741 +0.186379 0.546982 +0.185511 0.546901 +0.186088 0.547049 +0.187018 0.547115 +0.186727 0.547182 +0.187710 0.547231 +0.187419 0.547299 +0.189201 0.547410 +0.188910 0.547477 +0.190750 0.547513 +0.190460 0.547580 +0.183650 0.501462 +0.183940 0.501529 +0.190750 0.499638 +0.192265 0.499606 +0.191974 0.499539 +0.189201 0.499741 +0.190460 0.499571 +0.187710 0.499919 +0.188910 0.499674 +0.187018 0.500036 +0.187419 0.499852 +0.186379 0.500169 +0.186727 0.499969 +0.186088 0.500102 +0.185802 0.500317 +0.185511 0.500250 +0.185297 0.500477 +0.185007 0.500409 +0.184525 0.500821 +0.184234 0.500754 +0.184079 0.501179 +0.183789 0.501112 +0.808026 0.499539 +0.807735 0.499606 +0.815921 0.501179 +0.816060 0.501529 +0.816350 0.501462 +0.815475 0.500821 +0.816211 0.501112 +0.814703 0.500477 +0.815766 0.500754 +0.814198 0.500317 +0.814993 0.500409 +0.813622 0.500169 +0.814489 0.500250 +0.813912 0.500102 +0.812982 0.500036 +0.813273 0.499969 +0.812290 0.499919 +0.812581 0.499852 +0.810799 0.499741 +0.811090 0.499674 +0.809250 0.499638 +0.809541 0.499571 +0.816350 0.545689 +0.816060 0.545622 +0.809250 0.547513 +0.807735 0.547545 +0.808026 0.547612 +0.810799 0.547410 +0.809541 0.547580 +0.812290 0.547231 +0.811090 0.547477 +0.812982 0.547115 +0.812581 0.547299 +0.813622 0.546982 +0.813273 0.547182 +0.813912 0.547049 +0.814198 0.546834 +0.814489 0.546901 +0.814703 0.546674 +0.814994 0.546741 +0.815475 0.546330 +0.815766 0.546397 +0.815921 0.545972 +0.816211 0.546039 +0.195305 0.542997 +0.195305 0.542997 +0.201924 0.544879 +0.203630 0.544920 +0.203630 0.544920 +0.201924 0.544879 +0.200323 0.544762 +0.200323 0.544762 +0.198913 0.544581 +0.197743 0.544357 +0.198913 0.544581 +0.197743 0.544357 +0.196770 0.544087 +0.196770 0.544087 +0.195990 0.543761 +0.195990 0.543761 +0.195481 0.543391 +0.195481 0.543391 +0.203630 0.502231 +0.203630 0.502231 +0.195481 0.503760 +0.195305 0.504154 +0.195305 0.504154 +0.195481 0.503760 +0.195990 0.503390 +0.195990 0.503390 +0.196770 0.503064 +0.197743 0.502794 +0.196770 0.503064 +0.197743 0.502794 +0.198913 0.502569 +0.198913 0.502569 +0.200323 0.502389 +0.200323 0.502389 +0.201924 0.502272 +0.201924 0.502272 +0.799677 0.544762 +0.796370 0.544920 +0.796370 0.544920 +0.798076 0.544879 +0.799677 0.544762 +0.798076 0.544879 +0.804695 0.542997 +0.804695 0.542997 +0.804519 0.543391 +0.804011 0.543761 +0.804519 0.543391 +0.803230 0.544087 +0.804011 0.543761 +0.803230 0.544087 +0.802257 0.544357 +0.801088 0.544581 +0.802257 0.544357 +0.801088 0.544581 +0.796370 0.502231 +0.796370 0.502231 +0.804695 0.504154 +0.804695 0.504154 +0.804519 0.503760 +0.804519 0.503760 +0.804011 0.503390 +0.803230 0.503064 +0.804011 0.503390 +0.803230 0.503064 +0.802257 0.502794 +0.801088 0.502569 +0.802257 0.502794 +0.799677 0.502389 +0.801088 0.502569 +0.799677 0.502389 +0.798076 0.502272 +0.798076 0.502272 +0.849651 0.703935 +0.849651 0.702407 +0.150350 0.702407 +0.849651 0.703195 +0.150350 0.706253 +0.849651 0.706253 +0.150350 0.706172 +0.150350 0.705937 +0.849651 0.706172 +0.849651 0.705937 +0.150350 0.705576 +0.150350 0.705127 +0.849651 0.705576 +0.849651 0.705127 +0.150350 0.704587 +0.150350 0.703935 +0.849651 0.704587 +0.150350 0.703195 +0.150350 0.710099 +0.849651 0.710099 +0.849651 0.706253 +0.150350 0.706253 +0.849651 0.706335 +0.849651 0.706570 +0.150350 0.706335 +0.150350 0.706570 +0.849651 0.706930 +0.849651 0.707380 +0.150350 0.706930 +0.150350 0.707380 +0.849651 0.707920 +0.150350 0.707920 +0.849651 0.708572 +0.849651 0.709311 +0.150350 0.708572 +0.150350 0.709311 +0.130284 0.712022 +0.150350 0.711697 +0.150350 0.711874 +0.150350 0.711984 +0.150350 0.712022 +0.150350 0.711459 +0.150350 0.711169 +0.150350 0.710837 +0.150350 0.710476 +0.150350 0.710099 +0.128648 0.710114 +0.108200 0.710129 +0.089408 0.710142 +0.073138 0.710154 +0.059766 0.710164 +0.049917 0.710172 +0.043837 0.710177 +0.041792 0.710179 +0.041987 0.710520 +0.042473 0.710865 +0.043267 0.711194 +0.044347 0.711487 +0.045658 0.711724 +0.047117 0.711893 +0.048629 0.711991 +0.050110 0.712022 +0.051996 0.712022 +0.057603 0.712022 +0.066689 0.712022 +0.079027 0.712022 +0.094043 0.712022 +0.111397 0.712022 +0.131331 0.711990 +0.130584 0.711711 +0.130257 0.711464 +0.130951 0.711888 +0.129990 0.711159 +0.129799 0.710817 +0.129687 0.710462 +0.109065 0.710475 +0.090103 0.710487 +0.073671 0.710497 +0.060158 0.710506 +0.050202 0.710513 +0.044054 0.710518 +0.044530 0.710863 +0.045309 0.711193 +0.046371 0.711486 +0.047659 0.711724 +0.049092 0.711893 +0.050579 0.711991 +0.056378 0.711991 +0.065767 0.711991 +0.078511 0.711991 +0.094007 0.711991 +0.111887 0.711990 +0.054969 0.711893 +0.053611 0.711723 +0.052391 0.711484 +0.051387 0.711190 +0.050651 0.710859 +0.064485 0.711892 +0.077402 0.711891 +0.063249 0.711721 +0.076334 0.711719 +0.062140 0.711481 +0.075375 0.711478 +0.061228 0.711186 +0.074589 0.711181 +0.060562 0.710854 +0.074016 0.710846 +0.093110 0.711890 +0.111236 0.711889 +0.092246 0.711717 +0.110610 0.711714 +0.091471 0.711474 +0.110049 0.711469 +0.090837 0.711174 +0.109591 0.711167 +0.090377 0.710838 +0.109260 0.710828 +0.044347 0.711487 +0.048574 0.711989 +0.050110 0.712022 +0.050110 0.712022 +0.046963 0.711879 +0.048574 0.711989 +0.046963 0.711879 +0.045537 0.711706 +0.044347 0.711487 +0.045537 0.711706 +0.041792 0.710179 +0.041792 0.710179 +0.041999 0.710532 +0.042540 0.710899 +0.041999 0.710532 +0.043350 0.711221 +0.042540 0.710899 +0.043350 0.711221 +0.137206 0.710114 +0.158429 0.710099 +0.081836 0.712022 +0.067767 0.712022 +0.057715 0.712022 +0.099156 0.712022 +0.118557 0.712022 +0.138719 0.712022 +0.158429 0.711990 +0.158429 0.712022 +0.158429 0.711887 +0.051918 0.712022 +0.050110 0.712022 +0.048629 0.711991 +0.047117 0.711893 +0.045658 0.711724 +0.044347 0.711487 +0.043267 0.711194 +0.042473 0.710865 +0.041987 0.710520 +0.041792 0.710179 +0.043740 0.710178 +0.049982 0.710174 +0.060805 0.710166 +0.075954 0.710156 +0.094604 0.710143 +0.115496 0.710129 +0.158429 0.711709 +0.158429 0.711459 +0.158429 0.711151 +0.158429 0.710807 +0.158429 0.710449 +0.067135 0.711991 +0.080782 0.711991 +0.056985 0.711991 +0.050745 0.711991 +0.097423 0.711991 +0.116403 0.711990 +0.137003 0.711990 +0.136703 0.711888 +0.049261 0.711893 +0.047830 0.711724 +0.046544 0.711486 +0.045485 0.711193 +0.044707 0.710864 +0.044230 0.710518 +0.050846 0.710514 +0.061609 0.710508 +0.076081 0.710499 +0.093728 0.710488 +0.113856 0.710476 +0.135704 0.710463 +0.136413 0.711712 +0.136154 0.711464 +0.135944 0.711160 +0.135792 0.710818 +0.115816 0.711890 +0.115250 0.711715 +0.114744 0.711470 +0.114331 0.711168 +0.114032 0.710829 +0.096574 0.711891 +0.095757 0.711717 +0.095024 0.711474 +0.079706 0.711892 +0.078668 0.711720 +0.077737 0.711479 +0.094423 0.711175 +0.093988 0.710839 +0.076973 0.711182 +0.076416 0.710848 +0.065873 0.711892 +0.064656 0.711721 +0.063563 0.711482 +0.055585 0.711893 +0.054236 0.711723 +0.053023 0.711485 +0.062665 0.711187 +0.062008 0.710855 +0.052025 0.711191 +0.051293 0.710860 +0.841571 0.712022 +0.158429 0.712022 +0.158429 0.710493 +0.158429 0.710099 +0.841571 0.710099 +0.841571 0.710493 +0.158429 0.710863 +0.841571 0.710863 +0.158429 0.711189 +0.158429 0.711459 +0.841571 0.711189 +0.158429 0.711684 +0.841571 0.711459 +0.158429 0.711864 +0.841571 0.711684 +0.841571 0.711864 +0.158429 0.711981 +0.841571 0.711981 +0.956261 0.710178 +0.958208 0.710179 +0.942285 0.712022 +0.948082 0.712022 +0.932234 0.712022 +0.918164 0.712022 +0.900845 0.712022 +0.881443 0.712022 +0.951371 0.711991 +0.949890 0.712022 +0.952884 0.711893 +0.954342 0.711724 +0.955653 0.711487 +0.861281 0.712022 +0.841571 0.712022 +0.841571 0.711990 +0.841571 0.711887 +0.841571 0.711709 +0.841571 0.711459 +0.841571 0.711151 +0.841571 0.710807 +0.841571 0.710449 +0.841571 0.710099 +0.862795 0.710114 +0.884505 0.710129 +0.905396 0.710143 +0.924046 0.710156 +0.939196 0.710166 +0.950019 0.710173 +0.956734 0.711194 +0.957527 0.710865 +0.958014 0.710520 +0.943015 0.711991 +0.932865 0.711991 +0.949255 0.711991 +0.919218 0.711991 +0.902577 0.711991 +0.883597 0.711990 +0.862997 0.711990 +0.950739 0.711893 +0.952170 0.711724 +0.953456 0.711486 +0.863298 0.711888 +0.863587 0.711712 +0.863846 0.711464 +0.864057 0.711160 +0.864208 0.710818 +0.864297 0.710463 +0.886145 0.710476 +0.906273 0.710488 +0.923920 0.710499 +0.938391 0.710508 +0.949154 0.710514 +0.955770 0.710518 +0.954516 0.711193 +0.955294 0.710863 +0.944415 0.711893 +0.945765 0.711723 +0.946977 0.711485 +0.947976 0.711191 +0.948707 0.710860 +0.934128 0.711892 +0.935345 0.711721 +0.936437 0.711482 +0.920295 0.711892 +0.921333 0.711720 +0.922263 0.711479 +0.937335 0.711187 +0.937992 0.710855 +0.923027 0.711182 +0.923584 0.710848 +0.903426 0.711891 +0.904244 0.711717 +0.904977 0.711474 +0.884185 0.711890 +0.884750 0.711715 +0.885256 0.711470 +0.905577 0.711175 +0.906013 0.710839 +0.885670 0.711168 +0.885968 0.710829 +0.954464 0.711706 +0.951426 0.711989 +0.949890 0.712022 +0.949890 0.712022 +0.951426 0.711989 +0.953037 0.711879 +0.954464 0.711706 +0.953037 0.711879 +0.958001 0.710532 +0.958208 0.710179 +0.958208 0.710179 +0.958001 0.710532 +0.957460 0.710899 +0.957460 0.710899 +0.956650 0.711221 +0.955653 0.711487 +0.956650 0.711221 +0.955653 0.711487 +0.871353 0.710114 +0.849651 0.710099 +0.958014 0.710520 +0.958208 0.710179 +0.955653 0.711487 +0.954342 0.711724 +0.952884 0.711893 +0.951371 0.711991 +0.949890 0.712022 +0.948005 0.712022 +0.942397 0.712022 +0.933312 0.712022 +0.920974 0.712022 +0.905958 0.712022 +0.888604 0.712022 +0.869716 0.712022 +0.849651 0.712022 +0.849651 0.711984 +0.849651 0.711874 +0.849651 0.711697 +0.849651 0.711460 +0.849651 0.711170 +0.849651 0.710837 +0.849651 0.710477 +0.891800 0.710129 +0.910593 0.710142 +0.926862 0.710154 +0.940235 0.710164 +0.950084 0.710172 +0.956164 0.710177 +0.957527 0.710865 +0.956734 0.711194 +0.955470 0.710863 +0.954691 0.711193 +0.953630 0.711486 +0.952342 0.711723 +0.950908 0.711893 +0.949421 0.711991 +0.943622 0.711991 +0.934233 0.711991 +0.921489 0.711991 +0.905994 0.711991 +0.888114 0.711990 +0.868669 0.711990 +0.869050 0.711888 +0.869416 0.711711 +0.869744 0.711464 +0.870010 0.711159 +0.870202 0.710817 +0.870314 0.710462 +0.890936 0.710475 +0.909897 0.710487 +0.926329 0.710497 +0.939843 0.710506 +0.949798 0.710513 +0.955947 0.710517 +0.949350 0.710859 +0.948614 0.711190 +0.947610 0.711484 +0.946390 0.711722 +0.945031 0.711893 +0.939439 0.710854 +0.925985 0.710846 +0.938772 0.711186 +0.925412 0.711181 +0.937860 0.711481 +0.924626 0.711478 +0.936751 0.711721 +0.923667 0.711719 +0.935515 0.711892 +0.922598 0.711891 +0.909623 0.710838 +0.890740 0.710828 +0.909163 0.711174 +0.890410 0.711167 +0.908529 0.711474 +0.889952 0.711469 +0.907755 0.711717 +0.889391 0.711714 +0.906891 0.711890 +0.888764 0.711889 +0.148786 0.675510 +0.075425 0.675510 +0.075425 0.676640 +0.149025 0.676640 +0.075425 0.676519 +0.075425 0.676291 +0.148991 0.676454 +0.075425 0.676086 +0.148955 0.676264 +0.075425 0.675911 +0.148919 0.676080 +0.148884 0.675911 +0.075425 0.675761 +0.148852 0.675765 +0.075425 0.675633 +0.148825 0.675647 +0.075425 0.675541 +0.148803 0.675562 +0.148877 0.676184 +0.148901 0.676328 +0.075425 0.675566 +0.075425 0.675510 +0.148786 0.675510 +0.148788 0.675550 +0.075425 0.675667 +0.148794 0.675612 +0.075425 0.675796 +0.148803 0.675694 +0.075425 0.675953 +0.148817 0.675796 +0.148834 0.675914 +0.075425 0.676144 +0.148854 0.676044 +0.075425 0.676328 +0.150350 0.688737 +0.075425 0.688737 +0.075425 0.688705 +0.150350 0.688705 +0.150350 0.689701 +0.150350 0.689843 +0.075425 0.689843 +0.150350 0.689474 +0.075425 0.689701 +0.075425 0.689474 +0.150350 0.689270 +0.075425 0.689270 +0.150350 0.689098 +0.150350 0.688950 +0.075425 0.689098 +0.150350 0.688826 +0.075425 0.688950 +0.075425 0.688826 +0.075425 0.703830 +0.075425 0.703413 +0.075425 0.703177 +0.150350 0.703177 +0.150350 0.703413 +0.075425 0.703635 +0.150350 0.704330 +0.075425 0.704330 +0.150350 0.704306 +0.075425 0.704306 +0.150350 0.704235 +0.150350 0.704127 +0.075425 0.704235 +0.150350 0.703992 +0.075425 0.704127 +0.150350 0.703830 +0.075425 0.703992 +0.150350 0.703635 +0.075425 0.704127 +0.075425 0.704306 +0.075425 0.704330 +0.150350 0.704330 +0.075425 0.704235 +0.150350 0.704306 +0.150350 0.703413 +0.150350 0.703177 +0.075425 0.703177 +0.075425 0.703413 +0.150350 0.703635 +0.075425 0.703635 +0.150350 0.703830 +0.075425 0.703830 +0.150350 0.703992 +0.075425 0.703992 +0.150350 0.704127 +0.150350 0.704235 +0.340719 0.036263 +0.331342 0.038600 +0.336084 0.036819 +0.615267 0.102265 +0.624572 0.097396 +0.620009 0.100484 +0.628645 0.093073 +0.631954 0.087752 +0.610631 0.102820 +0.634318 0.081791 +0.635681 0.075597 +0.636107 0.069542 +0.635681 0.063486 +0.634318 0.057292 +0.631954 0.051331 +0.628645 0.046010 +0.624572 0.041688 +0.620009 0.038600 +0.615267 0.036819 +0.610631 0.036263 +0.340719 0.102820 +0.336084 0.102265 +0.331342 0.100484 +0.326779 0.097396 +0.322706 0.093073 +0.319397 0.087752 +0.317033 0.081791 +0.315669 0.075597 +0.315244 0.069542 +0.315669 0.063486 +0.317033 0.057292 +0.319397 0.051331 +0.322706 0.046010 +0.326779 0.041688 + + + + + + + + + + + +

2 0 2 0 1 0 1 2 1 0 3 0 2 4 2 3 5 3 24 6 24 4 7 4 5 8 5 9 9 9 6 10 6 7 11 7 9 12 9 8 13 8 6 14 6 11 15 11 8 16 8 9 17 9 11 18 11 10 19 10 8 20 8 13 21 13 10 22 10 11 23 11 13 24 13 12 25 12 10 26 10 15 27 15 12 28 12 13 29 13 15 30 15 14 31 14 12 32 12 17 33 17 14 34 14 15 35 15 17 36 17 16 37 16 14 38 14 19 39 19 16 40 16 17 41 17 19 42 19 18 43 18 16 44 16 21 45 21 18 46 18 19 47 19 21 48 21 20 49 20 18 50 18 23 51 23 20 52 20 21 53 21 23 54 23 22 55 22 20 56 20 25 57 25 22 58 22 23 59 23 25 60 25 24 61 24 22 62 22 4 63 4 24 64 24 25 65 25 37 66 37 26 67 26 27 68 27 30 69 30 28 70 28 29 71 29 31 72 31 28 73 28 30 74 30 34 75 34 28 76 28 31 77 31 34 78 34 32 79 32 28 80 28 34 81 34 33 82 33 32 83 32 35 84 35 33 85 33 34 86 34 38 87 38 33 88 33 35 89 35 38 90 38 36 91 36 33 92 33 38 93 38 37 94 37 36 95 36 39 96 39 37 97 37 38 98 38 26 99 26 37 100 37 39 101 39 72 102 72 43 103 43 40 104 40 40 105 40 41 106 41 42 107 42 40 108 40 43 109 43 41 110 41 48 111 48 44 112 44 45 113 45 48 114 48 46 115 46 44 116 44 48 117 48 47 118 47 46 119 46 50 120 50 47 121 47 48 122 48 50 123 50 49 124 49 47 125 47 52 126 52 49 127 49 50 128 50 52 129 52 51 130 51 49 131 49 54 132 54 51 133 51 52 134 52 54 135 54 53 136 53 51 137 51 55 138 55 53 139 53 54 140 54 57 141 57 53 142 53 55 143 55 57 144 57 56 145 56 53 146 53 59 147 59 56 148 56 57 149 57 59 150 59 58 151 58 56 152 56 61 153 61 58 154 58 59 155 59 61 156 61 60 157 60 58 158 58 63 159 63 60 160 60 61 161 61 63 162 63 62 163 62 60 164 60 65 165 65 62 166 62 63 167 63 65 168 65 64 169 64 62 170 62 67 171 67 64 172 64 65 173 65 67 174 67 66 175 66 64 176 64 69 177 69 66 178 66 67 179 67 69 180 69 68 181 68 66 182 66 71 183 71 68 184 68 69 185 69 71 186 71 70 187 70 68 188 68 73 189 73 70 190 70 71 191 71 73 192 73 72 193 72 70 194 70 43 195 43 72 196 72 73 197 73 101 198 101 82 199 82 74 200 74 77 201 77 75 202 75 76 203 76 79 204 79 75 205 75 77 206 77 79 207 79 78 208 78 75 209 75 81 210 81 78 211 78 79 212 79 81 213 81 80 214 80 78 215 78 83 216 83 80 217 80 81 218 81 83 219 83 82 220 82 80 221 80 74 222 74 82 223 82 83 224 83 86 225 86 84 226 84 85 227 85 88 228 88 84 229 84 86 230 86 88 231 88 87 232 87 84 233 84 90 234 90 87 235 87 88 236 88 90 237 90 89 238 89 87 239 87 92 240 92 89 241 89 90 242 90 92 243 92 91 244 91 89 245 89 93 246 93 91 247 91 92 248 92 96 249 96 91 250 91 93 251 93 96 252 96 94 253 94 91 254 91 96 255 96 95 256 95 94 257 94 97 258 97 95 259 95 96 260 96 99 261 99 95 262 95 97 263 97 99 264 99 98 265 98 95 266 95 102 267 102 98 268 98 99 269 99 102 270 102 100 271 100 98 272 98 102 273 102 101 274 101 100 275 100 103 276 103 101 277 101 102 278 102 82 279 82 101 280 101 103 281 103 115 282 115 104 283 104 105 284 105 109 285 109 106 286 106 107 287 107 109 288 109 108 289 108 106 290 106 111 291 111 108 292 108 109 293 109 111 294 111 110 295 110 108 296 108 113 297 113 110 298 110 111 299 111 113 300 113 112 301 112 110 302 110 116 303 116 112 304 112 113 305 113 116 306 116 114 307 114 112 308 112 116 309 116 115 310 115 114 311 114 117 312 117 115 313 115 116 314 116 104 315 104 115 316 115 117 317 117 150 318 150 131 319 131 118 320 118 123 321 123 119 322 119 120 323 120 123 324 123 121 325 121 119 326 119 123 327 123 122 328 122 121 329 121 125 330 125 122 331 122 123 332 123 125 333 125 124 334 124 122 335 122 126 336 126 124 337 124 125 338 125 128 339 128 124 340 124 126 341 126 128 342 128 127 343 127 124 344 124 130 345 130 127 346 127 128 347 128 130 348 130 129 349 129 127 350 127 118 351 118 129 352 129 130 353 130 118 354 118 131 355 131 129 356 129 136 357 136 132 358 132 133 359 133 136 360 136 134 361 134 132 362 132 136 363 136 135 364 135 134 365 134 137 366 137 135 367 135 136 368 136 140 369 140 135 370 135 137 371 137 140 372 140 138 373 138 135 374 135 140 375 140 139 376 139 138 377 138 141 378 141 139 379 139 140 380 140 143 381 143 139 382 139 141 383 141 143 384 143 142 385 142 139 386 139 146 387 146 142 388 142 143 389 143 146 390 146 144 391 144 142 392 142 146 393 146 145 394 145 144 395 144 148 396 148 145 397 145 146 398 146 148 399 148 147 400 147 145 401 145 149 402 149 147 403 147 148 404 148 151 405 151 147 406 147 149 407 149 151 408 151 150 409 150 147 410 147 131 411 131 150 412 150 151 413 151 154 414 154 152 415 152 153 416 153 152 417 152 154 418 154 155 419 155 158 420 158 156 421 156 157 422 157 156 423 156 158 424 158 159 425 159 162 426 162 160 427 160 161 428 161 160 429 160 162 430 162 163 431 163 166 432 166 164 433 164 165 434 165 164 435 164 166 436 166 167 437 167 170 438 170 168 439 168 169 440 169 168 441 168 170 442 170 171 443 171 174 444 174 172 445 172 173 446 173 172 447 172 174 448 174 175 449 175 178 450 178 176 451 176 177 452 177 176 453 176 178 454 178 179 455 179 182 456 182 180 457 180 181 458 181 180 459 180 182 460 182 183 461 183 186 462 186 184 463 184 185 464 185 184 465 184 186 466 186 187 467 187 190 468 190 188 469 188 189 470 189 188 471 188 190 472 190 191 473 191 194 474 194 192 475 192 193 476 193 192 477 192 194 478 194 195 479 195 198 480 198 196 481 196 197 482 197 196 483 196 198 484 198 199 485 199 202 486 202 200 487 200 201 488 201 200 489 200 202 490 202 203 491 203 206 492 206 204 493 204 205 494 205 204 495 204 206 496 206 207 497 207 210 498 210 208 499 208 209 500 209 208 501 208 210 502 210 211 503 211 214 504 214 212 505 212 213 506 213 212 507 212 214 508 214 215 509 215 218 510 218 216 511 216 217 512 217 216 513 216 218 514 218 219 515 219 222 516 222 220 517 220 221 518 221 220 519 220 222 520 222 223 521 223 270 522 270 260 523 260 224 524 224 236 525 236 225 526 225 226 527 226 229 528 229 227 529 227 228 530 228 232 531 232 227 532 227 229 533 229 236 534 236 230 535 230 225 536 225 236 537 236 231 538 231 230 539 230 235 540 235 227 541 227 232 542 232 227 543 227 233 544 233 234 545 234 235 546 235 233 547 233 227 548 227 245 549 245 233 550 233 235 551 235 240 552 240 236 553 236 237 554 237 240 555 240 231 556 231 236 557 236 240 558 240 238 559 238 231 560 231 240 561 240 239 562 239 238 563 238 241 564 241 239 565 239 240 566 240 243 567 243 239 568 239 241 569 241 243 570 243 242 571 242 239 572 239 262 573 262 242 574 242 243 575 243 262 576 262 244 577 244 242 578 242 248 579 248 233 580 233 245 581 245 248 582 248 246 583 246 233 584 233 248 585 248 247 586 247 246 587 246 250 588 250 247 589 247 248 590 248 250 591 250 249 592 249 247 593 247 252 594 252 249 595 249 250 596 250 252 597 252 251 598 251 249 599 249 253 600 253 251 601 251 252 602 252 255 603 255 251 604 251 253 605 253 255 606 255 254 607 254 251 608 251 257 609 257 254 610 254 255 611 255 257 612 257 256 613 256 254 614 254 259 615 259 256 616 256 257 617 257 259 618 259 258 619 258 256 620 256 261 621 261 258 622 258 259 623 259 261 624 261 260 625 260 258 626 258 224 627 224 260 628 260 261 629 261 265 630 265 244 631 244 262 632 262 265 633 265 263 634 263 244 635 244 265 636 265 264 637 264 263 638 263 267 639 267 264 640 264 265 641 265 267 642 267 266 643 266 264 644 264 269 645 269 266 646 266 267 647 267 269 648 269 268 649 268 266 650 266 271 651 271 268 652 268 269 653 269 271 654 271 270 655 270 268 656 268 260 657 260 270 658 270 271 659 271 318 660 318 308 661 308 272 662 272 278 663 278 273 664 273 274 665 274 284 666 284 275 667 275 276 668 276 284 669 284 277 670 277 275 671 275 279 672 279 273 673 273 278 674 278 283 675 283 273 676 273 279 677 279 284 678 284 280 679 280 277 680 277 273 681 273 281 682 281 282 683 282 283 684 283 281 685 281 273 686 273 293 687 293 281 688 281 283 689 283 288 690 288 284 691 284 285 692 285 288 693 288 280 694 280 284 695 284 288 696 288 286 697 286 280 698 280 288 699 288 287 700 287 286 701 286 289 702 289 287 703 287 288 704 288 291 705 291 287 706 287 289 707 289 291 708 291 290 709 290 287 710 287 310 711 310 290 712 290 291 713 291 310 714 310 292 715 292 290 716 290 296 717 296 281 718 281 293 719 293 296 720 296 294 721 294 281 722 281 296 723 296 295 724 295 294 725 294 298 726 298 295 727 295 296 728 296 298 729 298 297 730 297 295 731 295 300 732 300 297 733 297 298 734 298 300 735 300 299 736 299 297 737 297 301 738 301 299 739 299 300 740 300 303 741 303 299 742 299 301 743 301 303 744 303 302 745 302 299 746 299 305 747 305 302 748 302 303 749 303 305 750 305 304 751 304 302 752 302 307 753 307 304 754 304 305 755 305 307 756 307 306 757 306 304 758 304 309 759 309 306 760 306 307 761 307 309 762 309 308 763 308 306 764 306 272 765 272 308 766 308 309 767 309 313 768 313 292 769 292 310 770 310 313 771 313 311 772 311 292 773 292 313 774 313 312 775 312 311 776 311 315 777 315 312 778 312 313 779 313 315 780 315 314 781 314 312 782 312 317 783 317 314 784 314 315 785 315 317 786 317 316 787 316 314 788 314 319 789 319 316 790 316 317 791 317 319 792 319 318 793 318 316 794 316 308 795 308 318 796 318 319 797 319 335 798 335 320 799 320 321 800 321 334 801 334 322 802 322 323 803 323 332 804 332 324 805 324 325 806 325 332 807 332 326 808 326 324 809 324 332 810 332 327 811 327 326 812 326 332 813 332 328 814 328 327 815 327 332 816 332 329 817 329 328 818 328 332 819 332 330 820 330 329 821 329 332 822 332 331 823 331 330 824 330 322 825 322 331 826 331 332 827 332 322 828 322 333 829 333 331 830 331 334 831 334 333 832 333 322 833 322 336 834 336 333 835 333 334 836 334 336 837 336 335 838 335 333 839 333 337 840 337 335 841 335 336 842 336 320 843 320 335 844 335 337 845 337 340 846 340 338 847 338 339 848 339 338 849 338 340 850 340 341 851 341 357 852 357 342 853 342 343 854 343 356 855 356 344 856 344 345 857 345 354 858 354 346 859 346 347 860 347 354 861 354 348 862 348 346 863 346 354 864 354 349 865 349 348 866 348 354 867 354 350 868 350 349 869 349 354 870 354 351 871 351 350 872 350 354 873 354 352 874 352 351 875 351 354 876 354 353 877 353 352 878 352 344 879 344 353 880 353 354 881 354 344 882 344 355 883 355 353 884 353 356 885 356 355 886 355 344 887 344 358 888 358 355 889 355 356 890 356 358 891 358 357 892 357 355 893 355 359 894 359 357 895 357 358 896 358 342 897 342 357 898 357 359 899 359 362 900 362 360 901 360 361 902 361 360 903 360 362 904 362 363 905 363 366 906 366 364 907 364 365 908 365 368 909 368 366 910 366 367 911 367 364 912 364 366 913 366 368 914 368 371 915 371 369 916 369 370 917 370 369 918 369 371 919 371 372 920 372 377 921 377 373 922 373 374 923 374 373 924 373 375 925 375 376 926 376 373 927 373 377 928 377 375 929 375 380 930 380 378 931 378 379 932 379 382 933 382 380 934 380 381 935 381 378 936 378 380 937 380 382 938 382 385 939 385 383 940 383 384 941 384 383 942 383 385 943 385 386 944 386 391 945 391 387 946 387 388 947 388 387 948 387 389 949 389 390 950 390 387 951 387 391 952 391 389 953 389 394 954 394 392 955 392 393 956 393 396 957 396 394 958 394 395 959 395 392 960 392 394 961 394 396 962 396 399 963 399 397 964 397 398 965 398 397 966 397 399 967 399 400 968 400 405 969 405 401 970 401 402 971 402 401 972 401 403 973 403 404 974 404 401 975 401 405 976 405 403 977 403 408 978 408 406 979 406 407 980 407 410 981 410 408 982 408 409 983 409 406 984 406 408 985 408 410 986 410 413 987 413 411 988 411 412 989 412 411 990 411 413 991 413 414 992 414 419 993 419 415 994 415 416 995 416 415 996 415 417 997 417 418 998 418 415 999 415 419 1000 419 417 1001 417 422 1002 422 420 1003 420 421 1004 421 424 1005 424 422 1006 422 423 1007 423 420 1008 420 422 1009 422 424 1010 424 427 1011 427 425 1012 425 426 1013 426 425 1014 425 427 1015 427 428 1016 428 433 1017 433 429 1018 429 430 1019 430 429 1020 429 431 1021 431 432 1022 432 429 1023 429 433 1024 433 431 1025 431 436 1026 436 434 1027 434 435 1028 435 438 1029 438 436 1030 436 437 1031 437 434 1032 434 436 1033 436 438 1034 438 441 1035 441 439 1036 439 440 1037 440 439 1038 439 441 1039 441 442 1040 442 447 1041 447 443 1042 443 444 1043 444 443 1044 443 445 1045 445 446 1046 446 443 1047 443 447 1048 447 445 1049 445 450 1050 450 448 1051 448 449 1052 449 452 1053 452 450 1054 450 451 1055 451 448 1056 448 450 1057 450 452 1058 452 455 1059 455 453 1060 453 454 1061 454 453 1062 453 455 1063 455 456 1064 456 461 1065 461 457 1066 457 458 1067 458 457 1068 457 459 1069 459 460 1070 460 457 1071 457 461 1072 461 459 1073 459 464 1074 464 462 1075 462 463 1076 463 466 1077 466 464 1078 464 465 1079 465 462 1080 462 464 1081 464 466 1082 466 469 1083 469 467 1084 467 468 1085 468 467 1086 467 469 1087 469 470 1088 470 475 1089 475 471 1090 471 472 1091 472 471 1092 471 473 1093 473 474 1094 474 471 1095 471 475 1096 475 473 1097 473 478 1098 478 476 1099 476 477 1100 477 480 1101 480 478 1102 478 479 1103 479 476 1104 476 478 1105 478 480 1106 480 483 1107 483 481 1108 481 482 1109 482 481 1110 481 483 1111 483 484 1112 484 489 1113 489 485 1114 485 486 1115 486 485 1116 485 487 1117 487 488 1118 488 485 1119 485 489 1120 489 487 1121 487 492 1122 492 490 1123 490 491 1124 491 490 1125 490 492 1126 492 493 1127 493 498 1128 498 494 1129 494 495 1130 495 494 1131 494 496 1132 496 497 1133 497 494 1134 494 498 1135 498 496 1136 496 501 1137 501 499 1138 499 500 1139 500 503 1140 503 501 1141 501 502 1142 502 499 1143 499 501 1144 501 503 1145 503 506 1146 506 504 1147 504 505 1148 505 504 1149 504 506 1150 506 507 1151 507 510 1152 510 508 1153 508 509 1154 509 508 1155 508 510 1156 510 511 1157 511 514 1158 514 512 1159 512 513 1160 513 516 1161 516 514 1162 514 515 1163 515 512 1164 512 514 1165 514 516 1166 516 521 1167 521 517 1168 517 518 1169 518 517 1170 517 519 1171 519 520 1172 520 517 1173 517 521 1174 521 519 1175 519 524 1176 524 522 1177 522 523 1178 523 522 1179 522 524 1180 524 525 1181 525 528 1182 528 526 1183 526 527 1184 527 530 1185 530 528 1186 528 529 1187 529 526 1188 526 528 1189 528 530 1190 530 535 1191 535 531 1192 531 532 1193 532 531 1194 531 533 1195 533 534 1196 534 531 1197 531 535 1198 535 533 1199 533 538 1200 538 536 1201 536 537 1202 537 536 1203 536 538 1204 538 539 1205 539 542 1206 542 540 1207 540 541 1208 541 544 1209 544 542 1210 542 543 1211 543 540 1212 540 542 1213 542 544 1214 544 549 1215 549 545 1216 545 546 1217 546 545 1218 545 547 1219 547 548 1220 548 545 1221 545 549 1222 549 547 1223 547 552 1224 552 550 1225 550 551 1226 551 550 1227 550 552 1228 552 553 1229 553 556 1230 556 554 1231 554 555 1232 555 558 1233 558 556 1234 556 557 1235 557 554 1236 554 556 1237 556 558 1238 558 563 1239 563 559 1240 559 560 1241 560 559 1242 559 561 1243 561 562 1244 562 559 1245 559 563 1246 563 561 1247 561 566 1248 566 564 1249 564 565 1250 565 564 1251 564 566 1252 566 567 1253 567 570 1254 570 568 1255 568 569 1256 569 572 1257 572 570 1258 570 571 1259 571 568 1260 568 570 1261 570 572 1262 572 577 1263 577 573 1264 573 574 1265 574 573 1266 573 575 1267 575 576 1268 576 573 1269 573 577 1270 577 575 1271 575 580 1272 580 578 1273 578 579 1274 579 578 1275 578 580 1276 580 581 1277 581 584 1278 584 582 1279 582 583 1280 583 586 1281 586 584 1282 584 585 1283 585 582 1284 582 584 1285 584 586 1286 586 591 1287 591 587 1288 587 588 1289 588 587 1290 587 589 1291 589 590 1292 590 587 1293 587 591 1294 591 589 1295 589 594 1296 594 592 1297 592 593 1298 593 592 1299 592 594 1300 594 595 1301 595 598 1302 598 596 1303 596 597 1304 597 600 1305 600 598 1306 598 599 1307 599 596 1308 596 598 1309 598 600 1310 600 605 1311 605 601 1312 601 602 1313 602 601 1314 601 603 1315 603 604 1316 604 601 1317 601 605 1318 605 603 1319 603 608 1320 608 606 1321 606 607 1322 607 606 1323 606 608 1324 608 609 1325 609 612 1326 612 610 1327 610 611 1328 611 614 1329 614 612 1330 612 613 1331 613 610 1332 610 612 1333 612 614 1334 614 619 1335 619 615 1336 615 616 1337 616 615 1338 615 617 1339 617 618 1340 618 615 1341 615 619 1342 619 617 1343 617 622 1344 622 620 1345 620 621 1346 621 620 1347 620 622 1348 622 623 1349 623 626 1350 626 624 1351 624 625 1352 625 628 1353 628 626 1354 626 627 1355 627 624 1356 624 626 1357 626 628 1358 628 633 1359 633 629 1360 629 630 1361 630 629 1362 629 631 1363 631 632 1364 632 629 1365 629 633 1366 633 631 1367 631 636 1368 636 634 1369 634 635 1370 635 634 1371 634 636 1372 636 637 1373 637 640 1374 640 638 1375 638 639 1376 639 642 1377 642 640 1378 640 641 1379 641 638 1380 638 640 1381 640 642 1382 642 647 1383 647 643 1384 643 644 1385 644 643 1386 643 645 1387 645 646 1388 646 643 1389 643 647 1390 647 645 1391 645 650 1392 650 648 1393 648 649 1394 649 648 1395 648 650 1396 650 651 1397 651 723 1398 723 662 1399 662 652 1400 652 668 1401 668 653 1402 653 654 1403 654 663 1404 663 668 1405 668 654 1406 654 663 1407 663 655 1408 655 668 1409 668 663 1410 663 656 1411 656 655 1412 655 663 1413 663 657 1414 657 656 1415 656 663 1416 663 658 1417 658 657 1418 657 663 1419 663 659 1420 659 658 1421 658 663 1422 663 660 1423 660 659 1424 659 663 1425 663 661 1426 661 660 1427 660 663 1428 663 662 1429 662 661 1430 661 664 1431 664 662 1432 662 663 1433 663 665 1434 665 662 1435 662 664 1436 664 652 1437 652 662 1438 662 665 1439 665 668 1440 668 666 1441 666 653 1442 653 668 1443 668 667 1444 667 666 1445 666 674 1446 674 667 1447 667 668 1448 668 674 1449 674 669 1450 669 667 1451 667 674 1452 674 670 1453 670 669 1454 669 674 1455 674 671 1456 671 670 1457 670 674 1458 674 672 1459 672 671 1460 671 674 1461 674 673 1462 673 672 1463 672 675 1464 675 673 1465 673 674 1466 674 676 1467 676 673 1468 673 675 1469 675 677 1470 677 673 1471 673 676 1472 676 678 1473 678 673 1474 673 677 1475 677 679 1476 679 673 1477 673 678 1478 678 680 1479 680 673 1480 673 679 1481 679 681 1482 681 673 1483 673 680 1484 680 686 1485 686 673 1486 673 681 1487 681 686 1488 686 682 1489 682 673 1490 673 686 1491 686 683 1492 683 682 1493 682 686 1494 686 684 1495 684 683 1496 683 686 1497 686 685 1498 685 684 1499 684 692 1500 692 685 1501 685 686 1502 686 692 1503 692 687 1504 687 685 1505 685 692 1506 692 688 1507 688 687 1508 687 692 1509 692 689 1510 689 688 1511 688 692 1512 692 690 1513 690 689 1514 689 692 1515 692 691 1516 691 690 1517 690 693 1518 693 691 1519 691 692 1520 692 694 1521 694 691 1522 691 693 1523 693 695 1524 695 691 1525 691 694 1526 694 696 1527 696 691 1528 691 695 1529 695 697 1530 697 691 1531 691 696 1532 696 698 1533 698 691 1534 691 697 1535 697 699 1536 699 691 1537 691 698 1538 698 704 1539 704 691 1540 691 699 1541 699 704 1542 704 700 1543 700 691 1544 691 704 1545 704 701 1546 701 700 1547 700 704 1548 704 702 1549 702 701 1550 701 704 1551 704 703 1552 703 702 1553 702 710 1554 710 703 1555 703 704 1556 704 710 1557 710 705 1558 705 703 1559 703 710 1560 710 706 1561 706 705 1562 705 710 1563 710 707 1564 707 706 1565 706 710 1566 710 708 1567 708 707 1568 707 710 1569 710 709 1570 709 708 1571 708 711 1572 711 709 1573 709 710 1574 710 712 1575 712 709 1576 709 711 1577 711 713 1578 713 709 1579 709 712 1580 712 714 1581 714 709 1582 709 713 1583 713 715 1584 715 709 1585 709 714 1586 714 716 1587 716 709 1588 709 715 1589 715 717 1590 717 709 1591 709 716 1592 716 722 1593 722 709 1594 709 717 1595 717 722 1596 722 718 1597 718 709 1598 709 722 1599 722 719 1600 719 718 1601 718 722 1602 722 720 1603 720 719 1604 719 722 1605 722 721 1606 721 720 1607 720 662 1608 662 721 1609 721 722 1610 722 662 1611 662 723 1612 723 721 1613 721 765 1614 765 727 1615 727 724 1616 724 733 1617 733 725 1618 725 726 1619 726 733 1620 733 727 1621 727 725 1622 725 730 1623 730 752 1624 752 728 1625 728 752 1626 752 729 1627 729 728 1628 728 732 1629 732 752 1630 752 730 1631 730 752 1632 752 731 1633 731 729 1634 729 734 1635 734 752 1636 752 732 1637 732 734 1638 734 733 1639 733 752 1640 752 735 1641 735 733 1642 733 734 1643 734 736 1644 736 733 1645 733 735 1646 735 737 1647 737 733 1648 733 736 1649 736 738 1650 738 733 1651 733 737 1652 737 739 1653 739 733 1654 733 738 1655 738 740 1656 740 733 1657 733 739 1658 739 741 1659 741 733 1660 733 740 1661 740 742 1662 742 733 1663 733 741 1664 741 742 1665 742 727 1666 727 733 1667 733 743 1668 743 727 1669 727 742 1670 742 744 1671 744 727 1672 727 743 1673 743 745 1674 745 727 1675 727 744 1676 744 746 1677 746 727 1678 727 745 1679 745 748 1680 748 727 1681 727 746 1682 746 752 1683 752 747 1684 747 731 1685 731 750 1686 750 727 1687 727 748 1688 748 752 1689 752 749 1690 749 747 1691 747 724 1692 724 727 1693 727 750 1694 750 752 1695 752 751 1696 751 749 1697 749 762 1698 762 751 1699 751 752 1700 752 762 1701 762 753 1702 753 751 1703 751 762 1704 762 754 1705 754 753 1706 753 762 1707 762 755 1708 755 754 1709 754 762 1710 762 756 1711 756 755 1712 755 762 1713 762 757 1714 757 756 1715 756 762 1716 762 758 1717 758 757 1718 757 762 1719 762 759 1720 759 758 1721 758 762 1722 762 760 1723 760 759 1724 759 762 1725 762 761 1726 761 760 1727 760 727 1728 727 761 1729 761 762 1730 762 727 1731 727 763 1732 763 761 1733 761 727 1734 727 764 1735 764 763 1736 763 727 1737 727 765 1738 765 764 1739 764 820 1740 820 772 1741 772 766 1742 766 769 1743 769 767 1744 767 768 1745 768 770 1746 770 767 1747 767 769 1748 769 771 1749 771 767 1750 767 770 1751 770 772 1752 772 767 1753 767 771 1754 771 788 1755 788 818 1756 818 772 1757 772 788 1758 788 773 1759 773 818 1760 818 777 1761 777 774 1762 774 775 1763 775 777 1764 777 776 1765 776 774 1766 774 778 1767 778 776 1768 776 777 1769 777 779 1770 779 776 1771 776 778 1772 778 780 1773 780 776 1774 776 779 1775 779 781 1776 781 776 1777 776 780 1778 780 782 1779 782 776 1780 776 781 1781 781 783 1782 783 776 1783 776 782 1784 782 784 1785 784 776 1786 776 783 1787 783 787 1788 787 776 1789 776 784 1790 784 803 1791 803 785 1792 785 786 1793 786 789 1794 789 776 1795 776 787 1796 787 789 1797 789 788 1798 788 776 1799 776 790 1800 790 788 1801 788 789 1802 789 791 1803 791 788 1804 788 790 1805 790 792 1806 792 788 1807 788 791 1808 791 793 1809 793 788 1810 788 792 1811 792 794 1812 794 788 1813 788 793 1814 793 795 1815 795 788 1816 788 794 1817 794 796 1818 796 788 1819 788 795 1820 795 803 1821 803 796 1822 796 785 1823 785 803 1824 803 788 1825 788 796 1826 796 788 1827 788 797 1828 797 773 1829 773 803 1830 803 797 1831 797 788 1832 788 803 1833 803 798 1834 798 797 1835 797 803 1836 803 799 1837 799 798 1838 798 803 1839 803 800 1840 800 799 1841 799 803 1842 803 801 1843 801 800 1844 800 803 1845 803 802 1846 802 801 1847 801 804 1848 804 802 1849 802 803 1850 803 805 1851 805 802 1852 802 804 1853 804 806 1854 806 802 1855 802 805 1856 805 807 1857 807 802 1858 802 806 1859 806 808 1860 808 802 1861 802 807 1862 807 809 1863 809 802 1864 802 808 1865 808 810 1866 810 802 1867 802 809 1868 809 812 1869 812 802 1870 802 810 1871 810 812 1872 812 811 1873 811 802 1874 802 767 1875 767 811 1876 811 812 1877 812 767 1878 767 813 1879 813 811 1880 811 767 1881 767 814 1882 814 813 1883 813 767 1884 767 815 1885 815 814 1886 814 767 1887 767 816 1888 816 815 1889 815 767 1890 767 817 1891 817 816 1892 816 766 1893 766 772 1894 772 818 1895 818 767 1896 767 819 1897 819 817 1898 817 772 1899 772 819 1900 819 767 1901 767 772 1902 772 820 1903 820 819 1904 819 836 1905 836 833 1906 833 821 1907 821 824 1908 824 822 1909 822 823 1910 823 825 1911 825 822 1912 822 824 1913 824 826 1914 826 822 1915 822 825 1916 825 830 1917 830 822 1918 822 826 1919 826 837 1920 837 827 1921 827 828 1922 828 837 1923 837 829 1924 829 827 1925 827 832 1926 832 822 1927 822 830 1928 830 832 1929 832 831 1930 831 822 1931 822 834 1932 834 831 1933 831 832 1934 832 834 1935 834 833 1936 833 831 1937 831 821 1938 821 833 1939 833 834 1940 834 837 1941 837 835 1942 835 829 1943 829 837 1944 837 836 1945 836 835 1946 835 833 1947 833 836 1948 836 837 1949 837 853 1950 853 838 1951 838 839 1952 839 843 1953 843 846 1954 846 840 1955 840 843 1956 843 841 1957 841 846 1958 846 846 1959 846 842 1960 842 840 1961 840 852 1962 852 841 1963 841 843 1964 843 851 1965 851 844 1966 844 845 1967 845 848 1968 848 846 1969 846 847 1970 847 848 1971 848 842 1972 842 846 1973 846 838 1974 838 842 1975 842 848 1976 848 841 1977 841 849 1978 849 850 1979 850 852 1980 852 849 1981 849 841 1982 841 852 1983 852 851 1984 851 849 1985 849 852 1986 852 844 1987 844 851 1988 851 842 1989 842 844 1990 844 852 1991 852 842 1992 842 853 1993 853 844 1994 844 838 1995 838 853 1996 853 842 1997 842 856 1998 856 854 1999 854 855 2000 855 854 2001 854 856 2002 856 857 2003 857 860 2004 860 858 2005 858 859 2006 859 858 2007 858 860 2008 860 861 2009 861 864 2010 864 862 2011 862 863 2012 863 862 2013 862 864 2014 864 865 2015 865 868 2016 868 866 2017 866 867 2018 867 866 2019 866 868 2020 868 869 2021 869 872 2022 872 870 2023 870 871 2024 871 870 2025 870 872 2026 872 873 2027 873 876 2028 876 874 2029 874 875 2030 875 874 2031 874 876 2032 876 877 2033 877 880 2034 880 878 2035 878 879 2036 879 878 2037 878 880 2038 880 881 2039 881 884 2040 884 882 2041 882 883 2042 883 882 2043 882 884 2044 884 885 2045 885 888 2046 888 886 2047 886 887 2048 887 886 2049 886 888 2050 888 889 2051 889 892 2052 892 890 2053 890 891 2054 891 890 2055 890 892 2056 892 893 2057 893 896 2058 896 894 2059 894 895 2060 895 894 2061 894 896 2062 896 897 2063 897 900 2064 900 898 2065 898 899 2066 899 898 2067 898 900 2068 900 901 2069 901 904 2070 904 902 2071 902 903 2072 903 902 2073 902 904 2074 904 905 2075 905 908 2076 908 906 2077 906 907 2078 907 906 2079 906 908 2080 908 909 2081 909 912 2082 912 910 2083 910 911 2084 911 910 2085 910 912 2086 912 913 2087 913 916 2088 916 914 2089 914 915 2090 915 914 2091 914 916 2092 916 917 2093 917 920 2094 920 918 2095 918 919 2096 919 918 2097 918 920 2098 920 921 2099 921 940 2100 940 922 2101 922 938 2102 938 927 2103 927 923 2104 923 924 2105 924 940 2106 940 925 2107 925 926 2108 926 929 2109 929 923 2110 923 927 2111 927 940 2112 940 928 2113 928 925 2114 925 931 2115 931 923 2116 923 929 2117 929 940 2118 940 930 2119 930 928 2120 928 933 2121 933 923 2122 923 931 2123 931 940 2124 940 932 2125 932 930 2126 930 935 2127 935 923 2128 923 933 2129 933 940 2130 940 934 2131 934 932 2132 932 937 2133 937 923 2134 923 935 2135 935 940 2136 940 936 2137 936 934 2138 934 939 2139 939 923 2140 923 937 2141 937 940 2142 940 938 2143 938 936 2144 936 941 2145 941 923 2146 923 939 2147 939 941 2148 941 940 2149 940 923 2150 923 922 2151 922 940 2152 940 941 2153 941 962 2154 962 943 2155 943 942 2156 942 948 2157 948 943 2158 943 944 2159 944 960 2160 960 945 2161 945 946 2162 946 960 2163 960 947 2164 947 945 2165 945 950 2166 950 943 2167 943 948 2168 948 960 2169 960 949 2170 949 947 2171 947 952 2172 952 943 2173 943 950 2174 950 960 2175 960 951 2176 951 949 2177 949 954 2178 954 943 2179 943 952 2180 952 960 2181 960 953 2182 953 951 2183 951 956 2184 956 943 2185 943 954 2186 954 960 2187 960 955 2188 955 953 2189 953 958 2190 958 943 2191 943 956 2192 956 960 2193 960 957 2194 957 955 2195 955 942 2196 942 943 2197 943 958 2198 958 960 2199 960 959 2200 959 957 2201 957 943 2202 943 959 2203 959 960 2204 960 943 2205 943 961 2206 961 959 2207 959 943 2208 943 962 2209 962 961 2210 961 965 2211 965 963 2212 963 964 2213 964 963 2214 963 965 2215 965 966 2216 966 985 2217 985 967 2218 967 983 2219 983 973 2220 973 968 2221 968 969 2222 969 985 2223 985 970 2224 970 971 2225 971 985 2226 985 972 2227 972 970 2228 970 974 2229 974 968 2230 968 973 2231 973 976 2232 976 968 2233 968 974 2234 974 985 2235 985 975 2236 975 972 2237 972 978 2238 978 968 2239 968 976 2240 976 985 2241 985 977 2242 977 975 2243 975 980 2244 980 968 2245 968 978 2246 978 985 2247 985 979 2248 979 977 2249 977 982 2250 982 968 2251 968 980 2252 980 985 2253 985 981 2254 981 979 2255 979 984 2256 984 968 2257 968 982 2258 982 985 2259 985 983 2260 983 981 2261 981 986 2262 986 968 2263 968 984 2264 984 986 2265 986 985 2266 985 968 2267 968 967 2268 967 985 2269 985 986 2270 986 1007 2271 1007 988 2272 988 987 2273 987 993 2274 993 988 2275 988 989 2276 989 1005 2277 1005 990 2278 990 991 2279 991 1005 2280 1005 992 2281 992 990 2282 990 994 2283 994 988 2284 988 993 2285 993 997 2286 997 988 2287 988 994 2288 994 1005 2289 1005 995 2290 995 992 2291 992 1005 2292 1005 996 2293 996 995 2294 995 999 2295 999 988 2296 988 997 2297 997 1005 2298 1005 998 2299 998 996 2300 996 1001 2301 1001 988 2302 988 999 2303 999 1005 2304 1005 1000 2305 1000 998 2306 998 1003 2307 1003 988 2308 988 1001 2309 1001 1005 2310 1005 1002 2311 1002 1000 2312 1000 987 2313 987 988 2314 988 1003 2315 1003 1005 2316 1005 1004 2317 1004 1002 2318 1002 988 2319 988 1004 2320 1004 1005 2321 1005 988 2322 988 1006 2323 1006 1004 2324 1004 988 2325 988 1007 2326 1007 1006 2327 1006 1045 2328 1045 1009 2329 1009 1008 2330 1008 1011 2331 1011 1009 2332 1009 1010 2333 1010 1012 2334 1012 1009 2335 1009 1011 2336 1011 1013 2337 1013 1009 2338 1009 1012 2339 1012 1014 2340 1014 1009 2341 1009 1013 2342 1013 1015 2343 1015 1009 2344 1009 1014 2345 1014 1016 2346 1016 1009 2347 1009 1015 2348 1015 1017 2349 1017 1009 2350 1009 1016 2351 1016 1018 2352 1018 1009 2353 1009 1017 2354 1017 1019 2355 1019 1009 2356 1009 1018 2357 1018 1020 2358 1020 1009 2359 1009 1019 2360 1019 1021 2361 1021 1009 2362 1009 1020 2363 1020 1022 2364 1022 1009 2365 1009 1021 2366 1021 1023 2367 1023 1009 2368 1009 1022 2369 1022 1024 2370 1024 1009 2371 1009 1023 2372 1023 1025 2373 1025 1009 2374 1009 1024 2375 1024 1008 2376 1008 1009 2377 1009 1025 2378 1025 1044 2379 1044 1026 2380 1026 1027 2381 1027 1044 2382 1044 1028 2383 1028 1026 2384 1026 1044 2385 1044 1029 2386 1029 1028 2387 1028 1044 2388 1044 1030 2389 1030 1029 2390 1029 1044 2391 1044 1031 2392 1031 1030 2393 1030 1044 2394 1044 1032 2395 1032 1031 2396 1031 1044 2397 1044 1033 2398 1033 1032 2399 1032 1044 2400 1044 1034 2401 1034 1033 2402 1033 1044 2403 1044 1035 2404 1035 1034 2405 1034 1044 2406 1044 1036 2407 1036 1035 2408 1035 1044 2409 1044 1037 2410 1037 1036 2411 1036 1044 2412 1044 1038 2413 1038 1037 2414 1037 1044 2415 1044 1039 2416 1039 1038 2417 1038 1044 2418 1044 1040 2419 1040 1039 2420 1039 1044 2421 1044 1041 2422 1041 1040 2423 1040 1044 2424 1044 1042 2425 1042 1041 2426 1041 1044 2427 1044 1043 2428 1043 1042 2429 1042 1009 2430 1009 1043 2431 1043 1044 2432 1044 1009 2433 1009 1045 2434 1045 1043 2435 1043 1111 2436 1111 1076 2437 1076 1046 2438 1046 1048 2439 1048 1047 2440 1047 1071 2441 1071 1050 2442 1050 1047 2443 1047 1048 2444 1048 1050 2445 1050 1049 2446 1049 1047 2447 1047 1052 2448 1052 1049 2449 1049 1050 2450 1050 1052 2451 1052 1051 2452 1051 1049 2453 1049 1054 2454 1054 1051 2455 1051 1052 2456 1052 1054 2457 1054 1053 2458 1053 1051 2459 1051 1056 2460 1056 1053 2461 1053 1054 2462 1054 1056 2463 1056 1055 2464 1055 1053 2465 1053 1058 2466 1058 1055 2467 1055 1056 2468 1056 1058 2469 1058 1057 2470 1057 1055 2471 1055 1060 2472 1060 1057 2473 1057 1058 2474 1058 1060 2475 1060 1059 2476 1059 1057 2477 1057 1062 2478 1062 1059 2479 1059 1060 2480 1060 1062 2481 1062 1061 2482 1061 1059 2483 1059 1064 2484 1064 1061 2485 1061 1062 2486 1062 1064 2487 1064 1063 2488 1063 1061 2489 1061 1066 2490 1066 1063 2491 1063 1064 2492 1064 1066 2493 1066 1065 2494 1065 1063 2495 1063 1068 2496 1068 1065 2497 1065 1066 2498 1066 1068 2499 1068 1067 2500 1067 1065 2501 1065 1070 2502 1070 1067 2503 1067 1068 2504 1068 1070 2505 1070 1069 2506 1069 1067 2507 1067 1078 2508 1078 1069 2509 1069 1070 2510 1070 1073 2511 1073 1048 2512 1048 1071 2513 1071 1073 2514 1073 1072 2515 1072 1048 2516 1048 1075 2517 1075 1072 2518 1072 1073 2519 1073 1075 2520 1075 1074 2521 1074 1072 2522 1072 1046 2523 1046 1074 2524 1074 1075 2525 1075 1046 2526 1046 1076 2527 1076 1074 2528 1074 1078 2529 1078 1077 2530 1077 1069 2531 1069 1079 2532 1079 1077 2533 1077 1078 2534 1078 1082 2535 1082 1077 2536 1077 1079 2537 1079 1082 2538 1082 1080 2539 1080 1077 2540 1077 1082 2541 1082 1081 2542 1081 1080 2543 1080 1084 2544 1084 1081 2545 1081 1082 2546 1082 1084 2547 1084 1083 2548 1083 1081 2549 1081 1086 2550 1086 1083 2551 1083 1084 2552 1084 1086 2553 1086 1085 2554 1085 1083 2555 1083 1088 2556 1088 1085 2557 1085 1086 2558 1086 1088 2559 1088 1087 2560 1087 1085 2561 1085 1090 2562 1090 1087 2563 1087 1088 2564 1088 1090 2565 1090 1089 2566 1089 1087 2567 1087 1092 2568 1092 1089 2569 1089 1090 2570 1090 1092 2571 1092 1091 2572 1091 1089 2573 1089 1094 2574 1094 1091 2575 1091 1092 2576 1092 1094 2577 1094 1093 2578 1093 1091 2579 1091 1096 2580 1096 1093 2581 1093 1094 2582 1094 1096 2583 1096 1095 2584 1095 1093 2585 1093 1098 2586 1098 1095 2587 1095 1096 2588 1096 1098 2589 1098 1097 2590 1097 1095 2591 1095 1100 2592 1100 1097 2593 1097 1098 2594 1098 1100 2595 1100 1099 2596 1099 1097 2597 1097 1102 2598 1102 1099 2599 1099 1100 2600 1100 1102 2601 1102 1101 2602 1101 1099 2603 1099 1104 2604 1104 1101 2605 1101 1102 2606 1102 1104 2607 1104 1103 2608 1103 1101 2609 1101 1106 2610 1106 1103 2611 1103 1104 2612 1104 1106 2613 1106 1105 2614 1105 1103 2615 1103 1108 2616 1108 1105 2617 1105 1106 2618 1106 1108 2619 1108 1107 2620 1107 1105 2621 1105 1110 2622 1110 1107 2623 1107 1108 2624 1108 1110 2625 1110 1109 2626 1109 1107 2627 1107 1112 2628 1112 1109 2629 1109 1110 2630 1110 1112 2631 1112 1111 2632 1111 1109 2633 1109 1113 2634 1113 1111 2635 1111 1112 2636 1112 1076 2637 1076 1111 2638 1111 1113 2639 1113 1121 2640 1121 1114 2641 1114 1115 2642 1115 1120 2643 1120 1116 2644 1116 1117 2645 1117 1120 2646 1120 1118 2647 1118 1116 2648 1116 1120 2649 1120 1119 2650 1119 1118 2651 1118 1114 2652 1114 1119 2653 1119 1120 2654 1120 1114 2655 1114 1121 2656 1121 1119 2657 1119 1124 2658 1124 1122 2659 1122 1123 2660 1123 1122 2661 1122 1124 2662 1124 1125 2663 1125 1128 2664 1128 1126 2665 1126 1127 2666 1127 1126 2667 1126 1128 2668 1128 1129 2669 1129 1132 2670 1132 1130 2671 1130 1131 2672 1131 1134 2673 1134 1132 2674 1132 1133 2675 1133 1135 2676 1135 1132 2677 1132 1134 2678 1134 1136 2679 1136 1132 2680 1132 1135 2681 1135 1137 2682 1137 1132 2683 1132 1136 2684 1136 1138 2685 1138 1132 2686 1132 1137 2687 1137 1139 2688 1139 1132 2689 1132 1138 2690 1138 1140 2691 1140 1132 2692 1132 1139 2693 1139 1141 2694 1141 1132 2695 1132 1140 2696 1140 1130 2697 1130 1132 2698 1132 1141 2699 1141 1153 2700 1153 1142 2701 1142 1143 2702 1143 1142 2703 1142 1144 2704 1144 1145 2705 1145 1142 2706 1142 1146 2707 1146 1144 2708 1144 1142 2709 1142 1147 2710 1147 1146 2711 1146 1142 2712 1142 1148 2713 1148 1147 2714 1147 1142 2715 1142 1149 2716 1149 1148 2717 1148 1142 2718 1142 1150 2719 1150 1149 2720 1149 1142 2721 1142 1151 2722 1151 1150 2723 1150 1142 2724 1142 1152 2725 1152 1151 2726 1151 1142 2727 1142 1153 2728 1153 1152 2729 1152 1205 2730 1205 1184 2731 1184 1154 2732 1154 1157 2733 1157 1155 2734 1155 1156 2735 1156 1158 2736 1158 1155 2737 1155 1157 2738 1157 1159 2739 1159 1155 2740 1155 1158 2741 1158 1160 2742 1160 1155 2743 1155 1159 2744 1159 1161 2745 1161 1155 2746 1155 1160 2747 1160 1162 2748 1162 1155 2749 1155 1161 2750 1161 1163 2751 1163 1155 2752 1155 1162 2753 1162 1164 2754 1164 1155 2755 1155 1163 2756 1163 1165 2757 1165 1155 2758 1155 1164 2759 1164 1166 2760 1166 1155 2761 1155 1165 2762 1165 1191 2763 1191 1155 2764 1155 1166 2765 1166 1191 2766 1191 1167 2767 1167 1155 2768 1155 1180 2769 1180 1168 2770 1168 1169 2771 1169 1180 2772 1180 1170 2773 1170 1168 2774 1168 1180 2775 1180 1171 2776 1171 1170 2777 1170 1180 2778 1180 1172 2779 1172 1171 2780 1171 1180 2781 1180 1173 2782 1173 1172 2783 1172 1180 2784 1180 1174 2785 1174 1173 2786 1173 1180 2787 1180 1175 2788 1175 1174 2789 1174 1180 2790 1180 1176 2791 1176 1175 2792 1175 1180 2793 1180 1177 2794 1177 1176 2795 1176 1180 2796 1180 1178 2797 1178 1177 2798 1177 1180 2799 1180 1179 2800 1179 1178 2801 1178 1185 2802 1185 1179 2803 1179 1180 2804 1180 1179 2805 1179 1181 2806 1181 1182 2807 1182 1179 2808 1179 1183 2809 1183 1181 2810 1181 1185 2811 1185 1183 2812 1183 1179 2813 1179 1185 2814 1185 1184 2815 1184 1183 2816 1183 1186 2817 1186 1184 2818 1184 1185 2819 1185 1195 2820 1195 1184 2821 1184 1186 2822 1186 1184 2823 1184 1187 2824 1187 1188 2825 1188 1192 2826 1192 1189 2827 1189 1190 2828 1190 1192 2829 1192 1191 2830 1191 1189 2831 1189 1192 2832 1192 1167 2833 1167 1191 2834 1191 1197 2835 1197 1167 2836 1167 1192 2837 1192 1197 2838 1197 1193 2839 1193 1167 2840 1167 1197 2841 1197 1194 2842 1194 1193 2843 1193 1154 2844 1154 1184 2845 1184 1195 2846 1195 1197 2847 1197 1196 2848 1196 1194 2849 1194 1187 2850 1187 1196 2851 1196 1197 2852 1197 1187 2853 1187 1198 2854 1198 1196 2855 1196 1187 2856 1187 1199 2857 1199 1198 2858 1198 1187 2859 1187 1200 2860 1200 1199 2861 1199 1187 2862 1187 1201 2863 1201 1200 2864 1200 1187 2865 1187 1202 2866 1202 1201 2867 1201 1184 2868 1184 1202 2869 1202 1187 2870 1187 1184 2871 1184 1203 2872 1203 1202 2873 1202 1184 2874 1184 1204 2875 1204 1203 2876 1203 1184 2877 1184 1205 2878 1205 1204 2879 1204 1280 2880 1280 1272 2881 1272 1206 2882 1206 1272 2883 1272 1207 2884 1207 1208 2885 1208 1272 2886 1272 1209 2887 1209 1207 2888 1207 1272 2889 1272 1210 2890 1210 1209 2891 1209 1272 2892 1272 1211 2893 1211 1210 2894 1210 1272 2895 1272 1212 2896 1212 1211 2897 1211 1272 2898 1272 1213 2899 1213 1212 2900 1212 1215 2901 1215 1214 2902 1214 1246 2903 1246 1257 2904 1257 1214 2905 1214 1215 2906 1215 1218 2907 1218 1216 2908 1216 1217 2909 1217 1222 2910 1222 1216 2911 1216 1218 2912 1218 1222 2913 1222 1219 2914 1219 1216 2915 1216 1222 2916 1222 1220 2917 1220 1219 2918 1219 1222 2919 1222 1221 2920 1221 1220 2921 1220 1225 2922 1225 1221 2923 1221 1222 2924 1222 1225 2925 1225 1223 2926 1223 1221 2927 1221 1225 2928 1225 1224 2929 1224 1223 2930 1223 1227 2931 1227 1224 2932 1224 1225 2933 1225 1227 2934 1227 1226 2935 1226 1224 2936 1224 1229 2937 1229 1226 2938 1226 1227 2939 1227 1229 2940 1229 1228 2941 1228 1226 2942 1226 1231 2943 1231 1228 2944 1228 1229 2945 1229 1231 2946 1231 1230 2947 1230 1228 2948 1228 1232 2949 1232 1230 2950 1230 1231 2951 1231 1234 2952 1234 1230 2953 1230 1232 2954 1232 1234 2955 1234 1233 2956 1233 1230 2957 1230 1235 2958 1235 1233 2959 1233 1234 2960 1234 1237 2961 1237 1233 2962 1233 1235 2963 1235 1272 2964 1272 1236 2965 1236 1213 2966 1213 1249 2967 1249 1233 2968 1233 1237 2969 1237 1249 2970 1249 1238 2971 1238 1233 2972 1233 1249 2973 1249 1239 2974 1239 1238 2975 1238 1249 2976 1249 1240 2977 1240 1239 2978 1239 1249 2979 1249 1241 2980 1241 1240 2981 1240 1249 2982 1249 1242 2983 1242 1241 2984 1241 1249 2985 1249 1243 2986 1243 1242 2987 1242 1248 2988 1248 1244 2989 1244 1245 2990 1245 1272 2991 1272 1246 2992 1246 1236 2993 1236 1249 2994 1249 1247 2995 1247 1243 2996 1243 1247 2997 1247 1244 2998 1244 1248 2999 1248 1249 3000 1249 1244 3001 1244 1247 3002 1247 1250 3003 1250 1244 3004 1244 1249 3005 1249 1251 3006 1251 1244 3007 1244 1250 3008 1250 1252 3009 1252 1244 3010 1244 1251 3011 1251 1253 3012 1253 1244 3013 1244 1252 3014 1252 1254 3015 1254 1244 3016 1244 1253 3017 1253 1255 3018 1255 1244 3019 1244 1254 3020 1254 1256 3021 1256 1244 3022 1244 1255 3023 1255 1214 3024 1214 1244 3025 1244 1256 3026 1256 1258 3027 1258 1214 3028 1214 1257 3029 1257 1258 3030 1258 1244 3031 1244 1214 3032 1214 1259 3033 1259 1244 3034 1244 1258 3035 1258 1260 3036 1260 1244 3037 1244 1259 3038 1259 1261 3039 1261 1244 3040 1244 1260 3041 1260 1262 3042 1262 1244 3043 1244 1261 3044 1261 1271 3045 1271 1244 3046 1244 1262 3047 1262 1271 3048 1271 1263 3049 1263 1244 3050 1244 1271 3051 1271 1264 3052 1264 1263 3053 1263 1271 3054 1271 1265 3055 1265 1264 3056 1264 1271 3057 1271 1266 3058 1266 1265 3059 1265 1271 3060 1271 1267 3061 1267 1266 3062 1266 1271 3063 1271 1268 3064 1268 1267 3065 1267 1271 3066 1271 1269 3067 1269 1268 3068 1268 1271 3069 1271 1270 3070 1270 1269 3071 1269 1273 3072 1273 1270 3073 1270 1271 3074 1271 1273 3075 1273 1272 3076 1272 1270 3077 1270 1274 3078 1274 1272 3079 1272 1273 3080 1273 1275 3081 1275 1272 3082 1272 1274 3083 1274 1276 3084 1276 1272 3085 1272 1275 3086 1275 1277 3087 1277 1272 3088 1272 1276 3089 1276 1279 3090 1279 1272 3091 1272 1277 3092 1277 1246 3093 1246 1278 3094 1278 1215 3095 1215 1206 3096 1206 1272 3097 1272 1279 3098 1279 1246 3099 1246 1280 3100 1280 1278 3101 1278 1272 3102 1272 1280 3103 1280 1246 3104 1246 1300 3105 1300 1281 3106 1281 1304 3107 1304 1297 3108 1297 1282 3109 1282 1283 3110 1283 1297 3111 1297 1284 3112 1284 1282 3113 1282 1297 3114 1297 1285 3115 1285 1284 3116 1284 1297 3117 1297 1286 3118 1286 1285 3119 1285 1289 3120 1289 1287 3121 1287 1288 3122 1288 1302 3123 1302 1287 3124 1287 1289 3125 1289 1302 3126 1302 1290 3127 1290 1287 3128 1287 1302 3129 1302 1291 3130 1291 1290 3131 1290 1302 3132 1302 1292 3133 1292 1291 3134 1291 1302 3135 1302 1293 3136 1293 1292 3137 1292 1302 3138 1302 1294 3139 1294 1293 3140 1293 1302 3141 1302 1295 3142 1295 1294 3143 1294 1297 3144 1297 1296 3145 1296 1286 3146 1286 1299 3147 1299 1296 3148 1296 1297 3149 1297 1299 3150 1299 1298 3151 1298 1296 3152 1296 1301 3153 1301 1298 3154 1298 1299 3155 1299 1301 3156 1301 1300 3157 1300 1298 3158 1298 1306 3159 1306 1300 3160 1300 1301 3161 1301 1303 3162 1303 1295 3163 1295 1302 3164 1302 1305 3165 1305 1295 3166 1295 1303 3167 1303 1305 3168 1305 1304 3169 1304 1295 3170 1295 1300 3171 1300 1304 3172 1304 1305 3173 1305 1281 3174 1281 1300 3175 1300 1306 3176 1306 1331 3177 1331 1307 3178 1307 1308 3179 1308 1331 3180 1331 1308 3181 1308 1309 3182 1309 1307 3183 1307 1310 3184 1310 1311 3185 1311 1316 3186 1316 1312 3187 1312 1313 3188 1313 1316 3189 1316 1314 3190 1314 1312 3191 1312 1316 3192 1316 1315 3193 1315 1314 3194 1314 1319 3195 1319 1315 3196 1315 1316 3197 1316 1319 3198 1319 1317 3199 1317 1315 3200 1315 1319 3201 1319 1318 3202 1318 1317 3203 1317 1321 3204 1321 1318 3205 1318 1319 3206 1319 1321 3207 1321 1320 3208 1320 1318 3209 1318 1323 3210 1323 1320 3211 1320 1321 3212 1321 1323 3213 1323 1322 3214 1322 1320 3215 1320 1324 3216 1324 1322 3217 1322 1323 3218 1323 1326 3219 1326 1322 3220 1322 1324 3221 1324 1326 3222 1326 1325 3223 1325 1322 3224 1322 1328 3225 1328 1325 3226 1325 1326 3227 1326 1328 3228 1328 1327 3229 1327 1325 3230 1325 1330 3231 1330 1327 3232 1327 1328 3233 1328 1330 3234 1330 1329 3235 1329 1327 3236 1327 1310 3237 1310 1329 3238 1329 1330 3239 1330 1310 3240 1310 1331 3241 1331 1329 3242 1329 1307 3243 1307 1331 3244 1331 1310 3245 1310 1356 3246 1356 1333 3247 1333 1332 3248 1332 1332 3249 1332 1333 3250 1333 1334 3251 1334 1338 3252 1338 1335 3253 1335 1336 3254 1336 1338 3255 1338 1337 3256 1337 1335 3257 1335 1340 3258 1340 1337 3259 1337 1338 3260 1338 1340 3261 1340 1339 3262 1339 1337 3263 1337 1341 3264 1341 1339 3265 1339 1340 3266 1340 1343 3267 1343 1339 3268 1339 1341 3269 1341 1343 3270 1343 1342 3271 1342 1339 3272 1339 1345 3273 1345 1342 3274 1342 1343 3275 1343 1345 3276 1345 1344 3277 1344 1342 3278 1342 1348 3279 1348 1344 3280 1344 1345 3281 1345 1348 3282 1348 1346 3283 1346 1344 3284 1344 1348 3285 1348 1347 3286 1347 1346 3287 1346 1350 3288 1350 1347 3289 1347 1348 3290 1348 1350 3291 1350 1349 3292 1349 1347 3293 1347 1352 3294 1352 1349 3295 1349 1350 3296 1350 1352 3297 1352 1351 3298 1351 1349 3299 1349 1354 3300 1354 1351 3301 1351 1352 3302 1352 1354 3303 1354 1353 3304 1353 1351 3305 1351 1333 3306 1333 1353 3307 1353 1354 3308 1354 1333 3309 1333 1355 3310 1355 1353 3311 1353 1333 3312 1333 1356 3313 1356 1355 3314 1355 1359 3315 1359 1357 3316 1357 1358 3317 1358 1357 3318 1357 1359 3319 1359 1360 3320 1360 1363 3321 1363 1361 3322 1361 1362 3323 1362 1361 3324 1361 1363 3325 1363 1364 3326 1364 1367 3327 1367 1365 3328 1365 1366 3329 1366 1365 3330 1365 1367 3331 1367 1368 3332 1368 1371 3333 1371 1369 3334 1369 1370 3335 1370 1369 3336 1369 1371 3337 1371 1372 3338 1372 1431 3339 1431 1373 3340 1373 1391 3341 1391 1409 3342 1409 1374 3343 1374 1377 3344 1377 1409 3345 1409 1375 3346 1375 1374 3347 1374 1409 3348 1409 1376 3349 1376 1375 3350 1375 1378 3351 1378 1409 3352 1409 1377 3353 1377 1379 3354 1379 1409 3355 1409 1378 3356 1378 1380 3357 1380 1409 3358 1409 1379 3359 1379 1381 3360 1381 1409 3361 1409 1380 3362 1380 1431 3363 1431 1409 3364 1409 1381 3365 1381 1420 3366 1420 1382 3367 1382 1398 3368 1398 1420 3369 1420 1383 3370 1383 1382 3371 1382 1420 3372 1420 1384 3373 1384 1383 3374 1383 1420 3375 1420 1385 3376 1385 1384 3377 1384 1420 3378 1420 1386 3379 1386 1385 3380 1385 1420 3381 1420 1387 3382 1387 1386 3383 1386 1420 3384 1420 1388 3385 1388 1387 3386 1387 1420 3387 1420 1389 3388 1389 1388 3389 1388 1441 3390 1441 1442 3391 1442 1390 3392 1390 1441 3393 1441 1391 3394 1391 1442 3395 1442 1443 3396 1443 1373 3397 1373 1392 3398 1392 1443 3399 1443 1393 3400 1393 1373 3401 1373 1440 3402 1440 1438 3403 1438 1394 3404 1394 1440 3405 1440 1395 3406 1395 1438 3407 1438 1439 3408 1439 1436 3409 1436 1396 3410 1396 1439 3411 1439 1397 3412 1397 1436 3413 1436 1419 3414 1419 1420 3415 1420 1398 3416 1398 1419 3417 1419 1399 3418 1399 1420 3419 1420 1419 3420 1419 1407 3421 1407 1399 3422 1399 1419 3423 1419 1400 3424 1400 1407 3425 1407 1400 3426 1400 1434 3427 1434 1401 3428 1401 1400 3429 1400 1402 3430 1402 1434 3431 1434 1419 3432 1419 1402 3433 1402 1400 3434 1400 1419 3435 1419 1403 3436 1403 1402 3437 1402 1419 3438 1419 1405 3439 1405 1403 3440 1403 1419 3441 1419 1404 3442 1404 1405 3443 1405 1435 3444 1435 1403 3445 1403 1405 3446 1405 1435 3447 1435 1406 3448 1406 1403 3449 1403 1433 3450 1433 1399 3451 1399 1407 3452 1407 1433 3453 1433 1408 3454 1408 1399 3455 1399 1437 3456 1437 1376 3457 1376 1409 3458 1409 1437 3459 1437 1410 3460 1410 1376 3461 1376 1437 3462 1437 1411 3463 1411 1410 3464 1410 1437 3465 1437 1412 3466 1412 1411 3467 1411 1437 3468 1437 1413 3469 1413 1412 3470 1412 1437 3471 1437 1414 3472 1414 1413 3473 1413 1437 3474 1437 1415 3475 1415 1414 3476 1414 1437 3477 1437 1416 3478 1416 1415 3479 1415 1437 3480 1437 1417 3481 1417 1416 3482 1416 1437 3483 1437 1418 3484 1418 1417 3485 1417 1437 3486 1437 1419 3487 1419 1418 3488 1418 1432 3489 1432 1389 3490 1389 1420 3491 1420 1432 3492 1432 1421 3493 1421 1389 3494 1389 1432 3495 1432 1422 3496 1422 1421 3497 1421 1432 3498 1432 1423 3499 1423 1422 3500 1422 1432 3501 1432 1424 3502 1424 1423 3503 1423 1432 3504 1432 1425 3505 1425 1424 3506 1424 1432 3507 1432 1426 3508 1426 1425 3509 1425 1432 3510 1432 1427 3511 1427 1426 3512 1426 1432 3513 1432 1428 3514 1428 1427 3515 1427 1432 3516 1432 1429 3517 1429 1428 3518 1428 1432 3519 1432 1430 3520 1430 1429 3521 1429 1432 3522 1432 1431 3523 1431 1430 3524 1430 1408 3525 1408 1431 3526 1431 1432 3527 1432 1433 3528 1433 1431 3529 1431 1408 3530 1408 1401 3531 1401 1431 3532 1431 1433 3533 1433 1434 3534 1434 1431 3535 1431 1401 3536 1401 1406 3537 1406 1431 3538 1431 1434 3539 1434 1435 3540 1435 1431 3541 1431 1406 3542 1406 1445 3543 1445 1431 3544 1431 1435 3545 1435 1431 3546 1431 1436 3547 1436 1409 3548 1409 1397 3549 1397 1419 3550 1419 1437 3551 1437 1439 3552 1439 1419 3553 1419 1397 3554 1397 1431 3555 1431 1396 3556 1396 1436 3557 1436 1431 3558 1431 1438 3559 1438 1396 3560 1396 1395 3561 1395 1419 3562 1419 1439 3563 1439 1440 3564 1440 1419 3565 1419 1395 3566 1395 1390 3567 1390 1419 3568 1419 1440 3569 1440 1431 3570 1431 1394 3571 1394 1438 3572 1438 1431 3573 1431 1441 3574 1441 1394 3575 1394 1431 3576 1431 1391 3577 1391 1441 3578 1441 1442 3579 1442 1419 3580 1419 1390 3581 1390 1393 3582 1393 1419 3583 1419 1442 3584 1442 1443 3585 1443 1419 3586 1419 1393 3587 1393 1444 3588 1444 1419 3589 1419 1443 3590 1443 1444 3591 1444 1404 3592 1404 1419 3593 1419 1446 3594 1446 1404 3595 1404 1444 3596 1444 1446 3597 1446 1445 3598 1445 1404 3599 1404 1446 3600 1446 1431 3601 1431 1445 3602 1445 1392 3603 1392 1431 3604 1431 1446 3605 1446 1373 3606 1373 1431 3607 1431 1392 3608 1392 1449 3609 1449 1447 3610 1447 1448 3611 1448 1447 3612 1447 1449 3613 1449 1450 3614 1450 1453 3615 1453 1451 3616 1451 1452 3617 1452 1451 3618 1451 1453 3619 1453 1454 3620 1454 1457 3621 1457 1455 3622 1455 1456 3623 1456 1455 3624 1455 1457 3625 1457 1458 3626 1458 1509 3627 1509 1492 3628 1492 1520 3629 1520 1460 3630 1460 1508 3631 1508 1459 3632 1459 1461 3633 1461 1508 3634 1508 1460 3635 1460 1499 3636 1499 1508 3637 1508 1461 3638 1461 1508 3639 1508 1462 3640 1462 1459 3641 1459 1508 3642 1508 1463 3643 1463 1462 3644 1462 1508 3645 1508 1464 3646 1464 1463 3647 1463 1508 3648 1508 1465 3649 1465 1464 3650 1464 1508 3651 1508 1466 3652 1466 1465 3653 1465 1468 3654 1468 1484 3655 1484 1467 3656 1467 1469 3657 1469 1484 3658 1484 1468 3659 1468 1470 3660 1470 1484 3661 1484 1469 3662 1469 1471 3663 1471 1484 3664 1484 1470 3665 1470 1472 3666 1472 1484 3667 1484 1471 3668 1471 1473 3669 1473 1484 3670 1484 1472 3671 1472 1474 3672 1474 1484 3673 1484 1473 3674 1473 1511 3675 1511 1484 3676 1484 1474 3677 1474 1476 3678 1476 1475 3679 1475 1491 3680 1491 1525 3681 1525 1475 3682 1475 1476 3683 1476 1478 3684 1478 1477 3685 1477 1526 3686 1526 1490 3687 1490 1477 3688 1477 1478 3689 1478 1480 3690 1480 1479 3691 1479 1527 3692 1527 1489 3693 1489 1479 3694 1479 1480 3695 1480 1482 3696 1482 1481 3697 1481 1528 3698 1528 1488 3699 1488 1481 3700 1481 1482 3701 1482 1484 3702 1484 1483 3703 1483 1467 3704 1467 1493 3705 1493 1483 3706 1483 1484 3707 1484 1485 3708 1485 1483 3709 1483 1493 3710 1493 1495 3711 1495 1483 3712 1483 1485 3713 1485 1486 3714 1486 1483 3715 1483 1495 3716 1495 1497 3717 1497 1483 3718 1483 1486 3719 1486 1487 3720 1487 1483 3721 1483 1497 3722 1497 1481 3723 1481 1483 3724 1483 1487 3725 1487 1488 3726 1488 1483 3727 1483 1481 3728 1481 1479 3729 1479 1483 3730 1483 1488 3731 1488 1489 3732 1489 1483 3733 1483 1479 3734 1479 1477 3735 1477 1483 3736 1483 1489 3737 1489 1490 3738 1490 1483 3739 1483 1477 3740 1477 1476 3741 1476 1483 3742 1483 1490 3743 1490 1491 3744 1491 1483 3745 1483 1476 3746 1476 1523 3747 1523 1483 3748 1483 1491 3749 1491 1493 3750 1493 1492 3751 1492 1485 3752 1485 1520 3753 1520 1492 3754 1492 1493 3755 1493 1495 3756 1495 1494 3757 1494 1486 3758 1486 1530 3759 1530 1494 3760 1494 1495 3761 1495 1497 3762 1497 1496 3763 1496 1487 3764 1487 1529 3765 1529 1496 3766 1496 1497 3767 1497 1499 3768 1499 1498 3769 1498 1508 3770 1508 1500 3771 1500 1498 3772 1498 1499 3773 1499 1501 3774 1501 1498 3775 1498 1500 3776 1500 1502 3777 1502 1498 3778 1498 1501 3779 1501 1503 3780 1503 1498 3781 1498 1502 3782 1502 1504 3783 1504 1498 3784 1498 1503 3785 1503 1505 3786 1505 1498 3787 1498 1504 3788 1504 1506 3789 1506 1498 3790 1498 1505 3791 1505 1507 3792 1507 1498 3793 1498 1506 3794 1506 1483 3795 1483 1498 3796 1498 1507 3797 1507 1522 3798 1522 1466 3799 1466 1508 3800 1508 1522 3801 1522 1509 3802 1509 1466 3803 1466 1511 3804 1511 1510 3805 1510 1484 3806 1484 1512 3807 1512 1510 3808 1510 1511 3809 1511 1513 3810 1513 1510 3811 1510 1512 3812 1512 1514 3813 1514 1510 3814 1510 1513 3815 1513 1515 3816 1515 1510 3817 1510 1514 3818 1514 1516 3819 1516 1510 3820 1510 1515 3821 1515 1517 3822 1517 1510 3823 1510 1516 3824 1516 1518 3825 1518 1510 3826 1510 1517 3827 1517 1519 3828 1519 1510 3829 1510 1518 3830 1518 1509 3831 1509 1510 3832 1510 1519 3833 1519 1509 3834 1509 1520 3835 1520 1510 3836 1510 1483 3837 1483 1521 3838 1521 1498 3839 1498 1523 3840 1523 1521 3841 1521 1483 3842 1483 1523 3843 1523 1522 3844 1522 1521 3845 1521 1524 3846 1524 1522 3847 1522 1523 3848 1523 1524 3849 1524 1509 3850 1509 1522 3851 1522 1475 3852 1475 1509 3853 1509 1524 3854 1524 1525 3855 1525 1509 3856 1509 1475 3857 1475 1478 3858 1478 1509 3859 1509 1525 3860 1525 1526 3861 1526 1509 3862 1509 1478 3863 1478 1480 3864 1480 1509 3865 1509 1526 3866 1526 1527 3867 1527 1509 3868 1509 1480 3869 1480 1482 3870 1482 1509 3871 1509 1527 3872 1527 1528 3873 1528 1509 3874 1509 1482 3875 1482 1496 3876 1496 1509 3877 1509 1528 3878 1528 1529 3879 1529 1509 3880 1509 1496 3881 1496 1494 3882 1494 1509 3883 1509 1529 3884 1529 1530 3885 1530 1509 3886 1509 1494 3887 1494 1492 3888 1492 1509 3889 1509 1530 3890 1530 1536 3891 1536 1531 3892 1531 1532 3893 1532 1535 3894 1535 1533 3895 1533 1534 3896 1534 1531 3897 1531 1533 3898 1533 1535 3899 1535 1531 3900 1531 1536 3901 1536 1533 3902 1533 1541 3903 1541 1537 3904 1537 1538 3905 1538 1542 3906 1542 1539 3907 1539 1540 3908 1540 1542 3909 1542 1541 3910 1541 1539 3911 1539 1537 3912 1537 1541 3913 1541 1542 3914 1542 1547 3915 1547 1543 3916 1543 1544 3917 1544 1548 3918 1548 1545 3919 1545 1546 3920 1546 1548 3921 1548 1547 3922 1547 1545 3923 1545 1543 3924 1543 1547 3925 1547 1548 3926 1548 1554 3927 1554 1549 3928 1549 1550 3929 1550 1553 3930 1553 1551 3931 1551 1552 3932 1552 1549 3933 1549 1551 3934 1551 1553 3935 1553 1549 3936 1549 1554 3937 1554 1551 3938 1551 1557 3939 1557 1555 3940 1555 1556 3941 1556 1555 3942 1555 1557 3943 1557 1558 3944 1558 1563 3945 1563 1559 3946 1559 1560 3947 1560 1564 3948 1564 1561 3949 1561 1562 3950 1562 1564 3951 1564 1563 3952 1563 1561 3953 1561 1559 3954 1559 1563 3955 1563 1564 3956 1564 1570 3957 1570 1565 3958 1565 1566 3959 1566 1569 3960 1569 1567 3961 1567 1568 3962 1568 1565 3963 1565 1567 3964 1567 1569 3965 1569 1565 3966 1565 1570 3967 1570 1567 3968 1567 1575 3969 1575 1571 3970 1571 1572 3971 1572 1576 3972 1576 1573 3973 1573 1574 3974 1574 1576 3975 1576 1575 3976 1575 1573 3977 1573 1571 3978 1571 1575 3979 1575 1576 3980 1576 1582 3981 1582 1577 3982 1577 1578 3983 1578 1581 3984 1581 1579 3985 1579 1580 3986 1580 1577 3987 1577 1579 3988 1579 1581 3989 1581 1577 3990 1577 1582 3991 1582 1579 3992 1579 1587 3993 1587 1583 3994 1583 1584 3995 1584 1588 3996 1588 1585 3997 1585 1586 3998 1586 1588 3999 1588 1587 4000 1587 1585 4001 1585 1583 4002 1583 1587 4003 1587 1588 4004 1588 1594 4005 1594 1589 4006 1589 1590 4007 1590 1593 4008 1593 1591 4009 1591 1592 4010 1592 1589 4011 1589 1591 4012 1591 1593 4013 1593 1589 4014 1589 1594 4015 1594 1591 4016 1591 1599 4017 1599 1595 4018 1595 1596 4019 1596 1600 4020 1600 1597 4021 1597 1598 4022 1598 1600 4023 1600 1599 4024 1599 1597 4025 1597 1595 4026 1595 1599 4027 1599 1600 4028 1600 1606 4029 1606 1601 4030 1601 1602 4031 1602 1605 4032 1605 1603 4033 1603 1604 4034 1604 1601 4035 1601 1603 4036 1603 1605 4037 1605 1601 4038 1601 1606 4039 1606 1603 4040 1603 1611 4041 1611 1607 4042 1607 1608 4043 1608 1612 4044 1612 1609 4045 1609 1610 4046 1610 1612 4047 1612 1611 4048 1611 1609 4049 1609 1607 4050 1607 1611 4051 1611 1612 4052 1612 1618 4053 1618 1613 4054 1613 1614 4055 1614 1617 4056 1617 1615 4057 1615 1616 4058 1616 1613 4059 1613 1615 4060 1615 1617 4061 1617 1613 4062 1613 1618 4063 1618 1615 4064 1615 1623 4065 1623 1619 4066 1619 1620 4067 1620 1624 4068 1624 1621 4069 1621 1622 4070 1622 1624 4071 1624 1623 4072 1623 1621 4073 1621 1619 4074 1619 1623 4075 1623 1624 4076 1624 1630 4077 1630 1625 4078 1625 1626 4079 1626 1629 4080 1629 1627 4081 1627 1628 4082 1628 1625 4083 1625 1627 4084 1627 1629 4085 1629 1625 4086 1625 1630 4087 1630 1627 4088 1627 1635 4089 1635 1631 4090 1631 1632 4091 1632 1636 4092 1636 1633 4093 1633 1634 4094 1634 1636 4095 1636 1635 4096 1635 1633 4097 1633 1631 4098 1631 1635 4099 1635 1636 4100 1636 1642 4101 1642 1637 4102 1637 1638 4103 1638 1641 4104 1641 1639 4105 1639 1640 4106 1640 1637 4107 1637 1639 4108 1639 1641 4109 1641 1637 4110 1637 1642 4111 1642 1639 4112 1639 1647 4113 1647 1643 4114 1643 1644 4115 1644 1648 4116 1648 1645 4117 1645 1646 4118 1646 1648 4119 1648 1647 4120 1647 1645 4121 1645 1643 4122 1643 1647 4123 1647 1648 4124 1648 1654 4125 1654 1649 4126 1649 1650 4127 1650 1653 4128 1653 1651 4129 1651 1652 4130 1652 1649 4131 1649 1651 4132 1651 1653 4133 1653 1649 4134 1649 1654 4135 1654 1651 4136 1651 1660 4137 1660 1655 4138 1655 1656 4139 1656 1659 4140 1659 1657 4141 1657 1658 4142 1658 1655 4143 1655 1657 4144 1657 1659 4145 1659 1655 4146 1655 1660 4147 1660 1657 4148 1657 1665 4149 1665 1661 4150 1661 1662 4151 1662 1666 4152 1666 1663 4153 1663 1664 4154 1664 1666 4155 1666 1665 4156 1665 1663 4157 1663 1661 4158 1661 1665 4159 1665 1666 4160 1666 1672 4161 1672 1667 4162 1667 1668 4163 1668 1671 4164 1671 1669 4165 1669 1670 4166 1670 1667 4167 1667 1669 4168 1669 1671 4169 1671 1667 4170 1667 1672 4171 1672 1669 4172 1669 1677 4173 1677 1673 4174 1673 1674 4175 1674 1678 4176 1678 1675 4177 1675 1676 4178 1676 1678 4179 1678 1677 4180 1677 1675 4181 1675 1673 4182 1673 1677 4183 1677 1678 4184 1678 1684 4185 1684 1679 4186 1679 1680 4187 1680 1683 4188 1683 1681 4189 1681 1682 4190 1682 1679 4191 1679 1681 4192 1681 1683 4193 1683 1679 4194 1679 1684 4195 1684 1681 4196 1681 1689 4197 1689 1685 4198 1685 1686 4199 1686 1690 4200 1690 1687 4201 1687 1688 4202 1688 1690 4203 1690 1689 4204 1689 1687 4205 1687 1685 4206 1685 1689 4207 1689 1690 4208 1690 1696 4209 1696 1691 4210 1691 1692 4211 1692 1695 4212 1695 1693 4213 1693 1694 4214 1694 1691 4215 1691 1693 4216 1693 1695 4217 1695 1691 4218 1691 1696 4219 1696 1693 4220 1693 1701 4221 1701 1697 4222 1697 1698 4223 1698 1702 4224 1702 1699 4225 1699 1700 4226 1700 1702 4227 1702 1701 4228 1701 1699 4229 1699 1697 4230 1697 1701 4231 1701 1702 4232 1702 1708 4233 1708 1703 4234 1703 1704 4235 1704 1707 4236 1707 1705 4237 1705 1706 4238 1706 1703 4239 1703 1705 4240 1705 1707 4241 1707 1703 4242 1703 1708 4243 1708 1705 4244 1705 1713 4245 1713 1709 4246 1709 1710 4247 1710 1714 4248 1714 1711 4249 1711 1712 4250 1712 1714 4251 1714 1713 4252 1713 1711 4253 1711 1709 4254 1709 1713 4255 1713 1714 4256 1714 1720 4257 1720 1715 4258 1715 1716 4259 1716 1719 4260 1719 1717 4261 1717 1718 4262 1718 1715 4263 1715 1717 4264 1717 1719 4265 1719 1715 4266 1715 1720 4267 1720 1717 4268 1717 1725 4269 1725 1721 4270 1721 1722 4271 1722 1726 4272 1726 1723 4273 1723 1724 4274 1724 1726 4275 1726 1725 4276 1725 1723 4277 1723 1721 4278 1721 1725 4279 1725 1726 4280 1726 1732 4281 1732 1727 4282 1727 1728 4283 1728 1731 4284 1731 1729 4285 1729 1730 4286 1730 1727 4287 1727 1729 4288 1729 1731 4289 1731 1727 4290 1727 1732 4291 1732 1729 4292 1729 1737 4293 1737 1733 4294 1733 1734 4295 1734 1738 4296 1738 1735 4297 1735 1736 4298 1736 1738 4299 1738 1737 4300 1737 1735 4301 1735 1733 4302 1733 1737 4303 1737 1738 4304 1738 1744 4305 1744 1739 4306 1739 1740 4307 1740 1743 4308 1743 1741 4309 1741 1742 4310 1742 1739 4311 1739 1741 4312 1741 1743 4313 1743 1739 4314 1739 1744 4315 1744 1741 4316 1741 1749 4317 1749 1745 4318 1745 1746 4319 1746 1750 4320 1750 1747 4321 1747 1748 4322 1748 1750 4323 1750 1749 4324 1749 1747 4325 1747 1745 4326 1745 1749 4327 1749 1750 4328 1750 1768 4329 1768 1751 4330 1751 1752 4331 1752 1755 4332 1755 1753 4333 1753 1754 4334 1754 1757 4335 1757 1753 4336 1753 1755 4337 1755 1757 4338 1757 1756 4339 1756 1753 4340 1753 1759 4341 1759 1756 4342 1756 1757 4343 1757 1759 4344 1759 1758 4345 1758 1756 4346 1756 1761 4347 1761 1758 4348 1758 1759 4349 1759 1761 4350 1761 1760 4351 1760 1758 4352 1758 1763 4353 1763 1760 4354 1760 1761 4355 1761 1763 4356 1763 1762 4357 1762 1760 4358 1760 1765 4359 1765 1762 4360 1762 1763 4361 1763 1765 4362 1765 1764 4363 1764 1762 4364 1762 1767 4365 1767 1764 4366 1764 1765 4367 1765 1767 4368 1767 1766 4369 1766 1764 4370 1764 1751 4371 1751 1766 4372 1766 1767 4373 1767 1751 4374 1751 1768 4375 1768 1766 4376 1766 1786 4377 1786 1769 4378 1769 1770 4379 1770 1773 4380 1773 1771 4381 1771 1772 4382 1772 1775 4383 1775 1771 4384 1771 1773 4385 1773 1775 4386 1775 1774 4387 1774 1771 4388 1771 1777 4389 1777 1774 4390 1774 1775 4391 1775 1777 4392 1777 1776 4393 1776 1774 4394 1774 1779 4395 1779 1776 4396 1776 1777 4397 1777 1779 4398 1779 1778 4399 1778 1776 4400 1776 1781 4401 1781 1778 4402 1778 1779 4403 1779 1781 4404 1781 1780 4405 1780 1778 4406 1778 1783 4407 1783 1780 4408 1780 1781 4409 1781 1783 4410 1783 1782 4411 1782 1780 4412 1780 1785 4413 1785 1782 4414 1782 1783 4415 1783 1785 4416 1785 1784 4417 1784 1782 4418 1782 1769 4419 1769 1784 4420 1784 1785 4421 1785 1769 4422 1769 1786 4423 1786 1784 4424 1784 1804 4425 1804 1787 4426 1787 1788 4427 1788 1791 4428 1791 1789 4429 1789 1790 4430 1790 1793 4431 1793 1789 4432 1789 1791 4433 1791 1793 4434 1793 1792 4435 1792 1789 4436 1789 1795 4437 1795 1792 4438 1792 1793 4439 1793 1795 4440 1795 1794 4441 1794 1792 4442 1792 1797 4443 1797 1794 4444 1794 1795 4445 1795 1797 4446 1797 1796 4447 1796 1794 4448 1794 1799 4449 1799 1796 4450 1796 1797 4451 1797 1799 4452 1799 1798 4453 1798 1796 4454 1796 1801 4455 1801 1798 4456 1798 1799 4457 1799 1801 4458 1801 1800 4459 1800 1798 4460 1798 1803 4461 1803 1800 4462 1800 1801 4463 1801 1803 4464 1803 1802 4465 1802 1800 4466 1800 1787 4467 1787 1802 4468 1802 1803 4469 1803 1787 4470 1787 1804 4471 1804 1802 4472 1802 1822 4473 1822 1805 4474 1805 1806 4475 1806 1809 4476 1809 1807 4477 1807 1808 4478 1808 1811 4479 1811 1807 4480 1807 1809 4481 1809 1811 4482 1811 1810 4483 1810 1807 4484 1807 1813 4485 1813 1810 4486 1810 1811 4487 1811 1813 4488 1813 1812 4489 1812 1810 4490 1810 1815 4491 1815 1812 4492 1812 1813 4493 1813 1815 4494 1815 1814 4495 1814 1812 4496 1812 1817 4497 1817 1814 4498 1814 1815 4499 1815 1817 4500 1817 1816 4501 1816 1814 4502 1814 1819 4503 1819 1816 4504 1816 1817 4505 1817 1819 4506 1819 1818 4507 1818 1816 4508 1816 1821 4509 1821 1818 4510 1818 1819 4511 1819 1821 4512 1821 1820 4513 1820 1818 4514 1818 1805 4515 1805 1820 4516 1820 1821 4517 1821 1805 4518 1805 1822 4519 1822 1820 4520 1820 1840 4521 1840 1823 4522 1823 1824 4523 1824 1827 4524 1827 1825 4525 1825 1826 4526 1826 1829 4527 1829 1825 4528 1825 1827 4529 1827 1829 4530 1829 1828 4531 1828 1825 4532 1825 1831 4533 1831 1828 4534 1828 1829 4535 1829 1831 4536 1831 1830 4537 1830 1828 4538 1828 1833 4539 1833 1830 4540 1830 1831 4541 1831 1833 4542 1833 1832 4543 1832 1830 4544 1830 1835 4545 1835 1832 4546 1832 1833 4547 1833 1835 4548 1835 1834 4549 1834 1832 4550 1832 1837 4551 1837 1834 4552 1834 1835 4553 1835 1837 4554 1837 1836 4555 1836 1834 4556 1834 1839 4557 1839 1836 4558 1836 1837 4559 1837 1839 4560 1839 1838 4561 1838 1836 4562 1836 1823 4563 1823 1838 4564 1838 1839 4565 1839 1823 4566 1823 1840 4567 1840 1838 4568 1838 1858 4569 1858 1841 4570 1841 1842 4571 1842 1845 4572 1845 1843 4573 1843 1844 4574 1844 1847 4575 1847 1843 4576 1843 1845 4577 1845 1847 4578 1847 1846 4579 1846 1843 4580 1843 1849 4581 1849 1846 4582 1846 1847 4583 1847 1849 4584 1849 1848 4585 1848 1846 4586 1846 1851 4587 1851 1848 4588 1848 1849 4589 1849 1851 4590 1851 1850 4591 1850 1848 4592 1848 1853 4593 1853 1850 4594 1850 1851 4595 1851 1853 4596 1853 1852 4597 1852 1850 4598 1850 1855 4599 1855 1852 4600 1852 1853 4601 1853 1855 4602 1855 1854 4603 1854 1852 4604 1852 1857 4605 1857 1854 4606 1854 1855 4607 1855 1857 4608 1857 1856 4609 1856 1854 4610 1854 1841 4611 1841 1856 4612 1856 1857 4613 1857 1841 4614 1841 1858 4615 1858 1856 4616 1856 1876 4617 1876 1859 4618 1859 1860 4619 1860 1863 4620 1863 1861 4621 1861 1862 4622 1862 1865 4623 1865 1861 4624 1861 1863 4625 1863 1865 4626 1865 1864 4627 1864 1861 4628 1861 1867 4629 1867 1864 4630 1864 1865 4631 1865 1867 4632 1867 1866 4633 1866 1864 4634 1864 1869 4635 1869 1866 4636 1866 1867 4637 1867 1869 4638 1869 1868 4639 1868 1866 4640 1866 1871 4641 1871 1868 4642 1868 1869 4643 1869 1871 4644 1871 1870 4645 1870 1868 4646 1868 1873 4647 1873 1870 4648 1870 1871 4649 1871 1873 4650 1873 1872 4651 1872 1870 4652 1870 1875 4653 1875 1872 4654 1872 1873 4655 1873 1875 4656 1875 1874 4657 1874 1872 4658 1872 1859 4659 1859 1874 4660 1874 1875 4661 1875 1859 4662 1859 1876 4663 1876 1874 4664 1874 1894 4665 1894 1877 4666 1877 1878 4667 1878 1881 4668 1881 1879 4669 1879 1880 4670 1880 1883 4671 1883 1879 4672 1879 1881 4673 1881 1883 4674 1883 1882 4675 1882 1879 4676 1879 1885 4677 1885 1882 4678 1882 1883 4679 1883 1885 4680 1885 1884 4681 1884 1882 4682 1882 1887 4683 1887 1884 4684 1884 1885 4685 1885 1887 4686 1887 1886 4687 1886 1884 4688 1884 1889 4689 1889 1886 4690 1886 1887 4691 1887 1889 4692 1889 1888 4693 1888 1886 4694 1886 1891 4695 1891 1888 4696 1888 1889 4697 1889 1891 4698 1891 1890 4699 1890 1888 4700 1888 1893 4701 1893 1890 4702 1890 1891 4703 1891 1893 4704 1893 1892 4705 1892 1890 4706 1890 1877 4707 1877 1892 4708 1892 1893 4709 1893 1877 4710 1877 1894 4711 1894 1892 4712 1892 1912 4713 1912 1895 4714 1895 1896 4715 1896 1899 4716 1899 1897 4717 1897 1898 4718 1898 1901 4719 1901 1897 4720 1897 1899 4721 1899 1901 4722 1901 1900 4723 1900 1897 4724 1897 1903 4725 1903 1900 4726 1900 1901 4727 1901 1903 4728 1903 1902 4729 1902 1900 4730 1900 1905 4731 1905 1902 4732 1902 1903 4733 1903 1905 4734 1905 1904 4735 1904 1902 4736 1902 1907 4737 1907 1904 4738 1904 1905 4739 1905 1907 4740 1907 1906 4741 1906 1904 4742 1904 1909 4743 1909 1906 4744 1906 1907 4745 1907 1909 4746 1909 1908 4747 1908 1906 4748 1906 1911 4749 1911 1908 4750 1908 1909 4751 1909 1911 4752 1911 1910 4753 1910 1908 4754 1908 1895 4755 1895 1910 4756 1910 1911 4757 1911 1895 4758 1895 1912 4759 1912 1910 4760 1910 1929 4761 1929 1913 4762 1913 1914 4763 1914 1918 4764 1918 1915 4765 1915 1916 4766 1916 1918 4767 1918 1917 4768 1917 1915 4769 1915 1920 4770 1920 1917 4771 1917 1918 4772 1918 1920 4773 1920 1919 4774 1919 1917 4775 1917 1922 4776 1922 1919 4777 1919 1920 4778 1920 1922 4779 1922 1921 4780 1921 1919 4781 1919 1924 4782 1924 1921 4783 1921 1922 4784 1922 1924 4785 1924 1923 4786 1923 1921 4787 1921 1926 4788 1926 1923 4789 1923 1924 4790 1924 1926 4791 1926 1925 4792 1925 1923 4793 1923 1928 4794 1928 1925 4795 1925 1926 4796 1926 1928 4797 1928 1927 4798 1927 1925 4799 1925 1930 4800 1930 1927 4801 1927 1928 4802 1928 1930 4803 1930 1929 4804 1929 1927 4805 1927 1913 4806 1913 1929 4807 1929 1930 4808 1930 1947 4809 1947 1931 4810 1931 1932 4811 1932 1936 4812 1936 1933 4813 1933 1934 4814 1934 1936 4815 1936 1935 4816 1935 1933 4817 1933 1938 4818 1938 1935 4819 1935 1936 4820 1936 1938 4821 1938 1937 4822 1937 1935 4823 1935 1940 4824 1940 1937 4825 1937 1938 4826 1938 1940 4827 1940 1939 4828 1939 1937 4829 1937 1942 4830 1942 1939 4831 1939 1940 4832 1940 1942 4833 1942 1941 4834 1941 1939 4835 1939 1944 4836 1944 1941 4837 1941 1942 4838 1942 1944 4839 1944 1943 4840 1943 1941 4841 1941 1946 4842 1946 1943 4843 1943 1944 4844 1944 1946 4845 1946 1945 4846 1945 1943 4847 1943 1948 4848 1948 1945 4849 1945 1946 4850 1946 1948 4851 1948 1947 4852 1947 1945 4853 1945 1931 4854 1931 1947 4855 1947 1948 4856 1948 1965 4857 1965 1949 4858 1949 1950 4859 1950 1954 4860 1954 1951 4861 1951 1952 4862 1952 1954 4863 1954 1953 4864 1953 1951 4865 1951 1956 4866 1956 1953 4867 1953 1954 4868 1954 1956 4869 1956 1955 4870 1955 1953 4871 1953 1958 4872 1958 1955 4873 1955 1956 4874 1956 1958 4875 1958 1957 4876 1957 1955 4877 1955 1960 4878 1960 1957 4879 1957 1958 4880 1958 1960 4881 1960 1959 4882 1959 1957 4883 1957 1962 4884 1962 1959 4885 1959 1960 4886 1960 1962 4887 1962 1961 4888 1961 1959 4889 1959 1964 4890 1964 1961 4891 1961 1962 4892 1962 1964 4893 1964 1963 4894 1963 1961 4895 1961 1966 4896 1966 1963 4897 1963 1964 4898 1964 1966 4899 1966 1965 4900 1965 1963 4901 1963 1949 4902 1949 1965 4903 1965 1966 4904 1966 1983 4905 1983 1967 4906 1967 1968 4907 1968 1972 4908 1972 1969 4909 1969 1970 4910 1970 1972 4911 1972 1971 4912 1971 1969 4913 1969 1974 4914 1974 1971 4915 1971 1972 4916 1972 1974 4917 1974 1973 4918 1973 1971 4919 1971 1976 4920 1976 1973 4921 1973 1974 4922 1974 1976 4923 1976 1975 4924 1975 1973 4925 1973 1978 4926 1978 1975 4927 1975 1976 4928 1976 1978 4929 1978 1977 4930 1977 1975 4931 1975 1980 4932 1980 1977 4933 1977 1978 4934 1978 1980 4935 1980 1979 4936 1979 1977 4937 1977 1982 4938 1982 1979 4939 1979 1980 4940 1980 1982 4941 1982 1981 4942 1981 1979 4943 1979 1984 4944 1984 1981 4945 1981 1982 4946 1982 1984 4947 1984 1983 4948 1983 1981 4949 1981 1967 4950 1967 1983 4951 1983 1984 4952 1984 2001 4953 2001 1985 4954 1985 1986 4955 1986 1990 4956 1990 1987 4957 1987 1988 4958 1988 1990 4959 1990 1989 4960 1989 1987 4961 1987 1992 4962 1992 1989 4963 1989 1990 4964 1990 1992 4965 1992 1991 4966 1991 1989 4967 1989 1994 4968 1994 1991 4969 1991 1992 4970 1992 1994 4971 1994 1993 4972 1993 1991 4973 1991 1996 4974 1996 1993 4975 1993 1994 4976 1994 1996 4977 1996 1995 4978 1995 1993 4979 1993 1998 4980 1998 1995 4981 1995 1996 4982 1996 1998 4983 1998 1997 4984 1997 1995 4985 1995 2000 4986 2000 1997 4987 1997 1998 4988 1998 2000 4989 2000 1999 4990 1999 1997 4991 1997 2002 4992 2002 1999 4993 1999 2000 4994 2000 2002 4995 2002 2001 4996 2001 1999 4997 1999 1985 4998 1985 2001 4999 2001 2002 5000 2002 2019 5001 2019 2003 5002 2003 2004 5003 2004 2008 5004 2008 2005 5005 2005 2006 5006 2006 2008 5007 2008 2007 5008 2007 2005 5009 2005 2010 5010 2010 2007 5011 2007 2008 5012 2008 2010 5013 2010 2009 5014 2009 2007 5015 2007 2012 5016 2012 2009 5017 2009 2010 5018 2010 2012 5019 2012 2011 5020 2011 2009 5021 2009 2014 5022 2014 2011 5023 2011 2012 5024 2012 2014 5025 2014 2013 5026 2013 2011 5027 2011 2016 5028 2016 2013 5029 2013 2014 5030 2014 2016 5031 2016 2015 5032 2015 2013 5033 2013 2018 5034 2018 2015 5035 2015 2016 5036 2016 2018 5037 2018 2017 5038 2017 2015 5039 2015 2020 5040 2020 2017 5041 2017 2018 5042 2018 2020 5043 2020 2019 5044 2019 2017 5045 2017 2003 5046 2003 2019 5047 2019 2020 5048 2020 2037 5049 2037 2021 5050 2021 2022 5051 2022 2026 5052 2026 2023 5053 2023 2024 5054 2024 2026 5055 2026 2025 5056 2025 2023 5057 2023 2028 5058 2028 2025 5059 2025 2026 5060 2026 2028 5061 2028 2027 5062 2027 2025 5063 2025 2030 5064 2030 2027 5065 2027 2028 5066 2028 2030 5067 2030 2029 5068 2029 2027 5069 2027 2032 5070 2032 2029 5071 2029 2030 5072 2030 2032 5073 2032 2031 5074 2031 2029 5075 2029 2034 5076 2034 2031 5077 2031 2032 5078 2032 2034 5079 2034 2033 5080 2033 2031 5081 2031 2036 5082 2036 2033 5083 2033 2034 5084 2034 2036 5085 2036 2035 5086 2035 2033 5087 2033 2038 5088 2038 2035 5089 2035 2036 5090 2036 2038 5091 2038 2037 5092 2037 2035 5093 2035 2021 5094 2021 2037 5095 2037 2038 5096 2038 2055 5097 2055 2039 5098 2039 2040 5099 2040 2044 5100 2044 2041 5101 2041 2042 5102 2042 2044 5103 2044 2043 5104 2043 2041 5105 2041 2046 5106 2046 2043 5107 2043 2044 5108 2044 2046 5109 2046 2045 5110 2045 2043 5111 2043 2048 5112 2048 2045 5113 2045 2046 5114 2046 2048 5115 2048 2047 5116 2047 2045 5117 2045 2050 5118 2050 2047 5119 2047 2048 5120 2048 2050 5121 2050 2049 5122 2049 2047 5123 2047 2052 5124 2052 2049 5125 2049 2050 5126 2050 2052 5127 2052 2051 5128 2051 2049 5129 2049 2054 5130 2054 2051 5131 2051 2052 5132 2052 2054 5133 2054 2053 5134 2053 2051 5135 2051 2056 5136 2056 2053 5137 2053 2054 5138 2054 2056 5139 2056 2055 5140 2055 2053 5141 2053 2039 5142 2039 2055 5143 2055 2056 5144 2056 2073 5145 2073 2057 5146 2057 2058 5147 2058 2062 5148 2062 2059 5149 2059 2060 5150 2060 2062 5151 2062 2061 5152 2061 2059 5153 2059 2064 5154 2064 2061 5155 2061 2062 5156 2062 2064 5157 2064 2063 5158 2063 2061 5159 2061 2066 5160 2066 2063 5161 2063 2064 5162 2064 2066 5163 2066 2065 5164 2065 2063 5165 2063 2068 5166 2068 2065 5167 2065 2066 5168 2066 2068 5169 2068 2067 5170 2067 2065 5171 2065 2070 5172 2070 2067 5173 2067 2068 5174 2068 2070 5175 2070 2069 5176 2069 2067 5177 2067 2072 5178 2072 2069 5179 2069 2070 5180 2070 2072 5181 2072 2071 5182 2071 2069 5183 2069 2074 5184 2074 2071 5185 2071 2072 5186 2072 2074 5187 2074 2073 5188 2073 2071 5189 2071 2057 5190 2057 2073 5191 2073 2074 5192 2074 2093 5193 2093 2075 5194 2075 2076 5195 2076 2079 5196 2079 2077 5197 2077 2078 5198 2078 2080 5199 2080 2077 5200 2077 2079 5201 2079 2082 5202 2082 2077 5203 2077 2080 5204 2080 2082 5205 2082 2081 5206 2081 2077 5207 2077 2084 5208 2084 2081 5209 2081 2082 5210 2082 2084 5211 2084 2083 5212 2083 2081 5213 2081 2086 5214 2086 2083 5215 2083 2084 5216 2084 2086 5217 2086 2085 5218 2085 2083 5219 2083 2088 5220 2088 2085 5221 2085 2086 5222 2086 2088 5223 2088 2087 5224 2087 2085 5225 2085 2090 5226 2090 2087 5227 2087 2088 5228 2088 2090 5229 2090 2089 5230 2089 2087 5231 2087 2092 5232 2092 2089 5233 2089 2090 5234 2090 2092 5235 2092 2091 5236 2091 2089 5237 2089 2094 5238 2094 2091 5239 2091 2092 5240 2092 2094 5241 2094 2093 5242 2093 2091 5243 2091 2075 5244 2075 2093 5245 2093 2094 5246 2094 2116 5247 2116 2095 5248 2095 2096 5249 2096 2101 5250 2101 2097 5251 2097 2098 5252 2098 2101 5253 2101 2099 5254 2099 2097 5255 2097 2101 5256 2101 2100 5257 2100 2099 5258 2099 2103 5259 2103 2100 5260 2100 2101 5261 2101 2103 5262 2103 2102 5263 2102 2100 5264 2100 2105 5265 2105 2102 5266 2102 2103 5267 2103 2105 5268 2105 2104 5269 2104 2102 5270 2102 2107 5271 2107 2104 5272 2104 2105 5273 2105 2107 5274 2107 2106 5275 2106 2104 5276 2104 2109 5277 2109 2106 5278 2106 2107 5279 2107 2109 5280 2109 2108 5281 2108 2106 5282 2106 2111 5283 2111 2108 5284 2108 2109 5285 2109 2111 5286 2111 2110 5287 2110 2108 5288 2108 2113 5289 2113 2110 5290 2110 2111 5291 2111 2113 5292 2113 2112 5293 2112 2110 5294 2110 2115 5295 2115 2112 5296 2112 2113 5297 2113 2115 5298 2115 2114 5299 2114 2112 5300 2112 2095 5301 2095 2114 5302 2114 2115 5303 2115 2095 5304 2095 2116 5305 2116 2114 5306 2114 2145 5307 2145 2117 5308 2117 2118 5309 2118 2123 5310 2123 2119 5311 2119 2120 5312 2120 2123 5313 2123 2121 5314 2121 2119 5315 2119 2123 5316 2123 2122 5317 2122 2121 5318 2121 2140 5319 2140 2122 5320 2122 2123 5321 2123 2127 5322 2127 2124 5323 2124 2125 5324 2125 2127 5325 2127 2126 5326 2126 2124 5327 2124 2129 5328 2129 2126 5329 2126 2127 5330 2127 2129 5331 2129 2128 5332 2128 2126 5333 2126 2131 5334 2131 2128 5335 2128 2129 5336 2129 2131 5337 2131 2130 5338 2130 2128 5339 2128 2133 5340 2133 2130 5341 2130 2131 5342 2131 2133 5343 2133 2132 5344 2132 2130 5345 2130 2135 5346 2135 2132 5347 2132 2133 5348 2133 2135 5349 2135 2134 5350 2134 2132 5351 2132 2137 5352 2137 2134 5353 2134 2135 5354 2135 2137 5355 2137 2136 5356 2136 2134 5357 2134 2139 5358 2139 2136 5359 2136 2137 5360 2137 2139 5361 2139 2138 5362 2138 2136 5363 2136 2142 5364 2142 2138 5365 2138 2139 5366 2139 2142 5367 2142 2140 5368 2140 2138 5369 2138 2142 5370 2142 2122 5371 2122 2140 5372 2140 2142 5373 2142 2141 5374 2141 2122 5375 2122 2146 5376 2146 2141 5377 2141 2142 5378 2142 2146 5379 2146 2143 5380 2143 2141 5381 2141 2146 5382 2146 2144 5383 2144 2143 5384 2143 2146 5385 2146 2145 5386 2145 2144 5387 2144 2117 5388 2117 2145 5389 2145 2146 5390 2146 2166 5391 2166 2147 5392 2147 2148 5393 2148 2152 5394 2152 2149 5395 2149 2150 5396 2150 2152 5397 2152 2151 5398 2151 2149 5399 2149 2153 5400 2153 2151 5401 2151 2152 5402 2152 2155 5403 2155 2151 5404 2151 2153 5405 2153 2155 5406 2155 2154 5407 2154 2151 5408 2151 2157 5409 2157 2154 5410 2154 2155 5411 2155 2157 5412 2157 2156 5413 2156 2154 5414 2154 2159 5415 2159 2156 5416 2156 2157 5417 2157 2159 5418 2159 2158 5419 2158 2156 5420 2156 2161 5421 2161 2158 5422 2158 2159 5423 2159 2161 5424 2161 2160 5425 2160 2158 5426 2158 2163 5427 2163 2160 5428 2160 2161 5429 2161 2163 5430 2163 2162 5431 2162 2160 5432 2160 2165 5433 2165 2162 5434 2162 2163 5435 2163 2165 5436 2165 2164 5437 2164 2162 5438 2162 2147 5439 2147 2164 5440 2164 2165 5441 2165 2147 5442 2147 2166 5443 2166 2164 5444 2164 2187 5445 2187 2167 5446 2167 2168 5447 2168 2172 5448 2172 2169 5449 2169 2170 5450 2170 2172 5451 2172 2171 5452 2171 2169 5453 2169 2174 5454 2174 2171 5455 2171 2172 5456 2172 2174 5457 2174 2173 5458 2173 2171 5459 2171 2176 5460 2176 2173 5461 2173 2174 5462 2174 2176 5463 2176 2175 5464 2175 2173 5465 2173 2178 5466 2178 2175 5467 2175 2176 5468 2176 2178 5469 2178 2177 5470 2177 2175 5471 2175 2180 5472 2180 2177 5473 2177 2178 5474 2178 2180 5475 2180 2179 5476 2179 2177 5477 2177 2182 5478 2182 2179 5479 2179 2180 5480 2180 2182 5481 2182 2181 5482 2181 2179 5483 2179 2184 5484 2184 2181 5485 2181 2182 5486 2182 2184 5487 2184 2183 5488 2183 2181 5489 2181 2186 5490 2186 2183 5491 2183 2184 5492 2184 2186 5493 2186 2185 5494 2185 2183 5495 2183 2188 5496 2188 2185 5497 2185 2186 5498 2186 2188 5499 2188 2187 5500 2187 2185 5501 2185 2167 5502 2167 2187 5503 2187 2188 5504 2188 2218 5505 2218 2189 5506 2189 2190 5507 2190 2193 5508 2193 2191 5509 2191 2192 5510 2192 2194 5511 2194 2191 5512 2191 2193 5513 2193 2213 5514 2213 2191 5515 2191 2194 5516 2194 2213 5517 2213 2195 5518 2195 2191 5519 2191 2198 5520 2198 2196 5521 2196 2197 5522 2197 2200 5523 2200 2196 5524 2196 2198 5525 2198 2200 5526 2200 2199 5527 2199 2196 5528 2196 2202 5529 2202 2199 5530 2199 2200 5531 2200 2202 5532 2202 2201 5533 2201 2199 5534 2199 2204 5535 2204 2201 5536 2201 2202 5537 2202 2204 5538 2204 2203 5539 2203 2201 5540 2201 2206 5541 2206 2203 5542 2203 2204 5543 2204 2206 5544 2206 2205 5545 2205 2203 5546 2203 2208 5547 2208 2205 5548 2205 2206 5549 2206 2208 5550 2208 2207 5551 2207 2205 5552 2205 2210 5553 2210 2207 5554 2207 2208 5555 2208 2210 5556 2210 2209 5557 2209 2207 5558 2207 2212 5559 2212 2209 5560 2209 2210 5561 2210 2212 5562 2212 2211 5563 2211 2209 5564 2209 2195 5565 2195 2211 5566 2211 2212 5567 2212 2213 5568 2213 2211 5569 2211 2195 5570 2195 2215 5571 2215 2211 5572 2211 2213 5573 2213 2215 5574 2215 2214 5575 2214 2211 5576 2211 2216 5577 2216 2214 5578 2214 2215 5579 2215 2217 5580 2217 2214 5581 2214 2216 5582 2216 2189 5583 2189 2214 5584 2214 2217 5585 2217 2189 5586 2189 2218 5587 2218 2214 5588 2214 2237 5589 4325 2219 5590 4326 2220 5591 4327 2225 5592 4328 2221 5593 4329 2222 5594 4330 2225 5595 4328 2223 5596 4331 2221 5597 4329 2225 5598 4328 2224 5599 4332 2223 5600 4331 2238 5601 4333 2224 5602 4332 2225 5603 4328 2238 5604 4333 2226 5605 4334 2224 5606 4332 2238 5607 4333 2227 5608 4335 2226 5609 4334 2238 5610 4333 2228 5611 4336 2227 5612 4335 2238 5613 4333 2229 5614 4337 2228 5615 4336 2238 5616 4333 2230 5617 4338 2229 5618 4337 2238 5619 4333 2231 5620 4339 2230 5621 4338 2238 5622 4333 2232 5623 4340 2231 5624 4339 2238 5625 4333 2233 5626 4341 2232 5627 4340 2238 5628 4333 2234 5629 4342 2233 5630 4341 2238 5631 4333 2235 5632 4343 2234 5633 4342 2238 5634 4333 2236 5635 4344 2235 5636 4343 2238 5637 4333 2237 5638 4325 2236 5639 4344 2239 5640 4345 2237 5641 4325 2238 5642 4333 2240 5643 4346 2237 5644 4325 2239 5645 4345 2241 5646 4347 2237 5647 4325 2240 5648 4346 2242 5649 4348 2237 5650 4325 2241 5651 4347 2243 5652 4349 2237 5653 4325 2242 5654 4348 2244 5655 4350 2237 5656 4325 2243 5657 4349 2245 5658 4351 2237 5659 4325 2244 5660 4350 2246 5661 4352 2237 5662 4325 2245 5663 4351 2247 5664 4353 2237 5665 4325 2246 5666 4352 2248 5667 4354 2237 5668 4325 2247 5669 4353 2249 5670 4355 2237 5671 4325 2248 5672 4354 2250 5673 4356 2237 5674 4325 2249 5675 4355 2251 5676 4357 2237 5677 4325 2250 5678 4356 2252 5679 4358 2237 5680 4325 2251 5681 4357 2219 5682 4326 2237 5683 4325 2252 5684 4358 2260 5685 2226 2253 5686 2219 2254 5687 2220 2258 5688 2224 2255 5689 2221 2256 5690 2222 2258 5691 2224 2257 5692 2223 2255 5693 2221 2261 5694 2227 2257 5695 2223 2258 5696 2224 2261 5697 2227 2259 5698 2225 2257 5699 2223 2261 5700 2227 2260 5701 2226 2259 5702 2225 2262 5703 2228 2260 5704 2226 2261 5705 2227 2253 5706 2219 2260 5707 2226 2262 5708 2228 2302 5709 2268 2263 5710 2229 2264 5711 2230 2303 5712 2269 2265 5713 2231 2263 5714 2229 2304 5715 2270 2265 5716 2231 2303 5717 2269 2300 5718 2266 2266 5719 2232 2267 5720 2233 2305 5721 2271 2265 5722 2231 2304 5723 2270 2305 5724 2271 2268 5725 2234 2265 5726 2231 2306 5727 2272 2268 5728 2234 2305 5729 2271 2306 5730 2272 2269 5731 2235 2268 5732 2234 2307 5733 2273 2269 5734 2235 2306 5735 2272 2307 5736 2273 2270 5737 2236 2269 5738 2235 2308 5739 2274 2270 5740 2236 2307 5741 2273 2308 5742 2274 2271 5743 2237 2270 5744 2236 2309 5745 2275 2271 5746 2237 2308 5747 2274 2309 5748 2275 2272 5749 2238 2271 5750 2237 2310 5751 2276 2272 5752 2238 2309 5753 2275 2310 5754 2276 2273 5755 2239 2272 5756 2238 2311 5757 2277 2273 5758 2239 2310 5759 2276 2311 5760 2277 2274 5761 2240 2273 5762 2239 2312 5763 2278 2274 5764 2240 2311 5765 2277 2312 5766 2278 2275 5767 2241 2274 5768 2240 2313 5769 2279 2275 5770 2241 2312 5771 2278 2313 5772 2279 2276 5773 2242 2275 5774 2241 2314 5775 2280 2276 5776 2242 2313 5777 2279 2314 5778 2280 2277 5779 2243 2276 5780 2242 2315 5781 2281 2277 5782 2243 2314 5783 2280 2315 5784 2281 2278 5785 2244 2277 5786 2243 2315 5787 2281 2279 5788 2245 2278 5789 2244 2316 5790 2282 2279 5791 2245 2315 5792 2281 2316 5793 2282 2280 5794 2246 2279 5795 2245 2317 5796 2283 2280 5797 2246 2316 5798 2282 2317 5799 2283 2281 5800 2247 2280 5801 2246 2317 5802 2283 2282 5803 2248 2281 5804 2247 2317 5805 2283 2283 5806 2249 2282 5807 2248 2318 5808 2284 2283 5809 2249 2317 5810 2283 2318 5811 2284 2284 5812 2250 2283 5813 2249 2319 5814 2285 2284 5815 2250 2318 5816 2284 2319 5817 2285 2285 5818 2251 2284 5819 2250 2319 5820 2285 2286 5821 2252 2285 5822 2251 2320 5823 2286 2286 5824 2252 2319 5825 2285 2320 5826 2286 2287 5827 2253 2286 5828 2252 2321 5829 2287 2287 5830 2253 2320 5831 2286 2321 5832 2287 2288 5833 2254 2287 5834 2253 2322 5835 2288 2288 5836 2254 2321 5837 2287 2322 5838 2288 2289 5839 2255 2288 5840 2254 2323 5841 2289 2289 5842 2255 2322 5843 2288 2323 5844 2289 2290 5845 2256 2289 5846 2255 2324 5847 2290 2290 5848 2256 2323 5849 2289 2324 5850 2290 2291 5851 2257 2290 5852 2256 2325 5853 2291 2291 5854 2257 2324 5855 2290 2325 5856 2291 2292 5857 2258 2291 5858 2257 2326 5859 2292 2292 5860 2258 2325 5861 2291 2326 5862 2292 2293 5863 2259 2292 5864 2258 2327 5865 2293 2293 5866 2259 2326 5867 2292 2327 5868 2293 2294 5869 2260 2293 5870 2259 2328 5871 2294 2294 5872 2260 2327 5873 2293 2328 5874 2294 2295 5875 2261 2294 5876 2260 2329 5877 2295 2295 5878 2261 2328 5879 2294 2329 5880 2295 2296 5881 2262 2295 5882 2261 2330 5883 2296 2296 5884 2262 2329 5885 2295 2330 5886 2296 2297 5887 2263 2296 5888 2262 2331 5889 2297 2297 5890 2263 2330 5891 2296 2331 5892 2297 2298 5893 2264 2297 5894 2263 2332 5895 2298 2298 5896 2264 2331 5897 2297 2332 5898 2298 2299 5899 2265 2298 5900 2264 2333 5901 2299 2299 5902 2265 2332 5903 2298 2333 5904 2299 2300 5905 2266 2299 5906 2265 2333 5907 2299 2266 5908 2232 2300 5909 2266 2333 5910 2299 2301 5911 2267 2266 5912 2232 2334 5913 2300 2301 5914 2267 2333 5915 2299 2303 5916 2269 2301 5917 2267 2334 5918 2300 2303 5919 2269 2302 5920 2268 2301 5921 2267 2263 5922 2229 2302 5923 2268 2303 5924 2269 2319 5925 2285 2335 5926 2301 2320 5927 2286 2335 5928 2301 2319 5929 2285 2318 5930 2284 2320 5931 2286 2336 5932 2302 2321 5933 2287 2336 5934 2302 2320 5935 2286 2335 5936 2301 2321 5937 2287 2337 5938 2303 2322 5939 2288 2337 5940 2303 2321 5941 2287 2336 5942 2302 2318 5943 2284 2316 5944 2282 2335 5945 2301 2316 5946 2282 2318 5947 2284 2317 5948 2283 2335 5949 2301 2315 5950 2281 2336 5951 2302 2315 5952 2281 2335 5953 2301 2316 5954 2282 2336 5955 2302 2314 5956 2280 2337 5957 2303 2314 5958 2280 2336 5959 2302 2315 5960 2281 2322 5961 2288 2338 5962 2304 2323 5963 2289 2338 5964 2304 2322 5965 2288 2337 5966 2303 2323 5967 2289 2339 5968 2305 2324 5969 2290 2339 5970 2305 2323 5971 2289 2338 5972 2304 2324 5973 2290 2340 5974 2306 2325 5975 2291 2340 5976 2306 2324 5977 2290 2339 5978 2305 2325 5979 2291 2341 5980 2307 2326 5981 2292 2341 5982 2307 2325 5983 2291 2340 5984 2306 2337 5985 2303 2313 5986 2279 2338 5987 2304 2313 5988 2279 2337 5989 2303 2314 5990 2280 2338 5991 2304 2312 5992 2278 2339 5993 2305 2312 5994 2278 2338 5995 2304 2313 5996 2279 2339 5997 2305 2311 5998 2277 2340 5999 2306 2311 6000 2277 2339 6001 2305 2312 6002 2278 2340 6003 2306 2310 6004 2276 2341 6005 2307 2310 6006 2276 2340 6007 2306 2311 6008 2277 2326 6009 2292 2342 6010 2308 2327 6011 2293 2342 6012 2308 2326 6013 2292 2341 6014 2307 2327 6015 2293 2343 6016 2309 2328 6017 2294 2343 6018 2309 2327 6019 2293 2342 6020 2308 2328 6021 2294 2344 6022 2310 2329 6023 2295 2344 6024 2310 2328 6025 2294 2343 6026 2309 2329 6027 2295 2345 6028 2311 2330 6029 2296 2345 6030 2311 2329 6031 2295 2344 6032 2310 2341 6033 2307 2309 6034 2275 2342 6035 2308 2309 6036 2275 2341 6037 2307 2310 6038 2276 2342 6039 2308 2308 6040 2274 2343 6041 2309 2308 6042 2274 2342 6043 2308 2309 6044 2275 2343 6045 2309 2307 6046 2273 2344 6047 2310 2307 6048 2273 2343 6049 2309 2308 6050 2274 2344 6051 2310 2306 6052 2272 2345 6053 2311 2306 6054 2272 2344 6055 2310 2307 6056 2273 2330 6057 2296 2346 6058 2312 2331 6059 2297 2346 6060 2312 2330 6061 2296 2345 6062 2311 2331 6063 2297 2347 6064 2313 2332 6065 2298 2347 6066 2313 2331 6067 2297 2346 6068 2312 2332 6069 2298 2334 6070 2300 2333 6071 2299 2334 6072 2300 2332 6073 2298 2347 6074 2313 2345 6075 2311 2305 6076 2271 2346 6077 2312 2305 6078 2271 2345 6079 2311 2306 6080 2272 2346 6081 2312 2304 6082 2270 2347 6083 2313 2304 6084 2270 2346 6085 2312 2305 6086 2271 2347 6087 2313 2303 6088 2269 2334 6089 2300 2303 6090 2269 2347 6091 2313 2304 6092 2270 2387 6093 2353 2388 6094 2354 2348 6095 2314 2388 6096 2354 2349 6097 2315 2348 6098 2314 2388 6099 2354 2350 6100 2316 2349 6101 2315 2388 6102 2354 2351 6103 2317 2350 6104 2316 2389 6105 2355 2351 6106 2317 2388 6107 2354 2389 6108 2355 2352 6109 2318 2351 6110 2317 2390 6111 2356 2352 6112 2318 2389 6113 2355 2370 6114 2336 2353 6115 2319 2354 6116 2320 2390 6117 2356 2355 6118 2321 2352 6119 2318 2390 6120 2356 2356 6121 2322 2355 6122 2321 2391 6123 2357 2356 6124 2322 2390 6125 2356 2391 6126 2357 2357 6127 2323 2356 6128 2322 2392 6129 2358 2357 6130 2323 2391 6131 2357 2392 6132 2358 2358 6133 2324 2357 6134 2323 2393 6135 2359 2358 6136 2324 2392 6137 2358 2393 6138 2359 2359 6139 2325 2358 6140 2324 2394 6141 2360 2359 6142 2325 2393 6143 2359 2394 6144 2360 2360 6145 2326 2359 6146 2325 2395 6147 2361 2360 6148 2326 2394 6149 2360 2395 6150 2361 2361 6151 2327 2360 6152 2326 2396 6153 2362 2361 6154 2327 2395 6155 2361 2396 6156 2362 2362 6157 2328 2361 6158 2327 2397 6159 2363 2362 6160 2328 2396 6161 2362 2397 6162 2363 2363 6163 2329 2362 6164 2328 2398 6165 2364 2363 6166 2329 2397 6167 2363 2398 6168 2364 2364 6169 2330 2363 6170 2329 2399 6171 2365 2364 6172 2330 2398 6173 2364 2399 6174 2365 2365 6175 2331 2364 6176 2330 2400 6177 2366 2365 6178 2331 2399 6179 2365 2400 6180 2366 2366 6181 2332 2365 6182 2331 2401 6183 2367 2366 6184 2332 2400 6185 2366 2401 6186 2367 2367 6187 2333 2366 6188 2332 2402 6189 2368 2367 6190 2333 2401 6191 2367 2402 6192 2368 2368 6193 2334 2367 6194 2333 2403 6195 2369 2368 6196 2334 2402 6197 2368 2403 6198 2369 2369 6199 2335 2368 6200 2334 2404 6201 2370 2369 6202 2335 2403 6203 2369 2404 6204 2370 2370 6205 2336 2369 6206 2335 2404 6207 2370 2353 6208 2319 2370 6209 2336 2404 6210 2370 2371 6211 2337 2353 6212 2319 2405 6213 2371 2371 6214 2337 2404 6215 2370 2406 6216 2372 2371 6217 2337 2405 6218 2371 2406 6219 2372 2372 6220 2338 2371 6221 2337 2406 6222 2372 2373 6223 2339 2372 6224 2338 2406 6225 2372 2374 6226 2340 2373 6227 2339 2406 6228 2372 2375 6229 2341 2374 6230 2340 2407 6231 2373 2375 6232 2341 2406 6233 2372 2407 6234 2373 2376 6235 2342 2375 6236 2341 2408 6237 2374 2376 6238 2342 2407 6239 2373 2408 6240 2374 2377 6241 2343 2376 6242 2342 2409 6243 2375 2377 6244 2343 2408 6245 2374 2409 6246 2375 2378 6247 2344 2377 6248 2343 2410 6249 2376 2378 6250 2344 2409 6251 2375 2410 6252 2376 2379 6253 2345 2378 6254 2344 2411 6255 2377 2379 6256 2345 2410 6257 2376 2411 6258 2377 2380 6259 2346 2379 6260 2345 2412 6261 2378 2380 6262 2346 2411 6263 2377 2412 6264 2378 2381 6265 2347 2380 6266 2346 2413 6267 2379 2381 6268 2347 2412 6269 2378 2413 6270 2379 2382 6271 2348 2381 6272 2347 2414 6273 2380 2382 6274 2348 2413 6275 2379 2415 6276 2381 2382 6277 2348 2414 6278 2380 2415 6279 2381 2383 6280 2349 2382 6281 2348 2416 6282 2382 2383 6283 2349 2415 6284 2381 2416 6285 2382 2384 6286 2350 2383 6287 2349 2416 6288 2382 2385 6289 2351 2384 6290 2350 2417 6291 2383 2385 6292 2351 2416 6293 2382 2417 6294 2383 2386 6295 2352 2385 6296 2351 2418 6297 2384 2386 6298 2352 2417 6299 2383 2418 6300 2384 2387 6301 2353 2386 6302 2352 2419 6303 2385 2387 6304 2353 2418 6305 2384 2388 6306 2354 2387 6307 2353 2419 6308 2385 2406 6309 2372 2420 6310 2386 2407 6311 2373 2420 6312 2386 2406 6313 2372 2405 6314 2371 2407 6315 2373 2421 6316 2387 2408 6317 2374 2421 6318 2387 2407 6319 2373 2420 6320 2386 2408 6321 2374 2422 6322 2388 2409 6323 2375 2422 6324 2388 2408 6325 2374 2421 6326 2387 2405 6327 2371 2403 6328 2369 2420 6329 2386 2403 6330 2369 2405 6331 2371 2404 6332 2370 2420 6333 2386 2402 6334 2368 2421 6335 2387 2402 6336 2368 2420 6337 2386 2403 6338 2369 2421 6339 2387 2401 6340 2367 2422 6341 2388 2401 6342 2367 2421 6343 2387 2402 6344 2368 2409 6345 2375 2423 6346 2389 2410 6347 2376 2423 6348 2389 2409 6349 2375 2422 6350 2388 2410 6351 2376 2424 6352 2390 2411 6353 2377 2424 6354 2390 2410 6355 2376 2423 6356 2389 2411 6357 2377 2425 6358 2391 2412 6359 2378 2425 6360 2391 2411 6361 2377 2424 6362 2390 2412 6363 2378 2426 6364 2392 2413 6365 2379 2426 6366 2392 2412 6367 2378 2425 6368 2391 2422 6369 2388 2400 6370 2366 2423 6371 2389 2400 6372 2366 2422 6373 2388 2401 6374 2367 2423 6375 2389 2399 6376 2365 2424 6377 2390 2399 6378 2365 2423 6379 2389 2400 6380 2366 2424 6381 2390 2398 6382 2364 2425 6383 2391 2398 6384 2364 2424 6385 2390 2399 6386 2365 2425 6387 2391 2397 6388 2363 2426 6389 2392 2397 6390 2363 2425 6391 2391 2398 6392 2364 2413 6393 2379 2427 6394 2393 2414 6395 2380 2427 6396 2393 2413 6397 2379 2426 6398 2392 2414 6399 2380 2428 6400 2394 2415 6401 2381 2428 6402 2394 2414 6403 2380 2427 6404 2393 2415 6405 2381 2429 6406 2395 2416 6407 2382 2429 6408 2395 2415 6409 2381 2428 6410 2394 2416 6411 2382 2430 6412 2396 2417 6413 2383 2430 6414 2396 2416 6415 2382 2429 6416 2395 2426 6417 2392 2396 6418 2362 2427 6419 2393 2396 6420 2362 2426 6421 2392 2397 6422 2363 2427 6423 2393 2395 6424 2361 2428 6425 2394 2395 6426 2361 2427 6427 2393 2396 6428 2362 2428 6429 2394 2394 6430 2360 2429 6431 2395 2394 6432 2360 2428 6433 2394 2395 6434 2361 2429 6435 2395 2393 6436 2359 2430 6437 2396 2393 6438 2359 2429 6439 2395 2394 6440 2360 2417 6441 2383 2431 6442 2397 2418 6443 2384 2431 6444 2397 2417 6445 2383 2430 6446 2396 2418 6447 2384 2432 6448 2398 2419 6449 2385 2432 6450 2398 2418 6451 2384 2431 6452 2397 2419 6453 2385 2389 6454 2355 2388 6455 2354 2389 6456 2355 2419 6457 2385 2432 6458 2398 2430 6459 2396 2392 6460 2358 2431 6461 2397 2392 6462 2358 2430 6463 2396 2393 6464 2359 2431 6465 2397 2391 6466 2357 2432 6467 2398 2391 6468 2357 2431 6469 2397 2392 6470 2358 2432 6471 2398 2390 6472 2356 2389 6473 2355 2390 6474 2356 2432 6475 2398 2391 6476 2357 2441 6477 2407 2434 6478 2400 2433 6479 2399 2436 6480 2402 2434 6481 2400 2435 6482 2401 2433 6483 2399 2434 6484 2400 2436 6485 2402 2439 6486 2405 2437 6487 2403 2438 6488 2404 2440 6489 2406 2437 6490 2403 2439 6491 2405 2442 6492 2408 2437 6493 2403 2440 6494 2406 2442 6495 2408 2441 6496 2407 2437 6497 2403 2434 6498 2400 2441 6499 2407 2442 6500 2408 2479 6501 2445 2443 6502 2409 2444 6503 2410 2447 6504 2413 2445 6505 2411 2446 6506 2412 2449 6507 2415 2445 6508 2411 2447 6509 2413 2449 6510 2415 2448 6511 2414 2445 6512 2411 2451 6513 2417 2448 6514 2414 2449 6515 2415 2451 6516 2417 2450 6517 2416 2448 6518 2414 2453 6519 2419 2450 6520 2416 2451 6521 2417 2453 6522 2419 2452 6523 2418 2450 6524 2416 2455 6525 2421 2452 6526 2418 2453 6527 2419 2455 6528 2421 2454 6529 2420 2452 6530 2418 2457 6531 2423 2454 6532 2420 2455 6533 2421 2457 6534 2423 2456 6535 2422 2454 6536 2420 2459 6537 2425 2456 6538 2422 2457 6539 2423 2459 6540 2425 2458 6541 2424 2456 6542 2422 2462 6543 2428 2458 6544 2424 2459 6545 2425 2462 6546 2428 2460 6547 2426 2458 6548 2424 2462 6549 2428 2461 6550 2427 2460 6551 2426 2464 6552 2430 2461 6553 2427 2462 6554 2428 2464 6555 2430 2463 6556 2429 2461 6557 2427 2467 6558 2433 2463 6559 2429 2464 6560 2430 2467 6561 2433 2465 6562 2431 2463 6563 2429 2467 6564 2433 2466 6565 2432 2465 6566 2431 2470 6567 2436 2466 6568 2432 2467 6569 2433 2470 6570 2436 2468 6571 2434 2466 6572 2432 2470 6573 2436 2469 6574 2435 2468 6575 2434 2472 6576 2438 2469 6577 2435 2470 6578 2436 2472 6579 2438 2471 6580 2437 2469 6581 2435 2474 6582 2440 2471 6583 2437 2472 6584 2438 2474 6585 2440 2473 6586 2439 2471 6587 2437 2476 6588 2442 2473 6589 2439 2474 6590 2440 2476 6591 2442 2475 6592 2441 2473 6593 2439 2478 6594 2444 2475 6595 2441 2476 6596 2442 2478 6597 2444 2477 6598 2443 2475 6599 2441 2480 6600 2446 2477 6601 2443 2478 6602 2444 2480 6603 2446 2479 6604 2445 2477 6605 2443 2443 6606 2409 2479 6607 2445 2480 6608 2446 2483 6609 2449 2481 6610 2447 2482 6611 2448 2485 6612 2451 2483 6613 2449 2484 6614 2450 2486 6615 2452 2483 6616 2449 2485 6617 2451 2487 6618 2453 2483 6619 2449 2486 6620 2452 2488 6621 2454 2483 6622 2449 2487 6623 2453 2489 6624 2455 2483 6625 2449 2488 6626 2454 2490 6627 2456 2483 6628 2449 2489 6629 2455 2491 6630 2457 2483 6631 2449 2490 6632 2456 2492 6633 2458 2483 6634 2449 2491 6635 2457 2493 6636 2459 2483 6637 2449 2492 6638 2458 2494 6639 2460 2483 6640 2449 2493 6641 2459 2495 6642 2461 2483 6643 2449 2494 6644 2460 2481 6645 2447 2483 6646 2449 2495 6647 2461 2507 6648 2473 2496 6649 2462 2497 6650 2463 2500 6651 2466 2498 6652 2464 2499 6653 2465 2501 6654 2467 2498 6655 2464 2500 6656 2466 2504 6657 2470 2498 6658 2464 2501 6659 2467 2504 6660 2470 2502 6661 2468 2498 6662 2464 2504 6663 2470 2503 6664 2469 2502 6665 2468 2505 6666 2471 2503 6667 2469 2504 6668 2470 2508 6669 2474 2503 6670 2469 2505 6671 2471 2508 6672 2474 2506 6673 2472 2503 6674 2469 2508 6675 2474 2507 6676 2473 2506 6677 2472 2509 6678 2475 2507 6679 2473 2508 6680 2474 2496 6681 2462 2507 6682 2473 2509 6683 2475 2530 6684 2496 2510 6685 2476 2511 6686 2477 2514 6687 2480 2512 6688 2478 2513 6689 2479 2515 6690 2481 2512 6691 2478 2514 6692 2480 2517 6693 2483 2512 6694 2478 2515 6695 2481 2517 6696 2483 2516 6697 2482 2512 6698 2478 2519 6699 2485 2516 6700 2482 2517 6701 2483 2519 6702 2485 2518 6703 2484 2516 6704 2482 2521 6705 2487 2518 6706 2484 2519 6707 2485 2521 6708 2487 2520 6709 2486 2518 6710 2484 2523 6711 2489 2520 6712 2486 2521 6713 2487 2523 6714 2489 2522 6715 2488 2520 6716 2486 2524 6717 2490 2522 6718 2488 2523 6719 2489 2525 6720 2491 2522 6721 2488 2524 6722 2490 2526 6723 2492 2522 6724 2488 2525 6725 2491 2531 6726 2497 2522 6727 2488 2526 6728 2492 2531 6729 2497 2527 6730 2493 2522 6731 2488 2531 6732 2497 2528 6733 2494 2527 6734 2493 2531 6735 2497 2529 6736 2495 2528 6737 2494 2531 6738 2497 2530 6739 2496 2529 6740 2495 2532 6741 2498 2530 6742 2496 2531 6743 2497 2533 6744 2499 2530 6745 2496 2532 6746 2498 2534 6747 2500 2530 6748 2496 2533 6749 2499 2535 6750 2501 2530 6751 2496 2534 6752 2500 2536 6753 2502 2530 6754 2496 2535 6755 2501 2537 6756 2503 2530 6757 2496 2536 6758 2502 2538 6759 2504 2530 6760 2496 2537 6761 2503 2539 6762 2505 2530 6763 2496 2538 6764 2504 2540 6765 2506 2530 6766 2496 2539 6767 2505 2541 6768 2507 2530 6769 2496 2540 6770 2506 2542 6771 2508 2530 6772 2496 2541 6773 2507 2543 6774 2509 2530 6775 2496 2542 6776 2508 2544 6777 2510 2530 6778 2496 2543 6779 2509 2510 6780 2476 2530 6781 2496 2544 6782 2510 2572 6783 2538 2549 6784 2515 2545 6785 2511 2548 6786 2514 2546 6787 2512 2547 6788 2513 2550 6789 2516 2546 6790 2512 2548 6791 2514 2550 6792 2516 2549 6793 2515 2546 6794 2512 2545 6795 2511 2549 6796 2515 2550 6797 2516 2555 6798 2521 2551 6799 2517 2552 6800 2518 2555 6801 2521 2553 6802 2519 2551 6803 2517 2555 6804 2521 2554 6805 2520 2553 6806 2519 2556 6807 2522 2554 6808 2520 2555 6809 2521 2559 6810 2525 2554 6811 2520 2556 6812 2522 2559 6813 2525 2557 6814 2523 2554 6815 2520 2559 6816 2525 2558 6817 2524 2557 6818 2523 2560 6819 2526 2558 6820 2524 2559 6821 2525 2563 6822 2529 2558 6823 2524 2560 6824 2526 2563 6825 2529 2561 6826 2527 2558 6827 2524 2563 6828 2529 2562 6829 2528 2561 6830 2527 2564 6831 2530 2562 6832 2528 2563 6833 2529 2566 6834 2532 2562 6835 2528 2564 6836 2530 2566 6837 2532 2565 6838 2531 2562 6839 2528 2569 6840 2535 2565 6841 2531 2566 6842 2532 2569 6843 2535 2567 6844 2533 2565 6845 2531 2569 6846 2535 2568 6847 2534 2567 6848 2533 2570 6849 2536 2568 6850 2534 2569 6851 2535 2573 6852 2539 2568 6853 2534 2570 6854 2536 2573 6855 2539 2571 6856 2537 2568 6857 2534 2573 6858 2539 2572 6859 2538 2571 6860 2537 2574 6861 2540 2572 6862 2538 2573 6863 2539 2549 6864 2515 2572 6865 2538 2574 6866 2540 2577 6867 2543 2575 6868 2541 2576 6869 2542 2575 6870 2541 2577 6871 2543 2578 6872 2544 2588 6873 2554 2579 6874 2545 2580 6875 2546 2583 6876 2549 2581 6877 2547 2582 6878 2548 2584 6879 2550 2581 6880 2547 2583 6881 2549 2585 6882 2551 2581 6883 2547 2584 6884 2550 2586 6885 2552 2581 6886 2547 2585 6887 2551 2589 6888 2555 2581 6889 2547 2586 6890 2552 2589 6891 2555 2587 6892 2553 2581 6893 2547 2589 6894 2555 2588 6895 2554 2587 6896 2553 2590 6897 2556 2588 6898 2554 2589 6899 2555 2591 6900 2557 2588 6901 2554 2590 6902 2556 2592 6903 2558 2588 6904 2554 2591 6905 2557 2593 6906 2559 2588 6907 2554 2592 6908 2558 2594 6909 2560 2588 6910 2554 2593 6911 2559 2595 6912 2561 2588 6913 2554 2594 6914 2560 2579 6915 2545 2588 6916 2554 2595 6917 2561 2611 6918 2577 2596 6919 2562 2597 6920 2563 2600 6921 2566 2598 6922 2564 2599 6923 2565 2601 6924 2567 2598 6925 2564 2600 6926 2566 2603 6927 2569 2598 6928 2564 2601 6929 2567 2603 6930 2569 2602 6931 2568 2598 6932 2564 2607 6933 2573 2602 6934 2568 2603 6935 2569 2607 6936 2573 2604 6937 2570 2602 6938 2568 2607 6939 2573 2605 6940 2571 2604 6941 2570 2607 6942 2573 2606 6943 2572 2605 6944 2571 2609 6945 2575 2606 6946 2572 2607 6947 2573 2609 6948 2575 2608 6949 2574 2606 6950 2572 2612 6951 2578 2608 6952 2574 2609 6953 2575 2612 6954 2578 2610 6955 2576 2608 6956 2574 2612 6957 2578 2611 6958 2577 2610 6959 2576 2596 6960 2562 2611 6961 2577 2612 6962 2578 2615 6963 2581 2613 6964 2579 2614 6965 2580 2617 6966 2583 2615 6967 2581 2616 6968 2582 2613 6969 2579 2615 6970 2581 2617 6971 2583 2620 6972 2586 2618 6973 2584 2619 6974 2585 2618 6975 2584 2620 6976 2586 2621 6977 2587 2624 6978 2590 2622 6979 2588 2623 6980 2589 2622 6981 2588 2624 6982 2590 2625 6983 2591 2638 6984 2604 2626 6985 2592 2627 6986 2593 2630 6987 2596 2628 6988 2594 2629 6989 2595 2632 6990 2598 2628 6991 2594 2630 6992 2596 2632 6993 2598 2631 6994 2597 2628 6995 2594 2634 6996 2600 2631 6997 2597 2632 6998 2598 2634 6999 2600 2633 7000 2599 2631 7001 2597 2639 7002 2605 2633 7003 2599 2634 7004 2600 2639 7005 2605 2635 7006 2601 2633 7007 2599 2639 7008 2605 2636 7009 2602 2635 7010 2601 2639 7011 2605 2637 7012 2603 2636 7013 2602 2639 7014 2605 2638 7015 2604 2637 7016 2603 2640 7017 2606 2638 7018 2604 2639 7019 2605 2641 7020 2607 2638 7021 2604 2640 7022 2606 2642 7023 2608 2638 7024 2604 2641 7025 2607 2643 7026 2609 2638 7027 2604 2642 7028 2608 2644 7029 2610 2638 7030 2604 2643 7031 2609 2645 7032 2611 2638 7033 2604 2644 7034 2610 2646 7035 2612 2638 7036 2604 2645 7037 2611 2647 7038 2613 2638 7039 2604 2646 7040 2612 2648 7041 2614 2638 7042 2604 2647 7043 2613 2649 7044 2615 2638 7045 2604 2648 7046 2614 2650 7047 2616 2638 7048 2604 2649 7049 2615 2651 7050 2617 2638 7051 2604 2650 7052 2616 2652 7053 2618 2638 7054 2604 2651 7055 2617 2653 7056 2619 2638 7057 2604 2652 7058 2618 2654 7059 2620 2638 7060 2604 2653 7061 2619 2655 7062 2621 2638 7063 2604 2654 7064 2620 2656 7065 2622 2638 7066 2604 2655 7067 2621 2657 7068 2623 2638 7069 2604 2656 7070 2622 2658 7071 2624 2638 7072 2604 2657 7073 2623 2659 7074 2625 2638 7075 2604 2658 7076 2624 2660 7077 2626 2638 7078 2604 2659 7079 2625 2661 7080 2627 2638 7081 2604 2660 7082 2626 2662 7083 2628 2638 7084 2604 2661 7085 2627 2663 7086 2629 2638 7087 2604 2662 7088 2628 2664 7089 2630 2638 7090 2604 2663 7091 2629 2626 7092 2592 2638 7093 2604 2664 7094 2630 2702 7095 2668 2665 7096 2631 2684 7097 2650 2668 7098 2634 2666 7099 2632 2667 7100 2633 2670 7101 2636 2666 7102 2632 2668 7103 2634 2670 7104 2636 2669 7105 2635 2666 7106 2632 2672 7107 2638 2669 7108 2635 2670 7109 2636 2672 7110 2638 2671 7111 2637 2669 7112 2635 2674 7113 2640 2671 7114 2637 2672 7115 2638 2674 7116 2640 2673 7117 2639 2671 7118 2637 2676 7119 2642 2673 7120 2639 2674 7121 2640 2676 7122 2642 2675 7123 2641 2673 7124 2639 2678 7125 2644 2675 7126 2641 2676 7127 2642 2678 7128 2644 2677 7129 2643 2675 7130 2641 2680 7131 2646 2677 7132 2643 2678 7133 2644 2680 7134 2646 2679 7135 2645 2677 7136 2643 2683 7137 2649 2679 7138 2645 2680 7139 2646 2683 7140 2649 2681 7141 2647 2679 7142 2645 2683 7143 2649 2682 7144 2648 2681 7145 2647 2702 7146 2668 2682 7147 2648 2683 7148 2649 2702 7149 2668 2684 7150 2650 2682 7151 2648 2688 7152 2654 2685 7153 2651 2686 7154 2652 2688 7155 2654 2687 7156 2653 2685 7157 2651 2690 7158 2656 2687 7159 2653 2688 7160 2654 2690 7161 2656 2689 7162 2655 2687 7163 2653 2692 7164 2658 2689 7165 2655 2690 7166 2656 2692 7167 2658 2691 7168 2657 2689 7169 2655 2694 7170 2660 2691 7171 2657 2692 7172 2658 2694 7173 2660 2693 7174 2659 2691 7175 2657 2696 7176 2662 2693 7177 2659 2694 7178 2660 2696 7179 2662 2695 7180 2661 2693 7181 2659 2698 7182 2664 2695 7183 2661 2696 7184 2662 2698 7185 2664 2697 7186 2663 2695 7187 2661 2700 7188 2666 2697 7189 2663 2698 7190 2664 2700 7191 2666 2699 7192 2665 2697 7193 2663 2701 7194 2667 2699 7195 2665 2700 7196 2666 2665 7197 2631 2699 7198 2665 2701 7199 2667 2665 7200 2631 2702 7201 2668 2699 7202 2665 2705 7203 2671 2703 7204 2669 2704 7205 2670 2707 7206 2673 2705 7207 2671 2706 7208 2672 2708 7209 2674 2705 7210 2671 2707 7211 2673 2709 7212 2675 2705 7213 2671 2708 7214 2674 2710 7215 2676 2705 7216 2671 2709 7217 2675 2711 7218 2677 2705 7219 2671 2710 7220 2676 2712 7221 2678 2705 7222 2671 2711 7223 2677 2713 7224 2679 2705 7225 2671 2712 7226 2678 2714 7227 2680 2705 7228 2671 2713 7229 2679 2715 7230 2681 2705 7231 2671 2714 7232 2680 2716 7233 2682 2705 7234 2671 2715 7235 2681 2717 7236 2683 2705 7237 2671 2716 7238 2682 2703 7239 2669 2705 7240 2671 2717 7241 2683 2731 7242 2697 2718 7243 2684 2719 7244 2685 2722 7245 2688 2720 7246 2686 2721 7247 2687 2723 7248 2689 2720 7249 2686 2722 7250 2688 2726 7251 2692 2720 7252 2686 2723 7253 2689 2726 7254 2692 2724 7255 2690 2720 7256 2686 2726 7257 2692 2725 7258 2691 2724 7259 2690 2727 7260 2693 2725 7261 2691 2726 7262 2692 2730 7263 2696 2725 7264 2691 2727 7265 2693 2730 7266 2696 2728 7267 2694 2725 7268 2691 2730 7269 2696 2729 7270 2695 2728 7271 2694 2718 7272 2684 2729 7273 2695 2730 7274 2696 2718 7275 2684 2731 7276 2697 2729 7277 2695 2752 7278 2718 2732 7279 2698 2733 7280 2699 2737 7281 2703 2734 7282 2700 2735 7283 2701 2737 7284 2703 2736 7285 2702 2734 7286 2700 2739 7287 2705 2736 7288 2702 2737 7289 2703 2739 7290 2705 2738 7291 2704 2736 7292 2702 2741 7293 2707 2738 7294 2704 2739 7295 2705 2741 7296 2707 2740 7297 2706 2738 7298 2704 2743 7299 2709 2740 7300 2706 2741 7301 2707 2743 7302 2709 2742 7303 2708 2740 7304 2706 2745 7305 2711 2742 7306 2708 2743 7307 2709 2745 7308 2711 2744 7309 2710 2742 7310 2708 2746 7311 2712 2744 7312 2710 2745 7313 2711 2747 7314 2713 2744 7315 2710 2746 7316 2712 2748 7317 2714 2744 7318 2710 2747 7319 2713 2753 7320 2719 2744 7321 2710 2748 7322 2714 2753 7323 2719 2749 7324 2715 2744 7325 2710 2753 7326 2719 2750 7327 2716 2749 7328 2715 2753 7329 2719 2751 7330 2717 2750 7331 2716 2753 7332 2719 2752 7333 2718 2751 7334 2717 2754 7335 2720 2752 7336 2718 2753 7337 2719 2755 7338 2721 2752 7339 2718 2754 7340 2720 2756 7341 2722 2752 7342 2718 2755 7343 2721 2757 7344 2723 2752 7345 2718 2756 7346 2722 2758 7347 2724 2752 7348 2718 2757 7349 2723 2759 7350 2725 2752 7351 2718 2758 7352 2724 2760 7353 2726 2752 7354 2718 2759 7355 2725 2761 7356 2727 2752 7357 2718 2760 7358 2726 2762 7359 2728 2752 7360 2718 2761 7361 2727 2763 7362 2729 2752 7363 2718 2762 7364 2728 2764 7365 2730 2752 7366 2718 2763 7367 2729 2765 7368 2731 2752 7369 2718 2764 7370 2730 2766 7371 2732 2752 7372 2718 2765 7373 2731 2732 7374 2698 2752 7375 2718 2766 7376 2732 2820 7377 2786 2767 7378 2733 2784 7379 2750 2771 7380 2737 2768 7381 2734 2769 7382 2735 2771 7383 2737 2770 7384 2736 2768 7385 2734 2774 7386 2740 2770 7387 2736 2771 7388 2737 2774 7389 2740 2772 7390 2738 2770 7391 2736 2774 7392 2740 2773 7393 2739 2772 7394 2738 2775 7395 2741 2773 7396 2739 2774 7397 2740 2778 7398 2744 2773 7399 2739 2775 7400 2741 2778 7401 2744 2776 7402 2742 2773 7403 2739 2778 7404 2744 2777 7405 2743 2776 7406 2742 2779 7407 2745 2777 7408 2743 2778 7409 2744 2782 7410 2748 2777 7411 2743 2779 7412 2745 2782 7413 2748 2780 7414 2746 2777 7415 2743 2782 7416 2748 2781 7417 2747 2780 7418 2746 2783 7419 2749 2781 7420 2747 2782 7421 2748 2820 7422 2786 2781 7423 2747 2783 7424 2749 2820 7425 2786 2784 7426 2750 2781 7427 2747 2789 7428 2755 2785 7429 2751 2786 7430 2752 2789 7431 2755 2787 7432 2753 2785 7433 2751 2789 7434 2755 2788 7435 2754 2787 7436 2753 2791 7437 2757 2788 7438 2754 2789 7439 2755 2791 7440 2757 2790 7441 2756 2788 7442 2754 2792 7443 2758 2790 7444 2756 2791 7445 2757 2794 7446 2760 2790 7447 2756 2792 7448 2758 2794 7449 2760 2793 7450 2759 2790 7451 2756 2797 7452 2763 2793 7453 2759 2794 7454 2760 2797 7455 2763 2795 7456 2761 2793 7457 2759 2797 7458 2763 2796 7459 2762 2795 7460 2761 2798 7461 2764 2796 7462 2762 2797 7463 2763 2800 7464 2766 2796 7465 2762 2798 7466 2764 2800 7467 2766 2799 7468 2765 2796 7469 2762 2803 7470 2769 2799 7471 2765 2800 7472 2766 2803 7473 2769 2801 7474 2767 2799 7475 2765 2803 7476 2769 2802 7477 2768 2801 7478 2767 2805 7479 2771 2802 7480 2768 2803 7481 2769 2805 7482 2771 2804 7483 2770 2802 7484 2768 2806 7485 2772 2804 7486 2770 2805 7487 2771 2809 7488 2775 2804 7489 2770 2806 7490 2772 2809 7491 2775 2807 7492 2773 2804 7493 2770 2809 7494 2775 2808 7495 2774 2807 7496 2773 2811 7497 2777 2808 7498 2774 2809 7499 2775 2811 7500 2777 2810 7501 2776 2808 7502 2774 2813 7503 2779 2810 7504 2776 2811 7505 2777 2813 7506 2779 2812 7507 2778 2810 7508 2776 2814 7509 2780 2812 7510 2778 2813 7511 2779 2816 7512 2782 2812 7513 2778 2814 7514 2780 2816 7515 2782 2815 7516 2781 2812 7517 2778 2818 7518 2784 2815 7519 2781 2816 7520 2782 2818 7521 2784 2817 7522 2783 2815 7523 2781 2767 7524 2733 2817 7525 2783 2818 7526 2784 2767 7527 2733 2819 7528 2785 2817 7529 2783 2767 7530 2733 2820 7531 2786 2819 7532 2785 2823 7533 2789 2821 7534 2787 2822 7535 2788 2821 7536 2787 2823 7537 2789 2824 7538 2790 2834 7539 2800 2825 7540 2791 2826 7541 2792 2829 7542 2795 2827 7543 2793 2828 7544 2794 2830 7545 2796 2827 7546 2793 2829 7547 2795 2831 7548 2797 2827 7549 2793 2830 7550 2796 2832 7551 2798 2827 7552 2793 2831 7553 2797 2835 7554 2801 2827 7555 2793 2832 7556 2798 2835 7557 2801 2833 7558 2799 2827 7559 2793 2835 7560 2801 2834 7561 2800 2833 7562 2799 2836 7563 2802 2834 7564 2800 2835 7565 2801 2837 7566 2803 2834 7567 2800 2836 7568 2802 2838 7569 2804 2834 7570 2800 2837 7571 2803 2839 7572 2805 2834 7573 2800 2838 7574 2804 2840 7575 2806 2834 7576 2800 2839 7577 2805 2841 7578 2807 2834 7579 2800 2840 7580 2806 2825 7581 2791 2834 7582 2800 2841 7583 2807 2856 7584 2822 2842 7585 2808 2843 7586 2809 2846 7587 2812 2844 7588 2810 2845 7589 2811 2848 7590 2814 2844 7591 2810 2846 7592 2812 2848 7593 2814 2847 7594 2813 2844 7595 2810 2858 7596 2824 2847 7597 2813 2848 7598 2814 2852 7599 2818 2849 7600 2815 2850 7601 2816 2852 7602 2818 2851 7603 2817 2849 7604 2815 2854 7605 2820 2851 7606 2817 2852 7607 2818 2854 7608 2820 2853 7609 2819 2851 7610 2817 2857 7611 2823 2853 7612 2819 2854 7613 2820 2857 7614 2823 2855 7615 2821 2853 7616 2819 2857 7617 2823 2856 7618 2822 2855 7619 2821 2860 7620 2826 2856 7621 2822 2857 7622 2823 2861 7623 2827 2847 7624 2813 2858 7625 2824 2861 7626 2827 2859 7627 2825 2847 7628 2813 2861 7629 2827 2860 7630 2826 2859 7631 2825 2842 7632 2808 2860 7633 2826 2861 7634 2827 2842 7635 2808 2856 7636 2822 2860 7637 2826 2864 7638 2830 2862 7639 2828 2863 7640 2829 2866 7641 2832 2864 7642 2830 2865 7643 2831 2862 7644 2828 2864 7645 2830 2866 7646 2832 2869 7647 2835 2867 7648 2833 2868 7649 2834 2867 7650 2833 2869 7651 2835 2870 7652 2836 2873 7653 2839 2871 7654 2837 2872 7655 2838 2871 7656 2837 2873 7657 2839 2874 7658 2840 2877 7659 2843 2875 7660 2841 2876 7661 2842 2875 7662 2841 2877 7663 2843 2878 7664 2844 2886 7665 2852 2882 7666 2848 2879 7667 2845 2882 7668 2848 2880 7669 2846 2881 7670 2847 2879 7671 2845 2882 7672 2848 2883 7673 2849 2880 7674 2846 2884 7675 2850 2885 7676 2851 2882 7677 2848 2884 7678 2850 2880 7679 2846 2882 7680 2848 2886 7681 2852 2884 7682 2850 2889 7683 2855 2887 7684 2853 2888 7685 2854 2887 7686 2853 2889 7687 2855 2890 7688 2856 2893 7689 2859 2891 7690 2857 2892 7691 2858 2891 7692 2857 2893 7693 2859 2894 7694 2860 2897 7695 2863 2895 7696 2861 2896 7697 2862 2895 7698 2861 2897 7699 2863 2898 7700 2864 2901 7701 2867 2899 7702 2865 2900 7703 2866 2899 7704 2865 2901 7705 2867 2902 7706 2868 2905 7707 2871 2903 7708 2869 2904 7709 2870 2903 7710 2869 2905 7711 2871 2906 7712 2872 2909 7713 2875 2907 7714 2873 2908 7715 2874 2907 7716 2873 2909 7717 2875 2910 7718 2876 2913 7719 2879 2911 7720 2877 2912 7721 2878 2911 7722 2877 2913 7723 2879 2914 7724 2880 2917 7725 2883 2915 7726 2881 2916 7727 2882 2915 7728 2881 2917 7729 2883 2918 7730 2884 2921 7731 2887 2919 7732 2885 2920 7733 2886 2919 7734 2885 2921 7735 2887 2922 7736 2888 2925 7737 2891 2923 7738 2889 2924 7739 2890 2923 7740 2889 2925 7741 2891 2926 7742 2892 2929 7743 2895 2927 7744 2893 2928 7745 2894 2927 7746 2893 2929 7747 2895 2930 7748 2896 2933 7749 2899 2931 7750 2897 2932 7751 2898 2931 7752 2897 2933 7753 2899 2934 7754 2900 2937 7755 2903 2935 7756 2901 2936 7757 2902 2935 7758 2901 2937 7759 2903 2938 7760 2904 2941 7761 2907 2939 7762 2905 2940 7763 2906 2943 7764 2909 2941 7765 2907 2942 7766 2908 2944 7767 2910 2941 7768 2907 2943 7769 2909 2945 7770 2911 2941 7771 2907 2944 7772 2910 2946 7773 2912 2941 7774 2907 2945 7775 2911 2947 7776 2913 2941 7777 2907 2946 7778 2912 2948 7779 2914 2941 7780 2907 2947 7781 2913 2949 7782 2915 2941 7783 2907 2948 7784 2914 2950 7785 2916 2941 7786 2907 2949 7787 2915 2951 7788 2917 2941 7789 2907 2950 7790 2916 2952 7791 2918 2941 7792 2907 2951 7793 2917 2953 7794 2919 2941 7795 2907 2952 7796 2918 2954 7797 2920 2941 7798 2907 2953 7799 2919 2955 7800 2921 2941 7801 2907 2954 7802 2920 2956 7803 2922 2941 7804 2907 2955 7805 2921 2957 7806 2923 2941 7807 2907 2956 7808 2922 2958 7809 2924 2941 7810 2907 2957 7811 2923 2939 7812 2905 2941 7813 2907 2958 7814 2924 2961 7815 2927 2959 7816 2925 2960 7817 2926 2959 7818 2925 2961 7819 2927 2962 7820 2928 2965 7821 2931 2963 7822 2929 2964 7823 2930 2963 7824 2929 2965 7825 2931 2966 7826 2932 2969 7827 2935 2967 7828 2933 2968 7829 2934 2967 7830 2933 2969 7831 2935 2970 7832 2936 2973 7833 2939 2971 7834 2937 2972 7835 2938 2971 7836 2937 2973 7837 2939 2974 7838 2940 2977 7839 2943 2975 7840 2941 2976 7841 2942 2975 7842 2941 2977 7843 2943 2978 7844 2944 2981 7845 2947 2979 7846 2945 2980 7847 2946 2979 7848 2945 2981 7849 2947 2982 7850 2948 2985 7851 2951 2983 7852 2949 2984 7853 2950 2983 7854 2949 2985 7855 2951 2986 7856 2952 2989 7857 2955 2987 7858 2953 2988 7859 2954 2987 7860 2953 2989 7861 2955 2990 7862 2956 2993 7863 2959 2991 7864 2957 2992 7865 2958 2991 7866 2957 2993 7867 2959 2994 7868 2960 2997 7869 2963 2995 7870 2961 2996 7871 2962 2995 7872 2961 2997 7873 2963 2998 7874 2964 3001 7875 2967 2999 7876 2965 3000 7877 2966 2999 7878 2965 3001 7879 2967 3002 7880 2968 3005 7881 2971 3003 7882 2969 3004 7883 2970 3003 7884 2969 3005 7885 2971 3006 7886 2972 3009 7887 2975 3007 7888 2973 3008 7889 2974 3007 7890 2973 3009 7891 2975 3010 7892 2976 3013 7893 2979 3011 7894 2977 3012 7895 2978 3011 7896 2977 3013 7897 2979 3014 7898 2980 3017 7899 2983 3015 7900 2981 3016 7901 2982 3015 7902 2981 3017 7903 2983 3018 7904 2984 3021 7905 2987 3019 7906 2985 3020 7907 2986 3019 7908 2985 3021 7909 2987 3022 7910 2988 3025 7911 2991 3023 7912 2989 3024 7913 2990 3023 7914 2989 3025 7915 2991 3026 7916 2992 3029 7917 2995 3027 7918 2993 3028 7919 2994 3027 7920 2993 3029 7921 2995 3030 7922 2996 3033 7923 2999 3031 7924 2997 3032 7925 2998 3031 7926 2997 3033 7927 2999 3034 7928 3000 3037 7929 3003 3035 7930 3001 3036 7931 3002 3035 7932 3001 3037 7933 3003 3038 7934 3004 3041 7935 3007 3039 7936 3005 3040 7937 3006 3039 7938 3005 3041 7939 3007 3042 7940 3008 3045 7941 3011 3043 7942 3009 3044 7943 3010 3043 7944 3009 3045 7945 3011 3046 7946 3012 3177 7947 3143 3067 7948 3033 3183 7949 3149 3126 7950 3092 3047 7951 3013 3054 7952 3020 3130 7953 3096 3140 7954 3106 3048 7955 3014 3140 7956 3106 3049 7957 3015 3048 7958 3014 3156 7959 3122 3161 7960 3127 3050 7961 3016 3161 7962 3127 3051 7963 3017 3050 7964 3016 3165 7965 3131 3174 7966 3140 3052 7967 3018 3174 7968 3140 3053 7969 3019 3052 7970 3018 3179 7971 3145 3126 7972 3092 3054 7973 3020 3057 7974 3023 3055 7975 3021 3056 7976 3022 3195 7977 3161 3055 7978 3021 3057 7979 3023 3151 7980 3117 3058 7981 3024 3059 7982 3025 3151 7983 3117 3060 7984 3026 3058 7985 3024 3149 7986 3115 3061 7987 3027 3062 7988 3028 3149 7989 3115 3063 7990 3029 3061 7991 3027 3066 7992 3032 3064 7993 3030 3065 7994 3031 3146 7995 3112 3064 7996 3030 3066 7997 3032 3145 7998 3111 3183 7999 3149 3067 8000 3033 3145 8001 3111 3068 8002 3034 3183 8003 3149 3070 8004 3036 3069 8005 3035 3178 8006 3144 3170 8007 3136 3069 8008 3035 3070 8009 3036 3072 8010 3038 3071 8011 3037 3136 8012 3102 3180 8013 3146 3071 8014 3037 3072 8015 3038 3198 8016 3164 3073 8017 3039 3074 8018 3040 3198 8019 3164 3075 8020 3041 3073 8021 3039 3197 8022 3163 3076 8023 3042 3077 8024 3043 3197 8025 3163 3078 8026 3044 3076 8027 3042 3196 8028 3162 3079 8029 3045 3080 8030 3046 3196 8031 3162 3081 8032 3047 3079 8033 3045 3194 8034 3160 3082 8035 3048 3083 8036 3049 3194 8037 3160 3084 8038 3050 3082 8039 3048 3193 8040 3159 3085 8041 3051 3086 8042 3052 3193 8043 3159 3087 8044 3053 3085 8045 3051 3192 8046 3158 3088 8047 3054 3089 8048 3055 3192 8049 3158 3090 8050 3056 3088 8051 3054 3191 8052 3157 3091 8053 3057 3092 8054 3058 3191 8055 3157 3093 8056 3059 3091 8057 3057 3190 8058 3156 3094 8059 3060 3095 8060 3061 3190 8061 3156 3096 8062 3062 3094 8063 3060 3189 8064 3155 3097 8065 3063 3098 8066 3064 3189 8067 3155 3099 8068 3065 3097 8069 3063 3155 8070 3121 3100 8071 3066 3101 8072 3067 3155 8073 3121 3102 8074 3068 3100 8075 3066 3154 8076 3120 3103 8077 3069 3104 8078 3070 3154 8079 3120 3105 8080 3071 3103 8081 3069 3153 8082 3119 3106 8083 3072 3107 8084 3073 3153 8085 3119 3108 8086 3074 3106 8087 3072 3152 8088 3118 3109 8089 3075 3110 8090 3076 3152 8091 3118 3111 8092 3077 3109 8093 3075 3150 8094 3116 3112 8095 3078 3113 8096 3079 3150 8097 3116 3114 8098 3080 3112 8099 3078 3148 8100 3114 3115 8101 3081 3116 8102 3082 3148 8103 3114 3117 8104 3083 3115 8105 3081 3147 8106 3113 3118 8107 3084 3119 8108 3085 3147 8109 3113 3120 8110 3086 3118 8111 3084 3134 8112 3100 3144 8113 3110 3121 8114 3087 3134 8115 3100 3122 8116 3088 3144 8117 3110 3171 8118 3137 3157 8119 3123 3123 8120 3089 3171 8121 3137 3124 8122 3090 3157 8123 3123 3126 8124 3092 3125 8125 3091 3047 8126 3013 3135 8127 3101 3125 8128 3091 3126 8129 3092 3135 8130 3101 3127 8131 3093 3125 8132 3091 3135 8133 3101 3128 8134 3094 3127 8135 3093 3135 8136 3101 3129 8137 3095 3128 8138 3094 3132 8139 3098 3140 8140 3106 3130 8141 3096 3132 8142 3098 3131 8143 3097 3140 8144 3106 3133 8145 3099 3131 8146 3097 3132 8147 3098 3129 8148 3095 3131 8149 3097 3133 8150 3099 3135 8151 3101 3131 8152 3097 3129 8153 3095 3135 8154 3101 3134 8155 3100 3131 8156 3097 3072 8157 3038 3134 8158 3100 3135 8159 3101 3072 8160 3038 3122 8161 3088 3134 8162 3100 3136 8163 3102 3122 8164 3088 3072 8165 3038 3068 8166 3034 3122 8167 3088 3136 8168 3102 3068 8169 3034 3137 8170 3103 3122 8171 3088 3145 8172 3111 3137 8173 3103 3068 8174 3034 3145 8175 3111 3138 8176 3104 3137 8177 3103 3140 8178 3106 3139 8179 3105 3049 8180 3015 3121 8181 3087 3139 8182 3105 3140 8183 3106 3121 8184 3087 3141 8185 3107 3139 8186 3105 3121 8187 3087 3142 8188 3108 3141 8189 3107 3121 8190 3087 3143 8191 3109 3142 8192 3108 3144 8193 3110 3143 8194 3109 3121 8195 3087 3138 8196 3104 3143 8197 3109 3144 8198 3110 3145 8199 3111 3143 8200 3109 3138 8201 3104 3064 8202 3030 3143 8203 3109 3145 8204 3111 3146 8205 3112 3143 8206 3109 3064 8207 3030 3120 8208 3086 3143 8209 3109 3146 8210 3112 3147 8211 3113 3143 8212 3109 3120 8213 3086 3117 8214 3083 3143 8215 3109 3147 8216 3113 3148 8217 3114 3143 8218 3109 3117 8219 3083 3063 8220 3029 3143 8221 3109 3148 8222 3114 3149 8223 3115 3143 8224 3109 3063 8225 3029 3114 8226 3080 3143 8227 3109 3149 8228 3115 3150 8229 3116 3143 8230 3109 3114 8231 3080 3060 8232 3026 3143 8233 3109 3150 8234 3116 3151 8235 3117 3143 8236 3109 3060 8237 3026 3111 8238 3077 3143 8239 3109 3151 8240 3117 3152 8241 3118 3143 8242 3109 3111 8243 3077 3108 8244 3074 3143 8245 3109 3152 8246 3118 3153 8247 3119 3143 8248 3109 3108 8249 3074 3105 8250 3071 3143 8251 3109 3153 8252 3119 3154 8253 3120 3143 8254 3109 3105 8255 3071 3102 8256 3068 3143 8257 3109 3154 8258 3120 3155 8259 3121 3143 8260 3109 3102 8261 3068 3185 8262 3151 3143 8263 3109 3155 8264 3121 3158 8265 3124 3161 8266 3127 3156 8267 3122 3158 8268 3124 3157 8269 3123 3161 8270 3127 3159 8271 3125 3157 8272 3123 3158 8273 3124 3143 8274 3109 3157 8275 3123 3159 8276 3125 3161 8277 3127 3160 8278 3126 3051 8279 3017 3169 8280 3135 3160 8281 3126 3161 8282 3127 3169 8283 3135 3162 8284 3128 3160 8285 3126 3169 8286 3135 3163 8287 3129 3162 8288 3128 3169 8289 3135 3164 8290 3130 3163 8291 3129 3167 8292 3133 3174 8293 3140 3165 8294 3131 3167 8295 3133 3166 8296 3132 3174 8297 3140 3168 8298 3134 3166 8299 3132 3167 8300 3133 3164 8301 3130 3166 8302 3132 3168 8303 3134 3169 8304 3135 3166 8305 3132 3164 8306 3130 3124 8307 3090 3166 8308 3132 3169 8309 3135 3124 8310 3090 3170 8311 3136 3166 8312 3132 3171 8313 3137 3170 8314 3136 3124 8315 3090 3171 8316 3137 3069 8317 3035 3170 8318 3136 3186 8319 3152 3069 8320 3035 3171 8321 3137 3186 8322 3152 3172 8323 3138 3069 8324 3035 3174 8325 3140 3173 8326 3139 3053 8327 3019 3070 8328 3036 3173 8329 3139 3174 8330 3140 3070 8331 3036 3175 8332 3141 3173 8333 3139 3070 8334 3036 3176 8335 3142 3175 8336 3141 3070 8337 3036 3177 8338 3143 3176 8339 3142 3178 8340 3144 3177 8341 3143 3070 8342 3036 3187 8343 3153 3177 8344 3143 3178 8345 3144 3181 8346 3147 3126 8347 3092 3179 8348 3145 3181 8349 3147 3180 8350 3146 3126 8351 3092 3182 8352 3148 3180 8353 3146 3181 8354 3147 3177 8355 3143 3180 8356 3146 3182 8357 3148 3143 8358 3109 3123 8359 3089 3157 8360 3123 3177 8361 3143 3071 8362 3037 3180 8363 3146 3177 8364 3143 3183 8365 3149 3071 8366 3037 3143 8367 3109 3184 8368 3150 3123 8369 3089 3185 8370 3151 3184 8371 3150 3143 8372 3109 3188 8373 3154 3184 8374 3150 3185 8375 3151 3188 8376 3154 3186 8377 3152 3184 8378 3150 3188 8379 3154 3172 8380 3138 3186 8381 3152 3188 8382 3154 3187 8383 3153 3172 8384 3138 3188 8385 3154 3177 8386 3143 3187 8387 3153 3099 8388 3065 3177 8389 3143 3188 8390 3154 3189 8391 3155 3177 8392 3143 3099 8393 3065 3096 8394 3062 3177 8395 3143 3189 8396 3155 3190 8397 3156 3177 8398 3143 3096 8399 3062 3093 8400 3059 3177 8401 3143 3190 8402 3156 3191 8403 3157 3177 8404 3143 3093 8405 3059 3090 8406 3056 3177 8407 3143 3191 8408 3157 3192 8409 3158 3177 8410 3143 3090 8411 3056 3087 8412 3053 3177 8413 3143 3192 8414 3158 3193 8415 3159 3177 8416 3143 3087 8417 3053 3084 8418 3050 3177 8419 3143 3193 8420 3159 3194 8421 3160 3177 8422 3143 3084 8423 3050 3055 8424 3021 3177 8425 3143 3194 8426 3160 3195 8427 3161 3177 8428 3143 3055 8429 3021 3081 8430 3047 3177 8431 3143 3195 8432 3161 3196 8433 3162 3177 8434 3143 3081 8435 3047 3078 8436 3044 3177 8437 3143 3196 8438 3162 3197 8439 3163 3177 8440 3143 3078 8441 3044 3075 8442 3041 3177 8443 3143 3197 8444 3163 3198 8445 3164 3177 8446 3143 3075 8447 3041 3067 8448 3033 3177 8449 3143 3198 8450 3164 3201 8451 3167 3199 8452 3165 3200 8453 3166 3199 8454 3165 3201 8455 3167 3202 8456 3168 3205 8457 3171 3203 8458 3169 3204 8459 3170 3203 8460 3169 3205 8461 3171 3206 8462 3172 3209 8463 3175 3207 8464 3173 3208 8465 3174 3207 8466 3173 3209 8467 3175 3210 8468 3176 3213 8469 3179 3211 8470 3177 3212 8471 3178 3211 8472 3177 3213 8473 3179 3214 8474 3180 3217 8475 3183 3215 8476 3181 3216 8477 3182 3215 8478 3181 3217 8479 3183 3218 8480 3184 3221 8481 3187 3219 8482 3185 3220 8483 3186 3219 8484 3185 3221 8485 3187 3222 8486 3188 3225 8487 3191 3223 8488 3189 3224 8489 3190 3223 8490 3189 3225 8491 3191 3226 8492 3192 3229 8493 3195 3227 8494 3193 3228 8495 3194 3227 8496 3193 3229 8497 3195 3230 8498 3196 3233 8499 3199 3231 8500 3197 3232 8501 3198 3231 8502 3197 3233 8503 3199 3234 8504 3200 3237 8505 3203 3235 8506 3201 3236 8507 3202 3235 8508 3201 3237 8509 3203 3238 8510 3204 3241 8511 3207 3239 8512 3205 3240 8513 3206 3239 8514 3205 3241 8515 3207 3242 8516 3208 3245 8517 3211 3243 8518 3209 3244 8519 3210 3243 8520 3209 3245 8521 3211 3246 8522 3212 3249 8523 3215 3247 8524 3213 3248 8525 3214 3247 8526 3213 3249 8527 3215 3250 8528 3216 3253 8529 3219 3251 8530 3217 3252 8531 3218 3251 8532 3217 3253 8533 3219 3254 8534 3220 3257 8535 3223 3255 8536 3221 3256 8537 3222 3255 8538 3221 3257 8539 3223 3258 8540 3224 3261 8541 3227 3259 8542 3225 3260 8543 3226 3259 8544 3225 3261 8545 3227 3262 8546 3228 3265 8547 3231 3263 8548 3229 3264 8549 3230 3263 8550 3229 3265 8551 3231 3266 8552 3232 3269 8553 3235 3267 8554 3233 3268 8555 3234 3267 8556 3233 3269 8557 3235 3270 8558 3236 3273 8559 3239 3271 8560 3237 3272 8561 3238 3271 8562 3237 3273 8563 3239 3274 8564 3240 3277 8565 3243 3275 8566 3241 3276 8567 3242 3275 8568 3241 3277 8569 3243 3278 8570 3244 3281 8571 3247 3279 8572 3245 3280 8573 3246 3279 8574 3245 3281 8575 3247 3282 8576 3248 3285 8577 3251 3283 8578 3249 3284 8579 3250 3283 8580 3249 3285 8581 3251 3286 8582 3252 3289 8583 3255 3287 8584 3253 3288 8585 3254 3287 8586 3253 3289 8587 3255 3290 8588 3256 3293 8589 3259 3291 8590 3257 3292 8591 3258 3291 8592 3257 3293 8593 3259 3294 8594 3260 3297 8595 3263 3295 8596 3261 3296 8597 3262 3295 8598 3261 3297 8599 3263 3298 8600 3264 3301 8601 3267 3299 8602 3265 3300 8603 3266 3299 8604 3265 3301 8605 3267 3302 8606 3268 3305 8607 3271 3303 8608 3269 3304 8609 3270 3303 8610 3269 3305 8611 3271 3306 8612 3272 3309 8613 3275 3307 8614 3273 3308 8615 3274 3307 8616 3273 3309 8617 3275 3310 8618 3276 3313 8619 3279 3311 8620 3277 3312 8621 3278 3311 8622 3277 3313 8623 3279 3314 8624 3280 3317 8625 3283 3315 8626 3281 3316 8627 3282 3315 8628 3281 3317 8629 3283 3318 8630 3284 3321 8631 3287 3319 8632 3285 3320 8633 3286 3319 8634 3285 3321 8635 3287 3322 8636 3288 3325 8637 3291 3323 8638 3289 3324 8639 3290 3323 8640 3289 3325 8641 3291 3326 8642 3292 3329 8643 3295 3327 8644 3293 3328 8645 3294 3327 8646 3293 3329 8647 3295 3330 8648 3296 3333 8649 3299 3331 8650 3297 3332 8651 3298 3331 8652 3297 3333 8653 3299 3334 8654 3300 3337 8655 3303 3335 8656 3301 3336 8657 3302 3335 8658 3301 3337 8659 3303 3338 8660 3304 3341 8661 3307 3339 8662 3305 3340 8663 3306 3339 8664 3305 3341 8665 3307 3342 8666 3308 3345 8667 3311 3343 8668 3309 3344 8669 3310 3343 8670 3309 3345 8671 3311 3346 8672 3312 3349 8673 3315 3347 8674 3313 3348 8675 3314 3347 8676 3313 3349 8677 3315 3350 8678 3316 3353 8679 3319 3351 8680 3317 3352 8681 3318 3351 8682 3317 3353 8683 3319 3354 8684 3320 3357 8685 3323 3355 8686 3321 3356 8687 3322 3355 8688 3321 3357 8689 3323 3358 8690 3324 3361 8691 3327 3359 8692 3325 3360 8693 3326 3359 8694 3325 3361 8695 3327 3362 8696 3328 3365 8697 3331 3363 8698 3329 3364 8699 3330 3363 8700 3329 3365 8701 3331 3366 8702 3332 3369 8703 3335 3367 8704 3333 3368 8705 3334 3367 8706 3333 3369 8707 3335 3370 8708 3336 3373 8709 3339 3371 8710 3337 3372 8711 3338 3371 8712 3337 3373 8713 3339 3374 8714 3340 3388 8715 3354 3375 8716 3341 3376 8717 3342 3381 8718 3347 3377 8719 3343 3378 8720 3344 3381 8721 3347 3379 8722 3345 3377 8723 3343 3381 8724 3347 3380 8725 3346 3379 8726 3345 3383 8727 3349 3380 8728 3346 3381 8729 3347 3383 8730 3349 3382 8731 3348 3380 8732 3346 3385 8733 3351 3382 8734 3348 3383 8735 3349 3385 8736 3351 3384 8737 3350 3382 8738 3348 3387 8739 3353 3384 8740 3350 3385 8741 3351 3387 8742 3353 3386 8743 3352 3384 8744 3350 3375 8745 3341 3386 8746 3352 3387 8747 3353 3375 8748 3341 3388 8749 3354 3386 8750 3352 3401 8751 3367 3389 8752 3355 3390 8753 3356 3393 8754 3359 3391 8755 3357 3392 8756 3358 3394 8757 3360 3391 8758 3357 3393 8759 3359 3396 8760 3362 3391 8761 3357 3394 8762 3360 3396 8763 3362 3395 8764 3361 3391 8765 3357 3398 8766 3364 3395 8767 3361 3396 8768 3362 3398 8769 3364 3397 8770 3363 3395 8771 3361 3400 8772 3366 3397 8773 3363 3398 8774 3364 3400 8775 3366 3399 8776 3365 3397 8777 3363 3402 8778 3368 3399 8779 3365 3400 8780 3366 3402 8781 3368 3401 8782 3367 3399 8783 3365 3389 8784 3355 3401 8785 3367 3402 8786 3368 3416 8787 3382 3403 8788 3369 3404 8789 3370 3408 8790 3374 3405 8791 3371 3406 8792 3372 3408 8793 3374 3407 8794 3373 3405 8795 3371 3411 8796 3377 3407 8797 3373 3408 8798 3374 3411 8799 3377 3409 8800 3375 3407 8801 3373 3411 8802 3377 3410 8803 3376 3409 8804 3375 3413 8805 3379 3410 8806 3376 3411 8807 3377 3413 8808 3379 3412 8809 3378 3410 8810 3376 3415 8811 3381 3412 8812 3378 3413 8813 3379 3415 8814 3381 3414 8815 3380 3412 8816 3378 3403 8817 3369 3414 8818 3380 3415 8819 3381 3403 8820 3369 3416 8821 3382 3414 8822 3380 3429 8823 3395 3417 8824 3383 3418 8825 3384 3423 8826 3389 3419 8827 3385 3420 8828 3386 3423 8829 3389 3421 8830 3387 3419 8831 3385 3423 8832 3389 3422 8833 3388 3421 8834 3387 3424 8835 3390 3422 8836 3388 3423 8837 3389 3426 8838 3392 3422 8839 3388 3424 8840 3390 3426 8841 3392 3425 8842 3391 3422 8843 3388 3428 8844 3394 3425 8845 3391 3426 8846 3392 3428 8847 3394 3427 8848 3393 3425 8849 3391 3430 8850 3396 3427 8851 3393 3428 8852 3394 3430 8853 3396 3429 8854 3395 3427 8855 3393 3417 8856 3383 3429 8857 3395 3430 8858 3396 3435 8859 3401 3431 8860 3397 3432 8861 3398 3465 8862 3431 3433 8863 3399 3434 8864 3400 3465 8865 3431 3435 8866 3401 3433 8867 3399 3431 8868 3397 3436 8869 3402 3437 8870 3403 3431 8871 3397 3438 8872 3404 3436 8873 3402 3474 8874 3440 3439 8875 3405 3440 8876 3406 3474 8877 3440 3441 8878 3407 3439 8879 3405 3473 8880 3439 3442 8881 3408 3443 8882 3409 3473 8883 3439 3444 8884 3410 3442 8885 3408 3472 8886 3438 3445 8887 3411 3446 8888 3412 3472 8889 3438 3447 8890 3413 3445 8891 3411 3471 8892 3437 3448 8893 3414 3449 8894 3415 3471 8895 3437 3450 8896 3416 3448 8897 3414 3470 8898 3436 3451 8899 3417 3452 8900 3418 3470 8901 3436 3453 8902 3419 3451 8903 3417 3469 8904 3435 3454 8905 3420 3455 8906 3421 3469 8907 3435 3456 8908 3422 3454 8909 3420 3468 8910 3434 3457 8911 3423 3458 8912 3424 3468 8913 3434 3459 8914 3425 3457 8915 3423 3467 8916 3433 3460 8917 3426 3461 8918 3427 3467 8919 3433 3462 8920 3428 3460 8921 3426 3466 8922 3432 3463 8923 3429 3464 8924 3430 3466 8925 3432 3465 8926 3431 3463 8927 3429 3466 8928 3432 3435 8929 3401 3465 8930 3431 3462 8931 3428 3435 8932 3401 3466 8933 3432 3467 8934 3433 3435 8935 3401 3462 8936 3428 3459 8937 3425 3435 8938 3401 3467 8939 3433 3468 8940 3434 3435 8941 3401 3459 8942 3425 3456 8943 3422 3435 8944 3401 3468 8945 3434 3469 8946 3435 3435 8947 3401 3456 8948 3422 3453 8949 3419 3435 8950 3401 3469 8951 3435 3470 8952 3436 3435 8953 3401 3453 8954 3419 3450 8955 3416 3435 8956 3401 3470 8957 3436 3471 8958 3437 3435 8959 3401 3450 8960 3416 3447 8961 3413 3435 8962 3401 3471 8963 3437 3472 8964 3438 3435 8965 3401 3447 8966 3413 3444 8967 3410 3435 8968 3401 3472 8969 3438 3473 8970 3439 3435 8971 3401 3444 8972 3410 3441 8973 3407 3435 8974 3401 3473 8975 3439 3474 8976 3440 3435 8977 3401 3441 8978 3407 3438 8979 3404 3435 8980 3401 3474 8981 3440 3431 8982 3397 3435 8983 3401 3438 8984 3404 3477 8985 3443 3482 8986 3448 3478 8987 3444 3509 8988 3475 3475 8989 3441 3476 8990 3442 3509 8991 3475 3477 8992 3443 3475 8993 3441 3477 8994 3443 3478 8995 3444 3479 8996 3445 3478 8997 3444 3480 8998 3446 3481 8999 3447 3478 9000 3444 3482 9001 3448 3480 9002 3446 3518 9003 3484 3483 9004 3449 3484 9005 3450 3518 9006 3484 3485 9007 3451 3483 9008 3449 3517 9009 3483 3486 9010 3452 3487 9011 3453 3517 9012 3483 3488 9013 3454 3486 9014 3452 3516 9015 3482 3489 9016 3455 3490 9017 3456 3516 9018 3482 3491 9019 3457 3489 9020 3455 3515 9021 3481 3492 9022 3458 3493 9023 3459 3515 9024 3481 3494 9025 3460 3492 9026 3458 3514 9027 3480 3495 9028 3461 3496 9029 3462 3514 9030 3480 3497 9031 3463 3495 9032 3461 3513 9033 3479 3498 9034 3464 3499 9035 3465 3513 9036 3479 3500 9037 3466 3498 9038 3464 3512 9039 3478 3501 9040 3467 3502 9041 3468 3512 9042 3478 3503 9043 3469 3501 9044 3467 3511 9045 3477 3504 9046 3470 3505 9047 3471 3511 9048 3477 3506 9049 3472 3504 9050 3470 3510 9051 3476 3507 9052 3473 3508 9053 3474 3510 9054 3476 3509 9055 3475 3507 9056 3473 3510 9057 3476 3477 9058 3443 3509 9059 3475 3506 9060 3472 3477 9061 3443 3510 9062 3476 3511 9063 3477 3477 9064 3443 3506 9065 3472 3503 9066 3469 3477 9067 3443 3511 9068 3477 3512 9069 3478 3477 9070 3443 3503 9071 3469 3500 9072 3466 3477 9073 3443 3512 9074 3478 3513 9075 3479 3477 9076 3443 3500 9077 3466 3497 9078 3463 3477 9079 3443 3513 9080 3479 3514 9081 3480 3477 9082 3443 3497 9083 3463 3494 9084 3460 3477 9085 3443 3514 9086 3480 3515 9087 3481 3477 9088 3443 3494 9089 3460 3491 9090 3457 3477 9091 3443 3515 9092 3481 3516 9093 3482 3477 9094 3443 3491 9095 3457 3488 9096 3454 3477 9097 3443 3516 9098 3482 3517 9099 3483 3477 9100 3443 3488 9101 3454 3485 9102 3451 3477 9103 3443 3517 9104 3483 3518 9105 3484 3477 9106 3443 3485 9107 3451 3482 9108 3448 3477 9109 3443 3518 9110 3484 3535 9111 3501 3519 9112 3485 3520 9113 3486 3523 9114 3489 3521 9115 3487 3522 9116 3488 3525 9117 3491 3521 9118 3487 3523 9119 3489 3525 9120 3491 3524 9121 3490 3521 9122 3487 3527 9123 3493 3524 9124 3490 3525 9125 3491 3527 9126 3493 3526 9127 3492 3524 9128 3490 3529 9129 3495 3526 9130 3492 3527 9131 3493 3529 9132 3495 3528 9133 3494 3526 9134 3492 3531 9135 3497 3528 9136 3494 3529 9137 3495 3531 9138 3497 3530 9139 3496 3528 9140 3494 3532 9141 3498 3530 9142 3496 3531 9143 3497 3534 9144 3500 3530 9145 3496 3532 9146 3498 3534 9147 3500 3533 9148 3499 3530 9149 3496 3536 9150 3502 3533 9151 3499 3534 9152 3500 3536 9153 3502 3535 9154 3501 3533 9155 3499 3519 9156 3485 3535 9157 3501 3536 9158 3502 3554 9159 3520 3537 9160 3503 3538 9161 3504 3542 9162 3508 3539 9163 3505 3540 9164 3506 3542 9165 3508 3541 9166 3507 3539 9167 3505 3544 9168 3510 3541 9169 3507 3542 9170 3508 3544 9171 3510 3543 9172 3509 3541 9173 3507 3546 9174 3512 3543 9175 3509 3544 9176 3510 3546 9177 3512 3545 9178 3511 3543 9179 3509 3548 9180 3514 3545 9181 3511 3546 9182 3512 3548 9183 3514 3547 9184 3513 3545 9185 3511 3551 9186 3517 3547 9187 3513 3548 9188 3514 3551 9189 3517 3549 9190 3515 3547 9191 3513 3551 9192 3517 3550 9193 3516 3549 9194 3515 3553 9195 3519 3550 9196 3516 3551 9197 3517 3553 9198 3519 3552 9199 3518 3550 9200 3516 3537 9201 3503 3552 9202 3518 3553 9203 3519 3537 9204 3503 3554 9205 3520 3552 9206 3518 3576 9207 3542 3555 9208 3521 3556 9209 3522 3559 9210 3525 3557 9211 3523 3558 9212 3524 3561 9213 3527 3557 9214 3523 3559 9215 3525 3561 9216 3527 3560 9217 3526 3557 9218 3523 3563 9219 3529 3560 9220 3526 3561 9221 3527 3563 9222 3529 3562 9223 3528 3560 9224 3526 3565 9225 3531 3562 9226 3528 3563 9227 3529 3565 9228 3531 3564 9229 3530 3562 9230 3528 3567 9231 3533 3564 9232 3530 3565 9233 3531 3567 9234 3533 3566 9235 3532 3564 9236 3530 3569 9237 3535 3566 9238 3532 3567 9239 3533 3569 9240 3535 3568 9241 3534 3566 9242 3532 3571 9243 3537 3568 9244 3534 3569 9245 3535 3571 9246 3537 3570 9247 3536 3568 9248 3534 3573 9249 3539 3570 9250 3536 3571 9251 3537 3573 9252 3539 3572 9253 3538 3570 9254 3536 3575 9255 3541 3572 9256 3538 3573 9257 3539 3575 9258 3541 3574 9259 3540 3572 9260 3538 3555 9261 3521 3574 9262 3540 3575 9263 3541 3555 9264 3521 3576 9265 3542 3574 9266 3540 3593 9267 3559 3577 9268 3543 3578 9269 3544 3582 9270 3548 3579 9271 3545 3580 9272 3546 3582 9273 3548 3581 9274 3547 3579 9275 3545 3584 9276 3550 3581 9277 3547 3582 9278 3548 3584 9279 3550 3583 9280 3549 3581 9281 3547 3586 9282 3552 3583 9283 3549 3584 9284 3550 3586 9285 3552 3585 9286 3551 3583 9287 3549 3588 9288 3554 3585 9289 3551 3586 9290 3552 3588 9291 3554 3587 9292 3553 3585 9293 3551 3590 9294 3556 3587 9295 3553 3588 9296 3554 3590 9297 3556 3589 9298 3555 3587 9299 3553 3592 9300 3558 3589 9301 3555 3590 9302 3556 3592 9303 3558 3591 9304 3557 3589 9305 3555 3594 9306 3560 3591 9307 3557 3592 9308 3558 3594 9309 3560 3593 9310 3559 3591 9311 3557 3577 9312 3543 3593 9313 3559 3594 9314 3560 3597 9315 3563 3595 9316 3561 3596 9317 3562 3595 9318 3561 3597 9319 3563 3598 9320 3564 3616 9321 3582 3599 9322 3565 3600 9323 3566 3603 9324 3569 3601 9325 3567 3602 9326 3568 3605 9327 3571 3601 9328 3567 3603 9329 3569 3605 9330 3571 3604 9331 3570 3601 9332 3567 3607 9333 3573 3604 9334 3570 3605 9335 3571 3607 9336 3573 3606 9337 3572 3604 9338 3570 3609 9339 3575 3606 9340 3572 3607 9341 3573 3609 9342 3575 3608 9343 3574 3606 9344 3572 3611 9345 3577 3608 9346 3574 3609 9347 3575 3611 9348 3577 3610 9349 3576 3608 9350 3574 3613 9351 3579 3610 9352 3576 3611 9353 3577 3613 9354 3579 3612 9355 3578 3610 9356 3576 3615 9357 3581 3612 9358 3578 3613 9359 3579 3615 9360 3581 3614 9361 3580 3612 9362 3578 3599 9363 3565 3614 9364 3580 3615 9365 3581 3599 9366 3565 3616 9367 3582 3614 9368 3580 3633 9369 3599 3617 9370 3583 3618 9371 3584 3621 9372 3587 3619 9373 3585 3620 9374 3586 3623 9375 3589 3619 9376 3585 3621 9377 3587 3623 9378 3589 3622 9379 3588 3619 9380 3585 3625 9381 3591 3622 9382 3588 3623 9383 3589 3625 9384 3591 3624 9385 3590 3622 9386 3588 3627 9387 3593 3624 9388 3590 3625 9389 3591 3627 9390 3593 3626 9391 3592 3624 9392 3590 3628 9393 3594 3626 9394 3592 3627 9395 3593 3630 9396 3596 3626 9397 3592 3628 9398 3594 3630 9399 3596 3629 9400 3595 3626 9401 3592 3632 9402 3598 3629 9403 3595 3630 9404 3596 3632 9405 3598 3631 9406 3597 3629 9407 3595 3634 9408 3600 3631 9409 3597 3632 9410 3598 3634 9411 3600 3633 9412 3599 3631 9413 3597 3617 9414 3583 3633 9415 3599 3634 9416 3600 3655 9417 3621 3635 9418 3601 3636 9419 3602 3639 9420 3605 3637 9421 3603 3638 9422 3604 3641 9423 3607 3637 9424 3603 3639 9425 3605 3641 9426 3607 3640 9427 3606 3637 9428 3603 3643 9429 3609 3640 9430 3606 3641 9431 3607 3643 9432 3609 3642 9433 3608 3640 9434 3606 3645 9435 3611 3642 9436 3608 3643 9437 3609 3645 9438 3611 3644 9439 3610 3642 9440 3608 3647 9441 3613 3644 9442 3610 3645 9443 3611 3647 9444 3613 3646 9445 3612 3644 9446 3610 3648 9447 3614 3646 9448 3612 3647 9449 3613 3650 9450 3616 3646 9451 3612 3648 9452 3614 3650 9453 3616 3649 9454 3615 3646 9455 3612 3652 9456 3618 3649 9457 3615 3650 9458 3616 3652 9459 3618 3651 9460 3617 3649 9461 3615 3654 9462 3620 3651 9463 3617 3652 9464 3618 3654 9465 3620 3653 9466 3619 3651 9467 3617 3656 9468 3622 3653 9469 3619 3654 9470 3620 3656 9471 3622 3655 9472 3621 3653 9473 3619 3635 9474 3601 3655 9475 3621 3656 9476 3622 3673 9477 3639 3657 9478 3623 3658 9479 3624 3661 9480 3627 3659 9481 3625 3660 9482 3626 3663 9483 3629 3659 9484 3625 3661 9485 3627 3663 9486 3629 3662 9487 3628 3659 9488 3625 3665 9489 3631 3662 9490 3628 3663 9491 3629 3665 9492 3631 3664 9493 3630 3662 9494 3628 3667 9495 3633 3664 9496 3630 3665 9497 3631 3667 9498 3633 3666 9499 3632 3664 9500 3630 3668 9501 3634 3666 9502 3632 3667 9503 3633 3670 9504 3636 3666 9505 3632 3668 9506 3634 3670 9507 3636 3669 9508 3635 3666 9509 3632 3672 9510 3638 3669 9511 3635 3670 9512 3636 3672 9513 3638 3671 9514 3637 3669 9515 3635 3674 9516 3640 3671 9517 3637 3672 9518 3638 3674 9519 3640 3673 9520 3639 3671 9521 3637 3657 9522 3623 3673 9523 3639 3674 9524 3640 3695 9525 3661 3675 9526 3641 3676 9527 3642 3679 9528 3645 3677 9529 3643 3678 9530 3644 3681 9531 3647 3677 9532 3643 3679 9533 3645 3681 9534 3647 3680 9535 3646 3677 9536 3643 3683 9537 3649 3680 9538 3646 3681 9539 3647 3683 9540 3649 3682 9541 3648 3680 9542 3646 3685 9543 3651 3682 9544 3648 3683 9545 3649 3685 9546 3651 3684 9547 3650 3682 9548 3648 3687 9549 3653 3684 9550 3650 3685 9551 3651 3687 9552 3653 3686 9553 3652 3684 9554 3650 3688 9555 3654 3686 9556 3652 3687 9557 3653 3690 9558 3656 3686 9559 3652 3688 9560 3654 3690 9561 3656 3689 9562 3655 3686 9563 3652 3692 9564 3658 3689 9565 3655 3690 9566 3656 3692 9567 3658 3691 9568 3657 3689 9569 3655 3694 9570 3660 3691 9571 3657 3692 9572 3658 3694 9573 3660 3693 9574 3659 3691 9575 3657 3696 9576 3662 3693 9577 3659 3694 9578 3660 3696 9579 3662 3695 9580 3661 3693 9581 3659 3675 9582 3641 3695 9583 3661 3696 9584 3662 3717 9585 3683 3697 9586 3663 3698 9587 3664 3701 9588 3667 3699 9589 3665 3700 9590 3666 3703 9591 3669 3699 9592 3665 3701 9593 3667 3703 9594 3669 3702 9595 3668 3699 9596 3665 3705 9597 3671 3702 9598 3668 3703 9599 3669 3705 9600 3671 3704 9601 3670 3702 9602 3668 3707 9603 3673 3704 9604 3670 3705 9605 3671 3707 9606 3673 3706 9607 3672 3704 9608 3670 3709 9609 3675 3706 9610 3672 3707 9611 3673 3709 9612 3675 3708 9613 3674 3706 9614 3672 3710 9615 3676 3708 9616 3674 3709 9617 3675 3712 9618 3678 3708 9619 3674 3710 9620 3676 3712 9621 3678 3711 9622 3677 3708 9623 3674 3714 9624 3680 3711 9625 3677 3712 9626 3678 3714 9627 3680 3713 9628 3679 3711 9629 3677 3716 9630 3682 3713 9631 3679 3714 9632 3680 3716 9633 3682 3715 9634 3681 3713 9635 3679 3718 9636 3684 3715 9637 3681 3716 9638 3682 3718 9639 3684 3717 9640 3683 3715 9641 3681 3697 9642 3663 3717 9643 3683 3718 9644 3684 3739 9645 3705 3719 9646 3685 3720 9647 3686 3723 9648 3689 3721 9649 3687 3722 9650 3688 3725 9651 3691 3721 9652 3687 3723 9653 3689 3725 9654 3691 3724 9655 3690 3721 9656 3687 3727 9657 3693 3724 9658 3690 3725 9659 3691 3727 9660 3693 3726 9661 3692 3724 9662 3690 3729 9663 3695 3726 9664 3692 3727 9665 3693 3729 9666 3695 3728 9667 3694 3726 9668 3692 3731 9669 3697 3728 9670 3694 3729 9671 3695 3731 9672 3697 3730 9673 3696 3728 9674 3694 3732 9675 3698 3730 9676 3696 3731 9677 3697 3734 9678 3700 3730 9679 3696 3732 9680 3698 3734 9681 3700 3733 9682 3699 3730 9683 3696 3736 9684 3702 3733 9685 3699 3734 9686 3700 3736 9687 3702 3735 9688 3701 3733 9689 3699 3738 9690 3704 3735 9691 3701 3736 9692 3702 3738 9693 3704 3737 9694 3703 3735 9695 3701 3740 9696 3706 3737 9697 3703 3738 9698 3704 3740 9699 3706 3739 9700 3705 3737 9701 3703 3719 9702 3685 3739 9703 3705 3740 9704 3706 3761 9705 3727 3741 9706 3707 3742 9707 3708 3745 9708 3711 3743 9709 3709 3744 9710 3710 3747 9711 3713 3743 9712 3709 3745 9713 3711 3747 9714 3713 3746 9715 3712 3743 9716 3709 3749 9717 3715 3746 9718 3712 3747 9719 3713 3749 9720 3715 3748 9721 3714 3746 9722 3712 3751 9723 3717 3748 9724 3714 3749 9725 3715 3751 9726 3717 3750 9727 3716 3748 9728 3714 3753 9729 3719 3750 9730 3716 3751 9731 3717 3753 9732 3719 3752 9733 3718 3750 9734 3716 3754 9735 3720 3752 9736 3718 3753 9737 3719 3756 9738 3722 3752 9739 3718 3754 9740 3720 3756 9741 3722 3755 9742 3721 3752 9743 3718 3758 9744 3724 3755 9745 3721 3756 9746 3722 3758 9747 3724 3757 9748 3723 3755 9749 3721 3760 9750 3726 3757 9751 3723 3758 9752 3724 3760 9753 3726 3759 9754 3725 3757 9755 3723 3762 9756 3728 3759 9757 3725 3760 9758 3726 3762 9759 3728 3761 9760 3727 3759 9761 3725 3741 9762 3707 3761 9763 3727 3762 9764 3728 3783 9765 3749 3763 9766 3729 3764 9767 3730 3767 9768 3733 3765 9769 3731 3766 9770 3732 3769 9771 3735 3765 9772 3731 3767 9773 3733 3769 9774 3735 3768 9775 3734 3765 9776 3731 3771 9777 3737 3768 9778 3734 3769 9779 3735 3771 9780 3737 3770 9781 3736 3768 9782 3734 3773 9783 3739 3770 9784 3736 3771 9785 3737 3773 9786 3739 3772 9787 3738 3770 9788 3736 3775 9789 3741 3772 9790 3738 3773 9791 3739 3775 9792 3741 3774 9793 3740 3772 9794 3738 3776 9795 3742 3774 9796 3740 3775 9797 3741 3778 9798 3744 3774 9799 3740 3776 9800 3742 3778 9801 3744 3777 9802 3743 3774 9803 3740 3780 9804 3746 3777 9805 3743 3778 9806 3744 3780 9807 3746 3779 9808 3745 3777 9809 3743 3782 9810 3748 3779 9811 3745 3780 9812 3746 3782 9813 3748 3781 9814 3747 3779 9815 3745 3784 9816 3750 3781 9817 3747 3782 9818 3748 3784 9819 3750 3783 9820 3749 3781 9821 3747 3763 9822 3729 3783 9823 3749 3784 9824 3750 3801 9825 3767 3785 9826 3751 3786 9827 3752 3789 9828 3755 3787 9829 3753 3788 9830 3754 3790 9831 3756 3787 9832 3753 3789 9833 3755 3792 9834 3758 3787 9835 3753 3790 9836 3756 3792 9837 3758 3791 9838 3757 3787 9839 3753 3795 9840 3761 3791 9841 3757 3792 9842 3758 3795 9843 3761 3793 9844 3759 3791 9845 3757 3795 9846 3761 3794 9847 3760 3793 9848 3759 3796 9849 3762 3794 9850 3760 3795 9851 3761 3798 9852 3764 3794 9853 3760 3796 9854 3762 3798 9855 3764 3797 9856 3763 3794 9857 3760 3800 9858 3766 3797 9859 3763 3798 9860 3764 3800 9861 3766 3799 9862 3765 3797 9863 3763 3802 9864 3768 3799 9865 3765 3800 9866 3766 3802 9867 3768 3801 9868 3767 3799 9869 3765 3785 9870 3751 3801 9871 3767 3802 9872 3768 3819 9873 3785 3803 9874 3769 3804 9875 3770 3807 9876 3773 3805 9877 3771 3806 9878 3772 3808 9879 3774 3805 9880 3771 3807 9881 3773 3810 9882 3776 3805 9883 3771 3808 9884 3774 3810 9885 3776 3809 9886 3775 3805 9887 3771 3813 9888 3779 3809 9889 3775 3810 9890 3776 3813 9891 3779 3811 9892 3777 3809 9893 3775 3813 9894 3779 3812 9895 3778 3811 9896 3777 3814 9897 3780 3812 9898 3778 3813 9899 3779 3816 9900 3782 3812 9901 3778 3814 9902 3780 3816 9903 3782 3815 9904 3781 3812 9905 3778 3818 9906 3784 3815 9907 3781 3816 9908 3782 3818 9909 3784 3817 9910 3783 3815 9911 3781 3820 9912 3786 3817 9913 3783 3818 9914 3784 3820 9915 3786 3819 9916 3785 3817 9917 3783 3803 9918 3769 3819 9919 3785 3820 9920 3786 3836 9921 3802 3825 9922 3791 3821 9923 3787 3826 9924 3792 3822 9925 3788 3823 9926 3789 3826 9927 3792 3824 9928 3790 3822 9929 3788 3826 9930 3792 3825 9931 3791 3824 9932 3790 3821 9933 3787 3825 9934 3791 3826 9935 3792 3831 9936 3797 3827 9937 3793 3828 9938 3794 3831 9939 3797 3829 9940 3795 3827 9941 3793 3831 9942 3797 3830 9943 3796 3829 9944 3795 3833 9945 3799 3830 9946 3796 3831 9947 3797 3833 9948 3799 3832 9949 3798 3830 9950 3796 3834 9951 3800 3832 9952 3798 3833 9953 3799 3837 9954 3803 3832 9955 3798 3834 9956 3800 3837 9957 3803 3835 9958 3801 3832 9959 3798 3837 9960 3803 3836 9961 3802 3835 9962 3801 3838 9963 3804 3836 9964 3802 3837 9965 3803 3825 9966 3791 3836 9967 3802 3838 9968 3804 3855 9969 3821 3839 9970 3805 3840 9971 3806 3844 9972 3810 3841 9973 3807 3842 9974 3808 3844 9975 3810 3843 9976 3809 3841 9977 3807 3847 9978 3813 3843 9979 3809 3844 9980 3810 3847 9981 3813 3845 9982 3811 3843 9983 3809 3847 9984 3813 3846 9985 3812 3845 9986 3811 3848 9987 3814 3846 9988 3812 3847 9989 3813 3851 9990 3817 3846 9991 3812 3848 9992 3814 3851 9993 3817 3849 9994 3815 3846 9995 3812 3851 9996 3817 3850 9997 3816 3849 9998 3815 3853 9999 3819 3850 10000 3816 3851 10001 3817 3853 10002 3819 3852 10003 3818 3850 10004 3816 3854 10005 3820 3852 10006 3818 3853 10007 3819 3856 10008 3822 3852 10009 3818 3854 10010 3820 3856 10011 3822 3855 10012 3821 3852 10013 3818 3839 10014 3805 3855 10015 3821 3856 10016 3822 3874 10017 3840 3857 10018 3823 3860 10019 3826 3874 10020 3840 3858 10021 3824 3859 10022 3825 3874 10023 3840 3860 10024 3826 3858 10025 3824 3865 10026 3831 3861 10027 3827 3862 10028 3828 3865 10029 3831 3863 10030 3829 3861 10031 3827 3865 10032 3831 3864 10033 3830 3863 10034 3829 3866 10035 3832 3864 10036 3830 3865 10037 3831 3869 10038 3835 3864 10039 3830 3866 10040 3832 3869 10041 3835 3867 10042 3833 3864 10043 3830 3869 10044 3835 3868 10045 3834 3867 10046 3833 3870 10047 3836 3868 10048 3834 3869 10049 3835 3873 10050 3839 3868 10051 3834 3870 10052 3836 3873 10053 3839 3871 10054 3837 3868 10055 3834 3873 10056 3839 3872 10057 3838 3871 10058 3837 3857 10059 3823 3872 10060 3838 3873 10061 3839 3857 10062 3823 3874 10063 3840 3872 10064 3838 3890 10065 3856 3875 10066 3841 3876 10067 3842 3881 10068 3847 3877 10069 3843 3878 10070 3844 3881 10071 3847 3879 10072 3845 3877 10073 3843 3881 10074 3847 3880 10075 3846 3879 10076 3845 3882 10077 3848 3880 10078 3846 3881 10079 3847 3885 10080 3851 3880 10081 3846 3882 10082 3848 3885 10083 3851 3883 10084 3849 3880 10085 3846 3885 10086 3851 3884 10087 3850 3883 10088 3849 3886 10089 3852 3884 10090 3850 3885 10091 3851 3888 10092 3854 3884 10093 3850 3886 10094 3852 3888 10095 3854 3887 10096 3853 3884 10097 3850 3891 10098 3857 3887 10099 3853 3888 10100 3854 3891 10101 3857 3889 10102 3855 3887 10103 3853 3891 10104 3857 3890 10105 3856 3889 10106 3855 3892 10107 3858 3890 10108 3856 3891 10109 3857 3875 10110 3841 3890 10111 3856 3892 10112 3858 3925 10113 3891 3893 10114 3859 3897 10115 3863 3926 10116 3892 3898 10117 3864 3927 10118 3893 3926 10119 3892 3894 10120 3860 3898 10121 3864 3926 10122 3892 3895 10123 3861 3894 10124 3860 3928 10125 3894 3895 10126 3861 3926 10127 3892 3928 10128 3894 3896 10129 3862 3895 10130 3861 3925 10131 3891 3896 10132 3862 3928 10133 3894 3925 10134 3891 3897 10135 3863 3896 10136 3862 3899 10137 3865 3927 10138 3893 3898 10139 3864 3899 10140 3865 3929 10141 3895 3927 10142 3893 3900 10143 3866 3929 10144 3895 3899 10145 3865 3900 10146 3866 3930 10147 3896 3929 10148 3895 3901 10149 3867 3930 10150 3896 3900 10151 3866 3901 10152 3867 3931 10153 3897 3930 10154 3896 3902 10155 3868 3931 10156 3897 3901 10157 3867 3903 10158 3869 3931 10159 3897 3902 10160 3868 3903 10161 3869 3932 10162 3898 3931 10163 3897 3904 10164 3870 3932 10165 3898 3903 10166 3869 3904 10167 3870 3933 10168 3899 3932 10169 3898 3905 10170 3871 3933 10171 3899 3904 10172 3870 3905 10173 3871 3934 10174 3900 3933 10175 3899 3906 10176 3872 3934 10177 3900 3905 10178 3871 3906 10179 3872 3935 10180 3901 3934 10181 3900 3907 10182 3873 3935 10183 3901 3906 10184 3872 3907 10185 3873 3936 10186 3902 3935 10187 3901 3908 10188 3874 3936 10189 3902 3907 10190 3873 3908 10191 3874 3937 10192 3903 3936 10193 3902 3909 10194 3875 3937 10195 3903 3908 10196 3874 3911 10197 3877 3909 10198 3875 3910 10199 3876 3911 10200 3877 3937 10201 3903 3909 10202 3875 3912 10203 3878 3937 10204 3903 3911 10205 3877 3912 10206 3878 3938 10207 3904 3937 10208 3903 3913 10209 3879 3938 10210 3904 3912 10211 3878 3913 10212 3879 3939 10213 3905 3938 10214 3904 3914 10215 3880 3939 10216 3905 3913 10217 3879 3914 10218 3880 3940 10219 3906 3939 10220 3905 3915 10221 3881 3940 10222 3906 3914 10223 3880 3915 10224 3881 3941 10225 3907 3940 10226 3906 3916 10227 3882 3941 10228 3907 3915 10229 3881 3916 10230 3882 3942 10231 3908 3941 10232 3907 3917 10233 3883 3942 10234 3908 3916 10235 3882 3917 10236 3883 3943 10237 3909 3942 10238 3908 3918 10239 3884 3943 10240 3909 3917 10241 3883 3919 10242 3885 3943 10243 3909 3918 10244 3884 3920 10245 3886 3943 10246 3909 3919 10247 3885 3920 10248 3886 3944 10249 3910 3943 10250 3909 3921 10251 3887 3944 10252 3910 3920 10253 3886 3921 10254 3887 3945 10255 3911 3944 10256 3910 3922 10257 3888 3945 10258 3911 3921 10259 3887 3922 10260 3888 3946 10261 3912 3945 10262 3911 3923 10263 3889 3946 10264 3912 3922 10265 3888 3923 10266 3889 3947 10267 3913 3946 10268 3912 3924 10269 3890 3947 10270 3913 3923 10271 3889 3924 10272 3890 3948 10273 3914 3947 10274 3913 3893 10275 3859 3948 10276 3914 3924 10277 3890 3893 10278 3859 3925 10279 3891 3948 10280 3914 3943 10281 3909 3949 10282 3915 3942 10283 3908 3949 10284 3915 3943 10285 3909 3944 10286 3910 3942 10287 3908 3950 10288 3916 3941 10289 3907 3950 10290 3916 3942 10291 3908 3949 10292 3915 3941 10293 3907 3951 10294 3917 3940 10295 3906 3951 10296 3917 3941 10297 3907 3950 10298 3916 3940 10299 3906 3952 10300 3918 3939 10301 3905 3952 10302 3918 3940 10303 3906 3951 10304 3917 3939 10305 3905 3953 10306 3919 3938 10307 3904 3953 10308 3919 3939 10309 3905 3952 10310 3918 3938 10311 3904 3936 10312 3902 3937 10313 3903 3936 10314 3902 3938 10315 3904 3953 10316 3919 3944 10317 3910 3954 10318 3920 3949 10319 3915 3954 10320 3920 3944 10321 3910 3945 10322 3911 3945 10323 3911 3955 10324 3921 3954 10325 3920 3955 10326 3921 3945 10327 3911 3946 10328 3912 3949 10329 3915 3956 10330 3922 3950 10331 3916 3956 10332 3922 3949 10333 3915 3954 10334 3920 3954 10335 3920 3957 10336 3923 3956 10337 3922 3957 10338 3923 3954 10339 3920 3955 10340 3921 3950 10341 3916 3958 10342 3924 3951 10343 3917 3958 10344 3924 3950 10345 3916 3956 10346 3922 3956 10347 3922 3959 10348 3925 3958 10349 3924 3959 10350 3925 3956 10351 3922 3957 10352 3923 3951 10353 3917 3960 10354 3926 3952 10355 3918 3960 10356 3926 3951 10357 3917 3958 10358 3924 3958 10359 3924 3961 10360 3927 3960 10361 3926 3961 10362 3927 3958 10363 3924 3959 10364 3925 3952 10365 3918 3962 10366 3928 3953 10367 3919 3962 10368 3928 3952 10369 3918 3960 10370 3926 3960 10371 3926 3963 10372 3929 3962 10373 3928 3963 10374 3929 3960 10375 3926 3961 10376 3927 3953 10377 3919 3935 10378 3901 3936 10379 3902 3935 10380 3901 3953 10381 3919 3962 10382 3928 3962 10383 3928 3934 10384 3900 3935 10385 3901 3934 10386 3900 3962 10387 3928 3963 10388 3929 3946 10389 3912 3964 10390 3930 3955 10391 3921 3964 10392 3930 3946 10393 3912 3947 10394 3913 3947 10395 3913 3965 10396 3931 3964 10397 3930 3965 10398 3931 3947 10399 3913 3948 10400 3914 3955 10401 3921 3966 10402 3932 3957 10403 3923 3966 10404 3932 3955 10405 3921 3964 10406 3930 3964 10407 3930 3967 10408 3933 3966 10409 3932 3967 10410 3933 3964 10411 3930 3965 10412 3931 3957 10413 3923 3968 10414 3934 3959 10415 3925 3968 10416 3934 3957 10417 3923 3966 10418 3932 3966 10419 3932 3969 10420 3935 3968 10421 3934 3969 10422 3935 3966 10423 3932 3967 10424 3933 3959 10425 3925 3970 10426 3936 3961 10427 3927 3970 10428 3936 3959 10429 3925 3968 10430 3934 3968 10431 3934 3971 10432 3937 3970 10433 3936 3971 10434 3937 3968 10435 3934 3969 10436 3935 3961 10437 3927 3972 10438 3938 3963 10439 3929 3972 10440 3938 3961 10441 3927 3970 10442 3936 3970 10443 3936 3973 10444 3939 3972 10445 3938 3973 10446 3939 3970 10447 3936 3971 10448 3937 3963 10449 3929 3933 10450 3899 3934 10451 3900 3933 10452 3899 3963 10453 3929 3972 10454 3938 3972 10455 3938 3932 10456 3898 3933 10457 3899 3932 10458 3898 3972 10459 3938 3973 10460 3939 3948 10461 3914 3928 10462 3894 3965 10463 3931 3928 10464 3894 3948 10465 3914 3925 10466 3891 3965 10467 3931 3926 10468 3892 3967 10469 3933 3926 10470 3892 3965 10471 3931 3928 10472 3894 3967 10473 3933 3927 10474 3893 3969 10475 3935 3927 10476 3893 3967 10477 3933 3926 10478 3892 3969 10479 3935 3929 10480 3895 3971 10481 3937 3929 10482 3895 3969 10483 3935 3927 10484 3893 3971 10485 3937 3930 10486 3896 3973 10487 3939 3930 10488 3896 3971 10489 3937 3929 10490 3895 3973 10491 3939 3931 10492 3897 3932 10493 3898 3931 10494 3897 3973 10495 3939 3930 10496 3896 3989 10497 3955 3982 10498 3948 3974 10499 3940 3977 10500 3943 3975 10501 3941 3976 10502 3942 3979 10503 3945 3975 10504 3941 3977 10505 3943 3979 10506 3945 3978 10507 3944 3975 10508 3941 3980 10509 3946 3978 10510 3944 3979 10511 3945 3983 10512 3949 3978 10513 3944 3980 10514 3946 3983 10515 3949 3981 10516 3947 3978 10517 3944 3983 10518 3949 3982 10519 3948 3981 10520 3947 3974 10521 3940 3982 10522 3948 3983 10523 3949 3988 10524 3954 3984 10525 3950 3985 10526 3951 3988 10527 3954 3986 10528 3952 3984 10529 3950 3988 10530 3954 3987 10531 3953 3986 10532 3952 3990 10533 3956 3987 10534 3953 3988 10535 3954 3990 10536 3956 3989 10537 3955 3987 10538 3953 3991 10539 3957 3989 10540 3955 3990 10541 3956 3982 10542 3948 3989 10543 3955 3991 10544 3957 4023 10545 3989 3992 10546 3958 3993 10547 3959 4024 10548 3990 3994 10549 3960 3995 10550 3961 4025 10551 3991 3994 10552 3960 4024 10553 3990 3995 10554 3961 4026 10555 3992 4024 10556 3990 3996 10557 3962 4026 10558 3992 3995 10559 3961 3996 10560 3962 4027 10561 3993 4026 10562 3992 4003 10563 3969 4027 10564 3993 3996 10565 3962 4028 10566 3994 3994 10567 3960 4025 10568 3991 4028 10569 3994 3997 10570 3963 3994 10571 3960 4029 10572 3995 3997 10573 3963 4028 10574 3994 4029 10575 3995 3998 10576 3964 3997 10577 3963 4030 10578 3996 3998 10579 3964 4029 10580 3995 4030 10581 3996 3999 10582 3965 3998 10583 3964 3999 10584 3965 4000 10585 3966 4001 10586 3967 4030 10587 3996 4000 10588 3966 3999 10589 3965 4030 10590 3996 4002 10591 3968 4000 10592 3966 4031 10593 3997 4002 10594 3968 4030 10595 3996 4005 10596 3971 4003 10597 3969 4004 10598 3970 4005 10599 3971 4027 10600 3993 4003 10601 3969 4006 10602 3972 4027 10603 3993 4005 10604 3971 4006 10605 3972 4032 10606 3998 4027 10607 3993 4007 10608 3973 4032 10609 3998 4006 10610 3972 4007 10611 3973 4033 10612 3999 4032 10613 3998 4008 10614 3974 4033 10615 3999 4007 10616 3973 4008 10617 3974 4034 10618 4000 4033 10619 3999 4009 10620 3975 4034 10621 4000 4008 10622 3974 4009 10623 3975 4035 10624 4001 4034 10625 4000 4010 10626 3976 4035 10627 4001 4009 10628 3975 4010 10629 3976 4036 10630 4002 4035 10631 4001 4011 10632 3977 4036 10633 4002 4010 10634 3976 4011 10635 3977 4037 10636 4003 4036 10637 4002 4012 10638 3978 4037 10639 4003 4011 10640 3977 4013 10641 3979 4037 10642 4003 4012 10643 3978 4014 10644 3980 4037 10645 4003 4013 10646 3979 4014 10647 3980 4038 10648 4004 4037 10649 4003 4015 10650 3981 4038 10651 4004 4014 10652 3980 4015 10653 3981 4039 10654 4005 4038 10655 4004 4016 10656 3982 4039 10657 4005 4015 10658 3981 4016 10659 3982 4040 10660 4006 4039 10661 4005 4016 10662 3982 4041 10663 4007 4040 10664 4006 4017 10665 3983 4041 10666 4007 4016 10667 3982 4017 10668 3983 4042 10669 4008 4041 10670 4007 4018 10671 3984 4042 10672 4008 4017 10673 3983 4018 10674 3984 4043 10675 4009 4042 10676 4008 3992 10677 3958 4043 10678 4009 4018 10679 3984 4044 10680 4010 4002 10681 3968 4031 10682 3997 4044 10683 4010 4019 10684 3985 4002 10685 3968 4044 10686 4010 4020 10687 3986 4019 10688 3985 4045 10689 4011 4020 10690 3986 4044 10691 4010 4046 10692 4012 4020 10693 3986 4045 10694 4011 4046 10695 4012 4021 10696 3987 4020 10697 3986 4047 10698 4013 4021 10699 3987 4046 10700 4012 4047 10701 4013 4022 10702 3988 4021 10703 3987 4043 10704 4009 4022 10705 3988 4047 10706 4013 4043 10707 4009 4023 10708 3989 4022 10709 3988 3992 10710 3958 4023 10711 3989 4043 10712 4009 4030 10713 3996 4048 10714 4014 4031 10715 3997 4048 10716 4014 4030 10717 3996 4029 10718 3995 4031 10719 3997 4049 10720 4015 4044 10721 4010 4049 10722 4015 4031 10723 3997 4048 10724 4014 4044 10725 4010 4050 10726 4016 4045 10727 4011 4050 10728 4016 4044 10729 4010 4049 10730 4015 4045 10731 4011 4051 10732 4017 4046 10733 4012 4051 10734 4017 4045 10735 4011 4050 10736 4016 4046 10737 4012 4052 10738 4018 4047 10739 4013 4052 10740 4018 4046 10741 4012 4051 10742 4017 4047 10743 4013 4042 10744 4008 4043 10745 4009 4042 10746 4008 4047 10747 4013 4052 10748 4018 4029 10749 3995 4053 10750 4019 4048 10751 4014 4053 10752 4019 4029 10753 3995 4028 10754 3994 4048 10755 4014 4054 10756 4020 4049 10757 4015 4054 10758 4020 4048 10759 4014 4053 10760 4019 4049 10761 4015 4055 10762 4021 4050 10763 4016 4055 10764 4021 4049 10765 4015 4054 10766 4020 4028 10767 3994 4056 10768 4022 4053 10769 4019 4056 10770 4022 4028 10771 3994 4025 10772 3991 4053 10773 4019 4057 10774 4023 4054 10775 4020 4057 10776 4023 4053 10777 4019 4056 10778 4022 4054 10779 4020 4058 10780 4024 4055 10781 4021 4058 10782 4024 4054 10783 4020 4057 10784 4023 4050 10785 4016 4059 10786 4025 4051 10787 4017 4059 10788 4025 4050 10789 4016 4055 10790 4021 4051 10791 4017 4060 10792 4026 4052 10793 4018 4060 10794 4026 4051 10795 4017 4059 10796 4025 4052 10797 4018 4041 10798 4007 4042 10799 4008 4041 10800 4007 4052 10801 4018 4060 10802 4026 4055 10803 4021 4061 10804 4027 4059 10805 4025 4061 10806 4027 4055 10807 4021 4058 10808 4024 4059 10809 4025 4062 10810 4028 4060 10811 4026 4062 10812 4028 4059 10813 4025 4061 10814 4027 4060 10815 4026 4040 10816 4006 4041 10817 4007 4040 10818 4006 4060 10819 4026 4062 10820 4028 4025 10821 3991 4063 10822 4029 4056 10823 4022 4063 10824 4029 4025 10825 3991 4024 10826 3990 4056 10827 4022 4064 10828 4030 4057 10829 4023 4064 10830 4030 4056 10831 4022 4063 10832 4029 4057 10833 4023 4065 10834 4031 4058 10835 4024 4065 10836 4031 4057 10837 4023 4064 10838 4030 4024 10839 3990 4066 10840 4032 4063 10841 4029 4066 10842 4032 4024 10843 3990 4026 10844 3992 4063 10845 4029 4067 10846 4033 4064 10847 4030 4067 10848 4033 4063 10849 4029 4066 10850 4032 4064 10851 4030 4068 10852 4034 4065 10853 4031 4068 10854 4034 4064 10855 4030 4067 10856 4033 4058 10857 4024 4069 10858 4035 4061 10859 4027 4069 10860 4035 4058 10861 4024 4065 10862 4031 4061 10863 4027 4070 10864 4036 4062 10865 4028 4070 10866 4036 4061 10867 4027 4069 10868 4035 4062 10869 4028 4039 10870 4005 4040 10871 4006 4039 10872 4005 4062 10873 4028 4070 10874 4036 4065 10875 4031 4071 10876 4037 4069 10877 4035 4071 10878 4037 4065 10879 4031 4068 10880 4034 4069 10881 4035 4072 10882 4038 4070 10883 4036 4072 10884 4038 4069 10885 4035 4071 10886 4037 4070 10887 4036 4038 10888 4004 4039 10889 4005 4038 10890 4004 4070 10891 4036 4072 10892 4038 4026 10893 3992 4032 10894 3998 4066 10895 4032 4032 10896 3998 4026 10897 3992 4027 10898 3993 4066 10899 4032 4033 10900 3999 4067 10901 4033 4033 10902 3999 4066 10903 4032 4032 10904 3998 4067 10905 4033 4034 10906 4000 4068 10907 4034 4034 10908 4000 4067 10909 4033 4033 10910 3999 4068 10911 4034 4035 10912 4001 4071 10913 4037 4035 10914 4001 4068 10915 4034 4034 10916 4000 4071 10917 4037 4036 10918 4002 4072 10919 4038 4036 10920 4002 4071 10921 4037 4035 10922 4001 4072 10923 4038 4037 10924 4003 4038 10925 4004 4037 10926 4003 4072 10927 4038 4036 10928 4002 4089 10929 4055 4073 10930 4039 4074 10931 4040 4077 10932 4043 4075 10933 4041 4076 10934 4042 4078 10935 4044 4075 10936 4041 4077 10937 4043 4080 10938 4046 4075 10939 4041 4078 10940 4044 4080 10941 4046 4079 10942 4045 4075 10943 4041 4083 10944 4049 4079 10945 4045 4080 10946 4046 4083 10947 4049 4081 10948 4047 4079 10949 4045 4083 10950 4049 4082 10951 4048 4081 10952 4047 4085 10953 4051 4082 10954 4048 4083 10955 4049 4085 10956 4051 4084 10957 4050 4082 10958 4048 4087 10959 4053 4084 10960 4050 4085 10961 4051 4087 10962 4053 4086 10963 4052 4084 10964 4050 4088 10965 4054 4086 10966 4052 4087 10967 4053 4090 10968 4056 4086 10969 4052 4088 10970 4054 4090 10971 4056 4089 10972 4055 4086 10973 4052 4073 10974 4039 4089 10975 4055 4090 10976 4056 4122 10977 4088 4091 10978 4057 4092 10979 4058 4123 10980 4089 4095 10981 4061 4124 10982 4090 4123 10983 4089 4093 10984 4059 4095 10985 4061 4125 10986 4091 4093 10987 4059 4123 10988 4089 4125 10989 4091 4094 10990 4060 4093 10991 4059 4096 10992 4062 4124 10993 4090 4095 10994 4061 4096 10995 4062 4126 10996 4092 4124 10997 4090 4097 10998 4063 4126 10999 4092 4096 11000 4062 4097 11001 4063 4127 11002 4093 4126 11003 4092 4097 11004 4063 4128 11005 4094 4127 11006 4093 4098 11007 4064 4128 11008 4094 4097 11009 4063 4098 11010 4064 4129 11011 4095 4128 11012 4094 4104 11013 4070 4129 11014 4095 4098 11015 4064 4094 11016 4060 4099 11017 4065 4100 11018 4066 4125 11019 4091 4099 11020 4065 4094 11021 4060 4130 11022 4096 4099 11023 4065 4125 11024 4091 4130 11025 4096 4101 11026 4067 4099 11027 4065 4130 11028 4096 4102 11029 4068 4101 11030 4067 4131 11031 4097 4102 11032 4068 4130 11033 4096 4132 11034 4098 4102 11035 4068 4131 11036 4097 4132 11037 4098 4103 11038 4069 4102 11039 4068 4106 11040 4072 4104 11041 4070 4105 11042 4071 4106 11043 4072 4129 11044 4095 4104 11045 4070 4107 11046 4073 4129 11047 4095 4106 11048 4072 4107 11049 4073 4133 11050 4099 4129 11051 4095 4108 11052 4074 4133 11053 4099 4107 11054 4073 4108 11055 4074 4134 11056 4100 4133 11057 4099 4109 11058 4075 4134 11059 4100 4108 11060 4074 4109 11061 4075 4135 11062 4101 4134 11063 4100 4110 11064 4076 4135 11065 4101 4109 11066 4075 4110 11067 4076 4136 11068 4102 4135 11069 4101 4111 11070 4077 4136 11071 4102 4110 11072 4076 4111 11073 4077 4137 11074 4103 4136 11075 4102 4112 11076 4078 4137 11077 4103 4111 11078 4077 4112 11079 4078 4138 11080 4104 4137 11081 4103 4113 11082 4079 4138 11083 4104 4112 11084 4078 4114 11085 4080 4138 11086 4104 4113 11087 4079 4115 11088 4081 4138 11089 4104 4114 11090 4080 4115 11091 4081 4139 11092 4105 4138 11093 4104 4116 11094 4082 4139 11095 4105 4115 11096 4081 4116 11097 4082 4140 11098 4106 4139 11099 4105 4117 11100 4083 4140 11101 4106 4116 11102 4082 4117 11103 4083 4141 11104 4107 4140 11105 4106 4118 11106 4084 4141 11107 4107 4117 11108 4083 4118 11109 4084 4142 11110 4108 4141 11111 4107 4118 11112 4084 4143 11113 4109 4142 11114 4108 4119 11115 4085 4143 11116 4109 4118 11117 4084 4119 11118 4085 4144 11119 4110 4143 11120 4109 4091 11121 4057 4144 11122 4110 4119 11123 4085 4145 11124 4111 4103 11125 4069 4132 11126 4098 4145 11127 4111 4120 11128 4086 4103 11129 4069 4146 11130 4112 4120 11131 4086 4145 11132 4111 4146 11133 4112 4121 11134 4087 4120 11135 4086 4144 11136 4110 4121 11137 4087 4146 11138 4112 4144 11139 4110 4122 11140 4088 4121 11141 4087 4091 11142 4057 4122 11143 4088 4144 11144 4110 4125 11145 4091 4147 11146 4113 4130 11147 4096 4147 11148 4113 4125 11149 4091 4123 11150 4089 4130 11151 4096 4148 11152 4114 4131 11153 4097 4148 11154 4114 4130 11155 4096 4147 11156 4113 4131 11157 4097 4149 11158 4115 4132 11159 4098 4149 11160 4115 4131 11161 4097 4148 11162 4114 4132 11163 4098 4150 11164 4116 4145 11165 4111 4150 11166 4116 4132 11167 4098 4149 11168 4115 4145 11169 4111 4151 11170 4117 4146 11171 4112 4151 11172 4117 4145 11173 4111 4150 11174 4116 4146 11175 4112 4143 11176 4109 4144 11177 4110 4143 11178 4109 4146 11179 4112 4151 11180 4117 4123 11181 4089 4152 11182 4118 4147 11183 4113 4152 11184 4118 4123 11185 4089 4124 11186 4090 4147 11187 4113 4153 11188 4119 4148 11189 4114 4153 11190 4119 4147 11191 4113 4152 11192 4118 4148 11193 4114 4154 11194 4120 4149 11195 4115 4154 11196 4120 4148 11197 4114 4153 11198 4119 4124 11199 4090 4155 11200 4121 4152 11201 4118 4155 11202 4121 4124 11203 4090 4126 11204 4092 4152 11205 4118 4156 11206 4122 4153 11207 4119 4156 11208 4122 4152 11209 4118 4155 11210 4121 4153 11211 4119 4157 11212 4123 4154 11213 4120 4157 11214 4123 4153 11215 4119 4156 11216 4122 4149 11217 4115 4158 11218 4124 4150 11219 4116 4158 11220 4124 4149 11221 4115 4154 11222 4120 4150 11223 4116 4159 11224 4125 4151 11225 4117 4159 11226 4125 4150 11227 4116 4158 11228 4124 4151 11229 4117 4142 11230 4108 4143 11231 4109 4142 11232 4108 4151 11233 4117 4159 11234 4125 4154 11235 4120 4160 11236 4126 4158 11237 4124 4160 11238 4126 4154 11239 4120 4157 11240 4123 4158 11241 4124 4161 11242 4127 4159 11243 4125 4161 11244 4127 4158 11245 4124 4160 11246 4126 4159 11247 4125 4141 11248 4107 4142 11249 4108 4141 11250 4107 4159 11251 4125 4161 11252 4127 4126 11253 4092 4162 11254 4128 4155 11255 4121 4162 11256 4128 4126 11257 4092 4127 11258 4093 4155 11259 4121 4163 11260 4129 4156 11261 4122 4163 11262 4129 4155 11263 4121 4162 11264 4128 4156 11265 4122 4164 11266 4130 4157 11267 4123 4164 11268 4130 4156 11269 4122 4163 11270 4129 4127 11271 4093 4165 11272 4131 4162 11273 4128 4165 11274 4131 4127 11275 4093 4128 11276 4094 4162 11277 4128 4166 11278 4132 4163 11279 4129 4166 11280 4132 4162 11281 4128 4165 11282 4131 4163 11283 4129 4167 11284 4133 4164 11285 4130 4167 11286 4133 4163 11287 4129 4166 11288 4132 4157 11289 4123 4168 11290 4134 4160 11291 4126 4168 11292 4134 4157 11293 4123 4164 11294 4130 4160 11295 4126 4169 11296 4135 4161 11297 4127 4169 11298 4135 4160 11299 4126 4168 11300 4134 4161 11301 4127 4140 11302 4106 4141 11303 4107 4140 11304 4106 4161 11305 4127 4169 11306 4135 4164 11307 4130 4170 11308 4136 4168 11309 4134 4170 11310 4136 4164 11311 4130 4167 11312 4133 4168 11313 4134 4171 11314 4137 4169 11315 4135 4171 11316 4137 4168 11317 4134 4170 11318 4136 4169 11319 4135 4139 11320 4105 4140 11321 4106 4139 11322 4105 4169 11323 4135 4171 11324 4137 4128 11325 4094 4133 11326 4099 4165 11327 4131 4133 11328 4099 4128 11329 4094 4129 11330 4095 4165 11331 4131 4134 11332 4100 4166 11333 4132 4134 11334 4100 4165 11335 4131 4133 11336 4099 4166 11337 4132 4135 11338 4101 4167 11339 4133 4135 11340 4101 4166 11341 4132 4134 11342 4100 4167 11343 4133 4136 11344 4102 4170 11345 4136 4136 11346 4102 4167 11347 4133 4135 11348 4101 4170 11349 4136 4137 11350 4103 4171 11351 4137 4137 11352 4103 4170 11353 4136 4136 11354 4102 4171 11355 4137 4138 11356 4104 4139 11357 4105 4138 11358 4104 4171 11359 4137 4137 11360 4103 4187 11361 4153 4178 11362 4144 4172 11363 4138 4175 11364 4141 4173 11365 4139 4174 11366 4140 4176 11367 4142 4173 11368 4139 4175 11369 4141 4179 11370 4145 4173 11371 4139 4176 11372 4142 4179 11373 4145 4177 11374 4143 4173 11375 4139 4179 11376 4145 4178 11377 4144 4177 11378 4143 4172 11379 4138 4178 11380 4144 4179 11381 4145 4182 11382 4148 4180 11383 4146 4181 11384 4147 4183 11385 4149 4180 11386 4146 4182 11387 4148 4185 11388 4151 4180 11389 4146 4183 11390 4149 4185 11391 4151 4184 11392 4150 4180 11393 4146 4188 11394 4154 4184 11395 4150 4185 11396 4151 4188 11397 4154 4186 11398 4152 4184 11399 4150 4188 11400 4154 4187 11401 4153 4186 11402 4152 4189 11403 4155 4187 11404 4153 4188 11405 4154 4178 11406 4144 4187 11407 4153 4189 11408 4155 4221 11409 4187 4222 11410 4188 4223 11411 4189 4213 11412 4179 4190 11413 4156 4191 11414 4157 4219 11415 4185 4192 11416 4158 4193 11417 4159 4224 11418 4190 4221 11419 4187 4223 11420 4189 4224 11421 4190 4194 11422 4160 4221 11423 4187 4225 11424 4191 4194 11425 4160 4224 11426 4190 4225 11427 4191 4195 11428 4161 4194 11429 4160 4226 11430 4192 4195 11431 4161 4225 11432 4191 4226 11433 4192 4196 11434 4162 4195 11435 4161 4227 11436 4193 4196 11437 4162 4226 11438 4192 4227 11439 4193 4197 11440 4163 4196 11441 4162 4227 11442 4193 4198 11443 4164 4197 11444 4163 4227 11445 4193 4199 11446 4165 4198 11447 4164 4227 11448 4193 4200 11449 4166 4199 11450 4165 4228 11451 4194 4200 11452 4166 4227 11453 4193 4229 11454 4195 4200 11455 4166 4228 11456 4194 4229 11457 4195 4201 11458 4167 4200 11459 4166 4229 11460 4195 4202 11461 4168 4201 11462 4167 4230 11463 4196 4202 11464 4168 4229 11465 4195 4231 11466 4197 4202 11467 4168 4230 11468 4196 4231 11469 4197 4203 11470 4169 4202 11471 4168 4231 11472 4197 4204 11473 4170 4203 11474 4169 4232 11475 4198 4204 11476 4170 4231 11477 4197 4232 11478 4198 4205 11479 4171 4204 11480 4170 4233 11481 4199 4205 11482 4171 4232 11483 4198 4233 11484 4199 4206 11485 4172 4205 11486 4171 4233 11487 4199 4207 11488 4173 4206 11489 4172 4234 11490 4200 4207 11491 4173 4233 11492 4199 4234 11493 4200 4208 11494 4174 4207 11495 4173 4235 11496 4201 4208 11497 4174 4234 11498 4200 4235 11499 4201 4209 11500 4175 4208 11501 4174 4236 11502 4202 4209 11503 4175 4235 11504 4201 4236 11505 4202 4210 11506 4176 4209 11507 4175 4236 11508 4202 4211 11509 4177 4210 11510 4176 4237 11511 4203 4211 11512 4177 4236 11513 4202 4237 11514 4203 4212 11515 4178 4211 11516 4177 4238 11517 4204 4212 11518 4178 4237 11519 4203 4238 11520 4204 4213 11521 4179 4212 11522 4178 4239 11523 4205 4213 11524 4179 4238 11525 4204 4239 11526 4205 4190 11527 4156 4213 11528 4179 4240 11529 4206 4190 11530 4156 4239 11531 4205 4240 11532 4206 4214 11533 4180 4190 11534 4156 4241 11535 4207 4214 11536 4180 4240 11537 4206 4241 11538 4207 4215 11539 4181 4214 11540 4180 4242 11541 4208 4215 11542 4181 4241 11543 4207 4242 11544 4208 4216 11545 4182 4215 11546 4181 4243 11547 4209 4216 11548 4182 4242 11549 4208 4243 11550 4209 4217 11551 4183 4216 11552 4182 4244 11553 4210 4217 11554 4183 4243 11555 4209 4244 11556 4210 4218 11557 4184 4217 11558 4183 4245 11559 4211 4218 11560 4184 4244 11561 4210 4245 11562 4211 4219 11563 4185 4218 11564 4184 4245 11565 4211 4192 11566 4158 4219 11567 4185 4222 11568 4188 4192 11569 4158 4245 11570 4211 4222 11571 4188 4220 11572 4186 4192 11573 4158 4222 11574 4188 4221 11575 4187 4220 11576 4186 4245 11577 4211 4246 11578 4212 4222 11579 4188 4246 11580 4212 4245 11581 4211 4244 11582 4210 4222 11583 4188 4247 11584 4213 4223 11585 4189 4247 11586 4213 4222 11587 4188 4246 11588 4212 4223 11589 4189 4248 11590 4214 4224 11591 4190 4248 11592 4214 4223 11593 4189 4247 11594 4213 4224 11595 4190 4249 11596 4215 4225 11597 4191 4249 11598 4215 4224 11599 4190 4248 11600 4214 4225 11601 4191 4250 11602 4216 4226 11603 4192 4250 11604 4216 4225 11605 4191 4249 11606 4215 4226 11607 4192 4228 11608 4194 4227 11609 4193 4228 11610 4194 4226 11611 4192 4250 11612 4216 4244 11613 4210 4251 11614 4217 4246 11615 4212 4251 11616 4217 4244 11617 4210 4243 11618 4209 4243 11619 4209 4252 11620 4218 4251 11621 4217 4252 11622 4218 4243 11623 4209 4242 11624 4208 4246 11625 4212 4253 11626 4219 4247 11627 4213 4253 11628 4219 4246 11629 4212 4251 11630 4217 4251 11631 4217 4254 11632 4220 4253 11633 4219 4254 11634 4220 4251 11635 4217 4252 11636 4218 4247 11637 4213 4255 11638 4221 4248 11639 4214 4255 11640 4221 4247 11641 4213 4253 11642 4219 4253 11643 4219 4256 11644 4222 4255 11645 4221 4256 11646 4222 4253 11647 4219 4254 11648 4220 4248 11649 4214 4257 11650 4223 4249 11651 4215 4257 11652 4223 4248 11653 4214 4255 11654 4221 4255 11655 4221 4258 11656 4224 4257 11657 4223 4258 11658 4224 4255 11659 4221 4256 11660 4222 4249 11661 4215 4259 11662 4225 4250 11663 4216 4259 11664 4225 4249 11665 4215 4257 11666 4223 4257 11667 4223 4260 11668 4226 4259 11669 4225 4260 11670 4226 4257 11671 4223 4258 11672 4224 4250 11673 4216 4229 11674 4195 4228 11675 4194 4229 11676 4195 4250 11677 4216 4259 11678 4225 4259 11679 4225 4230 11680 4196 4229 11681 4195 4230 11682 4196 4259 11683 4225 4260 11684 4226 4242 11685 4208 4261 11686 4227 4252 11687 4218 4261 11688 4227 4242 11689 4208 4241 11690 4207 4241 11691 4207 4262 11692 4228 4261 11693 4227 4262 11694 4228 4241 11695 4207 4240 11696 4206 4252 11697 4218 4263 11698 4229 4254 11699 4220 4263 11700 4229 4252 11701 4218 4261 11702 4227 4261 11703 4227 4264 11704 4230 4263 11705 4229 4264 11706 4230 4261 11707 4227 4262 11708 4228 4254 11709 4220 4265 11710 4231 4256 11711 4222 4265 11712 4231 4254 11713 4220 4263 11714 4229 4263 11715 4229 4266 11716 4232 4265 11717 4231 4266 11718 4232 4263 11719 4229 4264 11720 4230 4256 11721 4222 4267 11722 4233 4258 11723 4224 4267 11724 4233 4256 11725 4222 4265 11726 4231 4265 11727 4231 4268 11728 4234 4267 11729 4233 4268 11730 4234 4265 11731 4231 4266 11732 4232 4258 11733 4224 4269 11734 4235 4260 11735 4226 4269 11736 4235 4258 11737 4224 4267 11738 4233 4267 11739 4233 4270 11740 4236 4269 11741 4235 4270 11742 4236 4267 11743 4233 4268 11744 4234 4260 11745 4226 4231 11746 4197 4230 11747 4196 4231 11748 4197 4260 11749 4226 4269 11750 4235 4269 11751 4235 4232 11752 4198 4231 11753 4197 4232 11754 4198 4269 11755 4235 4270 11756 4236 4240 11757 4206 4238 11758 4204 4262 11759 4228 4238 11760 4204 4240 11761 4206 4239 11762 4205 4262 11763 4228 4237 11764 4203 4264 11765 4230 4237 11766 4203 4262 11767 4228 4238 11768 4204 4264 11769 4230 4236 11770 4202 4266 11771 4232 4236 11772 4202 4264 11773 4230 4237 11774 4203 4266 11775 4232 4235 11776 4201 4268 11777 4234 4235 11778 4201 4266 11779 4232 4236 11780 4202 4268 11781 4234 4234 11782 4200 4270 11783 4236 4234 11784 4200 4268 11785 4234 4235 11786 4201 4270 11787 4236 4233 11788 4199 4232 11789 4198 4233 11790 4199 4270 11791 4236 4234 11792 4200 4287 11793 4253 4271 11794 4237 4272 11795 4238 4277 11796 4243 4273 11797 4239 4274 11798 4240 4277 11799 4243 4275 11800 4241 4273 11801 4239 4277 11802 4243 4276 11803 4242 4275 11804 4241 4279 11805 4245 4276 11806 4242 4277 11807 4243 4279 11808 4245 4278 11809 4244 4276 11810 4242 4281 11811 4247 4278 11812 4244 4279 11813 4245 4281 11814 4247 4280 11815 4246 4278 11816 4244 4282 11817 4248 4280 11818 4246 4281 11819 4247 4284 11820 4250 4280 11821 4246 4282 11822 4248 4284 11823 4250 4283 11824 4249 4280 11825 4246 4286 11826 4252 4283 11827 4249 4284 11828 4250 4286 11829 4252 4285 11830 4251 4283 11831 4249 4288 11832 4254 4285 11833 4251 4286 11834 4252 4288 11835 4254 4287 11836 4253 4285 11837 4251 4271 11838 4237 4287 11839 4253 4288 11840 4254 4304 11841 4270 4289 11842 4255 4290 11843 4256 4293 11844 4259 4291 11845 4257 4292 11846 4258 4294 11847 4260 4291 11848 4257 4293 11849 4259 4296 11850 4262 4291 11851 4257 4294 11852 4260 4296 11853 4262 4295 11854 4261 4291 11855 4257 4298 11856 4264 4295 11857 4261 4296 11858 4262 4298 11859 4264 4297 11860 4263 4295 11861 4261 4300 11862 4266 4297 11863 4263 4298 11864 4264 4300 11865 4266 4299 11866 4265 4297 11867 4263 4301 11868 4267 4299 11869 4265 4300 11870 4266 4303 11871 4269 4299 11872 4265 4301 11873 4267 4303 11874 4269 4302 11875 4268 4299 11876 4265 4289 11877 4255 4302 11878 4268 4303 11879 4269 4289 11880 4255 4304 11881 4270 4302 11882 4268 4320 11883 4286 4306 11884 4272 4305 11885 4271 4308 11886 4274 4306 11887 4272 4307 11888 4273 4305 11889 4271 4306 11890 4272 4308 11891 4274 4311 11892 4277 4309 11893 4275 4310 11894 4276 4313 11895 4279 4309 11896 4275 4311 11897 4277 4313 11898 4279 4312 11899 4278 4309 11900 4275 4314 11901 4280 4312 11902 4278 4313 11903 4279 4316 11904 4282 4312 11905 4278 4314 11906 4280 4316 11907 4282 4315 11908 4281 4312 11909 4278 4319 11910 4285 4315 11911 4281 4316 11912 4282 4319 11913 4285 4317 11914 4283 4315 11915 4281 4319 11916 4285 4318 11917 4284 4317 11918 4283 4321 11919 4287 4318 11920 4284 4319 11921 4285 4321 11922 4287 4320 11923 4286 4318 11924 4284 4322 11925 4288 4320 11926 4286 4321 11927 4287 4306 11928 4272 4320 11929 4286 4322 11930 4288 4340 11931 4306 4323 11932 4289 4328 11933 4294 4326 11934 4292 4324 11935 4290 4325 11936 4291 4327 11937 4293 4324 11938 4290 4326 11939 4292 4340 11940 4306 4324 11941 4290 4327 11942 4293 4340 11943 4306 4328 11944 4294 4324 11945 4290 4332 11946 4298 4329 11947 4295 4330 11948 4296 4332 11949 4298 4331 11950 4297 4329 11951 4295 4335 11952 4301 4331 11953 4297 4332 11954 4298 4335 11955 4301 4333 11956 4299 4331 11957 4297 4335 11958 4301 4334 11959 4300 4333 11960 4299 4337 11961 4303 4334 11962 4300 4335 11963 4301 4337 11964 4303 4336 11965 4302 4334 11966 4300 4339 11967 4305 4336 11968 4302 4337 11969 4303 4339 11970 4305 4338 11971 4304 4336 11972 4302 4323 11973 4289 4338 11974 4304 4339 11975 4305 4323 11976 4289 4340 11977 4306 4338 11978 4304 4358 11979 4324 4341 11980 4307 4345 11981 4311 4344 11982 4310 4342 11983 4308 4343 11984 4309 4346 11985 4312 4342 11986 4308 4344 11987 4310 4346 11988 4312 4345 11989 4311 4342 11990 4308 4358 11991 4324 4345 11992 4311 4346 11993 4312 4349 11994 4315 4347 11995 4313 4348 11996 4314 4350 11997 4316 4347 11998 4313 4349 11999 4315 4352 12000 4318 4347 12001 4313 4350 12002 4316 4352 12003 4318 4351 12004 4317 4347 12005 4313 4354 12006 4320 4351 12007 4317 4352 12008 4318 4354 12009 4320 4353 12010 4319 4351 12011 4317 4356 12012 4322 4353 12013 4319 4354 12014 4320 4356 12015 4322 4355 12016 4321 4353 12017 4319 4341 12018 4307 4355 12019 4321 4356 12020 4322 4341 12021 4307 4357 12022 4323 4355 12023 4321 4341 12024 4307 4358 12025 4324 4357 12026 4323

+
+
+ + + + +0.021304 0.500000 1.000000 +0.021304 0.500000 0.000000 +0.418849 0.010610 0.000000 +0.521304 0.000000 0.000000 +0.521304 0.000000 1.000000 +0.418849 0.010610 1.000000 +0.322715 0.041129 0.000000 +0.322715 0.041129 1.000000 +0.237987 0.088015 0.000000 +0.167751 0.146447 0.000000 +0.237987 0.088015 1.000000 +0.109320 0.216683 0.000000 +0.167751 0.146447 1.000000 +0.109320 0.216683 1.000000 +0.062433 0.301411 0.000000 +0.062433 0.301411 1.000000 +0.031914 0.397545 0.000000 +0.031914 0.397545 1.000000 +0.521304 0.000000 0.000000 +4.135448 0.000000 0.000000 +4.135448 0.000000 1.000000 +0.521304 0.000000 1.000000 +4.635013 0.479149 0.000000 +6.546594 46.279148 0.000000 +6.546594 46.279148 1.000000 +4.635013 0.479149 1.000000 +2.432885 46.799999 1.000000 +6.047029 46.799999 1.000000 +6.047029 46.799999 0.000000 +2.432885 46.799999 0.000000 +0.021739 0.520851 1.000000 +1.933320 46.320850 1.000000 +1.933320 46.320850 0.000000 +0.021739 0.520851 0.000000 +0.021739 0.520851 1.000000 +0.021304 0.500000 1.000000 +2.021891 46.584751 1.000000 +1.974224 46.499073 1.000000 +1.944994 46.409370 1.000000 +2.086782 46.660851 1.000000 +2.165519 46.722511 1.000000 +2.253112 46.766563 1.000000 +2.343956 46.792027 1.000000 +2.432885 46.799999 1.000000 +1.933320 46.320850 1.000000 +6.047029 46.799999 1.000000 +6.146117 46.790085 1.000000 +6.243177 46.759918 1.000000 +6.332133 46.710751 1.000000 +6.407879 46.646103 1.000000 +6.469311 46.567726 1.000000 +6.514728 46.476799 1.000000 +6.540818 46.378563 1.000000 +6.546594 46.279148 1.000000 +4.635013 0.479149 1.000000 +4.623340 0.390630 1.000000 +4.594109 0.300927 1.000000 +4.546442 0.215247 1.000000 +4.481551 0.139150 1.000000 +4.402814 0.077489 1.000000 +4.315221 0.033436 1.000000 +4.224378 0.007972 1.000000 +4.135448 0.000000 1.000000 +0.521304 0.000000 1.000000 +0.430323 0.008347 1.000000 +0.337257 0.035106 1.000000 +0.247699 0.081502 1.000000 +0.167751 0.146447 1.000000 +0.102806 0.226395 1.000000 +0.056410 0.315953 1.000000 +0.029651 0.409018 1.000000 +0.029651 0.409018 0.000000 +0.021304 0.500000 0.000000 +6.514728 46.476799 0.000000 +6.540818 46.378563 0.000000 +6.469311 46.567726 0.000000 +6.407879 46.646103 0.000000 +6.332133 46.710751 0.000000 +6.243177 46.759918 0.000000 +6.146117 46.790085 0.000000 +6.047029 46.799999 0.000000 +6.546594 46.279148 0.000000 +2.432885 46.799999 0.000000 +2.343956 46.792027 0.000000 +2.253112 46.766563 0.000000 +2.165519 46.722511 0.000000 +2.086782 46.660851 0.000000 +2.021891 46.584751 0.000000 +1.974224 46.499073 0.000000 +1.944994 46.409370 0.000000 +1.933320 46.320850 0.000000 +0.021739 0.520851 0.000000 +4.635013 0.479149 0.000000 +4.623340 0.390630 0.000000 +4.594109 0.300927 0.000000 +4.546442 0.215247 0.000000 +4.481551 0.139150 0.000000 +4.402814 0.077489 0.000000 +4.315221 0.033436 0.000000 +4.224378 0.007972 0.000000 +4.135448 0.000000 0.000000 +0.521304 0.000000 0.000000 +0.430323 0.008347 0.000000 +0.337257 0.035106 0.000000 +0.247699 0.081502 0.000000 +0.167751 0.146447 0.000000 +0.102806 0.226395 0.000000 +0.056410 0.315953 0.000000 +0.021304 0.500000 1.000000 +0.021739 0.520851 1.000000 +0.021739 0.520851 0.000000 +0.021413 0.510428 1.000000 +0.021413 0.510428 0.000000 +0.021304 0.500000 0.000000 +4.135448 0.000000 1.000000 +4.135448 0.000000 0.000000 +4.622595 0.387361 0.000000 +4.635013 0.479149 0.000000 +4.635013 0.479149 1.000000 +4.622595 0.387361 1.000000 +4.590077 0.291885 0.000000 +4.590077 0.291885 1.000000 +4.541434 0.208152 0.000000 +4.541434 0.208152 1.000000 +4.481551 0.139150 0.000000 +4.481551 0.139150 1.000000 +4.410111 0.082196 0.000000 +4.324424 0.037087 0.000000 +4.410111 0.082196 1.000000 +4.324424 0.037087 1.000000 +4.227674 0.008579 0.000000 +4.227674 0.008579 1.000000 +2.026899 46.591846 1.000000 +1.945738 46.412640 0.000000 +1.933320 46.320850 0.000000 +1.933320 46.320850 1.000000 +1.978256 46.508114 0.000000 +1.945738 46.412640 1.000000 +2.026899 46.591846 0.000000 +1.978256 46.508114 1.000000 +2.340659 46.791420 1.000000 +2.432885 46.799999 1.000000 +2.432885 46.799999 0.000000 +2.340659 46.791420 0.000000 +2.243910 46.762913 1.000000 +2.158221 46.717804 1.000000 +2.243910 46.762913 0.000000 +2.158221 46.717804 0.000000 +2.086782 46.660851 1.000000 +2.086782 46.660851 0.000000 +6.464833 46.574665 0.000000 +6.546594 46.279148 1.000000 +6.546594 46.279148 0.000000 +6.546920 46.289574 1.000000 +6.538450 46.392227 1.000000 +6.546920 46.289574 0.000000 +6.538450 46.392227 0.000000 +6.509942 46.488976 1.000000 +6.464833 46.574665 1.000000 +6.509942 46.488976 0.000000 +6.047029 46.799999 0.000000 +6.047029 46.799999 1.000000 +6.057456 46.799892 0.000000 +6.057456 46.799892 1.000000 +6.159668 46.787148 0.000000 +6.159668 46.787148 1.000000 +6.255145 46.754631 0.000000 +6.255145 46.754631 1.000000 +6.338877 46.705986 0.000000 +6.407879 46.646103 0.000000 +6.338877 46.705986 1.000000 +6.407879 46.646103 1.000000 + + + + + + + + + + + +-0.978781 -0.204909 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.204909 -0.978781 0.000000 +0.000000 -1.000000 0.000000 +-0.204909 -0.978781 0.000000 +-0.204909 -0.978781 0.000000 +0.000000 -1.000000 0.000000 +-0.397177 -0.917742 0.000000 +-0.204909 -0.978781 0.000000 +-0.204909 -0.978781 0.000000 +-0.397177 -0.917742 0.000000 +-0.397177 -0.917742 0.000000 +-0.204909 -0.978781 0.000000 +-0.566635 -0.823969 0.000000 +-0.397177 -0.917742 0.000000 +-0.397177 -0.917742 0.000000 +-0.566635 -0.823969 0.000000 +-0.566635 -0.823969 0.000000 +-0.397177 -0.917742 0.000000 +-0.566635 -0.823969 0.000000 +-0.707107 -0.707107 0.000000 +-0.566635 -0.823969 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.566635 -0.823969 0.000000 +-0.707107 -0.707107 0.000000 +-0.823969 -0.566635 0.000000 +-0.707107 -0.707107 0.000000 +-0.823969 -0.566635 0.000000 +-0.823969 -0.566635 0.000000 +-0.707107 -0.707107 0.000000 +-0.917742 -0.397177 0.000000 +-0.823969 -0.566635 0.000000 +-0.823969 -0.566635 0.000000 +-0.917742 -0.397177 0.000000 +-0.917742 -0.397177 0.000000 +-0.823969 -0.566635 0.000000 +-0.978781 -0.204909 0.000000 +-0.917742 -0.397177 0.000000 +-0.917742 -0.397177 0.000000 +-0.978781 -0.204909 0.000000 +-0.978781 -0.204909 0.000000 +-0.917742 -0.397177 0.000000 +-1.000000 0.000000 0.000000 +-0.978781 -0.204909 0.000000 +-0.978781 -0.204909 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.999130 -0.041701 0.000000 +0.999130 -0.041701 0.000000 +0.999130 -0.041701 0.000000 +0.999130 -0.041701 0.000000 +0.999130 -0.041701 0.000000 +0.999130 -0.041701 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999130 0.041701 0.000000 +-0.999130 0.041701 0.000000 +-0.999130 0.041701 0.000000 +-0.999130 0.041701 0.000000 +-0.999130 0.041701 0.000000 +-0.999130 0.041701 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.999783 0.020855 0.000000 +-1.000000 0.000000 0.000000 +-0.999783 0.020855 0.000000 +-0.999783 0.020855 0.000000 +-0.999130 0.041701 0.000000 +-0.999130 0.041701 0.000000 +-0.999783 0.020855 0.000000 +-0.999783 0.020855 0.000000 +-0.999130 0.041701 0.000000 +-1.000000 0.000000 0.000000 +-0.999783 0.020855 0.000000 +-1.000000 0.000000 0.000000 +0.184452 -0.982841 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.999130 -0.041701 0.000000 +0.974295 -0.225278 0.000000 +0.999130 -0.041701 0.000000 +0.974295 -0.225278 0.000000 +0.974295 -0.225278 0.000000 +0.999130 -0.041701 0.000000 +0.909259 -0.416231 0.000000 +0.974295 -0.225278 0.000000 +0.974295 -0.225278 0.000000 +0.909259 -0.416231 0.000000 +0.909259 -0.416231 0.000000 +0.974295 -0.225278 0.000000 +0.811973 -0.583695 0.000000 +0.909259 -0.416231 0.000000 +0.909259 -0.416231 0.000000 +0.811973 -0.583695 0.000000 +0.811973 -0.583695 0.000000 +0.909259 -0.416231 0.000000 +0.692206 -0.721700 0.000000 +0.811973 -0.583695 0.000000 +0.811973 -0.583695 0.000000 +0.692206 -0.721700 0.000000 +0.692206 -0.721700 0.000000 +0.811973 -0.583695 0.000000 +0.549327 -0.835607 0.000000 +0.692206 -0.721700 0.000000 +0.692206 -0.721700 0.000000 +0.549327 -0.835607 0.000000 +0.549327 -0.835607 0.000000 +0.692206 -0.721700 0.000000 +0.549327 -0.835607 0.000000 +0.377951 -0.925825 0.000000 +0.549327 -0.835607 0.000000 +0.377951 -0.925825 0.000000 +0.377951 -0.925825 0.000000 +0.549327 -0.835607 0.000000 +0.184452 -0.982841 0.000000 +0.377951 -0.925825 0.000000 +0.377951 -0.925825 0.000000 +0.184452 -0.982841 0.000000 +0.184452 -0.982841 0.000000 +0.377951 -0.925825 0.000000 +0.000000 -1.000000 0.000000 +0.184452 -0.982841 0.000000 +0.184452 -0.982841 0.000000 +-0.692206 0.721700 0.000000 +-0.811973 0.583695 0.000000 +-0.811973 0.583695 0.000000 +-0.999130 0.041701 0.000000 +-0.974295 0.225278 0.000000 +-0.999130 0.041701 0.000000 +-0.974295 0.225278 0.000000 +-0.974295 0.225278 0.000000 +-0.999130 0.041701 0.000000 +-0.974295 0.225278 0.000000 +-0.909259 0.416231 0.000000 +-0.974295 0.225278 0.000000 +-0.909259 0.416231 0.000000 +-0.909259 0.416231 0.000000 +-0.974295 0.225278 0.000000 +-0.909259 0.416231 0.000000 +-0.811973 0.583695 0.000000 +-0.909259 0.416231 0.000000 +-0.811973 0.583695 0.000000 +-0.811973 0.583695 0.000000 +-0.909259 0.416231 0.000000 +0.000000 1.000000 0.000000 +-0.184452 0.982841 0.000000 +0.000000 1.000000 0.000000 +-0.184452 0.982841 0.000000 +-0.184452 0.982841 0.000000 +0.000000 1.000000 0.000000 +-0.377951 0.925825 0.000000 +-0.184452 0.982841 0.000000 +-0.184452 0.982841 0.000000 +-0.377951 0.925825 0.000000 +-0.377951 0.925825 0.000000 +-0.184452 0.982841 0.000000 +-0.377951 0.925825 0.000000 +-0.549327 0.835607 0.000000 +-0.377951 0.925825 0.000000 +-0.549327 0.835607 0.000000 +-0.549327 0.835607 0.000000 +-0.377951 0.925825 0.000000 +-0.692206 0.721700 0.000000 +-0.549327 0.835607 0.000000 +-0.549327 0.835607 0.000000 +-0.692206 0.721700 0.000000 +-0.692206 0.721700 0.000000 +-0.549327 0.835607 0.000000 +-0.811973 0.583695 0.000000 +-0.692206 0.721700 0.000000 +-0.692206 0.721700 0.000000 +0.721700 0.692206 0.000000 +0.835607 0.549327 0.000000 +0.835607 0.549327 0.000000 +0.999783 -0.020855 0.000000 +0.999130 -0.041701 0.000000 +0.999130 -0.041701 0.000000 +0.999783 -0.020855 0.000000 +0.999783 -0.020855 0.000000 +0.999130 -0.041701 0.000000 +0.999783 -0.020855 0.000000 +0.982841 0.184452 0.000000 +0.999783 -0.020855 0.000000 +0.982841 0.184452 0.000000 +0.982841 0.184452 0.000000 +0.999783 -0.020855 0.000000 +0.925825 0.377951 0.000000 +0.982841 0.184452 0.000000 +0.982841 0.184452 0.000000 +0.925825 0.377951 0.000000 +0.925825 0.377951 0.000000 +0.982841 0.184452 0.000000 +0.925825 0.377951 0.000000 +0.835607 0.549327 0.000000 +0.925825 0.377951 0.000000 +0.835607 0.549327 0.000000 +0.835607 0.549327 0.000000 +0.925825 0.377951 0.000000 +0.020855 0.999783 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.020855 0.999783 0.000000 +0.020855 0.999783 0.000000 +0.000000 1.000000 0.000000 +0.225278 0.974295 0.000000 +0.020855 0.999783 0.000000 +0.020855 0.999783 0.000000 +0.225278 0.974295 0.000000 +0.225278 0.974295 0.000000 +0.020855 0.999783 0.000000 +0.416231 0.909259 0.000000 +0.225278 0.974295 0.000000 +0.225278 0.974295 0.000000 +0.416231 0.909259 0.000000 +0.416231 0.909259 0.000000 +0.225278 0.974295 0.000000 +0.583695 0.811973 0.000000 +0.416231 0.909259 0.000000 +0.416231 0.909259 0.000000 +0.583695 0.811973 0.000000 +0.583695 0.811973 0.000000 +0.416231 0.909259 0.000000 +0.583695 0.811973 0.000000 +0.721700 0.692206 0.000000 +0.583695 0.811973 0.000000 +0.721700 0.692206 0.000000 +0.721700 0.692206 0.000000 +0.583695 0.811973 0.000000 +0.835607 0.549327 0.000000 +0.721700 0.692206 0.000000 +0.721700 0.692206 0.000000 + + + + + + + + + + + +0.396240 0.000000 +0.396240 0.126945 +0.309562 0.126945 +0.297180 0.126945 +0.297180 -0.000000 +0.309562 -0.000000 +0.321945 0.126945 +0.321945 0.000000 +0.334327 0.126945 +0.346710 0.126945 +0.334327 -0.000000 +0.359092 0.126945 +0.346710 -0.000000 +0.359092 -0.000000 +0.371475 0.126945 +0.371475 -0.000000 +0.383857 0.126945 +0.383857 -0.000000 +-0.126945 -0.066177 +-0.126945 -0.524975 +0.000000 -0.524975 +0.000000 -0.066177 +-0.126945 -0.060879 +-0.126945 -5.880026 +0.000000 -5.880026 +0.000000 -0.060879 +0.060879 -0.000000 +0.519676 -0.000000 +0.519676 0.126945 +0.060879 0.126945 +0.000000 0.066177 +0.000000 5.885324 +-0.126945 5.885324 +-0.126945 0.066177 +0.002760 0.066119 +0.002704 0.063473 +0.256669 5.913706 +0.250618 5.902829 +0.246907 5.891442 +0.264907 5.923366 +0.274902 5.931194 +0.286022 5.936786 +0.297554 5.940019 +0.308843 5.941031 +0.245426 5.880205 +0.767641 5.941031 +0.780219 5.939772 +0.792541 5.935943 +0.803833 5.929701 +0.813449 5.921494 +0.821247 5.911545 +0.827013 5.900002 +0.830325 5.887531 +0.831058 5.874911 +0.588392 0.060826 +0.586910 0.049589 +0.583200 0.038201 +0.577148 0.027325 +0.568911 0.017664 +0.558916 0.009837 +0.547796 0.004245 +0.536264 0.001012 +0.524975 0.000000 +0.066177 0.000000 +0.054627 0.001060 +0.042813 0.004457 +0.031444 0.010346 +0.021295 0.018591 +0.013051 0.028740 +0.007161 0.040109 +0.003764 0.051923 +0.051923 0.003764 +0.063473 0.002704 +5.900002 0.827013 +5.887531 0.830325 +5.911545 0.821247 +5.921494 0.813449 +5.929701 0.803833 +5.935943 0.792541 +5.939772 0.780219 +5.941031 0.767641 +5.874911 0.831058 +5.941031 0.308843 +5.940019 0.297554 +5.936786 0.286022 +5.931194 0.274902 +5.923366 0.264907 +5.913706 0.256669 +5.902829 0.250618 +5.891442 0.246907 +5.880205 0.245426 +0.066119 0.002760 +0.060826 0.588392 +0.049589 0.586910 +0.038201 0.583200 +0.027325 0.577148 +0.017664 0.568911 +0.009837 0.558916 +0.004245 0.547796 +0.001012 0.536264 +0.000000 0.524975 +0.000000 0.066177 +0.001060 0.054627 +0.004457 0.042813 +0.010346 0.031444 +0.018591 0.021295 +0.028740 0.013051 +0.040109 0.007161 +-0.000139 -0.000000 +0.002770 -0.000000 +0.002770 0.126945 +0.001315 -0.000000 +0.001315 0.126945 +-0.000139 0.126945 +0.297248 -0.000000 +0.297248 0.126945 +0.211818 0.126945 +0.200682 0.126945 +0.200682 -0.000000 +0.211818 0.000000 +0.224200 0.126945 +0.224200 -0.000000 +0.236583 0.126945 +0.236583 0.000000 +0.248965 0.126945 +0.248965 0.000000 +0.261348 0.126945 +0.273730 0.126945 +0.261348 -0.000000 +0.273730 -0.000000 +0.286113 0.126945 +0.286113 -0.000000 +0.038463 0.000000 +0.013698 0.126945 +0.002562 0.126945 +0.002562 -0.000000 +0.026080 0.126945 +0.013698 0.000000 +0.038463 0.126945 +0.026080 0.000000 +0.087993 -0.000000 +0.099128 0.000000 +0.099128 0.126945 +0.087993 0.126945 +0.075610 -0.000000 +0.063228 -0.000000 +0.075610 0.126945 +0.063228 0.126945 +0.050845 -0.000000 +0.050845 0.126945 +0.162288 0.126945 +0.200682 0.000000 +0.200682 0.126945 +0.199435 -0.000000 +0.187053 -0.000000 +0.199435 0.126945 +0.187053 0.126945 +0.174670 -0.000000 +0.162288 0.000000 +0.174670 0.126945 +0.099128 0.126945 +0.099128 -0.000000 +0.100375 0.126945 +0.100375 -0.000000 +0.112758 0.126945 +0.112758 0.000000 +0.125140 0.126945 +0.125140 0.000000 +0.137523 0.126945 +0.149905 0.126945 +0.137523 0.000000 +0.149905 -0.000000 + + + + + + + + + + + +

16 0 16 0 1 0 1 2 1 4 3 4 2 4 2 3 5 3 5 6 5 2 7 2 4 8 4 7 9 7 2 10 2 5 11 5 7 12 7 6 13 6 2 14 2 10 15 10 6 16 6 7 17 7 10 18 10 8 19 8 6 20 6 10 21 10 9 22 9 8 23 8 12 24 12 9 25 9 10 26 10 12 27 12 11 28 11 9 29 9 13 30 13 11 31 11 12 32 12 15 33 15 11 34 11 13 35 13 15 36 15 14 37 14 11 38 11 17 39 17 14 40 14 15 41 15 17 42 17 16 43 16 14 44 14 0 45 0 16 46 16 17 47 17 20 48 20 18 49 18 19 50 19 18 51 18 20 52 20 21 53 21 24 54 24 22 55 22 23 56 23 22 57 22 24 58 24 25 59 25 28 60 28 26 61 26 27 62 27 26 63 26 28 64 28 29 65 29 32 66 32 30 67 30 31 68 31 30 69 30 32 70 32 33 71 33 70 72 70 34 73 34 35 74 35 38 75 38 36 76 36 37 77 37 44 78 44 36 79 36 38 80 38 44 81 44 39 82 39 36 83 36 44 84 44 40 85 40 39 86 39 44 87 44 41 88 41 40 89 40 44 90 44 42 91 42 41 92 41 44 93 44 43 94 43 42 95 42 34 96 34 43 97 43 44 98 44 34 99 34 45 100 45 43 101 43 34 102 34 46 103 46 45 104 45 34 105 34 47 106 47 46 107 46 34 108 34 48 109 48 47 110 47 34 111 34 49 112 49 48 113 48 34 114 34 50 115 50 49 116 49 34 117 34 51 118 51 50 119 50 34 120 34 52 121 52 51 122 51 34 123 34 53 124 53 52 125 52 34 126 34 54 127 54 53 128 53 34 129 34 55 130 55 54 131 54 34 132 34 56 133 56 55 134 55 34 135 34 57 136 57 56 137 56 34 138 34 58 139 58 57 140 57 34 141 34 59 142 59 58 143 58 34 144 34 60 145 60 59 146 59 34 147 34 61 148 61 60 149 60 34 150 34 62 151 62 61 152 61 34 153 34 63 154 63 62 155 62 34 156 34 64 157 64 63 158 63 34 159 34 65 160 65 64 161 64 34 162 34 66 163 66 65 164 65 34 165 34 67 166 67 66 167 66 34 168 34 68 169 68 67 170 67 34 171 34 69 172 69 68 173 68 34 174 34 70 175 70 69 176 69 91 177 91 71 178 71 72 179 72 81 180 81 73 181 73 74 182 74 81 183 81 75 184 75 73 185 73 81 186 81 76 187 76 75 188 75 81 189 81 77 190 77 76 191 76 81 192 81 78 193 78 77 194 77 81 195 81 79 196 79 78 197 78 81 198 81 80 199 80 79 200 79 92 201 92 80 202 80 81 203 81 92 204 92 82 205 82 80 206 80 92 207 92 83 208 83 82 209 82 92 210 92 84 211 84 83 212 83 92 213 92 85 214 85 84 215 84 92 216 92 86 217 86 85 218 85 92 219 92 87 220 87 86 221 86 92 222 92 88 223 88 87 224 87 92 225 92 89 226 89 88 227 88 92 228 92 90 229 90 89 230 89 92 231 92 91 232 91 90 233 90 93 234 93 91 235 91 92 236 92 94 237 94 91 238 91 93 239 93 95 240 95 91 241 91 94 242 94 96 243 96 91 244 91 95 245 95 97 246 97 91 247 91 96 248 96 98 249 98 91 250 91 97 251 97 99 252 99 91 253 91 98 254 98 100 255 100 91 256 91 99 257 99 101 258 101 91 259 91 100 260 100 102 261 102 91 262 91 101 263 101 103 264 103 91 265 91 102 266 102 104 267 104 91 268 91 103 269 103 105 270 105 91 271 91 104 272 104 106 273 106 91 274 91 105 275 105 107 276 107 91 277 91 106 278 106 71 279 71 91 280 91 107 281 107 112 282 112 108 283 108 111 284 111 112 285 112 109 286 109 110 287 110 112 288 112 111 289 111 109 290 109 108 291 108 112 292 112 113 293 113 130 294 130 114 295 114 115 296 115 118 297 118 116 298 116 117 299 117 119 300 119 116 301 116 118 302 118 121 303 121 116 304 116 119 305 119 121 306 121 120 307 120 116 308 116 123 309 123 120 310 120 121 311 121 123 312 123 122 313 122 120 314 120 125 315 125 122 316 122 123 317 123 125 318 125 124 319 124 122 320 122 128 321 128 124 322 124 125 323 125 128 324 128 126 325 126 124 326 124 128 327 128 127 328 127 126 329 126 129 330 129 127 331 127 128 332 128 131 333 131 127 334 127 129 335 129 131 336 131 130 337 130 127 338 127 114 339 114 130 340 130 131 341 131 148 342 148 138 343 138 132 344 132 135 345 135 133 346 133 134 347 134 137 348 137 133 349 133 135 350 135 137 351 137 136 352 136 133 353 133 139 354 139 136 355 136 137 356 137 139 357 139 138 358 138 136 359 136 132 360 132 138 361 138 139 362 139 142 363 142 140 364 140 141 365 141 143 366 143 140 367 140 142 368 142 146 369 146 140 370 140 143 371 143 146 372 146 144 373 144 140 374 140 146 375 146 145 376 145 144 377 144 147 378 147 145 379 145 146 380 146 149 381 149 145 382 145 147 383 147 149 384 149 148 385 148 145 386 145 138 387 138 148 388 148 149 389 149 169 390 169 158 391 158 150 392 150 155 393 155 151 394 151 152 395 152 155 396 155 153 397 153 151 398 151 155 399 155 154 400 154 153 401 153 156 402 156 154 403 154 155 404 155 159 405 159 154 406 154 156 407 156 159 408 159 157 409 157 154 410 154 159 411 159 158 412 158 157 413 157 150 414 150 158 415 158 159 416 159 163 417 163 160 418 160 161 419 161 163 420 163 162 421 162 160 422 160 165 423 165 162 424 162 163 425 163 165 426 165 164 427 164 162 428 162 167 429 167 164 430 164 165 431 165 167 432 167 166 433 166 164 434 164 170 435 170 166 436 166 167 437 167 170 438 170 168 439 168 166 440 166 170 441 170 169 442 169 168 443 168 171 444 171 169 445 169 170 446 170 158 447 158 169 448 169 171 449 171

+
+
+ + + + +1.401116 -0.140982 5.000000 +1.396872 -0.100000 5.000000 +1.555890 -0.295756 0.000000 +1.596872 -0.300000 0.000000 +1.596872 -0.300000 5.000000 +1.517437 -0.283548 0.000000 +1.555890 -0.295756 5.000000 +1.517437 -0.283548 5.000000 +1.483545 -0.264794 0.000000 +1.483545 -0.264794 5.000000 +1.455451 -0.241421 0.000000 +1.432078 -0.213327 0.000000 +1.455451 -0.241421 5.000000 +1.432078 -0.213327 5.000000 +1.413324 -0.179435 0.000000 +1.401116 -0.140982 0.000000 +1.413324 -0.179435 5.000000 +1.396872 -0.100000 0.000000 +4.500000 0.300000 3.650000 +4.500000 -0.300000 3.650000 +4.500000 -0.300000 1.350000 +4.500000 0.300000 1.350000 +4.290742 -0.300000 1.369199 +4.290742 0.300000 1.369199 +4.076691 -0.300000 1.430743 +4.076691 0.300000 1.430743 +3.870709 -0.300000 1.537455 +3.870709 0.300000 1.537455 +3.686827 -0.300000 1.686827 +3.686827 0.300000 1.686827 +3.537455 -0.300000 1.870709 +3.537455 0.300000 1.870709 +3.430743 -0.300000 2.076691 +3.430743 0.300000 2.076691 +3.369199 -0.300000 2.290742 +3.369199 0.300000 2.290742 +3.350000 -0.300000 2.500000 +3.350000 0.300000 2.500000 +3.369199 -0.300000 2.709258 +3.369199 0.300000 2.709258 +3.430743 -0.300000 2.923309 +3.430743 0.300000 2.923309 +3.537455 -0.300000 3.129291 +3.537455 0.300000 3.129291 +3.686827 -0.300000 3.313173 +3.686827 0.300000 3.313173 +3.870709 -0.300000 3.462545 +3.870709 0.300000 3.462545 +4.076691 -0.300000 3.569257 +4.076691 0.300000 3.569257 +4.290742 -0.300000 3.630801 +4.290742 0.300000 3.630801 +1.397263 -0.087500 5.000000 +1.400000 0.000000 5.000000 +1.400000 0.000000 0.000000 +1.399316 -0.043771 5.000000 +1.399316 -0.043771 0.000000 +1.397263 -0.087500 0.000000 +1.400000 0.000000 0.000000 +1.400000 0.000000 5.000000 +-1.376628 0.254748 5.000000 +-1.400000 0.000000 5.000000 +-1.400000 0.000000 0.000000 +-1.376628 0.254748 0.000000 +-1.301704 0.515333 5.000000 +-1.301704 0.515333 0.000000 +-1.171794 0.766094 5.000000 +-1.171794 0.766094 0.000000 +-0.989949 0.989949 5.000000 +-0.989949 0.989949 0.000000 +-0.766094 1.171794 5.000000 +-0.766094 1.171794 0.000000 +-0.515333 1.301704 5.000000 +-0.515333 1.301704 0.000000 +-0.254748 1.376628 5.000000 +-0.254748 1.376628 0.000000 +0.000000 1.400000 5.000000 +0.000000 1.400000 0.000000 +0.254748 1.376628 5.000000 +0.254748 1.376628 0.000000 +0.515333 1.301704 5.000000 +0.515333 1.301704 0.000000 +0.766094 1.171794 5.000000 +0.766094 1.171794 0.000000 +0.989949 0.989949 5.000000 +0.989949 0.989949 0.000000 +1.171794 0.766094 5.000000 +1.171794 0.766094 0.000000 +1.301704 0.515333 5.000000 +1.301704 0.515333 0.000000 +1.376628 0.254748 5.000000 +1.376628 0.254748 0.000000 +-2.000000 0.000000 5.000000 +-2.000000 0.000000 0.000000 +1.675583 -1.091981 0.000000 +1.841167 -0.781091 0.000000 +1.841167 -0.781091 5.000000 +1.675583 -1.091981 5.000000 +1.422335 -1.406045 0.000000 +1.422335 -1.406045 5.000000 +1.104042 -1.667660 0.000000 +1.104042 -1.667660 5.000000 +0.738896 -1.858503 0.000000 +0.350869 -1.968982 0.000000 +0.738896 -1.858503 5.000000 +0.350869 -1.968982 5.000000 +-0.035257 -1.999689 0.000000 +-0.035257 -1.999689 5.000000 +-0.398538 -1.959890 0.000000 +-0.398538 -1.959890 5.000000 +-0.748512 -1.854651 0.000000 +-0.748512 -1.854651 5.000000 +-1.091981 -1.675583 0.000000 +-1.406045 -1.422335 0.000000 +-1.091981 -1.675583 5.000000 +-1.406045 -1.422335 5.000000 +-1.667660 -1.104042 0.000000 +-1.667660 -1.104042 5.000000 +-1.858503 -0.738896 0.000000 +-1.858503 -0.738896 5.000000 +-1.968982 -0.350869 0.000000 +-1.968982 -0.350869 5.000000 +1.397263 -0.087500 5.000000 +1.396872 -0.100000 5.000000 +1.690629 -1.068539 5.000000 +1.841167 -0.781091 5.000000 +1.288817 -0.546764 5.000000 +1.485778 -1.338829 5.000000 +1.183440 -0.747977 5.000000 +1.229884 -1.577145 5.000000 +1.040045 -0.937180 5.000000 +0.931497 -1.769834 5.000000 +0.860919 -1.104002 5.000000 +0.603730 -1.906701 5.000000 +0.652048 -1.238884 5.000000 +0.262410 -1.982710 5.000000 +0.422611 -1.334691 5.000000 +-0.076367 -1.998541 5.000000 +0.183687 -1.387897 5.000000 +-0.398538 -1.959890 5.000000 +-0.053457 -1.398979 5.000000 +-0.710219 -1.869649 5.000000 +-0.278977 -1.371923 5.000000 +-1.015909 -1.722768 5.000000 +-0.497153 -1.308755 5.000000 +-1.300437 -1.519494 5.000000 +-0.711136 -1.205937 5.000000 +-1.548721 -1.265489 5.000000 +-0.910306 -1.063646 5.000000 +-1.748157 -0.971569 5.000000 +-1.084105 -0.885842 5.000000 +-1.890657 -0.652241 5.000000 +-1.223710 -0.680098 5.000000 +-1.973678 -0.323412 5.000000 +-1.323460 -0.456568 5.000000 +-2.000000 0.000000 5.000000 +-1.381575 -0.226388 5.000000 +-1.970700 0.341092 5.000000 +-1.400000 0.000000 5.000000 +-1.877667 0.688743 5.000000 +-1.376628 0.254748 5.000000 +-1.717326 1.025082 5.000000 +-1.301704 0.515333 5.000000 +-1.492908 1.330874 5.000000 +-1.171794 0.766094 5.000000 +-1.214793 1.588797 5.000000 +-0.989949 0.989949 5.000000 +-0.899003 1.786559 5.000000 +-0.766094 1.171794 5.000000 +-0.564276 1.918748 5.000000 +-0.515333 1.301704 5.000000 +-0.228774 1.986872 5.000000 +-0.254748 1.376628 5.000000 +0.113430 1.996781 5.000000 +0.000000 1.400000 5.000000 +0.469441 1.944126 5.000000 +0.254748 1.376628 5.000000 +0.821913 1.823310 5.000000 +0.515333 1.301704 5.000000 +1.151369 1.635344 5.000000 +0.766094 1.171794 5.000000 +1.439412 1.388558 5.000000 +1.671998 1.097462 5.000000 +0.989949 0.989949 5.000000 +1.841608 0.780052 5.000000 +1.171794 0.766094 5.000000 +1.947662 0.454545 5.000000 +1.301704 0.515333 5.000000 +6.000000 -0.300000 5.000000 +6.000000 0.300000 5.000000 +1.596872 -0.300000 5.000000 +2.142429 0.300000 5.000000 +2.078438 0.310513 5.000000 +1.972444 0.394619 5.000000 +1.376628 0.254748 5.000000 +2.018112 0.343330 5.000000 +1.400000 0.000000 5.000000 +1.560479 -0.296661 5.000000 +1.523253 -0.285958 5.000000 +1.487430 -0.267399 5.000000 +1.455451 -0.241421 5.000000 +1.429473 -0.209442 5.000000 +1.410914 -0.173619 5.000000 +1.400211 -0.136393 5.000000 +1.400211 -0.136393 0.000000 +1.396872 -0.100000 0.000000 +1.288817 -0.546764 0.000000 +1.841167 -0.781091 0.000000 +1.183440 -0.747977 0.000000 +1.690629 -1.068539 0.000000 +1.040045 -0.937180 0.000000 +1.485778 -1.338829 0.000000 +0.860919 -1.104002 0.000000 +1.229884 -1.577145 0.000000 +0.652048 -1.238884 0.000000 +0.931497 -1.769834 0.000000 +0.422611 -1.334691 0.000000 +0.603730 -1.906701 0.000000 +0.183687 -1.387897 0.000000 +0.262410 -1.982710 0.000000 +-0.053457 -1.398979 0.000000 +-0.076367 -1.998541 0.000000 +-0.278977 -1.371923 0.000000 +-0.398538 -1.959890 0.000000 +-0.497153 -1.308755 0.000000 +-0.710219 -1.869649 0.000000 +-0.711136 -1.205937 0.000000 +-1.015909 -1.722768 0.000000 +-0.910306 -1.063646 0.000000 +-1.300437 -1.519494 0.000000 +-1.084105 -0.885842 0.000000 +-1.548721 -1.265489 0.000000 +-1.223710 -0.680098 0.000000 +-1.748157 -0.971569 0.000000 +-1.323460 -0.456568 0.000000 +-1.890657 -0.652241 0.000000 +-1.381575 -0.226388 0.000000 +-1.973678 -0.323412 0.000000 +-1.400000 0.000000 0.000000 +-2.000000 0.000000 0.000000 +-1.376628 0.254748 0.000000 +-1.970700 0.341092 0.000000 +-1.301704 0.515333 0.000000 +-1.877667 0.688743 0.000000 +-1.171794 0.766094 0.000000 +-1.717326 1.025082 0.000000 +-0.989949 0.989949 0.000000 +-1.492908 1.330874 0.000000 +-0.766094 1.171794 0.000000 +-1.214793 1.588797 0.000000 +-0.515333 1.301704 0.000000 +-0.899003 1.786559 0.000000 +-0.254748 1.376628 0.000000 +-0.564276 1.918748 0.000000 +0.000000 1.400000 0.000000 +-0.228774 1.986872 0.000000 +0.254748 1.376628 0.000000 +0.113430 1.996781 0.000000 +0.515333 1.301704 0.000000 +0.469441 1.944126 0.000000 +0.766094 1.171794 0.000000 +0.821913 1.823310 0.000000 +1.151369 1.635344 0.000000 +0.989949 0.989949 0.000000 +1.439412 1.388558 0.000000 +1.171794 0.766094 0.000000 +1.671998 1.097462 0.000000 +1.301704 0.515333 0.000000 +1.841608 0.780052 0.000000 +1.376628 0.254748 0.000000 +6.000000 0.300000 0.000000 +6.000000 -0.300000 0.000000 +2.142429 0.300000 0.000000 +2.078438 0.310513 0.000000 +2.018112 0.343330 0.000000 +1.947662 0.454545 0.000000 +1.400000 0.000000 0.000000 +1.972444 0.394619 0.000000 +1.397263 -0.087500 0.000000 +1.596872 -0.300000 0.000000 +1.560479 -0.296661 0.000000 +1.523253 -0.285958 0.000000 +1.487430 -0.267399 0.000000 +1.455451 -0.241421 0.000000 +1.429473 -0.209442 0.000000 +1.410914 -0.173619 0.000000 +1.912074 0.586492 5.000000 +1.947662 0.454545 5.000000 +-2.000000 0.000000 0.000000 +-2.000000 0.000000 5.000000 +-1.995331 0.136582 0.000000 +-1.931581 0.518646 0.000000 +-1.995331 0.136582 5.000000 +-1.931581 0.518646 5.000000 +-1.788191 0.895753 0.000000 +-1.566699 1.243163 0.000000 +-1.788191 0.895753 5.000000 +-1.566699 1.243163 5.000000 +-1.278719 1.537816 0.000000 +-1.278719 1.537816 5.000000 +-0.944069 1.763160 0.000000 +-0.944069 1.763160 5.000000 +-0.586492 1.912074 0.000000 +-0.586492 1.912074 5.000000 +-0.228774 1.986872 0.000000 +-0.228774 1.986872 5.000000 +0.136582 1.995331 0.000000 +0.136582 1.995331 5.000000 +0.518646 1.931581 0.000000 +0.518646 1.931581 5.000000 +0.895753 1.788191 0.000000 +0.895753 1.788191 5.000000 +1.243163 1.566699 0.000000 +1.243163 1.566699 5.000000 +1.537816 1.278719 0.000000 +1.537816 1.278719 5.000000 +1.763160 0.944069 0.000000 +1.912074 0.586492 0.000000 +1.763160 0.944069 5.000000 +1.947662 0.454545 0.000000 +-1.378288 -0.245608 0.000000 +-1.400000 0.000000 0.000000 +1.288817 -0.546764 5.000000 +1.288817 -0.546764 0.000000 +1.172908 -0.764387 5.000000 +1.172908 -0.764387 0.000000 +0.995634 -0.984232 5.000000 +0.995634 -0.984232 0.000000 +0.772830 -1.167362 5.000000 +0.772830 -1.167362 0.000000 +0.517227 -1.300952 5.000000 +0.517227 -1.300952 0.000000 +0.245608 -1.378288 5.000000 +0.245608 -1.378288 0.000000 +-0.024680 -1.399782 5.000000 +-0.024680 -1.399782 0.000000 +-0.278977 -1.371923 5.000000 +-0.523959 -1.298256 5.000000 +-0.278977 -1.371923 0.000000 +-0.523959 -1.298256 0.000000 +-0.764387 -1.172908 5.000000 +-0.984232 -0.995634 5.000000 +-0.764387 -1.172908 0.000000 +-0.984232 -0.995634 0.000000 +-1.167362 -0.772830 5.000000 +-1.300952 -0.517227 5.000000 +-1.167362 -0.772830 0.000000 +-1.300952 -0.517227 0.000000 +-1.378288 -0.245608 5.000000 +-1.400000 0.000000 5.000000 +3.537455 0.300000 3.129291 +5.129291 0.300000 3.462545 +2.142429 0.300000 5.000000 +4.923309 0.300000 3.569257 +4.709258 0.300000 3.630801 +4.500000 0.300000 3.650000 +4.290742 0.300000 3.630801 +4.076691 0.300000 3.569257 +3.870709 0.300000 3.462545 +3.686827 0.300000 3.313173 +5.313173 0.300000 3.313173 +6.000000 0.300000 5.000000 +6.181963 0.300000 4.983305 +6.368095 0.300000 4.929788 +6.547210 0.300000 4.836996 +6.707107 0.300000 4.707107 +6.836996 0.300000 4.547210 +6.929788 0.300000 4.368095 +6.983305 0.300000 4.181963 +5.462545 0.300000 3.129291 +7.000000 0.300000 4.000000 +5.569257 0.300000 2.923309 +5.630801 0.300000 2.709258 +5.650000 0.300000 2.500000 +5.630801 0.300000 2.290742 +5.569257 0.300000 2.076691 +5.462545 0.300000 1.870709 +5.313173 0.300000 1.686827 +7.000000 0.300000 1.000000 +6.983305 0.300000 0.818037 +6.929788 0.300000 0.631905 +6.836996 0.300000 0.452790 +6.707107 0.300000 0.292893 +6.547210 0.300000 0.163004 +6.368095 0.300000 0.070212 +6.181963 0.300000 0.016695 +5.129291 0.300000 1.537455 +4.923309 0.300000 1.430743 +6.000000 0.300000 0.000000 +4.709258 0.300000 1.369199 +4.500000 0.300000 1.350000 +4.290742 0.300000 1.369199 +4.076691 0.300000 1.430743 +3.870709 0.300000 1.537455 +3.686827 0.300000 1.686827 +3.537455 0.300000 1.870709 +3.430743 0.300000 2.076691 +2.142429 0.300000 0.000000 +3.369199 0.300000 2.290742 +3.350000 0.300000 2.500000 +3.369199 0.300000 2.709258 +3.430743 0.300000 2.923309 +6.368095 -0.300000 4.929788 +6.181963 -0.300000 4.983305 +4.923309 -0.300000 3.569257 +6.000000 -0.300000 5.000000 +4.709258 -0.300000 3.630801 +4.500000 -0.300000 3.650000 +4.290742 -0.300000 3.630801 +4.076691 -0.300000 3.569257 +3.870709 -0.300000 3.462545 +3.686827 -0.300000 3.313173 +3.537455 -0.300000 3.129291 +1.596872 -0.300000 5.000000 +3.430743 -0.300000 2.923309 +3.369199 -0.300000 2.709258 +3.350000 -0.300000 2.500000 +3.369199 -0.300000 2.290742 +3.430743 -0.300000 2.076691 +3.537455 -0.300000 1.870709 +3.686827 -0.300000 1.686827 +5.129291 -0.300000 3.462545 +3.870709 -0.300000 1.537455 +1.596872 -0.300000 0.000000 +4.076691 -0.300000 1.430743 +4.290742 -0.300000 1.369199 +4.500000 -0.300000 1.350000 +4.709258 -0.300000 1.369199 +4.923309 -0.300000 1.430743 +5.129291 -0.300000 1.537455 +5.313173 -0.300000 1.686827 +6.000000 -0.300000 0.000000 +6.181963 -0.300000 0.016695 +6.368095 -0.300000 0.070212 +6.547210 -0.300000 0.163004 +6.707107 -0.300000 0.292893 +6.836996 -0.300000 0.452790 +6.929788 -0.300000 0.631905 +6.983305 -0.300000 0.818037 +5.462545 -0.300000 1.870709 +7.000000 -0.300000 1.000000 +5.569257 -0.300000 2.076691 +5.630801 -0.300000 2.290742 +5.650000 -0.300000 2.500000 +5.630801 -0.300000 2.709258 +5.569257 -0.300000 2.923309 +5.462545 -0.300000 3.129291 +5.313173 -0.300000 3.313173 +7.000000 -0.300000 4.000000 +6.983305 -0.300000 4.181963 +6.929788 -0.300000 4.368095 +6.836996 -0.300000 4.547210 +6.707107 -0.300000 4.707107 +6.547210 -0.300000 4.836996 +7.000000 -0.300000 4.000000 +7.000000 -0.300000 1.000000 +7.000000 0.300000 1.000000 +7.000000 0.300000 4.000000 +1.841167 -0.781091 5.000000 +1.841167 -0.781091 0.000000 +1.288817 -0.546764 0.000000 +1.288817 -0.546764 5.000000 +4.500000 -0.300000 3.650000 +4.500000 0.300000 3.650000 +4.500000 0.300000 1.350000 +4.500000 -0.300000 1.350000 +4.709258 0.300000 1.369199 +4.709258 -0.300000 1.369199 +4.923309 0.300000 1.430743 +4.923309 -0.300000 1.430743 +5.129291 0.300000 1.537455 +5.129291 -0.300000 1.537455 +5.313173 0.300000 1.686827 +5.313173 -0.300000 1.686827 +5.462545 0.300000 1.870709 +5.462545 -0.300000 1.870709 +5.569257 0.300000 2.076691 +5.569257 -0.300000 2.076691 +5.630801 0.300000 2.290742 +5.630801 -0.300000 2.290742 +5.650000 0.300000 2.500000 +5.650000 -0.300000 2.500000 +5.630801 0.300000 2.709258 +5.630801 -0.300000 2.709258 +5.569257 0.300000 2.923309 +5.569257 -0.300000 2.923309 +5.462545 0.300000 3.129291 +5.313173 0.300000 3.313173 +5.462545 -0.300000 3.129291 +5.313173 -0.300000 3.313173 +5.129291 0.300000 3.462545 +5.129291 -0.300000 3.462545 +4.923309 0.300000 3.569257 +4.923309 -0.300000 3.569257 +4.709258 0.300000 3.630801 +4.709258 -0.300000 3.630801 +7.000000 -0.300000 4.000000 +7.000000 0.300000 4.000000 +6.000000 0.300000 5.000000 +6.000000 -0.300000 5.000000 +6.204909 0.300000 4.978781 +6.397177 0.300000 4.917742 +6.204909 -0.300000 4.978781 +6.566635 0.300000 4.823969 +6.397177 -0.300000 4.917742 +6.566635 -0.300000 4.823969 +6.707107 0.300000 4.707107 +6.707107 -0.300000 4.707107 +6.823969 0.300000 4.566635 +6.823969 -0.300000 4.566635 +6.917742 0.300000 4.397177 +6.917742 -0.300000 4.397177 +6.978781 0.300000 4.204909 +6.978781 -0.300000 4.204909 +6.000000 -0.300000 0.000000 +6.000000 0.300000 0.000000 +7.000000 0.300000 1.000000 +7.000000 -0.300000 1.000000 +6.978781 0.300000 0.795090 +6.978781 -0.300000 0.795090 +6.917742 0.300000 0.602823 +6.917742 -0.300000 0.602823 +6.823969 0.300000 0.433365 +6.707107 0.300000 0.292893 +6.823969 -0.300000 0.433365 +6.707107 -0.300000 0.292893 +6.566635 0.300000 0.176031 +6.566635 -0.300000 0.176031 +6.397177 0.300000 0.082258 +6.204909 0.300000 0.021219 +6.397177 -0.300000 0.082258 +6.204909 -0.300000 0.021219 +1.396872 -0.100000 5.000000 +1.396970 -0.093747 5.000000 +1.397263 -0.087500 5.000000 +1.397263 -0.087500 0.000000 +1.396970 -0.093747 0.000000 +1.396872 -0.100000 0.000000 +1.952645 0.436895 0.000000 +1.947662 0.454545 0.000000 +2.124108 0.300841 5.000000 +2.142429 0.300000 5.000000 +2.142429 0.300000 0.000000 +2.124108 0.300841 0.000000 +2.084510 0.308570 5.000000 +2.084510 0.308570 0.000000 +2.048696 0.323325 5.000000 +2.018112 0.343330 5.000000 +2.048696 0.323325 0.000000 +1.991680 0.368567 5.000000 +2.018112 0.343330 0.000000 +1.969171 0.400090 5.000000 +1.991680 0.368567 0.000000 +1.969171 0.400090 0.000000 +1.952645 0.436895 5.000000 +1.947662 0.454545 5.000000 + + + + + + + + + + + +-1.000000 0.000000 0.000000 +-0.978781 -0.204909 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.204909 -0.978781 0.000000 +0.000000 -1.000000 0.000000 +-0.204909 -0.978781 0.000000 +-0.204909 -0.978781 0.000000 +0.000000 -1.000000 0.000000 +-0.204909 -0.978781 0.000000 +-0.397177 -0.917742 0.000000 +-0.204909 -0.978781 0.000000 +-0.397177 -0.917742 0.000000 +-0.397177 -0.917742 0.000000 +-0.204909 -0.978781 0.000000 +-0.566635 -0.823969 0.000000 +-0.397177 -0.917742 0.000000 +-0.397177 -0.917742 0.000000 +-0.566635 -0.823969 0.000000 +-0.566635 -0.823969 0.000000 +-0.397177 -0.917742 0.000000 +-0.707107 -0.707107 0.000000 +-0.566635 -0.823969 0.000000 +-0.566635 -0.823969 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.566635 -0.823969 0.000000 +-0.707107 -0.707107 0.000000 +-0.823969 -0.566635 0.000000 +-0.707107 -0.707107 0.000000 +-0.823969 -0.566635 0.000000 +-0.823969 -0.566635 0.000000 +-0.707107 -0.707107 0.000000 +-0.917742 -0.397177 0.000000 +-0.823969 -0.566635 0.000000 +-0.823969 -0.566635 0.000000 +-0.917742 -0.397177 0.000000 +-0.917742 -0.397177 0.000000 +-0.823969 -0.566635 0.000000 +-0.917742 -0.397177 0.000000 +-0.978781 -0.204909 0.000000 +-0.917742 -0.397177 0.000000 +-0.978781 -0.204909 0.000000 +-0.978781 -0.204909 0.000000 +-0.917742 -0.397177 0.000000 +-0.978781 -0.204909 0.000000 +-1.000000 0.000000 0.000000 +-0.978781 -0.204909 0.000000 +0.181963 0.000000 -0.983305 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.181963 0.000000 0.983305 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.181963 0.000000 0.983305 +0.181963 0.000000 0.983305 +0.000000 0.000000 1.000000 +0.368095 0.000000 0.929788 +0.181963 0.000000 0.983305 +0.181963 0.000000 0.983305 +0.368095 0.000000 0.929788 +0.368095 0.000000 0.929788 +0.181963 0.000000 0.983305 +0.547210 0.000000 0.836995 +0.368095 0.000000 0.929788 +0.368095 0.000000 0.929788 +0.547210 0.000000 0.836995 +0.547210 0.000000 0.836995 +0.368095 0.000000 0.929788 +0.707107 0.000000 0.707107 +0.547210 0.000000 0.836995 +0.547210 0.000000 0.836995 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.547210 0.000000 0.836995 +0.836995 0.000000 0.547210 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.836995 0.000000 0.547210 +0.836995 0.000000 0.547210 +0.707107 0.000000 0.707107 +0.929788 0.000000 0.368095 +0.836995 0.000000 0.547210 +0.836995 0.000000 0.547210 +0.929788 0.000000 0.368095 +0.929788 0.000000 0.368095 +0.836995 0.000000 0.547210 +0.983305 0.000000 0.181963 +0.929788 0.000000 0.368095 +0.929788 0.000000 0.368095 +0.983305 0.000000 0.181963 +0.983305 0.000000 0.181963 +0.929788 0.000000 0.368095 +1.000000 0.000000 0.000000 +0.983305 0.000000 0.181963 +0.983305 0.000000 0.181963 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.000000 0.181963 +0.983305 0.000000 -0.181963 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.000000 -0.181963 +0.983305 0.000000 -0.181963 +1.000000 0.000000 0.000000 +0.929788 0.000000 -0.368095 +0.983305 0.000000 -0.181963 +0.983305 0.000000 -0.181963 +0.929788 0.000000 -0.368095 +0.929788 0.000000 -0.368095 +0.983305 0.000000 -0.181963 +0.836995 0.000000 -0.547210 +0.929788 0.000000 -0.368095 +0.929788 0.000000 -0.368095 +0.836995 0.000000 -0.547210 +0.836995 0.000000 -0.547210 +0.929788 0.000000 -0.368095 +0.707107 0.000000 -0.707107 +0.836995 0.000000 -0.547210 +0.836995 0.000000 -0.547210 +0.707107 0.000000 -0.707107 +0.707107 0.000000 -0.707107 +0.836995 0.000000 -0.547210 +0.547210 0.000000 -0.836995 +0.707107 0.000000 -0.707107 +0.707107 0.000000 -0.707107 +0.547210 0.000000 -0.836995 +0.547210 0.000000 -0.836995 +0.707107 0.000000 -0.707107 +0.368095 0.000000 -0.929788 +0.547210 0.000000 -0.836995 +0.547210 0.000000 -0.836995 +0.368095 0.000000 -0.929788 +0.368095 0.000000 -0.929788 +0.547210 0.000000 -0.836995 +0.181963 0.000000 -0.983305 +0.368095 0.000000 -0.929788 +0.368095 0.000000 -0.929788 +0.181963 0.000000 -0.983305 +0.181963 0.000000 -0.983305 +0.368095 0.000000 -0.929788 +0.000000 0.000000 -1.000000 +0.181963 0.000000 -0.983305 +0.181963 0.000000 -0.983305 +-0.999511 0.031265 0.000000 +-0.998045 0.062500 0.000000 +-0.999511 0.031265 0.000000 +-0.999511 0.031265 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.999511 0.031265 0.000000 +-0.999511 0.031265 0.000000 +-1.000000 0.000000 0.000000 +-0.998045 0.062500 0.000000 +-0.999511 0.031265 0.000000 +-0.998045 0.062500 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.984491 -0.175434 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.920584 -0.390545 0.000000 +0.837791 -0.545991 0.000000 +0.920584 -0.390545 0.000000 +0.837791 -0.545991 0.000000 +0.837791 -0.545991 0.000000 +0.920584 -0.390545 0.000000 +0.711167 -0.703023 0.000000 +0.837791 -0.545991 0.000000 +0.837791 -0.545991 0.000000 +0.711167 -0.703023 0.000000 +0.711167 -0.703023 0.000000 +0.837791 -0.545991 0.000000 +0.552021 -0.833830 0.000000 +0.711167 -0.703023 0.000000 +0.711167 -0.703023 0.000000 +0.552021 -0.833830 0.000000 +0.552021 -0.833830 0.000000 +0.711167 -0.703023 0.000000 +0.369448 -0.929251 0.000000 +0.552021 -0.833830 0.000000 +0.552021 -0.833830 0.000000 +0.369448 -0.929251 0.000000 +0.369448 -0.929251 0.000000 +0.552021 -0.833830 0.000000 +0.369448 -0.929251 0.000000 +0.175434 -0.984491 0.000000 +0.369448 -0.929251 0.000000 +0.175434 -0.984491 0.000000 +0.175434 -0.984491 0.000000 +0.369448 -0.929251 0.000000 +-0.017629 -0.999845 0.000000 +0.175434 -0.984491 0.000000 +0.175434 -0.984491 0.000000 +-0.017629 -0.999845 0.000000 +-0.017629 -0.999845 0.000000 +0.175434 -0.984491 0.000000 +-0.199269 -0.979945 0.000000 +-0.017629 -0.999845 0.000000 +-0.017629 -0.999845 0.000000 +-0.199269 -0.979945 0.000000 +-0.199269 -0.979945 0.000000 +-0.017629 -0.999845 0.000000 +-0.374256 -0.927325 0.000000 +-0.199269 -0.979945 0.000000 +-0.199269 -0.979945 0.000000 +-0.374256 -0.927325 0.000000 +-0.374256 -0.927325 0.000000 +-0.199269 -0.979945 0.000000 +-0.545991 -0.837791 0.000000 +-0.374256 -0.927325 0.000000 +-0.374256 -0.927325 0.000000 +-0.545991 -0.837791 0.000000 +-0.545991 -0.837791 0.000000 +-0.374256 -0.927325 0.000000 +-0.545991 -0.837791 0.000000 +-0.703023 -0.711167 0.000000 +-0.545991 -0.837791 0.000000 +-0.703023 -0.711167 0.000000 +-0.703023 -0.711167 0.000000 +-0.545991 -0.837791 0.000000 +-0.833830 -0.552021 0.000000 +-0.703023 -0.711167 0.000000 +-0.703023 -0.711167 0.000000 +-0.833830 -0.552021 0.000000 +-0.833830 -0.552021 0.000000 +-0.703023 -0.711167 0.000000 +-0.929251 -0.369448 0.000000 +-0.833830 -0.552021 0.000000 +-0.833830 -0.552021 0.000000 +-0.929251 -0.369448 0.000000 +-0.929251 -0.369448 0.000000 +-0.833830 -0.552021 0.000000 +-0.984491 -0.175434 0.000000 +-0.929251 -0.369448 0.000000 +-0.929251 -0.369448 0.000000 +-0.984491 -0.175434 0.000000 +-0.984491 -0.175434 0.000000 +-0.929251 -0.369448 0.000000 +-1.000000 0.000000 0.000000 +-0.984491 -0.175434 0.000000 +-0.984491 -0.175434 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.973831 0.227273 0.000000 +0.956037 0.293246 0.000000 +0.973831 0.227273 0.000000 +-0.997665 0.068291 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.997665 0.068291 0.000000 +-0.997665 0.068291 0.000000 +-1.000000 0.000000 0.000000 +-0.997665 0.068291 0.000000 +-0.965791 0.259323 0.000000 +-0.997665 0.068291 0.000000 +-0.965791 0.259323 0.000000 +-0.965791 0.259323 0.000000 +-0.997665 0.068291 0.000000 +-0.894095 0.447876 0.000000 +-0.965791 0.259323 0.000000 +-0.965791 0.259323 0.000000 +-0.894095 0.447876 0.000000 +-0.894095 0.447876 0.000000 +-0.965791 0.259323 0.000000 +-0.894095 0.447876 0.000000 +-0.783349 0.621582 0.000000 +-0.894095 0.447876 0.000000 +-0.783349 0.621582 0.000000 +-0.783349 0.621582 0.000000 +-0.894095 0.447876 0.000000 +-0.639360 0.768908 0.000000 +-0.783349 0.621582 0.000000 +-0.783349 0.621582 0.000000 +-0.639360 0.768908 0.000000 +-0.639360 0.768908 0.000000 +-0.783349 0.621582 0.000000 +-0.472034 0.881580 0.000000 +-0.639360 0.768908 0.000000 +-0.639360 0.768908 0.000000 +-0.472034 0.881580 0.000000 +-0.472034 0.881580 0.000000 +-0.639360 0.768908 0.000000 +-0.293246 0.956037 0.000000 +-0.472034 0.881580 0.000000 +-0.472034 0.881580 0.000000 +-0.293246 0.956037 0.000000 +-0.293246 0.956037 0.000000 +-0.472034 0.881580 0.000000 +-0.114387 0.993436 0.000000 +-0.293246 0.956037 0.000000 +-0.293246 0.956037 0.000000 +-0.114387 0.993436 0.000000 +-0.114387 0.993436 0.000000 +-0.293246 0.956037 0.000000 +0.068291 0.997665 0.000000 +-0.114387 0.993436 0.000000 +-0.114387 0.993436 0.000000 +0.068291 0.997665 0.000000 +0.068291 0.997665 0.000000 +-0.114387 0.993436 0.000000 +0.259323 0.965791 0.000000 +0.068291 0.997665 0.000000 +0.068291 0.997665 0.000000 +0.259323 0.965791 0.000000 +0.259323 0.965791 0.000000 +0.068291 0.997665 0.000000 +0.447876 0.894095 0.000000 +0.259323 0.965791 0.000000 +0.259323 0.965791 0.000000 +0.447876 0.894095 0.000000 +0.447876 0.894095 0.000000 +0.259323 0.965791 0.000000 +0.621582 0.783349 0.000000 +0.447876 0.894095 0.000000 +0.447876 0.894095 0.000000 +0.621582 0.783349 0.000000 +0.621582 0.783349 0.000000 +0.447876 0.894095 0.000000 +0.768908 0.639360 0.000000 +0.621582 0.783349 0.000000 +0.621582 0.783349 0.000000 +0.768908 0.639360 0.000000 +0.768908 0.639360 0.000000 +0.621582 0.783349 0.000000 +0.881580 0.472034 0.000000 +0.768908 0.639360 0.000000 +0.768908 0.639360 0.000000 +0.881580 0.472034 0.000000 +0.881580 0.472034 0.000000 +0.768908 0.639360 0.000000 +0.881580 0.472034 0.000000 +0.956037 0.293246 0.000000 +0.881580 0.472034 0.000000 +0.956037 0.293246 0.000000 +0.956037 0.293246 0.000000 +0.881580 0.472034 0.000000 +0.956037 0.293246 0.000000 +0.973831 0.227273 0.000000 +0.956037 0.293246 0.000000 +1.000000 0.000000 0.000000 +0.984491 0.175434 0.000000 +1.000000 0.000000 0.000000 +-0.837791 0.545991 0.000000 +-0.920584 0.390545 0.000000 +-0.920584 0.390545 0.000000 +-0.837791 0.545991 0.000000 +-0.837791 0.545991 0.000000 +-0.920584 0.390545 0.000000 +-0.711167 0.703023 0.000000 +-0.837791 0.545991 0.000000 +-0.837791 0.545991 0.000000 +-0.711167 0.703023 0.000000 +-0.711167 0.703023 0.000000 +-0.837791 0.545991 0.000000 +-0.552021 0.833830 0.000000 +-0.711167 0.703023 0.000000 +-0.711167 0.703023 0.000000 +-0.552021 0.833830 0.000000 +-0.552021 0.833830 0.000000 +-0.711167 0.703023 0.000000 +-0.369448 0.929251 0.000000 +-0.552021 0.833830 0.000000 +-0.552021 0.833830 0.000000 +-0.369448 0.929251 0.000000 +-0.369448 0.929251 0.000000 +-0.552021 0.833830 0.000000 +-0.175434 0.984491 0.000000 +-0.369448 0.929251 0.000000 +-0.369448 0.929251 0.000000 +-0.175434 0.984491 0.000000 +-0.175434 0.984491 0.000000 +-0.369448 0.929251 0.000000 +0.017629 0.999845 0.000000 +-0.175434 0.984491 0.000000 +-0.175434 0.984491 0.000000 +0.017629 0.999845 0.000000 +0.017629 0.999845 0.000000 +-0.175434 0.984491 0.000000 +0.199269 0.979945 0.000000 +0.017629 0.999845 0.000000 +0.017629 0.999845 0.000000 +0.199269 0.979945 0.000000 +0.199269 0.979945 0.000000 +0.017629 0.999845 0.000000 +0.199269 0.979945 0.000000 +0.374256 0.927325 0.000000 +0.199269 0.979945 0.000000 +0.374256 0.927325 0.000000 +0.374256 0.927325 0.000000 +0.199269 0.979945 0.000000 +0.545991 0.837791 0.000000 +0.374256 0.927325 0.000000 +0.374256 0.927325 0.000000 +0.545991 0.837791 0.000000 +0.545991 0.837791 0.000000 +0.374256 0.927325 0.000000 +0.545991 0.837791 0.000000 +0.703023 0.711167 0.000000 +0.545991 0.837791 0.000000 +0.703023 0.711167 0.000000 +0.703023 0.711167 0.000000 +0.545991 0.837791 0.000000 +0.833830 0.552021 0.000000 +0.703023 0.711167 0.000000 +0.703023 0.711167 0.000000 +0.833830 0.552021 0.000000 +0.833830 0.552021 0.000000 +0.703023 0.711167 0.000000 +0.833830 0.552021 0.000000 +0.929251 0.369448 0.000000 +0.833830 0.552021 0.000000 +0.929251 0.369448 0.000000 +0.929251 0.369448 0.000000 +0.833830 0.552021 0.000000 +0.984491 0.175434 0.000000 +0.929251 0.369448 0.000000 +0.929251 0.369448 0.000000 +0.984491 0.175434 0.000000 +0.984491 0.175434 0.000000 +0.929251 0.369448 0.000000 +0.984491 0.175434 0.000000 +1.000000 0.000000 0.000000 +0.984491 0.175434 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.390545 0.920584 0.000000 +0.390545 0.920584 0.000000 +0.390545 0.920584 0.000000 +0.390545 0.920584 0.000000 +0.390545 0.920584 0.000000 +0.390545 0.920584 0.000000 +-0.181963 0.000000 -0.983305 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.181963 0.000000 0.983305 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.181963 0.000000 0.983305 +-0.181963 0.000000 0.983305 +0.000000 0.000000 1.000000 +-0.368095 0.000000 0.929788 +-0.181963 0.000000 0.983305 +-0.181963 0.000000 0.983305 +-0.368095 0.000000 0.929788 +-0.368095 0.000000 0.929788 +-0.181963 0.000000 0.983305 +-0.547210 0.000000 0.836995 +-0.368095 0.000000 0.929788 +-0.368095 0.000000 0.929788 +-0.547210 0.000000 0.836995 +-0.547210 0.000000 0.836995 +-0.368095 0.000000 0.929788 +-0.707107 0.000000 0.707107 +-0.547210 0.000000 0.836995 +-0.547210 0.000000 0.836995 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.547210 0.000000 0.836995 +-0.836995 0.000000 0.547210 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.836995 0.000000 0.547210 +-0.836995 0.000000 0.547210 +-0.707107 0.000000 0.707107 +-0.929788 0.000000 0.368095 +-0.836995 0.000000 0.547210 +-0.836995 0.000000 0.547210 +-0.929788 0.000000 0.368095 +-0.929788 0.000000 0.368095 +-0.836995 0.000000 0.547210 +-0.983305 0.000000 0.181963 +-0.929788 0.000000 0.368095 +-0.929788 0.000000 0.368095 +-0.983305 0.000000 0.181963 +-0.983305 0.000000 0.181963 +-0.929788 0.000000 0.368095 +-1.000000 0.000000 0.000000 +-0.983305 0.000000 0.181963 +-0.983305 0.000000 0.181963 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.000000 0.181963 +-0.983305 0.000000 -0.181963 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.000000 -0.181963 +-0.983305 0.000000 -0.181963 +-1.000000 0.000000 0.000000 +-0.929788 0.000000 -0.368095 +-0.983305 0.000000 -0.181963 +-0.983305 0.000000 -0.181963 +-0.929788 0.000000 -0.368095 +-0.929788 0.000000 -0.368095 +-0.983305 0.000000 -0.181963 +-0.836995 0.000000 -0.547210 +-0.929788 0.000000 -0.368095 +-0.929788 0.000000 -0.368095 +-0.836995 0.000000 -0.547210 +-0.836995 0.000000 -0.547210 +-0.929788 0.000000 -0.368095 +-0.836995 0.000000 -0.547210 +-0.707107 0.000000 -0.707107 +-0.836995 0.000000 -0.547210 +-0.707107 0.000000 -0.707107 +-0.707107 0.000000 -0.707107 +-0.836995 0.000000 -0.547210 +-0.547210 0.000000 -0.836995 +-0.707107 0.000000 -0.707107 +-0.707107 0.000000 -0.707107 +-0.547210 0.000000 -0.836995 +-0.547210 0.000000 -0.836995 +-0.707107 0.000000 -0.707107 +-0.368095 0.000000 -0.929788 +-0.547210 0.000000 -0.836995 +-0.547210 0.000000 -0.836995 +-0.368095 0.000000 -0.929788 +-0.368095 0.000000 -0.929788 +-0.547210 0.000000 -0.836995 +-0.181963 0.000000 -0.983305 +-0.368095 0.000000 -0.929788 +-0.368095 0.000000 -0.929788 +-0.181963 0.000000 -0.983305 +-0.181963 0.000000 -0.983305 +-0.368095 0.000000 -0.929788 +0.000000 0.000000 -1.000000 +-0.181963 0.000000 -0.983305 +-0.181963 0.000000 -0.983305 +0.978781 0.000000 0.204909 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.204909 0.000000 0.978781 +0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +0.204909 0.000000 0.978781 +0.397177 0.000000 0.917742 +0.204909 0.000000 0.978781 +0.397177 0.000000 0.917742 +0.397177 0.000000 0.917742 +0.204909 0.000000 0.978781 +0.397177 0.000000 0.917742 +0.566635 0.000000 0.823969 +0.397177 0.000000 0.917742 +0.566635 0.000000 0.823969 +0.566635 0.000000 0.823969 +0.397177 0.000000 0.917742 +0.707107 0.000000 0.707107 +0.566635 0.000000 0.823969 +0.566635 0.000000 0.823969 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.566635 0.000000 0.823969 +0.823969 0.000000 0.566635 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.823969 0.000000 0.566635 +0.823969 0.000000 0.566635 +0.707107 0.000000 0.707107 +0.917742 0.000000 0.397177 +0.823969 0.000000 0.566635 +0.823969 0.000000 0.566635 +0.917742 0.000000 0.397177 +0.917742 0.000000 0.397177 +0.823969 0.000000 0.566635 +0.978781 0.000000 0.204909 +0.917742 0.000000 0.397177 +0.917742 0.000000 0.397177 +0.978781 0.000000 0.204909 +0.978781 0.000000 0.204909 +0.917742 0.000000 0.397177 +1.000000 0.000000 0.000000 +0.978781 0.000000 0.204909 +0.978781 0.000000 0.204909 +0.204909 0.000000 -0.978781 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.978781 0.000000 -0.204909 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.978781 0.000000 -0.204909 +0.978781 0.000000 -0.204909 +1.000000 0.000000 0.000000 +0.917742 0.000000 -0.397177 +0.978781 0.000000 -0.204909 +0.978781 0.000000 -0.204909 +0.917742 0.000000 -0.397177 +0.917742 0.000000 -0.397177 +0.978781 0.000000 -0.204909 +0.823969 0.000000 -0.566635 +0.917742 0.000000 -0.397177 +0.917742 0.000000 -0.397177 +0.823969 0.000000 -0.566635 +0.823969 0.000000 -0.566635 +0.917742 0.000000 -0.397177 +0.823969 0.000000 -0.566635 +0.707107 0.000000 -0.707107 +0.823969 0.000000 -0.566635 +0.707107 0.000000 -0.707107 +0.707107 0.000000 -0.707107 +0.823969 0.000000 -0.566635 +0.566635 0.000000 -0.823969 +0.707107 0.000000 -0.707107 +0.707107 0.000000 -0.707107 +0.566635 0.000000 -0.823969 +0.566635 0.000000 -0.823969 +0.707107 0.000000 -0.707107 +0.397177 0.000000 -0.917742 +0.566635 0.000000 -0.823969 +0.566635 0.000000 -0.823969 +0.397177 0.000000 -0.917742 +0.397177 0.000000 -0.917742 +0.566635 0.000000 -0.823969 +0.397177 0.000000 -0.917742 +0.204909 0.000000 -0.978781 +0.397177 0.000000 -0.917742 +0.204909 0.000000 -0.978781 +0.204909 0.000000 -0.978781 +0.397177 0.000000 -0.917742 +0.000000 0.000000 -1.000000 +0.204909 0.000000 -0.978781 +0.204909 0.000000 -0.978781 +-0.999511 0.031265 0.000000 +-1.000000 0.000000 0.000000 +-0.999511 0.031265 0.000000 +-0.998045 0.062500 0.000000 +-0.999511 0.031265 0.000000 +-0.998045 0.062500 0.000000 +-0.999511 0.031265 0.000000 +-0.999511 0.031265 0.000000 +-0.998045 0.062500 0.000000 +-1.000000 0.000000 0.000000 +-0.999511 0.031265 0.000000 +-1.000000 0.000000 0.000000 +0.973831 0.227273 0.000000 +0.948917 0.315524 0.000000 +0.973831 0.227273 0.000000 +0.000000 1.000000 0.000000 +0.091605 0.995795 0.000000 +0.000000 1.000000 0.000000 +0.091605 0.995795 0.000000 +0.091605 0.995795 0.000000 +0.000000 1.000000 0.000000 +0.289592 0.957150 0.000000 +0.091605 0.995795 0.000000 +0.091605 0.995795 0.000000 +0.289592 0.957150 0.000000 +0.289592 0.957150 0.000000 +0.091605 0.995795 0.000000 +0.468664 0.883377 0.000000 +0.289592 0.957150 0.000000 +0.289592 0.957150 0.000000 +0.468664 0.883377 0.000000 +0.468664 0.883377 0.000000 +0.289592 0.957150 0.000000 +0.468664 0.883377 0.000000 +0.621582 0.783349 0.000000 +0.468664 0.883377 0.000000 +0.621582 0.783349 0.000000 +0.621582 0.783349 0.000000 +0.468664 0.883377 0.000000 +0.621582 0.783349 0.000000 +0.753745 0.657167 0.000000 +0.621582 0.783349 0.000000 +0.753745 0.657167 0.000000 +0.753745 0.657167 0.000000 +0.621582 0.783349 0.000000 +0.753745 0.657167 0.000000 +0.866286 0.499548 0.000000 +0.753745 0.657167 0.000000 +0.866286 0.499548 0.000000 +0.866286 0.499548 0.000000 +0.753745 0.657167 0.000000 +0.948917 0.315524 0.000000 +0.866286 0.499548 0.000000 +0.866286 0.499548 0.000000 +0.948917 0.315524 0.000000 +0.948917 0.315524 0.000000 +0.866286 0.499548 0.000000 +0.948917 0.315524 0.000000 +0.973831 0.227273 0.000000 +0.948917 0.315524 0.000000 + + + + + + + + + + + +0.646420 0.000000 +0.667272 0.000000 +0.521307 2.672212 +0.500454 2.672212 +0.500454 0.000000 +0.542159 2.672212 +0.521307 0.000000 +0.542159 0.000000 +0.563011 2.672212 +0.563011 0.000000 +0.583863 2.672212 +0.604716 2.672212 +0.583863 0.000000 +0.604716 0.000000 +0.625568 2.672212 +0.646420 2.672212 +0.625568 0.000000 +0.667272 2.672212 +5.023758 1.918408 +5.344423 1.918408 +5.344423 3.836816 +5.023758 3.836816 +5.344423 3.716915 +5.023758 3.716915 +5.344423 3.597015 +5.023758 3.597015 +5.344423 3.477114 +5.023758 3.477114 +5.344423 3.357214 +5.023758 3.357214 +5.344423 3.237313 +5.023758 3.237313 +5.344423 3.117413 +5.023758 3.117413 +5.344423 2.997512 +5.023758 2.997512 +5.344423 2.877612 +5.023758 2.877612 +5.344423 2.757711 +5.023758 2.757711 +5.344423 2.637811 +5.023758 2.637811 +5.344423 2.517910 +5.023758 2.517910 +5.344423 2.398010 +5.023758 2.398010 +5.344423 2.278109 +5.023758 2.278109 +5.344423 2.158209 +5.023758 2.158209 +5.344423 2.038308 +5.023758 2.038308 +0.000000 2.384356 +0.000000 2.333043 +2.672212 2.333043 +0.000000 2.358700 +2.672212 2.358700 +2.672212 2.384356 +2.672212 2.335453 +-0.000000 2.335453 +-0.000000 0.145966 +-0.000000 0.000000 +2.672212 0.000000 +2.672212 0.145966 +-0.000000 0.291932 +2.672212 0.291932 +-0.000000 0.437897 +2.672212 0.437897 +-0.000000 0.583863 +2.672212 0.583863 +-0.000000 0.729829 +2.672212 0.729829 +-0.000000 0.875795 +2.672212 0.875795 +-0.000000 1.021761 +2.672212 1.021761 +-0.000000 1.167727 +2.672212 1.167727 +-0.000000 1.313692 +2.672212 1.313692 +-0.000000 1.459658 +2.672212 1.459658 +-0.000000 1.605624 +2.672212 1.605624 +-0.000000 1.751590 +2.672212 1.751590 +-0.000000 1.897556 +2.672212 1.897556 +-0.000000 2.043521 +2.672212 2.043521 +-0.000000 2.189487 +2.672212 2.189487 +6.657839 0.000000 +6.657839 2.672212 +3.966456 2.672212 +3.777344 2.672212 +3.777344 0.000000 +3.966456 0.000000 +4.174979 2.672212 +4.174979 0.000000 +4.383501 2.672212 +4.383501 0.000000 +4.592024 2.672212 +4.800547 2.672212 +4.592024 0.000000 +4.800547 0.000000 +5.009069 2.672212 +5.009069 -0.000000 +5.217592 2.672212 +5.217592 0.000000 +5.426114 2.672212 +5.426114 -0.000000 +5.634637 2.672212 +5.843160 2.672212 +5.634637 -0.000000 +5.843160 -0.000000 +6.051682 2.672212 +6.051682 -0.000000 +6.260205 2.672212 +6.260205 -0.000000 +6.468727 2.672212 +6.468727 -0.000000 +0.746756 -0.046764 +0.746548 -0.053444 +0.903544 -0.571072 +0.983998 -0.417448 +0.688798 -0.292214 +0.794063 -0.715527 +0.632480 -0.399751 +0.657302 -0.842893 +0.555844 -0.500869 +0.497831 -0.945874 +0.460111 -0.590025 +0.322659 -1.019022 +0.348482 -0.662112 +0.140243 -1.059644 +0.225861 -0.713315 +-0.040814 -1.068105 +0.098170 -0.741751 +-0.212996 -1.047448 +-0.028570 -0.747674 +-0.379571 -0.999220 +-0.149097 -0.733214 +-0.542945 -0.920720 +-0.265700 -0.699454 +-0.695009 -0.812082 +-0.380061 -0.644504 +-0.827702 -0.676331 +-0.486506 -0.568457 +-0.934289 -0.519247 +-0.579392 -0.473432 +-1.010447 -0.348585 +-0.654003 -0.363473 +-1.054817 -0.172845 +-0.707313 -0.244009 +-1.068885 -0.000000 +-0.738372 -0.120992 +-1.053225 0.182294 +-0.748219 -0.000000 +-1.003505 0.368093 +-0.735728 0.136148 +-0.917812 0.547847 +-0.695686 0.275416 +-0.797873 0.711275 +-0.626256 0.409433 +-0.649237 0.849121 +-0.529071 0.529071 +-0.480465 0.954813 +-0.409433 0.626256 +-0.301573 1.025460 +-0.275416 0.695686 +-0.122267 1.061869 +-0.136148 0.735728 +0.060622 1.067164 +-0.000000 0.748219 +0.250889 1.039023 +0.136148 0.735728 +0.439265 0.974454 +0.275416 0.695686 +0.615340 0.873997 +0.409433 0.626256 +0.769283 0.742104 +0.893587 0.586530 +0.529071 0.529071 +0.984233 0.416893 +0.626256 0.409433 +1.040913 0.242928 +0.695686 0.275416 +3.206654 -0.160333 +3.206654 0.160333 +0.853436 -0.160333 +1.145005 0.160333 +1.110805 0.165951 +1.054157 0.210901 +0.735728 0.136148 +1.078565 0.183490 +0.748219 -0.000000 +0.833986 -0.158548 +0.814091 -0.152828 +0.794946 -0.142909 +0.777854 -0.129026 +0.763971 -0.111935 +0.754052 -0.092789 +0.748332 -0.072894 +-0.072894 0.748332 +-0.053444 0.746548 +-0.292214 0.688798 +-0.417448 0.983998 +-0.399751 0.632480 +-0.571072 0.903544 +-0.500869 0.555844 +-0.715527 0.794063 +-0.590025 0.460111 +-0.842893 0.657302 +-0.662112 0.348482 +-0.945874 0.497831 +-0.713315 0.225861 +-1.019022 0.322659 +-0.741751 0.098170 +-1.059644 0.140243 +-0.747674 -0.028570 +-1.068105 -0.040814 +-0.733214 -0.149097 +-1.047448 -0.212996 +-0.699454 -0.265700 +-0.999220 -0.379571 +-0.644504 -0.380061 +-0.920720 -0.542945 +-0.568457 -0.486506 +-0.812082 -0.695009 +-0.473432 -0.579392 +-0.676331 -0.827702 +-0.363473 -0.654003 +-0.519247 -0.934289 +-0.244009 -0.707313 +-0.348585 -1.010447 +-0.120992 -0.738372 +-0.172845 -1.054817 +-0.000000 -0.748219 +-0.000000 -1.068885 +0.136148 -0.735728 +0.182294 -1.053225 +0.275416 -0.695686 +0.368093 -1.003505 +0.409433 -0.626256 +0.547847 -0.917812 +0.529071 -0.529071 +0.711275 -0.797873 +0.626256 -0.409433 +0.849121 -0.649237 +0.695686 -0.275416 +0.954813 -0.480465 +0.735728 -0.136148 +1.025460 -0.301573 +0.748219 0.000000 +1.061869 -0.122267 +0.735728 0.136148 +1.067164 0.060622 +0.695686 0.275416 +1.039023 0.250889 +0.626256 0.409433 +0.974454 0.439265 +0.873997 0.615340 +0.529071 0.529071 +0.742104 0.769283 +0.409433 0.626256 +0.586530 0.893587 +0.275416 0.695686 +0.416893 0.984233 +0.136148 0.735728 +0.160333 3.206654 +-0.160333 3.206654 +0.160333 1.145005 +0.165951 1.110805 +0.183490 1.078565 +0.242928 1.040913 +-0.000000 0.748219 +0.210901 1.054157 +-0.046764 0.746756 +-0.160333 0.853436 +-0.158548 0.833986 +-0.152828 0.814091 +-0.142909 0.794946 +-0.129026 0.777854 +-0.111935 0.763971 +-0.092789 0.754052 +3.006094 -0.000000 +3.082386 -0.000000 +0.010485 2.672212 +0.010485 -0.000000 +0.086777 2.672212 +0.295300 2.672212 +0.086777 -0.000000 +0.295300 -0.000000 +0.503823 2.672212 +0.712345 2.672212 +0.503823 -0.000000 +0.712345 -0.000000 +0.920868 2.672212 +0.920868 -0.000000 +1.129390 2.672212 +1.129390 -0.000000 +1.337913 2.672212 +1.337913 -0.000000 +1.546435 2.672212 +1.546435 -0.000000 +1.754958 2.672212 +1.754958 -0.000000 +1.963481 2.672212 +1.963481 -0.000000 +2.172003 2.672212 +2.172003 -0.000000 +2.380526 2.672212 +2.380526 -0.000000 +2.589048 2.672212 +2.589048 -0.000000 +2.797571 2.672212 +3.006094 2.672212 +2.797571 -0.000000 +3.082386 2.672212 +2.672212 -0.142797 +2.672212 -0.010419 +-0.000000 -2.026766 +2.672212 -2.026766 +-0.000000 -1.894387 +2.672212 -1.894387 +-0.000000 -1.748421 +2.672212 -1.748421 +-0.000000 -1.602455 +2.672212 -1.602455 +-0.000000 -1.456490 +2.672212 -1.456490 +-0.000000 -1.310524 +2.672212 -1.310524 +-0.000000 -1.164558 +2.672212 -1.164558 +-0.000000 -1.018592 +-0.000000 -0.872626 +2.672212 -1.018592 +2.672212 -0.872626 +-0.000000 -0.726660 +-0.000000 -0.580695 +2.672212 -0.726660 +2.672212 -0.580695 +-0.000000 -0.434729 +-0.000000 -0.288763 +2.672212 -0.434729 +2.672212 -0.288763 +-0.000000 -0.142797 +-0.000000 -0.010419 +1.672426 1.890566 +1.850531 2.741310 +2.672212 1.145005 +1.907562 2.631225 +1.940454 2.516827 +1.950715 2.404990 +1.940454 2.293154 +1.907562 2.178756 +1.850531 2.068671 +1.770700 1.970397 +1.770700 2.839585 +2.672212 3.206654 +2.663289 3.303903 +2.634688 3.403379 +2.585095 3.499106 +2.515677 3.584562 +2.430221 3.653980 +2.334495 3.703572 +2.235018 3.732174 +1.672426 2.919415 +2.137769 3.741096 +1.562340 2.976447 +1.447942 3.009339 +1.336106 3.019599 +1.224270 3.009339 +1.109872 2.976447 +0.999786 2.919415 +0.901512 2.839585 +0.534442 3.741096 +0.437194 3.732174 +0.337717 3.703572 +0.241990 3.653980 +0.156535 3.584562 +0.087117 3.499106 +0.037524 3.403379 +0.008922 3.303903 +0.821681 2.741310 +0.764650 2.631225 +-0.000000 3.206654 +0.731758 2.516827 +0.721497 2.404990 +0.731758 2.293154 +0.764650 2.178756 +0.821681 2.068671 +0.901512 1.970397 +0.999786 1.890566 +1.109872 1.833535 +-0.000000 1.145005 +1.224270 1.800642 +1.336106 1.790382 +1.447942 1.800642 +1.562340 1.833535 +3.403379 2.634688 +3.303903 2.663289 +2.631225 1.907562 +3.206654 2.672212 +2.516827 1.940454 +2.404990 1.950715 +2.293154 1.940454 +2.178756 1.907562 +2.068671 1.850531 +1.970397 1.770700 +1.890566 1.672426 +0.853436 2.672212 +1.833535 1.562340 +1.800642 1.447942 +1.790382 1.336106 +1.800642 1.224270 +1.833535 1.109872 +1.890566 0.999786 +1.970397 0.901512 +2.741310 1.850531 +2.068671 0.821681 +0.853436 0.000000 +2.178756 0.764650 +2.293154 0.731758 +2.404990 0.721497 +2.516827 0.731758 +2.631225 0.764650 +2.741310 0.821681 +2.839585 0.901512 +3.206654 0.000000 +3.303903 0.008922 +3.403379 0.037524 +3.499106 0.087117 +3.584562 0.156535 +3.653980 0.241990 +3.703572 0.337717 +3.732174 0.437194 +2.919415 0.999786 +3.741096 0.534442 +2.976447 1.109872 +3.009339 1.224270 +3.019599 1.336106 +3.009339 1.447942 +2.976447 1.562340 +2.919415 1.672426 +2.839585 1.770700 +3.741096 2.137769 +3.732174 2.235018 +3.703572 2.334495 +3.653980 2.430221 +3.584562 2.515677 +3.499106 2.585095 +-0.320665 2.137769 +-0.320665 0.534442 +-0.000000 0.534442 +-0.000000 2.137769 +5.344423 0.658349 +2.672212 0.658349 +2.672212 0.337684 +5.344423 0.337684 +5.344423 1.918408 +5.023758 1.918408 +5.023758 0.000000 +5.344423 0.000000 +5.023758 0.119900 +5.344423 0.119900 +5.023758 0.239801 +5.344423 0.239801 +5.023758 0.359701 +5.344423 0.359701 +5.023758 0.479602 +5.344423 0.479602 +5.023758 0.599503 +5.344423 0.599503 +5.023758 0.719403 +5.344423 0.719403 +5.023758 0.839303 +5.344423 0.839303 +5.023758 0.959204 +5.344423 0.959204 +5.023758 1.079104 +5.344423 1.079104 +5.023758 1.199005 +5.344423 1.199005 +5.023758 1.318905 +5.023758 1.438806 +5.344423 1.318905 +5.344423 1.438806 +5.023758 1.558706 +5.344423 1.558706 +5.023758 1.678607 +5.344423 1.678607 +5.023758 1.798507 +5.344423 1.798507 +0.834090 -0.320665 +0.834090 0.000000 +-0.000000 0.000000 +-0.000000 -0.320665 +0.104261 -0.000000 +0.208523 -0.000000 +0.104261 -0.320665 +0.312784 -0.000000 +0.208523 -0.320665 +0.312784 -0.320665 +0.417045 -0.000000 +0.417045 -0.320665 +0.521307 -0.000000 +0.521307 -0.320665 +0.625568 0.000000 +0.625568 -0.320665 +0.729829 0.000000 +0.729829 -0.320665 +-0.000000 0.160333 +-0.000000 -0.160333 +0.834090 -0.160333 +0.834090 0.160333 +0.729829 -0.160333 +0.729829 0.160333 +0.625568 -0.160333 +0.625568 0.160333 +0.521307 -0.160333 +0.417045 -0.160333 +0.521307 0.160333 +0.417045 0.160333 +0.312784 -0.160333 +0.312784 0.160333 +0.208523 -0.160333 +0.104261 -0.160333 +0.208523 0.160333 +0.104261 0.160333 +-0.000344 -0.000000 +0.003321 -0.000000 +0.006986 -0.000000 +0.006986 2.672212 +0.003321 2.672212 +-0.000344 2.672212 +2.672212 0.634246 +2.672212 0.643543 +0.000000 0.509132 +0.000000 0.499835 +2.672212 0.499835 +2.672212 0.509132 +0.000000 0.529984 +2.672212 0.529984 +0.000000 0.550837 +0.000000 0.571689 +2.672212 0.550837 +0.000000 0.592541 +2.672212 0.571689 +0.000000 0.613393 +2.672212 0.592541 +2.672212 0.613393 +-0.000000 0.634246 +0.000000 0.643543 + + + + + + + + + + + +

17 0 17 0 1 0 1 2 1 4 3 4 2 4 2 3 5 3 6 6 6 2 7 2 4 8 4 6 9 6 5 10 5 2 11 2 7 12 7 5 13 5 6 14 6 9 15 9 5 16 5 7 17 7 9 18 9 8 19 8 5 20 5 12 21 12 8 22 8 9 23 9 12 24 12 10 25 10 8 26 8 12 27 12 11 28 11 10 29 10 13 30 13 11 31 11 12 32 12 16 33 16 11 34 11 13 35 13 16 36 16 14 37 14 11 38 11 16 39 16 15 40 15 14 41 14 0 42 0 15 43 15 16 44 16 0 45 0 17 46 17 15 47 15 50 48 50 18 49 18 19 50 19 23 51 23 20 52 20 21 53 21 23 54 23 22 55 22 20 56 20 25 57 25 22 58 22 23 59 23 25 60 25 24 61 24 22 62 22 27 63 27 24 64 24 25 65 25 27 66 27 26 67 26 24 68 24 29 69 29 26 70 26 27 71 27 29 72 29 28 73 28 26 74 26 31 75 31 28 76 28 29 77 29 31 78 31 30 79 30 28 80 28 33 81 33 30 82 30 31 83 31 33 84 33 32 85 32 30 86 30 35 87 35 32 88 32 33 89 33 35 90 35 34 91 34 32 92 32 37 93 37 34 94 34 35 95 35 37 96 37 36 97 36 34 98 34 39 99 39 36 100 36 37 101 37 39 102 39 38 103 38 36 104 36 41 105 41 38 106 38 39 107 39 41 108 41 40 109 40 38 110 38 43 111 43 40 112 40 41 113 41 43 114 43 42 115 42 40 116 40 45 117 45 42 118 42 43 119 43 45 120 45 44 121 44 42 122 42 47 123 47 44 124 44 45 125 45 47 126 47 46 127 46 44 128 44 49 129 49 46 130 46 47 131 47 49 132 49 48 133 48 46 134 46 51 135 51 48 136 48 49 137 49 51 138 51 50 139 50 48 140 48 18 141 18 50 142 50 51 143 51 56 144 56 52 145 52 55 146 55 56 147 56 53 148 53 54 149 54 56 150 56 55 151 55 53 152 53 52 153 52 56 154 56 57 155 57 90 156 90 58 157 58 59 158 59 62 159 62 60 160 60 61 161 61 63 162 63 60 163 60 62 164 62 65 165 65 60 166 60 63 167 63 65 168 65 64 169 64 60 170 60 67 171 67 64 172 64 65 173 65 67 174 67 66 175 66 64 176 64 69 177 69 66 178 66 67 179 67 69 180 69 68 181 68 66 182 66 71 183 71 68 184 68 69 185 69 71 186 71 70 187 70 68 188 68 73 189 73 70 190 70 71 191 71 73 192 73 72 193 72 70 194 70 75 195 75 72 196 72 73 197 73 75 198 75 74 199 74 72 200 72 77 201 77 74 202 74 75 203 75 77 204 77 76 205 76 74 206 74 79 207 79 76 208 76 77 209 77 79 210 79 78 211 78 76 212 76 81 213 81 78 214 78 79 215 79 81 216 81 80 217 80 78 218 78 83 219 83 80 220 80 81 221 81 83 222 83 82 223 82 80 224 80 85 225 85 82 226 82 83 227 83 85 228 85 84 229 84 82 230 82 87 231 87 84 232 84 85 233 85 87 234 87 86 235 86 84 236 84 89 237 89 86 238 86 87 239 87 89 240 89 88 241 88 86 242 86 91 243 91 88 244 88 89 245 89 91 246 91 90 247 90 88 248 88 58 249 58 90 250 90 91 251 91 120 252 120 92 253 92 93 254 93 96 255 96 94 256 94 95 257 95 97 258 97 94 259 94 96 260 96 99 261 99 94 262 94 97 263 97 99 264 99 98 265 98 94 266 94 101 267 101 98 268 98 99 269 99 101 270 101 100 271 100 98 272 98 104 273 104 100 274 100 101 275 101 104 276 104 102 277 102 100 278 100 104 279 104 103 280 103 102 281 102 105 282 105 103 283 103 104 284 104 107 285 107 103 286 103 105 287 105 107 288 107 106 289 106 103 290 103 109 291 109 106 292 106 107 293 107 109 294 109 108 295 108 106 296 106 111 297 111 108 298 108 109 299 109 111 300 111 110 301 110 108 302 108 114 303 114 110 304 110 111 305 111 114 306 114 112 307 112 110 308 110 114 309 114 113 310 113 112 311 112 115 312 115 113 313 113 114 314 114 117 315 117 113 316 113 115 317 115 117 318 117 116 319 116 113 320 113 119 321 119 116 322 116 117 323 117 119 324 119 118 325 118 116 326 116 121 327 121 118 328 118 119 329 119 121 330 121 120 331 120 118 332 118 92 333 92 120 334 120 121 335 121 203 336 203 122 337 122 123 338 123 126 339 126 124 340 124 125 341 125 128 342 128 124 343 124 126 344 126 128 345 128 127 346 127 124 347 124 130 348 130 127 349 127 128 350 128 130 351 130 129 352 129 127 353 127 132 354 132 129 355 129 130 356 130 132 357 132 131 358 131 129 359 129 134 360 134 131 361 131 132 362 132 134 363 134 133 364 133 131 365 131 136 366 136 133 367 133 134 368 134 136 369 136 135 370 135 133 371 133 138 372 138 135 373 135 136 374 136 138 375 138 137 376 137 135 377 135 140 378 140 137 379 137 138 380 138 140 381 140 139 382 139 137 383 137 142 384 142 139 385 139 140 386 140 142 387 142 141 388 141 139 389 139 144 390 144 141 391 141 142 392 142 144 393 144 143 394 143 141 395 141 146 396 146 143 397 143 144 398 144 146 399 146 145 400 145 143 401 143 148 402 148 145 403 145 146 404 146 148 405 148 147 406 147 145 407 145 150 408 150 147 409 147 148 410 148 150 411 150 149 412 149 147 413 147 152 414 152 149 415 149 150 416 150 152 417 152 151 418 151 149 419 149 154 420 154 151 421 151 152 422 152 154 423 154 153 424 153 151 425 151 156 426 156 153 427 153 154 428 154 156 429 156 155 430 155 153 431 153 158 432 158 155 433 155 156 434 156 158 435 158 157 436 157 155 437 155 160 438 160 157 439 157 158 440 158 160 441 160 159 442 159 157 443 157 162 444 162 159 445 159 160 446 160 162 447 162 161 448 161 159 449 159 164 450 164 161 451 161 162 452 162 164 453 164 163 454 163 161 455 161 166 456 166 163 457 163 164 458 164 166 459 166 165 460 165 163 461 163 168 462 168 165 463 165 166 464 166 168 465 168 167 466 167 165 467 165 170 468 170 167 469 167 168 470 168 170 471 170 169 472 169 167 473 167 172 474 172 169 475 169 170 476 170 172 477 172 171 478 171 169 479 169 174 480 174 171 481 171 172 482 172 174 483 174 173 484 173 171 485 171 176 486 176 173 487 173 174 488 174 176 489 176 175 490 175 173 491 173 178 492 178 175 493 175 176 494 176 178 495 178 177 496 177 175 497 175 180 498 180 177 499 177 178 500 178 180 501 180 179 502 179 177 503 177 183 504 183 179 505 179 180 506 180 183 507 183 181 508 181 179 509 179 183 510 183 182 511 182 181 512 181 185 513 185 182 514 182 183 515 183 185 516 185 184 517 184 182 518 182 187 519 187 184 520 184 185 521 185 187 522 187 186 523 186 184 524 184 194 525 194 186 526 186 187 527 187 191 528 191 188 529 188 189 530 189 191 531 191 190 532 190 188 533 188 192 534 192 190 535 190 191 536 191 195 537 195 190 538 190 192 539 192 194 540 194 193 541 193 186 542 186 196 543 196 193 544 193 194 545 194 196 546 196 195 547 195 193 548 193 196 549 196 190 550 190 195 551 195 122 552 122 190 553 190 196 554 196 122 555 122 197 556 197 190 557 190 122 558 122 198 559 198 197 560 197 122 561 122 199 562 199 198 563 198 122 564 122 200 565 200 199 566 199 122 567 122 201 568 201 200 569 200 122 570 122 202 571 202 201 572 201 122 573 122 203 574 203 202 575 202 278 576 278 204 577 204 205 578 205 209 579 209 206 580 206 207 581 207 209 582 209 208 583 208 206 584 206 211 585 211 208 586 208 209 587 209 211 588 211 210 589 210 208 590 208 213 591 213 210 592 210 211 593 211 213 594 213 212 595 212 210 596 210 215 597 215 212 598 212 213 599 213 215 600 215 214 601 214 212 602 212 217 603 217 214 604 214 215 605 215 217 606 217 216 607 216 214 608 214 219 609 219 216 610 216 217 611 217 219 612 219 218 613 218 216 614 216 221 615 221 218 616 218 219 617 219 221 618 221 220 619 220 218 620 218 223 621 223 220 622 220 221 623 221 223 624 223 222 625 222 220 626 220 225 627 225 222 628 222 223 629 223 225 630 225 224 631 224 222 632 222 227 633 227 224 634 224 225 635 225 227 636 227 226 637 226 224 638 224 229 639 229 226 640 226 227 641 227 229 642 229 228 643 228 226 644 226 231 645 231 228 646 228 229 647 229 231 648 231 230 649 230 228 650 228 233 651 233 230 652 230 231 653 231 233 654 233 232 655 232 230 656 230 235 657 235 232 658 232 233 659 233 235 660 235 234 661 234 232 662 232 237 663 237 234 664 234 235 665 235 237 666 237 236 667 236 234 668 234 239 669 239 236 670 236 237 671 237 239 672 239 238 673 238 236 674 236 241 675 241 238 676 238 239 677 239 241 678 241 240 679 240 238 680 238 243 681 243 240 682 240 241 683 241 243 684 243 242 685 242 240 686 240 245 687 245 242 688 242 243 689 243 245 690 245 244 691 244 242 692 242 247 693 247 244 694 244 245 695 245 247 696 247 246 697 246 244 698 244 249 699 249 246 700 246 247 701 247 249 702 249 248 703 248 246 704 246 251 705 251 248 706 248 249 707 249 251 708 251 250 709 250 248 710 248 253 711 253 250 712 250 251 713 251 253 714 253 252 715 252 250 716 250 255 717 255 252 718 252 253 719 253 255 720 255 254 721 254 252 722 252 257 723 257 254 724 254 255 725 255 257 726 257 256 727 256 254 728 254 259 729 259 256 730 256 257 731 257 259 732 259 258 733 258 256 734 256 261 735 261 258 736 258 259 737 259 261 738 261 260 739 260 258 740 258 262 741 262 260 742 260 261 743 261 264 744 264 260 745 260 262 746 262 264 747 264 263 748 263 260 749 260 266 750 266 263 751 263 264 752 264 266 753 266 265 754 265 263 755 263 268 756 268 265 757 265 266 758 266 268 759 268 267 760 267 265 761 265 275 762 275 267 763 267 268 764 268 275 765 275 269 766 269 267 767 267 279 768 279 270 769 270 271 770 271 279 771 279 272 772 272 270 773 270 279 774 279 273 775 273 272 776 272 279 777 279 274 778 274 273 779 273 277 780 277 269 781 269 275 782 275 277 783 277 276 784 276 269 785 269 274 786 274 276 787 276 277 788 277 279 789 279 276 790 276 274 791 274 279 792 279 278 793 278 276 794 276 280 795 280 278 796 278 279 797 279 281 798 281 278 799 278 280 800 280 282 801 282 278 802 278 281 803 281 283 804 283 278 805 278 282 806 282 284 807 284 278 808 278 283 809 283 285 810 285 278 811 278 284 812 284 204 813 204 278 814 278 285 815 285 319 816 319 286 817 286 287 818 287 292 819 292 288 820 288 289 821 289 292 822 292 290 823 290 288 824 288 292 825 292 291 826 291 290 827 290 293 828 293 291 829 291 292 830 292 296 831 296 291 832 291 293 833 293 296 834 296 294 835 294 291 836 291 296 837 296 295 838 295 294 839 294 297 840 297 295 841 295 296 842 296 299 843 299 295 844 295 297 845 297 299 846 299 298 847 298 295 848 295 301 849 301 298 850 298 299 851 299 301 852 301 300 853 300 298 854 298 303 855 303 300 856 300 301 857 301 303 858 303 302 859 302 300 860 300 305 861 305 302 862 302 303 863 303 305 864 305 304 865 304 302 866 302 307 867 307 304 868 304 305 869 305 307 870 307 306 871 306 304 872 304 309 873 309 306 874 306 307 875 307 309 876 309 308 877 308 306 878 306 311 879 311 308 880 308 309 881 309 311 882 311 310 883 310 308 884 308 313 885 313 310 886 310 311 887 311 313 888 313 312 889 312 310 890 310 315 891 315 312 892 312 313 893 313 315 894 315 314 895 314 312 896 312 318 897 318 314 898 314 315 899 315 318 900 318 316 901 316 314 902 314 318 903 318 317 904 317 316 905 316 286 906 286 317 907 317 318 908 318 286 909 286 319 910 319 317 911 317 349 912 349 320 913 320 321 914 321 325 915 325 322 916 322 323 917 323 325 918 325 324 919 324 322 920 322 327 921 327 324 922 324 325 923 325 327 924 327 326 925 326 324 926 324 329 927 329 326 928 326 327 929 327 329 930 329 328 931 328 326 932 326 331 933 331 328 934 328 329 935 329 331 936 331 330 937 330 328 938 328 333 939 333 330 940 330 331 941 331 333 942 333 332 943 332 330 944 330 335 945 335 332 946 332 333 947 333 335 948 335 334 949 334 332 950 332 338 951 338 334 952 334 335 953 335 338 954 338 336 955 336 334 956 334 338 957 338 337 958 337 336 959 336 339 960 339 337 961 337 338 962 338 342 963 342 337 964 337 339 965 339 342 966 342 340 967 340 337 968 337 342 969 342 341 970 341 340 971 340 343 972 343 341 973 341 342 974 342 346 975 346 341 976 341 343 977 343 346 978 346 344 979 344 341 980 341 346 981 346 345 982 345 344 983 344 347 984 347 345 985 345 346 986 346 320 987 320 345 988 345 347 989 347 320 990 320 348 991 348 345 992 345 320 993 320 349 994 349 348 995 348 401 996 401 352 997 352 350 998 350 353 999 353 361 1000 361 351 1001 351 353 1002 353 352 1003 352 361 1004 361 354 1005 354 352 1006 352 353 1007 353 355 1008 355 352 1009 352 354 1010 354 356 1011 356 352 1012 352 355 1013 355 357 1014 357 352 1015 352 356 1016 356 358 1017 358 352 1018 352 357 1019 357 359 1020 359 352 1021 352 358 1022 358 350 1023 350 352 1024 352 359 1025 359 361 1026 361 360 1027 360 351 1028 351 362 1029 362 360 1030 360 361 1031 361 363 1032 363 360 1033 360 362 1034 362 364 1035 364 360 1036 360 363 1037 363 365 1038 365 360 1039 360 364 1040 364 366 1041 366 360 1042 360 365 1043 365 367 1044 367 360 1045 360 366 1046 366 368 1047 368 360 1048 360 367 1049 367 370 1050 370 360 1051 360 368 1052 368 370 1053 370 369 1054 369 360 1055 360 378 1056 378 369 1057 369 370 1058 370 378 1059 378 371 1060 371 369 1061 369 378 1062 378 372 1063 372 371 1064 371 378 1065 378 373 1066 373 372 1067 372 378 1068 378 374 1069 374 373 1070 373 378 1071 378 375 1072 375 374 1073 374 378 1074 378 376 1075 376 375 1076 375 378 1077 378 377 1078 377 376 1079 376 379 1080 379 377 1081 377 378 1082 378 380 1083 380 377 1084 377 379 1085 379 381 1086 381 377 1087 377 380 1088 380 382 1089 382 377 1090 377 381 1091 381 383 1092 383 377 1093 377 382 1094 382 384 1095 384 377 1096 377 383 1097 383 385 1098 385 377 1099 377 384 1100 384 388 1101 388 377 1102 377 385 1103 385 388 1104 388 386 1105 386 377 1106 377 388 1107 388 387 1108 387 386 1109 386 397 1110 397 387 1111 387 388 1112 388 397 1113 397 389 1114 389 387 1115 387 397 1116 397 390 1117 390 389 1118 389 397 1119 397 391 1120 391 390 1121 390 397 1122 397 392 1123 392 391 1124 391 397 1125 397 393 1126 393 392 1127 392 397 1128 397 394 1129 394 393 1130 393 397 1131 397 395 1132 395 394 1133 394 397 1134 397 396 1135 396 395 1136 395 352 1137 352 396 1138 396 397 1139 397 352 1140 352 398 1141 398 396 1142 396 352 1143 352 399 1144 399 398 1145 398 352 1146 352 400 1147 400 399 1148 399 352 1149 352 401 1150 401 400 1151 400 405 1152 405 402 1153 402 403 1154 403 405 1155 405 404 1156 404 421 1157 421 413 1158 413 404 1159 404 405 1160 405 413 1161 413 406 1162 406 404 1163 404 413 1164 413 407 1165 407 406 1166 406 413 1167 413 408 1168 408 407 1169 407 413 1170 413 409 1171 409 408 1172 408 413 1173 413 410 1174 410 409 1175 409 413 1176 413 411 1177 411 410 1178 410 413 1179 413 412 1180 412 411 1181 411 423 1182 423 412 1183 412 413 1184 413 423 1185 423 414 1186 414 412 1187 412 423 1188 423 415 1189 415 414 1190 414 423 1191 423 416 1192 416 415 1193 415 423 1194 423 417 1195 417 416 1196 416 423 1197 423 418 1198 418 417 1199 417 423 1200 423 419 1201 419 418 1202 418 423 1203 423 420 1204 420 419 1205 419 447 1206 447 405 1207 405 421 1208 421 423 1209 423 422 1210 422 420 1211 420 431 1212 431 422 1213 422 423 1214 423 431 1215 431 424 1216 424 422 1217 422 431 1218 431 425 1219 425 424 1220 424 431 1221 431 426 1222 426 425 1223 425 431 1224 431 427 1225 427 426 1226 426 431 1227 431 428 1228 428 427 1229 427 431 1230 431 429 1231 429 428 1232 428 431 1233 431 430 1234 430 429 1235 429 432 1236 432 430 1237 430 431 1238 431 433 1239 433 430 1240 430 432 1241 432 434 1242 434 430 1243 430 433 1244 433 435 1245 435 430 1246 430 434 1247 434 436 1248 436 430 1249 430 435 1250 435 437 1251 437 430 1252 430 436 1253 436 438 1254 438 430 1255 430 437 1256 437 440 1257 440 430 1258 430 438 1259 438 440 1260 440 439 1261 439 430 1262 430 448 1263 448 439 1264 439 440 1265 440 448 1266 448 441 1267 441 439 1268 439 448 1269 448 442 1270 442 441 1271 441 448 1272 448 443 1273 443 442 1274 442 448 1275 448 444 1276 444 443 1277 443 448 1278 448 445 1279 445 444 1280 444 448 1281 448 446 1282 446 445 1283 445 448 1284 448 447 1285 447 446 1286 446 448 1287 448 405 1288 405 447 1289 447 449 1290 449 405 1291 405 448 1292 448 450 1293 450 405 1294 405 449 1295 449 451 1296 451 405 1297 405 450 1298 450 452 1299 452 405 1300 405 451 1301 451 453 1302 453 405 1303 405 452 1304 452 402 1305 402 405 1306 405 453 1307 453 456 1308 456 454 1309 454 455 1310 455 454 1311 454 456 1312 456 457 1313 457 460 1314 460 458 1315 458 459 1316 459 458 1317 458 460 1318 460 461 1319 461 494 1320 494 462 1321 462 463 1322 463 467 1323 467 464 1324 464 465 1325 465 467 1326 467 466 1327 466 464 1328 464 469 1329 469 466 1330 466 467 1331 467 469 1332 469 468 1333 468 466 1334 466 471 1335 471 468 1336 468 469 1337 469 471 1338 471 470 1339 470 468 1340 468 473 1341 473 470 1342 470 471 1343 471 473 1344 473 472 1345 472 470 1346 470 475 1347 475 472 1348 472 473 1349 473 475 1350 475 474 1351 474 472 1352 472 477 1353 477 474 1354 474 475 1355 475 477 1356 477 476 1357 476 474 1358 474 479 1359 479 476 1360 476 477 1361 477 479 1362 479 478 1363 478 476 1364 476 481 1365 481 478 1366 478 479 1367 479 481 1368 481 480 1369 480 478 1370 478 483 1371 483 480 1372 480 481 1373 481 483 1374 483 482 1375 482 480 1376 480 485 1377 485 482 1378 482 483 1379 483 485 1380 485 484 1381 484 482 1382 482 488 1383 488 484 1384 484 485 1385 485 488 1386 488 486 1387 486 484 1388 484 488 1389 488 487 1390 487 486 1391 486 489 1392 489 487 1393 487 488 1394 488 491 1395 491 487 1396 487 489 1397 489 491 1398 491 490 1399 490 487 1400 487 493 1401 493 490 1402 490 491 1403 491 493 1404 493 492 1405 492 490 1406 490 495 1407 495 492 1408 492 493 1409 493 495 1410 495 494 1411 494 492 1412 492 462 1413 462 494 1414 494 495 1415 495 512 1416 512 496 1417 496 497 1418 497 502 1419 502 498 1420 498 499 1421 499 502 1422 502 500 1423 500 498 1424 498 502 1425 502 501 1426 501 500 1427 500 504 1428 504 501 1429 501 502 1430 502 504 1431 504 503 1432 503 501 1433 501 505 1434 505 503 1435 503 504 1436 504 507 1437 507 503 1438 503 505 1439 505 507 1440 507 506 1441 506 503 1442 503 509 1443 509 506 1444 506 507 1445 507 509 1446 509 508 1447 508 506 1448 506 511 1449 511 508 1450 508 509 1451 509 511 1452 511 510 1453 510 508 1454 508 513 1455 513 510 1456 510 511 1457 511 513 1458 513 512 1459 512 510 1460 510 496 1461 496 512 1462 512 513 1463 513 529 1464 529 514 1465 514 515 1466 515 519 1467 519 516 1468 516 517 1469 517 519 1470 519 518 1471 518 516 1472 516 521 1473 521 518 1474 518 519 1475 519 521 1476 521 520 1477 520 518 1478 518 524 1479 524 520 1480 520 521 1481 521 524 1482 524 522 1483 522 520 1484 520 524 1485 524 523 1486 523 522 1487 522 525 1488 525 523 1489 523 524 1490 524 527 1491 527 523 1492 523 525 1493 525 527 1494 527 526 1495 526 523 1496 523 530 1497 530 526 1498 526 527 1499 527 530 1500 530 528 1501 528 526 1502 526 530 1503 530 529 1504 529 528 1505 528 531 1506 531 529 1507 529 530 1508 530 514 1509 514 529 1510 529 531 1511 531 536 1512 536 532 1513 532 533 1514 533 535 1515 535 533 1516 533 534 1517 534 536 1518 536 533 1519 533 535 1520 535 532 1521 532 536 1522 536 537 1523 537 555 1524 555 538 1525 538 539 1526 539 542 1527 542 540 1528 540 541 1529 541 543 1530 543 540 1531 540 542 1532 542 545 1533 545 540 1534 540 543 1535 543 545 1536 545 544 1537 544 540 1538 540 548 1539 548 544 1540 544 545 1541 545 548 1542 548 546 1543 546 544 1544 544 548 1545 548 547 1546 547 546 1547 546 550 1548 550 547 1549 547 548 1550 548 550 1551 550 549 1552 549 547 1553 547 552 1554 552 549 1555 549 550 1556 550 552 1557 552 551 1558 551 549 1559 549 553 1560 553 551 1561 551 552 1562 552 538 1563 538 551 1564 551 553 1565 553 538 1566 538 554 1567 554 551 1568 551 538 1569 538 555 1570 555 554 1571 554

+
+
+ + + + +25.180824 18.000000 2.197359 +24.878183 18.000000 2.500000 +34.540485 17.113510 2.500000 +34.621819 18.000000 2.500000 +34.319176 18.000000 2.197359 +34.242897 17.168579 2.197359 +34.279758 16.206711 2.500000 +33.827690 15.334094 2.500000 +33.998367 16.318110 2.197359 +33.574379 15.499702 2.197359 +33.194897 14.555105 2.500000 +32.980896 14.769105 2.197359 +32.415905 13.922311 2.500000 +32.250298 14.175620 2.197359 +31.543289 13.470242 2.500000 +31.431890 13.751634 2.197359 +30.636490 13.209516 2.500000 +30.581421 13.507105 2.197359 +29.750000 13.128182 2.500000 +29.750000 13.430824 2.197359 +28.863510 13.209516 2.500000 +28.918579 13.507105 2.197359 +27.956711 13.470242 2.500000 +28.068110 13.751634 2.197359 +27.084095 13.922311 2.500000 +27.249702 14.175620 2.197359 +26.305105 14.555105 2.500000 +26.519104 14.769105 2.197359 +25.672312 15.334094 2.500000 +25.925621 15.499702 2.197359 +25.220242 16.206711 2.500000 +25.501633 16.318110 2.197359 +24.959517 17.113510 2.500000 +25.257105 17.168579 2.197359 +48.205379 49.028038 5.712908 +41.794621 49.028038 5.712908 +41.790218 49.528019 5.208545 +48.209782 49.528019 5.208545 +41.790291 49.436611 5.216971 +48.209709 49.436611 5.216971 +41.790527 49.343082 5.244003 +48.209473 49.343082 5.244003 +41.790936 49.253120 5.290896 +48.209064 49.253120 5.290896 +41.791203 49.211426 5.321545 +48.208797 49.211426 5.321545 +41.791512 49.172928 5.356537 +48.208488 49.172928 5.356537 +41.791847 49.138271 5.395341 +48.208153 49.138271 5.395341 +41.792213 49.107990 5.437300 +48.207787 49.107990 5.437300 +41.793003 49.061882 5.527670 +48.206997 49.061882 5.527670 +41.793823 49.035667 5.621431 +48.206177 49.035667 5.621431 +12.400000 8.000000 5.000000 +12.400000 8.000000 1.000000 +11.100000 8.000000 1.000000 +11.100000 8.000000 5.000000 +11.110851 7.881724 1.000000 +11.145638 7.760738 1.000000 +11.110851 7.881724 5.000000 +11.145638 7.760738 5.000000 +11.205953 7.644314 1.000000 +11.290380 7.540380 1.000000 +11.205953 7.644314 5.000000 +11.290380 7.540380 5.000000 +11.394314 7.455953 1.000000 +11.394314 7.455953 5.000000 +11.510738 7.395638 1.000000 +11.631724 7.360851 1.000000 +11.510738 7.395638 5.000000 +11.750000 7.350000 1.000000 +11.631724 7.360851 5.000000 +11.750000 7.350000 5.000000 +11.868276 7.360851 1.000000 +11.868276 7.360851 5.000000 +11.989262 7.395638 1.000000 +11.989262 7.395638 5.000000 +12.105686 7.455953 1.000000 +12.105686 7.455953 5.000000 +12.209620 7.540380 1.000000 +12.209620 7.540380 5.000000 +12.294047 7.644314 1.000000 +12.294047 7.644314 5.000000 +12.354362 7.760738 1.000000 +12.354362 7.760738 5.000000 +12.389149 7.881724 1.000000 +12.389149 7.881724 5.000000 +47.110851 7.881724 5.000000 +47.110851 7.881724 1.000000 +47.099998 8.000000 1.000000 +47.099998 8.000000 5.000000 +48.389149 7.881724 5.000000 +48.400002 8.000000 5.000000 +48.400002 8.000000 1.000000 +48.389149 7.881724 1.000000 +48.354362 7.760738 5.000000 +48.354362 7.760738 1.000000 +48.294048 7.644314 5.000000 +48.294048 7.644314 1.000000 +48.209618 7.540380 5.000000 +48.209618 7.540380 1.000000 +48.105686 7.455953 5.000000 +48.105686 7.455953 1.000000 +47.989262 7.395638 5.000000 +47.989262 7.395638 1.000000 +47.868275 7.360851 5.000000 +47.868275 7.360851 1.000000 +47.750000 7.350000 5.000000 +47.750000 7.350000 1.000000 +47.631725 7.360851 5.000000 +47.631725 7.360851 1.000000 +47.510738 7.395638 5.000000 +47.394314 7.455953 5.000000 +47.510738 7.395638 1.000000 +47.394314 7.455953 1.000000 +47.290382 7.540380 5.000000 +47.290382 7.540380 1.000000 +47.205952 7.644314 5.000000 +47.205952 7.644314 1.000000 +47.145638 7.760738 5.000000 +47.145638 7.760738 1.000000 +44.040382 38.540382 5.000000 +43.849998 39.000000 1.000000 +43.849998 39.000000 5.000000 +43.860851 38.881725 1.000000 +43.895638 38.760738 1.000000 +43.860851 38.881725 5.000000 +43.955952 38.644314 1.000000 +43.895638 38.760738 5.000000 +44.040382 38.540382 1.000000 +43.955952 38.644314 5.000000 +45.139149 38.881725 5.000000 +45.150002 39.000000 5.000000 +45.150002 39.000000 1.000000 +45.139149 38.881725 1.000000 +45.104362 38.760738 5.000000 +45.104362 38.760738 1.000000 +45.044048 38.644314 5.000000 +45.044048 38.644314 1.000000 +44.959618 38.540382 5.000000 +44.855686 38.455952 5.000000 +44.959618 38.540382 1.000000 +44.855686 38.455952 1.000000 +44.739262 38.395638 5.000000 +44.739262 38.395638 1.000000 +44.618275 38.360851 5.000000 +44.618275 38.360851 1.000000 +44.500000 38.349998 5.000000 +44.500000 38.349998 1.000000 +44.381725 38.360851 5.000000 +44.381725 38.360851 1.000000 +44.260738 38.395638 5.000000 +44.260738 38.395638 1.000000 +44.144314 38.455952 5.000000 +44.144314 38.455952 1.000000 +14.360851 38.881725 5.000000 +14.360851 38.881725 1.000000 +14.350000 39.000000 1.000000 +14.350000 39.000000 5.000000 +15.650000 39.000000 5.000000 +15.650000 39.000000 1.000000 +15.639149 38.881725 5.000000 +15.639149 38.881725 1.000000 +15.604362 38.760738 5.000000 +15.604362 38.760738 1.000000 +15.544047 38.644314 5.000000 +15.459620 38.540382 5.000000 +15.544047 38.644314 1.000000 +15.459620 38.540382 1.000000 +15.355686 38.455952 5.000000 +15.355686 38.455952 1.000000 +15.239262 38.395638 5.000000 +15.239262 38.395638 1.000000 +15.118276 38.360851 5.000000 +15.118276 38.360851 1.000000 +15.000000 38.349998 5.000000 +15.000000 38.349998 1.000000 +14.881724 38.360851 5.000000 +14.881724 38.360851 1.000000 +14.760738 38.395638 5.000000 +14.760738 38.395638 1.000000 +14.644314 38.455952 5.000000 +14.644314 38.455952 1.000000 +14.540380 38.540382 5.000000 +14.540380 38.540382 1.000000 +14.455953 38.644314 5.000000 +14.455953 38.644314 1.000000 +14.395638 38.760738 5.000000 +14.395638 38.760738 1.000000 +49.716610 8.363926 2.500000 +49.695156 8.359956 5.000000 +49.728184 8.000000 5.000000 +49.750000 8.000000 2.500000 +45.750000 8.000000 2.500000 +45.771816 8.000000 5.000000 +45.783390 8.363926 2.500000 +45.804844 8.359956 5.000000 +45.890423 8.736190 2.500000 +45.910709 8.728159 5.000000 +46.076008 9.094419 2.500000 +46.335785 9.414213 2.500000 +46.094269 9.082481 5.000000 +46.655579 9.673991 2.500000 +46.351215 9.398787 5.000000 +47.013809 9.859576 2.500000 +46.667519 9.655730 5.000000 +47.386074 9.966611 2.500000 +47.021843 9.839292 5.000000 +47.390045 9.945158 5.000000 +47.750000 10.000000 2.500000 +47.750000 9.978183 5.000000 +48.113926 9.966611 2.500000 +48.486191 9.859576 2.500000 +48.109955 9.945158 5.000000 +48.844421 9.673991 2.500000 +48.478157 9.839292 5.000000 +49.164215 9.414213 2.500000 +48.832481 9.655730 5.000000 +49.148785 9.398787 5.000000 +49.423992 9.094419 2.500000 +49.405731 9.082481 5.000000 +49.609577 8.736190 2.500000 +49.589291 8.728159 5.000000 +13.728183 8.000000 5.000000 +13.750000 8.000000 2.500000 +9.783389 8.363926 2.500000 +9.750000 8.000000 2.500000 +9.771817 8.000000 5.000000 +9.804842 8.359956 5.000000 +9.890424 8.736190 2.500000 +9.910708 8.728159 5.000000 +10.076009 9.094419 2.500000 +10.094270 9.082481 5.000000 +10.335787 9.414213 2.500000 +10.351213 9.398787 5.000000 +10.655581 9.673991 2.500000 +11.013810 9.859576 2.500000 +10.667519 9.655730 5.000000 +11.386074 9.966611 2.500000 +11.021841 9.839292 5.000000 +11.750000 10.000000 2.500000 +11.390044 9.945158 5.000000 +11.750000 9.978183 5.000000 +12.113926 9.966611 2.500000 +12.486190 9.859576 2.500000 +12.109956 9.945158 5.000000 +12.844419 9.673991 2.500000 +12.478159 9.839292 5.000000 +13.164213 9.414213 2.500000 +12.832481 9.655730 5.000000 +13.148787 9.398787 5.000000 +13.423991 9.094419 2.500000 +13.405730 9.082481 5.000000 +13.609576 8.736190 2.500000 +13.589292 8.728159 5.000000 +13.716611 8.363926 2.500000 +13.695158 8.359956 5.000000 +46.466610 39.363926 2.500000 +46.445156 39.359955 5.000000 +46.478184 39.000000 5.000000 +46.500000 39.000000 2.500000 +42.500000 39.000000 2.500000 +42.521816 39.000000 5.000000 +42.533390 39.363926 2.500000 +42.554844 39.359955 5.000000 +42.640423 39.736191 2.500000 +42.660709 39.728157 5.000000 +42.826008 40.094421 2.500000 +42.844269 40.082481 5.000000 +43.085785 40.414215 2.500000 +43.101215 40.398785 5.000000 +43.405579 40.673992 2.500000 +43.417519 40.655731 5.000000 +43.763809 40.859577 2.500000 +43.771843 40.839291 5.000000 +44.136074 40.966610 2.500000 +44.140045 40.945156 5.000000 +44.500000 41.000000 2.500000 +44.500000 40.978184 5.000000 +44.863926 40.966610 2.500000 +44.859955 40.945156 5.000000 +45.236191 40.859577 2.500000 +45.228157 40.839291 5.000000 +45.594421 40.673992 2.500000 +45.582481 40.655731 5.000000 +45.914215 40.414215 2.500000 +45.898785 40.398785 5.000000 +46.173992 40.094421 2.500000 +46.155731 40.082481 5.000000 +46.359577 39.736191 2.500000 +46.339291 39.728157 5.000000 +16.966610 39.363926 2.500000 +16.945158 39.359955 5.000000 +16.978184 39.000000 5.000000 +17.000000 39.000000 2.500000 +13.000000 39.000000 2.500000 +13.021817 39.000000 5.000000 +13.033389 39.363926 2.500000 +13.054842 39.359955 5.000000 +13.140424 39.736191 2.500000 +13.160708 39.728157 5.000000 +13.326009 40.094421 2.500000 +13.344270 40.082481 5.000000 +13.585787 40.414215 2.500000 +13.601213 40.398785 5.000000 +13.905581 40.673992 2.500000 +13.917519 40.655731 5.000000 +14.263810 40.859577 2.500000 +14.636074 40.966610 2.500000 +14.271841 40.839291 5.000000 +14.640044 40.945156 5.000000 +15.000000 41.000000 2.500000 +15.000000 40.978184 5.000000 +15.363926 40.966610 2.500000 +15.359956 40.945156 5.000000 +15.736190 40.859577 2.500000 +16.094419 40.673992 2.500000 +15.728159 40.839291 5.000000 +16.082481 40.655731 5.000000 +16.414213 40.414215 2.500000 +16.398787 40.398785 5.000000 +16.673990 40.094421 2.500000 +16.655729 40.082481 5.000000 +16.859577 39.736191 2.500000 +16.839291 39.728157 5.000000 +8.750000 53.000000 3.500000 +17.724691 53.000000 3.500000 +17.706366 50.900002 5.600000 +8.750000 50.900002 5.600000 +17.706671 51.282124 5.564941 +17.707653 51.673000 5.452556 +8.750000 51.330311 5.555440 +17.709352 52.049141 5.257690 +8.750000 51.734074 5.427258 +17.710464 52.223625 5.130342 +8.750000 52.089931 5.230335 +17.711733 52.384926 4.984924 +8.750000 52.384926 4.984924 +17.713140 52.530342 4.823626 +17.714664 52.657692 4.649140 +8.750000 52.630337 4.689933 +17.717947 52.852554 4.272999 +8.750000 52.827259 4.334073 +17.721357 52.964943 3.882123 +8.750000 52.955441 3.930310 +25.194763 18.000000 0.600000 +25.180824 18.000000 2.197359 +34.242897 17.168579 2.197359 +34.319176 18.000000 2.197359 +34.305237 18.000000 0.600000 +33.998367 16.318110 2.197359 +34.229187 17.171116 0.600000 +33.985405 16.323242 0.600000 +33.574379 15.499702 2.197359 +33.562714 15.507330 0.600000 +32.980896 14.769105 2.197359 +32.971039 14.778961 0.600000 +32.250298 14.175620 2.197359 +31.431890 13.751634 2.197359 +32.242668 14.187288 0.600000 +31.426758 13.764595 0.600000 +30.581421 13.507105 2.197359 +30.578884 13.520812 0.600000 +29.750000 13.430824 2.197359 +29.750000 13.444764 0.600000 +28.918579 13.507105 2.197359 +28.921116 13.520812 0.600000 +28.068110 13.751634 2.197359 +28.073242 13.764595 0.600000 +27.249702 14.175620 2.197359 +27.257330 14.187288 0.600000 +26.519104 14.769105 2.197359 +26.528961 14.778961 0.600000 +25.925621 15.499702 2.197359 +25.501633 16.318110 2.197359 +25.937288 15.507330 0.600000 +25.514595 16.323242 0.600000 +25.257105 17.168579 2.197359 +25.270811 17.171116 0.600000 +9.744764 53.505257 0.000000 +9.744764 53.030544 0.000000 +9.269416 54.000000 0.000000 +10.172572 54.000000 0.000000 +10.009594 53.946487 0.000000 +9.933414 53.896481 0.000000 +9.866547 53.832287 0.000000 +9.228784 53.030544 0.000000 +9.812678 53.756855 0.000000 +9.774189 53.674252 0.000000 +9.751824 53.588985 0.000000 +29.198511 53.448513 6.500000 +24.801489 53.448513 6.500000 +24.750000 53.500000 0.600000 +29.250000 53.500000 0.600000 +19.301489 53.448513 6.500000 +19.250000 53.500000 0.600000 +23.750000 53.500000 0.600000 +23.698511 53.448513 6.500000 +24.801489 51.000000 6.500000 +29.198511 51.000000 6.500000 +29.205494 51.000000 5.700000 +24.794506 51.000000 5.700000 +19.294506 51.000000 5.700000 +19.301489 51.000000 6.500000 +23.698511 51.000000 6.500000 +23.705494 51.000000 5.700000 +29.198511 53.448513 6.500000 +29.198511 51.000000 6.500000 +24.801489 51.000000 6.500000 +24.801489 53.448513 6.500000 +19.301489 51.000000 6.500000 +19.301489 53.448513 6.500000 +23.698511 53.448513 6.500000 +23.698511 51.000000 6.500000 +24.794506 51.000000 5.700000 +29.205494 51.000000 5.700000 +29.205494 50.044506 5.700000 +24.794506 50.044506 5.700000 +23.705494 50.044506 5.700000 +19.294506 50.044506 5.700000 +19.294506 51.000000 5.700000 +23.705494 51.000000 5.700000 +29.205494 50.044506 5.700000 +29.250000 50.000000 0.600000 +24.750000 50.000000 0.600000 +24.794506 50.044506 5.700000 +19.250000 50.000000 0.600000 +19.294506 50.044506 5.700000 +23.705494 50.044506 5.700000 +23.750000 50.000000 0.600000 +34.750000 53.500000 0.600000 +34.698513 53.448513 6.500000 +30.301489 53.448513 6.500000 +30.250000 53.500000 0.600000 +30.301489 51.000000 6.500000 +34.698513 51.000000 6.500000 +34.705494 51.000000 5.700000 +30.294506 51.000000 5.700000 +34.698513 53.448513 6.500000 +34.698513 51.000000 6.500000 +30.301489 51.000000 6.500000 +30.301489 53.448513 6.500000 +34.705494 51.000000 5.700000 +34.705494 50.044506 5.700000 +30.294506 50.044506 5.700000 +30.294506 51.000000 5.700000 +34.750000 50.000000 0.600000 +30.250000 50.000000 0.600000 +30.294506 50.044506 5.700000 +34.705494 50.044506 5.700000 +40.250000 53.500000 0.600000 +40.198513 53.448513 6.500000 +35.801487 53.448513 6.500000 +35.750000 53.500000 0.600000 +35.801487 51.000000 6.500000 +40.198513 51.000000 6.500000 +40.205494 51.000000 5.700000 +35.794506 51.000000 5.700000 +40.198513 53.448513 6.500000 +40.198513 51.000000 6.500000 +35.801487 51.000000 6.500000 +35.801487 53.448513 6.500000 +40.205494 51.000000 5.700000 +40.205494 50.044506 5.700000 +35.794506 50.044506 5.700000 +35.794506 51.000000 5.700000 +40.250000 50.000000 0.600000 +35.750000 50.000000 0.600000 +35.794506 50.044506 5.700000 +40.205494 50.044506 5.700000 +11.290321 49.419685 5.220422 +11.288004 49.385597 4.954847 +11.290875 49.791862 5.283824 +11.290443 49.686607 5.234362 +11.290227 49.559456 5.209534 +11.266581 43.516544 2.500000 +11.250000 43.499962 0.600000 +11.250000 48.774693 0.600000 +11.307597 43.500000 7.200000 +11.266581 43.500000 2.500000 +11.307597 49.041016 7.200000 +11.275308 48.799999 3.500000 +11.294620 49.028038 5.712908 +11.293611 49.040554 5.597287 +11.279835 48.865067 4.018695 +11.292550 49.085503 5.475780 +11.284214 49.064640 4.520517 +11.291558 49.167519 5.362080 +11.290777 49.283134 5.272619 +50.271217 53.030544 0.000000 +49.755238 53.030544 0.000000 +49.409264 53.980927 0.000000 +49.327427 54.000000 0.000000 +49.490406 53.946487 0.000000 +49.566586 53.896481 0.000000 +49.633453 53.832287 0.000000 +49.687321 53.756855 0.000000 +50.230583 54.000000 0.000000 +49.725811 53.674252 0.000000 +49.755238 53.505257 0.000000 +48.209473 49.343082 5.244003 +48.209614 49.665207 5.227733 +48.209126 49.791862 5.283824 +48.209782 49.528019 5.208545 +48.209709 49.436611 5.216971 +48.250000 48.774693 0.600000 +48.250000 43.499962 0.600000 +48.224693 48.799999 3.500000 +48.192402 43.500000 7.200000 +48.192402 49.041016 7.200000 +48.233418 43.500000 2.500000 +48.233418 43.516544 2.500000 +48.220165 48.865067 4.018695 +48.205379 49.028038 5.712908 +48.215786 49.064640 4.520517 +48.206177 49.035667 5.621431 +48.206997 49.061882 5.527670 +48.211994 49.385597 4.954847 +48.207787 49.107990 5.437300 +48.208488 49.172928 5.356537 +48.209064 49.253120 5.290896 +28.073242 22.235405 0.600000 +25.180824 18.000000 2.197359 +25.194763 18.000000 0.600000 +25.257105 18.831421 2.197359 +25.501633 19.681890 2.197359 +25.270811 18.828884 0.600000 +25.514595 19.676758 0.600000 +25.925621 20.500298 2.197359 +25.937288 20.492670 0.600000 +26.519104 21.230896 2.197359 +26.528961 21.221039 0.600000 +27.249702 21.824379 2.197359 +28.068110 22.248367 2.197359 +27.257330 21.812712 0.600000 +34.305237 18.000000 0.600000 +34.319176 18.000000 2.197359 +34.229187 18.828884 0.600000 +33.985405 19.676758 0.600000 +34.242897 18.831421 2.197359 +33.998367 19.681890 2.197359 +33.562714 20.492670 0.600000 +33.574379 20.500298 2.197359 +32.971039 21.221039 0.600000 +32.980896 21.230896 2.197359 +32.242668 21.812712 0.600000 +32.250298 21.824379 2.197359 +31.426758 22.235405 0.600000 +31.431890 22.248367 2.197359 +30.578884 22.479189 0.600000 +30.581421 22.492895 2.197359 +29.750000 22.555237 0.600000 +29.750000 22.569176 2.197359 +28.921116 22.479189 0.600000 +28.918579 22.492895 2.197359 +41.793594 50.764496 5.595623 +41.792683 50.232586 5.491119 +41.793823 49.035667 5.621431 +41.794621 49.028038 5.712908 +41.793003 49.061882 5.527670 +41.792213 49.107990 5.437300 +41.791512 49.172928 5.356537 +41.790936 49.253120 5.290896 +41.790527 49.343082 5.244003 +41.790291 49.436611 5.216971 +41.750000 43.499962 0.600000 +41.750000 53.025307 0.600000 +41.766582 49.000000 2.500000 +41.766582 43.516544 2.500000 +41.790218 49.528019 5.208545 +41.790386 49.665207 5.227733 +41.790874 49.791862 5.283824 +41.775307 53.000000 3.500000 +41.779530 52.943523 3.983753 +41.783955 52.751610 4.490726 +41.788082 52.405640 4.963914 +41.791325 51.920517 5.335360 +41.793209 51.349003 5.551437 +42.749962 42.500000 0.600000 +42.766544 42.516582 2.500000 +47.233456 42.516582 2.500000 +47.250038 42.500000 0.600000 +17.717947 52.852554 4.272999 +17.721357 52.964943 3.882123 +17.733419 49.000000 2.500000 +17.705379 49.028038 5.712908 +17.706388 49.040554 5.597287 +17.707449 49.085503 5.475780 +17.708443 49.167519 5.362080 +17.709223 49.283134 5.272619 +17.750000 53.025307 0.600000 +17.750000 43.499962 0.600000 +17.733419 43.516544 2.500000 +17.724691 53.000000 3.500000 +17.709679 49.419685 5.220422 +17.709774 49.559456 5.209534 +17.709557 49.686607 5.234362 +17.709126 49.791862 5.283824 +17.707069 50.323818 5.519410 +17.706366 50.900002 5.600000 +17.706671 51.282124 5.564941 +17.707653 51.673000 5.452556 +17.709352 52.049141 5.257690 +17.711733 52.384926 4.984924 +17.714664 52.657692 4.649140 +16.750038 42.500000 0.600000 +12.249962 42.500000 0.600000 +12.266543 42.516582 2.500000 +16.733458 42.516582 2.500000 +26.305105 21.444895 2.500000 +11.283275 43.334583 2.500000 +11.266581 43.516544 2.500000 +48.233418 43.500000 2.500000 +48.233418 43.516544 2.500000 +48.250114 43.318035 2.500000 +11.266581 43.500000 2.500000 +16.733458 42.516582 2.500000 +15.363926 40.966610 2.500000 +15.000000 41.000000 2.500000 +14.636074 40.966610 2.500000 +14.263810 40.859577 2.500000 +47.233456 42.516582 2.500000 +43.763809 40.859577 2.500000 +44.136074 40.966610 2.500000 +44.500000 41.000000 2.500000 +44.863926 40.966610 2.500000 +45.236191 40.859577 2.500000 +13.905581 40.673992 2.500000 +11.336789 43.148457 2.500000 +11.249886 43.318035 2.500000 +48.216724 43.334583 2.500000 +48.303635 43.131905 2.500000 +15.736190 40.859577 2.500000 +43.405579 40.673992 2.500000 +6.505707 0.000000 2.500000 +52.994293 0.000000 2.500000 +52.960762 0.800000 2.500000 +13.585787 40.414215 2.500000 +45.594421 40.673992 2.500000 +34.279758 16.206711 2.500000 +45.890423 8.736190 2.500000 +41.766582 49.000000 2.500000 +17.733419 49.000000 2.500000 +41.766582 43.516544 2.500000 +48.844421 6.326009 2.500000 +7.531098 0.800000 2.500000 +6.539237 0.800000 2.500000 +11.013810 6.140423 2.500000 +10.266543 42.500000 2.500000 +9.278847 42.500000 2.500000 +51.968903 0.800000 2.500000 +50.221153 42.500000 2.500000 +17.733419 43.516544 2.500000 +41.783276 43.334583 2.500000 +49.233456 42.500000 2.500000 +46.076008 9.094419 2.500000 +10.448513 42.516693 2.500000 +10.655581 6.326009 2.500000 +49.164215 6.585786 2.500000 +33.827690 15.334094 2.500000 +45.783390 8.363926 2.500000 +34.540485 17.113510 2.500000 +17.716724 43.334583 2.500000 +41.836788 43.148457 2.500000 +46.335785 9.414213 2.500000 +48.486191 6.140423 2.500000 +48.113926 6.033389 2.500000 +47.750000 6.000000 2.500000 +47.386074 6.033389 2.500000 +47.013809 6.140423 2.500000 +46.655579 6.326009 2.500000 +46.335785 6.585786 2.500000 +46.076008 6.905581 2.500000 +45.890423 7.263811 2.500000 +45.783390 7.636074 2.500000 +45.750000 8.000000 2.500000 +11.386074 6.033389 2.500000 +13.326009 40.094421 2.500000 +45.914215 40.414215 2.500000 +16.094419 40.673992 2.500000 +16.915419 42.533276 2.500000 +43.085785 40.414215 2.500000 +42.766544 42.516582 2.500000 +10.634652 42.570213 2.500000 +11.429577 42.969349 2.500000 +11.196366 43.131905 2.500000 +48.163212 43.148457 2.500000 +48.396431 42.952789 2.500000 +49.051487 42.516693 2.500000 +33.194897 14.555105 2.500000 +32.415905 13.922311 2.500000 +31.543289 13.470242 2.500000 +30.636490 13.209516 2.500000 +29.750000 13.128182 2.500000 +28.863510 13.209516 2.500000 +27.956711 13.470242 2.500000 +27.084095 13.922311 2.500000 +26.305105 14.555105 2.500000 +25.672312 15.334094 2.500000 +25.220242 16.206711 2.500000 +10.335787 6.585786 2.500000 +49.423992 6.905581 2.500000 +34.621819 18.000000 2.500000 +17.663210 43.148457 2.500000 +41.929577 42.969349 2.500000 +46.655579 9.673991 2.500000 +12.266543 42.516582 2.500000 +47.415417 42.533276 2.500000 +17.101545 42.586788 2.500000 +42.584583 42.533276 2.500000 +11.750000 6.000000 2.500000 +10.813773 42.663006 2.500000 +48.865349 42.570213 2.500000 +42.826008 40.094421 2.500000 +16.414213 40.414215 2.500000 +46.173992 40.094421 2.500000 +13.140424 39.736191 2.500000 +11.559459 42.809460 2.500000 +11.103570 42.952789 2.500000 +48.070423 42.969349 2.500000 +48.526325 42.792892 2.500000 +12.084581 42.533276 2.500000 +47.601543 42.586788 2.500000 +24.959517 17.113510 2.500000 +17.280653 42.679577 2.500000 +42.398457 42.586788 2.500000 +34.540485 18.886490 2.500000 +47.013809 9.859576 2.500000 +10.076009 6.905581 2.500000 +17.570423 42.969349 2.500000 +42.059460 42.809460 2.500000 +49.609577 7.263811 2.500000 +10.973677 42.792892 2.500000 +11.719347 42.679577 2.500000 +11.898455 42.586788 2.500000 +48.686226 42.663006 2.500000 +47.940540 42.809460 2.500000 +47.780651 42.679577 2.500000 +12.113926 6.033389 2.500000 +47.386074 9.966611 2.500000 +34.279758 19.793289 2.500000 +16.673990 40.094421 2.500000 +17.440542 42.809460 2.500000 +16.859577 39.736191 2.500000 +16.966610 39.363926 2.500000 +17.000000 39.000000 2.500000 +16.966610 38.636074 2.500000 +16.859577 38.263809 2.500000 +42.219349 42.679577 2.500000 +42.640423 39.736191 2.500000 +42.533390 39.363926 2.500000 +42.500000 39.000000 2.500000 +42.533390 38.636074 2.500000 +42.640423 38.263809 2.500000 +42.826008 37.905579 2.500000 +16.673990 37.905579 2.500000 +43.085785 37.585785 2.500000 +13.033389 39.363926 2.500000 +13.000000 39.000000 2.500000 +13.033389 38.636074 2.500000 +13.140424 38.263809 2.500000 +13.326009 37.905579 2.500000 +13.585787 37.585785 2.500000 +13.905581 37.326008 2.500000 +14.263810 37.140423 2.500000 +14.636074 37.033390 2.500000 +15.000000 37.000000 2.500000 +15.363926 37.033390 2.500000 +15.736190 37.140423 2.500000 +16.094419 37.326008 2.500000 +16.414213 37.585785 2.500000 +43.405579 37.326008 2.500000 +46.359577 39.736191 2.500000 +46.466610 39.363926 2.500000 +46.500000 39.000000 2.500000 +46.466610 38.636074 2.500000 +46.359577 38.263809 2.500000 +46.173992 37.905579 2.500000 +45.914215 37.585785 2.500000 +45.594421 37.326008 2.500000 +45.236191 37.140423 2.500000 +44.863926 37.033390 2.500000 +44.500000 37.000000 2.500000 +44.136074 37.033390 2.500000 +43.763809 37.140423 2.500000 +9.890424 7.263811 2.500000 +49.716610 7.636074 2.500000 +12.486190 6.140423 2.500000 +47.750000 10.000000 2.500000 +33.827690 20.665905 2.500000 +49.750000 8.000000 2.500000 +9.783389 7.636074 2.500000 +48.113926 9.966611 2.500000 +12.844419 6.326009 2.500000 +33.194897 21.444895 2.500000 +9.750000 8.000000 2.500000 +9.783389 8.363926 2.500000 +9.890424 8.736190 2.500000 +10.076009 9.094419 2.500000 +10.335787 9.414213 2.500000 +10.655581 9.673991 2.500000 +11.013810 9.859576 2.500000 +11.386074 9.966611 2.500000 +11.750000 10.000000 2.500000 +12.113926 9.966611 2.500000 +12.486190 9.859576 2.500000 +12.844419 9.673991 2.500000 +49.716610 8.363926 2.500000 +49.609577 8.736190 2.500000 +49.423992 9.094419 2.500000 +49.164215 9.414213 2.500000 +48.844421 9.673991 2.500000 +48.486191 9.859576 2.500000 +32.415905 22.077688 2.500000 +31.543289 22.529758 2.500000 +30.636490 22.790483 2.500000 +29.750000 22.871817 2.500000 +28.863510 22.790483 2.500000 +27.956711 22.529758 2.500000 +27.084095 22.077688 2.500000 +13.164213 6.585786 2.500000 +13.423991 6.905581 2.500000 +13.609576 7.263811 2.500000 +13.716611 7.636074 2.500000 +13.750000 8.000000 2.500000 +13.716611 8.363926 2.500000 +13.609576 8.736190 2.500000 +13.423991 9.094419 2.500000 +13.164213 9.414213 2.500000 +24.878183 18.000000 2.500000 +24.959517 18.886490 2.500000 +25.220242 19.793289 2.500000 +25.672312 20.665905 2.500000 +17.733419 49.000000 2.500000 +41.766582 49.000000 2.500000 +11.307597 49.041016 7.200000 +11.294620 49.028038 5.712908 +48.192402 49.041016 7.200000 +41.794621 49.028038 5.712908 +48.205379 49.028038 5.712908 +17.705379 49.028038 5.712908 +8.750000 54.929787 7.368095 +8.750000 54.983307 7.181963 +8.750000 48.769512 0.006429 +8.750000 46.000000 0.002418 +8.750000 48.799999 3.500000 +8.750000 48.835060 3.882123 +8.750000 48.947445 4.272999 +8.750000 49.142311 4.649140 +8.750000 49.415077 4.984924 +8.750000 54.003105 0.019273 +8.750000 53.030403 0.016364 +8.750000 49.750858 5.257690 +8.750000 46.000000 8.000000 +8.750000 50.127003 5.452556 +8.750000 50.517879 5.564941 +8.750000 50.900002 5.600000 +8.750000 51.282124 5.564941 +8.750000 51.673000 5.452556 +8.750000 52.049141 5.257690 +8.750000 52.384926 4.984924 +8.750000 54.198982 0.039783 +8.750000 54.386253 0.097992 +8.750000 54.558437 0.190769 +8.750000 54.709076 0.314984 +8.750000 54.832500 0.466678 +8.750000 54.924435 0.639802 +8.750000 54.980900 0.827079 +8.750000 55.000000 1.022485 +8.750000 55.000000 7.000000 +8.750000 53.000000 3.500000 +8.750000 52.964943 3.882123 +8.750000 52.852554 4.272999 +8.750000 52.657692 4.649140 +8.750000 54.000000 8.000000 +8.750000 54.181965 7.983305 +8.750000 54.368095 7.929788 +8.750000 54.547211 7.836996 +8.750000 54.707108 7.707107 +8.750000 54.836994 7.547210 +49.255257 1.994764 0.000000 +9.050192 48.769455 0.000000 +9.744764 48.769455 0.000000 +7.006145 0.000000 0.000000 +9.744764 2.494745 0.000000 +9.753111 2.403764 0.000000 +9.779868 2.310701 0.000000 +9.826262 2.221147 0.000000 +49.755238 2.494745 0.000000 +49.755238 48.769455 0.000000 +50.449810 48.769455 0.000000 +49.746891 2.403764 0.000000 +49.720131 2.310701 0.000000 +49.673737 2.221147 0.000000 +49.608799 2.141203 0.000000 +49.528854 2.076262 0.000000 +9.891203 2.141203 0.000000 +9.971148 2.076262 0.000000 +49.439301 2.029868 0.000000 +49.346237 2.003111 0.000000 +10.060701 2.029868 0.000000 +10.153764 2.003111 0.000000 +52.493855 0.000000 0.000000 +10.244745 1.994764 0.000000 +0.083825 2.000000 7.000000 +1.886059 45.000000 7.000000 +8.750000 46.000000 0.002418 +8.750000 48.769512 0.006429 +9.050192 48.769455 0.000000 +8.730375 45.803238 0.002701 +8.673090 45.615417 0.004278 +8.580098 45.442612 0.007793 +8.455296 45.291088 0.014397 +7.006145 0.000000 0.000000 +8.303518 45.167259 0.025363 +8.130529 45.075230 0.041835 +7.943920 45.018959 0.064543 +6.186487 0.000000 0.048069 +7.750000 45.000000 0.093651 +6.621591 45.000000 0.377813 +5.360488 0.000000 0.195843 +5.506912 45.000000 0.871388 +4.546373 0.000000 0.445602 +3.762930 0.000000 0.795163 +4.463519 45.000000 1.575874 +3.028129 0.000000 1.237784 +3.549521 45.000000 2.471668 +2.357775 0.000000 1.762583 +1.764399 0.000000 2.355404 +2.813944 45.000000 3.518687 +1.256540 0.000000 3.000000 +2.288376 45.000000 4.662069 +0.655461 0.112321 4.053846 +1.982702 45.000000 5.841338 +0.270816 0.483345 5.144720 +0.097806 1.124963 6.159761 +9.269416 54.000000 0.000000 +9.228784 53.030544 0.000000 +8.750000 53.030403 0.016364 +8.750000 54.003105 0.019273 +11.277561 48.815937 3.758229 +11.275308 48.799999 3.500000 +17.707941 50.048347 5.419555 +17.709126 49.791862 5.283824 +8.750000 50.469688 5.555440 +8.750000 50.900002 5.600000 +17.706366 50.900002 5.600000 +17.706541 50.610508 5.579950 +8.750000 50.065926 5.427258 +17.707069 50.323818 5.519410 +8.750000 49.710068 5.230335 +11.290875 49.791862 5.283824 +8.750000 49.415077 4.984924 +11.289568 49.580921 5.134024 +8.750000 49.169666 4.689933 +11.288004 49.385597 4.954847 +11.286207 49.211769 4.748951 +8.750000 48.972744 4.334073 +11.284214 49.064640 4.520517 +8.750000 48.844559 3.930310 +11.282071 48.948238 4.274998 +11.279835 48.865067 4.018695 +8.750000 48.799999 3.500000 +50.750000 53.030403 0.016364 +50.271217 53.030544 0.000000 +50.230583 54.000000 0.000000 +50.750000 54.003105 0.019273 +50.750000 48.799999 3.500000 +48.224693 48.799999 3.500000 +41.777370 52.986664 3.736283 +41.775307 53.000000 3.500000 +50.750000 53.000000 3.500000 +41.779530 52.943523 3.983753 +50.750000 52.964943 3.882123 +41.781742 52.866268 4.237420 +41.783955 52.751610 4.490726 +50.750000 52.852554 4.272999 +41.786091 52.597889 4.735789 +50.750000 52.657692 4.649140 +41.788082 52.405640 4.963914 +41.789848 52.177963 5.166376 +50.750000 52.384926 4.984924 +41.791325 51.920517 5.335360 +50.750000 52.049141 5.257690 +41.792454 51.641125 5.464875 +50.750000 51.673000 5.452556 +41.793209 51.349003 5.551437 +41.793587 51.053780 5.594362 +50.750000 51.282124 5.564941 +41.793594 50.764496 5.595623 +50.750000 50.900002 5.600000 +41.793278 50.488823 5.559353 +50.750000 50.517879 5.564941 +41.792683 50.232586 5.491119 +41.791862 49.999607 5.397180 +50.750000 50.127003 5.452556 +48.209126 49.791862 5.283824 +41.790874 49.791862 5.283824 +48.210434 49.580921 5.134024 +50.750000 49.750858 5.257690 +48.211994 49.385597 4.954847 +50.750000 49.415077 4.984924 +48.213791 49.211769 4.748951 +48.215786 49.064640 4.520517 +50.750000 49.142311 4.649140 +48.217930 48.948238 4.274998 +48.220165 48.865067 4.018695 +50.750000 48.947445 4.272999 +48.222439 48.815937 3.758229 +50.750000 48.835060 3.882123 +53.651989 42.500000 3.859945 +54.300812 42.500000 4.604214 +55.085659 42.500000 6.326080 +55.216526 42.500000 7.200000 +54.782894 42.500000 5.444029 +49.192440 42.500000 7.200000 +49.233456 42.500000 2.500000 +50.221153 42.500000 2.500000 +51.102116 42.500000 2.578083 +52.001518 42.500000 2.827114 +52.869480 42.500000 3.257517 +7.498482 42.500000 2.827114 +8.397882 42.500000 2.578083 +10.307559 42.500000 7.200000 +4.283473 42.500000 7.200000 +4.414341 42.500000 6.326080 +10.266543 42.500000 2.500000 +9.278847 42.500000 2.500000 +4.717106 42.500000 5.444029 +5.199188 42.500000 4.604214 +5.848010 42.500000 3.859945 +6.630519 42.500000 3.257517 +5.386691 0.000000 2.626603 +57.142223 0.000000 1.762583 +58.243462 0.000000 3.000000 +4.324344 0.000000 3.000000 +1.256540 0.000000 3.000000 +2.357775 0.000000 1.762583 +55.737068 0.000000 0.795163 +55.175655 0.000000 3.000000 +54.139511 0.000000 0.195843 +54.113308 0.000000 2.626603 +52.493855 0.000000 0.000000 +52.994293 0.000000 2.500000 +7.006145 0.000000 0.000000 +5.360488 0.000000 0.195843 +6.505707 0.000000 2.500000 +3.762930 0.000000 0.795163 +9.269416 55.000000 1.000000 +8.750000 55.000000 1.022485 +8.750000 55.000000 7.000000 +50.750000 55.000000 7.000000 +50.750000 55.000000 1.022485 +50.230583 55.000000 1.000000 +10.406014 49.554214 8.000000 +57.789120 5.000000 8.000000 +59.290440 5.000000 8.000000 +56.215359 42.548820 8.000000 +56.191986 42.725845 8.000000 +56.133503 42.905228 8.000000 +56.038158 43.076561 8.000000 +55.908379 43.228729 8.000000 +1.886059 45.000000 8.000000 +0.209562 5.000000 8.000000 +1.710879 5.000000 8.000000 +3.284641 42.548820 8.000000 +3.308015 42.725845 8.000000 +3.366496 42.905228 8.000000 +3.461841 43.076561 8.000000 +3.591622 43.228729 8.000000 +55.750912 43.352032 8.000000 +55.575745 43.440121 8.000000 +57.613941 45.000000 8.000000 +55.394073 43.491039 8.000000 +55.216232 43.506981 8.000000 +50.256943 43.506981 8.000000 +50.074982 43.523674 8.000000 +49.888855 43.577190 8.000000 +49.709747 43.669979 8.000000 +49.549858 43.799858 8.000000 +49.419979 43.959747 8.000000 +49.327190 44.138855 8.000000 +49.273674 44.324982 8.000000 +49.256981 44.506943 8.000000 +49.256981 49.007019 8.000000 +50.750000 45.000000 8.000000 +49.240288 49.188980 8.000000 +49.186771 49.375107 8.000000 +49.093987 49.554214 8.000000 +48.964104 49.714104 8.000000 +48.804214 49.843987 8.000000 +48.625107 49.936771 8.000000 +48.438980 49.990288 8.000000 +50.750000 54.000000 8.000000 +48.257019 50.006981 8.000000 +11.242980 50.006981 8.000000 +11.061019 49.990288 8.000000 +10.874892 49.936771 8.000000 +10.695785 49.843987 8.000000 +10.535896 49.714104 8.000000 +3.749087 43.352032 8.000000 +7.750000 45.000000 8.000000 +3.924256 43.440121 8.000000 +4.105925 43.491039 8.000000 +4.283767 43.506981 8.000000 +7.931963 45.016693 8.000000 +8.118094 45.070213 8.000000 +8.297210 45.163006 8.000000 +8.457107 45.292892 8.000000 +9.243056 43.506981 8.000000 +9.425018 43.523674 8.000000 +9.611144 43.577190 8.000000 +9.790252 43.669979 8.000000 +9.950141 43.799858 8.000000 +10.080023 43.959747 8.000000 +10.172811 44.138855 8.000000 +10.226325 44.324982 8.000000 +8.586995 45.452789 8.000000 +8.679789 45.631905 8.000000 +10.243018 44.506943 8.000000 +8.733305 45.818035 8.000000 +8.750000 46.000000 8.000000 +8.750000 54.000000 8.000000 +10.243018 49.007019 8.000000 +10.259712 49.188980 8.000000 +10.313227 49.375107 8.000000 +3.549521 45.000000 2.471668 +2.813944 45.000000 3.518687 +7.750000 45.000000 8.000000 +7.750000 45.000000 0.093651 +1.886059 45.000000 8.000000 +1.886059 45.000000 7.000000 +2.288376 45.000000 4.662069 +5.506912 45.000000 0.871388 +4.463519 45.000000 1.575874 +56.499413 45.000000 3.211897 +55.611912 45.000000 2.100743 +52.008339 45.000000 0.141289 +50.750000 45.000000 0.001442 +50.750000 45.000000 8.000000 +57.613941 45.000000 8.000000 +53.289589 45.000000 0.533115 +57.613941 45.000000 7.000000 +54.518024 45.000000 1.191652 +57.499542 45.000000 5.740186 +57.133457 45.000000 4.452371 +50.750000 54.368095 7.929788 +50.750000 54.181965 7.983305 +50.750000 45.000000 8.000000 +50.750000 45.000000 0.001442 +50.750000 48.769512 0.006429 +50.750000 48.799999 3.500000 +50.750000 48.835060 3.882123 +50.750000 48.947445 4.272999 +50.750000 49.142311 4.649140 +50.750000 53.000000 3.500000 +50.750000 53.030403 0.016364 +50.750000 54.003105 0.019273 +50.750000 54.198444 0.039180 +50.750000 54.385372 0.096723 +50.750000 54.557831 0.189882 +50.750000 54.708569 0.314474 +50.750000 54.831600 0.466025 +50.750000 54.923168 0.638857 +50.750000 54.980293 0.826500 +50.750000 55.000000 1.022485 +50.750000 52.964943 3.882123 +50.750000 52.852554 4.272999 +50.750000 52.657692 4.649140 +50.750000 52.384926 4.984924 +50.750000 52.049141 5.257690 +50.750000 49.415077 4.984924 +50.750000 54.000000 8.000000 +50.750000 49.750858 5.257690 +50.750000 50.127003 5.452556 +50.750000 50.517879 5.564941 +50.750000 50.900002 5.600000 +50.750000 51.282124 5.564941 +50.750000 51.673000 5.452556 +50.750000 55.000000 7.000000 +50.750000 54.983307 7.181963 +50.750000 54.929787 7.368095 +50.750000 54.836994 7.547210 +50.750000 54.707108 7.707107 +50.750000 54.547211 7.836996 +0.209562 5.000000 8.000000 +1.886059 45.000000 8.000000 +1.886059 45.000000 7.000000 +0.083825 2.000000 7.000000 +0.143293 3.418861 7.743416 +57.613941 45.000000 7.000000 +57.613941 45.000000 8.000000 +59.356709 3.418861 7.743416 +59.416176 2.000000 7.000000 +59.290440 5.000000 8.000000 +57.789120 5.000000 8.000000 +56.215359 42.548820 8.000000 +56.215542 42.544456 7.500000 +57.880466 2.820550 7.500000 +57.835979 3.881966 7.873397 +3.284458 42.544456 7.500000 +3.284641 42.548820 8.000000 +1.664019 3.881966 7.873397 +1.619533 2.820550 7.500000 +1.710879 5.000000 8.000000 +49.702766 43.662994 7.200000 +3.293383 42.542286 7.200000 +1.753047 5.790992 7.200000 +2.744909 5.790992 7.200000 +3.320181 42.732285 7.200000 +3.382431 42.912872 7.200000 +3.477150 43.078228 7.200000 +3.601359 43.222519 7.200000 +3.751101 43.340431 7.200000 +3.920831 43.428062 7.200000 +4.103721 43.481846 7.200000 +4.294103 43.500000 7.200000 +56.755089 5.790992 7.200000 +57.746952 5.790992 7.200000 +55.216526 42.500000 7.200000 +56.206615 42.542286 7.200000 +56.180382 42.731731 7.200000 +56.118683 42.912090 7.200000 +56.023602 43.077759 7.200000 +55.899109 43.222073 7.200000 +55.749432 43.339680 7.200000 +55.580040 43.426975 7.200000 +55.396881 43.481300 7.200000 +49.192440 42.500000 7.200000 +55.205898 43.500000 7.200000 +50.249962 43.500000 7.200000 +50.068001 43.516693 7.200000 +49.881874 43.570210 7.200000 +4.283473 42.500000 7.200000 +9.250038 43.500000 7.200000 +9.431999 43.516693 7.200000 +9.618126 43.570210 7.200000 +9.797234 43.662994 7.200000 +9.957123 43.792877 7.200000 +10.307559 42.500000 7.200000 +10.489530 42.516693 7.200000 +10.675668 42.570213 7.200000 +10.854790 42.663006 7.200000 +11.014693 42.792892 7.200000 +11.144587 42.952789 7.200000 +11.237383 43.131905 7.200000 +10.087004 43.952766 7.200000 +11.290902 43.318035 7.200000 +10.179791 44.131874 7.200000 +10.233306 44.318001 7.200000 +11.307597 43.500000 7.200000 +10.250000 44.499962 7.200000 +10.250000 49.000038 7.200000 +10.266694 49.181999 7.200000 +10.320209 49.368126 7.200000 +10.412996 49.547234 7.200000 +10.542877 49.707123 7.200000 +10.702766 49.837006 7.200000 +10.881874 49.929790 7.200000 +11.068001 49.983307 7.200000 +11.249962 50.000000 7.200000 +48.250038 50.000000 7.200000 +11.307597 49.041016 7.200000 +48.431999 49.983307 7.200000 +48.618126 49.929790 7.200000 +48.797234 49.837006 7.200000 +48.957123 49.707123 7.200000 +49.087006 49.547234 7.200000 +49.179790 49.368126 7.200000 +49.233307 49.181999 7.200000 +49.250000 49.000038 7.200000 +48.192402 49.041016 7.200000 +49.250000 44.499962 7.200000 +49.266693 44.318001 7.200000 +49.320210 44.131874 7.200000 +49.412994 43.952766 7.200000 +48.192402 43.500000 7.200000 +48.209099 43.318035 7.200000 +49.542877 43.792877 7.200000 +48.262615 43.131905 7.200000 +48.355412 42.952789 7.200000 +48.485306 42.792892 7.200000 +48.645210 42.663006 7.200000 +48.824333 42.570213 7.200000 +49.010471 42.516693 7.200000 +49.250000 49.000038 7.200000 +49.250000 44.499962 7.200000 +49.256981 44.506943 8.000000 +49.256981 49.007019 8.000000 +55.205898 43.500000 7.200000 +55.216419 43.502541 7.491273 +50.256943 43.506981 8.000000 +50.249962 43.500000 7.200000 +55.216232 43.506981 8.000000 +4.283767 43.506981 8.000000 +4.283581 43.502541 7.491273 +4.294103 43.500000 7.200000 +9.250038 43.500000 7.200000 +9.243056 43.506981 8.000000 +10.243018 44.506943 8.000000 +10.250000 44.499962 7.200000 +10.250000 49.000038 7.200000 +10.243018 49.007019 8.000000 +11.242980 50.006981 8.000000 +11.249962 50.000000 7.200000 +48.250038 50.000000 7.200000 +48.257019 50.006981 8.000000 +59.323788 4.204260 7.936274 +59.290440 5.000000 8.000000 +55.891747 0.017996 3.423835 +55.175655 0.000000 3.000000 +58.243462 0.000000 3.000000 +56.524059 0.092928 3.959500 +57.048111 0.257256 4.583154 +58.842350 0.111289 4.049048 +57.442474 0.536461 5.253180 +59.063648 0.262266 4.598087 +59.227562 0.480338 5.138377 +57.704731 0.945818 5.926364 +59.338596 0.768482 5.662890 +57.844658 1.473176 6.544223 +59.401817 1.121461 6.155460 +57.892529 2.107283 7.078258 +59.424423 1.533466 6.603054 +59.416176 2.000000 7.000000 +57.880466 2.820550 7.500000 +59.387890 2.674828 7.426463 +57.835979 3.881966 7.873397 +59.356709 3.418861 7.743416 +57.789120 5.000000 8.000000 +1.710879 5.000000 8.000000 +0.209562 5.000000 8.000000 +1.256540 0.000000 3.000000 +4.324344 0.000000 3.000000 +0.655461 0.112321 4.053846 +3.611197 0.017818 3.421742 +2.979651 0.092201 3.955777 +0.435477 0.263742 4.601441 +2.458615 0.254089 4.573636 +0.270816 0.483345 5.144720 +0.160629 0.770222 5.666266 +2.060599 0.533256 5.246820 +0.097806 1.124963 6.159761 +1.798153 0.938965 5.916846 +0.075437 1.535799 6.605641 +1.655914 1.469439 6.540500 +0.083825 2.000000 7.000000 +0.112109 2.674828 7.426463 +1.607526 2.104334 7.076165 +0.143293 3.418861 7.743416 +1.619533 2.820550 7.500000 +0.176211 4.204260 7.936274 +1.664019 3.881966 7.873397 +2.744909 5.790992 7.200000 +1.753047 5.790992 7.200000 +6.539237 0.800000 2.500000 +7.531098 0.800000 2.500000 +5.263665 0.812688 2.665291 +6.260767 0.812560 2.663911 +4.074477 0.882157 3.150442 +5.074368 0.881276 3.145882 +3.062596 1.094513 3.915542 +4.064015 1.091090 3.906142 +2.323076 1.555113 4.856564 +3.322806 1.546908 4.843436 +2.071707 1.900474 5.340680 +3.070807 1.887481 5.324516 +1.898696 2.314760 5.793858 +2.893577 2.305068 5.784458 +1.789320 2.797781 6.205082 +2.782995 2.786443 6.196584 +1.731375 3.333013 6.554118 +2.723781 3.324954 6.549558 +1.709977 3.908938 6.832264 +2.701913 3.903281 6.829962 +1.712400 4.521249 7.036088 +2.704171 4.516007 7.034709 +1.728638 5.149429 7.158844 +2.720437 5.147714 7.158625 +57.746952 5.790992 7.200000 +56.755089 5.790992 7.200000 +53.244473 0.812688 2.665291 +51.968903 0.800000 2.500000 +52.960762 0.800000 2.500000 +54.433662 0.882157 3.150442 +54.231094 0.812560 2.663911 +55.445541 1.094513 3.915542 +55.417492 0.881276 3.145882 +56.427849 1.091090 3.906142 +56.185062 1.555113 4.856564 +57.169056 1.546908 4.843436 +56.436432 1.900474 5.340680 +57.421055 1.887481 5.324516 +56.609444 2.314760 5.793858 +57.598286 2.305068 5.784458 +56.718819 2.797781 6.205082 +57.708866 2.786443 6.196584 +56.776764 3.333013 6.554118 +57.768082 3.324954 6.549558 +56.798161 3.908938 6.832264 +57.789948 3.903281 6.829962 +56.795738 4.521249 7.036088 +57.787689 4.516007 7.034709 +56.779499 5.149429 7.158844 +57.771423 5.147714 7.158625 +56.755089 5.790992 7.200000 +55.216526 42.500000 7.200000 +51.102116 42.500000 2.578083 +50.221153 42.500000 2.500000 +51.968903 0.800000 2.500000 +52.612640 0.802487 2.541375 +52.001518 42.500000 2.827114 +53.244473 0.812688 2.665291 +52.869480 42.500000 3.257517 +53.856758 0.836090 2.870038 +54.433662 0.882157 3.150442 +53.651989 42.500000 3.859945 +54.969219 0.963870 3.503416 +54.300812 42.500000 4.604214 +55.445541 1.094513 3.915542 +55.855343 1.289073 4.375484 +54.782894 42.500000 5.444029 +56.185062 1.555113 4.856564 +55.085659 42.500000 6.326080 +56.609444 2.314760 5.793858 +56.776764 3.333013 6.554118 +56.795738 4.521249 7.036088 +4.414341 42.500000 6.326080 +4.283473 42.500000 7.200000 +7.531098 0.800000 2.500000 +9.278847 42.500000 2.500000 +6.889077 0.802478 2.541156 +6.260767 0.812560 2.663911 +8.397882 42.500000 2.578083 +5.648891 0.835780 2.867736 +7.498482 42.500000 2.827114 +5.074368 0.881276 3.145882 +4.542032 0.961583 3.494917 +6.630519 42.500000 3.257517 +4.064015 1.091090 3.906142 +5.848010 42.500000 3.859945 +3.657338 1.281298 4.359320 +3.322806 1.546908 4.843436 +5.199188 42.500000 4.604214 +2.893577 2.305068 5.784458 +4.717106 42.500000 5.444029 +2.723781 3.324954 6.549558 +2.704171 4.516007 7.034709 +2.744909 5.790992 7.200000 +6.505707 0.000000 2.500000 +6.539237 0.800000 2.500000 +3.293383 42.542286 7.200000 +3.284458 42.544456 7.500000 +1.753047 5.790992 7.200000 +1.619533 2.820550 7.500000 +1.712400 4.521249 7.036088 +1.607526 2.104334 7.076165 +1.731375 3.333013 6.554118 +1.898696 2.314760 5.793858 +1.655914 1.469439 6.540500 +1.798153 0.938965 5.916846 +2.323076 1.555113 4.856564 +2.060599 0.533256 5.246820 +2.652797 1.289073 4.375484 +2.458615 0.254089 4.573636 +3.062596 1.094513 3.915542 +2.979651 0.092201 3.955777 +3.538918 0.963870 3.503416 +4.074477 0.882157 3.150442 +3.611197 0.017818 3.421742 +4.651381 0.836090 2.870038 +4.324344 0.000000 3.000000 +5.263665 0.812688 2.665291 +5.895498 0.802487 2.541375 +5.386691 0.000000 2.626603 +57.746952 5.790992 7.200000 +53.602787 0.802478 2.541156 +52.960762 0.800000 2.500000 +52.994293 0.000000 2.500000 +54.231094 0.812560 2.663911 +54.113308 0.000000 2.626603 +54.842972 0.835780 2.867736 +55.417492 0.881276 3.145882 +55.175655 0.000000 3.000000 +55.949829 0.961583 3.494917 +55.891747 0.017996 3.423835 +56.427849 1.091090 3.906142 +56.834526 1.281298 4.359320 +56.524059 0.092928 3.959500 +57.169056 1.546908 4.843436 +57.048111 0.257256 4.583154 +57.598286 2.305068 5.784458 +57.442474 0.536461 5.253180 +57.768082 3.324954 6.549558 +57.704731 0.945818 5.926364 +57.844658 1.473176 6.544223 +57.787689 4.516007 7.034709 +57.880466 2.820550 7.500000 +56.215542 42.544456 7.500000 +56.206615 42.542286 7.200000 +57.892529 2.107283 7.078258 +57.613941 45.000000 7.000000 +59.416176 2.000000 7.000000 +50.449810 48.769455 0.000000 +50.750000 48.769512 0.006429 +52.493855 0.000000 0.000000 +53.313515 0.000000 0.048069 +50.750000 45.000000 0.001442 +54.139511 0.000000 0.195843 +52.008339 45.000000 0.141289 +54.953629 0.000000 0.445602 +55.737068 0.000000 0.795163 +53.289589 45.000000 0.533115 +56.471870 0.000000 1.237784 +54.518024 45.000000 1.191652 +57.142223 0.000000 1.762583 +57.735600 0.000000 2.355404 +55.611912 45.000000 2.100743 +58.243462 0.000000 3.000000 +58.842350 0.111289 4.049048 +56.499413 45.000000 3.211897 +59.227562 0.480338 5.138377 +57.133457 45.000000 4.452371 +59.401817 1.121461 6.155460 +57.499542 45.000000 5.740186 +49.750000 53.025307 0.600000 +49.755238 53.030544 0.000000 +41.775307 53.000000 3.500000 +41.750000 53.025307 0.600000 +50.750000 53.000000 3.500000 +50.750000 53.030403 0.016364 +50.271217 53.030544 0.000000 +50.449810 48.769455 0.000000 +49.755238 48.769455 0.000000 +48.250000 48.774693 0.600000 +48.224693 48.799999 3.500000 +49.750000 48.774693 0.600000 +50.750000 48.799999 3.500000 +50.750000 48.769512 0.006429 +9.750000 48.774693 0.600000 +9.744764 48.769455 0.000000 +8.750000 48.799999 3.500000 +11.275308 48.799999 3.500000 +11.250000 48.774693 0.600000 +8.750000 48.769512 0.006429 +9.050192 48.769455 0.000000 +9.228784 53.030544 0.000000 +9.744764 53.030544 0.000000 +9.750000 53.025307 0.600000 +17.750000 53.025307 0.600000 +17.724691 53.000000 3.500000 +8.750000 53.000000 3.500000 +8.750000 53.030403 0.016364 +13.033389 38.636074 2.500000 +13.054842 38.640045 5.000000 +13.021817 39.000000 5.000000 +13.000000 39.000000 2.500000 +17.000000 39.000000 2.500000 +16.978184 39.000000 5.000000 +16.966610 38.636074 2.500000 +16.945158 38.640045 5.000000 +16.859577 38.263809 2.500000 +16.673990 37.905579 2.500000 +16.839291 38.271843 5.000000 +16.655729 37.917519 5.000000 +16.414213 37.585785 2.500000 +16.398787 37.601215 5.000000 +16.094419 37.326008 2.500000 +16.082481 37.344269 5.000000 +15.736190 37.140423 2.500000 +15.728159 37.160709 5.000000 +15.363926 37.033390 2.500000 +15.359956 37.054844 5.000000 +15.000000 37.000000 2.500000 +15.000000 37.021816 5.000000 +14.636074 37.033390 2.500000 +14.640044 37.054844 5.000000 +14.263810 37.140423 2.500000 +14.271841 37.160709 5.000000 +13.905581 37.326008 2.500000 +13.917519 37.344269 5.000000 +13.585787 37.585785 2.500000 +13.601213 37.601215 5.000000 +13.326009 37.905579 2.500000 +13.344270 37.917519 5.000000 +13.140424 38.263809 2.500000 +13.160708 38.271843 5.000000 +14.395638 39.239262 5.000000 +13.601213 40.398785 5.000000 +14.455953 39.355686 5.000000 +13.917519 40.655731 5.000000 +14.540380 39.459618 5.000000 +14.271841 40.839291 5.000000 +14.644314 39.544048 5.000000 +14.640044 40.945156 5.000000 +14.760738 39.604362 5.000000 +15.000000 40.978184 5.000000 +14.881724 39.639149 5.000000 +15.359956 40.945156 5.000000 +15.000000 39.650002 5.000000 +15.728159 40.839291 5.000000 +15.118276 39.639149 5.000000 +16.082481 40.655731 5.000000 +15.239262 39.604362 5.000000 +16.398787 40.398785 5.000000 +15.355686 39.544048 5.000000 +16.655729 40.082481 5.000000 +15.459620 39.459618 5.000000 +16.839291 39.728157 5.000000 +15.544047 39.355686 5.000000 +16.945158 39.359955 5.000000 +15.604362 39.239262 5.000000 +16.978184 39.000000 5.000000 +15.639149 39.118275 5.000000 +16.945158 38.640045 5.000000 +15.650000 39.000000 5.000000 +16.839291 38.271843 5.000000 +15.639149 38.881725 5.000000 +16.655729 37.917519 5.000000 +15.604362 38.760738 5.000000 +16.398787 37.601215 5.000000 +15.544047 38.644314 5.000000 +16.082481 37.344269 5.000000 +15.459620 38.540382 5.000000 +15.728159 37.160709 5.000000 +15.355686 38.455952 5.000000 +15.359956 37.054844 5.000000 +15.239262 38.395638 5.000000 +15.000000 37.021816 5.000000 +15.118276 38.360851 5.000000 +14.640044 37.054844 5.000000 +15.000000 38.349998 5.000000 +14.271841 37.160709 5.000000 +14.881724 38.360851 5.000000 +13.917519 37.344269 5.000000 +14.760738 38.395638 5.000000 +13.601213 37.601215 5.000000 +14.644314 38.455952 5.000000 +13.344270 37.917519 5.000000 +14.540380 38.540382 5.000000 +13.160708 38.271843 5.000000 +14.455953 38.644314 5.000000 +13.054842 38.640045 5.000000 +14.395638 38.760738 5.000000 +13.021817 39.000000 5.000000 +14.360851 38.881725 5.000000 +13.054842 39.359955 5.000000 +14.350000 39.000000 5.000000 +13.160708 39.728157 5.000000 +14.360851 39.118275 5.000000 +13.344270 40.082481 5.000000 +42.533390 38.636074 2.500000 +42.554844 38.640045 5.000000 +42.521816 39.000000 5.000000 +42.500000 39.000000 2.500000 +46.500000 39.000000 2.500000 +46.478184 39.000000 5.000000 +46.466610 38.636074 2.500000 +46.445156 38.640045 5.000000 +46.359577 38.263809 2.500000 +46.339291 38.271843 5.000000 +46.173992 37.905579 2.500000 +46.155731 37.917519 5.000000 +45.914215 37.585785 2.500000 +45.898785 37.601215 5.000000 +45.594421 37.326008 2.500000 +45.582481 37.344269 5.000000 +45.236191 37.140423 2.500000 +45.228157 37.160709 5.000000 +44.863926 37.033390 2.500000 +44.859955 37.054844 5.000000 +44.500000 37.000000 2.500000 +44.500000 37.021816 5.000000 +44.136074 37.033390 2.500000 +44.140045 37.054844 5.000000 +43.763809 37.140423 2.500000 +43.771843 37.160709 5.000000 +43.405579 37.326008 2.500000 +43.417519 37.344269 5.000000 +43.085785 37.585785 2.500000 +43.101215 37.601215 5.000000 +42.826008 37.905579 2.500000 +42.844269 37.917519 5.000000 +42.640423 38.263809 2.500000 +42.660709 38.271843 5.000000 +43.895638 38.760738 5.000000 +42.521816 39.000000 5.000000 +43.860851 38.881725 5.000000 +42.554844 39.359955 5.000000 +43.849998 39.000000 5.000000 +42.660709 39.728157 5.000000 +43.860851 39.118275 5.000000 +42.844269 40.082481 5.000000 +43.895638 39.239262 5.000000 +43.101215 40.398785 5.000000 +43.955952 39.355686 5.000000 +43.417519 40.655731 5.000000 +44.040382 39.459618 5.000000 +43.771843 40.839291 5.000000 +44.144314 39.544048 5.000000 +44.140045 40.945156 5.000000 +44.260738 39.604362 5.000000 +44.500000 40.978184 5.000000 +44.381725 39.639149 5.000000 +44.859955 40.945156 5.000000 +44.500000 39.650002 5.000000 +45.228157 40.839291 5.000000 +44.618275 39.639149 5.000000 +45.582481 40.655731 5.000000 +44.739262 39.604362 5.000000 +45.898785 40.398785 5.000000 +44.855686 39.544048 5.000000 +46.155731 40.082481 5.000000 +44.959618 39.459618 5.000000 +46.339291 39.728157 5.000000 +45.044048 39.355686 5.000000 +46.445156 39.359955 5.000000 +45.104362 39.239262 5.000000 +46.478184 39.000000 5.000000 +45.139149 39.118275 5.000000 +46.445156 38.640045 5.000000 +45.150002 39.000000 5.000000 +46.339291 38.271843 5.000000 +45.139149 38.881725 5.000000 +46.155731 37.917519 5.000000 +45.104362 38.760738 5.000000 +45.898785 37.601215 5.000000 +45.044048 38.644314 5.000000 +45.582481 37.344269 5.000000 +44.959618 38.540382 5.000000 +45.228157 37.160709 5.000000 +44.855686 38.455952 5.000000 +44.859955 37.054844 5.000000 +44.739262 38.395638 5.000000 +44.500000 37.021816 5.000000 +44.618275 38.360851 5.000000 +44.140045 37.054844 5.000000 +44.500000 38.349998 5.000000 +43.771843 37.160709 5.000000 +44.381725 38.360851 5.000000 +43.417519 37.344269 5.000000 +44.260738 38.395638 5.000000 +43.101215 37.601215 5.000000 +44.144314 38.455952 5.000000 +42.844269 37.917519 5.000000 +44.040382 38.540382 5.000000 +42.660709 38.271843 5.000000 +43.955952 38.644314 5.000000 +42.554844 38.640045 5.000000 +13.750000 8.000000 2.500000 +13.728183 8.000000 5.000000 +9.771817 8.000000 5.000000 +9.750000 8.000000 2.500000 +9.804842 7.640044 5.000000 +9.783389 7.636074 2.500000 +9.910708 7.271842 5.000000 +9.890424 7.263811 2.500000 +10.094270 6.917519 5.000000 +10.076009 6.905581 2.500000 +10.351213 6.601213 5.000000 +10.335787 6.585786 2.500000 +10.667519 6.344270 5.000000 +10.655581 6.326009 2.500000 +11.021841 6.160709 5.000000 +11.013810 6.140423 2.500000 +11.390044 6.054842 5.000000 +11.386074 6.033389 2.500000 +11.750000 6.021817 5.000000 +11.750000 6.000000 2.500000 +12.109956 6.054842 5.000000 +12.113926 6.033389 2.500000 +12.478159 6.160709 5.000000 +12.486190 6.140423 2.500000 +12.832481 6.344270 5.000000 +12.844419 6.326009 2.500000 +13.148787 6.601213 5.000000 +13.164213 6.585786 2.500000 +13.405730 6.917519 5.000000 +13.423991 6.905581 2.500000 +13.589292 7.271842 5.000000 +13.609576 7.263811 2.500000 +13.695158 7.640044 5.000000 +13.716611 7.636074 2.500000 +12.400000 8.000000 5.000000 +13.589292 7.271842 5.000000 +12.389149 7.881724 5.000000 +13.405730 6.917519 5.000000 +12.354362 7.760738 5.000000 +13.148787 6.601213 5.000000 +12.294047 7.644314 5.000000 +12.832481 6.344270 5.000000 +12.209620 7.540380 5.000000 +12.478159 6.160709 5.000000 +12.105686 7.455953 5.000000 +12.109956 6.054842 5.000000 +11.989262 7.395638 5.000000 +11.750000 6.021817 5.000000 +11.868276 7.360851 5.000000 +11.390044 6.054842 5.000000 +11.750000 7.350000 5.000000 +11.021841 6.160709 5.000000 +11.631724 7.360851 5.000000 +10.667519 6.344270 5.000000 +11.510738 7.395638 5.000000 +10.351213 6.601213 5.000000 +11.394314 7.455953 5.000000 +10.094270 6.917519 5.000000 +11.290380 7.540380 5.000000 +9.910708 7.271842 5.000000 +11.205953 7.644314 5.000000 +9.804842 7.640044 5.000000 +11.145638 7.760738 5.000000 +9.771817 8.000000 5.000000 +11.110851 7.881724 5.000000 +9.804842 8.359956 5.000000 +11.100000 8.000000 5.000000 +9.910708 8.728159 5.000000 +11.110851 8.118276 5.000000 +10.094270 9.082481 5.000000 +11.145638 8.239262 5.000000 +10.351213 9.398787 5.000000 +11.205953 8.355686 5.000000 +10.667519 9.655730 5.000000 +11.290380 8.459620 5.000000 +11.021841 9.839292 5.000000 +11.394314 8.544047 5.000000 +11.390044 9.945158 5.000000 +11.510738 8.604362 5.000000 +11.750000 9.978183 5.000000 +11.631724 8.639149 5.000000 +12.109956 9.945158 5.000000 +11.750000 8.650000 5.000000 +12.478159 9.839292 5.000000 +11.868276 8.639149 5.000000 +12.832481 9.655730 5.000000 +11.989262 8.604362 5.000000 +13.148787 9.398787 5.000000 +12.105686 8.544047 5.000000 +13.405730 9.082481 5.000000 +12.209620 8.459620 5.000000 +13.589292 8.728159 5.000000 +12.294047 8.355686 5.000000 +13.695158 8.359956 5.000000 +12.354362 8.239262 5.000000 +13.728183 8.000000 5.000000 +12.389149 8.118276 5.000000 +13.695158 7.640044 5.000000 +45.783390 7.636074 2.500000 +45.804844 7.640044 5.000000 +45.771816 8.000000 5.000000 +45.750000 8.000000 2.500000 +49.750000 8.000000 2.500000 +49.728184 8.000000 5.000000 +49.716610 7.636074 2.500000 +49.695156 7.640044 5.000000 +49.609577 7.263811 2.500000 +49.589291 7.271842 5.000000 +49.423992 6.905581 2.500000 +49.405731 6.917519 5.000000 +49.164215 6.585786 2.500000 +49.148785 6.601213 5.000000 +48.844421 6.326009 2.500000 +48.832481 6.344270 5.000000 +48.486191 6.140423 2.500000 +48.478157 6.160709 5.000000 +48.113926 6.033389 2.500000 +48.109955 6.054842 5.000000 +47.750000 6.000000 2.500000 +47.750000 6.021817 5.000000 +47.386074 6.033389 2.500000 +47.390045 6.054842 5.000000 +47.013809 6.140423 2.500000 +47.021843 6.160709 5.000000 +46.655579 6.326009 2.500000 +46.667519 6.344270 5.000000 +46.335785 6.585786 2.500000 +46.351215 6.601213 5.000000 +46.076008 6.905581 2.500000 +46.094269 6.917519 5.000000 +45.890423 7.263811 2.500000 +45.910709 7.271842 5.000000 +48.294048 8.355686 5.000000 +49.695156 8.359956 5.000000 +48.354362 8.239262 5.000000 +49.728184 8.000000 5.000000 +48.389149 8.118276 5.000000 +49.695156 7.640044 5.000000 +48.400002 8.000000 5.000000 +49.589291 7.271842 5.000000 +48.389149 7.881724 5.000000 +49.405731 6.917519 5.000000 +48.354362 7.760738 5.000000 +49.148785 6.601213 5.000000 +48.294048 7.644314 5.000000 +48.832481 6.344270 5.000000 +48.209618 7.540380 5.000000 +48.478157 6.160709 5.000000 +48.105686 7.455953 5.000000 +48.109955 6.054842 5.000000 +47.989262 7.395638 5.000000 +47.750000 6.021817 5.000000 +47.868275 7.360851 5.000000 +47.390045 6.054842 5.000000 +47.750000 7.350000 5.000000 +47.021843 6.160709 5.000000 +47.631725 7.360851 5.000000 +46.667519 6.344270 5.000000 +47.510738 7.395638 5.000000 +46.351215 6.601213 5.000000 +47.394314 7.455953 5.000000 +46.094269 6.917519 5.000000 +47.290382 7.540380 5.000000 +45.910709 7.271842 5.000000 +47.205952 7.644314 5.000000 +45.804844 7.640044 5.000000 +47.145638 7.760738 5.000000 +45.771816 8.000000 5.000000 +47.110851 7.881724 5.000000 +45.804844 8.359956 5.000000 +47.099998 8.000000 5.000000 +45.910709 8.728159 5.000000 +47.110851 8.118276 5.000000 +46.094269 9.082481 5.000000 +47.145638 8.239262 5.000000 +46.351215 9.398787 5.000000 +47.205952 8.355686 5.000000 +46.667519 9.655730 5.000000 +47.290382 8.459620 5.000000 +47.021843 9.839292 5.000000 +47.394314 8.544047 5.000000 +47.390045 9.945158 5.000000 +47.510738 8.604362 5.000000 +47.750000 9.978183 5.000000 +47.631725 8.639149 5.000000 +48.109955 9.945158 5.000000 +47.750000 8.650000 5.000000 +48.478157 9.839292 5.000000 +47.868275 8.639149 5.000000 +48.832481 9.655730 5.000000 +47.989262 8.604362 5.000000 +49.148785 9.398787 5.000000 +48.105686 8.544047 5.000000 +49.405731 9.082481 5.000000 +48.209618 8.459620 5.000000 +49.589291 8.728159 5.000000 +15.000000 39.650002 1.000000 +14.881724 39.639149 1.000000 +14.455953 39.355686 1.000000 +14.395638 39.239262 1.000000 +14.540380 39.459618 1.000000 +14.644314 39.544048 1.000000 +14.360851 39.118275 1.000000 +14.760738 39.604362 1.000000 +14.350000 39.000000 1.000000 +14.360851 38.881725 1.000000 +14.395638 38.760738 1.000000 +14.455953 38.644314 1.000000 +14.540380 38.540382 1.000000 +14.644314 38.455952 1.000000 +14.760738 38.395638 1.000000 +14.881724 38.360851 1.000000 +15.000000 38.349998 1.000000 +15.118276 38.360851 1.000000 +15.239262 38.395638 1.000000 +15.355686 38.455952 1.000000 +15.459620 38.540382 1.000000 +15.544047 38.644314 1.000000 +15.604362 38.760738 1.000000 +15.639149 38.881725 1.000000 +15.650000 39.000000 1.000000 +15.639149 39.118275 1.000000 +15.604362 39.239262 1.000000 +15.544047 39.355686 1.000000 +15.459620 39.459618 1.000000 +15.355686 39.544048 1.000000 +15.239262 39.604362 1.000000 +15.118276 39.639149 1.000000 +14.350000 39.000000 5.000000 +14.350000 39.000000 1.000000 +15.650000 39.000000 1.000000 +15.650000 39.000000 5.000000 +15.639149 39.118275 1.000000 +15.639149 39.118275 5.000000 +15.604362 39.239262 1.000000 +15.544047 39.355686 1.000000 +15.604362 39.239262 5.000000 +15.544047 39.355686 5.000000 +15.459620 39.459618 1.000000 +15.355686 39.544048 1.000000 +15.459620 39.459618 5.000000 +15.239262 39.604362 1.000000 +15.355686 39.544048 5.000000 +15.118276 39.639149 1.000000 +15.239262 39.604362 5.000000 +15.000000 39.650002 1.000000 +15.118276 39.639149 5.000000 +14.881724 39.639149 1.000000 +15.000000 39.650002 5.000000 +14.881724 39.639149 5.000000 +14.760738 39.604362 1.000000 +14.644314 39.544048 1.000000 +14.760738 39.604362 5.000000 +14.540380 39.459618 1.000000 +14.644314 39.544048 5.000000 +14.455953 39.355686 1.000000 +14.540380 39.459618 5.000000 +14.455953 39.355686 5.000000 +14.395638 39.239262 1.000000 +14.395638 39.239262 5.000000 +14.360851 39.118275 1.000000 +14.360851 39.118275 5.000000 +44.500000 39.650002 1.000000 +44.381725 39.639149 1.000000 +43.955952 39.355686 1.000000 +43.895638 39.239262 1.000000 +44.040382 39.459618 1.000000 +44.144314 39.544048 1.000000 +43.860851 39.118275 1.000000 +44.260738 39.604362 1.000000 +43.849998 39.000000 1.000000 +43.860851 38.881725 1.000000 +43.895638 38.760738 1.000000 +43.955952 38.644314 1.000000 +44.040382 38.540382 1.000000 +44.144314 38.455952 1.000000 +44.260738 38.395638 1.000000 +44.381725 38.360851 1.000000 +44.500000 38.349998 1.000000 +44.618275 38.360851 1.000000 +44.739262 38.395638 1.000000 +44.855686 38.455952 1.000000 +44.959618 38.540382 1.000000 +45.044048 38.644314 1.000000 +45.104362 38.760738 1.000000 +45.139149 38.881725 1.000000 +45.150002 39.000000 1.000000 +45.139149 39.118275 1.000000 +45.104362 39.239262 1.000000 +45.044048 39.355686 1.000000 +44.959618 39.459618 1.000000 +44.855686 39.544048 1.000000 +44.739262 39.604362 1.000000 +44.618275 39.639149 1.000000 +43.895638 39.239262 5.000000 +43.860851 39.118275 5.000000 +43.849998 39.000000 5.000000 +43.849998 39.000000 1.000000 +45.150002 39.000000 1.000000 +45.150002 39.000000 5.000000 +45.139149 39.118275 1.000000 +45.104362 39.239262 1.000000 +45.139149 39.118275 5.000000 +45.104362 39.239262 5.000000 +45.044048 39.355686 1.000000 +44.959618 39.459618 1.000000 +45.044048 39.355686 5.000000 +44.959618 39.459618 5.000000 +44.855686 39.544048 1.000000 +44.855686 39.544048 5.000000 +44.739262 39.604362 1.000000 +44.739262 39.604362 5.000000 +44.618275 39.639149 1.000000 +44.618275 39.639149 5.000000 +44.500000 39.650002 1.000000 +44.500000 39.650002 5.000000 +44.381725 39.639149 1.000000 +44.381725 39.639149 5.000000 +44.260738 39.604362 1.000000 +44.260738 39.604362 5.000000 +44.144314 39.544048 1.000000 +44.144314 39.544048 5.000000 +44.040382 39.459618 1.000000 +44.040382 39.459618 5.000000 +43.955952 39.355686 1.000000 +43.955952 39.355686 5.000000 +43.895638 39.239262 1.000000 +43.860851 39.118275 1.000000 +47.750000 8.650000 1.000000 +47.631725 8.639149 1.000000 +47.205952 8.355686 1.000000 +47.145638 8.239262 1.000000 +47.290382 8.459620 1.000000 +47.394314 8.544047 1.000000 +47.110851 8.118276 1.000000 +47.510738 8.604362 1.000000 +47.099998 8.000000 1.000000 +47.110851 7.881724 1.000000 +47.145638 7.760738 1.000000 +47.205952 7.644314 1.000000 +47.290382 7.540380 1.000000 +47.394314 7.455953 1.000000 +47.510738 7.395638 1.000000 +47.631725 7.360851 1.000000 +47.750000 7.350000 1.000000 +47.868275 7.360851 1.000000 +47.989262 7.395638 1.000000 +48.105686 7.455953 1.000000 +48.209618 7.540380 1.000000 +48.294048 7.644314 1.000000 +48.354362 7.760738 1.000000 +48.389149 7.881724 1.000000 +48.400002 8.000000 1.000000 +48.389149 8.118276 1.000000 +48.354362 8.239262 1.000000 +48.294048 8.355686 1.000000 +48.209618 8.459620 1.000000 +48.105686 8.544047 1.000000 +47.989262 8.604362 1.000000 +47.868275 8.639149 1.000000 +47.145638 8.239262 1.000000 +47.110851 8.118276 5.000000 +47.099998 8.000000 5.000000 +47.099998 8.000000 1.000000 +47.145638 8.239262 5.000000 +47.110851 8.118276 1.000000 +48.400002 8.000000 1.000000 +48.400002 8.000000 5.000000 +48.389149 8.118276 1.000000 +48.354362 8.239262 1.000000 +48.389149 8.118276 5.000000 +48.354362 8.239262 5.000000 +48.294048 8.355686 1.000000 +48.294048 8.355686 5.000000 +48.209618 8.459620 1.000000 +48.209618 8.459620 5.000000 +48.105686 8.544047 1.000000 +48.105686 8.544047 5.000000 +47.989262 8.604362 1.000000 +47.989262 8.604362 5.000000 +47.868275 8.639149 1.000000 +47.750000 8.650000 1.000000 +47.868275 8.639149 5.000000 +47.750000 8.650000 5.000000 +47.631725 8.639149 1.000000 +47.631725 8.639149 5.000000 +47.510738 8.604362 1.000000 +47.510738 8.604362 5.000000 +47.394314 8.544047 1.000000 +47.394314 8.544047 5.000000 +47.290382 8.459620 1.000000 +47.205952 8.355686 1.000000 +47.290382 8.459620 5.000000 +47.205952 8.355686 5.000000 +11.750000 8.650000 1.000000 +11.631724 8.639149 1.000000 +11.205953 8.355686 1.000000 +11.145638 8.239262 1.000000 +11.290380 8.459620 1.000000 +11.394314 8.544047 1.000000 +11.110851 8.118276 1.000000 +11.510738 8.604362 1.000000 +11.100000 8.000000 1.000000 +11.110851 7.881724 1.000000 +11.145638 7.760738 1.000000 +11.205953 7.644314 1.000000 +11.290380 7.540380 1.000000 +11.394314 7.455953 1.000000 +11.510738 7.395638 1.000000 +11.631724 7.360851 1.000000 +11.750000 7.350000 1.000000 +11.868276 7.360851 1.000000 +11.989262 7.395638 1.000000 +12.105686 7.455953 1.000000 +12.209620 7.540380 1.000000 +12.294047 7.644314 1.000000 +12.354362 7.760738 1.000000 +12.389149 7.881724 1.000000 +12.400000 8.000000 1.000000 +12.389149 8.118276 1.000000 +12.354362 8.239262 1.000000 +12.294047 8.355686 1.000000 +12.209620 8.459620 1.000000 +12.105686 8.544047 1.000000 +11.989262 8.604362 1.000000 +11.868276 8.639149 1.000000 +12.389149 8.118276 1.000000 +12.400000 8.000000 1.000000 +11.110851 8.118276 5.000000 +11.100000 8.000000 5.000000 +11.100000 8.000000 1.000000 +11.145638 8.239262 5.000000 +11.110851 8.118276 1.000000 +11.145638 8.239262 1.000000 +11.205953 8.355686 5.000000 +11.205953 8.355686 1.000000 +11.290380 8.459620 5.000000 +11.394314 8.544047 5.000000 +11.290380 8.459620 1.000000 +11.394314 8.544047 1.000000 +11.510738 8.604362 5.000000 +11.510738 8.604362 1.000000 +11.631724 8.639149 5.000000 +11.750000 8.650000 5.000000 +11.631724 8.639149 1.000000 +11.750000 8.650000 1.000000 +11.868276 8.639149 5.000000 +11.868276 8.639149 1.000000 +11.989262 8.604362 5.000000 +11.989262 8.604362 1.000000 +12.105686 8.544047 5.000000 +12.105686 8.544047 1.000000 +12.209620 8.459620 5.000000 +12.209620 8.459620 1.000000 +12.294047 8.355686 5.000000 +12.294047 8.355686 1.000000 +12.354362 8.239262 5.000000 +12.354362 8.239262 1.000000 +12.389149 8.118276 5.000000 +12.400000 8.000000 5.000000 +49.755238 53.030544 0.000000 +49.750000 53.025307 0.600000 +49.750000 53.500019 0.600000 +49.755238 53.505257 0.000000 +49.750000 2.499981 0.600000 +49.750000 48.774693 0.600000 +49.755238 48.769455 0.000000 +49.755238 2.494745 0.000000 +9.744764 48.769455 0.000000 +9.750000 48.774693 0.600000 +9.750000 2.499981 0.600000 +9.744764 2.494745 0.000000 +40.250000 50.000000 0.600000 +41.750000 53.025307 0.600000 +32.971039 14.778961 0.600000 +48.250000 48.774693 0.600000 +49.750000 48.774693 0.600000 +48.250000 43.499962 0.600000 +48.233307 43.318001 0.600000 +48.179790 43.131874 0.600000 +48.087006 42.952766 0.600000 +47.957123 42.792877 0.600000 +47.797234 42.662994 0.600000 +47.618126 42.570210 0.600000 +47.431999 42.516693 0.600000 +47.250038 42.500000 0.600000 +49.750000 53.500019 0.600000 +49.750000 53.025307 0.600000 +49.741653 53.591000 0.600000 +49.714897 53.684063 0.600000 +49.668503 53.773617 0.600000 +49.603561 53.853561 0.600000 +49.523617 53.918503 0.600000 +49.434063 53.964897 0.600000 +49.341000 53.991653 0.600000 +49.250019 54.000000 0.600000 +9.750000 2.499981 0.600000 +9.750000 48.774693 0.600000 +11.250000 48.774693 0.600000 +11.250000 43.499962 0.600000 +11.266694 43.318001 0.600000 +11.320209 43.131874 0.600000 +11.412996 42.952766 0.600000 +11.542877 42.792877 0.600000 +11.702766 42.662994 0.600000 +11.881874 42.570210 0.600000 +12.068001 42.516693 0.600000 +35.750000 53.500000 0.600000 +34.750000 50.000000 0.600000 +24.750000 53.500000 0.600000 +23.750000 50.000000 0.600000 +29.250000 50.000000 0.600000 +30.250000 53.500000 0.600000 +17.750000 53.025307 0.600000 +9.750000 53.025307 0.600000 +9.750000 53.500019 0.600000 +9.758347 53.591000 0.600000 +9.785104 53.684063 0.600000 +9.831498 53.773617 0.600000 +9.896439 53.853561 0.600000 +9.976383 53.918503 0.600000 +10.065937 53.964897 0.600000 +10.159000 53.991653 0.600000 +42.749962 42.500000 0.600000 +12.249962 42.500000 0.600000 +35.750000 50.000000 0.600000 +32.242668 14.187288 0.600000 +49.250019 2.000000 0.600000 +31.426758 13.764595 0.600000 +30.578884 13.520812 0.600000 +29.750000 13.444764 0.600000 +28.921116 13.520812 0.600000 +28.073242 13.764595 0.600000 +27.257330 14.187288 0.600000 +26.528961 14.778961 0.600000 +25.937288 15.507330 0.600000 +25.514595 16.323242 0.600000 +33.562714 15.507330 0.600000 +16.750038 42.500000 0.600000 +42.568001 42.516693 0.600000 +42.381874 42.570210 0.600000 +16.931999 42.516693 0.600000 +33.985405 16.323242 0.600000 +25.270811 17.171116 0.600000 +17.118126 42.570210 0.600000 +42.202766 42.662994 0.600000 +10.249981 2.000000 0.600000 +10.159000 2.008347 0.600000 +10.065937 2.035104 0.600000 +9.976383 2.081498 0.600000 +9.896439 2.146439 0.600000 +9.831498 2.226383 0.600000 +9.785104 2.315937 0.600000 +9.758347 2.409000 0.600000 +25.194763 18.000000 0.600000 +25.270811 18.828884 0.600000 +25.514595 19.676758 0.600000 +25.937288 20.492670 0.600000 +26.528961 21.221039 0.600000 +27.257330 21.812712 0.600000 +28.073242 22.235405 0.600000 +17.297234 42.662994 0.600000 +28.921116 22.479189 0.600000 +17.457123 42.792877 0.600000 +29.750000 22.555237 0.600000 +17.587004 42.952766 0.600000 +30.578884 22.479189 0.600000 +49.341000 2.008347 0.600000 +49.434063 2.035104 0.600000 +49.523617 2.081498 0.600000 +49.603561 2.146439 0.600000 +49.668503 2.226383 0.600000 +49.714897 2.315937 0.600000 +49.741653 2.409000 0.600000 +49.750000 2.499981 0.600000 +34.229187 17.171116 0.600000 +34.305237 18.000000 0.600000 +34.229187 18.828884 0.600000 +33.985405 19.676758 0.600000 +33.562714 20.492670 0.600000 +32.971039 21.221039 0.600000 +32.242668 21.812712 0.600000 +31.426758 22.235405 0.600000 +42.042877 42.792877 0.600000 +41.912994 42.952766 0.600000 +41.820210 43.131874 0.600000 +17.679792 43.131874 0.600000 +41.766693 43.318001 0.600000 +17.733307 43.318001 0.600000 +41.750000 43.499962 0.600000 +30.250000 50.000000 0.600000 +24.750000 50.000000 0.600000 +19.250000 50.000000 0.600000 +17.750000 43.499962 0.600000 +19.250000 53.500000 0.600000 +10.249981 54.000000 0.600000 +40.250000 53.500000 0.600000 +34.750000 53.500000 0.600000 +29.250000 53.500000 0.600000 +23.750000 53.500000 0.600000 +10.249981 54.000000 0.600000 +10.244745 54.005238 0.000014 +49.255257 54.005238 0.000014 +49.250019 54.000000 0.600000 +9.750000 53.500019 0.600000 +9.750000 53.025307 0.600000 +9.744764 53.030544 0.000000 +9.744764 53.505257 0.000000 +10.249981 2.000000 0.600000 +49.250019 2.000000 0.600000 +49.255257 1.994764 0.000000 +10.244745 1.994764 0.000000 +40.205494 51.000000 5.700000 +40.198513 51.000000 6.500000 +40.250000 53.500000 0.600000 +40.250000 50.000000 0.600000 +40.205494 50.044506 5.700000 +40.198513 53.448513 6.500000 +19.301489 53.448513 6.500000 +19.301489 51.000000 6.500000 +19.250000 50.000000 0.600000 +19.250000 53.500000 0.600000 +19.294506 51.000000 5.700000 +19.294506 50.044506 5.700000 +35.794506 51.000000 5.700000 +35.794506 50.044506 5.700000 +35.750000 50.000000 0.600000 +35.750000 53.500000 0.600000 +35.801487 53.448513 6.500000 +35.801487 51.000000 6.500000 +34.705494 51.000000 5.700000 +34.698513 51.000000 6.500000 +34.750000 53.500000 0.600000 +34.750000 50.000000 0.600000 +34.705494 50.044506 5.700000 +34.698513 53.448513 6.500000 +30.294506 51.000000 5.700000 +30.294506 50.044506 5.700000 +30.250000 50.000000 0.600000 +30.250000 53.500000 0.600000 +30.301489 53.448513 6.500000 +30.301489 51.000000 6.500000 +29.205494 51.000000 5.700000 +29.198511 51.000000 6.500000 +29.250000 53.500000 0.600000 +29.250000 50.000000 0.600000 +29.205494 50.044506 5.700000 +29.198511 53.448513 6.500000 +24.801489 53.448513 6.500000 +24.801489 51.000000 6.500000 +24.750000 50.000000 0.600000 +24.750000 53.500000 0.600000 +24.794506 51.000000 5.700000 +24.794506 50.044506 5.700000 +23.705494 51.000000 5.700000 +23.698511 51.000000 6.500000 +23.750000 53.500000 0.600000 +23.750000 50.000000 0.600000 +23.705494 50.044506 5.700000 +23.698511 53.448513 6.500000 +9.269416 54.181965 0.016695 +9.269416 54.000000 0.000000 +8.750000 54.980900 0.827079 +8.750000 55.000000 1.022485 +9.269416 55.000000 1.000000 +9.269416 54.983307 0.818037 +8.750000 54.924435 0.639802 +9.269416 54.929787 0.631905 +8.750000 54.832500 0.466678 +9.269416 54.836994 0.452790 +8.750000 54.709076 0.314984 +8.750000 54.558437 0.190769 +9.269416 54.707108 0.292893 +8.750000 54.386253 0.097992 +9.269416 54.547211 0.163004 +8.750000 54.198982 0.039783 +9.269416 54.368095 0.070212 +8.750000 54.003105 0.019273 +49.255257 54.005238 0.000014 +50.230583 54.204910 0.021219 +50.230583 54.000000 0.000000 +49.327427 54.000000 0.000000 +9.269416 54.978783 0.795090 +9.269416 55.000000 1.000000 +50.230583 55.000000 1.000000 +50.230583 54.978783 0.795090 +9.269416 54.917744 0.602823 +9.269416 54.823971 0.433365 +50.230583 54.917744 0.602823 +50.230583 54.823971 0.433365 +9.269416 54.707108 0.292893 +10.172572 54.000000 0.000000 +9.269416 54.000000 0.000000 +10.244745 54.005238 0.000014 +50.230583 54.707108 0.292893 +9.269416 54.566635 0.176031 +50.230583 54.566635 0.176031 +9.269416 54.397179 0.082258 +50.230583 54.397179 0.082258 +9.269416 54.204910 0.021219 +50.750000 54.003105 0.019273 +50.230583 54.000000 0.000000 +50.230583 55.000000 1.000000 +50.750000 55.000000 1.022485 +50.230583 54.983307 0.818037 +50.230583 54.929787 0.631905 +50.750000 54.980293 0.826500 +50.230583 54.836994 0.452790 +50.750000 54.923168 0.638857 +50.230583 54.707108 0.292893 +50.750000 54.831600 0.466025 +50.750000 54.708569 0.314474 +50.230583 54.547211 0.163004 +50.750000 54.557831 0.189882 +50.230583 54.368095 0.070212 +50.750000 54.385372 0.096723 +50.230583 54.181965 0.016695 +50.750000 54.198444 0.039180 +3.307832 42.721466 7.498446 +3.284458 42.544456 7.500000 +4.103721 43.481846 7.200000 +4.294103 43.500000 7.200000 +4.283581 43.502541 7.491273 +4.105739 43.486603 7.491477 +3.920831 43.428062 7.200000 +3.924070 43.435688 7.491988 +3.751101 43.340431 7.200000 +3.748901 43.347603 7.492821 +3.601359 43.222519 7.200000 +3.477150 43.078228 7.200000 +3.591437 43.224316 7.493955 +3.382431 42.912872 7.200000 +3.461656 43.072159 7.495330 +3.320181 42.732285 7.200000 +3.366312 42.900837 7.496860 +3.293383 42.542286 7.200000 +3.308015 42.725845 8.000000 +3.284641 42.548820 8.000000 +4.283581 43.502541 7.491273 +4.283767 43.506981 8.000000 +4.099214 43.485401 7.491490 +4.105925 43.491039 8.000000 +3.905710 43.428406 7.492059 +3.924256 43.440121 8.000000 +3.734326 43.338203 7.492908 +3.749087 43.352032 8.000000 +3.591437 43.224316 7.493955 +3.591622 43.228729 8.000000 +3.471658 43.086327 7.495203 +3.374358 42.918877 7.496700 +3.461841 43.076561 8.000000 +3.309306 42.727936 7.498390 +3.366496 42.905228 8.000000 +3.284458 42.544456 7.500000 +56.206615 42.542286 7.200000 +56.215542 42.544456 7.500000 +55.216419 43.502541 7.491273 +55.205898 43.500000 7.200000 +55.394260 43.486603 7.491477 +55.575932 43.435688 7.491988 +55.396881 43.481300 7.200000 +55.751099 43.347603 7.492821 +55.580040 43.426975 7.200000 +55.908562 43.224316 7.493955 +55.749432 43.339680 7.200000 +55.899109 43.222073 7.200000 +56.038345 43.072159 7.495330 +56.023602 43.077759 7.200000 +56.133686 42.900837 7.496860 +56.118683 42.912090 7.200000 +56.192169 42.721466 7.498446 +56.180382 42.731731 7.200000 +56.215542 42.544456 7.500000 +56.215359 42.548820 8.000000 +55.216232 43.506981 8.000000 +55.216419 43.502541 7.491273 +55.394073 43.491039 8.000000 +55.575745 43.440121 8.000000 +55.400787 43.485401 7.491490 +55.750912 43.352032 8.000000 +55.594292 43.428406 7.492059 +55.908379 43.228729 8.000000 +55.765675 43.338203 7.492908 +56.038158 43.076561 8.000000 +55.908562 43.224316 7.493955 +56.028343 43.086327 7.495203 +56.133503 42.905228 8.000000 +56.125641 42.918877 7.496700 +56.191986 42.725845 8.000000 +56.190693 42.727936 7.498390 +48.257019 50.006981 8.000000 +48.250038 50.000000 7.200000 +49.233307 49.181999 7.200000 +49.250000 49.000038 7.200000 +49.256981 49.007019 8.000000 +49.179790 49.368126 7.200000 +49.240288 49.188980 8.000000 +49.087006 49.547234 7.200000 +49.186771 49.375107 8.000000 +49.026363 49.630318 7.200000 +49.093987 49.554214 8.000000 +48.957123 49.707123 7.200000 +49.033348 49.637299 8.000000 +48.964104 49.714104 8.000000 +48.880318 49.776363 7.200000 +48.887299 49.783348 8.000000 +48.797234 49.837006 7.200000 +48.804214 49.843987 8.000000 +48.618126 49.929790 7.200000 +48.625107 49.936771 8.000000 +48.431999 49.983307 7.200000 +48.438980 49.990288 8.000000 +50.249962 43.500000 7.200000 +50.256943 43.506981 8.000000 +49.273674 44.324982 8.000000 +49.256981 44.506943 8.000000 +49.250000 44.499962 7.200000 +49.327190 44.138855 8.000000 +49.266693 44.318001 7.200000 +49.419979 43.959747 8.000000 +49.320210 44.131874 7.200000 +49.480618 43.876663 8.000000 +49.412994 43.952766 7.200000 +49.549858 43.799858 8.000000 +49.473637 43.869682 7.200000 +49.542877 43.792877 7.200000 +49.626663 43.730618 8.000000 +49.619682 43.723637 7.200000 +49.709747 43.669979 8.000000 +49.702766 43.662994 7.200000 +49.888855 43.577190 8.000000 +49.881874 43.570210 7.200000 +50.074982 43.523674 8.000000 +50.068001 43.516693 7.200000 +10.243018 49.007019 8.000000 +10.250000 49.000038 7.200000 +11.068001 49.983307 7.200000 +11.249962 50.000000 7.200000 +11.242980 50.006981 8.000000 +10.881874 49.929790 7.200000 +11.061019 49.990288 8.000000 +10.702766 49.837006 7.200000 +10.874892 49.936771 8.000000 +10.619682 49.776363 7.200000 +10.695785 49.843987 8.000000 +10.542877 49.707123 7.200000 +10.612700 49.783348 8.000000 +10.535896 49.714104 8.000000 +10.473635 49.630318 7.200000 +10.466653 49.637299 8.000000 +10.412996 49.547234 7.200000 +10.406014 49.554214 8.000000 +10.320209 49.368126 7.200000 +10.313227 49.375107 8.000000 +10.266694 49.181999 7.200000 +10.259712 49.188980 8.000000 +7.943920 45.018959 0.064543 +7.750000 45.000000 0.093651 +8.750000 46.000000 8.000000 +8.750000 46.000000 0.002418 +8.728781 45.795090 8.000000 +8.730375 45.803238 0.002701 +8.667742 45.602821 8.000000 +8.673090 45.615417 0.004278 +8.573969 45.433365 8.000000 +8.580098 45.442612 0.007793 +8.457107 45.292892 8.000000 +8.316634 45.176029 8.000000 +8.455296 45.291088 0.014397 +8.147178 45.082256 8.000000 +8.303518 45.167259 0.025363 +7.954909 45.021217 8.000000 +8.130529 45.075230 0.041835 +7.750000 45.000000 8.000000 +10.250000 44.499962 7.200000 +10.243018 44.506943 8.000000 +9.425018 43.523674 8.000000 +9.243056 43.506981 8.000000 +9.250038 43.500000 7.200000 +9.611144 43.577190 8.000000 +9.431999 43.516693 7.200000 +9.790252 43.669979 8.000000 +9.618126 43.570210 7.200000 +9.873337 43.730618 8.000000 +9.797234 43.662994 7.200000 +9.950141 43.799858 8.000000 +9.880318 43.723637 7.200000 +9.957123 43.792877 7.200000 +10.019383 43.876663 8.000000 +10.026365 43.869682 7.200000 +10.080023 43.959747 8.000000 +10.087004 43.952766 7.200000 +10.172811 44.138855 8.000000 +10.179791 44.131874 7.200000 +10.226325 44.324982 8.000000 +10.233306 44.318001 7.200000 +9.744764 2.494745 0.000000 +9.750000 2.499981 0.600000 +10.159000 2.008347 0.600000 +10.249981 2.000000 0.600000 +10.244745 1.994764 0.000000 +10.065937 2.035104 0.600000 +10.153764 2.003111 0.000000 +9.976383 2.081498 0.600000 +10.060701 2.029868 0.000000 +9.934841 2.111817 0.600000 +9.971148 2.076262 0.000000 +9.896439 2.146439 0.600000 +9.929605 2.106581 0.000000 +9.891203 2.141203 0.000000 +9.861817 2.184841 0.600000 +9.856582 2.179605 0.000000 +9.831498 2.226383 0.600000 +9.826262 2.221147 0.000000 +9.785104 2.315937 0.600000 +9.779868 2.310701 0.000000 +9.758347 2.409000 0.600000 +9.753111 2.403764 0.000000 +49.255257 1.994764 0.000000 +49.250019 2.000000 0.600000 +49.741653 2.409000 0.600000 +49.750000 2.499981 0.600000 +49.755238 2.494745 0.000000 +49.746891 2.403764 0.000000 +49.714897 2.315937 0.600000 +49.720131 2.310701 0.000000 +49.668503 2.226383 0.600000 +49.673737 2.221147 0.000000 +49.638184 2.184841 0.600000 +49.643417 2.179605 0.000000 +49.603561 2.146439 0.600000 +49.608799 2.141203 0.000000 +49.565159 2.111817 0.600000 +49.570396 2.106581 0.000000 +49.523617 2.081498 0.600000 +49.528854 2.076262 0.000000 +49.434063 2.035104 0.600000 +49.439301 2.029868 0.000000 +49.341000 2.008347 0.600000 +49.346237 2.003111 0.000000 +49.748177 53.588985 0.000000 +49.755238 53.505257 0.000000 +49.341000 53.991653 0.600000 +49.250019 54.000000 0.600000 +49.255257 54.005238 0.000014 +49.327427 54.000000 0.000000 +49.434063 53.964897 0.600000 +49.409264 53.980927 0.000000 +49.523617 53.918503 0.600000 +49.490406 53.946487 0.000000 +49.565159 53.888184 0.600000 +49.566586 53.896481 0.000000 +49.603561 53.853561 0.600000 +49.638184 53.815159 0.600000 +49.633453 53.832287 0.000000 +49.668503 53.773617 0.600000 +49.714897 53.684063 0.600000 +49.687321 53.756855 0.000000 +49.741653 53.591000 0.600000 +49.725811 53.674252 0.000000 +49.750000 53.500019 0.600000 +10.172572 54.000000 0.000000 +10.244745 54.005238 0.000014 +9.758347 53.591000 0.600000 +9.750000 53.500019 0.600000 +9.744764 53.505257 0.000000 +9.751824 53.588985 0.000000 +9.785104 53.684063 0.600000 +9.774189 53.674252 0.000000 +9.831498 53.773617 0.600000 +9.812678 53.756855 0.000000 +9.861817 53.815159 0.600000 +9.896439 53.853561 0.600000 +9.866547 53.832287 0.000000 +9.934841 53.888184 0.600000 +9.976383 53.918503 0.600000 +9.933414 53.896481 0.000000 +10.065937 53.964897 0.600000 +10.009594 53.946487 0.000000 +10.159000 53.991653 0.600000 +10.090737 53.980927 0.000000 +10.249981 54.000000 0.600000 +41.790874 49.791862 5.283824 +48.209126 49.791862 5.283824 +48.209782 49.528019 5.208545 +41.790218 49.528019 5.208545 +48.209740 49.596947 5.213318 +41.790260 49.596947 5.213318 +48.209614 49.665207 5.227733 +41.790386 49.665207 5.227733 +48.209408 49.730793 5.251508 +41.790592 49.730793 5.251508 +17.705379 49.028038 5.712908 +11.294620 49.028038 5.712908 +11.290639 49.742264 5.256771 +11.290875 49.791862 5.283824 +17.709126 49.791862 5.283824 +17.709360 49.742264 5.256771 +11.290443 49.686607 5.234362 +17.709557 49.686607 5.234362 +11.290301 49.625366 5.218112 +17.709698 49.625366 5.218112 +11.290227 49.559456 5.209534 +17.709774 49.559456 5.209534 +11.290231 49.490276 5.209971 +17.709770 49.490276 5.209971 +11.290321 49.419685 5.220422 +17.709679 49.419685 5.220422 +11.290504 49.349865 5.241361 +17.709496 49.349865 5.241361 +11.290777 49.283134 5.272619 +17.709223 49.283134 5.272619 +11.291133 49.221725 5.313344 +17.708868 49.221725 5.313344 +11.291558 49.167519 5.362080 +17.708443 49.167519 5.362080 +11.292037 49.121868 5.416929 +17.707964 49.121868 5.416929 +11.292550 49.085503 5.475780 +17.707449 49.085503 5.475780 +11.293080 49.058540 5.536531 +17.706919 49.058540 5.536531 +11.293611 49.040554 5.597287 +17.706388 49.040554 5.597287 +11.294127 49.030739 5.656476 +17.705873 49.030739 5.656476 +47.250038 42.500000 0.600000 +47.233456 42.516582 2.500000 +48.216724 43.334583 2.500000 +48.233418 43.516544 2.500000 +48.250000 43.499962 0.600000 +48.163212 43.148457 2.500000 +48.233307 43.318001 0.600000 +48.070423 42.969349 2.500000 +48.179790 43.131874 0.600000 +48.009785 42.886265 2.500000 +48.087006 42.952766 0.600000 +47.940540 42.809460 2.500000 +48.026363 42.869682 0.600000 +47.957123 42.792877 0.600000 +47.863735 42.740215 2.500000 +47.880318 42.723637 0.600000 +47.780651 42.679577 2.500000 +47.797234 42.662994 0.600000 +47.601543 42.586788 2.500000 +47.618126 42.570210 0.600000 +47.415417 42.533276 2.500000 +47.431999 42.516693 0.600000 +41.750000 43.499962 0.600000 +41.766582 43.516544 2.500000 +42.584583 42.533276 2.500000 +42.766544 42.516582 2.500000 +42.749962 42.500000 0.600000 +42.398457 42.586788 2.500000 +42.568001 42.516693 0.600000 +42.219349 42.679577 2.500000 +42.381874 42.570210 0.600000 +42.136265 42.740215 2.500000 +42.202766 42.662994 0.600000 +42.059460 42.809460 2.500000 +42.119682 42.723637 0.600000 +42.042877 42.792877 0.600000 +41.990215 42.886265 2.500000 +41.973637 42.869682 0.600000 +41.929577 42.969349 2.500000 +41.912994 42.952766 0.600000 +41.836788 43.148457 2.500000 +41.820210 43.131874 0.600000 +41.783276 43.334583 2.500000 +41.766693 43.318001 0.600000 +16.750038 42.500000 0.600000 +16.733458 42.516582 2.500000 +17.716724 43.334583 2.500000 +17.733419 43.516544 2.500000 +17.750000 43.499962 0.600000 +17.663210 43.148457 2.500000 +17.733307 43.318001 0.600000 +17.570423 42.969349 2.500000 +17.679792 43.131874 0.600000 +17.509785 42.886265 2.500000 +17.587004 42.952766 0.600000 +17.440542 42.809460 2.500000 +17.526365 42.869682 0.600000 +17.457123 42.792877 0.600000 +17.363737 42.740215 2.500000 +17.380318 42.723637 0.600000 +17.280653 42.679577 2.500000 +17.297234 42.662994 0.600000 +17.101545 42.586788 2.500000 +17.118126 42.570210 0.600000 +16.915419 42.533276 2.500000 +16.931999 42.516693 0.600000 +11.250000 43.499962 0.600000 +11.266581 43.516544 2.500000 +12.084581 42.533276 2.500000 +12.266543 42.516582 2.500000 +12.249962 42.500000 0.600000 +11.898455 42.586788 2.500000 +12.068001 42.516693 0.600000 +11.719347 42.679577 2.500000 +11.881874 42.570210 0.600000 +11.636263 42.740215 2.500000 +11.702766 42.662994 0.600000 +11.559459 42.809460 2.500000 +11.619682 42.723637 0.600000 +11.542877 42.792877 0.600000 +11.490216 42.886265 2.500000 +11.473635 42.869682 0.600000 +11.429577 42.969349 2.500000 +11.412996 42.952766 0.600000 +11.336789 43.148457 2.500000 +11.320209 43.131874 0.600000 +11.283275 43.334583 2.500000 +11.266694 43.318001 0.600000 +49.051487 42.516693 2.500000 +49.233456 42.500000 2.500000 +48.209099 43.318035 7.200000 +48.192402 43.500000 7.200000 +48.233418 43.500000 2.500000 +48.262615 43.131905 7.200000 +48.250114 43.318035 2.500000 +48.355412 42.952789 7.200000 +48.303635 43.131905 2.500000 +48.416058 42.869701 7.200000 +48.396431 42.952789 2.500000 +48.485306 42.792892 7.200000 +48.457073 42.869701 2.500000 +48.562119 42.723648 7.200000 +48.526325 42.792892 2.500000 +48.645210 42.663006 7.200000 +48.603134 42.723648 2.500000 +48.824333 42.570213 7.200000 +48.686226 42.663006 2.500000 +49.010471 42.516693 7.200000 +48.865349 42.570213 2.500000 +49.192440 42.500000 7.200000 +10.307559 42.500000 7.200000 +10.266543 42.500000 2.500000 +11.266581 43.500000 2.500000 +11.307597 43.500000 7.200000 +11.249886 43.318035 2.500000 +11.290902 43.318035 7.200000 +11.196366 43.131905 2.500000 +11.237383 43.131905 7.200000 +11.103570 42.952789 2.500000 +11.144587 42.952789 7.200000 +11.042926 42.869701 2.500000 +11.083942 42.869701 7.200000 +10.973677 42.792892 2.500000 +11.014693 42.792892 7.200000 +10.896865 42.723648 2.500000 +10.937881 42.723648 7.200000 +10.813773 42.663006 2.500000 +10.854790 42.663006 7.200000 +10.634652 42.570213 2.500000 +10.675668 42.570213 7.200000 +10.448513 42.516693 2.500000 +10.489530 42.516693 7.200000 +50.750000 54.204910 7.978781 +8.750000 54.204910 7.978781 +8.750000 54.000000 8.000000 +50.750000 54.000000 8.000000 +50.750000 55.000000 7.000000 +8.750000 55.000000 7.000000 +50.750000 54.978783 7.204909 +8.750000 54.978783 7.204909 +50.750000 54.917744 7.397177 +8.750000 54.917744 7.397177 +50.750000 54.823971 7.566635 +50.750000 54.707108 7.707107 +8.750000 54.823971 7.566635 +8.750000 54.707108 7.707107 +50.750000 54.566635 7.823969 +50.750000 54.397179 7.917742 +8.750000 54.566635 7.823969 +8.750000 54.397179 7.917742 +34.242897 18.831421 2.197359 +34.319176 18.000000 2.197359 +24.959517 18.886490 2.500000 +24.878183 18.000000 2.500000 +25.180824 18.000000 2.197359 +25.257105 18.831421 2.197359 +25.220242 19.793289 2.500000 +25.501633 19.681890 2.197359 +25.672312 20.665905 2.500000 +25.925621 20.500298 2.197359 +26.305105 21.444895 2.500000 +26.519104 21.230896 2.197359 +27.084095 22.077688 2.500000 +27.249702 21.824379 2.197359 +27.956711 22.529758 2.500000 +28.068110 22.248367 2.197359 +28.863510 22.790483 2.500000 +29.750000 22.871817 2.500000 +28.918579 22.492895 2.197359 +29.750000 22.569176 2.197359 +30.636490 22.790483 2.500000 +30.581421 22.492895 2.197359 +31.543289 22.529758 2.500000 +31.431890 22.248367 2.197359 +32.415905 22.077688 2.500000 +32.250298 21.824379 2.197359 +33.194897 21.444895 2.500000 +32.980896 21.230896 2.197359 +33.827690 20.665905 2.500000 +33.574379 20.500298 2.197359 +34.279758 19.793289 2.500000 +34.540485 18.886490 2.500000 +33.998367 19.681890 2.197359 +34.621819 18.000000 2.500000 + + + + + + + + + + + +0.695302 0.128667 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.695302 0.128667 0.707107 +-0.707107 0.000000 0.707107 +-0.695302 0.128667 0.707107 +-0.695302 0.128667 0.707107 +-0.707107 0.000000 0.707107 +-0.657460 0.260282 0.707107 +-0.695302 0.128667 0.707107 +-0.695302 0.128667 0.707107 +-0.657460 0.260282 0.707107 +-0.657460 0.260282 0.707107 +-0.695302 0.128667 0.707107 +-0.657460 0.260282 0.707107 +-0.591845 0.386936 0.707107 +-0.657460 0.260282 0.707107 +-0.591845 0.386936 0.707107 +-0.591845 0.386936 0.707107 +-0.657460 0.260282 0.707107 +-0.500000 0.500000 0.707107 +-0.591845 0.386936 0.707107 +-0.591845 0.386936 0.707107 +-0.500000 0.500000 0.707107 +-0.500000 0.500000 0.707107 +-0.591845 0.386936 0.707107 +-0.386936 0.591845 0.707107 +-0.500000 0.500000 0.707107 +-0.500000 0.500000 0.707107 +-0.386936 0.591845 0.707107 +-0.386936 0.591845 0.707107 +-0.500000 0.500000 0.707107 +-0.260282 0.657460 0.707107 +-0.386936 0.591845 0.707107 +-0.386936 0.591845 0.707107 +-0.260282 0.657460 0.707107 +-0.260282 0.657460 0.707107 +-0.386936 0.591845 0.707107 +-0.128667 0.695302 0.707107 +-0.260282 0.657460 0.707107 +-0.260282 0.657460 0.707107 +-0.128667 0.695302 0.707107 +-0.128667 0.695302 0.707107 +-0.260282 0.657460 0.707107 +0.000000 0.707107 0.707107 +-0.128667 0.695302 0.707107 +-0.128667 0.695302 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +-0.128667 0.695302 0.707107 +0.128667 0.695302 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.128667 0.695302 0.707107 +0.128667 0.695302 0.707107 +0.000000 0.707107 0.707107 +0.260282 0.657460 0.707107 +0.128667 0.695302 0.707107 +0.128667 0.695302 0.707107 +0.260282 0.657460 0.707107 +0.260282 0.657460 0.707107 +0.128667 0.695302 0.707107 +0.386936 0.591845 0.707107 +0.260282 0.657460 0.707107 +0.260282 0.657460 0.707107 +0.386936 0.591845 0.707107 +0.386936 0.591845 0.707107 +0.260282 0.657460 0.707107 +0.500000 0.500000 0.707107 +0.386936 0.591845 0.707107 +0.386936 0.591845 0.707107 +0.500000 0.500000 0.707107 +0.500000 0.500000 0.707107 +0.386936 0.591845 0.707107 +0.591845 0.386936 0.707107 +0.500000 0.500000 0.707107 +0.500000 0.500000 0.707107 +0.591845 0.386936 0.707107 +0.591845 0.386936 0.707107 +0.500000 0.500000 0.707107 +0.657460 0.260282 0.707107 +0.591845 0.386936 0.707107 +0.591845 0.386936 0.707107 +0.657460 0.260282 0.707107 +0.657460 0.260282 0.707107 +0.591845 0.386936 0.707107 +0.695302 0.128667 0.707107 +0.657460 0.260282 0.707107 +0.657460 0.260282 0.707107 +0.695302 0.128667 0.707107 +0.695302 0.128667 0.707107 +0.657460 0.260282 0.707107 +0.707107 0.000000 0.707107 +0.695302 0.128667 0.707107 +0.695302 0.128667 0.707107 +0.000000 -0.984705 -0.174228 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.182814 -0.983148 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -0.182814 -0.983148 +0.000000 -0.182814 -0.983148 +0.000000 0.000000 -1.000000 +0.000000 -0.369871 -0.929083 +0.000000 -0.182814 -0.983148 +0.000000 -0.182814 -0.983148 +0.000000 -0.369871 -0.929083 +0.000000 -0.369871 -0.929083 +0.000000 -0.182814 -0.983148 +0.000000 -0.549800 -0.835296 +0.000000 -0.369871 -0.929083 +0.000000 -0.369871 -0.929083 +0.000000 -0.549800 -0.835296 +0.000000 -0.549800 -0.835296 +0.000000 -0.369871 -0.929083 +0.000000 -0.633186 -0.774000 +0.000000 -0.549800 -0.835296 +0.000000 -0.549800 -0.835296 +0.000000 -0.633186 -0.774000 +0.000000 -0.633186 -0.774000 +0.000000 -0.549800 -0.835296 +0.000000 -0.710185 -0.704015 +0.000000 -0.633186 -0.774000 +0.000000 -0.633186 -0.774000 +0.000000 -0.710185 -0.704015 +0.000000 -0.710185 -0.704015 +0.000000 -0.633186 -0.774000 +0.000000 -0.779496 -0.626408 +0.000000 -0.710185 -0.704015 +0.000000 -0.710185 -0.704015 +0.000000 -0.779496 -0.626408 +0.000000 -0.779496 -0.626408 +0.000000 -0.710185 -0.704015 +0.000000 -0.840062 -0.542490 +0.000000 -0.779496 -0.626408 +0.000000 -0.779496 -0.626408 +0.000000 -0.840062 -0.542490 +0.000000 -0.840062 -0.542490 +0.000000 -0.779496 -0.626408 +0.000000 -0.932276 -0.361749 +0.000000 -0.840062 -0.542490 +0.000000 -0.840062 -0.542490 +0.000000 -0.932276 -0.361749 +0.000000 -0.932276 -0.361749 +0.000000 -0.840062 -0.542490 +0.000000 -0.984705 -0.174228 +0.000000 -0.932276 -0.361749 +0.000000 -0.932276 -0.361749 +0.000000 -0.984705 -0.174228 +0.000000 -0.984705 -0.174228 +0.000000 -0.932276 -0.361749 +0.000000 -0.999962 0.008727 +0.000000 -0.984705 -0.174228 +0.000000 -0.984705 -0.174228 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.929753 0.368081 0.008727 +0.983268 0.181956 0.008727 +0.983268 0.181956 0.008727 +0.999962 0.000000 0.008727 +0.983268 0.181956 0.008727 +0.999962 0.000000 0.008727 +0.983268 0.181956 0.008727 +0.983268 0.181956 0.008727 +0.999962 0.000000 0.008727 +-0.983268 0.181956 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.983268 0.181956 0.008727 +-0.983268 0.181956 0.008727 +-0.999962 0.000000 0.008727 +-0.929753 0.368081 0.008727 +-0.983268 0.181956 0.008727 +-0.983268 0.181956 0.008727 +-0.929753 0.368081 0.008727 +-0.929753 0.368081 0.008727 +-0.983268 0.181956 0.008727 +-0.836964 0.547189 0.008727 +-0.929753 0.368081 0.008727 +-0.929753 0.368081 0.008727 +-0.836964 0.547189 0.008727 +-0.836964 0.547189 0.008727 +-0.929753 0.368081 0.008727 +-0.836964 0.547189 0.008727 +-0.707080 0.707080 0.008727 +-0.836964 0.547189 0.008727 +-0.707080 0.707080 0.008727 +-0.707080 0.707080 0.008727 +-0.836964 0.547189 0.008727 +-0.707080 0.707080 0.008727 +-0.547189 0.836964 0.008727 +-0.707080 0.707080 0.008727 +-0.547189 0.836964 0.008727 +-0.547189 0.836964 0.008727 +-0.707080 0.707080 0.008727 +-0.547189 0.836964 0.008727 +-0.368081 0.929753 0.008727 +-0.547189 0.836964 0.008727 +-0.368081 0.929753 0.008727 +-0.368081 0.929753 0.008727 +-0.547189 0.836964 0.008727 +-0.368081 0.929753 0.008727 +-0.181956 0.983268 0.008727 +-0.368081 0.929753 0.008727 +-0.181956 0.983268 0.008727 +-0.181956 0.983268 0.008727 +-0.368081 0.929753 0.008727 +0.000000 0.999962 0.008727 +-0.181956 0.983268 0.008727 +-0.181956 0.983268 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +-0.181956 0.983268 0.008727 +0.181956 0.983268 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.181956 0.983268 0.008727 +0.181956 0.983268 0.008727 +0.000000 0.999962 0.008727 +0.181956 0.983268 0.008727 +0.368081 0.929753 0.008727 +0.181956 0.983268 0.008727 +0.368081 0.929753 0.008727 +0.368081 0.929753 0.008727 +0.181956 0.983268 0.008727 +0.368081 0.929753 0.008727 +0.547189 0.836964 0.008727 +0.368081 0.929753 0.008727 +0.547189 0.836964 0.008727 +0.547189 0.836964 0.008727 +0.368081 0.929753 0.008727 +0.547189 0.836964 0.008727 +0.707080 0.707080 0.008727 +0.547189 0.836964 0.008727 +0.707080 0.707080 0.008727 +0.707080 0.707080 0.008727 +0.547189 0.836964 0.008727 +0.836964 0.547189 0.008727 +0.707080 0.707080 0.008727 +0.707080 0.707080 0.008727 +0.836964 0.547189 0.008727 +0.836964 0.547189 0.008727 +0.707080 0.707080 0.008727 +0.929753 0.368081 0.008727 +0.836964 0.547189 0.008727 +0.836964 0.547189 0.008727 +0.929753 0.368081 0.008727 +0.929753 0.368081 0.008727 +0.836964 0.547189 0.008727 +0.983268 0.181956 0.008727 +0.929753 0.368081 0.008727 +0.929753 0.368081 0.008727 +0.983268 0.181956 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.983268 0.181956 0.008727 +-0.999962 0.000000 0.008727 +-0.983268 0.181956 0.008727 +-0.983268 0.181956 0.008727 +-0.999962 0.000000 0.008727 +-0.929753 0.368081 0.008727 +-0.983268 0.181956 0.008727 +-0.983268 0.181956 0.008727 +-0.929753 0.368081 0.008727 +-0.929753 0.368081 0.008727 +-0.983268 0.181956 0.008727 +-0.836964 0.547189 0.008727 +-0.929753 0.368081 0.008727 +-0.929753 0.368081 0.008727 +-0.836964 0.547189 0.008727 +-0.836964 0.547189 0.008727 +-0.929753 0.368081 0.008727 +-0.707080 0.707080 0.008727 +-0.836964 0.547189 0.008727 +-0.836964 0.547189 0.008727 +-0.707080 0.707080 0.008727 +-0.707080 0.707080 0.008727 +-0.836964 0.547189 0.008727 +-0.547189 0.836964 0.008727 +-0.707080 0.707080 0.008727 +-0.707080 0.707080 0.008727 +-0.547189 0.836964 0.008727 +-0.547189 0.836964 0.008727 +-0.707080 0.707080 0.008727 +-0.547189 0.836964 0.008727 +-0.368081 0.929753 0.008727 +-0.547189 0.836964 0.008727 +-0.368081 0.929753 0.008727 +-0.368081 0.929753 0.008727 +-0.547189 0.836964 0.008727 +-0.368081 0.929753 0.008727 +-0.181956 0.983268 0.008727 +-0.368081 0.929753 0.008727 +-0.181956 0.983268 0.008727 +-0.181956 0.983268 0.008727 +-0.368081 0.929753 0.008727 +-0.181956 0.983268 0.008727 +0.000000 0.999962 0.008727 +-0.181956 0.983268 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +-0.181956 0.983268 0.008727 +0.181956 0.983268 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.181956 0.983268 0.008727 +0.181956 0.983268 0.008727 +0.000000 0.999962 0.008727 +0.181956 0.983268 0.008727 +0.368081 0.929753 0.008727 +0.181956 0.983268 0.008727 +0.368081 0.929753 0.008727 +0.368081 0.929753 0.008727 +0.181956 0.983268 0.008727 +0.368081 0.929753 0.008727 +0.547189 0.836964 0.008727 +0.368081 0.929753 0.008727 +0.547189 0.836964 0.008727 +0.547189 0.836964 0.008727 +0.368081 0.929753 0.008727 +0.547189 0.836964 0.008727 +0.707080 0.707080 0.008727 +0.547189 0.836964 0.008727 +0.707080 0.707080 0.008727 +0.707080 0.707080 0.008727 +0.547189 0.836964 0.008727 +0.836964 0.547189 0.008727 +0.707080 0.707080 0.008727 +0.707080 0.707080 0.008727 +0.836964 0.547189 0.008727 +0.836964 0.547189 0.008727 +0.707080 0.707080 0.008727 +0.929753 0.368081 0.008727 +0.836964 0.547189 0.008727 +0.836964 0.547189 0.008727 +0.929753 0.368081 0.008727 +0.929753 0.368081 0.008727 +0.836964 0.547189 0.008727 +0.983268 0.181956 0.008727 +0.929753 0.368081 0.008727 +0.929753 0.368081 0.008727 +0.983268 0.181956 0.008727 +0.983268 0.181956 0.008727 +0.929753 0.368081 0.008727 +0.999962 0.000000 0.008727 +0.983268 0.181956 0.008727 +0.983268 0.181956 0.008727 +0.929753 0.368081 0.008727 +0.983268 0.181956 0.008727 +0.983268 0.181956 0.008727 +0.999962 0.000000 0.008727 +0.983268 0.181956 0.008727 +0.999962 0.000000 0.008727 +0.983268 0.181956 0.008727 +0.983268 0.181956 0.008727 +0.999962 0.000000 0.008727 +-0.983268 0.181956 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.983268 0.181956 0.008727 +-0.983268 0.181956 0.008727 +-0.999962 0.000000 0.008727 +-0.929753 0.368081 0.008727 +-0.983268 0.181956 0.008727 +-0.983268 0.181956 0.008727 +-0.929753 0.368081 0.008727 +-0.929753 0.368081 0.008727 +-0.983268 0.181956 0.008727 +-0.836964 0.547189 0.008727 +-0.929753 0.368081 0.008727 +-0.929753 0.368081 0.008727 +-0.836964 0.547189 0.008727 +-0.836964 0.547189 0.008727 +-0.929753 0.368081 0.008727 +-0.707080 0.707080 0.008727 +-0.836964 0.547189 0.008727 +-0.836964 0.547189 0.008727 +-0.707080 0.707080 0.008727 +-0.707080 0.707080 0.008727 +-0.836964 0.547189 0.008727 +-0.547189 0.836964 0.008727 +-0.707080 0.707080 0.008727 +-0.707080 0.707080 0.008727 +-0.547189 0.836964 0.008727 +-0.547189 0.836964 0.008727 +-0.707080 0.707080 0.008727 +-0.368081 0.929753 0.008727 +-0.547189 0.836964 0.008727 +-0.547189 0.836964 0.008727 +-0.368081 0.929753 0.008727 +-0.368081 0.929753 0.008727 +-0.547189 0.836964 0.008727 +-0.181956 0.983268 0.008727 +-0.368081 0.929753 0.008727 +-0.368081 0.929753 0.008727 +-0.181956 0.983268 0.008727 +-0.181956 0.983268 0.008727 +-0.368081 0.929753 0.008727 +0.000000 0.999962 0.008727 +-0.181956 0.983268 0.008727 +-0.181956 0.983268 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +-0.181956 0.983268 0.008727 +0.181956 0.983268 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.181956 0.983268 0.008727 +0.181956 0.983268 0.008727 +0.000000 0.999962 0.008727 +0.368081 0.929753 0.008727 +0.181956 0.983268 0.008727 +0.181956 0.983268 0.008727 +0.368081 0.929753 0.008727 +0.368081 0.929753 0.008727 +0.181956 0.983268 0.008727 +0.547189 0.836964 0.008727 +0.368081 0.929753 0.008727 +0.368081 0.929753 0.008727 +0.547189 0.836964 0.008727 +0.547189 0.836964 0.008727 +0.368081 0.929753 0.008727 +0.707080 0.707080 0.008727 +0.547189 0.836964 0.008727 +0.547189 0.836964 0.008727 +0.707080 0.707080 0.008727 +0.707080 0.707080 0.008727 +0.547189 0.836964 0.008727 +0.836964 0.547189 0.008727 +0.707080 0.707080 0.008727 +0.707080 0.707080 0.008727 +0.836964 0.547189 0.008727 +0.836964 0.547189 0.008727 +0.707080 0.707080 0.008727 +0.929753 0.368081 0.008727 +0.836964 0.547189 0.008727 +0.836964 0.547189 0.008727 +0.929753 0.368081 0.008727 +0.929753 0.368081 0.008727 +0.836964 0.547189 0.008727 +0.983268 0.181956 0.008727 +0.929753 0.368081 0.008727 +0.929753 0.368081 0.008727 +0.929753 0.368081 0.008727 +0.983268 0.181956 0.008727 +0.983268 0.181956 0.008727 +0.999962 0.000000 0.008727 +0.983268 0.181956 0.008727 +0.999962 0.000000 0.008727 +0.983268 0.181956 0.008727 +0.983268 0.181956 0.008727 +0.999962 0.000000 0.008727 +-0.983268 0.181956 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.983268 0.181956 0.008727 +-0.983268 0.181956 0.008727 +-0.999962 0.000000 0.008727 +-0.929753 0.368081 0.008727 +-0.983268 0.181956 0.008727 +-0.983268 0.181956 0.008727 +-0.929753 0.368081 0.008727 +-0.929753 0.368081 0.008727 +-0.983268 0.181956 0.008727 +-0.836964 0.547189 0.008727 +-0.929753 0.368081 0.008727 +-0.929753 0.368081 0.008727 +-0.836964 0.547189 0.008727 +-0.836964 0.547189 0.008727 +-0.929753 0.368081 0.008727 +-0.707080 0.707080 0.008727 +-0.836964 0.547189 0.008727 +-0.836964 0.547189 0.008727 +-0.707080 0.707080 0.008727 +-0.707080 0.707080 0.008727 +-0.836964 0.547189 0.008727 +-0.547189 0.836964 0.008727 +-0.707080 0.707080 0.008727 +-0.707080 0.707080 0.008727 +-0.547189 0.836964 0.008727 +-0.547189 0.836964 0.008727 +-0.707080 0.707080 0.008727 +-0.368081 0.929753 0.008727 +-0.547189 0.836964 0.008727 +-0.547189 0.836964 0.008727 +-0.368081 0.929753 0.008727 +-0.368081 0.929753 0.008727 +-0.547189 0.836964 0.008727 +-0.368081 0.929753 0.008727 +-0.181956 0.983268 0.008727 +-0.368081 0.929753 0.008727 +-0.181956 0.983268 0.008727 +-0.181956 0.983268 0.008727 +-0.368081 0.929753 0.008727 +0.000000 0.999962 0.008727 +-0.181956 0.983268 0.008727 +-0.181956 0.983268 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +-0.181956 0.983268 0.008727 +0.181956 0.983268 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.181956 0.983268 0.008727 +0.181956 0.983268 0.008727 +0.000000 0.999962 0.008727 +0.368081 0.929753 0.008727 +0.181956 0.983268 0.008727 +0.181956 0.983268 0.008727 +0.368081 0.929753 0.008727 +0.368081 0.929753 0.008727 +0.181956 0.983268 0.008727 +0.368081 0.929753 0.008727 +0.547189 0.836964 0.008727 +0.368081 0.929753 0.008727 +0.547189 0.836964 0.008727 +0.547189 0.836964 0.008727 +0.368081 0.929753 0.008727 +0.707080 0.707080 0.008727 +0.547189 0.836964 0.008727 +0.547189 0.836964 0.008727 +0.707080 0.707080 0.008727 +0.707080 0.707080 0.008727 +0.547189 0.836964 0.008727 +0.836964 0.547189 0.008727 +0.707080 0.707080 0.008727 +0.707080 0.707080 0.008727 +0.836964 0.547189 0.008727 +0.836964 0.547189 0.008727 +0.707080 0.707080 0.008727 +0.929753 0.368081 0.008727 +0.836964 0.547189 0.008727 +0.836964 0.547189 0.008727 +0.929753 0.368081 0.008727 +0.929753 0.368081 0.008727 +0.836964 0.547189 0.008727 +0.983268 0.181956 0.008727 +0.929753 0.368081 0.008727 +0.929753 0.368081 0.008727 +0.000000 -0.983305 -0.181963 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -0.204909 -0.978781 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -0.204909 -0.978781 +0.000000 -0.181963 -0.983305 +0.000000 0.000000 -1.000000 +0.000000 -0.204909 -0.978781 +0.000000 -0.368095 -0.929788 +0.000000 -0.181963 -0.983305 +0.000000 -0.397177 -0.917742 +0.000000 -0.368095 -0.929788 +0.000000 -0.204909 -0.978781 +0.000000 -0.397177 -0.917742 +0.000000 -0.547210 -0.836995 +0.000000 -0.368095 -0.929788 +0.000000 -0.566635 -0.823969 +0.000000 -0.547210 -0.836995 +0.000000 -0.397177 -0.917742 +0.000000 -0.566635 -0.823969 +0.000000 -0.630298 -0.776353 +0.000000 -0.547210 -0.836995 +0.000000 -0.707107 -0.707107 +0.000000 -0.630298 -0.776353 +0.000000 -0.566635 -0.823969 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.630298 -0.776353 +0.000000 -0.823969 -0.566635 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.823969 -0.566635 +0.000000 -0.776353 -0.630298 +0.000000 -0.707107 -0.707107 +0.000000 -0.823969 -0.566635 +0.000000 -0.836995 -0.547210 +0.000000 -0.776353 -0.630298 +0.000000 -0.917742 -0.397177 +0.000000 -0.836995 -0.547210 +0.000000 -0.823969 -0.566635 +0.000000 -0.917742 -0.397177 +0.000000 -0.929788 -0.368095 +0.000000 -0.836995 -0.547210 +0.000000 -0.978781 -0.204909 +0.000000 -0.929788 -0.368095 +0.000000 -0.917742 -0.397177 +0.000000 -0.978781 -0.204909 +0.000000 -0.983305 -0.181963 +0.000000 -0.929788 -0.368095 +0.000000 -1.000000 0.000000 +0.000000 -0.983305 -0.181963 +0.000000 -0.978781 -0.204909 +0.983268 0.181956 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.983268 0.181956 0.008727 +-0.999962 0.000000 0.008727 +-0.983268 0.181956 0.008727 +-0.983268 0.181956 0.008727 +-0.999962 0.000000 0.008727 +-0.983268 0.181956 0.008727 +-0.929753 0.368081 0.008727 +-0.983268 0.181956 0.008727 +-0.929753 0.368081 0.008727 +-0.929753 0.368081 0.008727 +-0.983268 0.181956 0.008727 +-0.836964 0.547189 0.008727 +-0.929753 0.368081 0.008727 +-0.929753 0.368081 0.008727 +-0.836964 0.547189 0.008727 +-0.836964 0.547189 0.008727 +-0.929753 0.368081 0.008727 +-0.707080 0.707080 0.008727 +-0.836964 0.547189 0.008727 +-0.836964 0.547189 0.008727 +-0.707080 0.707080 0.008727 +-0.707080 0.707080 0.008727 +-0.836964 0.547189 0.008727 +-0.547189 0.836964 0.008727 +-0.707080 0.707080 0.008727 +-0.707080 0.707080 0.008727 +-0.547189 0.836964 0.008727 +-0.547189 0.836964 0.008727 +-0.707080 0.707080 0.008727 +-0.547189 0.836964 0.008727 +-0.368081 0.929753 0.008727 +-0.547189 0.836964 0.008727 +-0.368081 0.929753 0.008727 +-0.368081 0.929753 0.008727 +-0.547189 0.836964 0.008727 +-0.181956 0.983268 0.008727 +-0.368081 0.929753 0.008727 +-0.368081 0.929753 0.008727 +-0.181956 0.983268 0.008727 +-0.181956 0.983268 0.008727 +-0.368081 0.929753 0.008727 +0.000000 0.999962 0.008727 +-0.181956 0.983268 0.008727 +-0.181956 0.983268 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +-0.181956 0.983268 0.008727 +0.181956 0.983268 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.181956 0.983268 0.008727 +0.181956 0.983268 0.008727 +0.000000 0.999962 0.008727 +0.368081 0.929753 0.008727 +0.181956 0.983268 0.008727 +0.181956 0.983268 0.008727 +0.368081 0.929753 0.008727 +0.368081 0.929753 0.008727 +0.181956 0.983268 0.008727 +0.547189 0.836964 0.008727 +0.368081 0.929753 0.008727 +0.368081 0.929753 0.008727 +0.547189 0.836964 0.008727 +0.547189 0.836964 0.008727 +0.368081 0.929753 0.008727 +0.707080 0.707080 0.008727 +0.547189 0.836964 0.008727 +0.547189 0.836964 0.008727 +0.707080 0.707080 0.008727 +0.707080 0.707080 0.008727 +0.547189 0.836964 0.008727 +0.836964 0.547189 0.008727 +0.707080 0.707080 0.008727 +0.707080 0.707080 0.008727 +0.836964 0.547189 0.008727 +0.836964 0.547189 0.008727 +0.707080 0.707080 0.008727 +0.836964 0.547189 0.008727 +0.929753 0.368081 0.008727 +0.836964 0.547189 0.008727 +0.929753 0.368081 0.008727 +0.929753 0.368081 0.008727 +0.836964 0.547189 0.008727 +0.983268 0.181956 0.008727 +0.929753 0.368081 0.008727 +0.929753 0.368081 0.008727 +0.983268 0.181956 0.008727 +0.983268 0.181956 0.008727 +0.929753 0.368081 0.008727 +0.999962 0.000000 0.008727 +0.983268 0.181956 0.008727 +0.983268 0.181956 0.008727 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +0.181956 -0.983268 0.008727 +0.368081 -0.929753 0.008727 +0.368081 -0.929753 0.008727 +0.983268 -0.181956 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.983268 -0.181956 0.008727 +0.983268 -0.181956 0.008727 +0.999962 0.000000 0.008727 +0.983268 -0.181956 0.008727 +0.929753 -0.368081 0.008727 +0.983268 -0.181956 0.008727 +0.929753 -0.368081 0.008727 +0.929753 -0.368081 0.008727 +0.983268 -0.181956 0.008727 +0.836964 -0.547189 0.008727 +0.929753 -0.368081 0.008727 +0.929753 -0.368081 0.008727 +0.836964 -0.547189 0.008727 +0.836964 -0.547189 0.008727 +0.929753 -0.368081 0.008727 +0.707080 -0.707080 0.008727 +0.836964 -0.547189 0.008727 +0.836964 -0.547189 0.008727 +0.707080 -0.707080 0.008727 +0.707080 -0.707080 0.008727 +0.836964 -0.547189 0.008727 +0.547189 -0.836964 0.008727 +0.707080 -0.707080 0.008727 +0.707080 -0.707080 0.008727 +0.547189 -0.836964 0.008727 +0.547189 -0.836964 0.008727 +0.707080 -0.707080 0.008727 +0.547189 -0.836964 0.008727 +0.368081 -0.929753 0.008727 +0.547189 -0.836964 0.008727 +0.368081 -0.929753 0.008727 +0.368081 -0.929753 0.008727 +0.547189 -0.836964 0.008727 +-0.983268 -0.181956 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.983268 -0.181956 0.008727 +-0.983268 -0.181956 0.008727 +-0.999962 0.000000 0.008727 +-0.983268 -0.181956 0.008727 +-0.929753 -0.368081 0.008727 +-0.983268 -0.181956 0.008727 +-0.929753 -0.368081 0.008727 +-0.929753 -0.368081 0.008727 +-0.983268 -0.181956 0.008727 +-0.836964 -0.547189 0.008727 +-0.929753 -0.368081 0.008727 +-0.929753 -0.368081 0.008727 +-0.836964 -0.547189 0.008727 +-0.836964 -0.547189 0.008727 +-0.929753 -0.368081 0.008727 +-0.707080 -0.707080 0.008727 +-0.836964 -0.547189 0.008727 +-0.836964 -0.547189 0.008727 +-0.707080 -0.707080 0.008727 +-0.707080 -0.707080 0.008727 +-0.836964 -0.547189 0.008727 +-0.547189 -0.836964 0.008727 +-0.707080 -0.707080 0.008727 +-0.707080 -0.707080 0.008727 +-0.547189 -0.836964 0.008727 +-0.547189 -0.836964 0.008727 +-0.707080 -0.707080 0.008727 +-0.368081 -0.929753 0.008727 +-0.547189 -0.836964 0.008727 +-0.547189 -0.836964 0.008727 +-0.368081 -0.929753 0.008727 +-0.368081 -0.929753 0.008727 +-0.547189 -0.836964 0.008727 +-0.181956 -0.983268 0.008727 +-0.368081 -0.929753 0.008727 +-0.368081 -0.929753 0.008727 +-0.181956 -0.983268 0.008727 +-0.181956 -0.983268 0.008727 +-0.368081 -0.929753 0.008727 +0.000000 -0.999962 0.008727 +-0.181956 -0.983268 0.008727 +-0.181956 -0.983268 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +-0.181956 -0.983268 0.008727 +0.181956 -0.983268 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.181956 -0.983268 0.008727 +0.181956 -0.983268 0.008727 +0.000000 -0.999962 0.008727 +0.368081 -0.929753 0.008727 +0.181956 -0.983268 0.008727 +0.181956 -0.983268 0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.985341 0.041298 -0.165523 +-0.999123 0.041876 0.000000 +-0.999123 0.041876 0.000000 +0.000000 0.000000 -1.000000 +-0.026256 0.001100 -0.999655 +-0.042810 0.001794 -0.999082 +0.000000 0.000000 -1.000000 +-0.026256 0.001100 -0.999655 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.027879 0.001168 -0.999611 +-0.026256 0.001100 -0.999655 +0.000000 0.000000 -1.000000 +-0.034925 0.001464 -0.999389 +-0.027879 0.001168 -0.999611 +0.000000 0.000000 -1.000000 +-0.047154 0.001976 -0.998886 +-0.034925 0.001464 -0.999389 +0.000000 0.000000 -1.000000 +-0.064046 0.002684 -0.997943 +-0.047154 0.001976 -0.998886 +-0.116889 0.004899 -0.993133 +-0.064046 0.002684 -0.997943 +0.000000 0.000000 -1.000000 +-0.116889 0.004899 -0.993133 +-0.084950 0.003560 -0.996379 +-0.064046 0.002684 -0.997943 +-0.116889 0.004899 -0.993133 +-0.109070 0.004571 -0.994024 +-0.084950 0.003560 -0.996379 +-0.116889 0.004899 -0.993133 +-0.135345 0.005673 -0.990782 +-0.109070 0.004571 -0.994024 +-0.234682 0.009836 -0.972022 +-0.135345 0.005673 -0.990782 +-0.116889 0.004899 -0.993133 +-0.234682 0.009836 -0.972022 +-0.162886 0.006827 -0.986621 +-0.135345 0.005673 -0.990782 +-0.234682 0.009836 -0.972022 +-0.323805 0.013571 -0.946027 +-0.162886 0.006827 -0.986621 +-0.350780 0.014702 -0.936343 +-0.323805 0.013571 -0.946027 +-0.234682 0.009836 -0.972022 +-0.350780 0.014702 -0.936343 +-0.482765 0.020234 -0.875516 +-0.323805 0.013571 -0.946027 +-0.462504 0.019385 -0.886405 +-0.482765 0.020234 -0.875516 +-0.350780 0.014702 -0.936343 +-0.567292 0.023777 -0.823174 +-0.482765 0.020234 -0.875516 +-0.462504 0.019385 -0.886405 +-0.567292 0.023777 -0.823174 +-0.631560 0.026470 -0.774875 +-0.482765 0.020234 -0.875516 +-0.662888 0.027783 -0.748203 +-0.631560 0.026470 -0.774875 +-0.567292 0.023777 -0.823174 +-0.662888 0.027783 -0.748203 +-0.761902 0.031933 -0.646905 +-0.631560 0.026470 -0.774875 +-0.747508 0.031330 -0.663514 +-0.761902 0.031933 -0.646905 +-0.662888 0.027783 -0.748203 +-0.819932 0.034365 -0.571429 +-0.761902 0.031933 -0.646905 +-0.747508 0.031330 -0.663514 +-0.819932 0.034365 -0.571429 +-0.866800 0.036330 -0.497330 +-0.761902 0.031933 -0.646905 +-0.906321 0.037986 -0.420879 +-0.866800 0.036330 -0.497330 +-0.819932 0.034365 -0.571429 +-0.906321 0.037986 -0.420879 +-0.941750 0.039471 -0.333990 +-0.866800 0.036330 -0.497330 +-0.963392 0.040378 -0.265040 +-0.941750 0.039471 -0.333990 +-0.906321 0.037986 -0.420879 +-0.963392 0.040378 -0.265040 +-0.985341 0.041298 -0.165523 +-0.941750 0.039471 -0.333990 +-0.991899 0.041573 -0.120034 +-0.985341 0.041298 -0.165523 +-0.963392 0.040378 -0.265040 +-0.999123 0.041876 0.000000 +-0.985341 0.041298 -0.165523 +-0.991899 0.041573 -0.120034 +-0.068277 0.002862 -0.997662 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.068277 0.002862 -0.997662 +-0.074091 0.003105 -0.997247 +0.000000 1.000000 0.000000 +0.000000 0.992411 -0.122966 +0.000000 1.000000 0.000000 +0.000000 0.527685 -0.849440 +0.000000 0.405548 -0.914074 +0.000000 0.527685 -0.849440 +0.000000 0.000000 -1.000000 +0.000000 0.204909 -0.978781 +0.000000 0.000000 -1.000000 +0.000000 0.137854 -0.990453 +0.000000 0.204909 -0.978781 +0.000000 0.000000 -1.000000 +0.000000 0.274372 -0.961624 +0.000000 0.204909 -0.978781 +0.000000 0.137854 -0.990453 +0.000000 0.274372 -0.961624 +0.000000 0.397177 -0.917742 +0.000000 0.204909 -0.978781 +0.000000 0.405548 -0.914074 +0.000000 0.397177 -0.917742 +0.000000 0.274372 -0.961624 +0.000000 0.527685 -0.849440 +0.000000 0.397177 -0.917742 +0.000000 0.405548 -0.914074 +0.000000 0.527685 -0.849440 +0.000000 0.566635 -0.823969 +0.000000 0.397177 -0.917742 +0.000000 0.628133 -0.778106 +0.000000 0.566635 -0.823969 +0.000000 0.527685 -0.849440 +0.000000 0.628133 -0.778106 +0.000000 0.707107 -0.707107 +0.000000 0.566635 -0.823969 +0.000000 0.721145 -0.692784 +0.000000 0.707107 -0.707107 +0.000000 0.628133 -0.778106 +0.000000 0.721145 -0.692784 +0.000000 0.823969 -0.566635 +0.000000 0.707107 -0.707107 +0.000000 0.803919 -0.594739 +0.000000 0.823969 -0.566635 +0.000000 0.721145 -0.692784 +0.000000 0.873981 -0.485961 +0.000000 0.823969 -0.566635 +0.000000 0.803919 -0.594739 +0.000000 0.873981 -0.485961 +0.000000 0.917742 -0.397177 +0.000000 0.823969 -0.566635 +0.000000 0.929411 -0.369047 +0.000000 0.917742 -0.397177 +0.000000 0.873981 -0.485961 +0.000000 0.929411 -0.369047 +0.000000 0.978781 -0.204909 +0.000000 0.917742 -0.397177 +0.000000 0.969016 -0.246998 +0.000000 0.978781 -0.204909 +0.000000 0.929411 -0.369047 +0.000000 0.992411 -0.122966 +0.000000 0.978781 -0.204909 +0.000000 0.969016 -0.246998 +0.000000 0.992411 -0.122966 +0.000000 1.000000 0.000000 +0.000000 0.978781 -0.204909 +0.000000 0.000000 -1.000000 +0.068277 0.002862 -0.997662 +0.000000 0.000000 -1.000000 +0.068277 0.002862 -0.997662 +0.000000 0.000000 -1.000000 +0.074091 0.003105 -0.997247 +0.000000 0.992411 -0.122966 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -0.993650 -0.112516 +0.000000 -1.000000 0.000000 +0.000000 -0.983305 -0.181963 +0.000000 -0.993650 -0.112516 +0.000000 -1.000000 0.000000 +0.000000 -0.983305 -0.181963 +0.000000 -0.973106 -0.230359 +0.000000 -0.993650 -0.112516 +0.000000 -0.929788 -0.368095 +0.000000 -0.973106 -0.230359 +0.000000 -0.983305 -0.181963 +0.000000 -0.929788 -0.368095 +0.000000 -0.936318 -0.351152 +0.000000 -0.973106 -0.230359 +0.000000 -0.929788 -0.368095 +0.000000 -0.881719 -0.471774 +0.000000 -0.936318 -0.351152 +0.000000 -0.836995 -0.547210 +0.000000 -0.881719 -0.471774 +0.000000 -0.929788 -0.368095 +0.000000 -0.836995 -0.547210 +0.000000 -0.808518 -0.588471 +0.000000 -0.881719 -0.471774 +0.000000 -0.707107 -0.707107 +0.000000 -0.808518 -0.588471 +0.000000 -0.836995 -0.547210 +0.000000 -0.707107 -0.707107 +0.000000 -0.716972 -0.697102 +0.000000 -0.808518 -0.588471 +0.000000 -0.707107 -0.707107 +0.000000 -0.608554 -0.793512 +0.000000 -0.716972 -0.697102 +0.000000 -0.547210 -0.836995 +0.000000 -0.608554 -0.793512 +0.000000 -0.707107 -0.707107 +0.000000 -0.547210 -0.836995 +0.000000 -0.485961 -0.873981 +0.000000 -0.608554 -0.793512 +0.000000 -0.368095 -0.929788 +0.000000 -0.485961 -0.873981 +0.000000 -0.547210 -0.836995 +0.000000 -0.368095 -0.929788 +0.000000 -0.352916 -0.935655 +0.000000 -0.485961 -0.873981 +0.000000 -0.181963 -0.983305 +0.000000 -0.352916 -0.935655 +0.000000 -0.368095 -0.929788 +0.000000 -0.181963 -0.983305 +0.000000 -0.213811 -0.976875 +0.000000 -0.352916 -0.935655 +0.000000 -0.181963 -0.983305 +0.000000 -0.073228 -0.997315 +0.000000 -0.213811 -0.976875 +0.000000 0.000000 -1.000000 +0.000000 -0.073228 -0.997315 +0.000000 -0.181963 -0.983305 +0.000000 0.000000 -1.000000 +0.000000 0.064526 -0.997916 +0.000000 -0.073228 -0.997315 +0.000000 0.181963 -0.983305 +0.000000 0.064526 -0.997916 +0.000000 0.000000 -1.000000 +0.000000 0.181963 -0.983305 +0.000000 0.195798 -0.980644 +0.000000 0.064526 -0.997916 +0.000000 0.368095 -0.929788 +0.000000 0.195798 -0.980644 +0.000000 0.181963 -0.983305 +0.000000 0.368095 -0.929788 +0.000000 0.317817 -0.948152 +0.000000 0.195798 -0.980644 +0.000000 0.368095 -0.929788 +0.000000 0.428759 -0.903419 +0.000000 0.317817 -0.948152 +0.000000 0.547210 -0.836995 +0.000000 0.428759 -0.903419 +0.000000 0.368095 -0.929788 +0.000000 0.428759 -0.903419 +0.000000 0.527685 -0.849440 +0.000000 0.527685 -0.849440 +0.000000 0.547210 -0.836995 +0.000000 0.527685 -0.849440 +0.000000 0.428759 -0.903419 +0.000000 0.547210 -0.836995 +0.000000 0.628133 -0.778106 +0.000000 0.527685 -0.849440 +0.000000 0.707107 -0.707107 +0.000000 0.628133 -0.778106 +0.000000 0.547210 -0.836995 +0.000000 0.707107 -0.707107 +0.000000 0.721145 -0.692784 +0.000000 0.628133 -0.778106 +0.000000 0.836995 -0.547210 +0.000000 0.721145 -0.692784 +0.000000 0.707107 -0.707107 +0.000000 0.836995 -0.547210 +0.000000 0.803919 -0.594739 +0.000000 0.721145 -0.692784 +0.000000 0.836995 -0.547210 +0.000000 0.873981 -0.485961 +0.000000 0.803919 -0.594739 +0.000000 0.929788 -0.368095 +0.000000 0.873981 -0.485961 +0.000000 0.836995 -0.547210 +0.000000 0.929788 -0.368095 +0.000000 0.929411 -0.369047 +0.000000 0.873981 -0.485961 +0.000000 0.929788 -0.368095 +0.000000 0.969016 -0.246998 +0.000000 0.929411 -0.369047 +0.000000 0.983305 -0.181963 +0.000000 0.969016 -0.246998 +0.000000 0.929788 -0.368095 +0.000000 0.983305 -0.181963 +0.000000 0.992411 -0.122966 +0.000000 0.969016 -0.246998 +0.000000 1.000000 0.000000 +0.000000 0.992411 -0.122966 +0.000000 0.983305 -0.181963 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.999123 0.041876 0.000000 +-0.999123 0.041876 0.000000 +-0.999123 0.041876 0.000000 +-0.999123 0.041876 0.000000 +-0.999123 0.041876 0.000000 +-0.999123 0.041876 0.000000 +-0.999123 0.041876 0.000000 +-0.999123 0.041876 0.000000 +-0.999123 0.041876 0.000000 +0.999123 0.041876 0.000000 +0.999123 0.041876 0.000000 +0.999123 0.041876 0.000000 +0.999123 0.041876 0.000000 +0.999123 0.041876 0.000000 +0.999123 0.041876 0.000000 +0.999123 0.041876 0.000000 +0.999123 0.041876 0.000000 +0.999123 0.041876 0.000000 +-0.999123 -0.041876 0.000000 +-0.999123 -0.041876 0.000000 +-0.999123 -0.041876 0.000000 +-0.999123 -0.041876 0.000000 +-0.999123 -0.041876 0.000000 +-0.999123 -0.041876 0.000000 +-0.999123 -0.041876 0.000000 +-0.999123 -0.041876 0.000000 +-0.999123 -0.041876 0.000000 +0.999123 -0.041876 0.000000 +0.999123 -0.041876 0.000000 +0.999123 -0.041876 0.000000 +0.999123 -0.041876 0.000000 +0.999123 -0.041876 0.000000 +0.999123 -0.041876 0.000000 +0.999123 -0.041876 0.000000 +0.999123 -0.041876 0.000000 +0.999123 -0.041876 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 0.000000 1.000000 +0.000000 -0.159148 0.987255 +0.000000 0.000000 1.000000 +0.000000 -1.000000 0.000000 +0.000000 -0.996401 0.084767 +0.000000 -1.000000 0.000000 +0.000000 -0.977742 0.209810 +0.000000 -0.996401 0.084767 +0.000000 -1.000000 0.000000 +0.000000 -0.977742 0.209810 +0.000000 -0.981414 0.191900 +0.000000 -0.996401 0.084767 +0.000000 -0.977742 0.209810 +0.000000 -0.948549 0.316631 +0.000000 -0.981414 0.191900 +0.000000 -0.947547 0.319617 +0.000000 -0.948549 0.316631 +0.000000 -0.977742 0.209810 +0.000000 -0.947547 0.319617 +0.000000 -0.892708 0.450636 +0.000000 -0.948549 0.316631 +0.000000 -0.903932 0.427675 +0.000000 -0.892708 0.450636 +0.000000 -0.947547 0.319617 +0.000000 -0.846359 0.532613 +0.000000 -0.892708 0.450636 +0.000000 -0.903932 0.427675 +0.000000 -0.846359 0.532613 +0.000000 -0.810836 0.585273 +0.000000 -0.892708 0.450636 +0.000000 -0.775708 0.631092 +0.000000 -0.810836 0.585273 +0.000000 -0.846359 0.532613 +0.000000 -0.775708 0.631092 +0.000000 -0.705365 0.708845 +0.000000 -0.810836 0.585273 +0.000000 -0.693323 0.720627 +0.000000 -0.705365 0.708845 +0.000000 -0.775708 0.631092 +0.000000 -0.693323 0.720627 +0.000000 -0.578543 0.815652 +0.000000 -0.705365 0.708845 +0.000000 -0.600000 0.800000 +0.000000 -0.578543 0.815652 +0.000000 -0.693323 0.720627 +0.000000 -0.465034 0.885293 +0.000000 -0.578543 0.815652 +0.000000 -0.600000 0.800000 +0.000000 -0.465034 0.885293 +0.000000 -0.435890 0.900000 +0.000000 -0.578543 0.815652 +0.000000 -0.316228 0.948683 +0.000000 -0.435890 0.900000 +0.000000 -0.465034 0.885293 +0.000000 -0.316228 0.948683 +0.000000 -0.223607 0.974679 +0.000000 -0.435890 0.900000 +0.000000 -0.159148 0.987255 +0.000000 -0.223607 0.974679 +0.000000 -0.316228 0.948683 +0.000000 -0.159148 0.987255 +0.000000 0.000000 1.000000 +0.000000 -0.223607 0.974679 +0.000000 -0.159148 0.987255 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -0.996436 0.084348 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -0.996436 0.084348 +0.000000 -0.977536 0.210769 +0.000000 -1.000000 0.000000 +0.000000 -0.981560 0.191155 +0.000000 -0.977536 0.210769 +0.000000 -0.996436 0.084348 +0.000000 -0.949182 0.314727 +0.000000 -0.977536 0.210769 +0.000000 -0.981560 0.191155 +0.000000 -0.949182 0.314727 +0.000000 -0.947313 0.320309 +0.000000 -0.977536 0.210769 +0.000000 -0.893349 0.449364 +0.000000 -0.947313 0.320309 +0.000000 -0.949182 0.314727 +0.000000 -0.893349 0.449364 +0.000000 -0.903331 0.428944 +0.000000 -0.947313 0.320309 +0.000000 -0.893349 0.449364 +0.000000 -0.845956 0.533253 +0.000000 -0.903331 0.428944 +0.000000 -0.812207 0.583369 +0.000000 -0.845956 0.533253 +0.000000 -0.893349 0.449364 +0.000000 -0.812207 0.583369 +0.000000 -0.775007 0.631952 +0.000000 -0.845956 0.533253 +0.000000 -0.706112 0.708100 +0.000000 -0.775007 0.631952 +0.000000 -0.812207 0.583369 +0.000000 -0.706112 0.708100 +0.000000 -0.692822 0.721109 +0.000000 -0.775007 0.631952 +0.000000 -0.579133 0.815233 +0.000000 -0.692822 0.721109 +0.000000 -0.706112 0.708100 +0.000000 -0.579133 0.815233 +0.000000 -0.600000 0.800000 +0.000000 -0.692822 0.721109 +0.000000 -0.579133 0.815233 +0.000000 -0.465034 0.885293 +0.000000 -0.600000 0.800000 +0.000000 -0.435890 0.900000 +0.000000 -0.465034 0.885293 +0.000000 -0.579133 0.815233 +0.000000 -0.435890 0.900000 +0.000000 -0.316228 0.948683 +0.000000 -0.465034 0.885293 +0.000000 -0.223607 0.974679 +0.000000 -0.316228 0.948683 +0.000000 -0.435890 0.900000 +0.000000 -0.223607 0.974679 +0.000000 -0.159148 0.987255 +0.000000 -0.316228 0.948683 +0.000000 0.000000 1.000000 +0.000000 -0.159148 0.987255 +0.000000 -0.223607 0.974679 +0.000000 -0.128308 0.991734 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -0.995686 0.092782 +0.000000 -0.998198 0.060000 +0.000000 -0.998198 0.060000 +0.000000 -0.995686 0.092782 +0.000000 -0.995661 0.093058 +0.000000 -0.998198 0.060000 +0.000000 -0.981943 0.189176 +0.000000 -0.995661 0.093058 +0.000000 -0.995686 0.092782 +0.000000 -0.981943 0.189176 +0.000000 -0.981767 0.190088 +0.000000 -0.995661 0.093058 +0.000000 -0.939980 0.341229 +0.000000 -0.981767 0.190088 +0.000000 -0.981943 0.189176 +0.000000 -0.939980 0.341229 +0.000000 -0.939296 0.343108 +0.000000 -0.981767 0.190088 +0.000000 -0.848817 0.528687 +0.000000 -0.939296 0.343108 +0.000000 -0.939980 0.341229 +0.000000 -0.848817 0.528687 +0.000000 -0.847176 0.531313 +0.000000 -0.939296 0.343108 +0.000000 -0.780702 0.624903 +0.000000 -0.847176 0.531313 +0.000000 -0.848817 0.528687 +0.000000 -0.780702 0.624903 +0.000000 -0.778104 0.628136 +0.000000 -0.847176 0.531313 +0.000000 -0.697185 0.716892 +0.000000 -0.778104 0.628136 +0.000000 -0.780702 0.624903 +0.000000 -0.697185 0.716892 +0.000000 -0.695246 0.718772 +0.000000 -0.778104 0.628136 +0.000000 -0.600910 0.799317 +0.000000 -0.695246 0.718772 +0.000000 -0.697185 0.716892 +0.000000 -0.600910 0.799317 +0.000000 -0.598642 0.801017 +0.000000 -0.695246 0.718772 +0.000000 -0.493208 0.869912 +0.000000 -0.598642 0.801017 +0.000000 -0.600910 0.799317 +0.000000 -0.493208 0.869912 +0.000000 -0.491596 0.870824 +0.000000 -0.598642 0.801017 +0.000000 -0.377542 0.925992 +0.000000 -0.491596 0.870824 +0.000000 -0.493208 0.869912 +0.000000 -0.377542 0.925992 +0.000000 -0.376411 0.926453 +0.000000 -0.491596 0.870824 +0.000000 -0.254997 0.966942 +0.000000 -0.376411 0.926453 +0.000000 -0.377542 0.925992 +0.000000 -0.254997 0.966942 +0.000000 -0.253949 0.967218 +0.000000 -0.376411 0.926453 +0.000000 -0.128651 0.991690 +0.000000 -0.253949 0.967218 +0.000000 -0.254997 0.966942 +0.000000 -0.128651 0.991690 +0.000000 -0.128308 0.991734 +0.000000 -0.253949 0.967218 +0.000000 0.000000 1.000000 +0.000000 -0.128308 0.991734 +0.000000 -0.128651 0.991690 +0.000000 -0.128308 0.991734 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -0.998198 0.060000 +0.000000 -0.995661 0.093058 +0.000000 -0.998198 0.060000 +0.000000 -0.995686 0.092782 +0.000000 -0.995661 0.093058 +0.000000 -0.998198 0.060000 +0.000000 -0.995686 0.092782 +0.000000 -0.981767 0.190088 +0.000000 -0.995661 0.093058 +0.000000 -0.981943 0.189176 +0.000000 -0.981767 0.190088 +0.000000 -0.995686 0.092782 +0.000000 -0.981943 0.189176 +0.000000 -0.939296 0.343108 +0.000000 -0.981767 0.190088 +0.000000 -0.939980 0.341229 +0.000000 -0.939296 0.343108 +0.000000 -0.981943 0.189176 +0.000000 -0.848817 0.528687 +0.000000 -0.939296 0.343108 +0.000000 -0.939980 0.341229 +0.000000 -0.848817 0.528687 +0.000000 -0.847176 0.531313 +0.000000 -0.939296 0.343108 +0.000000 -0.780702 0.624903 +0.000000 -0.847176 0.531313 +0.000000 -0.848817 0.528687 +0.000000 -0.780702 0.624903 +0.000000 -0.778104 0.628136 +0.000000 -0.847176 0.531313 +0.000000 -0.697185 0.716892 +0.000000 -0.778104 0.628136 +0.000000 -0.780702 0.624903 +0.000000 -0.697185 0.716892 +0.000000 -0.695246 0.718772 +0.000000 -0.778104 0.628136 +0.000000 -0.600910 0.799317 +0.000000 -0.695246 0.718772 +0.000000 -0.697185 0.716892 +0.000000 -0.600910 0.799317 +0.000000 -0.598642 0.801017 +0.000000 -0.695246 0.718772 +0.000000 -0.493208 0.869912 +0.000000 -0.598642 0.801017 +0.000000 -0.600910 0.799317 +0.000000 -0.493208 0.869912 +0.000000 -0.491596 0.870824 +0.000000 -0.598642 0.801017 +0.000000 -0.377542 0.925992 +0.000000 -0.491596 0.870824 +0.000000 -0.493208 0.869912 +0.000000 -0.377542 0.925992 +0.000000 -0.376411 0.926453 +0.000000 -0.491596 0.870824 +0.000000 -0.254997 0.966942 +0.000000 -0.376411 0.926453 +0.000000 -0.377542 0.925992 +0.000000 -0.254997 0.966942 +0.000000 -0.253949 0.967218 +0.000000 -0.376411 0.926453 +0.000000 -0.128651 0.991690 +0.000000 -0.253949 0.967218 +0.000000 -0.254997 0.966942 +0.000000 -0.128651 0.991690 +0.000000 -0.128308 0.991734 +0.000000 -0.253949 0.967218 +0.000000 0.000000 1.000000 +0.000000 -0.128308 0.991734 +0.000000 -0.128651 0.991690 +-0.971195 -0.040705 0.234784 +-0.997323 -0.041800 0.060000 +-0.997323 -0.041800 0.060000 +0.000000 0.000000 1.000000 +-0.175884 -0.007372 0.984383 +0.000000 0.000000 1.000000 +-0.128538 -0.005387 0.991690 +-0.175884 -0.007372 0.984383 +0.000000 0.000000 1.000000 +-0.254773 -0.010678 0.966942 +-0.175884 -0.007372 0.984383 +-0.128538 -0.005387 0.991690 +-0.254773 -0.010678 0.966942 +-0.355448 -0.014898 0.934577 +-0.175884 -0.007372 0.984383 +-0.377211 -0.015810 0.925992 +-0.355448 -0.014898 0.934577 +-0.254773 -0.010678 0.966942 +-0.377211 -0.015810 0.925992 +-0.528737 -0.022161 0.848497 +-0.355448 -0.014898 0.934577 +-0.492775 -0.020653 0.869912 +-0.528737 -0.022161 0.848497 +-0.377211 -0.015810 0.925992 +-0.600383 -0.025163 0.799317 +-0.528737 -0.022161 0.848497 +-0.492775 -0.020653 0.869912 +-0.600383 -0.025163 0.799317 +-0.684964 -0.028709 0.728011 +-0.528737 -0.022161 0.848497 +-0.696573 -0.029195 0.716892 +-0.684964 -0.028709 0.728011 +-0.600383 -0.025163 0.799317 +-0.696573 -0.029195 0.716892 +-0.814501 -0.034138 0.579157 +-0.684964 -0.028709 0.728011 +-0.780017 -0.032692 0.624903 +-0.814501 -0.034138 0.579157 +-0.696573 -0.029195 0.716892 +-0.848072 -0.035545 0.528687 +-0.814501 -0.034138 0.579157 +-0.780017 -0.032692 0.624903 +-0.848072 -0.035545 0.528687 +-0.910748 -0.038172 0.411194 +-0.814501 -0.034138 0.579157 +-0.939156 -0.039362 0.341229 +-0.910748 -0.038172 0.411194 +-0.848072 -0.035545 0.528687 +-0.939156 -0.039362 0.341229 +-0.971195 -0.040705 0.234784 +-0.910748 -0.038172 0.411194 +-0.981082 -0.041120 0.189176 +-0.971195 -0.040705 0.234784 +-0.939156 -0.039362 0.341229 +-0.994813 -0.041695 0.092782 +-0.971195 -0.040705 0.234784 +-0.981082 -0.041120 0.189176 +-0.997323 -0.041800 0.060000 +-0.971195 -0.040705 0.234784 +-0.994813 -0.041695 0.092782 +0.997323 -0.041800 0.060000 +0.971195 -0.040705 0.234784 +0.997323 -0.041800 0.060000 +0.175884 -0.007372 0.984383 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.175884 -0.007372 0.984383 +0.128195 -0.005373 0.991734 +0.000000 0.000000 1.000000 +0.175884 -0.007372 0.984383 +0.253726 -0.010634 0.967218 +0.128195 -0.005373 0.991734 +0.355448 -0.014898 0.934577 +0.253726 -0.010634 0.967218 +0.175884 -0.007372 0.984383 +0.355448 -0.014898 0.934577 +0.376081 -0.015762 0.926453 +0.253726 -0.010634 0.967218 +0.528737 -0.022161 0.848497 +0.376081 -0.015762 0.926453 +0.355448 -0.014898 0.934577 +0.528737 -0.022161 0.848497 +0.491165 -0.020586 0.870824 +0.376081 -0.015762 0.926453 +0.528737 -0.022161 0.848497 +0.598117 -0.025069 0.801017 +0.491165 -0.020586 0.870824 +0.684964 -0.028709 0.728011 +0.598117 -0.025069 0.801017 +0.528737 -0.022161 0.848497 +0.684964 -0.028709 0.728011 +0.694637 -0.029114 0.718772 +0.598117 -0.025069 0.801017 +0.814501 -0.034138 0.579157 +0.694637 -0.029114 0.718772 +0.684964 -0.028709 0.728011 +0.814501 -0.034138 0.579157 +0.777421 -0.032584 0.628136 +0.694637 -0.029114 0.718772 +0.814501 -0.034138 0.579157 +0.846433 -0.035476 0.531313 +0.777421 -0.032584 0.628136 +0.910748 -0.038172 0.411194 +0.846433 -0.035476 0.531313 +0.814501 -0.034138 0.579157 +0.910748 -0.038172 0.411194 +0.938472 -0.039334 0.343108 +0.846433 -0.035476 0.531313 +0.971195 -0.040705 0.234784 +0.938472 -0.039334 0.343108 +0.910748 -0.038172 0.411194 +0.971195 -0.040705 0.234784 +0.980906 -0.041112 0.190088 +0.938472 -0.039334 0.343108 +0.971195 -0.040705 0.234784 +0.994787 -0.041694 0.093058 +0.980906 -0.041112 0.190088 +0.971195 -0.040705 0.234784 +0.997323 -0.041800 0.060000 +0.994787 -0.041694 0.093058 +0.128538 -0.005387 0.991690 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.999123 -0.041876 0.000000 +0.997323 -0.041800 0.060000 +0.999123 -0.041876 0.000000 +0.999123 -0.041876 0.000000 +0.997323 -0.041800 0.060000 +0.997323 -0.041800 0.060000 +0.995527 -0.041725 0.084767 +0.997323 -0.041800 0.060000 +0.999123 -0.041876 0.000000 +0.995527 -0.041725 0.084767 +0.994813 -0.041695 0.092782 +0.997323 -0.041800 0.060000 +0.980554 -0.041097 0.191900 +0.994813 -0.041695 0.092782 +0.995527 -0.041725 0.084767 +0.980554 -0.041097 0.191900 +0.981082 -0.041120 0.189176 +0.994813 -0.041695 0.092782 +0.980554 -0.041097 0.191900 +0.939156 -0.039362 0.341229 +0.981082 -0.041120 0.189176 +0.947717 -0.039721 0.316631 +0.939156 -0.039362 0.341229 +0.980554 -0.041097 0.191900 +0.891925 -0.037383 0.450636 +0.939156 -0.039362 0.341229 +0.947717 -0.039721 0.316631 +0.891925 -0.037383 0.450636 +0.848072 -0.035545 0.528687 +0.939156 -0.039362 0.341229 +0.810125 -0.033954 0.585273 +0.848072 -0.035545 0.528687 +0.891925 -0.037383 0.450636 +0.810125 -0.033954 0.585273 +0.780017 -0.032692 0.624903 +0.848072 -0.035545 0.528687 +0.704746 -0.029538 0.708845 +0.780017 -0.032692 0.624903 +0.810125 -0.033954 0.585273 +0.704746 -0.029538 0.708845 +0.696573 -0.029195 0.716892 +0.780017 -0.032692 0.624903 +0.578036 -0.024227 0.815652 +0.696573 -0.029195 0.716892 +0.704746 -0.029538 0.708845 +0.578036 -0.024227 0.815652 +0.600383 -0.025163 0.799317 +0.696573 -0.029195 0.716892 +0.578036 -0.024227 0.815652 +0.492775 -0.020653 0.869912 +0.600383 -0.025163 0.799317 +0.435508 -0.018253 0.900000 +0.492775 -0.020653 0.869912 +0.578036 -0.024227 0.815652 +0.435508 -0.018253 0.900000 +0.377211 -0.015810 0.925992 +0.492775 -0.020653 0.869912 +0.223411 -0.009364 0.974679 +0.377211 -0.015810 0.925992 +0.435508 -0.018253 0.900000 +0.223411 -0.009364 0.974679 +0.254773 -0.010678 0.966942 +0.377211 -0.015810 0.925992 +0.223411 -0.009364 0.974679 +0.128538 -0.005387 0.991690 +0.254773 -0.010678 0.966942 +0.000000 0.000000 1.000000 +0.128538 -0.005387 0.991690 +0.223411 -0.009364 0.974679 +-0.995562 -0.041726 0.084348 +-0.997323 -0.041800 0.060000 +-0.994787 -0.041694 0.093058 +0.000000 0.000000 1.000000 +-0.128195 -0.005373 0.991734 +0.000000 0.000000 1.000000 +-0.223411 -0.009364 0.974679 +-0.128195 -0.005373 0.991734 +0.000000 0.000000 1.000000 +-0.223411 -0.009364 0.974679 +-0.253726 -0.010634 0.967218 +-0.128195 -0.005373 0.991734 +-0.435508 -0.018253 0.900000 +-0.253726 -0.010634 0.967218 +-0.223411 -0.009364 0.974679 +-0.435508 -0.018253 0.900000 +-0.376081 -0.015762 0.926453 +-0.253726 -0.010634 0.967218 +-0.435508 -0.018253 0.900000 +-0.491165 -0.020586 0.870824 +-0.376081 -0.015762 0.926453 +-0.578625 -0.024252 0.815233 +-0.491165 -0.020586 0.870824 +-0.435508 -0.018253 0.900000 +-0.578625 -0.024252 0.815233 +-0.598117 -0.025069 0.801017 +-0.491165 -0.020586 0.870824 +-0.705493 -0.029569 0.708100 +-0.598117 -0.025069 0.801017 +-0.578625 -0.024252 0.815233 +-0.705493 -0.029569 0.708100 +-0.694637 -0.029114 0.718772 +-0.598117 -0.025069 0.801017 +-0.705493 -0.029569 0.708100 +-0.777421 -0.032584 0.628136 +-0.694637 -0.029114 0.718772 +-0.811495 -0.034012 0.583369 +-0.777421 -0.032584 0.628136 +-0.705493 -0.029569 0.708100 +-0.811495 -0.034012 0.583369 +-0.846433 -0.035476 0.531313 +-0.777421 -0.032584 0.628136 +-0.892565 -0.037410 0.449364 +-0.846433 -0.035476 0.531313 +-0.811495 -0.034012 0.583369 +-0.892565 -0.037410 0.449364 +-0.938472 -0.039334 0.343108 +-0.846433 -0.035476 0.531313 +-0.948350 -0.039748 0.314727 +-0.938472 -0.039334 0.343108 +-0.892565 -0.037410 0.449364 +-0.948350 -0.039748 0.314727 +-0.980906 -0.041112 0.190088 +-0.938472 -0.039334 0.343108 +-0.980699 -0.041103 0.191155 +-0.980906 -0.041112 0.190088 +-0.948350 -0.039748 0.314727 +-0.995562 -0.041726 0.084348 +-0.980906 -0.041112 0.190088 +-0.980699 -0.041103 0.191155 +-0.995562 -0.041726 0.084348 +-0.994787 -0.041694 0.093058 +-0.980906 -0.041112 0.190088 +-0.997323 -0.041800 0.060000 +-0.999123 -0.041876 0.000000 +-0.999123 -0.041876 0.000000 +-0.997323 -0.041800 0.060000 +-0.999123 -0.041876 0.000000 +-0.997323 -0.041800 0.060000 +-0.997323 -0.041800 0.060000 +-0.995562 -0.041726 0.084348 +-0.999123 -0.041876 0.000000 +0.991825 0.041570 -0.120648 +0.999123 0.041876 0.000000 +0.999123 0.041876 0.000000 +0.020279 0.000850 -0.999794 +0.000000 0.000000 -1.000000 +0.042810 0.001794 -0.999082 +0.020279 0.000850 -0.999794 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.020279 0.000850 -0.999794 +0.116889 0.004899 -0.993133 +0.000000 0.000000 -1.000000 +0.199727 0.008371 -0.979816 +0.116889 0.004899 -0.993133 +0.020279 0.000850 -0.999794 +0.199727 0.008371 -0.979816 +0.234682 0.009836 -0.972022 +0.116889 0.004899 -0.993133 +0.382441 0.016029 -0.923841 +0.234682 0.009836 -0.972022 +0.199727 0.008371 -0.979816 +0.382441 0.016029 -0.923841 +0.350780 0.014702 -0.936343 +0.234682 0.009836 -0.972022 +0.382441 0.016029 -0.923841 +0.462504 0.019385 -0.886405 +0.350780 0.014702 -0.936343 +0.557625 0.023371 -0.829764 +0.462504 0.019385 -0.886405 +0.382441 0.016029 -0.923841 +0.557625 0.023371 -0.829764 +0.567292 0.023777 -0.823174 +0.462504 0.019385 -0.886405 +0.713620 0.029910 -0.699894 +0.567292 0.023777 -0.823174 +0.557625 0.023371 -0.829764 +0.713620 0.029910 -0.699894 +0.662888 0.027783 -0.748203 +0.567292 0.023777 -0.823174 +0.713620 0.029910 -0.699894 +0.747508 0.031330 -0.663514 +0.662888 0.027783 -0.748203 +0.840184 0.035214 -0.541158 +0.747508 0.031330 -0.663514 +0.713620 0.029910 -0.699894 +0.840184 0.035214 -0.541158 +0.819932 0.034365 -0.571429 +0.747508 0.031330 -0.663514 +0.840184 0.035214 -0.541158 +0.906003 0.037973 -0.421565 +0.819932 0.034365 -0.571429 +0.930603 0.039004 -0.363947 +0.906003 0.037973 -0.421565 +0.840184 0.035214 -0.541158 +0.930603 0.039004 -0.363947 +0.963142 0.040368 -0.265946 +0.906003 0.037973 -0.421565 +0.982809 0.041192 -0.179973 +0.963142 0.040368 -0.265946 +0.930603 0.039004 -0.363947 +0.982809 0.041192 -0.179973 +0.991825 0.041570 -0.120648 +0.963142 0.040368 -0.265946 +0.999123 0.041876 0.000000 +0.991825 0.041570 -0.120648 +0.982809 0.041192 -0.179973 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +-0.929753 -0.368081 0.008727 +-0.983268 -0.181956 0.008727 +-0.983268 -0.181956 0.008727 +-0.999962 0.000000 0.008727 +-0.983268 -0.181956 0.008727 +-0.999962 0.000000 0.008727 +-0.983268 -0.181956 0.008727 +-0.983268 -0.181956 0.008727 +-0.999962 0.000000 0.008727 +0.983268 -0.181956 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.983268 -0.181956 0.008727 +0.983268 -0.181956 0.008727 +0.999962 0.000000 0.008727 +0.929753 -0.368081 0.008727 +0.983268 -0.181956 0.008727 +0.983268 -0.181956 0.008727 +0.929753 -0.368081 0.008727 +0.929753 -0.368081 0.008727 +0.983268 -0.181956 0.008727 +0.929753 -0.368081 0.008727 +0.836964 -0.547189 0.008727 +0.929753 -0.368081 0.008727 +0.836964 -0.547189 0.008727 +0.836964 -0.547189 0.008727 +0.929753 -0.368081 0.008727 +0.707080 -0.707080 0.008727 +0.836964 -0.547189 0.008727 +0.836964 -0.547189 0.008727 +0.707080 -0.707080 0.008727 +0.707080 -0.707080 0.008727 +0.836964 -0.547189 0.008727 +0.547189 -0.836964 0.008727 +0.707080 -0.707080 0.008727 +0.707080 -0.707080 0.008727 +0.547189 -0.836964 0.008727 +0.547189 -0.836964 0.008727 +0.707080 -0.707080 0.008727 +0.368081 -0.929753 0.008727 +0.547189 -0.836964 0.008727 +0.547189 -0.836964 0.008727 +0.368081 -0.929753 0.008727 +0.368081 -0.929753 0.008727 +0.547189 -0.836964 0.008727 +0.181956 -0.983268 0.008727 +0.368081 -0.929753 0.008727 +0.368081 -0.929753 0.008727 +0.181956 -0.983268 0.008727 +0.181956 -0.983268 0.008727 +0.368081 -0.929753 0.008727 +0.000000 -0.999962 0.008727 +0.181956 -0.983268 0.008727 +0.181956 -0.983268 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.181956 -0.983268 0.008727 +-0.181956 -0.983268 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +-0.181956 -0.983268 0.008727 +-0.181956 -0.983268 0.008727 +0.000000 -0.999962 0.008727 +-0.368081 -0.929753 0.008727 +-0.181956 -0.983268 0.008727 +-0.181956 -0.983268 0.008727 +-0.368081 -0.929753 0.008727 +-0.368081 -0.929753 0.008727 +-0.181956 -0.983268 0.008727 +-0.547189 -0.836964 0.008727 +-0.368081 -0.929753 0.008727 +-0.368081 -0.929753 0.008727 +-0.547189 -0.836964 0.008727 +-0.547189 -0.836964 0.008727 +-0.368081 -0.929753 0.008727 +-0.707080 -0.707080 0.008727 +-0.547189 -0.836964 0.008727 +-0.547189 -0.836964 0.008727 +-0.707080 -0.707080 0.008727 +-0.707080 -0.707080 0.008727 +-0.547189 -0.836964 0.008727 +-0.836964 -0.547189 0.008727 +-0.707080 -0.707080 0.008727 +-0.707080 -0.707080 0.008727 +-0.836964 -0.547189 0.008727 +-0.836964 -0.547189 0.008727 +-0.707080 -0.707080 0.008727 +-0.929753 -0.368081 0.008727 +-0.836964 -0.547189 0.008727 +-0.836964 -0.547189 0.008727 +-0.929753 -0.368081 0.008727 +-0.929753 -0.368081 0.008727 +-0.836964 -0.547189 0.008727 +-0.983268 -0.181956 0.008727 +-0.929753 -0.368081 0.008727 +-0.929753 -0.368081 0.008727 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.929753 -0.368081 0.008727 +-0.983268 -0.181956 0.008727 +-0.983268 -0.181956 0.008727 +-0.999962 0.000000 0.008727 +-0.983268 -0.181956 0.008727 +-0.999962 0.000000 0.008727 +-0.983268 -0.181956 0.008727 +-0.983268 -0.181956 0.008727 +-0.999962 0.000000 0.008727 +0.983268 -0.181956 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.983268 -0.181956 0.008727 +0.983268 -0.181956 0.008727 +0.999962 0.000000 0.008727 +0.929753 -0.368081 0.008727 +0.983268 -0.181956 0.008727 +0.983268 -0.181956 0.008727 +0.929753 -0.368081 0.008727 +0.929753 -0.368081 0.008727 +0.983268 -0.181956 0.008727 +0.836964 -0.547189 0.008727 +0.929753 -0.368081 0.008727 +0.929753 -0.368081 0.008727 +0.836964 -0.547189 0.008727 +0.836964 -0.547189 0.008727 +0.929753 -0.368081 0.008727 +0.707080 -0.707080 0.008727 +0.836964 -0.547189 0.008727 +0.836964 -0.547189 0.008727 +0.707080 -0.707080 0.008727 +0.707080 -0.707080 0.008727 +0.836964 -0.547189 0.008727 +0.547189 -0.836964 0.008727 +0.707080 -0.707080 0.008727 +0.707080 -0.707080 0.008727 +0.547189 -0.836964 0.008727 +0.547189 -0.836964 0.008727 +0.707080 -0.707080 0.008727 +0.368081 -0.929753 0.008727 +0.547189 -0.836964 0.008727 +0.547189 -0.836964 0.008727 +0.368081 -0.929753 0.008727 +0.368081 -0.929753 0.008727 +0.547189 -0.836964 0.008727 +0.181956 -0.983268 0.008727 +0.368081 -0.929753 0.008727 +0.368081 -0.929753 0.008727 +0.181956 -0.983268 0.008727 +0.181956 -0.983268 0.008727 +0.368081 -0.929753 0.008727 +0.000000 -0.999962 0.008727 +0.181956 -0.983268 0.008727 +0.181956 -0.983268 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.181956 -0.983268 0.008727 +-0.181956 -0.983268 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +-0.181956 -0.983268 0.008727 +-0.181956 -0.983268 0.008727 +0.000000 -0.999962 0.008727 +-0.368081 -0.929753 0.008727 +-0.181956 -0.983268 0.008727 +-0.181956 -0.983268 0.008727 +-0.368081 -0.929753 0.008727 +-0.368081 -0.929753 0.008727 +-0.181956 -0.983268 0.008727 +-0.547189 -0.836964 0.008727 +-0.368081 -0.929753 0.008727 +-0.368081 -0.929753 0.008727 +-0.547189 -0.836964 0.008727 +-0.547189 -0.836964 0.008727 +-0.368081 -0.929753 0.008727 +-0.707080 -0.707080 0.008727 +-0.547189 -0.836964 0.008727 +-0.547189 -0.836964 0.008727 +-0.707080 -0.707080 0.008727 +-0.707080 -0.707080 0.008727 +-0.547189 -0.836964 0.008727 +-0.836964 -0.547189 0.008727 +-0.707080 -0.707080 0.008727 +-0.707080 -0.707080 0.008727 +-0.836964 -0.547189 0.008727 +-0.836964 -0.547189 0.008727 +-0.707080 -0.707080 0.008727 +-0.929753 -0.368081 0.008727 +-0.836964 -0.547189 0.008727 +-0.836964 -0.547189 0.008727 +-0.929753 -0.368081 0.008727 +-0.929753 -0.368081 0.008727 +-0.836964 -0.547189 0.008727 +-0.983268 -0.181956 0.008727 +-0.929753 -0.368081 0.008727 +-0.929753 -0.368081 0.008727 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.983268 -0.181956 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +-0.983268 -0.181956 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.983268 -0.181956 0.008727 +-0.983268 -0.181956 0.008727 +-0.999962 0.000000 0.008727 +-0.929753 -0.368081 0.008727 +-0.983268 -0.181956 0.008727 +-0.983268 -0.181956 0.008727 +-0.929753 -0.368081 0.008727 +-0.929753 -0.368081 0.008727 +-0.983268 -0.181956 0.008727 +-0.836964 -0.547189 0.008727 +-0.929753 -0.368081 0.008727 +-0.929753 -0.368081 0.008727 +-0.836964 -0.547189 0.008727 +-0.836964 -0.547189 0.008727 +-0.929753 -0.368081 0.008727 +-0.707080 -0.707080 0.008727 +-0.836964 -0.547189 0.008727 +-0.836964 -0.547189 0.008727 +-0.707080 -0.707080 0.008727 +-0.707080 -0.707080 0.008727 +-0.836964 -0.547189 0.008727 +-0.547189 -0.836964 0.008727 +-0.707080 -0.707080 0.008727 +-0.707080 -0.707080 0.008727 +-0.547189 -0.836964 0.008727 +-0.547189 -0.836964 0.008727 +-0.707080 -0.707080 0.008727 +-0.368081 -0.929753 0.008727 +-0.547189 -0.836964 0.008727 +-0.547189 -0.836964 0.008727 +-0.368081 -0.929753 0.008727 +-0.368081 -0.929753 0.008727 +-0.547189 -0.836964 0.008727 +-0.181956 -0.983268 0.008727 +-0.368081 -0.929753 0.008727 +-0.368081 -0.929753 0.008727 +-0.181956 -0.983268 0.008727 +-0.181956 -0.983268 0.008727 +-0.368081 -0.929753 0.008727 +0.000000 -0.999962 0.008727 +-0.181956 -0.983268 0.008727 +-0.181956 -0.983268 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +-0.181956 -0.983268 0.008727 +0.181956 -0.983268 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.181956 -0.983268 0.008727 +0.181956 -0.983268 0.008727 +0.000000 -0.999962 0.008727 +0.368081 -0.929753 0.008727 +0.181956 -0.983268 0.008727 +0.181956 -0.983268 0.008727 +0.368081 -0.929753 0.008727 +0.368081 -0.929753 0.008727 +0.181956 -0.983268 0.008727 +0.547189 -0.836964 0.008727 +0.368081 -0.929753 0.008727 +0.368081 -0.929753 0.008727 +0.547189 -0.836964 0.008727 +0.547189 -0.836964 0.008727 +0.368081 -0.929753 0.008727 +0.707080 -0.707080 0.008727 +0.547189 -0.836964 0.008727 +0.547189 -0.836964 0.008727 +0.707080 -0.707080 0.008727 +0.707080 -0.707080 0.008727 +0.547189 -0.836964 0.008727 +0.836964 -0.547189 0.008727 +0.707080 -0.707080 0.008727 +0.707080 -0.707080 0.008727 +0.836964 -0.547189 0.008727 +0.836964 -0.547189 0.008727 +0.707080 -0.707080 0.008727 +0.929753 -0.368081 0.008727 +0.836964 -0.547189 0.008727 +0.836964 -0.547189 0.008727 +0.929753 -0.368081 0.008727 +0.929753 -0.368081 0.008727 +0.836964 -0.547189 0.008727 +0.983268 -0.181956 0.008727 +0.929753 -0.368081 0.008727 +0.929753 -0.368081 0.008727 +0.983268 -0.181956 0.008727 +0.983268 -0.181956 0.008727 +0.929753 -0.368081 0.008727 +0.999962 0.000000 0.008727 +0.983268 -0.181956 0.008727 +0.983268 -0.181956 0.008727 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.929753 -0.368081 0.008727 +-0.983268 -0.181956 0.008727 +-0.983268 -0.181956 0.008727 +-0.999962 0.000000 0.008727 +-0.983268 -0.181956 0.008727 +-0.999962 0.000000 0.008727 +-0.983268 -0.181956 0.008727 +-0.983268 -0.181956 0.008727 +-0.999962 0.000000 0.008727 +0.983268 -0.181956 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.983268 -0.181956 0.008727 +0.983268 -0.181956 0.008727 +0.999962 0.000000 0.008727 +0.929753 -0.368081 0.008727 +0.983268 -0.181956 0.008727 +0.983268 -0.181956 0.008727 +0.929753 -0.368081 0.008727 +0.929753 -0.368081 0.008727 +0.983268 -0.181956 0.008727 +0.836964 -0.547189 0.008727 +0.929753 -0.368081 0.008727 +0.929753 -0.368081 0.008727 +0.836964 -0.547189 0.008727 +0.836964 -0.547189 0.008727 +0.929753 -0.368081 0.008727 +0.707080 -0.707080 0.008727 +0.836964 -0.547189 0.008727 +0.836964 -0.547189 0.008727 +0.707080 -0.707080 0.008727 +0.707080 -0.707080 0.008727 +0.836964 -0.547189 0.008727 +0.547189 -0.836964 0.008727 +0.707080 -0.707080 0.008727 +0.707080 -0.707080 0.008727 +0.547189 -0.836964 0.008727 +0.547189 -0.836964 0.008727 +0.707080 -0.707080 0.008727 +0.368081 -0.929753 0.008727 +0.547189 -0.836964 0.008727 +0.547189 -0.836964 0.008727 +0.368081 -0.929753 0.008727 +0.368081 -0.929753 0.008727 +0.547189 -0.836964 0.008727 +0.181956 -0.983268 0.008727 +0.368081 -0.929753 0.008727 +0.368081 -0.929753 0.008727 +0.181956 -0.983268 0.008727 +0.181956 -0.983268 0.008727 +0.368081 -0.929753 0.008727 +0.000000 -0.999962 0.008727 +0.181956 -0.983268 0.008727 +0.181956 -0.983268 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.181956 -0.983268 0.008727 +-0.181956 -0.983268 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +-0.181956 -0.983268 0.008727 +-0.181956 -0.983268 0.008727 +0.000000 -0.999962 0.008727 +-0.368081 -0.929753 0.008727 +-0.181956 -0.983268 0.008727 +-0.181956 -0.983268 0.008727 +-0.368081 -0.929753 0.008727 +-0.368081 -0.929753 0.008727 +-0.181956 -0.983268 0.008727 +-0.547189 -0.836964 0.008727 +-0.368081 -0.929753 0.008727 +-0.368081 -0.929753 0.008727 +-0.547189 -0.836964 0.008727 +-0.547189 -0.836964 0.008727 +-0.368081 -0.929753 0.008727 +-0.707080 -0.707080 0.008727 +-0.547189 -0.836964 0.008727 +-0.547189 -0.836964 0.008727 +-0.707080 -0.707080 0.008727 +-0.707080 -0.707080 0.008727 +-0.547189 -0.836964 0.008727 +-0.836964 -0.547189 0.008727 +-0.707080 -0.707080 0.008727 +-0.707080 -0.707080 0.008727 +-0.836964 -0.547189 0.008727 +-0.836964 -0.547189 0.008727 +-0.707080 -0.707080 0.008727 +-0.929753 -0.368081 0.008727 +-0.836964 -0.547189 0.008727 +-0.836964 -0.547189 0.008727 +-0.929753 -0.368081 0.008727 +-0.929753 -0.368081 0.008727 +-0.836964 -0.547189 0.008727 +-0.983268 -0.181956 0.008727 +-0.929753 -0.368081 0.008727 +-0.929753 -0.368081 0.008727 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.074086 0.003105 -0.997247 +0.000000 0.181963 -0.983305 +0.000000 0.000000 -1.000000 +0.000000 1.000000 0.000000 +-0.016297 0.980865 -0.194008 +0.000000 1.000000 0.000000 +0.000000 0.983305 -0.181963 +-0.016297 0.980865 -0.194008 +0.000000 1.000000 0.000000 +0.000000 0.929788 -0.368095 +-0.016297 0.980865 -0.194008 +0.000000 0.983305 -0.181963 +0.000000 0.929788 -0.368095 +-0.030987 0.924436 -0.380077 +-0.016297 0.980865 -0.194008 +0.000000 0.836995 -0.547210 +-0.030987 0.924436 -0.380077 +0.000000 0.929788 -0.368095 +0.000000 0.836995 -0.547210 +-0.043829 0.832556 -0.552205 +-0.030987 0.924436 -0.380077 +0.000000 0.707107 -0.707107 +-0.043829 0.832556 -0.552205 +0.000000 0.836995 -0.547210 +0.000000 0.707107 -0.707107 +-0.054535 0.709075 -0.703021 +-0.043829 0.832556 -0.552205 +0.000000 0.707107 -0.707107 +-0.062982 0.558699 -0.826975 +-0.054535 0.709075 -0.703021 +0.000000 0.547210 -0.836995 +-0.062982 0.558699 -0.826975 +0.000000 0.707107 -0.707107 +0.000000 0.547210 -0.836995 +-0.069101 0.386572 -0.919667 +-0.062982 0.558699 -0.826975 +0.000000 0.368095 -0.929788 +-0.069101 0.386572 -0.919667 +0.000000 0.547210 -0.836995 +0.000000 0.368095 -0.929788 +-0.072816 0.199074 -0.977276 +-0.069101 0.386572 -0.919667 +0.000000 0.181963 -0.983305 +-0.072816 0.199074 -0.977276 +0.000000 0.368095 -0.929788 +0.000000 0.181963 -0.983305 +-0.074086 0.003105 -0.997247 +-0.072816 0.199074 -0.977276 +0.000000 0.204909 -0.978781 +0.000000 0.005236 -0.999986 +0.000000 0.005236 -0.999986 +0.000000 0.000000 -1.000000 +0.000000 0.204909 -0.978781 +0.000000 0.000000 -1.000000 +0.000000 0.005236 -0.999986 +0.000000 0.204909 -0.978781 +0.000000 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 0.978781 -0.204909 +0.000000 1.000000 0.000000 +0.000000 0.978781 -0.204909 +0.000000 0.978781 -0.204909 +0.000000 1.000000 0.000000 +0.000000 0.917742 -0.397177 +0.000000 0.978781 -0.204909 +0.000000 0.978781 -0.204909 +0.000000 0.917742 -0.397177 +0.000000 0.917742 -0.397177 +0.000000 0.978781 -0.204909 +0.000000 0.917742 -0.397177 +0.000000 0.823969 -0.566635 +0.000000 0.917742 -0.397177 +0.000000 0.823969 -0.566635 +0.000000 0.823969 -0.566635 +0.000000 0.917742 -0.397177 +0.000000 0.707107 -0.707107 +0.000000 0.823969 -0.566635 +0.000000 0.823969 -0.566635 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.823969 -0.566635 +0.000000 0.204909 -0.978781 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.204909 -0.978781 +0.000000 0.005236 -0.999986 +0.000000 0.000000 -1.000000 +0.000000 0.566635 -0.823969 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.566635 -0.823969 +0.000000 0.566635 -0.823969 +0.000000 0.707107 -0.707107 +0.000000 0.397177 -0.917742 +0.000000 0.566635 -0.823969 +0.000000 0.566635 -0.823969 +0.000000 0.397177 -0.917742 +0.000000 0.397177 -0.917742 +0.000000 0.566635 -0.823969 +0.000000 0.204909 -0.978781 +0.000000 0.397177 -0.917742 +0.000000 0.397177 -0.917742 +0.000000 0.204909 -0.978781 +0.000000 0.204909 -0.978781 +0.000000 0.397177 -0.917742 +0.000000 0.005236 -0.999986 +0.000000 0.204909 -0.978781 +0.000000 0.204909 -0.978781 +0.000000 0.181963 -0.983305 +0.074086 0.003105 -0.997247 +0.000000 0.000000 -1.000000 +0.016351 0.980731 -0.194676 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.016351 0.980731 -0.194676 +0.000000 0.983305 -0.181963 +0.000000 1.000000 0.000000 +0.016351 0.980731 -0.194676 +0.000000 0.929788 -0.368095 +0.000000 0.983305 -0.181963 +0.031084 0.923918 -0.381325 +0.000000 0.929788 -0.368095 +0.016351 0.980731 -0.194676 +0.031084 0.923918 -0.381325 +0.000000 0.836995 -0.547210 +0.000000 0.929788 -0.368095 +0.043893 0.831978 -0.553069 +0.000000 0.836995 -0.547210 +0.031084 0.923918 -0.381325 +0.043893 0.831978 -0.553069 +0.000000 0.707107 -0.707107 +0.000000 0.836995 -0.547210 +0.054570 0.708569 -0.703528 +0.000000 0.707107 -0.707107 +0.043893 0.831978 -0.553069 +0.063016 0.557871 -0.827532 +0.000000 0.707107 -0.707107 +0.054570 0.708569 -0.703528 +0.063016 0.557871 -0.827532 +0.000000 0.547210 -0.836995 +0.000000 0.707107 -0.707107 +0.069126 0.385373 -0.920168 +0.000000 0.547210 -0.836995 +0.063016 0.557871 -0.827532 +0.069126 0.385373 -0.920168 +0.000000 0.368095 -0.929788 +0.000000 0.547210 -0.836995 +0.072819 0.198437 -0.977405 +0.000000 0.368095 -0.929788 +0.069126 0.385373 -0.920168 +0.072819 0.198437 -0.977405 +0.000000 0.181963 -0.983305 +0.000000 0.368095 -0.929788 +0.074086 0.003105 -0.997247 +0.000000 0.181963 -0.983305 +0.072819 0.198437 -0.977405 +0.997323 -0.041800 0.059997 +0.975749 -0.218887 0.001553 +0.999123 -0.041876 0.000000 +0.000000 -0.999962 0.008727 +0.189449 -0.981650 0.021721 +0.000000 -0.999962 0.008727 +0.177842 -0.984022 0.008522 +0.189449 -0.981650 0.021721 +0.000000 -0.999962 0.008727 +0.359510 -0.933107 0.008012 +0.189449 -0.981650 0.021721 +0.177842 -0.984022 0.008522 +0.359510 -0.933107 0.008012 +0.371590 -0.927815 0.032855 +0.189449 -0.981650 0.021721 +0.534680 -0.845024 0.007179 +0.371590 -0.927815 0.032855 +0.359510 -0.933107 0.008012 +0.534680 -0.845024 0.007179 +0.540738 -0.840137 0.042100 +0.371590 -0.927815 0.032855 +0.692144 -0.721734 0.006045 +0.540738 -0.840137 0.042100 +0.534680 -0.845024 0.007179 +0.692144 -0.721734 0.006045 +0.689995 -0.722126 0.049399 +0.540738 -0.840137 0.042100 +0.692144 -0.721734 0.006045 +0.814187 -0.578011 0.054796 +0.689995 -0.722126 0.049399 +0.821924 -0.569578 0.004670 +0.814187 -0.578011 0.054796 +0.692144 -0.721734 0.006045 +0.821924 -0.569578 0.004670 +0.909003 -0.412687 0.058341 +0.814187 -0.578011 0.054796 +0.917268 -0.398257 0.003140 +0.909003 -0.412687 0.058341 +0.821924 -0.569578 0.004670 +0.917268 -0.398257 0.003140 +0.970887 -0.231886 0.060064 +0.909003 -0.412687 0.058341 +0.975749 -0.218887 0.001553 +0.970887 -0.231886 0.060064 +0.917268 -0.398257 0.003140 +0.975749 -0.218887 0.001553 +0.997323 -0.041800 0.059997 +0.970887 -0.231886 0.060064 +0.999123 -0.041876 0.000000 +0.975749 -0.218887 0.001553 +0.999123 -0.041876 0.000000 +0.177842 -0.984022 0.008522 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.177842 -0.984022 0.008522 +0.184367 -0.982821 0.008510 +0.000000 -0.999962 0.008727 +0.359510 -0.933107 0.008012 +0.184367 -0.982821 0.008510 +0.177842 -0.984022 0.008522 +0.359510 -0.933107 0.008012 +0.377871 -0.925824 0.007941 +0.184367 -0.982821 0.008510 +0.534680 -0.845024 0.007179 +0.377871 -0.925824 0.007941 +0.359510 -0.933107 0.008012 +0.534680 -0.845024 0.007179 +0.549255 -0.835625 0.007091 +0.377871 -0.925824 0.007941 +0.692144 -0.721734 0.006045 +0.549255 -0.835625 0.007091 +0.534680 -0.845024 0.007179 +0.692144 -0.721734 0.006045 +0.692144 -0.721734 0.006045 +0.549255 -0.835625 0.007091 +0.821924 -0.569578 0.004670 +0.692144 -0.721734 0.006045 +0.692144 -0.721734 0.006045 +0.821924 -0.569578 0.004670 +0.811922 -0.583746 0.004797 +0.692144 -0.721734 0.006045 +0.821924 -0.569578 0.004670 +0.909223 -0.416296 0.003300 +0.811922 -0.583746 0.004797 +0.917268 -0.398257 0.003140 +0.909223 -0.416296 0.003300 +0.821924 -0.569578 0.004670 +0.917268 -0.398257 0.003140 +0.974275 -0.225356 0.001610 +0.909223 -0.416296 0.003300 +0.975749 -0.218887 0.001553 +0.974275 -0.225356 0.001610 +0.917268 -0.398257 0.003140 +0.975749 -0.218887 0.001553 +0.999123 -0.041876 0.000000 +0.974275 -0.225356 0.001610 +-0.975749 -0.218887 0.001553 +-0.997323 -0.041800 0.059997 +-0.999123 -0.041876 0.000000 +-0.190128 -0.981518 0.021765 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +-0.190128 -0.981518 0.021765 +-0.177842 -0.984022 0.008522 +0.000000 -0.999962 0.008727 +-0.190128 -0.981518 0.021765 +-0.359510 -0.933107 0.008012 +-0.177842 -0.984022 0.008522 +-0.372715 -0.927362 0.032921 +-0.359510 -0.933107 0.008012 +-0.190128 -0.981518 0.021765 +-0.372715 -0.927362 0.032921 +-0.534680 -0.845024 0.007179 +-0.359510 -0.933107 0.008012 +-0.541456 -0.839673 0.042139 +-0.534680 -0.845024 0.007179 +-0.372715 -0.927362 0.032921 +-0.541456 -0.839673 0.042139 +-0.692144 -0.721734 0.006045 +-0.534680 -0.845024 0.007179 +-0.690461 -0.721680 0.049420 +-0.692144 -0.721734 0.006045 +-0.541456 -0.839673 0.042139 +-0.814658 -0.577346 0.054812 +-0.692144 -0.721734 0.006045 +-0.690461 -0.721680 0.049420 +-0.814658 -0.577346 0.054812 +-0.821924 -0.569578 0.004670 +-0.692144 -0.721734 0.006045 +-0.909486 -0.411619 0.058349 +-0.821924 -0.569578 0.004670 +-0.814658 -0.577346 0.054812 +-0.909486 -0.411619 0.058349 +-0.917268 -0.398257 0.003140 +-0.821924 -0.569578 0.004670 +-0.971042 -0.231234 0.060062 +-0.917268 -0.398257 0.003140 +-0.909486 -0.411619 0.058349 +-0.971042 -0.231234 0.060062 +-0.975749 -0.218887 0.001553 +-0.917268 -0.398257 0.003140 +-0.997323 -0.041800 0.059997 +-0.975749 -0.218887 0.001553 +-0.971042 -0.231234 0.060062 +-0.975749 -0.218887 0.001553 +-0.999123 -0.041876 0.000000 +-0.999123 -0.041876 0.000000 +-0.184367 -0.982821 0.008510 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +-0.184367 -0.982821 0.008510 +-0.177842 -0.984022 0.008522 +0.000000 -0.999962 0.008727 +-0.184367 -0.982821 0.008510 +-0.359510 -0.933107 0.008012 +-0.177842 -0.984022 0.008522 +-0.377871 -0.925824 0.007941 +-0.359510 -0.933107 0.008012 +-0.184367 -0.982821 0.008510 +-0.377871 -0.925824 0.007941 +-0.534680 -0.845024 0.007179 +-0.359510 -0.933107 0.008012 +-0.549255 -0.835625 0.007091 +-0.534680 -0.845024 0.007179 +-0.377871 -0.925824 0.007941 +-0.549255 -0.835625 0.007091 +-0.692144 -0.721734 0.006045 +-0.534680 -0.845024 0.007179 +-0.692144 -0.721734 0.006045 +-0.692144 -0.721734 0.006045 +-0.549255 -0.835625 0.007091 +-0.692144 -0.721734 0.006045 +-0.821924 -0.569578 0.004670 +-0.692144 -0.721734 0.006045 +-0.811922 -0.583746 0.004797 +-0.821924 -0.569578 0.004670 +-0.692144 -0.721734 0.006045 +-0.909223 -0.416296 0.003300 +-0.821924 -0.569578 0.004670 +-0.811922 -0.583746 0.004797 +-0.909223 -0.416296 0.003300 +-0.917268 -0.398257 0.003140 +-0.821924 -0.569578 0.004670 +-0.974275 -0.225356 0.001610 +-0.917268 -0.398257 0.003140 +-0.909223 -0.416296 0.003300 +-0.974275 -0.225356 0.001610 +-0.975749 -0.218887 0.001553 +-0.917268 -0.398257 0.003140 +-0.999123 -0.041876 0.000000 +-0.975749 -0.218887 0.001553 +-0.974275 -0.225356 0.001610 +-0.181949 -0.983255 0.010169 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +-0.999962 0.000000 0.008727 +-0.983255 -0.181949 0.010169 +-0.999962 0.000000 0.008727 +-0.983255 -0.181949 0.010169 +-0.983255 -0.181949 0.010169 +-0.999962 0.000000 0.008727 +-0.983255 -0.181949 0.010169 +-0.929731 -0.368065 0.011326 +-0.983255 -0.181949 0.010169 +-0.929731 -0.368065 0.011326 +-0.929731 -0.368065 0.011326 +-0.983255 -0.181949 0.010169 +-0.929731 -0.368065 0.011326 +-0.836937 -0.547166 0.012079 +-0.929731 -0.368065 0.011326 +-0.836937 -0.547166 0.012079 +-0.836937 -0.547166 0.012079 +-0.929731 -0.368065 0.011326 +-0.836937 -0.547166 0.012079 +-0.776296 -0.630249 0.012275 +-0.836937 -0.547166 0.012079 +-0.776296 -0.630249 0.012275 +-0.776296 -0.630249 0.012275 +-0.836937 -0.547166 0.012079 +-0.776296 -0.630249 0.012275 +-0.707053 -0.707053 0.012341 +-0.776296 -0.630249 0.012275 +-0.707053 -0.707053 0.012341 +-0.707053 -0.707053 0.012341 +-0.776296 -0.630249 0.012275 +-0.630249 -0.776296 0.012275 +-0.707053 -0.707053 0.012341 +-0.707053 -0.707053 0.012341 +-0.630249 -0.776296 0.012275 +-0.630249 -0.776296 0.012275 +-0.707053 -0.707053 0.012341 +-0.547166 -0.836937 0.012079 +-0.630249 -0.776296 0.012275 +-0.630249 -0.776296 0.012275 +-0.547166 -0.836937 0.012079 +-0.547166 -0.836937 0.012079 +-0.630249 -0.776296 0.012275 +-0.368065 -0.929731 0.011326 +-0.547166 -0.836937 0.012079 +-0.547166 -0.836937 0.012079 +-0.368065 -0.929731 0.011326 +-0.368065 -0.929731 0.011326 +-0.547166 -0.836937 0.012079 +-0.181949 -0.983255 0.010169 +-0.368065 -0.929731 0.011326 +-0.368065 -0.929731 0.011326 +-0.181949 -0.983255 0.010169 +-0.181949 -0.983255 0.010169 +-0.368065 -0.929731 0.011326 +0.000000 -0.999962 0.008727 +-0.181949 -0.983255 0.010169 +-0.181949 -0.983255 0.010169 +-0.181949 -0.983255 0.010169 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +-0.999962 0.000000 0.008727 +-0.983255 -0.181949 0.010169 +-0.999962 0.000000 0.008727 +-0.983255 -0.181949 0.010169 +-0.983255 -0.181949 0.010169 +-0.999962 0.000000 0.008727 +-0.983255 -0.181949 0.010169 +-0.929731 -0.368065 0.011326 +-0.983255 -0.181949 0.010169 +-0.929731 -0.368065 0.011326 +-0.929731 -0.368065 0.011326 +-0.983255 -0.181949 0.010169 +-0.929731 -0.368065 0.011326 +-0.836937 -0.547166 0.012079 +-0.929731 -0.368065 0.011326 +-0.836937 -0.547166 0.012079 +-0.836937 -0.547166 0.012079 +-0.929731 -0.368065 0.011326 +-0.836937 -0.547166 0.012079 +-0.776296 -0.630249 0.012275 +-0.836937 -0.547166 0.012079 +-0.776296 -0.630249 0.012275 +-0.776296 -0.630249 0.012275 +-0.836937 -0.547166 0.012079 +-0.776296 -0.630249 0.012275 +-0.707053 -0.707053 0.012341 +-0.776296 -0.630249 0.012275 +-0.707053 -0.707053 0.012341 +-0.707053 -0.707053 0.012341 +-0.776296 -0.630249 0.012275 +-0.630249 -0.776296 0.012275 +-0.707053 -0.707053 0.012341 +-0.707053 -0.707053 0.012341 +-0.630249 -0.776296 0.012275 +-0.630249 -0.776296 0.012275 +-0.707053 -0.707053 0.012341 +-0.547166 -0.836937 0.012079 +-0.630249 -0.776296 0.012275 +-0.630249 -0.776296 0.012275 +-0.547166 -0.836937 0.012079 +-0.547166 -0.836937 0.012079 +-0.630249 -0.776296 0.012275 +-0.368065 -0.929731 0.011326 +-0.547166 -0.836937 0.012079 +-0.547166 -0.836937 0.012079 +-0.368065 -0.929731 0.011326 +-0.368065 -0.929731 0.011326 +-0.547166 -0.836937 0.012079 +-0.181949 -0.983255 0.010169 +-0.368065 -0.929731 0.011326 +-0.368065 -0.929731 0.011326 +-0.181949 -0.983255 0.010169 +-0.181949 -0.983255 0.010169 +-0.368065 -0.929731 0.011326 +0.000000 -0.999962 0.008727 +-0.181949 -0.983255 0.010169 +-0.181949 -0.983255 0.010169 +0.983255 -0.181949 0.010169 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.000000 -0.999962 0.008727 +0.181949 -0.983255 0.010169 +0.000000 -0.999962 0.008727 +0.181949 -0.983255 0.010169 +0.181949 -0.983255 0.010169 +0.000000 -0.999962 0.008727 +0.181949 -0.983255 0.010169 +0.368065 -0.929731 0.011326 +0.181949 -0.983255 0.010169 +0.368065 -0.929731 0.011326 +0.368065 -0.929731 0.011326 +0.181949 -0.983255 0.010169 +0.368065 -0.929731 0.011326 +0.547166 -0.836937 0.012079 +0.368065 -0.929731 0.011326 +0.547166 -0.836937 0.012079 +0.547166 -0.836937 0.012079 +0.368065 -0.929731 0.011326 +0.547166 -0.836937 0.012079 +0.630249 -0.776296 0.012275 +0.547166 -0.836937 0.012079 +0.630249 -0.776296 0.012275 +0.630249 -0.776296 0.012275 +0.547166 -0.836937 0.012079 +0.630249 -0.776296 0.012275 +0.707053 -0.707053 0.012341 +0.630249 -0.776296 0.012275 +0.707053 -0.707053 0.012341 +0.707053 -0.707053 0.012341 +0.630249 -0.776296 0.012275 +0.776296 -0.630249 0.012275 +0.707053 -0.707053 0.012341 +0.707053 -0.707053 0.012341 +0.776296 -0.630249 0.012275 +0.776296 -0.630249 0.012275 +0.707053 -0.707053 0.012341 +0.836937 -0.547166 0.012079 +0.776296 -0.630249 0.012275 +0.776296 -0.630249 0.012275 +0.836937 -0.547166 0.012079 +0.836937 -0.547166 0.012079 +0.776296 -0.630249 0.012275 +0.929731 -0.368065 0.011326 +0.836937 -0.547166 0.012079 +0.836937 -0.547166 0.012079 +0.929731 -0.368065 0.011326 +0.929731 -0.368065 0.011326 +0.836937 -0.547166 0.012079 +0.983255 -0.181949 0.010169 +0.929731 -0.368065 0.011326 +0.929731 -0.368065 0.011326 +0.983255 -0.181949 0.010169 +0.983255 -0.181949 0.010169 +0.929731 -0.368065 0.011326 +0.999962 0.000000 0.008727 +0.983255 -0.181949 0.010169 +0.983255 -0.181949 0.010169 +0.000000 1.000000 0.000000 +-0.193915 0.981018 0.000000 +0.000000 1.000000 0.000000 +-0.980448 0.196777 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.980448 0.196777 0.000000 +-0.978781 0.204909 0.000000 +-1.000000 0.000000 0.000000 +-0.923090 0.384584 0.000000 +-0.978781 0.204909 0.000000 +-0.980448 0.196777 0.000000 +-0.923090 0.384584 0.000000 +-0.917742 0.397177 0.000000 +-0.978781 0.204909 0.000000 +-0.830205 0.557459 0.000000 +-0.917742 0.397177 0.000000 +-0.923090 0.384584 0.000000 +-0.830205 0.557459 0.000000 +-0.823969 0.566635 0.000000 +-0.917742 0.397177 0.000000 +-0.705296 0.708913 0.000000 +-0.823969 0.566635 0.000000 +-0.830205 0.557459 0.000000 +-0.705296 0.708913 0.000000 +-0.707107 0.707107 0.000000 +-0.823969 0.566635 0.000000 +-0.705296 0.708913 0.000000 +-0.566635 0.823969 0.000000 +-0.707107 0.707107 0.000000 +-0.553562 0.832808 0.000000 +-0.566635 0.823969 0.000000 +-0.705296 0.708913 0.000000 +-0.553562 0.832808 0.000000 +-0.397177 0.917742 0.000000 +-0.566635 0.823969 0.000000 +-0.380529 0.924769 0.000000 +-0.397177 0.917742 0.000000 +-0.553562 0.832808 0.000000 +-0.380529 0.924769 0.000000 +-0.204909 0.978781 0.000000 +-0.397177 0.917742 0.000000 +-0.193915 0.981018 0.000000 +-0.204909 0.978781 0.000000 +-0.380529 0.924769 0.000000 +-0.193915 0.981018 0.000000 +0.000000 1.000000 0.000000 +-0.204909 0.978781 0.000000 +0.983255 -0.181949 0.010169 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.000000 -0.999962 0.008727 +0.181949 -0.983255 0.010169 +0.000000 -0.999962 0.008727 +0.181949 -0.983255 0.010169 +0.181949 -0.983255 0.010169 +0.000000 -0.999962 0.008727 +0.181949 -0.983255 0.010169 +0.368065 -0.929731 0.011326 +0.181949 -0.983255 0.010169 +0.368065 -0.929731 0.011326 +0.368065 -0.929731 0.011326 +0.181949 -0.983255 0.010169 +0.368065 -0.929731 0.011326 +0.547166 -0.836937 0.012079 +0.368065 -0.929731 0.011326 +0.547166 -0.836937 0.012079 +0.547166 -0.836937 0.012079 +0.368065 -0.929731 0.011326 +0.547166 -0.836937 0.012079 +0.630249 -0.776296 0.012275 +0.547166 -0.836937 0.012079 +0.630249 -0.776296 0.012275 +0.630249 -0.776296 0.012275 +0.547166 -0.836937 0.012079 +0.630249 -0.776296 0.012275 +0.707053 -0.707053 0.012341 +0.630249 -0.776296 0.012275 +0.707053 -0.707053 0.012341 +0.707053 -0.707053 0.012341 +0.630249 -0.776296 0.012275 +0.776296 -0.630249 0.012275 +0.707053 -0.707053 0.012341 +0.707053 -0.707053 0.012341 +0.776296 -0.630249 0.012275 +0.776296 -0.630249 0.012275 +0.707053 -0.707053 0.012341 +0.836937 -0.547166 0.012079 +0.776296 -0.630249 0.012275 +0.776296 -0.630249 0.012275 +0.836937 -0.547166 0.012079 +0.836937 -0.547166 0.012079 +0.776296 -0.630249 0.012275 +0.929731 -0.368065 0.011326 +0.836937 -0.547166 0.012079 +0.836937 -0.547166 0.012079 +0.929731 -0.368065 0.011326 +0.929731 -0.368065 0.011326 +0.836937 -0.547166 0.012079 +0.983255 -0.181949 0.010169 +0.929731 -0.368065 0.011326 +0.929731 -0.368065 0.011326 +0.983255 -0.181949 0.010169 +0.983255 -0.181949 0.010169 +0.929731 -0.368065 0.011326 +0.999962 0.000000 0.008727 +0.983255 -0.181949 0.010169 +0.983255 -0.181949 0.010169 +0.983255 0.181949 -0.010169 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.000000 0.999962 -0.008727 +0.181949 0.983255 -0.010169 +0.000000 0.999962 -0.008727 +0.181949 0.983255 -0.010169 +0.181949 0.983255 -0.010169 +0.000000 0.999962 -0.008727 +0.181949 0.983255 -0.010169 +0.368065 0.929731 -0.011326 +0.181949 0.983255 -0.010169 +0.368065 0.929731 -0.011326 +0.368065 0.929731 -0.011326 +0.181949 0.983255 -0.010169 +0.368065 0.929731 -0.011326 +0.547166 0.836937 -0.012079 +0.368065 0.929731 -0.011326 +0.547166 0.836937 -0.012079 +0.547166 0.836937 -0.012079 +0.368065 0.929731 -0.011326 +0.547166 0.836937 -0.012079 +0.630249 0.776296 -0.012275 +0.547166 0.836937 -0.012079 +0.630249 0.776296 -0.012275 +0.630249 0.776296 -0.012275 +0.547166 0.836937 -0.012079 +0.630249 0.776296 -0.012275 +0.707053 0.707053 -0.012341 +0.630249 0.776296 -0.012275 +0.707053 0.707053 -0.012341 +0.707053 0.707053 -0.012341 +0.630249 0.776296 -0.012275 +0.776296 0.630249 -0.012275 +0.707053 0.707053 -0.012341 +0.707053 0.707053 -0.012341 +0.776296 0.630249 -0.012275 +0.776296 0.630249 -0.012275 +0.707053 0.707053 -0.012341 +0.836937 0.547166 -0.012079 +0.776296 0.630249 -0.012275 +0.776296 0.630249 -0.012275 +0.836937 0.547166 -0.012079 +0.836937 0.547166 -0.012079 +0.776296 0.630249 -0.012275 +0.929731 0.368065 -0.011326 +0.836937 0.547166 -0.012079 +0.836937 0.547166 -0.012079 +0.929731 0.368065 -0.011326 +0.929731 0.368065 -0.011326 +0.836937 0.547166 -0.012079 +0.983255 0.181949 -0.010169 +0.929731 0.368065 -0.011326 +0.929731 0.368065 -0.011326 +0.983255 0.181949 -0.010169 +0.983255 0.181949 -0.010169 +0.929731 0.368065 -0.011326 +0.999962 0.000000 -0.008727 +0.983255 0.181949 -0.010169 +0.983255 0.181949 -0.010169 +-0.181944 0.983256 -0.010169 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +-0.999962 0.000000 -0.008727 +-0.983249 0.181984 -0.010169 +-0.999962 0.000000 -0.008727 +-0.983255 0.181949 -0.010169 +-0.983249 0.181984 -0.010169 +-0.999962 0.000000 -0.008727 +-0.929731 0.368065 -0.011326 +-0.983249 0.181984 -0.010169 +-0.983255 0.181949 -0.010169 +-0.929731 0.368065 -0.011326 +-0.929719 0.368095 -0.011326 +-0.983249 0.181984 -0.010169 +-0.836937 0.547166 -0.012079 +-0.929719 0.368095 -0.011326 +-0.929731 0.368065 -0.011326 +-0.836937 0.547166 -0.012079 +-0.836922 0.547189 -0.012079 +-0.929719 0.368095 -0.011326 +-0.776296 0.630249 -0.012275 +-0.836922 0.547189 -0.012079 +-0.836937 0.547166 -0.012079 +-0.776296 0.630249 -0.012275 +-0.776280 0.630268 -0.012275 +-0.836922 0.547189 -0.012079 +-0.707053 0.707053 -0.012341 +-0.776280 0.630268 -0.012275 +-0.776296 0.630249 -0.012275 +-0.707053 0.707053 -0.012341 +-0.707037 0.707069 -0.012341 +-0.776280 0.630268 -0.012275 +-0.630249 0.776296 -0.012275 +-0.707037 0.707069 -0.012341 +-0.707053 0.707053 -0.012341 +-0.630249 0.776296 -0.012275 +-0.630234 0.776308 -0.012275 +-0.707037 0.707069 -0.012341 +-0.547166 0.836937 -0.012079 +-0.630234 0.776308 -0.012275 +-0.630249 0.776296 -0.012275 +-0.547166 0.836937 -0.012079 +-0.547152 0.836946 -0.012079 +-0.630234 0.776308 -0.012275 +-0.368065 0.929731 -0.011326 +-0.547152 0.836946 -0.012079 +-0.547166 0.836937 -0.012079 +-0.368065 0.929731 -0.011326 +-0.368055 0.929735 -0.011326 +-0.547152 0.836946 -0.012079 +-0.181949 0.983255 -0.010169 +-0.368055 0.929735 -0.011326 +-0.368065 0.929731 -0.011326 +-0.181949 0.983255 -0.010169 +-0.181944 0.983256 -0.010169 +-0.368055 0.929735 -0.011326 +0.000000 0.999962 -0.008727 +-0.181944 0.983256 -0.010169 +-0.181949 0.983255 -0.010169 +-0.999962 0.000000 -0.008727 +-0.985829 -0.167452 -0.010065 +-0.999962 0.000000 -0.008727 +0.000000 -0.999962 -0.008727 +-0.181984 -0.983249 -0.010169 +0.000000 -0.999962 -0.008727 +-0.144334 -0.989479 -0.009895 +-0.181984 -0.983249 -0.010169 +0.000000 -0.999962 -0.008727 +-0.307995 -0.951325 -0.010990 +-0.181984 -0.983249 -0.010169 +-0.144334 -0.989479 -0.009895 +-0.307995 -0.951325 -0.010990 +-0.368095 -0.929719 -0.011326 +-0.181984 -0.983249 -0.010169 +-0.470275 -0.882441 -0.011805 +-0.368095 -0.929719 -0.011326 +-0.307995 -0.951325 -0.010990 +-0.470275 -0.882441 -0.011805 +-0.547189 -0.836922 -0.012079 +-0.368095 -0.929719 -0.011326 +-0.622630 -0.782420 -0.012262 +-0.547189 -0.836922 -0.012079 +-0.470275 -0.882441 -0.011805 +-0.622630 -0.782420 -0.012262 +-0.630268 -0.776280 -0.012275 +-0.547189 -0.836922 -0.012079 +-0.756365 -0.654033 -0.012308 +-0.630268 -0.776280 -0.012275 +-0.622630 -0.782420 -0.012262 +-0.756365 -0.654033 -0.012308 +-0.707069 -0.707037 -0.012341 +-0.630268 -0.776280 -0.012275 +-0.756365 -0.654033 -0.012308 +-0.776308 -0.630234 -0.012275 +-0.707069 -0.707037 -0.012341 +-0.864106 -0.503169 -0.011932 +-0.776308 -0.630234 -0.012275 +-0.756365 -0.654033 -0.012308 +-0.864106 -0.503169 -0.011932 +-0.836946 -0.547152 -0.012079 +-0.776308 -0.630234 -0.012275 +-0.864106 -0.503169 -0.011932 +-0.929735 -0.368055 -0.011326 +-0.836946 -0.547152 -0.012079 +-0.941090 -0.337973 -0.011162 +-0.929735 -0.368055 -0.011326 +-0.864106 -0.503169 -0.011932 +-0.941090 -0.337973 -0.011162 +-0.983256 -0.181944 -0.010169 +-0.929735 -0.368055 -0.011326 +-0.985829 -0.167452 -0.010065 +-0.983256 -0.181944 -0.010169 +-0.941090 -0.337973 -0.011162 +-0.985829 -0.167452 -0.010065 +-0.999962 0.000000 -0.008727 +-0.983256 -0.181944 -0.010169 +0.000000 -0.999962 -0.008727 +0.144334 -0.989479 -0.009895 +0.000000 -0.999962 -0.008727 +0.999962 0.000000 -0.008727 +0.983249 -0.181984 -0.010169 +0.999962 0.000000 -0.008727 +0.985829 -0.167452 -0.010065 +0.983249 -0.181984 -0.010169 +0.999962 0.000000 -0.008727 +0.941090 -0.337973 -0.011162 +0.983249 -0.181984 -0.010169 +0.985829 -0.167452 -0.010065 +0.941090 -0.337973 -0.011162 +0.929719 -0.368095 -0.011326 +0.983249 -0.181984 -0.010169 +0.864106 -0.503169 -0.011932 +0.929719 -0.368095 -0.011326 +0.941090 -0.337973 -0.011162 +0.864106 -0.503169 -0.011932 +0.836922 -0.547189 -0.012079 +0.929719 -0.368095 -0.011326 +0.756365 -0.654033 -0.012308 +0.836922 -0.547189 -0.012079 +0.864106 -0.503169 -0.011932 +0.756365 -0.654033 -0.012308 +0.776280 -0.630268 -0.012275 +0.836922 -0.547189 -0.012079 +0.756365 -0.654033 -0.012308 +0.707037 -0.707069 -0.012341 +0.776280 -0.630268 -0.012275 +0.622630 -0.782420 -0.012262 +0.707037 -0.707069 -0.012341 +0.756365 -0.654033 -0.012308 +0.622630 -0.782420 -0.012262 +0.630234 -0.776308 -0.012275 +0.707037 -0.707069 -0.012341 +0.622630 -0.782420 -0.012262 +0.547152 -0.836946 -0.012079 +0.630234 -0.776308 -0.012275 +0.470275 -0.882441 -0.011805 +0.547152 -0.836946 -0.012079 +0.622630 -0.782420 -0.012262 +0.470275 -0.882441 -0.011805 +0.368055 -0.929735 -0.011326 +0.547152 -0.836946 -0.012079 +0.307995 -0.951325 -0.010990 +0.368055 -0.929735 -0.011326 +0.470275 -0.882441 -0.011805 +0.307995 -0.951325 -0.010990 +0.181944 -0.983256 -0.010169 +0.368055 -0.929735 -0.011326 +0.144334 -0.989479 -0.009895 +0.181944 -0.983256 -0.010169 +0.307995 -0.951325 -0.010990 +0.144334 -0.989479 -0.009895 +0.000000 -0.999962 -0.008727 +0.181944 -0.983256 -0.010169 +0.000000 0.405548 -0.914074 +0.000000 0.527685 -0.849440 +0.000000 0.527685 -0.849440 +0.000000 0.137854 -0.990453 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.137854 -0.990453 +0.000000 0.137854 -0.990453 +0.000000 0.000000 -1.000000 +0.000000 0.274372 -0.961624 +0.000000 0.137854 -0.990453 +0.000000 0.137854 -0.990453 +0.000000 0.274372 -0.961624 +0.000000 0.274372 -0.961624 +0.000000 0.137854 -0.990453 +0.000000 0.405548 -0.914074 +0.000000 0.274372 -0.961624 +0.000000 0.274372 -0.961624 +0.000000 0.405548 -0.914074 +0.000000 0.405548 -0.914074 +0.000000 0.274372 -0.961624 +0.000000 0.527685 -0.849440 +0.000000 0.405548 -0.914074 +0.000000 0.405548 -0.914074 +0.000000 -0.994563 -0.104138 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.000000 0.527685 -0.849440 +0.000000 0.428488 -0.903548 +0.000000 0.527685 -0.849440 +0.000000 0.428488 -0.903548 +0.000000 0.428488 -0.903548 +0.000000 0.527685 -0.849440 +0.000000 0.317178 -0.948366 +0.000000 0.428488 -0.903548 +0.000000 0.428488 -0.903548 +0.000000 0.317178 -0.948366 +0.000000 0.317178 -0.948366 +0.000000 0.428488 -0.903548 +0.000000 0.194692 -0.980864 +0.000000 0.317178 -0.948366 +0.000000 0.317178 -0.948366 +0.000000 0.194692 -0.980864 +0.000000 0.194692 -0.980864 +0.000000 0.317178 -0.948366 +0.000000 0.062871 -0.998022 +0.000000 0.194692 -0.980864 +0.000000 0.194692 -0.980864 +0.000000 0.062871 -0.998022 +0.000000 0.062871 -0.998022 +0.000000 0.194692 -0.980864 +0.000000 -0.075483 -0.997147 +0.000000 0.062871 -0.998022 +0.000000 0.062871 -0.998022 +0.000000 -0.075483 -0.997147 +0.000000 -0.075483 -0.997147 +0.000000 0.062871 -0.998022 +0.000000 -0.216667 -0.976246 +0.000000 -0.075483 -0.997147 +0.000000 -0.075483 -0.997147 +0.000000 -0.216667 -0.976246 +0.000000 -0.216667 -0.976246 +0.000000 -0.075483 -0.997147 +0.000000 -0.356313 -0.934367 +0.000000 -0.216667 -0.976246 +0.000000 -0.216667 -0.976246 +0.000000 -0.356313 -0.934367 +0.000000 -0.356313 -0.934367 +0.000000 -0.216667 -0.976246 +0.000000 -0.489769 -0.871852 +0.000000 -0.356313 -0.934367 +0.000000 -0.356313 -0.934367 +0.000000 -0.489769 -0.871852 +0.000000 -0.489769 -0.871852 +0.000000 -0.356313 -0.934367 +0.000000 -0.612589 -0.790402 +0.000000 -0.489769 -0.871852 +0.000000 -0.489769 -0.871852 +0.000000 -0.612589 -0.790402 +0.000000 -0.612589 -0.790402 +0.000000 -0.489769 -0.871852 +0.000000 -0.721005 -0.692930 +0.000000 -0.612589 -0.790402 +0.000000 -0.612589 -0.790402 +0.000000 -0.721005 -0.692930 +0.000000 -0.721005 -0.692930 +0.000000 -0.612589 -0.790402 +0.000000 -0.812306 -0.583231 +0.000000 -0.721005 -0.692930 +0.000000 -0.721005 -0.692930 +0.000000 -0.812306 -0.583231 +0.000000 -0.812306 -0.583231 +0.000000 -0.721005 -0.692930 +0.000000 -0.885032 -0.465530 +0.000000 -0.812306 -0.583231 +0.000000 -0.812306 -0.583231 +0.000000 -0.885032 -0.465530 +0.000000 -0.885032 -0.465530 +0.000000 -0.812306 -0.583231 +0.000000 -0.938960 -0.344027 +0.000000 -0.885032 -0.465530 +0.000000 -0.885032 -0.465530 +0.000000 -0.938960 -0.344027 +0.000000 -0.938960 -0.344027 +0.000000 -0.885032 -0.465530 +0.000000 -0.974929 -0.222516 +0.000000 -0.938960 -0.344027 +0.000000 -0.938960 -0.344027 +0.000000 -0.974929 -0.222516 +0.000000 -0.974929 -0.222516 +0.000000 -0.938960 -0.344027 +0.000000 -0.994563 -0.104138 +0.000000 -0.974929 -0.222516 +0.000000 -0.974929 -0.222516 +0.000000 -0.994563 -0.104138 +0.000000 -0.994563 -0.104138 +0.000000 -0.974929 -0.222516 +0.000000 -0.999962 0.008727 +0.000000 -0.994563 -0.104138 +0.000000 -0.994563 -0.104138 +-0.181949 0.983255 -0.010169 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +-0.999962 0.000000 -0.008727 +-0.983255 0.181949 -0.010169 +-0.999962 0.000000 -0.008727 +-0.983255 0.181949 -0.010169 +-0.983255 0.181949 -0.010169 +-0.999962 0.000000 -0.008727 +-0.983255 0.181949 -0.010169 +-0.929731 0.368065 -0.011326 +-0.983255 0.181949 -0.010169 +-0.929731 0.368065 -0.011326 +-0.929731 0.368065 -0.011326 +-0.983255 0.181949 -0.010169 +-0.929731 0.368065 -0.011326 +-0.836937 0.547166 -0.012079 +-0.929731 0.368065 -0.011326 +-0.836937 0.547166 -0.012079 +-0.836937 0.547166 -0.012079 +-0.929731 0.368065 -0.011326 +-0.836937 0.547166 -0.012079 +-0.776296 0.630249 -0.012275 +-0.836937 0.547166 -0.012079 +-0.776296 0.630249 -0.012275 +-0.776296 0.630249 -0.012275 +-0.836937 0.547166 -0.012079 +-0.776296 0.630249 -0.012275 +-0.707053 0.707053 -0.012341 +-0.776296 0.630249 -0.012275 +-0.707053 0.707053 -0.012341 +-0.707053 0.707053 -0.012341 +-0.776296 0.630249 -0.012275 +-0.630249 0.776296 -0.012275 +-0.707053 0.707053 -0.012341 +-0.707053 0.707053 -0.012341 +-0.630249 0.776296 -0.012275 +-0.630249 0.776296 -0.012275 +-0.707053 0.707053 -0.012341 +-0.547166 0.836937 -0.012079 +-0.630249 0.776296 -0.012275 +-0.630249 0.776296 -0.012275 +-0.547166 0.836937 -0.012079 +-0.547166 0.836937 -0.012079 +-0.630249 0.776296 -0.012275 +-0.368065 0.929731 -0.011326 +-0.547166 0.836937 -0.012079 +-0.547166 0.836937 -0.012079 +-0.368065 0.929731 -0.011326 +-0.368065 0.929731 -0.011326 +-0.547166 0.836937 -0.012079 +-0.181949 0.983255 -0.010169 +-0.368065 0.929731 -0.011326 +-0.368065 0.929731 -0.011326 +-0.181949 0.983255 -0.010169 +-0.181949 0.983255 -0.010169 +-0.368065 0.929731 -0.011326 +0.000000 0.999962 -0.008727 +-0.181949 0.983255 -0.010169 +-0.181949 0.983255 -0.010169 +0.983255 0.181949 -0.010169 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.000000 0.999962 -0.008727 +0.181949 0.983255 -0.010169 +0.000000 0.999962 -0.008727 +0.181949 0.983255 -0.010169 +0.181949 0.983255 -0.010169 +0.000000 0.999962 -0.008727 +0.181949 0.983255 -0.010169 +0.368065 0.929731 -0.011326 +0.181949 0.983255 -0.010169 +0.368065 0.929731 -0.011326 +0.368065 0.929731 -0.011326 +0.181949 0.983255 -0.010169 +0.368065 0.929731 -0.011326 +0.547166 0.836937 -0.012079 +0.368065 0.929731 -0.011326 +0.547166 0.836937 -0.012079 +0.547166 0.836937 -0.012079 +0.368065 0.929731 -0.011326 +0.547166 0.836937 -0.012079 +0.630249 0.776296 -0.012275 +0.547166 0.836937 -0.012079 +0.630249 0.776296 -0.012275 +0.630249 0.776296 -0.012275 +0.547166 0.836937 -0.012079 +0.630249 0.776296 -0.012275 +0.707053 0.707053 -0.012341 +0.630249 0.776296 -0.012275 +0.707053 0.707053 -0.012341 +0.707053 0.707053 -0.012341 +0.630249 0.776296 -0.012275 +0.776296 0.630249 -0.012275 +0.707053 0.707053 -0.012341 +0.707053 0.707053 -0.012341 +0.776296 0.630249 -0.012275 +0.776296 0.630249 -0.012275 +0.707053 0.707053 -0.012341 +0.836937 0.547166 -0.012079 +0.776296 0.630249 -0.012275 +0.776296 0.630249 -0.012275 +0.836937 0.547166 -0.012079 +0.836937 0.547166 -0.012079 +0.776296 0.630249 -0.012275 +0.929731 0.368065 -0.011326 +0.836937 0.547166 -0.012079 +0.836937 0.547166 -0.012079 +0.929731 0.368065 -0.011326 +0.929731 0.368065 -0.011326 +0.836937 0.547166 -0.012079 +0.983255 0.181949 -0.010169 +0.929731 0.368065 -0.011326 +0.929731 0.368065 -0.011326 +0.983255 0.181949 -0.010169 +0.983255 0.181949 -0.010169 +0.929731 0.368065 -0.011326 +0.999962 0.000000 -0.008727 +0.983255 0.181949 -0.010169 +0.983255 0.181949 -0.010169 +-0.181949 0.983255 -0.010169 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +-0.999962 0.000000 -0.008727 +-0.983255 0.181949 -0.010169 +-0.999962 0.000000 -0.008727 +-0.983255 0.181949 -0.010169 +-0.983255 0.181949 -0.010169 +-0.999962 0.000000 -0.008727 +-0.983255 0.181949 -0.010169 +-0.929731 0.368065 -0.011326 +-0.983255 0.181949 -0.010169 +-0.929731 0.368065 -0.011326 +-0.929731 0.368065 -0.011326 +-0.983255 0.181949 -0.010169 +-0.929731 0.368065 -0.011326 +-0.836937 0.547166 -0.012079 +-0.929731 0.368065 -0.011326 +-0.836937 0.547166 -0.012079 +-0.836937 0.547166 -0.012079 +-0.929731 0.368065 -0.011326 +-0.836937 0.547166 -0.012079 +-0.776296 0.630249 -0.012275 +-0.836937 0.547166 -0.012079 +-0.776296 0.630249 -0.012275 +-0.776296 0.630249 -0.012275 +-0.836937 0.547166 -0.012079 +-0.776296 0.630249 -0.012275 +-0.707053 0.707053 -0.012341 +-0.776296 0.630249 -0.012275 +-0.707053 0.707053 -0.012341 +-0.707053 0.707053 -0.012341 +-0.776296 0.630249 -0.012275 +-0.630249 0.776296 -0.012275 +-0.707053 0.707053 -0.012341 +-0.707053 0.707053 -0.012341 +-0.630249 0.776296 -0.012275 +-0.630249 0.776296 -0.012275 +-0.707053 0.707053 -0.012341 +-0.547166 0.836937 -0.012079 +-0.630249 0.776296 -0.012275 +-0.630249 0.776296 -0.012275 +-0.547166 0.836937 -0.012079 +-0.547166 0.836937 -0.012079 +-0.630249 0.776296 -0.012275 +-0.368065 0.929731 -0.011326 +-0.547166 0.836937 -0.012079 +-0.547166 0.836937 -0.012079 +-0.368065 0.929731 -0.011326 +-0.368065 0.929731 -0.011326 +-0.547166 0.836937 -0.012079 +-0.181949 0.983255 -0.010169 +-0.368065 0.929731 -0.011326 +-0.368065 0.929731 -0.011326 +-0.181949 0.983255 -0.010169 +-0.181949 0.983255 -0.010169 +-0.368065 0.929731 -0.011326 +0.000000 0.999962 -0.008727 +-0.181949 0.983255 -0.010169 +-0.181949 0.983255 -0.010169 +0.983255 0.181949 -0.010169 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.000000 0.999962 -0.008727 +0.181949 0.983255 -0.010169 +0.000000 0.999962 -0.008727 +0.181949 0.983255 -0.010169 +0.181949 0.983255 -0.010169 +0.000000 0.999962 -0.008727 +0.181949 0.983255 -0.010169 +0.368065 0.929731 -0.011326 +0.181949 0.983255 -0.010169 +0.368065 0.929731 -0.011326 +0.368065 0.929731 -0.011326 +0.181949 0.983255 -0.010169 +0.368065 0.929731 -0.011326 +0.547166 0.836937 -0.012079 +0.368065 0.929731 -0.011326 +0.547166 0.836937 -0.012079 +0.547166 0.836937 -0.012079 +0.368065 0.929731 -0.011326 +0.547166 0.836937 -0.012079 +0.630249 0.776296 -0.012275 +0.547166 0.836937 -0.012079 +0.630249 0.776296 -0.012275 +0.630249 0.776296 -0.012275 +0.547166 0.836937 -0.012079 +0.630249 0.776296 -0.012275 +0.707053 0.707053 -0.012341 +0.630249 0.776296 -0.012275 +0.707053 0.707053 -0.012341 +0.707053 0.707053 -0.012341 +0.630249 0.776296 -0.012275 +0.776296 0.630249 -0.012275 +0.707053 0.707053 -0.012341 +0.707053 0.707053 -0.012341 +0.776296 0.630249 -0.012275 +0.776296 0.630249 -0.012275 +0.707053 0.707053 -0.012341 +0.836937 0.547166 -0.012079 +0.776296 0.630249 -0.012275 +0.776296 0.630249 -0.012275 +0.836937 0.547166 -0.012079 +0.836937 0.547166 -0.012079 +0.776296 0.630249 -0.012275 +0.929731 0.368065 -0.011326 +0.836937 0.547166 -0.012079 +0.836937 0.547166 -0.012079 +0.929731 0.368065 -0.011326 +0.929731 0.368065 -0.011326 +0.836937 0.547166 -0.012079 +0.983255 0.181949 -0.010169 +0.929731 0.368065 -0.011326 +0.929731 0.368065 -0.011326 +0.983255 0.181949 -0.010169 +0.983255 0.181949 -0.010169 +0.929731 0.368065 -0.011326 +0.999962 0.000000 -0.008727 +0.983255 0.181949 -0.010169 +0.983255 0.181949 -0.010169 +0.000000 -1.000000 0.000000 +-0.181956 -0.983305 -0.001588 +0.000000 -1.000000 0.000000 +-0.999962 0.000000 -0.008727 +-0.983268 -0.181963 -0.008581 +-0.999962 0.000000 -0.008727 +-0.983268 -0.181963 -0.008581 +-0.983268 -0.181963 -0.008581 +-0.999962 0.000000 -0.008727 +-0.983268 -0.181963 -0.008581 +-0.929753 -0.368095 -0.008114 +-0.983268 -0.181963 -0.008581 +-0.929753 -0.368095 -0.008114 +-0.929753 -0.368095 -0.008114 +-0.983268 -0.181963 -0.008581 +-0.929753 -0.368095 -0.008114 +-0.836964 -0.547210 -0.007304 +-0.929753 -0.368095 -0.008114 +-0.836964 -0.547210 -0.007304 +-0.836964 -0.547210 -0.007304 +-0.929753 -0.368095 -0.008114 +-0.836964 -0.547210 -0.007304 +-0.776324 -0.630298 -0.006775 +-0.836964 -0.547210 -0.007304 +-0.776324 -0.630298 -0.006775 +-0.776324 -0.630298 -0.006775 +-0.836964 -0.547210 -0.007304 +-0.776324 -0.630298 -0.006775 +-0.707080 -0.707107 -0.006171 +-0.776324 -0.630298 -0.006775 +-0.707080 -0.707107 -0.006171 +-0.707080 -0.707107 -0.006171 +-0.776324 -0.630298 -0.006775 +-0.707080 -0.707107 -0.006171 +-0.630274 -0.776353 -0.005500 +-0.707080 -0.707107 -0.006171 +-0.630274 -0.776353 -0.005500 +-0.630274 -0.776353 -0.005500 +-0.707080 -0.707107 -0.006171 +-0.630274 -0.776353 -0.005500 +-0.547189 -0.836995 -0.004775 +-0.630274 -0.776353 -0.005500 +-0.547189 -0.836995 -0.004775 +-0.547189 -0.836995 -0.004775 +-0.630274 -0.776353 -0.005500 +-0.547189 -0.836995 -0.004775 +-0.368081 -0.929788 -0.003212 +-0.547189 -0.836995 -0.004775 +-0.368081 -0.929788 -0.003212 +-0.368081 -0.929788 -0.003212 +-0.547189 -0.836995 -0.004775 +-0.368081 -0.929788 -0.003212 +-0.181956 -0.983305 -0.001588 +-0.368081 -0.929788 -0.003212 +-0.181956 -0.983305 -0.001588 +-0.181956 -0.983305 -0.001588 +-0.368081 -0.929788 -0.003212 +-0.181956 -0.983305 -0.001588 +0.000000 -1.000000 0.000000 +-0.181956 -0.983305 -0.001588 +0.181956 -0.983305 -0.001588 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.983268 -0.181963 -0.008581 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.983268 -0.181963 -0.008581 +0.983268 -0.181963 -0.008581 +0.999962 0.000000 -0.008727 +0.929753 -0.368095 -0.008114 +0.983268 -0.181963 -0.008581 +0.983268 -0.181963 -0.008581 +0.929753 -0.368095 -0.008114 +0.929753 -0.368095 -0.008114 +0.983268 -0.181963 -0.008581 +0.836964 -0.547210 -0.007304 +0.929753 -0.368095 -0.008114 +0.929753 -0.368095 -0.008114 +0.836964 -0.547210 -0.007304 +0.836964 -0.547210 -0.007304 +0.929753 -0.368095 -0.008114 +0.776324 -0.630298 -0.006775 +0.836964 -0.547210 -0.007304 +0.836964 -0.547210 -0.007304 +0.776324 -0.630298 -0.006775 +0.776324 -0.630298 -0.006775 +0.836964 -0.547210 -0.007304 +0.707080 -0.707107 -0.006171 +0.776324 -0.630298 -0.006775 +0.776324 -0.630298 -0.006775 +0.707080 -0.707107 -0.006171 +0.707080 -0.707107 -0.006171 +0.776324 -0.630298 -0.006775 +0.630274 -0.776353 -0.005500 +0.707080 -0.707107 -0.006171 +0.707080 -0.707107 -0.006171 +0.630274 -0.776353 -0.005500 +0.630274 -0.776353 -0.005500 +0.707080 -0.707107 -0.006171 +0.547189 -0.836995 -0.004775 +0.630274 -0.776353 -0.005500 +0.630274 -0.776353 -0.005500 +0.547189 -0.836995 -0.004775 +0.547189 -0.836995 -0.004775 +0.630274 -0.776353 -0.005500 +0.368081 -0.929788 -0.003212 +0.547189 -0.836995 -0.004775 +0.547189 -0.836995 -0.004775 +0.368081 -0.929788 -0.003212 +0.368081 -0.929788 -0.003212 +0.547189 -0.836995 -0.004775 +0.181956 -0.983305 -0.001588 +0.368081 -0.929788 -0.003212 +0.368081 -0.929788 -0.003212 +0.181956 -0.983305 -0.001588 +0.181956 -0.983305 -0.001588 +0.368081 -0.929788 -0.003212 +0.000000 -1.000000 0.000000 +0.181956 -0.983305 -0.001588 +0.181956 -0.983305 -0.001588 +0.000000 0.397177 0.917742 +0.000000 0.204909 0.978781 +0.000000 0.204909 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.204909 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.204909 0.978781 +0.000000 0.204909 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.978781 0.204909 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.978781 0.204909 +0.000000 0.978781 0.204909 +0.000000 1.000000 0.000000 +0.000000 0.917742 0.397177 +0.000000 0.978781 0.204909 +0.000000 0.978781 0.204909 +0.000000 0.917742 0.397177 +0.000000 0.917742 0.397177 +0.000000 0.978781 0.204909 +0.000000 0.823969 0.566635 +0.000000 0.917742 0.397177 +0.000000 0.917742 0.397177 +0.000000 0.823969 0.566635 +0.000000 0.823969 0.566635 +0.000000 0.917742 0.397177 +0.000000 0.823969 0.566635 +0.000000 0.707107 0.707107 +0.000000 0.823969 0.566635 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.823969 0.566635 +0.000000 0.566635 0.823969 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.566635 0.823969 +0.000000 0.566635 0.823969 +0.000000 0.707107 0.707107 +0.000000 0.566635 0.823969 +0.000000 0.397177 0.917742 +0.000000 0.566635 0.823969 +0.000000 0.397177 0.917742 +0.000000 0.397177 0.917742 +0.000000 0.566635 0.823969 +0.000000 0.204909 0.978781 +0.000000 0.397177 0.917742 +0.000000 0.397177 0.917742 +-0.707107 0.000000 0.707107 +-0.695302 -0.128667 0.707107 +-0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.695302 -0.128667 0.707107 +0.707107 0.000000 0.707107 +0.695302 -0.128667 0.707107 +0.695302 -0.128667 0.707107 +0.707107 0.000000 0.707107 +0.657460 -0.260282 0.707107 +0.695302 -0.128667 0.707107 +0.695302 -0.128667 0.707107 +0.657460 -0.260282 0.707107 +0.657460 -0.260282 0.707107 +0.695302 -0.128667 0.707107 +0.591845 -0.386936 0.707107 +0.657460 -0.260282 0.707107 +0.657460 -0.260282 0.707107 +0.591845 -0.386936 0.707107 +0.591845 -0.386936 0.707107 +0.657460 -0.260282 0.707107 +0.500000 -0.500000 0.707107 +0.591845 -0.386936 0.707107 +0.591845 -0.386936 0.707107 +0.500000 -0.500000 0.707107 +0.500000 -0.500000 0.707107 +0.591845 -0.386936 0.707107 +0.386936 -0.591845 0.707107 +0.500000 -0.500000 0.707107 +0.500000 -0.500000 0.707107 +0.386936 -0.591845 0.707107 +0.386936 -0.591845 0.707107 +0.500000 -0.500000 0.707107 +0.260282 -0.657460 0.707107 +0.386936 -0.591845 0.707107 +0.386936 -0.591845 0.707107 +0.260282 -0.657460 0.707107 +0.260282 -0.657460 0.707107 +0.386936 -0.591845 0.707107 +0.128667 -0.695302 0.707107 +0.260282 -0.657460 0.707107 +0.260282 -0.657460 0.707107 +0.128667 -0.695302 0.707107 +0.128667 -0.695302 0.707107 +0.260282 -0.657460 0.707107 +0.128667 -0.695302 0.707107 +0.000000 -0.707107 0.707107 +0.128667 -0.695302 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.128667 -0.695302 0.707107 +-0.128667 -0.695302 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +-0.128667 -0.695302 0.707107 +-0.128667 -0.695302 0.707107 +0.000000 -0.707107 0.707107 +-0.260282 -0.657460 0.707107 +-0.128667 -0.695302 0.707107 +-0.128667 -0.695302 0.707107 +-0.260282 -0.657460 0.707107 +-0.260282 -0.657460 0.707107 +-0.128667 -0.695302 0.707107 +-0.386936 -0.591845 0.707107 +-0.260282 -0.657460 0.707107 +-0.260282 -0.657460 0.707107 +-0.386936 -0.591845 0.707107 +-0.386936 -0.591845 0.707107 +-0.260282 -0.657460 0.707107 +-0.500000 -0.500000 0.707107 +-0.386936 -0.591845 0.707107 +-0.386936 -0.591845 0.707107 +-0.500000 -0.500000 0.707107 +-0.500000 -0.500000 0.707107 +-0.386936 -0.591845 0.707107 +-0.591845 -0.386936 0.707107 +-0.500000 -0.500000 0.707107 +-0.500000 -0.500000 0.707107 +-0.591845 -0.386936 0.707107 +-0.591845 -0.386936 0.707107 +-0.500000 -0.500000 0.707107 +-0.657460 -0.260282 0.707107 +-0.591845 -0.386936 0.707107 +-0.591845 -0.386936 0.707107 +-0.657460 -0.260282 0.707107 +-0.657460 -0.260282 0.707107 +-0.591845 -0.386936 0.707107 +-0.657460 -0.260282 0.707107 +-0.695302 -0.128667 0.707107 +-0.657460 -0.260282 0.707107 +-0.695302 -0.128667 0.707107 +-0.695302 -0.128667 0.707107 +-0.657460 -0.260282 0.707107 +-0.695302 -0.128667 0.707107 +-0.707107 0.000000 0.707107 +-0.695302 -0.128667 0.707107 + + + + + + + + + + + +0.423090 0.589335 +0.417996 0.589335 +0.580638 0.586153 +0.582007 0.589335 +0.576912 0.589335 +0.575628 0.586351 +0.576249 0.582899 +0.568639 0.579766 +0.571512 0.583298 +0.564376 0.580361 +0.557988 0.576970 +0.554386 0.577738 +0.544875 0.574699 +0.542088 0.575608 +0.530187 0.573076 +0.528312 0.574086 +0.514923 0.572141 +0.513996 0.573209 +0.500001 0.571849 +0.500001 0.572935 +0.485079 0.572141 +0.486006 0.573209 +0.469815 0.573076 +0.471690 0.574086 +0.455127 0.574699 +0.457914 0.575608 +0.442014 0.576970 +0.445617 0.577738 +0.431363 0.579766 +0.435627 0.580361 +0.423753 0.582899 +0.428490 0.583298 +0.419365 0.586153 +0.424374 0.586351 +0.810654 0.700707 +0.702744 0.700707 +0.702670 0.702501 +0.810728 0.702501 +0.702671 0.702173 +0.810727 0.702173 +0.702675 0.701837 +0.810723 0.701837 +0.702682 0.701514 +0.810716 0.701514 +0.702687 0.701365 +0.810712 0.701365 +0.702692 0.701227 +0.810706 0.701227 +0.702697 0.701102 +0.810701 0.701102 +0.702704 0.700993 +0.810695 0.700993 +0.702717 0.700828 +0.810681 0.700828 +0.702731 0.700734 +0.810668 0.700734 +0.207955 0.553442 +0.207955 0.553442 +0.186072 0.553442 +0.186072 0.553442 +0.186255 0.553017 +0.186840 0.552583 +0.186255 0.553017 +0.186840 0.552583 +0.187856 0.552165 +0.189277 0.551792 +0.187856 0.552165 +0.189277 0.551792 +0.191026 0.551489 +0.191026 0.551489 +0.192986 0.551272 +0.195022 0.551148 +0.192986 0.551272 +0.197013 0.551109 +0.195022 0.551148 +0.197013 0.551109 +0.199004 0.551148 +0.199004 0.551148 +0.201041 0.551272 +0.201041 0.551272 +0.203001 0.551489 +0.203001 0.551489 +0.204750 0.551792 +0.204750 0.551792 +0.206171 0.552165 +0.206171 0.552165 +0.207186 0.552583 +0.207186 0.552583 +0.207772 0.553017 +0.207772 0.553017 +0.792230 0.553017 +0.792230 0.553017 +0.792048 0.553442 +0.792048 0.553442 +0.813747 0.553017 +0.813930 0.553442 +0.813930 0.553442 +0.813747 0.553017 +0.813162 0.552583 +0.813162 0.552583 +0.812147 0.552165 +0.812147 0.552165 +0.810725 0.551792 +0.810725 0.551792 +0.808976 0.551489 +0.808976 0.551489 +0.807016 0.551272 +0.807016 0.551272 +0.804980 0.551147 +0.804980 0.551147 +0.802989 0.551109 +0.802989 0.551109 +0.800998 0.551147 +0.800998 0.551147 +0.798961 0.551272 +0.797002 0.551489 +0.798961 0.551272 +0.797002 0.551489 +0.795252 0.551792 +0.795252 0.551792 +0.793831 0.552165 +0.793831 0.552165 +0.792816 0.552583 +0.792816 0.552583 +0.740546 0.663062 +0.737342 0.664712 +0.737342 0.664712 +0.737524 0.664288 +0.738110 0.663853 +0.737524 0.664288 +0.739125 0.663436 +0.738110 0.663853 +0.740546 0.663062 +0.739125 0.663436 +0.759041 0.664288 +0.759224 0.664712 +0.759224 0.664712 +0.759041 0.664288 +0.758456 0.663853 +0.758456 0.663853 +0.757441 0.663436 +0.757441 0.663436 +0.756019 0.663062 +0.754270 0.662759 +0.756019 0.663062 +0.754270 0.662759 +0.752310 0.662543 +0.752310 0.662543 +0.750274 0.662418 +0.750274 0.662418 +0.748283 0.662379 +0.748283 0.662379 +0.746292 0.662418 +0.746292 0.662418 +0.744255 0.662543 +0.744255 0.662543 +0.742296 0.662759 +0.742296 0.662759 +0.240961 0.664288 +0.240961 0.664288 +0.240778 0.664712 +0.240778 0.664712 +0.262661 0.664712 +0.262661 0.664712 +0.262478 0.664288 +0.262478 0.664288 +0.261893 0.663853 +0.261893 0.663853 +0.260877 0.663436 +0.259456 0.663062 +0.260877 0.663436 +0.259456 0.663062 +0.257707 0.662759 +0.257707 0.662759 +0.255747 0.662543 +0.255747 0.662543 +0.253711 0.662418 +0.253711 0.662418 +0.251720 0.662379 +0.251720 0.662379 +0.249729 0.662418 +0.249729 0.662418 +0.247692 0.662543 +0.247692 0.662543 +0.245732 0.662759 +0.245732 0.662759 +0.243983 0.663062 +0.243983 0.663062 +0.242562 0.663436 +0.242562 0.663436 +0.241547 0.663853 +0.241547 0.663853 +0.836092 0.554748 +0.835731 0.554734 +0.836287 0.553442 +0.836654 0.553442 +0.769324 0.553442 +0.769691 0.553442 +0.769886 0.554748 +0.770247 0.554734 +0.771687 0.556084 +0.772029 0.556055 +0.774811 0.557370 +0.779184 0.558518 +0.775118 0.557327 +0.784567 0.559450 +0.779444 0.558462 +0.790597 0.560116 +0.784768 0.559385 +0.796863 0.560501 +0.790732 0.560044 +0.796930 0.560423 +0.802989 0.560620 +0.802989 0.560542 +0.809115 0.560501 +0.815381 0.560116 +0.809048 0.560423 +0.821411 0.559450 +0.815246 0.560044 +0.826794 0.558518 +0.821210 0.559385 +0.826534 0.558462 +0.831167 0.557370 +0.830859 0.557327 +0.834290 0.556084 +0.833949 0.556055 +0.230311 0.553442 +0.230679 0.553442 +0.163910 0.554748 +0.163348 0.553442 +0.163715 0.553442 +0.164271 0.554734 +0.165712 0.556084 +0.166053 0.556055 +0.168836 0.557370 +0.169143 0.557327 +0.173208 0.558518 +0.173468 0.558462 +0.178591 0.559450 +0.184621 0.560116 +0.178792 0.559385 +0.190888 0.560501 +0.184757 0.560044 +0.197013 0.560620 +0.190954 0.560424 +0.197013 0.560542 +0.203139 0.560501 +0.209405 0.560116 +0.203072 0.560424 +0.215435 0.559450 +0.209270 0.560044 +0.220818 0.558518 +0.215234 0.559385 +0.220559 0.558462 +0.225191 0.557370 +0.224884 0.557327 +0.228315 0.556084 +0.227974 0.556055 +0.230117 0.554748 +0.229756 0.554734 +0.781386 0.666018 +0.781025 0.666004 +0.781581 0.664712 +0.781948 0.664712 +0.714617 0.664712 +0.714985 0.664712 +0.715180 0.666018 +0.715541 0.666004 +0.716981 0.667355 +0.717323 0.667326 +0.720105 0.668640 +0.720412 0.668598 +0.724478 0.669788 +0.724738 0.669733 +0.729861 0.670721 +0.730062 0.670655 +0.735891 0.671387 +0.736026 0.671314 +0.742157 0.671771 +0.742224 0.671694 +0.748283 0.671891 +0.748283 0.671813 +0.754409 0.671771 +0.754342 0.671694 +0.760675 0.671387 +0.760540 0.671314 +0.766705 0.670721 +0.766504 0.670655 +0.772088 0.669788 +0.771828 0.669733 +0.776461 0.668640 +0.776153 0.668598 +0.779584 0.667355 +0.779243 0.667326 +0.284823 0.666018 +0.284462 0.666004 +0.285018 0.664712 +0.285385 0.664712 +0.218054 0.664712 +0.218422 0.664712 +0.218616 0.666018 +0.218977 0.666004 +0.220418 0.667355 +0.220759 0.667326 +0.223542 0.668640 +0.223849 0.668598 +0.227915 0.669788 +0.228174 0.669733 +0.233298 0.670721 +0.233499 0.670655 +0.239328 0.671387 +0.245594 0.671771 +0.239463 0.671314 +0.245661 0.671694 +0.251720 0.671891 +0.251720 0.671813 +0.257845 0.671771 +0.257779 0.671694 +0.264112 0.671387 +0.270142 0.670721 +0.263976 0.671314 +0.269941 0.670655 +0.275525 0.669788 +0.275265 0.669733 +0.279897 0.668640 +0.279590 0.668598 +0.283021 0.667355 +0.282680 0.667326 +0.146516 0.714963 +0.297583 0.714963 +0.297275 0.707426 +0.146516 0.707426 +0.297280 0.708797 +0.297297 0.710200 +0.146516 0.708970 +0.297325 0.711550 +0.146516 0.710420 +0.297344 0.712177 +0.146516 0.711697 +0.297365 0.712756 +0.146516 0.712756 +0.297389 0.713278 +0.297415 0.713735 +0.146516 0.713637 +0.297470 0.714434 +0.146516 0.714343 +0.297527 0.714838 +0.146516 0.714803 +0.423324 0.589335 +0.423090 0.589335 +0.575628 0.586351 +0.576912 0.589335 +0.576678 0.589335 +0.571512 0.583298 +0.575398 0.586360 +0.571294 0.583317 +0.564376 0.580361 +0.564179 0.580388 +0.554386 0.577738 +0.554220 0.577774 +0.542088 0.575608 +0.528312 0.574086 +0.541959 0.575650 +0.528225 0.574133 +0.513996 0.573209 +0.513953 0.573258 +0.500001 0.572935 +0.500001 0.572985 +0.486006 0.573209 +0.486049 0.573258 +0.471690 0.574086 +0.471777 0.574133 +0.457914 0.575608 +0.458043 0.575650 +0.445617 0.577738 +0.445783 0.577774 +0.435627 0.580361 +0.428490 0.583298 +0.435823 0.580388 +0.428708 0.583317 +0.424374 0.586351 +0.424605 0.586360 +0.163260 0.716777 +0.163260 0.715073 +0.155259 0.718553 +0.170461 0.718553 +0.167718 0.718361 +0.166436 0.718181 +0.165310 0.717951 +0.154575 0.715073 +0.164403 0.717680 +0.163755 0.717384 +0.163379 0.717077 +0.490718 0.716573 +0.416705 0.716573 +0.415838 0.716758 +0.491585 0.716758 +0.324125 0.716573 +0.323258 0.716758 +0.399005 0.716758 +0.398139 0.716573 +0.416705 0.707785 +0.490718 0.707785 +0.490836 0.707785 +0.416587 0.707785 +0.324008 0.707785 +0.324125 0.707785 +0.398139 0.707785 +0.398256 0.707785 +0.490718 0.716573 +0.490718 0.707785 +0.416705 0.707785 +0.416705 0.716573 +0.324125 0.707785 +0.324125 0.716573 +0.398139 0.716573 +0.398139 0.707785 +0.416587 0.707785 +0.490836 0.707785 +0.490836 0.704355 +0.416587 0.704355 +0.398256 0.704355 +0.324008 0.704355 +0.324008 0.707785 +0.398256 0.707785 +0.490836 0.704355 +0.491585 0.704195 +0.415838 0.704195 +0.416587 0.704355 +0.323258 0.704195 +0.324008 0.704355 +0.398256 0.704355 +0.399005 0.704195 +0.584165 0.716758 +0.583298 0.716573 +0.509284 0.716573 +0.508418 0.716758 +0.509284 0.707785 +0.583298 0.707785 +0.583415 0.707785 +0.509167 0.707785 +0.583298 0.716573 +0.583298 0.707785 +0.509284 0.707785 +0.509284 0.716573 +0.583415 0.707785 +0.583415 0.704355 +0.509167 0.704355 +0.509167 0.707785 +0.584165 0.704195 +0.508418 0.704195 +0.509167 0.704355 +0.583415 0.704355 +0.676744 0.716758 +0.675877 0.716573 +0.601864 0.716573 +0.600997 0.716758 +0.601864 0.707785 +0.675877 0.707785 +0.675995 0.707785 +0.601746 0.707785 +0.675877 0.716573 +0.675877 0.707785 +0.601864 0.707785 +0.601864 0.716573 +0.675995 0.707785 +0.675995 0.704355 +0.601746 0.704355 +0.601746 0.707785 +0.676744 0.704195 +0.600997 0.704195 +0.601746 0.704355 +0.675995 0.704355 +0.189276 0.702112 +0.189237 0.701990 +0.189285 0.703448 +0.189278 0.703070 +0.189274 0.702614 +0.188876 0.680924 +0.188597 0.680864 +0.188597 0.699797 +0.189567 0.680864 +0.188876 0.680864 +0.189567 0.700753 +0.189023 0.699888 +0.189348 0.700707 +0.189331 0.700751 +0.189099 0.700122 +0.189313 0.700913 +0.189173 0.700838 +0.189297 0.701207 +0.189284 0.701622 +0.845428 0.715073 +0.836742 0.715073 +0.830919 0.718484 +0.829541 0.718553 +0.832285 0.718361 +0.833567 0.718181 +0.834692 0.717951 +0.835599 0.717680 +0.844744 0.718553 +0.836247 0.717384 +0.836742 0.716777 +0.810723 0.701837 +0.810725 0.702994 +0.810717 0.703448 +0.810728 0.702501 +0.810727 0.702173 +0.811405 0.699797 +0.811405 0.680864 +0.810979 0.699888 +0.810436 0.680864 +0.810436 0.700753 +0.811126 0.680864 +0.811126 0.680924 +0.810903 0.700122 +0.810654 0.700707 +0.810829 0.700838 +0.810668 0.700734 +0.810681 0.700828 +0.810766 0.701990 +0.810695 0.700993 +0.810706 0.701227 +0.810716 0.701514 +0.471777 0.604538 +0.423090 0.589335 +0.423324 0.589335 +0.424374 0.592320 +0.428490 0.595372 +0.424605 0.592311 +0.428708 0.595354 +0.435627 0.598310 +0.435823 0.598283 +0.445617 0.600932 +0.445783 0.600897 +0.457915 0.603063 +0.471690 0.604584 +0.458043 0.603021 +0.576678 0.589335 +0.576912 0.589335 +0.575398 0.592311 +0.571294 0.595354 +0.575628 0.592320 +0.571512 0.595372 +0.564179 0.598282 +0.564376 0.598310 +0.554220 0.600897 +0.554386 0.600932 +0.541959 0.603021 +0.542088 0.603063 +0.528225 0.604538 +0.528312 0.604584 +0.513954 0.605413 +0.513996 0.605462 +0.500001 0.605686 +0.500001 0.605736 +0.486049 0.605413 +0.486006 0.605462 +0.702727 0.706939 +0.702712 0.705030 +0.702731 0.700734 +0.702744 0.700707 +0.702717 0.700828 +0.702704 0.700993 +0.702692 0.701227 +0.702682 0.701514 +0.702675 0.701837 +0.702671 0.702173 +0.701993 0.680864 +0.701993 0.715054 +0.702272 0.700606 +0.702272 0.680924 +0.702670 0.702501 +0.702673 0.702994 +0.702681 0.703448 +0.702419 0.714963 +0.702490 0.714761 +0.702565 0.714072 +0.702634 0.712830 +0.702689 0.711089 +0.702720 0.709037 +0.718825 0.677275 +0.719104 0.677334 +0.794294 0.677334 +0.794573 0.677275 +0.297470 0.714434 +0.297527 0.714838 +0.297730 0.700606 +0.297258 0.700707 +0.297275 0.700751 +0.297293 0.700913 +0.297310 0.701207 +0.297323 0.701622 +0.298009 0.715054 +0.298009 0.680864 +0.297730 0.680924 +0.297583 0.714963 +0.297331 0.702112 +0.297332 0.702614 +0.297329 0.703070 +0.297321 0.703448 +0.297287 0.705358 +0.297275 0.707426 +0.297280 0.708797 +0.297297 0.710200 +0.297325 0.711550 +0.297365 0.712756 +0.297415 0.713735 +0.281177 0.677275 +0.205429 0.677275 +0.205708 0.677334 +0.280898 0.677334 +0.442014 0.601700 +0.189157 0.680271 +0.188876 0.680924 +0.811126 0.680864 +0.811126 0.680924 +0.811407 0.680211 +0.188876 0.680864 +0.280898 0.677334 +0.257845 0.671771 +0.251720 0.671891 +0.245594 0.671771 +0.239328 0.671387 +0.794294 0.677334 +0.735891 0.671387 +0.742157 0.671771 +0.748283 0.671891 +0.754409 0.671771 +0.760675 0.671387 +0.233298 0.670721 +0.190058 0.679603 +0.188595 0.680211 +0.810845 0.680271 +0.812308 0.679543 +0.264112 0.671387 +0.729861 0.670721 +0.108738 0.524727 +0.891264 0.524727 +0.890700 0.527598 +0.227915 0.669788 +0.766705 0.670721 +0.576249 0.582899 +0.771687 0.556084 +0.702272 0.700606 +0.297730 0.700606 +0.702272 0.680924 +0.821411 0.547433 +0.125998 0.527598 +0.109302 0.527598 +0.184621 0.546767 +0.172043 0.677275 +0.155417 0.677275 +0.874004 0.527598 +0.844585 0.677275 +0.297730 0.680924 +0.702553 0.680271 +0.827959 0.677275 +0.774811 0.557370 +0.175106 0.677335 +0.178591 0.547433 +0.826794 0.548365 +0.568639 0.579766 +0.769886 0.554748 +0.580638 0.586153 +0.297449 0.680271 +0.703454 0.679603 +0.779184 0.558518 +0.815381 0.546767 +0.809115 0.546383 +0.802989 0.546263 +0.796863 0.546383 +0.790597 0.546767 +0.784567 0.547433 +0.779184 0.548365 +0.774811 0.549513 +0.771687 0.550799 +0.769886 0.552135 +0.769324 0.553442 +0.190888 0.546383 +0.223542 0.668640 +0.772088 0.669788 +0.270142 0.670721 +0.283961 0.677394 +0.724478 0.669788 +0.719104 0.677334 +0.178239 0.677527 +0.191620 0.678960 +0.187694 0.679543 +0.809944 0.679603 +0.813870 0.678900 +0.824896 0.677335 +0.557988 0.576970 +0.544875 0.574699 +0.530187 0.573076 +0.514923 0.572141 +0.500001 0.571849 +0.485079 0.572141 +0.469815 0.573076 +0.455127 0.574699 +0.442014 0.576970 +0.431363 0.579766 +0.423753 0.582899 +0.173208 0.548366 +0.831167 0.549513 +0.582007 0.589335 +0.296549 0.679603 +0.705016 0.678960 +0.784567 0.559450 +0.205708 0.677334 +0.797357 0.677394 +0.287094 0.677586 +0.716041 0.677394 +0.197013 0.546263 +0.181254 0.677860 +0.821763 0.677527 +0.720105 0.668640 +0.275525 0.669788 +0.776461 0.668640 +0.220418 0.667355 +0.193806 0.678386 +0.186132 0.678900 +0.808383 0.678960 +0.816057 0.678326 +0.202645 0.677394 +0.800490 0.677586 +0.419365 0.586153 +0.290109 0.677920 +0.712908 0.677586 +0.580638 0.592517 +0.790597 0.560116 +0.168836 0.549513 +0.294987 0.678960 +0.707202 0.678386 +0.834290 0.550799 +0.183946 0.678326 +0.196498 0.677920 +0.199512 0.677586 +0.818748 0.677860 +0.806196 0.678386 +0.803505 0.677920 +0.203139 0.546383 +0.796863 0.560501 +0.576249 0.595772 +0.279897 0.668640 +0.292800 0.678386 +0.283021 0.667355 +0.284823 0.666018 +0.285385 0.664712 +0.284823 0.663406 +0.283021 0.662070 +0.709893 0.677920 +0.716981 0.667355 +0.715180 0.666018 +0.714617 0.664712 +0.715180 0.663406 +0.716981 0.662070 +0.720105 0.660784 +0.279897 0.660784 +0.724478 0.659636 +0.218616 0.666018 +0.218054 0.664712 +0.218616 0.663406 +0.220418 0.662070 +0.223542 0.660784 +0.227915 0.659636 +0.233298 0.658704 +0.239328 0.658037 +0.245594 0.657653 +0.251720 0.657533 +0.257845 0.657653 +0.264112 0.658037 +0.270142 0.658704 +0.275525 0.659636 +0.729861 0.658704 +0.779584 0.667355 +0.781386 0.666018 +0.781948 0.664712 +0.781386 0.663406 +0.779584 0.662070 +0.776461 0.660784 +0.772088 0.659636 +0.766705 0.658704 +0.760675 0.658037 +0.754409 0.657653 +0.748283 0.657533 +0.742157 0.657653 +0.735891 0.658037 +0.165712 0.550799 +0.836092 0.552135 +0.209405 0.546767 +0.802989 0.560620 +0.568639 0.598904 +0.836654 0.553442 +0.163910 0.552135 +0.809115 0.560501 +0.215435 0.547433 +0.557988 0.601700 +0.163348 0.553442 +0.163910 0.554748 +0.165712 0.556084 +0.168836 0.557370 +0.173208 0.558518 +0.178591 0.559450 +0.184621 0.560116 +0.190888 0.560501 +0.197013 0.560620 +0.203139 0.560501 +0.209405 0.560116 +0.215435 0.559450 +0.836092 0.554748 +0.834290 0.556084 +0.831167 0.557370 +0.826794 0.558518 +0.821411 0.559450 +0.815381 0.560116 +0.544875 0.603972 +0.530187 0.605594 +0.514923 0.606530 +0.500001 0.606822 +0.485079 0.606530 +0.469815 0.605594 +0.455127 0.603972 +0.220818 0.548366 +0.225191 0.549513 +0.228315 0.550799 +0.230117 0.552135 +0.230679 0.553442 +0.230117 0.554748 +0.228315 0.556084 +0.225191 0.557370 +0.220818 0.558518 +0.417996 0.589335 +0.419365 0.592517 +0.423753 0.595772 +0.431363 0.598904 +0.297730 0.700606 +0.702272 0.700606 +0.189567 0.700753 +0.189348 0.700707 +0.810436 0.700753 +0.702744 0.700707 +0.810654 0.700707 +0.297258 0.700707 +0.146516 0.721890 +0.146516 0.722082 +0.146516 0.699779 +0.146516 0.689838 +0.146516 0.699888 +0.146516 0.700014 +0.146516 0.700417 +0.146516 0.701117 +0.146516 0.702096 +0.146516 0.718564 +0.146516 0.715073 +0.146516 0.703301 +0.146516 0.689838 +0.146516 0.704651 +0.146516 0.706054 +0.146516 0.707426 +0.146516 0.708797 +0.146516 0.710200 +0.146516 0.711550 +0.146516 0.712756 +0.146516 0.719267 +0.146516 0.719939 +0.146516 0.720557 +0.146516 0.721098 +0.146516 0.721541 +0.146516 0.721871 +0.146516 0.722074 +0.146516 0.722142 +0.146516 0.722142 +0.146516 0.714963 +0.146516 0.714838 +0.146516 0.714434 +0.146516 0.713735 +0.146516 0.718553 +0.146516 0.719206 +0.146516 0.719874 +0.146516 0.720517 +0.146516 0.721091 +0.146516 0.721557 +0.828326 0.531887 +0.151569 0.699778 +0.163260 0.699778 +0.117162 0.524727 +0.163260 0.533681 +0.163400 0.533355 +0.163851 0.533021 +0.164632 0.532699 +0.836742 0.533681 +0.836742 0.699778 +0.848434 0.699778 +0.836602 0.533355 +0.836151 0.533021 +0.835370 0.532699 +0.834277 0.532412 +0.832932 0.532179 +0.165725 0.532412 +0.167071 0.532179 +0.831424 0.532013 +0.829858 0.531917 +0.168578 0.532013 +0.170144 0.531917 +0.882840 0.524727 +0.171676 0.531887 +0.000641 0.531905 +0.030977 0.686248 +0.146516 0.689838 +0.146516 0.699779 +0.151569 0.699778 +0.146185 0.689132 +0.145221 0.688457 +0.143656 0.687837 +0.141555 0.687293 +0.117162 0.524727 +0.139000 0.686849 +0.136088 0.686518 +0.132947 0.686316 +0.103365 0.524727 +0.129683 0.686248 +0.110689 0.686248 +0.089461 0.524727 +0.091926 0.686248 +0.075757 0.524727 +0.062570 0.524727 +0.074363 0.686248 +0.050201 0.524727 +0.058978 0.686248 +0.038917 0.524727 +0.028929 0.524727 +0.046596 0.686248 +0.020381 0.524727 +0.037749 0.686248 +0.010263 0.525130 +0.032604 0.686248 +0.003788 0.526462 +0.000876 0.528765 +0.155259 0.718553 +0.154575 0.715073 +0.146516 0.715073 +0.146516 0.718564 +0.189061 0.699945 +0.189023 0.699888 +0.297302 0.704369 +0.297321 0.703448 +0.146516 0.705881 +0.146516 0.707426 +0.297275 0.707426 +0.297278 0.706387 +0.146516 0.704432 +0.297287 0.705358 +0.146516 0.703155 +0.189285 0.703448 +0.146516 0.702096 +0.189263 0.702691 +0.146516 0.701215 +0.189237 0.701990 +0.189207 0.701366 +0.146516 0.700508 +0.189173 0.700838 +0.146516 0.700048 +0.189137 0.700420 +0.189099 0.700122 +0.146516 0.699888 +0.853487 0.715072 +0.845428 0.715073 +0.844744 0.718553 +0.853487 0.718564 +0.853487 0.699888 +0.810979 0.699888 +0.702454 0.714915 +0.702419 0.714963 +0.853487 0.714963 +0.702490 0.714761 +0.853487 0.714838 +0.702527 0.714483 +0.702565 0.714072 +0.853487 0.714434 +0.702601 0.713520 +0.853487 0.713735 +0.702634 0.712830 +0.702664 0.712013 +0.853487 0.712756 +0.702689 0.711089 +0.853487 0.711550 +0.702708 0.710086 +0.853487 0.710200 +0.702720 0.709037 +0.702727 0.707978 +0.853487 0.708797 +0.702727 0.706939 +0.853487 0.707426 +0.702722 0.705950 +0.853487 0.706054 +0.702712 0.705030 +0.702698 0.704194 +0.853487 0.704651 +0.810717 0.703448 +0.702681 0.703448 +0.810739 0.702691 +0.853487 0.703301 +0.810766 0.701990 +0.853487 0.702096 +0.810796 0.701366 +0.810829 0.700838 +0.853487 0.701117 +0.810865 0.700420 +0.810903 0.700122 +0.853487 0.700417 +0.810941 0.699945 +0.853487 0.700014 +0.902335 0.677275 +0.913256 0.677275 +0.926468 0.677275 +0.928670 0.677275 +0.921371 0.677275 +0.827269 0.677275 +0.827959 0.677275 +0.844585 0.677275 +0.859414 0.677275 +0.874553 0.677275 +0.889163 0.677275 +0.125449 0.677275 +0.140589 0.677275 +0.172733 0.677275 +0.071332 0.677275 +0.073535 0.677275 +0.172043 0.677275 +0.155417 0.677275 +0.078631 0.677275 +0.086746 0.677275 +0.097667 0.677275 +0.110839 0.677275 +0.089902 0.524727 +0.961085 0.524727 +0.979622 0.524727 +0.072020 0.524727 +0.020381 0.524727 +0.038917 0.524727 +0.937432 0.524727 +0.927982 0.524727 +0.910541 0.524727 +0.910100 0.524727 +0.882840 0.524727 +0.891264 0.524727 +0.117162 0.524727 +0.089461 0.524727 +0.108738 0.524727 +0.062570 0.524727 +0.155259 0.722142 +0.146516 0.722142 +0.146516 0.722142 +0.853487 0.722142 +0.853487 0.722142 +0.844744 0.722142 +0.174391 0.702595 +0.971974 0.542674 +0.997245 0.542674 +0.945483 0.677450 +0.945090 0.678086 +0.944106 0.678729 +0.942501 0.679344 +0.940316 0.679891 +0.030977 0.686248 +0.002757 0.542674 +0.028028 0.542674 +0.054519 0.677450 +0.054913 0.678086 +0.055897 0.678729 +0.057502 0.679344 +0.059686 0.679891 +0.937665 0.680333 +0.934717 0.680649 +0.969025 0.686248 +0.931659 0.680832 +0.928665 0.680889 +0.845187 0.680889 +0.842125 0.680949 +0.838992 0.681141 +0.835977 0.681475 +0.833285 0.681941 +0.831099 0.682515 +0.829537 0.683157 +0.828636 0.683825 +0.828355 0.684479 +0.828355 0.700631 +0.853487 0.686248 +0.828074 0.701284 +0.827174 0.701952 +0.825612 0.702595 +0.823426 0.703169 +0.820734 0.703635 +0.817719 0.703968 +0.814586 0.704160 +0.853487 0.718553 +0.811523 0.704220 +0.188479 0.704220 +0.185416 0.704160 +0.182283 0.703968 +0.179268 0.703635 +0.176577 0.703169 +0.062337 0.680333 +0.129683 0.686248 +0.065286 0.680649 +0.068343 0.680832 +0.071337 0.680889 +0.132746 0.686308 +0.135879 0.686500 +0.138894 0.686834 +0.141585 0.687300 +0.154815 0.680889 +0.157878 0.680949 +0.161011 0.681141 +0.164026 0.681475 +0.166717 0.681941 +0.168903 0.682515 +0.170465 0.683158 +0.171366 0.683826 +0.143772 0.687874 +0.145334 0.688517 +0.171647 0.684479 +0.146235 0.689185 +0.146516 0.689838 +0.146516 0.718553 +0.171647 0.700631 +0.171928 0.701284 +0.172829 0.701952 +0.058978 0.686248 +0.046596 0.686248 +0.129683 0.686248 +0.129683 0.686248 +0.030977 0.686248 +0.030977 0.686248 +0.037749 0.686248 +0.091926 0.686248 +0.074363 0.686248 +0.950265 0.686248 +0.935326 0.686248 +0.874668 0.686248 +0.853487 0.686248 +0.853487 0.686248 +0.969025 0.686248 +0.896235 0.686248 +0.969025 0.686248 +0.916913 0.686248 +0.967100 0.686248 +0.960937 0.686248 +0.853487 0.719874 +0.853487 0.719206 +0.853487 0.686248 +0.853487 0.686248 +0.853487 0.699779 +0.853487 0.699888 +0.853487 0.700014 +0.853487 0.700417 +0.853487 0.701117 +0.853487 0.714963 +0.853487 0.715072 +0.853487 0.718564 +0.853487 0.719265 +0.853487 0.719936 +0.853487 0.720555 +0.853487 0.721096 +0.853487 0.721538 +0.853487 0.721866 +0.853487 0.722071 +0.853487 0.722142 +0.853487 0.714838 +0.853487 0.714434 +0.853487 0.713735 +0.853487 0.712756 +0.853487 0.711550 +0.853487 0.702096 +0.853487 0.718553 +0.853487 0.703301 +0.853487 0.704651 +0.853487 0.706054 +0.853487 0.707426 +0.853487 0.708797 +0.853487 0.710200 +0.853487 0.722142 +0.853487 0.722082 +0.853487 0.721890 +0.853487 0.721557 +0.853487 0.721091 +0.853487 0.720517 +0.002757 0.542674 +0.030977 0.686248 +0.030977 0.686248 +0.000641 0.531905 +0.001642 0.536998 +0.969025 0.686248 +0.969025 0.686248 +0.998360 0.536998 +0.999361 0.531905 +0.997245 0.542674 +0.971974 0.542674 +0.945483 0.677450 +0.945486 0.677435 +0.973511 0.534851 +0.972763 0.538660 +0.054516 0.677435 +0.054519 0.677450 +0.027240 0.538661 +0.026491 0.534851 +0.028028 0.542674 +0.835859 0.681449 +0.054666 0.677427 +0.028738 0.545513 +0.045434 0.545513 +0.055117 0.678109 +0.056165 0.678757 +0.057760 0.679350 +0.059850 0.679868 +0.062371 0.680292 +0.065228 0.680606 +0.068306 0.680799 +0.071511 0.680864 +0.954568 0.545513 +0.971264 0.545513 +0.928670 0.677275 +0.945336 0.677427 +0.944895 0.678107 +0.943856 0.678754 +0.942256 0.679349 +0.940160 0.679867 +0.937641 0.680289 +0.934789 0.680602 +0.931706 0.680797 +0.827269 0.677275 +0.928491 0.680864 +0.845070 0.680864 +0.842007 0.680924 +0.838874 0.681116 +0.071332 0.677275 +0.154933 0.680864 +0.157995 0.680924 +0.161128 0.681116 +0.164143 0.681449 +0.166835 0.681916 +0.172733 0.677275 +0.175796 0.677335 +0.178930 0.677527 +0.181945 0.677860 +0.184636 0.678326 +0.186823 0.678900 +0.188385 0.679543 +0.169021 0.682490 +0.189286 0.680211 +0.170583 0.683132 +0.171484 0.683800 +0.189567 0.680864 +0.171765 0.684454 +0.171765 0.700606 +0.172046 0.701259 +0.172946 0.701927 +0.174508 0.702570 +0.176694 0.703144 +0.179386 0.703610 +0.182401 0.703943 +0.185534 0.704135 +0.188597 0.704195 +0.811406 0.704195 +0.189567 0.700753 +0.814469 0.704135 +0.817602 0.703943 +0.820617 0.703610 +0.823308 0.703144 +0.825494 0.702570 +0.827056 0.701927 +0.827957 0.701259 +0.828238 0.700606 +0.810436 0.700753 +0.828238 0.684454 +0.828519 0.683800 +0.829420 0.683132 +0.830982 0.682489 +0.810436 0.680864 +0.810717 0.680211 +0.833168 0.681916 +0.811618 0.679543 +0.813180 0.678900 +0.815366 0.678326 +0.818058 0.677860 +0.821073 0.677527 +0.824206 0.677335 +0.828238 0.700606 +0.828238 0.684454 +0.828355 0.684479 +0.828355 0.700631 +0.928491 0.680864 +0.928669 0.680873 +0.845187 0.680889 +0.845070 0.680864 +0.928665 0.680889 +0.071337 0.680889 +0.071334 0.680874 +0.071511 0.680864 +0.154933 0.680864 +0.154815 0.680889 +0.171647 0.684479 +0.171765 0.684454 +0.171765 0.700606 +0.171647 0.700631 +0.188479 0.704220 +0.188597 0.704195 +0.811406 0.704195 +0.811523 0.704220 +0.997806 0.539817 +0.997245 0.542674 +0.940036 0.524791 +0.927982 0.524727 +0.979622 0.524727 +0.950679 0.525060 +0.959501 0.525650 +0.989702 0.525126 +0.966139 0.526652 +0.993427 0.525668 +0.996187 0.526451 +0.970553 0.528122 +0.998056 0.527485 +0.972909 0.530014 +0.999120 0.528752 +0.973714 0.532290 +0.999500 0.530231 +0.999361 0.531905 +0.973511 0.534851 +0.998885 0.534328 +0.972763 0.538660 +0.998360 0.536998 +0.971974 0.542674 +0.028028 0.542674 +0.002757 0.542674 +0.020381 0.524727 +0.072020 0.524727 +0.010263 0.525130 +0.060016 0.524791 +0.049385 0.525058 +0.006560 0.525673 +0.040615 0.525639 +0.003788 0.526462 +0.001934 0.527491 +0.033915 0.526641 +0.000876 0.528765 +0.029497 0.528097 +0.000500 0.530239 +0.027103 0.530001 +0.000641 0.531905 +0.001117 0.534328 +0.026289 0.532280 +0.001642 0.536998 +0.026491 0.534851 +0.002196 0.539817 +0.027240 0.538661 +0.045434 0.545513 +0.028738 0.545513 +0.109302 0.527598 +0.125998 0.527598 +0.087831 0.527644 +0.104615 0.527643 +0.067814 0.527893 +0.084645 0.527890 +0.050781 0.528655 +0.067638 0.528643 +0.038333 0.530309 +0.055161 0.530279 +0.034102 0.531548 +0.050920 0.531502 +0.031190 0.533035 +0.047936 0.533000 +0.029349 0.534769 +0.046075 0.534728 +0.028373 0.536690 +0.045078 0.536661 +0.028013 0.538757 +0.044710 0.538737 +0.028054 0.540955 +0.044748 0.540936 +0.028327 0.543210 +0.045022 0.543204 +0.971264 0.545513 +0.954568 0.545513 +0.895475 0.527644 +0.874004 0.527598 +0.890700 0.527598 +0.915492 0.527893 +0.912083 0.527643 +0.932525 0.528655 +0.932053 0.527890 +0.949060 0.528643 +0.944973 0.530309 +0.961536 0.530279 +0.949204 0.531548 +0.965778 0.531502 +0.952117 0.533035 +0.968762 0.533000 +0.953958 0.534769 +0.970623 0.534728 +0.954933 0.536690 +0.971620 0.536661 +0.955293 0.538757 +0.971988 0.538737 +0.955252 0.540955 +0.971950 0.540936 +0.954979 0.543210 +0.971676 0.543204 +0.954568 0.545513 +0.928670 0.677275 +0.859414 0.677275 +0.844585 0.677275 +0.874004 0.527598 +0.884840 0.527607 +0.874553 0.677275 +0.895475 0.527644 +0.889163 0.677275 +0.905782 0.527728 +0.915492 0.527893 +0.902335 0.677275 +0.924507 0.528186 +0.913256 0.677275 +0.932525 0.528655 +0.939423 0.529354 +0.921371 0.677275 +0.944973 0.530309 +0.926468 0.677275 +0.952117 0.533035 +0.954933 0.536690 +0.955252 0.540955 +0.073535 0.677275 +0.071332 0.677275 +0.125998 0.527598 +0.155417 0.677275 +0.115191 0.527607 +0.104615 0.527643 +0.140589 0.677275 +0.094316 0.527727 +0.125449 0.677275 +0.084645 0.527890 +0.075684 0.528178 +0.110839 0.677275 +0.067638 0.528643 +0.097667 0.677275 +0.060792 0.529326 +0.055161 0.530279 +0.086746 0.677275 +0.047936 0.533000 +0.078631 0.677275 +0.045078 0.536661 +0.044748 0.540936 +0.045434 0.545513 +0.108738 0.524727 +0.109302 0.527598 +0.054666 0.677427 +0.054516 0.677435 +0.028738 0.545513 +0.026491 0.534851 +0.028054 0.540955 +0.026289 0.532280 +0.028373 0.536690 +0.031190 0.533035 +0.027103 0.530001 +0.029497 0.528097 +0.038333 0.530309 +0.033915 0.526641 +0.043883 0.529354 +0.040615 0.525639 +0.050781 0.528655 +0.049385 0.525058 +0.058799 0.528186 +0.067814 0.527893 +0.060016 0.524791 +0.077525 0.527728 +0.072020 0.524727 +0.087831 0.527644 +0.098467 0.527607 +0.089902 0.524727 +0.971264 0.545513 +0.901507 0.527607 +0.890700 0.527598 +0.891264 0.524727 +0.912083 0.527643 +0.910100 0.524727 +0.922382 0.527727 +0.932053 0.527890 +0.927982 0.524727 +0.941014 0.528178 +0.940036 0.524791 +0.949060 0.528643 +0.955905 0.529326 +0.950679 0.525060 +0.961536 0.530279 +0.959501 0.525650 +0.968762 0.533000 +0.966139 0.526652 +0.971620 0.536661 +0.970553 0.528122 +0.972909 0.530014 +0.971950 0.540936 +0.973511 0.534851 +0.945486 0.677435 +0.945336 0.677427 +0.973714 0.532290 +0.969025 0.686248 +0.999361 0.531905 +0.848434 0.699778 +0.853487 0.699779 +0.882840 0.524727 +0.896637 0.524727 +0.853487 0.686248 +0.910541 0.524727 +0.874668 0.686248 +0.924245 0.524727 +0.937432 0.524727 +0.896235 0.686248 +0.949801 0.524727 +0.916913 0.686248 +0.961085 0.524727 +0.971073 0.524727 +0.935326 0.686248 +0.979622 0.524727 +0.989702 0.525126 +0.950265 0.686248 +0.996187 0.526451 +0.960937 0.686248 +0.999120 0.528752 +0.967100 0.686248 +0.836654 0.715054 +0.836742 0.715073 +0.702419 0.714963 +0.701993 0.715054 +0.853487 0.714963 +0.853487 0.715072 +0.845428 0.715073 +0.848434 0.699778 +0.836742 0.699778 +0.811405 0.699797 +0.810979 0.699888 +0.836654 0.699797 +0.853487 0.699888 +0.853487 0.699779 +0.163348 0.699797 +0.163260 0.699778 +0.146516 0.699888 +0.189023 0.699888 +0.188597 0.699797 +0.146516 0.699779 +0.151569 0.699778 +0.154575 0.715073 +0.163260 0.715073 +0.163348 0.715054 +0.298009 0.715054 +0.297583 0.714963 +0.146516 0.714963 +0.146516 0.715073 +0.218616 0.663406 +0.218977 0.663420 +0.218422 0.664712 +0.218054 0.664712 +0.285385 0.664712 +0.285018 0.664712 +0.284823 0.663406 +0.284462 0.663420 +0.283021 0.662070 +0.279897 0.660784 +0.282680 0.662099 +0.279590 0.660827 +0.275525 0.659636 +0.275265 0.659691 +0.270142 0.658704 +0.269941 0.658769 +0.264112 0.658037 +0.263976 0.658110 +0.257845 0.657653 +0.257779 0.657730 +0.251720 0.657533 +0.251720 0.657612 +0.245594 0.657653 +0.245661 0.657730 +0.239328 0.658037 +0.239463 0.658110 +0.233298 0.658704 +0.233499 0.658769 +0.227915 0.659636 +0.228174 0.659691 +0.223542 0.660784 +0.223849 0.660827 +0.220418 0.662070 +0.220759 0.662099 +0.241547 0.665571 +0.228174 0.669733 +0.242562 0.665989 +0.233499 0.670655 +0.243983 0.666362 +0.239463 0.671314 +0.245732 0.666665 +0.245661 0.671694 +0.247692 0.666882 +0.251720 0.671813 +0.249729 0.667006 +0.257779 0.671694 +0.251720 0.667045 +0.263976 0.671314 +0.253711 0.667006 +0.269941 0.670655 +0.255747 0.666882 +0.275265 0.669733 +0.257707 0.666665 +0.279590 0.668598 +0.259456 0.666362 +0.282680 0.667326 +0.260877 0.665989 +0.284462 0.666004 +0.261893 0.665571 +0.285018 0.664712 +0.262478 0.665137 +0.284462 0.663420 +0.262661 0.664712 +0.282680 0.662099 +0.262478 0.664288 +0.279590 0.660827 +0.261893 0.663853 +0.275265 0.659691 +0.260877 0.663436 +0.269941 0.658769 +0.259456 0.663062 +0.263976 0.658110 +0.257707 0.662759 +0.257779 0.657730 +0.255747 0.662543 +0.251720 0.657612 +0.253711 0.662418 +0.245661 0.657730 +0.251720 0.662379 +0.239463 0.658110 +0.249729 0.662418 +0.233499 0.658769 +0.247692 0.662543 +0.228174 0.659691 +0.245732 0.662759 +0.223849 0.660827 +0.243983 0.663062 +0.220759 0.662099 +0.242562 0.663436 +0.218977 0.663420 +0.241547 0.663853 +0.218422 0.664712 +0.240961 0.664288 +0.218977 0.666004 +0.240778 0.664712 +0.220759 0.667326 +0.240961 0.665137 +0.223849 0.668598 +0.715180 0.663406 +0.715541 0.663420 +0.714985 0.664712 +0.714617 0.664712 +0.781948 0.664712 +0.781581 0.664712 +0.781386 0.663406 +0.781025 0.663420 +0.779584 0.662070 +0.779243 0.662099 +0.776461 0.660784 +0.776153 0.660827 +0.772088 0.659636 +0.771828 0.659691 +0.766705 0.658704 +0.766504 0.658769 +0.760675 0.658037 +0.760540 0.658110 +0.754409 0.657653 +0.754342 0.657730 +0.748283 0.657533 +0.748283 0.657612 +0.742157 0.657653 +0.742224 0.657730 +0.735891 0.658037 +0.736026 0.658110 +0.729861 0.658704 +0.730062 0.658769 +0.724478 0.659636 +0.724738 0.659691 +0.720105 0.660784 +0.720412 0.660827 +0.716981 0.662070 +0.717323 0.662099 +0.738110 0.663853 +0.714985 0.664712 +0.737524 0.664288 +0.715541 0.666004 +0.737342 0.664712 +0.717323 0.667326 +0.737524 0.665137 +0.720412 0.668598 +0.738110 0.665571 +0.724738 0.669733 +0.739125 0.665989 +0.730062 0.670655 +0.740546 0.666362 +0.736026 0.671314 +0.742296 0.666665 +0.742224 0.671694 +0.744255 0.666882 +0.748283 0.671813 +0.746292 0.667006 +0.754342 0.671694 +0.748283 0.667045 +0.760540 0.671314 +0.750274 0.667006 +0.766504 0.670655 +0.752310 0.666882 +0.771828 0.669733 +0.754270 0.666665 +0.776153 0.668598 +0.756019 0.666362 +0.779243 0.667326 +0.757441 0.665989 +0.781025 0.666004 +0.758456 0.665571 +0.781581 0.664712 +0.759041 0.665137 +0.781025 0.663420 +0.759224 0.664712 +0.779243 0.662099 +0.759041 0.664288 +0.776153 0.660827 +0.758456 0.663853 +0.771828 0.659691 +0.757441 0.663436 +0.766504 0.658769 +0.756019 0.663062 +0.760540 0.658110 +0.754270 0.662759 +0.754342 0.657730 +0.752310 0.662543 +0.748283 0.657612 +0.750274 0.662418 +0.742224 0.657730 +0.748283 0.662379 +0.736026 0.658110 +0.746292 0.662418 +0.730062 0.658769 +0.744255 0.662543 +0.724738 0.659691 +0.742296 0.662759 +0.720412 0.660827 +0.740546 0.663062 +0.717323 0.662099 +0.739125 0.663436 +0.715541 0.663420 +0.230679 0.553442 +0.230311 0.553442 +0.163715 0.553442 +0.163348 0.553442 +0.164271 0.552150 +0.163910 0.552135 +0.166053 0.550828 +0.165712 0.550799 +0.169143 0.549556 +0.168836 0.549513 +0.173468 0.548421 +0.173208 0.548366 +0.178792 0.547499 +0.178591 0.547433 +0.184757 0.546840 +0.184621 0.546767 +0.190954 0.546460 +0.190888 0.546383 +0.197013 0.546341 +0.197013 0.546263 +0.203072 0.546460 +0.203139 0.546383 +0.209270 0.546840 +0.209405 0.546767 +0.215234 0.547499 +0.215435 0.547433 +0.220559 0.548421 +0.220818 0.548366 +0.224884 0.549556 +0.225191 0.549513 +0.227974 0.550828 +0.228315 0.550799 +0.229756 0.552150 +0.230117 0.552135 +0.207955 0.553442 +0.227974 0.550828 +0.207772 0.553017 +0.224884 0.549556 +0.207186 0.552583 +0.220559 0.548421 +0.206171 0.552165 +0.215234 0.547499 +0.204750 0.551792 +0.209270 0.546840 +0.203001 0.551489 +0.203072 0.546460 +0.201041 0.551272 +0.197013 0.546341 +0.199004 0.551148 +0.190954 0.546460 +0.197013 0.551109 +0.184757 0.546840 +0.195022 0.551148 +0.178792 0.547499 +0.192986 0.551272 +0.173468 0.548421 +0.191026 0.551489 +0.169143 0.549556 +0.189277 0.551792 +0.166053 0.550828 +0.187856 0.552165 +0.164271 0.552150 +0.186840 0.552583 +0.163715 0.553442 +0.186255 0.553017 +0.164271 0.554734 +0.186072 0.553442 +0.166053 0.556055 +0.186255 0.553866 +0.169143 0.557327 +0.186840 0.554300 +0.173468 0.558462 +0.187856 0.554718 +0.178792 0.559385 +0.189277 0.555091 +0.184757 0.560044 +0.191026 0.555394 +0.190954 0.560424 +0.192986 0.555611 +0.197013 0.560542 +0.195022 0.555736 +0.203072 0.560424 +0.197013 0.555775 +0.209270 0.560044 +0.199004 0.555736 +0.215234 0.559385 +0.201041 0.555611 +0.220559 0.558462 +0.203001 0.555394 +0.224884 0.557327 +0.204750 0.555091 +0.227974 0.556055 +0.206171 0.554718 +0.229756 0.554734 +0.207186 0.554300 +0.230311 0.553442 +0.207772 0.553866 +0.229756 0.552150 +0.769886 0.552135 +0.770247 0.552150 +0.769691 0.553442 +0.769324 0.553442 +0.836654 0.553442 +0.836287 0.553442 +0.836092 0.552135 +0.835731 0.552150 +0.834290 0.550799 +0.833949 0.550828 +0.831167 0.549513 +0.830859 0.549556 +0.826794 0.548365 +0.826534 0.548421 +0.821411 0.547433 +0.821210 0.547499 +0.815381 0.546767 +0.815246 0.546840 +0.809115 0.546383 +0.809048 0.546460 +0.802989 0.546263 +0.802989 0.546341 +0.796863 0.546383 +0.796930 0.546460 +0.790597 0.546767 +0.790732 0.546840 +0.784567 0.547433 +0.784768 0.547499 +0.779184 0.548365 +0.779444 0.548421 +0.774811 0.549513 +0.775118 0.549556 +0.771687 0.550799 +0.772029 0.550828 +0.812147 0.554718 +0.835731 0.554734 +0.813162 0.554300 +0.836287 0.553442 +0.813747 0.553866 +0.835731 0.552150 +0.813930 0.553442 +0.833949 0.550828 +0.813747 0.553017 +0.830859 0.549556 +0.813162 0.552583 +0.826534 0.548421 +0.812147 0.552165 +0.821210 0.547499 +0.810725 0.551792 +0.815246 0.546840 +0.808976 0.551489 +0.809048 0.546460 +0.807016 0.551272 +0.802989 0.546341 +0.804980 0.551147 +0.796930 0.546460 +0.802989 0.551109 +0.790732 0.546840 +0.800998 0.551147 +0.784768 0.547499 +0.798961 0.551272 +0.779444 0.548421 +0.797002 0.551489 +0.775118 0.549556 +0.795252 0.551792 +0.772029 0.550828 +0.793831 0.552165 +0.770247 0.552150 +0.792816 0.552583 +0.769691 0.553442 +0.792230 0.553017 +0.770247 0.554734 +0.792048 0.553442 +0.772029 0.556055 +0.792230 0.553866 +0.775118 0.557327 +0.792816 0.554300 +0.779444 0.558462 +0.793831 0.554718 +0.784768 0.559385 +0.795252 0.555091 +0.790732 0.560044 +0.797002 0.555394 +0.796930 0.560423 +0.798961 0.555611 +0.802989 0.560542 +0.800998 0.555736 +0.809048 0.560423 +0.802989 0.555775 +0.815246 0.560044 +0.804980 0.555736 +0.821210 0.559385 +0.807016 0.555611 +0.826534 0.558462 +0.808976 0.555394 +0.830859 0.557327 +0.810725 0.555091 +0.833949 0.556055 +0.251720 0.667045 +0.249729 0.667006 +0.242562 0.665989 +0.241547 0.665571 +0.243983 0.666362 +0.245732 0.666665 +0.240961 0.665137 +0.247692 0.666882 +0.240778 0.664712 +0.240961 0.664288 +0.241547 0.663853 +0.242562 0.663436 +0.243983 0.663062 +0.245732 0.662759 +0.247692 0.662543 +0.249729 0.662418 +0.251720 0.662379 +0.253711 0.662418 +0.255747 0.662543 +0.257707 0.662759 +0.259456 0.663062 +0.260877 0.663436 +0.261893 0.663853 +0.262478 0.664288 +0.262661 0.664712 +0.262478 0.665137 +0.261893 0.665571 +0.260877 0.665989 +0.259456 0.666362 +0.257707 0.666665 +0.255747 0.666882 +0.253711 0.667006 +0.240778 0.664712 +0.240778 0.664712 +0.262661 0.664712 +0.262661 0.664712 +0.262478 0.665137 +0.262478 0.665137 +0.261893 0.665571 +0.260877 0.665989 +0.261893 0.665571 +0.260877 0.665989 +0.259456 0.666362 +0.257707 0.666665 +0.259456 0.666362 +0.255747 0.666882 +0.257707 0.666665 +0.253711 0.667006 +0.255747 0.666882 +0.251720 0.667045 +0.253711 0.667006 +0.249729 0.667006 +0.251720 0.667045 +0.249729 0.667006 +0.247692 0.666882 +0.245732 0.666665 +0.247692 0.666882 +0.243983 0.666362 +0.245732 0.666665 +0.242562 0.665989 +0.243983 0.666362 +0.242562 0.665989 +0.241547 0.665571 +0.241547 0.665571 +0.240961 0.665137 +0.240961 0.665137 +0.748283 0.667045 +0.746292 0.667006 +0.739125 0.665989 +0.738110 0.665571 +0.740546 0.666362 +0.742296 0.666665 +0.737524 0.665137 +0.744255 0.666882 +0.737342 0.664712 +0.737524 0.664288 +0.738110 0.663853 +0.739125 0.663436 +0.740546 0.663062 +0.742296 0.662759 +0.744255 0.662543 +0.746292 0.662418 +0.748283 0.662379 +0.750274 0.662418 +0.752310 0.662543 +0.754270 0.662759 +0.756019 0.663062 +0.757441 0.663436 +0.758456 0.663853 +0.759041 0.664288 +0.759224 0.664712 +0.759041 0.665137 +0.758456 0.665571 +0.757441 0.665989 +0.756019 0.666362 +0.754270 0.666665 +0.752310 0.666882 +0.750274 0.667006 +0.738110 0.665571 +0.737524 0.665137 +0.737342 0.664712 +0.737342 0.664712 +0.759224 0.664712 +0.759224 0.664712 +0.759041 0.665137 +0.758456 0.665571 +0.759041 0.665137 +0.758456 0.665571 +0.757441 0.665989 +0.756019 0.666362 +0.757441 0.665989 +0.756019 0.666362 +0.754270 0.666665 +0.754270 0.666665 +0.752310 0.666882 +0.752310 0.666882 +0.750274 0.667006 +0.750274 0.667006 +0.748283 0.667045 +0.748283 0.667045 +0.746292 0.667006 +0.746292 0.667006 +0.744255 0.666882 +0.744255 0.666882 +0.742296 0.666665 +0.742296 0.666665 +0.740546 0.666362 +0.740546 0.666362 +0.739125 0.665989 +0.739125 0.665989 +0.738110 0.665571 +0.737524 0.665137 +0.802989 0.555775 +0.800998 0.555736 +0.793831 0.554718 +0.792816 0.554300 +0.795252 0.555091 +0.797002 0.555394 +0.792230 0.553866 +0.798961 0.555611 +0.792048 0.553442 +0.792230 0.553017 +0.792816 0.552583 +0.793831 0.552165 +0.795252 0.551792 +0.797002 0.551489 +0.798961 0.551272 +0.800998 0.551147 +0.802989 0.551109 +0.804980 0.551147 +0.807016 0.551272 +0.808976 0.551489 +0.810725 0.551792 +0.812147 0.552165 +0.813162 0.552583 +0.813747 0.553017 +0.813930 0.553442 +0.813747 0.553866 +0.813162 0.554300 +0.812147 0.554718 +0.810725 0.555091 +0.808976 0.555394 +0.807016 0.555611 +0.804980 0.555736 +0.792816 0.554300 +0.792230 0.553866 +0.792048 0.553442 +0.792048 0.553442 +0.792816 0.554300 +0.792230 0.553866 +0.813930 0.553442 +0.813930 0.553442 +0.813747 0.553866 +0.813162 0.554300 +0.813747 0.553866 +0.813162 0.554300 +0.812147 0.554718 +0.812147 0.554718 +0.810725 0.555091 +0.810725 0.555091 +0.808976 0.555394 +0.808976 0.555394 +0.807016 0.555611 +0.807016 0.555611 +0.804980 0.555736 +0.802989 0.555775 +0.804980 0.555736 +0.802989 0.555775 +0.800998 0.555736 +0.800998 0.555736 +0.798961 0.555611 +0.798961 0.555611 +0.797002 0.555394 +0.797002 0.555394 +0.795252 0.555091 +0.793831 0.554718 +0.795252 0.555091 +0.793831 0.554718 +0.197013 0.555775 +0.195022 0.555736 +0.187856 0.554718 +0.186840 0.554300 +0.189277 0.555091 +0.191026 0.555394 +0.186255 0.553866 +0.192986 0.555611 +0.186072 0.553442 +0.186255 0.553017 +0.186840 0.552583 +0.187856 0.552165 +0.189277 0.551792 +0.191026 0.551489 +0.192986 0.551272 +0.195022 0.551148 +0.197013 0.551109 +0.199004 0.551148 +0.201041 0.551272 +0.203001 0.551489 +0.204750 0.551792 +0.206171 0.552165 +0.207186 0.552583 +0.207772 0.553017 +0.207955 0.553442 +0.207772 0.553866 +0.207186 0.554300 +0.206171 0.554718 +0.204750 0.555091 +0.203001 0.555394 +0.201041 0.555611 +0.199004 0.555736 +0.207772 0.553866 +0.207955 0.553442 +0.186255 0.553866 +0.186072 0.553442 +0.186072 0.553442 +0.186840 0.554300 +0.186255 0.553866 +0.186840 0.554300 +0.187856 0.554718 +0.187856 0.554718 +0.189277 0.555091 +0.191026 0.555394 +0.189277 0.555091 +0.191026 0.555394 +0.192986 0.555611 +0.192986 0.555611 +0.195022 0.555736 +0.197013 0.555775 +0.195022 0.555736 +0.197013 0.555775 +0.199004 0.555736 +0.199004 0.555736 +0.201041 0.555611 +0.201041 0.555611 +0.203001 0.555394 +0.203001 0.555394 +0.204750 0.555091 +0.204750 0.555091 +0.206171 0.554718 +0.206171 0.554718 +0.207186 0.554300 +0.207186 0.554300 +0.207772 0.553866 +0.207955 0.553442 +0.836742 0.715073 +0.836654 0.715054 +0.836654 0.716758 +0.836742 0.716777 +0.836654 0.533700 +0.836654 0.699797 +0.836742 0.699778 +0.836742 0.533681 +0.163260 0.699778 +0.163348 0.699797 +0.163348 0.533700 +0.163260 0.533681 +0.676744 0.704195 +0.701993 0.715054 +0.554220 0.577774 +0.811405 0.699797 +0.836654 0.699797 +0.811405 0.680864 +0.811124 0.680211 +0.810223 0.679543 +0.808662 0.678900 +0.806475 0.678326 +0.803784 0.677860 +0.800769 0.677527 +0.797636 0.677335 +0.794573 0.677275 +0.836654 0.716758 +0.836654 0.715054 +0.836514 0.717085 +0.836063 0.717419 +0.835283 0.717740 +0.834189 0.718027 +0.832844 0.718260 +0.831336 0.718427 +0.829770 0.718523 +0.828238 0.718553 +0.163348 0.533700 +0.163348 0.699797 +0.188597 0.699797 +0.188597 0.680864 +0.188878 0.680211 +0.189779 0.679543 +0.191341 0.678900 +0.193527 0.678326 +0.196218 0.677860 +0.199233 0.677527 +0.202366 0.677335 +0.600997 0.716758 +0.584165 0.704195 +0.415838 0.716758 +0.399005 0.704195 +0.491585 0.704195 +0.508418 0.716758 +0.298009 0.715054 +0.163348 0.715054 +0.163348 0.716758 +0.163489 0.717085 +0.163939 0.717419 +0.164720 0.717740 +0.165813 0.718027 +0.167159 0.718260 +0.168666 0.718427 +0.170233 0.718523 +0.718825 0.677275 +0.205429 0.677275 +0.600997 0.704195 +0.541959 0.575650 +0.828238 0.531905 +0.528225 0.574133 +0.513953 0.573258 +0.500001 0.572985 +0.486049 0.573258 +0.471777 0.574133 +0.458043 0.575650 +0.445783 0.577774 +0.435823 0.580388 +0.428708 0.583317 +0.564179 0.580388 +0.281177 0.677275 +0.715762 0.677335 +0.712629 0.677527 +0.284240 0.677335 +0.571294 0.583317 +0.424605 0.586360 +0.287373 0.677527 +0.709614 0.677860 +0.171764 0.531905 +0.170233 0.531935 +0.168666 0.532031 +0.167159 0.532198 +0.165813 0.532431 +0.164720 0.532718 +0.163939 0.533039 +0.163489 0.533373 +0.423324 0.589335 +0.424605 0.592311 +0.428708 0.595354 +0.435823 0.598283 +0.445783 0.600897 +0.458043 0.603021 +0.471777 0.604538 +0.290388 0.677860 +0.486049 0.605413 +0.293080 0.678326 +0.500001 0.605686 +0.295266 0.678900 +0.513954 0.605413 +0.829769 0.531935 +0.831336 0.532031 +0.832843 0.532198 +0.834189 0.532431 +0.835282 0.532718 +0.836063 0.533039 +0.836514 0.533373 +0.836654 0.533700 +0.575398 0.586360 +0.576678 0.589335 +0.575398 0.592311 +0.571294 0.595354 +0.564179 0.598282 +0.554220 0.600897 +0.541959 0.603021 +0.528225 0.604538 +0.706923 0.678326 +0.704737 0.678900 +0.703175 0.679543 +0.296828 0.679543 +0.702274 0.680211 +0.297728 0.680211 +0.701993 0.680864 +0.508418 0.704195 +0.415838 0.704195 +0.323258 0.704195 +0.298009 0.680864 +0.323258 0.716758 +0.171764 0.718553 +0.676744 0.716758 +0.584165 0.716758 +0.491585 0.716758 +0.399005 0.716758 +0.171764 0.718553 +0.171676 0.718572 +0.828326 0.718572 +0.828238 0.718553 +0.163348 0.716758 +0.163348 0.715054 +0.163260 0.715073 +0.163260 0.716777 +0.171764 0.531905 +0.828238 0.531905 +0.828326 0.531887 +0.171676 0.531887 +0.675995 0.707785 +0.675877 0.707785 +0.676744 0.716758 +0.676744 0.704195 +0.675995 0.704355 +0.675877 0.716573 +0.324125 0.716573 +0.324125 0.707785 +0.323258 0.704195 +0.323258 0.716758 +0.324008 0.707785 +0.324008 0.704355 +0.601746 0.707785 +0.601746 0.704355 +0.600997 0.704195 +0.600997 0.716758 +0.601864 0.716573 +0.601864 0.707785 +0.583415 0.707785 +0.583298 0.707785 +0.584165 0.716758 +0.584165 0.704195 +0.583415 0.704355 +0.583298 0.716573 +0.509167 0.707785 +0.509167 0.704355 +0.508418 0.704195 +0.508418 0.716758 +0.509284 0.716573 +0.509284 0.707785 +0.490836 0.707785 +0.490718 0.707785 +0.491585 0.716758 +0.491585 0.704195 +0.490836 0.704355 +0.490718 0.716573 +0.416705 0.716573 +0.416705 0.707785 +0.415838 0.704195 +0.415838 0.716758 +0.416587 0.707785 +0.416587 0.704355 +0.398256 0.707785 +0.398139 0.707785 +0.399005 0.716758 +0.399005 0.704195 +0.398256 0.704355 +0.398139 0.716573 +0.155259 0.719206 +0.155259 0.718553 +0.146516 0.722074 +0.146516 0.722142 +0.155259 0.722142 +0.155259 0.722082 +0.146516 0.721871 +0.155259 0.721890 +0.146516 0.721541 +0.155259 0.721557 +0.146516 0.721098 +0.146516 0.720557 +0.155259 0.721091 +0.146516 0.719939 +0.155259 0.720517 +0.146516 0.719267 +0.155259 0.719874 +0.146516 0.718564 +0.828326 0.718572 +0.844744 0.719288 +0.844744 0.718553 +0.829541 0.718553 +0.155259 0.722066 +0.155259 0.722142 +0.844744 0.722142 +0.844744 0.722066 +0.155259 0.721847 +0.155259 0.721510 +0.844744 0.721847 +0.844744 0.721510 +0.155259 0.721091 +0.170461 0.718553 +0.155259 0.718553 +0.171676 0.718572 +0.844744 0.721091 +0.155259 0.720587 +0.844744 0.720587 +0.155259 0.719978 +0.844744 0.719978 +0.155259 0.719288 +0.853487 0.718564 +0.844744 0.718553 +0.844744 0.722142 +0.853487 0.722142 +0.844744 0.722082 +0.844744 0.721890 +0.853487 0.722071 +0.844744 0.721557 +0.853487 0.721866 +0.844744 0.721091 +0.853487 0.721538 +0.853487 0.721096 +0.844744 0.720517 +0.853487 0.720555 +0.844744 0.719874 +0.853487 0.719936 +0.844744 0.719206 +0.853487 0.719265 +0.054909 0.678070 +0.054516 0.677435 +0.068306 0.680799 +0.071511 0.680864 +0.071334 0.680874 +0.068340 0.680816 +0.065228 0.680606 +0.065282 0.680633 +0.062371 0.680292 +0.062334 0.680317 +0.059850 0.679868 +0.057760 0.679350 +0.059683 0.679875 +0.056165 0.678757 +0.057499 0.679329 +0.055117 0.678109 +0.055894 0.678714 +0.054666 0.677427 +0.054913 0.678086 +0.054519 0.677450 +0.071334 0.680874 +0.071337 0.680889 +0.068231 0.680812 +0.068343 0.680832 +0.064973 0.680607 +0.065286 0.680649 +0.062088 0.680284 +0.062337 0.680333 +0.059683 0.679875 +0.059686 0.679891 +0.057667 0.679380 +0.056029 0.678779 +0.057502 0.679344 +0.054934 0.678093 +0.055897 0.678729 +0.054516 0.677435 +0.945336 0.677427 +0.945486 0.677435 +0.928669 0.680873 +0.928491 0.680864 +0.931662 0.680816 +0.934720 0.680633 +0.931706 0.680797 +0.937669 0.680317 +0.934789 0.680602 +0.940319 0.679875 +0.937641 0.680289 +0.940160 0.679867 +0.942504 0.679329 +0.942256 0.679349 +0.944109 0.678714 +0.943856 0.678754 +0.945093 0.678070 +0.944895 0.678107 +0.945486 0.677435 +0.945483 0.677450 +0.928665 0.680889 +0.928669 0.680873 +0.931659 0.680832 +0.934717 0.680649 +0.931772 0.680812 +0.937665 0.680333 +0.935029 0.680607 +0.940316 0.679891 +0.937914 0.680284 +0.942501 0.679344 +0.940319 0.679875 +0.942335 0.679380 +0.944106 0.678729 +0.943973 0.678778 +0.945090 0.678086 +0.945068 0.678093 +0.811523 0.704220 +0.811406 0.704195 +0.827957 0.701259 +0.828238 0.700606 +0.828355 0.700631 +0.827056 0.701927 +0.828074 0.701284 +0.825494 0.702570 +0.827174 0.701952 +0.824474 0.702868 +0.825612 0.702595 +0.823308 0.703144 +0.824591 0.702893 +0.823426 0.703169 +0.822015 0.703393 +0.822133 0.703418 +0.820617 0.703610 +0.820734 0.703635 +0.817602 0.703943 +0.817719 0.703968 +0.814469 0.704135 +0.814586 0.704160 +0.845070 0.680864 +0.845187 0.680889 +0.828636 0.683825 +0.828355 0.684479 +0.828238 0.684454 +0.829537 0.683157 +0.828519 0.683800 +0.831099 0.682515 +0.829420 0.683132 +0.832120 0.682216 +0.830982 0.682489 +0.833285 0.681941 +0.832002 0.682191 +0.833168 0.681916 +0.834578 0.681692 +0.834461 0.681667 +0.835977 0.681475 +0.835859 0.681449 +0.838992 0.681141 +0.838874 0.681116 +0.842125 0.680949 +0.842007 0.680924 +0.171647 0.700631 +0.171765 0.700606 +0.185534 0.704135 +0.188597 0.704195 +0.188479 0.704220 +0.182401 0.703943 +0.185416 0.704160 +0.179386 0.703610 +0.182283 0.703968 +0.177987 0.703393 +0.179268 0.703635 +0.176694 0.703144 +0.177870 0.703418 +0.176577 0.703169 +0.175529 0.702868 +0.175411 0.702893 +0.174508 0.702570 +0.174391 0.702595 +0.172946 0.701927 +0.172829 0.701952 +0.172046 0.701259 +0.171928 0.701284 +0.132947 0.686316 +0.129683 0.686248 +0.146516 0.689838 +0.146516 0.689838 +0.146158 0.689102 +0.146185 0.689132 +0.145131 0.688412 +0.145221 0.688457 +0.143553 0.687804 +0.143656 0.687837 +0.141585 0.687300 +0.139221 0.686880 +0.141555 0.687293 +0.136369 0.686544 +0.139000 0.686849 +0.133132 0.686325 +0.136088 0.686518 +0.129683 0.686248 +0.171765 0.684454 +0.171647 0.684479 +0.157878 0.680949 +0.154815 0.680889 +0.154933 0.680864 +0.161011 0.681141 +0.157995 0.680924 +0.164026 0.681475 +0.161128 0.681116 +0.165424 0.681692 +0.164143 0.681449 +0.166717 0.681941 +0.165542 0.681667 +0.166835 0.681916 +0.167883 0.682216 +0.168000 0.682191 +0.168903 0.682515 +0.169021 0.682490 +0.170465 0.683158 +0.170583 0.683132 +0.171366 0.683826 +0.171484 0.683800 +0.163260 0.533681 +0.163348 0.533700 +0.170233 0.531935 +0.171764 0.531905 +0.171676 0.531887 +0.168666 0.532031 +0.170144 0.531917 +0.167159 0.532198 +0.168578 0.532013 +0.166459 0.532307 +0.167071 0.532179 +0.165813 0.532431 +0.166371 0.532288 +0.165725 0.532412 +0.165230 0.532569 +0.165142 0.532550 +0.164720 0.532718 +0.164632 0.532699 +0.163939 0.533039 +0.163851 0.533021 +0.163489 0.533373 +0.163400 0.533355 +0.828326 0.531887 +0.828238 0.531905 +0.836514 0.533373 +0.836654 0.533700 +0.836742 0.533681 +0.836602 0.533355 +0.836063 0.533039 +0.836151 0.533021 +0.835282 0.532718 +0.835370 0.532699 +0.834772 0.532569 +0.834860 0.532550 +0.834189 0.532431 +0.834277 0.532412 +0.833543 0.532307 +0.833631 0.532288 +0.832843 0.532198 +0.832932 0.532179 +0.831336 0.532031 +0.831424 0.532013 +0.829769 0.531935 +0.829858 0.531917 +0.836624 0.717077 +0.836742 0.716777 +0.829770 0.718523 +0.828238 0.718553 +0.828326 0.718572 +0.829541 0.718553 +0.831336 0.718427 +0.830919 0.718484 +0.832844 0.718260 +0.832285 0.718361 +0.833543 0.718151 +0.833567 0.718181 +0.834189 0.718027 +0.834772 0.717889 +0.834692 0.717951 +0.835283 0.717740 +0.836063 0.717419 +0.835599 0.717680 +0.836514 0.717085 +0.836247 0.717384 +0.836654 0.716758 +0.170461 0.718553 +0.171676 0.718572 +0.163489 0.717085 +0.163348 0.716758 +0.163260 0.716777 +0.163379 0.717077 +0.163939 0.717419 +0.163755 0.717384 +0.164720 0.717740 +0.164403 0.717680 +0.165230 0.717889 +0.165813 0.718027 +0.165310 0.717951 +0.166460 0.718152 +0.167159 0.718260 +0.166436 0.718181 +0.168666 0.718427 +0.167718 0.718361 +0.170233 0.718523 +0.169084 0.718484 +0.171764 0.718553 +0.702681 0.703448 +0.810717 0.703448 +0.810728 0.702501 +0.702670 0.702501 +0.810728 0.702749 +0.702671 0.702749 +0.810725 0.702994 +0.702673 0.702994 +0.810722 0.703229 +0.702676 0.703229 +0.297258 0.700707 +0.189348 0.700707 +0.189281 0.703270 +0.189285 0.703448 +0.297321 0.703448 +0.297325 0.703270 +0.189278 0.703070 +0.297329 0.703070 +0.189276 0.702851 +0.297331 0.702851 +0.189274 0.702614 +0.297332 0.702614 +0.189274 0.702366 +0.297332 0.702366 +0.189276 0.702112 +0.297331 0.702112 +0.189279 0.701862 +0.297328 0.701862 +0.189284 0.701622 +0.297323 0.701622 +0.189290 0.701402 +0.297317 0.701402 +0.189297 0.701207 +0.297310 0.701207 +0.189305 0.701043 +0.297302 0.701043 +0.189313 0.700913 +0.297293 0.700913 +0.189322 0.700816 +0.297284 0.700816 +0.189331 0.700751 +0.297275 0.700751 +0.189340 0.700716 +0.297267 0.700716 +0.794573 0.677275 +0.794294 0.677334 +0.810845 0.680271 +0.811126 0.680924 +0.811405 0.680864 +0.809944 0.679603 +0.811124 0.680211 +0.808383 0.678960 +0.810223 0.679543 +0.807362 0.678661 +0.808662 0.678900 +0.806196 0.678386 +0.807641 0.678602 +0.806475 0.678326 +0.804903 0.678137 +0.805183 0.678078 +0.803505 0.677920 +0.803784 0.677860 +0.800490 0.677586 +0.800769 0.677527 +0.797357 0.677394 +0.797636 0.677335 +0.701993 0.680864 +0.702272 0.680924 +0.716041 0.677394 +0.719104 0.677334 +0.718825 0.677275 +0.712908 0.677586 +0.715762 0.677335 +0.709893 0.677920 +0.712629 0.677527 +0.708495 0.678137 +0.709614 0.677860 +0.707202 0.678386 +0.708216 0.678078 +0.706923 0.678326 +0.706037 0.678661 +0.705757 0.678602 +0.705016 0.678960 +0.704737 0.678900 +0.703454 0.679603 +0.703175 0.679543 +0.702553 0.680271 +0.702274 0.680211 +0.281177 0.677275 +0.280898 0.677334 +0.297449 0.680271 +0.297730 0.680924 +0.298009 0.680864 +0.296549 0.679603 +0.297728 0.680211 +0.294987 0.678960 +0.296828 0.679543 +0.293966 0.678661 +0.295266 0.678900 +0.292800 0.678386 +0.294245 0.678602 +0.293080 0.678326 +0.291508 0.678137 +0.291787 0.678078 +0.290109 0.677920 +0.290388 0.677860 +0.287094 0.677586 +0.287373 0.677527 +0.283961 0.677394 +0.284240 0.677335 +0.188597 0.680864 +0.188876 0.680924 +0.202645 0.677394 +0.205708 0.677334 +0.205429 0.677275 +0.199512 0.677586 +0.202366 0.677335 +0.196498 0.677920 +0.199233 0.677527 +0.195099 0.678137 +0.196218 0.677860 +0.193806 0.678386 +0.194820 0.678078 +0.193527 0.678326 +0.192641 0.678661 +0.192362 0.678602 +0.191620 0.678960 +0.191341 0.678900 +0.190058 0.679603 +0.189779 0.679543 +0.189157 0.680271 +0.188878 0.680211 +0.824896 0.677335 +0.827959 0.677275 +0.810717 0.680211 +0.810436 0.680864 +0.811126 0.680864 +0.811618 0.679543 +0.811407 0.680211 +0.813180 0.678900 +0.812308 0.679543 +0.814200 0.678602 +0.813870 0.678900 +0.815366 0.678326 +0.814891 0.678602 +0.816659 0.678078 +0.816057 0.678326 +0.818058 0.677860 +0.817349 0.678078 +0.821073 0.677527 +0.818748 0.677860 +0.824206 0.677335 +0.821763 0.677527 +0.827269 0.677275 +0.172733 0.677275 +0.172043 0.677275 +0.188876 0.680864 +0.189567 0.680864 +0.188595 0.680211 +0.189286 0.680211 +0.187694 0.679543 +0.188385 0.679543 +0.186132 0.678900 +0.186823 0.678900 +0.185112 0.678602 +0.185802 0.678602 +0.183946 0.678326 +0.184636 0.678326 +0.182653 0.678078 +0.183343 0.678078 +0.181254 0.677860 +0.181945 0.677860 +0.178239 0.677527 +0.178930 0.677527 +0.175106 0.677335 +0.175796 0.677335 +0.853487 0.719288 +0.146516 0.719288 +0.146516 0.718553 +0.853487 0.718553 +0.853487 0.722142 +0.146516 0.722142 +0.853487 0.722066 +0.146516 0.722066 +0.853487 0.721847 +0.146516 0.721847 +0.853487 0.721510 +0.853487 0.721091 +0.146516 0.721510 +0.146516 0.721091 +0.853487 0.720587 +0.853487 0.719978 +0.146516 0.720587 +0.146516 0.719978 +0.575628 0.592320 +0.576912 0.589335 +0.419365 0.592517 +0.417996 0.589335 +0.423090 0.589335 +0.424374 0.592320 +0.423753 0.595772 +0.428490 0.595372 +0.431363 0.598904 +0.435627 0.598310 +0.442014 0.601700 +0.445617 0.600932 +0.455127 0.603972 +0.457915 0.603063 +0.469815 0.605594 +0.471690 0.604584 +0.485079 0.606530 +0.500001 0.606822 +0.486006 0.605462 +0.500001 0.605736 +0.514923 0.606530 +0.513996 0.605462 +0.530187 0.605594 +0.528312 0.604584 +0.544875 0.603972 +0.542088 0.603063 +0.557988 0.601700 +0.554386 0.600932 +0.568639 0.598904 +0.564376 0.598310 +0.576249 0.595772 +0.580638 0.592517 +0.571512 0.595372 +0.582007 0.589335 + + + + + + + + + + + +

32 0 32 0 1 0 1 2 1 4 3 4 2 4 2 3 5 3 5 6 5 2 7 2 4 8 4 8 9 8 2 10 2 5 11 5 8 12 8 6 13 6 2 14 2 8 15 8 7 16 7 6 17 6 9 18 9 7 19 7 8 20 8 11 21 11 7 22 7 9 23 9 11 24 11 10 25 10 7 26 7 13 27 13 10 28 10 11 29 11 13 30 13 12 31 12 10 32 10 15 33 15 12 34 12 13 35 13 15 36 15 14 37 14 12 38 12 17 39 17 14 40 14 15 41 15 17 42 17 16 43 16 14 44 14 19 45 19 16 46 16 17 47 17 19 48 19 18 49 18 16 50 16 21 51 21 18 52 18 19 53 19 21 54 21 20 55 20 18 56 18 23 57 23 20 58 20 21 59 21 23 60 23 22 61 22 20 62 20 25 63 25 22 64 22 23 65 23 25 66 25 24 67 24 22 68 22 27 69 27 24 70 24 25 71 25 27 72 27 26 73 26 24 74 24 29 75 29 26 76 26 27 77 27 29 78 29 28 79 28 26 80 26 31 81 31 28 82 28 29 83 29 31 84 31 30 85 30 28 86 28 33 87 33 30 88 30 31 89 31 33 90 33 32 91 32 30 92 30 0 93 0 32 94 32 33 95 33 54 96 54 34 97 34 35 98 35 39 99 39 36 100 36 37 101 37 39 102 39 38 103 38 36 104 36 41 105 41 38 106 38 39 107 39 41 108 41 40 109 40 38 110 38 43 111 43 40 112 40 41 113 41 43 114 43 42 115 42 40 116 40 45 117 45 42 118 42 43 119 43 45 120 45 44 121 44 42 122 42 47 123 47 44 124 44 45 125 45 47 126 47 46 127 46 44 128 44 49 129 49 46 130 46 47 131 47 49 132 49 48 133 48 46 134 46 51 135 51 48 136 48 49 137 49 51 138 51 50 139 50 48 140 48 53 141 53 50 142 50 51 143 51 53 144 53 52 145 52 50 146 50 55 147 55 52 148 52 53 149 53 55 150 55 54 151 54 52 152 52 34 153 34 54 154 54 55 155 55 88 156 88 56 157 56 57 158 57 62 159 62 58 160 58 59 161 59 62 162 62 60 163 60 58 164 58 62 165 62 61 166 61 60 167 60 63 168 63 61 169 61 62 170 62 66 171 66 61 172 61 63 173 63 66 174 66 64 175 64 61 176 61 66 177 66 65 178 65 64 179 64 67 180 67 65 181 65 66 182 66 69 183 69 65 184 65 67 185 67 69 186 69 68 187 68 65 188 65 72 189 72 68 190 68 69 191 69 72 192 72 70 193 70 68 194 68 72 195 72 71 196 71 70 197 70 74 198 74 71 199 71 72 200 72 74 201 74 73 202 73 71 203 71 75 204 75 73 205 73 74 206 74 77 207 77 73 208 73 75 209 75 77 210 77 76 211 76 73 212 73 79 213 79 76 214 76 77 215 77 79 216 79 78 217 78 76 218 76 81 219 81 78 220 78 79 221 79 81 222 81 80 223 80 78 224 78 83 225 83 80 226 80 81 227 81 83 228 83 82 229 82 80 230 80 85 231 85 82 232 82 83 233 83 85 234 85 84 235 84 82 236 82 87 237 87 84 238 84 85 239 85 87 240 87 86 241 86 84 242 84 89 243 89 86 244 86 87 245 87 89 246 89 88 247 88 86 248 86 56 249 56 88 250 88 89 251 89 122 252 122 91 253 91 90 254 90 93 255 93 91 256 91 92 257 92 90 258 90 91 259 91 93 260 93 96 261 96 94 262 94 95 263 95 97 264 97 94 265 94 96 266 96 99 267 99 94 268 94 97 269 97 99 270 99 98 271 98 94 272 94 101 273 101 98 274 98 99 275 99 101 276 101 100 277 100 98 278 98 103 279 103 100 280 100 101 281 101 103 282 103 102 283 102 100 284 100 105 285 105 102 286 102 103 287 103 105 288 105 104 289 104 102 290 102 107 291 107 104 292 104 105 293 105 107 294 107 106 295 106 104 296 104 109 297 109 106 298 106 107 299 107 109 300 109 108 301 108 106 302 106 111 303 111 108 304 108 109 305 109 111 306 111 110 307 110 108 308 108 113 309 113 110 310 110 111 311 111 113 312 113 112 313 112 110 314 110 116 315 116 112 316 112 113 317 113 116 318 116 114 319 114 112 320 112 116 321 116 115 322 115 114 323 114 117 324 117 115 325 115 116 326 116 119 327 119 115 328 115 117 329 117 119 330 119 118 331 118 115 332 115 121 333 121 118 334 118 119 335 119 121 336 121 120 337 120 118 338 118 123 339 123 120 340 120 121 341 121 123 342 123 122 343 122 120 344 120 91 345 91 122 346 122 123 347 123 156 348 156 132 349 132 124 350 124 129 351 129 125 352 125 126 353 126 129 354 129 127 355 127 125 356 125 129 357 129 128 358 128 127 359 127 131 360 131 128 361 128 129 362 129 131 363 131 130 364 130 128 365 128 133 366 133 130 367 130 131 368 131 133 369 133 132 370 132 130 371 130 124 372 124 132 373 132 133 374 133 136 375 136 134 376 134 135 377 135 137 378 137 134 379 134 136 380 136 139 381 139 134 382 134 137 383 137 139 384 139 138 385 138 134 386 134 141 387 141 138 388 138 139 389 139 141 390 141 140 391 140 138 392 138 144 393 144 140 394 140 141 395 141 144 396 144 142 397 142 140 398 140 144 399 144 143 400 143 142 401 142 145 402 145 143 403 143 144 404 144 147 405 147 143 406 143 145 407 145 147 408 147 146 409 146 143 410 143 149 411 149 146 412 146 147 413 147 149 414 149 148 415 148 146 416 146 151 417 151 148 418 148 149 419 149 151 420 151 150 421 150 148 422 148 153 423 153 150 424 150 151 425 151 153 426 153 152 427 152 150 428 150 155 429 155 152 430 152 153 431 153 155 432 155 154 433 154 152 434 152 157 435 157 154 436 154 155 437 155 157 438 157 156 439 156 154 440 154 132 441 132 156 442 156 157 443 157 190 444 190 159 445 159 158 446 158 161 447 161 159 448 159 160 449 160 158 450 158 159 451 159 161 452 161 165 453 165 162 454 162 163 455 163 165 456 165 164 457 164 162 458 162 167 459 167 164 460 164 165 461 165 167 462 167 166 463 166 164 464 164 170 465 170 166 466 166 167 467 167 170 468 170 168 469 168 166 470 166 170 471 170 169 472 169 168 473 168 171 474 171 169 475 169 170 476 170 173 477 173 169 478 169 171 479 171 173 480 173 172 481 172 169 482 169 175 483 175 172 484 172 173 485 173 175 486 175 174 487 174 172 488 172 177 489 177 174 490 174 175 491 175 177 492 177 176 493 176 174 494 174 179 495 179 176 496 176 177 497 177 179 498 179 178 499 178 176 500 176 181 501 181 178 502 178 179 503 179 181 504 181 180 505 180 178 506 178 183 507 183 180 508 180 181 509 181 183 510 183 182 511 182 180 512 180 185 513 185 182 514 182 183 515 183 185 516 185 184 517 184 182 518 182 187 519 187 184 520 184 185 521 185 187 522 187 186 523 186 184 524 184 189 525 189 186 526 186 187 527 187 189 528 189 188 529 188 186 530 186 191 531 191 188 532 188 189 533 189 191 534 191 190 535 190 188 536 188 159 537 159 190 538 190 191 539 191 224 540 224 193 541 193 192 542 192 195 543 195 193 544 193 194 545 194 192 546 192 193 547 193 195 548 195 199 549 199 196 550 196 197 551 197 199 552 199 198 553 198 196 554 196 201 555 201 198 556 198 199 557 199 201 558 201 200 559 200 198 560 198 204 561 204 200 562 200 201 563 201 204 564 204 202 565 202 200 566 200 204 567 204 203 568 203 202 569 202 206 570 206 203 571 203 204 572 204 206 573 206 205 574 205 203 575 203 208 576 208 205 577 205 206 578 206 208 579 208 207 580 207 205 581 205 210 582 210 207 583 207 208 584 208 210 585 210 209 586 209 207 587 207 211 588 211 209 589 209 210 590 210 213 591 213 209 592 209 211 593 211 213 594 213 212 595 212 209 596 209 216 597 216 212 598 212 213 599 213 216 600 216 214 601 214 212 602 212 216 603 216 215 604 215 214 605 214 218 606 218 215 607 215 216 608 216 218 609 218 217 610 217 215 611 215 220 612 220 217 613 217 218 614 218 220 615 220 219 616 219 217 617 217 221 618 221 219 619 219 220 620 220 223 621 223 219 622 219 221 623 221 223 624 223 222 625 222 219 626 219 225 627 225 222 628 222 223 629 223 225 630 225 224 631 224 222 632 222 193 633 193 224 634 224 225 635 225 258 636 258 226 637 226 227 638 227 230 639 230 228 640 228 229 641 229 231 642 231 228 643 228 230 644 230 233 645 233 228 646 228 231 647 231 233 648 233 232 649 232 228 650 228 235 651 235 232 652 232 233 653 233 235 654 235 234 655 234 232 656 232 237 657 237 234 658 234 235 659 235 237 660 237 236 661 236 234 662 234 240 663 240 236 664 236 237 665 237 240 666 240 238 667 238 236 668 236 240 669 240 239 670 239 238 671 238 242 672 242 239 673 239 240 674 240 242 675 242 241 676 241 239 677 239 244 678 244 241 679 241 242 680 242 244 681 244 243 682 243 241 683 241 245 684 245 243 685 243 244 686 244 248 687 248 243 688 243 245 689 245 248 690 248 246 691 246 243 692 243 248 693 248 247 694 247 246 695 246 250 696 250 247 697 247 248 698 248 250 699 250 249 700 249 247 701 247 252 702 252 249 703 249 250 704 250 252 705 252 251 706 251 249 707 249 253 708 253 251 709 251 252 710 252 255 711 255 251 712 251 253 713 253 255 714 255 254 715 254 251 716 251 257 717 257 254 718 254 255 719 255 257 720 257 256 721 256 254 722 254 259 723 259 256 724 256 257 725 257 259 726 259 258 727 258 256 728 256 226 729 226 258 730 258 259 731 259 292 732 292 261 733 261 260 734 260 263 735 263 261 736 261 262 737 262 260 738 260 261 739 261 263 740 263 267 741 267 264 742 264 265 743 265 267 744 267 266 745 266 264 746 264 269 747 269 266 748 266 267 749 267 269 750 269 268 751 268 266 752 266 271 753 271 268 754 268 269 755 269 271 756 271 270 757 270 268 758 268 273 759 273 270 760 270 271 761 271 273 762 273 272 763 272 270 764 270 275 765 275 272 766 272 273 767 273 275 768 275 274 769 274 272 770 272 277 771 277 274 772 274 275 773 275 277 774 277 276 775 276 274 776 274 279 777 279 276 778 276 277 779 277 279 780 279 278 781 278 276 782 276 281 783 281 278 784 278 279 785 279 281 786 281 280 787 280 278 788 278 283 789 283 280 790 280 281 791 281 283 792 283 282 793 282 280 794 280 285 795 285 282 796 282 283 797 283 285 798 285 284 799 284 282 800 282 287 801 287 284 802 284 285 803 285 287 804 287 286 805 286 284 806 284 289 807 289 286 808 286 287 809 287 289 810 289 288 811 288 286 812 286 291 813 291 288 814 288 289 815 289 291 816 291 290 817 290 288 818 288 293 819 293 290 820 290 291 821 291 293 822 293 292 823 292 290 824 290 261 825 261 292 826 292 293 827 293 326 828 326 295 829 295 294 830 294 297 831 297 295 832 295 296 833 296 294 834 294 295 835 295 297 836 297 301 837 301 298 838 298 299 839 299 301 840 301 300 841 300 298 842 298 303 843 303 300 844 300 301 845 301 303 846 303 302 847 302 300 848 300 305 849 305 302 850 302 303 851 303 305 852 305 304 853 304 302 854 302 307 855 307 304 856 304 305 857 305 307 858 307 306 859 306 304 860 304 309 861 309 306 862 306 307 863 307 309 864 309 308 865 308 306 866 306 312 867 312 308 868 308 309 869 309 312 870 312 310 871 310 308 872 308 312 873 312 311 874 311 310 875 310 313 876 313 311 877 311 312 878 312 315 879 315 311 880 311 313 881 313 315 882 315 314 883 314 311 884 311 317 885 317 314 886 314 315 887 315 317 888 317 316 889 316 314 890 314 320 891 320 316 892 316 317 893 317 320 894 320 318 895 318 316 896 316 320 897 320 319 898 319 318 899 318 321 900 321 319 901 319 320 902 320 323 903 323 319 904 319 321 905 321 323 906 323 322 907 322 319 908 319 325 909 325 322 910 322 323 911 323 325 912 325 324 913 324 322 914 322 327 915 327 324 916 324 325 917 325 327 918 327 326 919 326 324 920 324 295 921 295 326 922 326 327 923 327 346 924 346 328 925 328 329 926 329 334 927 334 330 928 330 331 929 331 334 930 334 332 931 332 330 932 330 334 933 334 333 934 333 332 935 332 336 936 336 333 937 333 334 938 334 336 939 336 335 940 335 333 941 333 338 942 338 335 943 335 336 944 336 338 945 338 337 946 337 335 947 335 340 948 340 337 949 337 338 950 338 340 951 340 339 952 339 337 953 337 343 954 343 339 955 339 340 956 340 343 957 343 341 958 341 339 959 339 343 960 343 342 961 342 341 962 341 345 963 345 342 964 342 343 965 343 345 966 345 344 967 344 342 968 342 347 969 347 344 970 344 345 971 345 347 972 347 346 973 346 344 974 344 328 975 328 346 976 346 347 977 347 380 978 380 348 979 348 349 980 349 352 981 352 350 982 350 351 983 351 354 984 354 350 985 350 352 986 352 354 987 354 353 988 353 350 989 350 355 990 355 353 991 353 354 992 354 357 993 357 353 994 353 355 995 355 357 996 357 356 997 356 353 998 353 359 999 359 356 1000 356 357 1001 357 359 1002 359 358 1003 358 356 1004 356 362 1005 362 358 1006 358 359 1007 359 362 1008 362 360 1009 360 358 1010 358 362 1011 362 361 1012 361 360 1013 360 363 1014 363 361 1015 361 362 1016 362 365 1017 365 361 1018 361 363 1019 363 365 1020 365 364 1021 364 361 1022 361 367 1023 367 364 1024 364 365 1025 365 367 1026 367 366 1027 366 364 1028 364 369 1029 369 366 1030 366 367 1031 367 369 1032 369 368 1033 368 366 1034 366 371 1035 371 368 1036 368 369 1037 369 371 1038 371 370 1039 370 368 1040 368 373 1041 373 370 1042 370 371 1043 371 373 1044 373 372 1045 372 370 1046 370 375 1047 375 372 1048 372 373 1049 373 375 1050 375 374 1051 374 372 1052 372 378 1053 378 374 1054 374 375 1055 375 378 1056 378 376 1057 376 374 1058 374 378 1059 378 377 1060 377 376 1061 376 379 1062 379 377 1063 377 378 1064 378 381 1065 381 377 1066 377 379 1067 379 381 1068 381 380 1069 380 377 1070 377 348 1071 348 380 1072 380 381 1073 381 389 1074 389 382 1075 382 383 1076 383 386 1077 386 384 1078 384 385 1079 385 387 1080 387 384 1081 384 386 1082 386 388 1083 388 384 1084 384 387 1085 387 390 1086 390 384 1087 384 388 1088 388 390 1089 390 389 1090 389 384 1091 384 391 1092 391 389 1093 389 390 1094 390 392 1095 392 389 1096 389 391 1097 391 382 1098 382 389 1099 389 392 1100 392 395 1101 395 393 1102 393 394 1103 394 393 1104 393 395 1105 395 396 1106 396 399 1107 399 397 1108 397 398 1109 398 397 1110 397 399 1111 399 400 1112 400 403 1113 403 401 1114 401 402 1115 402 401 1116 401 403 1117 403 404 1118 404 407 1119 407 405 1120 405 406 1121 406 405 1122 405 407 1123 407 408 1124 408 411 1125 411 409 1126 409 410 1127 410 409 1128 409 411 1129 411 412 1130 412 415 1131 415 413 1132 413 414 1133 414 413 1134 413 415 1135 415 416 1136 416 419 1137 419 417 1138 417 418 1139 418 417 1140 417 419 1141 419 420 1142 420 423 1143 423 421 1144 421 422 1145 422 421 1146 421 423 1147 423 424 1148 424 427 1149 427 425 1150 425 426 1151 426 425 1152 425 427 1153 427 428 1154 428 431 1155 431 429 1156 429 430 1157 430 429 1158 429 431 1159 431 432 1160 432 435 1161 435 433 1162 433 434 1163 434 433 1164 433 435 1165 435 436 1166 436 439 1167 439 437 1168 437 438 1169 438 437 1170 437 439 1171 439 440 1172 440 443 1173 443 441 1174 441 442 1175 442 441 1176 441 443 1177 443 444 1178 444 447 1179 447 445 1180 445 446 1181 446 445 1182 445 447 1183 447 448 1184 448 451 1185 451 449 1186 449 450 1187 450 449 1188 449 451 1189 451 452 1190 452 455 1191 455 453 1192 453 454 1193 454 453 1194 453 455 1195 455 456 1196 456 459 1197 459 457 1198 457 458 1199 458 457 1200 457 459 1201 459 460 1202 460 463 1203 463 461 1204 461 462 1205 462 461 1206 461 463 1207 463 464 1208 464 467 1209 467 465 1210 465 466 1211 466 465 1212 465 467 1213 467 468 1214 468 471 1215 471 469 1216 469 470 1217 470 469 1218 469 471 1219 471 472 1220 472 491 1221 491 474 1222 474 473 1223 473 476 1224 476 474 1225 474 475 1226 475 477 1227 477 474 1228 474 476 1229 476 473 1230 473 474 1231 474 477 1232 477 480 1233 480 478 1234 478 479 1235 479 484 1236 484 478 1237 478 480 1238 480 478 1239 478 481 1240 481 482 1241 482 484 1242 484 481 1243 481 478 1244 478 484 1245 484 483 1246 483 481 1247 481 487 1248 487 483 1249 483 484 1250 484 487 1251 487 485 1252 485 483 1253 483 487 1254 487 486 1255 486 485 1256 485 489 1257 489 486 1258 486 487 1259 487 489 1260 489 488 1261 488 486 1262 486 474 1263 474 488 1264 488 489 1265 489 474 1266 474 490 1267 490 488 1268 488 474 1269 474 491 1270 491 490 1271 490 502 1272 502 492 1273 492 493 1274 493 500 1275 500 494 1276 494 495 1277 495 500 1278 500 496 1279 496 494 1280 494 500 1281 500 497 1282 497 496 1283 496 500 1284 500 498 1285 498 497 1286 497 500 1287 500 499 1288 499 498 1289 498 492 1290 492 499 1291 499 500 1292 500 492 1293 492 501 1294 501 499 1295 499 492 1296 492 502 1297 502 501 1298 501 520 1299 520 503 1300 503 507 1301 507 520 1302 520 504 1303 504 505 1304 505 520 1305 520 506 1306 506 504 1307 504 520 1308 520 507 1309 507 506 1310 506 514 1311 514 508 1312 508 509 1313 509 514 1314 514 510 1315 510 508 1316 508 516 1317 516 511 1318 511 512 1319 512 516 1320 516 513 1321 513 511 1322 511 516 1323 516 514 1324 514 513 1325 513 516 1326 516 510 1327 510 514 1328 514 516 1329 516 515 1330 515 510 1331 510 518 1332 518 515 1333 515 516 1334 516 518 1335 518 517 1336 517 515 1337 515 519 1338 519 517 1339 517 518 1340 518 521 1341 521 517 1342 517 519 1343 519 521 1344 521 520 1345 520 517 1346 517 522 1347 522 520 1348 520 521 1349 521 523 1350 523 520 1351 520 522 1352 522 503 1353 503 520 1354 520 523 1355 523 556 1356 556 536 1357 536 524 1358 524 529 1359 529 525 1360 525 526 1361 526 529 1362 529 527 1363 527 525 1364 525 529 1365 529 528 1366 528 527 1367 527 530 1368 530 528 1369 528 529 1370 529 532 1371 532 528 1372 528 530 1373 530 532 1374 532 531 1375 531 528 1376 528 534 1377 534 531 1378 531 532 1379 532 534 1380 534 533 1381 533 531 1382 531 537 1383 537 533 1384 533 534 1385 534 537 1386 537 535 1387 535 533 1388 533 537 1389 537 536 1390 536 535 1391 535 524 1392 524 536 1393 536 537 1394 537 542 1395 542 538 1396 538 539 1397 539 542 1398 542 540 1399 540 538 1400 538 542 1401 542 541 1402 541 540 1403 540 543 1404 543 541 1405 541 542 1406 542 545 1407 545 541 1408 541 543 1409 543 545 1410 545 544 1411 544 541 1412 541 547 1413 547 544 1414 544 545 1415 545 547 1416 547 546 1417 546 544 1418 544 549 1419 549 546 1420 546 547 1421 547 549 1422 549 548 1423 548 546 1424 546 551 1425 551 548 1426 548 549 1427 549 551 1428 551 550 1429 550 548 1430 548 553 1431 553 550 1432 550 551 1433 551 553 1434 553 552 1435 552 550 1436 550 555 1437 555 552 1438 552 553 1439 553 555 1440 555 554 1441 554 552 1442 552 557 1443 557 554 1444 554 555 1445 555 557 1446 557 556 1447 556 554 1448 554 536 1449 536 556 1450 556 557 1451 557 574 1452 574 558 1453 558 559 1454 559 570 1455 570 560 1456 560 561 1457 561 570 1458 570 562 1459 562 560 1460 560 570 1461 570 563 1462 563 562 1463 562 570 1464 570 564 1465 564 563 1466 563 570 1467 570 565 1468 565 564 1469 564 570 1470 570 566 1471 566 565 1472 565 570 1473 570 567 1474 567 566 1475 566 575 1476 575 568 1477 568 569 1478 569 568 1479 568 570 1480 570 571 1481 571 575 1482 575 570 1483 570 568 1484 568 575 1485 575 567 1486 567 570 1487 570 575 1488 575 572 1489 572 567 1490 567 575 1491 575 573 1492 573 572 1493 572 575 1494 575 574 1495 574 573 1496 573 576 1497 576 574 1498 574 575 1499 575 577 1500 577 574 1501 574 576 1502 576 578 1503 578 574 1504 574 577 1505 577 579 1506 579 574 1507 574 578 1508 578 580 1509 580 574 1510 574 579 1511 579 558 1512 558 574 1513 574 580 1514 580 583 1515 583 581 1516 581 582 1517 582 581 1518 581 583 1519 583 584 1520 584 596 1521 596 585 1522 585 586 1523 586 589 1524 589 587 1525 587 588 1526 588 590 1527 590 587 1528 587 589 1529 589 591 1530 591 587 1531 587 590 1532 590 592 1533 592 587 1534 587 591 1535 591 597 1536 597 587 1537 587 592 1538 592 595 1539 595 593 1540 593 594 1541 594 587 1542 587 593 1543 593 595 1544 595 587 1545 587 596 1546 596 593 1547 593 597 1548 597 596 1549 596 587 1550 587 598 1551 598 596 1552 596 597 1553 597 599 1554 599 596 1555 596 598 1556 598 600 1557 600 596 1558 596 599 1559 599 601 1560 601 596 1561 596 600 1562 600 602 1563 602 596 1564 596 601 1565 601 603 1566 603 596 1567 596 602 1568 602 604 1569 604 596 1570 596 603 1571 603 605 1572 605 596 1573 596 604 1574 604 606 1575 606 596 1576 596 605 1577 605 607 1578 607 596 1579 596 606 1580 606 585 1581 585 596 1582 596 607 1583 607 610 1584 610 608 1585 608 609 1586 609 608 1587 608 610 1588 610 611 1589 611 774 1590 774 612 1591 612 822 1592 822 618 1593 618 613 1594 613 614 1595 614 633 1596 633 615 1597 615 616 1598 616 633 1599 633 617 1600 617 615 1601 615 632 1602 632 613 1603 613 618 1604 618 709 1605 709 635 1606 635 619 1607 619 709 1608 709 620 1609 620 635 1610 635 709 1611 709 621 1612 621 620 1613 620 709 1614 709 622 1615 622 621 1616 621 709 1617 709 623 1618 623 622 1619 622 625 1620 625 624 1621 624 685 1622 685 626 1623 626 624 1624 624 625 1625 625 627 1626 627 624 1627 624 626 1628 626 628 1629 628 624 1630 624 627 1631 627 629 1632 629 624 1633 624 628 1634 628 641 1635 641 624 1636 624 629 1637 629 709 1638 709 630 1639 630 623 1640 623 632 1641 632 631 1642 631 613 1643 613 688 1644 688 631 1645 631 632 1646 632 689 1647 689 617 1648 617 633 1649 633 689 1650 689 634 1651 634 617 1652 617 682 1653 682 619 1654 619 635 1655 635 685 1656 685 636 1657 636 625 1658 625 639 1659 639 637 1660 637 638 1661 638 653 1662 653 637 1663 637 639 1664 639 709 1665 709 640 1666 640 630 1667 630 681 1668 681 624 1669 624 641 1670 641 658 1671 658 642 1672 642 662 1673 662 662 1674 662 643 1675 643 658 1676 658 655 1677 655 644 1678 644 645 1679 645 655 1680 655 646 1681 646 644 1682 644 668 1683 668 653 1684 653 647 1685 647 637 1686 637 648 1687 648 649 1688 649 653 1689 653 648 1690 648 637 1691 637 648 1692 648 650 1693 650 660 1694 660 648 1695 648 651 1696 651 652 1697 652 657 1698 657 653 1699 653 654 1700 654 665 1701 665 646 1702 646 655 1703 655 665 1704 665 656 1705 656 646 1706 646 691 1707 691 653 1708 653 657 1709 657 667 1710 667 642 1711 642 658 1712 658 648 1713 648 659 1714 659 651 1715 651 703 1716 703 648 1717 648 660 1718 660 653 1719 653 661 1720 661 647 1721 647 692 1722 692 643 1723 643 662 1724 662 692 1725 692 663 1726 663 643 1727 643 667 1728 667 664 1729 664 642 1730 642 706 1731 706 656 1732 656 665 1733 665 706 1734 706 666 1735 666 656 1736 656 708 1737 708 664 1738 664 667 1739 667 669 1740 669 653 1741 653 668 1742 668 669 1743 669 648 1744 648 653 1745 653 670 1746 670 648 1747 648 669 1748 669 671 1749 671 648 1750 648 670 1751 670 672 1752 672 648 1753 648 671 1754 671 673 1755 673 648 1756 648 672 1757 672 674 1758 674 648 1759 648 673 1760 673 675 1761 675 648 1762 648 674 1763 674 676 1764 676 648 1765 648 675 1766 675 677 1767 677 648 1768 648 676 1769 676 678 1770 678 648 1771 648 677 1772 677 663 1773 663 648 1774 648 678 1775 678 648 1776 648 679 1777 679 650 1778 650 709 1779 709 680 1780 680 640 1781 640 718 1782 718 624 1783 624 681 1784 681 717 1785 717 619 1786 619 682 1787 682 717 1788 717 683 1789 683 619 1790 619 685 1791 685 684 1792 684 636 1793 636 712 1794 712 684 1795 684 685 1796 685 648 1797 648 686 1798 686 659 1799 659 688 1800 688 687 1801 687 631 1802 631 721 1803 721 687 1804 687 688 1805 688 722 1806 722 634 1807 634 689 1808 689 722 1809 722 690 1810 690 634 1811 634 715 1812 715 653 1813 653 691 1814 691 693 1815 693 663 1816 663 692 1817 692 693 1818 693 648 1819 648 663 1820 663 694 1821 694 648 1822 648 693 1823 693 695 1824 695 648 1825 648 694 1826 694 696 1827 696 648 1828 648 695 1829 695 697 1830 697 648 1831 648 696 1832 696 698 1833 698 648 1834 648 697 1835 697 699 1836 699 648 1837 648 698 1838 698 700 1839 700 648 1840 648 699 1841 699 701 1842 701 648 1843 648 700 1844 700 702 1845 702 648 1846 648 701 1847 701 726 1848 726 648 1849 648 702 1850 702 731 1851 731 648 1852 648 703 1853 703 653 1854 653 704 1855 704 661 1856 661 708 1857 708 705 1858 705 664 1859 664 732 1860 732 666 1861 666 706 1862 706 732 1863 732 707 1864 707 666 1865 666 730 1866 730 705 1867 705 708 1868 708 724 1869 724 680 1870 680 709 1871 709 718 1872 718 710 1873 710 624 1874 624 717 1875 717 711 1876 711 683 1877 683 728 1878 728 684 1879 684 712 1880 712 648 1881 648 713 1882 713 679 1883 679 648 1884 648 714 1885 714 686 1886 686 738 1887 738 653 1888 653 715 1889 715 728 1890 728 716 1891 716 684 1892 684 744 1893 744 711 1894 711 717 1895 717 775 1896 775 710 1897 710 718 1898 718 724 1899 724 719 1900 719 680 1901 680 721 1902 721 720 1903 720 687 1904 687 735 1905 735 720 1906 720 721 1907 721 739 1908 739 690 1909 690 722 1910 722 739 1911 739 723 1912 723 690 1913 690 737 1914 737 719 1915 719 724 1916 724 775 1917 775 725 1918 725 710 1919 710 832 1920 832 648 1921 648 726 1922 726 744 1923 744 727 1924 727 711 1925 711 751 1926 751 716 1927 716 728 1928 728 730 1929 730 729 1930 729 705 1931 705 742 1932 742 729 1933 729 730 1934 730 788 1935 788 648 1936 648 731 1937 731 745 1938 745 707 1939 707 732 1940 732 745 1941 745 733 1942 733 707 1943 707 653 1944 653 734 1945 734 704 1946 704 648 1947 648 735 1948 735 714 1949 714 648 1950 648 720 1951 720 735 1952 735 648 1953 648 736 1954 736 720 1955 720 648 1956 648 737 1957 737 736 1958 736 723 1959 723 653 1960 653 738 1961 738 739 1962 739 653 1963 653 723 1964 723 740 1965 740 653 1966 653 739 1967 739 725 1968 725 653 1969 653 740 1970 740 648 1971 648 741 1972 741 713 1973 713 791 1974 791 729 1975 729 742 1976 742 791 1977 791 743 1978 743 729 1979 729 746 1980 746 727 1981 727 744 1982 744 746 1983 746 745 1984 745 727 1985 727 746 1986 746 733 1987 733 745 1988 745 747 1989 747 733 1990 733 746 1991 746 748 1992 748 733 1993 733 747 1994 747 749 1995 749 733 1996 733 748 1997 748 750 1998 750 733 1999 733 749 2000 749 758 2001 758 733 2002 733 750 2003 750 758 2004 758 751 2005 751 733 2006 733 758 2007 758 716 2008 716 751 2009 751 758 2010 758 752 2011 752 716 2012 716 758 2013 758 753 2014 753 752 2015 752 758 2016 758 754 2017 754 753 2018 753 758 2019 758 755 2020 755 754 2021 754 758 2022 758 756 2023 756 755 2024 755 758 2025 758 757 2026 757 756 2027 756 773 2028 773 757 2029 757 758 2030 758 773 2031 773 759 2032 759 757 2033 757 737 2034 737 760 2035 760 719 2036 719 648 2037 648 760 2038 760 737 2039 737 648 2040 648 761 2041 761 760 2042 760 648 2043 648 762 2044 762 761 2045 761 648 2046 648 763 2047 763 762 2048 762 648 2049 648 764 2050 764 763 2051 763 648 2052 648 765 2053 765 764 2054 764 648 2055 648 766 2056 766 765 2057 765 648 2058 648 767 2059 767 766 2060 766 648 2061 648 768 2062 768 767 2063 767 648 2064 648 769 2065 769 768 2066 768 648 2067 648 770 2068 770 769 2069 769 648 2070 648 771 2071 771 770 2072 770 648 2073 648 772 2074 772 771 2075 771 772 2076 772 759 2077 759 773 2078 773 772 2079 772 774 2080 774 759 2081 759 776 2082 776 725 2083 725 775 2084 775 776 2085 776 653 2086 653 725 2087 725 777 2088 777 653 2089 653 776 2090 776 778 2091 778 653 2092 653 777 2093 777 779 2094 779 653 2095 653 778 2096 778 780 2097 780 653 2098 653 779 2099 779 781 2100 781 653 2101 653 780 2102 780 782 2103 782 653 2104 653 781 2105 781 783 2106 783 653 2107 653 782 2108 782 784 2109 784 653 2110 653 783 2111 783 785 2112 785 653 2113 653 784 2114 784 786 2115 786 653 2116 653 785 2117 785 787 2118 787 653 2119 653 786 2120 786 774 2121 774 653 2122 653 787 2123 787 794 2124 794 648 2125 648 788 2126 788 653 2127 653 789 2128 789 734 2129 734 648 2130 648 790 2131 790 741 2132 741 795 2133 795 743 2134 743 791 2135 791 795 2136 795 792 2137 792 743 2138 743 653 2139 653 793 2140 793 789 2141 789 798 2142 798 648 2143 648 794 2144 794 815 2145 815 792 2146 792 795 2147 795 648 2148 648 796 2149 796 790 2150 790 815 2151 815 797 2152 797 792 2153 792 799 2154 799 648 2155 648 798 2156 798 799 2157 799 772 2158 772 648 2159 648 800 2160 800 772 2161 772 799 2162 799 801 2163 801 772 2164 772 800 2165 800 802 2166 802 772 2167 772 801 2168 801 803 2169 803 772 2170 772 802 2171 802 804 2172 804 772 2173 772 803 2174 803 805 2175 805 772 2176 772 804 2177 804 806 2178 806 772 2179 772 805 2180 805 807 2181 807 772 2182 772 806 2183 806 808 2184 808 772 2185 772 807 2186 807 808 2187 808 774 2188 774 772 2189 772 809 2190 809 774 2191 774 808 2192 808 831 2193 831 774 2194 774 809 2195 809 653 2196 653 810 2197 810 793 2198 793 774 2199 774 810 2200 810 653 2201 653 774 2202 774 811 2203 811 810 2204 810 774 2205 774 812 2206 812 811 2207 811 774 2208 774 813 2209 813 812 2210 812 774 2211 774 814 2212 814 813 2213 813 774 2214 774 815 2215 815 814 2216 814 774 2217 774 797 2218 797 815 2219 815 774 2220 774 816 2221 816 797 2222 797 774 2223 774 817 2224 817 816 2225 816 774 2226 774 818 2227 818 817 2228 817 774 2229 774 819 2230 819 818 2231 818 774 2232 774 820 2233 820 819 2234 819 774 2235 774 821 2236 821 820 2237 820 774 2238 774 822 2239 822 821 2240 821 648 2241 648 823 2242 823 796 2243 796 832 2244 832 823 2245 823 648 2246 648 832 2247 832 824 2248 824 823 2249 823 832 2250 832 825 2251 825 824 2252 824 832 2253 832 826 2254 826 825 2255 825 832 2256 832 827 2257 827 826 2258 826 832 2259 832 828 2260 828 827 2261 827 832 2262 832 829 2263 829 828 2264 828 832 2265 832 830 2266 830 829 2267 829 832 2268 832 831 2269 831 830 2270 830 833 2271 833 831 2272 831 832 2273 832 834 2274 834 831 2275 831 833 2276 833 835 2277 835 831 2278 831 834 2279 834 612 2280 612 831 2281 831 835 2282 835 612 2283 612 774 2284 774 831 2285 831 841 2286 841 836 2287 836 837 2288 837 843 2289 843 838 2290 838 839 2291 839 843 2292 843 840 2293 840 838 2294 838 840 2295 840 841 2296 841 842 2297 842 843 2298 843 841 2299 841 840 2300 840 836 2301 836 841 2302 841 843 2303 843 872 2304 872 844 2305 844 845 2306 845 856 2307 856 846 2308 846 847 2309 847 856 2310 856 848 2311 848 846 2312 846 856 2313 856 849 2314 849 848 2315 848 856 2316 856 850 2317 850 849 2318 849 856 2319 856 851 2320 851 850 2321 850 856 2322 856 852 2323 852 851 2324 851 873 2325 873 853 2326 853 854 2327 854 856 2328 856 855 2329 855 852 2330 852 877 2331 877 855 2332 855 856 2333 856 877 2334 877 857 2335 857 855 2336 855 877 2337 877 858 2338 858 857 2339 857 877 2340 877 859 2341 859 858 2342 858 877 2343 877 860 2344 860 859 2345 859 877 2346 877 861 2347 861 860 2348 860 877 2349 877 862 2350 862 861 2351 861 877 2352 877 863 2353 863 862 2354 862 873 2355 873 864 2356 864 853 2357 853 873 2358 873 865 2359 865 864 2360 864 873 2361 873 866 2362 866 865 2363 865 873 2364 873 867 2365 867 866 2366 866 873 2367 873 868 2368 868 867 2369 867 873 2370 873 869 2371 869 868 2372 868 873 2373 873 870 2374 870 869 2375 869 873 2376 873 871 2377 871 870 2378 870 873 2379 873 872 2380 872 871 2381 871 874 2382 874 872 2383 872 873 2384 873 875 2385 875 872 2386 872 874 2387 874 876 2388 876 872 2389 872 875 2390 875 863 2391 863 872 2392 872 876 2393 876 877 2394 877 872 2395 872 863 2396 863 878 2397 878 872 2398 872 877 2399 877 879 2400 879 872 2401 872 878 2402 878 880 2403 880 872 2404 872 879 2405 879 881 2406 881 872 2407 872 880 2408 880 882 2409 882 872 2410 872 881 2411 881 844 2412 844 872 2413 872 882 2414 882 905 2415 905 883 2416 883 902 2417 902 887 2418 887 884 2419 884 885 2420 885 887 2421 887 886 2422 886 884 2423 884 888 2424 888 886 2425 886 887 2426 887 889 2427 889 886 2428 886 888 2429 888 890 2430 890 886 2431 886 889 2432 889 899 2433 899 886 2434 886 890 2435 890 893 2436 893 891 2437 891 892 2438 892 905 2439 905 891 2440 891 893 2441 893 905 2442 905 894 2443 894 891 2444 891 905 2445 905 895 2446 895 894 2447 894 905 2448 905 896 2449 896 895 2450 895 905 2451 905 897 2452 897 896 2453 896 905 2454 905 898 2455 898 897 2456 897 900 2457 900 886 2458 886 899 2459 899 903 2460 903 886 2461 886 900 2462 900 905 2463 905 901 2464 901 898 2465 898 905 2466 905 902 2467 902 901 2468 901 904 2469 904 886 2470 886 903 2471 903 906 2472 906 886 2473 886 904 2474 904 906 2475 906 905 2476 905 886 2477 886 883 2478 883 905 2479 905 906 2480 906 936 2481 936 907 2482 907 908 2483 908 911 2484 911 909 2485 909 910 2486 910 916 2487 916 909 2488 909 911 2489 911 916 2490 916 912 2491 912 909 2492 909 916 2493 916 913 2494 913 912 2495 912 916 2496 916 914 2497 914 913 2498 913 916 2499 916 915 2500 915 914 2501 914 920 2502 920 915 2503 915 916 2504 916 920 2505 920 917 2506 917 915 2507 915 920 2508 920 918 2509 918 917 2510 917 920 2511 920 919 2512 919 918 2513 918 923 2514 923 919 2515 919 920 2516 920 923 2517 923 921 2518 921 919 2519 919 923 2520 923 922 2521 922 921 2522 921 925 2523 925 922 2524 922 923 2525 923 925 2526 925 924 2527 924 922 2528 922 926 2529 926 924 2530 924 925 2531 925 928 2532 928 924 2533 924 926 2534 926 928 2535 928 927 2536 927 924 2537 924 930 2538 930 927 2539 927 928 2540 928 930 2541 930 929 2542 929 927 2543 927 931 2544 931 929 2545 929 930 2546 930 933 2547 933 929 2548 929 931 2549 931 933 2550 933 932 2551 932 929 2552 929 935 2553 935 932 2554 932 933 2555 933 935 2556 935 934 2557 934 932 2558 932 937 2559 937 934 2560 934 935 2561 935 937 2562 937 936 2563 936 934 2564 934 938 2565 938 936 2566 936 937 2567 937 907 2568 907 936 2569 936 938 2570 938 941 2571 941 939 2572 939 940 2573 940 939 2574 939 941 2575 941 942 2576 942 965 2577 965 943 2578 943 944 2579 944 954 2580 954 945 2581 945 946 2582 946 949 2583 949 947 2584 947 948 2585 948 950 2586 950 947 2587 947 949 2588 949 952 2589 952 947 2590 947 950 2591 950 952 2592 952 951 2593 951 947 2594 947 945 2595 945 951 2596 951 952 2597 952 954 2598 954 951 2599 951 945 2600 945 954 2601 954 953 2602 953 951 2603 951 956 2604 956 953 2605 953 954 2606 954 956 2607 956 955 2608 955 953 2609 953 958 2610 958 955 2611 955 956 2612 956 958 2613 958 957 2614 957 955 2615 955 959 2616 959 957 2617 957 958 2618 958 961 2619 961 957 2620 957 959 2621 959 961 2622 961 960 2623 960 957 2624 957 963 2625 963 960 2626 960 961 2627 961 963 2628 963 962 2629 962 960 2630 960 964 2631 964 962 2632 962 963 2633 963 943 2634 943 962 2635 962 964 2636 964 943 2637 943 965 2638 965 962 2639 962 968 2640 968 966 2641 966 967 2642 967 966 2643 966 968 2644 968 969 2645 969 1011 2646 1011 970 2647 970 971 2648 971 974 2649 974 972 2650 972 973 2651 973 976 2652 976 972 2653 972 974 2654 974 976 2655 976 975 2656 975 972 2657 972 979 2658 979 975 2659 975 976 2660 976 979 2661 979 977 2662 977 975 2663 975 979 2664 979 978 2665 978 977 2666 977 981 2667 981 978 2668 978 979 2669 979 981 2670 981 980 2671 980 978 2672 978 984 2673 984 980 2674 980 981 2675 981 984 2676 984 982 2677 982 980 2678 980 984 2679 984 983 2680 983 982 2681 982 986 2682 986 983 2683 983 984 2684 984 986 2685 986 985 2686 985 983 2687 983 988 2688 988 985 2689 985 986 2690 986 988 2691 988 987 2692 987 985 2693 985 991 2694 991 987 2695 987 988 2696 988 991 2697 991 989 2698 989 987 2699 987 991 2700 991 990 2701 990 989 2702 989 993 2703 993 990 2704 990 991 2705 991 993 2706 993 992 2707 992 990 2708 990 995 2709 995 992 2710 992 993 2711 993 995 2712 995 994 2713 994 992 2714 992 998 2715 998 994 2716 994 995 2717 995 998 2718 998 996 2719 996 994 2720 994 998 2721 998 997 2722 997 996 2723 996 1002 2724 1002 997 2725 997 998 2726 998 997 2727 997 999 2728 999 1000 2729 1000 1002 2730 1002 999 2731 999 997 2732 997 1002 2733 1002 1001 2734 1001 999 2735 999 1004 2736 1004 1001 2737 1001 1002 2738 1002 1004 2739 1004 1003 2740 1003 1001 2741 1001 1007 2742 1007 1003 2743 1003 1004 2744 1004 1007 2745 1007 1005 2746 1005 1003 2747 1003 1007 2748 1007 1006 2749 1006 1005 2750 1005 1010 2751 1010 1006 2752 1006 1007 2753 1007 1010 2754 1010 1008 2755 1008 1006 2756 1006 1010 2757 1010 1009 2758 1009 1008 2759 1008 1012 2760 1012 1009 2761 1009 1010 2762 1010 1012 2763 1012 1011 2764 1011 1009 2765 1009 970 2766 970 1011 2767 1011 1012 2768 1012 1017 2769 1017 1013 2770 1013 1014 2771 1014 1018 2772 1018 1015 2773 1015 1016 2774 1016 1018 2775 1018 1017 2776 1017 1015 2777 1015 1019 2778 1019 1017 2779 1017 1018 2780 1018 1020 2781 1020 1017 2782 1017 1019 2783 1019 1021 2784 1021 1017 2785 1017 1020 2786 1020 1022 2787 1022 1017 2788 1017 1021 2789 1021 1023 2790 1023 1017 2791 1017 1022 2792 1022 1013 2793 1013 1017 2794 1017 1023 2795 1023 1030 2796 1030 1024 2797 1024 1025 2798 1025 1028 2799 1028 1026 2800 1026 1027 2801 1027 1031 2802 1031 1026 2803 1026 1028 2804 1028 1031 2805 1031 1029 2806 1029 1026 2807 1026 1031 2808 1031 1030 2809 1030 1029 2810 1029 1032 2811 1032 1030 2812 1030 1031 2813 1031 1033 2814 1033 1030 2815 1030 1032 2816 1032 1034 2817 1034 1030 2818 1030 1033 2819 1033 1024 2820 1024 1030 2821 1030 1034 2822 1034 1050 2823 1050 1035 2824 1035 1038 2825 1038 1042 2826 1042 1036 2827 1036 1037 2828 1037 1040 2829 1040 1038 2830 1038 1039 2831 1039 1050 2832 1050 1038 2833 1038 1040 2834 1040 1042 2835 1042 1041 2836 1041 1036 2837 1036 1044 2838 1044 1041 2839 1041 1042 2840 1042 1044 2841 1044 1043 2842 1043 1041 2843 1041 1046 2844 1046 1043 2845 1043 1044 2846 1044 1046 2847 1046 1045 2848 1045 1043 2849 1043 1049 2850 1049 1045 2851 1045 1046 2852 1046 1049 2853 1049 1047 2854 1047 1045 2855 1045 1049 2856 1049 1048 2857 1048 1047 2858 1047 1035 2859 1035 1048 2860 1048 1049 2861 1049 1035 2862 1035 1050 2863 1050 1048 2864 1048 1053 2865 1053 1051 2866 1051 1052 2867 1052 1055 2868 1055 1053 2869 1053 1054 2870 1054 1056 2871 1056 1053 2872 1053 1055 2873 1055 1051 2874 1051 1053 2875 1053 1056 2876 1056 1125 2877 1125 1057 2878 1057 1102 2879 1102 1075 2880 1075 1058 2881 1058 1059 2882 1059 1075 2883 1075 1060 2884 1060 1058 2885 1058 1075 2886 1075 1061 2887 1061 1060 2888 1060 1075 2889 1075 1062 2890 1062 1061 2891 1061 1075 2892 1075 1063 2893 1063 1062 2894 1062 1075 2895 1075 1064 2896 1064 1063 2897 1063 1067 2898 1067 1065 2899 1065 1066 2900 1066 1068 2901 1068 1065 2902 1065 1067 2903 1067 1069 2904 1069 1065 2905 1065 1068 2906 1068 1070 2907 1070 1065 2908 1065 1069 2909 1069 1071 2910 1071 1065 2911 1065 1070 2912 1070 1072 2913 1072 1065 2914 1065 1071 2915 1071 1103 2916 1103 1065 2917 1065 1072 2918 1072 1075 2919 1075 1073 2920 1073 1064 2921 1064 1075 2922 1075 1074 2923 1074 1073 2924 1073 1088 2925 1088 1074 2926 1074 1075 2927 1075 1088 2928 1088 1076 2929 1076 1074 2930 1074 1088 2931 1088 1077 2932 1077 1076 2933 1076 1088 2934 1088 1078 2935 1078 1077 2936 1077 1088 2937 1088 1079 2938 1079 1078 2939 1078 1088 2940 1088 1080 2941 1080 1079 2942 1079 1088 2943 1088 1081 2944 1081 1080 2945 1080 1088 2946 1088 1082 2947 1082 1081 2948 1081 1088 2949 1088 1083 2950 1083 1082 2951 1082 1088 2952 1088 1084 2953 1084 1083 2954 1083 1088 2955 1088 1085 2956 1085 1084 2957 1084 1088 2958 1088 1086 2959 1086 1085 2960 1085 1088 2961 1088 1087 2962 1087 1086 2963 1086 1096 2964 1096 1087 2965 1087 1088 2966 1088 1096 2967 1096 1089 2968 1089 1087 2969 1087 1096 2970 1096 1090 2971 1090 1089 2972 1089 1096 2973 1096 1091 2974 1091 1090 2975 1090 1096 2976 1096 1092 2977 1092 1091 2978 1091 1096 2979 1096 1093 2980 1093 1092 2981 1092 1096 2982 1096 1094 2983 1094 1093 2984 1093 1096 2985 1096 1095 2986 1095 1094 2987 1094 1125 2988 1125 1095 2989 1095 1096 2990 1096 1125 2991 1125 1097 2992 1097 1095 2993 1095 1125 2994 1125 1098 2995 1098 1097 2996 1097 1125 2997 1125 1099 2998 1099 1098 2999 1098 1125 3000 1125 1100 3001 1100 1099 3002 1099 1125 3003 1125 1101 3004 1101 1100 3005 1100 1125 3006 1125 1102 3007 1102 1101 3008 1101 1105 3009 1105 1065 3010 1065 1103 3011 1103 1105 3012 1105 1104 3013 1104 1065 3014 1065 1106 3015 1106 1104 3016 1104 1105 3017 1105 1107 3018 1107 1104 3019 1104 1106 3020 1106 1112 3021 1112 1104 3022 1104 1107 3023 1107 1112 3024 1112 1108 3025 1108 1104 3026 1104 1112 3027 1112 1109 3028 1109 1108 3029 1108 1112 3030 1112 1110 3031 1110 1109 3032 1109 1112 3033 1112 1111 3034 1111 1110 3035 1110 1113 3036 1113 1111 3037 1111 1112 3038 1112 1114 3039 1114 1111 3040 1111 1113 3041 1113 1115 3042 1115 1111 3043 1111 1114 3044 1114 1116 3045 1116 1111 3046 1111 1115 3047 1115 1117 3048 1117 1111 3049 1111 1116 3050 1116 1118 3051 1118 1111 3052 1111 1117 3053 1117 1119 3054 1119 1111 3055 1111 1118 3056 1118 1122 3057 1122 1111 3058 1111 1119 3059 1119 1122 3060 1122 1120 3061 1120 1111 3062 1111 1122 3063 1122 1121 3064 1121 1120 3065 1120 1126 3066 1126 1121 3067 1121 1122 3068 1122 1126 3069 1126 1123 3070 1123 1121 3071 1121 1126 3072 1126 1124 3073 1124 1123 3074 1123 1126 3075 1126 1125 3076 1125 1124 3077 1124 1127 3078 1127 1125 3079 1125 1126 3080 1126 1128 3081 1128 1125 3082 1125 1127 3083 1127 1057 3084 1057 1125 3085 1125 1128 3086 1128 1135 3087 1135 1129 3088 1129 1130 3089 1130 1136 3090 1136 1131 3091 1131 1132 3092 1132 1136 3093 1136 1133 3094 1133 1131 3095 1131 1136 3096 1136 1134 3097 1134 1133 3098 1133 1136 3099 1136 1135 3100 1135 1134 3101 1134 1137 3102 1137 1135 3103 1135 1136 3104 1136 1129 3105 1129 1135 3106 1135 1137 3107 1137 1146 3108 1146 1138 3109 1138 1139 3110 1139 1142 3111 1142 1140 3112 1140 1141 3113 1141 1143 3114 1143 1140 3115 1140 1142 3116 1142 1145 3117 1145 1140 3118 1140 1143 3119 1143 1145 3120 1145 1144 3121 1144 1140 3122 1140 1147 3123 1147 1144 3124 1144 1145 3125 1145 1147 3126 1147 1146 3127 1146 1144 3128 1144 1148 3129 1148 1146 3130 1146 1147 3131 1147 1138 3132 1138 1146 3133 1146 1148 3134 1148 1175 3135 1175 1149 3136 1149 1150 3137 1150 1153 3138 1153 1151 3139 1151 1152 3140 1152 1154 3141 1154 1151 3142 1151 1153 3143 1153 1155 3144 1155 1151 3145 1151 1154 3146 1154 1156 3147 1156 1151 3148 1151 1155 3149 1155 1157 3150 1157 1151 3151 1151 1156 3152 1156 1174 3153 1174 1151 3154 1151 1157 3155 1157 1160 3156 1160 1158 3157 1158 1159 3158 1159 1161 3159 1161 1158 3160 1158 1160 3161 1160 1162 3162 1162 1158 3163 1158 1161 3164 1161 1163 3165 1163 1158 3166 1158 1162 3167 1162 1164 3168 1164 1158 3169 1158 1163 3170 1163 1165 3171 1165 1158 3172 1158 1164 3173 1164 1166 3174 1166 1158 3175 1158 1165 3176 1165 1167 3177 1167 1158 3178 1158 1166 3179 1166 1168 3180 1168 1158 3181 1158 1167 3182 1167 1182 3183 1182 1158 3184 1158 1168 3185 1168 1182 3186 1182 1169 3187 1169 1158 3188 1158 1182 3189 1182 1170 3190 1170 1169 3191 1169 1182 3192 1182 1171 3193 1171 1170 3194 1170 1182 3195 1182 1172 3196 1172 1171 3197 1171 1182 3198 1182 1173 3199 1173 1172 3200 1172 1176 3201 1176 1151 3202 1151 1174 3203 1174 1176 3204 1176 1175 3205 1175 1151 3206 1151 1177 3207 1177 1175 3208 1175 1176 3209 1176 1178 3210 1178 1175 3211 1175 1177 3212 1177 1179 3213 1179 1175 3214 1175 1178 3215 1178 1180 3216 1180 1175 3217 1175 1179 3218 1179 1181 3219 1181 1175 3220 1175 1180 3221 1180 1173 3222 1173 1175 3223 1175 1181 3224 1181 1182 3225 1182 1175 3226 1175 1173 3227 1173 1183 3228 1183 1175 3229 1175 1182 3230 1182 1184 3231 1184 1175 3232 1175 1183 3233 1183 1185 3234 1185 1175 3235 1175 1184 3236 1184 1186 3237 1186 1175 3238 1175 1185 3239 1185 1187 3240 1187 1175 3241 1175 1186 3242 1186 1149 3243 1149 1175 3244 1175 1187 3245 1187 1190 3246 1190 1188 3247 1188 1189 3248 1189 1192 3249 1192 1190 3250 1190 1191 3251 1191 1188 3252 1188 1190 3253 1190 1192 3254 1192 1197 3255 1197 1193 3256 1193 1194 3257 1194 1193 3258 1193 1195 3259 1195 1196 3260 1196 1193 3261 1193 1197 3262 1197 1195 3263 1195 1200 3264 1200 1198 3265 1198 1199 3266 1199 1202 3267 1202 1200 3268 1200 1201 3269 1201 1198 3270 1198 1200 3271 1200 1202 3272 1202 1207 3273 1207 1203 3274 1203 1204 3275 1204 1203 3276 1203 1205 3277 1205 1206 3278 1206 1203 3279 1203 1207 3280 1207 1205 3281 1205 1281 3282 1281 1231 3283 1231 1208 3284 1208 1211 3285 1211 1209 3286 1209 1210 3287 1210 1236 3288 1236 1209 3289 1209 1211 3290 1211 1236 3291 1236 1212 3292 1212 1209 3293 1209 1236 3294 1236 1213 3295 1213 1212 3296 1212 1236 3297 1236 1214 3298 1214 1213 3299 1213 1236 3300 1236 1215 3301 1215 1214 3302 1214 1236 3303 1236 1216 3304 1216 1215 3305 1215 1236 3306 1236 1217 3307 1217 1216 3308 1216 1236 3309 1236 1218 3310 1218 1217 3311 1217 1236 3312 1236 1219 3313 1219 1218 3314 1218 1223 3315 1223 1220 3316 1220 1221 3317 1221 1223 3318 1223 1222 3319 1222 1220 3320 1220 1224 3321 1224 1222 3322 1222 1223 3323 1223 1225 3324 1225 1222 3325 1222 1224 3326 1224 1226 3327 1226 1222 3328 1222 1225 3329 1225 1227 3330 1227 1222 3331 1222 1226 3332 1226 1228 3333 1228 1222 3334 1222 1227 3335 1227 1229 3336 1229 1222 3337 1222 1228 3338 1228 1230 3339 1230 1222 3340 1222 1229 3341 1229 1232 3342 1232 1222 3343 1222 1230 3344 1230 1232 3345 1232 1231 3346 1231 1222 3347 1222 1233 3348 1233 1231 3349 1231 1232 3350 1232 1234 3351 1234 1231 3352 1231 1233 3353 1233 1235 3354 1235 1231 3355 1231 1234 3356 1234 1208 3357 1208 1231 3358 1231 1235 3359 1235 1242 3360 1242 1219 3361 1219 1236 3362 1236 1242 3363 1242 1237 3364 1237 1219 3365 1219 1242 3366 1242 1238 3367 1238 1237 3368 1237 1242 3369 1242 1239 3370 1239 1238 3371 1238 1242 3372 1242 1240 3373 1240 1239 3374 1239 1242 3375 1242 1241 3376 1241 1240 3377 1240 1243 3378 1243 1241 3379 1241 1242 3380 1242 1244 3381 1244 1241 3382 1241 1243 3383 1243 1245 3384 1245 1241 3385 1241 1244 3386 1244 1246 3387 1246 1241 3388 1241 1245 3389 1245 1247 3390 1247 1241 3391 1241 1246 3392 1246 1248 3393 1248 1241 3394 1241 1247 3395 1247 1250 3396 1250 1241 3397 1241 1248 3398 1248 1250 3399 1250 1249 3400 1249 1241 3401 1241 1253 3402 1253 1249 3403 1249 1250 3404 1250 1253 3405 1253 1251 3406 1251 1249 3407 1249 1253 3408 1253 1252 3409 1252 1251 3410 1251 1265 3411 1265 1252 3412 1252 1253 3413 1253 1265 3414 1265 1254 3415 1254 1252 3416 1252 1265 3417 1265 1255 3418 1255 1254 3419 1254 1265 3420 1265 1256 3421 1256 1255 3422 1255 1265 3423 1265 1257 3424 1257 1256 3425 1256 1265 3426 1265 1258 3427 1258 1257 3428 1257 1265 3429 1265 1259 3430 1259 1258 3431 1258 1265 3432 1265 1260 3433 1260 1259 3434 1259 1265 3435 1265 1261 3436 1261 1260 3437 1260 1265 3438 1265 1262 3439 1262 1261 3440 1261 1265 3441 1265 1263 3442 1263 1262 3443 1262 1265 3444 1265 1264 3445 1264 1263 3446 1263 1274 3447 1274 1264 3448 1264 1265 3449 1265 1274 3450 1274 1266 3451 1266 1264 3452 1264 1274 3453 1274 1267 3454 1267 1266 3455 1266 1274 3456 1274 1268 3457 1268 1267 3458 1267 1274 3459 1274 1269 3460 1269 1268 3461 1268 1274 3462 1274 1270 3463 1270 1269 3464 1269 1274 3465 1274 1271 3466 1271 1270 3467 1270 1274 3468 1274 1272 3469 1272 1271 3470 1271 1274 3471 1274 1273 3472 1273 1272 3473 1272 1279 3474 1279 1273 3475 1273 1274 3476 1274 1279 3477 1279 1275 3478 1275 1273 3479 1273 1279 3480 1279 1276 3481 1276 1275 3482 1275 1279 3483 1279 1277 3484 1277 1276 3485 1276 1279 3486 1279 1278 3487 1278 1277 3488 1277 1280 3489 1280 1278 3490 1278 1279 3491 1279 1282 3492 1282 1278 3493 1278 1280 3494 1280 1282 3495 1282 1281 3496 1281 1278 3497 1278 1283 3498 1283 1281 3499 1281 1282 3500 1282 1284 3501 1284 1281 3502 1281 1283 3503 1283 1285 3504 1285 1281 3505 1281 1284 3506 1284 1286 3507 1286 1281 3508 1281 1285 3509 1285 1287 3510 1287 1281 3511 1281 1286 3512 1286 1231 3513 1231 1281 3514 1281 1287 3515 1287 1290 3516 1290 1288 3517 1288 1289 3518 1289 1288 3519 1288 1290 3520 1290 1291 3521 1291 1296 3522 1296 1292 3523 1292 1293 3524 1293 1292 3525 1292 1294 3526 1294 1295 3527 1295 1292 3528 1292 1296 3529 1296 1294 3530 1294 1299 3531 1299 1297 3532 1297 1298 3533 1298 1301 3534 1301 1299 3535 1299 1300 3536 1300 1297 3537 1297 1299 3538 1299 1301 3539 1301 1304 3540 1304 1302 3541 1302 1303 3542 1303 1302 3543 1302 1304 3544 1304 1305 3545 1305 1308 3546 1308 1306 3547 1306 1307 3548 1307 1306 3549 1306 1308 3550 1308 1309 3551 1309 1332 3552 1332 1310 3553 1310 1311 3554 1311 1314 3555 1314 1312 3556 1312 1313 3557 1313 1317 3558 1317 1312 3559 1312 1314 3560 1314 1317 3561 1317 1315 3562 1315 1312 3563 1312 1317 3564 1317 1316 3565 1316 1315 3566 1315 1319 3567 1319 1316 3568 1316 1317 3569 1317 1319 3570 1319 1318 3571 1318 1316 3572 1316 1320 3573 1320 1318 3574 1318 1319 3575 1319 1322 3576 1322 1318 3577 1318 1320 3578 1320 1322 3579 1322 1321 3580 1321 1318 3581 1318 1324 3582 1324 1321 3583 1321 1322 3584 1322 1324 3585 1324 1323 3586 1323 1321 3587 1321 1326 3588 1326 1323 3589 1323 1324 3590 1324 1326 3591 1326 1325 3592 1325 1323 3593 1323 1327 3594 1327 1325 3595 1325 1326 3596 1326 1329 3597 1329 1325 3598 1325 1327 3599 1327 1329 3600 1329 1328 3601 1328 1325 3602 1325 1331 3603 1331 1328 3604 1328 1329 3605 1329 1331 3606 1331 1330 3607 1330 1328 3608 1328 1310 3609 1310 1330 3610 1330 1331 3611 1331 1310 3612 1310 1332 3613 1332 1330 3614 1330 1354 3615 1354 1333 3616 1333 1334 3617 1334 1338 3618 1338 1335 3619 1335 1336 3620 1336 1338 3621 1338 1337 3622 1337 1335 3623 1335 1339 3624 1339 1337 3625 1337 1338 3626 1338 1341 3627 1341 1337 3628 1337 1339 3629 1339 1341 3630 1341 1340 3631 1340 1337 3632 1337 1344 3633 1344 1340 3634 1340 1341 3635 1341 1344 3636 1344 1342 3637 1342 1340 3638 1340 1344 3639 1344 1343 3640 1343 1342 3641 1342 1346 3642 1346 1343 3643 1343 1344 3644 1344 1346 3645 1346 1345 3646 1345 1343 3647 1343 1348 3648 1348 1345 3649 1345 1346 3650 1346 1348 3651 1348 1347 3652 1347 1345 3653 1345 1351 3654 1351 1347 3655 1347 1348 3656 1348 1351 3657 1351 1349 3658 1349 1347 3659 1347 1351 3660 1351 1350 3661 1350 1349 3662 1349 1353 3663 1353 1350 3664 1350 1351 3665 1351 1353 3666 1353 1352 3667 1352 1350 3668 1350 1355 3669 1355 1352 3670 1352 1353 3671 1353 1355 3672 1355 1354 3673 1354 1352 3674 1352 1333 3675 1333 1354 3676 1354 1355 3677 1355 1380 3678 1380 1356 3679 1356 1357 3680 1357 1361 3681 1361 1358 3682 1358 1359 3683 1359 1361 3684 1361 1360 3685 1360 1358 3686 1358 1363 3687 1363 1360 3688 1360 1361 3689 1361 1363 3690 1363 1362 3691 1362 1360 3692 1360 1365 3693 1365 1362 3694 1362 1363 3695 1363 1365 3696 1365 1364 3697 1364 1362 3698 1362 1367 3699 1367 1364 3700 1364 1365 3701 1365 1367 3702 1367 1366 3703 1366 1364 3704 1364 1369 3705 1369 1366 3706 1366 1367 3707 1367 1369 3708 1369 1368 3709 1368 1366 3710 1366 1371 3711 1371 1368 3712 1368 1369 3713 1369 1371 3714 1371 1370 3715 1370 1368 3716 1368 1373 3717 1373 1370 3718 1370 1371 3719 1371 1373 3720 1373 1372 3721 1372 1370 3722 1370 1375 3723 1375 1372 3724 1372 1373 3725 1373 1375 3726 1375 1374 3727 1374 1372 3728 1372 1377 3729 1377 1374 3730 1374 1375 3731 1375 1377 3732 1377 1376 3733 1376 1374 3734 1374 1379 3735 1379 1376 3736 1376 1377 3737 1377 1379 3738 1379 1378 3739 1378 1376 3740 1376 1381 3741 1381 1378 3742 1378 1379 3743 1379 1381 3744 1381 1380 3745 1380 1378 3746 1378 1356 3747 1356 1380 3748 1380 1381 3749 1381 1406 3750 1406 1382 3751 1382 1383 3752 1383 1386 3753 1386 1384 3754 1384 1385 3755 1385 1388 3756 1388 1384 3757 1384 1386 3758 1386 1388 3759 1388 1387 3760 1387 1384 3761 1384 1390 3762 1390 1387 3763 1387 1388 3764 1388 1390 3765 1390 1389 3766 1389 1387 3767 1387 1391 3768 1391 1389 3769 1389 1390 3770 1390 1393 3771 1393 1389 3772 1389 1391 3773 1391 1393 3774 1393 1392 3775 1392 1389 3776 1389 1395 3777 1395 1392 3778 1392 1393 3779 1393 1395 3780 1395 1394 3781 1394 1392 3782 1392 1397 3783 1397 1394 3784 1394 1395 3785 1395 1397 3786 1397 1396 3787 1396 1394 3788 1394 1399 3789 1399 1396 3790 1396 1397 3791 1397 1399 3792 1399 1398 3793 1398 1396 3794 1396 1401 3795 1401 1398 3796 1398 1399 3797 1399 1401 3798 1401 1400 3799 1400 1398 3800 1398 1403 3801 1403 1400 3802 1400 1401 3803 1401 1403 3804 1403 1402 3805 1402 1400 3806 1400 1405 3807 1405 1402 3808 1402 1403 3809 1403 1405 3810 1405 1404 3811 1404 1402 3812 1402 1407 3813 1407 1404 3814 1404 1405 3815 1405 1407 3816 1407 1406 3817 1406 1404 3818 1404 1382 3819 1382 1406 3820 1406 1407 3821 1407 1426 3822 1426 1408 3823 1408 1409 3824 1409 1412 3825 1412 1410 3826 1410 1411 3827 1411 1413 3828 1413 1410 3829 1410 1412 3830 1412 1415 3831 1415 1410 3832 1410 1413 3833 1413 1415 3834 1415 1414 3835 1414 1410 3836 1410 1417 3837 1417 1414 3838 1414 1415 3839 1415 1417 3840 1417 1416 3841 1416 1414 3842 1414 1418 3843 1418 1416 3844 1416 1417 3845 1417 1420 3846 1420 1416 3847 1416 1418 3848 1418 1420 3849 1420 1419 3850 1419 1416 3851 1416 1422 3852 1422 1419 3853 1419 1420 3854 1420 1422 3855 1422 1421 3856 1421 1419 3857 1419 1423 3858 1423 1421 3859 1421 1422 3860 1422 1425 3861 1425 1421 3862 1421 1423 3863 1423 1425 3864 1425 1424 3865 1424 1421 3866 1421 1427 3867 1427 1424 3868 1424 1425 3869 1425 1427 3870 1427 1426 3871 1426 1424 3872 1424 1428 3873 1428 1426 3874 1426 1427 3875 1427 1429 3876 1429 1426 3877 1426 1428 3878 1428 1408 3879 1408 1426 3880 1426 1429 3881 1429 1451 3882 1451 1430 3883 1430 1431 3884 1431 1436 3885 1436 1432 3886 1432 1433 3887 1433 1436 3888 1436 1434 3889 1434 1432 3890 1432 1436 3891 1436 1435 3892 1435 1434 3893 1434 1438 3894 1438 1435 3895 1435 1436 3896 1436 1438 3897 1438 1437 3898 1437 1435 3899 1435 1441 3900 1441 1437 3901 1437 1438 3902 1438 1441 3903 1441 1439 3904 1439 1437 3905 1437 1441 3906 1441 1440 3907 1440 1439 3908 1439 1443 3909 1443 1440 3910 1440 1441 3911 1441 1443 3912 1443 1442 3913 1442 1440 3914 1440 1446 3915 1446 1442 3916 1442 1443 3917 1443 1446 3918 1446 1444 3919 1444 1442 3920 1442 1446 3921 1446 1445 3922 1445 1444 3923 1444 1448 3924 1448 1445 3925 1445 1446 3926 1446 1448 3927 1448 1447 3928 1447 1445 3929 1445 1430 3930 1430 1447 3931 1447 1448 3932 1448 1430 3933 1430 1449 3934 1449 1447 3935 1447 1430 3936 1430 1450 3937 1450 1449 3938 1449 1430 3939 1430 1451 3940 1451 1450 3941 1450 1476 3942 1476 1452 3943 1452 1453 3944 1453 1457 3945 1457 1454 3946 1454 1455 3947 1455 1457 3948 1457 1456 3949 1456 1454 3950 1454 1459 3951 1459 1456 3952 1456 1457 3953 1457 1459 3954 1459 1458 3955 1458 1456 3956 1456 1462 3957 1462 1458 3958 1458 1459 3959 1459 1462 3960 1462 1460 3961 1460 1458 3962 1458 1462 3963 1462 1461 3964 1461 1460 3965 1460 1463 3966 1463 1461 3967 1461 1462 3968 1462 1465 3969 1465 1461 3970 1461 1463 3971 1463 1465 3972 1465 1464 3973 1464 1461 3974 1461 1467 3975 1467 1464 3976 1464 1465 3977 1465 1467 3978 1467 1466 3979 1466 1464 3980 1464 1469 3981 1469 1466 3982 1466 1467 3983 1467 1469 3984 1469 1468 3985 1468 1466 3986 1466 1472 3987 1472 1468 3988 1468 1469 3989 1469 1472 3990 1472 1470 3991 1470 1468 3992 1468 1472 3993 1472 1471 3994 1471 1470 3995 1470 1474 3996 1474 1471 3997 1471 1472 3998 1472 1474 3999 1474 1473 4000 1473 1471 4001 1471 1477 4002 1477 1473 4003 1473 1474 4004 1474 1477 4005 1477 1475 4006 1475 1473 4007 1473 1477 4008 1477 1476 4009 1476 1475 4010 1475 1452 4011 1452 1476 4012 1476 1477 4013 1477 1503 4014 1503 1478 4015 1478 1499 4016 1499 1481 4017 1481 1479 4018 1479 1480 4019 1480 1483 4020 1483 1479 4021 1479 1481 4022 1481 1483 4023 1483 1482 4024 1482 1479 4025 1479 1486 4026 1486 1482 4027 1482 1483 4028 1483 1486 4029 1486 1484 4030 1484 1482 4031 1482 1486 4032 1486 1485 4033 1485 1484 4034 1484 1488 4035 1488 1485 4036 1485 1486 4037 1486 1488 4038 1488 1487 4039 1487 1485 4040 1485 1491 4041 1491 1487 4042 1487 1488 4043 1488 1491 4044 1491 1489 4045 1489 1487 4046 1487 1491 4047 1491 1490 4048 1490 1489 4049 1489 1493 4050 1493 1490 4051 1490 1491 4052 1491 1493 4053 1493 1492 4054 1492 1490 4055 1490 1495 4056 1495 1492 4057 1492 1493 4058 1493 1495 4059 1495 1494 4060 1494 1492 4061 1492 1497 4062 1497 1494 4063 1494 1495 4064 1495 1497 4065 1497 1496 4066 1496 1494 4067 1494 1498 4068 1498 1496 4069 1496 1497 4070 1497 1503 4071 1503 1496 4072 1496 1498 4073 1498 1503 4074 1503 1499 4075 1499 1496 4076 1496 1502 4077 1502 1500 4078 1500 1501 4079 1501 1478 4080 1478 1500 4081 1500 1502 4082 1502 1478 4083 1478 1503 4084 1503 1500 4085 1500 1526 4086 1526 1504 4087 1504 1505 4088 1505 1510 4089 1510 1506 4090 1506 1507 4091 1507 1510 4092 1510 1508 4093 1508 1506 4094 1506 1510 4095 1510 1509 4096 1509 1508 4097 1508 1512 4098 1512 1509 4099 1509 1510 4100 1510 1512 4101 1512 1511 4102 1511 1509 4103 1509 1515 4104 1515 1511 4105 1511 1512 4106 1512 1515 4107 1515 1513 4108 1513 1511 4109 1511 1515 4110 1515 1514 4111 1514 1513 4112 1513 1517 4113 1517 1514 4114 1514 1515 4115 1515 1517 4116 1517 1516 4117 1516 1514 4118 1514 1520 4119 1520 1516 4120 1516 1517 4121 1517 1520 4122 1520 1518 4123 1518 1516 4124 1516 1520 4125 1520 1519 4126 1519 1518 4127 1518 1523 4128 1523 1519 4129 1519 1520 4130 1520 1523 4131 1523 1521 4132 1521 1519 4133 1519 1523 4134 1523 1522 4135 1522 1521 4136 1521 1525 4137 1525 1522 4138 1522 1523 4139 1523 1525 4140 1525 1524 4141 1524 1522 4142 1522 1527 4143 1527 1524 4144 1524 1525 4145 1525 1527 4146 1527 1526 4147 1526 1524 4148 1524 1504 4149 1504 1526 4150 1526 1527 4151 1527 1534 4152 1534 1528 4153 1528 1529 4154 1529 1528 4155 1528 1530 4156 1530 1531 4157 1531 1528 4158 1528 1532 4159 1532 1530 4160 1530 1528 4161 1528 1533 4162 1533 1532 4163 1532 1528 4164 1528 1534 4165 1534 1533 4166 1533 1539 4167 1539 1535 4168 1535 1536 4169 1536 1540 4170 1540 1537 4171 1537 1538 4172 1538 1540 4173 1540 1539 4174 1539 1537 4175 1537 1541 4176 1541 1539 4177 1539 1540 4178 1540 1535 4179 1535 1539 4180 1539 1541 4181 1541 1548 4182 1548 1542 4183 1542 1543 4184 1543 1546 4185 1546 1544 4186 1544 1545 4187 1545 1542 4188 1542 1544 4189 1544 1546 4190 1546 1542 4191 1542 1547 4192 1547 1544 4193 1544 1542 4194 1542 1548 4195 1548 1547 4196 1547 1551 4197 1551 1549 4198 1549 1550 4199 1550 1553 4200 1553 1551 4201 1551 1552 4202 1552 1554 4203 1554 1551 4204 1551 1553 4205 1553 1555 4206 1555 1551 4207 1551 1554 4208 1554 1549 4209 1549 1551 4210 1551 1555 4211 1555 1588 4212 1588 1557 4213 1557 1556 4214 1556 1559 4215 1559 1557 4216 1557 1558 4217 1558 1556 4218 1556 1557 4219 1557 1559 4220 1559 1563 4221 1563 1560 4222 1560 1561 4223 1561 1563 4224 1563 1562 4225 1562 1560 4226 1560 1566 4227 1566 1562 4228 1562 1563 4229 1563 1566 4230 1566 1564 4231 1564 1562 4232 1562 1566 4233 1566 1565 4234 1565 1564 4235 1564 1567 4236 1567 1565 4237 1565 1566 4238 1566 1569 4239 1569 1565 4240 1565 1567 4241 1567 1569 4242 1569 1568 4243 1568 1565 4244 1565 1571 4245 1571 1568 4246 1568 1569 4247 1569 1571 4248 1571 1570 4249 1570 1568 4250 1568 1573 4251 1573 1570 4252 1570 1571 4253 1571 1573 4254 1573 1572 4255 1572 1570 4256 1570 1575 4257 1575 1572 4258 1572 1573 4259 1573 1575 4260 1575 1574 4261 1574 1572 4262 1572 1577 4263 1577 1574 4264 1574 1575 4265 1575 1577 4266 1577 1576 4267 1576 1574 4268 1574 1579 4269 1579 1576 4270 1576 1577 4271 1577 1579 4272 1579 1578 4273 1578 1576 4274 1576 1581 4275 1581 1578 4276 1578 1579 4277 1579 1581 4278 1581 1580 4279 1580 1578 4280 1578 1583 4281 1583 1580 4282 1580 1581 4283 1581 1583 4284 1583 1582 4285 1582 1580 4286 1580 1585 4287 1585 1582 4288 1582 1583 4289 1583 1585 4290 1585 1584 4291 1584 1582 4292 1582 1587 4293 1587 1584 4294 1584 1585 4295 1585 1587 4296 1587 1586 4297 1586 1584 4298 1584 1589 4299 1589 1586 4300 1586 1587 4301 1587 1589 4302 1589 1588 4303 1588 1586 4304 1586 1557 4305 1557 1588 4306 1588 1589 4307 1589 1653 4308 1653 1590 4309 1590 1592 4310 1592 1592 4311 1592 1591 4312 1591 1653 4313 1653 1594 4314 1594 1591 4315 1591 1592 4316 1592 1594 4317 1594 1593 4318 1593 1591 4319 1591 1596 4320 1596 1593 4321 1593 1594 4322 1594 1596 4323 1596 1595 4324 1595 1593 4325 1593 1598 4326 1598 1595 4327 1595 1596 4328 1596 1598 4329 1598 1597 4330 1597 1595 4331 1595 1600 4332 1600 1597 4333 1597 1598 4334 1598 1600 4335 1600 1599 4336 1599 1597 4337 1597 1602 4338 1602 1599 4339 1599 1600 4340 1600 1602 4341 1602 1601 4342 1601 1599 4343 1599 1604 4344 1604 1601 4345 1601 1602 4346 1602 1604 4347 1604 1603 4348 1603 1601 4349 1601 1606 4350 1606 1603 4351 1603 1604 4352 1604 1606 4353 1606 1605 4354 1605 1603 4355 1603 1608 4356 1608 1605 4357 1605 1606 4358 1606 1608 4359 1608 1607 4360 1607 1605 4361 1605 1610 4362 1610 1607 4363 1607 1608 4364 1608 1610 4365 1610 1609 4366 1609 1607 4367 1607 1612 4368 1612 1609 4369 1609 1610 4370 1610 1612 4371 1612 1611 4372 1611 1609 4373 1609 1614 4374 1614 1611 4375 1611 1612 4376 1612 1614 4377 1614 1613 4378 1613 1611 4379 1611 1616 4380 1616 1613 4381 1613 1614 4382 1614 1616 4383 1616 1615 4384 1615 1613 4385 1613 1618 4386 1618 1615 4387 1615 1616 4388 1616 1618 4389 1618 1617 4390 1617 1615 4391 1615 1620 4392 1620 1617 4393 1617 1618 4394 1618 1620 4395 1620 1619 4396 1619 1617 4397 1617 1622 4398 1622 1619 4399 1619 1620 4400 1620 1622 4401 1622 1621 4402 1621 1619 4403 1619 1624 4404 1624 1621 4405 1621 1622 4406 1622 1624 4407 1624 1623 4408 1623 1621 4409 1621 1626 4410 1626 1623 4411 1623 1624 4412 1624 1626 4413 1626 1625 4414 1625 1623 4415 1623 1628 4416 1628 1625 4417 1625 1626 4418 1626 1628 4419 1628 1627 4420 1627 1625 4421 1625 1630 4422 1630 1627 4423 1627 1628 4424 1628 1630 4425 1630 1629 4426 1629 1627 4427 1627 1632 4428 1632 1629 4429 1629 1630 4430 1630 1632 4431 1632 1631 4432 1631 1629 4433 1629 1634 4434 1634 1631 4435 1631 1632 4436 1632 1634 4437 1634 1633 4438 1633 1631 4439 1631 1636 4440 1636 1633 4441 1633 1634 4442 1634 1636 4443 1636 1635 4444 1635 1633 4445 1633 1638 4446 1638 1635 4447 1635 1636 4448 1636 1638 4449 1638 1637 4450 1637 1635 4451 1635 1640 4452 1640 1637 4453 1637 1638 4454 1638 1640 4455 1640 1639 4456 1639 1637 4457 1637 1642 4458 1642 1639 4459 1639 1640 4460 1640 1642 4461 1642 1641 4462 1641 1639 4463 1639 1644 4464 1644 1641 4465 1641 1642 4466 1642 1644 4467 1644 1643 4468 1643 1641 4469 1641 1646 4470 1646 1643 4471 1643 1644 4472 1644 1646 4473 1646 1645 4474 1645 1643 4475 1643 1648 4476 1648 1645 4477 1645 1646 4478 1646 1648 4479 1648 1647 4480 1647 1645 4481 1645 1650 4482 1650 1647 4483 1647 1648 4484 1648 1650 4485 1650 1649 4486 1649 1647 4487 1647 1652 4488 1652 1649 4489 1649 1650 4490 1650 1652 4491 1652 1651 4492 1651 1649 4493 1649 1590 4494 1590 1651 4495 1651 1652 4496 1652 1590 4497 1590 1653 4498 1653 1651 4499 1651 1686 4500 1686 1655 4501 1655 1654 4502 1654 1657 4503 1657 1655 4504 1655 1656 4505 1656 1654 4506 1654 1655 4507 1655 1657 4508 1657 1661 4509 1661 1658 4510 1658 1659 4511 1659 1661 4512 1661 1660 4513 1660 1658 4514 1658 1663 4515 1663 1660 4516 1660 1661 4517 1661 1663 4518 1663 1662 4519 1662 1660 4520 1660 1665 4521 1665 1662 4522 1662 1663 4523 1663 1665 4524 1665 1664 4525 1664 1662 4526 1662 1667 4527 1667 1664 4528 1664 1665 4529 1665 1667 4530 1667 1666 4531 1666 1664 4532 1664 1669 4533 1669 1666 4534 1666 1667 4535 1667 1669 4536 1669 1668 4537 1668 1666 4538 1666 1671 4539 1671 1668 4540 1668 1669 4541 1669 1671 4542 1671 1670 4543 1670 1668 4544 1668 1673 4545 1673 1670 4546 1670 1671 4547 1671 1673 4548 1673 1672 4549 1672 1670 4550 1670 1675 4551 1675 1672 4552 1672 1673 4553 1673 1675 4554 1675 1674 4555 1674 1672 4556 1672 1677 4557 1677 1674 4558 1674 1675 4559 1675 1677 4560 1677 1676 4561 1676 1674 4562 1674 1679 4563 1679 1676 4564 1676 1677 4565 1677 1679 4566 1679 1678 4567 1678 1676 4568 1676 1681 4569 1681 1678 4570 1678 1679 4571 1679 1681 4572 1681 1680 4573 1680 1678 4574 1678 1683 4575 1683 1680 4576 1680 1681 4577 1681 1683 4578 1683 1682 4579 1682 1680 4580 1680 1685 4581 1685 1682 4582 1682 1683 4583 1683 1685 4584 1685 1684 4585 1684 1682 4586 1682 1687 4587 1687 1684 4588 1684 1685 4589 1685 1687 4590 1687 1686 4591 1686 1684 4592 1684 1655 4593 1655 1686 4594 1686 1687 4595 1687 1751 4596 1751 1688 4597 1688 1690 4598 1690 1690 4599 1690 1689 4600 1689 1751 4601 1751 1692 4602 1692 1689 4603 1689 1690 4604 1690 1692 4605 1692 1691 4606 1691 1689 4607 1689 1694 4608 1694 1691 4609 1691 1692 4610 1692 1694 4611 1694 1693 4612 1693 1691 4613 1691 1696 4614 1696 1693 4615 1693 1694 4616 1694 1696 4617 1696 1695 4618 1695 1693 4619 1693 1698 4620 1698 1695 4621 1695 1696 4622 1696 1698 4623 1698 1697 4624 1697 1695 4625 1695 1700 4626 1700 1697 4627 1697 1698 4628 1698 1700 4629 1700 1699 4630 1699 1697 4631 1697 1702 4632 1702 1699 4633 1699 1700 4634 1700 1702 4635 1702 1701 4636 1701 1699 4637 1699 1704 4638 1704 1701 4639 1701 1702 4640 1702 1704 4641 1704 1703 4642 1703 1701 4643 1701 1706 4644 1706 1703 4645 1703 1704 4646 1704 1706 4647 1706 1705 4648 1705 1703 4649 1703 1708 4650 1708 1705 4651 1705 1706 4652 1706 1708 4653 1708 1707 4654 1707 1705 4655 1705 1710 4656 1710 1707 4657 1707 1708 4658 1708 1710 4659 1710 1709 4660 1709 1707 4661 1707 1712 4662 1712 1709 4663 1709 1710 4664 1710 1712 4665 1712 1711 4666 1711 1709 4667 1709 1714 4668 1714 1711 4669 1711 1712 4670 1712 1714 4671 1714 1713 4672 1713 1711 4673 1711 1716 4674 1716 1713 4675 1713 1714 4676 1714 1716 4677 1716 1715 4678 1715 1713 4679 1713 1718 4680 1718 1715 4681 1715 1716 4682 1716 1718 4683 1718 1717 4684 1717 1715 4685 1715 1720 4686 1720 1717 4687 1717 1718 4688 1718 1720 4689 1720 1719 4690 1719 1717 4691 1717 1722 4692 1722 1719 4693 1719 1720 4694 1720 1722 4695 1722 1721 4696 1721 1719 4697 1719 1724 4698 1724 1721 4699 1721 1722 4700 1722 1724 4701 1724 1723 4702 1723 1721 4703 1721 1726 4704 1726 1723 4705 1723 1724 4706 1724 1726 4707 1726 1725 4708 1725 1723 4709 1723 1728 4710 1728 1725 4711 1725 1726 4712 1726 1728 4713 1728 1727 4714 1727 1725 4715 1725 1730 4716 1730 1727 4717 1727 1728 4718 1728 1730 4719 1730 1729 4720 1729 1727 4721 1727 1732 4722 1732 1729 4723 1729 1730 4724 1730 1732 4725 1732 1731 4726 1731 1729 4727 1729 1734 4728 1734 1731 4729 1731 1732 4730 1732 1734 4731 1734 1733 4732 1733 1731 4733 1731 1736 4734 1736 1733 4735 1733 1734 4736 1734 1736 4737 1736 1735 4738 1735 1733 4739 1733 1738 4740 1738 1735 4741 1735 1736 4742 1736 1738 4743 1738 1737 4744 1737 1735 4745 1735 1740 4746 1740 1737 4747 1737 1738 4748 1738 1740 4749 1740 1739 4750 1739 1737 4751 1737 1742 4752 1742 1739 4753 1739 1740 4754 1740 1742 4755 1742 1741 4756 1741 1739 4757 1739 1744 4758 1744 1741 4759 1741 1742 4760 1742 1744 4761 1744 1743 4762 1743 1741 4763 1741 1746 4764 1746 1743 4765 1743 1744 4766 1744 1746 4767 1746 1745 4768 1745 1743 4769 1743 1748 4770 1748 1745 4771 1745 1746 4772 1746 1748 4773 1748 1747 4774 1747 1745 4775 1745 1750 4776 1750 1747 4777 1747 1748 4778 1748 1750 4779 1750 1749 4780 1749 1747 4781 1747 1688 4782 1688 1749 4783 1749 1750 4784 1750 1688 4785 1688 1751 4786 1751 1749 4787 1749 1784 4788 1784 1752 4789 1752 1753 4790 1753 1757 4791 1757 1754 4792 1754 1755 4793 1755 1757 4794 1757 1756 4795 1756 1754 4796 1754 1759 4797 1759 1756 4798 1756 1757 4799 1757 1759 4800 1759 1758 4801 1758 1756 4802 1756 1761 4803 1761 1758 4804 1758 1759 4805 1759 1761 4806 1761 1760 4807 1760 1758 4808 1758 1763 4809 1763 1760 4810 1760 1761 4811 1761 1763 4812 1763 1762 4813 1762 1760 4814 1760 1765 4815 1765 1762 4816 1762 1763 4817 1763 1765 4818 1765 1764 4819 1764 1762 4820 1762 1767 4821 1767 1764 4822 1764 1765 4823 1765 1767 4824 1767 1766 4825 1766 1764 4826 1764 1769 4827 1769 1766 4828 1766 1767 4829 1767 1769 4830 1769 1768 4831 1768 1766 4832 1766 1771 4833 1771 1768 4834 1768 1769 4835 1769 1771 4836 1771 1770 4837 1770 1768 4838 1768 1773 4839 1773 1770 4840 1770 1771 4841 1771 1773 4842 1773 1772 4843 1772 1770 4844 1770 1775 4845 1775 1772 4846 1772 1773 4847 1773 1775 4848 1775 1774 4849 1774 1772 4850 1772 1777 4851 1777 1774 4852 1774 1775 4853 1775 1777 4854 1777 1776 4855 1776 1774 4856 1774 1779 4857 1779 1776 4858 1776 1777 4859 1777 1779 4860 1779 1778 4861 1778 1776 4862 1776 1781 4863 1781 1778 4864 1778 1779 4865 1779 1781 4866 1781 1780 4867 1780 1778 4868 1778 1783 4869 1783 1780 4870 1780 1781 4871 1781 1783 4872 1783 1782 4873 1782 1780 4874 1780 1785 4875 1785 1782 4876 1782 1783 4877 1783 1785 4878 1785 1784 4879 1784 1782 4880 1782 1752 4881 1752 1784 4882 1784 1785 4883 1785 1849 4884 1849 1786 4885 1786 1788 4886 1788 1788 4887 1788 1787 4888 1787 1849 4889 1849 1790 4890 1790 1787 4891 1787 1788 4892 1788 1790 4893 1790 1789 4894 1789 1787 4895 1787 1792 4896 1792 1789 4897 1789 1790 4898 1790 1792 4899 1792 1791 4900 1791 1789 4901 1789 1794 4902 1794 1791 4903 1791 1792 4904 1792 1794 4905 1794 1793 4906 1793 1791 4907 1791 1796 4908 1796 1793 4909 1793 1794 4910 1794 1796 4911 1796 1795 4912 1795 1793 4913 1793 1798 4914 1798 1795 4915 1795 1796 4916 1796 1798 4917 1798 1797 4918 1797 1795 4919 1795 1800 4920 1800 1797 4921 1797 1798 4922 1798 1800 4923 1800 1799 4924 1799 1797 4925 1797 1802 4926 1802 1799 4927 1799 1800 4928 1800 1802 4929 1802 1801 4930 1801 1799 4931 1799 1804 4932 1804 1801 4933 1801 1802 4934 1802 1804 4935 1804 1803 4936 1803 1801 4937 1801 1806 4938 1806 1803 4939 1803 1804 4940 1804 1806 4941 1806 1805 4942 1805 1803 4943 1803 1808 4944 1808 1805 4945 1805 1806 4946 1806 1808 4947 1808 1807 4948 1807 1805 4949 1805 1810 4950 1810 1807 4951 1807 1808 4952 1808 1810 4953 1810 1809 4954 1809 1807 4955 1807 1812 4956 1812 1809 4957 1809 1810 4958 1810 1812 4959 1812 1811 4960 1811 1809 4961 1809 1814 4962 1814 1811 4963 1811 1812 4964 1812 1814 4965 1814 1813 4966 1813 1811 4967 1811 1816 4968 1816 1813 4969 1813 1814 4970 1814 1816 4971 1816 1815 4972 1815 1813 4973 1813 1818 4974 1818 1815 4975 1815 1816 4976 1816 1818 4977 1818 1817 4978 1817 1815 4979 1815 1820 4980 1820 1817 4981 1817 1818 4982 1818 1820 4983 1820 1819 4984 1819 1817 4985 1817 1822 4986 1822 1819 4987 1819 1820 4988 1820 1822 4989 1822 1821 4990 1821 1819 4991 1819 1824 4992 1824 1821 4993 1821 1822 4994 1822 1824 4995 1824 1823 4996 1823 1821 4997 1821 1826 4998 1826 1823 4999 1823 1824 5000 1824 1826 5001 1826 1825 5002 1825 1823 5003 1823 1828 5004 1828 1825 5005 1825 1826 5006 1826 1828 5007 1828 1827 5008 1827 1825 5009 1825 1830 5010 1830 1827 5011 1827 1828 5012 1828 1830 5013 1830 1829 5014 1829 1827 5015 1827 1832 5016 1832 1829 5017 1829 1830 5018 1830 1832 5019 1832 1831 5020 1831 1829 5021 1829 1834 5022 1834 1831 5023 1831 1832 5024 1832 1834 5025 1834 1833 5026 1833 1831 5027 1831 1836 5028 1836 1833 5029 1833 1834 5030 1834 1836 5031 1836 1835 5032 1835 1833 5033 1833 1838 5034 1838 1835 5035 1835 1836 5036 1836 1838 5037 1838 1837 5038 1837 1835 5039 1835 1840 5040 1840 1837 5041 1837 1838 5042 1838 1840 5043 1840 1839 5044 1839 1837 5045 1837 1842 5046 1842 1839 5047 1839 1840 5048 1840 1842 5049 1842 1841 5050 1841 1839 5051 1839 1844 5052 1844 1841 5053 1841 1842 5054 1842 1844 5055 1844 1843 5056 1843 1841 5057 1841 1846 5058 1846 1843 5059 1843 1844 5060 1844 1846 5061 1846 1845 5062 1845 1843 5063 1843 1848 5064 1848 1845 5065 1845 1846 5066 1846 1848 5067 1848 1847 5068 1847 1845 5069 1845 1786 5070 1786 1847 5071 1847 1848 5072 1848 1786 5073 1786 1849 5074 1849 1847 5075 1847 1882 5076 1882 1851 5077 1851 1850 5078 1850 1853 5079 1853 1851 5080 1851 1852 5081 1852 1850 5082 1850 1851 5083 1851 1853 5084 1853 1857 5085 1857 1854 5086 1854 1855 5087 1855 1857 5088 1857 1856 5089 1856 1854 5090 1854 1859 5091 1859 1856 5092 1856 1857 5093 1857 1859 5094 1859 1858 5095 1858 1856 5096 1856 1861 5097 1861 1858 5098 1858 1859 5099 1859 1861 5100 1861 1860 5101 1860 1858 5102 1858 1863 5103 1863 1860 5104 1860 1861 5105 1861 1863 5106 1863 1862 5107 1862 1860 5108 1860 1865 5109 1865 1862 5110 1862 1863 5111 1863 1865 5112 1865 1864 5113 1864 1862 5114 1862 1867 5115 1867 1864 5116 1864 1865 5117 1865 1867 5118 1867 1866 5119 1866 1864 5120 1864 1869 5121 1869 1866 5122 1866 1867 5123 1867 1869 5124 1869 1868 5125 1868 1866 5126 1866 1871 5127 1871 1868 5128 1868 1869 5129 1869 1871 5130 1871 1870 5131 1870 1868 5132 1868 1873 5133 1873 1870 5134 1870 1871 5135 1871 1873 5136 1873 1872 5137 1872 1870 5138 1870 1875 5139 1875 1872 5140 1872 1873 5141 1873 1875 5142 1875 1874 5143 1874 1872 5144 1872 1877 5145 1877 1874 5146 1874 1875 5147 1875 1877 5148 1877 1876 5149 1876 1874 5150 1874 1879 5151 1879 1876 5152 1876 1877 5153 1877 1879 5154 1879 1878 5155 1878 1876 5156 1876 1881 5157 1881 1878 5158 1878 1879 5159 1879 1881 5160 1881 1880 5161 1880 1878 5162 1878 1883 5163 1883 1880 5164 1880 1881 5165 1881 1883 5166 1883 1882 5167 1882 1880 5168 1880 1851 5169 1851 1882 5170 1882 1883 5171 1883 1947 5172 1947 1884 5173 1884 1886 5174 1886 1886 5175 1886 1885 5176 1885 1947 5177 1947 1888 5178 1888 1885 5179 1885 1886 5180 1886 1888 5181 1888 1887 5182 1887 1885 5183 1885 1890 5184 1890 1887 5185 1887 1888 5186 1888 1890 5187 1890 1889 5188 1889 1887 5189 1887 1892 5190 1892 1889 5191 1889 1890 5192 1890 1892 5193 1892 1891 5194 1891 1889 5195 1889 1894 5196 1894 1891 5197 1891 1892 5198 1892 1894 5199 1894 1893 5200 1893 1891 5201 1891 1896 5202 1896 1893 5203 1893 1894 5204 1894 1896 5205 1896 1895 5206 1895 1893 5207 1893 1898 5208 1898 1895 5209 1895 1896 5210 1896 1898 5211 1898 1897 5212 1897 1895 5213 1895 1900 5214 1900 1897 5215 1897 1898 5216 1898 1900 5217 1900 1899 5218 1899 1897 5219 1897 1902 5220 1902 1899 5221 1899 1900 5222 1900 1902 5223 1902 1901 5224 1901 1899 5225 1899 1904 5226 1904 1901 5227 1901 1902 5228 1902 1904 5229 1904 1903 5230 1903 1901 5231 1901 1906 5232 1906 1903 5233 1903 1904 5234 1904 1906 5235 1906 1905 5236 1905 1903 5237 1903 1908 5238 1908 1905 5239 1905 1906 5240 1906 1908 5241 1908 1907 5242 1907 1905 5243 1905 1910 5244 1910 1907 5245 1907 1908 5246 1908 1910 5247 1910 1909 5248 1909 1907 5249 1907 1912 5250 1912 1909 5251 1909 1910 5252 1910 1912 5253 1912 1911 5254 1911 1909 5255 1909 1914 5256 1914 1911 5257 1911 1912 5258 1912 1914 5259 1914 1913 5260 1913 1911 5261 1911 1916 5262 1916 1913 5263 1913 1914 5264 1914 1916 5265 1916 1915 5266 1915 1913 5267 1913 1918 5268 1918 1915 5269 1915 1916 5270 1916 1918 5271 1918 1917 5272 1917 1915 5273 1915 1920 5274 1920 1917 5275 1917 1918 5276 1918 1920 5277 1920 1919 5278 1919 1917 5279 1917 1922 5280 1922 1919 5281 1919 1920 5282 1920 1922 5283 1922 1921 5284 1921 1919 5285 1919 1924 5286 1924 1921 5287 1921 1922 5288 1922 1924 5289 1924 1923 5290 1923 1921 5291 1921 1926 5292 1926 1923 5293 1923 1924 5294 1924 1926 5295 1926 1925 5296 1925 1923 5297 1923 1928 5298 1928 1925 5299 1925 1926 5300 1926 1928 5301 1928 1927 5302 1927 1925 5303 1925 1930 5304 1930 1927 5305 1927 1928 5306 1928 1930 5307 1930 1929 5308 1929 1927 5309 1927 1932 5310 1932 1929 5311 1929 1930 5312 1930 1932 5313 1932 1931 5314 1931 1929 5315 1929 1934 5316 1934 1931 5317 1931 1932 5318 1932 1934 5319 1934 1933 5320 1933 1931 5321 1931 1936 5322 1936 1933 5323 1933 1934 5324 1934 1936 5325 1936 1935 5326 1935 1933 5327 1933 1938 5328 1938 1935 5329 1935 1936 5330 1936 1938 5331 1938 1937 5332 1937 1935 5333 1935 1940 5334 1940 1937 5335 1937 1938 5336 1938 1940 5337 1940 1939 5338 1939 1937 5339 1937 1942 5340 1942 1939 5341 1939 1940 5342 1940 1942 5343 1942 1941 5344 1941 1939 5345 1939 1944 5346 1944 1941 5347 1941 1942 5348 1942 1944 5349 1944 1943 5350 1943 1941 5351 1941 1946 5352 1946 1943 5353 1943 1944 5354 1944 1946 5355 1946 1945 5356 1945 1943 5357 1943 1884 5358 1884 1945 5359 1945 1946 5360 1946 1884 5361 1884 1947 5362 1947 1945 5363 1945 1955 5364 1955 1948 5365 1948 1949 5366 1949 1954 5367 1954 1950 5368 1950 1951 5369 1951 1954 5370 1954 1952 5371 1952 1950 5372 1950 1954 5373 1954 1953 5374 1953 1952 5375 1952 1956 5376 1956 1953 5377 1953 1954 5378 1954 1956 5379 1956 1955 5380 1955 1953 5381 1953 1957 5382 1957 1955 5383 1955 1956 5384 1956 1958 5385 1958 1955 5386 1955 1957 5387 1957 1959 5388 1959 1955 5389 1955 1958 5390 1958 1960 5391 1960 1955 5392 1955 1959 5393 1959 1961 5394 1961 1955 5395 1955 1960 5396 1960 1962 5397 1962 1955 5398 1955 1961 5399 1961 1963 5400 1963 1955 5401 1955 1962 5402 1962 1964 5403 1964 1955 5404 1955 1963 5405 1963 1965 5406 1965 1955 5407 1955 1964 5408 1964 1966 5409 1966 1955 5410 1955 1965 5411 1965 1967 5412 1967 1955 5413 1955 1966 5414 1966 1968 5415 1968 1955 5416 1955 1967 5417 1967 1969 5418 1969 1955 5419 1955 1968 5420 1968 1970 5421 1970 1955 5422 1955 1969 5423 1969 1971 5424 1971 1955 5425 1955 1970 5426 1970 1972 5427 1972 1955 5428 1955 1971 5429 1971 1973 5430 1973 1955 5431 1955 1972 5432 1972 1974 5433 1974 1955 5434 1955 1973 5435 1973 1975 5436 1975 1955 5437 1955 1974 5438 1974 1976 5439 1976 1955 5440 1955 1975 5441 1975 1977 5442 1977 1955 5443 1955 1976 5444 1976 1978 5445 1978 1955 5446 1955 1977 5447 1977 1979 5448 1979 1955 5449 1955 1978 5450 1978 1948 5451 1948 1955 5452 1955 1979 5453 1979 2012 5454 2012 1980 5455 1980 1981 5456 1981 1985 5457 1985 1982 5458 1982 1983 5459 1983 1985 5460 1985 1984 5461 1984 1982 5462 1982 1988 5463 1988 1984 5464 1984 1985 5465 1985 1988 5466 1988 1986 5467 1986 1984 5468 1984 1988 5469 1988 1987 5470 1987 1986 5471 1986 1989 5472 1989 1987 5473 1987 1988 5474 1988 1992 5475 1992 1987 5476 1987 1989 5477 1989 1992 5478 1992 1990 5479 1990 1987 5480 1987 1992 5481 1992 1991 5482 1991 1990 5483 1990 1994 5484 1994 1991 5485 1991 1992 5486 1992 1994 5487 1994 1993 5488 1993 1991 5489 1991 1996 5490 1996 1993 5491 1993 1994 5492 1994 1996 5493 1996 1995 5494 1995 1993 5495 1993 1998 5496 1998 1995 5497 1995 1996 5498 1996 1998 5499 1998 1997 5500 1997 1995 5501 1995 2000 5502 2000 1997 5503 1997 1998 5504 1998 2000 5505 2000 1999 5506 1999 1997 5507 1997 2001 5508 2001 1999 5509 1999 2000 5510 2000 2004 5511 2004 1999 5512 1999 2001 5513 2001 2004 5514 2004 2002 5515 2002 1999 5516 1999 2004 5517 2004 2003 5518 2003 2002 5519 2002 2006 5520 2006 2003 5521 2003 2004 5522 2004 2006 5523 2006 2005 5524 2005 2003 5525 2003 2008 5526 2008 2005 5527 2005 2006 5528 2006 2008 5529 2008 2007 5530 2007 2005 5531 2005 2009 5532 2009 2007 5533 2007 2008 5534 2008 2011 5535 2011 2007 5536 2007 2009 5537 2009 2011 5538 2011 2010 5539 2010 2007 5540 2007 2013 5541 2013 2010 5542 2010 2011 5543 2011 2013 5544 2013 2012 5545 2012 2010 5546 2010 1980 5547 1980 2012 5548 2012 2013 5549 2013 2021 5550 2021 2014 5551 2014 2015 5552 2015 2020 5553 2020 2016 5554 2016 2017 5555 2017 2020 5556 2020 2018 5557 2018 2016 5558 2016 2020 5559 2020 2019 5560 2019 2018 5561 2018 2022 5562 2022 2019 5563 2019 2020 5564 2020 2022 5565 2022 2021 5566 2021 2019 5567 2019 2023 5568 2023 2021 5569 2021 2022 5570 2022 2024 5571 2024 2021 5572 2021 2023 5573 2023 2025 5574 2025 2021 5575 2021 2024 5576 2024 2026 5577 2026 2021 5578 2021 2025 5579 2025 2027 5580 2027 2021 5581 2021 2026 5582 2026 2028 5583 2028 2021 5584 2021 2027 5585 2027 2029 5586 2029 2021 5587 2021 2028 5588 2028 2030 5589 2030 2021 5590 2021 2029 5591 2029 2031 5592 2031 2021 5593 2021 2030 5594 2030 2032 5595 2032 2021 5596 2021 2031 5597 2031 2033 5598 2033 2021 5599 2021 2032 5600 2032 2034 5601 2034 2021 5602 2021 2033 5603 2033 2035 5604 2035 2021 5605 2021 2034 5606 2034 2036 5607 2036 2021 5608 2021 2035 5609 2035 2037 5610 2037 2021 5611 2021 2036 5612 2036 2038 5613 2038 2021 5614 2021 2037 5615 2037 2039 5616 2039 2021 5617 2021 2038 5618 2038 2040 5619 2040 2021 5620 2021 2039 5621 2039 2041 5622 2041 2021 5623 2021 2040 5624 2040 2042 5625 2042 2021 5626 2021 2041 5627 2041 2043 5628 2043 2021 5629 2021 2042 5630 2042 2044 5631 2044 2021 5632 2021 2043 5633 2043 2045 5634 2045 2021 5635 2021 2044 5636 2044 2014 5637 2014 2021 5638 2021 2045 5639 2045 2079 5640 2079 2046 5641 2046 2047 5642 2047 2049 5643 2049 2047 5644 2047 2048 5645 2048 2079 5646 2079 2047 5647 2047 2049 5648 2049 2054 5649 2054 2050 5650 2050 2051 5651 2051 2054 5652 2054 2052 5653 2052 2050 5654 2050 2054 5655 2054 2053 5656 2053 2052 5657 2052 2055 5658 2055 2053 5659 2053 2054 5660 2054 2058 5661 2058 2053 5662 2053 2055 5663 2055 2058 5664 2058 2056 5665 2056 2053 5666 2053 2058 5667 2058 2057 5668 2057 2056 5669 2056 2059 5670 2059 2057 5671 2057 2058 5672 2058 2061 5673 2061 2057 5674 2057 2059 5675 2059 2061 5676 2061 2060 5677 2060 2057 5678 2057 2063 5679 2063 2060 5680 2060 2061 5681 2061 2063 5682 2063 2062 5683 2062 2060 5684 2060 2065 5685 2065 2062 5686 2062 2063 5687 2063 2065 5688 2065 2064 5689 2064 2062 5690 2062 2067 5691 2067 2064 5692 2064 2065 5693 2065 2067 5694 2067 2066 5695 2066 2064 5696 2064 2069 5697 2069 2066 5698 2066 2067 5699 2067 2069 5700 2069 2068 5701 2068 2066 5702 2066 2071 5703 2071 2068 5704 2068 2069 5705 2069 2071 5706 2071 2070 5707 2070 2068 5708 2068 2073 5709 2073 2070 5710 2070 2071 5711 2071 2073 5712 2073 2072 5713 2072 2070 5714 2070 2075 5715 2075 2072 5716 2072 2073 5717 2073 2075 5718 2075 2074 5719 2074 2072 5720 2072 2077 5721 2077 2074 5722 2074 2075 5723 2075 2077 5724 2077 2076 5725 2076 2074 5726 2074 2046 5727 2046 2076 5728 2076 2077 5729 2077 2046 5730 2046 2078 5731 2078 2076 5732 2076 2046 5733 2046 2079 5734 2079 2078 5735 2078 2087 5736 2087 2080 5737 2080 2081 5738 2081 2086 5739 2086 2082 5740 2082 2083 5741 2083 2086 5742 2086 2084 5743 2084 2082 5744 2082 2086 5745 2086 2085 5746 2085 2084 5747 2084 2088 5748 2088 2085 5749 2085 2086 5750 2086 2088 5751 2088 2087 5752 2087 2085 5753 2085 2089 5754 2089 2087 5755 2087 2088 5756 2088 2090 5757 2090 2087 5758 2087 2089 5759 2089 2091 5760 2091 2087 5761 2087 2090 5762 2090 2092 5763 2092 2087 5764 2087 2091 5765 2091 2093 5766 2093 2087 5767 2087 2092 5768 2092 2094 5769 2094 2087 5770 2087 2093 5771 2093 2095 5772 2095 2087 5773 2087 2094 5774 2094 2096 5775 2096 2087 5776 2087 2095 5777 2095 2097 5778 2097 2087 5779 2087 2096 5780 2096 2098 5781 2098 2087 5782 2087 2097 5783 2097 2099 5784 2099 2087 5785 2087 2098 5786 2098 2100 5787 2100 2087 5788 2087 2099 5789 2099 2101 5790 2101 2087 5791 2087 2100 5792 2100 2102 5793 2102 2087 5794 2087 2101 5795 2101 2103 5796 2103 2087 5797 2087 2102 5798 2102 2104 5799 2104 2087 5800 2087 2103 5801 2103 2105 5802 2105 2087 5803 2087 2104 5804 2104 2106 5805 2106 2087 5806 2087 2105 5807 2105 2107 5808 2107 2087 5809 2087 2106 5810 2106 2108 5811 2108 2087 5812 2087 2107 5813 2107 2109 5814 2109 2087 5815 2087 2108 5816 2108 2110 5817 2110 2087 5818 2087 2109 5819 2109 2111 5820 2111 2087 5821 2087 2110 5822 2110 2080 5823 2080 2087 5824 2087 2111 5825 2111 2143 5826 2143 2116 5827 2116 2112 5828 2112 2115 5829 2115 2113 5830 2113 2114 5831 2114 2117 5832 2117 2113 5833 2113 2115 5834 2115 2117 5835 2117 2116 5836 2116 2113 5837 2113 2112 5838 2112 2116 5839 2116 2117 5840 2117 2122 5841 2122 2118 5842 2118 2119 5843 2119 2122 5844 2122 2120 5845 2120 2118 5846 2118 2122 5847 2122 2121 5848 2121 2120 5849 2120 2123 5850 2123 2121 5851 2121 2122 5852 2122 2125 5853 2125 2121 5854 2121 2123 5855 2123 2125 5856 2125 2124 5857 2124 2121 5858 2121 2127 5859 2127 2124 5860 2124 2125 5861 2125 2127 5862 2127 2126 5863 2126 2124 5864 2124 2129 5865 2129 2126 5866 2126 2127 5867 2127 2129 5868 2129 2128 5869 2128 2126 5870 2126 2131 5871 2131 2128 5872 2128 2129 5873 2129 2131 5874 2131 2130 5875 2130 2128 5876 2128 2134 5877 2134 2130 5878 2130 2131 5879 2131 2134 5880 2134 2132 5881 2132 2130 5882 2130 2134 5883 2134 2133 5884 2133 2132 5885 2132 2135 5886 2135 2133 5887 2133 2134 5888 2134 2137 5889 2137 2133 5890 2133 2135 5891 2135 2137 5892 2137 2136 5893 2136 2133 5894 2133 2139 5895 2139 2136 5896 2136 2137 5897 2137 2139 5898 2139 2138 5899 2138 2136 5900 2136 2141 5901 2141 2138 5902 2138 2139 5903 2139 2141 5904 2141 2140 5905 2140 2138 5906 2138 2144 5907 2144 2140 5908 2140 2141 5909 2141 2144 5910 2144 2142 5911 2142 2140 5912 2140 2144 5913 2144 2143 5914 2143 2142 5915 2142 2145 5916 2145 2143 5917 2143 2144 5918 2144 2116 5919 2116 2143 5920 2143 2145 5921 2145 2153 5922 2153 2146 5923 2146 2147 5924 2147 2152 5925 2152 2148 5926 2148 2149 5927 2149 2152 5928 2152 2150 5929 2150 2148 5930 2148 2152 5931 2152 2151 5932 2151 2150 5933 2150 2154 5934 2154 2151 5935 2151 2152 5936 2152 2154 5937 2154 2153 5938 2153 2151 5939 2151 2155 5940 2155 2153 5941 2153 2154 5942 2154 2156 5943 2156 2153 5944 2153 2155 5945 2155 2157 5946 2157 2153 5947 2153 2156 5948 2156 2158 5949 2158 2153 5950 2153 2157 5951 2157 2159 5952 2159 2153 5953 2153 2158 5954 2158 2160 5955 2160 2153 5956 2153 2159 5957 2159 2161 5958 2161 2153 5959 2153 2160 5960 2160 2162 5961 2162 2153 5962 2153 2161 5963 2161 2163 5964 2163 2153 5965 2153 2162 5966 2162 2164 5967 2164 2153 5968 2153 2163 5969 2163 2165 5970 2165 2153 5971 2153 2164 5972 2164 2166 5973 2166 2153 5974 2153 2165 5975 2165 2167 5976 2167 2153 5977 2153 2166 5978 2166 2168 5979 2168 2153 5980 2153 2167 5981 2167 2169 5982 2169 2153 5983 2153 2168 5984 2168 2170 5985 2170 2153 5986 2153 2169 5987 2169 2171 5988 2171 2153 5989 2153 2170 5990 2170 2172 5991 2172 2153 5992 2153 2171 5993 2171 2173 5994 2173 2153 5995 2153 2172 5996 2172 2174 5997 2174 2153 5998 2153 2173 5999 2173 2175 6000 2175 2153 6001 2153 2174 6002 2174 2176 6003 2176 2153 6004 2153 2175 6005 2175 2177 6006 2177 2153 6007 2153 2176 6008 2176 2146 6009 2146 2153 6010 2153 2177 6011 2177 2211 6012 2211 2178 6013 2178 2179 6014 2179 2182 6015 2182 2180 6016 2180 2181 6017 2181 2184 6018 2184 2180 6019 2180 2182 6020 2182 2184 6021 2184 2183 6022 2183 2180 6023 2180 2185 6024 2185 2183 6025 2183 2184 6026 2184 2187 6027 2187 2183 6028 2183 2185 6029 2185 2187 6030 2187 2186 6031 2186 2183 6032 2183 2190 6033 2190 2186 6034 2186 2187 6035 2187 2190 6036 2190 2188 6037 2188 2186 6038 2186 2190 6039 2190 2189 6040 2189 2188 6041 2188 2191 6042 2191 2189 6043 2189 2190 6044 2190 2193 6045 2193 2189 6046 2189 2191 6047 2191 2193 6048 2193 2192 6049 2192 2189 6050 2189 2196 6051 2196 2192 6052 2192 2193 6053 2193 2196 6054 2196 2194 6055 2194 2192 6056 2192 2196 6057 2196 2195 6058 2195 2194 6059 2194 2197 6060 2197 2195 6061 2195 2196 6062 2196 2199 6063 2199 2195 6064 2195 2197 6065 2197 2199 6066 2199 2198 6067 2198 2195 6068 2195 2201 6069 2201 2198 6070 2198 2199 6071 2199 2201 6072 2201 2200 6073 2200 2198 6074 2198 2203 6075 2203 2200 6076 2200 2201 6077 2201 2203 6078 2203 2202 6079 2202 2200 6080 2200 2205 6081 2205 2202 6082 2202 2203 6083 2203 2205 6084 2205 2204 6085 2204 2202 6086 2202 2207 6087 2207 2204 6088 2204 2205 6089 2205 2207 6090 2207 2206 6091 2206 2204 6092 2204 2209 6093 2209 2206 6094 2206 2207 6095 2207 2209 6096 2209 2208 6097 2208 2206 6098 2206 2178 6099 2178 2208 6100 2208 2209 6101 2209 2178 6102 2178 2210 6103 2210 2208 6104 2208 2178 6105 2178 2211 6106 2211 2210 6107 2210 2214 6108 2214 2212 6109 2212 2213 6110 2213 2212 6111 2212 2214 6112 2214 2215 6113 2215 2218 6114 2218 2216 6115 2216 2217 6116 2217 2216 6117 2216 2218 6118 2218 2219 6119 2219 2222 6120 2222 2220 6121 2220 2221 6122 2221 2220 6123 2220 2222 6124 2222 2223 6125 2223 2347 6126 2347 2346 6127 2346 2265 6128 2265 2225 6129 2225 2224 6130 2224 2348 6131 2348 2341 6132 2341 2224 6133 2224 2225 6134 2225 2289 6135 2289 2279 6136 2279 2226 6137 2226 2326 6138 2326 2227 6139 2227 2228 6140 2228 2326 6141 2326 2229 6142 2229 2227 6143 2227 2326 6144 2326 2230 6145 2230 2229 6146 2229 2326 6147 2326 2231 6148 2231 2230 6149 2230 2326 6150 2326 2232 6151 2232 2231 6152 2231 2326 6153 2326 2233 6154 2233 2232 6155 2232 2326 6156 2326 2234 6157 2234 2233 6158 2233 2326 6159 2326 2235 6160 2235 2234 6161 2234 2326 6162 2326 2236 6163 2236 2235 6164 2235 2326 6165 2326 2237 6166 2237 2236 6167 2236 2225 6168 2225 2238 6169 2238 2239 6170 2239 2225 6171 2225 2240 6172 2240 2238 6173 2238 2225 6174 2225 2241 6175 2241 2240 6176 2240 2225 6177 2225 2242 6178 2242 2241 6179 2241 2225 6180 2225 2243 6181 2243 2242 6182 2242 2225 6183 2225 2244 6184 2244 2243 6185 2243 2225 6186 2225 2245 6187 2245 2244 6188 2244 2225 6189 2225 2246 6190 2246 2245 6191 2245 2225 6192 2225 2247 6193 2247 2246 6194 2246 2250 6195 2250 2248 6196 2248 2249 6197 2249 2251 6198 2251 2248 6199 2248 2250 6200 2250 2252 6201 2252 2248 6202 2248 2251 6203 2251 2253 6204 2253 2248 6205 2248 2252 6206 2252 2254 6207 2254 2248 6208 2248 2253 6209 2253 2255 6210 2255 2248 6211 2248 2254 6212 2254 2256 6213 2256 2248 6214 2248 2255 6215 2255 2257 6216 2257 2248 6217 2248 2256 6218 2256 2258 6219 2258 2248 6220 2248 2257 6221 2257 2276 6222 2276 2248 6223 2248 2258 6224 2258 2277 6225 2277 2349 6226 2349 2259 6227 2259 2277 6228 2277 2260 6229 2260 2349 6230 2349 2343 6231 2343 2351 6232 2351 2261 6233 2261 2343 6234 2343 2262 6235 2262 2351 6236 2351 2350 6237 2350 2342 6238 2342 2263 6239 2263 2350 6240 2350 2264 6241 2264 2342 6242 2342 2267 6243 2267 2265 6244 2265 2266 6245 2266 2268 6246 2268 2265 6247 2265 2267 6248 2267 2269 6249 2269 2265 6250 2265 2268 6251 2268 2270 6252 2270 2265 6253 2265 2269 6254 2269 2271 6255 2271 2265 6256 2265 2270 6257 2270 2272 6258 2272 2265 6259 2265 2271 6260 2271 2273 6261 2273 2265 6262 2265 2272 6263 2272 2274 6264 2274 2265 6265 2265 2273 6266 2273 2347 6267 2347 2265 6268 2265 2274 6269 2274 2326 6270 2326 2275 6271 2275 2237 6272 2237 2290 6273 2290 2248 6274 2248 2276 6275 2276 2341 6276 2341 2277 6277 2277 2224 6278 2224 2279 6279 2279 2278 6280 2278 2226 6281 2226 2298 6282 2298 2278 6283 2278 2279 6284 2279 2298 6285 2298 2280 6286 2280 2278 6287 2278 2298 6288 2298 2281 6289 2281 2280 6290 2280 2298 6291 2298 2282 6292 2282 2281 6293 2281 2298 6294 2298 2283 6295 2283 2282 6296 2282 2298 6297 2298 2284 6298 2284 2283 6299 2283 2298 6300 2298 2285 6301 2285 2284 6302 2284 2298 6303 2298 2286 6304 2286 2285 6305 2285 2298 6306 2298 2287 6307 2287 2286 6308 2286 2298 6309 2298 2288 6310 2288 2287 6311 2287 2294 6312 2294 2279 6313 2279 2289 6314 2289 2293 6315 2293 2248 6316 2248 2290 6317 2290 2326 6318 2326 2291 6319 2291 2275 6320 2275 2326 6321 2326 2292 6322 2292 2291 6323 2291 2296 6324 2296 2248 6325 2248 2293 6326 2293 2327 6327 2327 2279 6328 2279 2294 6329 2294 2298 6330 2298 2295 6331 2295 2288 6332 2288 2313 6333 2313 2248 6334 2248 2296 6335 2296 2326 6336 2326 2297 6337 2297 2292 6338 2292 2299 6339 2299 2295 6340 2295 2298 6341 2298 2300 6342 2300 2295 6343 2295 2299 6344 2299 2301 6345 2301 2295 6346 2295 2300 6347 2300 2302 6348 2302 2295 6349 2295 2301 6350 2301 2303 6351 2303 2295 6352 2295 2302 6353 2302 2304 6354 2304 2295 6355 2295 2303 6356 2303 2305 6357 2305 2295 6358 2295 2304 6359 2304 2248 6360 2248 2295 6361 2295 2305 6362 2305 2313 6363 2313 2295 6364 2295 2248 6365 2248 2313 6366 2313 2306 6367 2306 2295 6368 2295 2313 6369 2313 2307 6370 2307 2306 6371 2306 2313 6372 2313 2308 6373 2308 2307 6374 2307 2313 6375 2313 2309 6376 2309 2308 6377 2308 2313 6378 2313 2310 6379 2310 2309 6380 2309 2313 6381 2313 2311 6382 2311 2310 6383 2310 2313 6384 2313 2312 6385 2312 2311 6386 2311 2315 6387 2315 2312 6388 2312 2313 6389 2313 2315 6390 2315 2314 6391 2314 2312 6392 2312 2317 6393 2317 2314 6394 2314 2315 6395 2315 2317 6396 2317 2316 6397 2316 2314 6398 2314 2338 6399 2338 2316 6400 2316 2317 6401 2317 2338 6402 2338 2318 6403 2318 2316 6404 2316 2327 6405 2327 2319 6406 2319 2279 6407 2279 2327 6408 2327 2320 6409 2320 2319 6410 2319 2327 6411 2327 2321 6412 2321 2320 6413 2320 2327 6414 2327 2322 6415 2322 2321 6416 2321 2327 6417 2327 2323 6418 2323 2322 6419 2322 2327 6420 2327 2324 6421 2324 2323 6422 2323 2327 6423 2327 2325 6424 2325 2324 6425 2324 2327 6426 2327 2326 6427 2326 2325 6428 2325 2327 6429 2327 2297 6430 2297 2326 6431 2326 2328 6432 2328 2297 6433 2297 2327 6434 2327 2329 6435 2329 2297 6436 2297 2328 6437 2328 2330 6438 2330 2297 6439 2297 2329 6440 2329 2331 6441 2331 2297 6442 2297 2330 6443 2330 2332 6444 2332 2297 6445 2297 2331 6446 2331 2333 6447 2333 2297 6448 2297 2332 6449 2332 2334 6450 2334 2297 6451 2297 2333 6452 2333 2318 6453 2318 2297 6454 2297 2334 6455 2334 2338 6456 2338 2297 6457 2297 2318 6458 2318 2338 6459 2338 2335 6460 2335 2297 6461 2297 2338 6462 2338 2336 6463 2336 2335 6464 2335 2338 6465 2338 2337 6466 2337 2336 6467 2336 2340 6468 2340 2337 6469 2337 2338 6470 2338 2340 6471 2340 2339 6472 2339 2337 6473 2337 2345 6474 2345 2339 6475 2339 2340 6476 2340 2345 6477 2345 2341 6478 2341 2339 6479 2339 2345 6480 2345 2277 6481 2277 2341 6482 2341 2345 6483 2345 2260 6484 2260 2277 6485 2277 2345 6486 2345 2342 6487 2342 2260 6488 2260 2345 6489 2345 2263 6490 2263 2342 6491 2342 2345 6492 2345 2343 6493 2343 2263 6494 2263 2345 6495 2345 2262 6496 2262 2343 6497 2343 2345 6498 2345 2344 6499 2344 2262 6500 2262 2265 6501 2265 2344 6502 2344 2345 6503 2345 2265 6504 2265 2346 6505 2346 2344 6506 2344 2348 6507 2348 2247 6508 2247 2225 6509 2225 2348 6510 2348 2347 6511 2347 2247 6512 2247 2259 6513 2259 2347 6514 2347 2348 6515 2348 2349 6516 2349 2347 6517 2347 2259 6518 2259 2264 6519 2264 2347 6520 2347 2349 6521 2349 2350 6522 2350 2347 6523 2347 2264 6524 2264 2261 6525 2261 2347 6526 2347 2350 6527 2350 2351 6528 2351 2347 6529 2347 2261 6530 2261 2346 6531 2346 2347 6532 2347 2351 6533 2351 2354 6534 2354 2352 6535 2352 2353 6536 2353 2352 6537 2352 2354 6538 2354 2355 6539 2355 2358 6540 2358 2356 6541 2356 2357 6542 2357 2356 6543 2356 2358 6544 2358 2359 6545 2359 2362 6546 2362 2360 6547 2360 2361 6548 2361 2360 6549 2360 2362 6550 2362 2363 6551 2363 2369 6552 2369 2364 6553 2364 2365 6554 2365 2368 6555 2368 2366 6556 2366 2367 6557 2367 2364 6558 2364 2366 6559 2366 2368 6560 2368 2364 6561 2364 2369 6562 2369 2366 6563 2366 2374 6564 2374 2370 6565 2370 2371 6566 2371 2370 6567 2370 2372 6568 2372 2373 6569 2373 2372 6570 2372 2374 6571 2374 2375 6572 2375 2370 6573 2370 2374 6574 2374 2372 6575 2372 2378 6576 2378 2376 6577 2376 2377 6578 2377 2380 6579 2380 2378 6580 2378 2379 6581 2379 2376 6582 2376 2380 6583 2380 2381 6584 2381 2376 6585 2376 2378 6586 2378 2380 6587 2380 2387 6588 2387 2382 6589 2382 2383 6590 2383 2386 6591 2386 2384 6592 2384 2385 6593 2385 2382 6594 2382 2384 6595 2384 2386 6596 2386 2382 6597 2382 2387 6598 2387 2384 6599 2384 2390 6600 2390 2388 6601 2388 2389 6602 2389 2392 6603 2392 2390 6604 2390 2391 6605 2391 2388 6606 2388 2392 6607 2392 2393 6608 2393 2388 6609 2388 2390 6610 2390 2392 6611 2392 2399 6612 2399 2394 6613 2394 2395 6614 2395 2398 6615 2398 2396 6616 2396 2397 6617 2397 2394 6618 2394 2396 6619 2396 2398 6620 2398 2394 6621 2394 2399 6622 2399 2396 6623 2396 2404 6624 2404 2400 6625 2400 2401 6626 2401 2400 6627 2400 2402 6628 2402 2403 6629 2403 2402 6630 2402 2404 6631 2404 2405 6632 2405 2400 6633 2400 2404 6634 2404 2402 6635 2402 2411 6636 2411 2406 6637 2406 2407 6638 2407 2410 6639 2410 2408 6640 2408 2409 6641 2409 2406 6642 2406 2408 6643 2408 2410 6644 2410 2406 6645 2406 2411 6646 2411 2408 6647 2408 2429 6648 2429 2412 6649 2412 2413 6650 2413 2416 6651 2416 2414 6652 2414 2415 6653 2415 2417 6654 2417 2414 6655 2414 2416 6656 2416 2419 6657 2419 2414 6658 2414 2417 6659 2417 2419 6660 2419 2418 6661 2418 2414 6662 2414 2421 6663 2421 2418 6664 2418 2419 6665 2419 2421 6666 2421 2420 6667 2420 2418 6668 2418 2424 6669 2424 2420 6670 2420 2421 6671 2421 2424 6672 2424 2422 6673 2422 2420 6674 2420 2424 6675 2424 2423 6676 2423 2422 6677 2422 2426 6678 2426 2423 6679 2423 2424 6680 2424 2426 6681 2426 2425 6682 2425 2423 6683 2423 2428 6684 2428 2425 6685 2425 2426 6686 2426 2428 6687 2428 2427 6688 2427 2425 6689 2425 2412 6690 2412 2427 6691 2427 2428 6692 2428 2412 6693 2412 2429 6694 2429 2427 6695 2427 2451 6696 2451 2430 6697 2430 2445 6698 2445 2433 6699 2433 2431 6700 2431 2432 6701 2432 2430 6702 2430 2431 6703 2431 2433 6704 2433 2436 6705 2436 2434 6706 2434 2435 6707 2435 2437 6708 2437 2434 6709 2434 2436 6710 2436 2440 6711 2440 2434 6712 2434 2437 6713 2437 2440 6714 2440 2438 6715 2438 2434 6716 2434 2440 6717 2440 2439 6718 2439 2438 6719 2438 2441 6720 2441 2439 6721 2439 2440 6722 2440 2446 6723 2446 2439 6724 2439 2441 6725 2441 2446 6726 2446 2442 6727 2442 2439 6728 2439 2451 6729 2451 2443 6730 2443 2444 6731 2444 2451 6732 2451 2445 6733 2445 2443 6734 2443 2448 6735 2448 2442 6736 2442 2446 6737 2446 2448 6738 2448 2447 6739 2447 2442 6740 2442 2450 6741 2450 2447 6742 2447 2448 6743 2448 2450 6744 2450 2449 6745 2449 2447 6746 2447 2431 6747 2431 2449 6748 2449 2450 6749 2450 2431 6750 2431 2451 6751 2451 2449 6752 2449 2430 6753 2430 2451 6754 2451 2431 6755 2431 2468 6756 2468 2452 6757 2452 2453 6758 2453 2458 6759 2458 2454 6760 2454 2455 6761 2455 2458 6762 2458 2456 6763 2456 2454 6764 2454 2458 6765 2458 2457 6766 2457 2456 6767 2456 2460 6768 2460 2457 6769 2457 2458 6770 2458 2460 6771 2460 2459 6772 2459 2457 6773 2457 2462 6774 2462 2459 6775 2459 2460 6776 2460 2462 6777 2462 2461 6778 2461 2459 6779 2459 2463 6780 2463 2461 6781 2461 2462 6782 2462 2465 6783 2465 2461 6784 2461 2463 6785 2463 2465 6786 2465 2464 6787 2464 2461 6788 2461 2467 6789 2467 2464 6790 2464 2465 6791 2465 2467 6792 2467 2466 6793 2466 2464 6794 2464 2469 6795 2469 2466 6796 2466 2467 6797 2467 2469 6798 2469 2468 6799 2468 2466 6800 2466 2452 6801 2452 2468 6802 2468 2469 6803 2469 2487 6804 2487 2470 6805 2470 2471 6806 2471 2474 6807 2474 2472 6808 2472 2473 6809 2473 2475 6810 2475 2472 6811 2472 2474 6812 2474 2477 6813 2477 2472 6814 2472 2475 6815 2475 2477 6816 2477 2476 6817 2476 2472 6818 2472 2479 6819 2479 2476 6820 2476 2477 6821 2477 2479 6822 2479 2478 6823 2478 2476 6824 2476 2482 6825 2482 2478 6826 2478 2479 6827 2479 2482 6828 2482 2480 6829 2480 2478 6830 2478 2482 6831 2482 2481 6832 2481 2480 6833 2480 2484 6834 2484 2481 6835 2481 2482 6836 2482 2484 6837 2484 2483 6838 2483 2481 6839 2481 2486 6840 2486 2483 6841 2483 2484 6842 2484 2486 6843 2486 2485 6844 2485 2483 6845 2483 2470 6846 2470 2485 6847 2485 2486 6848 2486 2470 6849 2470 2487 6850 2487 2485 6851 2485 2505 6852 2505 2488 6853 2488 2489 6854 2489 2493 6855 2493 2490 6856 2490 2491 6857 2491 2493 6858 2493 2492 6859 2492 2490 6860 2490 2495 6861 2495 2492 6862 2492 2493 6863 2493 2495 6864 2495 2494 6865 2494 2492 6866 2492 2497 6867 2497 2494 6868 2494 2495 6869 2495 2497 6870 2497 2496 6871 2496 2494 6872 2494 2499 6873 2499 2496 6874 2496 2497 6875 2497 2499 6876 2499 2498 6877 2498 2496 6878 2496 2502 6879 2502 2498 6880 2498 2499 6881 2499 2502 6882 2502 2500 6883 2500 2498 6884 2498 2502 6885 2502 2501 6886 2501 2500 6887 2500 2504 6888 2504 2501 6889 2501 2502 6890 2502 2504 6891 2504 2503 6892 2503 2501 6893 2501 2488 6894 2488 2503 6895 2503 2504 6896 2504 2488 6897 2488 2505 6898 2505 2503 6899 2503 2522 6900 2522 2506 6901 2506 2507 6902 2507 2512 6903 2512 2508 6904 2508 2509 6905 2509 2512 6906 2512 2510 6907 2510 2508 6908 2508 2512 6909 2512 2511 6910 2511 2510 6911 2510 2514 6912 2514 2511 6913 2511 2512 6914 2512 2514 6915 2514 2513 6916 2513 2511 6917 2511 2516 6918 2516 2513 6919 2513 2514 6920 2514 2516 6921 2516 2515 6922 2515 2513 6923 2513 2517 6924 2517 2515 6925 2515 2516 6926 2516 2519 6927 2519 2515 6928 2515 2517 6929 2517 2519 6930 2519 2518 6931 2518 2515 6932 2515 2521 6933 2521 2518 6934 2518 2519 6935 2519 2521 6936 2521 2520 6937 2520 2518 6938 2518 2523 6939 2523 2520 6940 2520 2521 6941 2521 2523 6942 2523 2522 6943 2522 2520 6944 2520 2506 6945 2506 2522 6946 2522 2523 6947 2523 2540 6948 2540 2524 6949 2524 2525 6950 2525 2530 6951 2530 2526 6952 2526 2527 6953 2527 2530 6954 2530 2528 6955 2528 2526 6956 2526 2530 6957 2530 2529 6958 2529 2528 6959 2528 2532 6960 2532 2529 6961 2529 2530 6962 2530 2532 6963 2532 2531 6964 2531 2529 6965 2529 2534 6966 2534 2531 6967 2531 2532 6968 2532 2534 6969 2534 2533 6970 2533 2531 6971 2531 2536 6972 2536 2533 6973 2533 2534 6974 2534 2536 6975 2536 2535 6976 2535 2533 6977 2533 2537 6978 2537 2535 6979 2535 2536 6980 2536 2539 6981 2539 2535 6982 2535 2537 6983 2537 2539 6984 2539 2538 6985 2538 2535 6986 2535 2541 6987 2541 2538 6988 2538 2539 6989 2539 2541 6990 2541 2540 6991 2540 2538 6992 2538 2524 6993 2524 2540 6994 2540 2541 6995 2541 2562 6996 2562 2542 6997 2542 2543 6998 2543 2546 6999 2546 2544 7000 2544 2545 7001 2545 2548 7002 2548 2544 7003 2544 2546 7004 2546 2548 7005 2548 2547 7006 2547 2544 7007 2544 2550 7008 2550 2547 7009 2547 2548 7010 2548 2550 7011 2550 2549 7012 2549 2547 7013 2547 2552 7014 2552 2549 7015 2549 2550 7016 2550 2552 7017 2552 2551 7018 2551 2549 7019 2549 2554 7020 2554 2551 7021 2551 2552 7022 2552 2554 7023 2554 2553 7024 2553 2551 7025 2551 2555 7026 2555 2553 7027 2553 2554 7028 2554 2557 7029 2557 2553 7030 2553 2555 7031 2555 2557 7032 2557 2556 7033 2556 2553 7034 2553 2559 7035 2559 2556 7036 2556 2557 7037 2557 2559 7038 2559 2558 7039 2558 2556 7040 2556 2561 7041 2561 2558 7042 2558 2559 7043 2559 2561 7044 2561 2560 7045 2560 2558 7046 2558 2563 7047 2563 2560 7048 2560 2561 7049 2561 2563 7050 2563 2562 7051 2562 2560 7052 2560 2542 7053 2542 2562 7054 2562 2563 7055 2563 2584 7056 2584 2564 7057 2564 2565 7058 2565 2568 7059 2568 2566 7060 2566 2567 7061 2567 2570 7062 2570 2566 7063 2566 2568 7064 2568 2570 7065 2570 2569 7066 2569 2566 7067 2566 2572 7068 2572 2569 7069 2569 2570 7070 2570 2572 7071 2572 2571 7072 2571 2569 7073 2569 2574 7074 2574 2571 7075 2571 2572 7076 2572 2574 7077 2574 2573 7078 2573 2571 7079 2571 2576 7080 2576 2573 7081 2573 2574 7082 2574 2576 7083 2576 2575 7084 2575 2573 7085 2573 2577 7086 2577 2575 7087 2575 2576 7088 2576 2579 7089 2579 2575 7090 2575 2577 7091 2577 2579 7092 2579 2578 7093 2578 2575 7094 2575 2581 7095 2581 2578 7096 2578 2579 7097 2579 2581 7098 2581 2580 7099 2580 2578 7100 2578 2583 7101 2583 2580 7102 2580 2581 7103 2581 2583 7104 2583 2582 7105 2582 2580 7106 2580 2585 7107 2585 2582 7108 2582 2583 7109 2583 2585 7110 2585 2584 7111 2584 2582 7112 2582 2564 7113 2564 2584 7114 2584 2585 7115 2585 2606 7116 2606 2586 7117 2586 2587 7118 2587 2590 7119 2590 2588 7120 2588 2589 7121 2589 2592 7122 2592 2588 7123 2588 2590 7124 2590 2592 7125 2592 2591 7126 2591 2588 7127 2588 2594 7128 2594 2591 7129 2591 2592 7130 2592 2594 7131 2594 2593 7132 2593 2591 7133 2591 2596 7134 2596 2593 7135 2593 2594 7136 2594 2596 7137 2596 2595 7138 2595 2593 7139 2593 2598 7140 2598 2595 7141 2595 2596 7142 2596 2598 7143 2598 2597 7144 2597 2595 7145 2595 2599 7146 2599 2597 7147 2597 2598 7148 2598 2601 7149 2601 2597 7150 2597 2599 7151 2599 2601 7152 2601 2600 7153 2600 2597 7154 2597 2603 7155 2603 2600 7156 2600 2601 7157 2601 2603 7158 2603 2602 7159 2602 2600 7160 2600 2605 7161 2605 2602 7162 2602 2603 7163 2603 2605 7164 2605 2604 7165 2604 2602 7166 2602 2607 7167 2607 2604 7168 2604 2605 7169 2605 2607 7170 2607 2606 7171 2606 2604 7172 2604 2586 7173 2586 2606 7174 2606 2607 7175 2607 2625 7176 2625 2608 7177 2608 2609 7178 2609 2613 7179 2613 2610 7180 2610 2611 7181 2611 2613 7182 2613 2612 7183 2612 2610 7184 2610 2615 7185 2615 2612 7186 2612 2613 7187 2613 2615 7188 2615 2614 7189 2614 2612 7190 2612 2617 7191 2617 2614 7192 2614 2615 7193 2615 2617 7194 2617 2616 7195 2616 2614 7196 2614 2620 7197 2620 2616 7198 2616 2617 7199 2617 2620 7200 2620 2618 7201 2618 2616 7202 2616 2620 7203 2620 2619 7204 2619 2618 7205 2618 2622 7206 2622 2619 7207 2619 2620 7208 2620 2622 7209 2622 2621 7210 2621 2619 7211 2619 2624 7212 2624 2621 7213 2621 2622 7214 2622 2624 7215 2624 2623 7216 2623 2621 7217 2621 2608 7218 2608 2623 7219 2623 2624 7220 2624 2608 7221 2608 2625 7222 2625 2623 7223 2623 2646 7224 2646 2626 7225 2626 2627 7226 2627 2630 7227 2630 2628 7228 2628 2629 7229 2629 2632 7230 2632 2628 7231 2628 2630 7232 2630 2632 7233 2632 2631 7234 2631 2628 7235 2628 2634 7236 2634 2631 7237 2631 2632 7238 2632 2634 7239 2634 2633 7240 2633 2631 7241 2631 2636 7242 2636 2633 7243 2633 2634 7244 2634 2636 7245 2636 2635 7246 2635 2633 7247 2633 2638 7248 2638 2635 7249 2635 2636 7250 2636 2638 7251 2638 2637 7252 2637 2635 7253 2635 2639 7254 2639 2637 7255 2637 2638 7256 2638 2641 7257 2641 2637 7258 2637 2639 7259 2639 2641 7260 2641 2640 7261 2640 2637 7262 2637 2643 7263 2643 2640 7264 2640 2641 7265 2641 2643 7266 2643 2642 7267 2642 2640 7268 2640 2645 7269 2645 2642 7270 2642 2643 7271 2643 2645 7272 2645 2644 7273 2644 2642 7274 2642 2647 7275 2647 2644 7276 2644 2645 7277 2645 2647 7278 2647 2646 7279 2646 2644 7280 2644 2626 7281 2626 2646 7282 2646 2647 7283 2647 2668 7284 2668 2648 7285 2648 2649 7286 2649 2652 7287 2652 2650 7288 2650 2651 7289 2651 2654 7290 2654 2650 7291 2650 2652 7292 2652 2654 7293 2654 2653 7294 2653 2650 7295 2650 2656 7296 2656 2653 7297 2653 2654 7298 2654 2656 7299 2656 2655 7300 2655 2653 7301 2653 2658 7302 2658 2655 7303 2655 2656 7304 2656 2658 7305 2658 2657 7306 2657 2655 7307 2655 2660 7308 2660 2657 7309 2657 2658 7310 2658 2660 7311 2660 2659 7312 2659 2657 7313 2657 2661 7314 2661 2659 7315 2659 2660 7316 2660 2663 7317 2663 2659 7318 2659 2661 7319 2661 2663 7320 2663 2662 7321 2662 2659 7322 2659 2665 7323 2665 2662 7324 2662 2663 7325 2663 2665 7326 2665 2664 7327 2664 2662 7328 2662 2667 7329 2667 2664 7330 2664 2665 7331 2665 2667 7332 2667 2666 7333 2666 2664 7334 2664 2669 7335 2669 2666 7336 2666 2667 7337 2667 2669 7338 2669 2668 7339 2668 2666 7340 2666 2648 7341 2648 2668 7342 2668 2669 7343 2669 2690 7344 2690 2670 7345 2670 2671 7346 2671 2674 7347 2674 2672 7348 2672 2673 7349 2673 2675 7350 2675 2672 7351 2672 2674 7352 2674 2677 7353 2677 2672 7354 2672 2675 7355 2675 2677 7356 2677 2676 7357 2676 2672 7358 2672 2679 7359 2679 2676 7360 2676 2677 7361 2677 2679 7362 2679 2678 7363 2678 2676 7364 2676 2681 7365 2681 2678 7366 2678 2679 7367 2679 2681 7368 2681 2680 7369 2680 2678 7370 2678 2683 7371 2683 2680 7372 2680 2681 7373 2681 2683 7374 2683 2682 7375 2682 2680 7376 2680 2685 7377 2685 2682 7378 2682 2683 7379 2683 2685 7380 2685 2684 7381 2684 2682 7382 2682 2687 7383 2687 2684 7384 2684 2685 7385 2685 2687 7386 2687 2686 7387 2686 2684 7388 2684 2689 7389 2689 2686 7390 2686 2687 7391 2687 2689 7392 2689 2688 7393 2688 2686 7394 2686 2691 7395 2691 2688 7396 2688 2689 7397 2689 2691 7398 2691 2690 7399 2690 2688 7400 2688 2670 7401 2670 2690 7402 2690 2691 7403 2691 2712 7404 2712 2692 7405 2692 2693 7406 2693 2696 7407 2696 2694 7408 2694 2695 7409 2695 2697 7410 2697 2694 7411 2694 2696 7412 2696 2699 7413 2699 2694 7414 2694 2697 7415 2697 2699 7416 2699 2698 7417 2698 2694 7418 2694 2701 7419 2701 2698 7420 2698 2699 7421 2699 2701 7422 2701 2700 7423 2700 2698 7424 2698 2703 7425 2703 2700 7426 2700 2701 7427 2701 2703 7428 2703 2702 7429 2702 2700 7430 2700 2706 7431 2706 2702 7432 2702 2703 7433 2703 2706 7434 2706 2704 7435 2704 2702 7436 2702 2706 7437 2706 2705 7438 2705 2704 7439 2704 2709 7440 2709 2705 7441 2705 2706 7442 2706 2709 7443 2709 2707 7444 2707 2705 7445 2705 2709 7446 2709 2708 7447 2708 2707 7448 2707 2711 7449 2711 2708 7450 2708 2709 7451 2709 2711 7452 2711 2710 7453 2710 2708 7454 2708 2692 7455 2692 2710 7456 2710 2711 7457 2711 2692 7458 2692 2712 7459 2712 2710 7460 2710 2733 7461 2733 2713 7462 2713 2714 7463 2714 2717 7464 2717 2715 7465 2715 2716 7466 2716 2718 7467 2718 2715 7468 2715 2717 7469 2717 2720 7470 2720 2715 7471 2715 2718 7472 2718 2720 7473 2720 2719 7474 2719 2715 7475 2715 2722 7476 2722 2719 7477 2719 2720 7478 2720 2722 7479 2722 2721 7480 2721 2719 7481 2719 2725 7482 2725 2721 7483 2721 2722 7484 2722 2725 7485 2725 2723 7486 2723 2721 7487 2721 2725 7488 2725 2724 7489 2724 2723 7490 2723 2728 7491 2728 2724 7492 2724 2725 7493 2725 2728 7494 2728 2726 7495 2726 2724 7496 2724 2728 7497 2728 2727 7498 2727 2726 7499 2726 2730 7500 2730 2727 7501 2727 2728 7502 2728 2730 7503 2730 2729 7504 2729 2727 7505 2727 2732 7506 2732 2729 7507 2729 2730 7508 2730 2732 7509 2732 2731 7510 2731 2729 7511 2729 2713 7512 2713 2731 7513 2731 2732 7514 2732 2713 7515 2713 2733 7516 2733 2731 7517 2731 2742 7518 2742 2734 7519 2734 2735 7520 2735 2739 7521 2739 2736 7522 2736 2737 7523 2737 2739 7524 2739 2738 7525 2738 2736 7526 2736 2741 7527 2741 2738 7528 2738 2739 7529 2739 2741 7530 2741 2740 7531 2740 2738 7532 2738 2743 7533 2743 2740 7534 2740 2741 7535 2741 2743 7536 2743 2742 7537 2742 2740 7538 2740 2734 7539 2734 2742 7540 2742 2743 7541 2743 2776 7542 2776 2744 7543 2744 2745 7544 2745 2748 7545 2748 2746 7546 2746 2747 7547 2747 2749 7548 2749 2746 7549 2746 2748 7550 2748 2751 7551 2751 2746 7552 2746 2749 7553 2749 2751 7554 2751 2750 7555 2750 2746 7556 2746 2753 7557 2753 2750 7558 2750 2751 7559 2751 2753 7560 2753 2752 7561 2752 2750 7562 2750 2755 7563 2755 2752 7564 2752 2753 7565 2753 2755 7566 2755 2754 7567 2754 2752 7568 2752 2757 7569 2757 2754 7570 2754 2755 7571 2755 2757 7572 2757 2756 7573 2756 2754 7574 2754 2759 7575 2759 2756 7576 2756 2757 7577 2757 2759 7578 2759 2758 7579 2758 2756 7580 2756 2761 7581 2761 2758 7582 2758 2759 7583 2759 2761 7584 2761 2760 7585 2760 2758 7586 2758 2763 7587 2763 2760 7588 2760 2761 7589 2761 2763 7590 2763 2762 7591 2762 2760 7592 2760 2765 7593 2765 2762 7594 2762 2763 7595 2763 2765 7596 2765 2764 7597 2764 2762 7598 2762 2767 7599 2767 2764 7600 2764 2765 7601 2765 2767 7602 2767 2766 7603 2766 2764 7604 2764 2769 7605 2769 2766 7606 2766 2767 7607 2767 2769 7608 2769 2768 7609 2768 2766 7610 2766 2771 7611 2771 2768 7612 2768 2769 7613 2769 2771 7614 2771 2770 7615 2770 2768 7616 2768 2773 7617 2773 2770 7618 2770 2771 7619 2771 2773 7620 2773 2772 7621 2772 2770 7622 2770 2775 7623 2775 2772 7624 2772 2773 7625 2773 2775 7626 2775 2774 7627 2774 2772 7628 2772 2777 7629 2777 2774 7630 2774 2775 7631 2775 2777 7632 2777 2776 7633 2776 2774 7634 2774 2744 7635 2744 2776 7636 2776 2777 7637 2777 2798 7638 2798 2778 7639 2778 2779 7640 2779 2782 7641 2782 2780 7642 2780 2781 7643 2781 2784 7644 2784 2780 7645 2780 2782 7646 2782 2784 7647 2784 2783 7648 2783 2780 7649 2780 2786 7650 2786 2783 7651 2783 2784 7652 2784 2786 7653 2786 2785 7654 2785 2783 7655 2783 2788 7656 2788 2785 7657 2785 2786 7658 2786 2788 7659 2788 2787 7660 2787 2785 7661 2785 2790 7662 2790 2787 7663 2787 2788 7664 2788 2790 7665 2790 2789 7666 2789 2787 7667 2787 2791 7668 2791 2789 7669 2789 2790 7670 2790 2793 7671 2793 2789 7672 2789 2791 7673 2791 2793 7674 2793 2792 7675 2792 2789 7676 2789 2795 7677 2795 2792 7678 2792 2793 7679 2793 2795 7680 2795 2794 7681 2794 2792 7682 2792 2797 7683 2797 2794 7684 2794 2795 7685 2795 2797 7686 2797 2796 7687 2796 2794 7688 2794 2799 7689 2799 2796 7690 2796 2797 7691 2797 2799 7692 2799 2798 7693 2798 2796 7694 2796 2778 7695 2778 2798 7696 2798 2799 7697 2799 2820 7698 2820 2800 7699 2800 2801 7700 2801 2804 7701 2804 2802 7702 2802 2803 7703 2803 2806 7704 2806 2802 7705 2802 2804 7706 2804 2806 7707 2806 2805 7708 2805 2802 7709 2802 2808 7710 2808 2805 7711 2805 2806 7712 2806 2808 7713 2808 2807 7714 2807 2805 7715 2805 2810 7716 2810 2807 7717 2807 2808 7718 2808 2810 7719 2810 2809 7720 2809 2807 7721 2807 2812 7722 2812 2809 7723 2809 2810 7724 2810 2812 7725 2812 2811 7726 2811 2809 7727 2809 2813 7728 2813 2811 7729 2811 2812 7730 2812 2815 7731 2815 2811 7732 2811 2813 7733 2813 2815 7734 2815 2814 7735 2814 2811 7736 2811 2817 7737 2817 2814 7738 2814 2815 7739 2815 2817 7740 2817 2816 7741 2816 2814 7742 2814 2819 7743 2819 2816 7744 2816 2817 7745 2817 2819 7746 2819 2818 7747 2818 2816 7748 2816 2821 7749 2821 2818 7750 2818 2819 7751 2819 2821 7752 2821 2820 7753 2820 2818 7754 2818 2800 7755 2800 2820 7756 2820 2821 7757 2821 2842 7758 2842 2822 7759 2822 2823 7760 2823 2826 7761 2826 2824 7762 2824 2825 7763 2825 2828 7764 2828 2824 7765 2824 2826 7766 2826 2828 7767 2828 2827 7768 2827 2824 7769 2824 2830 7770 2830 2827 7771 2827 2828 7772 2828 2830 7773 2830 2829 7774 2829 2827 7775 2827 2832 7776 2832 2829 7777 2829 2830 7778 2830 2832 7779 2832 2831 7780 2831 2829 7781 2829 2834 7782 2834 2831 7783 2831 2832 7784 2832 2834 7785 2834 2833 7786 2833 2831 7787 2831 2835 7788 2835 2833 7789 2833 2834 7790 2834 2837 7791 2837 2833 7792 2833 2835 7793 2835 2837 7794 2837 2836 7795 2836 2833 7796 2833 2839 7797 2839 2836 7798 2836 2837 7799 2837 2839 7800 2839 2838 7801 2838 2836 7802 2836 2841 7803 2841 2838 7804 2838 2839 7805 2839 2841 7806 2841 2840 7807 2840 2838 7808 2838 2843 7809 2843 2840 7810 2840 2841 7811 2841 2843 7812 2843 2842 7813 2842 2840 7814 2840 2822 7815 2822 2842 7816 2842 2843 7817 2843 2864 7818 2864 2844 7819 2844 2845 7820 2845 2848 7821 2848 2846 7822 2846 2847 7823 2847 2850 7824 2850 2846 7825 2846 2848 7826 2848 2850 7827 2850 2849 7828 2849 2846 7829 2846 2852 7830 2852 2849 7831 2849 2850 7832 2850 2852 7833 2852 2851 7834 2851 2849 7835 2849 2854 7836 2854 2851 7837 2851 2852 7838 2852 2854 7839 2854 2853 7840 2853 2851 7841 2851 2856 7842 2856 2853 7843 2853 2854 7844 2854 2856 7845 2856 2855 7846 2855 2853 7847 2853 2857 7848 2857 2855 7849 2855 2856 7850 2856 2859 7851 2859 2855 7852 2855 2857 7853 2857 2859 7854 2859 2858 7855 2858 2855 7856 2855 2861 7857 2861 2858 7858 2858 2859 7859 2859 2861 7860 2861 2860 7861 2860 2858 7862 2858 2863 7863 2863 2860 7864 2860 2861 7865 2861 2863 7866 2863 2862 7867 2862 2860 7868 2860 2865 7869 2865 2862 7870 2862 2863 7871 2863 2865 7872 2865 2864 7873 2864 2862 7874 2862 2844 7875 2844 2864 7876 2864 2865 7877 2865 2887 7878 2887 2866 7879 2866 2867 7880 2867 2870 7881 2870 2868 7882 2868 2869 7883 2869 2872 7884 2872 2868 7885 2868 2870 7886 2870 2872 7887 2872 2871 7888 2871 2868 7889 2868 2874 7890 2874 2871 7891 2871 2872 7892 2872 2874 7893 2874 2873 7894 2873 2871 7895 2871 2876 7896 2876 2873 7897 2873 2874 7898 2874 2876 7899 2876 2875 7900 2875 2873 7901 2873 2878 7902 2878 2875 7903 2875 2876 7904 2876 2878 7905 2878 2877 7906 2877 2875 7907 2875 2880 7908 2880 2877 7909 2877 2878 7910 2878 2880 7911 2880 2879 7912 2879 2877 7913 2877 2882 7914 2882 2879 7915 2879 2880 7916 2880 2882 7917 2882 2881 7918 2881 2879 7919 2879 2884 7920 2884 2881 7921 2881 2882 7922 2882 2884 7923 2884 2883 7924 2883 2881 7925 2881 2886 7926 2886 2883 7927 2883 2884 7928 2884 2886 7929 2886 2885 7930 2885 2883 7931 2883 2866 7932 2866 2885 7933 2885 2886 7934 2886 2866 7935 2866 2887 7936 2887 2885 7937 2885 2908 7938 2908 2888 7939 2888 2889 7940 2889 2893 7941 2893 2890 7942 2890 2891 7943 2891 2893 7944 2893 2892 7945 2892 2890 7946 2890 2895 7947 2895 2892 7948 2892 2893 7949 2893 2895 7950 2895 2894 7951 2894 2892 7952 2892 2897 7953 2897 2894 7954 2894 2895 7955 2895 2897 7956 2897 2896 7957 2896 2894 7958 2894 2899 7959 2899 2896 7960 2896 2897 7961 2897 2899 7962 2899 2898 7963 2898 2896 7964 2896 2901 7965 2901 2898 7966 2898 2899 7967 2899 2901 7968 2901 2900 7969 2900 2898 7970 2898 2903 7971 2903 2900 7972 2900 2901 7973 2901 2903 7974 2903 2902 7975 2902 2900 7976 2900 2905 7977 2905 2902 7978 2902 2903 7979 2903 2905 7980 2905 2904 7981 2904 2902 7982 2902 2907 7983 2907 2904 7984 2904 2905 7985 2905 2907 7986 2907 2906 7987 2906 2904 7988 2904 2909 7989 2909 2906 7990 2906 2907 7991 2907 2909 7992 2909 2908 7993 2908 2906 7994 2906 2888 7995 2888 2908 7996 2908 2909 7997 2909 2925 7998 2925 2911 7999 2911 2910 8000 2910 2913 8001 2913 2911 8002 2911 2912 8003 2912 2910 8004 2910 2911 8005 2911 2913 8006 2913 2917 8007 2917 2914 8008 2914 2915 8009 2915 2917 8010 2917 2916 8011 2916 2914 8012 2914 2919 8013 2919 2916 8014 2916 2917 8015 2917 2919 8016 2919 2918 8017 2918 2916 8018 2916 2922 8019 2922 2918 8020 2918 2919 8021 2919 2922 8022 2922 2920 8023 2920 2918 8024 2918 2922 8025 2922 2921 8026 2921 2920 8027 2920 2923 8028 2923 2921 8029 2921 2922 8030 2922 2926 8031 2926 2921 8032 2921 2923 8033 2923 2926 8034 2926 2924 8035 2924 2921 8036 2921 2926 8037 2926 2925 8038 2925 2924 8039 2924 2927 8040 2927 2925 8041 2925 2926 8042 2926 2911 8043 2911 2925 8044 2925 2927 8045 2927 2961 8046 2961 2928 8047 2928 2929 8048 2929 2932 8049 2932 2930 8050 2930 2931 8051 2931 2933 8052 2933 2930 8053 2930 2932 8054 2932 2935 8055 2935 2930 8056 2930 2933 8057 2933 2935 8058 2935 2934 8059 2934 2930 8060 2930 2937 8061 2937 2934 8062 2934 2935 8063 2935 2937 8064 2937 2936 8065 2936 2934 8066 2934 2939 8067 2939 2936 8068 2936 2937 8069 2937 2939 8070 2939 2938 8071 2938 2936 8072 2936 2941 8073 2941 2938 8074 2938 2939 8075 2939 2941 8076 2941 2940 8077 2940 2938 8078 2938 2943 8079 2943 2940 8080 2940 2941 8081 2941 2943 8082 2943 2942 8083 2942 2940 8084 2940 2946 8085 2946 2942 8086 2942 2943 8087 2943 2946 8088 2946 2944 8089 2944 2942 8090 2942 2946 8091 2946 2945 8092 2945 2944 8093 2944 2947 8094 2947 2945 8095 2945 2946 8096 2946 2949 8097 2949 2945 8098 2945 2947 8099 2947 2949 8100 2949 2948 8101 2948 2945 8102 2945 2951 8103 2951 2948 8104 2948 2949 8105 2949 2951 8106 2951 2950 8107 2950 2948 8108 2948 2953 8109 2953 2950 8110 2950 2951 8111 2951 2953 8112 2953 2952 8113 2952 2950 8114 2950 2955 8115 2955 2952 8116 2952 2953 8117 2953 2955 8118 2955 2954 8119 2954 2952 8120 2952 2957 8121 2957 2954 8122 2954 2955 8123 2955 2957 8124 2957 2956 8125 2956 2954 8126 2954 2960 8127 2960 2956 8128 2956 2957 8129 2957 2960 8130 2960 2958 8131 2958 2956 8132 2956 2960 8133 2960 2959 8134 2959 2958 8135 2958 2928 8136 2928 2959 8137 2959 2960 8138 2960 2928 8139 2928 2961 8140 2961 2959 8141 2959

+
+
+ + + + +23.417124 19.640474 0.199970 +22.968220 17.973848 0.000000 +22.897223 17.200001 0.000000 +22.690147 17.200001 0.199970 +23.195816 18.765425 0.000000 +22.764603 18.011528 0.199970 +23.590445 19.527163 0.000000 +23.003281 18.841648 0.199970 +31.609854 17.200001 0.199970 +31.402779 17.200001 0.000000 +31.535397 18.011528 0.199970 +31.331779 17.973848 0.000000 +31.296719 18.841648 0.199970 +30.882877 19.640474 0.199970 +31.104183 18.765425 0.000000 +30.303593 20.353592 0.199970 +30.709557 19.527163 0.000000 +30.157167 20.207169 0.000000 +29.590475 20.932877 0.199970 +29.477161 20.759556 0.000000 +28.791649 21.346720 0.199970 +28.715425 21.154184 0.000000 +27.961529 21.585398 0.199970 +27.923849 21.381781 0.000000 +27.150000 21.659853 0.199970 +27.150000 21.452778 0.000000 +26.338472 21.585398 0.199970 +25.508352 21.346720 0.199970 +26.376152 21.381781 0.000000 +24.709524 20.932877 0.199970 +25.584576 21.154184 0.000000 +23.996408 20.353592 0.199970 +24.822838 20.759556 0.000000 +24.142832 20.207169 0.000000 +14.250000 38.200001 7.000000 +13.300000 38.200001 6.050000 +11.515025 38.036232 6.050000 +11.500000 38.200001 6.050000 +10.550000 38.200001 7.000000 +10.580885 37.863369 7.000000 +11.563190 37.868713 6.050000 +10.679892 37.519024 7.000000 +11.646704 37.707512 6.050000 +10.851559 37.187660 7.000000 +11.763604 37.563602 6.050000 +11.907511 37.446705 6.050000 +11.091852 36.891853 7.000000 +11.387662 36.651558 7.000000 +12.068715 37.363190 6.050000 +11.719025 36.479893 7.000000 +12.236234 37.315025 6.050000 +12.063369 36.380886 7.000000 +12.400000 37.299999 6.050000 +12.400000 36.349998 7.000000 +12.563766 37.315025 6.050000 +12.736631 36.380886 7.000000 +12.731285 37.363190 6.050000 +13.080976 36.479893 7.000000 +12.892488 37.446705 6.050000 +13.412338 36.651558 7.000000 +13.036396 37.563602 6.050000 +13.708148 36.891853 7.000000 +13.153296 37.707512 6.050000 +13.948442 37.187660 7.000000 +13.236810 37.868713 6.050000 +14.120109 37.519024 7.000000 +13.284975 38.036232 6.050000 +14.219115 37.863369 7.000000 +11.515025 38.036232 6.050000 +11.500000 38.200001 5.700000 +11.500000 38.200001 6.050000 +11.515025 38.036232 5.700000 +13.284975 38.036232 6.050000 +13.300000 38.200001 6.050000 +13.300000 38.200001 5.700000 +13.236810 37.868713 6.050000 +13.284975 38.036232 5.700000 +13.236810 37.868713 5.700000 +13.153296 37.707512 6.050000 +13.153296 37.707512 5.700000 +13.036396 37.563602 6.050000 +13.036396 37.563602 5.700000 +12.892488 37.446705 6.050000 +12.731285 37.363190 6.050000 +12.892488 37.446705 5.700000 +12.731285 37.363190 5.700000 +12.563766 37.315025 6.050000 +12.563766 37.315025 5.700000 +12.400000 37.299999 6.050000 +12.236234 37.315025 6.050000 +12.400000 37.299999 5.700000 +12.236234 37.315025 5.700000 +12.068715 37.363190 6.050000 +12.068715 37.363190 5.700000 +11.907511 37.446705 6.050000 +11.763604 37.563602 6.050000 +11.907511 37.446705 5.700000 +11.763604 37.563602 5.700000 +11.646704 37.707512 6.050000 +11.563190 37.868713 6.050000 +11.646704 37.707512 5.700000 +11.563190 37.868713 5.700000 +41.146706 37.707512 6.050000 +41.000000 38.200001 6.050000 +40.049999 38.200001 7.000000 +41.015026 38.036232 6.050000 +41.063190 37.868713 6.050000 +40.080887 37.863369 7.000000 +43.719116 37.863369 7.000000 +43.750000 38.200001 7.000000 +42.799999 38.200001 6.050000 +42.784973 38.036232 6.050000 +43.620110 37.519024 7.000000 +42.736809 37.868713 6.050000 +43.448441 37.187660 7.000000 +42.653297 37.707512 6.050000 +43.208149 36.891853 7.000000 +42.536396 37.563602 6.050000 +42.912338 36.651558 7.000000 +42.392490 37.446705 6.050000 +42.580975 36.479893 7.000000 +42.231285 37.363190 6.050000 +42.236633 36.380886 7.000000 +42.063766 37.315025 6.050000 +41.900002 36.349998 7.000000 +41.900002 37.299999 6.050000 +41.563370 36.380886 7.000000 +41.736233 37.315025 6.050000 +41.219025 36.479893 7.000000 +41.568714 37.363190 6.050000 +40.887661 36.651558 7.000000 +41.407513 37.446705 6.050000 +40.591854 36.891853 7.000000 +41.263603 37.563602 6.050000 +40.351559 37.187660 7.000000 +40.179893 37.519024 7.000000 +41.000000 38.200001 5.700000 +41.000000 38.200001 6.050000 +42.799999 38.200001 6.050000 +42.799999 38.200001 5.700000 +42.784973 38.036232 6.050000 +42.736809 37.868713 6.050000 +42.784973 38.036232 5.700000 +42.653297 37.707512 6.050000 +42.736809 37.868713 5.700000 +42.653297 37.707512 5.700000 +42.536396 37.563602 6.050000 +42.536396 37.563602 5.700000 +42.392490 37.446705 6.050000 +42.392490 37.446705 5.700000 +42.231285 37.363190 6.050000 +42.063766 37.315025 6.050000 +42.231285 37.363190 5.700000 +42.063766 37.315025 5.700000 +41.900002 37.299999 6.050000 +41.900002 37.299999 5.700000 +41.736233 37.315025 6.050000 +41.736233 37.315025 5.700000 +41.568714 37.363190 6.050000 +41.568714 37.363190 5.700000 +41.407513 37.446705 6.050000 +41.407513 37.446705 5.700000 +41.263603 37.563602 6.050000 +41.263603 37.563602 5.700000 +41.146706 37.707512 6.050000 +41.146706 37.707512 5.700000 +41.063190 37.868713 6.050000 +41.063190 37.868713 5.700000 +41.015026 38.036232 6.050000 +41.015026 38.036232 5.700000 +47.000000 7.200000 7.000000 +46.049999 7.200000 6.050000 +44.250000 7.200000 6.050000 +43.299999 7.200000 7.000000 +44.265026 7.036233 6.050000 +43.330887 6.863369 7.000000 +44.313190 6.868715 6.050000 +43.429893 6.519025 7.000000 +44.396706 6.707511 6.050000 +43.601559 6.187662 7.000000 +44.513603 6.563604 6.050000 +43.841854 5.891852 7.000000 +44.657513 6.446704 6.050000 +44.137661 5.651558 7.000000 +44.818714 6.363191 6.050000 +44.469025 5.479892 7.000000 +44.986233 6.315025 6.050000 +44.813370 5.380885 7.000000 +45.150002 6.300000 6.050000 +45.150002 5.350000 7.000000 +45.313766 6.315025 6.050000 +45.486633 5.380885 7.000000 +45.481285 6.363191 6.050000 +45.830975 5.479892 7.000000 +45.642490 6.446704 6.050000 +46.162338 5.651558 7.000000 +45.786396 6.563604 6.050000 +46.458149 5.891852 7.000000 +45.903297 6.707511 6.050000 +46.698441 6.187662 7.000000 +45.986809 6.868715 6.050000 +46.870110 6.519025 7.000000 +46.034973 7.036233 6.050000 +46.969116 6.863369 7.000000 +44.313190 6.868715 6.050000 +44.250000 7.200000 5.700000 +44.250000 7.200000 6.050000 +44.265026 7.036233 5.700000 +44.313190 6.868715 5.700000 +44.265026 7.036233 6.050000 +46.034973 7.036233 6.050000 +46.049999 7.200000 6.050000 +46.049999 7.200000 5.700000 +46.034973 7.036233 5.700000 +45.986809 6.868715 6.050000 +45.903297 6.707511 6.050000 +45.986809 6.868715 5.700000 +45.903297 6.707511 5.700000 +45.786396 6.563604 6.050000 +45.786396 6.563604 5.700000 +45.642490 6.446704 6.050000 +45.642490 6.446704 5.700000 +45.481285 6.363191 6.050000 +45.481285 6.363191 5.700000 +45.313766 6.315025 6.050000 +45.313766 6.315025 5.700000 +45.150002 6.300000 6.050000 +45.150002 6.300000 5.700000 +44.986233 6.315025 6.050000 +44.986233 6.315025 5.700000 +44.818714 6.363191 6.050000 +44.818714 6.363191 5.700000 +44.657513 6.446704 6.050000 +44.657513 6.446704 5.700000 +44.513603 6.563604 6.050000 +44.513603 6.563604 5.700000 +44.396706 6.707511 6.050000 +44.396706 6.707511 5.700000 +11.000000 7.200000 7.000000 +10.050000 7.200000 6.050000 +8.250000 7.200000 6.050000 +7.300000 7.200000 7.000000 +8.265025 7.036233 6.050000 +7.330885 6.863369 7.000000 +8.313190 6.868715 6.050000 +7.429892 6.519025 7.000000 +8.396704 6.707511 6.050000 +7.601558 6.187662 7.000000 +8.513604 6.563604 6.050000 +7.841853 5.891852 7.000000 +8.657511 6.446704 6.050000 +8.137662 5.651558 7.000000 +8.818715 6.363191 6.050000 +8.469025 5.479892 7.000000 +8.986234 6.315025 6.050000 +8.813369 5.380885 7.000000 +9.150000 6.300000 6.050000 +9.150000 5.350000 7.000000 +9.313766 6.315025 6.050000 +9.486631 5.380885 7.000000 +9.481285 6.363191 6.050000 +9.830976 5.479892 7.000000 +9.642488 6.446704 6.050000 +10.162338 5.651558 7.000000 +9.786396 6.563604 6.050000 +10.458148 5.891852 7.000000 +9.903296 6.707511 6.050000 +10.698442 6.187662 7.000000 +9.986810 6.868715 6.050000 +10.870109 6.519025 7.000000 +10.034975 7.036233 6.050000 +10.969115 6.863369 7.000000 +8.250000 7.200000 5.700000 +8.250000 7.200000 6.050000 +10.050000 7.200000 6.050000 +10.050000 7.200000 5.700000 +10.034975 7.036233 6.050000 +9.986810 6.868715 6.050000 +10.034975 7.036233 5.700000 +9.986810 6.868715 5.700000 +9.903296 6.707511 6.050000 +9.903296 6.707511 5.700000 +9.786396 6.563604 6.050000 +9.786396 6.563604 5.700000 +9.642488 6.446704 6.050000 +9.642488 6.446704 5.700000 +9.481285 6.363191 6.050000 +9.481285 6.363191 5.700000 +9.313766 6.315025 6.050000 +9.313766 6.315025 5.700000 +9.150000 6.300000 6.050000 +9.150000 6.300000 5.700000 +8.986234 6.315025 6.050000 +8.986234 6.315025 5.700000 +8.818715 6.363191 6.050000 +8.818715 6.363191 5.700000 +8.657511 6.446704 6.050000 +8.657511 6.446704 5.700000 +8.513604 6.563604 6.050000 +8.513604 6.563604 5.700000 +8.396704 6.707511 6.050000 +8.396704 6.707511 5.700000 +8.313190 6.868715 6.050000 +8.313190 6.868715 5.700000 +8.265025 7.036233 6.050000 +8.265025 7.036233 5.700000 +47.150002 7.200000 7.200000 +47.150002 7.200000 7.000000 +43.183388 6.836074 7.000000 +43.150002 7.200000 7.000000 +43.150002 7.200000 7.200000 +43.183388 6.836074 7.200000 +43.290424 6.463810 7.000000 +43.290424 6.463810 7.200000 +43.476009 6.105580 7.000000 +43.476009 6.105580 7.200000 +43.735786 5.785787 7.000000 +43.735786 5.785787 7.200000 +44.055580 5.526009 7.000000 +44.055580 5.526009 7.200000 +44.413811 5.340424 7.000000 +44.413811 5.340424 7.200000 +44.786076 5.233389 7.000000 +44.786076 5.233389 7.200000 +45.150002 5.200000 7.000000 +45.150002 5.200000 7.200000 +45.513927 5.233389 7.000000 +45.513927 5.233389 7.200000 +45.886189 5.340424 7.000000 +45.886189 5.340424 7.200000 +46.244419 5.526009 7.000000 +46.244419 5.526009 7.200000 +46.564213 5.785787 7.000000 +46.823990 6.105580 7.000000 +46.564213 5.785787 7.200000 +46.823990 6.105580 7.200000 +47.009575 6.463810 7.000000 +47.009575 6.463810 7.200000 +47.116611 6.836074 7.000000 +47.116611 6.836074 7.200000 +11.150000 7.200000 7.200000 +11.150000 7.200000 7.000000 +7.150000 7.200000 7.000000 +7.150000 7.200000 7.200000 +7.183389 6.836074 7.000000 +7.183389 6.836074 7.200000 +7.290423 6.463810 7.000000 +7.290423 6.463810 7.200000 +7.476009 6.105580 7.000000 +7.476009 6.105580 7.200000 +7.735786 5.785787 7.000000 +7.735786 5.785787 7.200000 +8.055580 5.526009 7.000000 +8.055580 5.526009 7.200000 +8.413811 5.340424 7.000000 +8.413811 5.340424 7.200000 +8.786074 5.233389 7.000000 +8.786074 5.233389 7.200000 +9.150000 5.200000 7.000000 +9.150000 5.200000 7.200000 +9.513927 5.233389 7.000000 +9.513927 5.233389 7.200000 +9.886189 5.340424 7.000000 +9.886189 5.340424 7.200000 +10.244419 5.526009 7.000000 +10.244419 5.526009 7.200000 +10.564214 5.785787 7.000000 +10.564214 5.785787 7.200000 +10.823991 6.105580 7.000000 +10.823991 6.105580 7.200000 +11.009577 6.463810 7.000000 +11.009577 6.463810 7.200000 +11.116611 6.836074 7.000000 +11.116611 6.836074 7.200000 +43.900002 38.200001 7.200000 +43.900002 38.200001 7.000000 +39.900002 38.200001 7.000000 +39.900002 38.200001 7.200000 +39.933388 37.836075 7.000000 +39.933388 37.836075 7.200000 +40.040424 37.463810 7.000000 +40.226009 37.105579 7.000000 +40.040424 37.463810 7.200000 +40.226009 37.105579 7.200000 +40.485786 36.785786 7.000000 +40.485786 36.785786 7.200000 +40.805580 36.526009 7.000000 +41.163811 36.340424 7.000000 +40.805580 36.526009 7.200000 +41.536076 36.233391 7.000000 +41.163811 36.340424 7.200000 +41.536076 36.233391 7.200000 +41.900002 36.200001 7.000000 +41.900002 36.200001 7.200000 +42.263927 36.233391 7.000000 +42.263927 36.233391 7.200000 +42.636189 36.340424 7.000000 +42.636189 36.340424 7.200000 +42.994419 36.526009 7.000000 +42.994419 36.526009 7.200000 +43.314213 36.785786 7.000000 +43.314213 36.785786 7.200000 +43.573990 37.105579 7.000000 +43.573990 37.105579 7.200000 +43.759575 37.463810 7.000000 +43.759575 37.463810 7.200000 +43.866611 37.836075 7.000000 +43.866611 37.836075 7.200000 +14.400000 38.200001 7.200000 +14.400000 38.200001 7.000000 +10.433390 37.836075 7.000000 +10.400000 38.200001 7.000000 +10.400000 38.200001 7.200000 +10.433390 37.836075 7.200000 +10.540423 37.463810 7.000000 +10.540423 37.463810 7.200000 +10.726009 37.105579 7.000000 +10.726009 37.105579 7.200000 +10.985786 36.785786 7.000000 +11.305580 36.526009 7.000000 +10.985786 36.785786 7.200000 +11.305580 36.526009 7.200000 +11.663811 36.340424 7.000000 +11.663811 36.340424 7.200000 +12.036074 36.233391 7.000000 +12.036074 36.233391 7.200000 +12.400000 36.200001 7.000000 +12.400000 36.200001 7.200000 +12.763927 36.233391 7.000000 +12.763927 36.233391 7.200000 +13.136189 36.340424 7.000000 +13.136189 36.340424 7.200000 +13.494419 36.526009 7.000000 +13.494419 36.526009 7.200000 +13.814214 36.785786 7.000000 +13.814214 36.785786 7.200000 +14.073991 37.105579 7.000000 +14.073991 37.105579 7.200000 +14.259577 37.463810 7.000000 +14.259577 37.463810 7.200000 +14.366611 37.836075 7.000000 +14.366611 37.836075 7.200000 +14.352555 37.427002 5.700000 +14.464941 37.817879 5.700000 +14.500000 38.200001 5.700000 +14.555856 38.200001 2.500000 +10.244143 38.200001 2.500000 +10.300000 38.200001 5.700000 +10.280135 37.807713 2.500000 +10.395510 37.406441 2.500000 +10.335059 37.817879 5.700000 +10.595558 37.020294 2.500000 +10.447445 37.427002 5.700000 +10.642309 37.050861 5.700000 +10.875580 36.675579 2.500000 +10.915075 36.715076 5.700000 +11.220294 36.395557 2.500000 +11.606441 36.195511 2.500000 +11.250859 36.442310 5.700000 +11.627001 36.247444 5.700000 +12.007714 36.080135 2.500000 +12.400000 36.044144 2.500000 +12.017878 36.135059 5.700000 +12.400000 36.099998 5.700000 +12.792286 36.080135 2.500000 +12.782123 36.135059 5.700000 +13.193560 36.195511 2.500000 +13.579705 36.395557 2.500000 +13.172998 36.247444 5.700000 +13.924420 36.675579 2.500000 +13.549141 36.442310 5.700000 +13.884924 36.715076 5.700000 +14.204442 37.020294 2.500000 +14.157691 37.050861 5.700000 +14.404490 37.406441 2.500000 +14.519865 37.807713 2.500000 +42.673000 36.247444 5.700000 +43.964943 37.817879 5.700000 +44.000000 38.200001 5.700000 +44.055855 38.200001 2.500000 +44.019863 37.807713 2.500000 +43.852554 37.427002 5.700000 +43.904491 37.406441 2.500000 +43.657692 37.050861 5.700000 +43.704441 37.020294 2.500000 +43.384926 36.715076 5.700000 +43.424419 36.675579 2.500000 +43.049141 36.442310 5.700000 +39.744144 38.200001 2.500000 +39.799999 38.200001 5.700000 +39.780136 37.807713 2.500000 +39.895512 37.406441 2.500000 +39.835060 37.817879 5.700000 +39.947445 37.427002 5.700000 +40.095558 37.020294 2.500000 +40.142311 37.050861 5.700000 +40.375580 36.675579 2.500000 +40.415077 36.715076 5.700000 +40.720295 36.395557 2.500000 +40.750858 36.442310 5.700000 +41.106441 36.195511 2.500000 +41.127003 36.247444 5.700000 +41.507713 36.080135 2.500000 +41.517879 36.135059 5.700000 +41.900002 36.044144 2.500000 +42.292286 36.080135 2.500000 +41.900002 36.099998 5.700000 +42.282124 36.135059 5.700000 +42.693558 36.195511 2.500000 +43.079704 36.395557 2.500000 +6.994144 7.200000 2.500000 +7.050000 7.200000 5.700000 +11.214941 6.817878 5.700000 +11.250000 7.200000 5.700000 +11.305856 7.200000 2.500000 +11.102555 6.427001 5.700000 +11.269865 6.807714 2.500000 +11.154490 6.406441 2.500000 +10.907691 6.050859 5.700000 +10.634924 5.715076 5.700000 +10.954442 6.020295 2.500000 +10.674420 5.675580 2.500000 +10.299141 5.442309 5.700000 +10.329705 5.395558 2.500000 +9.922998 5.247445 5.700000 +9.943560 5.195510 2.500000 +9.532123 5.135059 5.700000 +9.542286 5.080135 2.500000 +9.150000 5.100000 5.700000 +9.150000 5.044144 2.500000 +8.767878 5.135059 5.700000 +8.757714 5.080135 2.500000 +8.377001 5.247445 5.700000 +8.356441 5.195510 2.500000 +8.000859 5.442309 5.700000 +7.970294 5.395558 2.500000 +7.665076 5.715076 5.700000 +7.625579 5.675580 2.500000 +7.392309 6.050859 5.700000 +7.345558 6.020295 2.500000 +7.197444 6.427001 5.700000 +7.145510 6.406441 2.500000 +7.085059 6.817878 5.700000 +7.030135 6.807714 2.500000 +47.154491 6.406441 2.500000 +47.214943 6.817878 5.700000 +47.250000 7.200000 5.700000 +47.305855 7.200000 2.500000 +47.102554 6.427001 5.700000 +47.269863 6.807714 2.500000 +42.994144 7.200000 2.500000 +43.049999 7.200000 5.700000 +43.030136 6.807714 2.500000 +43.085060 6.817878 5.700000 +43.145512 6.406441 2.500000 +43.345558 6.020295 2.500000 +43.197445 6.427001 5.700000 +43.392311 6.050859 5.700000 +43.625580 5.675580 2.500000 +43.665077 5.715076 5.700000 +43.970295 5.395558 2.500000 +44.000858 5.442309 5.700000 +44.356441 5.195510 2.500000 +44.757713 5.080135 2.500000 +44.377003 5.247445 5.700000 +44.767879 5.135059 5.700000 +45.150002 5.044144 2.500000 +45.150002 5.100000 5.700000 +45.542286 5.080135 2.500000 +45.532124 5.135059 5.700000 +45.943558 5.195510 2.500000 +46.329704 5.395558 2.500000 +45.923000 5.247445 5.700000 +46.674419 5.675580 2.500000 +46.299141 5.442309 5.700000 +46.634926 5.715076 5.700000 +46.954441 6.020295 2.500000 +46.907692 6.050859 5.700000 +43.393829 45.305523 3.400000 +43.436646 45.454430 7.200000 +43.450001 45.599998 7.200000 +43.450001 45.599998 3.400000 +43.393829 45.305523 7.200000 +43.436646 45.454430 3.400000 +41.849998 45.599998 3.400000 +41.849998 45.599998 7.200000 +41.863358 45.454430 3.400000 +41.906170 45.305523 3.400000 +41.863358 45.454430 7.200000 +41.906170 45.305523 7.200000 +41.980404 45.162231 3.400000 +41.980404 45.162231 7.200000 +42.084316 45.034313 3.400000 +42.084316 45.034313 7.200000 +42.212231 44.930405 3.400000 +42.212231 44.930405 7.200000 +42.355526 44.856171 3.400000 +42.355526 44.856171 7.200000 +42.504429 44.813354 3.400000 +42.504429 44.813354 7.200000 +42.650002 44.799999 3.400000 +42.650002 44.799999 7.200000 +42.795570 44.813354 3.400000 +42.795570 44.813354 7.200000 +42.944477 44.856171 3.400000 +42.944477 44.856171 7.200000 +43.087769 44.930405 3.400000 +43.215687 45.034313 3.400000 +43.087769 44.930405 7.200000 +43.215687 45.034313 7.200000 +43.319595 45.162231 3.400000 +43.319595 45.162231 7.200000 +12.436645 45.454430 3.400000 +12.450000 45.599998 7.200000 +12.450000 45.599998 3.400000 +12.436645 45.454430 7.200000 +10.850000 45.599998 3.400000 +10.850000 45.599998 7.200000 +10.863356 45.454430 3.400000 +10.863356 45.454430 7.200000 +10.906169 45.305523 3.400000 +10.906169 45.305523 7.200000 +10.980404 45.162231 3.400000 +10.980404 45.162231 7.200000 +11.084314 45.034313 3.400000 +11.084314 45.034313 7.200000 +11.212233 44.930405 3.400000 +11.212233 44.930405 7.200000 +11.355524 44.856171 3.400000 +11.355524 44.856171 7.200000 +11.504430 44.813354 3.400000 +11.504430 44.813354 7.200000 +11.650000 44.799999 3.400000 +11.650000 44.799999 7.200000 +11.795570 44.813354 3.400000 +11.795570 44.813354 7.200000 +11.944476 44.856171 3.400000 +11.944476 44.856171 7.200000 +12.087768 44.930405 3.400000 +12.087768 44.930405 7.200000 +12.215686 45.034313 3.400000 +12.215686 45.034313 7.200000 +12.319596 45.162231 3.400000 +12.319596 45.162231 7.200000 +12.393830 45.305523 3.400000 +12.393830 45.305523 7.200000 +28.917767 15.432233 0.000000 +29.650000 17.200001 7.200000 +29.650000 17.200001 0.000000 +29.608263 16.745092 7.200000 +29.608263 16.745092 0.000000 +29.474470 16.279764 7.200000 +29.474470 16.279764 0.000000 +29.242489 15.831976 7.200000 +28.917767 15.432233 7.200000 +29.242489 15.831976 0.000000 +24.650000 17.200001 0.000000 +24.650000 17.200001 7.200000 +24.691736 16.745092 0.000000 +24.691736 16.745092 7.200000 +24.825529 16.279764 0.000000 +24.825529 16.279764 7.200000 +25.057510 15.831976 0.000000 +25.057510 15.831976 7.200000 +25.382233 15.432233 0.000000 +25.781975 15.107512 0.000000 +25.382233 15.432233 7.200000 +25.781975 15.107512 7.200000 +26.229763 14.875529 0.000000 +26.229763 14.875529 7.200000 +26.695093 14.741736 0.000000 +26.695093 14.741736 7.200000 +27.150000 14.700000 0.000000 +27.150000 14.700000 7.200000 +27.604908 14.741736 0.000000 +27.604908 14.741736 7.200000 +28.070236 14.875529 0.000000 +28.070236 14.875529 7.200000 +28.518024 15.107512 0.000000 +28.518024 15.107512 7.200000 +22.764603 16.388472 0.199970 +22.725126 16.381166 2.500000 +22.650000 17.200001 2.500000 +22.690147 17.200001 0.199970 +31.609854 17.200001 0.199970 +31.650000 17.200001 2.500000 +31.535397 16.388472 0.199970 +31.574875 16.381166 2.500000 +31.296719 15.558352 0.199970 +31.334047 15.543573 2.500000 +30.882877 14.759525 0.199970 +30.916479 14.737556 2.500000 +30.303593 14.046408 0.199970 +30.331980 14.018020 2.500000 +29.590475 13.467123 0.199970 +29.612444 13.433520 2.500000 +28.791649 13.053281 0.199970 +28.806427 13.015953 2.500000 +27.961529 12.814603 0.199970 +27.968834 12.775126 2.500000 +27.150000 12.740148 0.199970 +27.150000 12.700000 2.500000 +26.338472 12.814603 0.199970 +26.331165 12.775126 2.500000 +25.508352 13.053281 0.199970 +25.493574 13.015953 2.500000 +24.709524 13.467123 0.199970 +23.996408 14.046408 0.199970 +24.687555 13.433520 2.500000 +23.968019 14.018020 2.500000 +23.417124 14.759525 0.199970 +23.383520 14.737556 2.500000 +23.003281 15.558352 0.199970 +22.965952 15.543573 2.500000 +45.400002 42.599846 7.200000 +45.333672 42.533520 3.400000 +45.333672 47.033825 3.400000 +45.400002 47.100151 7.200000 +14.900000 48.050819 4.382547 +9.949026 48.050819 4.382547 +9.899848 48.099998 7.200000 +44.400154 48.099998 7.200000 +44.350975 48.050819 4.382547 +39.400002 48.035110 3.482548 +14.900000 48.035110 3.482548 +39.400002 48.050819 4.382547 +8.966330 47.033825 3.400000 +8.966330 42.533520 3.400000 +8.900000 42.599846 7.200000 +8.900000 47.100151 7.200000 +7.966482 41.533672 3.400000 +14.400000 41.533672 3.400000 +1.873786 41.584747 6.326080 +1.743557 41.599998 7.200000 +2.175905 41.569351 5.444029 +7.900152 41.599998 7.200000 +2.657373 41.554691 4.604214 +3.305650 41.541698 3.859945 +4.087719 41.531185 3.257517 +4.955367 41.523670 2.827114 +5.854586 41.519325 2.578083 +6.735492 41.517960 2.500000 +14.400000 41.517960 2.500000 +39.900002 41.517960 2.500000 +39.900002 41.533672 3.400000 +46.399849 41.599998 7.200000 +52.556442 41.599998 7.200000 +52.426212 41.584747 6.326080 +46.333519 41.533672 3.400000 +52.124096 41.569351 5.444029 +51.642628 41.554691 4.604214 +50.994350 41.541698 3.859945 +50.212280 41.531185 3.257517 +49.344635 41.523670 2.827114 +48.445415 41.519325 2.578083 +47.564507 41.517960 2.500000 +45.150002 5.200000 7.200000 +1.743557 41.599998 7.200000 +7.183389 6.836074 7.200000 +7.150000 7.200000 7.200000 +7.183389 7.563926 7.200000 +7.290423 7.936190 7.200000 +7.476009 8.294419 7.200000 +7.735786 8.614214 7.200000 +8.055580 8.873991 7.200000 +54.087376 5.073030 7.200000 +47.150002 7.200000 7.200000 +47.116611 7.563926 7.200000 +47.009575 7.936190 7.200000 +46.823990 8.294419 7.200000 +46.564213 8.614214 7.200000 +46.244419 8.873991 7.200000 +45.886189 9.059577 7.200000 +52.556442 41.599998 7.200000 +45.513927 9.166611 7.200000 +7.900152 41.599998 7.200000 +8.413811 9.059577 7.200000 +8.786074 9.166611 7.200000 +45.150002 9.200000 7.200000 +25.057510 15.831976 7.200000 +10.823991 8.294419 7.200000 +47.116611 6.836074 7.200000 +7.290423 6.463810 7.200000 +8.082108 41.616692 7.200000 +11.084314 46.165684 7.200000 +43.087769 46.269596 7.200000 +46.399849 41.599998 7.200000 +10.726009 39.294418 7.200000 +8.607170 41.892830 7.200000 +8.737030 42.052696 7.200000 +10.985786 39.614212 7.200000 +45.692829 41.892830 7.200000 +42.994419 39.873993 7.200000 +43.314213 39.614212 7.200000 +45.852695 41.762970 7.200000 +9.150000 9.200000 7.200000 +44.786076 9.166611 7.200000 +11.212233 46.269596 7.200000 +42.944477 46.343830 7.200000 +10.564214 8.614214 7.200000 +25.382233 15.432233 7.200000 +11.009577 7.936190 7.200000 +24.825529 16.279764 7.200000 +8.829803 42.231781 7.200000 +45.562969 42.052696 7.200000 +8.268220 41.670197 7.200000 +46.217892 41.616692 7.200000 +8.447305 41.762970 7.200000 +46.031780 41.670197 7.200000 +43.573990 39.294418 7.200000 +10.540423 38.936188 7.200000 +47.009575 6.463810 7.200000 +7.476009 6.105580 7.200000 +44.413811 9.059577 7.200000 +9.513927 9.166611 7.200000 +11.305580 39.873993 7.200000 +10.980404 46.037769 7.200000 +43.215687 46.165684 7.200000 +42.636189 40.059578 7.200000 +10.244419 8.873991 7.200000 +45.470200 42.231781 7.200000 +8.883308 42.417892 7.200000 +44.582108 48.083309 7.200000 +44.768219 48.029800 7.200000 +44.947304 47.937031 7.200000 +45.107170 47.807171 7.200000 +45.237030 47.647305 7.200000 +45.329803 47.468220 7.200000 +45.383308 47.282108 7.200000 +45.400002 47.100151 7.200000 +45.400002 42.599846 7.200000 +43.319595 46.037769 7.200000 +43.393829 45.894474 7.200000 +43.436646 45.745571 7.200000 +43.450001 45.599998 7.200000 +43.436646 45.454430 7.200000 +43.393829 45.305523 7.200000 +43.319595 45.162231 7.200000 +43.215687 45.034313 7.200000 +43.087769 44.930405 7.200000 +9.899848 48.099998 7.200000 +9.717892 48.083309 7.200000 +9.531780 48.029800 7.200000 +9.352695 47.937031 7.200000 +9.192830 47.807171 7.200000 +9.062970 47.647305 7.200000 +8.970198 47.468220 7.200000 +8.916692 47.282108 7.200000 +8.900000 47.100151 7.200000 +10.906169 45.894474 7.200000 +10.863356 45.745571 7.200000 +10.850000 45.599998 7.200000 +10.863356 45.454430 7.200000 +10.906169 45.305523 7.200000 +10.980404 45.162231 7.200000 +11.084314 45.034313 7.200000 +11.212233 44.930405 7.200000 +11.355524 44.856171 7.200000 +25.781975 15.107512 7.200000 +11.116611 7.563926 7.200000 +24.691736 16.745092 7.200000 +11.355524 46.343830 7.200000 +42.795570 46.386642 7.200000 +9.886189 9.059577 7.200000 +44.055580 8.873991 7.200000 +46.823990 6.105580 7.200000 +7.735786 5.785787 7.200000 +11.504430 44.813354 7.200000 +42.944477 44.856171 7.200000 +11.663811 40.059578 7.200000 +8.900000 42.599846 7.200000 +11.650000 44.799999 7.200000 +12.036074 40.166611 7.200000 +11.795570 44.813354 7.200000 +11.944476 44.856171 7.200000 +12.400000 40.200001 7.200000 +12.087768 44.930405 7.200000 +12.763927 40.166611 7.200000 +12.215686 45.034313 7.200000 +42.263927 40.166611 7.200000 +45.416691 42.417892 7.200000 +42.795570 44.813354 7.200000 +41.900002 40.200001 7.200000 +42.650002 44.799999 7.200000 +42.504429 44.813354 7.200000 +41.536076 40.166611 7.200000 +42.355526 44.856171 7.200000 +41.163811 40.059578 7.200000 +42.212231 44.930405 7.200000 +11.150000 7.200000 7.200000 +26.229763 14.875529 7.200000 +10.433390 38.563927 7.200000 +43.759575 38.936188 7.200000 +24.650000 17.200001 7.200000 +13.136189 40.059578 7.200000 +12.319596 45.162231 7.200000 +11.504430 46.386642 7.200000 +44.400154 48.099998 7.200000 +11.650000 46.400002 7.200000 +11.795570 46.386642 7.200000 +11.944476 46.343830 7.200000 +12.087768 46.269596 7.200000 +12.215686 46.165684 7.200000 +12.319596 46.037769 7.200000 +12.393830 45.894474 7.200000 +12.436645 45.745571 7.200000 +12.450000 45.599998 7.200000 +12.436645 45.454430 7.200000 +12.393830 45.305523 7.200000 +13.494419 39.873993 7.200000 +13.814214 39.614212 7.200000 +14.073991 39.294418 7.200000 +14.259577 38.936188 7.200000 +14.366611 38.563927 7.200000 +14.400000 38.200001 7.200000 +14.366611 37.836075 7.200000 +42.650002 46.400002 7.200000 +40.805580 39.873993 7.200000 +42.084316 45.034313 7.200000 +43.735786 8.614214 7.200000 +11.116611 6.836074 7.200000 +26.695093 14.741736 7.200000 +46.564213 5.785787 7.200000 +8.055580 5.526009 7.200000 +14.259577 37.463810 7.200000 +24.691736 17.654907 7.200000 +10.400000 38.200001 7.200000 +10.433390 37.836075 7.200000 +10.540423 37.463810 7.200000 +10.726009 37.105579 7.200000 +10.985786 36.785786 7.200000 +11.305580 36.526009 7.200000 +11.663811 36.340424 7.200000 +12.036074 36.233391 7.200000 +12.400000 36.200001 7.200000 +12.763927 36.233391 7.200000 +24.825529 18.120237 7.200000 +13.136189 36.340424 7.200000 +25.057510 18.568024 7.200000 +13.494419 36.526009 7.200000 +25.382233 18.967768 7.200000 +13.814214 36.785786 7.200000 +25.781975 19.292488 7.200000 +14.073991 37.105579 7.200000 +26.229763 19.524471 7.200000 +26.695093 19.658264 7.200000 +27.150000 19.700001 7.200000 +43.866611 38.563927 7.200000 +43.900002 38.200001 7.200000 +43.866611 37.836075 7.200000 +43.759575 37.463810 7.200000 +43.573990 37.105579 7.200000 +43.314213 36.785786 7.200000 +42.994419 36.526009 7.200000 +42.636189 36.340424 7.200000 +42.263927 36.233391 7.200000 +41.900002 36.200001 7.200000 +41.536076 36.233391 7.200000 +41.163811 36.340424 7.200000 +43.476009 8.294419 7.200000 +40.805580 36.526009 7.200000 +41.980404 45.162231 7.200000 +40.485786 39.614212 7.200000 +42.504429 46.386642 7.200000 +27.604908 19.658264 7.200000 +11.009577 6.463810 7.200000 +27.150000 14.700000 7.200000 +40.485786 36.785786 7.200000 +43.290424 7.936190 7.200000 +41.906170 45.305523 7.200000 +46.244419 5.526009 7.200000 +8.413811 5.340424 7.200000 +42.355526 46.343830 7.200000 +42.212231 46.269596 7.200000 +42.084316 46.165684 7.200000 +41.980404 46.037769 7.200000 +41.906170 45.894474 7.200000 +41.863358 45.745571 7.200000 +41.849998 45.599998 7.200000 +41.863358 45.454430 7.200000 +28.070236 19.524471 7.200000 +28.518024 19.292488 7.200000 +28.917767 18.967768 7.200000 +29.242489 18.568024 7.200000 +29.474470 18.120237 7.200000 +29.608263 17.654907 7.200000 +40.226009 39.294418 7.200000 +10.823991 6.105580 7.200000 +27.604908 14.741736 7.200000 +43.183388 7.563926 7.200000 +40.226009 37.105579 7.200000 +29.650000 17.200001 7.200000 +45.886189 5.340424 7.200000 +8.786074 5.233389 7.200000 +40.040424 38.936188 7.200000 +39.933388 38.563927 7.200000 +39.900002 38.200001 7.200000 +39.933388 37.836075 7.200000 +40.040424 37.463810 7.200000 +29.608263 16.745092 7.200000 +29.474470 16.279764 7.200000 +29.242489 15.831976 7.200000 +28.917767 15.432233 7.200000 +43.150002 7.200000 7.200000 +43.183388 6.836074 7.200000 +28.518024 15.107512 7.200000 +43.290424 6.463810 7.200000 +28.070236 14.875529 7.200000 +43.476009 6.105580 7.200000 +43.735786 5.785787 7.200000 +10.564214 5.785787 7.200000 +44.055580 5.526009 7.200000 +10.244419 5.526009 7.200000 +44.413811 5.340424 7.200000 +9.886189 5.340424 7.200000 +44.786076 5.233389 7.200000 +9.150000 5.200000 7.200000 +0.212623 5.073030 7.200000 +9.513927 5.233389 7.200000 +45.513927 5.233389 7.200000 +7.145510 7.993559 2.500000 +30.916479 14.737556 2.500000 +43.345558 8.379705 2.500000 +14.900000 47.035263 2.500000 +39.400002 47.035263 2.500000 +14.900000 42.018036 2.500000 +41.106441 40.204491 2.500000 +13.579705 40.004440 2.500000 +7.970294 5.395558 2.500000 +45.943558 5.195510 2.500000 +39.400002 42.018036 2.500000 +14.891653 41.927040 2.500000 +43.625580 8.724421 2.500000 +46.329704 5.395558 2.500000 +7.625579 5.675580 2.500000 +40.720295 40.004440 2.500000 +13.924420 39.724419 2.500000 +30.331980 14.018020 2.500000 +43.145512 7.993559 2.500000 +31.334047 15.543573 2.500000 +39.408348 41.927040 2.500000 +14.864894 41.833961 2.500000 +8.356441 5.195510 2.500000 +49.301189 0.082039 2.500000 +8.757714 5.080135 2.500000 +9.150000 5.044144 2.500000 +9.542286 5.080135 2.500000 +9.943560 5.195510 2.500000 +10.329705 5.395558 2.500000 +10.674420 5.675580 2.500000 +10.954442 6.020295 2.500000 +11.154490 6.406441 2.500000 +11.269865 6.807714 2.500000 +11.305856 7.200000 2.500000 +45.542286 5.080135 2.500000 +43.970295 9.004442 2.500000 +39.809017 41.526310 2.500000 +14.400000 41.517960 2.500000 +43.030136 7.592286 2.500000 +29.612444 13.433520 2.500000 +31.574875 16.381166 2.500000 +46.674419 5.675580 2.500000 +7.345558 6.020295 2.500000 +41.507713 40.319866 2.500000 +39.900002 41.517960 2.500000 +41.900002 40.355858 2.500000 +42.292286 40.319866 2.500000 +42.693558 40.204491 2.500000 +43.079704 40.004440 2.500000 +43.424419 39.724419 2.500000 +43.704441 39.379707 2.500000 +43.904491 38.993561 2.500000 +44.019863 38.592285 2.500000 +47.564507 41.517960 2.500000 +44.055855 38.200001 2.500000 +44.019863 37.807713 2.500000 +43.904491 37.406441 2.500000 +43.704441 37.020294 2.500000 +43.424419 36.675579 2.500000 +43.079704 36.395557 2.500000 +42.693558 36.195511 2.500000 +42.292286 36.080135 2.500000 +41.900002 36.044144 2.500000 +41.507713 36.080135 2.500000 +13.193560 40.204491 2.500000 +6.735492 41.517960 2.500000 +12.792286 40.319866 2.500000 +12.400000 40.355858 2.500000 +12.007714 40.319866 2.500000 +11.606441 40.204491 2.500000 +11.220294 40.004440 2.500000 +10.875580 39.724419 2.500000 +10.595558 39.379707 2.500000 +10.395510 38.993561 2.500000 +4.998812 0.082039 2.500000 +10.280135 38.592285 2.500000 +10.244143 38.200001 2.500000 +10.280135 37.807713 2.500000 +10.395510 37.406441 2.500000 +10.595558 37.020294 2.500000 +10.875580 36.675579 2.500000 +11.220294 36.395557 2.500000 +11.606441 36.195511 2.500000 +12.007714 36.080135 2.500000 +12.400000 36.044144 2.500000 +39.435104 41.833961 2.500000 +14.818498 41.744392 2.500000 +11.269865 7.592286 2.500000 +44.356441 9.204490 2.500000 +41.106441 36.195511 2.500000 +12.792286 36.080135 2.500000 +42.994144 7.200000 2.500000 +45.150002 5.044144 2.500000 +44.757713 5.080135 2.500000 +44.356441 5.195510 2.500000 +43.970295 5.395558 2.500000 +43.625580 5.675580 2.500000 +43.345558 6.020295 2.500000 +43.145512 6.406441 2.500000 +43.030136 6.807714 2.500000 +11.154490 7.993559 2.500000 +40.375580 39.724419 2.500000 +39.715954 41.553074 2.500000 +14.490981 41.526310 2.500000 +14.204442 39.379707 2.500000 +28.806427 13.015953 2.500000 +14.584047 41.553074 2.500000 +31.650000 17.200001 2.500000 +39.626396 41.599476 2.500000 +44.757713 9.319865 2.500000 +39.481503 41.744392 2.500000 +14.753553 41.664429 2.500000 +40.720295 36.395557 2.500000 +13.193560 36.195511 2.500000 +46.954441 6.020295 2.500000 +7.145510 6.406441 2.500000 +10.954442 8.379705 2.500000 +31.574875 18.018833 2.500000 +45.150002 9.355856 2.500000 +40.095558 39.379707 2.500000 +39.546448 41.664429 2.500000 +39.895512 38.993561 2.500000 +39.780136 38.592285 2.500000 +39.744144 38.200001 2.500000 +39.780136 37.807713 2.500000 +39.895512 37.406441 2.500000 +14.673605 41.599476 2.500000 +14.404490 38.993561 2.500000 +14.519865 38.592285 2.500000 +14.555856 38.200001 2.500000 +14.519865 37.807713 2.500000 +14.404490 37.406441 2.500000 +14.204442 37.020294 2.500000 +40.095558 37.020294 2.500000 +13.924420 36.675579 2.500000 +40.375580 36.675579 2.500000 +13.579705 36.395557 2.500000 +27.968834 12.775126 2.500000 +27.150000 12.700000 2.500000 +26.331165 12.775126 2.500000 +25.493574 13.015953 2.500000 +24.687555 13.433520 2.500000 +23.968019 14.018020 2.500000 +23.383520 14.737556 2.500000 +22.965952 15.543573 2.500000 +22.725126 16.381166 2.500000 +10.674420 8.724421 2.500000 +22.650000 17.200001 2.500000 +10.329705 9.004442 2.500000 +22.725126 18.018833 2.500000 +9.943560 9.204490 2.500000 +22.965952 18.856426 2.500000 +9.542286 9.319865 2.500000 +47.154491 6.406441 2.500000 +7.030135 6.807714 2.500000 +45.542286 9.319865 2.500000 +9.150000 9.355856 2.500000 +23.383520 19.662443 2.500000 +31.334047 18.856426 2.500000 +6.994144 7.200000 2.500000 +47.269863 6.807714 2.500000 +45.943558 9.204490 2.500000 +8.757714 9.319865 2.500000 +23.968019 20.381981 2.500000 +30.916479 19.662443 2.500000 +47.305855 7.200000 2.500000 +47.269863 7.592286 2.500000 +47.154491 7.993559 2.500000 +46.954441 8.379705 2.500000 +46.674419 8.724421 2.500000 +46.329704 9.004442 2.500000 +30.331980 20.381981 2.500000 +29.612444 20.966480 2.500000 +28.806427 21.384047 2.500000 +27.968834 21.624874 2.500000 +27.150000 21.700001 2.500000 +26.331165 21.624874 2.500000 +25.493574 21.384047 2.500000 +24.687555 20.966480 2.500000 +8.356441 9.204490 2.500000 +7.970294 9.004442 2.500000 +7.625579 8.724421 2.500000 +7.345558 8.379705 2.500000 +7.030135 7.592286 2.500000 +31.650000 17.200001 2.500000 +31.609854 17.200001 0.199970 +22.690147 17.200001 0.199970 +22.650000 17.200001 2.500000 +22.764603 18.011528 0.199970 +22.725126 18.018833 2.500000 +23.003281 18.841648 0.199970 +22.965952 18.856426 2.500000 +23.417124 19.640474 0.199970 +23.383520 19.662443 2.500000 +23.996408 20.353592 0.199970 +23.968019 20.381981 2.500000 +24.709524 20.932877 0.199970 +24.687555 20.966480 2.500000 +25.508352 21.346720 0.199970 +25.493574 21.384047 2.500000 +26.338472 21.585398 0.199970 +26.331165 21.624874 2.500000 +27.150000 21.659853 0.199970 +27.150000 21.700001 2.500000 +27.961529 21.585398 0.199970 +27.968834 21.624874 2.500000 +28.791649 21.346720 0.199970 +28.806427 21.384047 2.500000 +29.590475 20.932877 0.199970 +29.612444 20.966480 2.500000 +30.303593 20.353592 0.199970 +30.331980 20.381981 2.500000 +30.882877 19.640474 0.199970 +30.916479 19.662443 2.500000 +31.296719 18.841648 0.199970 +31.334047 18.856426 2.500000 +31.535397 18.011528 0.199970 +31.574875 18.018833 2.500000 +25.382233 15.432233 0.000000 +25.584576 13.245816 0.000000 +25.781975 15.107512 0.000000 +26.376152 13.018220 0.000000 +26.229763 14.875529 0.000000 +27.150000 12.947222 0.000000 +26.695093 14.741736 0.000000 +27.923849 13.018220 0.000000 +27.150000 14.700000 0.000000 +28.715425 13.245816 0.000000 +27.604908 14.741736 0.000000 +29.477161 13.640444 0.000000 +28.070236 14.875529 0.000000 +30.157167 14.192832 0.000000 +28.518024 15.107512 0.000000 +30.709557 14.872838 0.000000 +28.917767 15.432233 0.000000 +31.104183 15.634575 0.000000 +29.242489 15.831976 0.000000 +31.331779 16.426151 0.000000 +29.474470 16.279764 0.000000 +31.402779 17.200001 0.000000 +29.608263 16.745092 0.000000 +31.331779 17.973848 0.000000 +29.650000 17.200001 0.000000 +31.104183 18.765425 0.000000 +29.608263 17.654907 0.000000 +30.709557 19.527163 0.000000 +29.474470 18.120237 0.000000 +30.157167 20.207169 0.000000 +29.242489 18.568024 0.000000 +29.477161 20.759556 0.000000 +28.917767 18.967768 0.000000 +28.715425 21.154184 0.000000 +28.518024 19.292488 0.000000 +27.923849 21.381781 0.000000 +28.070236 19.524471 0.000000 +27.150000 21.452778 0.000000 +27.604908 19.658264 0.000000 +26.376152 21.381781 0.000000 +27.150000 19.700001 0.000000 +25.584576 21.154184 0.000000 +26.695093 19.658264 0.000000 +24.822838 20.759556 0.000000 +26.229763 19.524471 0.000000 +24.142832 20.207169 0.000000 +25.781975 19.292488 0.000000 +23.590445 19.527163 0.000000 +25.382233 18.967768 0.000000 +23.195816 18.765425 0.000000 +25.057510 18.568024 0.000000 +22.968220 17.973848 0.000000 +24.825529 18.120237 0.000000 +22.897223 17.200001 0.000000 +24.691736 17.654907 0.000000 +22.968220 16.426151 0.000000 +24.650000 17.200001 0.000000 +23.195816 15.634575 0.000000 +24.691736 16.745092 0.000000 +23.590445 14.872838 0.000000 +24.825529 16.279764 0.000000 +24.142832 14.192832 0.000000 +25.057510 15.831976 0.000000 +24.822838 13.640444 0.000000 +24.825529 18.120237 7.200000 +24.691736 17.654907 7.200000 +24.650000 17.200001 7.200000 +24.650000 17.200001 0.000000 +29.650000 17.200001 0.000000 +29.650000 17.200001 7.200000 +29.608263 17.654907 0.000000 +29.608263 17.654907 7.200000 +29.474470 18.120237 0.000000 +29.242489 18.568024 0.000000 +29.474470 18.120237 7.200000 +28.917767 18.967768 0.000000 +29.242489 18.568024 7.200000 +28.518024 19.292488 0.000000 +28.917767 18.967768 7.200000 +28.518024 19.292488 7.200000 +28.070236 19.524471 0.000000 +28.070236 19.524471 7.200000 +27.604908 19.658264 0.000000 +27.604908 19.658264 7.200000 +27.150000 19.700001 0.000000 +27.150000 19.700001 7.200000 +26.695093 19.658264 0.000000 +26.695093 19.658264 7.200000 +26.229763 19.524471 0.000000 +26.229763 19.524471 7.200000 +25.781975 19.292488 0.000000 +25.382233 18.967768 0.000000 +25.781975 19.292488 7.200000 +25.382233 18.967768 7.200000 +25.057510 18.568024 0.000000 +25.057510 18.568024 7.200000 +24.825529 18.120237 0.000000 +24.691736 17.654907 0.000000 +39.400002 47.751884 3.686749 +39.400002 48.035110 3.482548 +39.400002 48.050819 4.382547 +39.400002 48.031300 4.202608 +39.400002 47.975662 4.019274 +39.400002 47.881760 3.843408 +39.400002 42.033749 3.400000 +39.400002 42.018036 2.500000 +39.400002 47.050972 3.400000 +39.400002 47.035263 2.500000 +39.400002 47.215519 2.516380 +39.400002 47.231228 3.416380 +39.400002 47.399796 2.568808 +39.400002 47.577271 2.659627 +39.400002 47.415504 3.468808 +39.400002 47.736172 2.786750 +39.400002 47.866051 2.943408 +39.400002 47.592983 3.559627 +39.400002 47.959953 3.119274 +39.400002 48.015587 3.302608 +42.504429 46.386642 3.400000 +46.151562 41.550362 3.400000 +46.333519 41.533672 3.400000 +45.965450 41.603870 3.400000 +45.786366 41.696640 3.400000 +45.626499 41.826500 3.400000 +45.496639 41.986366 3.400000 +45.333672 47.033825 3.400000 +43.393829 45.894474 3.400000 +43.436646 45.745571 3.400000 +43.450001 45.599998 3.400000 +43.436646 45.454430 3.400000 +43.393829 45.305523 3.400000 +43.319595 45.162231 3.400000 +45.403870 42.165451 3.400000 +43.215687 45.034313 3.400000 +45.350361 42.351563 3.400000 +39.400002 47.050972 3.400000 +45.333523 47.050972 3.400000 +43.087769 44.930405 3.400000 +45.333672 42.533520 3.400000 +42.944477 44.856171 3.400000 +42.795570 44.813354 3.400000 +42.650002 44.799999 3.400000 +42.504429 44.813354 3.400000 +42.355526 44.856171 3.400000 +42.212231 44.930405 3.400000 +42.084316 45.034313 3.400000 +43.319595 46.037769 3.400000 +41.980404 45.162231 3.400000 +39.900002 41.533672 3.400000 +39.809017 41.542019 3.400000 +39.715954 41.568783 3.400000 +39.626396 41.615185 3.400000 +39.546448 41.680141 3.400000 +39.481503 41.760101 3.400000 +39.435104 41.849670 3.400000 +39.408348 41.942753 3.400000 +39.400002 42.033749 3.400000 +41.906170 45.305523 3.400000 +41.863358 45.454430 3.400000 +41.849998 45.599998 3.400000 +41.863358 45.745571 3.400000 +41.906170 45.894474 3.400000 +41.980404 46.037769 3.400000 +42.084316 46.165684 3.400000 +43.215687 46.165684 3.400000 +42.212231 46.269596 3.400000 +43.087769 46.269596 3.400000 +42.355526 46.343830 3.400000 +42.944477 46.343830 3.400000 +42.795570 46.386642 3.400000 +42.650002 46.400002 3.400000 +14.900000 47.592983 3.559627 +14.900000 48.031300 4.202608 +14.900000 48.050819 4.382547 +14.900000 47.975662 4.019274 +14.900000 47.881760 3.843408 +14.900000 47.751884 3.686749 +14.900000 47.035263 2.500000 +14.900000 42.018036 2.500000 +14.900000 42.033749 3.400000 +14.900000 47.215519 2.516380 +14.900000 47.050972 3.400000 +14.900000 47.399796 2.568808 +14.900000 47.577271 2.659627 +14.900000 47.736172 2.786750 +14.900000 47.231228 3.416380 +14.900000 47.866051 2.943408 +14.900000 47.959953 3.119274 +14.900000 47.415504 3.468808 +14.900000 48.015587 3.302608 +14.900000 48.035110 3.482548 +11.944476 46.343830 3.400000 +14.400000 41.533672 3.400000 +7.966482 41.533672 3.400000 +8.148438 41.550362 3.400000 +8.334549 41.603870 3.400000 +8.513635 41.696640 3.400000 +8.673499 41.826500 3.400000 +8.966330 42.533520 3.400000 +10.980404 46.037769 3.400000 +10.906169 45.894474 3.400000 +10.863356 45.745571 3.400000 +10.850000 45.599998 3.400000 +10.863356 45.454430 3.400000 +10.906169 45.305523 3.400000 +8.803359 41.986366 3.400000 +10.980404 45.162231 3.400000 +8.896132 42.165451 3.400000 +8.966330 47.033825 3.400000 +8.966476 47.050972 3.400000 +11.084314 45.034313 3.400000 +8.949637 42.351563 3.400000 +11.212233 44.930405 3.400000 +11.355524 44.856171 3.400000 +11.504430 44.813354 3.400000 +11.650000 44.799999 3.400000 +11.795570 44.813354 3.400000 +11.944476 44.856171 3.400000 +12.087768 44.930405 3.400000 +11.084314 46.165684 3.400000 +12.215686 45.034313 3.400000 +14.490981 41.542019 3.400000 +14.584047 41.568783 3.400000 +14.673605 41.615185 3.400000 +14.753553 41.680141 3.400000 +14.818498 41.760101 3.400000 +14.864894 41.849670 3.400000 +14.891653 41.942753 3.400000 +14.900000 42.033749 3.400000 +14.900000 47.050972 3.400000 +12.319596 45.162231 3.400000 +12.393830 45.305523 3.400000 +12.436645 45.454430 3.400000 +12.450000 45.599998 3.400000 +12.436645 45.745571 3.400000 +12.393830 45.894474 3.400000 +12.319596 46.037769 3.400000 +11.212233 46.269596 3.400000 +12.215686 46.165684 3.400000 +11.355524 46.343830 3.400000 +12.087768 46.269596 3.400000 +11.504430 46.386642 3.400000 +11.650000 46.400002 3.400000 +11.795570 46.386642 3.400000 +10.906169 45.894474 3.400000 +10.863356 45.745571 7.200000 +10.850000 45.599998 7.200000 +10.850000 45.599998 3.400000 +10.863356 45.745571 3.400000 +10.906169 45.894474 7.200000 +12.450000 45.599998 3.400000 +12.450000 45.599998 7.200000 +12.436645 45.745571 3.400000 +12.393830 45.894474 3.400000 +12.436645 45.745571 7.200000 +12.319596 46.037769 3.400000 +12.393830 45.894474 7.200000 +12.215686 46.165684 3.400000 +12.319596 46.037769 7.200000 +12.215686 46.165684 7.200000 +12.087768 46.269596 3.400000 +12.087768 46.269596 7.200000 +11.944476 46.343830 3.400000 +11.944476 46.343830 7.200000 +11.795570 46.386642 3.400000 +11.795570 46.386642 7.200000 +11.650000 46.400002 3.400000 +11.650000 46.400002 7.200000 +11.504430 46.386642 3.400000 +11.504430 46.386642 7.200000 +11.355524 46.343830 3.400000 +11.355524 46.343830 7.200000 +11.212233 46.269596 3.400000 +11.084314 46.165684 3.400000 +11.212233 46.269596 7.200000 +10.980404 46.037769 3.400000 +11.084314 46.165684 7.200000 +10.980404 46.037769 7.200000 +42.355526 46.343830 3.400000 +41.863358 45.745571 7.200000 +41.849998 45.599998 7.200000 +41.849998 45.599998 3.400000 +41.863358 45.745571 3.400000 +41.906170 45.894474 7.200000 +41.906170 45.894474 3.400000 +41.980404 46.037769 7.200000 +41.980404 46.037769 3.400000 +42.084316 46.165684 7.200000 +42.212231 46.269596 7.200000 +42.084316 46.165684 3.400000 +42.212231 46.269596 3.400000 +42.355526 46.343830 7.200000 +43.450001 45.599998 3.400000 +43.450001 45.599998 7.200000 +43.436646 45.745571 3.400000 +43.393829 45.894474 3.400000 +43.436646 45.745571 7.200000 +43.393829 45.894474 7.200000 +43.319595 46.037769 3.400000 +43.319595 46.037769 7.200000 +43.215687 46.165684 3.400000 +43.215687 46.165684 7.200000 +43.087769 46.269596 3.400000 +42.944477 46.343830 3.400000 +43.087769 46.269596 7.200000 +42.795570 46.386642 3.400000 +42.944477 46.343830 7.200000 +42.795570 46.386642 7.200000 +42.650002 46.400002 3.400000 +42.650002 46.400002 7.200000 +42.504429 46.386642 3.400000 +42.504429 46.386642 7.200000 +45.943558 9.204490 2.500000 +43.085060 7.582122 5.700000 +43.049999 7.200000 5.700000 +42.994144 7.200000 2.500000 +43.030136 7.592286 2.500000 +43.197445 7.972999 5.700000 +43.145512 7.993559 2.500000 +43.392311 8.349140 5.700000 +43.665077 8.684924 5.700000 +43.345558 8.379705 2.500000 +44.000858 8.957690 5.700000 +43.625580 8.724421 2.500000 +43.970295 9.004442 2.500000 +44.377003 9.152555 5.700000 +44.767879 9.264941 5.700000 +44.356441 9.204490 2.500000 +45.150002 9.300000 5.700000 +44.757713 9.319865 2.500000 +45.532124 9.264941 5.700000 +45.150002 9.355856 2.500000 +45.542286 9.319865 2.500000 +45.923000 9.152555 5.700000 +47.305855 7.200000 2.500000 +47.250000 7.200000 5.700000 +47.269863 7.592286 2.500000 +47.154491 7.993559 2.500000 +47.214943 7.582122 5.700000 +46.954441 8.379705 2.500000 +47.102554 7.972999 5.700000 +46.907692 8.349140 5.700000 +46.674419 8.724421 2.500000 +46.634926 8.684924 5.700000 +46.329704 9.004442 2.500000 +46.299141 8.957690 5.700000 +46.049999 7.200000 5.700000 +47.102554 7.972999 5.700000 +46.034973 7.363767 5.700000 +46.907692 8.349140 5.700000 +45.986809 7.531285 5.700000 +46.634926 8.684924 5.700000 +45.903297 7.692489 5.700000 +46.299141 8.957690 5.700000 +45.786396 7.836396 5.700000 +45.923000 9.152555 5.700000 +45.642490 7.953296 5.700000 +45.532124 9.264941 5.700000 +45.481285 8.036810 5.700000 +45.150002 9.300000 5.700000 +45.313766 8.084975 5.700000 +44.767879 9.264941 5.700000 +45.150002 8.100000 5.700000 +44.377003 9.152555 5.700000 +44.986233 8.084975 5.700000 +44.000858 8.957690 5.700000 +44.818714 8.036810 5.700000 +43.665077 8.684924 5.700000 +44.657513 7.953296 5.700000 +43.392311 8.349140 5.700000 +44.513603 7.836396 5.700000 +43.197445 7.972999 5.700000 +44.396706 7.692489 5.700000 +43.085060 7.582122 5.700000 +44.313190 7.531285 5.700000 +43.049999 7.200000 5.700000 +44.265026 7.363767 5.700000 +43.085060 6.817878 5.700000 +44.250000 7.200000 5.700000 +43.197445 6.427001 5.700000 +44.265026 7.036233 5.700000 +43.392311 6.050859 5.700000 +44.313190 6.868715 5.700000 +43.665077 5.715076 5.700000 +44.396706 6.707511 5.700000 +44.000858 5.442309 5.700000 +44.513603 6.563604 5.700000 +44.377003 5.247445 5.700000 +44.657513 6.446704 5.700000 +44.767879 5.135059 5.700000 +44.818714 6.363191 5.700000 +45.150002 5.100000 5.700000 +44.986233 6.315025 5.700000 +45.532124 5.135059 5.700000 +45.150002 6.300000 5.700000 +45.923000 5.247445 5.700000 +45.313766 6.315025 5.700000 +46.299141 5.442309 5.700000 +45.481285 6.363191 5.700000 +46.634926 5.715076 5.700000 +45.642490 6.446704 5.700000 +46.907692 6.050859 5.700000 +45.786396 6.563604 5.700000 +47.102554 6.427001 5.700000 +45.903297 6.707511 5.700000 +47.214943 6.817878 5.700000 +45.986809 6.868715 5.700000 +47.250000 7.200000 5.700000 +46.034973 7.036233 5.700000 +47.214943 7.582122 5.700000 +7.050000 7.200000 5.700000 +6.994144 7.200000 2.500000 +11.305856 7.200000 2.500000 +11.250000 7.200000 5.700000 +11.269865 7.592286 2.500000 +11.154490 7.993559 2.500000 +11.214941 7.582122 5.700000 +11.102555 7.972999 5.700000 +10.954442 8.379705 2.500000 +10.674420 8.724421 2.500000 +10.907691 8.349140 5.700000 +10.329705 9.004442 2.500000 +10.634924 8.684924 5.700000 +10.299141 8.957690 5.700000 +9.943560 9.204490 2.500000 +9.922998 9.152555 5.700000 +9.542286 9.319865 2.500000 +9.150000 9.355856 2.500000 +9.532123 9.264941 5.700000 +9.150000 9.300000 5.700000 +8.757714 9.319865 2.500000 +8.767878 9.264941 5.700000 +8.356441 9.204490 2.500000 +8.377001 9.152555 5.700000 +7.970294 9.004442 2.500000 +8.000859 8.957690 5.700000 +7.625579 8.724421 2.500000 +7.665076 8.684924 5.700000 +7.345558 8.379705 2.500000 +7.392309 8.349140 5.700000 +7.145510 7.993559 2.500000 +7.197444 7.972999 5.700000 +7.030135 7.592286 2.500000 +7.085059 7.582122 5.700000 +9.786396 6.563604 5.700000 +11.102555 6.427001 5.700000 +9.903296 6.707511 5.700000 +11.214941 6.817878 5.700000 +9.986810 6.868715 5.700000 +11.250000 7.200000 5.700000 +10.034975 7.036233 5.700000 +11.214941 7.582122 5.700000 +10.050000 7.200000 5.700000 +11.102555 7.972999 5.700000 +10.034975 7.363767 5.700000 +10.907691 8.349140 5.700000 +9.986810 7.531285 5.700000 +10.634924 8.684924 5.700000 +9.903296 7.692489 5.700000 +10.299141 8.957690 5.700000 +9.786396 7.836396 5.700000 +9.922998 9.152555 5.700000 +9.642488 7.953296 5.700000 +9.532123 9.264941 5.700000 +9.481285 8.036810 5.700000 +9.150000 9.300000 5.700000 +9.313766 8.084975 5.700000 +8.767878 9.264941 5.700000 +9.150000 8.100000 5.700000 +8.377001 9.152555 5.700000 +8.986234 8.084975 5.700000 +8.000859 8.957690 5.700000 +8.818715 8.036810 5.700000 +7.665076 8.684924 5.700000 +8.657511 7.953296 5.700000 +7.392309 8.349140 5.700000 +8.513604 7.836396 5.700000 +7.197444 7.972999 5.700000 +8.396704 7.692489 5.700000 +7.085059 7.582122 5.700000 +8.313190 7.531285 5.700000 +7.050000 7.200000 5.700000 +8.265025 7.363767 5.700000 +7.085059 6.817878 5.700000 +8.250000 7.200000 5.700000 +7.197444 6.427001 5.700000 +8.265025 7.036233 5.700000 +7.392309 6.050859 5.700000 +8.313190 6.868715 5.700000 +7.665076 5.715076 5.700000 +8.396704 6.707511 5.700000 +8.000859 5.442309 5.700000 +8.513604 6.563604 5.700000 +8.377001 5.247445 5.700000 +8.657511 6.446704 5.700000 +8.767878 5.135059 5.700000 +8.818715 6.363191 5.700000 +9.150000 5.100000 5.700000 +8.986234 6.315025 5.700000 +9.532123 5.135059 5.700000 +9.150000 6.300000 5.700000 +9.922998 5.247445 5.700000 +9.313766 6.315025 5.700000 +10.299141 5.442309 5.700000 +9.481285 6.363191 5.700000 +10.634924 5.715076 5.700000 +9.642488 6.446704 5.700000 +10.907691 6.050859 5.700000 +40.375580 39.724419 2.500000 +39.835060 38.582123 5.700000 +39.799999 38.200001 5.700000 +39.744144 38.200001 2.500000 +39.947445 38.973000 5.700000 +39.780136 38.592285 2.500000 +39.895512 38.993561 2.500000 +40.142311 39.349140 5.700000 +40.415077 39.684925 5.700000 +40.095558 39.379707 2.500000 +44.055855 38.200001 2.500000 +44.000000 38.200001 5.700000 +44.019863 38.592285 2.500000 +43.964943 38.582123 5.700000 +43.904491 38.993561 2.500000 +43.704441 39.379707 2.500000 +43.852554 38.973000 5.700000 +43.657692 39.349140 5.700000 +43.424419 39.724419 2.500000 +43.384926 39.684925 5.700000 +43.079704 40.004440 2.500000 +42.693558 40.204491 2.500000 +43.049141 39.957691 5.700000 +42.292286 40.319866 2.500000 +42.673000 40.152554 5.700000 +42.282124 40.264942 5.700000 +41.900002 40.355858 2.500000 +41.900002 40.299999 5.700000 +41.507713 40.319866 2.500000 +41.106441 40.204491 2.500000 +41.517879 40.264942 5.700000 +41.127003 40.152554 5.700000 +40.720295 40.004440 2.500000 +40.750858 39.957691 5.700000 +42.231285 39.036808 5.700000 +41.900002 40.299999 5.700000 +42.063766 39.084976 5.700000 +41.517879 40.264942 5.700000 +41.900002 39.099998 5.700000 +41.127003 40.152554 5.700000 +41.736233 39.084976 5.700000 +40.750858 39.957691 5.700000 +41.568714 39.036808 5.700000 +40.415077 39.684925 5.700000 +41.407513 38.953297 5.700000 +40.142311 39.349140 5.700000 +41.263603 38.836395 5.700000 +39.947445 38.973000 5.700000 +41.146706 38.692490 5.700000 +39.835060 38.582123 5.700000 +41.063190 38.531284 5.700000 +39.799999 38.200001 5.700000 +41.015026 38.363766 5.700000 +39.835060 37.817879 5.700000 +41.000000 38.200001 5.700000 +39.947445 37.427002 5.700000 +41.015026 38.036232 5.700000 +40.142311 37.050861 5.700000 +41.063190 37.868713 5.700000 +40.415077 36.715076 5.700000 +41.146706 37.707512 5.700000 +40.750858 36.442310 5.700000 +41.263603 37.563602 5.700000 +41.127003 36.247444 5.700000 +41.407513 37.446705 5.700000 +41.517879 36.135059 5.700000 +41.568714 37.363190 5.700000 +41.900002 36.099998 5.700000 +41.736233 37.315025 5.700000 +42.282124 36.135059 5.700000 +41.900002 37.299999 5.700000 +42.673000 36.247444 5.700000 +42.063766 37.315025 5.700000 +43.049141 36.442310 5.700000 +42.231285 37.363190 5.700000 +43.384926 36.715076 5.700000 +42.392490 37.446705 5.700000 +43.657692 37.050861 5.700000 +42.536396 37.563602 5.700000 +43.852554 37.427002 5.700000 +42.653297 37.707512 5.700000 +43.964943 37.817879 5.700000 +42.736809 37.868713 5.700000 +44.000000 38.200001 5.700000 +42.784973 38.036232 5.700000 +43.964943 38.582123 5.700000 +42.799999 38.200001 5.700000 +43.852554 38.973000 5.700000 +42.784973 38.363766 5.700000 +43.657692 39.349140 5.700000 +42.736809 38.531284 5.700000 +43.384926 39.684925 5.700000 +42.653297 38.692490 5.700000 +43.049141 39.957691 5.700000 +42.536396 38.836395 5.700000 +42.673000 40.152554 5.700000 +42.392490 38.953297 5.700000 +42.282124 40.264942 5.700000 +14.555856 38.200001 2.500000 +14.500000 38.200001 5.700000 +10.335059 38.582123 5.700000 +10.300000 38.200001 5.700000 +10.244143 38.200001 2.500000 +10.447445 38.973000 5.700000 +10.280135 38.592285 2.500000 +10.642309 39.349140 5.700000 +10.395510 38.993561 2.500000 +10.915075 39.684925 5.700000 +10.595558 39.379707 2.500000 +11.250859 39.957691 5.700000 +10.875580 39.724419 2.500000 +11.627001 40.152554 5.700000 +11.220294 40.004440 2.500000 +11.606441 40.204491 2.500000 +12.017878 40.264942 5.700000 +12.400000 40.299999 5.700000 +12.007714 40.319866 2.500000 +12.782123 40.264942 5.700000 +12.400000 40.355858 2.500000 +12.792286 40.319866 2.500000 +13.172998 40.152554 5.700000 +13.549141 39.957691 5.700000 +13.193560 40.204491 2.500000 +13.884924 39.684925 5.700000 +13.579705 40.004440 2.500000 +14.157691 39.349140 5.700000 +13.924420 39.724419 2.500000 +14.204442 39.379707 2.500000 +14.352555 38.973000 5.700000 +14.404490 38.993561 2.500000 +14.464941 38.582123 5.700000 +14.519865 38.592285 2.500000 +13.153296 38.692490 5.700000 +13.549141 39.957691 5.700000 +13.036396 38.836395 5.700000 +13.172998 40.152554 5.700000 +12.892488 38.953297 5.700000 +12.782123 40.264942 5.700000 +12.731285 39.036808 5.700000 +12.400000 40.299999 5.700000 +12.563766 39.084976 5.700000 +12.017878 40.264942 5.700000 +12.400000 39.099998 5.700000 +11.627001 40.152554 5.700000 +12.236234 39.084976 5.700000 +11.250859 39.957691 5.700000 +12.068715 39.036808 5.700000 +10.915075 39.684925 5.700000 +11.907511 38.953297 5.700000 +10.642309 39.349140 5.700000 +11.763604 38.836395 5.700000 +10.447445 38.973000 5.700000 +11.646704 38.692490 5.700000 +10.335059 38.582123 5.700000 +11.563190 38.531284 5.700000 +10.300000 38.200001 5.700000 +11.515025 38.363766 5.700000 +10.335059 37.817879 5.700000 +11.500000 38.200001 5.700000 +10.447445 37.427002 5.700000 +11.515025 38.036232 5.700000 +10.642309 37.050861 5.700000 +11.563190 37.868713 5.700000 +10.915075 36.715076 5.700000 +11.646704 37.707512 5.700000 +11.250859 36.442310 5.700000 +11.763604 37.563602 5.700000 +11.627001 36.247444 5.700000 +11.907511 37.446705 5.700000 +12.017878 36.135059 5.700000 +12.068715 37.363190 5.700000 +12.400000 36.099998 5.700000 +12.236234 37.315025 5.700000 +12.782123 36.135059 5.700000 +12.400000 37.299999 5.700000 +13.172998 36.247444 5.700000 +12.563766 37.315025 5.700000 +13.549141 36.442310 5.700000 +12.731285 37.363190 5.700000 +13.884924 36.715076 5.700000 +12.892488 37.446705 5.700000 +14.157691 37.050861 5.700000 +13.036396 37.563602 5.700000 +14.352555 37.427002 5.700000 +13.153296 37.707512 5.700000 +14.464941 37.817879 5.700000 +13.236810 37.868713 5.700000 +14.500000 38.200001 5.700000 +13.284975 38.036232 5.700000 +14.464941 38.582123 5.700000 +13.300000 38.200001 5.700000 +14.352555 38.973000 5.700000 +13.284975 38.363766 5.700000 +14.157691 39.349140 5.700000 +13.236810 38.531284 5.700000 +13.884924 39.684925 5.700000 +10.400000 38.200001 7.200000 +10.400000 38.200001 7.000000 +14.366611 38.563927 7.000000 +14.400000 38.200001 7.000000 +14.400000 38.200001 7.200000 +14.259577 38.936188 7.000000 +14.366611 38.563927 7.200000 +14.259577 38.936188 7.200000 +14.073991 39.294418 7.000000 +14.073991 39.294418 7.200000 +13.814214 39.614212 7.000000 +13.814214 39.614212 7.200000 +13.494419 39.873993 7.000000 +13.494419 39.873993 7.200000 +13.136189 40.059578 7.000000 +13.136189 40.059578 7.200000 +12.763927 40.166611 7.000000 +12.763927 40.166611 7.200000 +12.400000 40.200001 7.000000 +12.400000 40.200001 7.200000 +12.036074 40.166611 7.000000 +12.036074 40.166611 7.200000 +11.663811 40.059578 7.000000 +11.663811 40.059578 7.200000 +11.305580 39.873993 7.000000 +11.305580 39.873993 7.200000 +10.985786 39.614212 7.000000 +10.985786 39.614212 7.200000 +10.726009 39.294418 7.000000 +10.726009 39.294418 7.200000 +10.540423 38.936188 7.000000 +10.540423 38.936188 7.200000 +10.433390 38.563927 7.000000 +10.433390 38.563927 7.200000 +12.063369 40.019115 7.000000 +12.763927 40.166611 7.000000 +12.400000 40.049999 7.000000 +13.136189 40.059578 7.000000 +12.736631 40.019115 7.000000 +13.494419 39.873993 7.000000 +13.080976 39.920109 7.000000 +13.814214 39.614212 7.000000 +13.412338 39.748440 7.000000 +14.073991 39.294418 7.000000 +13.708148 39.508148 7.000000 +14.259577 38.936188 7.000000 +13.948442 39.212337 7.000000 +14.366611 38.563927 7.000000 +14.120109 38.880974 7.000000 +14.400000 38.200001 7.000000 +14.219115 38.536633 7.000000 +14.366611 37.836075 7.000000 +14.250000 38.200001 7.000000 +14.259577 37.463810 7.000000 +14.219115 37.863369 7.000000 +14.073991 37.105579 7.000000 +14.120109 37.519024 7.000000 +13.814214 36.785786 7.000000 +13.948442 37.187660 7.000000 +13.494419 36.526009 7.000000 +13.708148 36.891853 7.000000 +13.136189 36.340424 7.000000 +13.412338 36.651558 7.000000 +12.763927 36.233391 7.000000 +13.080976 36.479893 7.000000 +12.400000 36.200001 7.000000 +12.736631 36.380886 7.000000 +12.036074 36.233391 7.000000 +12.400000 36.349998 7.000000 +11.663811 36.340424 7.000000 +12.063369 36.380886 7.000000 +11.305580 36.526009 7.000000 +11.719025 36.479893 7.000000 +10.985786 36.785786 7.000000 +11.387662 36.651558 7.000000 +10.726009 37.105579 7.000000 +11.091852 36.891853 7.000000 +10.540423 37.463810 7.000000 +10.851559 37.187660 7.000000 +10.433390 37.836075 7.000000 +10.679892 37.519024 7.000000 +10.400000 38.200001 7.000000 +10.580885 37.863369 7.000000 +10.433390 38.563927 7.000000 +10.550000 38.200001 7.000000 +10.540423 38.936188 7.000000 +10.580885 38.536633 7.000000 +10.726009 39.294418 7.000000 +10.679892 38.880974 7.000000 +10.985786 39.614212 7.000000 +10.851559 39.212337 7.000000 +11.305580 39.873993 7.000000 +11.091852 39.508148 7.000000 +11.663811 40.059578 7.000000 +11.387662 39.748440 7.000000 +12.036074 40.166611 7.000000 +11.719025 39.920109 7.000000 +12.400000 40.200001 7.000000 +39.900002 38.200001 7.200000 +39.900002 38.200001 7.000000 +43.866611 38.563927 7.000000 +43.900002 38.200001 7.000000 +43.900002 38.200001 7.200000 +43.866611 38.563927 7.200000 +43.759575 38.936188 7.000000 +43.573990 39.294418 7.000000 +43.759575 38.936188 7.200000 +43.314213 39.614212 7.000000 +43.573990 39.294418 7.200000 +43.314213 39.614212 7.200000 +42.994419 39.873993 7.000000 +42.636189 40.059578 7.000000 +42.994419 39.873993 7.200000 +42.636189 40.059578 7.200000 +42.263927 40.166611 7.000000 +42.263927 40.166611 7.200000 +41.900002 40.200001 7.000000 +41.536076 40.166611 7.000000 +41.900002 40.200001 7.200000 +41.536076 40.166611 7.200000 +41.163811 40.059578 7.000000 +41.163811 40.059578 7.200000 +40.805580 39.873993 7.000000 +40.805580 39.873993 7.200000 +40.485786 39.614212 7.000000 +40.485786 39.614212 7.200000 +40.226009 39.294418 7.000000 +40.226009 39.294418 7.200000 +40.040424 38.936188 7.000000 +40.040424 38.936188 7.200000 +39.933388 38.563927 7.000000 +39.933388 38.563927 7.200000 +41.900002 40.049999 7.000000 +42.636189 40.059578 7.000000 +42.236633 40.019115 7.000000 +42.994419 39.873993 7.000000 +42.580975 39.920109 7.000000 +43.314213 39.614212 7.000000 +42.912338 39.748440 7.000000 +43.573990 39.294418 7.000000 +43.208149 39.508148 7.000000 +43.759575 38.936188 7.000000 +43.448441 39.212337 7.000000 +43.866611 38.563927 7.000000 +43.620110 38.880974 7.000000 +43.900002 38.200001 7.000000 +43.719116 38.536633 7.000000 +43.866611 37.836075 7.000000 +43.750000 38.200001 7.000000 +43.759575 37.463810 7.000000 +43.719116 37.863369 7.000000 +43.573990 37.105579 7.000000 +43.620110 37.519024 7.000000 +43.314213 36.785786 7.000000 +43.448441 37.187660 7.000000 +42.994419 36.526009 7.000000 +43.208149 36.891853 7.000000 +42.636189 36.340424 7.000000 +42.912338 36.651558 7.000000 +42.263927 36.233391 7.000000 +42.580975 36.479893 7.000000 +41.900002 36.200001 7.000000 +42.236633 36.380886 7.000000 +41.536076 36.233391 7.000000 +41.900002 36.349998 7.000000 +41.163811 36.340424 7.000000 +41.563370 36.380886 7.000000 +40.805580 36.526009 7.000000 +41.219025 36.479893 7.000000 +40.485786 36.785786 7.000000 +40.887661 36.651558 7.000000 +40.226009 37.105579 7.000000 +40.591854 36.891853 7.000000 +40.040424 37.463810 7.000000 +40.351559 37.187660 7.000000 +39.933388 37.836075 7.000000 +40.179893 37.519024 7.000000 +39.900002 38.200001 7.000000 +40.080887 37.863369 7.000000 +39.933388 38.563927 7.000000 +40.049999 38.200001 7.000000 +40.040424 38.936188 7.000000 +40.080887 38.536633 7.000000 +40.226009 39.294418 7.000000 +40.179893 38.880974 7.000000 +40.485786 39.614212 7.000000 +40.351559 39.212337 7.000000 +40.805580 39.873993 7.000000 +40.591854 39.508148 7.000000 +41.163811 40.059578 7.000000 +40.887661 39.748440 7.000000 +41.536076 40.166611 7.000000 +41.219025 39.920109 7.000000 +41.900002 40.200001 7.000000 +41.563370 40.019115 7.000000 +42.263927 40.166611 7.000000 +11.150000 7.200000 7.000000 +11.150000 7.200000 7.200000 +7.183389 7.563926 7.200000 +7.150000 7.200000 7.200000 +7.150000 7.200000 7.000000 +7.290423 7.936190 7.200000 +7.183389 7.563926 7.000000 +7.290423 7.936190 7.000000 +7.476009 8.294419 7.200000 +7.476009 8.294419 7.000000 +7.735786 8.614214 7.200000 +7.735786 8.614214 7.000000 +8.055580 8.873991 7.200000 +8.055580 8.873991 7.000000 +8.413811 9.059577 7.200000 +8.413811 9.059577 7.000000 +8.786074 9.166611 7.200000 +8.786074 9.166611 7.000000 +9.150000 9.200000 7.200000 +9.150000 9.200000 7.000000 +9.513927 9.166611 7.200000 +9.513927 9.166611 7.000000 +9.886189 9.059577 7.200000 +9.886189 9.059577 7.000000 +10.244419 8.873991 7.200000 +10.244419 8.873991 7.000000 +10.564214 8.614214 7.200000 +10.564214 8.614214 7.000000 +10.823991 8.294419 7.200000 +10.823991 8.294419 7.000000 +11.009577 7.936190 7.200000 +11.009577 7.936190 7.000000 +11.116611 7.563926 7.200000 +11.116611 7.563926 7.000000 +11.000000 7.200000 7.000000 +11.009577 6.463810 7.000000 +10.969115 6.863369 7.000000 +10.823991 6.105580 7.000000 +10.870109 6.519025 7.000000 +10.564214 5.785787 7.000000 +10.698442 6.187662 7.000000 +10.244419 5.526009 7.000000 +10.458148 5.891852 7.000000 +9.886189 5.340424 7.000000 +10.162338 5.651558 7.000000 +9.513927 5.233389 7.000000 +9.830976 5.479892 7.000000 +9.150000 5.200000 7.000000 +9.486631 5.380885 7.000000 +8.786074 5.233389 7.000000 +9.150000 5.350000 7.000000 +8.413811 5.340424 7.000000 +8.813369 5.380885 7.000000 +8.055580 5.526009 7.000000 +8.469025 5.479892 7.000000 +7.735786 5.785787 7.000000 +8.137662 5.651558 7.000000 +7.476009 6.105580 7.000000 +7.841853 5.891852 7.000000 +7.290423 6.463810 7.000000 +7.601558 6.187662 7.000000 +7.183389 6.836074 7.000000 +7.429892 6.519025 7.000000 +7.150000 7.200000 7.000000 +7.330885 6.863369 7.000000 +7.183389 7.563926 7.000000 +7.300000 7.200000 7.000000 +7.290423 7.936190 7.000000 +7.330885 7.536632 7.000000 +7.476009 8.294419 7.000000 +7.429892 7.880975 7.000000 +7.735786 8.614214 7.000000 +7.601558 8.212338 7.000000 +8.055580 8.873991 7.000000 +7.841853 8.508147 7.000000 +8.413811 9.059577 7.000000 +8.137662 8.748442 7.000000 +8.786074 9.166611 7.000000 +8.469025 8.920109 7.000000 +9.150000 9.200000 7.000000 +8.813369 9.019114 7.000000 +9.513927 9.166611 7.000000 +9.150000 9.050000 7.000000 +9.886189 9.059577 7.000000 +9.486631 9.019114 7.000000 +10.244419 8.873991 7.000000 +9.830976 8.920109 7.000000 +10.564214 8.614214 7.000000 +10.162338 8.748442 7.000000 +10.823991 8.294419 7.000000 +10.458148 8.508147 7.000000 +11.009577 7.936190 7.000000 +10.698442 8.212338 7.000000 +11.116611 7.563926 7.000000 +10.870109 7.880975 7.000000 +11.150000 7.200000 7.000000 +10.969115 7.536632 7.000000 +11.116611 6.836074 7.000000 +46.244419 8.873991 7.000000 +47.116611 7.563926 7.000000 +47.150002 7.200000 7.000000 +47.150002 7.200000 7.200000 +47.116611 7.563926 7.200000 +47.009575 7.936190 7.000000 +47.009575 7.936190 7.200000 +46.823990 8.294419 7.000000 +46.564213 8.614214 7.000000 +46.823990 8.294419 7.200000 +43.150002 7.200000 7.200000 +43.150002 7.200000 7.000000 +43.183388 7.563926 7.200000 +43.183388 7.563926 7.000000 +43.290424 7.936190 7.200000 +43.290424 7.936190 7.000000 +43.476009 8.294419 7.200000 +43.476009 8.294419 7.000000 +43.735786 8.614214 7.200000 +44.055580 8.873991 7.200000 +43.735786 8.614214 7.000000 +44.413811 9.059577 7.200000 +44.055580 8.873991 7.000000 +44.413811 9.059577 7.000000 +44.786076 9.166611 7.200000 +44.786076 9.166611 7.000000 +45.150002 9.200000 7.200000 +45.150002 9.200000 7.000000 +45.513927 9.166611 7.200000 +45.513927 9.166611 7.000000 +45.886189 9.059577 7.200000 +45.886189 9.059577 7.000000 +46.244419 8.873991 7.200000 +46.564213 8.614214 7.200000 +46.458149 8.508147 7.000000 +47.009575 7.936190 7.000000 +46.698441 8.212338 7.000000 +47.116611 7.563926 7.000000 +46.870110 7.880975 7.000000 +47.150002 7.200000 7.000000 +46.969116 7.536632 7.000000 +47.116611 6.836074 7.000000 +47.000000 7.200000 7.000000 +47.009575 6.463810 7.000000 +46.969116 6.863369 7.000000 +46.823990 6.105580 7.000000 +46.870110 6.519025 7.000000 +46.564213 5.785787 7.000000 +46.698441 6.187662 7.000000 +46.244419 5.526009 7.000000 +46.458149 5.891852 7.000000 +45.886189 5.340424 7.000000 +46.162338 5.651558 7.000000 +45.513927 5.233389 7.000000 +45.830975 5.479892 7.000000 +45.150002 5.200000 7.000000 +45.486633 5.380885 7.000000 +44.786076 5.233389 7.000000 +45.150002 5.350000 7.000000 +44.413811 5.340424 7.000000 +44.813370 5.380885 7.000000 +44.055580 5.526009 7.000000 +44.469025 5.479892 7.000000 +43.735786 5.785787 7.000000 +44.137661 5.651558 7.000000 +43.476009 6.105580 7.000000 +43.841854 5.891852 7.000000 +43.290424 6.463810 7.000000 +43.601559 6.187662 7.000000 +43.183388 6.836074 7.000000 +43.429893 6.519025 7.000000 +43.150002 7.200000 7.000000 +43.330887 6.863369 7.000000 +43.183388 7.563926 7.000000 +43.299999 7.200000 7.000000 +43.290424 7.936190 7.000000 +43.330887 7.536632 7.000000 +43.476009 8.294419 7.000000 +43.429893 7.880975 7.000000 +43.735786 8.614214 7.000000 +43.601559 8.212338 7.000000 +44.055580 8.873991 7.000000 +43.841854 8.508147 7.000000 +44.413811 9.059577 7.000000 +44.137661 8.748442 7.000000 +44.786076 9.166611 7.000000 +44.469025 8.920109 7.000000 +45.150002 9.200000 7.000000 +44.813370 9.019114 7.000000 +45.513927 9.166611 7.000000 +45.150002 9.050000 7.000000 +45.886189 9.059577 7.000000 +45.486633 9.019114 7.000000 +46.244419 8.873991 7.000000 +45.830975 8.920109 7.000000 +46.564213 8.614214 7.000000 +46.162338 8.748442 7.000000 +46.823990 8.294419 7.000000 +8.313190 7.531285 5.700000 +8.265025 7.363767 6.050000 +8.250000 7.200000 6.050000 +8.250000 7.200000 5.700000 +8.265025 7.363767 5.700000 +8.313190 7.531285 6.050000 +10.050000 7.200000 5.700000 +10.050000 7.200000 6.050000 +10.034975 7.363767 5.700000 +10.034975 7.363767 6.050000 +9.986810 7.531285 5.700000 +9.986810 7.531285 6.050000 +9.903296 7.692489 5.700000 +9.786396 7.836396 5.700000 +9.903296 7.692489 6.050000 +9.642488 7.953296 5.700000 +9.786396 7.836396 6.050000 +9.481285 8.036810 5.700000 +9.642488 7.953296 6.050000 +9.313766 8.084975 5.700000 +9.481285 8.036810 6.050000 +9.150000 8.100000 5.700000 +9.313766 8.084975 6.050000 +9.150000 8.100000 6.050000 +8.986234 8.084975 5.700000 +8.986234 8.084975 6.050000 +8.818715 8.036810 5.700000 +8.818715 8.036810 6.050000 +8.657511 7.953296 5.700000 +8.657511 7.953296 6.050000 +8.513604 7.836396 5.700000 +8.513604 7.836396 6.050000 +8.396704 7.692489 5.700000 +8.396704 7.692489 6.050000 +8.265025 7.363767 6.050000 +7.330885 7.536632 7.000000 +7.300000 7.200000 7.000000 +8.250000 7.200000 6.050000 +10.050000 7.200000 6.050000 +11.000000 7.200000 7.000000 +10.034975 7.363767 6.050000 +10.969115 7.536632 7.000000 +9.986810 7.531285 6.050000 +9.903296 7.692489 6.050000 +10.870109 7.880975 7.000000 +10.698442 8.212338 7.000000 +9.786396 7.836396 6.050000 +10.458148 8.508147 7.000000 +9.642488 7.953296 6.050000 +9.481285 8.036810 6.050000 +10.162338 8.748442 7.000000 +9.830976 8.920109 7.000000 +9.313766 8.084975 6.050000 +9.486631 9.019114 7.000000 +9.150000 8.100000 6.050000 +9.150000 9.050000 7.000000 +8.986234 8.084975 6.050000 +8.813369 9.019114 7.000000 +8.818715 8.036810 6.050000 +8.469025 8.920109 7.000000 +8.657511 7.953296 6.050000 +8.137662 8.748442 7.000000 +8.513604 7.836396 6.050000 +8.396704 7.692489 6.050000 +7.841853 8.508147 7.000000 +7.601558 8.212338 7.000000 +8.313190 7.531285 6.050000 +7.429892 7.880975 7.000000 +44.396706 7.692489 5.700000 +44.250000 7.200000 6.050000 +44.250000 7.200000 5.700000 +44.265026 7.363767 6.050000 +44.313190 7.531285 6.050000 +44.265026 7.363767 5.700000 +44.396706 7.692489 6.050000 +44.313190 7.531285 5.700000 +46.049999 7.200000 5.700000 +46.049999 7.200000 6.050000 +46.034973 7.363767 5.700000 +45.986809 7.531285 5.700000 +46.034973 7.363767 6.050000 +45.903297 7.692489 5.700000 +45.986809 7.531285 6.050000 +45.903297 7.692489 6.050000 +45.786396 7.836396 5.700000 +45.786396 7.836396 6.050000 +45.642490 7.953296 5.700000 +45.481285 8.036810 5.700000 +45.642490 7.953296 6.050000 +45.313766 8.084975 5.700000 +45.481285 8.036810 6.050000 +45.313766 8.084975 6.050000 +45.150002 8.100000 5.700000 +44.986233 8.084975 5.700000 +45.150002 8.100000 6.050000 +44.986233 8.084975 6.050000 +44.818714 8.036810 5.700000 +44.657513 7.953296 5.700000 +44.818714 8.036810 6.050000 +44.657513 7.953296 6.050000 +44.513603 7.836396 5.700000 +44.513603 7.836396 6.050000 +44.265026 7.363767 6.050000 +43.330887 7.536632 7.000000 +43.299999 7.200000 7.000000 +44.250000 7.200000 6.050000 +46.049999 7.200000 6.050000 +47.000000 7.200000 7.000000 +46.034973 7.363767 6.050000 +46.969116 7.536632 7.000000 +45.986809 7.531285 6.050000 +46.870110 7.880975 7.000000 +45.903297 7.692489 6.050000 +45.786396 7.836396 6.050000 +46.698441 8.212338 7.000000 +45.642490 7.953296 6.050000 +46.458149 8.508147 7.000000 +45.481285 8.036810 6.050000 +46.162338 8.748442 7.000000 +45.313766 8.084975 6.050000 +45.830975 8.920109 7.000000 +45.150002 8.100000 6.050000 +45.486633 9.019114 7.000000 +44.986233 8.084975 6.050000 +45.150002 9.050000 7.000000 +44.818714 8.036810 6.050000 +44.813370 9.019114 7.000000 +44.657513 7.953296 6.050000 +44.469025 8.920109 7.000000 +44.513603 7.836396 6.050000 +44.137661 8.748442 7.000000 +43.841854 8.508147 7.000000 +44.396706 7.692489 6.050000 +43.601559 8.212338 7.000000 +44.313190 7.531285 6.050000 +43.429893 7.880975 7.000000 +41.063190 38.531284 5.700000 +41.000000 38.200001 6.050000 +41.000000 38.200001 5.700000 +41.015026 38.363766 6.050000 +41.063190 38.531284 6.050000 +41.015026 38.363766 5.700000 +42.799999 38.200001 5.700000 +42.799999 38.200001 6.050000 +42.784973 38.363766 5.700000 +42.736809 38.531284 5.700000 +42.784973 38.363766 6.050000 +42.736809 38.531284 6.050000 +42.653297 38.692490 5.700000 +42.653297 38.692490 6.050000 +42.536396 38.836395 5.700000 +42.536396 38.836395 6.050000 +42.392490 38.953297 5.700000 +42.392490 38.953297 6.050000 +42.231285 39.036808 5.700000 +42.231285 39.036808 6.050000 +42.063766 39.084976 5.700000 +42.063766 39.084976 6.050000 +41.900002 39.099998 5.700000 +41.900002 39.099998 6.050000 +41.736233 39.084976 5.700000 +41.736233 39.084976 6.050000 +41.568714 39.036808 5.700000 +41.568714 39.036808 6.050000 +41.407513 38.953297 5.700000 +41.263603 38.836395 5.700000 +41.407513 38.953297 6.050000 +41.263603 38.836395 6.050000 +41.146706 38.692490 5.700000 +41.146706 38.692490 6.050000 +40.049999 38.200001 7.000000 +41.000000 38.200001 6.050000 +42.784973 38.363766 6.050000 +42.799999 38.200001 6.050000 +43.750000 38.200001 7.000000 +43.719116 38.536633 7.000000 +42.736809 38.531284 6.050000 +42.653297 38.692490 6.050000 +43.620110 38.880974 7.000000 +42.536396 38.836395 6.050000 +43.448441 39.212337 7.000000 +42.392490 38.953297 6.050000 +43.208149 39.508148 7.000000 +42.912338 39.748440 7.000000 +42.231285 39.036808 6.050000 +42.580975 39.920109 7.000000 +42.063766 39.084976 6.050000 +41.900002 39.099998 6.050000 +42.236633 40.019115 7.000000 +41.736233 39.084976 6.050000 +41.900002 40.049999 7.000000 +41.563370 40.019115 7.000000 +41.568714 39.036808 6.050000 +41.219025 39.920109 7.000000 +41.407513 38.953297 6.050000 +40.887661 39.748440 7.000000 +41.263603 38.836395 6.050000 +40.591854 39.508148 7.000000 +41.146706 38.692490 6.050000 +40.351559 39.212337 7.000000 +41.063190 38.531284 6.050000 +40.179893 38.880974 7.000000 +41.015026 38.363766 6.050000 +40.080887 38.536633 7.000000 +11.763604 38.836395 5.700000 +11.515025 38.363766 6.050000 +11.500000 38.200001 6.050000 +11.500000 38.200001 5.700000 +11.515025 38.363766 5.700000 +11.563190 38.531284 6.050000 +11.563190 38.531284 5.700000 +11.646704 38.692490 6.050000 +11.763604 38.836395 6.050000 +11.646704 38.692490 5.700000 +13.300000 38.200001 5.700000 +13.300000 38.200001 6.050000 +13.284975 38.363766 5.700000 +13.236810 38.531284 5.700000 +13.284975 38.363766 6.050000 +13.153296 38.692490 5.700000 +13.236810 38.531284 6.050000 +13.153296 38.692490 6.050000 +13.036396 38.836395 5.700000 +13.036396 38.836395 6.050000 +12.892488 38.953297 5.700000 +12.731285 39.036808 5.700000 +12.892488 38.953297 6.050000 +12.731285 39.036808 6.050000 +12.563766 39.084976 5.700000 +12.400000 39.099998 5.700000 +12.563766 39.084976 6.050000 +12.400000 39.099998 6.050000 +12.236234 39.084976 5.700000 +12.236234 39.084976 6.050000 +12.068715 39.036808 5.700000 +12.068715 39.036808 6.050000 +11.907511 38.953297 5.700000 +11.907511 38.953297 6.050000 +10.580885 38.536633 7.000000 +10.550000 38.200001 7.000000 +13.300000 38.200001 6.050000 +14.250000 38.200001 7.000000 +13.284975 38.363766 6.050000 +14.219115 38.536633 7.000000 +13.236810 38.531284 6.050000 +13.153296 38.692490 6.050000 +14.120109 38.880974 7.000000 +13.948442 39.212337 7.000000 +13.036396 38.836395 6.050000 +12.892488 38.953297 6.050000 +13.708148 39.508148 7.000000 +13.412338 39.748440 7.000000 +12.731285 39.036808 6.050000 +13.080976 39.920109 7.000000 +12.563766 39.084976 6.050000 +12.736631 40.019115 7.000000 +12.400000 39.099998 6.050000 +12.400000 40.049999 7.000000 +12.236234 39.084976 6.050000 +12.063369 40.019115 7.000000 +12.068715 39.036808 6.050000 +11.907511 38.953297 6.050000 +11.719025 39.920109 7.000000 +11.387662 39.748440 7.000000 +11.763604 38.836395 6.050000 +11.091852 39.508148 7.000000 +11.646704 38.692490 6.050000 +10.851559 39.212337 7.000000 +11.563190 38.531284 6.050000 +10.679892 38.880974 7.000000 +11.515025 38.363766 6.050000 +11.500000 38.200001 6.050000 +0.191494 2.606993 6.549558 +0.171885 3.798046 7.034709 +0.212623 5.073030 7.200000 +1.743557 41.599998 7.200000 +5.854586 41.519325 2.578083 +6.735492 41.517960 2.500000 +4.998812 0.082039 2.500000 +4.356790 0.084517 2.541156 +4.955367 41.523670 2.827114 +3.728481 0.094599 2.663911 +4.087719 41.531185 3.257517 +3.116605 0.117818 2.867736 +2.542082 0.163315 3.145882 +3.305650 41.541698 3.859945 +2.009745 0.243622 3.494917 +2.657373 41.554691 4.604214 +1.531729 0.373129 3.906142 +1.125051 0.563337 4.359320 +2.175905 41.569351 5.444029 +0.790519 0.828947 4.843436 +1.873786 41.584747 6.326080 +0.361291 1.587107 5.784458 +52.426212 41.584747 6.326080 +52.556442 41.599998 7.200000 +49.301189 0.082039 2.500000 +47.564507 41.517960 2.500000 +49.944927 0.084526 2.541375 +50.576759 0.094727 2.665291 +48.445415 41.519325 2.578083 +51.189045 0.118129 2.870038 +49.344635 41.523670 2.827114 +51.765945 0.164196 3.150442 +52.301506 0.245909 3.503416 +50.212280 41.531185 3.257517 +52.777828 0.376552 3.915542 +50.994350 41.541698 3.859945 +53.187630 0.571112 4.375484 +53.517349 0.837152 4.856564 +51.642628 41.554691 4.604214 +53.941730 1.596799 5.793858 +52.124096 41.569351 5.444029 +54.109051 2.615052 6.554118 +54.128025 3.803288 7.036088 +54.087376 5.073030 7.200000 +49.301189 0.082039 2.500000 +50.576759 0.094727 2.665291 +54.111786 4.431468 7.158844 +54.087376 5.073030 7.200000 +0.212623 5.073030 7.200000 +0.188151 4.429753 7.158625 +54.128025 3.803288 7.036088 +54.130447 3.190976 6.832264 +0.171885 3.798046 7.034709 +0.169627 3.185319 6.829962 +54.109051 2.615052 6.554118 +0.191494 2.606993 6.549558 +54.051105 2.079819 6.205082 +0.250709 2.068482 6.196584 +53.941730 1.596799 5.793858 +0.361291 1.587107 5.784458 +53.768719 1.182513 5.340680 +53.517349 0.837152 4.856564 +0.538520 1.169519 5.324516 +0.790519 0.828947 4.843436 +52.777828 0.376552 3.915542 +1.531729 0.373129 3.906142 +51.765945 0.164196 3.150442 +2.542082 0.163315 3.145882 +3.728481 0.094599 2.663911 +4.998812 0.082039 2.500000 +44.528107 48.031300 4.202608 +44.350975 48.050819 4.382547 +45.400002 47.100151 7.200000 +45.333672 47.033825 3.400000 +45.383308 47.282108 7.200000 +45.333523 47.050972 3.400000 +45.329803 47.468220 7.200000 +45.314339 47.231228 3.416380 +45.237030 47.647305 7.200000 +45.259663 47.415504 3.468808 +45.176399 47.730377 7.200000 +45.167385 47.592983 3.559627 +45.107170 47.807171 7.200000 +45.030376 47.876400 7.200000 +45.039757 47.751884 3.686749 +44.947304 47.937031 7.200000 +44.768219 48.029800 7.200000 +44.883606 47.881760 3.843408 +44.582108 48.083309 7.200000 +44.709198 47.975662 4.019274 +44.400154 48.099998 7.200000 +46.217892 41.616692 7.200000 +46.399849 41.599998 7.200000 +45.333672 42.533520 3.400000 +45.400002 42.599846 7.200000 +45.350361 42.351563 3.400000 +45.416691 42.417892 7.200000 +45.403870 42.165451 3.400000 +45.470200 42.231781 7.200000 +45.496639 41.986366 3.400000 +45.562969 42.052696 7.200000 +45.557270 41.903294 3.400000 +45.623600 41.969624 7.200000 +45.626499 41.826500 3.400000 +45.703293 41.757271 3.400000 +45.692829 41.892830 7.200000 +45.786366 41.696640 3.400000 +45.769623 41.823601 7.200000 +45.965450 41.603870 3.400000 +45.852695 41.762970 7.200000 +46.151562 41.550362 3.400000 +46.031780 41.670197 7.200000 +46.333519 41.533672 3.400000 +9.899848 48.099998 7.200000 +9.949026 48.050819 4.382547 +8.966476 47.050972 3.400000 +8.966330 47.033825 3.400000 +8.900000 47.100151 7.200000 +8.985662 47.231228 3.416380 +8.916692 47.282108 7.200000 +9.040336 47.415504 3.468808 +8.970198 47.468220 7.200000 +9.132613 47.592983 3.559627 +9.062970 47.647305 7.200000 +9.260243 47.751884 3.686749 +9.123599 47.730377 7.200000 +9.192830 47.807171 7.200000 +9.416395 47.881760 3.843408 +9.269623 47.876400 7.200000 +9.352695 47.937031 7.200000 +9.590803 47.975662 4.019274 +9.531780 48.029800 7.200000 +9.771892 48.031300 4.202608 +9.717892 48.083309 7.200000 +8.883308 42.417892 7.200000 +8.900000 42.599846 7.200000 +7.966482 41.533672 3.400000 +7.900152 41.599998 7.200000 +8.148438 41.550362 3.400000 +8.082108 41.616692 7.200000 +8.334549 41.603870 3.400000 +8.268220 41.670197 7.200000 +8.513635 41.696640 3.400000 +8.447305 41.762970 7.200000 +8.596706 41.757271 3.400000 +8.530377 41.823601 7.200000 +8.673499 41.826500 3.400000 +8.742730 41.903294 3.400000 +8.607170 41.892830 7.200000 +8.803359 41.986366 3.400000 +8.676401 41.969624 7.200000 +8.896132 42.165451 3.400000 +8.737030 42.052696 7.200000 +8.949637 42.351563 3.400000 +8.829803 42.231781 7.200000 +8.966330 42.533520 3.400000 +31.402779 17.200001 0.000000 +31.609854 17.200001 0.199970 +22.764603 16.388472 0.199970 +22.690147 17.200001 0.199970 +22.897223 17.200001 0.000000 +22.968220 16.426151 0.000000 +23.003281 15.558352 0.199970 +23.417124 14.759525 0.199970 +23.195816 15.634575 0.000000 +23.996408 14.046408 0.199970 +23.590445 14.872838 0.000000 +24.709524 13.467123 0.199970 +24.142832 14.192832 0.000000 +24.822838 13.640444 0.000000 +25.508352 13.053281 0.199970 +25.584576 13.245816 0.000000 +26.338472 12.814603 0.199970 +26.376152 13.018220 0.000000 +27.150000 12.740148 0.199970 +27.150000 12.947222 0.000000 +27.961529 12.814603 0.199970 +28.791649 13.053281 0.199970 +27.923849 13.018220 0.000000 +29.590475 13.467123 0.199970 +28.715425 13.245816 0.000000 +29.477161 13.640444 0.000000 +30.303593 14.046408 0.199970 +30.157167 14.192832 0.000000 +30.882877 14.759525 0.199970 +30.709557 14.872838 0.000000 +31.296719 15.558352 0.199970 +31.104183 15.634575 0.000000 +31.535397 16.388472 0.199970 +31.331779 16.426151 0.000000 +39.400002 42.018036 2.500000 +39.400002 42.033749 3.400000 +39.900002 41.533672 3.400000 +39.900002 41.517960 2.500000 +39.809017 41.542019 3.400000 +39.809017 41.526310 2.500000 +39.715954 41.568783 3.400000 +39.715954 41.553074 2.500000 +39.626396 41.615185 3.400000 +39.626396 41.599476 2.500000 +39.584850 41.645512 3.400000 +39.584850 41.629803 2.500000 +39.546448 41.680141 3.400000 +39.546448 41.664429 2.500000 +39.511822 41.718552 3.400000 +39.511822 41.702839 2.500000 +39.481503 41.760101 3.400000 +39.481503 41.744392 2.500000 +39.435104 41.849670 3.400000 +39.435104 41.833961 2.500000 +39.408348 41.942753 3.400000 +39.408348 41.927040 2.500000 +14.490981 41.526310 2.500000 +14.400000 41.517960 2.500000 +14.891653 41.942753 3.400000 +14.900000 42.033749 3.400000 +14.900000 42.018036 2.500000 +14.864894 41.849670 3.400000 +14.891653 41.927040 2.500000 +14.818498 41.760101 3.400000 +14.864894 41.833961 2.500000 +14.788177 41.718552 3.400000 +14.818498 41.744392 2.500000 +14.753553 41.680141 3.400000 +14.788177 41.702839 2.500000 +14.715149 41.645512 3.400000 +14.753553 41.664429 2.500000 +14.673605 41.615185 3.400000 +14.715149 41.629803 2.500000 +14.584047 41.568783 3.400000 +14.673605 41.599476 2.500000 +14.490981 41.542019 3.400000 +14.584047 41.553074 2.500000 +14.400000 41.533672 3.400000 +39.400002 48.050819 4.382547 +44.350975 48.050819 4.382547 +45.314339 47.231228 3.416380 +45.333523 47.050972 3.400000 +39.400002 47.050972 3.400000 +45.259663 47.415504 3.468808 +39.400002 47.247334 3.419468 +45.167385 47.592983 3.559627 +39.400002 47.440128 3.478827 +45.039757 47.751884 3.686749 +39.400002 47.610397 3.571117 +44.883606 47.881760 3.843408 +39.400002 47.751884 3.686749 +39.400002 47.869968 3.826197 +44.709198 47.975662 4.019274 +39.400002 47.965214 3.994829 +44.528107 48.031300 4.202608 +39.400002 48.027927 4.186557 +9.771892 48.031300 4.202608 +9.949026 48.050819 4.382547 +14.900000 47.247334 3.419468 +14.900000 47.050972 3.400000 +8.966476 47.050972 3.400000 +8.985662 47.231228 3.416380 +14.900000 47.440128 3.478827 +9.040336 47.415504 3.468808 +14.900000 47.610397 3.571117 +9.132613 47.592983 3.559627 +14.900000 47.751884 3.686749 +9.260243 47.751884 3.686749 +14.900000 47.869968 3.826197 +14.900000 47.965214 3.994829 +9.416395 47.881760 3.843408 +14.900000 48.027927 4.186557 +9.590803 47.975662 4.019274 +14.900000 48.050819 4.382547 +14.900000 47.231625 2.519468 +39.400002 47.231625 2.519468 +39.400002 47.035263 2.500000 +14.900000 47.035263 2.500000 +14.900000 48.012218 3.286557 +14.900000 48.035110 3.482548 +39.400002 48.035110 3.482548 +14.900000 47.949505 3.094829 +39.400002 48.012218 3.286557 +14.900000 47.854256 2.926197 +39.400002 47.949505 3.094829 +39.400002 47.854256 2.926197 +14.900000 47.736172 2.786750 +39.400002 47.736172 2.786750 +14.900000 47.594688 2.671118 +39.400002 47.594688 2.671118 +14.900000 47.424416 2.578827 +39.400002 47.424416 2.578827 + + + + + + + + + + + +-0.491198 0.491198 -0.719340 +-0.581426 0.380124 -0.719340 +-0.581426 0.380124 -0.719340 +-0.694658 0.000000 -0.719340 +-0.683061 0.126402 -0.719340 +-0.694658 0.000000 -0.719340 +-0.683061 0.126402 -0.719340 +-0.683061 0.126402 -0.719340 +-0.694658 0.000000 -0.719340 +-0.683061 0.126402 -0.719340 +-0.645885 0.255700 -0.719340 +-0.683061 0.126402 -0.719340 +-0.645885 0.255700 -0.719340 +-0.645885 0.255700 -0.719340 +-0.683061 0.126402 -0.719340 +-0.645885 0.255700 -0.719340 +-0.581426 0.380124 -0.719340 +-0.645885 0.255700 -0.719340 +-0.581426 0.380124 -0.719340 +-0.581426 0.380124 -0.719340 +-0.645885 0.255700 -0.719340 +0.683061 0.126402 -0.719340 +0.694658 0.000000 -0.719340 +0.694658 0.000000 -0.719340 +0.683061 0.126402 -0.719340 +0.683061 0.126402 -0.719340 +0.694658 0.000000 -0.719340 +0.645885 0.255700 -0.719340 +0.683061 0.126402 -0.719340 +0.683061 0.126402 -0.719340 +0.645885 0.255700 -0.719340 +0.645885 0.255700 -0.719340 +0.683061 0.126402 -0.719340 +0.645885 0.255700 -0.719340 +0.581426 0.380124 -0.719340 +0.645885 0.255700 -0.719340 +0.581426 0.380124 -0.719340 +0.581426 0.380124 -0.719340 +0.645885 0.255700 -0.719340 +0.581426 0.380124 -0.719340 +0.491198 0.491198 -0.719340 +0.581426 0.380124 -0.719340 +0.491198 0.491198 -0.719340 +0.491198 0.491198 -0.719340 +0.581426 0.380124 -0.719340 +0.380124 0.581426 -0.719340 +0.491198 0.491198 -0.719340 +0.491198 0.491198 -0.719340 +0.380124 0.581426 -0.719340 +0.380124 0.581426 -0.719340 +0.491198 0.491198 -0.719340 +0.255700 0.645885 -0.719340 +0.380124 0.581426 -0.719340 +0.380124 0.581426 -0.719340 +0.255700 0.645885 -0.719340 +0.255700 0.645885 -0.719340 +0.380124 0.581426 -0.719340 +0.126402 0.683061 -0.719340 +0.255700 0.645885 -0.719340 +0.255700 0.645885 -0.719340 +0.126402 0.683061 -0.719340 +0.126402 0.683061 -0.719340 +0.255700 0.645885 -0.719340 +0.000000 0.694658 -0.719340 +0.126402 0.683061 -0.719340 +0.126402 0.683061 -0.719340 +0.000000 0.694658 -0.719340 +0.000000 0.694658 -0.719340 +0.126402 0.683061 -0.719340 +-0.126402 0.683061 -0.719340 +0.000000 0.694658 -0.719340 +0.000000 0.694658 -0.719340 +-0.126402 0.683061 -0.719340 +-0.126402 0.683061 -0.719340 +0.000000 0.694658 -0.719340 +-0.126402 0.683061 -0.719340 +-0.255700 0.645885 -0.719340 +-0.126402 0.683061 -0.719340 +-0.255700 0.645885 -0.719340 +-0.255700 0.645885 -0.719340 +-0.126402 0.683061 -0.719340 +-0.255700 0.645885 -0.719340 +-0.380124 0.581426 -0.719340 +-0.255700 0.645885 -0.719340 +-0.380124 0.581426 -0.719340 +-0.380124 0.581426 -0.719340 +-0.255700 0.645885 -0.719340 +-0.380124 0.581426 -0.719340 +-0.491198 0.491198 -0.719340 +-0.380124 0.581426 -0.719340 +-0.491198 0.491198 -0.719340 +-0.491198 0.491198 -0.719340 +-0.380124 0.581426 -0.719340 +-0.581426 0.380124 -0.719340 +-0.491198 0.491198 -0.719340 +-0.491198 0.491198 -0.719340 +-0.695302 0.128667 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.695302 0.128667 0.707107 +0.707107 0.000000 0.707107 +0.695302 0.128667 0.707107 +0.695302 0.128667 0.707107 +0.707107 0.000000 0.707107 +0.657460 0.260282 0.707107 +0.695302 0.128667 0.707107 +0.695302 0.128667 0.707107 +0.657460 0.260282 0.707107 +0.657460 0.260282 0.707107 +0.695302 0.128667 0.707107 +0.591845 0.386936 0.707107 +0.657460 0.260282 0.707107 +0.657460 0.260282 0.707107 +0.591845 0.386936 0.707107 +0.591845 0.386936 0.707107 +0.657460 0.260282 0.707107 +0.500000 0.500000 0.707107 +0.591845 0.386936 0.707107 +0.591845 0.386936 0.707107 +0.500000 0.500000 0.707107 +0.500000 0.500000 0.707107 +0.591845 0.386936 0.707107 +0.500000 0.500000 0.707107 +0.386936 0.591845 0.707107 +0.500000 0.500000 0.707107 +0.386936 0.591845 0.707107 +0.386936 0.591845 0.707107 +0.500000 0.500000 0.707107 +0.260282 0.657460 0.707107 +0.386936 0.591845 0.707107 +0.386936 0.591845 0.707107 +0.260282 0.657460 0.707107 +0.260282 0.657460 0.707107 +0.386936 0.591845 0.707107 +0.128667 0.695302 0.707107 +0.260282 0.657460 0.707107 +0.260282 0.657460 0.707107 +0.128667 0.695302 0.707107 +0.128667 0.695302 0.707107 +0.260282 0.657460 0.707107 +0.000000 0.707107 0.707107 +0.128667 0.695302 0.707107 +0.128667 0.695302 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.128667 0.695302 0.707107 +-0.128667 0.695302 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +-0.128667 0.695302 0.707107 +-0.128667 0.695302 0.707107 +0.000000 0.707107 0.707107 +-0.260282 0.657460 0.707107 +-0.128667 0.695302 0.707107 +-0.128667 0.695302 0.707107 +-0.260282 0.657460 0.707107 +-0.260282 0.657460 0.707107 +-0.128667 0.695302 0.707107 +-0.386936 0.591845 0.707107 +-0.260282 0.657460 0.707107 +-0.260282 0.657460 0.707107 +-0.386936 0.591845 0.707107 +-0.386936 0.591845 0.707107 +-0.260282 0.657460 0.707107 +-0.500000 0.500000 0.707107 +-0.386936 0.591845 0.707107 +-0.386936 0.591845 0.707107 +-0.500000 0.500000 0.707107 +-0.500000 0.500000 0.707107 +-0.386936 0.591845 0.707107 +-0.591845 0.386936 0.707107 +-0.500000 0.500000 0.707107 +-0.500000 0.500000 0.707107 +-0.591845 0.386936 0.707107 +-0.591845 0.386936 0.707107 +-0.500000 0.500000 0.707107 +-0.657460 0.260282 0.707107 +-0.591845 0.386936 0.707107 +-0.591845 0.386936 0.707107 +-0.657460 0.260282 0.707107 +-0.657460 0.260282 0.707107 +-0.591845 0.386936 0.707107 +-0.695302 0.128667 0.707107 +-0.657460 0.260282 0.707107 +-0.657460 0.260282 0.707107 +-0.695302 0.128667 0.707107 +-0.695302 0.128667 0.707107 +-0.657460 0.260282 0.707107 +-0.707107 0.000000 0.707107 +-0.695302 0.128667 0.707107 +-0.695302 0.128667 0.707107 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.657460 0.260282 0.707107 +0.591845 0.386936 0.707107 +0.657460 0.260282 0.707107 +0.695302 0.128667 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.695302 0.128667 0.707107 +0.695302 0.128667 0.707107 +0.707107 0.000000 0.707107 +0.695302 0.128667 0.707107 +0.657460 0.260282 0.707107 +0.695302 0.128667 0.707107 +0.657460 0.260282 0.707107 +0.657460 0.260282 0.707107 +0.695302 0.128667 0.707107 +-0.707107 0.000000 0.707107 +-0.695302 0.128667 0.707107 +-0.707107 0.000000 0.707107 +-0.695302 0.128667 0.707107 +-0.695302 0.128667 0.707107 +-0.707107 0.000000 0.707107 +-0.657460 0.260282 0.707107 +-0.695302 0.128667 0.707107 +-0.695302 0.128667 0.707107 +-0.657460 0.260282 0.707107 +-0.657460 0.260282 0.707107 +-0.695302 0.128667 0.707107 +-0.591845 0.386936 0.707107 +-0.657460 0.260282 0.707107 +-0.657460 0.260282 0.707107 +-0.591845 0.386936 0.707107 +-0.591845 0.386936 0.707107 +-0.657460 0.260282 0.707107 +-0.500000 0.500000 0.707107 +-0.591845 0.386936 0.707107 +-0.591845 0.386936 0.707107 +-0.500000 0.500000 0.707107 +-0.500000 0.500000 0.707107 +-0.591845 0.386936 0.707107 +-0.386936 0.591845 0.707107 +-0.500000 0.500000 0.707107 +-0.500000 0.500000 0.707107 +-0.386936 0.591845 0.707107 +-0.386936 0.591845 0.707107 +-0.500000 0.500000 0.707107 +-0.260282 0.657460 0.707107 +-0.386936 0.591845 0.707107 +-0.386936 0.591845 0.707107 +-0.260282 0.657460 0.707107 +-0.260282 0.657460 0.707107 +-0.386936 0.591845 0.707107 +-0.128667 0.695302 0.707107 +-0.260282 0.657460 0.707107 +-0.260282 0.657460 0.707107 +-0.128667 0.695302 0.707107 +-0.128667 0.695302 0.707107 +-0.260282 0.657460 0.707107 +0.000000 0.707107 0.707107 +-0.128667 0.695302 0.707107 +-0.128667 0.695302 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +-0.128667 0.695302 0.707107 +0.128667 0.695302 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.128667 0.695302 0.707107 +0.128667 0.695302 0.707107 +0.000000 0.707107 0.707107 +0.260282 0.657460 0.707107 +0.128667 0.695302 0.707107 +0.128667 0.695302 0.707107 +0.260282 0.657460 0.707107 +0.260282 0.657460 0.707107 +0.128667 0.695302 0.707107 +0.386936 0.591845 0.707107 +0.260282 0.657460 0.707107 +0.260282 0.657460 0.707107 +0.386936 0.591845 0.707107 +0.386936 0.591845 0.707107 +0.260282 0.657460 0.707107 +0.500000 0.500000 0.707107 +0.386936 0.591845 0.707107 +0.386936 0.591845 0.707107 +0.500000 0.500000 0.707107 +0.500000 0.500000 0.707107 +0.386936 0.591845 0.707107 +0.591845 0.386936 0.707107 +0.500000 0.500000 0.707107 +0.500000 0.500000 0.707107 +0.591845 0.386936 0.707107 +0.591845 0.386936 0.707107 +0.500000 0.500000 0.707107 +0.591845 0.386936 0.707107 +0.657460 0.260282 0.707107 +0.591845 0.386936 0.707107 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +-0.695302 0.128667 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +0.695302 0.128667 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.695302 0.128667 0.707107 +0.695302 0.128667 0.707107 +0.707107 0.000000 0.707107 +0.657460 0.260282 0.707107 +0.695302 0.128667 0.707107 +0.695302 0.128667 0.707107 +0.657460 0.260282 0.707107 +0.657460 0.260282 0.707107 +0.695302 0.128667 0.707107 +0.591845 0.386936 0.707107 +0.657460 0.260282 0.707107 +0.657460 0.260282 0.707107 +0.591845 0.386936 0.707107 +0.591845 0.386936 0.707107 +0.657460 0.260282 0.707107 +0.500000 0.500000 0.707107 +0.591845 0.386936 0.707107 +0.591845 0.386936 0.707107 +0.500000 0.500000 0.707107 +0.500000 0.500000 0.707107 +0.591845 0.386936 0.707107 +0.386936 0.591845 0.707107 +0.500000 0.500000 0.707107 +0.500000 0.500000 0.707107 +0.386936 0.591845 0.707107 +0.386936 0.591845 0.707107 +0.500000 0.500000 0.707107 +0.260282 0.657460 0.707107 +0.386936 0.591845 0.707107 +0.386936 0.591845 0.707107 +0.260282 0.657460 0.707107 +0.260282 0.657460 0.707107 +0.386936 0.591845 0.707107 +0.128667 0.695302 0.707107 +0.260282 0.657460 0.707107 +0.260282 0.657460 0.707107 +0.128667 0.695302 0.707107 +0.128667 0.695302 0.707107 +0.260282 0.657460 0.707107 +0.000000 0.707107 0.707107 +0.128667 0.695302 0.707107 +0.128667 0.695302 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.128667 0.695302 0.707107 +-0.128667 0.695302 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +-0.128667 0.695302 0.707107 +-0.128667 0.695302 0.707107 +0.000000 0.707107 0.707107 +-0.260282 0.657460 0.707107 +-0.128667 0.695302 0.707107 +-0.128667 0.695302 0.707107 +-0.260282 0.657460 0.707107 +-0.260282 0.657460 0.707107 +-0.128667 0.695302 0.707107 +-0.386936 0.591845 0.707107 +-0.260282 0.657460 0.707107 +-0.260282 0.657460 0.707107 +-0.386936 0.591845 0.707107 +-0.386936 0.591845 0.707107 +-0.260282 0.657460 0.707107 +-0.500000 0.500000 0.707107 +-0.386936 0.591845 0.707107 +-0.386936 0.591845 0.707107 +-0.500000 0.500000 0.707107 +-0.500000 0.500000 0.707107 +-0.386936 0.591845 0.707107 +-0.591845 0.386936 0.707107 +-0.500000 0.500000 0.707107 +-0.500000 0.500000 0.707107 +-0.591845 0.386936 0.707107 +-0.591845 0.386936 0.707107 +-0.500000 0.500000 0.707107 +-0.657460 0.260282 0.707107 +-0.591845 0.386936 0.707107 +-0.591845 0.386936 0.707107 +-0.657460 0.260282 0.707107 +-0.657460 0.260282 0.707107 +-0.591845 0.386936 0.707107 +-0.695302 0.128667 0.707107 +-0.657460 0.260282 0.707107 +-0.657460 0.260282 0.707107 +-0.695302 0.128667 0.707107 +-0.695302 0.128667 0.707107 +-0.657460 0.260282 0.707107 +-0.707107 0.000000 0.707107 +-0.695302 0.128667 0.707107 +-0.695302 0.128667 0.707107 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +-0.695302 0.128667 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +0.695302 0.128667 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.695302 0.128667 0.707107 +0.695302 0.128667 0.707107 +0.707107 0.000000 0.707107 +0.657460 0.260282 0.707107 +0.695302 0.128667 0.707107 +0.695302 0.128667 0.707107 +0.657460 0.260282 0.707107 +0.657460 0.260282 0.707107 +0.695302 0.128667 0.707107 +0.591845 0.386936 0.707107 +0.657460 0.260282 0.707107 +0.657460 0.260282 0.707107 +0.591845 0.386936 0.707107 +0.591845 0.386936 0.707107 +0.657460 0.260282 0.707107 +0.500000 0.500000 0.707107 +0.591845 0.386936 0.707107 +0.591845 0.386936 0.707107 +0.500000 0.500000 0.707107 +0.500000 0.500000 0.707107 +0.591845 0.386936 0.707107 +0.386936 0.591845 0.707107 +0.500000 0.500000 0.707107 +0.500000 0.500000 0.707107 +0.386936 0.591845 0.707107 +0.386936 0.591845 0.707107 +0.500000 0.500000 0.707107 +0.260282 0.657460 0.707107 +0.386936 0.591845 0.707107 +0.386936 0.591845 0.707107 +0.260282 0.657460 0.707107 +0.260282 0.657460 0.707107 +0.386936 0.591845 0.707107 +0.128667 0.695302 0.707107 +0.260282 0.657460 0.707107 +0.260282 0.657460 0.707107 +0.128667 0.695302 0.707107 +0.128667 0.695302 0.707107 +0.260282 0.657460 0.707107 +0.000000 0.707107 0.707107 +0.128667 0.695302 0.707107 +0.128667 0.695302 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.128667 0.695302 0.707107 +-0.128667 0.695302 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +-0.128667 0.695302 0.707107 +-0.128667 0.695302 0.707107 +0.000000 0.707107 0.707107 +-0.260282 0.657460 0.707107 +-0.128667 0.695302 0.707107 +-0.128667 0.695302 0.707107 +-0.260282 0.657460 0.707107 +-0.260282 0.657460 0.707107 +-0.128667 0.695302 0.707107 +-0.386936 0.591845 0.707107 +-0.260282 0.657460 0.707107 +-0.260282 0.657460 0.707107 +-0.386936 0.591845 0.707107 +-0.386936 0.591845 0.707107 +-0.260282 0.657460 0.707107 +-0.500000 0.500000 0.707107 +-0.386936 0.591845 0.707107 +-0.386936 0.591845 0.707107 +-0.500000 0.500000 0.707107 +-0.500000 0.500000 0.707107 +-0.386936 0.591845 0.707107 +-0.591845 0.386936 0.707107 +-0.500000 0.500000 0.707107 +-0.500000 0.500000 0.707107 +-0.591845 0.386936 0.707107 +-0.591845 0.386936 0.707107 +-0.500000 0.500000 0.707107 +-0.657460 0.260282 0.707107 +-0.591845 0.386936 0.707107 +-0.591845 0.386936 0.707107 +-0.657460 0.260282 0.707107 +-0.657460 0.260282 0.707107 +-0.591845 0.386936 0.707107 +-0.695302 0.128667 0.707107 +-0.657460 0.260282 0.707107 +-0.657460 0.260282 0.707107 +-0.695302 0.128667 0.707107 +-0.695302 0.128667 0.707107 +-0.657460 0.260282 0.707107 +-0.707107 0.000000 0.707107 +-0.695302 0.128667 0.707107 +-0.695302 0.128667 0.707107 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.983156 0.181935 -0.017452 +-0.929647 0.368039 -0.017452 +-0.983156 0.181935 -0.017452 +-0.999848 0.000000 -0.017452 +-0.983156 0.181935 -0.017452 +-0.999848 0.000000 -0.017452 +-0.983156 0.181935 -0.017452 +-0.983156 0.181935 -0.017452 +-0.999848 0.000000 -0.017452 +0.983156 0.181935 -0.017452 +0.999848 0.000000 -0.017452 +0.999848 0.000000 -0.017452 +0.983156 0.181935 -0.017452 +0.983156 0.181935 -0.017452 +0.999848 0.000000 -0.017452 +0.983156 0.181935 -0.017452 +0.929647 0.368039 -0.017452 +0.983156 0.181935 -0.017452 +0.929647 0.368039 -0.017452 +0.929647 0.368039 -0.017452 +0.983156 0.181935 -0.017452 +0.929647 0.368039 -0.017452 +0.836868 0.547126 -0.017452 +0.929647 0.368039 -0.017452 +0.836868 0.547126 -0.017452 +0.836868 0.547126 -0.017452 +0.929647 0.368039 -0.017452 +0.706999 0.706999 -0.017452 +0.836868 0.547126 -0.017452 +0.836868 0.547126 -0.017452 +0.706999 0.706999 -0.017452 +0.706999 0.706999 -0.017452 +0.836868 0.547126 -0.017452 +0.547126 0.836868 -0.017452 +0.706999 0.706999 -0.017452 +0.706999 0.706999 -0.017452 +0.547126 0.836868 -0.017452 +0.547126 0.836868 -0.017452 +0.706999 0.706999 -0.017452 +0.547126 0.836868 -0.017452 +0.368039 0.929647 -0.017452 +0.547126 0.836868 -0.017452 +0.368039 0.929647 -0.017452 +0.368039 0.929647 -0.017452 +0.547126 0.836868 -0.017452 +0.181935 0.983156 -0.017452 +0.368039 0.929647 -0.017452 +0.368039 0.929647 -0.017452 +0.181935 0.983156 -0.017452 +0.181935 0.983156 -0.017452 +0.368039 0.929647 -0.017452 +0.181935 0.983156 -0.017452 +0.000000 0.999848 -0.017452 +0.181935 0.983156 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.181935 0.983156 -0.017452 +-0.181935 0.983156 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +-0.181935 0.983156 -0.017452 +-0.181935 0.983156 -0.017452 +0.000000 0.999848 -0.017452 +-0.368039 0.929647 -0.017452 +-0.181935 0.983156 -0.017452 +-0.181935 0.983156 -0.017452 +-0.368039 0.929647 -0.017452 +-0.368039 0.929647 -0.017452 +-0.181935 0.983156 -0.017452 +-0.368039 0.929647 -0.017452 +-0.547126 0.836868 -0.017452 +-0.368039 0.929647 -0.017452 +-0.547126 0.836868 -0.017452 +-0.547126 0.836868 -0.017452 +-0.368039 0.929647 -0.017452 +-0.547126 0.836868 -0.017452 +-0.706999 0.706999 -0.017452 +-0.547126 0.836868 -0.017452 +-0.706999 0.706999 -0.017452 +-0.706999 0.706999 -0.017452 +-0.547126 0.836868 -0.017452 +-0.836868 0.547126 -0.017452 +-0.706999 0.706999 -0.017452 +-0.706999 0.706999 -0.017452 +-0.836868 0.547126 -0.017452 +-0.836868 0.547126 -0.017452 +-0.706999 0.706999 -0.017452 +-0.929647 0.368039 -0.017452 +-0.836868 0.547126 -0.017452 +-0.836868 0.547126 -0.017452 +-0.929647 0.368039 -0.017452 +-0.929647 0.368039 -0.017452 +-0.836868 0.547126 -0.017452 +-0.929647 0.368039 -0.017452 +-0.983156 0.181935 -0.017452 +-0.929647 0.368039 -0.017452 +-0.547126 0.836868 -0.017452 +-0.368039 0.929647 -0.017452 +-0.547126 0.836868 -0.017452 +-0.999848 0.000000 -0.017452 +-0.983156 0.181935 -0.017452 +-0.999848 0.000000 -0.017452 +-0.983156 0.181935 -0.017452 +-0.983156 0.181935 -0.017452 +-0.999848 0.000000 -0.017452 +-0.929647 0.368039 -0.017452 +-0.983156 0.181935 -0.017452 +-0.983156 0.181935 -0.017452 +-0.929647 0.368039 -0.017452 +-0.929647 0.368039 -0.017452 +-0.983156 0.181935 -0.017452 +-0.836868 0.547126 -0.017452 +-0.929647 0.368039 -0.017452 +-0.929647 0.368039 -0.017452 +-0.836868 0.547126 -0.017452 +-0.836868 0.547126 -0.017452 +-0.929647 0.368039 -0.017452 +-0.706999 0.706999 -0.017452 +-0.836868 0.547126 -0.017452 +-0.836868 0.547126 -0.017452 +-0.706999 0.706999 -0.017452 +-0.706999 0.706999 -0.017452 +-0.836868 0.547126 -0.017452 +-0.547126 0.836868 -0.017452 +-0.706999 0.706999 -0.017452 +-0.706999 0.706999 -0.017452 +-0.547126 0.836868 -0.017452 +-0.547126 0.836868 -0.017452 +-0.706999 0.706999 -0.017452 +0.983156 0.181935 -0.017452 +0.999848 0.000000 -0.017452 +0.999848 0.000000 -0.017452 +0.983156 0.181935 -0.017452 +0.983156 0.181935 -0.017452 +0.999848 0.000000 -0.017452 +0.983156 0.181935 -0.017452 +0.929647 0.368039 -0.017452 +0.983156 0.181935 -0.017452 +0.929647 0.368039 -0.017452 +0.929647 0.368039 -0.017452 +0.983156 0.181935 -0.017452 +0.836868 0.547126 -0.017452 +0.929647 0.368039 -0.017452 +0.929647 0.368039 -0.017452 +0.836868 0.547126 -0.017452 +0.836868 0.547126 -0.017452 +0.929647 0.368039 -0.017452 +0.706999 0.706999 -0.017452 +0.836868 0.547126 -0.017452 +0.836868 0.547126 -0.017452 +0.706999 0.706999 -0.017452 +0.706999 0.706999 -0.017452 +0.836868 0.547126 -0.017452 +0.547126 0.836868 -0.017452 +0.706999 0.706999 -0.017452 +0.706999 0.706999 -0.017452 +0.547126 0.836868 -0.017452 +0.547126 0.836868 -0.017452 +0.706999 0.706999 -0.017452 +0.368039 0.929647 -0.017452 +0.547126 0.836868 -0.017452 +0.547126 0.836868 -0.017452 +0.368039 0.929647 -0.017452 +0.368039 0.929647 -0.017452 +0.547126 0.836868 -0.017452 +0.181935 0.983156 -0.017452 +0.368039 0.929647 -0.017452 +0.368039 0.929647 -0.017452 +0.181935 0.983156 -0.017452 +0.181935 0.983156 -0.017452 +0.368039 0.929647 -0.017452 +0.000000 0.999848 -0.017452 +0.181935 0.983156 -0.017452 +0.181935 0.983156 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.181935 0.983156 -0.017452 +0.000000 0.999848 -0.017452 +-0.181935 0.983156 -0.017452 +0.000000 0.999848 -0.017452 +-0.181935 0.983156 -0.017452 +-0.181935 0.983156 -0.017452 +0.000000 0.999848 -0.017452 +-0.368039 0.929647 -0.017452 +-0.181935 0.983156 -0.017452 +-0.181935 0.983156 -0.017452 +-0.368039 0.929647 -0.017452 +-0.368039 0.929647 -0.017452 +-0.181935 0.983156 -0.017452 +-0.368039 0.929647 -0.017452 +-0.547126 0.836868 -0.017452 +-0.368039 0.929647 -0.017452 +0.983156 0.181935 -0.017452 +0.999848 0.000000 -0.017452 +0.999848 0.000000 -0.017452 +-0.999848 0.000000 -0.017452 +-0.983156 0.181935 -0.017452 +-0.999848 0.000000 -0.017452 +-0.983156 0.181935 -0.017452 +-0.983156 0.181935 -0.017452 +-0.999848 0.000000 -0.017452 +-0.983156 0.181935 -0.017452 +-0.929647 0.368039 -0.017452 +-0.983156 0.181935 -0.017452 +-0.929647 0.368039 -0.017452 +-0.929647 0.368039 -0.017452 +-0.983156 0.181935 -0.017452 +-0.836868 0.547126 -0.017452 +-0.929647 0.368039 -0.017452 +-0.929647 0.368039 -0.017452 +-0.836868 0.547126 -0.017452 +-0.836868 0.547126 -0.017452 +-0.929647 0.368039 -0.017452 +-0.836868 0.547126 -0.017452 +-0.706999 0.706999 -0.017452 +-0.836868 0.547126 -0.017452 +-0.706999 0.706999 -0.017452 +-0.706999 0.706999 -0.017452 +-0.836868 0.547126 -0.017452 +-0.547126 0.836868 -0.017452 +-0.706999 0.706999 -0.017452 +-0.706999 0.706999 -0.017452 +-0.547126 0.836868 -0.017452 +-0.547126 0.836868 -0.017452 +-0.706999 0.706999 -0.017452 +-0.368039 0.929647 -0.017452 +-0.547126 0.836868 -0.017452 +-0.547126 0.836868 -0.017452 +-0.368039 0.929647 -0.017452 +-0.368039 0.929647 -0.017452 +-0.547126 0.836868 -0.017452 +-0.181935 0.983156 -0.017452 +-0.368039 0.929647 -0.017452 +-0.368039 0.929647 -0.017452 +-0.181935 0.983156 -0.017452 +-0.181935 0.983156 -0.017452 +-0.368039 0.929647 -0.017452 +0.000000 0.999848 -0.017452 +-0.181935 0.983156 -0.017452 +-0.181935 0.983156 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +-0.181935 0.983156 -0.017452 +0.181935 0.983156 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.181935 0.983156 -0.017452 +0.181935 0.983156 -0.017452 +0.000000 0.999848 -0.017452 +0.368039 0.929647 -0.017452 +0.181935 0.983156 -0.017452 +0.181935 0.983156 -0.017452 +0.368039 0.929647 -0.017452 +0.368039 0.929647 -0.017452 +0.181935 0.983156 -0.017452 +0.547126 0.836868 -0.017452 +0.368039 0.929647 -0.017452 +0.368039 0.929647 -0.017452 +0.547126 0.836868 -0.017452 +0.547126 0.836868 -0.017452 +0.368039 0.929647 -0.017452 +0.706999 0.706999 -0.017452 +0.547126 0.836868 -0.017452 +0.547126 0.836868 -0.017452 +0.706999 0.706999 -0.017452 +0.706999 0.706999 -0.017452 +0.547126 0.836868 -0.017452 +0.836868 0.547126 -0.017452 +0.706999 0.706999 -0.017452 +0.706999 0.706999 -0.017452 +0.836868 0.547126 -0.017452 +0.836868 0.547126 -0.017452 +0.706999 0.706999 -0.017452 +0.929647 0.368039 -0.017452 +0.836868 0.547126 -0.017452 +0.836868 0.547126 -0.017452 +0.929647 0.368039 -0.017452 +0.929647 0.368039 -0.017452 +0.836868 0.547126 -0.017452 +0.983156 0.181935 -0.017452 +0.929647 0.368039 -0.017452 +0.929647 0.368039 -0.017452 +0.983156 0.181935 -0.017452 +0.983156 0.181935 -0.017452 +0.929647 0.368039 -0.017452 +0.999848 0.000000 -0.017452 +0.983156 0.181935 -0.017452 +0.983156 0.181935 -0.017452 +-0.836868 0.547126 -0.017452 +-0.929647 0.368039 -0.017452 +-0.929647 0.368039 -0.017452 +-0.999848 0.000000 -0.017452 +-0.983156 0.181935 -0.017452 +-0.999848 0.000000 -0.017452 +-0.983156 0.181935 -0.017452 +-0.983156 0.181935 -0.017452 +-0.999848 0.000000 -0.017452 +-0.983156 0.181935 -0.017452 +-0.929647 0.368039 -0.017452 +-0.983156 0.181935 -0.017452 +-0.929647 0.368039 -0.017452 +-0.929647 0.368039 -0.017452 +-0.983156 0.181935 -0.017452 +0.983156 0.181935 -0.017452 +0.999848 0.000000 -0.017452 +0.999848 0.000000 -0.017452 +0.983156 0.181935 -0.017452 +0.983156 0.181935 -0.017452 +0.999848 0.000000 -0.017452 +0.929647 0.368039 -0.017452 +0.983156 0.181935 -0.017452 +0.983156 0.181935 -0.017452 +0.929647 0.368039 -0.017452 +0.929647 0.368039 -0.017452 +0.983156 0.181935 -0.017452 +0.929647 0.368039 -0.017452 +0.836868 0.547126 -0.017452 +0.929647 0.368039 -0.017452 +0.836868 0.547126 -0.017452 +0.836868 0.547126 -0.017452 +0.929647 0.368039 -0.017452 +0.706999 0.706999 -0.017452 +0.836868 0.547126 -0.017452 +0.836868 0.547126 -0.017452 +0.706999 0.706999 -0.017452 +0.706999 0.706999 -0.017452 +0.836868 0.547126 -0.017452 +0.547126 0.836868 -0.017452 +0.706999 0.706999 -0.017452 +0.706999 0.706999 -0.017452 +0.547126 0.836868 -0.017452 +0.547126 0.836868 -0.017452 +0.706999 0.706999 -0.017452 +0.368039 0.929647 -0.017452 +0.547126 0.836868 -0.017452 +0.547126 0.836868 -0.017452 +0.368039 0.929647 -0.017452 +0.368039 0.929647 -0.017452 +0.547126 0.836868 -0.017452 +0.368039 0.929647 -0.017452 +0.181935 0.983156 -0.017452 +0.368039 0.929647 -0.017452 +0.181935 0.983156 -0.017452 +0.181935 0.983156 -0.017452 +0.368039 0.929647 -0.017452 +0.000000 0.999848 -0.017452 +0.181935 0.983156 -0.017452 +0.181935 0.983156 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.181935 0.983156 -0.017452 +-0.181935 0.983156 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +-0.181935 0.983156 -0.017452 +-0.181935 0.983156 -0.017452 +0.000000 0.999848 -0.017452 +-0.368039 0.929647 -0.017452 +-0.181935 0.983156 -0.017452 +-0.181935 0.983156 -0.017452 +-0.368039 0.929647 -0.017452 +-0.368039 0.929647 -0.017452 +-0.181935 0.983156 -0.017452 +-0.368039 0.929647 -0.017452 +-0.547126 0.836868 -0.017452 +-0.368039 0.929647 -0.017452 +-0.547126 0.836868 -0.017452 +-0.547126 0.836868 -0.017452 +-0.368039 0.929647 -0.017452 +-0.547126 0.836868 -0.017452 +-0.706999 0.706999 -0.017452 +-0.547126 0.836868 -0.017452 +-0.706999 0.706999 -0.017452 +-0.706999 0.706999 -0.017452 +-0.547126 0.836868 -0.017452 +-0.836868 0.547126 -0.017452 +-0.706999 0.706999 -0.017452 +-0.706999 0.706999 -0.017452 +-0.836868 0.547126 -0.017452 +-0.836868 0.547126 -0.017452 +-0.706999 0.706999 -0.017452 +-0.929647 0.368039 -0.017452 +-0.836868 0.547126 -0.017452 +-0.836868 0.547126 -0.017452 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.929647 -0.368039 -0.017452 +-0.983156 -0.181935 -0.017452 +-0.983156 -0.181935 -0.017452 +-0.999848 0.000000 -0.017452 +-0.983156 -0.181935 -0.017452 +-0.999848 0.000000 -0.017452 +-0.983156 -0.181935 -0.017452 +-0.983156 -0.181935 -0.017452 +-0.999848 0.000000 -0.017452 +0.983156 -0.181935 -0.017452 +0.999848 0.000000 -0.017452 +0.999848 0.000000 -0.017452 +0.983156 -0.181935 -0.017452 +0.983156 -0.181935 -0.017452 +0.999848 0.000000 -0.017452 +0.929647 -0.368039 -0.017452 +0.983156 -0.181935 -0.017452 +0.983156 -0.181935 -0.017452 +0.929647 -0.368039 -0.017452 +0.929647 -0.368039 -0.017452 +0.983156 -0.181935 -0.017452 +0.836868 -0.547126 -0.017452 +0.929647 -0.368039 -0.017452 +0.929647 -0.368039 -0.017452 +0.836868 -0.547126 -0.017452 +0.836868 -0.547126 -0.017452 +0.929647 -0.368039 -0.017452 +0.706999 -0.706999 -0.017452 +0.836868 -0.547126 -0.017452 +0.836868 -0.547126 -0.017452 +0.706999 -0.706999 -0.017452 +0.706999 -0.706999 -0.017452 +0.836868 -0.547126 -0.017452 +0.547126 -0.836868 -0.017452 +0.706999 -0.706999 -0.017452 +0.706999 -0.706999 -0.017452 +0.547126 -0.836868 -0.017452 +0.547126 -0.836868 -0.017452 +0.706999 -0.706999 -0.017452 +0.368039 -0.929647 -0.017452 +0.547126 -0.836868 -0.017452 +0.547126 -0.836868 -0.017452 +0.368039 -0.929647 -0.017452 +0.368039 -0.929647 -0.017452 +0.547126 -0.836868 -0.017452 +0.181935 -0.983156 -0.017452 +0.368039 -0.929647 -0.017452 +0.368039 -0.929647 -0.017452 +0.181935 -0.983156 -0.017452 +0.181935 -0.983156 -0.017452 +0.368039 -0.929647 -0.017452 +0.000000 -0.999848 -0.017452 +0.181935 -0.983156 -0.017452 +0.181935 -0.983156 -0.017452 +0.000000 -0.999848 -0.017452 +0.000000 -0.999848 -0.017452 +0.181935 -0.983156 -0.017452 +-0.181935 -0.983156 -0.017452 +0.000000 -0.999848 -0.017452 +0.000000 -0.999848 -0.017452 +-0.181935 -0.983156 -0.017452 +-0.181935 -0.983156 -0.017452 +0.000000 -0.999848 -0.017452 +-0.368039 -0.929647 -0.017452 +-0.181935 -0.983156 -0.017452 +-0.181935 -0.983156 -0.017452 +-0.368039 -0.929647 -0.017452 +-0.368039 -0.929647 -0.017452 +-0.181935 -0.983156 -0.017452 +-0.547126 -0.836868 -0.017452 +-0.368039 -0.929647 -0.017452 +-0.368039 -0.929647 -0.017452 +-0.547126 -0.836868 -0.017452 +-0.547126 -0.836868 -0.017452 +-0.368039 -0.929647 -0.017452 +-0.547126 -0.836868 -0.017452 +-0.706999 -0.706999 -0.017452 +-0.547126 -0.836868 -0.017452 +-0.706999 -0.706999 -0.017452 +-0.706999 -0.706999 -0.017452 +-0.547126 -0.836868 -0.017452 +-0.836868 -0.547126 -0.017452 +-0.706999 -0.706999 -0.017452 +-0.706999 -0.706999 -0.017452 +-0.836868 -0.547126 -0.017452 +-0.836868 -0.547126 -0.017452 +-0.706999 -0.706999 -0.017452 +-0.929647 -0.368039 -0.017452 +-0.836868 -0.547126 -0.017452 +-0.836868 -0.547126 -0.017452 +-0.929647 -0.368039 -0.017452 +-0.929647 -0.368039 -0.017452 +-0.836868 -0.547126 -0.017452 +-0.983156 -0.181935 -0.017452 +-0.929647 -0.368039 -0.017452 +-0.929647 -0.368039 -0.017452 +0.999848 0.000000 -0.017452 +0.999848 0.000000 -0.017452 +0.999848 0.000000 -0.017452 +0.999848 0.000000 -0.017452 +0.999848 0.000000 -0.017452 +0.999848 0.000000 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +-0.999848 0.000000 -0.017452 +-0.999848 0.000000 -0.017452 +-0.999848 0.000000 -0.017452 +-0.999848 0.000000 -0.017452 +-0.999848 0.000000 -0.017452 +-0.999848 0.000000 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.983156 0.181935 -0.017452 +0.999848 0.000000 -0.017452 +0.999848 0.000000 -0.017452 +-0.983156 0.181935 -0.017452 +-0.999848 0.000000 -0.017452 +-0.999848 0.000000 -0.017452 +-0.983156 0.181935 -0.017452 +-0.983156 0.181935 -0.017452 +-0.999848 0.000000 -0.017452 +-0.929647 0.368039 -0.017452 +-0.983156 0.181935 -0.017452 +-0.983156 0.181935 -0.017452 +-0.929647 0.368039 -0.017452 +-0.929647 0.368039 -0.017452 +-0.983156 0.181935 -0.017452 +-0.836868 0.547126 -0.017452 +-0.929647 0.368039 -0.017452 +-0.929647 0.368039 -0.017452 +-0.836868 0.547126 -0.017452 +-0.836868 0.547126 -0.017452 +-0.929647 0.368039 -0.017452 +-0.706999 0.706999 -0.017452 +-0.836868 0.547126 -0.017452 +-0.836868 0.547126 -0.017452 +-0.706999 0.706999 -0.017452 +-0.706999 0.706999 -0.017452 +-0.836868 0.547126 -0.017452 +-0.547126 0.836868 -0.017452 +-0.706999 0.706999 -0.017452 +-0.706999 0.706999 -0.017452 +-0.547126 0.836868 -0.017452 +-0.547126 0.836868 -0.017452 +-0.706999 0.706999 -0.017452 +-0.368039 0.929647 -0.017452 +-0.547126 0.836868 -0.017452 +-0.547126 0.836868 -0.017452 +-0.368039 0.929647 -0.017452 +-0.368039 0.929647 -0.017452 +-0.547126 0.836868 -0.017452 +-0.181935 0.983156 -0.017452 +-0.368039 0.929647 -0.017452 +-0.368039 0.929647 -0.017452 +-0.181935 0.983156 -0.017452 +-0.181935 0.983156 -0.017452 +-0.368039 0.929647 -0.017452 +0.000000 0.999848 -0.017452 +-0.181935 0.983156 -0.017452 +-0.181935 0.983156 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +-0.181935 0.983156 -0.017452 +0.181935 0.983156 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.181935 0.983156 -0.017452 +0.181935 0.983156 -0.017452 +0.000000 0.999848 -0.017452 +0.368039 0.929647 -0.017452 +0.181935 0.983156 -0.017452 +0.181935 0.983156 -0.017452 +0.368039 0.929647 -0.017452 +0.368039 0.929647 -0.017452 +0.181935 0.983156 -0.017452 +0.547126 0.836868 -0.017452 +0.368039 0.929647 -0.017452 +0.368039 0.929647 -0.017452 +0.547126 0.836868 -0.017452 +0.547126 0.836868 -0.017452 +0.368039 0.929647 -0.017452 +0.706999 0.706999 -0.017452 +0.547126 0.836868 -0.017452 +0.547126 0.836868 -0.017452 +0.706999 0.706999 -0.017452 +0.706999 0.706999 -0.017452 +0.547126 0.836868 -0.017452 +0.836868 0.547126 -0.017452 +0.706999 0.706999 -0.017452 +0.706999 0.706999 -0.017452 +0.836868 0.547126 -0.017452 +0.836868 0.547126 -0.017452 +0.706999 0.706999 -0.017452 +0.929647 0.368039 -0.017452 +0.836868 0.547126 -0.017452 +0.836868 0.547126 -0.017452 +0.929647 0.368039 -0.017452 +0.929647 0.368039 -0.017452 +0.836868 0.547126 -0.017452 +0.983156 0.181935 -0.017452 +0.929647 0.368039 -0.017452 +0.929647 0.368039 -0.017452 +0.983156 0.181935 -0.017452 +0.983156 0.181935 -0.017452 +0.929647 0.368039 -0.017452 +0.999848 0.000000 -0.017452 +0.983156 0.181935 -0.017452 +0.983156 0.181935 -0.017452 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +-0.547126 -0.836868 -0.017452 +-0.368039 -0.929647 -0.017452 +-0.368039 -0.929647 -0.017452 +0.999848 0.000000 -0.017452 +0.983156 -0.181935 -0.017452 +0.999848 0.000000 -0.017452 +0.983156 -0.181935 -0.017452 +0.983156 -0.181935 -0.017452 +0.999848 0.000000 -0.017452 +0.929647 -0.368039 -0.017452 +0.983156 -0.181935 -0.017452 +0.983156 -0.181935 -0.017452 +0.929647 -0.368039 -0.017452 +0.929647 -0.368039 -0.017452 +0.983156 -0.181935 -0.017452 +0.836868 -0.547126 -0.017452 +0.929647 -0.368039 -0.017452 +0.929647 -0.368039 -0.017452 +0.836868 -0.547126 -0.017452 +0.836868 -0.547126 -0.017452 +0.929647 -0.368039 -0.017452 +0.836868 -0.547126 -0.017452 +0.706999 -0.706999 -0.017452 +0.836868 -0.547126 -0.017452 +0.706999 -0.706999 -0.017452 +0.706999 -0.706999 -0.017452 +0.836868 -0.547126 -0.017452 +0.706999 -0.706999 -0.017452 +0.547126 -0.836868 -0.017452 +0.706999 -0.706999 -0.017452 +0.547126 -0.836868 -0.017452 +0.547126 -0.836868 -0.017452 +0.706999 -0.706999 -0.017452 +0.368039 -0.929647 -0.017452 +0.547126 -0.836868 -0.017452 +0.547126 -0.836868 -0.017452 +0.368039 -0.929647 -0.017452 +0.368039 -0.929647 -0.017452 +0.547126 -0.836868 -0.017452 +0.368039 -0.929647 -0.017452 +0.181935 -0.983156 -0.017452 +0.368039 -0.929647 -0.017452 +0.181935 -0.983156 -0.017452 +0.181935 -0.983156 -0.017452 +0.368039 -0.929647 -0.017452 +0.181935 -0.983156 -0.017452 +0.000000 -0.999848 -0.017452 +0.181935 -0.983156 -0.017452 +0.000000 -0.999848 -0.017452 +0.000000 -0.999848 -0.017452 +0.181935 -0.983156 -0.017452 +0.000000 -0.999848 -0.017452 +-0.181935 -0.983156 -0.017452 +0.000000 -0.999848 -0.017452 +-0.181935 -0.983156 -0.017452 +-0.181935 -0.983156 -0.017452 +0.000000 -0.999848 -0.017452 +-0.368039 -0.929647 -0.017452 +-0.181935 -0.983156 -0.017452 +-0.181935 -0.983156 -0.017452 +-0.368039 -0.929647 -0.017452 +-0.368039 -0.929647 -0.017452 +-0.181935 -0.983156 -0.017452 +-0.983156 -0.181935 -0.017452 +-0.999848 0.000000 -0.017452 +-0.999848 0.000000 -0.017452 +-0.983156 -0.181935 -0.017452 +-0.983156 -0.181935 -0.017452 +-0.999848 0.000000 -0.017452 +-0.983156 -0.181935 -0.017452 +-0.929647 -0.368039 -0.017452 +-0.983156 -0.181935 -0.017452 +-0.929647 -0.368039 -0.017452 +-0.929647 -0.368039 -0.017452 +-0.983156 -0.181935 -0.017452 +-0.929647 -0.368039 -0.017452 +-0.836868 -0.547126 -0.017452 +-0.929647 -0.368039 -0.017452 +-0.836868 -0.547126 -0.017452 +-0.836868 -0.547126 -0.017452 +-0.929647 -0.368039 -0.017452 +-0.706999 -0.706999 -0.017452 +-0.836868 -0.547126 -0.017452 +-0.836868 -0.547126 -0.017452 +-0.706999 -0.706999 -0.017452 +-0.706999 -0.706999 -0.017452 +-0.836868 -0.547126 -0.017452 +-0.547126 -0.836868 -0.017452 +-0.706999 -0.706999 -0.017452 +-0.706999 -0.706999 -0.017452 +-0.547126 -0.836868 -0.017452 +-0.547126 -0.836868 -0.017452 +-0.706999 -0.706999 -0.017452 +-0.368039 -0.929647 -0.017452 +-0.547126 -0.836868 -0.017452 +-0.547126 -0.836868 -0.017452 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.983156 -0.181935 -0.017452 +0.999848 0.000000 -0.017452 +0.999848 0.000000 -0.017452 +-0.983156 -0.181935 -0.017452 +-0.999848 0.000000 -0.017452 +-0.999848 0.000000 -0.017452 +-0.983156 -0.181935 -0.017452 +-0.983156 -0.181935 -0.017452 +-0.999848 0.000000 -0.017452 +-0.983156 -0.181935 -0.017452 +-0.929647 -0.368039 -0.017452 +-0.983156 -0.181935 -0.017452 +-0.929647 -0.368039 -0.017452 +-0.929647 -0.368039 -0.017452 +-0.983156 -0.181935 -0.017452 +-0.836868 -0.547126 -0.017452 +-0.929647 -0.368039 -0.017452 +-0.929647 -0.368039 -0.017452 +-0.836868 -0.547126 -0.017452 +-0.836868 -0.547126 -0.017452 +-0.929647 -0.368039 -0.017452 +-0.836868 -0.547126 -0.017452 +-0.706999 -0.706999 -0.017452 +-0.836868 -0.547126 -0.017452 +-0.706999 -0.706999 -0.017452 +-0.706999 -0.706999 -0.017452 +-0.836868 -0.547126 -0.017452 +-0.706999 -0.706999 -0.017452 +-0.547126 -0.836868 -0.017452 +-0.706999 -0.706999 -0.017452 +-0.547126 -0.836868 -0.017452 +-0.547126 -0.836868 -0.017452 +-0.706999 -0.706999 -0.017452 +-0.368039 -0.929647 -0.017452 +-0.547126 -0.836868 -0.017452 +-0.547126 -0.836868 -0.017452 +-0.368039 -0.929647 -0.017452 +-0.368039 -0.929647 -0.017452 +-0.547126 -0.836868 -0.017452 +-0.181935 -0.983156 -0.017452 +-0.368039 -0.929647 -0.017452 +-0.368039 -0.929647 -0.017452 +-0.181935 -0.983156 -0.017452 +-0.181935 -0.983156 -0.017452 +-0.368039 -0.929647 -0.017452 +-0.181935 -0.983156 -0.017452 +0.000000 -0.999848 -0.017452 +-0.181935 -0.983156 -0.017452 +0.000000 -0.999848 -0.017452 +0.000000 -0.999848 -0.017452 +-0.181935 -0.983156 -0.017452 +0.181935 -0.983156 -0.017452 +0.000000 -0.999848 -0.017452 +0.000000 -0.999848 -0.017452 +0.181935 -0.983156 -0.017452 +0.181935 -0.983156 -0.017452 +0.000000 -0.999848 -0.017452 +0.368039 -0.929647 -0.017452 +0.181935 -0.983156 -0.017452 +0.181935 -0.983156 -0.017452 +0.368039 -0.929647 -0.017452 +0.368039 -0.929647 -0.017452 +0.181935 -0.983156 -0.017452 +0.547126 -0.836868 -0.017452 +0.368039 -0.929647 -0.017452 +0.368039 -0.929647 -0.017452 +0.547126 -0.836868 -0.017452 +0.547126 -0.836868 -0.017452 +0.368039 -0.929647 -0.017452 +0.706999 -0.706999 -0.017452 +0.547126 -0.836868 -0.017452 +0.547126 -0.836868 -0.017452 +0.706999 -0.706999 -0.017452 +0.706999 -0.706999 -0.017452 +0.547126 -0.836868 -0.017452 +0.836868 -0.547126 -0.017452 +0.706999 -0.706999 -0.017452 +0.706999 -0.706999 -0.017452 +0.836868 -0.547126 -0.017452 +0.836868 -0.547126 -0.017452 +0.706999 -0.706999 -0.017452 +0.929647 -0.368039 -0.017452 +0.836868 -0.547126 -0.017452 +0.836868 -0.547126 -0.017452 +0.929647 -0.368039 -0.017452 +0.929647 -0.368039 -0.017452 +0.836868 -0.547126 -0.017452 +0.983156 -0.181935 -0.017452 +0.929647 -0.368039 -0.017452 +0.929647 -0.368039 -0.017452 +0.983156 -0.181935 -0.017452 +0.983156 -0.181935 -0.017452 +0.929647 -0.368039 -0.017452 +0.999848 0.000000 -0.017452 +0.983156 -0.181935 -0.017452 +0.983156 -0.181935 -0.017452 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.547126 -0.836868 -0.017452 +0.706999 -0.706999 -0.017452 +0.706999 -0.706999 -0.017452 +0.999848 0.000000 -0.017452 +0.983156 -0.181935 -0.017452 +0.999848 0.000000 -0.017452 +0.983156 -0.181935 -0.017452 +0.983156 -0.181935 -0.017452 +0.999848 0.000000 -0.017452 +0.983156 -0.181935 -0.017452 +0.929647 -0.368039 -0.017452 +0.983156 -0.181935 -0.017452 +0.929647 -0.368039 -0.017452 +0.929647 -0.368039 -0.017452 +0.983156 -0.181935 -0.017452 +0.836868 -0.547126 -0.017452 +0.929647 -0.368039 -0.017452 +0.929647 -0.368039 -0.017452 +0.836868 -0.547126 -0.017452 +0.836868 -0.547126 -0.017452 +0.929647 -0.368039 -0.017452 +0.836868 -0.547126 -0.017452 +0.706999 -0.706999 -0.017452 +0.836868 -0.547126 -0.017452 +0.706999 -0.706999 -0.017452 +0.706999 -0.706999 -0.017452 +0.836868 -0.547126 -0.017452 +-0.983156 -0.181935 -0.017452 +-0.999848 0.000000 -0.017452 +-0.999848 0.000000 -0.017452 +-0.983156 -0.181935 -0.017452 +-0.983156 -0.181935 -0.017452 +-0.999848 0.000000 -0.017452 +-0.929647 -0.368039 -0.017452 +-0.983156 -0.181935 -0.017452 +-0.983156 -0.181935 -0.017452 +-0.929647 -0.368039 -0.017452 +-0.929647 -0.368039 -0.017452 +-0.983156 -0.181935 -0.017452 +-0.929647 -0.368039 -0.017452 +-0.836868 -0.547126 -0.017452 +-0.929647 -0.368039 -0.017452 +-0.836868 -0.547126 -0.017452 +-0.836868 -0.547126 -0.017452 +-0.929647 -0.368039 -0.017452 +-0.706999 -0.706999 -0.017452 +-0.836868 -0.547126 -0.017452 +-0.836868 -0.547126 -0.017452 +-0.706999 -0.706999 -0.017452 +-0.706999 -0.706999 -0.017452 +-0.836868 -0.547126 -0.017452 +-0.547126 -0.836868 -0.017452 +-0.706999 -0.706999 -0.017452 +-0.706999 -0.706999 -0.017452 +-0.547126 -0.836868 -0.017452 +-0.547126 -0.836868 -0.017452 +-0.706999 -0.706999 -0.017452 +-0.547126 -0.836868 -0.017452 +-0.368039 -0.929647 -0.017452 +-0.547126 -0.836868 -0.017452 +-0.368039 -0.929647 -0.017452 +-0.368039 -0.929647 -0.017452 +-0.547126 -0.836868 -0.017452 +-0.368039 -0.929647 -0.017452 +-0.181935 -0.983156 -0.017452 +-0.368039 -0.929647 -0.017452 +-0.181935 -0.983156 -0.017452 +-0.181935 -0.983156 -0.017452 +-0.368039 -0.929647 -0.017452 +0.000000 -0.999848 -0.017452 +-0.181935 -0.983156 -0.017452 +-0.181935 -0.983156 -0.017452 +0.000000 -0.999848 -0.017452 +0.000000 -0.999848 -0.017452 +-0.181935 -0.983156 -0.017452 +0.181935 -0.983156 -0.017452 +0.000000 -0.999848 -0.017452 +0.000000 -0.999848 -0.017452 +0.181935 -0.983156 -0.017452 +0.181935 -0.983156 -0.017452 +0.000000 -0.999848 -0.017452 +0.181935 -0.983156 -0.017452 +0.368039 -0.929647 -0.017452 +0.181935 -0.983156 -0.017452 +0.368039 -0.929647 -0.017452 +0.368039 -0.929647 -0.017452 +0.181935 -0.983156 -0.017452 +0.547126 -0.836868 -0.017452 +0.368039 -0.929647 -0.017452 +0.368039 -0.929647 -0.017452 +0.547126 -0.836868 -0.017452 +0.547126 -0.836868 -0.017452 +0.368039 -0.929647 -0.017452 +0.706999 -0.706999 -0.017452 +0.547126 -0.836868 -0.017452 +0.547126 -0.836868 -0.017452 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.983156 -0.181935 -0.017452 +-0.999848 0.000000 -0.017452 +-0.999848 0.000000 -0.017452 +0.999848 0.000000 -0.017452 +0.983156 -0.181935 -0.017452 +0.999848 0.000000 -0.017452 +0.983156 -0.181935 -0.017452 +0.983156 -0.181935 -0.017452 +0.999848 0.000000 -0.017452 +0.983156 -0.181935 -0.017452 +0.929647 -0.368039 -0.017452 +0.983156 -0.181935 -0.017452 +0.929647 -0.368039 -0.017452 +0.929647 -0.368039 -0.017452 +0.983156 -0.181935 -0.017452 +0.929647 -0.368039 -0.017452 +0.836868 -0.547126 -0.017452 +0.929647 -0.368039 -0.017452 +0.836868 -0.547126 -0.017452 +0.836868 -0.547126 -0.017452 +0.929647 -0.368039 -0.017452 +0.836868 -0.547126 -0.017452 +0.706999 -0.706999 -0.017452 +0.836868 -0.547126 -0.017452 +0.706999 -0.706999 -0.017452 +0.706999 -0.706999 -0.017452 +0.836868 -0.547126 -0.017452 +0.706999 -0.706999 -0.017452 +0.547126 -0.836868 -0.017452 +0.706999 -0.706999 -0.017452 +0.547126 -0.836868 -0.017452 +0.547126 -0.836868 -0.017452 +0.706999 -0.706999 -0.017452 +0.547126 -0.836868 -0.017452 +0.368039 -0.929647 -0.017452 +0.547126 -0.836868 -0.017452 +0.368039 -0.929647 -0.017452 +0.368039 -0.929647 -0.017452 +0.547126 -0.836868 -0.017452 +0.181935 -0.983156 -0.017452 +0.368039 -0.929647 -0.017452 +0.368039 -0.929647 -0.017452 +0.181935 -0.983156 -0.017452 +0.181935 -0.983156 -0.017452 +0.368039 -0.929647 -0.017452 +0.181935 -0.983156 -0.017452 +0.000000 -0.999848 -0.017452 +0.181935 -0.983156 -0.017452 +0.000000 -0.999848 -0.017452 +0.000000 -0.999848 -0.017452 +0.181935 -0.983156 -0.017452 +0.000000 -0.999848 -0.017452 +-0.181935 -0.983156 -0.017452 +0.000000 -0.999848 -0.017452 +-0.181935 -0.983156 -0.017452 +-0.181935 -0.983156 -0.017452 +0.000000 -0.999848 -0.017452 +-0.368039 -0.929647 -0.017452 +-0.181935 -0.983156 -0.017452 +-0.181935 -0.983156 -0.017452 +-0.368039 -0.929647 -0.017452 +-0.368039 -0.929647 -0.017452 +-0.181935 -0.983156 -0.017452 +-0.368039 -0.929647 -0.017452 +-0.547126 -0.836868 -0.017452 +-0.368039 -0.929647 -0.017452 +-0.547126 -0.836868 -0.017452 +-0.547126 -0.836868 -0.017452 +-0.368039 -0.929647 -0.017452 +-0.547126 -0.836868 -0.017452 +-0.706999 -0.706999 -0.017452 +-0.547126 -0.836868 -0.017452 +-0.706999 -0.706999 -0.017452 +-0.706999 -0.706999 -0.017452 +-0.547126 -0.836868 -0.017452 +-0.706999 -0.706999 -0.017452 +-0.836868 -0.547126 -0.017452 +-0.706999 -0.706999 -0.017452 +-0.836868 -0.547126 -0.017452 +-0.836868 -0.547126 -0.017452 +-0.706999 -0.706999 -0.017452 +-0.929647 -0.368039 -0.017452 +-0.836868 -0.547126 -0.017452 +-0.836868 -0.547126 -0.017452 +-0.929647 -0.368039 -0.017452 +-0.929647 -0.368039 -0.017452 +-0.836868 -0.547126 -0.017452 +-0.983156 -0.181935 -0.017452 +-0.929647 -0.368039 -0.017452 +-0.929647 -0.368039 -0.017452 +-0.983156 -0.181935 -0.017452 +-0.983156 -0.181935 -0.017452 +-0.929647 -0.368039 -0.017452 +-0.999848 0.000000 -0.017452 +-0.983156 -0.181935 -0.017452 +-0.983156 -0.181935 -0.017452 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.657460 -0.260282 0.707107 +0.695302 -0.128667 0.707107 +0.695302 -0.128667 0.707107 +0.707107 0.000000 0.707107 +0.695302 -0.128667 0.707107 +0.707107 0.000000 0.707107 +0.695302 -0.128667 0.707107 +0.695302 -0.128667 0.707107 +0.707107 0.000000 0.707107 +-0.695302 -0.128667 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.695302 -0.128667 0.707107 +-0.695302 -0.128667 0.707107 +-0.707107 0.000000 0.707107 +-0.657460 -0.260282 0.707107 +-0.695302 -0.128667 0.707107 +-0.695302 -0.128667 0.707107 +-0.657460 -0.260282 0.707107 +-0.657460 -0.260282 0.707107 +-0.695302 -0.128667 0.707107 +-0.657460 -0.260282 0.707107 +-0.591845 -0.386936 0.707107 +-0.657460 -0.260282 0.707107 +-0.591845 -0.386936 0.707107 +-0.591845 -0.386936 0.707107 +-0.657460 -0.260282 0.707107 +-0.500000 -0.500000 0.707107 +-0.591845 -0.386936 0.707107 +-0.591845 -0.386936 0.707107 +-0.500000 -0.500000 0.707107 +-0.500000 -0.500000 0.707107 +-0.591845 -0.386936 0.707107 +-0.386936 -0.591845 0.707107 +-0.500000 -0.500000 0.707107 +-0.500000 -0.500000 0.707107 +-0.386936 -0.591845 0.707107 +-0.386936 -0.591845 0.707107 +-0.500000 -0.500000 0.707107 +-0.386936 -0.591845 0.707107 +-0.260282 -0.657460 0.707107 +-0.386936 -0.591845 0.707107 +-0.260282 -0.657460 0.707107 +-0.260282 -0.657460 0.707107 +-0.386936 -0.591845 0.707107 +-0.128667 -0.695302 0.707107 +-0.260282 -0.657460 0.707107 +-0.260282 -0.657460 0.707107 +-0.128667 -0.695302 0.707107 +-0.128667 -0.695302 0.707107 +-0.260282 -0.657460 0.707107 +0.000000 -0.707107 0.707107 +-0.128667 -0.695302 0.707107 +-0.128667 -0.695302 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +-0.128667 -0.695302 0.707107 +0.128667 -0.695302 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.128667 -0.695302 0.707107 +0.128667 -0.695302 0.707107 +0.000000 -0.707107 0.707107 +0.260282 -0.657460 0.707107 +0.128667 -0.695302 0.707107 +0.128667 -0.695302 0.707107 +0.260282 -0.657460 0.707107 +0.260282 -0.657460 0.707107 +0.128667 -0.695302 0.707107 +0.386936 -0.591845 0.707107 +0.260282 -0.657460 0.707107 +0.260282 -0.657460 0.707107 +0.386936 -0.591845 0.707107 +0.386936 -0.591845 0.707107 +0.260282 -0.657460 0.707107 +0.500000 -0.500000 0.707107 +0.386936 -0.591845 0.707107 +0.386936 -0.591845 0.707107 +0.500000 -0.500000 0.707107 +0.500000 -0.500000 0.707107 +0.386936 -0.591845 0.707107 +0.500000 -0.500000 0.707107 +0.591845 -0.386936 0.707107 +0.500000 -0.500000 0.707107 +0.591845 -0.386936 0.707107 +0.591845 -0.386936 0.707107 +0.500000 -0.500000 0.707107 +0.657460 -0.260282 0.707107 +0.591845 -0.386936 0.707107 +0.591845 -0.386936 0.707107 +0.657460 -0.260282 0.707107 +0.657460 -0.260282 0.707107 +0.591845 -0.386936 0.707107 +0.695302 -0.128667 0.707107 +0.657460 -0.260282 0.707107 +0.657460 -0.260282 0.707107 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.657460 -0.260282 0.707107 +0.695302 -0.128667 0.707107 +0.695302 -0.128667 0.707107 +0.707107 0.000000 0.707107 +0.695302 -0.128667 0.707107 +0.707107 0.000000 0.707107 +0.695302 -0.128667 0.707107 +0.695302 -0.128667 0.707107 +0.707107 0.000000 0.707107 +-0.695302 -0.128667 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.695302 -0.128667 0.707107 +-0.695302 -0.128667 0.707107 +-0.707107 0.000000 0.707107 +-0.657460 -0.260282 0.707107 +-0.695302 -0.128667 0.707107 +-0.695302 -0.128667 0.707107 +-0.657460 -0.260282 0.707107 +-0.657460 -0.260282 0.707107 +-0.695302 -0.128667 0.707107 +-0.591845 -0.386936 0.707107 +-0.657460 -0.260282 0.707107 +-0.657460 -0.260282 0.707107 +-0.591845 -0.386936 0.707107 +-0.591845 -0.386936 0.707107 +-0.657460 -0.260282 0.707107 +-0.591845 -0.386936 0.707107 +-0.500000 -0.500000 0.707107 +-0.591845 -0.386936 0.707107 +-0.500000 -0.500000 0.707107 +-0.500000 -0.500000 0.707107 +-0.591845 -0.386936 0.707107 +-0.500000 -0.500000 0.707107 +-0.386936 -0.591845 0.707107 +-0.500000 -0.500000 0.707107 +-0.386936 -0.591845 0.707107 +-0.386936 -0.591845 0.707107 +-0.500000 -0.500000 0.707107 +-0.386936 -0.591845 0.707107 +-0.260282 -0.657460 0.707107 +-0.386936 -0.591845 0.707107 +-0.260282 -0.657460 0.707107 +-0.260282 -0.657460 0.707107 +-0.386936 -0.591845 0.707107 +-0.260282 -0.657460 0.707107 +-0.128667 -0.695302 0.707107 +-0.260282 -0.657460 0.707107 +-0.128667 -0.695302 0.707107 +-0.128667 -0.695302 0.707107 +-0.260282 -0.657460 0.707107 +-0.128667 -0.695302 0.707107 +0.000000 -0.707107 0.707107 +-0.128667 -0.695302 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +-0.128667 -0.695302 0.707107 +0.000000 -0.707107 0.707107 +0.128667 -0.695302 0.707107 +0.000000 -0.707107 0.707107 +0.128667 -0.695302 0.707107 +0.128667 -0.695302 0.707107 +0.000000 -0.707107 0.707107 +0.128667 -0.695302 0.707107 +0.260282 -0.657460 0.707107 +0.128667 -0.695302 0.707107 +0.260282 -0.657460 0.707107 +0.260282 -0.657460 0.707107 +0.128667 -0.695302 0.707107 +0.260282 -0.657460 0.707107 +0.386936 -0.591845 0.707107 +0.260282 -0.657460 0.707107 +0.386936 -0.591845 0.707107 +0.386936 -0.591845 0.707107 +0.260282 -0.657460 0.707107 +0.386936 -0.591845 0.707107 +0.500000 -0.500000 0.707107 +0.386936 -0.591845 0.707107 +0.500000 -0.500000 0.707107 +0.500000 -0.500000 0.707107 +0.386936 -0.591845 0.707107 +0.591845 -0.386936 0.707107 +0.500000 -0.500000 0.707107 +0.500000 -0.500000 0.707107 +0.591845 -0.386936 0.707107 +0.591845 -0.386936 0.707107 +0.500000 -0.500000 0.707107 +0.657460 -0.260282 0.707107 +0.591845 -0.386936 0.707107 +0.591845 -0.386936 0.707107 +0.657460 -0.260282 0.707107 +0.657460 -0.260282 0.707107 +0.591845 -0.386936 0.707107 +0.695302 -0.128667 0.707107 +0.657460 -0.260282 0.707107 +0.657460 -0.260282 0.707107 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.695302 -0.128667 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.695302 -0.128667 0.707107 +-0.707107 0.000000 0.707107 +-0.695302 -0.128667 0.707107 +-0.695302 -0.128667 0.707107 +-0.707107 0.000000 0.707107 +-0.657460 -0.260282 0.707107 +-0.695302 -0.128667 0.707107 +-0.695302 -0.128667 0.707107 +-0.657460 -0.260282 0.707107 +-0.657460 -0.260282 0.707107 +-0.695302 -0.128667 0.707107 +-0.657460 -0.260282 0.707107 +-0.591845 -0.386936 0.707107 +-0.657460 -0.260282 0.707107 +-0.591845 -0.386936 0.707107 +-0.591845 -0.386936 0.707107 +-0.657460 -0.260282 0.707107 +-0.591845 -0.386936 0.707107 +-0.500000 -0.500000 0.707107 +-0.591845 -0.386936 0.707107 +-0.500000 -0.500000 0.707107 +-0.500000 -0.500000 0.707107 +-0.591845 -0.386936 0.707107 +-0.500000 -0.500000 0.707107 +-0.386936 -0.591845 0.707107 +-0.500000 -0.500000 0.707107 +-0.386936 -0.591845 0.707107 +-0.386936 -0.591845 0.707107 +-0.500000 -0.500000 0.707107 +-0.260282 -0.657460 0.707107 +-0.386936 -0.591845 0.707107 +-0.386936 -0.591845 0.707107 +-0.260282 -0.657460 0.707107 +-0.260282 -0.657460 0.707107 +-0.386936 -0.591845 0.707107 +-0.128667 -0.695302 0.707107 +-0.260282 -0.657460 0.707107 +-0.260282 -0.657460 0.707107 +-0.128667 -0.695302 0.707107 +-0.128667 -0.695302 0.707107 +-0.260282 -0.657460 0.707107 +-0.128667 -0.695302 0.707107 +0.000000 -0.707107 0.707107 +-0.128667 -0.695302 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +-0.128667 -0.695302 0.707107 +0.000000 -0.707107 0.707107 +0.128667 -0.695302 0.707107 +0.000000 -0.707107 0.707107 +0.128667 -0.695302 0.707107 +0.128667 -0.695302 0.707107 +0.000000 -0.707107 0.707107 +0.260282 -0.657460 0.707107 +0.128667 -0.695302 0.707107 +0.128667 -0.695302 0.707107 +0.260282 -0.657460 0.707107 +0.260282 -0.657460 0.707107 +0.128667 -0.695302 0.707107 +0.386936 -0.591845 0.707107 +0.260282 -0.657460 0.707107 +0.260282 -0.657460 0.707107 +0.386936 -0.591845 0.707107 +0.386936 -0.591845 0.707107 +0.260282 -0.657460 0.707107 +0.500000 -0.500000 0.707107 +0.386936 -0.591845 0.707107 +0.386936 -0.591845 0.707107 +0.500000 -0.500000 0.707107 +0.500000 -0.500000 0.707107 +0.386936 -0.591845 0.707107 +0.591845 -0.386936 0.707107 +0.500000 -0.500000 0.707107 +0.500000 -0.500000 0.707107 +0.591845 -0.386936 0.707107 +0.591845 -0.386936 0.707107 +0.500000 -0.500000 0.707107 +0.657460 -0.260282 0.707107 +0.591845 -0.386936 0.707107 +0.591845 -0.386936 0.707107 +0.657460 -0.260282 0.707107 +0.657460 -0.260282 0.707107 +0.591845 -0.386936 0.707107 +0.695302 -0.128667 0.707107 +0.657460 -0.260282 0.707107 +0.657460 -0.260282 0.707107 +0.695302 -0.128667 0.707107 +0.695302 -0.128667 0.707107 +0.657460 -0.260282 0.707107 +0.707107 0.000000 0.707107 +0.695302 -0.128667 0.707107 +0.695302 -0.128667 0.707107 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 0.000000 0.707107 +0.695302 -0.128667 0.707107 +0.707107 0.000000 0.707107 +-0.695302 -0.128667 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.695302 -0.128667 0.707107 +-0.695302 -0.128667 0.707107 +-0.707107 0.000000 0.707107 +-0.657460 -0.260282 0.707107 +-0.695302 -0.128667 0.707107 +-0.695302 -0.128667 0.707107 +-0.657460 -0.260282 0.707107 +-0.657460 -0.260282 0.707107 +-0.695302 -0.128667 0.707107 +-0.657460 -0.260282 0.707107 +-0.591845 -0.386936 0.707107 +-0.657460 -0.260282 0.707107 +-0.591845 -0.386936 0.707107 +-0.591845 -0.386936 0.707107 +-0.657460 -0.260282 0.707107 +-0.500000 -0.500000 0.707107 +-0.591845 -0.386936 0.707107 +-0.591845 -0.386936 0.707107 +-0.500000 -0.500000 0.707107 +-0.500000 -0.500000 0.707107 +-0.591845 -0.386936 0.707107 +-0.500000 -0.500000 0.707107 +-0.386936 -0.591845 0.707107 +-0.500000 -0.500000 0.707107 +-0.386936 -0.591845 0.707107 +-0.386936 -0.591845 0.707107 +-0.500000 -0.500000 0.707107 +-0.260282 -0.657460 0.707107 +-0.386936 -0.591845 0.707107 +-0.386936 -0.591845 0.707107 +-0.260282 -0.657460 0.707107 +-0.260282 -0.657460 0.707107 +-0.386936 -0.591845 0.707107 +-0.128667 -0.695302 0.707107 +-0.260282 -0.657460 0.707107 +-0.260282 -0.657460 0.707107 +-0.128667 -0.695302 0.707107 +-0.128667 -0.695302 0.707107 +-0.260282 -0.657460 0.707107 +0.000000 -0.707107 0.707107 +-0.128667 -0.695302 0.707107 +-0.128667 -0.695302 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +-0.128667 -0.695302 0.707107 +0.128667 -0.695302 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.128667 -0.695302 0.707107 +0.128667 -0.695302 0.707107 +0.000000 -0.707107 0.707107 +0.260282 -0.657460 0.707107 +0.128667 -0.695302 0.707107 +0.128667 -0.695302 0.707107 +0.260282 -0.657460 0.707107 +0.260282 -0.657460 0.707107 +0.128667 -0.695302 0.707107 +0.260282 -0.657460 0.707107 +0.386936 -0.591845 0.707107 +0.260282 -0.657460 0.707107 +0.386936 -0.591845 0.707107 +0.386936 -0.591845 0.707107 +0.260282 -0.657460 0.707107 +0.500000 -0.500000 0.707107 +0.386936 -0.591845 0.707107 +0.386936 -0.591845 0.707107 +0.500000 -0.500000 0.707107 +0.500000 -0.500000 0.707107 +0.386936 -0.591845 0.707107 +0.591845 -0.386936 0.707107 +0.500000 -0.500000 0.707107 +0.500000 -0.500000 0.707107 +0.591845 -0.386936 0.707107 +0.591845 -0.386936 0.707107 +0.500000 -0.500000 0.707107 +0.657460 -0.260282 0.707107 +0.591845 -0.386936 0.707107 +0.591845 -0.386936 0.707107 +0.657460 -0.260282 0.707107 +0.657460 -0.260282 0.707107 +0.591845 -0.386936 0.707107 +0.695302 -0.128667 0.707107 +0.657460 -0.260282 0.707107 +0.657460 -0.260282 0.707107 +0.695302 -0.128667 0.707107 +0.695302 -0.128667 0.707107 +0.657460 -0.260282 0.707107 +0.695302 -0.128667 0.707107 +0.707107 0.000000 0.707107 +0.695302 -0.128667 0.707107 +-0.997323 0.041800 -0.060000 +-0.980906 0.041112 -0.190088 +-0.994787 0.041694 -0.093058 +-0.971195 0.040705 -0.234784 +-0.997323 0.041800 -0.060000 +-0.997323 0.041800 -0.060000 +0.000000 0.000000 -1.000000 +-0.175884 0.007372 -0.984383 +0.000000 0.000000 -1.000000 +-0.128195 0.005373 -0.991734 +-0.175884 0.007372 -0.984383 +0.000000 0.000000 -1.000000 +-0.253726 0.010634 -0.967218 +-0.175884 0.007372 -0.984383 +-0.128195 0.005373 -0.991734 +-0.253726 0.010634 -0.967218 +-0.355448 0.014898 -0.934577 +-0.175884 0.007372 -0.984383 +-0.376081 0.015762 -0.926453 +-0.355448 0.014898 -0.934577 +-0.253726 0.010634 -0.967218 +-0.376081 0.015762 -0.926453 +-0.528737 0.022161 -0.848497 +-0.355448 0.014898 -0.934577 +-0.491165 0.020586 -0.870824 +-0.528737 0.022161 -0.848497 +-0.376081 0.015762 -0.926453 +-0.598117 0.025069 -0.801017 +-0.528737 0.022161 -0.848497 +-0.491165 0.020586 -0.870824 +-0.598117 0.025069 -0.801017 +-0.684964 0.028709 -0.728011 +-0.528737 0.022161 -0.848497 +-0.694637 0.029114 -0.718772 +-0.684964 0.028709 -0.728011 +-0.598117 0.025069 -0.801017 +-0.694637 0.029114 -0.718772 +-0.814501 0.034138 -0.579157 +-0.684964 0.028709 -0.728011 +-0.777421 0.032584 -0.628136 +-0.814501 0.034138 -0.579157 +-0.694637 0.029114 -0.718772 +-0.846433 0.035476 -0.531313 +-0.814501 0.034138 -0.579157 +-0.777421 0.032584 -0.628136 +-0.846433 0.035476 -0.531313 +-0.910748 0.038172 -0.411194 +-0.814501 0.034138 -0.579157 +-0.938472 0.039334 -0.343108 +-0.910748 0.038172 -0.411194 +-0.846433 0.035476 -0.531313 +-0.938472 0.039334 -0.343108 +-0.971195 0.040705 -0.234784 +-0.910748 0.038172 -0.411194 +-0.980906 0.041112 -0.190088 +-0.971195 0.040705 -0.234784 +-0.938472 0.039334 -0.343108 +-0.980906 0.041112 -0.190088 +-0.997323 0.041800 -0.060000 +-0.971195 0.040705 -0.234784 +0.997323 0.041800 -0.060000 +0.971195 0.040705 -0.234784 +0.997323 0.041800 -0.060000 +0.175884 0.007372 -0.984383 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.175884 0.007372 -0.984383 +0.128538 0.005387 -0.991690 +0.000000 0.000000 -1.000000 +0.175884 0.007372 -0.984383 +0.254773 0.010678 -0.966942 +0.128538 0.005387 -0.991690 +0.355448 0.014898 -0.934577 +0.254773 0.010678 -0.966942 +0.175884 0.007372 -0.984383 +0.355448 0.014898 -0.934577 +0.377211 0.015810 -0.925992 +0.254773 0.010678 -0.966942 +0.528737 0.022161 -0.848497 +0.377211 0.015810 -0.925992 +0.355448 0.014898 -0.934577 +0.528737 0.022161 -0.848497 +0.492775 0.020653 -0.869912 +0.377211 0.015810 -0.925992 +0.528737 0.022161 -0.848497 +0.600383 0.025163 -0.799317 +0.492775 0.020653 -0.869912 +0.684964 0.028709 -0.728011 +0.600383 0.025163 -0.799317 +0.528737 0.022161 -0.848497 +0.684964 0.028709 -0.728011 +0.696573 0.029195 -0.716892 +0.600383 0.025163 -0.799317 +0.814501 0.034138 -0.579157 +0.696573 0.029195 -0.716892 +0.684964 0.028709 -0.728011 +0.814501 0.034138 -0.579157 +0.780017 0.032692 -0.624903 +0.696573 0.029195 -0.716892 +0.814501 0.034138 -0.579157 +0.848072 0.035545 -0.528687 +0.780017 0.032692 -0.624903 +0.910748 0.038172 -0.411194 +0.848072 0.035545 -0.528687 +0.814501 0.034138 -0.579157 +0.910748 0.038172 -0.411194 +0.939156 0.039362 -0.341229 +0.848072 0.035545 -0.528687 +0.971195 0.040705 -0.234784 +0.939156 0.039362 -0.341229 +0.910748 0.038172 -0.411194 +0.971195 0.040705 -0.234784 +0.981082 0.041120 -0.189176 +0.939156 0.039362 -0.341229 +0.971195 0.040705 -0.234784 +0.994813 0.041695 -0.092782 +0.981082 0.041120 -0.189176 +0.971195 0.040705 -0.234784 +0.997323 0.041800 -0.060000 +0.994813 0.041695 -0.092782 +0.000000 -0.981767 0.190088 +0.000000 -0.998198 0.060000 +0.000000 -0.995661 0.093058 +0.000000 0.000000 1.000000 +0.000000 -0.128308 0.991734 +0.000000 0.000000 1.000000 +0.000000 -0.128651 0.991690 +0.000000 -0.128308 0.991734 +0.000000 0.000000 1.000000 +0.000000 -0.254997 0.966942 +0.000000 -0.128308 0.991734 +0.000000 -0.128651 0.991690 +0.000000 -0.254997 0.966942 +0.000000 -0.253949 0.967218 +0.000000 -0.128308 0.991734 +0.000000 -0.254997 0.966942 +0.000000 -0.376411 0.926453 +0.000000 -0.253949 0.967218 +0.000000 -0.377542 0.925992 +0.000000 -0.376411 0.926453 +0.000000 -0.254997 0.966942 +0.000000 -0.493208 0.869912 +0.000000 -0.376411 0.926453 +0.000000 -0.377542 0.925992 +0.000000 -0.493208 0.869912 +0.000000 -0.491596 0.870824 +0.000000 -0.376411 0.926453 +0.000000 -0.600910 0.799317 +0.000000 -0.491596 0.870824 +0.000000 -0.493208 0.869912 +0.000000 -0.600910 0.799317 +0.000000 -0.598642 0.801017 +0.000000 -0.491596 0.870824 +0.000000 -0.697185 0.716892 +0.000000 -0.598642 0.801017 +0.000000 -0.600910 0.799317 +0.000000 -0.697185 0.716892 +0.000000 -0.695246 0.718772 +0.000000 -0.598642 0.801017 +0.000000 -0.780702 0.624903 +0.000000 -0.695246 0.718772 +0.000000 -0.697185 0.716892 +0.000000 -0.780702 0.624903 +0.000000 -0.778104 0.628136 +0.000000 -0.695246 0.718772 +0.000000 -0.780702 0.624903 +0.000000 -0.847176 0.531313 +0.000000 -0.778104 0.628136 +0.000000 -0.848817 0.528687 +0.000000 -0.847176 0.531313 +0.000000 -0.780702 0.624903 +0.000000 -0.939980 0.341229 +0.000000 -0.847176 0.531313 +0.000000 -0.848817 0.528687 +0.000000 -0.939980 0.341229 +0.000000 -0.939296 0.343108 +0.000000 -0.847176 0.531313 +0.000000 -0.981943 0.189176 +0.000000 -0.939296 0.343108 +0.000000 -0.939980 0.341229 +0.000000 -0.981943 0.189176 +0.000000 -0.981767 0.190088 +0.000000 -0.939296 0.343108 +0.000000 -0.995686 0.092782 +0.000000 -0.981767 0.190088 +0.000000 -0.981943 0.189176 +0.000000 -0.998198 0.060000 +0.000000 -0.981767 0.190088 +0.000000 -0.995686 0.092782 +0.000000 -0.998198 0.060000 +0.000000 -0.981767 0.190088 +0.000000 -0.998198 0.060000 +0.000000 0.999848 -0.017452 +0.180226 0.983416 -0.020311 +0.000000 0.999848 -0.017452 +0.999695 0.017145 -0.017749 +0.999848 0.000000 -0.017452 +0.999848 0.000000 -0.017452 +0.999695 0.017145 -0.017749 +0.983106 0.181906 -0.020335 +0.999848 0.000000 -0.017452 +0.980175 0.197064 -0.020549 +0.983106 0.181906 -0.020335 +0.999695 0.017145 -0.017749 +0.980175 0.197064 -0.020549 +0.929559 0.367977 -0.022649 +0.983106 0.181906 -0.020335 +0.924547 0.380386 -0.022778 +0.929559 0.367977 -0.022649 +0.980175 0.197064 -0.020549 +0.924547 0.380386 -0.022778 +0.836761 0.547036 -0.024154 +0.929559 0.367977 -0.022649 +0.830659 0.556254 -0.024209 +0.836761 0.547036 -0.024154 +0.924547 0.380386 -0.022778 +0.830659 0.556254 -0.024209 +0.776125 0.630101 -0.024546 +0.836761 0.547036 -0.024154 +0.700803 0.712928 -0.024677 +0.776125 0.630101 -0.024546 +0.830659 0.556254 -0.024209 +0.700803 0.712928 -0.024677 +0.706891 0.706891 -0.024678 +0.776125 0.630101 -0.024546 +0.700803 0.712928 -0.024677 +0.630101 0.776125 -0.024546 +0.706891 0.706891 -0.024678 +0.541926 0.840080 -0.024123 +0.630101 0.776125 -0.024546 +0.700803 0.712928 -0.024677 +0.541926 0.840080 -0.024123 +0.547036 0.836761 -0.024154 +0.630101 0.776125 -0.024546 +0.541926 0.840080 -0.024123 +0.367977 0.929559 -0.022649 +0.547036 0.836761 -0.024154 +0.364474 0.930939 -0.022612 +0.367977 0.929559 -0.022649 +0.541926 0.840080 -0.024123 +0.364474 0.930939 -0.022612 +0.181906 0.983106 -0.020335 +0.367977 0.929559 -0.022649 +0.180226 0.983416 -0.020311 +0.181906 0.983106 -0.020335 +0.364474 0.930939 -0.022612 +0.180226 0.983416 -0.020311 +0.000000 0.999848 -0.017452 +0.181906 0.983106 -0.020335 +0.000000 0.999848 -0.017452 +0.181906 0.983106 -0.020335 +0.000000 0.999848 -0.017452 +0.983106 0.181906 -0.020335 +0.999848 0.000000 -0.017452 +0.999848 0.000000 -0.017452 +0.983106 0.181906 -0.020335 +0.983106 0.181906 -0.020335 +0.999848 0.000000 -0.017452 +0.929559 0.367977 -0.022649 +0.983106 0.181906 -0.020335 +0.983106 0.181906 -0.020335 +0.929559 0.367977 -0.022649 +0.929559 0.367977 -0.022649 +0.983106 0.181906 -0.020335 +0.836761 0.547036 -0.024154 +0.929559 0.367977 -0.022649 +0.929559 0.367977 -0.022649 +0.836761 0.547036 -0.024154 +0.836761 0.547036 -0.024154 +0.929559 0.367977 -0.022649 +0.776125 0.630101 -0.024546 +0.836761 0.547036 -0.024154 +0.836761 0.547036 -0.024154 +0.776125 0.630101 -0.024546 +0.776125 0.630101 -0.024546 +0.836761 0.547036 -0.024154 +0.706891 0.706891 -0.024678 +0.776125 0.630101 -0.024546 +0.776125 0.630101 -0.024546 +0.706891 0.706891 -0.024678 +0.706891 0.706891 -0.024678 +0.776125 0.630101 -0.024546 +0.706891 0.706891 -0.024678 +0.630101 0.776125 -0.024546 +0.706891 0.706891 -0.024678 +0.630101 0.776125 -0.024546 +0.630101 0.776125 -0.024546 +0.706891 0.706891 -0.024678 +0.630101 0.776125 -0.024546 +0.547036 0.836761 -0.024154 +0.630101 0.776125 -0.024546 +0.547036 0.836761 -0.024154 +0.547036 0.836761 -0.024154 +0.630101 0.776125 -0.024546 +0.547036 0.836761 -0.024154 +0.367977 0.929559 -0.022649 +0.547036 0.836761 -0.024154 +0.367977 0.929559 -0.022649 +0.367977 0.929559 -0.022649 +0.547036 0.836761 -0.024154 +0.367977 0.929559 -0.022649 +0.181906 0.983106 -0.020335 +0.367977 0.929559 -0.022649 +0.181906 0.983106 -0.020335 +0.181906 0.983106 -0.020335 +0.367977 0.929559 -0.022649 +0.181906 0.983106 -0.020335 +0.000000 0.999848 -0.017452 +0.181906 0.983106 -0.020335 +-0.180226 0.983416 -0.020311 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +-0.999848 0.000000 -0.017452 +-0.999695 0.017145 -0.017749 +-0.999848 0.000000 -0.017452 +-0.983106 0.181906 -0.020335 +-0.999695 0.017145 -0.017749 +-0.999848 0.000000 -0.017452 +-0.983106 0.181906 -0.020335 +-0.980175 0.197064 -0.020549 +-0.999695 0.017145 -0.017749 +-0.929559 0.367977 -0.022649 +-0.980175 0.197064 -0.020549 +-0.983106 0.181906 -0.020335 +-0.929559 0.367977 -0.022649 +-0.924547 0.380386 -0.022778 +-0.980175 0.197064 -0.020549 +-0.836761 0.547036 -0.024154 +-0.924547 0.380386 -0.022778 +-0.929559 0.367977 -0.022649 +-0.836761 0.547036 -0.024154 +-0.830659 0.556254 -0.024209 +-0.924547 0.380386 -0.022778 +-0.776125 0.630101 -0.024546 +-0.830659 0.556254 -0.024209 +-0.836761 0.547036 -0.024154 +-0.776125 0.630101 -0.024546 +-0.700803 0.712928 -0.024677 +-0.830659 0.556254 -0.024209 +-0.706891 0.706891 -0.024678 +-0.700803 0.712928 -0.024677 +-0.776125 0.630101 -0.024546 +-0.630101 0.776125 -0.024546 +-0.700803 0.712928 -0.024677 +-0.706891 0.706891 -0.024678 +-0.630101 0.776125 -0.024546 +-0.541926 0.840080 -0.024123 +-0.700803 0.712928 -0.024677 +-0.547036 0.836761 -0.024154 +-0.541926 0.840080 -0.024123 +-0.630101 0.776125 -0.024546 +-0.367977 0.929559 -0.022649 +-0.541926 0.840080 -0.024123 +-0.547036 0.836761 -0.024154 +-0.367977 0.929559 -0.022649 +-0.364474 0.930939 -0.022612 +-0.541926 0.840080 -0.024123 +-0.181906 0.983106 -0.020335 +-0.364474 0.930939 -0.022612 +-0.367977 0.929559 -0.022649 +-0.181906 0.983106 -0.020335 +-0.180226 0.983416 -0.020311 +-0.364474 0.930939 -0.022612 +0.000000 0.999848 -0.017452 +-0.180226 0.983416 -0.020311 +-0.181906 0.983106 -0.020335 +-0.999848 0.000000 -0.017452 +-0.983106 0.181906 -0.020335 +-0.999848 0.000000 -0.017452 +-0.181906 0.983106 -0.020335 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +-0.181906 0.983106 -0.020335 +-0.181906 0.983106 -0.020335 +0.000000 0.999848 -0.017452 +-0.367977 0.929559 -0.022649 +-0.181906 0.983106 -0.020335 +-0.181906 0.983106 -0.020335 +-0.367977 0.929559 -0.022649 +-0.367977 0.929559 -0.022649 +-0.181906 0.983106 -0.020335 +-0.547036 0.836761 -0.024154 +-0.367977 0.929559 -0.022649 +-0.367977 0.929559 -0.022649 +-0.547036 0.836761 -0.024154 +-0.547036 0.836761 -0.024154 +-0.367977 0.929559 -0.022649 +-0.630101 0.776125 -0.024546 +-0.547036 0.836761 -0.024154 +-0.547036 0.836761 -0.024154 +-0.630101 0.776125 -0.024546 +-0.630101 0.776125 -0.024546 +-0.547036 0.836761 -0.024154 +-0.706891 0.706891 -0.024678 +-0.630101 0.776125 -0.024546 +-0.630101 0.776125 -0.024546 +-0.706891 0.706891 -0.024678 +-0.706891 0.706891 -0.024678 +-0.630101 0.776125 -0.024546 +-0.706891 0.706891 -0.024678 +-0.776125 0.630101 -0.024546 +-0.706891 0.706891 -0.024678 +-0.776125 0.630101 -0.024546 +-0.776125 0.630101 -0.024546 +-0.706891 0.706891 -0.024678 +-0.776125 0.630101 -0.024546 +-0.836761 0.547036 -0.024154 +-0.776125 0.630101 -0.024546 +-0.836761 0.547036 -0.024154 +-0.836761 0.547036 -0.024154 +-0.776125 0.630101 -0.024546 +-0.836761 0.547036 -0.024154 +-0.929559 0.367977 -0.022649 +-0.836761 0.547036 -0.024154 +-0.929559 0.367977 -0.022649 +-0.929559 0.367977 -0.022649 +-0.836761 0.547036 -0.024154 +-0.929559 0.367977 -0.022649 +-0.983106 0.181906 -0.020335 +-0.929559 0.367977 -0.022649 +-0.983106 0.181906 -0.020335 +-0.983106 0.181906 -0.020335 +-0.929559 0.367977 -0.022649 +-0.983106 0.181906 -0.020335 +-0.999848 0.000000 -0.017452 +-0.983106 0.181906 -0.020335 +0.683061 -0.126402 -0.719340 +0.694658 0.000000 -0.719340 +0.694658 0.000000 -0.719340 +-0.694658 0.000000 -0.719340 +-0.683061 -0.126402 -0.719340 +-0.694658 0.000000 -0.719340 +-0.683061 -0.126402 -0.719340 +-0.683061 -0.126402 -0.719340 +-0.694658 0.000000 -0.719340 +-0.645885 -0.255700 -0.719340 +-0.683061 -0.126402 -0.719340 +-0.683061 -0.126402 -0.719340 +-0.645885 -0.255700 -0.719340 +-0.645885 -0.255700 -0.719340 +-0.683061 -0.126402 -0.719340 +-0.645885 -0.255700 -0.719340 +-0.581426 -0.380124 -0.719340 +-0.645885 -0.255700 -0.719340 +-0.581426 -0.380124 -0.719340 +-0.581426 -0.380124 -0.719340 +-0.645885 -0.255700 -0.719340 +-0.581426 -0.380124 -0.719340 +-0.491198 -0.491198 -0.719340 +-0.581426 -0.380124 -0.719340 +-0.491198 -0.491198 -0.719340 +-0.491198 -0.491198 -0.719340 +-0.581426 -0.380124 -0.719340 +-0.491198 -0.491198 -0.719340 +-0.380124 -0.581426 -0.719340 +-0.491198 -0.491198 -0.719340 +-0.380124 -0.581426 -0.719340 +-0.380124 -0.581426 -0.719340 +-0.491198 -0.491198 -0.719340 +-0.255700 -0.645885 -0.719340 +-0.380124 -0.581426 -0.719340 +-0.380124 -0.581426 -0.719340 +-0.255700 -0.645885 -0.719340 +-0.255700 -0.645885 -0.719340 +-0.380124 -0.581426 -0.719340 +-0.126402 -0.683061 -0.719340 +-0.255700 -0.645885 -0.719340 +-0.255700 -0.645885 -0.719340 +-0.126402 -0.683061 -0.719340 +-0.126402 -0.683061 -0.719340 +-0.255700 -0.645885 -0.719340 +0.000000 -0.694658 -0.719340 +-0.126402 -0.683061 -0.719340 +-0.126402 -0.683061 -0.719340 +0.000000 -0.694658 -0.719340 +0.000000 -0.694658 -0.719340 +-0.126402 -0.683061 -0.719340 +0.126402 -0.683061 -0.719340 +0.000000 -0.694658 -0.719340 +0.000000 -0.694658 -0.719340 +0.126402 -0.683061 -0.719340 +0.126402 -0.683061 -0.719340 +0.000000 -0.694658 -0.719340 +0.126402 -0.683061 -0.719340 +0.255700 -0.645885 -0.719340 +0.126402 -0.683061 -0.719340 +0.255700 -0.645885 -0.719340 +0.255700 -0.645885 -0.719340 +0.126402 -0.683061 -0.719340 +0.255700 -0.645885 -0.719340 +0.380124 -0.581426 -0.719340 +0.255700 -0.645885 -0.719340 +0.380124 -0.581426 -0.719340 +0.380124 -0.581426 -0.719340 +0.255700 -0.645885 -0.719340 +0.491198 -0.491198 -0.719340 +0.380124 -0.581426 -0.719340 +0.380124 -0.581426 -0.719340 +0.491198 -0.491198 -0.719340 +0.491198 -0.491198 -0.719340 +0.380124 -0.581426 -0.719340 +0.581426 -0.380124 -0.719340 +0.491198 -0.491198 -0.719340 +0.491198 -0.491198 -0.719340 +0.581426 -0.380124 -0.719340 +0.581426 -0.380124 -0.719340 +0.491198 -0.491198 -0.719340 +0.645885 -0.255700 -0.719340 +0.581426 -0.380124 -0.719340 +0.581426 -0.380124 -0.719340 +0.645885 -0.255700 -0.719340 +0.645885 -0.255700 -0.719340 +0.581426 -0.380124 -0.719340 +0.683061 -0.126402 -0.719340 +0.645885 -0.255700 -0.719340 +0.645885 -0.255700 -0.719340 +0.683061 -0.126402 -0.719340 +0.683061 -0.126402 -0.719340 +0.645885 -0.255700 -0.719340 +0.694658 0.000000 -0.719340 +0.683061 -0.126402 -0.719340 +0.683061 -0.126402 -0.719340 +0.983305 0.181935 -0.003176 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.181963 0.983156 -0.017161 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.181963 0.983156 -0.017161 +0.181963 0.983156 -0.017161 +0.000000 0.999848 -0.017452 +0.368095 0.929647 -0.016227 +0.181963 0.983156 -0.017161 +0.181963 0.983156 -0.017161 +0.368095 0.929647 -0.016227 +0.368095 0.929647 -0.016227 +0.181963 0.983156 -0.017161 +0.547210 0.836868 -0.014608 +0.368095 0.929647 -0.016227 +0.368095 0.929647 -0.016227 +0.547210 0.836868 -0.014608 +0.547210 0.836868 -0.014608 +0.368095 0.929647 -0.016227 +0.630298 0.776235 -0.013549 +0.547210 0.836868 -0.014608 +0.547210 0.836868 -0.014608 +0.630298 0.776235 -0.013549 +0.630298 0.776235 -0.013549 +0.547210 0.836868 -0.014608 +0.707107 0.706999 -0.012341 +0.630298 0.776235 -0.013549 +0.630298 0.776235 -0.013549 +0.707107 0.706999 -0.012341 +0.707107 0.706999 -0.012341 +0.630298 0.776235 -0.013549 +0.776353 0.630202 -0.011000 +0.707107 0.706999 -0.012341 +0.707107 0.706999 -0.012341 +0.776353 0.630202 -0.011000 +0.776353 0.630202 -0.011000 +0.707107 0.706999 -0.012341 +0.836995 0.547126 -0.009550 +0.776353 0.630202 -0.011000 +0.776353 0.630202 -0.011000 +0.836995 0.547126 -0.009550 +0.836995 0.547126 -0.009550 +0.776353 0.630202 -0.011000 +0.929788 0.368039 -0.006424 +0.836995 0.547126 -0.009550 +0.836995 0.547126 -0.009550 +0.929788 0.368039 -0.006424 +0.929788 0.368039 -0.006424 +0.836995 0.547126 -0.009550 +0.983305 0.181935 -0.003176 +0.929788 0.368039 -0.006424 +0.929788 0.368039 -0.006424 +0.983305 0.181935 -0.003176 +0.983305 0.181935 -0.003176 +0.929788 0.368039 -0.006424 +1.000000 0.000000 0.000000 +0.983305 0.181935 -0.003176 +0.983305 0.181935 -0.003176 +0.000000 0.999848 -0.017452 +-0.181963 0.983156 -0.017161 +0.000000 0.999848 -0.017452 +-1.000000 0.000000 0.000000 +-0.983305 0.181935 -0.003176 +-1.000000 0.000000 0.000000 +-0.983305 0.181935 -0.003176 +-0.983305 0.181935 -0.003176 +-1.000000 0.000000 0.000000 +-0.983305 0.181935 -0.003176 +-0.929788 0.368039 -0.006424 +-0.983305 0.181935 -0.003176 +-0.929788 0.368039 -0.006424 +-0.929788 0.368039 -0.006424 +-0.983305 0.181935 -0.003176 +-0.929788 0.368039 -0.006424 +-0.836995 0.547126 -0.009550 +-0.929788 0.368039 -0.006424 +-0.836995 0.547126 -0.009550 +-0.836995 0.547126 -0.009550 +-0.929788 0.368039 -0.006424 +-0.836995 0.547126 -0.009550 +-0.776353 0.630202 -0.011000 +-0.836995 0.547126 -0.009550 +-0.776353 0.630202 -0.011000 +-0.776353 0.630202 -0.011000 +-0.836995 0.547126 -0.009550 +-0.776353 0.630202 -0.011000 +-0.707107 0.706999 -0.012341 +-0.776353 0.630202 -0.011000 +-0.707107 0.706999 -0.012341 +-0.707107 0.706999 -0.012341 +-0.776353 0.630202 -0.011000 +-0.707107 0.706999 -0.012341 +-0.630298 0.776235 -0.013549 +-0.707107 0.706999 -0.012341 +-0.630298 0.776235 -0.013549 +-0.630298 0.776235 -0.013549 +-0.707107 0.706999 -0.012341 +-0.630298 0.776235 -0.013549 +-0.547210 0.836868 -0.014608 +-0.630298 0.776235 -0.013549 +-0.547210 0.836868 -0.014608 +-0.547210 0.836868 -0.014608 +-0.630298 0.776235 -0.013549 +-0.547210 0.836868 -0.014608 +-0.368095 0.929647 -0.016227 +-0.547210 0.836868 -0.014608 +-0.368095 0.929647 -0.016227 +-0.368095 0.929647 -0.016227 +-0.547210 0.836868 -0.014608 +-0.368095 0.929647 -0.016227 +-0.181963 0.983156 -0.017161 +-0.368095 0.929647 -0.016227 +-0.181963 0.983156 -0.017161 +-0.181963 0.983156 -0.017161 +-0.368095 0.929647 -0.016227 +-0.181963 0.983156 -0.017161 +0.000000 0.999848 -0.017452 +-0.181963 0.983156 -0.017161 +0.000000 0.980325 -0.197392 +0.000000 0.999848 -0.017452 +0.000000 0.999848 -0.017452 +0.000000 0.000000 -1.000000 +0.000000 0.180253 -0.983620 +0.000000 0.000000 -1.000000 +0.000000 0.196360 -0.980532 +0.000000 0.180253 -0.983620 +0.000000 0.000000 -1.000000 +0.000000 0.196360 -0.980532 +0.000000 0.364530 -0.931192 +0.000000 0.180253 -0.983620 +0.000000 0.389154 -0.921173 +0.000000 0.364530 -0.931192 +0.000000 0.196360 -0.980532 +0.000000 0.389154 -0.921173 +0.000000 0.542008 -0.840373 +0.000000 0.364530 -0.931192 +0.000000 0.559423 -0.828883 +0.000000 0.542008 -0.840373 +0.000000 0.389154 -0.921173 +0.000000 0.559423 -0.828883 +0.000000 0.700909 -0.713250 +0.000000 0.542008 -0.840373 +0.000000 0.700909 -0.713250 +0.000000 0.700909 -0.713250 +0.000000 0.559423 -0.828883 +0.000000 0.700909 -0.713250 +0.000000 0.830786 -0.556592 +0.000000 0.700909 -0.713250 +0.000000 0.818993 -0.573803 +0.000000 0.830786 -0.556592 +0.000000 0.700909 -0.713250 +0.000000 0.914241 -0.405171 +0.000000 0.830786 -0.556592 +0.000000 0.818993 -0.573803 +0.000000 0.914241 -0.405171 +0.000000 0.924688 -0.380726 +0.000000 0.830786 -0.556592 +0.000000 0.976956 -0.213443 +0.000000 0.924688 -0.380726 +0.000000 0.914241 -0.405171 +0.000000 0.976956 -0.213443 +0.000000 0.980325 -0.197392 +0.000000 0.924688 -0.380726 +0.000000 0.999848 -0.017452 +0.000000 0.980325 -0.197392 +0.000000 0.976956 -0.213443 +0.000000 0.999848 -0.017452 +0.000000 0.980325 -0.197392 +0.000000 0.999848 -0.017452 +0.000000 0.000000 -1.000000 +0.000000 0.196360 -0.980532 +0.000000 0.000000 -1.000000 +0.000000 0.180253 -0.983620 +0.000000 0.196360 -0.980532 +0.000000 0.000000 -1.000000 +0.000000 0.364530 -0.931192 +0.000000 0.196360 -0.980532 +0.000000 0.180253 -0.983620 +0.000000 0.364530 -0.931192 +0.000000 0.389154 -0.921173 +0.000000 0.196360 -0.980532 +0.000000 0.542008 -0.840373 +0.000000 0.389154 -0.921173 +0.000000 0.364530 -0.931192 +0.000000 0.542008 -0.840373 +0.000000 0.559423 -0.828883 +0.000000 0.389154 -0.921173 +0.000000 0.700909 -0.713250 +0.000000 0.559423 -0.828883 +0.000000 0.542008 -0.840373 +0.000000 0.700909 -0.713250 +0.000000 0.700909 -0.713250 +0.000000 0.559423 -0.828883 +0.000000 0.830786 -0.556592 +0.000000 0.700909 -0.713250 +0.000000 0.700909 -0.713250 +0.000000 0.830786 -0.556592 +0.000000 0.818993 -0.573803 +0.000000 0.700909 -0.713250 +0.000000 0.830786 -0.556592 +0.000000 0.914241 -0.405171 +0.000000 0.818993 -0.573803 +0.000000 0.924688 -0.380726 +0.000000 0.914241 -0.405171 +0.000000 0.830786 -0.556592 +0.000000 0.924688 -0.380726 +0.000000 0.976956 -0.213443 +0.000000 0.914241 -0.405171 +0.000000 0.980325 -0.197392 +0.000000 0.976956 -0.213443 +0.000000 0.924688 -0.380726 +0.000000 0.980325 -0.197392 +0.000000 0.999848 -0.017452 +0.000000 0.976956 -0.213443 +0.000000 0.389154 -0.921173 +0.000000 0.196360 -0.980532 +0.000000 0.196360 -0.980532 +0.000000 0.000000 -1.000000 +0.000000 0.196360 -0.980532 +0.000000 0.000000 -1.000000 +0.000000 0.196360 -0.980532 +0.000000 0.196360 -0.980532 +0.000000 0.000000 -1.000000 +0.000000 0.999848 -0.017452 +0.000000 0.976956 -0.213443 +0.000000 0.999848 -0.017452 +0.000000 0.976956 -0.213443 +0.000000 0.976956 -0.213443 +0.000000 0.999848 -0.017452 +0.000000 0.976956 -0.213443 +0.000000 0.914241 -0.405171 +0.000000 0.976956 -0.213443 +0.000000 0.914241 -0.405171 +0.000000 0.914241 -0.405171 +0.000000 0.976956 -0.213443 +0.000000 0.914241 -0.405171 +0.000000 0.818993 -0.573803 +0.000000 0.914241 -0.405171 +0.000000 0.818993 -0.573803 +0.000000 0.818993 -0.573803 +0.000000 0.914241 -0.405171 +0.000000 0.700909 -0.713250 +0.000000 0.818993 -0.573803 +0.000000 0.818993 -0.573803 +0.000000 0.700909 -0.713250 +0.000000 0.700909 -0.713250 +0.000000 0.818993 -0.573803 +0.000000 0.559423 -0.828883 +0.000000 0.700909 -0.713250 +0.000000 0.700909 -0.713250 +0.000000 0.559423 -0.828883 +0.000000 0.559423 -0.828883 +0.000000 0.700909 -0.713250 +0.000000 0.389154 -0.921173 +0.000000 0.559423 -0.828883 +0.000000 0.559423 -0.828883 +0.000000 0.389154 -0.921173 +0.000000 0.389154 -0.921173 +0.000000 0.559423 -0.828883 +0.000000 0.196360 -0.980532 +0.000000 0.389154 -0.921173 +0.000000 0.389154 -0.921173 + + + + + + + + + + + +0.469416 0.579828 +0.467794 0.573060 +0.467537 0.569917 +0.466789 0.569917 +0.468616 0.576274 +0.467058 0.573213 +0.470042 0.579368 +0.467920 0.576584 +0.499023 0.569917 +0.498275 0.569917 +0.498754 0.573213 +0.498018 0.573060 +0.497891 0.576584 +0.496396 0.579828 +0.497196 0.576274 +0.494302 0.582724 +0.495769 0.579368 +0.493773 0.582130 +0.491725 0.585077 +0.491316 0.584373 +0.488839 0.586757 +0.488563 0.585975 +0.485839 0.587727 +0.485702 0.586900 +0.482906 0.588029 +0.482906 0.587188 +0.479973 0.587727 +0.476973 0.586757 +0.480109 0.586900 +0.474086 0.585077 +0.477249 0.585975 +0.471509 0.582724 +0.474496 0.584373 +0.472039 0.582130 +0.436288 0.655200 +0.432854 0.655200 +0.426404 0.654535 +0.426350 0.655200 +0.422916 0.655200 +0.423028 0.653833 +0.426578 0.653854 +0.423386 0.652434 +0.426880 0.653200 +0.424006 0.651089 +0.427302 0.652615 +0.427822 0.652141 +0.424875 0.649887 +0.425944 0.648912 +0.428405 0.651802 +0.427141 0.648214 +0.429010 0.651606 +0.428385 0.647812 +0.429602 0.651545 +0.429602 0.647687 +0.430194 0.651606 +0.430818 0.647812 +0.430799 0.651802 +0.432063 0.648214 +0.431382 0.652141 +0.433261 0.648912 +0.431902 0.652615 +0.434329 0.649887 +0.432324 0.653200 +0.435198 0.651089 +0.432626 0.653854 +0.435818 0.652434 +0.432800 0.654535 +0.436176 0.653833 +0.426404 0.654535 +0.426350 0.655200 +0.426350 0.655200 +0.426404 0.654535 +0.432800 0.654535 +0.432854 0.655200 +0.432854 0.655200 +0.432626 0.653854 +0.432800 0.654535 +0.432626 0.653854 +0.432324 0.653200 +0.432324 0.653200 +0.431902 0.652615 +0.431902 0.652615 +0.431382 0.652141 +0.430799 0.651802 +0.431382 0.652141 +0.430799 0.651802 +0.430194 0.651606 +0.430194 0.651606 +0.429602 0.651545 +0.429010 0.651606 +0.429602 0.651545 +0.429010 0.651606 +0.428405 0.651802 +0.428405 0.651802 +0.427822 0.652141 +0.427302 0.652615 +0.427822 0.652141 +0.427302 0.652615 +0.426880 0.653200 +0.426578 0.653854 +0.426880 0.653200 +0.426578 0.653854 +0.533487 0.653200 +0.532957 0.655200 +0.529524 0.655200 +0.533012 0.654535 +0.533186 0.653854 +0.529636 0.653833 +0.542784 0.653833 +0.542895 0.655200 +0.539462 0.655200 +0.539408 0.654535 +0.542426 0.652434 +0.539234 0.653854 +0.541806 0.651089 +0.538932 0.653200 +0.540937 0.649887 +0.538510 0.652615 +0.539868 0.648912 +0.537990 0.652141 +0.538671 0.648214 +0.537407 0.651802 +0.537426 0.647812 +0.536802 0.651606 +0.536210 0.647687 +0.536210 0.651545 +0.534993 0.647812 +0.535618 0.651606 +0.533749 0.648214 +0.535013 0.651802 +0.532551 0.648912 +0.534430 0.652141 +0.531482 0.649887 +0.533910 0.652615 +0.530614 0.651089 +0.529994 0.652434 +0.532957 0.655200 +0.532957 0.655200 +0.539462 0.655200 +0.539462 0.655200 +0.539408 0.654535 +0.539234 0.653854 +0.539408 0.654535 +0.538932 0.653200 +0.539234 0.653854 +0.538932 0.653200 +0.538510 0.652615 +0.538510 0.652615 +0.537990 0.652141 +0.537990 0.652141 +0.537407 0.651802 +0.536802 0.651606 +0.537407 0.651802 +0.536802 0.651606 +0.536210 0.651545 +0.536210 0.651545 +0.535618 0.651606 +0.535618 0.651606 +0.535013 0.651802 +0.535013 0.651802 +0.534430 0.652141 +0.534430 0.652141 +0.533910 0.652615 +0.533910 0.652615 +0.533487 0.653200 +0.533487 0.653200 +0.533186 0.653854 +0.533186 0.653854 +0.533012 0.654535 +0.533012 0.654535 +0.554640 0.529306 +0.551207 0.529306 +0.544702 0.529306 +0.541269 0.529306 +0.544757 0.528641 +0.541381 0.527939 +0.544931 0.527961 +0.541739 0.526541 +0.545232 0.527306 +0.542359 0.525195 +0.545655 0.526722 +0.543227 0.523994 +0.546175 0.526247 +0.544296 0.523018 +0.546758 0.525908 +0.545494 0.522321 +0.547363 0.525712 +0.546738 0.521919 +0.547955 0.525651 +0.547955 0.521793 +0.548546 0.525712 +0.549171 0.521919 +0.549152 0.525908 +0.550416 0.522321 +0.549735 0.526247 +0.551613 0.523018 +0.550255 0.526722 +0.552682 0.523994 +0.550677 0.527306 +0.553550 0.525195 +0.550979 0.527961 +0.554171 0.526541 +0.551153 0.528641 +0.554529 0.527939 +0.544931 0.527961 +0.544702 0.529306 +0.544702 0.529306 +0.544757 0.528641 +0.544931 0.527961 +0.544757 0.528641 +0.551153 0.528641 +0.551207 0.529306 +0.551207 0.529306 +0.551153 0.528641 +0.550979 0.527961 +0.550677 0.527306 +0.550979 0.527961 +0.550677 0.527306 +0.550255 0.526722 +0.550255 0.526722 +0.549735 0.526247 +0.549735 0.526247 +0.549152 0.525908 +0.549152 0.525908 +0.548546 0.525712 +0.548546 0.525712 +0.547955 0.525651 +0.547955 0.525651 +0.547363 0.525712 +0.547363 0.525712 +0.546758 0.525908 +0.546758 0.525908 +0.546175 0.526247 +0.546175 0.526247 +0.545655 0.526722 +0.545655 0.526722 +0.545232 0.527306 +0.545232 0.527306 +0.424543 0.529306 +0.421109 0.529306 +0.414605 0.529306 +0.411171 0.529306 +0.414659 0.528641 +0.411283 0.527939 +0.414833 0.527961 +0.411641 0.526541 +0.415135 0.527306 +0.412261 0.525195 +0.415557 0.526722 +0.413130 0.523994 +0.416077 0.526247 +0.414199 0.523018 +0.416660 0.525908 +0.415396 0.522321 +0.417265 0.525712 +0.416641 0.521919 +0.417857 0.525651 +0.417857 0.521793 +0.418449 0.525712 +0.419074 0.521919 +0.419054 0.525908 +0.420318 0.522321 +0.419637 0.526247 +0.421516 0.523018 +0.420157 0.526722 +0.422584 0.523994 +0.420579 0.527306 +0.423453 0.525195 +0.420881 0.527961 +0.424073 0.526541 +0.421055 0.528641 +0.424431 0.527939 +0.414605 0.529306 +0.414605 0.529306 +0.421109 0.529306 +0.421109 0.529306 +0.421055 0.528641 +0.420881 0.527961 +0.421055 0.528641 +0.420881 0.527961 +0.420579 0.527306 +0.420579 0.527306 +0.420157 0.526722 +0.420157 0.526722 +0.419637 0.526247 +0.419637 0.526247 +0.419054 0.525908 +0.419054 0.525908 +0.418449 0.525712 +0.418449 0.525712 +0.417857 0.525651 +0.417857 0.525651 +0.417265 0.525712 +0.417265 0.525712 +0.416660 0.525908 +0.416660 0.525908 +0.416077 0.526247 +0.416077 0.526247 +0.415557 0.526722 +0.415557 0.526722 +0.415135 0.527306 +0.415135 0.527306 +0.414833 0.527961 +0.414833 0.527961 +0.414659 0.528641 +0.414659 0.528641 +0.555182 0.529306 +0.555182 0.529306 +0.540848 0.527828 +0.540727 0.529306 +0.540727 0.529306 +0.540848 0.527828 +0.541235 0.526317 +0.541235 0.526317 +0.541905 0.524862 +0.541905 0.524862 +0.542844 0.523563 +0.542844 0.523563 +0.544000 0.522508 +0.544000 0.522508 +0.545294 0.521754 +0.545294 0.521754 +0.546640 0.521320 +0.546640 0.521320 +0.547955 0.521184 +0.547955 0.521184 +0.549270 0.521320 +0.549270 0.521320 +0.550615 0.521754 +0.550615 0.521754 +0.551910 0.522508 +0.551910 0.522508 +0.553065 0.523563 +0.554004 0.524862 +0.553065 0.523563 +0.554004 0.524862 +0.554675 0.526316 +0.554675 0.526316 +0.555062 0.527828 +0.555062 0.527828 +0.425085 0.529306 +0.425085 0.529306 +0.410629 0.529306 +0.410629 0.529306 +0.410750 0.527828 +0.410750 0.527828 +0.411137 0.526317 +0.411137 0.526317 +0.411808 0.524862 +0.411808 0.524862 +0.412746 0.523563 +0.412746 0.523563 +0.413902 0.522508 +0.413902 0.522508 +0.415197 0.521754 +0.415197 0.521754 +0.416542 0.521320 +0.416542 0.521320 +0.417857 0.521184 +0.417857 0.521184 +0.419172 0.521320 +0.419172 0.521320 +0.420518 0.521754 +0.420518 0.521754 +0.421812 0.522508 +0.421812 0.522508 +0.422968 0.523563 +0.422968 0.523563 +0.423907 0.524862 +0.423907 0.524862 +0.424577 0.526317 +0.424577 0.526317 +0.424964 0.527828 +0.424964 0.527828 +0.543438 0.655200 +0.543438 0.655200 +0.528982 0.655200 +0.528982 0.655200 +0.529103 0.653722 +0.529103 0.653722 +0.529490 0.652210 +0.530160 0.650755 +0.529490 0.652210 +0.530160 0.650755 +0.531099 0.649457 +0.531099 0.649457 +0.532255 0.648402 +0.533549 0.647648 +0.532255 0.648402 +0.534895 0.647213 +0.533549 0.647648 +0.534895 0.647213 +0.536210 0.647078 +0.536210 0.647078 +0.537525 0.647213 +0.537525 0.647213 +0.538870 0.647648 +0.538870 0.647648 +0.540165 0.648402 +0.540165 0.648402 +0.541321 0.649457 +0.541321 0.649457 +0.542259 0.650755 +0.542259 0.650755 +0.542930 0.652210 +0.542930 0.652210 +0.543317 0.653722 +0.543317 0.653722 +0.436830 0.655200 +0.436830 0.655200 +0.422495 0.653722 +0.422374 0.655200 +0.422374 0.655200 +0.422495 0.653722 +0.422882 0.652210 +0.422882 0.652210 +0.423553 0.650755 +0.423553 0.650755 +0.424491 0.649457 +0.425647 0.648402 +0.424491 0.649457 +0.425647 0.648402 +0.426942 0.647648 +0.426942 0.647648 +0.428287 0.647213 +0.428287 0.647213 +0.429602 0.647078 +0.429602 0.647078 +0.430917 0.647213 +0.430917 0.647213 +0.432262 0.647648 +0.432262 0.647648 +0.433557 0.648402 +0.433557 0.648402 +0.434713 0.649457 +0.434713 0.649457 +0.435651 0.650755 +0.435651 0.650755 +0.436322 0.652210 +0.436322 0.652210 +0.436709 0.653722 +0.436709 0.653722 +0.436658 0.652061 +0.437064 0.653648 +0.437191 0.655200 +0.437393 0.655200 +0.421811 0.655200 +0.422013 0.655200 +0.421941 0.653607 +0.422358 0.651977 +0.422140 0.653648 +0.423081 0.650409 +0.422546 0.652061 +0.423250 0.650533 +0.424093 0.649009 +0.424236 0.649170 +0.425339 0.647872 +0.426734 0.647059 +0.425449 0.648062 +0.426809 0.647270 +0.428184 0.646591 +0.429602 0.646445 +0.428221 0.646814 +0.429602 0.646671 +0.431020 0.646591 +0.430983 0.646814 +0.432470 0.647059 +0.433865 0.647872 +0.432396 0.647270 +0.435111 0.649009 +0.433755 0.648062 +0.434968 0.649170 +0.436123 0.650409 +0.435954 0.650533 +0.436846 0.651977 +0.437263 0.653607 +0.539003 0.647270 +0.543672 0.653648 +0.543799 0.655200 +0.544001 0.655200 +0.543871 0.653607 +0.543266 0.652061 +0.543454 0.651977 +0.542562 0.650533 +0.542731 0.650409 +0.541576 0.649169 +0.541719 0.649009 +0.540363 0.648062 +0.528419 0.655200 +0.528621 0.655200 +0.528549 0.653607 +0.528966 0.651977 +0.528747 0.653648 +0.529154 0.652061 +0.529689 0.650409 +0.529858 0.650533 +0.530701 0.649009 +0.530844 0.649169 +0.531947 0.647872 +0.532057 0.648062 +0.533342 0.647059 +0.533416 0.647270 +0.534792 0.646591 +0.534829 0.646814 +0.536210 0.646445 +0.537628 0.646591 +0.536210 0.646671 +0.537591 0.646814 +0.539078 0.647059 +0.540473 0.647872 +0.410066 0.529306 +0.410268 0.529306 +0.425319 0.527754 +0.425446 0.529306 +0.425648 0.529306 +0.424913 0.526167 +0.425518 0.527713 +0.425101 0.526084 +0.424209 0.524640 +0.423223 0.523276 +0.424378 0.524515 +0.423366 0.523115 +0.422010 0.522168 +0.422120 0.521978 +0.420651 0.521377 +0.420725 0.521166 +0.419238 0.520920 +0.419275 0.520697 +0.417857 0.520778 +0.417857 0.520551 +0.416476 0.520920 +0.416439 0.520697 +0.415064 0.521377 +0.414989 0.521166 +0.413704 0.522168 +0.413594 0.521978 +0.412491 0.523276 +0.412348 0.523115 +0.411505 0.524640 +0.411336 0.524515 +0.410801 0.526167 +0.410613 0.526084 +0.410395 0.527754 +0.410196 0.527713 +0.555199 0.526084 +0.555417 0.527754 +0.555544 0.529306 +0.555746 0.529306 +0.555011 0.526167 +0.555615 0.527713 +0.540164 0.529306 +0.540366 0.529306 +0.540294 0.527713 +0.540492 0.527754 +0.540711 0.526084 +0.541434 0.524515 +0.540899 0.526167 +0.541603 0.524640 +0.542446 0.523115 +0.542588 0.523276 +0.543692 0.521978 +0.543802 0.522168 +0.545087 0.521166 +0.546537 0.520697 +0.545161 0.521377 +0.546574 0.520920 +0.547955 0.520551 +0.547955 0.520778 +0.549372 0.520697 +0.549336 0.520920 +0.550823 0.521166 +0.552218 0.521978 +0.550748 0.521377 +0.553464 0.523115 +0.552108 0.522168 +0.553321 0.523276 +0.554476 0.524515 +0.554307 0.524640 +0.541608 0.684056 +0.541763 0.684661 +0.541811 0.685252 +0.541811 0.685252 +0.541608 0.684056 +0.541763 0.684661 +0.536029 0.685252 +0.536029 0.685252 +0.536077 0.684661 +0.536232 0.684056 +0.536077 0.684661 +0.536232 0.684056 +0.536500 0.683474 +0.536500 0.683474 +0.536876 0.682955 +0.536876 0.682955 +0.537338 0.682532 +0.537338 0.682532 +0.537856 0.682231 +0.537856 0.682231 +0.538394 0.682057 +0.538394 0.682057 +0.538920 0.682003 +0.538920 0.682003 +0.539446 0.682057 +0.539446 0.682057 +0.539984 0.682231 +0.539984 0.682231 +0.540502 0.682532 +0.540965 0.682955 +0.540502 0.682532 +0.540965 0.682955 +0.541340 0.683474 +0.541340 0.683474 +0.429734 0.684661 +0.429783 0.685252 +0.429783 0.685252 +0.429734 0.684661 +0.424001 0.685252 +0.424001 0.685252 +0.424049 0.684661 +0.424049 0.684661 +0.424204 0.684056 +0.424204 0.684056 +0.424472 0.683474 +0.424472 0.683474 +0.424847 0.682955 +0.424847 0.682955 +0.425310 0.682532 +0.425310 0.682532 +0.425827 0.682231 +0.425827 0.682231 +0.426366 0.682057 +0.426366 0.682057 +0.426892 0.682003 +0.426892 0.682003 +0.427418 0.682057 +0.427418 0.682057 +0.427956 0.682231 +0.427956 0.682231 +0.428474 0.682532 +0.428474 0.682532 +0.428936 0.682955 +0.428936 0.682955 +0.429311 0.683474 +0.429311 0.683474 +0.429580 0.684056 +0.429580 0.684056 +0.489294 0.562738 +0.491940 0.569917 +0.491940 0.569917 +0.491790 0.568070 +0.491790 0.568070 +0.491306 0.566180 +0.491306 0.566180 +0.490468 0.564362 +0.489294 0.562738 +0.490468 0.564362 +0.473871 0.569917 +0.473871 0.569917 +0.474022 0.568070 +0.474022 0.568070 +0.474506 0.566180 +0.474506 0.566180 +0.475344 0.564362 +0.475344 0.564362 +0.476517 0.562738 +0.477962 0.561419 +0.476517 0.562738 +0.477962 0.561419 +0.479580 0.560477 +0.479580 0.560477 +0.481262 0.559934 +0.481262 0.559934 +0.482906 0.559764 +0.482906 0.559764 +0.484550 0.559934 +0.484550 0.559934 +0.486232 0.560477 +0.486232 0.560477 +0.487850 0.561419 +0.487850 0.561419 +0.467058 0.566621 +0.466915 0.566592 +0.466644 0.569917 +0.466789 0.569917 +0.499023 0.569917 +0.499168 0.569917 +0.498754 0.566621 +0.498897 0.566592 +0.497891 0.563250 +0.498026 0.563190 +0.496396 0.560006 +0.496517 0.559917 +0.494302 0.557110 +0.494405 0.556995 +0.491725 0.554758 +0.491805 0.554621 +0.488839 0.553077 +0.488892 0.552925 +0.485839 0.552108 +0.485865 0.551947 +0.482906 0.551805 +0.482906 0.551642 +0.479973 0.552108 +0.479947 0.551947 +0.476973 0.553077 +0.476920 0.552925 +0.474086 0.554758 +0.471509 0.557110 +0.474007 0.554621 +0.471407 0.556995 +0.469416 0.560006 +0.469295 0.559917 +0.467920 0.563250 +0.467786 0.563190 +0.548858 0.673068 +0.548618 0.672799 +0.548618 0.691075 +0.548858 0.691344 +0.438637 0.695205 +0.420745 0.695205 +0.420567 0.695405 +0.545245 0.695405 +0.545067 0.695205 +0.527175 0.695141 +0.438637 0.695141 +0.527175 0.695205 +0.417193 0.691075 +0.417193 0.672799 +0.416954 0.673068 +0.416954 0.691344 +0.413580 0.668738 +0.436830 0.668738 +0.391562 0.668945 +0.391092 0.669007 +0.392654 0.668883 +0.413340 0.669007 +0.394394 0.668824 +0.396737 0.668771 +0.399563 0.668728 +0.402698 0.668698 +0.405948 0.668680 +0.409131 0.668674 +0.436830 0.668674 +0.528982 0.668674 +0.528982 0.668738 +0.552471 0.669007 +0.574720 0.669007 +0.574250 0.668945 +0.552232 0.668738 +0.573158 0.668883 +0.571418 0.668824 +0.569075 0.668771 +0.566249 0.668728 +0.563113 0.668698 +0.559864 0.668680 +0.556680 0.668674 +0.547955 0.521184 +0.391092 0.669007 +0.410750 0.527828 +0.410629 0.529306 +0.410750 0.530784 +0.411137 0.532296 +0.411808 0.533751 +0.412746 0.535049 +0.413902 0.536105 +0.580253 0.520668 +0.555182 0.529306 +0.555062 0.530784 +0.554675 0.532296 +0.554004 0.533751 +0.553065 0.535049 +0.551910 0.536105 +0.550615 0.536858 +0.574720 0.669007 +0.549270 0.537293 +0.413340 0.669007 +0.415197 0.536858 +0.416542 0.537293 +0.547955 0.537428 +0.475344 0.564362 +0.423907 0.533751 +0.555062 0.527828 +0.411137 0.526317 +0.413998 0.669075 +0.424847 0.687549 +0.540502 0.687971 +0.552471 0.669007 +0.423553 0.659644 +0.415895 0.670197 +0.416365 0.670846 +0.424491 0.660943 +0.549916 0.670197 +0.540165 0.661998 +0.541321 0.660943 +0.550494 0.669669 +0.417857 0.537429 +0.546640 0.537293 +0.425310 0.687971 +0.539984 0.688273 +0.422968 0.535049 +0.476517 0.562738 +0.424577 0.532296 +0.474506 0.566180 +0.416700 0.671573 +0.549447 0.670846 +0.414671 0.669293 +0.551814 0.669075 +0.415318 0.669669 +0.551141 0.669293 +0.542259 0.659644 +0.422882 0.658190 +0.554675 0.526316 +0.411808 0.524862 +0.545294 0.536858 +0.419172 0.537293 +0.425647 0.661998 +0.424472 0.687030 +0.540965 0.687549 +0.538870 0.662752 +0.421812 0.536105 +0.549112 0.671573 +0.416893 0.672329 +0.545902 0.695337 +0.546575 0.695120 +0.547222 0.694743 +0.547800 0.694215 +0.548269 0.693566 +0.548605 0.692839 +0.548798 0.692083 +0.548858 0.691344 +0.548858 0.673068 +0.541340 0.687030 +0.541608 0.686448 +0.541763 0.685843 +0.541811 0.685252 +0.541763 0.684661 +0.541608 0.684056 +0.541340 0.683474 +0.540965 0.682955 +0.540502 0.682532 +0.420567 0.695405 +0.419909 0.695337 +0.419237 0.695120 +0.418590 0.694743 +0.418012 0.694215 +0.417543 0.693566 +0.417207 0.692839 +0.417014 0.692083 +0.416954 0.691344 +0.424204 0.686448 +0.424049 0.685843 +0.424001 0.685252 +0.424049 0.684661 +0.424204 0.684056 +0.424472 0.683474 +0.424847 0.682955 +0.425310 0.682532 +0.425827 0.682231 +0.477962 0.561419 +0.424964 0.530784 +0.474022 0.568070 +0.425827 0.688273 +0.539446 0.688447 +0.420518 0.536858 +0.544000 0.536105 +0.554004 0.524862 +0.412746 0.523563 +0.426366 0.682057 +0.539984 0.682231 +0.426942 0.662752 +0.416954 0.673068 +0.426892 0.682003 +0.428287 0.663186 +0.427418 0.682057 +0.427956 0.682231 +0.429602 0.663322 +0.428474 0.682532 +0.430917 0.663186 +0.428936 0.682955 +0.537525 0.663186 +0.548919 0.672329 +0.539446 0.682057 +0.536210 0.663322 +0.538920 0.682003 +0.538394 0.682057 +0.534895 0.663186 +0.537856 0.682231 +0.533549 0.662752 +0.537338 0.682532 +0.425085 0.529306 +0.479580 0.560477 +0.422495 0.656678 +0.542930 0.658190 +0.473871 0.569917 +0.432262 0.662752 +0.429311 0.683474 +0.426366 0.688447 +0.545245 0.695405 +0.426892 0.688501 +0.427418 0.688447 +0.427956 0.688273 +0.428474 0.687971 +0.428936 0.687549 +0.429311 0.687030 +0.429580 0.686448 +0.429734 0.685843 +0.429783 0.685252 +0.429734 0.684661 +0.429580 0.684056 +0.433557 0.661998 +0.434713 0.660943 +0.435651 0.659644 +0.436322 0.658190 +0.436709 0.656678 +0.436830 0.655200 +0.436709 0.653722 +0.538920 0.688501 +0.532255 0.661998 +0.536876 0.682955 +0.542844 0.535049 +0.424964 0.527828 +0.481262 0.559934 +0.553065 0.523563 +0.413902 0.522508 +0.436322 0.652210 +0.474022 0.571765 +0.422374 0.655200 +0.422495 0.653722 +0.422882 0.652210 +0.423553 0.650755 +0.424491 0.649457 +0.425647 0.648402 +0.426942 0.647648 +0.428287 0.647213 +0.429602 0.647078 +0.430917 0.647213 +0.474506 0.573654 +0.432262 0.647648 +0.475344 0.575473 +0.433557 0.648402 +0.476517 0.577096 +0.434713 0.649457 +0.477962 0.578415 +0.435651 0.650755 +0.479580 0.579357 +0.481262 0.579900 +0.482906 0.580070 +0.543317 0.656678 +0.543438 0.655200 +0.543317 0.653722 +0.542930 0.652210 +0.542259 0.650755 +0.541321 0.649457 +0.540165 0.648402 +0.538870 0.647648 +0.537525 0.647213 +0.536210 0.647078 +0.534895 0.647213 +0.533549 0.647648 +0.541905 0.533751 +0.532255 0.648402 +0.536500 0.683474 +0.531099 0.660943 +0.538394 0.688447 +0.484550 0.579900 +0.424577 0.526317 +0.482906 0.559764 +0.531099 0.649457 +0.541235 0.532296 +0.536232 0.684056 +0.551910 0.522508 +0.415197 0.521754 +0.537856 0.688273 +0.537338 0.687971 +0.536876 0.687549 +0.536500 0.687030 +0.536232 0.686448 +0.536077 0.685843 +0.536029 0.685252 +0.536077 0.684661 +0.486232 0.579357 +0.487850 0.578415 +0.489294 0.577096 +0.490468 0.575473 +0.491306 0.573654 +0.491790 0.571765 +0.530160 0.659644 +0.423907 0.524862 +0.484550 0.559934 +0.540848 0.530784 +0.530160 0.650755 +0.491940 0.569917 +0.550615 0.521754 +0.416542 0.521320 +0.529490 0.658190 +0.529103 0.656678 +0.528982 0.655200 +0.529103 0.653722 +0.529490 0.652210 +0.491790 0.568070 +0.491306 0.566180 +0.490468 0.564362 +0.489294 0.562738 +0.540727 0.529306 +0.540848 0.527828 +0.487850 0.561419 +0.541235 0.526317 +0.486232 0.560477 +0.541905 0.524862 +0.542844 0.523563 +0.422968 0.523563 +0.544000 0.522508 +0.421812 0.522508 +0.545294 0.521754 +0.420518 0.521754 +0.546640 0.521320 +0.417857 0.521184 +0.385559 0.520669 +0.419172 0.521320 +0.549270 0.521320 +0.410613 0.532529 +0.496517 0.559917 +0.541434 0.534097 +0.438637 0.691081 +0.527175 0.691081 +0.438637 0.670705 +0.533342 0.663340 +0.433865 0.662528 +0.413594 0.521978 +0.550823 0.521166 +0.527175 0.670705 +0.438606 0.670336 +0.542446 0.535497 +0.552218 0.521978 +0.412348 0.523115 +0.531947 0.662528 +0.435111 0.661391 +0.494405 0.556995 +0.540711 0.532529 +0.498026 0.563190 +0.527205 0.670336 +0.438510 0.669958 +0.414989 0.521166 +0.562956 0.500400 +0.416439 0.520697 +0.417857 0.520551 +0.419275 0.520697 +0.420725 0.521166 +0.422120 0.521978 +0.423366 0.523115 +0.424378 0.524515 +0.425101 0.526084 +0.425518 0.527713 +0.425648 0.529306 +0.549372 0.520697 +0.543692 0.536634 +0.528653 0.668708 +0.436830 0.668674 +0.540294 0.530899 +0.491805 0.554621 +0.498897 0.566592 +0.553464 0.523115 +0.411336 0.524515 +0.534792 0.663809 +0.528982 0.668674 +0.536210 0.663955 +0.537628 0.663809 +0.539078 0.663340 +0.540473 0.662528 +0.541719 0.661391 +0.542731 0.659991 +0.543454 0.658423 +0.543871 0.656793 +0.556680 0.668674 +0.544001 0.655200 +0.543871 0.653607 +0.543454 0.651977 +0.542731 0.650409 +0.541719 0.649009 +0.540473 0.647872 +0.539078 0.647059 +0.537628 0.646591 +0.536210 0.646445 +0.534792 0.646591 +0.432470 0.663340 +0.409131 0.668674 +0.431020 0.663809 +0.429602 0.663955 +0.428184 0.663809 +0.426734 0.663340 +0.425339 0.662528 +0.424093 0.661391 +0.423081 0.659991 +0.422358 0.658423 +0.402855 0.500400 +0.421941 0.656793 +0.421811 0.655200 +0.421941 0.653607 +0.422358 0.651977 +0.423081 0.650409 +0.424093 0.649009 +0.425339 0.647872 +0.426734 0.647059 +0.428184 0.646591 +0.429602 0.646445 +0.527302 0.669958 +0.438342 0.669594 +0.425518 0.530899 +0.545087 0.537447 +0.533342 0.647059 +0.431020 0.646591 +0.540164 0.529306 +0.547955 0.520551 +0.546537 0.520697 +0.545087 0.521166 +0.543692 0.521978 +0.542446 0.523115 +0.541434 0.524515 +0.540711 0.526084 +0.540294 0.527713 +0.425101 0.532529 +0.530701 0.661391 +0.528317 0.668817 +0.437158 0.668708 +0.436123 0.659991 +0.488892 0.552925 +0.437495 0.668817 +0.499168 0.569917 +0.527993 0.669005 +0.546537 0.537915 +0.527470 0.669594 +0.438107 0.669269 +0.531947 0.647872 +0.432470 0.647059 +0.554476 0.524515 +0.410613 0.526084 +0.424378 0.534097 +0.498897 0.573242 +0.547955 0.538061 +0.529689 0.659991 +0.527705 0.669269 +0.528966 0.658423 +0.528549 0.656793 +0.528419 0.655200 +0.528549 0.653607 +0.528966 0.651977 +0.437818 0.669005 +0.436846 0.658423 +0.437263 0.656793 +0.437393 0.655200 +0.437263 0.653607 +0.436846 0.651977 +0.436123 0.650409 +0.529689 0.650409 +0.435111 0.649009 +0.530701 0.649009 +0.433865 0.647872 +0.485865 0.551947 +0.482906 0.551642 +0.479947 0.551947 +0.476920 0.552925 +0.474007 0.554621 +0.471407 0.556995 +0.469295 0.559917 +0.467786 0.563190 +0.466915 0.566592 +0.423366 0.535497 +0.466644 0.569917 +0.422120 0.536634 +0.466915 0.573242 +0.420725 0.537447 +0.467786 0.576644 +0.419275 0.537915 +0.555199 0.526084 +0.410196 0.527713 +0.549372 0.537915 +0.417857 0.538061 +0.469295 0.579917 +0.498026 0.576644 +0.410066 0.529306 +0.555615 0.527713 +0.550823 0.537447 +0.416439 0.537915 +0.471407 0.582839 +0.496517 0.579917 +0.555746 0.529306 +0.555615 0.530899 +0.555199 0.532529 +0.554476 0.534097 +0.553464 0.535497 +0.552218 0.536634 +0.494405 0.582839 +0.491805 0.585213 +0.488892 0.586909 +0.485865 0.587887 +0.482906 0.588192 +0.479947 0.587887 +0.476920 0.586909 +0.474007 0.585213 +0.414989 0.537447 +0.413594 0.536634 +0.412348 0.535497 +0.411336 0.534097 +0.410196 0.530899 +0.499168 0.569917 +0.499023 0.569917 +0.466789 0.569917 +0.466644 0.569917 +0.467058 0.573213 +0.466915 0.573242 +0.467920 0.576584 +0.467786 0.576644 +0.469416 0.579828 +0.469295 0.579917 +0.471509 0.582724 +0.471407 0.582839 +0.474086 0.585077 +0.474007 0.585213 +0.476973 0.586757 +0.476920 0.586909 +0.479973 0.587727 +0.479947 0.587887 +0.482906 0.588029 +0.482906 0.588192 +0.485839 0.587727 +0.485865 0.587887 +0.488839 0.586757 +0.488892 0.586909 +0.491725 0.585077 +0.491805 0.585213 +0.494302 0.582724 +0.494405 0.582839 +0.496396 0.579828 +0.496517 0.579917 +0.497891 0.576584 +0.498026 0.576644 +0.498754 0.573213 +0.498897 0.573242 +0.476517 0.562738 +0.477249 0.553859 +0.477962 0.561419 +0.480109 0.552935 +0.479580 0.560477 +0.482906 0.552646 +0.481262 0.559934 +0.485702 0.552935 +0.482906 0.559764 +0.488563 0.553859 +0.484550 0.559934 +0.491316 0.555461 +0.486232 0.560477 +0.493773 0.557705 +0.487850 0.561419 +0.495769 0.560466 +0.489294 0.562738 +0.497196 0.563560 +0.490468 0.564362 +0.498018 0.566774 +0.491306 0.566180 +0.498275 0.569917 +0.491790 0.568070 +0.498018 0.573060 +0.491940 0.569917 +0.497196 0.576274 +0.491790 0.571765 +0.495769 0.579368 +0.491306 0.573654 +0.493773 0.582130 +0.490468 0.575473 +0.491316 0.584373 +0.489294 0.577096 +0.488563 0.585975 +0.487850 0.578415 +0.485702 0.586900 +0.486232 0.579357 +0.482906 0.587188 +0.484550 0.579900 +0.480109 0.586900 +0.482906 0.580070 +0.477249 0.585975 +0.481262 0.579900 +0.474496 0.584373 +0.479580 0.579357 +0.472039 0.582130 +0.477962 0.578415 +0.470042 0.579368 +0.476517 0.577096 +0.468616 0.576274 +0.475344 0.575473 +0.467794 0.573060 +0.474506 0.573654 +0.467537 0.569917 +0.474022 0.571765 +0.467794 0.566774 +0.473871 0.569917 +0.468616 0.563560 +0.474022 0.568070 +0.470042 0.560466 +0.474506 0.566180 +0.472039 0.557705 +0.475344 0.564362 +0.474496 0.555461 +0.474506 0.573654 +0.474022 0.571765 +0.473871 0.569917 +0.473871 0.569917 +0.491940 0.569917 +0.491940 0.569917 +0.491790 0.571765 +0.491790 0.571765 +0.491306 0.573654 +0.490468 0.575473 +0.491306 0.573654 +0.489294 0.577096 +0.490468 0.575473 +0.487850 0.578415 +0.489294 0.577096 +0.487850 0.578415 +0.486232 0.579357 +0.486232 0.579357 +0.484550 0.579900 +0.484550 0.579900 +0.482906 0.580070 +0.482906 0.580070 +0.481262 0.579900 +0.481262 0.579900 +0.479580 0.579357 +0.479580 0.579357 +0.477962 0.578415 +0.476517 0.577096 +0.477962 0.578415 +0.476517 0.577096 +0.475344 0.575473 +0.475344 0.575473 +0.474506 0.573654 +0.474022 0.571765 +0.527175 0.693991 +0.527175 0.695141 +0.527175 0.695205 +0.527175 0.695126 +0.527175 0.694900 +0.527175 0.694518 +0.527175 0.670769 +0.527175 0.670705 +0.527175 0.691144 +0.527175 0.691081 +0.527175 0.691813 +0.527175 0.691876 +0.527175 0.692561 +0.527175 0.693282 +0.527175 0.692625 +0.527175 0.693927 +0.527175 0.694454 +0.527175 0.693345 +0.527175 0.694836 +0.527175 0.695062 +0.538394 0.688447 +0.551574 0.668806 +0.552232 0.668738 +0.550902 0.669023 +0.550255 0.669400 +0.549677 0.669927 +0.549208 0.670577 +0.548618 0.691075 +0.541608 0.686448 +0.541763 0.685843 +0.541811 0.685252 +0.541763 0.684661 +0.541608 0.684056 +0.541340 0.683474 +0.548872 0.671304 +0.540965 0.682955 +0.548679 0.672060 +0.527175 0.691144 +0.548618 0.691144 +0.540502 0.682532 +0.548618 0.672799 +0.539984 0.682231 +0.539446 0.682057 +0.538920 0.682003 +0.538394 0.682057 +0.537856 0.682231 +0.537338 0.682532 +0.536876 0.682955 +0.541340 0.687030 +0.536500 0.683474 +0.528982 0.668738 +0.528653 0.668772 +0.528317 0.668881 +0.527993 0.669069 +0.527705 0.669333 +0.527470 0.669658 +0.527302 0.670021 +0.527205 0.670399 +0.527175 0.670769 +0.536232 0.684056 +0.536077 0.684661 +0.536029 0.685252 +0.536077 0.685843 +0.536232 0.686448 +0.536500 0.687030 +0.536876 0.687549 +0.540965 0.687549 +0.537338 0.687971 +0.540502 0.687971 +0.537856 0.688273 +0.539984 0.688273 +0.539446 0.688447 +0.538920 0.688501 +0.438637 0.693345 +0.438637 0.695126 +0.438637 0.695205 +0.438637 0.694900 +0.438637 0.694518 +0.438637 0.693991 +0.438637 0.691081 +0.438637 0.670705 +0.438637 0.670769 +0.438637 0.691813 +0.438637 0.691144 +0.438637 0.692561 +0.438637 0.693282 +0.438637 0.693927 +0.438637 0.691876 +0.438637 0.694454 +0.438637 0.694836 +0.438637 0.692625 +0.438637 0.695062 +0.438637 0.695141 +0.427956 0.688273 +0.436830 0.668738 +0.413580 0.668738 +0.414238 0.668806 +0.414910 0.669023 +0.415557 0.669400 +0.416135 0.669927 +0.417193 0.672799 +0.424472 0.687030 +0.424204 0.686448 +0.424049 0.685843 +0.424001 0.685252 +0.424049 0.684661 +0.424204 0.684056 +0.416604 0.670577 +0.424472 0.683474 +0.416940 0.671304 +0.417193 0.691075 +0.417194 0.691144 +0.424847 0.682955 +0.417133 0.672060 +0.425310 0.682532 +0.425827 0.682231 +0.426366 0.682057 +0.426892 0.682003 +0.427418 0.682057 +0.427956 0.682231 +0.428474 0.682532 +0.424847 0.687549 +0.428936 0.682955 +0.437158 0.668772 +0.437495 0.668881 +0.437818 0.669069 +0.438107 0.669333 +0.438342 0.669658 +0.438510 0.670021 +0.438606 0.670399 +0.438637 0.670769 +0.438637 0.691144 +0.429311 0.683474 +0.429580 0.684056 +0.429734 0.684661 +0.429783 0.685252 +0.429734 0.685843 +0.429580 0.686448 +0.429311 0.687030 +0.425310 0.687971 +0.428936 0.687549 +0.425827 0.688273 +0.428474 0.687971 +0.426366 0.688447 +0.426892 0.688501 +0.427418 0.688447 +0.424204 0.686448 +0.424049 0.685843 +0.424001 0.685252 +0.424001 0.685252 +0.424049 0.685843 +0.424204 0.686448 +0.429783 0.685252 +0.429783 0.685252 +0.429734 0.685843 +0.429580 0.686448 +0.429734 0.685843 +0.429311 0.687030 +0.429580 0.686448 +0.428936 0.687549 +0.429311 0.687030 +0.428936 0.687549 +0.428474 0.687971 +0.428474 0.687971 +0.427956 0.688273 +0.427956 0.688273 +0.427418 0.688447 +0.427418 0.688447 +0.426892 0.688501 +0.426892 0.688501 +0.426366 0.688447 +0.426366 0.688447 +0.425827 0.688273 +0.425827 0.688273 +0.425310 0.687971 +0.424847 0.687549 +0.425310 0.687971 +0.424472 0.687030 +0.424847 0.687549 +0.424472 0.687030 +0.537856 0.688273 +0.536077 0.685843 +0.536029 0.685252 +0.536029 0.685252 +0.536077 0.685843 +0.536232 0.686448 +0.536232 0.686448 +0.536500 0.687030 +0.536500 0.687030 +0.536876 0.687549 +0.537338 0.687971 +0.536876 0.687549 +0.537338 0.687971 +0.537856 0.688273 +0.541811 0.685252 +0.541811 0.685252 +0.541763 0.685843 +0.541608 0.686448 +0.541763 0.685843 +0.541608 0.686448 +0.541340 0.687030 +0.541340 0.687030 +0.540965 0.687549 +0.540965 0.687549 +0.540502 0.687971 +0.539984 0.688273 +0.540502 0.687971 +0.539446 0.688447 +0.539984 0.688273 +0.539446 0.688447 +0.538920 0.688501 +0.538920 0.688501 +0.538394 0.688447 +0.538394 0.688447 +0.550823 0.537447 +0.540492 0.530858 +0.540366 0.529306 +0.540164 0.529306 +0.540294 0.530899 +0.540899 0.532445 +0.540711 0.532529 +0.541603 0.533973 +0.542589 0.535337 +0.541434 0.534097 +0.543802 0.536444 +0.542446 0.535497 +0.543692 0.536634 +0.545161 0.537236 +0.546574 0.537692 +0.545087 0.537447 +0.547955 0.537835 +0.546537 0.537915 +0.549336 0.537692 +0.547955 0.538061 +0.549372 0.537915 +0.550748 0.537236 +0.555746 0.529306 +0.555544 0.529306 +0.555615 0.530899 +0.555199 0.532529 +0.555417 0.530858 +0.554476 0.534097 +0.555011 0.532445 +0.554307 0.533973 +0.553464 0.535497 +0.553321 0.535337 +0.552218 0.536634 +0.552108 0.536444 +0.551207 0.529306 +0.555011 0.532445 +0.551153 0.529971 +0.554307 0.533973 +0.550979 0.530652 +0.553321 0.535337 +0.550677 0.531306 +0.552108 0.536444 +0.550255 0.531891 +0.550748 0.537236 +0.549735 0.532366 +0.549336 0.537692 +0.549152 0.532705 +0.547955 0.537835 +0.548547 0.532900 +0.546574 0.537692 +0.547955 0.532961 +0.545161 0.537236 +0.547363 0.532900 +0.543802 0.536444 +0.546758 0.532705 +0.542589 0.535337 +0.546175 0.532366 +0.541603 0.533973 +0.545655 0.531891 +0.540899 0.532445 +0.545232 0.531306 +0.540492 0.530858 +0.544931 0.530652 +0.540366 0.529306 +0.544757 0.529971 +0.540492 0.527754 +0.544702 0.529306 +0.540899 0.526167 +0.544757 0.528641 +0.541603 0.524640 +0.544931 0.527961 +0.542588 0.523276 +0.545232 0.527306 +0.543802 0.522168 +0.545655 0.526722 +0.545161 0.521377 +0.546175 0.526247 +0.546574 0.520920 +0.546758 0.525908 +0.547955 0.520778 +0.547363 0.525712 +0.549336 0.520920 +0.547955 0.525651 +0.550748 0.521377 +0.548546 0.525712 +0.552108 0.522168 +0.549152 0.525908 +0.553321 0.523276 +0.549735 0.526247 +0.554307 0.524640 +0.550255 0.526722 +0.555011 0.526167 +0.550677 0.527306 +0.555417 0.527754 +0.550979 0.527961 +0.555544 0.529306 +0.551153 0.528641 +0.555417 0.530858 +0.410268 0.529306 +0.410066 0.529306 +0.425648 0.529306 +0.425446 0.529306 +0.425518 0.530899 +0.425101 0.532529 +0.425319 0.530858 +0.424913 0.532445 +0.424378 0.534097 +0.423366 0.535497 +0.424209 0.533973 +0.422120 0.536634 +0.423223 0.535337 +0.422010 0.536444 +0.420725 0.537447 +0.420651 0.537236 +0.419275 0.537915 +0.417857 0.538061 +0.419238 0.537692 +0.417857 0.537835 +0.416439 0.537915 +0.416476 0.537692 +0.414989 0.537447 +0.415064 0.537236 +0.413594 0.536634 +0.413704 0.536444 +0.412348 0.535497 +0.412491 0.535337 +0.411336 0.534097 +0.411505 0.533973 +0.410613 0.532529 +0.410801 0.532445 +0.410196 0.530899 +0.410395 0.530858 +0.420157 0.526722 +0.424913 0.526167 +0.420579 0.527306 +0.425319 0.527754 +0.420881 0.527961 +0.425446 0.529306 +0.421055 0.528641 +0.425319 0.530858 +0.421109 0.529306 +0.424913 0.532445 +0.421055 0.529971 +0.424209 0.533973 +0.420881 0.530652 +0.423223 0.535337 +0.420579 0.531306 +0.422010 0.536444 +0.420157 0.531891 +0.420651 0.537236 +0.419637 0.532366 +0.419238 0.537692 +0.419054 0.532705 +0.417857 0.537835 +0.418449 0.532900 +0.416476 0.537692 +0.417857 0.532961 +0.415064 0.537236 +0.417265 0.532900 +0.413704 0.536444 +0.416660 0.532705 +0.412491 0.535337 +0.416077 0.532366 +0.411505 0.533973 +0.415557 0.531891 +0.410801 0.532445 +0.415135 0.531306 +0.410395 0.530858 +0.414833 0.530652 +0.410268 0.529306 +0.414659 0.529971 +0.410395 0.527754 +0.414605 0.529306 +0.410801 0.526167 +0.414659 0.528641 +0.411505 0.524640 +0.414833 0.527961 +0.412491 0.523276 +0.415135 0.527306 +0.413704 0.522168 +0.415557 0.526722 +0.415064 0.521377 +0.416077 0.526247 +0.416476 0.520920 +0.416660 0.525908 +0.417857 0.520778 +0.417265 0.525712 +0.419238 0.520920 +0.417857 0.525651 +0.420651 0.521377 +0.418449 0.525712 +0.422010 0.522168 +0.419054 0.525908 +0.423223 0.523276 +0.419637 0.526247 +0.424209 0.524640 +0.530701 0.661391 +0.528747 0.656752 +0.528621 0.655200 +0.528419 0.655200 +0.529154 0.658339 +0.528549 0.656793 +0.528966 0.658423 +0.529858 0.659867 +0.530844 0.661230 +0.529689 0.659991 +0.544001 0.655200 +0.543799 0.655200 +0.543871 0.656793 +0.543672 0.656752 +0.543454 0.658423 +0.542731 0.659991 +0.543266 0.658339 +0.542562 0.659867 +0.541719 0.661391 +0.541576 0.661230 +0.540473 0.662528 +0.539078 0.663340 +0.540363 0.662338 +0.537628 0.663809 +0.539003 0.663129 +0.537591 0.663586 +0.536210 0.663955 +0.536210 0.663728 +0.534792 0.663809 +0.533342 0.663340 +0.534829 0.663586 +0.533416 0.663129 +0.531947 0.662528 +0.532057 0.662338 +0.537407 0.658598 +0.536210 0.663728 +0.536802 0.658794 +0.534829 0.663586 +0.536210 0.658855 +0.533416 0.663129 +0.535618 0.658794 +0.532057 0.662338 +0.535013 0.658598 +0.530844 0.661230 +0.534430 0.658259 +0.529858 0.659867 +0.533910 0.657784 +0.529154 0.658339 +0.533487 0.657200 +0.528747 0.656752 +0.533186 0.656545 +0.528621 0.655200 +0.533012 0.655865 +0.528747 0.653648 +0.532957 0.655200 +0.529154 0.652061 +0.533012 0.654535 +0.529858 0.650533 +0.533186 0.653854 +0.530844 0.649169 +0.533487 0.653200 +0.532057 0.648062 +0.533910 0.652615 +0.533416 0.647270 +0.534430 0.652141 +0.534829 0.646814 +0.535013 0.651802 +0.536210 0.646671 +0.535618 0.651606 +0.537591 0.646814 +0.536210 0.651545 +0.539003 0.647270 +0.536802 0.651606 +0.540363 0.648062 +0.537407 0.651802 +0.541576 0.649169 +0.537990 0.652141 +0.542562 0.650533 +0.538510 0.652615 +0.543266 0.652061 +0.538932 0.653200 +0.543672 0.653648 +0.539234 0.653854 +0.543799 0.655200 +0.539408 0.654535 +0.543672 0.656752 +0.539462 0.655200 +0.543266 0.658339 +0.539408 0.655865 +0.542562 0.659867 +0.539234 0.656545 +0.541576 0.661230 +0.538932 0.657200 +0.540363 0.662338 +0.538510 0.657784 +0.539003 0.663129 +0.537990 0.658259 +0.537591 0.663586 +0.437393 0.655200 +0.437191 0.655200 +0.422140 0.656752 +0.422013 0.655200 +0.421811 0.655200 +0.422546 0.658339 +0.421941 0.656793 +0.423250 0.659867 +0.422358 0.658423 +0.424236 0.661230 +0.423081 0.659991 +0.425449 0.662338 +0.424093 0.661391 +0.426809 0.663129 +0.425339 0.662528 +0.426734 0.663340 +0.428221 0.663586 +0.429602 0.663728 +0.428184 0.663809 +0.430983 0.663586 +0.429602 0.663955 +0.431020 0.663809 +0.432396 0.663129 +0.433755 0.662338 +0.432470 0.663340 +0.434968 0.661230 +0.433865 0.662528 +0.435954 0.659867 +0.435111 0.661391 +0.436123 0.659991 +0.436658 0.658339 +0.436846 0.658423 +0.437064 0.656752 +0.437263 0.656793 +0.432324 0.657200 +0.433755 0.662338 +0.431902 0.657784 +0.432396 0.663129 +0.431382 0.658259 +0.430983 0.663586 +0.430799 0.658598 +0.429602 0.663728 +0.430194 0.658794 +0.428221 0.663586 +0.429602 0.658855 +0.426809 0.663129 +0.429010 0.658794 +0.425449 0.662338 +0.428405 0.658598 +0.424236 0.661230 +0.427822 0.658259 +0.423250 0.659867 +0.427302 0.657784 +0.422546 0.658339 +0.426880 0.657200 +0.422140 0.656752 +0.426578 0.656545 +0.422013 0.655200 +0.426404 0.655865 +0.422140 0.653648 +0.426350 0.655200 +0.422546 0.652061 +0.426404 0.654535 +0.423250 0.650533 +0.426578 0.653854 +0.424236 0.649170 +0.426880 0.653200 +0.425449 0.648062 +0.427302 0.652615 +0.426809 0.647270 +0.427822 0.652141 +0.428221 0.646814 +0.428405 0.651802 +0.429602 0.646671 +0.429010 0.651606 +0.430983 0.646814 +0.429602 0.651545 +0.432396 0.647270 +0.430194 0.651606 +0.433755 0.648062 +0.430799 0.651802 +0.434968 0.649170 +0.431382 0.652141 +0.435954 0.650533 +0.431902 0.652615 +0.436658 0.652061 +0.432324 0.653200 +0.437064 0.653648 +0.432626 0.653854 +0.437191 0.655200 +0.432800 0.654535 +0.437064 0.656752 +0.432854 0.655200 +0.436658 0.658339 +0.432800 0.655865 +0.435954 0.659867 +0.432626 0.656545 +0.434968 0.661230 +0.422374 0.655200 +0.422374 0.655200 +0.436709 0.656678 +0.436830 0.655200 +0.436830 0.655200 +0.436322 0.658190 +0.436709 0.656678 +0.436322 0.658190 +0.435651 0.659644 +0.435651 0.659644 +0.434713 0.660943 +0.434713 0.660943 +0.433557 0.661998 +0.433557 0.661998 +0.432262 0.662752 +0.432262 0.662752 +0.430917 0.663186 +0.430917 0.663186 +0.429602 0.663322 +0.429602 0.663322 +0.428287 0.663186 +0.428287 0.663186 +0.426942 0.662752 +0.426942 0.662752 +0.425647 0.661998 +0.425647 0.661998 +0.424491 0.660943 +0.424491 0.660943 +0.423553 0.659644 +0.423553 0.659644 +0.422882 0.658190 +0.422882 0.658190 +0.422495 0.656678 +0.422495 0.656678 +0.428385 0.662587 +0.430917 0.663186 +0.429602 0.662713 +0.432262 0.662752 +0.430818 0.662587 +0.433557 0.661998 +0.432063 0.662185 +0.434713 0.660943 +0.433261 0.661488 +0.435651 0.659644 +0.434329 0.660512 +0.436322 0.658190 +0.435198 0.659311 +0.436709 0.656678 +0.435818 0.657965 +0.436830 0.655200 +0.436176 0.656567 +0.436709 0.653722 +0.436288 0.655200 +0.436322 0.652210 +0.436176 0.653833 +0.435651 0.650755 +0.435818 0.652434 +0.434713 0.649457 +0.435198 0.651089 +0.433557 0.648402 +0.434329 0.649887 +0.432262 0.647648 +0.433261 0.648912 +0.430917 0.647213 +0.432063 0.648214 +0.429602 0.647078 +0.430818 0.647812 +0.428287 0.647213 +0.429602 0.647687 +0.426942 0.647648 +0.428385 0.647812 +0.425647 0.648402 +0.427141 0.648214 +0.424491 0.649457 +0.425944 0.648912 +0.423553 0.650755 +0.424875 0.649887 +0.422882 0.652210 +0.424006 0.651089 +0.422495 0.653722 +0.423386 0.652434 +0.422374 0.655200 +0.423028 0.653833 +0.422495 0.656678 +0.422916 0.655200 +0.422882 0.658190 +0.423028 0.656567 +0.423553 0.659644 +0.423386 0.657965 +0.424491 0.660943 +0.424006 0.659311 +0.425647 0.661998 +0.424875 0.660512 +0.426942 0.662752 +0.425944 0.661488 +0.428287 0.663186 +0.427141 0.662185 +0.429602 0.663322 +0.528982 0.655200 +0.528982 0.655200 +0.543317 0.656678 +0.543438 0.655200 +0.543438 0.655200 +0.543317 0.656678 +0.542930 0.658190 +0.542259 0.659644 +0.542930 0.658190 +0.541321 0.660943 +0.542259 0.659644 +0.541321 0.660943 +0.540165 0.661998 +0.538870 0.662752 +0.540165 0.661998 +0.538870 0.662752 +0.537525 0.663186 +0.537525 0.663186 +0.536210 0.663322 +0.534895 0.663186 +0.536210 0.663322 +0.534895 0.663186 +0.533549 0.662752 +0.533549 0.662752 +0.532255 0.661998 +0.532255 0.661998 +0.531099 0.660943 +0.531099 0.660943 +0.530160 0.659644 +0.530160 0.659644 +0.529490 0.658190 +0.529490 0.658190 +0.529103 0.656678 +0.529103 0.656678 +0.536210 0.662713 +0.538870 0.662752 +0.537426 0.662587 +0.540165 0.661998 +0.538671 0.662185 +0.541321 0.660943 +0.539868 0.661488 +0.542259 0.659644 +0.540937 0.660512 +0.542930 0.658190 +0.541806 0.659311 +0.543317 0.656678 +0.542426 0.657965 +0.543438 0.655200 +0.542784 0.656567 +0.543317 0.653722 +0.542895 0.655200 +0.542930 0.652210 +0.542784 0.653833 +0.542259 0.650755 +0.542426 0.652434 +0.541321 0.649457 +0.541806 0.651089 +0.540165 0.648402 +0.540937 0.649887 +0.538870 0.647648 +0.539868 0.648912 +0.537525 0.647213 +0.538671 0.648214 +0.536210 0.647078 +0.537426 0.647812 +0.534895 0.647213 +0.536210 0.647687 +0.533549 0.647648 +0.534993 0.647812 +0.532255 0.648402 +0.533749 0.648214 +0.531099 0.649457 +0.532551 0.648912 +0.530160 0.650755 +0.531482 0.649887 +0.529490 0.652210 +0.530614 0.651089 +0.529103 0.653722 +0.529994 0.652434 +0.528982 0.655200 +0.529636 0.653833 +0.529103 0.656678 +0.529524 0.655200 +0.529490 0.658190 +0.529636 0.656567 +0.530160 0.659644 +0.529994 0.657965 +0.531099 0.660943 +0.530614 0.659311 +0.532255 0.661998 +0.531482 0.660512 +0.533549 0.662752 +0.532551 0.661488 +0.534895 0.663186 +0.533749 0.662185 +0.536210 0.663322 +0.534993 0.662587 +0.537525 0.663186 +0.425085 0.529306 +0.425085 0.529306 +0.410750 0.530784 +0.410629 0.529306 +0.410629 0.529306 +0.411137 0.532296 +0.410750 0.530784 +0.411137 0.532296 +0.411808 0.533751 +0.411808 0.533751 +0.412746 0.535049 +0.412746 0.535049 +0.413902 0.536105 +0.413902 0.536105 +0.415197 0.536858 +0.415197 0.536858 +0.416542 0.537293 +0.416542 0.537293 +0.417857 0.537429 +0.417857 0.537429 +0.419172 0.537293 +0.419172 0.537293 +0.420518 0.536858 +0.420518 0.536858 +0.421812 0.536105 +0.421812 0.536105 +0.422968 0.535049 +0.422968 0.535049 +0.423907 0.533751 +0.423907 0.533751 +0.424577 0.532296 +0.424577 0.532296 +0.424964 0.530784 +0.424964 0.530784 +0.424543 0.529306 +0.424577 0.526317 +0.424431 0.527939 +0.423907 0.524862 +0.424073 0.526541 +0.422968 0.523563 +0.423453 0.525195 +0.421812 0.522508 +0.422584 0.523994 +0.420518 0.521754 +0.421516 0.523018 +0.419172 0.521320 +0.420318 0.522321 +0.417857 0.521184 +0.419074 0.521919 +0.416542 0.521320 +0.417857 0.521793 +0.415197 0.521754 +0.416641 0.521919 +0.413902 0.522508 +0.415396 0.522321 +0.412746 0.523563 +0.414199 0.523018 +0.411808 0.524862 +0.413130 0.523994 +0.411137 0.526317 +0.412261 0.525195 +0.410750 0.527828 +0.411641 0.526541 +0.410629 0.529306 +0.411283 0.527939 +0.410750 0.530784 +0.411171 0.529306 +0.411137 0.532296 +0.411283 0.530673 +0.411808 0.533751 +0.411641 0.532072 +0.412746 0.535049 +0.412261 0.533418 +0.413902 0.536105 +0.413130 0.534619 +0.415197 0.536858 +0.414199 0.535595 +0.416542 0.537293 +0.415396 0.536292 +0.417857 0.537429 +0.416641 0.536694 +0.419172 0.537293 +0.417857 0.536819 +0.420518 0.536858 +0.419074 0.536694 +0.421812 0.536105 +0.420318 0.536292 +0.422968 0.535049 +0.421516 0.535595 +0.423907 0.533751 +0.422584 0.534619 +0.424577 0.532296 +0.423453 0.533418 +0.424964 0.530784 +0.424073 0.532072 +0.425085 0.529306 +0.424431 0.530673 +0.424964 0.527828 +0.551910 0.536105 +0.555062 0.530784 +0.555182 0.529306 +0.555182 0.529306 +0.555062 0.530784 +0.554675 0.532296 +0.554675 0.532296 +0.554004 0.533751 +0.553065 0.535049 +0.554004 0.533751 +0.540727 0.529306 +0.540727 0.529306 +0.540848 0.530784 +0.540848 0.530784 +0.541235 0.532296 +0.541235 0.532296 +0.541905 0.533751 +0.541905 0.533751 +0.542844 0.535049 +0.544000 0.536105 +0.542844 0.535049 +0.545294 0.536858 +0.544000 0.536105 +0.545294 0.536858 +0.546640 0.537293 +0.546640 0.537293 +0.547955 0.537428 +0.547955 0.537428 +0.549270 0.537293 +0.549270 0.537293 +0.550615 0.536858 +0.550615 0.536858 +0.551910 0.536105 +0.553065 0.535049 +0.552682 0.534619 +0.554675 0.532296 +0.553551 0.533418 +0.555062 0.530784 +0.554171 0.532072 +0.555182 0.529306 +0.554529 0.530673 +0.555062 0.527828 +0.554640 0.529306 +0.554675 0.526316 +0.554529 0.527939 +0.554004 0.524862 +0.554171 0.526541 +0.553065 0.523563 +0.553550 0.525195 +0.551910 0.522508 +0.552682 0.523994 +0.550615 0.521754 +0.551613 0.523018 +0.549270 0.521320 +0.550416 0.522321 +0.547955 0.521184 +0.549171 0.521919 +0.546640 0.521320 +0.547955 0.521793 +0.545294 0.521754 +0.546738 0.521919 +0.544000 0.522508 +0.545494 0.522321 +0.542844 0.523563 +0.544296 0.523018 +0.541905 0.524862 +0.543227 0.523994 +0.541235 0.526317 +0.542359 0.525195 +0.540848 0.527828 +0.541739 0.526541 +0.540727 0.529306 +0.541381 0.527939 +0.540848 0.530784 +0.541269 0.529306 +0.541235 0.532296 +0.541381 0.530673 +0.541905 0.533751 +0.541739 0.532072 +0.542844 0.535049 +0.542359 0.533418 +0.544000 0.536105 +0.543227 0.534619 +0.545294 0.536858 +0.544296 0.535595 +0.546640 0.537293 +0.545494 0.536292 +0.547955 0.537428 +0.546738 0.536694 +0.549270 0.537293 +0.547955 0.536819 +0.550615 0.536858 +0.549171 0.536694 +0.551910 0.536105 +0.550416 0.536292 +0.553065 0.535049 +0.551613 0.535595 +0.554004 0.533751 +0.414833 0.530652 +0.414659 0.529971 +0.414605 0.529306 +0.414605 0.529306 +0.414659 0.529971 +0.414833 0.530652 +0.421109 0.529306 +0.421109 0.529306 +0.421055 0.529971 +0.421055 0.529971 +0.420881 0.530652 +0.420881 0.530652 +0.420579 0.531306 +0.420157 0.531891 +0.420579 0.531306 +0.419637 0.532366 +0.420157 0.531891 +0.419054 0.532705 +0.419637 0.532366 +0.418449 0.532900 +0.419054 0.532705 +0.417857 0.532961 +0.418449 0.532900 +0.417857 0.532961 +0.417265 0.532900 +0.417265 0.532900 +0.416660 0.532705 +0.416660 0.532705 +0.416077 0.532366 +0.416077 0.532366 +0.415557 0.531891 +0.415557 0.531891 +0.415135 0.531306 +0.415135 0.531306 +0.414659 0.529971 +0.411283 0.530673 +0.411171 0.529306 +0.414605 0.529306 +0.421109 0.529306 +0.424543 0.529306 +0.421055 0.529971 +0.424431 0.530673 +0.420881 0.530652 +0.420579 0.531306 +0.424073 0.532072 +0.423453 0.533418 +0.420157 0.531891 +0.422584 0.534619 +0.419637 0.532366 +0.419054 0.532705 +0.421516 0.535595 +0.420318 0.536292 +0.418449 0.532900 +0.419074 0.536694 +0.417857 0.532961 +0.417857 0.536819 +0.417265 0.532900 +0.416641 0.536694 +0.416660 0.532705 +0.415396 0.536292 +0.416077 0.532366 +0.414199 0.535595 +0.415557 0.531891 +0.415135 0.531306 +0.413130 0.534619 +0.412261 0.533418 +0.414833 0.530652 +0.411641 0.532072 +0.545232 0.531306 +0.544702 0.529306 +0.544702 0.529306 +0.544757 0.529971 +0.544931 0.530652 +0.544757 0.529971 +0.545232 0.531306 +0.544931 0.530652 +0.551207 0.529306 +0.551207 0.529306 +0.551153 0.529971 +0.550979 0.530652 +0.551153 0.529971 +0.550677 0.531306 +0.550979 0.530652 +0.550677 0.531306 +0.550255 0.531891 +0.550255 0.531891 +0.549735 0.532366 +0.549152 0.532705 +0.549735 0.532366 +0.548547 0.532900 +0.549152 0.532705 +0.548547 0.532900 +0.547955 0.532961 +0.547363 0.532900 +0.547955 0.532961 +0.547363 0.532900 +0.546758 0.532705 +0.546175 0.532366 +0.546758 0.532705 +0.546175 0.532366 +0.545655 0.531891 +0.545655 0.531891 +0.544757 0.529971 +0.541381 0.530673 +0.541269 0.529306 +0.544702 0.529306 +0.551207 0.529306 +0.554640 0.529306 +0.551153 0.529971 +0.554529 0.530673 +0.550979 0.530652 +0.554171 0.532072 +0.550677 0.531306 +0.550255 0.531891 +0.553551 0.533418 +0.549735 0.532366 +0.552682 0.534619 +0.549152 0.532705 +0.551613 0.535595 +0.548547 0.532900 +0.550416 0.536292 +0.547955 0.532961 +0.549171 0.536694 +0.547363 0.532900 +0.547955 0.536819 +0.546758 0.532705 +0.546738 0.536694 +0.546175 0.532366 +0.545494 0.536292 +0.545655 0.531891 +0.544296 0.535595 +0.543227 0.534619 +0.545232 0.531306 +0.542359 0.533418 +0.544931 0.530652 +0.541739 0.532072 +0.533186 0.656545 +0.532957 0.655200 +0.532957 0.655200 +0.533012 0.655865 +0.533186 0.656545 +0.533012 0.655865 +0.539462 0.655200 +0.539462 0.655200 +0.539408 0.655865 +0.539234 0.656545 +0.539408 0.655865 +0.539234 0.656545 +0.538932 0.657200 +0.538932 0.657200 +0.538510 0.657784 +0.538510 0.657784 +0.537990 0.658259 +0.537990 0.658259 +0.537407 0.658598 +0.537407 0.658598 +0.536802 0.658794 +0.536802 0.658794 +0.536210 0.658855 +0.536210 0.658855 +0.535618 0.658794 +0.535618 0.658794 +0.535013 0.658598 +0.535013 0.658598 +0.534430 0.658259 +0.533910 0.657784 +0.534430 0.658259 +0.533910 0.657784 +0.533487 0.657200 +0.533487 0.657200 +0.529524 0.655200 +0.532957 0.655200 +0.539408 0.655865 +0.539462 0.655200 +0.542895 0.655200 +0.542784 0.656567 +0.539234 0.656545 +0.538932 0.657200 +0.542426 0.657965 +0.538510 0.657784 +0.541806 0.659311 +0.537990 0.658259 +0.540937 0.660512 +0.539868 0.661488 +0.537407 0.658598 +0.538671 0.662185 +0.536802 0.658794 +0.536210 0.658855 +0.537426 0.662587 +0.535618 0.658794 +0.536210 0.662713 +0.534993 0.662587 +0.535013 0.658598 +0.533749 0.662185 +0.534430 0.658259 +0.532551 0.661488 +0.533910 0.657784 +0.531482 0.660512 +0.533487 0.657200 +0.530614 0.659311 +0.533186 0.656545 +0.529994 0.657965 +0.533012 0.655865 +0.529636 0.656567 +0.427302 0.657784 +0.426404 0.655865 +0.426350 0.655200 +0.426350 0.655200 +0.426404 0.655865 +0.426578 0.656545 +0.426578 0.656545 +0.426880 0.657200 +0.427302 0.657784 +0.426880 0.657200 +0.432854 0.655200 +0.432854 0.655200 +0.432800 0.655865 +0.432626 0.656545 +0.432800 0.655865 +0.432324 0.657200 +0.432626 0.656545 +0.432324 0.657200 +0.431902 0.657784 +0.431902 0.657784 +0.431382 0.658259 +0.430799 0.658598 +0.431382 0.658259 +0.430799 0.658598 +0.430194 0.658794 +0.429602 0.658855 +0.430194 0.658794 +0.429602 0.658855 +0.429010 0.658794 +0.429010 0.658794 +0.428405 0.658598 +0.428405 0.658598 +0.427822 0.658259 +0.427822 0.658259 +0.423028 0.656567 +0.422916 0.655200 +0.432854 0.655200 +0.436288 0.655200 +0.432800 0.655865 +0.436176 0.656567 +0.432626 0.656545 +0.432324 0.657200 +0.435818 0.657965 +0.435198 0.659311 +0.431902 0.657784 +0.431382 0.658259 +0.434329 0.660512 +0.433261 0.661488 +0.430799 0.658598 +0.432063 0.662185 +0.430194 0.658794 +0.430818 0.662587 +0.429602 0.658855 +0.429602 0.662713 +0.429010 0.658794 +0.428385 0.662587 +0.428405 0.658598 +0.427822 0.658259 +0.427141 0.662185 +0.425944 0.661488 +0.427302 0.657784 +0.424875 0.660512 +0.426880 0.657200 +0.424006 0.659311 +0.426578 0.656545 +0.423386 0.657965 +0.426404 0.655865 +0.426350 0.655200 +0.385483 0.510654 +0.385412 0.515491 +0.385559 0.520669 +0.391092 0.669007 +0.405948 0.668680 +0.409131 0.668674 +0.402855 0.500400 +0.400535 0.500410 +0.402698 0.668698 +0.398265 0.500451 +0.399563 0.668728 +0.396053 0.500545 +0.393977 0.500730 +0.396737 0.668771 +0.392053 0.501056 +0.394394 0.668824 +0.390326 0.501582 +0.388856 0.502354 +0.392654 0.668883 +0.387647 0.503433 +0.391562 0.668945 +0.386096 0.506512 +0.574250 0.668945 +0.574720 0.669007 +0.562956 0.500400 +0.556680 0.668674 +0.565283 0.500410 +0.567566 0.500451 +0.559864 0.668680 +0.569779 0.500546 +0.563113 0.668698 +0.571864 0.500733 +0.573799 0.501065 +0.566249 0.668728 +0.575520 0.501596 +0.569075 0.668771 +0.577001 0.502386 +0.578193 0.503466 +0.571418 0.668824 +0.579727 0.506551 +0.573158 0.668883 +0.580331 0.510686 +0.580400 0.515512 +0.580253 0.520668 +0.562956 0.500400 +0.567566 0.500451 +0.580341 0.518063 +0.580253 0.520668 +0.385559 0.520669 +0.385470 0.518056 +0.580400 0.515512 +0.580409 0.513025 +0.385412 0.515491 +0.385404 0.513002 +0.580331 0.510686 +0.385483 0.510654 +0.580122 0.508513 +0.385697 0.508467 +0.579727 0.506551 +0.386096 0.506512 +0.579101 0.504869 +0.578193 0.503466 +0.386737 0.504816 +0.387647 0.503433 +0.575520 0.501596 +0.390326 0.501582 +0.571864 0.500733 +0.393977 0.500730 +0.398265 0.500451 +0.402855 0.500400 +0.545707 0.695126 +0.545067 0.695205 +0.548858 0.691344 +0.548618 0.691075 +0.548798 0.692083 +0.548618 0.691144 +0.548605 0.692839 +0.548549 0.691876 +0.548269 0.693566 +0.548351 0.692625 +0.548050 0.693903 +0.548018 0.693345 +0.547800 0.694215 +0.547522 0.694496 +0.547556 0.693991 +0.547222 0.694743 +0.546575 0.695120 +0.546992 0.694518 +0.545902 0.695337 +0.546362 0.694900 +0.545245 0.695405 +0.551814 0.669075 +0.552471 0.669007 +0.548618 0.672799 +0.548858 0.673068 +0.548679 0.672060 +0.548919 0.672329 +0.548872 0.671304 +0.549112 0.671573 +0.549208 0.670577 +0.549447 0.670846 +0.549427 0.670239 +0.549666 0.670509 +0.549677 0.669927 +0.549954 0.669646 +0.549916 0.670197 +0.550255 0.669400 +0.550194 0.669916 +0.550902 0.669023 +0.550494 0.669669 +0.551574 0.668806 +0.551141 0.669293 +0.552232 0.668738 +0.420567 0.695405 +0.420745 0.695205 +0.417194 0.691144 +0.417193 0.691075 +0.416954 0.691344 +0.417263 0.691876 +0.417014 0.692083 +0.417461 0.692625 +0.417207 0.692839 +0.417794 0.693345 +0.417543 0.693566 +0.418256 0.693991 +0.417762 0.693904 +0.418012 0.694215 +0.418820 0.694518 +0.418289 0.694496 +0.418590 0.694743 +0.419450 0.694900 +0.419237 0.695120 +0.420105 0.695126 +0.419909 0.695337 +0.416893 0.672329 +0.416954 0.673068 +0.413580 0.668738 +0.413340 0.669007 +0.414238 0.668806 +0.413998 0.669075 +0.414910 0.669023 +0.414671 0.669293 +0.415557 0.669400 +0.415318 0.669669 +0.415858 0.669646 +0.415618 0.669916 +0.416135 0.669927 +0.416385 0.670239 +0.415895 0.670197 +0.416604 0.670577 +0.416146 0.670509 +0.416940 0.671304 +0.416365 0.670846 +0.417133 0.672060 +0.416700 0.671573 +0.417193 0.672799 +0.498275 0.569917 +0.499023 0.569917 +0.467058 0.566621 +0.466789 0.569917 +0.467537 0.569917 +0.467794 0.566774 +0.467920 0.563250 +0.469416 0.560006 +0.468616 0.563560 +0.471509 0.557110 +0.470042 0.560466 +0.474086 0.554758 +0.472039 0.557705 +0.474496 0.555461 +0.476973 0.553077 +0.477249 0.553859 +0.479973 0.552108 +0.480109 0.552935 +0.482906 0.551805 +0.482906 0.552646 +0.485839 0.552108 +0.488839 0.553077 +0.485702 0.552935 +0.491725 0.554758 +0.488563 0.553859 +0.491316 0.555461 +0.494302 0.557110 +0.493773 0.557705 +0.496396 0.560006 +0.495769 0.560466 +0.497891 0.563250 +0.497196 0.563560 +0.498754 0.566621 +0.498018 0.566774 +0.527175 0.670705 +0.527175 0.670769 +0.528982 0.668738 +0.528982 0.668674 +0.528653 0.668772 +0.528653 0.668708 +0.528317 0.668881 +0.528317 0.668817 +0.527993 0.669069 +0.527993 0.669005 +0.527843 0.669192 +0.527843 0.669128 +0.527705 0.669333 +0.527705 0.669269 +0.527579 0.669489 +0.527579 0.669425 +0.527470 0.669658 +0.527470 0.669594 +0.527302 0.670021 +0.527302 0.669958 +0.527205 0.670399 +0.527205 0.670336 +0.437158 0.668708 +0.436830 0.668674 +0.438606 0.670399 +0.438637 0.670769 +0.438637 0.670705 +0.438510 0.670021 +0.438606 0.670336 +0.438342 0.669658 +0.438510 0.669958 +0.438232 0.669489 +0.438342 0.669594 +0.438107 0.669333 +0.438232 0.669425 +0.437969 0.669192 +0.438107 0.669269 +0.437818 0.669069 +0.437969 0.669129 +0.437495 0.668881 +0.437818 0.669005 +0.437158 0.668772 +0.437495 0.668817 +0.436830 0.668738 +0.527175 0.695205 +0.545067 0.695205 +0.548549 0.691876 +0.548618 0.691144 +0.527175 0.691144 +0.548351 0.692625 +0.527175 0.691942 +0.548018 0.693345 +0.527175 0.692725 +0.547556 0.693991 +0.527175 0.693416 +0.546992 0.694518 +0.527175 0.693991 +0.527175 0.694470 +0.546362 0.694900 +0.527175 0.694857 +0.545707 0.695126 +0.527175 0.695112 +0.420105 0.695126 +0.420745 0.695205 +0.438637 0.691942 +0.438637 0.691144 +0.417194 0.691144 +0.417263 0.691876 +0.438637 0.692725 +0.417461 0.692625 +0.438637 0.693416 +0.417794 0.693345 +0.438637 0.693991 +0.418256 0.693991 +0.438637 0.694470 +0.438637 0.694857 +0.418820 0.694518 +0.438637 0.695112 +0.419450 0.694900 +0.438637 0.695205 +0.438637 0.691878 +0.527175 0.691878 +0.527175 0.691081 +0.438637 0.691081 +0.438637 0.695048 +0.438637 0.695141 +0.527175 0.695141 +0.438637 0.694794 +0.527175 0.695048 +0.438637 0.694407 +0.527175 0.694794 +0.527175 0.694407 +0.438637 0.693927 +0.527175 0.693927 +0.438637 0.693353 +0.527175 0.693353 +0.438637 0.692661 +0.527175 0.692661 + + + + + + + + + + + +

31 0 31 6 1 6 0 2 0 3 3 3 1 4 1 2 5 2 5 6 5 1 7 1 3 8 3 5 9 5 4 10 4 1 11 1 7 12 7 4 13 4 5 14 5 7 15 7 6 16 6 4 17 4 0 18 0 6 19 6 7 20 7 11 21 11 8 22 8 9 23 9 11 24 11 10 25 10 8 26 8 14 27 14 10 28 10 11 29 11 14 30 14 12 31 12 10 32 10 14 33 14 13 34 13 12 35 12 16 36 16 13 37 13 14 38 14 16 39 16 15 40 15 13 41 13 17 42 17 15 43 15 16 44 16 19 45 19 15 46 15 17 47 17 19 48 19 18 49 18 15 50 15 21 51 21 18 52 18 19 53 19 21 54 21 20 55 20 18 56 18 23 57 23 20 58 20 21 59 21 23 60 23 22 61 22 20 62 20 25 63 25 22 64 22 23 65 23 25 66 25 24 67 24 22 68 22 28 69 28 24 70 24 25 71 25 28 72 28 26 73 26 24 74 24 28 75 28 27 76 27 26 77 26 30 78 30 27 79 27 28 80 28 30 81 30 29 82 29 27 83 27 32 84 32 29 85 29 30 86 30 32 87 32 31 88 31 29 89 29 33 90 33 31 91 31 32 92 32 6 93 6 31 94 31 33 95 33 66 96 66 34 97 34 35 98 35 38 99 38 36 100 36 37 101 37 39 102 39 36 103 36 38 104 38 41 105 41 36 106 36 39 107 39 41 108 41 40 109 40 36 110 36 43 111 43 40 112 40 41 113 41 43 114 43 42 115 42 40 116 40 46 117 46 42 118 42 43 119 43 46 120 46 44 121 44 42 122 42 46 123 46 45 124 45 44 125 44 47 126 47 45 127 45 46 128 46 49 129 49 45 130 45 47 131 47 49 132 49 48 133 48 45 134 45 51 135 51 48 136 48 49 137 49 51 138 51 50 139 50 48 140 48 53 141 53 50 142 50 51 143 51 53 144 53 52 145 52 50 146 50 55 147 55 52 148 52 53 149 53 55 150 55 54 151 54 52 152 52 57 153 57 54 154 54 55 155 55 57 156 57 56 157 56 54 158 54 59 159 59 56 160 56 57 161 57 59 162 59 58 163 58 56 164 56 61 165 61 58 166 58 59 167 59 61 168 61 60 169 60 58 170 58 63 171 63 60 172 60 61 173 61 63 174 63 62 175 62 60 176 60 65 177 65 62 178 62 63 179 63 65 180 65 64 181 64 62 182 62 67 183 67 64 184 64 65 185 65 67 186 67 66 187 66 64 188 64 34 189 34 66 190 66 67 191 67 99 192 99 71 193 71 68 194 68 68 195 68 69 196 69 70 197 70 68 198 68 71 199 71 69 200 69 74 201 74 72 202 72 73 203 73 76 204 76 72 205 72 74 206 74 76 207 76 75 208 75 72 209 72 77 210 77 75 211 75 76 212 76 79 213 79 75 214 75 77 215 77 79 216 79 78 217 78 75 218 75 81 219 81 78 220 78 79 221 79 81 222 81 80 223 80 78 224 78 84 225 84 80 226 80 81 227 81 84 228 84 82 229 82 80 230 80 84 231 84 83 232 83 82 233 82 85 234 85 83 235 83 84 236 84 87 237 87 83 238 83 85 239 85 87 240 87 86 241 86 83 242 83 90 243 90 86 244 86 87 245 87 90 246 90 88 247 88 86 248 86 90 249 90 89 250 89 88 251 88 91 252 91 89 253 89 90 254 90 93 255 93 89 256 89 91 257 91 93 258 93 92 259 92 89 260 89 96 261 96 92 262 92 93 263 93 96 264 96 94 265 94 92 266 92 96 267 96 95 268 95 94 269 94 97 270 97 95 271 95 96 272 96 100 273 100 95 274 95 97 275 97 100 276 100 98 277 98 95 278 95 100 279 100 99 280 99 98 281 98 101 282 101 99 283 99 100 284 100 71 285 71 99 286 99 101 287 101 135 288 135 102 289 102 106 290 106 107 291 107 103 292 103 104 293 104 107 294 107 105 295 105 103 296 103 107 297 107 106 298 106 105 299 105 135 300 135 106 301 106 107 302 107 110 303 110 108 304 108 109 305 109 111 306 111 108 307 108 110 308 110 113 309 113 108 310 108 111 311 111 113 312 113 112 313 112 108 314 108 115 315 115 112 316 112 113 317 113 115 318 115 114 319 114 112 320 112 117 321 117 114 322 114 115 323 115 117 324 117 116 325 116 114 326 114 119 327 119 116 328 116 117 329 117 119 330 119 118 331 118 116 332 116 121 333 121 118 334 118 119 335 119 121 336 121 120 337 120 118 338 118 123 339 123 120 340 120 121 341 121 123 342 123 122 343 122 120 344 120 125 345 125 122 346 122 123 347 123 125 348 125 124 349 124 122 350 122 127 351 127 124 352 124 125 353 125 127 354 127 126 355 126 124 356 124 129 357 129 126 358 126 127 359 127 129 360 129 128 361 128 126 362 126 131 363 131 128 364 128 129 365 129 131 366 131 130 367 130 128 368 128 133 369 133 130 370 130 131 371 131 133 372 133 132 373 132 130 374 130 102 375 102 132 376 132 133 377 133 102 378 102 134 379 134 132 380 132 102 381 102 135 382 135 134 383 134 168 384 168 136 385 136 137 386 137 142 387 142 138 388 138 139 389 139 142 390 142 140 391 140 138 392 138 142 393 142 141 394 141 140 395 140 144 396 144 141 397 141 142 398 142 144 399 144 143 400 143 141 401 141 145 402 145 143 403 143 144 404 144 147 405 147 143 406 143 145 407 145 147 408 147 146 409 146 143 410 143 149 411 149 146 412 146 147 413 147 149 414 149 148 415 148 146 416 146 152 417 152 148 418 148 149 419 149 152 420 152 150 421 150 148 422 148 152 423 152 151 424 151 150 425 150 153 426 153 151 427 151 152 428 152 155 429 155 151 430 151 153 431 153 155 432 155 154 433 154 151 434 151 157 435 157 154 436 154 155 437 155 157 438 157 156 439 156 154 440 154 159 441 159 156 442 156 157 443 157 159 444 159 158 445 158 156 446 156 161 447 161 158 448 158 159 449 159 161 450 161 160 451 160 158 452 158 163 453 163 160 454 160 161 455 161 163 456 163 162 457 162 160 458 160 165 459 165 162 460 162 163 461 163 165 462 165 164 463 164 162 464 162 167 465 167 164 466 164 165 467 165 167 468 167 166 469 166 164 470 164 169 471 169 166 472 166 167 473 167 169 474 169 168 475 168 166 476 166 136 477 136 168 478 168 169 479 169 202 480 202 170 481 170 171 482 171 175 483 175 172 484 172 173 485 173 175 486 175 174 487 174 172 488 172 177 489 177 174 490 174 175 491 175 177 492 177 176 493 176 174 494 174 179 495 179 176 496 176 177 497 177 179 498 179 178 499 178 176 500 176 181 501 181 178 502 178 179 503 179 181 504 181 180 505 180 178 506 178 183 507 183 180 508 180 181 509 181 183 510 183 182 511 182 180 512 180 185 513 185 182 514 182 183 515 183 185 516 185 184 517 184 182 518 182 187 519 187 184 520 184 185 521 185 187 522 187 186 523 186 184 524 184 189 525 189 186 526 186 187 527 187 189 528 189 188 529 188 186 530 186 191 531 191 188 532 188 189 533 189 191 534 191 190 535 190 188 536 188 193 537 193 190 538 190 191 539 191 193 540 193 192 541 192 190 542 190 195 543 195 192 544 192 193 545 193 195 546 195 194 547 194 192 548 192 197 549 197 194 550 194 195 551 195 197 552 197 196 553 196 194 554 194 199 555 199 196 556 196 197 557 197 199 558 199 198 559 198 196 560 196 201 561 201 198 562 198 199 563 199 201 564 201 200 565 200 198 566 198 203 567 203 200 568 200 201 569 201 203 570 203 202 571 202 200 572 200 170 573 170 202 574 202 203 575 203 236 576 236 208 577 208 204 578 204 209 579 209 205 580 205 206 581 206 209 582 209 207 583 207 205 584 205 209 585 209 208 586 208 207 587 207 204 588 204 208 589 208 209 590 209 212 591 212 210 592 210 211 593 211 213 594 213 210 595 210 212 596 212 216 597 216 210 598 210 213 599 213 216 600 216 214 601 214 210 602 210 216 603 216 215 604 215 214 605 214 217 606 217 215 607 215 216 608 216 219 609 219 215 610 215 217 611 217 219 612 219 218 613 218 215 614 215 221 615 221 218 616 218 219 617 219 221 618 221 220 619 220 218 620 218 223 621 223 220 622 220 221 623 221 223 624 223 222 625 222 220 626 220 225 627 225 222 628 222 223 629 223 225 630 225 224 631 224 222 632 222 227 633 227 224 634 224 225 635 225 227 636 227 226 637 226 224 638 224 229 639 229 226 640 226 227 641 227 229 642 229 228 643 228 226 644 226 231 645 231 228 646 228 229 647 229 231 648 231 230 649 230 228 650 228 233 651 233 230 652 230 231 653 231 233 654 233 232 655 232 230 656 230 235 657 235 232 658 232 233 659 233 235 660 235 234 661 234 232 662 232 237 663 237 234 664 234 235 665 235 237 666 237 236 667 236 234 668 234 208 669 208 236 670 236 237 671 237 270 672 270 238 673 238 239 674 239 243 675 243 240 676 240 241 677 241 243 678 243 242 679 242 240 680 240 245 681 245 242 682 242 243 683 243 245 684 245 244 685 244 242 686 242 247 687 247 244 688 244 245 689 245 247 690 247 246 691 246 244 692 244 249 693 249 246 694 246 247 695 247 249 696 249 248 697 248 246 698 246 251 699 251 248 700 248 249 701 249 251 702 251 250 703 250 248 704 248 253 705 253 250 706 250 251 707 251 253 708 253 252 709 252 250 710 250 255 711 255 252 712 252 253 713 253 255 714 255 254 715 254 252 716 252 257 717 257 254 718 254 255 719 255 257 720 257 256 721 256 254 722 254 259 723 259 256 724 256 257 725 257 259 726 259 258 727 258 256 728 256 261 729 261 258 730 258 259 731 259 261 732 261 260 733 260 258 734 258 263 735 263 260 736 260 261 737 261 263 738 263 262 739 262 260 740 260 265 741 265 262 742 262 263 743 263 265 744 265 264 745 264 262 746 262 267 747 267 264 748 264 265 749 265 267 750 267 266 751 266 264 752 264 269 753 269 266 754 266 267 755 267 269 756 269 268 757 268 266 758 266 271 759 271 268 760 268 269 761 269 271 762 271 270 763 270 268 764 268 238 765 238 270 766 270 271 767 271 304 768 304 272 769 272 273 770 273 278 771 278 274 772 274 275 773 275 278 774 278 276 775 276 274 776 274 278 777 278 277 778 277 276 779 276 279 780 279 277 781 277 278 782 278 281 783 281 277 784 277 279 785 279 281 786 281 280 787 280 277 788 277 283 789 283 280 790 280 281 791 281 283 792 283 282 793 282 280 794 280 285 795 285 282 796 282 283 797 283 285 798 285 284 799 284 282 800 282 287 801 287 284 802 284 285 803 285 287 804 287 286 805 286 284 806 284 289 807 289 286 808 286 287 809 287 289 810 289 288 811 288 286 812 286 291 813 291 288 814 288 289 815 289 291 816 291 290 817 290 288 818 288 293 819 293 290 820 290 291 821 291 293 822 293 292 823 292 290 824 290 295 825 295 292 826 292 293 827 293 295 828 295 294 829 294 292 830 292 297 831 297 294 832 294 295 833 295 297 834 297 296 835 296 294 836 294 299 837 299 296 838 296 297 839 297 299 840 299 298 841 298 296 842 296 301 843 301 298 844 298 299 845 299 301 846 301 300 847 300 298 848 298 303 849 303 300 850 300 301 851 301 303 852 303 302 853 302 300 854 300 305 855 305 302 856 302 303 857 303 305 858 305 304 859 304 302 860 302 272 861 272 304 862 304 305 863 305 338 864 338 306 865 306 307 866 307 310 867 310 308 868 308 309 869 309 311 870 311 308 871 308 310 872 310 313 873 313 308 874 308 311 875 311 313 876 313 312 877 312 308 878 308 315 879 315 312 880 312 313 881 313 315 882 315 314 883 314 312 884 312 317 885 317 314 886 314 315 887 315 317 888 317 316 889 316 314 890 314 319 891 319 316 892 316 317 893 317 319 894 319 318 895 318 316 896 316 321 897 321 318 898 318 319 899 319 321 900 321 320 901 320 318 902 318 323 903 323 320 904 320 321 905 321 323 906 323 322 907 322 320 908 320 325 909 325 322 910 322 323 911 323 325 912 325 324 913 324 322 914 322 327 915 327 324 916 324 325 917 325 327 918 327 326 919 326 324 920 324 329 921 329 326 922 326 327 923 327 329 924 329 328 925 328 326 926 326 331 927 331 328 928 328 329 929 329 331 930 331 330 931 330 328 932 328 334 933 334 330 934 330 331 935 331 334 936 334 332 937 332 330 938 330 334 939 334 333 940 333 332 941 332 335 942 335 333 943 333 334 944 334 337 945 337 333 946 333 335 947 335 337 948 337 336 949 336 333 950 333 339 951 339 336 952 336 337 953 337 339 954 339 338 955 338 336 956 336 306 957 306 338 958 338 339 959 339 372 960 372 340 961 340 341 962 341 345 963 345 342 964 342 343 965 343 345 966 345 344 967 344 342 968 342 347 969 347 344 970 344 345 971 345 347 972 347 346 973 346 344 974 344 349 975 349 346 976 346 347 977 347 349 978 349 348 979 348 346 980 346 351 981 351 348 982 348 349 983 349 351 984 351 350 985 350 348 986 348 353 987 353 350 988 350 351 989 351 353 990 353 352 991 352 350 992 350 355 993 355 352 994 352 353 995 353 355 996 355 354 997 354 352 998 352 357 999 357 354 1000 354 355 1001 355 357 1002 357 356 1003 356 354 1004 354 359 1005 359 356 1006 356 357 1007 357 359 1008 359 358 1009 358 356 1010 356 361 1011 361 358 1012 358 359 1013 359 361 1014 361 360 1015 360 358 1016 358 363 1017 363 360 1018 360 361 1019 361 363 1020 363 362 1021 362 360 1022 360 365 1023 365 362 1024 362 363 1025 363 365 1026 365 364 1027 364 362 1028 362 367 1029 367 364 1030 364 365 1031 365 367 1032 367 366 1033 366 364 1034 364 369 1035 369 366 1036 366 367 1037 367 369 1038 369 368 1039 368 366 1040 366 371 1041 371 368 1042 368 369 1043 369 371 1044 371 370 1045 370 368 1046 368 373 1047 373 370 1048 370 371 1049 371 373 1050 373 372 1051 372 370 1052 370 340 1053 340 372 1054 372 373 1055 373 406 1056 406 374 1057 374 375 1058 375 379 1059 379 376 1060 376 377 1061 377 379 1062 379 378 1063 378 376 1064 376 382 1065 382 378 1066 378 379 1067 379 382 1068 382 380 1069 380 378 1070 378 382 1071 382 381 1072 381 380 1073 380 383 1074 383 381 1075 381 382 1076 382 385 1077 385 381 1078 381 383 1079 383 385 1080 385 384 1081 384 381 1082 381 388 1083 388 384 1084 384 385 1085 385 388 1086 388 386 1087 386 384 1088 384 388 1089 388 387 1090 387 386 1091 386 390 1092 390 387 1093 387 388 1094 388 390 1095 390 389 1096 389 387 1097 387 391 1098 391 389 1099 389 390 1100 390 393 1101 393 389 1102 389 391 1103 391 393 1104 393 392 1105 392 389 1106 389 395 1107 395 392 1108 392 393 1109 393 395 1110 395 394 1111 394 392 1112 392 397 1113 397 394 1114 394 395 1115 395 397 1116 397 396 1117 396 394 1118 394 399 1119 399 396 1120 396 397 1121 397 399 1122 399 398 1123 398 396 1124 396 401 1125 401 398 1126 398 399 1127 399 401 1128 401 400 1129 400 398 1130 398 403 1131 403 400 1132 400 401 1133 401 403 1134 403 402 1135 402 400 1136 400 405 1137 405 402 1138 402 403 1139 403 405 1140 405 404 1141 404 402 1142 402 407 1143 407 404 1144 404 405 1145 405 407 1146 407 406 1147 406 404 1148 404 374 1149 374 406 1150 406 407 1151 407 440 1152 440 408 1153 408 409 1154 409 412 1155 412 410 1156 410 411 1157 411 413 1158 413 410 1159 410 412 1160 412 415 1161 415 410 1162 410 413 1163 413 415 1164 415 414 1165 414 410 1166 410 417 1167 417 414 1168 414 415 1169 415 417 1170 417 416 1171 416 414 1172 414 420 1173 420 416 1174 416 417 1175 417 420 1176 420 418 1177 418 416 1178 416 420 1179 420 419 1180 419 418 1181 418 421 1182 421 419 1183 419 420 1184 420 423 1185 423 419 1186 419 421 1187 421 423 1188 423 422 1189 422 419 1190 419 425 1191 425 422 1192 422 423 1193 423 425 1194 425 424 1195 424 422 1196 422 427 1197 427 424 1198 424 425 1199 425 427 1200 427 426 1201 426 424 1202 424 429 1203 429 426 1204 426 427 1205 427 429 1206 429 428 1207 428 426 1208 426 431 1209 431 428 1210 428 429 1211 429 431 1212 431 430 1213 430 428 1214 428 433 1215 433 430 1216 430 431 1217 431 433 1218 433 432 1219 432 430 1220 430 435 1221 435 432 1222 432 433 1223 433 435 1224 435 434 1225 434 432 1226 432 437 1227 437 434 1228 434 435 1229 435 437 1230 437 436 1231 436 434 1232 434 439 1233 439 436 1234 436 437 1235 437 439 1236 439 438 1237 438 436 1238 436 441 1239 441 438 1240 438 439 1241 439 441 1242 441 440 1243 440 438 1244 438 408 1245 408 440 1246 440 441 1247 441 475 1248 475 442 1249 442 443 1250 443 445 1251 445 443 1252 443 444 1253 444 475 1254 475 443 1255 443 445 1256 445 450 1257 450 446 1258 446 447 1259 447 450 1260 450 448 1261 448 446 1262 446 450 1263 450 449 1264 449 448 1265 448 452 1266 452 449 1267 449 450 1268 450 452 1269 452 451 1270 451 449 1271 449 453 1272 453 451 1273 451 452 1274 452 455 1275 455 451 1276 451 453 1277 453 455 1278 455 454 1279 454 451 1280 451 458 1281 458 454 1282 454 455 1283 455 458 1284 458 456 1285 456 454 1286 454 458 1287 458 457 1288 457 456 1289 456 459 1290 459 457 1291 457 458 1292 458 462 1293 462 457 1294 457 459 1295 459 462 1296 462 460 1297 460 457 1298 457 462 1299 462 461 1300 461 460 1301 460 463 1302 463 461 1303 461 462 1304 462 465 1305 465 461 1306 461 463 1307 463 465 1308 465 464 1309 464 461 1310 461 468 1311 468 464 1312 464 465 1313 465 468 1314 468 466 1315 466 464 1316 464 468 1317 468 467 1318 467 466 1319 466 470 1320 470 467 1321 467 468 1322 468 470 1323 470 469 1324 469 467 1325 467 471 1326 471 469 1327 469 470 1328 470 473 1329 473 469 1330 469 471 1331 471 473 1332 473 472 1333 472 469 1334 469 442 1335 442 472 1336 472 473 1337 473 442 1338 442 474 1339 474 472 1340 472 442 1341 442 475 1342 475 474 1343 474 509 1344 509 476 1345 476 487 1346 487 479 1347 479 477 1348 477 478 1349 478 480 1350 480 477 1351 477 479 1352 479 482 1353 482 477 1354 477 480 1355 480 482 1356 482 481 1357 481 477 1358 477 484 1359 484 481 1360 481 482 1361 482 484 1362 484 483 1363 483 481 1364 481 486 1365 486 483 1366 483 484 1367 484 486 1368 486 485 1369 485 483 1370 483 509 1371 509 485 1372 485 486 1373 486 509 1374 509 487 1375 487 485 1376 485 492 1377 492 488 1378 488 489 1379 489 492 1380 492 490 1381 490 488 1382 488 492 1383 492 491 1384 491 490 1385 490 493 1386 493 491 1387 491 492 1388 492 495 1389 495 491 1390 491 493 1391 493 495 1392 495 494 1393 494 491 1394 491 497 1395 497 494 1396 494 495 1397 495 497 1398 497 496 1399 496 494 1400 494 499 1401 499 496 1402 496 497 1403 497 499 1404 499 498 1405 498 496 1406 496 501 1407 501 498 1408 498 499 1409 499 501 1410 501 500 1411 500 498 1412 498 503 1413 503 500 1414 500 501 1415 501 503 1416 503 502 1417 502 500 1418 500 506 1419 506 502 1420 502 503 1421 503 506 1422 506 504 1423 504 502 1424 502 506 1425 506 505 1426 505 504 1427 504 507 1428 507 505 1429 505 506 1430 506 476 1431 476 505 1432 505 507 1433 507 476 1434 476 508 1435 508 505 1436 505 476 1437 476 509 1438 509 508 1439 508 542 1440 542 510 1441 510 511 1442 511 514 1443 514 512 1444 512 513 1445 513 516 1446 516 512 1447 512 514 1448 514 516 1449 516 515 1450 515 512 1451 512 517 1452 517 515 1453 515 516 1454 516 520 1455 520 515 1456 515 517 1457 517 520 1458 520 518 1459 518 515 1460 515 520 1461 520 519 1462 519 518 1463 518 521 1464 521 519 1465 519 520 1466 520 523 1467 523 519 1468 519 521 1469 521 523 1470 523 522 1471 522 519 1472 519 525 1473 525 522 1474 522 523 1475 523 525 1476 525 524 1477 524 522 1478 522 527 1479 527 524 1480 524 525 1481 525 527 1482 527 526 1483 526 524 1484 524 529 1485 529 526 1486 526 527 1487 527 529 1488 529 528 1489 528 526 1490 526 531 1491 531 528 1492 528 529 1493 529 531 1494 531 530 1495 530 528 1496 528 533 1497 533 530 1498 530 531 1499 531 533 1500 533 532 1501 532 530 1502 530 535 1503 535 532 1504 532 533 1505 533 535 1506 535 534 1507 534 532 1508 532 537 1509 537 534 1510 534 535 1511 535 537 1512 537 536 1513 536 534 1514 534 539 1515 539 536 1516 536 537 1517 537 539 1518 539 538 1519 538 536 1520 536 541 1521 541 538 1522 538 539 1523 539 541 1524 541 540 1525 540 538 1526 538 543 1527 543 540 1528 540 541 1529 541 543 1530 543 542 1531 542 540 1532 540 510 1533 510 542 1534 542 543 1535 543 576 1536 576 548 1537 548 544 1538 544 547 1539 547 545 1540 545 546 1541 546 549 1542 549 545 1543 545 547 1544 547 549 1545 549 548 1546 548 545 1547 545 544 1548 544 548 1549 548 549 1550 549 553 1551 553 550 1552 550 551 1553 551 553 1554 553 552 1555 552 550 1556 550 556 1557 556 552 1558 552 553 1559 553 556 1560 556 554 1561 554 552 1562 552 556 1563 556 555 1564 555 554 1565 554 557 1566 557 555 1567 555 556 1568 556 559 1569 559 555 1570 555 557 1571 557 559 1572 559 558 1573 558 555 1574 555 561 1575 561 558 1576 558 559 1577 559 561 1578 561 560 1579 560 558 1580 558 564 1581 564 560 1582 560 561 1583 561 564 1584 564 562 1585 562 560 1586 560 564 1587 564 563 1588 563 562 1589 562 565 1590 565 563 1591 563 564 1592 564 567 1593 567 563 1594 563 565 1595 565 567 1596 567 566 1597 566 563 1598 563 569 1599 569 566 1600 566 567 1601 567 569 1602 569 568 1603 568 566 1604 566 572 1605 572 568 1606 568 569 1607 569 572 1608 572 570 1609 570 568 1610 568 572 1611 572 571 1612 571 570 1613 570 574 1614 574 571 1615 571 572 1616 572 574 1617 574 573 1618 573 571 1619 571 575 1620 575 573 1621 573 574 1622 574 577 1623 577 573 1624 573 575 1625 575 577 1626 577 576 1627 576 573 1628 573 548 1629 548 576 1630 576 577 1631 577 610 1632 610 582 1633 582 578 1634 578 581 1635 581 579 1636 579 580 1637 580 583 1638 583 579 1639 579 581 1640 581 583 1641 583 582 1642 582 579 1643 579 578 1644 578 582 1645 582 583 1646 583 588 1647 588 584 1648 584 585 1649 585 588 1650 588 586 1651 586 584 1652 584 588 1653 588 587 1654 587 586 1655 586 589 1656 589 587 1657 587 588 1658 588 591 1659 591 587 1660 587 589 1661 589 591 1662 591 590 1663 590 587 1664 587 593 1665 593 590 1666 590 591 1667 591 593 1668 593 592 1669 592 590 1670 590 595 1671 595 592 1672 592 593 1673 593 595 1674 595 594 1675 594 592 1676 592 597 1677 597 594 1678 594 595 1679 595 597 1680 597 596 1681 596 594 1682 594 599 1683 599 596 1684 596 597 1685 597 599 1686 599 598 1687 598 596 1688 596 601 1689 601 598 1690 598 599 1691 599 601 1692 601 600 1693 600 598 1694 598 603 1695 603 600 1696 600 601 1697 601 603 1698 603 602 1699 602 600 1700 600 605 1701 605 602 1702 602 603 1703 603 605 1704 605 604 1705 604 602 1706 602 608 1707 608 604 1708 604 605 1709 605 608 1710 608 606 1711 606 604 1712 604 608 1713 608 607 1714 607 606 1715 606 609 1716 609 607 1717 607 608 1718 608 611 1719 611 607 1720 607 609 1721 609 611 1722 611 610 1723 610 607 1724 607 582 1725 582 610 1726 610 611 1727 611 644 1728 644 615 1729 615 612 1730 612 612 1731 612 613 1732 613 614 1733 614 612 1734 612 615 1735 615 613 1736 613 619 1737 619 616 1738 616 617 1739 617 619 1740 619 618 1741 618 616 1742 616 621 1743 621 618 1744 618 619 1745 619 621 1746 621 620 1747 620 618 1748 618 623 1749 623 620 1750 620 621 1751 621 623 1752 623 622 1753 622 620 1754 620 625 1755 625 622 1756 622 623 1757 623 625 1758 625 624 1759 624 622 1760 622 627 1761 627 624 1762 624 625 1763 625 627 1764 627 626 1765 626 624 1766 624 629 1767 629 626 1768 626 627 1769 627 629 1770 629 628 1771 628 626 1772 626 631 1773 631 628 1774 628 629 1775 629 631 1776 631 630 1777 630 628 1778 628 633 1779 633 630 1780 630 631 1781 631 633 1782 633 632 1783 632 630 1784 630 635 1785 635 632 1786 632 633 1787 633 635 1788 635 634 1789 634 632 1790 632 637 1791 637 634 1792 634 635 1793 635 637 1794 637 636 1795 636 634 1796 634 639 1797 639 636 1798 636 637 1799 637 639 1800 639 638 1801 638 636 1802 636 641 1803 641 638 1804 638 639 1805 639 641 1806 641 640 1807 640 638 1808 638 643 1809 643 640 1810 640 641 1811 641 643 1812 643 642 1813 642 640 1814 640 645 1815 645 642 1816 642 643 1817 643 645 1818 645 644 1819 644 642 1820 642 615 1821 615 644 1822 644 645 1823 645 678 1824 678 654 1825 654 646 1826 646 650 1827 650 647 1828 647 648 1829 648 650 1830 650 649 1831 649 647 1832 647 652 1833 652 649 1834 649 650 1835 650 652 1836 652 651 1837 651 649 1838 649 655 1839 655 651 1840 651 652 1841 652 655 1842 655 653 1843 653 651 1844 651 655 1845 655 654 1846 654 653 1847 653 646 1848 646 654 1849 654 655 1850 655 659 1851 659 656 1852 656 657 1853 657 659 1854 659 658 1855 658 656 1856 656 661 1857 661 658 1858 658 659 1859 659 661 1860 661 660 1861 660 658 1862 658 663 1863 663 660 1864 660 661 1865 661 663 1866 663 662 1867 662 660 1868 660 666 1869 666 662 1870 662 663 1871 663 666 1872 666 664 1873 664 662 1874 662 666 1875 666 665 1876 665 664 1877 664 667 1878 667 665 1879 665 666 1880 666 669 1881 669 665 1882 665 667 1883 667 669 1884 669 668 1885 668 665 1886 665 671 1887 671 668 1888 668 669 1889 669 671 1890 671 670 1891 670 668 1892 668 673 1893 673 670 1894 670 671 1895 671 673 1896 673 672 1897 672 670 1898 670 675 1899 675 672 1900 672 673 1901 673 675 1902 675 674 1903 674 672 1904 672 677 1905 677 674 1906 674 675 1907 675 677 1908 677 676 1909 676 674 1910 674 679 1911 679 676 1912 676 677 1913 677 679 1914 679 678 1915 678 676 1916 676 654 1917 654 678 1918 678 679 1919 679 712 1920 712 681 1921 681 680 1922 680 683 1923 683 681 1924 681 682 1925 682 680 1926 680 681 1927 681 683 1928 683 687 1929 687 684 1930 684 685 1931 685 687 1932 687 686 1933 686 684 1934 684 689 1935 689 686 1936 686 687 1937 687 689 1938 689 688 1939 688 686 1940 686 691 1941 691 688 1942 688 689 1943 689 691 1944 691 690 1945 690 688 1946 688 693 1947 693 690 1948 690 691 1949 691 693 1950 693 692 1951 692 690 1952 690 695 1953 695 692 1954 692 693 1955 693 695 1956 695 694 1957 694 692 1958 692 697 1959 697 694 1960 694 695 1961 695 697 1962 697 696 1963 696 694 1964 694 699 1965 699 696 1966 696 697 1967 697 699 1968 699 698 1969 698 696 1970 696 701 1971 701 698 1972 698 699 1973 699 701 1974 701 700 1975 700 698 1976 698 703 1977 703 700 1978 700 701 1979 701 703 1980 703 702 1981 702 700 1982 700 705 1983 705 702 1984 702 703 1985 703 705 1986 705 704 1987 704 702 1988 702 708 1989 708 704 1990 704 705 1991 705 708 1992 708 706 1993 706 704 1994 704 708 1995 708 707 1996 707 706 1997 706 709 1998 709 707 1999 707 708 2000 708 711 2001 711 707 2002 707 709 2003 709 711 2004 711 710 2005 710 707 2006 707 713 2007 713 710 2008 710 711 2009 711 713 2010 713 712 2011 712 710 2012 710 681 2013 681 712 2014 712 713 2015 713 716 2016 716 714 2017 714 715 2018 715 714 2019 714 716 2020 716 717 2021 717 720 2022 720 718 2023 718 719 2024 719 722 2025 722 720 2026 720 721 2027 721 725 2028 725 720 2029 720 722 2030 722 718 2031 718 723 2032 723 724 2033 724 718 2034 718 725 2035 725 723 2036 723 718 2037 718 720 2038 720 725 2039 725 728 2040 728 726 2041 726 727 2042 727 726 2043 726 728 2044 728 729 2045 729 742 2046 742 730 2047 730 731 2048 731 735 2049 735 732 2050 732 733 2051 733 735 2052 735 734 2053 734 732 2054 732 730 2055 730 734 2056 734 735 2057 735 730 2058 730 736 2059 736 734 2060 734 730 2061 730 737 2062 737 736 2063 736 730 2064 730 738 2065 738 737 2066 737 730 2067 730 739 2068 739 738 2069 738 730 2070 730 740 2071 740 739 2072 739 730 2073 730 741 2074 741 740 2075 740 730 2076 730 742 2077 742 741 2078 741 748 2079 748 743 2080 743 744 2081 744 747 2082 747 745 2083 745 746 2084 746 749 2085 749 745 2086 745 747 2087 747 749 2088 749 748 2089 748 745 2090 745 750 2091 750 748 2092 748 749 2093 749 751 2094 751 748 2095 748 750 2096 750 752 2097 752 748 2098 748 751 2099 751 753 2100 753 748 2101 748 752 2102 752 754 2103 754 748 2104 748 753 2105 753 755 2106 755 748 2107 748 754 2108 754 743 2109 743 748 2110 748 755 2111 755 1018 2112 1018 756 2113 756 1015 2114 1015 758 2115 758 757 2116 757 1017 2117 1017 759 2118 759 757 2119 757 758 2120 758 760 2121 760 757 2122 757 759 2123 759 761 2124 761 757 2125 757 760 2126 760 762 2127 762 757 2128 757 761 2129 761 763 2130 763 757 2131 757 762 2132 762 764 2133 764 757 2134 757 763 2135 763 776 2136 776 757 2137 757 764 2138 764 773 2139 773 781 2140 781 765 2141 765 773 2142 773 766 2143 766 781 2144 781 773 2145 773 767 2146 767 766 2147 766 773 2148 773 768 2149 768 767 2150 767 773 2151 773 769 2152 769 768 2153 768 773 2154 773 770 2155 770 769 2156 769 773 2157 773 771 2158 771 770 2159 770 773 2160 773 772 2161 772 771 2162 771 786 2163 786 772 2164 772 773 2165 773 786 2166 786 774 2167 774 772 2168 772 776 2169 776 775 2170 775 757 2171 757 777 2172 777 775 2173 775 776 2174 776 795 2175 795 775 2176 775 777 2177 777 786 2178 786 778 2179 778 774 2180 774 802 2181 802 780 2182 780 779 2183 779 801 2184 801 779 2185 779 780 2186 780 811 2187 811 765 2188 765 781 2189 781 1017 2190 1017 782 2191 782 758 2192 758 795 2193 795 783 2194 783 775 2195 775 840 2196 840 784 2197 784 797 2198 797 817 2199 817 897 2200 897 785 2201 785 806 2202 806 778 2203 778 786 2204 786 788 2205 788 787 2206 787 790 2207 790 807 2208 807 787 2209 787 788 2210 788 790 2211 790 789 2212 789 788 2213 788 815 2214 815 789 2215 789 790 2216 790 804 2217 804 793 2218 793 791 2219 791 804 2220 804 792 2221 792 793 2222 793 809 2223 809 791 2224 791 793 2225 793 809 2226 809 794 2227 794 791 2228 791 814 2229 814 783 2230 783 795 2231 795 806 2232 806 796 2233 796 778 2234 778 861 2235 861 840 2236 840 797 2237 797 897 2238 897 798 2239 798 785 2240 785 802 2241 802 799 2242 799 780 2243 780 801 2244 801 800 2245 800 779 2246 779 859 2247 859 800 2248 800 801 2249 801 860 2250 860 799 2251 799 802 2252 802 815 2253 815 803 2254 803 789 2255 789 820 2256 820 792 2257 792 804 2258 804 814 2259 814 805 2260 805 783 2261 783 808 2262 808 796 2263 796 806 2264 806 805 2265 805 787 2266 787 807 2267 807 809 2268 809 808 2269 808 794 2270 794 892 2271 892 808 2272 808 809 2273 809 805 2274 805 810 2275 810 787 2276 787 865 2277 865 765 2278 765 811 2279 811 1017 2280 1017 812 2281 812 782 2282 782 808 2283 808 813 2284 813 796 2285 796 863 2286 863 805 2287 805 814 2288 814 869 2289 869 803 2290 803 815 2291 815 840 2292 840 816 2293 816 784 2294 784 831 2295 831 897 2296 897 817 2297 817 820 2298 820 818 2299 818 792 2300 792 860 2301 860 819 2302 819 799 2303 799 880 2304 880 818 2305 818 820 2306 820 869 2307 869 821 2308 821 803 2309 803 831 2310 831 822 2311 822 897 2312 897 831 2313 831 823 2314 823 822 2315 822 831 2316 831 824 2317 824 823 2318 823 831 2319 831 825 2320 825 824 2321 824 831 2322 831 826 2323 826 825 2324 825 831 2325 831 827 2326 827 826 2327 826 831 2328 831 828 2329 828 827 2330 827 831 2331 831 829 2332 829 828 2333 828 831 2334 831 830 2335 830 829 2336 829 832 2337 832 830 2338 830 831 2339 831 833 2340 833 830 2341 830 832 2342 832 834 2343 834 830 2344 830 833 2345 833 835 2346 835 830 2347 830 834 2348 834 836 2349 836 830 2350 830 835 2351 835 837 2352 837 830 2353 830 836 2354 836 838 2355 838 830 2356 830 837 2357 837 839 2358 839 830 2359 830 838 2360 838 868 2361 868 830 2362 830 839 2363 839 841 2364 841 816 2365 816 840 2366 840 842 2367 842 816 2368 816 841 2369 841 843 2370 843 816 2371 816 842 2372 842 844 2373 844 816 2374 816 843 2375 843 845 2376 845 816 2377 816 844 2378 844 846 2379 846 816 2380 816 845 2381 845 847 2382 847 816 2383 816 846 2384 846 848 2385 848 816 2386 816 847 2387 847 870 2388 870 816 2389 816 848 2390 848 870 2391 870 849 2392 849 816 2393 816 870 2394 870 850 2395 850 849 2396 849 870 2397 870 851 2398 851 850 2399 850 870 2400 870 852 2401 852 851 2402 851 870 2403 870 853 2404 853 852 2405 852 870 2406 870 854 2407 854 853 2408 853 870 2409 870 855 2410 855 854 2411 854 870 2412 870 856 2413 856 855 2414 855 870 2415 870 857 2416 857 856 2417 856 859 2418 859 858 2419 858 800 2420 800 889 2421 889 858 2422 858 859 2423 859 893 2424 893 819 2425 819 860 2426 860 896 2427 896 840 2428 840 861 2429 861 897 2430 897 862 2431 862 798 2432 798 819 2433 819 805 2434 805 863 2435 863 808 2436 808 864 2437 864 813 2438 813 922 2439 922 765 2440 765 865 2441 865 1017 2442 1017 866 2443 866 812 2444 812 870 2445 870 867 2446 867 857 2447 857 881 2448 881 830 2449 830 868 2450 868 872 2451 872 821 2452 821 869 2453 869 872 2454 872 870 2455 870 821 2456 821 872 2457 872 867 2458 867 870 2459 870 872 2460 872 871 2461 871 867 2462 867 875 2463 875 871 2464 871 872 2465 872 875 2466 875 873 2467 873 871 2468 871 875 2469 875 874 2470 874 873 2471 873 877 2472 877 874 2473 874 875 2474 875 877 2475 877 876 2476 876 874 2477 874 894 2478 894 876 2479 876 877 2480 877 894 2481 894 878 2482 878 876 2483 876 880 2484 880 879 2485 879 818 2486 818 830 2487 830 879 2488 879 880 2489 880 881 2490 881 879 2491 879 830 2492 830 883 2493 883 879 2494 879 881 2495 881 883 2496 883 882 2497 882 879 2498 879 884 2499 884 882 2500 882 883 2501 883 886 2502 886 882 2503 882 884 2504 884 886 2505 886 885 2506 885 882 2507 882 888 2508 888 885 2509 885 886 2510 886 888 2511 888 887 2512 887 885 2513 885 918 2514 918 887 2515 887 888 2516 888 920 2517 920 858 2518 858 889 2519 889 920 2520 920 890 2521 890 858 2522 858 805 2523 805 891 2524 891 810 2525 810 947 2526 947 808 2527 808 892 2528 892 925 2529 925 819 2530 819 893 2531 893 909 2532 909 878 2533 878 894 2534 894 909 2535 909 895 2536 895 878 2537 878 898 2538 898 840 2539 840 896 2540 896 898 2541 898 897 2542 897 840 2543 840 899 2544 899 897 2545 897 898 2546 898 900 2547 900 897 2548 897 899 2549 899 901 2550 901 897 2551 897 900 2552 900 902 2553 902 897 2554 897 901 2555 901 903 2556 903 897 2557 897 902 2558 902 904 2559 904 897 2560 897 903 2561 903 905 2562 905 897 2563 897 904 2564 904 906 2565 906 897 2566 897 905 2567 905 907 2568 907 897 2569 897 906 2570 906 908 2571 908 897 2572 897 907 2573 907 895 2574 895 897 2575 897 908 2576 908 909 2577 909 897 2578 897 895 2579 895 910 2580 910 897 2581 897 909 2582 909 911 2583 911 897 2584 897 910 2585 910 912 2586 912 897 2587 897 911 2588 911 913 2589 913 897 2590 897 912 2591 912 914 2592 914 897 2593 897 913 2594 913 915 2595 915 897 2596 897 914 2597 914 924 2598 924 897 2599 897 915 2600 915 897 2601 897 916 2602 916 862 2603 862 918 2604 918 917 2605 917 887 2606 887 961 2607 961 917 2608 917 918 2609 918 808 2610 808 919 2611 919 864 2612 864 965 2613 965 890 2614 890 920 2615 920 965 2616 965 921 2617 921 890 2618 890 970 2619 970 765 2620 765 922 2621 922 1017 2622 1017 923 2623 923 866 2624 866 943 2625 943 897 2626 897 924 2627 924 936 2628 936 819 2629 819 925 2630 925 805 2631 805 926 2632 926 891 2633 891 819 2634 819 926 2635 926 805 2636 805 819 2637 819 927 2638 927 926 2639 926 819 2640 819 928 2641 928 927 2642 927 819 2643 819 929 2644 929 928 2645 928 819 2646 819 930 2647 930 929 2648 929 819 2649 819 931 2650 931 930 2651 930 936 2652 936 931 2653 931 819 2654 819 936 2655 936 932 2656 932 931 2657 931 936 2658 936 933 2659 933 932 2660 932 936 2661 936 934 2662 934 933 2663 933 936 2664 936 935 2665 935 934 2666 934 938 2667 938 935 2668 935 936 2669 936 938 2670 938 937 2671 937 935 2672 935 940 2673 940 937 2674 937 938 2675 938 940 2676 940 939 2677 939 937 2678 937 942 2679 942 939 2680 939 940 2681 940 942 2682 942 941 2683 941 939 2684 939 944 2685 944 941 2686 941 942 2687 942 944 2688 944 943 2689 943 941 2690 941 945 2691 945 943 2692 943 944 2693 944 946 2694 946 943 2695 943 945 2696 945 964 2697 964 943 2698 943 946 2699 946 948 2700 948 808 2701 808 947 2702 947 948 2703 948 919 2704 919 808 2705 808 949 2706 949 919 2707 919 948 2708 948 950 2709 950 919 2710 919 949 2711 949 951 2712 951 919 2713 919 950 2714 950 952 2715 952 919 2716 919 951 2717 951 953 2718 953 919 2719 919 952 2720 952 954 2721 954 919 2722 919 953 2723 953 955 2724 955 919 2725 919 954 2726 954 956 2727 956 919 2728 919 955 2729 955 957 2730 957 919 2731 919 956 2732 956 958 2733 958 919 2734 919 957 2735 957 960 2736 960 919 2737 919 958 2738 958 960 2739 960 959 2740 959 919 2741 919 967 2742 967 959 2743 959 960 2744 960 969 2745 969 917 2746 917 961 2747 961 969 2748 969 962 2749 962 917 2750 917 897 2751 897 963 2752 963 916 2753 916 980 2754 980 943 2755 943 964 2756 964 987 2757 987 921 2758 921 965 2759 965 987 2760 987 966 2761 966 921 2762 921 990 2763 990 959 2764 959 967 2765 967 990 2766 990 968 2767 968 959 2768 959 979 2769 979 962 2770 962 969 2771 969 992 2772 992 765 2773 765 970 2774 970 1017 2775 1017 971 2776 971 923 2777 923 897 2778 897 972 2779 972 963 2780 963 943 2781 943 972 2782 972 897 2783 897 943 2784 943 973 2785 973 972 2786 972 943 2787 943 974 2788 974 973 2789 973 943 2790 943 975 2791 975 974 2792 974 943 2793 943 976 2794 976 975 2795 975 943 2796 943 977 2797 977 976 2798 976 943 2799 943 978 2800 978 977 2801 977 980 2802 980 978 2803 978 943 2804 943 980 2805 980 979 2806 979 978 2807 978 981 2808 981 979 2809 979 980 2810 980 982 2811 982 979 2812 979 981 2813 981 983 2814 983 979 2815 979 982 2816 982 984 2817 984 979 2818 979 983 2819 983 985 2820 985 979 2821 979 984 2822 984 991 2823 991 979 2824 979 985 2825 985 979 2826 979 986 2827 986 962 2828 962 1010 2829 1010 966 2830 966 987 2831 987 1010 2832 1010 988 2833 988 966 2834 966 990 2835 990 989 2836 989 968 2837 968 998 2838 998 989 2839 989 990 2840 990 999 2841 999 979 2842 979 991 2843 991 1019 2844 1019 765 2845 765 992 2846 992 1017 2847 1017 993 2848 993 971 2849 971 979 2850 979 994 2851 994 986 2852 986 999 2853 999 994 2854 994 979 2855 979 999 2856 999 995 2857 995 994 2858 994 999 2859 999 996 2860 996 995 2861 995 999 2862 999 997 2863 997 996 2864 996 999 2865 999 998 2866 998 997 2867 997 999 2868 999 989 2869 989 998 2870 998 1000 2871 1000 989 2872 989 999 2873 999 1001 2874 1001 989 2875 989 1000 2876 1000 1002 2877 1002 989 2878 989 1001 2879 1001 1005 2880 1005 989 2881 989 1002 2882 1002 1005 2883 1005 1003 2884 1003 989 2885 989 1005 2886 1005 1004 2887 1004 1003 2888 1003 1007 2889 1007 1004 2890 1004 1005 2891 1005 1007 2892 1007 1006 2893 1006 1004 2894 1004 988 2895 988 1006 2896 1006 1007 2897 1007 1010 2898 1010 1006 2899 1006 988 2900 988 1010 2901 1010 1008 2902 1008 1006 2903 1006 1010 2904 1010 1009 2905 1009 1008 2906 1008 1012 2907 1012 1009 2908 1009 1010 2909 1010 1012 2910 1012 1011 2911 1011 1009 2912 1009 1014 2913 1014 1011 2914 1011 1012 2915 1012 1014 2916 1014 1013 2917 1013 1011 2918 1011 1018 2919 1018 1013 2920 1013 1014 2921 1014 1018 2922 1018 1015 2923 1015 1013 2924 1013 1017 2925 1017 1016 2926 1016 993 2927 993 765 2928 765 1016 2929 1016 1017 2930 1017 765 2931 765 1018 2932 1018 1016 2933 1016 756 2934 756 765 2935 765 1019 2936 1019 756 2937 756 1018 2938 1018 765 2939 765 1203 2940 1203 1156 2941 1156 1020 2942 1020 1039 2943 1039 1022 2944 1022 1021 2945 1021 1038 2946 1038 1021 2947 1021 1022 2948 1022 1030 2949 1030 1023 2950 1023 1024 2951 1024 1030 2952 1030 1025 2953 1025 1023 2954 1023 1064 2955 1064 1026 2956 1026 1035 2957 1035 1084 2958 1084 1057 2959 1057 1027 2960 1027 1042 2961 1042 1094 2962 1094 1028 2963 1028 1043 2964 1043 1029 2965 1029 1033 2966 1033 1040 2967 1040 1025 2968 1025 1030 2969 1030 1040 2970 1040 1031 2971 1031 1025 2972 1025 1039 2973 1039 1032 2974 1032 1022 2975 1022 1061 2976 1061 1043 2977 1043 1033 2978 1033 1094 2979 1094 1034 2980 1034 1028 2981 1028 1121 2982 1121 1064 2983 1064 1035 2984 1035 1057 2985 1057 1036 2986 1036 1027 2987 1027 1038 2988 1038 1037 2989 1037 1021 2990 1021 1058 2991 1058 1037 2992 1037 1038 2993 1038 1060 2994 1060 1032 2995 1032 1039 2996 1039 1105 2997 1105 1031 2998 1031 1040 2999 1040 1105 3000 1105 1041 3001 1041 1031 3002 1031 1044 3003 1044 1094 3004 1094 1042 3005 1042 1044 3006 1044 1043 3007 1043 1094 3008 1094 1045 3009 1045 1043 3010 1043 1044 3011 1044 1046 3012 1046 1043 3013 1043 1045 3014 1045 1047 3015 1047 1043 3016 1043 1046 3017 1046 1048 3018 1048 1043 3019 1043 1047 3020 1047 1049 3021 1049 1043 3022 1043 1048 3023 1048 1050 3024 1050 1043 3025 1043 1049 3026 1049 1051 3027 1051 1043 3028 1043 1050 3029 1050 1052 3030 1052 1043 3031 1043 1051 3032 1051 1053 3033 1053 1043 3034 1043 1052 3035 1052 1107 3036 1107 1043 3037 1043 1053 3038 1053 1043 3039 1043 1054 3040 1054 1029 3041 1029 1060 3042 1060 1055 3043 1055 1032 3044 1032 1121 3045 1121 1056 3046 1056 1064 3047 1064 1123 3048 1123 1036 3049 1036 1057 3050 1057 1111 3051 1111 1037 3052 1037 1058 3053 1058 1111 3054 1111 1059 3055 1059 1037 3056 1037 1127 3057 1127 1055 3058 1055 1060 3059 1060 1134 3060 1134 1043 3061 1043 1061 3062 1061 1094 3063 1094 1062 3064 1062 1034 3065 1034 1064 3066 1064 1063 3067 1063 1026 3068 1026 1073 3069 1073 1063 3070 1063 1064 3071 1064 1073 3072 1073 1065 3073 1065 1063 3074 1063 1073 3075 1073 1066 3076 1066 1065 3077 1065 1073 3078 1073 1067 3079 1067 1066 3080 1066 1073 3081 1073 1068 3082 1068 1067 3083 1067 1073 3084 1073 1069 3085 1069 1068 3086 1068 1073 3087 1073 1070 3088 1070 1069 3089 1069 1073 3090 1073 1071 3091 1071 1070 3092 1070 1073 3093 1073 1072 3094 1072 1071 3095 1071 1043 3096 1043 1072 3097 1072 1073 3098 1073 1043 3099 1043 1074 3100 1074 1072 3101 1072 1043 3102 1043 1075 3103 1075 1074 3104 1074 1043 3105 1043 1076 3106 1076 1075 3107 1075 1043 3108 1043 1077 3109 1077 1076 3110 1076 1043 3111 1043 1078 3112 1078 1077 3113 1077 1043 3114 1043 1079 3115 1079 1078 3116 1078 1043 3117 1043 1080 3118 1080 1079 3119 1079 1043 3120 1043 1081 3121 1081 1080 3122 1080 1043 3123 1043 1082 3124 1082 1081 3125 1081 1043 3126 1043 1083 3127 1083 1082 3128 1082 1086 3129 1086 1057 3130 1057 1084 3131 1084 1086 3132 1086 1085 3133 1085 1057 3134 1057 1087 3135 1087 1085 3136 1085 1086 3137 1086 1088 3138 1088 1085 3139 1085 1087 3140 1087 1089 3141 1089 1085 3142 1085 1088 3143 1088 1090 3144 1090 1085 3145 1085 1089 3146 1089 1091 3147 1091 1085 3148 1085 1090 3149 1090 1092 3150 1092 1085 3151 1085 1091 3152 1091 1093 3153 1093 1085 3154 1085 1092 3155 1092 1095 3156 1095 1085 3157 1085 1093 3158 1093 1095 3159 1095 1094 3160 1094 1085 3161 1085 1096 3162 1096 1094 3163 1094 1095 3164 1095 1097 3165 1097 1094 3166 1094 1096 3167 1096 1098 3168 1098 1094 3169 1094 1097 3170 1097 1099 3171 1099 1094 3172 1094 1098 3173 1098 1100 3174 1100 1094 3175 1094 1099 3176 1099 1101 3177 1101 1094 3178 1094 1100 3179 1100 1102 3180 1102 1094 3181 1094 1101 3182 1101 1103 3183 1103 1094 3184 1094 1102 3185 1102 1104 3186 1104 1094 3187 1094 1103 3188 1103 1110 3189 1110 1094 3190 1094 1104 3191 1104 1130 3192 1130 1041 3193 1041 1105 3194 1105 1130 3195 1130 1106 3196 1106 1041 3197 1041 1120 3198 1120 1043 3199 1043 1107 3200 1107 1127 3201 1127 1108 3202 1108 1055 3203 1055 1043 3204 1043 1109 3205 1109 1083 3206 1083 1133 3207 1133 1094 3208 1094 1110 3209 1110 1119 3210 1119 1059 3211 1059 1111 3212 1111 1043 3213 1043 1112 3214 1112 1054 3215 1054 1120 3216 1120 1112 3217 1112 1043 3218 1043 1120 3219 1120 1113 3220 1113 1112 3221 1112 1120 3222 1120 1114 3223 1114 1113 3224 1113 1120 3225 1120 1115 3226 1115 1114 3227 1114 1120 3228 1120 1116 3229 1116 1115 3230 1115 1120 3231 1120 1117 3232 1117 1116 3233 1116 1120 3234 1120 1118 3235 1118 1117 3236 1117 1120 3237 1120 1119 3238 1119 1118 3239 1118 1136 3240 1136 1119 3241 1119 1120 3242 1120 1139 3243 1139 1056 3244 1056 1121 3245 1121 1139 3246 1139 1122 3247 1122 1056 3248 1056 1126 3249 1126 1036 3250 1036 1123 3251 1123 1126 3252 1126 1124 3253 1124 1036 3254 1036 1119 3255 1119 1125 3256 1125 1059 3257 1059 1146 3258 1146 1124 3259 1124 1126 3260 1126 1137 3261 1137 1108 3262 1108 1127 3263 1127 1139 3264 1139 1128 3265 1128 1122 3266 1122 1137 3267 1137 1129 3268 1129 1108 3269 1108 1140 3270 1140 1106 3271 1106 1130 3272 1130 1140 3273 1140 1131 3274 1131 1106 3275 1106 1043 3276 1043 1132 3277 1132 1109 3278 1109 1156 3279 1156 1094 3280 1094 1133 3281 1133 1173 3282 1173 1043 3283 1043 1134 3284 1134 1094 3285 1094 1135 3286 1135 1062 3287 1062 1166 3288 1166 1119 3289 1119 1136 3290 1136 1178 3291 1178 1129 3292 1129 1137 3293 1137 1178 3294 1178 1138 3295 1138 1129 3296 1129 1141 3297 1141 1128 3298 1128 1139 3299 1139 1141 3300 1141 1140 3301 1140 1128 3302 1128 1141 3303 1141 1131 3304 1131 1140 3305 1140 1142 3306 1142 1131 3307 1131 1141 3308 1141 1143 3309 1143 1131 3310 1131 1142 3311 1142 1144 3312 1144 1131 3313 1131 1143 3314 1143 1145 3315 1145 1131 3316 1131 1144 3317 1144 1153 3318 1153 1131 3319 1131 1145 3320 1145 1153 3321 1153 1146 3322 1146 1131 3323 1131 1153 3324 1153 1124 3325 1124 1146 3326 1146 1153 3327 1153 1147 3328 1147 1124 3329 1124 1153 3330 1153 1148 3331 1148 1147 3332 1147 1153 3333 1153 1149 3334 1149 1148 3335 1148 1153 3336 1153 1150 3337 1150 1149 3338 1149 1153 3339 1153 1151 3340 1151 1150 3341 1150 1153 3342 1153 1152 3343 1152 1151 3344 1151 1155 3345 1155 1152 3346 1152 1153 3347 1153 1155 3348 1155 1154 3349 1154 1152 3350 1152 1132 3351 1132 1154 3352 1154 1155 3353 1155 1132 3354 1132 1156 3355 1156 1154 3356 1154 1119 3357 1119 1157 3358 1157 1125 3359 1125 1166 3360 1166 1157 3361 1157 1119 3362 1119 1166 3363 1166 1158 3364 1158 1157 3365 1157 1166 3366 1166 1159 3367 1159 1158 3368 1158 1166 3369 1166 1160 3370 1160 1159 3371 1159 1166 3372 1166 1161 3373 1161 1160 3374 1160 1166 3375 1166 1162 3376 1162 1161 3377 1161 1166 3378 1166 1163 3379 1163 1162 3380 1162 1166 3381 1166 1164 3382 1164 1163 3383 1163 1166 3384 1166 1165 3385 1165 1164 3386 1164 1168 3387 1168 1165 3388 1165 1166 3389 1166 1168 3390 1168 1167 3391 1167 1165 3392 1165 1170 3393 1170 1167 3394 1167 1168 3395 1168 1170 3396 1170 1169 3397 1169 1167 3398 1167 1172 3399 1172 1169 3400 1169 1170 3401 1170 1172 3402 1172 1171 3403 1171 1169 3404 1169 1176 3405 1176 1171 3406 1171 1172 3407 1172 1180 3408 1180 1043 3409 1043 1173 3410 1173 1094 3411 1094 1174 3412 1174 1135 3413 1135 1178 3414 1178 1175 3415 1175 1138 3416 1138 1182 3417 1182 1171 3418 1171 1176 3419 1176 1182 3420 1182 1177 3421 1177 1171 3422 1171 1184 3423 1184 1175 3424 1175 1178 3425 1178 1094 3426 1094 1179 3427 1179 1174 3428 1174 1185 3429 1185 1043 3430 1043 1180 3431 1180 1184 3432 1184 1181 3433 1181 1175 3434 1175 1199 3435 1199 1177 3436 1177 1182 3437 1182 1199 3438 1199 1183 3439 1183 1177 3440 1177 1191 3441 1191 1181 3442 1181 1184 3443 1184 1186 3444 1186 1043 3445 1043 1185 3446 1185 1186 3447 1186 1132 3448 1132 1043 3449 1043 1187 3450 1187 1132 3451 1132 1186 3452 1186 1188 3453 1188 1132 3454 1132 1187 3455 1187 1189 3456 1189 1132 3457 1132 1188 3458 1188 1190 3459 1190 1132 3460 1132 1189 3461 1189 1181 3462 1181 1132 3463 1132 1190 3464 1190 1191 3465 1191 1132 3466 1132 1181 3467 1181 1191 3468 1191 1156 3469 1156 1132 3470 1132 1192 3471 1192 1156 3472 1156 1191 3473 1191 1193 3474 1193 1156 3475 1156 1192 3476 1192 1194 3477 1194 1156 3478 1156 1193 3479 1193 1195 3480 1195 1156 3481 1156 1194 3482 1194 1196 3483 1196 1156 3484 1156 1195 3485 1195 1197 3486 1197 1156 3487 1156 1196 3488 1196 1198 3489 1198 1156 3490 1156 1197 3491 1197 1183 3492 1183 1156 3493 1156 1198 3494 1198 1199 3495 1199 1156 3496 1156 1183 3497 1183 1200 3498 1200 1156 3499 1156 1199 3500 1199 1201 3501 1201 1156 3502 1156 1200 3503 1200 1202 3504 1202 1156 3505 1156 1201 3506 1201 1020 3507 1020 1156 3508 1156 1202 3509 1202 1094 3510 1094 1203 3511 1203 1179 3512 1179 1156 3513 1156 1203 3514 1203 1094 3515 1094 1236 3516 1236 1204 3517 1204 1205 3518 1205 1209 3519 1209 1206 3520 1206 1207 3521 1207 1209 3522 1209 1208 3523 1208 1206 3524 1206 1211 3525 1211 1208 3526 1208 1209 3527 1209 1211 3528 1211 1210 3529 1210 1208 3530 1208 1213 3531 1213 1210 3532 1210 1211 3533 1211 1213 3534 1213 1212 3535 1212 1210 3536 1210 1215 3537 1215 1212 3538 1212 1213 3539 1213 1215 3540 1215 1214 3541 1214 1212 3542 1212 1217 3543 1217 1214 3544 1214 1215 3545 1215 1217 3546 1217 1216 3547 1216 1214 3548 1214 1219 3549 1219 1216 3550 1216 1217 3551 1217 1219 3552 1219 1218 3553 1218 1216 3554 1216 1221 3555 1221 1218 3556 1218 1219 3557 1219 1221 3558 1221 1220 3559 1220 1218 3560 1218 1223 3561 1223 1220 3562 1220 1221 3563 1221 1223 3564 1223 1222 3565 1222 1220 3566 1220 1225 3567 1225 1222 3568 1222 1223 3569 1223 1225 3570 1225 1224 3571 1224 1222 3572 1222 1227 3573 1227 1224 3574 1224 1225 3575 1225 1227 3576 1227 1226 3577 1226 1224 3578 1224 1229 3579 1229 1226 3580 1226 1227 3581 1227 1229 3582 1229 1228 3583 1228 1226 3584 1226 1231 3585 1231 1228 3586 1228 1229 3587 1229 1231 3588 1231 1230 3589 1230 1228 3590 1228 1233 3591 1233 1230 3592 1230 1231 3593 1231 1233 3594 1233 1232 3595 1232 1230 3596 1230 1235 3597 1235 1232 3598 1232 1233 3599 1233 1235 3600 1235 1234 3601 1234 1232 3602 1232 1237 3603 1237 1234 3604 1234 1235 3605 1235 1237 3606 1237 1236 3607 1236 1234 3608 1234 1204 3609 1204 1236 3610 1236 1237 3611 1237 1301 3612 1301 1238 3613 1238 1240 3614 1240 1240 3615 1240 1239 3616 1239 1301 3617 1301 1242 3618 1242 1239 3619 1239 1240 3620 1240 1242 3621 1242 1241 3622 1241 1239 3623 1239 1244 3624 1244 1241 3625 1241 1242 3626 1242 1244 3627 1244 1243 3628 1243 1241 3629 1241 1246 3630 1246 1243 3631 1243 1244 3632 1244 1246 3633 1246 1245 3634 1245 1243 3635 1243 1248 3636 1248 1245 3637 1245 1246 3638 1246 1248 3639 1248 1247 3640 1247 1245 3641 1245 1250 3642 1250 1247 3643 1247 1248 3644 1248 1250 3645 1250 1249 3646 1249 1247 3647 1247 1252 3648 1252 1249 3649 1249 1250 3650 1250 1252 3651 1252 1251 3652 1251 1249 3653 1249 1254 3654 1254 1251 3655 1251 1252 3656 1252 1254 3657 1254 1253 3658 1253 1251 3659 1251 1256 3660 1256 1253 3661 1253 1254 3662 1254 1256 3663 1256 1255 3664 1255 1253 3665 1253 1258 3666 1258 1255 3667 1255 1256 3668 1256 1258 3669 1258 1257 3670 1257 1255 3671 1255 1260 3672 1260 1257 3673 1257 1258 3674 1258 1260 3675 1260 1259 3676 1259 1257 3677 1257 1262 3678 1262 1259 3679 1259 1260 3680 1260 1262 3681 1262 1261 3682 1261 1259 3683 1259 1264 3684 1264 1261 3685 1261 1262 3686 1262 1264 3687 1264 1263 3688 1263 1261 3689 1261 1266 3690 1266 1263 3691 1263 1264 3692 1264 1266 3693 1266 1265 3694 1265 1263 3695 1263 1268 3696 1268 1265 3697 1265 1266 3698 1266 1268 3699 1268 1267 3700 1267 1265 3701 1265 1270 3702 1270 1267 3703 1267 1268 3704 1268 1270 3705 1270 1269 3706 1269 1267 3707 1267 1272 3708 1272 1269 3709 1269 1270 3710 1270 1272 3711 1272 1271 3712 1271 1269 3713 1269 1274 3714 1274 1271 3715 1271 1272 3716 1272 1274 3717 1274 1273 3718 1273 1271 3719 1271 1276 3720 1276 1273 3721 1273 1274 3722 1274 1276 3723 1276 1275 3724 1275 1273 3725 1273 1278 3726 1278 1275 3727 1275 1276 3728 1276 1278 3729 1278 1277 3730 1277 1275 3731 1275 1280 3732 1280 1277 3733 1277 1278 3734 1278 1280 3735 1280 1279 3736 1279 1277 3737 1277 1282 3738 1282 1279 3739 1279 1280 3740 1280 1282 3741 1282 1281 3742 1281 1279 3743 1279 1284 3744 1284 1281 3745 1281 1282 3746 1282 1284 3747 1284 1283 3748 1283 1281 3749 1281 1286 3750 1286 1283 3751 1283 1284 3752 1284 1286 3753 1286 1285 3754 1285 1283 3755 1283 1288 3756 1288 1285 3757 1285 1286 3758 1286 1288 3759 1288 1287 3760 1287 1285 3761 1285 1290 3762 1290 1287 3763 1287 1288 3764 1288 1290 3765 1290 1289 3766 1289 1287 3767 1287 1292 3768 1292 1289 3769 1289 1290 3770 1290 1292 3771 1292 1291 3772 1291 1289 3773 1289 1294 3774 1294 1291 3775 1291 1292 3776 1292 1294 3777 1294 1293 3778 1293 1291 3779 1291 1296 3780 1296 1293 3781 1293 1294 3782 1294 1296 3783 1296 1295 3784 1295 1293 3785 1293 1298 3786 1298 1295 3787 1295 1296 3788 1296 1298 3789 1298 1297 3790 1297 1295 3791 1295 1300 3792 1300 1297 3793 1297 1298 3794 1298 1300 3795 1300 1299 3796 1299 1297 3797 1297 1238 3798 1238 1299 3799 1299 1300 3800 1300 1238 3801 1238 1301 3802 1301 1299 3803 1299 1335 3804 1335 1302 3805 1302 1303 3806 1303 1305 3807 1305 1303 3808 1303 1304 3809 1304 1335 3810 1335 1303 3811 1303 1305 3812 1305 1309 3813 1309 1306 3814 1306 1307 3815 1307 1309 3816 1309 1308 3817 1308 1306 3818 1306 1312 3819 1312 1308 3820 1308 1309 3821 1309 1312 3822 1312 1310 3823 1310 1308 3824 1308 1312 3825 1312 1311 3826 1311 1310 3827 1310 1314 3828 1314 1311 3829 1311 1312 3830 1312 1314 3831 1314 1313 3832 1313 1311 3833 1311 1316 3834 1316 1313 3835 1313 1314 3836 1314 1316 3837 1316 1315 3838 1315 1313 3839 1313 1317 3840 1317 1315 3841 1315 1316 3842 1316 1319 3843 1319 1315 3844 1315 1317 3845 1317 1319 3846 1319 1318 3847 1318 1315 3848 1315 1321 3849 1321 1318 3850 1318 1319 3851 1319 1321 3852 1321 1320 3853 1320 1318 3854 1318 1323 3855 1323 1320 3856 1320 1321 3857 1321 1323 3858 1323 1322 3859 1322 1320 3860 1320 1325 3861 1325 1322 3862 1322 1323 3863 1323 1325 3864 1325 1324 3865 1324 1322 3866 1322 1327 3867 1327 1324 3868 1324 1325 3869 1325 1327 3870 1327 1326 3871 1326 1324 3872 1324 1330 3873 1330 1326 3874 1326 1327 3875 1327 1330 3876 1330 1328 3877 1328 1326 3878 1326 1330 3879 1330 1329 3880 1329 1328 3881 1328 1331 3882 1331 1329 3883 1329 1330 3884 1330 1333 3885 1333 1329 3886 1329 1331 3887 1331 1333 3888 1333 1332 3889 1332 1329 3890 1329 1302 3891 1302 1332 3892 1332 1333 3893 1333 1302 3894 1302 1334 3895 1334 1332 3896 1332 1302 3897 1302 1335 3898 1335 1334 3899 1334 1353 3900 1353 1337 3901 1337 1336 3902 1336 1339 3903 1339 1337 3904 1337 1338 3905 1338 1340 3906 1340 1337 3907 1337 1339 3908 1339 1341 3909 1341 1337 3910 1337 1340 3911 1340 1336 3912 1336 1337 3913 1337 1341 3914 1341 1345 3915 1345 1342 3916 1342 1343 3917 1343 1345 3918 1345 1344 3919 1344 1342 3920 1342 1346 3921 1346 1344 3922 1344 1345 3923 1345 1348 3924 1348 1344 3925 1344 1346 3926 1346 1348 3927 1348 1347 3928 1347 1344 3929 1344 1349 3930 1349 1347 3931 1347 1348 3932 1348 1351 3933 1351 1347 3934 1347 1349 3935 1349 1351 3936 1351 1350 3937 1350 1347 3938 1347 1352 3939 1352 1350 3940 1350 1351 3941 1351 1354 3942 1354 1350 3943 1350 1352 3944 1352 1354 3945 1354 1353 3946 1353 1350 3947 1350 1355 3948 1355 1353 3949 1353 1354 3950 1354 1337 3951 1337 1353 3952 1353 1355 3953 1355 1373 3954 1373 1356 3955 1356 1405 3956 1405 1386 3957 1386 1357 3958 1357 1358 3959 1358 1386 3960 1386 1359 3961 1359 1357 3962 1357 1386 3963 1386 1360 3964 1360 1359 3965 1359 1386 3966 1386 1361 3967 1361 1360 3968 1360 1386 3969 1386 1362 3970 1362 1361 3971 1361 1376 3972 1376 1384 3973 1384 1363 3974 1363 1376 3975 1376 1364 3976 1364 1384 3977 1384 1376 3978 1376 1365 3979 1365 1364 3980 1364 1376 3981 1376 1366 3982 1366 1365 3983 1365 1376 3984 1376 1367 3985 1367 1366 3986 1366 1376 3987 1376 1368 3988 1368 1367 3989 1367 1376 3990 1376 1369 3991 1369 1368 3992 1368 1386 3993 1386 1370 3994 1370 1362 3995 1362 1376 3996 1376 1371 3997 1371 1369 3998 1369 1386 3999 1386 1372 4000 1372 1370 4001 1370 1363 4002 1363 1373 4003 1373 1374 4004 1374 1376 4005 1376 1375 4006 1375 1371 4007 1371 1386 4008 1386 1376 4009 1376 1372 4010 1372 1386 4011 1386 1375 4012 1375 1376 4013 1376 1386 4014 1386 1377 4015 1377 1375 4016 1375 1386 4017 1386 1378 4018 1378 1377 4019 1377 1386 4020 1386 1379 4021 1379 1378 4022 1378 1386 4023 1386 1380 4024 1380 1379 4025 1379 1386 4026 1386 1381 4027 1381 1380 4028 1380 1386 4029 1386 1382 4030 1382 1381 4031 1381 1386 4032 1386 1383 4033 1383 1382 4034 1382 1402 4035 1402 1363 4036 1363 1384 4037 1384 1386 4038 1386 1385 4039 1385 1383 4040 1383 1387 4041 1387 1385 4042 1385 1386 4043 1386 1388 4044 1388 1385 4045 1385 1387 4046 1387 1389 4047 1389 1385 4048 1385 1388 4049 1388 1390 4050 1390 1385 4051 1385 1389 4052 1389 1391 4053 1391 1385 4054 1385 1390 4055 1390 1392 4056 1392 1385 4057 1385 1391 4058 1391 1393 4059 1393 1385 4060 1385 1392 4061 1392 1394 4062 1394 1385 4063 1385 1393 4064 1393 1373 4065 1373 1385 4066 1385 1394 4067 1394 1373 4068 1373 1395 4069 1395 1385 4070 1385 1373 4071 1373 1396 4072 1396 1395 4073 1395 1373 4074 1373 1397 4075 1397 1396 4076 1396 1373 4077 1373 1398 4078 1398 1397 4079 1397 1373 4080 1373 1399 4081 1399 1398 4082 1398 1373 4083 1373 1400 4084 1400 1399 4085 1399 1373 4086 1373 1401 4087 1401 1400 4088 1400 1404 4089 1404 1363 4090 1363 1402 4091 1402 1373 4092 1373 1403 4093 1403 1401 4094 1401 1406 4095 1406 1363 4096 1363 1404 4097 1404 1373 4098 1373 1405 4099 1405 1403 4100 1403 1407 4101 1407 1363 4102 1363 1406 4103 1406 1407 4104 1407 1373 4105 1373 1363 4106 1363 1408 4107 1408 1373 4108 1373 1407 4109 1407 1356 4110 1356 1373 4111 1373 1408 4112 1408 1428 4113 1428 1409 4114 1409 1414 4115 1414 1428 4116 1428 1410 4117 1410 1411 4118 1411 1428 4119 1428 1412 4120 1412 1410 4121 1410 1428 4122 1428 1413 4123 1413 1412 4124 1412 1428 4125 1428 1414 4126 1414 1413 4127 1413 1417 4128 1417 1415 4129 1415 1416 4130 1416 1419 4131 1419 1415 4132 1415 1417 4133 1417 1419 4134 1419 1418 4135 1418 1415 4136 1415 1423 4137 1423 1418 4138 1418 1419 4139 1419 1423 4140 1423 1420 4141 1420 1418 4142 1418 1423 4143 1423 1421 4144 1421 1420 4145 1420 1423 4146 1423 1422 4147 1422 1421 4148 1421 1426 4149 1426 1422 4150 1422 1423 4151 1423 1426 4152 1426 1424 4153 1424 1422 4154 1422 1426 4155 1426 1425 4156 1425 1424 4157 1424 1409 4158 1409 1425 4159 1425 1426 4160 1426 1409 4161 1409 1427 4162 1427 1425 4163 1425 1409 4164 1409 1428 4165 1428 1427 4166 1427 1481 4167 1481 1467 4168 1467 1429 4169 1429 1432 4170 1432 1430 4171 1430 1431 4172 1431 1433 4173 1433 1430 4174 1430 1432 4175 1432 1434 4176 1434 1430 4177 1430 1433 4178 1433 1435 4179 1435 1430 4180 1430 1434 4181 1434 1443 4182 1443 1430 4183 1430 1435 4184 1435 1437 4185 1437 1436 4186 1436 1446 4187 1446 1438 4188 1438 1436 4189 1436 1437 4190 1437 1439 4191 1439 1436 4192 1436 1438 4193 1438 1440 4194 1440 1436 4195 1436 1439 4196 1439 1441 4197 1441 1436 4198 1436 1440 4199 1440 1442 4200 1442 1436 4201 1436 1441 4202 1441 1444 4203 1444 1436 4204 1436 1442 4205 1442 1445 4206 1445 1430 4207 1430 1443 4208 1443 1448 4209 1448 1436 4210 1436 1444 4211 1444 1449 4212 1449 1430 4213 1430 1445 4214 1445 1467 4215 1467 1446 4216 1446 1447 4217 1447 1450 4218 1450 1436 4219 1436 1448 4220 1448 1436 4221 1436 1430 4222 1430 1449 4223 1449 1450 4224 1450 1430 4225 1430 1436 4226 1436 1451 4227 1451 1430 4228 1430 1450 4229 1450 1452 4230 1452 1430 4231 1430 1451 4232 1451 1453 4233 1453 1430 4234 1430 1452 4235 1452 1454 4236 1454 1430 4237 1430 1453 4238 1453 1455 4239 1455 1430 4240 1430 1454 4241 1454 1456 4242 1456 1430 4243 1430 1455 4244 1455 1458 4245 1458 1430 4246 1430 1456 4247 1456 1446 4248 1446 1457 4249 1457 1437 4250 1437 1468 4251 1468 1430 4252 1430 1458 4253 1458 1468 4254 1468 1459 4255 1459 1430 4256 1430 1468 4257 1468 1460 4258 1460 1459 4259 1459 1468 4260 1468 1461 4261 1461 1460 4262 1460 1468 4263 1468 1462 4264 1462 1461 4265 1461 1468 4266 1468 1463 4267 1463 1462 4268 1462 1468 4269 1468 1464 4270 1464 1463 4271 1463 1468 4272 1468 1465 4273 1465 1464 4274 1464 1468 4275 1468 1466 4276 1466 1465 4277 1465 1468 4278 1468 1467 4279 1467 1466 4280 1466 1469 4281 1469 1467 4282 1467 1468 4283 1468 1470 4284 1470 1467 4285 1467 1469 4286 1469 1471 4287 1471 1467 4288 1467 1470 4289 1470 1472 4290 1472 1467 4291 1467 1471 4292 1471 1473 4293 1473 1467 4294 1467 1472 4295 1472 1474 4296 1474 1467 4297 1467 1473 4298 1473 1476 4299 1476 1467 4300 1467 1474 4301 1474 1446 4302 1446 1475 4303 1475 1457 4304 1457 1478 4305 1478 1467 4306 1467 1476 4307 1476 1446 4308 1446 1477 4309 1477 1475 4310 1475 1429 4311 1429 1467 4312 1467 1478 4313 1478 1446 4314 1446 1479 4315 1479 1477 4316 1477 1467 4317 1467 1479 4318 1479 1446 4319 1446 1467 4320 1467 1480 4321 1480 1479 4322 1479 1467 4323 1467 1481 4324 1481 1480 4325 1480 1513 4326 1513 1487 4327 1487 1482 4328 1482 1485 4329 1485 1483 4330 1483 1484 4331 1484 1486 4332 1486 1483 4333 1483 1485 4334 1485 1482 4335 1482 1483 4336 1483 1486 4337 1486 1482 4338 1482 1487 4339 1487 1483 4340 1483 1492 4341 1492 1488 4342 1488 1489 4343 1489 1492 4344 1492 1490 4345 1490 1488 4346 1488 1492 4347 1492 1491 4348 1491 1490 4349 1490 1494 4350 1494 1491 4351 1491 1492 4352 1492 1494 4353 1494 1493 4354 1493 1491 4355 1491 1496 4356 1496 1493 4357 1493 1494 4358 1494 1496 4359 1496 1495 4360 1495 1493 4361 1493 1497 4362 1497 1495 4363 1495 1496 4364 1496 1499 4365 1499 1495 4366 1495 1497 4367 1497 1499 4368 1499 1498 4369 1498 1495 4370 1495 1501 4371 1501 1498 4372 1498 1499 4373 1499 1501 4374 1501 1500 4375 1500 1498 4376 1498 1503 4377 1503 1500 4378 1500 1501 4379 1501 1503 4380 1503 1502 4381 1502 1500 4382 1500 1505 4383 1505 1502 4384 1502 1503 4385 1503 1505 4386 1505 1504 4387 1504 1502 4388 1502 1507 4389 1507 1504 4390 1504 1505 4391 1505 1507 4392 1507 1506 4393 1506 1504 4394 1504 1509 4395 1509 1506 4396 1506 1507 4397 1507 1509 4398 1509 1508 4399 1508 1506 4400 1506 1512 4401 1512 1508 4402 1508 1509 4403 1509 1512 4404 1512 1510 4405 1510 1508 4406 1508 1512 4407 1512 1511 4408 1511 1510 4409 1510 1514 4410 1514 1511 4411 1511 1512 4412 1512 1514 4413 1514 1513 4414 1513 1511 4415 1511 1515 4416 1515 1513 4417 1513 1514 4418 1514 1487 4419 1487 1513 4420 1513 1515 4421 1515 1548 4422 1548 1529 4423 1529 1516 4424 1516 1519 4425 1519 1517 4426 1517 1518 4427 1518 1520 4428 1520 1517 4429 1517 1519 4430 1519 1522 4431 1522 1517 4432 1517 1520 4433 1520 1522 4434 1522 1521 4435 1521 1517 4436 1517 1524 4437 1524 1521 4438 1521 1522 4439 1522 1524 4440 1524 1523 4441 1523 1521 4442 1521 1527 4443 1527 1523 4444 1523 1524 4445 1524 1527 4446 1527 1525 4447 1525 1523 4448 1523 1527 4449 1527 1526 4450 1526 1525 4451 1525 1528 4452 1528 1526 4453 1526 1527 4454 1527 1516 4455 1516 1526 4456 1526 1528 4457 1528 1516 4458 1516 1529 4459 1529 1526 4460 1526 1534 4461 1534 1530 4462 1530 1531 4463 1531 1534 4464 1534 1532 4465 1532 1530 4466 1530 1534 4467 1534 1533 4468 1533 1532 4469 1532 1535 4470 1535 1533 4471 1533 1534 4472 1534 1537 4473 1537 1533 4474 1533 1535 4475 1535 1537 4476 1537 1536 4477 1536 1533 4478 1533 1539 4479 1539 1536 4480 1536 1537 4481 1537 1539 4482 1539 1538 4483 1538 1536 4484 1536 1542 4485 1542 1538 4486 1538 1539 4487 1539 1542 4488 1542 1540 4489 1540 1538 4490 1538 1542 4491 1542 1541 4492 1541 1540 4493 1540 1544 4494 1544 1541 4495 1541 1542 4496 1542 1544 4497 1544 1543 4498 1543 1541 4499 1541 1545 4500 1545 1543 4501 1543 1544 4502 1544 1547 4503 1547 1543 4504 1543 1545 4505 1545 1547 4506 1547 1546 4507 1546 1543 4508 1543 1549 4509 1549 1546 4510 1546 1547 4511 1547 1549 4512 1549 1548 4513 1548 1546 4514 1546 1529 4515 1529 1548 4516 1548 1549 4517 1549 1582 4518 1582 1571 4519 1571 1550 4520 1550 1553 4521 1553 1551 4522 1551 1552 4523 1552 1554 4524 1554 1551 4525 1551 1553 4526 1553 1556 4527 1556 1551 4528 1551 1554 4529 1554 1556 4530 1556 1555 4531 1555 1551 4532 1551 1559 4533 1559 1555 4534 1555 1556 4535 1556 1559 4536 1559 1557 4537 1557 1555 4538 1555 1559 4539 1559 1558 4540 1558 1557 4541 1557 1561 4542 1561 1558 4543 1558 1559 4544 1559 1561 4545 1561 1560 4546 1560 1558 4547 1558 1562 4548 1562 1560 4549 1560 1561 4550 1561 1565 4551 1565 1560 4552 1560 1562 4553 1562 1565 4554 1565 1563 4555 1563 1560 4556 1560 1565 4557 1565 1564 4558 1564 1563 4559 1563 1567 4560 1567 1564 4561 1564 1565 4562 1565 1567 4563 1567 1566 4564 1566 1564 4565 1564 1569 4566 1569 1566 4567 1566 1567 4568 1567 1569 4569 1569 1568 4570 1568 1566 4571 1566 1570 4572 1570 1568 4573 1568 1569 4574 1569 1550 4575 1550 1568 4576 1568 1570 4577 1570 1550 4578 1550 1571 4579 1571 1568 4580 1568 1576 4581 1576 1572 4582 1572 1573 4583 1573 1576 4584 1576 1574 4585 1574 1572 4586 1572 1576 4587 1576 1575 4588 1575 1574 4589 1574 1578 4590 1578 1575 4591 1575 1576 4592 1576 1578 4593 1578 1577 4594 1577 1575 4595 1575 1579 4596 1579 1577 4597 1577 1578 4598 1578 1581 4599 1581 1577 4600 1577 1579 4601 1579 1581 4602 1581 1580 4603 1580 1577 4604 1577 1583 4605 1583 1580 4606 1580 1581 4607 1581 1583 4608 1583 1582 4609 1582 1580 4610 1580 1571 4611 1571 1582 4612 1582 1583 4613 1583 1647 4614 1647 1584 4615 1584 1586 4616 1586 1586 4617 1586 1585 4618 1585 1647 4619 1647 1588 4620 1588 1585 4621 1585 1586 4622 1586 1588 4623 1588 1587 4624 1587 1585 4625 1585 1590 4626 1590 1587 4627 1587 1588 4628 1588 1590 4629 1590 1589 4630 1589 1587 4631 1587 1592 4632 1592 1589 4633 1589 1590 4634 1590 1592 4635 1592 1591 4636 1591 1589 4637 1589 1594 4638 1594 1591 4639 1591 1592 4640 1592 1594 4641 1594 1593 4642 1593 1591 4643 1591 1596 4644 1596 1593 4645 1593 1594 4646 1594 1596 4647 1596 1595 4648 1595 1593 4649 1593 1598 4650 1598 1595 4651 1595 1596 4652 1596 1598 4653 1598 1597 4654 1597 1595 4655 1595 1600 4656 1600 1597 4657 1597 1598 4658 1598 1600 4659 1600 1599 4660 1599 1597 4661 1597 1602 4662 1602 1599 4663 1599 1600 4664 1600 1602 4665 1602 1601 4666 1601 1599 4667 1599 1604 4668 1604 1601 4669 1601 1602 4670 1602 1604 4671 1604 1603 4672 1603 1601 4673 1601 1606 4674 1606 1603 4675 1603 1604 4676 1604 1606 4677 1606 1605 4678 1605 1603 4679 1603 1608 4680 1608 1605 4681 1605 1606 4682 1606 1608 4683 1608 1607 4684 1607 1605 4685 1605 1610 4686 1610 1607 4687 1607 1608 4688 1608 1610 4689 1610 1609 4690 1609 1607 4691 1607 1612 4692 1612 1609 4693 1609 1610 4694 1610 1612 4695 1612 1611 4696 1611 1609 4697 1609 1614 4698 1614 1611 4699 1611 1612 4700 1612 1614 4701 1614 1613 4702 1613 1611 4703 1611 1616 4704 1616 1613 4705 1613 1614 4706 1614 1616 4707 1616 1615 4708 1615 1613 4709 1613 1618 4710 1618 1615 4711 1615 1616 4712 1616 1618 4713 1618 1617 4714 1617 1615 4715 1615 1620 4716 1620 1617 4717 1617 1618 4718 1618 1620 4719 1620 1619 4720 1619 1617 4721 1617 1622 4722 1622 1619 4723 1619 1620 4724 1620 1622 4725 1622 1621 4726 1621 1619 4727 1619 1624 4728 1624 1621 4729 1621 1622 4730 1622 1624 4731 1624 1623 4732 1623 1621 4733 1621 1626 4734 1626 1623 4735 1623 1624 4736 1624 1626 4737 1626 1625 4738 1625 1623 4739 1623 1628 4740 1628 1625 4741 1625 1626 4742 1626 1628 4743 1628 1627 4744 1627 1625 4745 1625 1630 4746 1630 1627 4747 1627 1628 4748 1628 1630 4749 1630 1629 4750 1629 1627 4751 1627 1632 4752 1632 1629 4753 1629 1630 4754 1630 1632 4755 1632 1631 4756 1631 1629 4757 1629 1634 4758 1634 1631 4759 1631 1632 4760 1632 1634 4761 1634 1633 4762 1633 1631 4763 1631 1636 4764 1636 1633 4765 1633 1634 4766 1634 1636 4767 1636 1635 4768 1635 1633 4769 1633 1638 4770 1638 1635 4771 1635 1636 4772 1636 1638 4773 1638 1637 4774 1637 1635 4775 1635 1640 4776 1640 1637 4777 1637 1638 4778 1638 1640 4779 1640 1639 4780 1639 1637 4781 1637 1642 4782 1642 1639 4783 1639 1640 4784 1640 1642 4785 1642 1641 4786 1641 1639 4787 1639 1644 4788 1644 1641 4789 1641 1642 4790 1642 1644 4791 1644 1643 4792 1643 1641 4793 1641 1646 4794 1646 1643 4795 1643 1644 4796 1644 1646 4797 1646 1645 4798 1645 1643 4799 1643 1584 4800 1584 1645 4801 1645 1646 4802 1646 1584 4803 1584 1647 4804 1647 1645 4805 1645 1680 4806 1680 1648 4807 1648 1649 4808 1649 1654 4809 1654 1650 4810 1650 1651 4811 1651 1654 4812 1654 1652 4813 1652 1650 4814 1650 1654 4815 1654 1653 4816 1653 1652 4817 1652 1655 4818 1655 1653 4819 1653 1654 4820 1654 1658 4821 1658 1653 4822 1653 1655 4823 1655 1658 4824 1658 1656 4825 1656 1653 4826 1653 1658 4827 1658 1657 4828 1657 1656 4829 1656 1660 4830 1660 1657 4831 1657 1658 4832 1658 1660 4833 1660 1659 4834 1659 1657 4835 1657 1661 4836 1661 1659 4837 1659 1660 4838 1660 1663 4839 1663 1659 4840 1659 1661 4841 1661 1663 4842 1663 1662 4843 1662 1659 4844 1659 1666 4845 1666 1662 4846 1662 1663 4847 1663 1666 4848 1666 1664 4849 1664 1662 4850 1662 1666 4851 1666 1665 4852 1665 1664 4853 1664 1667 4854 1667 1665 4855 1665 1666 4856 1666 1669 4857 1669 1665 4858 1665 1667 4859 1667 1669 4860 1669 1668 4861 1668 1665 4862 1665 1671 4863 1671 1668 4864 1668 1669 4865 1669 1671 4866 1671 1670 4867 1670 1668 4868 1668 1673 4869 1673 1670 4870 1670 1671 4871 1671 1673 4872 1673 1672 4873 1672 1670 4874 1670 1675 4875 1675 1672 4876 1672 1673 4877 1673 1675 4878 1675 1674 4879 1674 1672 4880 1672 1677 4881 1677 1674 4882 1674 1675 4883 1675 1677 4884 1677 1676 4885 1676 1674 4886 1674 1679 4887 1679 1676 4888 1676 1677 4889 1677 1679 4890 1679 1678 4891 1678 1676 4892 1676 1681 4893 1681 1678 4894 1678 1679 4895 1679 1681 4896 1681 1680 4897 1680 1678 4898 1678 1648 4899 1648 1680 4900 1680 1681 4901 1681 1745 4902 1745 1682 4903 1682 1684 4904 1684 1684 4905 1684 1683 4906 1683 1745 4907 1745 1686 4908 1686 1683 4909 1683 1684 4910 1684 1686 4911 1686 1685 4912 1685 1683 4913 1683 1688 4914 1688 1685 4915 1685 1686 4916 1686 1688 4917 1688 1687 4918 1687 1685 4919 1685 1690 4920 1690 1687 4921 1687 1688 4922 1688 1690 4923 1690 1689 4924 1689 1687 4925 1687 1692 4926 1692 1689 4927 1689 1690 4928 1690 1692 4929 1692 1691 4930 1691 1689 4931 1689 1694 4932 1694 1691 4933 1691 1692 4934 1692 1694 4935 1694 1693 4936 1693 1691 4937 1691 1696 4938 1696 1693 4939 1693 1694 4940 1694 1696 4941 1696 1695 4942 1695 1693 4943 1693 1698 4944 1698 1695 4945 1695 1696 4946 1696 1698 4947 1698 1697 4948 1697 1695 4949 1695 1700 4950 1700 1697 4951 1697 1698 4952 1698 1700 4953 1700 1699 4954 1699 1697 4955 1697 1702 4956 1702 1699 4957 1699 1700 4958 1700 1702 4959 1702 1701 4960 1701 1699 4961 1699 1704 4962 1704 1701 4963 1701 1702 4964 1702 1704 4965 1704 1703 4966 1703 1701 4967 1701 1706 4968 1706 1703 4969 1703 1704 4970 1704 1706 4971 1706 1705 4972 1705 1703 4973 1703 1708 4974 1708 1705 4975 1705 1706 4976 1706 1708 4977 1708 1707 4978 1707 1705 4979 1705 1710 4980 1710 1707 4981 1707 1708 4982 1708 1710 4983 1710 1709 4984 1709 1707 4985 1707 1712 4986 1712 1709 4987 1709 1710 4988 1710 1712 4989 1712 1711 4990 1711 1709 4991 1709 1714 4992 1714 1711 4993 1711 1712 4994 1712 1714 4995 1714 1713 4996 1713 1711 4997 1711 1716 4998 1716 1713 4999 1713 1714 5000 1714 1716 5001 1716 1715 5002 1715 1713 5003 1713 1718 5004 1718 1715 5005 1715 1716 5006 1716 1718 5007 1718 1717 5008 1717 1715 5009 1715 1720 5010 1720 1717 5011 1717 1718 5012 1718 1720 5013 1720 1719 5014 1719 1717 5015 1717 1722 5016 1722 1719 5017 1719 1720 5018 1720 1722 5019 1722 1721 5020 1721 1719 5021 1719 1724 5022 1724 1721 5023 1721 1722 5024 1722 1724 5025 1724 1723 5026 1723 1721 5027 1721 1726 5028 1726 1723 5029 1723 1724 5030 1724 1726 5031 1726 1725 5032 1725 1723 5033 1723 1728 5034 1728 1725 5035 1725 1726 5036 1726 1728 5037 1728 1727 5038 1727 1725 5039 1725 1730 5040 1730 1727 5041 1727 1728 5042 1728 1730 5043 1730 1729 5044 1729 1727 5045 1727 1732 5046 1732 1729 5047 1729 1730 5048 1730 1732 5049 1732 1731 5050 1731 1729 5051 1729 1734 5052 1734 1731 5053 1731 1732 5054 1732 1734 5055 1734 1733 5056 1733 1731 5057 1731 1736 5058 1736 1733 5059 1733 1734 5060 1734 1736 5061 1736 1735 5062 1735 1733 5063 1733 1738 5064 1738 1735 5065 1735 1736 5066 1736 1738 5067 1738 1737 5068 1737 1735 5069 1735 1740 5070 1740 1737 5071 1737 1738 5072 1738 1740 5073 1740 1739 5074 1739 1737 5075 1737 1742 5076 1742 1739 5077 1739 1740 5078 1740 1742 5079 1742 1741 5080 1741 1739 5081 1739 1744 5082 1744 1741 5083 1741 1742 5084 1742 1744 5085 1744 1743 5086 1743 1741 5087 1741 1682 5088 1682 1743 5089 1743 1744 5090 1744 1682 5091 1682 1745 5092 1745 1743 5093 1743 1778 5094 1778 1754 5095 1754 1746 5096 1746 1749 5097 1749 1747 5098 1747 1748 5099 1748 1751 5100 1751 1747 5101 1747 1749 5102 1749 1751 5103 1751 1750 5104 1750 1747 5105 1747 1752 5106 1752 1750 5107 1750 1751 5108 1751 1755 5109 1755 1750 5110 1750 1752 5111 1752 1755 5112 1755 1753 5113 1753 1750 5114 1750 1755 5115 1755 1754 5116 1754 1753 5117 1753 1746 5118 1746 1754 5119 1754 1755 5120 1755 1759 5121 1759 1756 5122 1756 1757 5123 1757 1759 5124 1759 1758 5125 1758 1756 5126 1756 1762 5127 1762 1758 5128 1758 1759 5129 1759 1762 5130 1762 1760 5131 1760 1758 5132 1758 1762 5133 1762 1761 5134 1761 1760 5135 1760 1763 5136 1763 1761 5137 1761 1762 5138 1762 1765 5139 1765 1761 5140 1761 1763 5141 1763 1765 5142 1765 1764 5143 1764 1761 5144 1761 1768 5145 1768 1764 5146 1764 1765 5147 1765 1768 5148 1768 1766 5149 1766 1764 5150 1764 1768 5151 1768 1767 5152 1767 1766 5153 1766 1770 5154 1770 1767 5155 1767 1768 5156 1768 1770 5157 1770 1769 5158 1769 1767 5159 1767 1771 5160 1771 1769 5161 1769 1770 5162 1770 1773 5163 1773 1769 5164 1769 1771 5165 1771 1773 5166 1773 1772 5167 1772 1769 5168 1769 1776 5169 1776 1772 5170 1772 1773 5171 1773 1776 5172 1776 1774 5173 1774 1772 5174 1772 1776 5175 1776 1775 5176 1775 1774 5177 1774 1777 5178 1777 1775 5179 1775 1776 5180 1776 1779 5181 1779 1775 5182 1775 1777 5183 1777 1779 5184 1779 1778 5185 1778 1775 5186 1775 1754 5187 1754 1778 5188 1778 1779 5189 1779 1843 5190 1843 1780 5191 1780 1782 5192 1782 1782 5193 1782 1781 5194 1781 1843 5195 1843 1784 5196 1784 1781 5197 1781 1782 5198 1782 1784 5199 1784 1783 5200 1783 1781 5201 1781 1786 5202 1786 1783 5203 1783 1784 5204 1784 1786 5205 1786 1785 5206 1785 1783 5207 1783 1788 5208 1788 1785 5209 1785 1786 5210 1786 1788 5211 1788 1787 5212 1787 1785 5213 1785 1790 5214 1790 1787 5215 1787 1788 5216 1788 1790 5217 1790 1789 5218 1789 1787 5219 1787 1792 5220 1792 1789 5221 1789 1790 5222 1790 1792 5223 1792 1791 5224 1791 1789 5225 1789 1794 5226 1794 1791 5227 1791 1792 5228 1792 1794 5229 1794 1793 5230 1793 1791 5231 1791 1796 5232 1796 1793 5233 1793 1794 5234 1794 1796 5235 1796 1795 5236 1795 1793 5237 1793 1798 5238 1798 1795 5239 1795 1796 5240 1796 1798 5241 1798 1797 5242 1797 1795 5243 1795 1800 5244 1800 1797 5245 1797 1798 5246 1798 1800 5247 1800 1799 5248 1799 1797 5249 1797 1802 5250 1802 1799 5251 1799 1800 5252 1800 1802 5253 1802 1801 5254 1801 1799 5255 1799 1804 5256 1804 1801 5257 1801 1802 5258 1802 1804 5259 1804 1803 5260 1803 1801 5261 1801 1806 5262 1806 1803 5263 1803 1804 5264 1804 1806 5265 1806 1805 5266 1805 1803 5267 1803 1808 5268 1808 1805 5269 1805 1806 5270 1806 1808 5271 1808 1807 5272 1807 1805 5273 1805 1810 5274 1810 1807 5275 1807 1808 5276 1808 1810 5277 1810 1809 5278 1809 1807 5279 1807 1812 5280 1812 1809 5281 1809 1810 5282 1810 1812 5283 1812 1811 5284 1811 1809 5285 1809 1814 5286 1814 1811 5287 1811 1812 5288 1812 1814 5289 1814 1813 5290 1813 1811 5291 1811 1816 5292 1816 1813 5293 1813 1814 5294 1814 1816 5295 1816 1815 5296 1815 1813 5297 1813 1818 5298 1818 1815 5299 1815 1816 5300 1816 1818 5301 1818 1817 5302 1817 1815 5303 1815 1820 5304 1820 1817 5305 1817 1818 5306 1818 1820 5307 1820 1819 5308 1819 1817 5309 1817 1822 5310 1822 1819 5311 1819 1820 5312 1820 1822 5313 1822 1821 5314 1821 1819 5315 1819 1824 5316 1824 1821 5317 1821 1822 5318 1822 1824 5319 1824 1823 5320 1823 1821 5321 1821 1826 5322 1826 1823 5323 1823 1824 5324 1824 1826 5325 1826 1825 5326 1825 1823 5327 1823 1828 5328 1828 1825 5329 1825 1826 5330 1826 1828 5331 1828 1827 5332 1827 1825 5333 1825 1830 5334 1830 1827 5335 1827 1828 5336 1828 1830 5337 1830 1829 5338 1829 1827 5339 1827 1832 5340 1832 1829 5341 1829 1830 5342 1830 1832 5343 1832 1831 5344 1831 1829 5345 1829 1834 5346 1834 1831 5347 1831 1832 5348 1832 1834 5349 1834 1833 5350 1833 1831 5351 1831 1836 5352 1836 1833 5353 1833 1834 5354 1834 1836 5355 1836 1835 5356 1835 1833 5357 1833 1838 5358 1838 1835 5359 1835 1836 5360 1836 1838 5361 1838 1837 5362 1837 1835 5363 1835 1840 5364 1840 1837 5365 1837 1838 5366 1838 1840 5367 1840 1839 5368 1839 1837 5369 1837 1842 5370 1842 1839 5371 1839 1840 5372 1840 1842 5373 1842 1841 5374 1841 1839 5375 1839 1780 5376 1780 1841 5377 1841 1842 5378 1842 1780 5379 1780 1843 5380 1843 1841 5381 1841 1876 5382 1876 1844 5383 1844 1845 5384 1845 1848 5385 1848 1846 5386 1846 1847 5387 1847 1850 5388 1850 1846 5389 1846 1848 5390 1848 1850 5391 1850 1849 5392 1849 1846 5393 1846 1852 5394 1852 1849 5395 1849 1850 5396 1850 1852 5397 1852 1851 5398 1851 1849 5399 1849 1854 5400 1854 1851 5401 1851 1852 5402 1852 1854 5403 1854 1853 5404 1853 1851 5405 1851 1856 5406 1856 1853 5407 1853 1854 5408 1854 1856 5409 1856 1855 5410 1855 1853 5411 1853 1858 5412 1858 1855 5413 1855 1856 5414 1856 1858 5415 1858 1857 5416 1857 1855 5417 1855 1859 5418 1859 1857 5419 1857 1858 5420 1858 1862 5421 1862 1857 5422 1857 1859 5423 1859 1862 5424 1862 1860 5425 1860 1857 5426 1857 1862 5427 1862 1861 5428 1861 1860 5429 1860 1864 5430 1864 1861 5431 1861 1862 5432 1862 1864 5433 1864 1863 5434 1863 1861 5435 1861 1865 5436 1865 1863 5437 1863 1864 5438 1864 1868 5439 1868 1863 5440 1863 1865 5441 1865 1868 5442 1868 1866 5443 1866 1863 5444 1863 1868 5445 1868 1867 5446 1867 1866 5447 1866 1870 5448 1870 1867 5449 1867 1868 5450 1868 1870 5451 1870 1869 5452 1869 1867 5453 1867 1872 5454 1872 1869 5455 1869 1870 5456 1870 1872 5457 1872 1871 5458 1871 1869 5459 1869 1873 5460 1873 1871 5461 1871 1872 5462 1872 1875 5463 1875 1871 5464 1871 1873 5465 1873 1875 5466 1875 1874 5467 1874 1871 5468 1871 1877 5469 1877 1874 5470 1874 1875 5471 1875 1877 5472 1877 1876 5473 1876 1874 5474 1874 1844 5475 1844 1876 5476 1876 1877 5477 1877 1941 5478 1941 1878 5479 1878 1880 5480 1880 1880 5481 1880 1879 5482 1879 1941 5483 1941 1882 5484 1882 1879 5485 1879 1880 5486 1880 1882 5487 1882 1881 5488 1881 1879 5489 1879 1884 5490 1884 1881 5491 1881 1882 5492 1882 1884 5493 1884 1883 5494 1883 1881 5495 1881 1886 5496 1886 1883 5497 1883 1884 5498 1884 1886 5499 1886 1885 5500 1885 1883 5501 1883 1888 5502 1888 1885 5503 1885 1886 5504 1886 1888 5505 1888 1887 5506 1887 1885 5507 1885 1890 5508 1890 1887 5509 1887 1888 5510 1888 1890 5511 1890 1889 5512 1889 1887 5513 1887 1892 5514 1892 1889 5515 1889 1890 5516 1890 1892 5517 1892 1891 5518 1891 1889 5519 1889 1894 5520 1894 1891 5521 1891 1892 5522 1892 1894 5523 1894 1893 5524 1893 1891 5525 1891 1896 5526 1896 1893 5527 1893 1894 5528 1894 1896 5529 1896 1895 5530 1895 1893 5531 1893 1898 5532 1898 1895 5533 1895 1896 5534 1896 1898 5535 1898 1897 5536 1897 1895 5537 1895 1900 5538 1900 1897 5539 1897 1898 5540 1898 1900 5541 1900 1899 5542 1899 1897 5543 1897 1902 5544 1902 1899 5545 1899 1900 5546 1900 1902 5547 1902 1901 5548 1901 1899 5549 1899 1904 5550 1904 1901 5551 1901 1902 5552 1902 1904 5553 1904 1903 5554 1903 1901 5555 1901 1906 5556 1906 1903 5557 1903 1904 5558 1904 1906 5559 1906 1905 5560 1905 1903 5561 1903 1908 5562 1908 1905 5563 1905 1906 5564 1906 1908 5565 1908 1907 5566 1907 1905 5567 1905 1910 5568 1910 1907 5569 1907 1908 5570 1908 1910 5571 1910 1909 5572 1909 1907 5573 1907 1912 5574 1912 1909 5575 1909 1910 5576 1910 1912 5577 1912 1911 5578 1911 1909 5579 1909 1914 5580 1914 1911 5581 1911 1912 5582 1912 1914 5583 1914 1913 5584 1913 1911 5585 1911 1916 5586 1916 1913 5587 1913 1914 5588 1914 1916 5589 1916 1915 5590 1915 1913 5591 1913 1918 5592 1918 1915 5593 1915 1916 5594 1916 1918 5595 1918 1917 5596 1917 1915 5597 1915 1920 5598 1920 1917 5599 1917 1918 5600 1918 1920 5601 1920 1919 5602 1919 1917 5603 1917 1922 5604 1922 1919 5605 1919 1920 5606 1920 1922 5607 1922 1921 5608 1921 1919 5609 1919 1924 5610 1924 1921 5611 1921 1922 5612 1922 1924 5613 1924 1923 5614 1923 1921 5615 1921 1926 5616 1926 1923 5617 1923 1924 5618 1924 1926 5619 1926 1925 5620 1925 1923 5621 1923 1928 5622 1928 1925 5623 1925 1926 5624 1926 1928 5625 1928 1927 5626 1927 1925 5627 1925 1930 5628 1930 1927 5629 1927 1928 5630 1928 1930 5631 1930 1929 5632 1929 1927 5633 1927 1932 5634 1932 1929 5635 1929 1930 5636 1930 1932 5637 1932 1931 5638 1931 1929 5639 1929 1934 5640 1934 1931 5641 1931 1932 5642 1932 1934 5643 1934 1933 5644 1933 1931 5645 1931 1936 5646 1936 1933 5647 1933 1934 5648 1934 1936 5649 1936 1935 5650 1935 1933 5651 1933 1938 5652 1938 1935 5653 1935 1936 5654 1936 1938 5655 1938 1937 5656 1937 1935 5657 1935 1940 5658 1940 1937 5659 1937 1938 5660 1938 1940 5661 1940 1939 5662 1939 1937 5663 1937 1878 5664 1878 1939 5665 1939 1940 5666 1940 1878 5667 1878 1941 5668 1941 1939 5669 1939 1974 5670 1974 1942 5671 1942 1943 5672 1943 1946 5673 1946 1944 5674 1944 1945 5675 1945 1948 5676 1948 1944 5677 1944 1946 5678 1946 1948 5679 1948 1947 5680 1947 1944 5681 1944 1949 5682 1949 1947 5683 1947 1948 5684 1948 1951 5685 1951 1947 5686 1947 1949 5687 1949 1951 5688 1951 1950 5689 1950 1947 5690 1947 1953 5691 1953 1950 5692 1950 1951 5693 1951 1953 5694 1953 1952 5695 1952 1950 5696 1950 1955 5697 1955 1952 5698 1952 1953 5699 1953 1955 5700 1955 1954 5701 1954 1952 5702 1952 1957 5703 1957 1954 5704 1954 1955 5705 1955 1957 5706 1957 1956 5707 1956 1954 5708 1954 1959 5709 1959 1956 5710 1956 1957 5711 1957 1959 5712 1959 1958 5713 1958 1956 5714 1956 1961 5715 1961 1958 5716 1958 1959 5717 1959 1961 5718 1961 1960 5719 1960 1958 5720 1958 1963 5721 1963 1960 5722 1960 1961 5723 1961 1963 5724 1963 1962 5725 1962 1960 5726 1960 1965 5727 1965 1962 5728 1962 1963 5729 1963 1965 5730 1965 1964 5731 1964 1962 5732 1962 1967 5733 1967 1964 5734 1964 1965 5735 1965 1967 5736 1967 1966 5737 1966 1964 5738 1964 1969 5739 1969 1966 5740 1966 1967 5741 1967 1969 5742 1969 1968 5743 1968 1966 5744 1966 1971 5745 1971 1968 5746 1968 1969 5747 1969 1971 5748 1971 1970 5749 1970 1968 5750 1968 1973 5751 1973 1970 5752 1970 1971 5753 1971 1973 5754 1973 1972 5755 1972 1970 5756 1970 1975 5757 1975 1972 5758 1972 1973 5759 1973 1975 5760 1975 1974 5761 1974 1972 5762 1972 1942 5763 1942 1974 5764 1974 1975 5765 1975 2039 5766 2039 1976 5767 1976 1978 5768 1978 1978 5769 1978 1977 5770 1977 2039 5771 2039 1980 5772 1980 1977 5773 1977 1978 5774 1978 1980 5775 1980 1979 5776 1979 1977 5777 1977 1982 5778 1982 1979 5779 1979 1980 5780 1980 1982 5781 1982 1981 5782 1981 1979 5783 1979 1984 5784 1984 1981 5785 1981 1982 5786 1982 1984 5787 1984 1983 5788 1983 1981 5789 1981 1986 5790 1986 1983 5791 1983 1984 5792 1984 1986 5793 1986 1985 5794 1985 1983 5795 1983 1988 5796 1988 1985 5797 1985 1986 5798 1986 1988 5799 1988 1987 5800 1987 1985 5801 1985 1990 5802 1990 1987 5803 1987 1988 5804 1988 1990 5805 1990 1989 5806 1989 1987 5807 1987 1992 5808 1992 1989 5809 1989 1990 5810 1990 1992 5811 1992 1991 5812 1991 1989 5813 1989 1994 5814 1994 1991 5815 1991 1992 5816 1992 1994 5817 1994 1993 5818 1993 1991 5819 1991 1996 5820 1996 1993 5821 1993 1994 5822 1994 1996 5823 1996 1995 5824 1995 1993 5825 1993 1998 5826 1998 1995 5827 1995 1996 5828 1996 1998 5829 1998 1997 5830 1997 1995 5831 1995 2000 5832 2000 1997 5833 1997 1998 5834 1998 2000 5835 2000 1999 5836 1999 1997 5837 1997 2002 5838 2002 1999 5839 1999 2000 5840 2000 2002 5841 2002 2001 5842 2001 1999 5843 1999 2004 5844 2004 2001 5845 2001 2002 5846 2002 2004 5847 2004 2003 5848 2003 2001 5849 2001 2006 5850 2006 2003 5851 2003 2004 5852 2004 2006 5853 2006 2005 5854 2005 2003 5855 2003 2008 5856 2008 2005 5857 2005 2006 5858 2006 2008 5859 2008 2007 5860 2007 2005 5861 2005 2010 5862 2010 2007 5863 2007 2008 5864 2008 2010 5865 2010 2009 5866 2009 2007 5867 2007 2012 5868 2012 2009 5869 2009 2010 5870 2010 2012 5871 2012 2011 5872 2011 2009 5873 2009 2014 5874 2014 2011 5875 2011 2012 5876 2012 2014 5877 2014 2013 5878 2013 2011 5879 2011 2016 5880 2016 2013 5881 2013 2014 5882 2014 2016 5883 2016 2015 5884 2015 2013 5885 2013 2018 5886 2018 2015 5887 2015 2016 5888 2016 2018 5889 2018 2017 5890 2017 2015 5891 2015 2020 5892 2020 2017 5893 2017 2018 5894 2018 2020 5895 2020 2019 5896 2019 2017 5897 2017 2022 5898 2022 2019 5899 2019 2020 5900 2020 2022 5901 2022 2021 5902 2021 2019 5903 2019 2024 5904 2024 2021 5905 2021 2022 5906 2022 2024 5907 2024 2023 5908 2023 2021 5909 2021 2026 5910 2026 2023 5911 2023 2024 5912 2024 2026 5913 2026 2025 5914 2025 2023 5915 2023 2028 5916 2028 2025 5917 2025 2026 5918 2026 2028 5919 2028 2027 5920 2027 2025 5921 2025 2030 5922 2030 2027 5923 2027 2028 5924 2028 2030 5925 2030 2029 5926 2029 2027 5927 2027 2032 5928 2032 2029 5929 2029 2030 5930 2030 2032 5931 2032 2031 5932 2031 2029 5933 2029 2034 5934 2034 2031 5935 2031 2032 5936 2032 2034 5937 2034 2033 5938 2033 2031 5939 2031 2036 5940 2036 2033 5941 2033 2034 5942 2034 2036 5943 2036 2035 5944 2035 2033 5945 2033 2038 5946 2038 2035 5947 2035 2036 5948 2036 2038 5949 2038 2037 5950 2037 2035 5951 2035 1976 5952 1976 2037 5953 2037 2038 5954 2038 1976 5955 1976 2039 5956 2039 2037 5957 2037 2072 5958 2072 2040 5959 2040 2041 5960 2041 2044 5961 2044 2042 5962 2042 2043 5963 2043 2045 5964 2045 2042 5965 2042 2044 5966 2044 2048 5967 2048 2042 5968 2042 2045 5969 2045 2048 5970 2048 2046 5971 2046 2042 5972 2042 2048 5973 2048 2047 5974 2047 2046 5975 2046 2050 5976 2050 2047 5977 2047 2048 5978 2048 2050 5979 2050 2049 5980 2049 2047 5981 2047 2051 5982 2051 2049 5983 2049 2050 5984 2050 2054 5985 2054 2049 5986 2049 2051 5987 2051 2054 5988 2054 2052 5989 2052 2049 5990 2049 2054 5991 2054 2053 5992 2053 2052 5993 2052 2055 5994 2055 2053 5995 2053 2054 5996 2054 2057 5997 2057 2053 5998 2053 2055 5999 2055 2057 6000 2057 2056 6001 2056 2053 6002 2053 2060 6003 2060 2056 6004 2056 2057 6005 2057 2060 6006 2060 2058 6007 2058 2056 6008 2056 2060 6009 2060 2059 6010 2059 2058 6011 2058 2061 6012 2061 2059 6013 2059 2060 6014 2060 2063 6015 2063 2059 6016 2059 2061 6017 2061 2063 6018 2063 2062 6019 2062 2059 6020 2059 2065 6021 2065 2062 6022 2062 2063 6023 2063 2065 6024 2065 2064 6025 2064 2062 6026 2062 2067 6027 2067 2064 6028 2064 2065 6029 2065 2067 6030 2067 2066 6031 2066 2064 6032 2064 2069 6033 2069 2066 6034 2066 2067 6035 2067 2069 6036 2069 2068 6037 2068 2066 6038 2066 2071 6039 2071 2068 6040 2068 2069 6041 2069 2071 6042 2071 2070 6043 2070 2068 6044 2068 2073 6045 2073 2070 6046 2070 2071 6047 2071 2073 6048 2073 2072 6049 2072 2070 6050 2070 2040 6051 2040 2072 6052 2072 2073 6053 2073 2137 6054 2137 2074 6055 2074 2076 6056 2076 2076 6057 2076 2075 6058 2075 2137 6059 2137 2078 6060 2078 2075 6061 2075 2076 6062 2076 2078 6063 2078 2077 6064 2077 2075 6065 2075 2080 6066 2080 2077 6067 2077 2078 6068 2078 2080 6069 2080 2079 6070 2079 2077 6071 2077 2082 6072 2082 2079 6073 2079 2080 6074 2080 2082 6075 2082 2081 6076 2081 2079 6077 2079 2084 6078 2084 2081 6079 2081 2082 6080 2082 2084 6081 2084 2083 6082 2083 2081 6083 2081 2086 6084 2086 2083 6085 2083 2084 6086 2084 2086 6087 2086 2085 6088 2085 2083 6089 2083 2088 6090 2088 2085 6091 2085 2086 6092 2086 2088 6093 2088 2087 6094 2087 2085 6095 2085 2090 6096 2090 2087 6097 2087 2088 6098 2088 2090 6099 2090 2089 6100 2089 2087 6101 2087 2092 6102 2092 2089 6103 2089 2090 6104 2090 2092 6105 2092 2091 6106 2091 2089 6107 2089 2094 6108 2094 2091 6109 2091 2092 6110 2092 2094 6111 2094 2093 6112 2093 2091 6113 2091 2096 6114 2096 2093 6115 2093 2094 6116 2094 2096 6117 2096 2095 6118 2095 2093 6119 2093 2098 6120 2098 2095 6121 2095 2096 6122 2096 2098 6123 2098 2097 6124 2097 2095 6125 2095 2100 6126 2100 2097 6127 2097 2098 6128 2098 2100 6129 2100 2099 6130 2099 2097 6131 2097 2102 6132 2102 2099 6133 2099 2100 6134 2100 2102 6135 2102 2101 6136 2101 2099 6137 2099 2104 6138 2104 2101 6139 2101 2102 6140 2102 2104 6141 2104 2103 6142 2103 2101 6143 2101 2106 6144 2106 2103 6145 2103 2104 6146 2104 2106 6147 2106 2105 6148 2105 2103 6149 2103 2108 6150 2108 2105 6151 2105 2106 6152 2106 2108 6153 2108 2107 6154 2107 2105 6155 2105 2110 6156 2110 2107 6157 2107 2108 6158 2108 2110 6159 2110 2109 6160 2109 2107 6161 2107 2112 6162 2112 2109 6163 2109 2110 6164 2110 2112 6165 2112 2111 6166 2111 2109 6167 2109 2114 6168 2114 2111 6169 2111 2112 6170 2112 2114 6171 2114 2113 6172 2113 2111 6173 2111 2116 6174 2116 2113 6175 2113 2114 6176 2114 2116 6177 2116 2115 6178 2115 2113 6179 2113 2118 6180 2118 2115 6181 2115 2116 6182 2116 2118 6183 2118 2117 6184 2117 2115 6185 2115 2120 6186 2120 2117 6187 2117 2118 6188 2118 2120 6189 2120 2119 6190 2119 2117 6191 2117 2122 6192 2122 2119 6193 2119 2120 6194 2120 2122 6195 2122 2121 6196 2121 2119 6197 2119 2124 6198 2124 2121 6199 2121 2122 6200 2122 2124 6201 2124 2123 6202 2123 2121 6203 2121 2126 6204 2126 2123 6205 2123 2124 6206 2124 2126 6207 2126 2125 6208 2125 2123 6209 2123 2128 6210 2128 2125 6211 2125 2126 6212 2126 2128 6213 2128 2127 6214 2127 2125 6215 2125 2130 6216 2130 2127 6217 2127 2128 6218 2128 2130 6219 2130 2129 6220 2129 2127 6221 2127 2132 6222 2132 2129 6223 2129 2130 6224 2130 2132 6225 2132 2131 6226 2131 2129 6227 2129 2134 6228 2134 2131 6229 2131 2132 6230 2132 2134 6231 2134 2133 6232 2133 2131 6233 2131 2136 6234 2136 2133 6235 2133 2134 6236 2134 2136 6237 2136 2135 6238 2135 2133 6239 2133 2074 6240 2074 2135 6241 2135 2136 6242 2136 2074 6243 2074 2137 6244 2137 2135 6245 2135 2170 6246 2170 2138 6247 2138 2139 6248 2139 2142 6249 2142 2140 6250 2140 2141 6251 2141 2144 6252 2144 2140 6253 2140 2142 6254 2142 2144 6255 2144 2143 6256 2143 2140 6257 2140 2145 6258 2145 2143 6259 2143 2144 6260 2144 2147 6261 2147 2143 6262 2143 2145 6263 2145 2147 6264 2147 2146 6265 2146 2143 6266 2143 2149 6267 2149 2146 6268 2146 2147 6269 2147 2149 6270 2149 2148 6271 2148 2146 6272 2146 2151 6273 2151 2148 6274 2148 2149 6275 2149 2151 6276 2151 2150 6277 2150 2148 6278 2148 2153 6279 2153 2150 6280 2150 2151 6281 2151 2153 6282 2153 2152 6283 2152 2150 6284 2150 2155 6285 2155 2152 6286 2152 2153 6287 2153 2155 6288 2155 2154 6289 2154 2152 6290 2152 2157 6291 2157 2154 6292 2154 2155 6293 2155 2157 6294 2157 2156 6295 2156 2154 6296 2154 2159 6297 2159 2156 6298 2156 2157 6299 2157 2159 6300 2159 2158 6301 2158 2156 6302 2156 2161 6303 2161 2158 6304 2158 2159 6305 2159 2161 6306 2161 2160 6307 2160 2158 6308 2158 2163 6309 2163 2160 6310 2160 2161 6311 2161 2163 6312 2163 2162 6313 2162 2160 6314 2160 2165 6315 2165 2162 6316 2162 2163 6317 2163 2165 6318 2165 2164 6319 2164 2162 6320 2162 2167 6321 2167 2164 6322 2164 2165 6323 2165 2167 6324 2167 2166 6325 2166 2164 6326 2164 2169 6327 2169 2166 6328 2166 2167 6329 2167 2169 6330 2169 2168 6331 2168 2166 6332 2166 2171 6333 2171 2168 6334 2168 2169 6335 2169 2171 6336 2171 2170 6337 2170 2168 6338 2168 2138 6339 2138 2170 6340 2170 2171 6341 2171 2235 6342 2235 2172 6343 2172 2174 6344 2174 2174 6345 2174 2173 6346 2173 2235 6347 2235 2176 6348 2176 2173 6349 2173 2174 6350 2174 2176 6351 2176 2175 6352 2175 2173 6353 2173 2178 6354 2178 2175 6355 2175 2176 6356 2176 2178 6357 2178 2177 6358 2177 2175 6359 2175 2180 6360 2180 2177 6361 2177 2178 6362 2178 2180 6363 2180 2179 6364 2179 2177 6365 2177 2182 6366 2182 2179 6367 2179 2180 6368 2180 2182 6369 2182 2181 6370 2181 2179 6371 2179 2184 6372 2184 2181 6373 2181 2182 6374 2182 2184 6375 2184 2183 6376 2183 2181 6377 2181 2186 6378 2186 2183 6379 2183 2184 6380 2184 2186 6381 2186 2185 6382 2185 2183 6383 2183 2188 6384 2188 2185 6385 2185 2186 6386 2186 2188 6387 2188 2187 6388 2187 2185 6389 2185 2190 6390 2190 2187 6391 2187 2188 6392 2188 2190 6393 2190 2189 6394 2189 2187 6395 2187 2192 6396 2192 2189 6397 2189 2190 6398 2190 2192 6399 2192 2191 6400 2191 2189 6401 2189 2194 6402 2194 2191 6403 2191 2192 6404 2192 2194 6405 2194 2193 6406 2193 2191 6407 2191 2196 6408 2196 2193 6409 2193 2194 6410 2194 2196 6411 2196 2195 6412 2195 2193 6413 2193 2198 6414 2198 2195 6415 2195 2196 6416 2196 2198 6417 2198 2197 6418 2197 2195 6419 2195 2200 6420 2200 2197 6421 2197 2198 6422 2198 2200 6423 2200 2199 6424 2199 2197 6425 2197 2202 6426 2202 2199 6427 2199 2200 6428 2200 2202 6429 2202 2201 6430 2201 2199 6431 2199 2204 6432 2204 2201 6433 2201 2202 6434 2202 2204 6435 2204 2203 6436 2203 2201 6437 2201 2206 6438 2206 2203 6439 2203 2204 6440 2204 2206 6441 2206 2205 6442 2205 2203 6443 2203 2208 6444 2208 2205 6445 2205 2206 6446 2206 2208 6447 2208 2207 6448 2207 2205 6449 2205 2210 6450 2210 2207 6451 2207 2208 6452 2208 2210 6453 2210 2209 6454 2209 2207 6455 2207 2212 6456 2212 2209 6457 2209 2210 6458 2210 2212 6459 2212 2211 6460 2211 2209 6461 2209 2214 6462 2214 2211 6463 2211 2212 6464 2212 2214 6465 2214 2213 6466 2213 2211 6467 2211 2216 6468 2216 2213 6469 2213 2214 6470 2214 2216 6471 2216 2215 6472 2215 2213 6473 2213 2218 6474 2218 2215 6475 2215 2216 6476 2216 2218 6477 2218 2217 6478 2217 2215 6479 2215 2220 6480 2220 2217 6481 2217 2218 6482 2218 2220 6483 2220 2219 6484 2219 2217 6485 2217 2222 6486 2222 2219 6487 2219 2220 6488 2220 2222 6489 2222 2221 6490 2221 2219 6491 2219 2224 6492 2224 2221 6493 2221 2222 6494 2222 2224 6495 2224 2223 6496 2223 2221 6497 2221 2226 6498 2226 2223 6499 2223 2224 6500 2224 2226 6501 2226 2225 6502 2225 2223 6503 2223 2228 6504 2228 2225 6505 2225 2226 6506 2226 2228 6507 2228 2227 6508 2227 2225 6509 2225 2230 6510 2230 2227 6511 2227 2228 6512 2228 2230 6513 2230 2229 6514 2229 2227 6515 2227 2232 6516 2232 2229 6517 2229 2230 6518 2230 2232 6519 2232 2231 6520 2231 2229 6521 2229 2234 6522 2234 2231 6523 2231 2232 6524 2232 2234 6525 2234 2233 6526 2233 2231 6527 2231 2172 6528 2172 2233 6529 2233 2234 6530 2234 2172 6531 2172 2235 6532 2235 2233 6533 2233 2269 6534 2269 2236 6535 2236 2244 6536 2244 2239 6537 2239 2237 6538 2237 2238 6539 2238 2240 6540 2240 2237 6541 2237 2239 6542 2239 2242 6543 2242 2237 6544 2237 2240 6545 2240 2242 6546 2242 2241 6547 2241 2237 6548 2237 2245 6549 2245 2241 6550 2241 2242 6551 2242 2245 6552 2245 2243 6553 2243 2241 6554 2241 2245 6555 2245 2244 6556 2244 2243 6557 2243 2269 6558 2269 2244 6559 2244 2245 6560 2245 2249 6561 2249 2246 6562 2246 2247 6563 2247 2249 6564 2249 2248 6565 2248 2246 6566 2246 2251 6567 2251 2248 6568 2248 2249 6569 2249 2251 6570 2251 2250 6571 2250 2248 6572 2248 2253 6573 2253 2250 6574 2250 2251 6575 2251 2253 6576 2253 2252 6577 2252 2250 6578 2250 2256 6579 2256 2252 6580 2252 2253 6581 2253 2256 6582 2256 2254 6583 2254 2252 6584 2252 2256 6585 2256 2255 6586 2255 2254 6587 2254 2258 6588 2258 2255 6589 2255 2256 6590 2256 2258 6591 2258 2257 6592 2257 2255 6593 2255 2259 6594 2259 2257 6595 2257 2258 6596 2258 2261 6597 2261 2257 6598 2257 2259 6599 2259 2261 6600 2261 2260 6601 2260 2257 6602 2257 2263 6603 2263 2260 6604 2260 2261 6605 2261 2263 6606 2263 2262 6607 2262 2260 6608 2260 2265 6609 2265 2262 6610 2262 2263 6611 2263 2265 6612 2265 2264 6613 2264 2262 6614 2262 2267 6615 2267 2264 6616 2264 2265 6617 2265 2267 6618 2267 2266 6619 2266 2264 6620 2264 2236 6621 2236 2266 6622 2266 2267 6623 2267 2236 6624 2236 2268 6625 2268 2266 6626 2266 2236 6627 2236 2269 6628 2269 2268 6629 2268 2333 6630 2333 2270 6631 2270 2272 6632 2272 2272 6633 2272 2271 6634 2271 2333 6635 2333 2274 6636 2274 2271 6637 2271 2272 6638 2272 2274 6639 2274 2273 6640 2273 2271 6641 2271 2276 6642 2276 2273 6643 2273 2274 6644 2274 2276 6645 2276 2275 6646 2275 2273 6647 2273 2278 6648 2278 2275 6649 2275 2276 6650 2276 2278 6651 2278 2277 6652 2277 2275 6653 2275 2280 6654 2280 2277 6655 2277 2278 6656 2278 2280 6657 2280 2279 6658 2279 2277 6659 2277 2282 6660 2282 2279 6661 2279 2280 6662 2280 2282 6663 2282 2281 6664 2281 2279 6665 2279 2284 6666 2284 2281 6667 2281 2282 6668 2282 2284 6669 2284 2283 6670 2283 2281 6671 2281 2286 6672 2286 2283 6673 2283 2284 6674 2284 2286 6675 2286 2285 6676 2285 2283 6677 2283 2288 6678 2288 2285 6679 2285 2286 6680 2286 2288 6681 2288 2287 6682 2287 2285 6683 2285 2290 6684 2290 2287 6685 2287 2288 6686 2288 2290 6687 2290 2289 6688 2289 2287 6689 2287 2292 6690 2292 2289 6691 2289 2290 6692 2290 2292 6693 2292 2291 6694 2291 2289 6695 2289 2294 6696 2294 2291 6697 2291 2292 6698 2292 2294 6699 2294 2293 6700 2293 2291 6701 2291 2296 6702 2296 2293 6703 2293 2294 6704 2294 2296 6705 2296 2295 6706 2295 2293 6707 2293 2298 6708 2298 2295 6709 2295 2296 6710 2296 2298 6711 2298 2297 6712 2297 2295 6713 2295 2300 6714 2300 2297 6715 2297 2298 6716 2298 2300 6717 2300 2299 6718 2299 2297 6719 2297 2302 6720 2302 2299 6721 2299 2300 6722 2300 2302 6723 2302 2301 6724 2301 2299 6725 2299 2304 6726 2304 2301 6727 2301 2302 6728 2302 2304 6729 2304 2303 6730 2303 2301 6731 2301 2306 6732 2306 2303 6733 2303 2304 6734 2304 2306 6735 2306 2305 6736 2305 2303 6737 2303 2308 6738 2308 2305 6739 2305 2306 6740 2306 2308 6741 2308 2307 6742 2307 2305 6743 2305 2310 6744 2310 2307 6745 2307 2308 6746 2308 2310 6747 2310 2309 6748 2309 2307 6749 2307 2312 6750 2312 2309 6751 2309 2310 6752 2310 2312 6753 2312 2311 6754 2311 2309 6755 2309 2314 6756 2314 2311 6757 2311 2312 6758 2312 2314 6759 2314 2313 6760 2313 2311 6761 2311 2316 6762 2316 2313 6763 2313 2314 6764 2314 2316 6765 2316 2315 6766 2315 2313 6767 2313 2318 6768 2318 2315 6769 2315 2316 6770 2316 2318 6771 2318 2317 6772 2317 2315 6773 2315 2320 6774 2320 2317 6775 2317 2318 6776 2318 2320 6777 2320 2319 6778 2319 2317 6779 2317 2322 6780 2322 2319 6781 2319 2320 6782 2320 2322 6783 2322 2321 6784 2321 2319 6785 2319 2324 6786 2324 2321 6787 2321 2322 6788 2322 2324 6789 2324 2323 6790 2323 2321 6791 2321 2326 6792 2326 2323 6793 2323 2324 6794 2324 2326 6795 2326 2325 6796 2325 2323 6797 2323 2328 6798 2328 2325 6799 2325 2326 6800 2326 2328 6801 2328 2327 6802 2327 2325 6803 2325 2330 6804 2330 2327 6805 2327 2328 6806 2328 2330 6807 2330 2329 6808 2329 2327 6809 2327 2332 6810 2332 2329 6811 2329 2330 6812 2330 2332 6813 2332 2331 6814 2331 2329 6815 2329 2270 6816 2270 2331 6817 2331 2332 6818 2332 2270 6819 2270 2333 6820 2333 2331 6821 2331 2366 6822 2366 2339 6823 2339 2334 6824 2334 2337 6825 2337 2335 6826 2335 2336 6827 2336 2338 6828 2338 2335 6829 2335 2337 6830 2337 2334 6831 2334 2335 6832 2335 2338 6833 2338 2334 6834 2334 2339 6835 2339 2335 6836 2335 2343 6837 2343 2340 6838 2340 2341 6839 2341 2343 6840 2343 2342 6841 2342 2340 6842 2340 2345 6843 2345 2342 6844 2342 2343 6845 2343 2345 6846 2345 2344 6847 2344 2342 6848 2342 2348 6849 2348 2344 6850 2344 2345 6851 2345 2348 6852 2348 2346 6853 2346 2344 6854 2344 2348 6855 2348 2347 6856 2347 2346 6857 2346 2350 6858 2350 2347 6859 2347 2348 6860 2348 2350 6861 2350 2349 6862 2349 2347 6863 2347 2352 6864 2352 2349 6865 2349 2350 6866 2350 2352 6867 2352 2351 6868 2351 2349 6869 2349 2354 6870 2354 2351 6871 2351 2352 6872 2352 2354 6873 2354 2353 6874 2353 2351 6875 2351 2356 6876 2356 2353 6877 2353 2354 6878 2354 2356 6879 2356 2355 6880 2355 2353 6881 2353 2357 6882 2357 2355 6883 2355 2356 6884 2356 2359 6885 2359 2355 6886 2355 2357 6887 2357 2359 6888 2359 2358 6889 2358 2355 6890 2355 2361 6891 2361 2358 6892 2358 2359 6893 2359 2361 6894 2361 2360 6895 2360 2358 6896 2358 2363 6897 2363 2360 6898 2360 2361 6899 2361 2363 6900 2363 2362 6901 2362 2360 6902 2360 2365 6903 2365 2362 6904 2362 2363 6905 2363 2365 6906 2365 2364 6907 2364 2362 6908 2362 2367 6909 2367 2364 6910 2364 2365 6911 2365 2367 6912 2367 2366 6913 2366 2364 6914 2364 2339 6915 2339 2366 6916 2366 2367 6917 2367 2400 6918 2400 2369 6919 2369 2368 6920 2368 2371 6921 2371 2369 6922 2369 2370 6923 2370 2368 6924 2368 2369 6925 2369 2371 6926 2371 2375 6927 2375 2372 6928 2372 2373 6929 2373 2375 6930 2375 2374 6931 2374 2372 6932 2372 2378 6933 2378 2374 6934 2374 2375 6935 2375 2378 6936 2378 2376 6937 2376 2374 6938 2374 2378 6939 2378 2377 6940 2377 2376 6941 2376 2379 6942 2379 2377 6943 2377 2378 6944 2378 2381 6945 2381 2377 6946 2377 2379 6947 2379 2381 6948 2381 2380 6949 2380 2377 6950 2377 2384 6951 2384 2380 6952 2380 2381 6953 2381 2384 6954 2384 2382 6955 2382 2380 6956 2380 2384 6957 2384 2383 6958 2383 2382 6959 2382 2385 6960 2385 2383 6961 2383 2384 6962 2384 2387 6963 2387 2383 6964 2383 2385 6965 2385 2387 6966 2387 2386 6967 2386 2383 6968 2383 2389 6969 2389 2386 6970 2386 2387 6971 2387 2389 6972 2389 2388 6973 2388 2386 6974 2386 2391 6975 2391 2388 6976 2388 2389 6977 2389 2391 6978 2391 2390 6979 2390 2388 6980 2388 2393 6981 2393 2390 6982 2390 2391 6983 2391 2393 6984 2393 2392 6985 2392 2390 6986 2390 2395 6987 2395 2392 6988 2392 2393 6989 2393 2395 6990 2395 2394 6991 2394 2392 6992 2392 2398 6993 2398 2394 6994 2394 2395 6995 2395 2398 6996 2398 2396 6997 2396 2394 6998 2394 2398 6999 2398 2397 7000 2397 2396 7001 2396 2399 7002 2399 2397 7003 2397 2398 7004 2398 2401 7005 2401 2397 7006 2397 2399 7007 2399 2401 7008 2401 2400 7009 2400 2397 7010 2397 2369 7011 2369 2400 7012 2400 2401 7013 2401 2434 7014 2434 2408 7015 2408 2402 7016 2402 2407 7017 2407 2403 7018 2403 2404 7019 2404 2407 7020 2407 2405 7021 2405 2403 7022 2403 2407 7023 2407 2406 7024 2406 2405 7025 2405 2409 7026 2409 2406 7027 2406 2407 7028 2407 2409 7029 2409 2408 7030 2408 2406 7031 2406 2402 7032 2402 2408 7033 2408 2409 7034 2409 2414 7035 2414 2410 7036 2410 2411 7037 2411 2414 7038 2414 2412 7039 2412 2410 7040 2410 2414 7041 2414 2413 7042 2413 2412 7043 2412 2416 7044 2416 2413 7045 2413 2414 7046 2414 2416 7047 2416 2415 7048 2415 2413 7049 2413 2417 7050 2417 2415 7051 2415 2416 7052 2416 2419 7053 2419 2415 7054 2415 2417 7055 2417 2419 7056 2419 2418 7057 2418 2415 7058 2415 2422 7059 2422 2418 7060 2418 2419 7061 2419 2422 7062 2422 2420 7063 2420 2418 7064 2418 2422 7065 2422 2421 7066 2421 2420 7067 2420 2424 7068 2424 2421 7069 2421 2422 7070 2422 2424 7071 2424 2423 7072 2423 2421 7073 2421 2425 7074 2425 2423 7075 2423 2424 7076 2424 2428 7077 2428 2423 7078 2423 2425 7079 2425 2428 7080 2428 2426 7081 2426 2423 7082 2423 2428 7083 2428 2427 7084 2427 2426 7085 2426 2429 7086 2429 2427 7087 2427 2428 7088 2428 2432 7089 2432 2427 7090 2427 2429 7091 2429 2432 7092 2432 2430 7093 2430 2427 7094 2427 2432 7095 2432 2431 7096 2431 2430 7097 2430 2433 7098 2433 2431 7099 2431 2432 7100 2432 2435 7101 2435 2431 7102 2431 2433 7103 2433 2435 7104 2435 2434 7105 2434 2431 7106 2431 2408 7107 2408 2434 7108 2434 2435 7109 2435 2468 7110 2468 2437 7111 2437 2436 7112 2436 2439 7113 2439 2437 7114 2437 2438 7115 2438 2436 7116 2436 2437 7117 2437 2439 7118 2439 2443 7119 2443 2440 7120 2440 2441 7121 2441 2443 7122 2443 2442 7123 2442 2440 7124 2440 2445 7125 2445 2442 7126 2442 2443 7127 2443 2445 7128 2445 2444 7129 2444 2442 7130 2442 2448 7131 2448 2444 7132 2444 2445 7133 2445 2448 7134 2448 2446 7135 2446 2444 7136 2444 2448 7137 2448 2447 7138 2447 2446 7139 2446 2450 7140 2450 2447 7141 2447 2448 7142 2448 2450 7143 2450 2449 7144 2449 2447 7145 2447 2452 7146 2452 2449 7147 2449 2450 7148 2450 2452 7149 2452 2451 7150 2451 2449 7151 2449 2454 7152 2454 2451 7153 2451 2452 7154 2452 2454 7155 2454 2453 7156 2453 2451 7157 2451 2456 7158 2456 2453 7159 2453 2454 7160 2454 2456 7161 2456 2455 7162 2455 2453 7163 2453 2458 7164 2458 2455 7165 2455 2456 7166 2456 2458 7167 2458 2457 7168 2457 2455 7169 2455 2460 7170 2460 2457 7171 2457 2458 7172 2458 2460 7173 2460 2459 7174 2459 2457 7175 2457 2462 7176 2462 2459 7177 2459 2460 7178 2460 2462 7179 2462 2461 7180 2461 2459 7181 2459 2464 7182 2464 2461 7183 2461 2462 7184 2462 2464 7185 2464 2463 7186 2463 2461 7187 2461 2465 7188 2465 2463 7189 2463 2464 7190 2464 2467 7191 2467 2463 7192 2463 2465 7193 2465 2467 7194 2467 2466 7195 2466 2463 7196 2463 2469 7197 2469 2466 7198 2466 2467 7199 2467 2469 7200 2469 2468 7201 2468 2466 7202 2466 2437 7203 2437 2468 7204 2468 2469 7205 2469 2502 7206 2502 2474 7207 2474 2470 7208 2470 2475 7209 2475 2471 7210 2471 2472 7211 2472 2475 7212 2475 2473 7213 2473 2471 7214 2471 2475 7215 2475 2474 7216 2474 2473 7217 2473 2470 7218 2470 2474 7219 2474 2475 7220 2475 2480 7221 2480 2476 7222 2476 2477 7223 2477 2480 7224 2480 2478 7225 2478 2476 7226 2476 2480 7227 2480 2479 7228 2479 2478 7229 2478 2481 7230 2481 2479 7231 2479 2480 7232 2480 2483 7233 2483 2479 7234 2479 2481 7235 2481 2483 7236 2483 2482 7237 2482 2479 7238 2479 2485 7239 2485 2482 7240 2482 2483 7241 2483 2485 7242 2485 2484 7243 2484 2482 7244 2482 2487 7245 2487 2484 7246 2484 2485 7247 2485 2487 7248 2487 2486 7249 2486 2484 7250 2484 2489 7251 2489 2486 7252 2486 2487 7253 2487 2489 7254 2489 2488 7255 2488 2486 7256 2486 2491 7257 2491 2488 7258 2488 2489 7259 2489 2491 7260 2491 2490 7261 2490 2488 7262 2488 2493 7263 2493 2490 7264 2490 2491 7265 2491 2493 7266 2493 2492 7267 2492 2490 7268 2490 2495 7269 2495 2492 7270 2492 2493 7271 2493 2495 7272 2495 2494 7273 2494 2492 7274 2492 2497 7275 2497 2494 7276 2494 2495 7277 2495 2497 7278 2497 2496 7279 2496 2494 7280 2494 2500 7281 2500 2496 7282 2496 2497 7283 2497 2500 7284 2500 2498 7285 2498 2496 7286 2496 2500 7287 2500 2499 7288 2499 2498 7289 2498 2501 7290 2501 2499 7291 2499 2500 7292 2500 2503 7293 2503 2499 7294 2499 2501 7295 2501 2503 7296 2503 2502 7297 2502 2499 7298 2499 2474 7299 2474 2502 7300 2502 2503 7301 2503 2536 7302 2536 2504 7303 2504 2505 7304 2505 2508 7305 2508 2506 7306 2506 2507 7307 2507 2509 7308 2509 2506 7309 2506 2508 7310 2508 2512 7311 2512 2506 7312 2506 2509 7313 2509 2512 7314 2512 2510 7315 2510 2506 7316 2506 2512 7317 2512 2511 7318 2511 2510 7319 2510 2514 7320 2514 2511 7321 2511 2512 7322 2512 2514 7323 2514 2513 7324 2513 2511 7325 2511 2516 7326 2516 2513 7327 2513 2514 7328 2514 2516 7329 2516 2515 7330 2515 2513 7331 2513 2517 7332 2517 2515 7333 2515 2516 7334 2516 2519 7335 2519 2515 7336 2515 2517 7337 2517 2519 7338 2519 2518 7339 2518 2515 7340 2515 2522 7341 2522 2518 7342 2518 2519 7343 2519 2522 7344 2522 2520 7345 2520 2518 7346 2518 2522 7347 2522 2521 7348 2521 2520 7349 2520 2524 7350 2524 2521 7351 2521 2522 7352 2522 2524 7353 2524 2523 7354 2523 2521 7355 2521 2525 7356 2525 2523 7357 2523 2524 7358 2524 2527 7359 2527 2523 7360 2523 2525 7361 2525 2527 7362 2527 2526 7363 2526 2523 7364 2523 2529 7365 2529 2526 7366 2526 2527 7367 2527 2529 7368 2529 2528 7369 2528 2526 7370 2526 2531 7371 2531 2528 7372 2528 2529 7373 2529 2531 7374 2531 2530 7375 2530 2528 7376 2528 2533 7377 2533 2530 7378 2530 2531 7379 2531 2533 7380 2533 2532 7381 2532 2530 7382 2530 2535 7383 2535 2532 7384 2532 2533 7385 2533 2535 7386 2535 2534 7387 2534 2532 7388 2532 2537 7389 2537 2534 7390 2534 2535 7391 2535 2537 7392 2537 2536 7393 2536 2534 7394 2534 2504 7395 2504 2536 7396 2536 2537 7397 2537 2570 7398 2570 2546 7399 2546 2538 7400 2538 2541 7401 2541 2539 7402 2539 2540 7403 2540 2542 7404 2542 2539 7405 2539 2541 7406 2541 2544 7407 2544 2539 7408 2539 2542 7409 2542 2544 7410 2544 2543 7411 2543 2539 7412 2539 2547 7413 2547 2543 7414 2543 2544 7415 2544 2547 7416 2547 2545 7417 2545 2543 7418 2543 2547 7419 2547 2546 7420 2546 2545 7421 2545 2538 7422 2538 2546 7423 2546 2547 7424 2547 2552 7425 2552 2548 7426 2548 2549 7427 2549 2552 7428 2552 2550 7429 2550 2548 7430 2548 2552 7431 2552 2551 7432 2551 2550 7433 2550 2554 7434 2554 2551 7435 2551 2552 7436 2552 2554 7437 2554 2553 7438 2553 2551 7439 2551 2555 7440 2555 2553 7441 2553 2554 7442 2554 2557 7443 2557 2553 7444 2553 2555 7445 2555 2557 7446 2557 2556 7447 2556 2553 7448 2553 2560 7449 2560 2556 7450 2556 2557 7451 2557 2560 7452 2560 2558 7453 2558 2556 7454 2556 2560 7455 2560 2559 7456 2559 2558 7457 2558 2561 7458 2561 2559 7459 2559 2560 7460 2560 2564 7461 2564 2559 7462 2559 2561 7463 2561 2564 7464 2564 2562 7465 2562 2559 7466 2559 2564 7467 2564 2563 7468 2563 2562 7469 2562 2565 7470 2565 2563 7471 2563 2564 7472 2564 2567 7473 2567 2563 7474 2563 2565 7475 2565 2567 7476 2567 2566 7477 2566 2563 7478 2563 2569 7479 2569 2566 7480 2566 2567 7481 2567 2569 7482 2569 2568 7483 2568 2566 7484 2566 2571 7485 2571 2568 7486 2568 2569 7487 2569 2571 7488 2571 2570 7489 2570 2568 7490 2568 2546 7491 2546 2570 7492 2570 2571 7493 2571 2605 7494 2605 2572 7495 2572 2573 7496 2573 2577 7497 2577 2574 7498 2574 2575 7499 2575 2577 7500 2577 2576 7501 2576 2574 7502 2574 2580 7503 2580 2576 7504 2576 2577 7505 2577 2580 7506 2580 2578 7507 2578 2576 7508 2576 2580 7509 2580 2579 7510 2579 2578 7511 2578 2581 7512 2581 2579 7513 2579 2580 7514 2580 2584 7515 2584 2579 7516 2579 2581 7517 2581 2584 7518 2584 2582 7519 2582 2579 7520 2579 2584 7521 2584 2583 7522 2583 2582 7523 2582 2585 7524 2585 2583 7525 2583 2584 7526 2584 2587 7527 2587 2583 7528 2583 2585 7529 2585 2587 7530 2587 2586 7531 2586 2583 7532 2583 2589 7533 2589 2586 7534 2586 2587 7535 2587 2589 7536 2589 2588 7537 2588 2586 7538 2586 2591 7539 2591 2588 7540 2588 2589 7541 2589 2591 7542 2591 2590 7543 2590 2588 7544 2588 2593 7545 2593 2590 7546 2590 2591 7547 2591 2593 7548 2593 2592 7549 2592 2590 7550 2590 2596 7551 2596 2592 7552 2592 2593 7553 2593 2596 7554 2596 2594 7555 2594 2592 7556 2592 2596 7557 2596 2595 7558 2595 2594 7559 2594 2597 7560 2597 2595 7561 2595 2596 7562 2596 2599 7563 2599 2595 7564 2595 2597 7565 2597 2599 7566 2599 2598 7567 2598 2595 7568 2595 2601 7569 2601 2598 7570 2598 2599 7571 2599 2601 7572 2601 2600 7573 2600 2598 7574 2598 2603 7575 2603 2600 7576 2600 2601 7577 2601 2603 7578 2603 2602 7579 2602 2600 7580 2600 2572 7581 2572 2602 7582 2602 2603 7583 2603 2572 7584 2572 2604 7585 2604 2602 7586 2602 2572 7587 2572 2605 7588 2605 2604 7589 2604 2608 7590 2608 2606 7591 2606 2607 7592 2607 2626 7593 2626 2608 7594 2608 2609 7595 2609 2612 7596 2612 2610 7597 2610 2611 7598 2611 2613 7599 2613 2610 7600 2610 2612 7601 2612 2615 7602 2615 2610 7603 2610 2613 7604 2613 2615 7605 2615 2614 7606 2614 2610 7607 2610 2617 7608 2617 2614 7609 2614 2615 7610 2615 2617 7611 2617 2616 7612 2616 2614 7613 2614 2618 7614 2618 2616 7615 2616 2617 7616 2617 2620 7617 2620 2616 7618 2616 2618 7619 2618 2620 7620 2620 2619 7621 2619 2616 7622 2616 2622 7623 2622 2619 7624 2619 2620 7625 2620 2622 7626 2622 2621 7627 2621 2619 7628 2619 2623 7629 2623 2621 7630 2621 2622 7631 2622 2625 7632 2625 2621 7633 2621 2623 7634 2623 2625 7635 2625 2624 7636 2624 2621 7637 2621 2627 7638 2627 2624 7639 2624 2625 7640 2625 2627 7641 2627 2626 7642 2626 2624 7643 2624 2606 7644 2606 2626 7645 2626 2627 7646 2627 2606 7647 2606 2608 7648 2608 2626 7649 2626 2649 7650 2649 2628 7651 2628 2629 7652 2629 2634 7653 2634 2630 7654 2630 2631 7655 2631 2634 7656 2634 2632 7657 2632 2630 7658 2630 2634 7659 2634 2633 7660 2633 2632 7661 2632 2636 7662 2636 2633 7663 2633 2634 7664 2634 2636 7665 2636 2635 7666 2635 2633 7667 2633 2639 7668 2639 2635 7669 2635 2636 7670 2636 2639 7671 2639 2637 7672 2637 2635 7673 2635 2639 7674 2639 2638 7675 2638 2637 7676 2637 2641 7677 2641 2638 7678 2638 2639 7679 2639 2641 7680 2641 2640 7681 2640 2638 7682 2638 2644 7683 2644 2640 7684 2640 2641 7685 2641 2644 7686 2644 2642 7687 2642 2640 7688 2640 2644 7689 2644 2643 7690 2643 2642 7691 2642 2646 7692 2646 2643 7693 2643 2644 7694 2644 2646 7695 2646 2645 7696 2645 2643 7697 2643 2628 7698 2628 2645 7699 2645 2646 7700 2646 2628 7701 2628 2647 7702 2647 2645 7703 2645 2628 7704 2628 2648 7705 2648 2647 7706 2647 2628 7707 2628 2649 7708 2649 2648 7709 2648 2672 7710 2672 2650 7711 2650 2651 7712 2651 2654 7713 2654 2652 7714 2652 2653 7715 2653 2655 7716 2655 2652 7717 2652 2654 7718 2654 2658 7719 2658 2652 7720 2652 2655 7721 2655 2658 7722 2658 2656 7723 2656 2652 7724 2652 2658 7725 2658 2657 7726 2657 2656 7727 2656 2659 7728 2659 2657 7729 2657 2658 7730 2658 2661 7731 2661 2657 7732 2657 2659 7733 2659 2661 7734 2661 2660 7735 2660 2657 7736 2657 2663 7737 2663 2660 7738 2660 2661 7739 2661 2663 7740 2663 2662 7741 2662 2660 7742 2660 2665 7743 2665 2662 7744 2662 2663 7745 2663 2665 7746 2665 2664 7747 2664 2662 7748 2662 2668 7749 2668 2664 7750 2664 2665 7751 2665 2668 7752 2668 2666 7753 2666 2664 7754 2664 2668 7755 2668 2667 7756 2667 2666 7757 2666 2669 7758 2669 2667 7759 2667 2668 7760 2668 2671 7761 2671 2667 7762 2667 2669 7763 2669 2671 7764 2671 2670 7765 2670 2667 7766 2667 2673 7767 2673 2670 7768 2670 2671 7769 2671 2673 7770 2673 2672 7771 2672 2670 7772 2670 2674 7773 2674 2672 7774 2672 2673 7775 2673 2675 7776 2675 2672 7777 2672 2674 7778 2674 2650 7779 2650 2672 7780 2672 2675 7781 2675 2696 7782 2696 2676 7783 2676 2677 7784 2677 2681 7785 2681 2678 7786 2678 2679 7787 2679 2681 7788 2681 2680 7789 2680 2678 7790 2678 2683 7791 2683 2680 7792 2680 2681 7793 2681 2683 7794 2683 2682 7795 2682 2680 7796 2680 2685 7797 2685 2682 7798 2682 2683 7799 2683 2685 7800 2685 2684 7801 2684 2682 7802 2682 2687 7803 2687 2684 7804 2684 2685 7805 2685 2687 7806 2687 2686 7807 2686 2684 7808 2684 2690 7809 2690 2686 7810 2686 2687 7811 2687 2690 7812 2690 2688 7813 2688 2686 7814 2686 2690 7815 2690 2689 7816 2689 2688 7817 2688 2693 7818 2693 2689 7819 2689 2690 7820 2690 2693 7821 2693 2691 7822 2691 2689 7823 2689 2693 7824 2693 2692 7825 2692 2691 7826 2691 2695 7827 2695 2692 7828 2692 2693 7829 2693 2695 7830 2695 2694 7831 2694 2692 7832 2692 2676 7833 2676 2694 7834 2694 2695 7835 2695 2676 7836 2676 2696 7837 2696 2694 7838 2694 2718 7839 2718 2697 7840 2697 2698 7841 2698 2702 7842 2702 2699 7843 2699 2700 7844 2700 2702 7845 2702 2701 7846 2701 2699 7847 2699 2704 7848 2704 2701 7849 2701 2702 7850 2702 2704 7851 2704 2703 7852 2703 2701 7853 2701 2706 7854 2706 2703 7855 2703 2704 7856 2704 2706 7857 2706 2705 7858 2705 2703 7859 2703 2708 7860 2708 2705 7861 2705 2706 7862 2706 2708 7863 2708 2707 7864 2707 2705 7865 2705 2711 7866 2711 2707 7867 2707 2708 7868 2708 2711 7869 2711 2709 7870 2709 2707 7871 2707 2711 7872 2711 2710 7873 2710 2709 7874 2709 2713 7875 2713 2710 7876 2710 2711 7877 2711 2713 7878 2713 2712 7879 2712 2710 7880 2710 2715 7881 2715 2712 7882 2712 2713 7883 2713 2715 7884 2715 2714 7885 2714 2712 7886 2712 2717 7887 2717 2714 7888 2714 2715 7889 2715 2717 7890 2717 2716 7891 2716 2714 7892 2714 2697 7893 2697 2716 7894 2716 2717 7895 2717 2697 7896 2697 2718 7897 2718 2716 7898 2716 2738 7899 2738 2719 7900 2719 2720 7901 2720 2723 7902 2723 2721 7903 2721 2722 7904 2722 2725 7905 2725 2721 7906 2721 2723 7907 2723 2725 7908 2725 2724 7909 2724 2721 7910 2721 2727 7911 2727 2724 7912 2724 2725 7913 2725 2727 7914 2727 2726 7915 2726 2724 7916 2724 2729 7917 2729 2726 7918 2726 2727 7919 2727 2729 7920 2729 2728 7921 2728 2726 7922 2726 2731 7923 2731 2728 7924 2728 2729 7925 2729 2731 7926 2731 2730 7927 2730 2728 7928 2728 2732 7929 2732 2730 7930 2730 2731 7931 2731 2734 7932 2734 2730 7933 2730 2732 7934 2732 2734 7935 2734 2733 7936 2733 2730 7937 2730 2735 7938 2735 2733 7939 2733 2734 7940 2734 2737 7941 2737 2733 7942 2733 2735 7943 2735 2737 7944 2737 2736 7945 2736 2733 7946 2733 2739 7947 2739 2736 7948 2736 2737 7949 2737 2739 7950 2739 2738 7951 2738 2736 7952 2736 2719 7953 2719 2738 7954 2738 2739 7955 2739 2761 7956 2761 2740 7957 2740 2741 7958 2741 2745 7959 2745 2742 7960 2742 2743 7961 2743 2745 7962 2745 2744 7963 2744 2742 7964 2742 2747 7965 2747 2744 7966 2744 2745 7967 2745 2747 7968 2747 2746 7969 2746 2744 7970 2744 2749 7971 2749 2746 7972 2746 2747 7973 2747 2749 7974 2749 2748 7975 2748 2746 7976 2746 2751 7977 2751 2748 7978 2748 2749 7979 2749 2751 7980 2751 2750 7981 2750 2748 7982 2748 2754 7983 2754 2750 7984 2750 2751 7985 2751 2754 7986 2754 2752 7987 2752 2750 7988 2750 2754 7989 2754 2753 7990 2753 2752 7991 2752 2756 7992 2756 2753 7993 2753 2754 7994 2754 2756 7995 2756 2755 7996 2755 2753 7997 2753 2758 7998 2758 2755 7999 2755 2756 8000 2756 2758 8001 2758 2757 8002 2757 2755 8003 2755 2760 8004 2760 2757 8005 2757 2758 8006 2758 2760 8007 2760 2759 8008 2759 2757 8009 2757 2740 8010 2740 2759 8011 2759 2760 8012 2760 2740 8013 2740 2761 8014 2761 2759 8015 2759 2794 8016 2794 2762 8017 2762 2763 8018 2763 2766 8019 2766 2764 8020 2764 2765 8021 2765 2767 8022 2767 2764 8023 2764 2766 8024 2766 2770 8025 2770 2764 8026 2764 2767 8027 2767 2770 8028 2770 2768 8029 2768 2764 8030 2764 2770 8031 2770 2769 8032 2769 2768 8033 2768 2772 8034 2772 2769 8035 2769 2770 8036 2770 2772 8037 2772 2771 8038 2771 2769 8039 2769 2774 8040 2774 2771 8041 2771 2772 8042 2772 2774 8043 2774 2773 8044 2773 2771 8045 2771 2775 8046 2775 2773 8047 2773 2774 8048 2774 2777 8049 2777 2773 8050 2773 2775 8051 2775 2777 8052 2777 2776 8053 2776 2773 8054 2773 2779 8055 2779 2776 8056 2776 2777 8057 2777 2779 8058 2779 2778 8059 2778 2776 8060 2776 2781 8061 2781 2778 8062 2778 2779 8063 2779 2781 8064 2781 2780 8065 2780 2778 8066 2778 2784 8067 2784 2780 8068 2780 2781 8069 2781 2784 8070 2784 2782 8071 2782 2780 8072 2780 2784 8073 2784 2783 8074 2783 2782 8075 2782 2786 8076 2786 2783 8077 2783 2784 8078 2784 2786 8079 2786 2785 8080 2785 2783 8081 2783 2787 8082 2787 2785 8083 2785 2786 8084 2786 2789 8085 2789 2785 8086 2785 2787 8087 2787 2789 8088 2789 2788 8089 2788 2785 8090 2785 2791 8091 2791 2788 8092 2788 2789 8093 2789 2791 8094 2791 2790 8095 2790 2788 8096 2788 2793 8097 2793 2790 8098 2790 2791 8099 2791 2793 8100 2793 2792 8101 2792 2790 8102 2790 2795 8103 2795 2792 8104 2792 2793 8105 2793 2795 8106 2795 2794 8107 2794 2792 8108 2792 2762 8109 2762 2794 8110 2794 2795 8111 2795 2816 8112 2816 2796 8113 2796 2797 8114 2797 2801 8115 2801 2798 8116 2798 2799 8117 2799 2801 8118 2801 2800 8119 2800 2798 8120 2798 2803 8121 2803 2800 8122 2800 2801 8123 2801 2803 8124 2803 2802 8125 2802 2800 8126 2800 2805 8127 2805 2802 8128 2802 2803 8129 2803 2805 8130 2805 2804 8131 2804 2802 8132 2802 2807 8133 2807 2804 8134 2804 2805 8135 2805 2807 8136 2807 2806 8137 2806 2804 8138 2804 2809 8139 2809 2806 8140 2806 2807 8141 2807 2809 8142 2809 2808 8143 2808 2806 8144 2806 2811 8145 2811 2808 8146 2808 2809 8147 2809 2811 8148 2811 2810 8149 2810 2808 8150 2808 2813 8151 2813 2810 8152 2810 2811 8153 2811 2813 8154 2813 2812 8155 2812 2810 8156 2810 2815 8157 2815 2812 8158 2812 2813 8159 2813 2815 8160 2815 2814 8161 2814 2812 8162 2812 2817 8163 2817 2814 8164 2814 2815 8165 2815 2817 8166 2817 2816 8167 2816 2814 8168 2814 2796 8169 2796 2816 8170 2816 2817 8171 2817 2839 8172 2839 2818 8173 2818 2819 8174 2819 2822 8175 2822 2820 8176 2820 2821 8177 2821 2824 8178 2824 2820 8179 2820 2822 8180 2822 2824 8181 2824 2823 8182 2823 2820 8183 2820 2826 8184 2826 2823 8185 2823 2824 8186 2824 2826 8187 2826 2825 8188 2825 2823 8189 2823 2828 8190 2828 2825 8191 2825 2826 8192 2826 2828 8193 2828 2827 8194 2827 2825 8195 2825 2830 8196 2830 2827 8197 2827 2828 8198 2828 2830 8199 2830 2829 8200 2829 2827 8201 2827 2832 8202 2832 2829 8203 2829 2830 8204 2830 2832 8205 2832 2831 8206 2831 2829 8207 2829 2834 8208 2834 2831 8209 2831 2832 8210 2832 2834 8211 2834 2833 8212 2833 2831 8213 2831 2836 8214 2836 2833 8215 2833 2834 8216 2834 2836 8217 2836 2835 8218 2835 2833 8219 2833 2838 8220 2838 2835 8221 2835 2836 8222 2836 2838 8223 2838 2837 8224 2837 2835 8225 2835 2818 8226 2818 2837 8227 2837 2838 8228 2838 2818 8229 2818 2839 8230 2839 2837 8231 2837 2856 8232 2856 2840 8233 2840 2841 8234 2841 2844 8235 2844 2842 8236 2842 2843 8237 2843 2846 8238 2846 2842 8239 2842 2844 8240 2844 2846 8241 2846 2845 8242 2845 2842 8243 2842 2848 8244 2848 2845 8245 2845 2846 8246 2846 2848 8247 2848 2847 8248 2847 2845 8249 2845 2850 8250 2850 2847 8251 2847 2848 8252 2848 2850 8253 2850 2849 8254 2849 2847 8255 2847 2852 8256 2852 2849 8257 2849 2850 8258 2850 2852 8259 2852 2851 8260 2851 2849 8261 2849 2853 8262 2853 2851 8263 2851 2852 8264 2852 2855 8265 2855 2851 8266 2851 2853 8267 2853 2855 8268 2855 2854 8269 2854 2851 8270 2851 2857 8271 2857 2854 8272 2854 2855 8273 2855 2857 8274 2857 2856 8275 2856 2854 8276 2854 2840 8277 2840 2856 8278 2856 2857 8279 2857 2875 8280 2875 2858 8281 2858 2859 8282 2859 2862 8283 2862 2860 8284 2860 2861 8285 2861 2863 8286 2863 2860 8287 2860 2862 8288 2862 2865 8289 2865 2860 8290 2860 2863 8291 2863 2865 8292 2865 2864 8293 2864 2860 8294 2860 2867 8295 2867 2864 8296 2864 2865 8297 2865 2867 8298 2867 2866 8299 2866 2864 8300 2864 2869 8301 2869 2866 8302 2866 2867 8303 2867 2869 8304 2869 2868 8305 2868 2866 8306 2866 2872 8307 2872 2868 8308 2868 2869 8309 2869 2872 8310 2872 2870 8311 2870 2868 8312 2868 2872 8313 2872 2871 8314 2871 2870 8315 2870 2874 8316 2874 2871 8317 2871 2872 8318 2872 2874 8319 2874 2873 8320 2873 2871 8321 2871 2858 8322 2858 2873 8323 2873 2874 8324 2874 2858 8325 2858 2875 8326 2875 2873 8327 2873 2892 8328 2892 2877 8329 2877 2876 8330 2876 2879 8331 2879 2877 8332 2877 2878 8333 2878 2876 8334 2876 2877 8335 2877 2879 8336 2879 2882 8337 2882 2880 8338 2880 2881 8339 2881 2884 8340 2884 2880 8341 2880 2882 8342 2882 2884 8343 2884 2883 8344 2883 2880 8345 2880 2886 8346 2886 2883 8347 2883 2884 8348 2884 2886 8349 2886 2885 8350 2885 2883 8351 2883 2887 8352 2887 2885 8353 2885 2886 8354 2886 2889 8355 2889 2885 8356 2885 2887 8357 2887 2889 8358 2889 2888 8359 2888 2885 8360 2885 2891 8361 2891 2888 8362 2888 2889 8363 2889 2891 8364 2891 2890 8365 2890 2888 8366 2888 2893 8367 2893 2890 8368 2890 2891 8369 2891 2893 8370 2893 2892 8371 2892 2890 8372 2890 2877 8373 2877 2892 8374 2892 2893 8375 2893

+
+
+ + + + +5.023253 0.450059 0.000000 +5.046465 1.003900 0.000000 +51.053535 1.003900 0.000000 +51.076748 0.450059 0.000000 +8.750000 49.200001 5.300000 +8.750000 49.200001 4.700000 +8.750000 44.700001 4.700000 +8.750000 44.700001 5.300000 +7.750000 43.700001 5.300000 +7.750000 43.700001 4.700000 +2.790538 43.700001 4.700000 +2.790538 43.700001 5.300000 +48.349998 43.700001 5.300000 +53.309464 43.700001 5.300000 +53.309464 43.700001 4.700000 +48.349998 43.700001 4.700000 +47.349998 44.700001 5.300000 +47.349998 44.700001 4.700000 +47.349998 49.200001 4.700000 +47.349998 49.200001 5.300000 +0.259713 6.196556 5.300000 +1.791415 42.741875 5.300000 +1.791415 42.741875 5.000000 +0.182544 4.355361 5.000000 +55.840286 6.196556 5.300000 +55.917458 4.355361 5.000000 +54.308586 42.741875 5.000000 +54.308586 42.741875 5.300000 +9.750000 50.200001 5.300000 +46.349998 50.200001 5.300000 +46.349998 50.200001 4.700000 +9.750000 50.200001 4.700000 +8.004748 43.323372 5.700000 +0.659362 6.179806 5.700000 +55.440639 6.179806 5.700000 +2.191065 42.725124 5.700000 +53.908936 42.725124 5.700000 +53.894913 42.831337 5.700000 +53.859821 42.938961 5.700000 +53.802616 43.041759 5.700000 +53.724747 43.133057 5.700000 +53.630268 43.207031 5.700000 +53.525169 43.259884 5.700000 +53.416168 43.290436 5.700000 +53.309464 43.299999 5.700000 +48.349998 43.299999 5.700000 +48.095253 43.323372 5.700000 +47.834667 43.398296 5.700000 +47.583908 43.528206 5.700000 +47.360050 43.710049 5.700000 +47.178207 43.933907 5.700000 +47.048298 44.184666 5.700000 +2.205089 42.831337 5.700000 +2.240177 42.938961 5.700000 +2.297384 43.041759 5.700000 +2.375252 43.133057 5.700000 +9.247803 49.528324 5.700000 +9.192127 49.420856 5.700000 +9.325736 49.624264 5.700000 +9.421674 49.702198 5.700000 +9.160017 49.309177 5.700000 +9.529143 49.757874 5.700000 +9.640822 49.789982 5.700000 +9.750000 49.799999 5.700000 +9.150000 49.200001 5.700000 +46.349998 49.799999 5.700000 +9.150000 44.700001 5.700000 +9.126628 44.445251 5.700000 +9.051703 44.184666 5.700000 +8.921794 43.933907 5.700000 +8.739949 43.710049 5.700000 +8.516093 43.528206 5.700000 +46.459179 49.789982 5.700000 +46.570858 49.757874 5.700000 +46.678326 49.702198 5.700000 +46.774265 49.624264 5.700000 +46.852196 49.528324 5.700000 +46.907871 49.420856 5.700000 +46.939983 49.309177 5.700000 +46.950001 49.200001 5.700000 +46.950001 44.700001 5.700000 +46.973373 44.445251 5.700000 +8.265332 43.398296 5.700000 +2.574832 43.259884 5.700000 +2.469731 43.207031 5.700000 +2.683833 43.290436 5.700000 +2.790538 43.299999 5.700000 +7.750000 43.299999 5.700000 +51.076748 0.054904 0.462069 +52.213001 0.080789 0.614447 +55.440639 6.179806 5.700000 +0.659362 6.179806 5.700000 +55.479733 5.182741 5.619302 +0.620268 5.182741 5.619302 +55.517807 4.211632 5.379310 +0.582193 4.211632 5.379310 +55.538418 3.156280 4.912790 +0.561533 3.160928 4.915383 +55.475597 2.207526 4.260357 +0.623696 2.212476 4.264482 +55.262005 1.408141 3.458689 +0.835446 1.413960 3.465692 +54.834442 0.800510 2.582722 +1.259884 0.805736 2.591823 +54.163319 0.400089 1.743853 +1.931694 0.402007 1.748785 +53.268505 0.178704 1.057812 +2.827909 0.179248 1.059906 +3.885897 0.080844 0.614747 +5.023253 0.054904 0.462069 +47.279789 49.568096 4.700000 +47.333305 49.381962 4.700000 +55.831974 6.179806 4.700000 +0.268027 6.179806 4.700000 +54.293976 42.875301 4.700000 +1.806024 42.875301 4.700000 +1.919721 43.191608 4.700000 +2.020730 43.338276 4.700000 +2.148395 43.466583 4.700000 +2.297097 43.569778 4.700000 +2.459200 43.643513 4.700000 +2.790538 43.700001 4.700000 +7.750000 43.700001 4.700000 +7.931963 43.716694 4.700000 +8.118094 43.770210 4.700000 +8.297210 43.863003 4.700000 +8.457107 43.992893 4.700000 +8.586995 44.152790 4.700000 +54.180279 43.191608 4.700000 +54.079269 43.338276 4.700000 +53.951607 43.466583 4.700000 +53.802902 43.569778 4.700000 +8.679789 44.331905 4.700000 +53.309464 43.700001 4.700000 +53.640800 43.643513 4.700000 +48.349998 43.700001 4.700000 +48.168037 43.716694 4.700000 +47.981907 43.770210 4.700000 +47.802792 43.863003 4.700000 +47.642895 43.992893 4.700000 +47.513004 44.152790 4.700000 +47.420212 44.331905 4.700000 +47.366695 44.518036 4.700000 +8.733305 44.518036 4.700000 +47.349998 44.700001 4.700000 +8.750000 44.700001 4.700000 +47.349998 49.200001 4.700000 +8.750000 49.200001 4.700000 +8.766695 49.381962 4.700000 +8.820211 49.568096 4.700000 +8.913005 49.747211 4.700000 +9.042893 49.907108 4.700000 +9.202790 50.036995 4.700000 +9.381906 50.129787 4.700000 +9.568037 50.183304 4.700000 +9.750000 50.200001 4.700000 +46.349998 50.200001 4.700000 +46.531963 50.183304 4.700000 +46.718094 50.129787 4.700000 +46.897209 50.036995 4.700000 +47.057106 49.907108 4.700000 +47.186996 49.747211 4.700000 +5.046465 1.003900 0.000000 +3.763711 1.022794 0.167258 +0.268027 6.179806 4.700000 +55.831974 6.179806 4.700000 +0.243240 5.530174 4.659426 +55.856701 5.531764 4.659624 +0.226440 4.891818 4.537964 +55.873466 4.896859 4.539251 +0.223200 4.271011 4.336993 +55.876862 4.276671 4.339223 +0.243308 3.683472 4.061614 +55.857162 3.691009 4.065730 +0.299632 3.133417 3.714204 +55.802151 3.145339 3.722796 +0.405972 2.638300 3.307590 +55.696575 2.647053 3.315711 +0.577898 2.204028 2.851596 +55.527523 2.214464 2.863936 +0.824112 1.845109 2.372351 +55.281242 1.851149 2.381445 +1.557518 1.351116 1.429704 +54.549229 1.353812 1.436437 +2.568746 1.110474 0.658392 +53.536560 1.111172 0.661442 +52.338547 1.022872 0.167857 +51.053535 1.003900 0.000000 +1.806024 42.875301 4.700000 +1.791415 42.741875 5.000000 +2.790538 43.700001 5.300000 +2.790538 43.700001 4.700000 +2.606172 43.682858 5.300000 +2.606172 43.682858 4.700000 +2.412668 43.625858 5.300000 +2.241284 43.535656 5.300000 +2.412668 43.625858 4.700000 +2.241284 43.535656 4.700000 +2.098395 43.421761 5.300000 +2.098439 43.421803 4.700000 +1.978616 43.283768 5.300000 +1.881315 43.116310 5.300000 +1.978616 43.283768 4.700000 +1.881315 43.116310 4.700000 +1.816263 42.925362 5.300000 +1.791415 42.741875 5.300000 +1.816263 42.925362 4.700000 +53.493828 43.682858 4.700000 +53.309464 43.700001 4.700000 +54.283737 42.925362 5.300000 +54.308586 42.741875 5.300000 +54.308586 42.741875 5.000000 +54.293976 42.875301 4.700000 +54.283737 42.925362 4.700000 +54.218685 43.116310 5.300000 +54.121384 43.283768 5.300000 +54.218685 43.116310 4.700000 +54.121384 43.283768 4.700000 +54.001606 43.421761 5.300000 +53.858715 43.535656 5.300000 +54.001560 43.421803 4.700000 +53.687332 43.625858 5.300000 +53.858715 43.535656 4.700000 +53.687332 43.625858 4.700000 +53.493828 43.682858 5.300000 +53.309464 43.700001 5.300000 +46.554909 50.178780 4.700000 +47.328781 49.404911 5.300000 +47.349998 49.200001 5.300000 +47.349998 49.200001 4.700000 +47.267742 49.597176 5.300000 +47.328781 49.404911 4.700000 +47.173969 49.766636 5.300000 +47.267742 49.597176 4.700000 +47.173969 49.766636 4.700000 +47.057106 49.907108 5.300000 +46.916634 50.023968 5.300000 +47.057106 49.907108 4.700000 +46.916634 50.023968 4.700000 +46.747177 50.117741 5.300000 +46.554909 50.178780 5.300000 +46.747177 50.117741 4.700000 +46.349998 50.200001 4.700000 +46.349998 50.200001 5.300000 +48.145092 43.721218 5.300000 +48.349998 43.700001 5.300000 +47.349998 44.700001 4.700000 +47.349998 44.700001 5.300000 +47.371220 44.495090 4.700000 +47.371220 44.495090 5.300000 +47.432259 44.302822 4.700000 +47.526031 44.133366 4.700000 +47.432259 44.302822 5.300000 +47.526031 44.133366 5.300000 +47.642895 43.992893 4.700000 +47.783367 43.876030 4.700000 +47.642895 43.992893 5.300000 +47.783367 43.876030 5.300000 +47.952824 43.782257 4.700000 +48.145092 43.721218 4.700000 +47.952824 43.782257 5.300000 +48.349998 43.700001 4.700000 +8.750000 49.200001 4.700000 +8.750000 49.200001 5.300000 +9.750000 50.200001 5.300000 +9.750000 50.200001 4.700000 +9.545091 50.178780 5.300000 +9.545091 50.178780 4.700000 +9.352822 50.117741 5.300000 +9.183366 50.023968 5.300000 +9.352822 50.117741 4.700000 +9.183366 50.023968 4.700000 +9.042893 49.907108 5.300000 +8.926031 49.766636 5.300000 +9.042893 49.907108 4.700000 +8.926031 49.766636 4.700000 +8.832258 49.597176 5.300000 +8.832258 49.597176 4.700000 +8.771219 49.404911 5.300000 +8.771219 49.404911 4.700000 +7.750000 43.700001 4.700000 +7.750000 43.700001 5.300000 +8.728781 44.495090 5.300000 +8.750000 44.700001 5.300000 +8.750000 44.700001 4.700000 +8.667742 44.302822 5.300000 +8.728781 44.495090 4.700000 +8.667742 44.302822 4.700000 +8.573969 44.133366 5.300000 +8.573969 44.133366 4.700000 +8.457107 43.992893 5.300000 +8.457107 43.992893 4.700000 +8.316634 43.876030 5.300000 +8.316634 43.876030 4.700000 +8.147178 43.782257 5.300000 +7.954909 43.721218 5.300000 +8.147178 43.782257 4.700000 +7.954909 43.721218 4.700000 +51.663212 0.456991 0.034366 +51.076748 0.450059 0.000000 +55.831974 6.179806 4.700000 +54.293976 42.875301 4.700000 +54.308586 42.741875 5.000000 +55.917458 4.355361 5.000000 +55.873466 4.896859 4.539251 +55.857162 3.691009 4.065730 +55.934925 3.299550 4.483398 +55.696575 2.647053 3.315711 +55.845245 2.374723 3.764354 +55.281242 1.851149 2.381445 +55.570770 1.624912 2.903586 +54.956322 1.566730 1.899902 +55.055389 1.082298 2.002173 +54.549229 1.353812 1.436437 +54.704544 0.888986 1.575214 +54.073853 1.206846 1.019759 +54.297115 0.742141 1.183121 +53.536560 1.111172 0.661442 +53.835320 0.633685 0.833326 +52.956234 1.054184 0.376358 +53.335548 0.558223 0.540595 +52.338547 1.022872 0.167857 +52.800880 0.507394 0.306994 +51.702747 1.007968 0.042092 +52.238148 0.475134 0.136762 +51.053535 1.003900 0.000000 +5.046465 1.003900 0.000000 +5.023253 0.450059 0.000000 +1.791415 42.741875 5.000000 +1.806024 42.875301 4.700000 +0.182544 4.355361 5.000000 +0.164964 3.304383 4.486423 +0.268027 6.179806 4.700000 +0.226440 4.891818 4.537964 +0.253774 2.379621 3.769007 +0.243308 3.683472 4.061614 +0.526357 1.629719 2.910249 +0.405972 2.638300 3.307590 +1.036925 1.087554 2.012745 +0.824112 1.845109 2.372351 +1.389434 0.891783 1.581834 +1.153650 1.560033 1.886985 +1.797200 0.743799 1.187994 +1.557518 1.351116 1.429704 +2.258617 0.634826 0.837382 +2.034219 1.204962 1.013582 +2.761022 0.558634 0.542342 +2.568746 1.110474 0.658392 +3.298228 0.507441 0.307541 +3.146728 1.053976 0.375137 +3.860602 0.475187 0.137062 +3.763711 1.022794 0.167258 +4.436124 0.457005 0.034444 +4.398077 1.007959 0.041985 +47.031963 49.200001 5.691513 +46.950001 49.200001 5.700000 +47.341511 44.700001 5.381964 +47.349998 44.700001 5.300000 +47.349998 49.200001 5.300000 +47.341511 49.200001 5.381964 +47.317097 44.700001 5.458871 +47.317097 49.200001 5.458871 +47.279587 44.700001 5.526654 +47.279587 49.200001 5.526654 +47.232841 44.700001 5.582843 +47.176655 44.700001 5.629588 +47.232841 49.200001 5.582843 +47.108871 44.700001 5.667097 +47.176655 49.200001 5.629588 +47.108871 49.200001 5.667097 +47.031963 44.700001 5.691513 +46.950001 44.700001 5.700000 +48.095253 43.323372 5.700000 +48.349998 43.299999 5.700000 +48.349998 43.381966 5.691513 +48.349998 43.458870 5.667097 +48.349998 43.526653 5.629588 +48.349998 43.582844 5.582843 +48.349998 43.629589 5.526654 +48.349998 43.667095 5.458871 +48.349998 43.691513 5.381964 +48.349998 43.700001 5.300000 +48.145092 43.721218 5.300000 +47.952824 43.782257 5.300000 +47.783367 43.876030 5.300000 +47.642895 43.992893 5.300000 +47.526031 44.133366 5.300000 +47.432259 44.302822 5.300000 +47.371220 44.495090 5.300000 +47.349998 44.700001 5.300000 +47.341511 44.700001 5.381964 +47.317097 44.700001 5.458871 +47.279587 44.700001 5.526654 +47.232841 44.700001 5.582843 +47.176655 44.700001 5.629588 +47.108871 44.700001 5.667097 +47.031963 44.700001 5.691513 +46.950001 44.700001 5.700000 +46.973373 44.445251 5.700000 +47.048298 44.184666 5.700000 +47.178207 43.933907 5.700000 +47.263107 43.817581 5.700000 +47.360050 43.710049 5.700000 +47.467583 43.613106 5.700000 +47.583908 43.528206 5.700000 +47.834667 43.398296 5.700000 +48.095680 43.485207 5.667097 +48.079922 43.409931 5.691513 +48.109570 43.551552 5.629588 +48.121082 43.606548 5.582843 +48.130661 43.652302 5.526654 +48.138348 43.689014 5.458871 +48.143353 43.712910 5.381964 +47.949451 43.774467 5.381964 +47.778557 43.869038 5.381964 +47.636890 43.986893 5.381964 +47.519039 44.128555 5.381964 +47.424469 44.299450 5.381964 +47.362911 44.493351 5.381964 +47.339012 44.488350 5.458871 +47.302299 44.480663 5.526654 +47.256546 44.471085 5.582843 +47.201550 44.459572 5.629588 +47.135208 44.445683 5.667097 +47.059933 44.429920 5.691513 +47.140385 44.176506 5.691513 +47.263977 43.953156 5.691513 +47.418007 43.768009 5.691513 +47.603153 43.613979 5.691513 +47.826508 43.490383 5.691513 +47.939754 43.752060 5.458871 +47.764721 43.848919 5.458871 +47.619629 43.969627 5.458871 +47.924858 43.717636 5.526654 +47.906292 43.674740 5.582843 +47.743469 43.818012 5.526654 +47.593105 43.943104 5.526654 +47.716980 43.779495 5.582843 +47.560051 43.910049 5.582843 +47.883972 43.623173 5.629588 +47.857052 43.560963 5.667097 +47.685143 43.733200 5.629588 +47.520317 43.870319 5.629588 +47.646732 43.677349 5.667097 +47.472389 43.822388 5.667097 +47.498920 44.114719 5.458871 +47.402061 44.289753 5.458871 +47.468014 44.093468 5.526654 +47.367638 44.274857 5.526654 +47.429497 44.066978 5.582843 +47.324738 44.256290 5.582843 +47.383198 44.035141 5.629588 +47.273170 44.233974 5.629588 +47.327347 43.996735 5.667097 +47.210964 44.207050 5.667097 +46.728180 49.665813 5.700000 +46.678326 49.702198 5.700000 +46.570858 49.757874 5.700000 +46.459179 49.789982 5.700000 +46.349998 49.881966 5.691513 +46.349998 49.799999 5.700000 +46.349998 49.958870 5.667097 +46.554909 50.178780 5.300000 +46.349998 50.200001 5.300000 +47.343323 49.200001 5.372785 +47.349998 49.200001 5.300000 +46.939983 49.309177 5.700000 +46.950001 49.200001 5.700000 +46.774265 49.624264 5.700000 +46.815811 49.578178 5.700000 +46.852196 49.528324 5.700000 +46.907871 49.420856 5.700000 +47.022785 49.200001 5.693322 +47.097237 49.200001 5.671916 +47.168884 49.200001 5.634798 +47.202118 49.200001 5.610541 +47.232841 49.200001 5.582843 +47.260540 49.200001 5.552119 +47.284798 49.200001 5.518884 +47.321915 49.200001 5.447238 +47.328781 49.404911 5.300000 +47.267742 49.597176 5.300000 +47.173969 49.766636 5.300000 +47.057106 49.907108 5.300000 +46.916634 50.023968 5.300000 +46.747177 50.117741 5.300000 +46.349998 50.191513 5.381964 +46.349998 50.167095 5.458871 +46.349998 50.129589 5.526654 +46.349998 50.082844 5.582843 +46.349998 50.026653 5.629588 +46.519390 50.009113 5.629588 +46.505501 49.942768 5.667097 +46.832222 49.682220 5.691513 +46.736423 49.761917 5.691513 +46.620861 49.825867 5.691513 +46.489742 49.867493 5.691513 +46.911919 49.586426 5.691513 +46.975868 49.470860 5.691513 +47.017494 49.339741 5.691513 +47.092770 49.355499 5.667097 +47.159115 49.369389 5.629588 +47.214111 49.380901 5.582843 +47.259861 49.390480 5.526654 +47.296577 49.398167 5.458871 +47.320473 49.403172 5.381964 +47.259953 49.593807 5.381964 +47.166977 49.761826 5.381964 +47.051105 49.901104 5.381964 +46.911827 50.016975 5.381964 +46.743805 50.109951 5.381964 +46.553169 50.170475 5.381964 +46.548168 50.146576 5.458871 +46.540482 50.109863 5.526654 +46.530903 50.064110 5.582843 +46.651405 49.896446 5.667097 +46.780003 49.825287 5.667097 +46.886604 49.736603 5.667097 +46.678329 49.958656 5.629588 +46.700645 50.010223 5.582843 +46.818409 49.881138 5.629588 +46.934532 49.784531 5.629588 +46.850250 49.927437 5.582843 +46.974262 49.824265 5.582843 +46.719212 50.053120 5.526654 +46.734108 50.087543 5.458871 +46.876736 49.965950 5.526654 +47.007317 49.857319 5.526654 +46.897991 49.996857 5.458871 +47.033840 49.883842 5.458871 +46.975285 49.630001 5.667097 +47.046448 49.501408 5.667097 +47.031136 49.668411 5.629588 +47.108654 49.528328 5.629588 +47.077435 49.700249 5.582843 +47.160221 49.550644 5.582843 +47.115952 49.726738 5.526654 +47.203121 49.569210 5.526654 +47.146858 49.747990 5.458871 +47.237545 49.584110 5.458871 +53.309464 43.458870 5.667097 +48.349998 43.299999 5.700000 +53.309464 43.299999 5.700000 +48.349998 43.381966 5.691513 +53.309464 43.381966 5.691513 +48.349998 43.458870 5.667097 +53.309464 43.700001 5.300000 +48.349998 43.700001 5.300000 +53.309464 43.691513 5.381964 +48.349998 43.691513 5.381964 +53.309464 43.667095 5.458871 +53.309464 43.629589 5.526654 +48.349998 43.667095 5.458871 +48.349998 43.629589 5.526654 +53.309464 43.582844 5.582843 +53.309464 43.526653 5.629588 +48.349998 43.582844 5.582843 +48.349998 43.526653 5.629588 +46.349998 50.129589 5.526654 +46.349998 50.200001 5.300000 +9.750000 50.200001 5.300000 +46.349998 50.191513 5.381964 +9.750000 50.191513 5.381964 +46.349998 50.167095 5.458871 +9.750000 49.799999 5.700000 +46.349998 49.799999 5.700000 +9.750000 49.881966 5.691513 +46.349998 49.881966 5.691513 +9.750000 49.958870 5.667097 +46.349998 49.958870 5.667097 +9.750000 50.026653 5.629588 +9.750000 50.082844 5.582843 +46.349998 50.026653 5.629588 +46.349998 50.082844 5.582843 +9.750000 50.129589 5.526654 +9.750000 50.167095 5.458871 +53.493828 43.682858 5.300000 +53.309464 43.700001 5.300000 +53.309464 43.610542 5.552119 +53.309464 43.634800 5.518884 +53.309464 43.671917 5.447238 +53.309464 43.693321 5.372785 +53.894913 42.831337 5.700000 +53.908936 42.725124 5.700000 +53.309464 43.372784 5.693322 +53.309464 43.299999 5.700000 +53.309464 43.582844 5.582843 +53.309464 43.552120 5.610541 +53.309464 43.518883 5.634798 +53.309464 43.447239 5.671916 +53.416168 43.290436 5.700000 +53.525169 43.259884 5.700000 +53.630268 43.207031 5.700000 +53.724747 43.133057 5.700000 +53.802616 43.041759 5.700000 +53.859821 42.938961 5.700000 +53.990826 42.728558 5.691513 +54.067669 42.731777 5.667097 +54.135391 42.734615 5.629588 +54.191528 42.736969 5.582843 +54.238235 42.738926 5.526654 +54.275711 42.740498 5.458871 +54.300106 42.741520 5.381964 +54.308586 42.741875 5.300000 +54.283737 42.925362 5.300000 +54.218685 43.116310 5.300000 +54.121384 43.283768 5.300000 +54.001606 43.421761 5.300000 +53.858715 43.535656 5.300000 +53.687332 43.625858 5.300000 +53.480846 43.613651 5.526654 +53.472229 43.567707 5.582843 +53.487762 43.650517 5.458871 +53.492264 43.674515 5.381964 +53.461868 43.512482 5.629588 +53.449371 43.445862 5.667097 +53.435192 43.370274 5.691513 +53.567154 43.331402 5.691513 +53.684032 43.269886 5.691513 +53.781479 43.192215 5.691513 +53.863163 43.098106 5.691513 +53.929520 42.983910 5.691513 +53.973881 42.853687 5.691513 +54.048809 42.871021 5.667097 +54.114849 42.886295 5.629588 +54.169594 42.898960 5.582843 +54.215137 42.909492 5.526654 +54.251678 42.917946 5.458871 +54.275467 42.923450 5.381964 +54.210968 43.112778 5.381964 +54.114491 43.278812 5.381964 +53.995731 43.415634 5.381964 +53.854053 43.528561 5.381964 +53.684124 43.618000 5.381964 +53.596218 43.402607 5.667097 +53.726276 43.334156 5.667097 +53.834709 43.247723 5.667097 +53.621830 43.465363 5.629588 +53.643063 43.517387 5.582843 +53.763504 43.390797 5.629588 +53.881626 43.296646 5.629588 +53.794369 43.437752 5.582843 +53.920517 43.337200 5.582843 +53.660725 43.560665 5.526654 +53.674900 43.595394 5.458871 +53.820042 43.476814 5.526654 +53.952869 43.370941 5.526654 +53.840645 43.508160 5.458871 +53.978832 43.398010 5.458871 +53.925606 43.143002 5.667097 +53.999443 43.015926 5.667097 +53.980640 43.182571 5.629588 +54.061073 43.044144 5.629588 +54.026260 43.215374 5.582843 +54.112164 43.067535 5.582843 +54.064213 43.242661 5.526654 +54.154663 43.086998 5.526654 +54.094669 43.264557 5.458871 +54.188766 43.102612 5.458871 +9.284188 49.578178 5.700000 +9.247803 49.528324 5.700000 +9.192127 49.420856 5.700000 +9.160017 49.309177 5.700000 +9.077215 49.200001 5.693322 +9.150000 49.200001 5.700000 +9.002762 49.200001 5.671916 +8.931116 49.200001 5.634798 +8.897881 49.200001 5.610541 +8.867157 49.200001 5.582843 +8.839458 49.200001 5.552119 +8.815202 49.200001 5.518884 +8.778085 49.200001 5.447238 +8.756678 49.200001 5.372785 +8.771219 49.404911 5.300000 +8.750000 49.200001 5.300000 +8.832258 49.597176 5.300000 +8.926031 49.766636 5.300000 +9.042893 49.907108 5.300000 +9.183366 50.023968 5.300000 +9.352822 50.117741 5.300000 +9.545091 50.178780 5.300000 +9.750000 50.191513 5.381964 +9.750000 50.200001 5.300000 +9.750000 50.167095 5.458871 +9.750000 50.129589 5.526654 +9.750000 50.082844 5.582843 +9.750000 50.026653 5.629588 +9.640822 49.789982 5.700000 +9.750000 49.799999 5.700000 +9.325736 49.624264 5.700000 +9.371821 49.665813 5.700000 +9.421674 49.702198 5.700000 +9.529143 49.757874 5.700000 +9.750000 49.881966 5.691513 +9.750000 49.958870 5.667097 +9.594501 49.942768 5.667097 +9.580611 50.009113 5.629588 +9.267778 49.682220 5.691513 +9.188083 49.586426 5.691513 +9.124133 49.470860 5.691513 +9.082507 49.339741 5.691513 +9.007232 49.355499 5.667097 +8.940887 49.369389 5.629588 +8.885890 49.380901 5.582843 +8.840137 49.390480 5.526654 +8.803424 49.398167 5.458871 +8.779527 49.403172 5.381964 +8.840048 49.593807 5.381964 +8.933024 49.761826 5.381964 +9.048895 49.901104 5.381964 +9.188175 50.016975 5.381964 +9.356194 50.109951 5.381964 +9.546830 50.170475 5.381964 +9.551833 50.146576 5.458871 +9.559519 50.109863 5.526654 +9.569098 50.064110 5.582843 +9.363576 49.761917 5.691513 +9.479139 49.825867 5.691513 +9.610259 49.867493 5.691513 +9.053553 49.501408 5.667097 +9.124714 49.630001 5.667097 +9.213397 49.736603 5.667097 +8.991345 49.528328 5.629588 +8.939778 49.550644 5.582843 +9.068863 49.668411 5.629588 +9.165467 49.784531 5.629588 +9.022565 49.700249 5.582843 +9.125736 49.824265 5.582843 +8.896878 49.569210 5.526654 +8.862454 49.584110 5.458871 +8.984049 49.726738 5.526654 +9.092682 49.857319 5.526654 +8.953142 49.747990 5.458871 +9.066159 49.883842 5.458871 +9.319998 49.825287 5.667097 +9.448594 49.896446 5.667097 +9.281590 49.881138 5.629588 +9.421672 49.958656 5.629588 +9.249751 49.927437 5.582843 +9.399355 50.010223 5.582843 +9.223264 49.965950 5.526654 +9.380789 50.053120 5.526654 +9.202009 49.996857 5.458871 +9.365891 50.087543 5.458871 +54.300106 42.741520 5.381964 +55.831806 6.196201 5.381964 +55.840286 6.196556 5.300000 +54.308586 42.741875 5.300000 +53.908936 42.725124 5.700000 +55.440639 6.179806 5.700000 +53.990826 42.728558 5.691513 +55.522530 6.183238 5.691513 +54.067669 42.731777 5.667097 +55.599369 6.186459 5.667097 +54.135391 42.734615 5.629588 +54.191528 42.736969 5.582843 +55.667091 6.189297 5.629588 +55.723232 6.191650 5.582843 +54.238235 42.738926 5.526654 +55.769936 6.193607 5.526654 +54.275711 42.740498 5.458871 +55.807411 6.195178 5.458871 +9.068036 44.700001 5.691513 +9.150000 44.700001 5.700000 +8.758488 49.200001 5.381964 +8.750000 49.200001 5.300000 +8.750000 44.700001 5.300000 +8.758488 44.700001 5.381964 +8.782904 49.200001 5.458871 +8.782904 44.700001 5.458871 +8.820413 49.200001 5.526654 +8.820413 44.700001 5.526654 +8.867157 49.200001 5.582843 +8.867157 44.700001 5.582843 +8.923347 49.200001 5.629588 +8.923347 44.700001 5.629588 +8.991129 49.200001 5.667097 +8.991129 44.700001 5.667097 +9.068036 49.200001 5.691513 +9.150000 49.200001 5.700000 +55.440639 6.179806 5.700000 +55.517807 4.211632 5.379310 +55.911663 4.331846 5.069518 +55.917458 4.355361 5.000000 +55.840286 6.196556 5.300000 +55.833614 6.196277 5.372785 +55.890938 4.307161 5.140660 +55.812229 6.195380 5.447238 +55.854206 4.282719 5.209076 +55.775143 6.193826 5.518884 +55.802299 4.260144 5.270014 +55.723232 6.191650 5.582843 +55.738094 4.240961 5.319277 +55.659328 6.188972 5.634798 +55.666008 4.226269 5.354140 +55.587746 6.185972 5.671916 +55.591053 4.216543 5.373811 +55.513359 6.182854 5.693322 +9.126628 44.445251 5.700000 +9.150000 44.700001 5.700000 +8.782904 44.700001 5.458871 +8.820413 44.700001 5.526654 +8.867157 44.700001 5.582843 +8.758488 44.700001 5.381964 +8.750000 44.700001 5.300000 +8.728781 44.495090 5.300000 +8.667742 44.302822 5.300000 +8.573969 44.133366 5.300000 +8.457107 43.992893 5.300000 +8.316634 43.876030 5.300000 +8.147178 43.782257 5.300000 +7.954909 43.721218 5.300000 +7.750000 43.700001 5.300000 +7.750000 43.691513 5.381964 +7.750000 43.667095 5.458871 +7.750000 43.629589 5.526654 +7.750000 43.582844 5.582843 +7.750000 43.526653 5.629588 +7.750000 43.458870 5.667097 +7.750000 43.381966 5.691513 +7.750000 43.299999 5.700000 +8.004748 43.323372 5.700000 +8.265332 43.398296 5.700000 +8.516093 43.528206 5.700000 +8.632418 43.613106 5.700000 +8.739949 43.710049 5.700000 +8.836894 43.817581 5.700000 +8.921794 43.933907 5.700000 +9.051703 44.184666 5.700000 +8.923347 44.700001 5.629588 +8.991129 44.700001 5.667097 +9.068036 44.700001 5.691513 +8.760986 44.488350 5.458871 +8.737088 44.493351 5.381964 +8.797699 44.480663 5.526654 +8.843452 44.471085 5.582843 +8.675531 44.299450 5.381964 +8.580963 44.128555 5.381964 +8.463108 43.986893 5.381964 +8.321444 43.869038 5.381964 +8.150548 43.774467 5.381964 +7.956649 43.712910 5.381964 +7.961652 43.689014 5.458871 +7.969337 43.652302 5.526654 +7.978916 43.606548 5.582843 +7.990430 43.551552 5.629588 +8.004319 43.485207 5.667097 +8.020078 43.409931 5.691513 +8.273494 43.490383 5.691513 +8.496845 43.613979 5.691513 +8.681993 43.768009 5.691513 +8.836021 43.953156 5.691513 +8.959617 44.176506 5.691513 +9.040069 44.429920 5.691513 +8.898449 44.459572 5.629588 +8.964793 44.445683 5.667097 +8.697939 44.289753 5.458871 +8.601081 44.114719 5.458871 +8.480372 43.969627 5.458871 +8.732362 44.274857 5.526654 +8.775262 44.256290 5.582843 +8.631987 44.093468 5.526654 +8.506896 43.943104 5.526654 +8.670504 44.066978 5.582843 +8.539949 43.910049 5.582843 +8.826829 44.233974 5.629588 +8.889036 44.207050 5.667097 +8.716801 44.035141 5.629588 +8.579681 43.870319 5.629588 +8.772652 43.996735 5.667097 +8.627611 43.822388 5.667097 +8.335279 43.848919 5.458871 +8.160246 43.752060 5.458871 +8.356533 43.818012 5.526654 +8.175143 43.717636 5.526654 +8.383020 43.779495 5.582843 +8.193709 43.674740 5.582843 +8.414859 43.733200 5.629588 +8.216026 43.623173 5.629588 +8.453267 43.677349 5.667097 +8.242949 43.560963 5.667097 +51.076748 0.290404 0.033243 +52.213001 0.080789 0.614447 +51.076748 0.054904 0.462069 +51.076748 0.213110 0.077734 +51.076748 0.146063 0.140027 +51.076748 0.094929 0.215928 +51.076748 0.062971 0.299190 +51.076748 0.050416 0.383109 +53.268505 0.178704 1.057812 +54.163319 0.400089 1.743853 +54.834442 0.800510 2.582722 +55.262005 1.408141 3.458689 +55.475597 2.207526 4.260357 +55.538418 3.156280 4.912790 +55.517807 4.211632 5.379310 +55.591053 4.216543 5.373811 +55.666008 4.226269 5.354140 +55.738094 4.240961 5.319277 +55.802299 4.260144 5.270014 +55.854206 4.282719 5.209076 +55.890938 4.307161 5.140660 +55.911663 4.331846 5.069518 +55.917458 4.355361 5.000000 +55.934925 3.299550 4.483398 +55.845245 2.374723 3.764354 +55.570770 1.624912 2.903586 +55.055389 1.082298 2.002173 +54.297115 0.742141 1.183121 +53.335548 0.558223 0.540595 +52.238148 0.475134 0.136762 +51.076748 0.450059 0.000000 +51.076748 0.371359 0.007819 +52.263725 0.314296 0.176487 +52.256290 0.235651 0.221082 +52.244019 0.167570 0.283502 +52.227718 0.116025 0.359392 +52.208820 0.084400 0.442289 +52.188999 0.072823 0.525335 +53.237740 0.159102 0.946322 +54.150589 0.361155 1.615986 +54.856689 0.743089 2.461797 +55.317829 1.347170 3.370054 +55.548889 2.160408 4.209879 +55.614952 3.133355 4.891364 +55.693844 3.144397 4.869908 +55.769360 3.164304 4.832841 +55.835506 3.192583 4.781178 +55.887074 3.227462 4.718184 +55.920921 3.266234 4.648726 +55.936562 3.305910 4.578108 +55.865852 2.385173 3.884476 +55.618481 1.615639 3.030733 +55.124084 1.042839 2.109092 +54.366909 0.678387 1.252627 +53.388813 0.482817 0.575838 +52.266319 0.396568 0.151027 +53.385506 0.398571 0.603436 +53.372047 0.318054 0.649492 +53.348282 0.248888 0.712380 +53.315834 0.197600 0.787349 +53.277775 0.167730 0.867628 +54.364979 0.593626 1.286576 +54.347458 0.512643 1.336729 +54.313789 0.443668 1.400632 +55.123280 0.962223 2.154320 +55.102615 0.885094 2.211474 +55.061207 0.819512 2.276710 +54.266361 0.393714 1.472950 +54.210030 0.366394 1.546849 +55.002041 0.772349 2.344137 +54.931366 0.747091 2.407459 +55.615288 1.545526 3.088651 +55.590614 1.478148 3.153115 +55.543751 1.420237 3.218979 +55.856770 2.329814 3.951310 +55.827221 2.276225 4.020014 +55.777100 2.229189 4.084982 +55.478012 1.377598 3.280202 +55.400059 1.353333 3.331566 +55.709751 2.192925 4.140609 +55.631290 2.169920 4.182796 +2.790538 43.299999 5.700000 +7.750000 43.299999 5.700000 +7.750000 43.700001 5.300000 +2.790538 43.700001 5.300000 +7.750000 43.691513 5.381964 +7.750000 43.667095 5.458871 +2.790538 43.691513 5.381964 +7.750000 43.629589 5.526654 +2.790538 43.667095 5.458871 +2.790538 43.629589 5.526654 +7.750000 43.582844 5.582843 +2.790538 43.582844 5.582843 +7.750000 43.526653 5.629588 +2.790538 43.526653 5.629588 +7.750000 43.458870 5.667097 +7.750000 43.381966 5.691513 +2.790538 43.458870 5.667097 +2.790538 43.381966 5.691513 +5.023253 0.198443 0.089051 +51.076748 0.051272 0.431129 +51.076748 0.054904 0.462069 +5.023253 0.054904 0.462069 +51.076748 0.053355 0.348753 +5.023253 0.051272 0.431129 +5.023253 0.053355 0.348753 +51.076748 0.071712 0.270179 +5.023253 0.071712 0.270179 +51.076748 0.103832 0.199683 +5.023253 0.103832 0.199683 +51.076748 0.146063 0.140027 +51.076748 0.198443 0.089051 +5.023253 0.146063 0.140027 +5.023253 0.450059 0.000000 +51.076748 0.450059 0.000000 +5.023253 0.418930 0.001213 +51.076748 0.418930 0.001213 +5.023253 0.337875 0.016054 +5.023253 0.263101 0.046380 +51.076748 0.337875 0.016054 +51.076748 0.263101 0.046380 +2.683833 43.290436 5.700000 +2.790538 43.299999 5.700000 +1.880796 42.738129 5.552119 +1.856560 42.739147 5.518884 +1.819475 42.740700 5.447238 +1.798087 42.741596 5.372785 +1.816263 42.925362 5.300000 +1.791415 42.741875 5.300000 +1.881315 43.116310 5.300000 +1.978616 43.283768 5.300000 +2.098395 43.421761 5.300000 +2.241284 43.535656 5.300000 +2.118343 42.728172 5.693322 +2.191065 42.725124 5.700000 +1.908470 42.736969 5.582843 +1.939166 42.735683 5.610541 +1.972373 42.734291 5.634798 +2.043956 42.731293 5.671916 +2.205089 42.831337 5.700000 +2.240177 42.938961 5.700000 +2.297384 43.041759 5.700000 +2.375252 43.133057 5.700000 +2.469731 43.207031 5.700000 +2.574832 43.259884 5.700000 +2.412668 43.625858 5.300000 +2.606172 43.682858 5.300000 +2.790538 43.700001 5.300000 +2.790538 43.693321 5.372785 +2.790538 43.671917 5.447238 +2.790538 43.634800 5.518884 +2.790538 43.610542 5.552119 +2.790538 43.582844 5.582843 +2.790538 43.552120 5.610541 +2.790538 43.518883 5.634798 +2.790538 43.447239 5.671916 +2.790538 43.372784 5.693322 +1.930407 42.898960 5.582843 +1.884864 42.909492 5.526654 +1.848320 42.917946 5.458871 +1.824533 42.923450 5.381964 +1.889033 43.112778 5.381964 +1.985508 43.278812 5.381964 +2.104270 43.415634 5.381964 +2.245946 43.528561 5.381964 +1.985150 42.886295 5.629588 +2.051189 42.871021 5.667097 +2.126118 42.853687 5.691513 +2.170481 42.983910 5.691513 +2.236837 43.098106 5.691513 +2.318521 43.192215 5.691513 +2.415967 43.269886 5.691513 +2.532844 43.331402 5.691513 +2.664807 43.370274 5.691513 +2.415875 43.618000 5.381964 +2.607737 43.674515 5.381964 +2.612238 43.650517 5.458871 +2.619153 43.613651 5.526654 +2.627772 43.567707 5.582843 +2.638131 43.512482 5.629588 +2.650628 43.445862 5.667097 +2.100555 43.015926 5.667097 +2.174394 43.143002 5.667097 +2.265291 43.247723 5.667097 +2.038926 43.044144 5.629588 +1.987838 43.067535 5.582843 +2.119360 43.182571 5.629588 +2.218375 43.296646 5.629588 +2.073739 43.215374 5.582843 +2.179485 43.337200 5.582843 +1.945336 43.086998 5.526654 +1.911232 43.102612 5.458871 +2.035786 43.242661 5.526654 +2.147130 43.370941 5.526654 +2.005331 43.264557 5.458871 +2.121169 43.398010 5.458871 +2.373725 43.334156 5.667097 +2.503783 43.402607 5.667097 +2.336495 43.390797 5.629588 +2.478170 43.465363 5.629588 +2.305633 43.437752 5.582843 +2.456938 43.517387 5.582843 +2.279958 43.476814 5.526654 +2.439274 43.560665 5.526654 +2.259356 43.508160 5.458871 +2.425101 43.595394 5.458871 +2.827909 0.179248 1.059906 +0.209063 4.307161 5.140660 +0.245796 4.282719 5.209076 +5.023253 0.050416 0.383109 +5.023253 0.054904 0.462069 +0.188338 4.331846 5.069518 +0.182544 4.355361 5.000000 +0.164964 3.304383 4.486423 +0.253774 2.379621 3.769007 +0.526357 1.629719 2.910249 +1.036925 1.087554 2.012745 +1.797200 0.743799 1.187994 +2.761022 0.558634 0.542342 +3.860602 0.475187 0.137062 +5.023253 0.450059 0.000000 +5.023253 0.371359 0.007819 +5.023253 0.290404 0.033243 +5.023253 0.213110 0.077734 +5.023253 0.146063 0.140027 +5.023253 0.094929 0.215928 +5.023253 0.062971 0.299190 +3.885897 0.080844 0.614747 +0.297701 4.260144 5.270014 +0.361906 4.240961 5.319277 +0.433990 4.226269 5.354140 +0.508947 4.216543 5.373811 +0.582193 4.211632 5.379310 +0.561533 3.160928 4.915383 +0.623696 2.212476 4.264482 +0.835446 1.413960 3.465692 +1.259884 0.805736 2.591823 +1.931694 0.402007 1.748785 +1.943971 0.363032 1.621130 +0.179061 3.270903 4.651530 +0.163393 3.310507 4.580903 +0.212924 3.232200 4.720984 +0.233317 2.390086 3.888985 +0.478640 1.621041 3.037964 +0.968524 1.048342 2.119837 +1.727260 0.680189 1.257831 +2.707305 0.483295 0.577878 +3.832288 0.396627 0.151369 +3.834882 0.314353 0.176829 +3.842329 0.235706 0.221426 +3.854613 0.167624 0.283846 +3.870933 0.116079 0.359735 +3.889853 0.084455 0.442631 +3.909698 0.072881 0.525674 +2.858635 0.159590 0.948343 +0.264495 3.197378 4.783969 +0.330633 3.169140 4.835617 +0.406133 3.149253 4.872668 +0.485003 3.138210 4.894109 +0.550333 2.165601 4.214311 +0.779483 1.352876 3.377173 +1.236417 0.748879 2.472396 +0.242436 2.334817 3.955854 +0.272015 2.281312 4.024571 +0.322148 2.234344 4.089530 +0.389494 2.198123 4.145130 +0.467946 2.175129 4.187275 +0.481868 1.551034 3.095974 +0.506578 1.483755 3.160486 +0.553476 1.425920 3.226349 +0.969335 0.967813 2.165217 +0.990036 0.890765 2.222463 +1.031522 0.825248 2.287713 +0.619246 1.383324 3.287523 +0.697229 1.359066 3.338799 +1.090799 0.778127 2.355071 +1.161603 0.752886 2.418251 +1.729176 0.595436 1.291839 +1.746718 0.514461 1.342031 +1.780447 0.445497 1.405942 +2.710612 0.399043 0.605491 +2.724089 0.318520 0.651556 +2.747894 0.249351 0.714447 +1.827965 0.395556 1.478235 +1.884409 0.368252 1.552076 +2.780400 0.198066 0.789409 +2.818527 0.168205 0.869673 +1.791415 42.741875 5.300000 +0.259713 6.196556 5.300000 +0.659362 6.179806 5.700000 +2.191065 42.725124 5.700000 +0.577470 6.183238 5.691513 +2.109173 42.728558 5.691513 +0.500630 6.186459 5.667097 +2.032333 42.731777 5.667097 +0.432907 6.189297 5.629588 +1.964610 42.734615 5.629588 +0.376767 6.191650 5.582843 +1.908470 42.736969 5.582843 +0.330063 6.193607 5.526654 +1.861766 42.738926 5.526654 +0.292587 6.195178 5.458871 +1.824290 42.740498 5.458871 +0.268193 6.196201 5.381964 +1.799896 42.741520 5.381964 +0.259713 6.196556 5.300000 +0.182544 4.355361 5.000000 +0.582193 4.211632 5.379310 +0.659362 6.179806 5.700000 +0.508947 4.216543 5.373811 +0.586640 6.182854 5.693322 +0.433990 4.226269 5.354140 +0.361906 4.240961 5.319277 +0.512253 6.185972 5.671916 +0.440670 6.188972 5.634798 +0.297701 4.260144 5.270014 +0.245796 4.282719 5.209076 +0.376767 6.191650 5.582843 +0.209063 4.307161 5.140660 +0.324857 6.193826 5.518884 +0.287773 6.195380 5.447238 +0.188338 4.331846 5.069518 +0.266385 6.196277 5.372785 + + + + + + + + + + + +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.999123 0.041876 0.000000 +-0.999123 0.041876 0.000000 +-0.999123 0.041876 0.000000 +-0.999123 0.041876 0.000000 +-0.999123 0.041876 0.000000 +-0.999123 0.041876 0.000000 +0.999123 0.041876 0.000000 +0.999123 0.041876 0.000000 +0.999123 0.041876 0.000000 +0.999123 0.041876 0.000000 +0.999123 0.041876 0.000000 +0.999123 0.041876 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -0.967920 0.251260 +0.000000 -0.987887 0.155172 +0.000000 -0.983712 0.179750 +0.000000 -0.160817 0.986984 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -0.160817 0.986984 +0.000000 -0.160817 0.986984 +0.000000 0.000000 1.000000 +0.000000 -0.317447 0.948276 +0.000000 -0.160817 0.986984 +0.000000 -0.160817 0.986984 +0.000000 -0.317447 0.948276 +0.000000 -0.317447 0.948276 +0.000000 -0.160817 0.986984 +0.000000 -0.486916 0.873449 +0.000000 -0.317447 0.948276 +0.000000 -0.317447 0.948276 +0.000000 -0.486916 0.873449 +0.000000 -0.487665 0.873031 +0.000000 -0.317447 0.948276 +0.000000 -0.639892 0.768465 +0.000000 -0.487665 0.873031 +0.000000 -0.486916 0.873449 +0.000000 -0.639892 0.768465 +0.000000 -0.640690 0.767799 +0.000000 -0.487665 0.873031 +0.000000 -0.768685 0.639628 +0.000000 -0.640690 0.767799 +0.000000 -0.639892 0.768465 +0.000000 -0.768685 0.639628 +0.000000 -0.769623 0.638498 +0.000000 -0.640690 0.767799 +0.000000 -0.866786 0.498681 +0.000000 -0.769623 0.638498 +0.000000 -0.768685 0.639628 +0.000000 -0.866786 0.498681 +0.000000 -0.867628 0.497213 +0.000000 -0.769623 0.638498 +0.000000 -0.931903 0.362707 +0.000000 -0.867628 0.497213 +0.000000 -0.866786 0.498681 +0.000000 -0.931903 0.362707 +0.000000 -0.932212 0.361912 +0.000000 -0.867628 0.497213 +0.000000 -0.967832 0.251598 +0.000000 -0.932212 0.361912 +0.000000 -0.931903 0.362707 +0.000000 -0.967832 0.251598 +0.000000 -0.967920 0.251260 +0.000000 -0.932212 0.361912 +0.000000 -0.983704 0.179798 +0.000000 -0.967920 0.251260 +0.000000 -0.967832 0.251598 +0.000000 -0.987887 0.155172 +0.000000 -0.967920 0.251260 +0.000000 -0.983704 0.179798 +0.000000 -0.987887 0.155172 +0.000000 -0.967920 0.251260 +0.000000 -0.987887 0.155172 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.974872 -0.222768 +0.000000 0.995367 -0.096154 +0.000000 0.991733 -0.128319 +0.000000 0.124620 -0.992205 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.124620 -0.992205 +0.000000 0.124925 -0.992166 +0.000000 0.000000 -1.000000 +0.000000 0.246721 -0.969087 +0.000000 0.124925 -0.992166 +0.000000 0.124620 -0.992205 +0.000000 0.246721 -0.969087 +0.000000 0.247690 -0.968839 +0.000000 0.124925 -0.992166 +0.000000 0.365987 -0.930620 +0.000000 0.247690 -0.968839 +0.000000 0.246721 -0.969087 +0.000000 0.365987 -0.930620 +0.000000 0.367076 -0.930191 +0.000000 0.247690 -0.968839 +0.000000 0.478615 -0.878025 +0.000000 0.367076 -0.930191 +0.000000 0.365987 -0.930620 +0.000000 0.478615 -0.878025 +0.000000 0.480064 -0.877233 +0.000000 0.367076 -0.930191 +0.000000 0.583551 -0.812076 +0.000000 0.480064 -0.877233 +0.000000 0.478615 -0.878025 +0.000000 0.583551 -0.812076 +0.000000 0.585844 -0.810424 +0.000000 0.480064 -0.877233 +0.000000 0.679376 -0.733791 +0.000000 0.585844 -0.810424 +0.000000 0.583551 -0.812076 +0.000000 0.679376 -0.733791 +0.000000 0.681059 -0.732229 +0.000000 0.585844 -0.810424 +0.000000 0.762566 -0.646911 +0.000000 0.681059 -0.732229 +0.000000 0.679376 -0.733791 +0.000000 0.762566 -0.646911 +0.000000 0.764573 -0.644538 +0.000000 0.681059 -0.732229 +0.000000 0.832434 -0.554124 +0.000000 0.764573 -0.644538 +0.000000 0.762566 -0.646911 +0.000000 0.832434 -0.554124 +0.000000 0.833596 -0.552375 +0.000000 0.764573 -0.644538 +0.000000 0.928076 -0.372392 +0.000000 0.833596 -0.552375 +0.000000 0.832434 -0.554124 +0.000000 0.928076 -0.372392 +0.000000 0.928594 -0.371097 +0.000000 0.833596 -0.552375 +0.000000 0.974737 -0.223354 +0.000000 0.928594 -0.371097 +0.000000 0.928076 -0.372392 +0.000000 0.974737 -0.223354 +0.000000 0.974872 -0.222768 +0.000000 0.928594 -0.371097 +0.000000 0.991718 -0.128434 +0.000000 0.974872 -0.222768 +0.000000 0.974737 -0.223354 +0.000000 0.995367 -0.096154 +0.000000 0.974872 -0.222768 +0.000000 0.991718 -0.128434 +0.000000 0.995367 -0.096154 +0.000000 0.974872 -0.222768 +0.000000 0.995367 -0.096154 +-0.999123 0.041876 0.000000 +-0.984515 0.175303 0.000000 +-0.999123 0.041876 0.000000 +-0.184366 0.982858 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.184366 0.982858 0.000000 +-0.184366 0.982858 0.000000 +0.000000 1.000000 0.000000 +-0.377871 0.925858 0.000000 +-0.184366 0.982858 0.000000 +-0.184366 0.982858 0.000000 +-0.377871 0.925858 0.000000 +-0.377871 0.925858 0.000000 +-0.184366 0.982858 0.000000 +-0.377871 0.925858 0.000000 +-0.549254 0.835655 0.000000 +-0.377871 0.925858 0.000000 +-0.549254 0.835655 0.000000 +-0.549254 0.835655 0.000000 +-0.377871 0.925858 0.000000 +-0.692143 0.721760 0.000000 +-0.549254 0.835655 0.000000 +-0.549254 0.835655 0.000000 +-0.692143 0.721760 0.000000 +-0.692143 0.721760 0.000000 +-0.549254 0.835655 0.000000 +-0.811922 0.583766 0.000000 +-0.692143 0.721760 0.000000 +-0.692143 0.721760 0.000000 +-0.811922 0.583766 0.000000 +-0.811922 0.583766 0.000000 +-0.692143 0.721760 0.000000 +-0.811922 0.583766 0.000000 +-0.909223 0.416310 0.000000 +-0.811922 0.583766 0.000000 +-0.909223 0.416310 0.000000 +-0.909223 0.416310 0.000000 +-0.811922 0.583766 0.000000 +-0.974275 0.225363 0.000000 +-0.909223 0.416310 0.000000 +-0.909223 0.416310 0.000000 +-0.974275 0.225363 0.000000 +-0.974275 0.225363 0.000000 +-0.909223 0.416310 0.000000 +-0.974275 0.225363 0.000000 +-0.999123 0.041876 0.000000 +-0.974275 0.225363 0.000000 +-0.984515 0.175303 0.000000 +-0.999123 0.041876 0.000000 +-0.974275 0.225363 0.000000 +0.000000 1.000000 0.000000 +0.184366 0.982858 0.000000 +0.000000 1.000000 0.000000 +0.999123 0.041876 0.000000 +0.974275 0.225363 0.000000 +0.999123 0.041876 0.000000 +0.984515 0.175303 0.000000 +0.974275 0.225363 0.000000 +0.999123 0.041876 0.000000 +0.974275 0.225363 0.000000 +0.974275 0.225363 0.000000 +0.984515 0.175303 0.000000 +0.909223 0.416310 0.000000 +0.974275 0.225363 0.000000 +0.974275 0.225363 0.000000 +0.909223 0.416310 0.000000 +0.909223 0.416310 0.000000 +0.974275 0.225363 0.000000 +0.909223 0.416310 0.000000 +0.811922 0.583766 0.000000 +0.909223 0.416310 0.000000 +0.811922 0.583766 0.000000 +0.811922 0.583766 0.000000 +0.909223 0.416310 0.000000 +0.692143 0.721760 0.000000 +0.811922 0.583766 0.000000 +0.811922 0.583766 0.000000 +0.692143 0.721760 0.000000 +0.692143 0.721760 0.000000 +0.811922 0.583766 0.000000 +0.692143 0.721760 0.000000 +0.549254 0.835655 0.000000 +0.692143 0.721760 0.000000 +0.549254 0.835655 0.000000 +0.549254 0.835655 0.000000 +0.692143 0.721760 0.000000 +0.549254 0.835655 0.000000 +0.377871 0.925858 0.000000 +0.549254 0.835655 0.000000 +0.377871 0.925858 0.000000 +0.377871 0.925858 0.000000 +0.549254 0.835655 0.000000 +0.184366 0.982858 0.000000 +0.377871 0.925858 0.000000 +0.377871 0.925858 0.000000 +0.184366 0.982858 0.000000 +0.184366 0.982858 0.000000 +0.377871 0.925858 0.000000 +0.184366 0.982858 0.000000 +0.000000 1.000000 0.000000 +0.184366 0.982858 0.000000 +0.000000 1.000000 0.000000 +0.204909 0.978781 0.000000 +0.204909 0.978781 0.000000 +1.000000 0.000000 0.000000 +0.978781 0.204909 0.000000 +1.000000 0.000000 0.000000 +0.978781 0.204909 0.000000 +0.978781 0.204909 0.000000 +1.000000 0.000000 0.000000 +0.978781 0.204909 0.000000 +0.917742 0.397177 0.000000 +0.978781 0.204909 0.000000 +0.917742 0.397177 0.000000 +0.917742 0.397177 0.000000 +0.978781 0.204909 0.000000 +0.917742 0.397177 0.000000 +0.823969 0.566635 0.000000 +0.917742 0.397177 0.000000 +0.823969 0.566635 0.000000 +0.823969 0.566635 0.000000 +0.917742 0.397177 0.000000 +0.707107 0.707107 0.000000 +0.823969 0.566635 0.000000 +0.823969 0.566635 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.823969 0.566635 0.000000 +0.707107 0.707107 0.000000 +0.566635 0.823969 0.000000 +0.707107 0.707107 0.000000 +0.566635 0.823969 0.000000 +0.566635 0.823969 0.000000 +0.707107 0.707107 0.000000 +0.397177 0.917742 0.000000 +0.566635 0.823969 0.000000 +0.566635 0.823969 0.000000 +0.397177 0.917742 0.000000 +0.397177 0.917742 0.000000 +0.566635 0.823969 0.000000 +0.397177 0.917742 0.000000 +0.204909 0.978781 0.000000 +0.397177 0.917742 0.000000 +0.204909 0.978781 0.000000 +0.204909 0.978781 0.000000 +0.397177 0.917742 0.000000 +0.204909 0.978781 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.204909 0.978781 0.000000 +0.000000 1.000000 0.000000 +0.978781 0.204909 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.978781 0.204909 0.000000 +0.978781 0.204909 0.000000 +1.000000 0.000000 0.000000 +0.917742 0.397177 0.000000 +0.978781 0.204909 0.000000 +0.978781 0.204909 0.000000 +0.917742 0.397177 0.000000 +0.917742 0.397177 0.000000 +0.978781 0.204909 0.000000 +0.917742 0.397177 0.000000 +0.823969 0.566635 0.000000 +0.917742 0.397177 0.000000 +0.823969 0.566635 0.000000 +0.823969 0.566635 0.000000 +0.917742 0.397177 0.000000 +0.707107 0.707107 0.000000 +0.823969 0.566635 0.000000 +0.823969 0.566635 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.823969 0.566635 0.000000 +0.707107 0.707107 0.000000 +0.566635 0.823969 0.000000 +0.707107 0.707107 0.000000 +0.566635 0.823969 0.000000 +0.566635 0.823969 0.000000 +0.707107 0.707107 0.000000 +0.397177 0.917742 0.000000 +0.566635 0.823969 0.000000 +0.566635 0.823969 0.000000 +0.397177 0.917742 0.000000 +0.397177 0.917742 0.000000 +0.566635 0.823969 0.000000 +0.397177 0.917742 0.000000 +0.204909 0.978781 0.000000 +0.397177 0.917742 0.000000 +0.204909 0.978781 0.000000 +0.204909 0.978781 0.000000 +0.397177 0.917742 0.000000 +0.204909 0.978781 0.000000 +0.000000 1.000000 0.000000 +0.204909 0.978781 0.000000 +-0.978781 0.204909 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.204909 0.978781 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.204909 0.978781 0.000000 +-0.204909 0.978781 0.000000 +0.000000 1.000000 0.000000 +-0.397177 0.917742 0.000000 +-0.204909 0.978781 0.000000 +-0.204909 0.978781 0.000000 +-0.397177 0.917742 0.000000 +-0.397177 0.917742 0.000000 +-0.204909 0.978781 0.000000 +-0.397177 0.917742 0.000000 +-0.566635 0.823969 0.000000 +-0.397177 0.917742 0.000000 +-0.566635 0.823969 0.000000 +-0.566635 0.823969 0.000000 +-0.397177 0.917742 0.000000 +-0.707107 0.707107 0.000000 +-0.566635 0.823969 0.000000 +-0.566635 0.823969 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.566635 0.823969 0.000000 +-0.707107 0.707107 0.000000 +-0.823969 0.566635 0.000000 +-0.707107 0.707107 0.000000 +-0.823969 0.566635 0.000000 +-0.823969 0.566635 0.000000 +-0.707107 0.707107 0.000000 +-0.917742 0.397177 0.000000 +-0.823969 0.566635 0.000000 +-0.823969 0.566635 0.000000 +-0.917742 0.397177 0.000000 +-0.917742 0.397177 0.000000 +-0.823969 0.566635 0.000000 +-0.978781 0.204909 0.000000 +-0.917742 0.397177 0.000000 +-0.917742 0.397177 0.000000 +-0.978781 0.204909 0.000000 +-0.978781 0.204909 0.000000 +-0.917742 0.397177 0.000000 +-1.000000 0.000000 0.000000 +-0.978781 0.204909 0.000000 +-0.978781 0.204909 0.000000 +-0.204909 0.978781 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.978781 0.204909 0.000000 +-1.000000 0.000000 0.000000 +-0.978781 0.204909 0.000000 +-0.978781 0.204909 0.000000 +-1.000000 0.000000 0.000000 +-0.978781 0.204909 0.000000 +-0.917742 0.397177 0.000000 +-0.978781 0.204909 0.000000 +-0.917742 0.397177 0.000000 +-0.917742 0.397177 0.000000 +-0.978781 0.204909 0.000000 +-0.823969 0.566635 0.000000 +-0.917742 0.397177 0.000000 +-0.917742 0.397177 0.000000 +-0.823969 0.566635 0.000000 +-0.823969 0.566635 0.000000 +-0.917742 0.397177 0.000000 +-0.707107 0.707107 0.000000 +-0.823969 0.566635 0.000000 +-0.823969 0.566635 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.823969 0.566635 0.000000 +-0.566635 0.823969 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.566635 0.823969 0.000000 +-0.566635 0.823969 0.000000 +-0.707107 0.707107 0.000000 +-0.397177 0.917742 0.000000 +-0.566635 0.823969 0.000000 +-0.566635 0.823969 0.000000 +-0.397177 0.917742 0.000000 +-0.397177 0.917742 0.000000 +-0.566635 0.823969 0.000000 +-0.397177 0.917742 0.000000 +-0.204909 0.978781 0.000000 +-0.397177 0.917742 0.000000 +-0.204909 0.978781 0.000000 +-0.204909 0.978781 0.000000 +-0.397177 0.917742 0.000000 +0.000000 1.000000 0.000000 +-0.204909 0.978781 0.000000 +-0.204909 0.978781 0.000000 +0.000000 0.000000 -1.000000 +0.117143 0.004910 -0.993103 +0.000000 0.000000 -1.000000 +0.999123 0.041876 0.000000 +0.997323 0.041800 -0.060000 +0.997323 0.041800 -0.060000 +0.999123 0.041876 0.000000 +0.997323 0.041800 -0.060000 +0.999123 0.041876 0.000000 +0.993776 0.041652 -0.103320 +0.997323 0.041800 -0.060000 +0.999123 0.041876 0.000000 +0.993776 0.041652 -0.103320 +0.994872 0.041697 -0.092150 +0.997323 0.041800 -0.060000 +0.993776 0.041652 -0.103320 +0.981526 0.041138 -0.186854 +0.994872 0.041697 -0.092150 +0.968133 0.040577 -0.247129 +0.981526 0.041138 -0.186854 +0.993776 0.041652 -0.103320 +0.968133 0.040577 -0.247129 +0.940730 0.039428 -0.336858 +0.981526 0.041138 -0.186854 +0.907059 0.038017 -0.419283 +0.940730 0.039428 -0.336858 +0.968133 0.040577 -0.247129 +0.907059 0.038017 -0.419283 +0.851149 0.035674 -0.523711 +0.940730 0.039428 -0.336858 +0.799624 0.033514 -0.599565 +0.851149 0.035674 -0.523711 +0.907059 0.038017 -0.419283 +0.799624 0.033514 -0.599565 +0.783898 0.032855 -0.620020 +0.851149 0.035674 -0.523711 +0.727952 0.030510 -0.684949 +0.783898 0.032855 -0.620020 +0.799624 0.033514 -0.599565 +0.727952 0.030510 -0.684949 +0.700841 0.029374 -0.712713 +0.783898 0.032855 -0.620020 +0.645388 0.027050 -0.763376 +0.700841 0.029374 -0.712713 +0.727952 0.030510 -0.684949 +0.645388 0.027050 -0.763376 +0.604702 0.025345 -0.796048 +0.700841 0.029374 -0.712713 +0.552284 0.023148 -0.833335 +0.604702 0.025345 -0.796048 +0.645388 0.027050 -0.763376 +0.552284 0.023148 -0.833335 +0.496632 0.020815 -0.867712 +0.604702 0.025345 -0.796048 +0.451873 0.018939 -0.891881 +0.496632 0.020815 -0.867712 +0.552284 0.023148 -0.833335 +0.451873 0.018939 -0.891881 +0.380294 0.015939 -0.924728 +0.496632 0.020815 -0.867712 +0.344701 0.014447 -0.938601 +0.380294 0.015939 -0.924728 +0.451873 0.018939 -0.891881 +0.344701 0.014447 -0.938601 +0.256710 0.010759 -0.966429 +0.380294 0.015939 -0.924728 +0.232082 0.009727 -0.972648 +0.256710 0.010759 -0.966429 +0.344701 0.014447 -0.938601 +0.232082 0.009727 -0.972648 +0.129645 0.005434 -0.991546 +0.256710 0.010759 -0.966429 +0.117143 0.004910 -0.993103 +0.129645 0.005434 -0.991546 +0.232082 0.009727 -0.972648 +0.117143 0.004910 -0.993103 +0.000000 0.000000 -1.000000 +0.129645 0.005434 -0.991546 +-0.117275 0.004915 -0.993087 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.997323 0.041800 -0.060000 +-0.999123 0.041876 0.000000 +-0.997323 0.041800 -0.060000 +-0.997323 0.041800 -0.060000 +-0.999123 0.041876 0.000000 +-0.999123 0.041876 0.000000 +-0.997323 0.041800 -0.060000 +-0.993838 0.041654 -0.102715 +-0.999123 0.041876 0.000000 +-0.994848 0.041696 -0.092407 +-0.993838 0.041654 -0.102715 +-0.997323 0.041800 -0.060000 +-0.981369 0.041132 -0.187677 +-0.993838 0.041654 -0.102715 +-0.994848 0.041696 -0.092407 +-0.981369 0.041132 -0.187677 +-0.968369 0.040587 -0.246199 +-0.993838 0.041654 -0.102715 +-0.940147 0.039404 -0.338482 +-0.968369 0.040587 -0.246199 +-0.981369 0.041132 -0.187677 +-0.940147 0.039404 -0.338482 +-0.907673 0.038043 -0.417950 +-0.968369 0.040587 -0.246199 +-0.850029 0.035627 -0.525530 +-0.907673 0.038043 -0.417950 +-0.940147 0.039404 -0.338482 +-0.850029 0.035627 -0.525530 +-0.801202 0.033580 -0.597451 +-0.907673 0.038043 -0.417950 +-0.781851 0.032769 -0.622603 +-0.801202 0.033580 -0.597451 +-0.850029 0.035627 -0.525530 +-0.781851 0.032769 -0.622603 +-0.729186 0.030562 -0.683633 +-0.801202 0.033580 -0.597451 +-0.699471 0.029317 -0.714059 +-0.729186 0.030562 -0.683633 +-0.781851 0.032769 -0.622603 +-0.699471 0.029317 -0.714059 +-0.646537 0.027098 -0.762401 +-0.729186 0.030562 -0.683633 +-0.603075 0.025276 -0.797284 +-0.646537 0.027098 -0.762401 +-0.699471 0.029317 -0.714059 +-0.603075 0.025276 -0.797284 +-0.553504 0.023199 -0.832524 +-0.646537 0.027098 -0.762401 +-0.495567 0.020770 -0.868322 +-0.553504 0.023199 -0.832524 +-0.603075 0.025276 -0.797284 +-0.495567 0.020770 -0.868322 +-0.452561 0.018968 -0.891532 +-0.553504 0.023199 -0.832524 +-0.379700 0.015914 -0.924973 +-0.452561 0.018968 -0.891532 +-0.495567 0.020770 -0.868322 +-0.379700 0.015914 -0.924973 +-0.344894 0.014455 -0.938530 +-0.452561 0.018968 -0.891532 +-0.256259 0.010740 -0.966548 +-0.344894 0.014455 -0.938530 +-0.379700 0.015914 -0.924973 +-0.256259 0.010740 -0.966548 +-0.232333 0.009738 -0.972588 +-0.344894 0.014455 -0.938530 +-0.129480 0.005427 -0.991567 +-0.232333 0.009738 -0.972588 +-0.256259 0.010740 -0.966548 +-0.129480 0.005427 -0.991567 +-0.117275 0.004915 -0.993087 +-0.232333 0.009738 -0.972588 +0.000000 0.000000 -1.000000 +-0.117275 0.004915 -0.993087 +-0.129480 0.005427 -0.991567 +0.000000 0.000000 1.000000 +0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 +0.978781 0.000000 0.204909 +1.000000 0.000000 0.000000 +0.978781 0.000000 0.204909 +0.978781 0.000000 0.204909 +1.000000 0.000000 0.000000 +0.917742 0.000000 0.397177 +0.978781 0.000000 0.204909 +0.978781 0.000000 0.204909 +0.917742 0.000000 0.397177 +0.917742 0.000000 0.397177 +0.978781 0.000000 0.204909 +0.823969 0.000000 0.566635 +0.917742 0.000000 0.397177 +0.917742 0.000000 0.397177 +0.823969 0.000000 0.566635 +0.823969 0.000000 0.566635 +0.917742 0.000000 0.397177 +0.707107 0.000000 0.707107 +0.823969 0.000000 0.566635 +0.823969 0.000000 0.566635 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.823969 0.000000 0.566635 +0.707107 0.000000 0.707107 +0.566635 0.000000 0.823969 +0.707107 0.000000 0.707107 +0.566635 0.000000 0.823969 +0.566635 0.000000 0.823969 +0.707107 0.000000 0.707107 +0.566635 0.000000 0.823969 +0.397177 0.000000 0.917742 +0.566635 0.000000 0.823969 +0.397177 0.000000 0.917742 +0.397177 0.000000 0.917742 +0.566635 0.000000 0.823969 +0.204909 0.000000 0.978781 +0.397177 0.000000 0.917742 +0.397177 0.000000 0.917742 +0.204909 0.000000 0.978781 +0.204909 0.000000 0.978781 +0.397177 0.000000 0.917742 +0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +0.204909 0.000000 0.978781 +0.000000 0.204909 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.204909 0.978781 +0.081385 0.388750 0.917742 +0.041988 0.200561 0.978781 +0.000000 0.397177 0.917742 +0.081385 0.388750 0.917742 +0.000000 0.204909 0.978781 +0.000000 0.397177 0.917742 +0.116109 0.554611 0.823969 +0.081385 0.388750 0.917742 +0.000000 0.566635 0.823969 +0.116109 0.554611 0.823969 +0.000000 0.397177 0.917742 +0.000000 0.566635 0.823969 +0.144893 0.692103 0.707107 +0.116109 0.554611 0.823969 +0.000000 0.707107 0.707107 +0.144893 0.692103 0.707107 +0.000000 0.566635 0.823969 +0.000000 0.823969 0.566635 +0.144893 0.692103 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.823969 0.566635 +0.168839 0.806485 0.566635 +0.144893 0.692103 0.707107 +0.000000 0.917742 0.397177 +0.168839 0.806485 0.566635 +0.000000 0.823969 0.566635 +0.000000 0.917742 0.397177 +0.188054 0.898268 0.397177 +0.168839 0.806485 0.566635 +0.000000 0.917742 0.397177 +0.200561 0.958012 0.204909 +0.188054 0.898268 0.397177 +0.000000 0.978781 0.204909 +0.200561 0.958012 0.204909 +0.000000 0.917742 0.397177 +0.000000 1.000000 0.000000 +0.200561 0.958012 0.204909 +0.000000 0.978781 0.204909 +0.204909 0.978781 0.000000 +0.200561 0.958012 0.204909 +0.000000 1.000000 0.000000 +0.204909 0.978781 0.000000 +0.388750 0.898268 0.204909 +0.200561 0.958012 0.204909 +0.397177 0.917742 0.000000 +0.388750 0.898268 0.204909 +0.204909 0.978781 0.000000 +0.566635 0.823969 0.000000 +0.388750 0.898268 0.204909 +0.397177 0.917742 0.000000 +0.566635 0.823969 0.000000 +0.554611 0.806485 0.204909 +0.388750 0.898268 0.204909 +0.566635 0.823969 0.000000 +0.692103 0.692103 0.204909 +0.554611 0.806485 0.204909 +0.707107 0.707107 0.000000 +0.692103 0.692103 0.204909 +0.566635 0.823969 0.000000 +0.707107 0.707107 0.000000 +0.806485 0.554611 0.204909 +0.692103 0.692103 0.204909 +0.823969 0.566635 0.000000 +0.806485 0.554611 0.204909 +0.707107 0.707107 0.000000 +0.917742 0.397177 0.000000 +0.806485 0.554611 0.204909 +0.823969 0.566635 0.000000 +0.917742 0.397177 0.000000 +0.898268 0.388750 0.204909 +0.806485 0.554611 0.204909 +0.978781 0.204909 0.000000 +0.898268 0.388750 0.204909 +0.917742 0.397177 0.000000 +0.978781 0.204909 0.000000 +0.958012 0.200561 0.204909 +0.898268 0.388750 0.204909 +1.000000 0.000000 0.000000 +0.958012 0.200561 0.204909 +0.978781 0.204909 0.000000 +0.978781 0.000000 0.204909 +0.958012 0.200561 0.204909 +1.000000 0.000000 0.000000 +0.978781 0.000000 0.204909 +0.898268 0.188054 0.397177 +0.958012 0.200561 0.204909 +0.917742 0.000000 0.397177 +0.898268 0.188054 0.397177 +0.978781 0.000000 0.204909 +0.823969 0.000000 0.566635 +0.898268 0.188054 0.397177 +0.917742 0.000000 0.397177 +0.823969 0.000000 0.566635 +0.806485 0.168839 0.566635 +0.898268 0.188054 0.397177 +0.707107 0.000000 0.707107 +0.806485 0.168839 0.566635 +0.823969 0.000000 0.566635 +0.707107 0.000000 0.707107 +0.692103 0.144893 0.707107 +0.806485 0.168839 0.566635 +0.566635 0.000000 0.823969 +0.692103 0.144893 0.707107 +0.707107 0.000000 0.707107 +0.566635 0.000000 0.823969 +0.554611 0.116109 0.823969 +0.692103 0.144893 0.707107 +0.397177 0.000000 0.917742 +0.554611 0.116109 0.823969 +0.566635 0.000000 0.823969 +0.397177 0.000000 0.917742 +0.388750 0.081385 0.917742 +0.554611 0.116109 0.823969 +0.204909 0.000000 0.978781 +0.388750 0.081385 0.917742 +0.397177 0.000000 0.917742 +0.204909 0.000000 0.978781 +0.200561 0.041988 0.978781 +0.388750 0.081385 0.917742 +0.000000 0.000000 1.000000 +0.200561 0.041988 0.978781 +0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +0.200561 0.041988 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.200561 0.041988 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.188054 0.081385 0.978781 +0.200561 0.041988 0.978781 +0.000000 0.000000 1.000000 +0.188054 0.081385 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.168839 0.116109 0.978781 +0.188054 0.081385 0.978781 +0.000000 0.000000 1.000000 +0.168839 0.116109 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.144893 0.144893 0.978781 +0.168839 0.116109 0.978781 +0.000000 0.000000 1.000000 +0.144893 0.144893 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.116109 0.168839 0.978781 +0.144893 0.144893 0.978781 +0.000000 0.000000 1.000000 +0.116109 0.168839 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.116109 0.168839 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.081385 0.188054 0.978781 +0.116109 0.168839 0.978781 +0.000000 0.000000 1.000000 +0.081385 0.188054 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.041988 0.200561 0.978781 +0.081385 0.188054 0.978781 +0.000000 0.000000 1.000000 +0.041988 0.200561 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.204909 0.978781 +0.041988 0.200561 0.978781 +0.200561 0.958012 0.204909 +0.364506 0.842250 0.397177 +0.188054 0.898268 0.397177 +0.364506 0.842250 0.397177 +0.200561 0.958012 0.204909 +0.388750 0.898268 0.204909 +0.388750 0.898268 0.204909 +0.520024 0.756191 0.397177 +0.364506 0.842250 0.397177 +0.520024 0.756191 0.397177 +0.388750 0.898268 0.204909 +0.554611 0.806485 0.204909 +0.554611 0.806485 0.204909 +0.648942 0.648942 0.397177 +0.520024 0.756191 0.397177 +0.648942 0.648942 0.397177 +0.554611 0.806485 0.204909 +0.692103 0.692103 0.204909 +0.188054 0.898268 0.397177 +0.327262 0.756191 0.566635 +0.168839 0.806485 0.566635 +0.327262 0.756191 0.566635 +0.188054 0.898268 0.397177 +0.364506 0.842250 0.397177 +0.168839 0.806485 0.566635 +0.280847 0.648942 0.707107 +0.144893 0.692103 0.707107 +0.280847 0.648942 0.707107 +0.168839 0.806485 0.566635 +0.327262 0.756191 0.566635 +0.364506 0.842250 0.397177 +0.466889 0.678925 0.566635 +0.327262 0.756191 0.566635 +0.466889 0.678925 0.566635 +0.364506 0.842250 0.397177 +0.520024 0.756191 0.397177 +0.520024 0.756191 0.397177 +0.582634 0.582634 0.566635 +0.466889 0.678925 0.566635 +0.582634 0.582634 0.566635 +0.520024 0.756191 0.397177 +0.648942 0.648942 0.397177 +0.327262 0.756191 0.566635 +0.400671 0.582634 0.707107 +0.280847 0.648942 0.707107 +0.400671 0.582634 0.707107 +0.327262 0.756191 0.566635 +0.466889 0.678925 0.566635 +0.466889 0.678925 0.566635 +0.500000 0.500000 0.707107 +0.400671 0.582634 0.707107 +0.500000 0.500000 0.707107 +0.466889 0.678925 0.566635 +0.582634 0.582634 0.566635 +0.144893 0.692103 0.707107 +0.225054 0.520024 0.823969 +0.116109 0.554611 0.823969 +0.225054 0.520024 0.823969 +0.144893 0.692103 0.707107 +0.280847 0.648942 0.707107 +0.116109 0.554611 0.823969 +0.157750 0.364506 0.917742 +0.081385 0.388750 0.917742 +0.157750 0.364506 0.917742 +0.116109 0.554611 0.823969 +0.225054 0.520024 0.823969 +0.280847 0.648942 0.707107 +0.321075 0.466889 0.823969 +0.225054 0.520024 0.823969 +0.321075 0.466889 0.823969 +0.280847 0.648942 0.707107 +0.400671 0.582634 0.707107 +0.400671 0.582634 0.707107 +0.400671 0.400671 0.823969 +0.321075 0.466889 0.823969 +0.400671 0.400671 0.823969 +0.400671 0.582634 0.707107 +0.500000 0.500000 0.707107 +0.225054 0.520024 0.823969 +0.225054 0.327262 0.917742 +0.157750 0.364506 0.917742 +0.225054 0.327262 0.917742 +0.225054 0.520024 0.823969 +0.321075 0.466889 0.823969 +0.321075 0.466889 0.823969 +0.280847 0.280847 0.917742 +0.225054 0.327262 0.917742 +0.280847 0.280847 0.917742 +0.321075 0.466889 0.823969 +0.400671 0.400671 0.823969 +0.081385 0.388750 0.917742 +0.081385 0.188054 0.978781 +0.041988 0.200561 0.978781 +0.081385 0.188054 0.978781 +0.081385 0.388750 0.917742 +0.157750 0.364506 0.917742 +0.157750 0.364506 0.917742 +0.116109 0.168839 0.978781 +0.081385 0.188054 0.978781 +0.116109 0.168839 0.978781 +0.157750 0.364506 0.917742 +0.225054 0.327262 0.917742 +0.225054 0.327262 0.917742 +0.144893 0.144893 0.978781 +0.116109 0.168839 0.978781 +0.144893 0.144893 0.978781 +0.225054 0.327262 0.917742 +0.280847 0.280847 0.917742 +0.692103 0.692103 0.204909 +0.756191 0.520024 0.397177 +0.648942 0.648942 0.397177 +0.756191 0.520024 0.397177 +0.692103 0.692103 0.204909 +0.806485 0.554611 0.204909 +0.806485 0.554611 0.204909 +0.842250 0.364506 0.397177 +0.756191 0.520024 0.397177 +0.842250 0.364506 0.397177 +0.806485 0.554611 0.204909 +0.898268 0.388750 0.204909 +0.898268 0.388750 0.204909 +0.898268 0.188054 0.397177 +0.842250 0.364506 0.397177 +0.898268 0.188054 0.397177 +0.898268 0.388750 0.204909 +0.958012 0.200561 0.204909 +0.648942 0.648942 0.397177 +0.678925 0.466889 0.566635 +0.582634 0.582634 0.566635 +0.678925 0.466889 0.566635 +0.648942 0.648942 0.397177 +0.756191 0.520024 0.397177 +0.756191 0.520024 0.397177 +0.756191 0.327262 0.566635 +0.678925 0.466889 0.566635 +0.756191 0.327262 0.566635 +0.756191 0.520024 0.397177 +0.842250 0.364506 0.397177 +0.582634 0.582634 0.566635 +0.582634 0.400671 0.707107 +0.500000 0.500000 0.707107 +0.582634 0.400671 0.707107 +0.582634 0.582634 0.566635 +0.678925 0.466889 0.566635 +0.678925 0.466889 0.566635 +0.648942 0.280847 0.707107 +0.582634 0.400671 0.707107 +0.648942 0.280847 0.707107 +0.678925 0.466889 0.566635 +0.756191 0.327262 0.566635 +0.842250 0.364506 0.397177 +0.806485 0.168839 0.566635 +0.756191 0.327262 0.566635 +0.806485 0.168839 0.566635 +0.842250 0.364506 0.397177 +0.898268 0.188054 0.397177 +0.756191 0.327262 0.566635 +0.692103 0.144893 0.707107 +0.648942 0.280847 0.707107 +0.692103 0.144893 0.707107 +0.756191 0.327262 0.566635 +0.806485 0.168839 0.566635 +0.500000 0.500000 0.707107 +0.466889 0.321075 0.823969 +0.400671 0.400671 0.823969 +0.466889 0.321075 0.823969 +0.500000 0.500000 0.707107 +0.582634 0.400671 0.707107 +0.582634 0.400671 0.707107 +0.520024 0.225054 0.823969 +0.466889 0.321075 0.823969 +0.520024 0.225054 0.823969 +0.582634 0.400671 0.707107 +0.648942 0.280847 0.707107 +0.400671 0.400671 0.823969 +0.327262 0.225054 0.917742 +0.280847 0.280847 0.917742 +0.327262 0.225054 0.917742 +0.400671 0.400671 0.823969 +0.466889 0.321075 0.823969 +0.466889 0.321075 0.823969 +0.364506 0.157750 0.917742 +0.327262 0.225054 0.917742 +0.364506 0.157750 0.917742 +0.466889 0.321075 0.823969 +0.520024 0.225054 0.823969 +0.648942 0.280847 0.707107 +0.554611 0.116109 0.823969 +0.520024 0.225054 0.823969 +0.554611 0.116109 0.823969 +0.648942 0.280847 0.707107 +0.692103 0.144893 0.707107 +0.520024 0.225054 0.823969 +0.388750 0.081385 0.917742 +0.364506 0.157750 0.917742 +0.388750 0.081385 0.917742 +0.520024 0.225054 0.823969 +0.554611 0.116109 0.823969 +0.280847 0.280847 0.917742 +0.168839 0.116109 0.978781 +0.144893 0.144893 0.978781 +0.168839 0.116109 0.978781 +0.280847 0.280847 0.917742 +0.327262 0.225054 0.917742 +0.327262 0.225054 0.917742 +0.188054 0.081385 0.978781 +0.168839 0.116109 0.978781 +0.188054 0.081385 0.978781 +0.327262 0.225054 0.917742 +0.364506 0.157750 0.917742 +0.364506 0.157750 0.917742 +0.200561 0.041988 0.978781 +0.188054 0.081385 0.978781 +0.200561 0.041988 0.978781 +0.364506 0.157750 0.917742 +0.388750 0.081385 0.917742 +0.116109 0.554611 0.823969 +0.000000 0.397177 0.917742 +0.081385 0.388750 0.917742 +0.144893 0.144893 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.116109 0.168839 0.978781 +0.000000 0.000000 1.000000 +0.144893 0.144893 0.978781 +0.116109 0.168839 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.081385 0.188054 0.978781 +0.000000 0.000000 1.000000 +0.116109 0.168839 0.978781 +0.081385 0.188054 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.041988 0.200561 0.978781 +0.000000 0.000000 1.000000 +0.081385 0.188054 0.978781 +0.041988 0.200561 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.204909 0.978781 +0.000000 0.000000 1.000000 +0.041988 0.200561 0.978781 +0.000000 0.204909 0.978781 +0.000000 0.000000 1.000000 +0.081385 0.388750 0.917742 +0.000000 0.204909 0.978781 +0.041988 0.200561 0.978781 +0.081385 0.388750 0.917742 +0.000000 0.397177 0.917742 +0.000000 0.204909 0.978781 +0.000000 0.978781 0.204909 +0.204909 0.978781 0.000000 +0.000000 1.000000 0.000000 +0.978781 0.204909 0.000000 +0.983305 0.000000 0.181963 +1.000000 0.000000 0.000000 +0.181963 0.000000 0.983305 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.168839 0.116109 0.978781 +0.144893 0.144893 0.978781 +0.000000 0.000000 1.000000 +0.168839 0.116109 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.168839 0.116109 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.188054 0.081385 0.978781 +0.168839 0.116109 0.978781 +0.000000 0.000000 1.000000 +0.188054 0.081385 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.200561 0.041988 0.978781 +0.188054 0.081385 0.978781 +0.000000 0.000000 1.000000 +0.200561 0.041988 0.978781 +0.000000 0.000000 1.000000 +0.181963 0.000000 0.983305 +0.200561 0.041988 0.978781 +0.000000 0.000000 1.000000 +0.368095 0.000000 0.929788 +0.200561 0.041988 0.978781 +0.181963 0.000000 0.983305 +0.368095 0.000000 0.929788 +0.388750 0.081385 0.917742 +0.200561 0.041988 0.978781 +0.547210 0.000000 0.836995 +0.388750 0.081385 0.917742 +0.368095 0.000000 0.929788 +0.547210 0.000000 0.836995 +0.554611 0.116109 0.823969 +0.388750 0.081385 0.917742 +0.630298 0.000000 0.776353 +0.554611 0.116109 0.823969 +0.547210 0.000000 0.836995 +0.630298 0.000000 0.776353 +0.692103 0.144893 0.707107 +0.554611 0.116109 0.823969 +0.707107 0.000000 0.707107 +0.692103 0.144893 0.707107 +0.630298 0.000000 0.776353 +0.776353 0.000000 0.630298 +0.692103 0.144893 0.707107 +0.707107 0.000000 0.707107 +0.776353 0.000000 0.630298 +0.806485 0.168839 0.566635 +0.692103 0.144893 0.707107 +0.836995 0.000000 0.547210 +0.806485 0.168839 0.566635 +0.776353 0.000000 0.630298 +0.836995 0.000000 0.547210 +0.898268 0.188054 0.397177 +0.806485 0.168839 0.566635 +0.929788 0.000000 0.368095 +0.898268 0.188054 0.397177 +0.836995 0.000000 0.547210 +0.929788 0.000000 0.368095 +0.958012 0.200561 0.204909 +0.898268 0.188054 0.397177 +0.983305 0.000000 0.181963 +0.958012 0.200561 0.204909 +0.929788 0.000000 0.368095 +0.978781 0.204909 0.000000 +0.958012 0.200561 0.204909 +0.983305 0.000000 0.181963 +0.978781 0.204909 0.000000 +0.898268 0.388750 0.204909 +0.958012 0.200561 0.204909 +0.917742 0.397177 0.000000 +0.898268 0.388750 0.204909 +0.978781 0.204909 0.000000 +0.823969 0.566635 0.000000 +0.898268 0.388750 0.204909 +0.917742 0.397177 0.000000 +0.823969 0.566635 0.000000 +0.806485 0.554611 0.204909 +0.898268 0.388750 0.204909 +0.823969 0.566635 0.000000 +0.692103 0.692103 0.204909 +0.806485 0.554611 0.204909 +0.707107 0.707107 0.000000 +0.692103 0.692103 0.204909 +0.823969 0.566635 0.000000 +0.707107 0.707107 0.000000 +0.554611 0.806485 0.204909 +0.692103 0.692103 0.204909 +0.566635 0.823969 0.000000 +0.554611 0.806485 0.204909 +0.707107 0.707107 0.000000 +0.397177 0.917742 0.000000 +0.554611 0.806485 0.204909 +0.566635 0.823969 0.000000 +0.397177 0.917742 0.000000 +0.388750 0.898268 0.204909 +0.554611 0.806485 0.204909 +0.204909 0.978781 0.000000 +0.388750 0.898268 0.204909 +0.397177 0.917742 0.000000 +0.204909 0.978781 0.000000 +0.200561 0.958012 0.204909 +0.388750 0.898268 0.204909 +0.000000 0.978781 0.204909 +0.200561 0.958012 0.204909 +0.204909 0.978781 0.000000 +0.000000 0.917742 0.397177 +0.200561 0.958012 0.204909 +0.000000 0.978781 0.204909 +0.000000 0.917742 0.397177 +0.188054 0.898268 0.397177 +0.200561 0.958012 0.204909 +0.000000 0.823969 0.566635 +0.188054 0.898268 0.397177 +0.000000 0.917742 0.397177 +0.000000 0.823969 0.566635 +0.168839 0.806485 0.566635 +0.188054 0.898268 0.397177 +0.000000 0.707107 0.707107 +0.168839 0.806485 0.566635 +0.000000 0.823969 0.566635 +0.000000 0.707107 0.707107 +0.144893 0.692103 0.707107 +0.168839 0.806485 0.566635 +0.000000 0.707107 0.707107 +0.116109 0.554611 0.823969 +0.144893 0.692103 0.707107 +0.000000 0.566635 0.823969 +0.116109 0.554611 0.823969 +0.000000 0.707107 0.707107 +0.000000 0.397177 0.917742 +0.116109 0.554611 0.823969 +0.000000 0.566635 0.823969 +0.041988 0.200561 0.978781 +0.157750 0.364506 0.917742 +0.081385 0.388750 0.917742 +0.157750 0.364506 0.917742 +0.041988 0.200561 0.978781 +0.081385 0.188054 0.978781 +0.081385 0.188054 0.978781 +0.225054 0.327262 0.917742 +0.157750 0.364506 0.917742 +0.225054 0.327262 0.917742 +0.081385 0.188054 0.978781 +0.116109 0.168839 0.978781 +0.116109 0.168839 0.978781 +0.280847 0.280847 0.917742 +0.225054 0.327262 0.917742 +0.280847 0.280847 0.917742 +0.116109 0.168839 0.978781 +0.144893 0.144893 0.978781 +0.081385 0.388750 0.917742 +0.225054 0.520024 0.823969 +0.116109 0.554611 0.823969 +0.225054 0.520024 0.823969 +0.081385 0.388750 0.917742 +0.157750 0.364506 0.917742 +0.116109 0.554611 0.823969 +0.280847 0.648942 0.707107 +0.144893 0.692103 0.707107 +0.280847 0.648942 0.707107 +0.116109 0.554611 0.823969 +0.225054 0.520024 0.823969 +0.157750 0.364506 0.917742 +0.321075 0.466889 0.823969 +0.225054 0.520024 0.823969 +0.321075 0.466889 0.823969 +0.157750 0.364506 0.917742 +0.225054 0.327262 0.917742 +0.225054 0.327262 0.917742 +0.400671 0.400671 0.823969 +0.321075 0.466889 0.823969 +0.400671 0.400671 0.823969 +0.225054 0.327262 0.917742 +0.280847 0.280847 0.917742 +0.225054 0.520024 0.823969 +0.400671 0.582634 0.707107 +0.280847 0.648942 0.707107 +0.400671 0.582634 0.707107 +0.225054 0.520024 0.823969 +0.321075 0.466889 0.823969 +0.321075 0.466889 0.823969 +0.500000 0.500000 0.707107 +0.400671 0.582634 0.707107 +0.500000 0.500000 0.707107 +0.321075 0.466889 0.823969 +0.400671 0.400671 0.823969 +0.144893 0.692103 0.707107 +0.327262 0.756191 0.566635 +0.168839 0.806485 0.566635 +0.327262 0.756191 0.566635 +0.144893 0.692103 0.707107 +0.280847 0.648942 0.707107 +0.168839 0.806485 0.566635 +0.364506 0.842250 0.397177 +0.188054 0.898268 0.397177 +0.364506 0.842250 0.397177 +0.168839 0.806485 0.566635 +0.327262 0.756191 0.566635 +0.280847 0.648942 0.707107 +0.466889 0.678925 0.566635 +0.327262 0.756191 0.566635 +0.466889 0.678925 0.566635 +0.280847 0.648942 0.707107 +0.400671 0.582634 0.707107 +0.400671 0.582634 0.707107 +0.582634 0.582634 0.566635 +0.466889 0.678925 0.566635 +0.582634 0.582634 0.566635 +0.400671 0.582634 0.707107 +0.500000 0.500000 0.707107 +0.327262 0.756191 0.566635 +0.520024 0.756191 0.397177 +0.364506 0.842250 0.397177 +0.520024 0.756191 0.397177 +0.327262 0.756191 0.566635 +0.466889 0.678925 0.566635 +0.466889 0.678925 0.566635 +0.648942 0.648942 0.397177 +0.520024 0.756191 0.397177 +0.648942 0.648942 0.397177 +0.466889 0.678925 0.566635 +0.582634 0.582634 0.566635 +0.188054 0.898268 0.397177 +0.388750 0.898268 0.204909 +0.200561 0.958012 0.204909 +0.388750 0.898268 0.204909 +0.188054 0.898268 0.397177 +0.364506 0.842250 0.397177 +0.364506 0.842250 0.397177 +0.554611 0.806485 0.204909 +0.388750 0.898268 0.204909 +0.554611 0.806485 0.204909 +0.364506 0.842250 0.397177 +0.520024 0.756191 0.397177 +0.520024 0.756191 0.397177 +0.692103 0.692103 0.204909 +0.554611 0.806485 0.204909 +0.692103 0.692103 0.204909 +0.520024 0.756191 0.397177 +0.648942 0.648942 0.397177 +0.144893 0.144893 0.978781 +0.327262 0.225054 0.917742 +0.280847 0.280847 0.917742 +0.327262 0.225054 0.917742 +0.144893 0.144893 0.978781 +0.168839 0.116109 0.978781 +0.168839 0.116109 0.978781 +0.364506 0.157750 0.917742 +0.327262 0.225054 0.917742 +0.364506 0.157750 0.917742 +0.168839 0.116109 0.978781 +0.188054 0.081385 0.978781 +0.188054 0.081385 0.978781 +0.388750 0.081385 0.917742 +0.364506 0.157750 0.917742 +0.388750 0.081385 0.917742 +0.188054 0.081385 0.978781 +0.200561 0.041988 0.978781 +0.280847 0.280847 0.917742 +0.466889 0.321075 0.823969 +0.400671 0.400671 0.823969 +0.466889 0.321075 0.823969 +0.280847 0.280847 0.917742 +0.327262 0.225054 0.917742 +0.327262 0.225054 0.917742 +0.520024 0.225054 0.823969 +0.466889 0.321075 0.823969 +0.520024 0.225054 0.823969 +0.327262 0.225054 0.917742 +0.364506 0.157750 0.917742 +0.400671 0.400671 0.823969 +0.582634 0.400671 0.707107 +0.500000 0.500000 0.707107 +0.582634 0.400671 0.707107 +0.400671 0.400671 0.823969 +0.466889 0.321075 0.823969 +0.466889 0.321075 0.823969 +0.648942 0.280847 0.707107 +0.582634 0.400671 0.707107 +0.648942 0.280847 0.707107 +0.466889 0.321075 0.823969 +0.520024 0.225054 0.823969 +0.364506 0.157750 0.917742 +0.554611 0.116109 0.823969 +0.520024 0.225054 0.823969 +0.554611 0.116109 0.823969 +0.364506 0.157750 0.917742 +0.388750 0.081385 0.917742 +0.520024 0.225054 0.823969 +0.692103 0.144893 0.707107 +0.648942 0.280847 0.707107 +0.692103 0.144893 0.707107 +0.520024 0.225054 0.823969 +0.554611 0.116109 0.823969 +0.500000 0.500000 0.707107 +0.678925 0.466889 0.566635 +0.582634 0.582634 0.566635 +0.678925 0.466889 0.566635 +0.500000 0.500000 0.707107 +0.582634 0.400671 0.707107 +0.582634 0.400671 0.707107 +0.756191 0.327262 0.566635 +0.678925 0.466889 0.566635 +0.756191 0.327262 0.566635 +0.582634 0.400671 0.707107 +0.648942 0.280847 0.707107 +0.582634 0.582634 0.566635 +0.756191 0.520024 0.397177 +0.648942 0.648942 0.397177 +0.756191 0.520024 0.397177 +0.582634 0.582634 0.566635 +0.678925 0.466889 0.566635 +0.678925 0.466889 0.566635 +0.842250 0.364506 0.397177 +0.756191 0.520024 0.397177 +0.842250 0.364506 0.397177 +0.678925 0.466889 0.566635 +0.756191 0.327262 0.566635 +0.648942 0.280847 0.707107 +0.806485 0.168839 0.566635 +0.756191 0.327262 0.566635 +0.806485 0.168839 0.566635 +0.648942 0.280847 0.707107 +0.692103 0.144893 0.707107 +0.756191 0.327262 0.566635 +0.898268 0.188054 0.397177 +0.842250 0.364506 0.397177 +0.898268 0.188054 0.397177 +0.756191 0.327262 0.566635 +0.806485 0.168839 0.566635 +0.648942 0.648942 0.397177 +0.806485 0.554611 0.204909 +0.692103 0.692103 0.204909 +0.806485 0.554611 0.204909 +0.648942 0.648942 0.397177 +0.756191 0.520024 0.397177 +0.756191 0.520024 0.397177 +0.898268 0.388750 0.204909 +0.806485 0.554611 0.204909 +0.898268 0.388750 0.204909 +0.756191 0.520024 0.397177 +0.842250 0.364506 0.397177 +0.842250 0.364506 0.397177 +0.958012 0.200561 0.204909 +0.898268 0.388750 0.204909 +0.958012 0.200561 0.204909 +0.842250 0.364506 0.397177 +0.898268 0.188054 0.397177 +0.000000 0.566635 0.823969 +0.000000 0.397177 0.917742 +0.000000 0.397177 0.917742 +0.000000 0.204909 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.204909 0.978781 +0.000000 0.204909 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.397177 0.917742 +0.000000 0.204909 0.978781 +0.000000 0.204909 0.978781 +0.000000 0.397177 0.917742 +0.000000 0.397177 0.917742 +0.000000 0.204909 0.978781 +0.000000 0.978781 0.204909 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.978781 0.204909 +0.000000 0.978781 0.204909 +0.000000 1.000000 0.000000 +0.000000 0.917742 0.397177 +0.000000 0.978781 0.204909 +0.000000 0.978781 0.204909 +0.000000 0.917742 0.397177 +0.000000 0.917742 0.397177 +0.000000 0.978781 0.204909 +0.000000 0.917742 0.397177 +0.000000 0.823969 0.566635 +0.000000 0.917742 0.397177 +0.000000 0.823969 0.566635 +0.000000 0.823969 0.566635 +0.000000 0.917742 0.397177 +0.000000 0.707107 0.707107 +0.000000 0.823969 0.566635 +0.000000 0.823969 0.566635 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.823969 0.566635 +0.000000 0.707107 0.707107 +0.000000 0.566635 0.823969 +0.000000 0.707107 0.707107 +0.000000 0.566635 0.823969 +0.000000 0.566635 0.823969 +0.000000 0.707107 0.707107 +0.000000 0.397177 0.917742 +0.000000 0.566635 0.823969 +0.000000 0.566635 0.823969 +0.000000 0.917742 0.397177 +0.000000 0.823969 0.566635 +0.000000 0.917742 0.397177 +0.000000 0.978781 0.204909 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.978781 0.204909 +0.000000 0.978781 0.204909 +0.000000 1.000000 0.000000 +0.000000 0.917742 0.397177 +0.000000 0.978781 0.204909 +0.000000 0.978781 0.204909 +0.000000 0.917742 0.397177 +0.000000 0.917742 0.397177 +0.000000 0.978781 0.204909 +0.000000 0.204909 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.204909 0.978781 +0.000000 0.204909 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.397177 0.917742 +0.000000 0.204909 0.978781 +0.000000 0.204909 0.978781 +0.000000 0.397177 0.917742 +0.000000 0.397177 0.917742 +0.000000 0.204909 0.978781 +0.000000 0.566635 0.823969 +0.000000 0.397177 0.917742 +0.000000 0.397177 0.917742 +0.000000 0.566635 0.823969 +0.000000 0.566635 0.823969 +0.000000 0.397177 0.917742 +0.000000 0.566635 0.823969 +0.000000 0.707107 0.707107 +0.000000 0.566635 0.823969 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.566635 0.823969 +0.000000 0.823969 0.566635 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.823969 0.566635 +0.000000 0.823969 0.566635 +0.000000 0.707107 0.707107 +0.000000 0.823969 0.566635 +0.000000 0.917742 0.397177 +0.000000 0.823969 0.566635 +0.000000 0.983305 0.181963 +0.184366 0.982858 0.000000 +0.000000 1.000000 0.000000 +0.151912 0.809844 0.566635 +0.000000 0.707107 0.707107 +0.130367 0.694985 0.707107 +0.151912 0.809844 0.566635 +0.000000 0.776353 0.630298 +0.000000 0.707107 0.707107 +0.151912 0.809844 0.566635 +0.000000 0.836995 0.547210 +0.000000 0.776353 0.630298 +0.169201 0.902010 0.397177 +0.000000 0.836995 0.547210 +0.151912 0.809844 0.566635 +0.169201 0.902010 0.397177 +0.000000 0.929788 0.368095 +0.000000 0.836995 0.547210 +0.180454 0.962002 0.204909 +0.000000 0.929788 0.368095 +0.169201 0.902010 0.397177 +0.180454 0.962002 0.204909 +0.000000 0.983305 0.181963 +0.000000 0.929788 0.368095 +0.204730 0.008581 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.181963 0.983305 +0.000000 0.000000 1.000000 +0.000000 0.630298 0.776353 +0.130367 0.694985 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.630298 0.776353 +0.104468 0.556921 0.823969 +0.130367 0.694985 0.707107 +0.000000 0.547210 0.836995 +0.104468 0.556921 0.823969 +0.000000 0.630298 0.776353 +0.000000 0.547210 0.836995 +0.073226 0.390369 0.917742 +0.104468 0.556921 0.823969 +0.000000 0.368095 0.929788 +0.073226 0.390369 0.917742 +0.000000 0.547210 0.836995 +0.000000 0.368095 0.929788 +0.037778 0.201397 0.978781 +0.073226 0.390369 0.917742 +0.000000 0.181963 0.983305 +0.037778 0.201397 0.978781 +0.000000 0.368095 0.929788 +0.000000 0.000000 1.000000 +0.037778 0.201397 0.978781 +0.000000 0.181963 0.983305 +0.000000 0.000000 1.000000 +0.037778 0.201397 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.077429 0.189717 0.978781 +0.037778 0.201397 0.978781 +0.000000 0.000000 1.000000 +0.077429 0.189717 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.112547 0.171234 0.978781 +0.077429 0.189717 0.978781 +0.000000 0.000000 1.000000 +0.112547 0.171234 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.141827 0.147896 0.978781 +0.112547 0.171234 0.978781 +0.000000 0.000000 1.000000 +0.166370 0.119619 0.978781 +0.141827 0.147896 0.978781 +0.000000 0.000000 1.000000 +0.166370 0.119619 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.186308 0.085306 0.978781 +0.166370 0.119619 0.978781 +0.000000 0.000000 1.000000 +0.186308 0.085306 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.199638 0.046179 0.978781 +0.186308 0.085306 0.978781 +0.000000 0.000000 1.000000 +0.199638 0.046179 0.978781 +0.000000 0.000000 1.000000 +0.204730 0.008581 0.978781 +0.199638 0.046179 0.978781 +0.000000 0.000000 1.000000 +0.204730 0.008581 0.978781 +0.386960 0.089509 0.917742 +0.199638 0.046179 0.978781 +0.396829 0.016632 0.917742 +0.386960 0.089509 0.917742 +0.204730 0.008581 0.978781 +0.566138 0.023728 0.823969 +0.386960 0.089509 0.917742 +0.396829 0.016632 0.917742 +0.566138 0.023728 0.823969 +0.552058 0.127698 0.823969 +0.386960 0.089509 0.917742 +0.566138 0.023728 0.823969 +0.688916 0.159355 0.707107 +0.552058 0.127698 0.823969 +0.706487 0.029611 0.707107 +0.688916 0.159355 0.707107 +0.566138 0.023728 0.823969 +0.706487 0.029611 0.707107 +0.802773 0.185692 0.566635 +0.688916 0.159355 0.707107 +0.823246 0.034504 0.566635 +0.802773 0.185692 0.566635 +0.706487 0.029611 0.707107 +0.916937 0.038431 0.397177 +0.802773 0.185692 0.566635 +0.823246 0.034504 0.566635 +0.916937 0.038431 0.397177 +0.894133 0.206825 0.397177 +0.802773 0.185692 0.566635 +0.977922 0.040987 0.204909 +0.894133 0.206825 0.397177 +0.916937 0.038431 0.397177 +0.977922 0.040987 0.204909 +0.953602 0.220581 0.204909 +0.894133 0.206825 0.397177 +0.999123 0.041876 0.000000 +0.953602 0.220581 0.204909 +0.977922 0.040987 0.204909 +0.974275 0.225363 0.000000 +0.953602 0.220581 0.204909 +0.999123 0.041876 0.000000 +0.909223 0.416310 0.000000 +0.953602 0.220581 0.204909 +0.974275 0.225363 0.000000 +0.909223 0.416310 0.000000 +0.889930 0.407476 0.204909 +0.953602 0.220581 0.204909 +0.811922 0.583766 0.000000 +0.889930 0.407476 0.204909 +0.909223 0.416310 0.000000 +0.811922 0.583766 0.000000 +0.794694 0.571379 0.204909 +0.889930 0.407476 0.204909 +0.811922 0.583766 0.000000 +0.677457 0.706445 0.204909 +0.794694 0.571379 0.204909 +0.692143 0.721760 0.000000 +0.677457 0.706445 0.204909 +0.811922 0.583766 0.000000 +0.692143 0.721760 0.000000 +0.537600 0.817923 0.204909 +0.677457 0.706445 0.204909 +0.549254 0.835655 0.000000 +0.537600 0.817923 0.204909 +0.692143 0.721760 0.000000 +0.377871 0.925858 0.000000 +0.537600 0.817923 0.204909 +0.549254 0.835655 0.000000 +0.377871 0.925858 0.000000 +0.369852 0.906213 0.204909 +0.537600 0.817923 0.204909 +0.184366 0.982858 0.000000 +0.369852 0.906213 0.204909 +0.377871 0.925858 0.000000 +0.184366 0.982858 0.000000 +0.180454 0.962002 0.204909 +0.369852 0.906213 0.204909 +0.184366 0.982858 0.000000 +0.000000 0.983305 0.181963 +0.180454 0.962002 0.204909 +0.037778 0.201397 0.978781 +0.150082 0.367730 0.917742 +0.073226 0.390369 0.917742 +0.150082 0.367730 0.917742 +0.037778 0.201397 0.978781 +0.077429 0.189717 0.978781 +0.077429 0.189717 0.978781 +0.218151 0.331903 0.917742 +0.150082 0.367730 0.917742 +0.218151 0.331903 0.917742 +0.077429 0.189717 0.978781 +0.112547 0.171234 0.978781 +0.112547 0.171234 0.978781 +0.274904 0.286667 0.917742 +0.218151 0.331903 0.917742 +0.274904 0.286667 0.917742 +0.112547 0.171234 0.978781 +0.141827 0.147896 0.978781 +0.073226 0.390369 0.917742 +0.214115 0.524623 0.823969 +0.104468 0.556921 0.823969 +0.214115 0.524623 0.823969 +0.073226 0.390369 0.917742 +0.150082 0.367730 0.917742 +0.104468 0.556921 0.823969 +0.267195 0.654681 0.707107 +0.130367 0.694985 0.707107 +0.267195 0.654681 0.707107 +0.104468 0.556921 0.823969 +0.214115 0.524623 0.823969 +0.150082 0.367730 0.917742 +0.311227 0.473511 0.823969 +0.214115 0.524623 0.823969 +0.311227 0.473511 0.823969 +0.150082 0.367730 0.917742 +0.218151 0.331903 0.917742 +0.218151 0.331903 0.917742 +0.392192 0.408974 0.823969 +0.311227 0.473511 0.823969 +0.392192 0.408974 0.823969 +0.218151 0.331903 0.917742 +0.274904 0.286667 0.917742 +0.214115 0.524623 0.823969 +0.388382 0.590897 0.707107 +0.267195 0.654681 0.707107 +0.388382 0.590897 0.707107 +0.214115 0.524623 0.823969 +0.311227 0.473511 0.823969 +0.311227 0.473511 0.823969 +0.489419 0.510362 0.707107 +0.388382 0.590897 0.707107 +0.489419 0.510362 0.707107 +0.311227 0.473511 0.823969 +0.392192 0.408974 0.823969 +0.130367 0.694985 0.707107 +0.311354 0.762879 0.566635 +0.151912 0.809844 0.566635 +0.311354 0.762879 0.566635 +0.130367 0.694985 0.707107 +0.267195 0.654681 0.707107 +0.151912 0.809844 0.566635 +0.346788 0.849699 0.397177 +0.169201 0.902010 0.397177 +0.346788 0.849699 0.397177 +0.151912 0.809844 0.566635 +0.311354 0.762879 0.566635 +0.267195 0.654681 0.707107 +0.452569 0.688554 0.566635 +0.311354 0.762879 0.566635 +0.452569 0.688554 0.566635 +0.267195 0.654681 0.707107 +0.388382 0.590897 0.707107 +0.388382 0.590897 0.707107 +0.570305 0.594708 0.566635 +0.452569 0.688554 0.566635 +0.570305 0.594708 0.566635 +0.388382 0.590897 0.707107 +0.489419 0.510362 0.707107 +0.311354 0.762879 0.566635 +0.504074 0.766916 0.397177 +0.346788 0.849699 0.397177 +0.504074 0.766916 0.397177 +0.311354 0.762879 0.566635 +0.452569 0.688554 0.566635 +0.452569 0.688554 0.566635 +0.635209 0.662390 0.397177 +0.504074 0.766916 0.397177 +0.635209 0.662390 0.397177 +0.452569 0.688554 0.566635 +0.570305 0.594708 0.566635 +0.169201 0.902010 0.397177 +0.369852 0.906213 0.204909 +0.180454 0.962002 0.204909 +0.369852 0.906213 0.204909 +0.169201 0.902010 0.397177 +0.346788 0.849699 0.397177 +0.346788 0.849699 0.397177 +0.537600 0.817923 0.204909 +0.369852 0.906213 0.204909 +0.537600 0.817923 0.204909 +0.346788 0.849699 0.397177 +0.504074 0.766916 0.397177 +0.504074 0.766916 0.397177 +0.677457 0.706445 0.204909 +0.537600 0.817923 0.204909 +0.677457 0.706445 0.204909 +0.504074 0.766916 0.397177 +0.635209 0.662390 0.397177 +0.141827 0.147896 0.978781 +0.322477 0.231859 0.917742 +0.274904 0.286667 0.917742 +0.322477 0.231859 0.917742 +0.141827 0.147896 0.978781 +0.166370 0.119619 0.978781 +0.166370 0.119619 0.978781 +0.361123 0.165349 0.917742 +0.322477 0.231859 0.917742 +0.361123 0.165349 0.917742 +0.166370 0.119619 0.978781 +0.186308 0.085306 0.978781 +0.186308 0.085306 0.978781 +0.386960 0.089509 0.917742 +0.361123 0.165349 0.917742 +0.386960 0.089509 0.917742 +0.186308 0.085306 0.978781 +0.199638 0.046179 0.978781 +0.274904 0.286667 0.917742 +0.460063 0.330782 0.823969 +0.392192 0.408974 0.823969 +0.460063 0.330782 0.823969 +0.274904 0.286667 0.917742 +0.322477 0.231859 0.917742 +0.322477 0.231859 0.917742 +0.515197 0.235896 0.823969 +0.460063 0.330782 0.823969 +0.515197 0.235896 0.823969 +0.322477 0.231859 0.917742 +0.361123 0.165349 0.917742 +0.392192 0.408974 0.823969 +0.574115 0.412785 0.707107 +0.489419 0.510362 0.707107 +0.574115 0.412785 0.707107 +0.392192 0.408974 0.823969 +0.460063 0.330782 0.823969 +0.460063 0.330782 0.823969 +0.642918 0.294376 0.707107 +0.574115 0.412785 0.707107 +0.642918 0.294376 0.707107 +0.460063 0.330782 0.823969 +0.515197 0.235896 0.823969 +0.361123 0.165349 0.917742 +0.552058 0.127698 0.823969 +0.515197 0.235896 0.823969 +0.552058 0.127698 0.823969 +0.361123 0.165349 0.917742 +0.386960 0.089509 0.917742 +0.515197 0.235896 0.823969 +0.688916 0.159355 0.707107 +0.642918 0.294376 0.707107 +0.688916 0.159355 0.707107 +0.515197 0.235896 0.823969 +0.552058 0.127698 0.823969 +0.489419 0.510362 0.707107 +0.668999 0.481005 0.566635 +0.570305 0.594708 0.566635 +0.668999 0.481005 0.566635 +0.489419 0.510362 0.707107 +0.574115 0.412785 0.707107 +0.574115 0.412785 0.707107 +0.749172 0.343027 0.566635 +0.668999 0.481005 0.566635 +0.749172 0.343027 0.566635 +0.574115 0.412785 0.707107 +0.642918 0.294376 0.707107 +0.570305 0.594708 0.566635 +0.745135 0.535747 0.397177 +0.635209 0.662390 0.397177 +0.745135 0.535747 0.397177 +0.570305 0.594708 0.566635 +0.668999 0.481005 0.566635 +0.668999 0.481005 0.566635 +0.834432 0.382065 0.397177 +0.745135 0.535747 0.397177 +0.834432 0.382065 0.397177 +0.668999 0.481005 0.566635 +0.749172 0.343027 0.566635 +0.642918 0.294376 0.707107 +0.802773 0.185692 0.566635 +0.749172 0.343027 0.566635 +0.802773 0.185692 0.566635 +0.642918 0.294376 0.707107 +0.688916 0.159355 0.707107 +0.749172 0.343027 0.566635 +0.894133 0.206825 0.397177 +0.834432 0.382065 0.397177 +0.894133 0.206825 0.397177 +0.749172 0.343027 0.566635 +0.802773 0.185692 0.566635 +0.635209 0.662390 0.397177 +0.794694 0.571379 0.204909 +0.677457 0.706445 0.204909 +0.794694 0.571379 0.204909 +0.635209 0.662390 0.397177 +0.745135 0.535747 0.397177 +0.745135 0.535747 0.397177 +0.889930 0.407476 0.204909 +0.794694 0.571379 0.204909 +0.889930 0.407476 0.204909 +0.745135 0.535747 0.397177 +0.834432 0.382065 0.397177 +0.834432 0.382065 0.397177 +0.953602 0.220581 0.204909 +0.889930 0.407476 0.204909 +0.953602 0.220581 0.204909 +0.834432 0.382065 0.397177 +0.894133 0.206825 0.397177 +-0.081385 0.388750 0.917742 +0.000000 0.566635 0.823969 +-0.116109 0.554611 0.823969 +-0.144893 0.144893 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.168839 0.116109 0.978781 +0.000000 0.000000 1.000000 +-0.144893 0.144893 0.978781 +-0.168839 0.116109 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.188054 0.081385 0.978781 +0.000000 0.000000 1.000000 +-0.168839 0.116109 0.978781 +-0.188054 0.081385 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.200561 0.041988 0.978781 +0.000000 0.000000 1.000000 +-0.188054 0.081385 0.978781 +-0.200561 0.041988 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.181963 0.000000 0.983305 +0.000000 0.000000 1.000000 +-0.200561 0.041988 0.978781 +-0.181963 0.000000 0.983305 +0.000000 0.000000 1.000000 +-0.200561 0.041988 0.978781 +-0.368095 0.000000 0.929788 +-0.181963 0.000000 0.983305 +-0.388750 0.081385 0.917742 +-0.368095 0.000000 0.929788 +-0.200561 0.041988 0.978781 +-0.388750 0.081385 0.917742 +-0.547210 0.000000 0.836995 +-0.368095 0.000000 0.929788 +-0.554611 0.116109 0.823969 +-0.547210 0.000000 0.836995 +-0.388750 0.081385 0.917742 +-0.554611 0.116109 0.823969 +-0.630298 0.000000 0.776353 +-0.547210 0.000000 0.836995 +-0.692103 0.144893 0.707107 +-0.630298 0.000000 0.776353 +-0.554611 0.116109 0.823969 +-0.692103 0.144893 0.707107 +-0.707107 0.000000 0.707107 +-0.630298 0.000000 0.776353 +-0.692103 0.144893 0.707107 +-0.776353 0.000000 0.630298 +-0.707107 0.000000 0.707107 +-0.806485 0.168839 0.566635 +-0.776353 0.000000 0.630298 +-0.692103 0.144893 0.707107 +-0.806485 0.168839 0.566635 +-0.836995 0.000000 0.547210 +-0.776353 0.000000 0.630298 +-0.898268 0.188054 0.397177 +-0.836995 0.000000 0.547210 +-0.806485 0.168839 0.566635 +-0.898268 0.188054 0.397177 +-0.929788 0.000000 0.368095 +-0.836995 0.000000 0.547210 +-0.958012 0.200561 0.204909 +-0.929788 0.000000 0.368095 +-0.898268 0.188054 0.397177 +-0.958012 0.200561 0.204909 +-0.983305 0.000000 0.181963 +-0.929788 0.000000 0.368095 +-0.983305 0.000000 0.181963 +-0.978781 0.204909 0.000000 +-1.000000 0.000000 0.000000 +-0.958012 0.200561 0.204909 +-0.978781 0.204909 0.000000 +-0.983305 0.000000 0.181963 +-0.898268 0.388750 0.204909 +-0.978781 0.204909 0.000000 +-0.958012 0.200561 0.204909 +-0.898268 0.388750 0.204909 +-0.917742 0.397177 0.000000 +-0.978781 0.204909 0.000000 +-0.806485 0.554611 0.204909 +-0.917742 0.397177 0.000000 +-0.898268 0.388750 0.204909 +-0.806485 0.554611 0.204909 +-0.823969 0.566635 0.000000 +-0.917742 0.397177 0.000000 +-0.692103 0.692103 0.204909 +-0.823969 0.566635 0.000000 +-0.806485 0.554611 0.204909 +-0.692103 0.692103 0.204909 +-0.707107 0.707107 0.000000 +-0.823969 0.566635 0.000000 +-0.692103 0.692103 0.204909 +-0.566635 0.823969 0.000000 +-0.707107 0.707107 0.000000 +-0.554611 0.806485 0.204909 +-0.566635 0.823969 0.000000 +-0.692103 0.692103 0.204909 +-0.554611 0.806485 0.204909 +-0.397177 0.917742 0.000000 +-0.566635 0.823969 0.000000 +-0.388750 0.898268 0.204909 +-0.397177 0.917742 0.000000 +-0.554611 0.806485 0.204909 +-0.200561 0.958012 0.204909 +-0.397177 0.917742 0.000000 +-0.388750 0.898268 0.204909 +-0.200561 0.958012 0.204909 +-0.204909 0.978781 0.000000 +-0.397177 0.917742 0.000000 +-0.204909 0.978781 0.000000 +0.000000 0.978781 0.204909 +0.000000 1.000000 0.000000 +-0.200561 0.958012 0.204909 +0.000000 0.978781 0.204909 +-0.204909 0.978781 0.000000 +-0.188054 0.898268 0.397177 +0.000000 0.978781 0.204909 +-0.200561 0.958012 0.204909 +-0.188054 0.898268 0.397177 +0.000000 0.917742 0.397177 +0.000000 0.978781 0.204909 +-0.188054 0.898268 0.397177 +0.000000 0.823969 0.566635 +0.000000 0.917742 0.397177 +-0.168839 0.806485 0.566635 +0.000000 0.823969 0.566635 +-0.188054 0.898268 0.397177 +-0.144893 0.692103 0.707107 +0.000000 0.823969 0.566635 +-0.168839 0.806485 0.566635 +-0.144893 0.692103 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.823969 0.566635 +-0.144893 0.692103 0.707107 +0.000000 0.566635 0.823969 +0.000000 0.707107 0.707107 +-0.116109 0.554611 0.823969 +0.000000 0.566635 0.823969 +-0.144893 0.692103 0.707107 +0.000000 0.204909 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.116109 0.168839 0.978781 +-0.144893 0.144893 0.978781 +0.000000 0.000000 1.000000 +-0.116109 0.168839 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.116109 0.168839 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.081385 0.188054 0.978781 +-0.116109 0.168839 0.978781 +0.000000 0.000000 1.000000 +-0.081385 0.188054 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.041988 0.200561 0.978781 +-0.081385 0.188054 0.978781 +0.000000 0.000000 1.000000 +-0.041988 0.200561 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.204909 0.978781 +-0.041988 0.200561 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.204909 0.978781 +-0.081385 0.388750 0.917742 +-0.041988 0.200561 0.978781 +0.000000 0.397177 0.917742 +-0.081385 0.388750 0.917742 +0.000000 0.204909 0.978781 +0.000000 0.566635 0.823969 +-0.081385 0.388750 0.917742 +0.000000 0.397177 0.917742 +-0.200561 0.041988 0.978781 +-0.364506 0.157750 0.917742 +-0.388750 0.081385 0.917742 +-0.364506 0.157750 0.917742 +-0.200561 0.041988 0.978781 +-0.188054 0.081385 0.978781 +-0.188054 0.081385 0.978781 +-0.327262 0.225054 0.917742 +-0.364506 0.157750 0.917742 +-0.327262 0.225054 0.917742 +-0.188054 0.081385 0.978781 +-0.168839 0.116109 0.978781 +-0.168839 0.116109 0.978781 +-0.280847 0.280847 0.917742 +-0.327262 0.225054 0.917742 +-0.280847 0.280847 0.917742 +-0.168839 0.116109 0.978781 +-0.144893 0.144893 0.978781 +-0.388750 0.081385 0.917742 +-0.520024 0.225054 0.823969 +-0.554611 0.116109 0.823969 +-0.520024 0.225054 0.823969 +-0.388750 0.081385 0.917742 +-0.364506 0.157750 0.917742 +-0.554611 0.116109 0.823969 +-0.648942 0.280847 0.707107 +-0.692103 0.144893 0.707107 +-0.648942 0.280847 0.707107 +-0.554611 0.116109 0.823969 +-0.520024 0.225054 0.823969 +-0.364506 0.157750 0.917742 +-0.466889 0.321075 0.823969 +-0.520024 0.225054 0.823969 +-0.466889 0.321075 0.823969 +-0.364506 0.157750 0.917742 +-0.327262 0.225054 0.917742 +-0.327262 0.225054 0.917742 +-0.400671 0.400671 0.823969 +-0.466889 0.321075 0.823969 +-0.400671 0.400671 0.823969 +-0.327262 0.225054 0.917742 +-0.280847 0.280847 0.917742 +-0.520024 0.225054 0.823969 +-0.582634 0.400671 0.707107 +-0.648942 0.280847 0.707107 +-0.582634 0.400671 0.707107 +-0.520024 0.225054 0.823969 +-0.466889 0.321075 0.823969 +-0.466889 0.321075 0.823969 +-0.500000 0.500000 0.707107 +-0.582634 0.400671 0.707107 +-0.500000 0.500000 0.707107 +-0.466889 0.321075 0.823969 +-0.400671 0.400671 0.823969 +-0.692103 0.144893 0.707107 +-0.756191 0.327262 0.566635 +-0.806485 0.168839 0.566635 +-0.756191 0.327262 0.566635 +-0.692103 0.144893 0.707107 +-0.648942 0.280847 0.707107 +-0.806485 0.168839 0.566635 +-0.842250 0.364506 0.397177 +-0.898268 0.188054 0.397177 +-0.842250 0.364506 0.397177 +-0.806485 0.168839 0.566635 +-0.756191 0.327262 0.566635 +-0.648942 0.280847 0.707107 +-0.678925 0.466889 0.566635 +-0.756191 0.327262 0.566635 +-0.678925 0.466889 0.566635 +-0.648942 0.280847 0.707107 +-0.582634 0.400671 0.707107 +-0.582634 0.400671 0.707107 +-0.582634 0.582634 0.566635 +-0.678925 0.466889 0.566635 +-0.582634 0.582634 0.566635 +-0.582634 0.400671 0.707107 +-0.500000 0.500000 0.707107 +-0.756191 0.327262 0.566635 +-0.756191 0.520024 0.397177 +-0.842250 0.364506 0.397177 +-0.756191 0.520024 0.397177 +-0.756191 0.327262 0.566635 +-0.678925 0.466889 0.566635 +-0.678925 0.466889 0.566635 +-0.648942 0.648942 0.397177 +-0.756191 0.520024 0.397177 +-0.648942 0.648942 0.397177 +-0.678925 0.466889 0.566635 +-0.582634 0.582634 0.566635 +-0.898268 0.188054 0.397177 +-0.898268 0.388750 0.204909 +-0.958012 0.200561 0.204909 +-0.898268 0.388750 0.204909 +-0.898268 0.188054 0.397177 +-0.842250 0.364506 0.397177 +-0.842250 0.364506 0.397177 +-0.806485 0.554611 0.204909 +-0.898268 0.388750 0.204909 +-0.806485 0.554611 0.204909 +-0.842250 0.364506 0.397177 +-0.756191 0.520024 0.397177 +-0.756191 0.520024 0.397177 +-0.692103 0.692103 0.204909 +-0.806485 0.554611 0.204909 +-0.692103 0.692103 0.204909 +-0.756191 0.520024 0.397177 +-0.648942 0.648942 0.397177 +-0.144893 0.144893 0.978781 +-0.225054 0.327262 0.917742 +-0.280847 0.280847 0.917742 +-0.225054 0.327262 0.917742 +-0.144893 0.144893 0.978781 +-0.116109 0.168839 0.978781 +-0.116109 0.168839 0.978781 +-0.157750 0.364506 0.917742 +-0.225054 0.327262 0.917742 +-0.157750 0.364506 0.917742 +-0.116109 0.168839 0.978781 +-0.081385 0.188054 0.978781 +-0.081385 0.188054 0.978781 +-0.081385 0.388750 0.917742 +-0.157750 0.364506 0.917742 +-0.081385 0.388750 0.917742 +-0.081385 0.188054 0.978781 +-0.041988 0.200561 0.978781 +-0.280847 0.280847 0.917742 +-0.321075 0.466889 0.823969 +-0.400671 0.400671 0.823969 +-0.321075 0.466889 0.823969 +-0.280847 0.280847 0.917742 +-0.225054 0.327262 0.917742 +-0.225054 0.327262 0.917742 +-0.225054 0.520024 0.823969 +-0.321075 0.466889 0.823969 +-0.225054 0.520024 0.823969 +-0.225054 0.327262 0.917742 +-0.157750 0.364506 0.917742 +-0.400671 0.400671 0.823969 +-0.400671 0.582634 0.707107 +-0.500000 0.500000 0.707107 +-0.400671 0.582634 0.707107 +-0.400671 0.400671 0.823969 +-0.321075 0.466889 0.823969 +-0.321075 0.466889 0.823969 +-0.280847 0.648942 0.707107 +-0.400671 0.582634 0.707107 +-0.280847 0.648942 0.707107 +-0.321075 0.466889 0.823969 +-0.225054 0.520024 0.823969 +-0.157750 0.364506 0.917742 +-0.116109 0.554611 0.823969 +-0.225054 0.520024 0.823969 +-0.116109 0.554611 0.823969 +-0.157750 0.364506 0.917742 +-0.081385 0.388750 0.917742 +-0.225054 0.520024 0.823969 +-0.144893 0.692103 0.707107 +-0.280847 0.648942 0.707107 +-0.144893 0.692103 0.707107 +-0.225054 0.520024 0.823969 +-0.116109 0.554611 0.823969 +-0.500000 0.500000 0.707107 +-0.466889 0.678925 0.566635 +-0.582634 0.582634 0.566635 +-0.466889 0.678925 0.566635 +-0.500000 0.500000 0.707107 +-0.400671 0.582634 0.707107 +-0.400671 0.582634 0.707107 +-0.327262 0.756191 0.566635 +-0.466889 0.678925 0.566635 +-0.327262 0.756191 0.566635 +-0.400671 0.582634 0.707107 +-0.280847 0.648942 0.707107 +-0.582634 0.582634 0.566635 +-0.520024 0.756191 0.397177 +-0.648942 0.648942 0.397177 +-0.520024 0.756191 0.397177 +-0.582634 0.582634 0.566635 +-0.466889 0.678925 0.566635 +-0.466889 0.678925 0.566635 +-0.364506 0.842250 0.397177 +-0.520024 0.756191 0.397177 +-0.364506 0.842250 0.397177 +-0.466889 0.678925 0.566635 +-0.327262 0.756191 0.566635 +-0.280847 0.648942 0.707107 +-0.168839 0.806485 0.566635 +-0.327262 0.756191 0.566635 +-0.168839 0.806485 0.566635 +-0.280847 0.648942 0.707107 +-0.144893 0.692103 0.707107 +-0.327262 0.756191 0.566635 +-0.188054 0.898268 0.397177 +-0.364506 0.842250 0.397177 +-0.188054 0.898268 0.397177 +-0.327262 0.756191 0.566635 +-0.168839 0.806485 0.566635 +-0.648942 0.648942 0.397177 +-0.554611 0.806485 0.204909 +-0.692103 0.692103 0.204909 +-0.554611 0.806485 0.204909 +-0.648942 0.648942 0.397177 +-0.520024 0.756191 0.397177 +-0.520024 0.756191 0.397177 +-0.388750 0.898268 0.204909 +-0.554611 0.806485 0.204909 +-0.388750 0.898268 0.204909 +-0.520024 0.756191 0.397177 +-0.364506 0.842250 0.397177 +-0.364506 0.842250 0.397177 +-0.200561 0.958012 0.204909 +-0.388750 0.898268 0.204909 +-0.200561 0.958012 0.204909 +-0.364506 0.842250 0.397177 +-0.188054 0.898268 0.397177 +0.916937 0.038431 0.397177 +0.977922 0.040987 0.204909 +0.977922 0.040987 0.204909 +0.999123 0.041876 0.000000 +0.977922 0.040987 0.204909 +0.999123 0.041876 0.000000 +0.977922 0.040987 0.204909 +0.977922 0.040987 0.204909 +0.999123 0.041876 0.000000 +0.204730 0.008581 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.204730 0.008581 0.978781 +0.204730 0.008581 0.978781 +0.000000 0.000000 1.000000 +0.396829 0.016632 0.917742 +0.204730 0.008581 0.978781 +0.204730 0.008581 0.978781 +0.396829 0.016632 0.917742 +0.396829 0.016632 0.917742 +0.204730 0.008581 0.978781 +0.566138 0.023728 0.823969 +0.396829 0.016632 0.917742 +0.396829 0.016632 0.917742 +0.566138 0.023728 0.823969 +0.566138 0.023728 0.823969 +0.396829 0.016632 0.917742 +0.566138 0.023728 0.823969 +0.706487 0.029611 0.707107 +0.566138 0.023728 0.823969 +0.706487 0.029611 0.707107 +0.706487 0.029611 0.707107 +0.566138 0.023728 0.823969 +0.823246 0.034504 0.566635 +0.706487 0.029611 0.707107 +0.706487 0.029611 0.707107 +0.823246 0.034504 0.566635 +0.823246 0.034504 0.566635 +0.706487 0.029611 0.707107 +0.916937 0.038431 0.397177 +0.823246 0.034504 0.566635 +0.823246 0.034504 0.566635 +0.916937 0.038431 0.397177 +0.916937 0.038431 0.397177 +0.823246 0.034504 0.566635 +0.977922 0.040987 0.204909 +0.916937 0.038431 0.397177 +0.916937 0.038431 0.397177 +0.000000 0.000000 1.000000 +-0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-0.978781 0.000000 0.204909 +-1.000000 0.000000 0.000000 +-0.978781 0.000000 0.204909 +-0.978781 0.000000 0.204909 +-1.000000 0.000000 0.000000 +-0.917742 0.000000 0.397177 +-0.978781 0.000000 0.204909 +-0.978781 0.000000 0.204909 +-0.917742 0.000000 0.397177 +-0.917742 0.000000 0.397177 +-0.978781 0.000000 0.204909 +-0.823969 0.000000 0.566635 +-0.917742 0.000000 0.397177 +-0.917742 0.000000 0.397177 +-0.823969 0.000000 0.566635 +-0.823969 0.000000 0.566635 +-0.917742 0.000000 0.397177 +-0.707107 0.000000 0.707107 +-0.823969 0.000000 0.566635 +-0.823969 0.000000 0.566635 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.823969 0.000000 0.566635 +-0.566635 0.000000 0.823969 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.566635 0.000000 0.823969 +-0.566635 0.000000 0.823969 +-0.707107 0.000000 0.707107 +-0.397177 0.000000 0.917742 +-0.566635 0.000000 0.823969 +-0.566635 0.000000 0.823969 +-0.397177 0.000000 0.917742 +-0.397177 0.000000 0.917742 +-0.566635 0.000000 0.823969 +-0.204909 0.000000 0.978781 +-0.397177 0.000000 0.917742 +-0.397177 0.000000 0.917742 +-0.204909 0.000000 0.978781 +-0.204909 0.000000 0.978781 +-0.397177 0.000000 0.917742 +-0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +-0.204909 0.000000 0.978781 +0.183114 -0.305170 0.934527 +0.000000 0.000000 1.000000 +0.000000 -0.317447 0.948276 +0.999123 0.041876 0.000000 +0.984637 -0.016912 0.173795 +0.999123 0.041876 0.000000 +0.982443 0.041177 0.181963 +0.984637 -0.016912 0.173795 +0.999123 0.041876 0.000000 +0.928973 0.038936 0.368095 +0.984637 -0.016912 0.173795 +0.982443 0.041177 0.181963 +0.928973 0.038936 0.368095 +0.932824 -0.078622 0.351650 +0.984637 -0.016912 0.173795 +0.836261 0.035050 0.547210 +0.932824 -0.078622 0.351650 +0.928973 0.038936 0.368095 +0.836261 0.035050 0.547210 +0.840993 -0.139729 0.522691 +0.932824 -0.078622 0.351650 +0.706487 0.029611 0.707107 +0.840993 -0.139729 0.522691 +0.836261 0.035050 0.547210 +0.706487 0.029611 0.707107 +0.711230 -0.196167 0.675034 +0.840993 -0.139729 0.522691 +0.546730 0.022915 0.836995 +0.711230 -0.196167 0.675034 +0.706487 0.029611 0.707107 +0.546730 0.022915 0.836995 +0.550718 -0.244124 0.798194 +0.711230 -0.196167 0.675034 +0.367772 0.015414 0.929788 +0.550718 -0.244124 0.798194 +0.546730 0.022915 0.836995 +0.367772 0.015414 0.929788 +0.370506 -0.280854 0.885351 +0.550718 -0.244124 0.798194 +0.181803 0.007620 0.983305 +0.370506 -0.280854 0.885351 +0.367772 0.015414 0.929788 +0.181803 0.007620 0.983305 +0.183114 -0.305170 0.934527 +0.370506 -0.280854 0.885351 +0.000000 0.000000 1.000000 +0.183114 -0.305170 0.934527 +0.181803 0.007620 0.983305 +-0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.898268 0.188054 0.397177 +-0.978781 0.000000 0.204909 +-0.958012 0.200561 0.204909 +-0.898268 0.188054 0.397177 +-0.917742 0.000000 0.397177 +-0.978781 0.000000 0.204909 +-0.806485 0.168839 0.566635 +-0.917742 0.000000 0.397177 +-0.898268 0.188054 0.397177 +-0.806485 0.168839 0.566635 +-0.823969 0.000000 0.566635 +-0.917742 0.000000 0.397177 +-0.692103 0.144893 0.707107 +-0.823969 0.000000 0.566635 +-0.806485 0.168839 0.566635 +-0.692103 0.144893 0.707107 +-0.707107 0.000000 0.707107 +-0.823969 0.000000 0.566635 +-0.978781 0.204909 0.000000 +-0.978781 0.000000 0.204909 +-1.000000 0.000000 0.000000 +-0.978781 0.204909 0.000000 +-0.958012 0.200561 0.204909 +-0.978781 0.000000 0.204909 +-0.978781 0.204909 0.000000 +-0.898268 0.388750 0.204909 +-0.958012 0.200561 0.204909 +-0.917742 0.397177 0.000000 +-0.898268 0.388750 0.204909 +-0.978781 0.204909 0.000000 +-0.823969 0.566635 0.000000 +-0.898268 0.388750 0.204909 +-0.917742 0.397177 0.000000 +-0.823969 0.566635 0.000000 +-0.806485 0.554611 0.204909 +-0.898268 0.388750 0.204909 +-0.823969 0.566635 0.000000 +-0.692103 0.692103 0.204909 +-0.806485 0.554611 0.204909 +-0.707107 0.707107 0.000000 +-0.692103 0.692103 0.204909 +-0.823969 0.566635 0.000000 +-0.566635 0.823969 0.000000 +-0.692103 0.692103 0.204909 +-0.707107 0.707107 0.000000 +-0.566635 0.823969 0.000000 +-0.554611 0.806485 0.204909 +-0.692103 0.692103 0.204909 +-0.397177 0.917742 0.000000 +-0.554611 0.806485 0.204909 +-0.566635 0.823969 0.000000 +-0.397177 0.917742 0.000000 +-0.388750 0.898268 0.204909 +-0.554611 0.806485 0.204909 +-0.204909 0.978781 0.000000 +-0.388750 0.898268 0.204909 +-0.397177 0.917742 0.000000 +-0.204909 0.978781 0.000000 +-0.200561 0.958012 0.204909 +-0.388750 0.898268 0.204909 +0.000000 1.000000 0.000000 +-0.200561 0.958012 0.204909 +-0.204909 0.978781 0.000000 +0.000000 0.978781 0.204909 +-0.200561 0.958012 0.204909 +0.000000 1.000000 0.000000 +0.000000 0.978781 0.204909 +-0.188054 0.898268 0.397177 +-0.200561 0.958012 0.204909 +0.000000 0.917742 0.397177 +-0.188054 0.898268 0.397177 +0.000000 0.978781 0.204909 +0.000000 0.823969 0.566635 +-0.188054 0.898268 0.397177 +0.000000 0.917742 0.397177 +0.000000 0.823969 0.566635 +-0.168839 0.806485 0.566635 +-0.188054 0.898268 0.397177 +0.000000 0.823969 0.566635 +-0.144893 0.692103 0.707107 +-0.168839 0.806485 0.566635 +0.000000 0.707107 0.707107 +-0.144893 0.692103 0.707107 +0.000000 0.823969 0.566635 +0.000000 0.566635 0.823969 +-0.144893 0.692103 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.566635 0.823969 +-0.116109 0.554611 0.823969 +-0.144893 0.692103 0.707107 +0.000000 0.397177 0.917742 +-0.116109 0.554611 0.823969 +0.000000 0.566635 0.823969 +0.000000 0.397177 0.917742 +-0.081385 0.388750 0.917742 +-0.116109 0.554611 0.823969 +0.000000 0.204909 0.978781 +-0.081385 0.388750 0.917742 +0.000000 0.397177 0.917742 +0.000000 0.204909 0.978781 +-0.041988 0.200561 0.978781 +-0.081385 0.388750 0.917742 +0.000000 0.000000 1.000000 +-0.041988 0.200561 0.978781 +0.000000 0.204909 0.978781 +0.000000 0.000000 1.000000 +-0.041988 0.200561 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.041988 0.200561 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.081385 0.188054 0.978781 +-0.041988 0.200561 0.978781 +0.000000 0.000000 1.000000 +-0.081385 0.188054 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.116109 0.168839 0.978781 +-0.081385 0.188054 0.978781 +0.000000 0.000000 1.000000 +-0.116109 0.168839 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.144893 0.144893 0.978781 +-0.116109 0.168839 0.978781 +0.000000 0.000000 1.000000 +-0.144893 0.144893 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.168839 0.116109 0.978781 +-0.144893 0.144893 0.978781 +0.000000 0.000000 1.000000 +-0.168839 0.116109 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.168839 0.116109 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.188054 0.081385 0.978781 +-0.168839 0.116109 0.978781 +0.000000 0.000000 1.000000 +-0.188054 0.081385 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.200561 0.041988 0.978781 +-0.188054 0.081385 0.978781 +0.000000 0.000000 1.000000 +-0.200561 0.041988 0.978781 +0.000000 0.000000 1.000000 +-0.554611 0.116109 0.823969 +-0.707107 0.000000 0.707107 +-0.692103 0.144893 0.707107 +-0.554611 0.116109 0.823969 +-0.566635 0.000000 0.823969 +-0.707107 0.000000 0.707107 +-0.554611 0.116109 0.823969 +-0.397177 0.000000 0.917742 +-0.566635 0.000000 0.823969 +-0.388750 0.081385 0.917742 +-0.397177 0.000000 0.917742 +-0.554611 0.116109 0.823969 +-0.388750 0.081385 0.917742 +-0.204909 0.000000 0.978781 +-0.397177 0.000000 0.917742 +-0.200561 0.041988 0.978781 +-0.204909 0.000000 0.978781 +-0.388750 0.081385 0.917742 +0.000000 0.000000 1.000000 +-0.204909 0.000000 0.978781 +-0.200561 0.041988 0.978781 +-0.958012 0.200561 0.204909 +-0.842250 0.364506 0.397177 +-0.898268 0.188054 0.397177 +-0.842250 0.364506 0.397177 +-0.958012 0.200561 0.204909 +-0.898268 0.388750 0.204909 +-0.898268 0.388750 0.204909 +-0.756191 0.520024 0.397177 +-0.842250 0.364506 0.397177 +-0.756191 0.520024 0.397177 +-0.898268 0.388750 0.204909 +-0.806485 0.554611 0.204909 +-0.806485 0.554611 0.204909 +-0.648942 0.648942 0.397177 +-0.756191 0.520024 0.397177 +-0.648942 0.648942 0.397177 +-0.806485 0.554611 0.204909 +-0.692103 0.692103 0.204909 +-0.898268 0.188054 0.397177 +-0.756191 0.327262 0.566635 +-0.806485 0.168839 0.566635 +-0.756191 0.327262 0.566635 +-0.898268 0.188054 0.397177 +-0.842250 0.364506 0.397177 +-0.806485 0.168839 0.566635 +-0.648942 0.280847 0.707107 +-0.692103 0.144893 0.707107 +-0.648942 0.280847 0.707107 +-0.806485 0.168839 0.566635 +-0.756191 0.327262 0.566635 +-0.842250 0.364506 0.397177 +-0.678925 0.466889 0.566635 +-0.756191 0.327262 0.566635 +-0.678925 0.466889 0.566635 +-0.842250 0.364506 0.397177 +-0.756191 0.520024 0.397177 +-0.756191 0.520024 0.397177 +-0.582634 0.582634 0.566635 +-0.678925 0.466889 0.566635 +-0.582634 0.582634 0.566635 +-0.756191 0.520024 0.397177 +-0.648942 0.648942 0.397177 +-0.756191 0.327262 0.566635 +-0.582634 0.400671 0.707107 +-0.648942 0.280847 0.707107 +-0.582634 0.400671 0.707107 +-0.756191 0.327262 0.566635 +-0.678925 0.466889 0.566635 +-0.678925 0.466889 0.566635 +-0.500000 0.500000 0.707107 +-0.582634 0.400671 0.707107 +-0.500000 0.500000 0.707107 +-0.678925 0.466889 0.566635 +-0.582634 0.582634 0.566635 +-0.692103 0.144893 0.707107 +-0.520024 0.225054 0.823969 +-0.554611 0.116109 0.823969 +-0.520024 0.225054 0.823969 +-0.692103 0.144893 0.707107 +-0.648942 0.280847 0.707107 +-0.554611 0.116109 0.823969 +-0.364506 0.157750 0.917742 +-0.388750 0.081385 0.917742 +-0.364506 0.157750 0.917742 +-0.554611 0.116109 0.823969 +-0.520024 0.225054 0.823969 +-0.648942 0.280847 0.707107 +-0.466889 0.321075 0.823969 +-0.520024 0.225054 0.823969 +-0.466889 0.321075 0.823969 +-0.648942 0.280847 0.707107 +-0.582634 0.400671 0.707107 +-0.582634 0.400671 0.707107 +-0.400671 0.400671 0.823969 +-0.466889 0.321075 0.823969 +-0.400671 0.400671 0.823969 +-0.582634 0.400671 0.707107 +-0.500000 0.500000 0.707107 +-0.520024 0.225054 0.823969 +-0.327262 0.225054 0.917742 +-0.364506 0.157750 0.917742 +-0.327262 0.225054 0.917742 +-0.520024 0.225054 0.823969 +-0.466889 0.321075 0.823969 +-0.466889 0.321075 0.823969 +-0.280847 0.280847 0.917742 +-0.327262 0.225054 0.917742 +-0.280847 0.280847 0.917742 +-0.466889 0.321075 0.823969 +-0.400671 0.400671 0.823969 +-0.388750 0.081385 0.917742 +-0.188054 0.081385 0.978781 +-0.200561 0.041988 0.978781 +-0.188054 0.081385 0.978781 +-0.388750 0.081385 0.917742 +-0.364506 0.157750 0.917742 +-0.364506 0.157750 0.917742 +-0.168839 0.116109 0.978781 +-0.188054 0.081385 0.978781 +-0.168839 0.116109 0.978781 +-0.364506 0.157750 0.917742 +-0.327262 0.225054 0.917742 +-0.327262 0.225054 0.917742 +-0.144893 0.144893 0.978781 +-0.168839 0.116109 0.978781 +-0.144893 0.144893 0.978781 +-0.327262 0.225054 0.917742 +-0.280847 0.280847 0.917742 +-0.692103 0.692103 0.204909 +-0.520024 0.756191 0.397177 +-0.648942 0.648942 0.397177 +-0.520024 0.756191 0.397177 +-0.692103 0.692103 0.204909 +-0.554611 0.806485 0.204909 +-0.554611 0.806485 0.204909 +-0.364506 0.842250 0.397177 +-0.520024 0.756191 0.397177 +-0.364506 0.842250 0.397177 +-0.554611 0.806485 0.204909 +-0.388750 0.898268 0.204909 +-0.388750 0.898268 0.204909 +-0.188054 0.898268 0.397177 +-0.364506 0.842250 0.397177 +-0.188054 0.898268 0.397177 +-0.388750 0.898268 0.204909 +-0.200561 0.958012 0.204909 +-0.648942 0.648942 0.397177 +-0.466889 0.678925 0.566635 +-0.582634 0.582634 0.566635 +-0.466889 0.678925 0.566635 +-0.648942 0.648942 0.397177 +-0.520024 0.756191 0.397177 +-0.520024 0.756191 0.397177 +-0.327262 0.756191 0.566635 +-0.466889 0.678925 0.566635 +-0.327262 0.756191 0.566635 +-0.520024 0.756191 0.397177 +-0.364506 0.842250 0.397177 +-0.582634 0.582634 0.566635 +-0.400671 0.582634 0.707107 +-0.500000 0.500000 0.707107 +-0.400671 0.582634 0.707107 +-0.582634 0.582634 0.566635 +-0.466889 0.678925 0.566635 +-0.466889 0.678925 0.566635 +-0.280847 0.648942 0.707107 +-0.400671 0.582634 0.707107 +-0.280847 0.648942 0.707107 +-0.466889 0.678925 0.566635 +-0.327262 0.756191 0.566635 +-0.364506 0.842250 0.397177 +-0.168839 0.806485 0.566635 +-0.327262 0.756191 0.566635 +-0.168839 0.806485 0.566635 +-0.364506 0.842250 0.397177 +-0.188054 0.898268 0.397177 +-0.327262 0.756191 0.566635 +-0.144893 0.692103 0.707107 +-0.280847 0.648942 0.707107 +-0.144893 0.692103 0.707107 +-0.327262 0.756191 0.566635 +-0.168839 0.806485 0.566635 +-0.500000 0.500000 0.707107 +-0.321075 0.466889 0.823969 +-0.400671 0.400671 0.823969 +-0.321075 0.466889 0.823969 +-0.500000 0.500000 0.707107 +-0.400671 0.582634 0.707107 +-0.400671 0.582634 0.707107 +-0.225054 0.520024 0.823969 +-0.321075 0.466889 0.823969 +-0.225054 0.520024 0.823969 +-0.400671 0.582634 0.707107 +-0.280847 0.648942 0.707107 +-0.400671 0.400671 0.823969 +-0.225054 0.327262 0.917742 +-0.280847 0.280847 0.917742 +-0.225054 0.327262 0.917742 +-0.400671 0.400671 0.823969 +-0.321075 0.466889 0.823969 +-0.321075 0.466889 0.823969 +-0.157750 0.364506 0.917742 +-0.225054 0.327262 0.917742 +-0.157750 0.364506 0.917742 +-0.321075 0.466889 0.823969 +-0.225054 0.520024 0.823969 +-0.280847 0.648942 0.707107 +-0.116109 0.554611 0.823969 +-0.225054 0.520024 0.823969 +-0.116109 0.554611 0.823969 +-0.280847 0.648942 0.707107 +-0.144893 0.692103 0.707107 +-0.225054 0.520024 0.823969 +-0.081385 0.388750 0.917742 +-0.157750 0.364506 0.917742 +-0.081385 0.388750 0.917742 +-0.225054 0.520024 0.823969 +-0.116109 0.554611 0.823969 +-0.280847 0.280847 0.917742 +-0.116109 0.168839 0.978781 +-0.144893 0.144893 0.978781 +-0.116109 0.168839 0.978781 +-0.280847 0.280847 0.917742 +-0.225054 0.327262 0.917742 +-0.225054 0.327262 0.917742 +-0.081385 0.188054 0.978781 +-0.116109 0.168839 0.978781 +-0.081385 0.188054 0.978781 +-0.225054 0.327262 0.917742 +-0.157750 0.364506 0.917742 +-0.157750 0.364506 0.917742 +-0.041988 0.200561 0.978781 +-0.081385 0.188054 0.978781 +-0.041988 0.200561 0.978781 +-0.157750 0.364506 0.917742 +-0.081385 0.388750 0.917742 +-0.000001 -0.196750 -0.980454 +0.234938 -0.395031 -0.888119 +-0.000002 -0.399136 -0.916892 +-0.000001 -0.999108 -0.042228 +-0.000014 -0.983714 0.179740 +0.000000 -0.987887 0.155172 +0.216342 -0.591644 -0.776630 +-0.000002 -0.399136 -0.916892 +0.234938 -0.395031 -0.888119 +0.216342 -0.591644 -0.776630 +-0.000004 -0.592372 -0.805665 +-0.000002 -0.399136 -0.916892 +0.216342 -0.591644 -0.776630 +-0.000005 -0.759991 -0.649934 +-0.000004 -0.592372 -0.805665 +0.185667 -0.761846 -0.620579 +-0.000005 -0.759991 -0.649934 +0.216342 -0.591644 -0.776630 +0.144917 -0.890709 -0.430855 +-0.000005 -0.759991 -0.649934 +0.185667 -0.761846 -0.620579 +0.144917 -0.890709 -0.430855 +-0.000004 -0.887826 -0.460180 +-0.000005 -0.759991 -0.649934 +0.097674 -0.969772 -0.223613 +-0.000004 -0.887826 -0.460180 +0.144917 -0.890709 -0.430855 +0.097674 -0.969772 -0.223613 +-0.000003 -0.967721 -0.252025 +-0.000004 -0.887826 -0.460180 +0.097674 -0.969772 -0.223613 +-0.000001 -0.999108 -0.042228 +-0.000003 -0.967721 -0.252025 +0.048121 -0.998713 -0.015998 +-0.000001 -0.999108 -0.042228 +0.097674 -0.969772 -0.223613 +0.048121 -0.998713 -0.015998 +-0.000014 -0.983714 0.179740 +-0.000001 -0.999108 -0.042228 +0.096979 -0.993132 0.065456 +-0.000014 -0.983714 0.179740 +0.048121 -0.998713 -0.015998 +0.096979 -0.993132 0.065456 +-0.000032 -0.967924 0.251243 +-0.000014 -0.983714 0.179740 +0.143644 -0.969028 0.200878 +-0.000032 -0.967924 0.251243 +0.096979 -0.993132 0.065456 +0.143644 -0.969028 0.200878 +-0.000093 -0.932241 0.361837 +-0.000032 -0.967924 0.251243 +0.180266 -0.908326 0.377423 +-0.000093 -0.932241 0.361837 +0.143644 -0.969028 0.200878 +0.180266 -0.908326 0.377423 +0.000009 -0.867611 0.497244 +-0.000093 -0.932241 0.361837 +0.198768 -0.800499 0.565414 +0.000009 -0.867611 0.497244 +0.180266 -0.908326 0.377423 +0.198768 -0.800499 0.565414 +0.000064 -0.769532 0.638608 +0.000009 -0.867611 0.497244 +0.199861 -0.653674 0.729909 +0.000064 -0.769532 0.638608 +0.198768 -0.800499 0.565414 +0.199861 -0.653674 0.729909 +0.000012 -0.640634 0.767846 +0.000064 -0.769532 0.638608 +0.192093 -0.484654 0.853353 +0.000012 -0.640634 0.767846 +0.199861 -0.653674 0.729909 +0.192093 -0.484654 0.853353 +0.000001 -0.487673 0.873026 +0.000012 -0.640634 0.767846 +0.192093 -0.484654 0.853353 +0.000000 -0.317447 0.948276 +0.000001 -0.487673 0.873026 +0.192093 -0.484654 0.853353 +0.183114 -0.305170 0.934527 +0.000000 -0.317447 0.948276 +0.389316 -0.457048 0.799712 +0.183114 -0.305170 0.934527 +0.192093 -0.484654 0.853353 +0.389316 -0.457048 0.799712 +0.370506 -0.280852 0.885352 +0.183114 -0.305170 0.934527 +0.389316 -0.457048 0.799712 +0.550718 -0.244121 0.798195 +0.370506 -0.280852 0.885352 +0.578110 -0.407282 0.707044 +0.550718 -0.244121 0.798195 +0.389316 -0.457048 0.799712 +0.578110 -0.407282 0.707044 +0.711230 -0.196164 0.675035 +0.550718 -0.244121 0.798195 +0.743476 -0.336584 0.577888 +0.711230 -0.196164 0.675035 +0.578110 -0.407282 0.707044 +0.743476 -0.336584 0.577888 +0.840993 -0.139727 0.522692 +0.711230 -0.196164 0.675035 +0.872393 -0.249386 0.420401 +0.840993 -0.139727 0.522692 +0.743476 -0.336584 0.577888 +0.957010 -0.152457 0.246758 +0.840993 -0.139727 0.522692 +0.872393 -0.249386 0.420401 +0.957010 -0.152457 0.246758 +0.932824 -0.078621 0.351651 +0.840993 -0.139727 0.522692 +0.996109 -0.053266 0.070212 +0.932824 -0.078621 0.351651 +0.957010 -0.152457 0.246758 +0.996109 -0.053266 0.070212 +0.984637 -0.016911 0.173795 +0.932824 -0.078621 0.351651 +0.996109 -0.053266 0.070212 +0.999123 0.041876 0.000000 +0.984637 -0.016911 0.173795 +0.996109 -0.053266 0.070212 +0.993776 0.041673 -0.103308 +0.999123 0.041876 0.000000 +0.992266 -0.091761 -0.083598 +0.993776 0.041673 -0.103308 +0.996109 -0.053266 0.070212 +0.992266 -0.091761 -0.083598 +0.968136 0.040598 -0.247111 +0.993776 0.041673 -0.103308 +0.950394 -0.129327 -0.282888 +0.968136 0.040598 -0.247111 +0.992266 -0.091761 -0.083598 +0.950394 -0.129327 -0.282888 +0.907078 0.038064 -0.419239 +0.968136 0.040598 -0.247111 +0.848751 -0.158951 -0.504338 +0.907078 0.038064 -0.419239 +0.950394 -0.129327 -0.282888 +0.848751 -0.158951 -0.504338 +0.799666 0.033559 -0.599507 +0.907078 0.038064 -0.419239 +0.684442 -0.175947 -0.707518 +0.799666 0.033559 -0.599507 +0.848751 -0.158951 -0.504338 +0.684442 -0.175947 -0.707518 +0.645227 0.026983 -0.763514 +0.799666 0.033559 -0.599507 +0.474661 -0.183845 -0.860755 +0.645227 0.026983 -0.763514 +0.684442 -0.175947 -0.707518 +0.474661 -0.183845 -0.860755 +0.451897 0.018942 -0.891869 +0.645227 0.026983 -0.763514 +0.241419 -0.189352 -0.951768 +0.451897 0.018942 -0.891869 +0.474661 -0.183845 -0.860755 +0.241419 -0.189352 -0.951768 +0.232153 0.009729 -0.972631 +0.451897 0.018942 -0.891869 +0.241419 -0.189352 -0.951768 +0.000000 0.000000 -1.000000 +0.232153 0.009729 -0.972631 +0.241419 -0.189352 -0.951768 +-0.000001 -0.196750 -0.980454 +0.000000 0.000000 -1.000000 +0.234938 -0.395031 -0.888119 +-0.000001 -0.196750 -0.980454 +0.241419 -0.189352 -0.951768 +0.241419 -0.189352 -0.951768 +0.466390 -0.394460 -0.791759 +0.234938 -0.395031 -0.888119 +0.466390 -0.394460 -0.791759 +0.241419 -0.189352 -0.951768 +0.474661 -0.183845 -0.860755 +0.234938 -0.395031 -0.888119 +0.432743 -0.595752 -0.676619 +0.216342 -0.591644 -0.776630 +0.432743 -0.595752 -0.676619 +0.234938 -0.395031 -0.888119 +0.466390 -0.394460 -0.791759 +0.216342 -0.591644 -0.776630 +0.373330 -0.768668 -0.519399 +0.185667 -0.761846 -0.620579 +0.373330 -0.768668 -0.519399 +0.216342 -0.591644 -0.776630 +0.432743 -0.595752 -0.676619 +0.185667 -0.761846 -0.620579 +0.292208 -0.896887 -0.331977 +0.144917 -0.890709 -0.430855 +0.292208 -0.896887 -0.331977 +0.185667 -0.761846 -0.620579 +0.373330 -0.768668 -0.519399 +0.144917 -0.890709 -0.430855 +0.197066 -0.971561 -0.131279 +0.097674 -0.969772 -0.223613 +0.197066 -0.971561 -0.131279 +0.144917 -0.890709 -0.430855 +0.292208 -0.896887 -0.331977 +0.097674 -0.969772 -0.223613 +0.096979 -0.993132 0.065456 +0.048121 -0.998713 -0.015998 +0.096979 -0.993132 0.065456 +0.097674 -0.969772 -0.223613 +0.197066 -0.971561 -0.131279 +0.474661 -0.183845 -0.860755 +0.679621 -0.387850 -0.622646 +0.466390 -0.394460 -0.791759 +0.679621 -0.387850 -0.622646 +0.474661 -0.183845 -0.860755 +0.684442 -0.175947 -0.707518 +0.466390 -0.394460 -0.791759 +0.635819 -0.590308 -0.497263 +0.432743 -0.595752 -0.676619 +0.635819 -0.590308 -0.497263 +0.466390 -0.394460 -0.791759 +0.679621 -0.387850 -0.622646 +0.432743 -0.595752 -0.676619 +0.551643 -0.762744 -0.337507 +0.373330 -0.768668 -0.519399 +0.551643 -0.762744 -0.337507 +0.432743 -0.595752 -0.676619 +0.635819 -0.590308 -0.497263 +0.684442 -0.175947 -0.707518 +0.846732 -0.360491 -0.391268 +0.679621 -0.387850 -0.622646 +0.846732 -0.360491 -0.391268 +0.684442 -0.175947 -0.707518 +0.848751 -0.158951 -0.504338 +0.679621 -0.387850 -0.622646 +0.795078 -0.553314 -0.248385 +0.635819 -0.590308 -0.497263 +0.795078 -0.553314 -0.248385 +0.679621 -0.387850 -0.622646 +0.846732 -0.360491 -0.391268 +0.635819 -0.590308 -0.497263 +0.691556 -0.717269 -0.085294 +0.551643 -0.762744 -0.337507 +0.691556 -0.717269 -0.085294 +0.635819 -0.590308 -0.497263 +0.795078 -0.553314 -0.248385 +0.373330 -0.768668 -0.519399 +0.433077 -0.887630 -0.156710 +0.292208 -0.896887 -0.331977 +0.433077 -0.887630 -0.156710 +0.373330 -0.768668 -0.519399 +0.551643 -0.762744 -0.337507 +0.292208 -0.896887 -0.331977 +0.292249 -0.955931 0.028036 +0.197066 -0.971561 -0.131279 +0.292249 -0.955931 0.028036 +0.292208 -0.896887 -0.331977 +0.433077 -0.887630 -0.156710 +0.197066 -0.971561 -0.131279 +0.143644 -0.969028 0.200878 +0.096979 -0.993132 0.065456 +0.143644 -0.969028 0.200878 +0.197066 -0.971561 -0.131279 +0.292249 -0.955931 0.028036 +0.551643 -0.762744 -0.337507 +0.543640 -0.835178 0.083273 +0.433077 -0.887630 -0.156710 +0.543640 -0.835178 0.083273 +0.551643 -0.762744 -0.337507 +0.691556 -0.717269 -0.085294 +0.433077 -0.887630 -0.156710 +0.366956 -0.898323 0.241577 +0.292249 -0.955931 0.028036 +0.366956 -0.898323 0.241577 +0.433077 -0.887630 -0.156710 +0.543640 -0.835178 0.083273 +0.292249 -0.955931 0.028036 +0.180266 -0.908326 0.377423 +0.143644 -0.969028 0.200878 +0.180266 -0.908326 0.377423 +0.292249 -0.955931 0.028036 +0.366956 -0.898323 0.241577 +0.848751 -0.158951 -0.504338 +0.942414 -0.304609 -0.138092 +0.846732 -0.360491 -0.391268 +0.942414 -0.304609 -0.138092 +0.848751 -0.158951 -0.504338 +0.950394 -0.129327 -0.282888 +0.846732 -0.360491 -0.391268 +0.880732 -0.473053 0.023068 +0.795078 -0.553314 -0.248385 +0.880732 -0.473053 0.023068 +0.846732 -0.360491 -0.391268 +0.942414 -0.304609 -0.138092 +0.795078 -0.553314 -0.248385 +0.763572 -0.617832 0.187727 +0.691556 -0.717269 -0.085294 +0.763572 -0.617832 0.187727 +0.795078 -0.553314 -0.248385 +0.880732 -0.473053 0.023068 +0.950394 -0.129327 -0.282888 +0.969565 -0.230159 0.083487 +0.942414 -0.304609 -0.138092 +0.969565 -0.230159 0.083487 +0.950394 -0.129327 -0.282888 +0.992266 -0.091761 -0.083598 +0.942414 -0.304609 -0.138092 +0.895688 -0.364133 0.255246 +0.880732 -0.473053 0.023068 +0.895688 -0.364133 0.255246 +0.942414 -0.304609 -0.138092 +0.969565 -0.230159 0.083487 +0.880732 -0.473053 0.023068 +0.770389 -0.481723 0.417666 +0.763572 -0.617832 0.187727 +0.770389 -0.481723 0.417666 +0.880732 -0.473053 0.023068 +0.895688 -0.364133 0.255246 +0.691556 -0.717269 -0.085294 +0.599223 -0.724429 0.340785 +0.543640 -0.835178 0.083273 +0.599223 -0.724429 0.340785 +0.691556 -0.717269 -0.085294 +0.763572 -0.617832 0.187727 +0.543640 -0.835178 0.083273 +0.404335 -0.785091 0.469196 +0.366956 -0.898323 0.241577 +0.404335 -0.785091 0.469196 +0.543640 -0.835178 0.083273 +0.599223 -0.724429 0.340785 +0.366956 -0.898323 0.241577 +0.198768 -0.800499 0.565414 +0.180266 -0.908326 0.377423 +0.198768 -0.800499 0.565414 +0.366956 -0.898323 0.241577 +0.404335 -0.785091 0.469196 +0.763572 -0.617832 0.187727 +0.602019 -0.572380 0.556735 +0.599223 -0.724429 0.340785 +0.602019 -0.572380 0.556735 +0.763572 -0.617832 0.187727 +0.770389 -0.481723 0.417666 +0.599223 -0.724429 0.340785 +0.405863 -0.629893 0.662201 +0.404335 -0.785091 0.469196 +0.405863 -0.629893 0.662201 +0.599223 -0.724429 0.340785 +0.602019 -0.572380 0.556735 +0.404335 -0.785091 0.469196 +0.199861 -0.653674 0.729909 +0.198768 -0.800499 0.565414 +0.199861 -0.653674 0.729909 +0.404335 -0.785091 0.469196 +0.405863 -0.629893 0.662201 +0.992266 -0.091761 -0.083598 +0.957010 -0.152457 0.246758 +0.969565 -0.230159 0.083487 +0.957010 -0.152457 0.246758 +0.992266 -0.091761 -0.083598 +0.996109 -0.053266 0.070212 +0.969565 -0.230159 0.083487 +0.872393 -0.249386 0.420401 +0.895688 -0.364133 0.255246 +0.872393 -0.249386 0.420401 +0.969565 -0.230159 0.083487 +0.957010 -0.152457 0.246758 +0.895688 -0.364133 0.255246 +0.743476 -0.336584 0.577888 +0.770389 -0.481723 0.417666 +0.743476 -0.336584 0.577888 +0.895688 -0.364133 0.255246 +0.872393 -0.249386 0.420401 +0.770389 -0.481723 0.417666 +0.578110 -0.407282 0.707044 +0.602019 -0.572380 0.556735 +0.578110 -0.407282 0.707044 +0.770389 -0.481723 0.417666 +0.743476 -0.336584 0.577888 +0.602019 -0.572380 0.556735 +0.389316 -0.457048 0.799712 +0.405863 -0.629893 0.662201 +0.389316 -0.457048 0.799712 +0.602019 -0.572380 0.556735 +0.578110 -0.407282 0.707044 +0.405863 -0.629893 0.662201 +0.192093 -0.484654 0.853353 +0.199861 -0.653674 0.729909 +0.192093 -0.484654 0.853353 +0.405863 -0.629893 0.662201 +0.389316 -0.457048 0.799712 +0.000000 0.204909 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.978781 0.204909 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.978781 0.204909 +0.000000 0.978781 0.204909 +0.000000 1.000000 0.000000 +0.000000 0.978781 0.204909 +0.000000 0.917742 0.397177 +0.000000 0.978781 0.204909 +0.000000 0.917742 0.397177 +0.000000 0.917742 0.397177 +0.000000 0.978781 0.204909 +0.000000 0.917742 0.397177 +0.000000 0.823969 0.566635 +0.000000 0.917742 0.397177 +0.000000 0.823969 0.566635 +0.000000 0.823969 0.566635 +0.000000 0.917742 0.397177 +0.000000 0.707107 0.707107 +0.000000 0.823969 0.566635 +0.000000 0.823969 0.566635 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.823969 0.566635 +0.000000 0.566635 0.823969 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.566635 0.823969 +0.000000 0.566635 0.823969 +0.000000 0.707107 0.707107 +0.000000 0.397177 0.917742 +0.000000 0.566635 0.823969 +0.000000 0.566635 0.823969 +0.000000 0.397177 0.917742 +0.000000 0.397177 0.917742 +0.000000 0.566635 0.823969 +0.000000 0.397177 0.917742 +0.000000 0.204909 0.978781 +0.000000 0.397177 0.917742 +0.000000 0.204909 0.978781 +0.000000 0.204909 0.978781 +0.000000 0.397177 0.917742 +0.000000 0.000000 1.000000 +0.000000 0.204909 0.978781 +0.000000 0.204909 0.978781 +0.000000 -0.467394 -0.884049 +0.000000 -0.629039 -0.777374 +0.000000 -0.629039 -0.777374 +0.000000 -0.987887 0.155172 +0.000000 -0.996967 0.077822 +0.000000 -0.987887 0.155172 +0.000000 -0.996967 0.077822 +0.000000 -0.996967 0.077822 +0.000000 -0.987887 0.155172 +0.000000 -0.996967 0.077822 +0.000000 -0.991759 -0.128117 +0.000000 -0.996967 0.077822 +0.000000 -0.991759 -0.128117 +0.000000 -0.991759 -0.128117 +0.000000 -0.996967 0.077822 +0.000000 -0.945868 -0.324552 +0.000000 -0.991759 -0.128117 +0.000000 -0.991759 -0.128117 +0.000000 -0.945868 -0.324552 +0.000000 -0.945868 -0.324552 +0.000000 -0.991759 -0.128117 +0.000000 -0.865567 -0.500793 +0.000000 -0.945868 -0.324552 +0.000000 -0.945868 -0.324552 +0.000000 -0.865567 -0.500793 +0.000000 -0.865567 -0.500793 +0.000000 -0.945868 -0.324552 +0.000000 -0.759991 -0.649934 +0.000000 -0.865567 -0.500793 +0.000000 -0.865567 -0.500793 +0.000000 -0.759991 -0.649934 +0.000000 -0.759991 -0.649934 +0.000000 -0.865567 -0.500793 +0.000000 -0.759991 -0.649934 +0.000000 -0.629039 -0.777374 +0.000000 -0.759991 -0.649934 +0.000000 -0.629039 -0.777374 +0.000000 -0.629039 -0.777374 +0.000000 -0.759991 -0.649934 +0.000000 -0.077822 -0.996967 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -0.077822 -0.996967 +0.000000 -0.077822 -0.996967 +0.000000 0.000000 -1.000000 +0.000000 -0.280459 -0.959866 +0.000000 -0.077822 -0.996967 +0.000000 -0.077822 -0.996967 +0.000000 -0.280459 -0.959866 +0.000000 -0.280459 -0.959866 +0.000000 -0.077822 -0.996967 +0.000000 -0.280459 -0.959866 +0.000000 -0.467394 -0.884049 +0.000000 -0.280459 -0.959866 +0.000000 -0.467394 -0.884049 +0.000000 -0.467394 -0.884049 +0.000000 -0.280459 -0.959866 +0.000000 -0.629039 -0.777374 +0.000000 -0.467394 -0.884049 +0.000000 -0.467394 -0.884049 +0.000000 0.181963 0.983305 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.688916 0.159355 0.707107 +-0.775672 0.032510 0.630298 +-0.706487 0.029611 0.707107 +-0.802773 0.185692 0.566635 +-0.775672 0.032510 0.630298 +-0.688916 0.159355 0.707107 +-0.802773 0.185692 0.566635 +-0.836261 0.035050 0.547210 +-0.775672 0.032510 0.630298 +-0.894133 0.206825 0.397177 +-0.836261 0.035050 0.547210 +-0.802773 0.185692 0.566635 +-0.894133 0.206825 0.397177 +-0.928973 0.038935 0.368095 +-0.836261 0.035050 0.547210 +-0.953602 0.220581 0.204909 +-0.928973 0.038935 0.368095 +-0.894133 0.206825 0.397177 +-0.953602 0.220581 0.204909 +-0.982443 0.041177 0.181963 +-0.928973 0.038935 0.368095 +-0.982443 0.041177 0.181963 +-0.974275 0.225363 0.000000 +-0.999123 0.041876 0.000000 +-0.953602 0.220581 0.204909 +-0.974275 0.225363 0.000000 +-0.982443 0.041177 0.181963 +-0.889930 0.407476 0.204909 +-0.974275 0.225363 0.000000 +-0.953602 0.220581 0.204909 +-0.889930 0.407476 0.204909 +-0.909223 0.416310 0.000000 +-0.974275 0.225363 0.000000 +-0.794694 0.571379 0.204909 +-0.909223 0.416310 0.000000 +-0.889930 0.407476 0.204909 +-0.794694 0.571379 0.204909 +-0.811922 0.583766 0.000000 +-0.909223 0.416310 0.000000 +-0.677457 0.706445 0.204909 +-0.811922 0.583766 0.000000 +-0.794694 0.571379 0.204909 +-0.677457 0.706445 0.204909 +-0.692143 0.721760 0.000000 +-0.811922 0.583766 0.000000 +-0.677457 0.706445 0.204909 +-0.549254 0.835655 0.000000 +-0.692143 0.721760 0.000000 +-0.537600 0.817923 0.204909 +-0.549254 0.835655 0.000000 +-0.677457 0.706445 0.204909 +0.000000 0.000000 1.000000 +-0.181803 0.007620 0.983305 +0.000000 0.000000 1.000000 +-0.706487 0.029611 0.707107 +-0.552058 0.127698 0.823969 +-0.688916 0.159355 0.707107 +-0.629745 0.026394 0.776353 +-0.552058 0.127698 0.823969 +-0.706487 0.029611 0.707107 +-0.546730 0.022915 0.836995 +-0.552058 0.127698 0.823969 +-0.629745 0.026394 0.776353 +-0.546730 0.022915 0.836995 +-0.386960 0.089509 0.917742 +-0.552058 0.127698 0.823969 +-0.367772 0.015414 0.929788 +-0.386960 0.089509 0.917742 +-0.546730 0.022915 0.836995 +-0.367772 0.015414 0.929788 +-0.199638 0.046179 0.978781 +-0.386960 0.089509 0.917742 +-0.181803 0.007620 0.983305 +-0.199638 0.046179 0.978781 +-0.367772 0.015414 0.929788 +0.000000 0.000000 1.000000 +-0.199638 0.046179 0.978781 +-0.181803 0.007620 0.983305 +0.000000 0.000000 1.000000 +-0.199638 0.046179 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.186308 0.085306 0.978781 +-0.199638 0.046179 0.978781 +0.000000 0.000000 1.000000 +-0.186308 0.085306 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.166370 0.119619 0.978781 +-0.186308 0.085306 0.978781 +0.000000 0.000000 1.000000 +-0.166370 0.119619 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.141827 0.147896 0.978781 +-0.166370 0.119619 0.978781 +0.000000 0.000000 1.000000 +-0.112547 0.171234 0.978781 +-0.141827 0.147896 0.978781 +0.000000 0.000000 1.000000 +-0.112547 0.171234 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.077429 0.189717 0.978781 +-0.112547 0.171234 0.978781 +0.000000 0.000000 1.000000 +-0.077429 0.189717 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.037778 0.201397 0.978781 +-0.077429 0.189717 0.978781 +0.000000 0.000000 1.000000 +-0.037778 0.201397 0.978781 +0.000000 0.000000 1.000000 +-0.369852 0.906213 0.204909 +-0.549254 0.835655 0.000000 +-0.537600 0.817923 0.204909 +-0.369852 0.906213 0.204909 +-0.377871 0.925858 0.000000 +-0.549254 0.835655 0.000000 +-0.180454 0.962002 0.204909 +-0.377871 0.925858 0.000000 +-0.369852 0.906213 0.204909 +-0.180454 0.962002 0.204909 +-0.184366 0.982858 0.000000 +-0.377871 0.925858 0.000000 +-0.180454 0.962002 0.204909 +0.000000 1.000000 0.000000 +-0.184366 0.982858 0.000000 +-0.180454 0.962002 0.204909 +0.000000 0.983305 0.181963 +0.000000 1.000000 0.000000 +-0.180454 0.962002 0.204909 +0.000000 0.929788 0.368095 +0.000000 0.983305 0.181963 +-0.169201 0.902010 0.397177 +0.000000 0.929788 0.368095 +-0.180454 0.962002 0.204909 +-0.169201 0.902010 0.397177 +0.000000 0.836995 0.547210 +0.000000 0.929788 0.368095 +-0.151912 0.809844 0.566635 +0.000000 0.836995 0.547210 +-0.169201 0.902010 0.397177 +-0.151912 0.809844 0.566635 +0.000000 0.776353 0.630298 +0.000000 0.836995 0.547210 +-0.130367 0.694985 0.707107 +0.000000 0.776353 0.630298 +-0.151912 0.809844 0.566635 +-0.130367 0.694985 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.776353 0.630298 +-0.104468 0.556921 0.823969 +0.000000 0.707107 0.707107 +-0.130367 0.694985 0.707107 +-0.104468 0.556921 0.823969 +0.000000 0.630298 0.776353 +0.000000 0.707107 0.707107 +-0.104468 0.556921 0.823969 +0.000000 0.547210 0.836995 +0.000000 0.630298 0.776353 +-0.073226 0.390369 0.917742 +0.000000 0.547210 0.836995 +-0.104468 0.556921 0.823969 +-0.073226 0.390369 0.917742 +0.000000 0.368095 0.929788 +0.000000 0.547210 0.836995 +-0.037778 0.201397 0.978781 +0.000000 0.368095 0.929788 +-0.073226 0.390369 0.917742 +-0.037778 0.201397 0.978781 +0.000000 0.181963 0.983305 +0.000000 0.368095 0.929788 +0.000000 0.000000 1.000000 +0.000000 0.181963 0.983305 +-0.037778 0.201397 0.978781 +-0.199638 0.046179 0.978781 +-0.361123 0.165349 0.917742 +-0.386960 0.089509 0.917742 +-0.361123 0.165349 0.917742 +-0.199638 0.046179 0.978781 +-0.186308 0.085306 0.978781 +-0.186308 0.085306 0.978781 +-0.322477 0.231859 0.917742 +-0.361123 0.165349 0.917742 +-0.322477 0.231859 0.917742 +-0.186308 0.085306 0.978781 +-0.166370 0.119619 0.978781 +-0.166370 0.119619 0.978781 +-0.274904 0.286667 0.917742 +-0.322477 0.231859 0.917742 +-0.274904 0.286667 0.917742 +-0.166370 0.119619 0.978781 +-0.141827 0.147896 0.978781 +-0.386960 0.089509 0.917742 +-0.515197 0.235896 0.823969 +-0.552058 0.127698 0.823969 +-0.515197 0.235896 0.823969 +-0.386960 0.089509 0.917742 +-0.361123 0.165349 0.917742 +-0.552058 0.127698 0.823969 +-0.642918 0.294376 0.707107 +-0.688916 0.159355 0.707107 +-0.642918 0.294376 0.707107 +-0.552058 0.127698 0.823969 +-0.515197 0.235896 0.823969 +-0.361123 0.165349 0.917742 +-0.460063 0.330782 0.823969 +-0.515197 0.235896 0.823969 +-0.460063 0.330782 0.823969 +-0.361123 0.165349 0.917742 +-0.322477 0.231859 0.917742 +-0.322477 0.231859 0.917742 +-0.392192 0.408974 0.823969 +-0.460063 0.330782 0.823969 +-0.392192 0.408974 0.823969 +-0.322477 0.231859 0.917742 +-0.274904 0.286667 0.917742 +-0.515197 0.235896 0.823969 +-0.574115 0.412785 0.707107 +-0.642918 0.294376 0.707107 +-0.574115 0.412785 0.707107 +-0.515197 0.235896 0.823969 +-0.460063 0.330782 0.823969 +-0.460063 0.330782 0.823969 +-0.489419 0.510362 0.707107 +-0.574115 0.412785 0.707107 +-0.489419 0.510362 0.707107 +-0.460063 0.330782 0.823969 +-0.392192 0.408974 0.823969 +-0.688916 0.159355 0.707107 +-0.749172 0.343027 0.566635 +-0.802773 0.185692 0.566635 +-0.749172 0.343027 0.566635 +-0.688916 0.159355 0.707107 +-0.642918 0.294376 0.707107 +-0.802773 0.185692 0.566635 +-0.834432 0.382065 0.397177 +-0.894133 0.206825 0.397177 +-0.834432 0.382065 0.397177 +-0.802773 0.185692 0.566635 +-0.749172 0.343027 0.566635 +-0.642918 0.294376 0.707107 +-0.668999 0.481005 0.566635 +-0.749172 0.343027 0.566635 +-0.668999 0.481005 0.566635 +-0.642918 0.294376 0.707107 +-0.574115 0.412785 0.707107 +-0.574115 0.412785 0.707107 +-0.570305 0.594708 0.566635 +-0.668999 0.481005 0.566635 +-0.570305 0.594708 0.566635 +-0.574115 0.412785 0.707107 +-0.489419 0.510362 0.707107 +-0.749172 0.343027 0.566635 +-0.745135 0.535747 0.397177 +-0.834432 0.382065 0.397177 +-0.745135 0.535747 0.397177 +-0.749172 0.343027 0.566635 +-0.668999 0.481005 0.566635 +-0.668999 0.481005 0.566635 +-0.635209 0.662390 0.397177 +-0.745135 0.535747 0.397177 +-0.635209 0.662390 0.397177 +-0.668999 0.481005 0.566635 +-0.570305 0.594708 0.566635 +-0.894133 0.206825 0.397177 +-0.889930 0.407476 0.204909 +-0.953602 0.220581 0.204909 +-0.889930 0.407476 0.204909 +-0.894133 0.206825 0.397177 +-0.834432 0.382065 0.397177 +-0.834432 0.382065 0.397177 +-0.794694 0.571379 0.204909 +-0.889930 0.407476 0.204909 +-0.794694 0.571379 0.204909 +-0.834432 0.382065 0.397177 +-0.745135 0.535747 0.397177 +-0.745135 0.535747 0.397177 +-0.677457 0.706445 0.204909 +-0.794694 0.571379 0.204909 +-0.677457 0.706445 0.204909 +-0.745135 0.535747 0.397177 +-0.635209 0.662390 0.397177 +-0.141827 0.147896 0.978781 +-0.218151 0.331903 0.917742 +-0.274904 0.286667 0.917742 +-0.218151 0.331903 0.917742 +-0.141827 0.147896 0.978781 +-0.112547 0.171234 0.978781 +-0.112547 0.171234 0.978781 +-0.150082 0.367730 0.917742 +-0.218151 0.331903 0.917742 +-0.150082 0.367730 0.917742 +-0.112547 0.171234 0.978781 +-0.077429 0.189717 0.978781 +-0.077429 0.189717 0.978781 +-0.073226 0.390369 0.917742 +-0.150082 0.367730 0.917742 +-0.073226 0.390369 0.917742 +-0.077429 0.189717 0.978781 +-0.037778 0.201397 0.978781 +-0.274904 0.286667 0.917742 +-0.311227 0.473511 0.823969 +-0.392192 0.408974 0.823969 +-0.311227 0.473511 0.823969 +-0.274904 0.286667 0.917742 +-0.218151 0.331903 0.917742 +-0.218151 0.331903 0.917742 +-0.214115 0.524623 0.823969 +-0.311227 0.473511 0.823969 +-0.214115 0.524623 0.823969 +-0.218151 0.331903 0.917742 +-0.150082 0.367730 0.917742 +-0.392192 0.408974 0.823969 +-0.388382 0.590897 0.707107 +-0.489419 0.510362 0.707107 +-0.388382 0.590897 0.707107 +-0.392192 0.408974 0.823969 +-0.311227 0.473511 0.823969 +-0.311227 0.473511 0.823969 +-0.267195 0.654681 0.707107 +-0.388382 0.590897 0.707107 +-0.267195 0.654681 0.707107 +-0.311227 0.473511 0.823969 +-0.214115 0.524623 0.823969 +-0.150082 0.367730 0.917742 +-0.104468 0.556921 0.823969 +-0.214115 0.524623 0.823969 +-0.104468 0.556921 0.823969 +-0.150082 0.367730 0.917742 +-0.073226 0.390369 0.917742 +-0.214115 0.524623 0.823969 +-0.130367 0.694985 0.707107 +-0.267195 0.654681 0.707107 +-0.130367 0.694985 0.707107 +-0.214115 0.524623 0.823969 +-0.104468 0.556921 0.823969 +-0.489419 0.510362 0.707107 +-0.452569 0.688554 0.566635 +-0.570305 0.594708 0.566635 +-0.452569 0.688554 0.566635 +-0.489419 0.510362 0.707107 +-0.388382 0.590897 0.707107 +-0.388382 0.590897 0.707107 +-0.311354 0.762879 0.566635 +-0.452569 0.688554 0.566635 +-0.311354 0.762879 0.566635 +-0.388382 0.590897 0.707107 +-0.267195 0.654681 0.707107 +-0.570305 0.594708 0.566635 +-0.504074 0.766916 0.397177 +-0.635209 0.662390 0.397177 +-0.504074 0.766916 0.397177 +-0.570305 0.594708 0.566635 +-0.452569 0.688554 0.566635 +-0.452569 0.688554 0.566635 +-0.346788 0.849699 0.397177 +-0.504074 0.766916 0.397177 +-0.346788 0.849699 0.397177 +-0.452569 0.688554 0.566635 +-0.311354 0.762879 0.566635 +-0.267195 0.654681 0.707107 +-0.151912 0.809844 0.566635 +-0.311354 0.762879 0.566635 +-0.151912 0.809844 0.566635 +-0.267195 0.654681 0.707107 +-0.130367 0.694985 0.707107 +-0.311354 0.762879 0.566635 +-0.169201 0.902010 0.397177 +-0.346788 0.849699 0.397177 +-0.169201 0.902010 0.397177 +-0.311354 0.762879 0.566635 +-0.151912 0.809844 0.566635 +-0.635209 0.662390 0.397177 +-0.537600 0.817923 0.204909 +-0.677457 0.706445 0.204909 +-0.537600 0.817923 0.204909 +-0.635209 0.662390 0.397177 +-0.504074 0.766916 0.397177 +-0.504074 0.766916 0.397177 +-0.369852 0.906213 0.204909 +-0.537600 0.817923 0.204909 +-0.369852 0.906213 0.204909 +-0.504074 0.766916 0.397177 +-0.346788 0.849699 0.397177 +-0.346788 0.849699 0.397177 +-0.180454 0.962002 0.204909 +-0.369852 0.906213 0.204909 +-0.180454 0.962002 0.204909 +-0.346788 0.849699 0.397177 +-0.169201 0.902010 0.397177 +0.000020 -0.931910 0.362691 +-0.143931 -0.968764 0.201939 +-0.000035 -0.967841 0.251563 +-0.956906 -0.152100 0.247381 +-0.984637 -0.016911 0.173795 +-0.996076 -0.053089 0.070814 +-0.956906 -0.152100 0.247381 +-0.932824 -0.078621 0.351651 +-0.984637 -0.016911 0.173795 +-0.872246 -0.248857 0.421018 +-0.932824 -0.078621 0.351651 +-0.956906 -0.152100 0.247381 +-0.872246 -0.248857 0.421018 +-0.840993 -0.139728 0.522692 +-0.932824 -0.078621 0.351651 +0.000015 -0.983705 0.179788 +0.000001 -0.999108 -0.042228 +0.000000 -0.987887 0.155172 +-0.999123 0.041876 0.000000 +-0.996076 -0.053089 0.070814 +-0.984637 -0.016911 0.173795 +-0.993839 0.041677 -0.102702 +-0.996076 -0.053089 0.070814 +-0.999123 0.041876 0.000000 +-0.993839 0.041677 -0.102702 +-0.992372 -0.091537 -0.082572 +-0.996076 -0.053089 0.070814 +-0.968373 0.040606 -0.246182 +-0.992372 -0.091537 -0.082572 +-0.993839 0.041677 -0.102702 +-0.968373 0.040606 -0.246182 +-0.950943 -0.129049 -0.281166 +-0.992372 -0.091537 -0.082572 +-0.907694 0.038097 -0.417900 +-0.950943 -0.129049 -0.281166 +-0.968373 0.040606 -0.246182 +-0.801082 0.033450 -0.597620 +-0.950943 -0.129049 -0.281166 +-0.907694 0.038097 -0.417900 +-0.801082 0.033450 -0.597620 +-0.850333 -0.158674 -0.501754 +-0.950943 -0.129049 -0.281166 +-0.801082 0.033450 -0.597620 +-0.685709 -0.175872 -0.706309 +-0.850333 -0.158674 -0.501754 +-0.646236 0.026986 -0.762660 +-0.685709 -0.175872 -0.706309 +-0.801082 0.033450 -0.597620 +-0.646236 0.026986 -0.762660 +-0.475480 -0.183824 -0.860306 +-0.685709 -0.175872 -0.706309 +-0.452585 0.018971 -0.891519 +-0.475480 -0.183824 -0.860306 +-0.646236 0.026986 -0.762660 +-0.452585 0.018971 -0.891519 +-0.241704 -0.189345 -0.951697 +-0.475480 -0.183824 -0.860306 +-0.232404 0.009740 -0.972571 +-0.241704 -0.189345 -0.951697 +-0.452585 0.018971 -0.891519 +0.000000 0.000000 -1.000000 +-0.241704 -0.189345 -0.951697 +-0.232404 0.009740 -0.972571 +0.000001 -0.196750 -0.980454 +-0.241704 -0.189345 -0.951697 +0.000000 0.000000 -1.000000 +0.000002 -0.399136 -0.916892 +-0.241704 -0.189345 -0.951697 +0.000001 -0.196750 -0.980454 +0.000002 -0.399136 -0.916892 +-0.235218 -0.395029 -0.888045 +-0.241704 -0.189345 -0.951697 +0.000004 -0.592372 -0.805665 +-0.235218 -0.395029 -0.888045 +0.000002 -0.399136 -0.916892 +0.000004 -0.592372 -0.805665 +-0.216602 -0.591648 -0.776554 +-0.235218 -0.395029 -0.888045 +0.000005 -0.759991 -0.649934 +-0.216602 -0.591648 -0.776554 +0.000004 -0.592372 -0.805665 +0.000005 -0.759991 -0.649934 +-0.185891 -0.761853 -0.620503 +-0.216602 -0.591648 -0.776554 +0.000005 -0.759991 -0.649934 +-0.145092 -0.890717 -0.430781 +-0.185891 -0.761853 -0.620503 +0.000004 -0.887826 -0.460180 +-0.145092 -0.890717 -0.430781 +0.000005 -0.759991 -0.649934 +0.000003 -0.967721 -0.252025 +-0.145092 -0.890717 -0.430781 +0.000004 -0.887826 -0.460180 +0.000003 -0.967721 -0.252025 +-0.097792 -0.969776 -0.223542 +-0.145092 -0.890717 -0.430781 +0.000001 -0.999108 -0.042228 +-0.097792 -0.969776 -0.223542 +0.000003 -0.967721 -0.252025 +0.000001 -0.999108 -0.042228 +-0.048179 -0.998712 -0.015934 +-0.097792 -0.969776 -0.223542 +0.000015 -0.983705 0.179788 +-0.048179 -0.998712 -0.015934 +0.000001 -0.999108 -0.042228 +-0.000035 -0.967841 0.251563 +-0.048179 -0.998712 -0.015934 +0.000015 -0.983705 0.179788 +-0.000035 -0.967841 0.251563 +-0.097156 -0.993088 0.065855 +-0.048179 -0.998712 -0.015934 +-0.000035 -0.967841 0.251563 +-0.143931 -0.968764 0.201939 +-0.097156 -0.993088 0.065855 +-0.743320 -0.335911 0.578480 +-0.840993 -0.139728 0.522692 +-0.872246 -0.248857 0.421018 +-0.743320 -0.335911 0.578480 +-0.711230 -0.196165 0.675035 +-0.840993 -0.139728 0.522692 +-0.743320 -0.335911 0.578480 +-0.550718 -0.244122 0.798194 +-0.711230 -0.196165 0.675035 +-0.577976 -0.406507 0.707599 +-0.550718 -0.244122 0.798194 +-0.743320 -0.335911 0.578480 +-0.389224 -0.456224 0.800228 +-0.550718 -0.244122 0.798194 +-0.577976 -0.406507 0.707599 +-0.389224 -0.456224 0.800228 +-0.370506 -0.280853 0.885351 +-0.550718 -0.244122 0.798194 +-0.192049 -0.483831 0.853830 +-0.370506 -0.280853 0.885351 +-0.389224 -0.456224 0.800228 +-0.192049 -0.483831 0.853830 +-0.183114 -0.305170 0.934527 +-0.370506 -0.280853 0.885351 +-0.192049 -0.483831 0.853830 +0.000000 -0.317447 0.948276 +-0.183114 -0.305170 0.934527 +-0.192049 -0.483831 0.853830 +0.000000 -0.486950 0.873430 +0.000000 -0.317447 0.948276 +-0.192049 -0.483831 0.853830 +-0.000012 -0.639834 0.768513 +0.000000 -0.486950 0.873430 +-0.199832 -0.652750 0.730743 +-0.000012 -0.639834 0.768513 +-0.192049 -0.483831 0.853830 +-0.199832 -0.652750 0.730743 +-0.000027 -0.768641 0.639681 +-0.000012 -0.639834 0.768513 +-0.198836 -0.799461 0.566856 +-0.000027 -0.768641 0.639681 +-0.199832 -0.652750 0.730743 +-0.180600 -0.907333 0.379645 +-0.000027 -0.768641 0.639681 +-0.198836 -0.799461 0.566856 +-0.180600 -0.907333 0.379645 +0.000026 -0.866796 0.498662 +-0.000027 -0.768641 0.639681 +-0.180600 -0.907333 0.379645 +0.000020 -0.931910 0.362691 +0.000026 -0.866796 0.498662 +-0.143931 -0.968764 0.201939 +0.000020 -0.931910 0.362691 +-0.180600 -0.907333 0.379645 +-0.996076 -0.053089 0.070814 +-0.969575 -0.229710 0.084602 +-0.956906 -0.152100 0.247381 +-0.969575 -0.229710 0.084602 +-0.996076 -0.053089 0.070814 +-0.992372 -0.091537 -0.082572 +-0.956906 -0.152100 0.247381 +-0.895629 -0.363472 0.256393 +-0.872246 -0.248857 0.421018 +-0.895629 -0.363472 0.256393 +-0.956906 -0.152100 0.247381 +-0.969575 -0.229710 0.084602 +-0.872246 -0.248857 0.421018 +-0.770297 -0.480892 0.418791 +-0.743320 -0.335911 0.578480 +-0.770297 -0.480892 0.418791 +-0.872246 -0.248857 0.421018 +-0.895629 -0.363472 0.256393 +-0.743320 -0.335911 0.578480 +-0.601930 -0.571445 0.557791 +-0.577976 -0.406507 0.707599 +-0.601930 -0.571445 0.557791 +-0.743320 -0.335911 0.578480 +-0.770297 -0.480892 0.418791 +-0.577976 -0.406507 0.707599 +-0.405801 -0.628929 0.663154 +-0.389224 -0.456224 0.800228 +-0.405801 -0.628929 0.663154 +-0.577976 -0.406507 0.707599 +-0.601930 -0.571445 0.557791 +-0.389224 -0.456224 0.800228 +-0.199832 -0.652750 0.730743 +-0.192049 -0.483831 0.853830 +-0.199832 -0.652750 0.730743 +-0.389224 -0.456224 0.800228 +-0.405801 -0.628929 0.663154 +-0.992372 -0.091537 -0.082572 +-0.942873 -0.304067 -0.136142 +-0.969575 -0.229710 0.084602 +-0.942873 -0.304067 -0.136142 +-0.992372 -0.091537 -0.082572 +-0.950943 -0.129049 -0.281166 +-0.969575 -0.229710 0.084602 +-0.881098 -0.472265 0.025140 +-0.895629 -0.363472 0.256393 +-0.881098 -0.472265 0.025140 +-0.969575 -0.229710 0.084602 +-0.942873 -0.304067 -0.136142 +-0.895629 -0.363472 0.256393 +-0.763852 -0.616853 0.189797 +-0.770297 -0.480892 0.418791 +-0.763852 -0.616853 0.189797 +-0.895629 -0.363472 0.256393 +-0.881098 -0.472265 0.025140 +-0.950943 -0.129049 -0.281166 +-0.848306 -0.359997 -0.388303 +-0.942873 -0.304067 -0.136142 +-0.848306 -0.359997 -0.388303 +-0.950943 -0.129049 -0.281166 +-0.850333 -0.158674 -0.501754 +-0.942873 -0.304067 -0.136142 +-0.796552 -0.552618 -0.245189 +-0.881098 -0.472265 0.025140 +-0.796552 -0.552618 -0.245189 +-0.942873 -0.304067 -0.136142 +-0.848306 -0.359997 -0.388303 +-0.881098 -0.472265 0.025140 +-0.692837 -0.716409 -0.082063 +-0.763852 -0.616853 0.189797 +-0.692837 -0.716409 -0.082063 +-0.881098 -0.472265 0.025140 +-0.796552 -0.552618 -0.245189 +-0.770297 -0.480892 0.418791 +-0.599427 -0.723341 0.342732 +-0.601930 -0.571445 0.557791 +-0.599427 -0.723341 0.342732 +-0.770297 -0.480892 0.418791 +-0.763852 -0.616853 0.189797 +-0.601930 -0.571445 0.557791 +-0.404471 -0.783987 0.470921 +-0.405801 -0.628929 0.663154 +-0.404471 -0.783987 0.470921 +-0.601930 -0.571445 0.557791 +-0.599427 -0.723341 0.342732 +-0.405801 -0.628929 0.663154 +-0.198836 -0.799461 0.566856 +-0.199832 -0.652750 0.730743 +-0.198836 -0.799461 0.566856 +-0.405801 -0.628929 0.663154 +-0.404471 -0.783987 0.470921 +-0.763852 -0.616853 0.189797 +-0.544646 -0.834211 0.086331 +-0.599427 -0.723341 0.342732 +-0.544646 -0.834211 0.086331 +-0.763852 -0.616853 0.189797 +-0.692837 -0.716409 -0.082063 +-0.599427 -0.723341 0.342732 +-0.367635 -0.897313 0.244281 +-0.404471 -0.783987 0.470921 +-0.367635 -0.897313 0.244281 +-0.599427 -0.723341 0.342732 +-0.544646 -0.834211 0.086331 +-0.404471 -0.783987 0.470921 +-0.180600 -0.907333 0.379645 +-0.198836 -0.799461 0.566856 +-0.180600 -0.907333 0.379645 +-0.404471 -0.783987 0.470921 +-0.367635 -0.897313 0.244281 +-0.850333 -0.158674 -0.501754 +-0.680919 -0.387753 -0.621287 +-0.848306 -0.359997 -0.388303 +-0.680919 -0.387753 -0.621287 +-0.850333 -0.158674 -0.501754 +-0.685709 -0.175872 -0.706309 +-0.848306 -0.359997 -0.388303 +-0.637062 -0.590191 -0.495809 +-0.796552 -0.552618 -0.245189 +-0.637062 -0.590191 -0.495809 +-0.848306 -0.359997 -0.388303 +-0.680919 -0.387753 -0.621287 +-0.796552 -0.552618 -0.245189 +-0.552739 -0.762602 -0.336031 +-0.692837 -0.716409 -0.082063 +-0.552739 -0.762602 -0.336031 +-0.796552 -0.552618 -0.245189 +-0.637062 -0.590191 -0.495809 +-0.685709 -0.175872 -0.706309 +-0.467214 -0.394455 -0.791275 +-0.680919 -0.387753 -0.621287 +-0.467214 -0.394455 -0.791275 +-0.685709 -0.175872 -0.706309 +-0.475480 -0.183824 -0.860306 +-0.680919 -0.387753 -0.621287 +-0.433522 -0.595762 -0.676111 +-0.637062 -0.590191 -0.495809 +-0.433522 -0.595762 -0.676111 +-0.680919 -0.387753 -0.621287 +-0.467214 -0.394455 -0.791275 +-0.637062 -0.590191 -0.495809 +-0.374010 -0.768684 -0.518885 +-0.552739 -0.762602 -0.336031 +-0.374010 -0.768684 -0.518885 +-0.637062 -0.590191 -0.495809 +-0.433522 -0.595762 -0.676111 +-0.692837 -0.716409 -0.082063 +-0.433945 -0.887454 -0.155297 +-0.544646 -0.834211 0.086331 +-0.433945 -0.887454 -0.155297 +-0.692837 -0.716409 -0.082063 +-0.552739 -0.762602 -0.336031 +-0.544646 -0.834211 0.086331 +-0.292835 -0.955714 0.029305 +-0.367635 -0.897313 0.244281 +-0.292835 -0.955714 0.029305 +-0.544646 -0.834211 0.086331 +-0.433945 -0.887454 -0.155297 +-0.367635 -0.897313 0.244281 +-0.143931 -0.968764 0.201939 +-0.180600 -0.907333 0.379645 +-0.143931 -0.968764 0.201939 +-0.367635 -0.897313 0.244281 +-0.292835 -0.955714 0.029305 +-0.552739 -0.762602 -0.336031 +-0.292744 -0.896896 -0.331478 +-0.433945 -0.887454 -0.155297 +-0.292744 -0.896896 -0.331478 +-0.552739 -0.762602 -0.336031 +-0.374010 -0.768684 -0.518885 +-0.433945 -0.887454 -0.155297 +-0.197427 -0.971550 -0.130819 +-0.292835 -0.955714 0.029305 +-0.197427 -0.971550 -0.130819 +-0.433945 -0.887454 -0.155297 +-0.292744 -0.896896 -0.331478 +-0.292835 -0.955714 0.029305 +-0.097156 -0.993088 0.065855 +-0.143931 -0.968764 0.201939 +-0.097156 -0.993088 0.065855 +-0.292835 -0.955714 0.029305 +-0.197427 -0.971550 -0.130819 +-0.475480 -0.183824 -0.860306 +-0.235218 -0.395029 -0.888045 +-0.467214 -0.394455 -0.791275 +-0.235218 -0.395029 -0.888045 +-0.475480 -0.183824 -0.860306 +-0.241704 -0.189345 -0.951697 +-0.467214 -0.394455 -0.791275 +-0.216602 -0.591648 -0.776554 +-0.433522 -0.595762 -0.676111 +-0.216602 -0.591648 -0.776554 +-0.467214 -0.394455 -0.791275 +-0.235218 -0.395029 -0.888045 +-0.433522 -0.595762 -0.676111 +-0.185891 -0.761853 -0.620503 +-0.374010 -0.768684 -0.518885 +-0.185891 -0.761853 -0.620503 +-0.433522 -0.595762 -0.676111 +-0.216602 -0.591648 -0.776554 +-0.374010 -0.768684 -0.518885 +-0.145092 -0.890717 -0.430781 +-0.292744 -0.896896 -0.331478 +-0.145092 -0.890717 -0.430781 +-0.374010 -0.768684 -0.518885 +-0.185891 -0.761853 -0.620503 +-0.292744 -0.896896 -0.331478 +-0.097792 -0.969776 -0.223542 +-0.197427 -0.971550 -0.130819 +-0.097792 -0.969776 -0.223542 +-0.292744 -0.896896 -0.331478 +-0.145092 -0.890717 -0.430781 +-0.197427 -0.971550 -0.130819 +-0.048179 -0.998712 -0.015934 +-0.097156 -0.993088 0.065855 +-0.048179 -0.998712 -0.015934 +-0.197427 -0.971550 -0.130819 +-0.097792 -0.969776 -0.223542 +-0.977922 0.040987 0.204909 +-0.999123 0.041876 0.000000 +-0.999123 0.041876 0.000000 +-0.204730 0.008581 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.204730 0.008581 0.978781 +-0.204730 0.008581 0.978781 +0.000000 0.000000 1.000000 +-0.396829 0.016632 0.917742 +-0.204730 0.008581 0.978781 +-0.204730 0.008581 0.978781 +-0.396829 0.016632 0.917742 +-0.396829 0.016632 0.917742 +-0.204730 0.008581 0.978781 +-0.566138 0.023728 0.823969 +-0.396829 0.016632 0.917742 +-0.396829 0.016632 0.917742 +-0.566138 0.023728 0.823969 +-0.566138 0.023728 0.823969 +-0.396829 0.016632 0.917742 +-0.706487 0.029611 0.707107 +-0.566138 0.023728 0.823969 +-0.566138 0.023728 0.823969 +-0.706487 0.029611 0.707107 +-0.706487 0.029611 0.707107 +-0.566138 0.023728 0.823969 +-0.823246 0.034504 0.566635 +-0.706487 0.029611 0.707107 +-0.706487 0.029611 0.707107 +-0.823246 0.034504 0.566635 +-0.823246 0.034504 0.566635 +-0.706487 0.029611 0.707107 +-0.916937 0.038431 0.397177 +-0.823246 0.034504 0.566635 +-0.823246 0.034504 0.566635 +-0.916937 0.038431 0.397177 +-0.916937 0.038431 0.397177 +-0.823246 0.034504 0.566635 +-0.977922 0.040987 0.204909 +-0.916937 0.038431 0.397177 +-0.916937 0.038431 0.397177 +-0.977922 0.040987 0.204909 +-0.977922 0.040987 0.204909 +-0.916937 0.038431 0.397177 +-0.999123 0.041876 0.000000 +-0.977922 0.040987 0.204909 +-0.977922 0.040987 0.204909 +-0.984637 -0.016912 0.173795 +-0.999123 0.041876 0.000000 +-0.999123 0.041876 0.000000 +-0.181803 0.007620 0.983305 +0.000000 -0.317447 0.948276 +0.000000 0.000000 1.000000 +-0.181803 0.007620 0.983305 +-0.183114 -0.305170 0.934527 +0.000000 -0.317447 0.948276 +-0.367772 0.015414 0.929788 +-0.183114 -0.305170 0.934527 +-0.181803 0.007620 0.983305 +-0.367772 0.015414 0.929788 +-0.370506 -0.280854 0.885351 +-0.183114 -0.305170 0.934527 +-0.367772 0.015414 0.929788 +-0.550718 -0.244124 0.798194 +-0.370506 -0.280854 0.885351 +-0.546730 0.022915 0.836995 +-0.550718 -0.244124 0.798194 +-0.367772 0.015414 0.929788 +-0.706487 0.029611 0.707107 +-0.550718 -0.244124 0.798194 +-0.546730 0.022915 0.836995 +-0.706487 0.029611 0.707107 +-0.711230 -0.196167 0.675034 +-0.550718 -0.244124 0.798194 +-0.706487 0.029611 0.707107 +-0.840993 -0.139729 0.522691 +-0.711230 -0.196167 0.675034 +-0.836261 0.035050 0.547210 +-0.840993 -0.139729 0.522691 +-0.706487 0.029611 0.707107 +-0.836261 0.035050 0.547210 +-0.932824 -0.078622 0.351650 +-0.840993 -0.139729 0.522691 +-0.928973 0.038936 0.368095 +-0.932824 -0.078622 0.351650 +-0.836261 0.035050 0.547210 +-0.982443 0.041177 0.181963 +-0.932824 -0.078622 0.351650 +-0.928973 0.038936 0.368095 +-0.982443 0.041177 0.181963 +-0.984637 -0.016912 0.173795 +-0.932824 -0.078622 0.351650 +-0.999123 0.041876 0.000000 +-0.984637 -0.016912 0.173795 +-0.982443 0.041177 0.181963 + + + + + + + + + + + +0.391244 0.473614 +0.391359 0.476648 +0.617966 0.476648 +0.618080 0.473614 +0.409600 0.740657 +0.409600 0.740657 +0.409600 0.716007 +0.409600 0.716007 +0.404675 0.710529 +0.404675 0.710529 +0.380247 0.710529 +0.380247 0.710529 +0.604649 0.710529 +0.629077 0.710529 +0.629077 0.710529 +0.604649 0.710529 +0.599724 0.716007 +0.599724 0.716007 +0.599724 0.740657 +0.599724 0.740657 +0.367781 0.505093 +0.375326 0.705281 +0.375326 0.705281 +0.367401 0.495007 +0.641543 0.505093 +0.641923 0.495007 +0.633998 0.705281 +0.633998 0.705281 +0.414526 0.746135 +0.594798 0.746135 +0.594798 0.746135 +0.414526 0.746135 +0.405930 0.708466 +0.369750 0.505001 +0.639574 0.505001 +0.377294 0.705189 +0.632030 0.705189 +0.631961 0.705771 +0.631788 0.706360 +0.631506 0.706923 +0.631123 0.707424 +0.630657 0.707829 +0.630140 0.708118 +0.629603 0.708286 +0.629077 0.708338 +0.604649 0.708338 +0.603395 0.708466 +0.602111 0.708877 +0.600876 0.709588 +0.599773 0.710584 +0.598878 0.711811 +0.598238 0.713184 +0.377363 0.705771 +0.377536 0.706360 +0.377818 0.706924 +0.378202 0.707424 +0.412052 0.742456 +0.411778 0.741867 +0.412436 0.742981 +0.412909 0.743408 +0.411620 0.741255 +0.413438 0.743713 +0.413988 0.743889 +0.414526 0.743944 +0.411570 0.740657 +0.594798 0.743944 +0.411570 0.716007 +0.411455 0.714612 +0.411086 0.713184 +0.410446 0.711811 +0.409551 0.710584 +0.408448 0.709588 +0.595336 0.743889 +0.595886 0.743713 +0.596416 0.743408 +0.596888 0.742981 +0.597272 0.742456 +0.597546 0.741867 +0.597704 0.741255 +0.597754 0.740657 +0.597754 0.716007 +0.597869 0.714612 +0.407213 0.708877 +0.379185 0.708118 +0.378667 0.707829 +0.379721 0.708286 +0.380247 0.708338 +0.404675 0.708338 +0.618080 0.471450 +0.623676 0.471592 +0.639574 0.505001 +0.369750 0.505001 +0.639767 0.499539 +0.369557 0.499539 +0.639954 0.494220 +0.369370 0.494220 +0.640056 0.488438 +0.369268 0.488464 +0.639746 0.483241 +0.369574 0.483269 +0.638694 0.478863 +0.370617 0.478894 +0.636588 0.475534 +0.372708 0.475563 +0.633283 0.473341 +0.376017 0.473351 +0.628875 0.472128 +0.380431 0.472131 +0.385642 0.471592 +0.391244 0.471450 +0.599378 0.742674 +0.599642 0.741654 +0.641502 0.505001 +0.367822 0.505001 +0.633926 0.706012 +0.375398 0.706012 +0.375958 0.707744 +0.376455 0.708548 +0.377084 0.709251 +0.377817 0.709816 +0.378615 0.710220 +0.380247 0.710529 +0.404675 0.710529 +0.405571 0.710621 +0.406488 0.710914 +0.407370 0.711422 +0.408158 0.712134 +0.408797 0.713010 +0.633366 0.707744 +0.632869 0.708548 +0.632240 0.709251 +0.631508 0.709816 +0.409254 0.713991 +0.629077 0.710529 +0.630709 0.710220 +0.604649 0.710529 +0.603753 0.710621 +0.602836 0.710914 +0.601954 0.711422 +0.601167 0.712134 +0.600527 0.713010 +0.600070 0.713991 +0.599806 0.715010 +0.409518 0.715010 +0.599724 0.716007 +0.409600 0.716007 +0.599724 0.740657 +0.409600 0.740657 +0.409683 0.741654 +0.409946 0.742674 +0.410403 0.743655 +0.411043 0.744531 +0.411830 0.745242 +0.412713 0.745750 +0.413630 0.746044 +0.414526 0.746135 +0.594798 0.746135 +0.595695 0.746044 +0.596611 0.745750 +0.597494 0.745242 +0.598281 0.744531 +0.598921 0.743655 +0.391359 0.476648 +0.385040 0.476752 +0.367822 0.505001 +0.641502 0.505001 +0.367700 0.501442 +0.641624 0.501451 +0.367618 0.497945 +0.641706 0.497973 +0.367602 0.494545 +0.641723 0.494576 +0.367701 0.491326 +0.641626 0.491368 +0.367978 0.488313 +0.641355 0.488379 +0.368502 0.485601 +0.640835 0.485649 +0.369349 0.483222 +0.640002 0.483279 +0.370561 0.481256 +0.638789 0.481289 +0.374174 0.478550 +0.635184 0.478565 +0.379155 0.477232 +0.630196 0.477236 +0.624295 0.476752 +0.617966 0.476648 +0.375398 0.706012 +0.375326 0.705281 +0.380247 0.710529 +0.380247 0.710529 +0.379339 0.710435 +0.379339 0.710435 +0.378386 0.710123 +0.377542 0.709629 +0.378386 0.710123 +0.377542 0.709629 +0.376838 0.709005 +0.376838 0.709005 +0.376248 0.708249 +0.375769 0.707332 +0.376248 0.708249 +0.375769 0.707332 +0.375448 0.706286 +0.375326 0.705281 +0.375448 0.706286 +0.629985 0.710435 +0.629077 0.710529 +0.633876 0.706286 +0.633998 0.705281 +0.633998 0.705281 +0.633926 0.706012 +0.633876 0.706286 +0.633556 0.707332 +0.633076 0.708249 +0.633556 0.707332 +0.633076 0.708249 +0.632486 0.709005 +0.631782 0.709629 +0.632486 0.709005 +0.630938 0.710123 +0.631782 0.709629 +0.630938 0.710123 +0.629985 0.710435 +0.629077 0.710529 +0.595808 0.746019 +0.599619 0.741780 +0.599724 0.740657 +0.599724 0.740657 +0.599319 0.742833 +0.599619 0.741780 +0.598857 0.743761 +0.599319 0.742833 +0.598857 0.743761 +0.598281 0.744531 +0.597589 0.745171 +0.598281 0.744531 +0.597589 0.745171 +0.596755 0.745684 +0.595808 0.746019 +0.596755 0.745684 +0.594798 0.746135 +0.594798 0.746135 +0.603640 0.710645 +0.604649 0.710529 +0.599724 0.716007 +0.599724 0.716007 +0.599828 0.714885 +0.599828 0.714885 +0.600129 0.713831 +0.600591 0.712903 +0.600129 0.713831 +0.600591 0.712903 +0.601167 0.712134 +0.601858 0.711493 +0.601167 0.712134 +0.601858 0.711493 +0.602693 0.710980 +0.603640 0.710645 +0.602693 0.710980 +0.604649 0.710529 +0.409600 0.740657 +0.409600 0.740657 +0.414526 0.746135 +0.414526 0.746135 +0.413516 0.746019 +0.413516 0.746019 +0.412569 0.745685 +0.411735 0.745171 +0.412569 0.745685 +0.411735 0.745171 +0.411043 0.744531 +0.410467 0.743761 +0.411043 0.744531 +0.410467 0.743761 +0.410005 0.742833 +0.410005 0.742833 +0.409705 0.741780 +0.409705 0.741780 +0.404675 0.710529 +0.404675 0.710529 +0.409496 0.714885 +0.409600 0.716007 +0.409600 0.716007 +0.409195 0.713831 +0.409496 0.714885 +0.409195 0.713831 +0.408733 0.712903 +0.408733 0.712903 +0.408158 0.712134 +0.408158 0.712134 +0.407466 0.711494 +0.407466 0.711494 +0.406631 0.710980 +0.405684 0.710646 +0.406631 0.710980 +0.405684 0.710646 +0.620969 0.473652 +0.618080 0.473614 +0.641502 0.505001 +0.633926 0.706012 +0.633998 0.705281 +0.641923 0.495007 +0.641706 0.497973 +0.641626 0.491368 +0.642009 0.489223 +0.640835 0.485649 +0.641567 0.484157 +0.638789 0.481289 +0.640215 0.480050 +0.637189 0.479731 +0.637677 0.477078 +0.635184 0.478565 +0.635949 0.476019 +0.632842 0.477760 +0.633942 0.475214 +0.630196 0.477236 +0.631667 0.474620 +0.627337 0.476924 +0.629206 0.474207 +0.624295 0.476752 +0.626572 0.473928 +0.621163 0.476670 +0.623800 0.473752 +0.617966 0.476648 +0.391359 0.476648 +0.391244 0.473614 +0.375326 0.705281 +0.375398 0.706012 +0.367401 0.495007 +0.367315 0.489250 +0.367822 0.505001 +0.367618 0.497945 +0.367752 0.484184 +0.367701 0.491326 +0.369095 0.480076 +0.368502 0.485601 +0.371610 0.477106 +0.370561 0.481256 +0.373346 0.476034 +0.372185 0.479695 +0.375354 0.475223 +0.374174 0.478550 +0.377627 0.474627 +0.376522 0.477750 +0.380102 0.474209 +0.379155 0.477232 +0.382748 0.473929 +0.382001 0.476923 +0.385518 0.473752 +0.385040 0.476752 +0.388352 0.473652 +0.388165 0.476670 +0.598157 0.740657 +0.597754 0.740657 +0.599682 0.716007 +0.599724 0.716007 +0.599724 0.740657 +0.599682 0.740657 +0.599562 0.716007 +0.599562 0.740657 +0.599377 0.716007 +0.599377 0.740657 +0.599147 0.716007 +0.598870 0.716007 +0.599147 0.740657 +0.598536 0.716007 +0.598870 0.740657 +0.598536 0.740657 +0.598157 0.716007 +0.597754 0.716007 +0.603395 0.708466 +0.604649 0.708338 +0.604649 0.708787 +0.604649 0.709208 +0.604649 0.709580 +0.604649 0.709888 +0.604649 0.710144 +0.604649 0.710349 +0.604649 0.710483 +0.604649 0.710529 +0.603640 0.710645 +0.602693 0.710980 +0.601858 0.711493 +0.601167 0.712134 +0.600591 0.712903 +0.600129 0.713831 +0.599828 0.714885 +0.599724 0.716007 +0.599682 0.716007 +0.599562 0.716007 +0.599377 0.716007 +0.599147 0.716007 +0.598870 0.716007 +0.598536 0.716007 +0.598157 0.716007 +0.597754 0.716007 +0.597869 0.714612 +0.598238 0.713184 +0.598878 0.711811 +0.599296 0.711173 +0.599773 0.710584 +0.600303 0.710053 +0.600876 0.709588 +0.602111 0.708877 +0.603397 0.709353 +0.603319 0.708940 +0.603465 0.709716 +0.603522 0.710017 +0.603569 0.710268 +0.603607 0.710469 +0.603632 0.710600 +0.602677 0.710937 +0.601835 0.711455 +0.601137 0.712101 +0.600557 0.712877 +0.600091 0.713813 +0.599788 0.714875 +0.599670 0.714848 +0.599489 0.714806 +0.599264 0.714753 +0.598993 0.714690 +0.598666 0.714614 +0.598295 0.714528 +0.598691 0.713139 +0.599300 0.711916 +0.600059 0.710902 +0.600971 0.710058 +0.602071 0.709381 +0.602629 0.710814 +0.601767 0.711345 +0.601052 0.712006 +0.602555 0.710626 +0.602464 0.710391 +0.601662 0.711176 +0.600921 0.711861 +0.601532 0.710965 +0.600758 0.711680 +0.602354 0.710108 +0.602221 0.709768 +0.601375 0.710711 +0.600563 0.711462 +0.601186 0.710405 +0.600327 0.711200 +0.600457 0.712801 +0.599980 0.713760 +0.600305 0.712685 +0.599811 0.713678 +0.600115 0.712539 +0.599599 0.713577 +0.599887 0.712365 +0.599346 0.713454 +0.599612 0.712155 +0.599039 0.713307 +0.596661 0.743209 +0.596416 0.743408 +0.595886 0.743713 +0.595336 0.743889 +0.594798 0.744393 +0.594798 0.743944 +0.594798 0.744814 +0.595808 0.746019 +0.594798 0.746135 +0.599691 0.740657 +0.599724 0.740657 +0.597704 0.741255 +0.597754 0.740657 +0.596888 0.742981 +0.597093 0.742729 +0.597272 0.742456 +0.597546 0.741867 +0.598112 0.740657 +0.598479 0.740657 +0.598832 0.740657 +0.598996 0.740657 +0.599147 0.740657 +0.599283 0.740657 +0.599403 0.740657 +0.599586 0.740657 +0.599619 0.741780 +0.599319 0.742833 +0.598857 0.743761 +0.598281 0.744531 +0.597589 0.745171 +0.596755 0.745684 +0.594798 0.746089 +0.594798 0.745955 +0.594798 0.745749 +0.594798 0.745493 +0.594798 0.745185 +0.595633 0.745089 +0.595564 0.744726 +0.597174 0.743299 +0.596702 0.743735 +0.596133 0.744086 +0.595487 0.744314 +0.597566 0.742774 +0.597881 0.742141 +0.598086 0.741423 +0.598457 0.741509 +0.598784 0.741585 +0.599055 0.741648 +0.599280 0.741701 +0.599461 0.741743 +0.599579 0.741770 +0.599280 0.742814 +0.598822 0.743735 +0.598252 0.744498 +0.597566 0.745132 +0.596738 0.745642 +0.595799 0.745973 +0.595775 0.745842 +0.595737 0.745641 +0.595689 0.745391 +0.596283 0.744472 +0.596916 0.744082 +0.597441 0.743597 +0.596416 0.744813 +0.596526 0.745095 +0.597106 0.744388 +0.597678 0.743859 +0.597262 0.744642 +0.597873 0.744077 +0.596617 0.745330 +0.596690 0.745519 +0.597393 0.744853 +0.598036 0.744258 +0.597498 0.745022 +0.598167 0.744403 +0.597878 0.743013 +0.598229 0.742308 +0.598153 0.743223 +0.598535 0.742456 +0.598381 0.743397 +0.598789 0.742578 +0.598571 0.743543 +0.599001 0.742680 +0.598723 0.743659 +0.599170 0.742761 +0.629077 0.709208 +0.604649 0.708338 +0.629077 0.708338 +0.604649 0.708787 +0.629077 0.708787 +0.604649 0.709208 +0.629077 0.710529 +0.604649 0.710529 +0.629077 0.710483 +0.604649 0.710483 +0.629077 0.710349 +0.629077 0.710144 +0.604649 0.710349 +0.604649 0.710144 +0.629077 0.709888 +0.629077 0.709580 +0.604649 0.709888 +0.604649 0.709580 +0.594798 0.745749 +0.594798 0.746135 +0.414526 0.746135 +0.594798 0.746089 +0.414526 0.746089 +0.594798 0.745955 +0.414526 0.743944 +0.594798 0.743944 +0.414526 0.744393 +0.594798 0.744393 +0.414526 0.744814 +0.594798 0.744814 +0.414526 0.745185 +0.414526 0.745493 +0.594798 0.745185 +0.594798 0.745493 +0.414526 0.745749 +0.414526 0.745955 +0.629985 0.710435 +0.629077 0.710529 +0.629077 0.710039 +0.629077 0.710172 +0.629077 0.710375 +0.629077 0.710493 +0.631961 0.705771 +0.632030 0.705189 +0.629077 0.708737 +0.629077 0.708338 +0.629077 0.709888 +0.629077 0.709719 +0.629077 0.709537 +0.629077 0.709145 +0.629603 0.708286 +0.630140 0.708118 +0.630657 0.707829 +0.631123 0.707424 +0.631506 0.706923 +0.631788 0.706360 +0.632433 0.705208 +0.632812 0.705225 +0.633145 0.705241 +0.633422 0.705254 +0.633652 0.705265 +0.633836 0.705273 +0.633957 0.705279 +0.633998 0.705281 +0.633876 0.706286 +0.633556 0.707332 +0.633076 0.708249 +0.632486 0.709005 +0.631782 0.709629 +0.630938 0.710123 +0.629921 0.710056 +0.629879 0.709805 +0.629955 0.710258 +0.629978 0.710390 +0.629828 0.709502 +0.629766 0.709137 +0.629696 0.708723 +0.630346 0.708510 +0.630922 0.708173 +0.631402 0.707748 +0.631804 0.707232 +0.632131 0.706607 +0.632350 0.705893 +0.632719 0.705988 +0.633044 0.706072 +0.633314 0.706141 +0.633538 0.706199 +0.633718 0.706245 +0.633835 0.706275 +0.633518 0.707313 +0.633042 0.708222 +0.632457 0.708972 +0.631760 0.709590 +0.630923 0.710080 +0.630490 0.708900 +0.631130 0.708525 +0.631664 0.708052 +0.630616 0.709244 +0.630720 0.709529 +0.631314 0.708835 +0.631895 0.708320 +0.631466 0.709093 +0.632087 0.708542 +0.630807 0.709766 +0.630877 0.709956 +0.631592 0.709307 +0.632246 0.708727 +0.631694 0.709478 +0.632374 0.708875 +0.632112 0.707478 +0.632476 0.706782 +0.632383 0.707695 +0.632779 0.706937 +0.632608 0.707875 +0.633031 0.707065 +0.632795 0.708024 +0.633240 0.707171 +0.632945 0.708144 +0.633408 0.707257 +0.412231 0.742729 +0.412052 0.742456 +0.411778 0.741867 +0.411620 0.741255 +0.411212 0.740657 +0.411570 0.740657 +0.410845 0.740657 +0.410492 0.740657 +0.410329 0.740657 +0.410177 0.740657 +0.410041 0.740657 +0.409921 0.740657 +0.409739 0.740657 +0.409633 0.740657 +0.409705 0.741780 +0.409600 0.740657 +0.410005 0.742833 +0.410467 0.743761 +0.411043 0.744531 +0.411735 0.745171 +0.412569 0.745685 +0.413516 0.746019 +0.414526 0.746089 +0.414526 0.746135 +0.414526 0.745955 +0.414526 0.745749 +0.414526 0.745493 +0.414526 0.745185 +0.413988 0.743889 +0.414526 0.743944 +0.412436 0.742981 +0.412663 0.743209 +0.412909 0.743408 +0.413438 0.743713 +0.414526 0.744393 +0.414526 0.744814 +0.413760 0.744726 +0.413691 0.745089 +0.412151 0.743299 +0.411758 0.742774 +0.411443 0.742141 +0.411238 0.741423 +0.410867 0.741509 +0.410540 0.741585 +0.410270 0.741648 +0.410044 0.741701 +0.409863 0.741743 +0.409746 0.741770 +0.410044 0.742814 +0.410502 0.743735 +0.411072 0.744498 +0.411759 0.745132 +0.412586 0.745642 +0.413525 0.745973 +0.413550 0.745842 +0.413588 0.745641 +0.413635 0.745391 +0.412622 0.743735 +0.413192 0.744086 +0.413837 0.744314 +0.411095 0.742308 +0.411446 0.743013 +0.411883 0.743597 +0.410789 0.742456 +0.410535 0.742578 +0.411171 0.743223 +0.411647 0.743859 +0.410943 0.743397 +0.411451 0.744077 +0.410324 0.742680 +0.410154 0.742761 +0.410753 0.743543 +0.411288 0.744258 +0.410601 0.743659 +0.411158 0.744403 +0.412408 0.744082 +0.413041 0.744472 +0.412219 0.744388 +0.412909 0.744813 +0.412062 0.744642 +0.412799 0.745095 +0.411931 0.744853 +0.412707 0.745330 +0.411827 0.745022 +0.412634 0.745519 +0.633957 0.705279 +0.641501 0.505091 +0.641543 0.505093 +0.633998 0.705281 +0.632030 0.705189 +0.639574 0.505001 +0.632433 0.705208 +0.639978 0.505020 +0.632812 0.705225 +0.640356 0.505037 +0.633145 0.705241 +0.633422 0.705254 +0.640690 0.505053 +0.640966 0.505066 +0.633652 0.705265 +0.641196 0.505076 +0.633836 0.705273 +0.641381 0.505085 +0.411167 0.716007 +0.411570 0.716007 +0.409642 0.740657 +0.409600 0.740657 +0.409600 0.716007 +0.409642 0.716007 +0.409762 0.740657 +0.409762 0.716007 +0.409947 0.740657 +0.409947 0.716007 +0.410177 0.740657 +0.410177 0.716007 +0.410454 0.740657 +0.410454 0.716007 +0.410788 0.740657 +0.410788 0.716007 +0.411167 0.740657 +0.411570 0.740657 +0.639574 0.505001 +0.639954 0.494220 +0.641894 0.494878 +0.641923 0.495007 +0.641543 0.505093 +0.641510 0.505091 +0.641792 0.494743 +0.641404 0.505086 +0.641611 0.494609 +0.641222 0.505078 +0.641356 0.494485 +0.640966 0.505066 +0.641039 0.494380 +0.640651 0.505051 +0.640684 0.494300 +0.640299 0.505035 +0.640315 0.494246 +0.639932 0.505018 +0.411455 0.714612 +0.411570 0.716007 +0.409762 0.716007 +0.409947 0.716007 +0.410177 0.716007 +0.409642 0.716007 +0.409600 0.716007 +0.409496 0.714885 +0.409195 0.713831 +0.408733 0.712903 +0.408158 0.712134 +0.407466 0.711494 +0.406631 0.710980 +0.405684 0.710646 +0.404675 0.710529 +0.404675 0.710483 +0.404675 0.710349 +0.404675 0.710144 +0.404675 0.709888 +0.404675 0.709580 +0.404675 0.709208 +0.404675 0.708787 +0.404675 0.708338 +0.405930 0.708466 +0.407213 0.708877 +0.408448 0.709588 +0.409021 0.710053 +0.409551 0.710584 +0.410028 0.711173 +0.410446 0.711811 +0.411086 0.713184 +0.410454 0.716007 +0.410788 0.716007 +0.411167 0.716007 +0.409654 0.714848 +0.409537 0.714875 +0.409835 0.714806 +0.410061 0.714753 +0.409233 0.713813 +0.408768 0.712877 +0.408187 0.712101 +0.407489 0.711455 +0.406648 0.710937 +0.405693 0.710600 +0.405717 0.710469 +0.405755 0.710268 +0.405802 0.710017 +0.405859 0.709716 +0.405927 0.709353 +0.406005 0.708940 +0.407253 0.709381 +0.408353 0.710058 +0.409265 0.710902 +0.410024 0.711916 +0.410633 0.713140 +0.411029 0.714528 +0.410331 0.714690 +0.410658 0.714614 +0.409344 0.713760 +0.408867 0.712801 +0.408272 0.712006 +0.409513 0.713678 +0.409725 0.713577 +0.409019 0.712685 +0.408403 0.711861 +0.409209 0.712540 +0.408566 0.711680 +0.409979 0.713454 +0.410285 0.713307 +0.409437 0.712365 +0.408761 0.711462 +0.409712 0.712155 +0.408997 0.711200 +0.407558 0.711345 +0.406695 0.710814 +0.407662 0.711176 +0.406769 0.710626 +0.407793 0.710965 +0.406860 0.710391 +0.407950 0.710711 +0.406970 0.710108 +0.408139 0.710405 +0.407103 0.709768 +0.618080 0.472740 +0.623676 0.471592 +0.618080 0.471450 +0.618080 0.472316 +0.618080 0.471949 +0.618080 0.471669 +0.618080 0.471494 +0.618080 0.471425 +0.628875 0.472128 +0.633283 0.473341 +0.636588 0.475534 +0.638694 0.478863 +0.639746 0.483241 +0.640056 0.488438 +0.639954 0.494220 +0.640315 0.494246 +0.640684 0.494300 +0.641039 0.494380 +0.641356 0.494485 +0.641611 0.494609 +0.641792 0.494743 +0.641894 0.494878 +0.641923 0.495007 +0.642009 0.489223 +0.641567 0.484157 +0.640215 0.480050 +0.637677 0.477078 +0.633942 0.475214 +0.629206 0.474207 +0.623800 0.473752 +0.618080 0.473614 +0.618080 0.473183 +0.623926 0.472871 +0.623890 0.472440 +0.623829 0.472067 +0.623749 0.471785 +0.623656 0.471611 +0.623558 0.471548 +0.628724 0.472021 +0.633220 0.473127 +0.636698 0.475219 +0.638969 0.478529 +0.640107 0.482983 +0.640433 0.488313 +0.640821 0.488373 +0.641193 0.488482 +0.641519 0.488637 +0.641773 0.488828 +0.641940 0.489041 +0.642017 0.489258 +0.641669 0.484215 +0.640450 0.479999 +0.638015 0.476861 +0.634286 0.474865 +0.629468 0.473794 +0.623939 0.473321 +0.629452 0.473332 +0.629385 0.472891 +0.629268 0.472512 +0.629108 0.472231 +0.628921 0.472068 +0.634276 0.474401 +0.634190 0.473957 +0.634024 0.473579 +0.638011 0.476420 +0.637909 0.475997 +0.637705 0.475638 +0.633790 0.473306 +0.633513 0.473156 +0.637414 0.475380 +0.637066 0.475241 +0.640434 0.479615 +0.640313 0.479246 +0.640082 0.478929 +0.641624 0.483911 +0.641478 0.483618 +0.641231 0.483360 +0.639758 0.478695 +0.639374 0.478562 +0.640900 0.483161 +0.640513 0.483035 +0.380247 0.708338 +0.404675 0.708338 +0.404675 0.710529 +0.380247 0.710529 +0.404675 0.710483 +0.404675 0.710349 +0.380247 0.710483 +0.404675 0.710144 +0.380247 0.710349 +0.380247 0.710144 +0.404675 0.709888 +0.380247 0.709888 +0.404675 0.709580 +0.380247 0.709580 +0.404675 0.709208 +0.404675 0.708787 +0.380247 0.709208 +0.380247 0.708787 +0.391244 0.472236 +0.618080 0.471430 +0.618080 0.471450 +0.391244 0.471450 +0.618080 0.471441 +0.391244 0.471430 +0.391244 0.471441 +0.618080 0.471542 +0.391244 0.471542 +0.618080 0.471718 +0.391244 0.471718 +0.618080 0.471949 +0.618080 0.472236 +0.391244 0.471949 +0.391244 0.473614 +0.618080 0.473614 +0.391244 0.473444 +0.618080 0.473444 +0.391244 0.473000 +0.391244 0.472590 +0.618080 0.473000 +0.618080 0.472590 +0.379721 0.708286 +0.380247 0.708338 +0.375766 0.705260 +0.375647 0.705266 +0.375464 0.705274 +0.375359 0.705279 +0.375448 0.706286 +0.375326 0.705281 +0.375769 0.707332 +0.376248 0.708249 +0.376838 0.709005 +0.377542 0.709629 +0.376936 0.705206 +0.377294 0.705189 +0.375902 0.705254 +0.376054 0.705247 +0.376217 0.705239 +0.376570 0.705223 +0.377363 0.705771 +0.377536 0.706360 +0.377818 0.706924 +0.378202 0.707424 +0.378667 0.707829 +0.379185 0.708118 +0.378386 0.710123 +0.379339 0.710435 +0.380247 0.710529 +0.380247 0.710493 +0.380247 0.710375 +0.380247 0.710172 +0.380247 0.710039 +0.380247 0.709888 +0.380247 0.709719 +0.380247 0.709537 +0.380247 0.709145 +0.380247 0.708737 +0.376010 0.706141 +0.375786 0.706199 +0.375606 0.706245 +0.375489 0.706276 +0.375807 0.707313 +0.376282 0.708222 +0.376867 0.708972 +0.377565 0.709590 +0.376280 0.706072 +0.376605 0.705988 +0.376974 0.705893 +0.377193 0.706607 +0.377520 0.707232 +0.377922 0.707748 +0.378402 0.708173 +0.378978 0.708510 +0.379628 0.708723 +0.378402 0.710080 +0.379347 0.710390 +0.379369 0.710258 +0.379403 0.710056 +0.379445 0.709805 +0.379496 0.709502 +0.379558 0.709137 +0.376849 0.706782 +0.377212 0.707478 +0.377660 0.708052 +0.376545 0.706937 +0.376293 0.707065 +0.376941 0.707695 +0.377429 0.708320 +0.376716 0.707875 +0.377237 0.708542 +0.376084 0.707171 +0.375916 0.707257 +0.376530 0.708024 +0.377078 0.708727 +0.376380 0.708144 +0.376950 0.708875 +0.378194 0.708525 +0.378835 0.708900 +0.378011 0.708836 +0.378708 0.709244 +0.377859 0.709093 +0.378604 0.709529 +0.377732 0.709307 +0.378517 0.709766 +0.377631 0.709478 +0.378447 0.709956 +0.380431 0.472131 +0.367532 0.494743 +0.367713 0.494609 +0.391244 0.471425 +0.391244 0.471450 +0.367430 0.494878 +0.367401 0.495007 +0.367315 0.489250 +0.367752 0.484184 +0.369095 0.480076 +0.371610 0.477106 +0.375354 0.475223 +0.380102 0.474209 +0.385518 0.473752 +0.391244 0.473614 +0.391244 0.473183 +0.391244 0.472740 +0.391244 0.472316 +0.391244 0.471949 +0.391244 0.471669 +0.391244 0.471494 +0.385642 0.471592 +0.367969 0.494485 +0.368285 0.494380 +0.368640 0.494300 +0.369009 0.494246 +0.369370 0.494220 +0.369268 0.488464 +0.369574 0.483269 +0.370617 0.478894 +0.372708 0.475563 +0.376017 0.473351 +0.376077 0.473138 +0.367384 0.489066 +0.367307 0.489283 +0.367551 0.488854 +0.367651 0.484241 +0.368860 0.480029 +0.371273 0.476892 +0.375010 0.474875 +0.379837 0.473796 +0.385378 0.473322 +0.385391 0.472871 +0.385428 0.472440 +0.385488 0.472067 +0.385568 0.471785 +0.385662 0.471612 +0.385759 0.471548 +0.380582 0.472023 +0.367805 0.488664 +0.368131 0.488509 +0.368503 0.488400 +0.368891 0.488340 +0.369213 0.483012 +0.370342 0.478560 +0.372592 0.475251 +0.367696 0.483939 +0.367842 0.483646 +0.368089 0.483388 +0.368421 0.483190 +0.368807 0.483064 +0.368876 0.479645 +0.368997 0.479277 +0.369228 0.478960 +0.371277 0.476451 +0.371379 0.476029 +0.371583 0.475670 +0.369552 0.478727 +0.369936 0.478594 +0.371875 0.475411 +0.372224 0.475273 +0.375019 0.474411 +0.375106 0.473967 +0.375272 0.473589 +0.379853 0.473335 +0.379920 0.472894 +0.380037 0.472515 +0.375506 0.473316 +0.375784 0.473166 +0.380197 0.472234 +0.380385 0.472070 +0.375326 0.705281 +0.367781 0.505093 +0.369750 0.505001 +0.377294 0.705189 +0.369347 0.505020 +0.376891 0.705208 +0.368968 0.505037 +0.376512 0.705226 +0.368635 0.505053 +0.376179 0.705241 +0.368358 0.505066 +0.375902 0.705254 +0.368128 0.505076 +0.375672 0.705265 +0.367943 0.505085 +0.375488 0.705273 +0.367823 0.505091 +0.375368 0.705279 +0.367781 0.505093 +0.367401 0.495007 +0.369370 0.494220 +0.369750 0.505001 +0.369009 0.494246 +0.369392 0.505018 +0.368640 0.494300 +0.368285 0.494380 +0.369025 0.505035 +0.368673 0.505051 +0.367969 0.494485 +0.367713 0.494609 +0.368358 0.505066 +0.367532 0.494743 +0.368102 0.505078 +0.367920 0.505086 +0.367430 0.494878 +0.367814 0.505091 + + + + + + + + + + + +

2 0 2 0 1 0 1 2 1 0 3 0 2 4 2 3 5 3 6 6 6 4 7 4 5 8 5 4 9 4 6 10 6 7 11 7 10 12 10 8 13 8 9 14 9 8 15 8 10 16 10 11 17 11 14 18 14 12 19 12 13 20 13 12 21 12 14 22 14 15 23 15 18 24 18 16 25 16 17 26 17 16 27 16 18 28 18 19 29 19 22 30 22 20 31 20 21 32 21 20 33 20 22 34 22 23 35 23 26 36 26 24 37 24 25 38 25 24 39 24 26 40 26 27 41 27 30 42 30 28 43 28 29 44 29 28 45 28 30 46 30 31 47 31 87 48 87 81 49 81 32 50 32 36 51 36 33 52 33 34 53 34 36 54 36 35 55 35 33 56 33 37 57 37 35 58 35 36 59 36 38 60 38 35 61 35 37 62 37 39 63 39 35 64 35 38 65 38 40 66 40 35 67 35 39 68 39 41 69 41 35 70 35 40 71 40 42 72 42 35 73 35 41 74 41 43 75 43 35 76 35 42 77 42 44 78 44 35 79 35 43 80 43 45 81 45 35 82 35 44 83 44 46 84 46 35 85 35 45 86 45 47 87 47 35 88 35 46 89 46 48 90 48 35 91 35 47 92 47 49 93 49 35 94 35 48 95 48 50 96 50 35 97 35 49 98 49 51 99 51 35 100 35 50 101 50 81 102 81 35 103 35 51 104 51 81 105 81 52 106 52 35 107 35 81 108 81 53 109 53 52 110 52 81 111 81 54 112 54 53 113 53 81 114 81 55 115 55 54 116 54 60 117 60 56 118 56 57 119 57 60 120 60 58 121 58 56 122 56 60 123 60 59 124 59 58 125 58 64 126 64 59 127 59 60 128 60 64 129 64 61 130 61 59 131 59 64 132 64 62 133 62 61 134 61 64 135 64 63 136 63 62 137 62 66 138 66 63 139 63 64 140 64 66 141 66 65 142 65 63 143 63 67 144 67 65 145 65 66 146 66 68 147 68 65 148 65 67 149 67 69 150 69 65 151 65 68 152 68 70 153 70 65 154 65 69 155 69 71 156 71 65 157 65 70 158 70 82 159 82 65 160 65 71 161 71 82 162 82 72 163 72 65 164 65 82 165 82 73 166 73 72 167 72 82 168 82 74 169 74 73 170 73 82 171 82 75 172 75 74 173 74 82 174 82 76 175 76 75 176 75 82 177 82 77 178 77 76 179 76 82 180 82 78 181 78 77 182 77 82 183 82 79 184 79 78 185 78 82 186 82 80 187 80 79 188 79 82 189 82 81 190 81 80 191 80 32 192 32 81 193 81 82 194 82 55 195 55 83 196 83 84 197 84 55 198 55 85 199 85 83 200 83 55 201 55 86 202 86 85 203 85 55 204 55 87 205 87 86 206 86 81 207 81 87 208 87 55 209 55 106 210 106 88 211 88 89 212 89 93 213 93 90 214 90 91 215 91 93 216 93 92 217 92 90 218 90 95 219 95 92 220 92 93 221 93 95 222 95 94 223 94 92 224 92 97 225 97 94 226 94 95 227 95 97 228 97 96 229 96 94 230 94 99 231 99 96 232 96 97 233 97 99 234 99 98 235 98 96 236 96 101 237 101 98 238 98 99 239 99 101 240 101 100 241 100 98 242 98 103 243 103 100 244 100 101 245 101 103 246 103 102 247 102 100 248 100 105 249 105 102 250 102 103 251 103 105 252 105 104 253 104 102 254 102 107 255 107 104 256 104 105 257 105 107 258 107 106 259 106 104 260 104 108 261 108 106 262 106 107 263 107 109 264 109 106 265 106 108 266 108 88 267 88 106 268 106 109 269 109 146 270 146 110 271 110 111 272 111 115 273 115 112 274 112 113 275 113 115 276 115 114 277 114 112 278 112 116 279 116 114 280 114 115 281 115 117 282 117 114 283 114 116 284 116 118 285 118 114 286 114 117 287 117 119 288 119 114 289 114 118 290 118 120 291 120 114 292 114 119 293 119 121 294 121 114 295 114 120 296 120 122 297 122 114 298 114 121 299 121 123 300 123 114 301 114 122 302 122 124 303 124 114 304 114 123 305 123 125 306 125 114 307 114 124 308 124 126 309 126 114 310 114 125 311 125 127 312 127 114 313 114 126 314 126 132 315 132 114 316 114 127 317 127 132 318 132 128 319 128 114 320 114 132 321 132 129 322 129 128 323 128 132 324 132 130 325 130 129 326 129 132 327 132 131 328 131 130 329 130 143 330 143 131 331 131 132 332 132 131 333 131 133 334 133 134 335 134 131 336 131 135 337 135 133 338 133 143 339 143 135 340 135 131 341 131 143 342 143 136 343 136 135 344 135 143 345 143 137 346 137 136 347 136 143 348 143 138 349 138 137 350 137 143 351 143 139 352 139 138 353 138 143 354 143 140 355 140 139 356 139 143 357 143 141 358 141 140 359 140 143 360 143 142 361 142 141 362 141 145 363 145 142 364 142 143 365 143 145 366 145 144 367 144 142 368 142 147 369 147 144 370 144 145 371 145 147 372 147 146 373 146 144 374 144 148 375 148 146 376 146 147 377 147 149 378 149 146 379 146 148 380 148 150 381 150 146 382 146 149 383 149 151 384 151 146 385 146 150 386 150 152 387 152 146 388 146 151 389 151 153 390 153 146 391 146 152 392 152 154 393 154 146 394 146 153 395 153 155 396 155 146 397 146 154 398 154 156 399 156 146 400 146 155 401 155 157 402 157 146 403 146 156 404 156 158 405 158 146 406 146 157 407 157 159 408 159 146 409 146 158 410 158 160 411 160 146 412 146 159 413 159 161 414 161 146 415 146 160 416 160 110 417 110 146 418 146 161 419 161 184 420 184 162 421 162 163 422 163 167 423 167 164 424 164 165 425 165 167 426 167 166 427 166 164 428 164 169 429 169 166 430 166 167 431 167 169 432 169 168 433 168 166 434 166 171 435 171 168 436 168 169 437 169 171 438 171 170 439 170 168 440 168 173 441 173 170 442 170 171 443 171 173 444 173 172 445 172 170 446 170 175 447 175 172 448 172 173 449 173 175 450 175 174 451 174 172 452 172 177 453 177 174 454 174 175 455 175 177 456 177 176 457 176 174 458 174 179 459 179 176 460 176 177 461 177 179 462 179 178 463 178 176 464 176 181 465 181 178 466 178 179 467 179 181 468 181 180 469 180 178 470 178 183 471 183 180 472 180 181 473 181 183 474 183 182 475 182 180 476 180 185 477 185 182 478 182 183 479 183 185 480 185 184 481 184 182 482 182 186 483 186 184 484 184 185 485 185 187 486 187 184 487 184 186 488 186 162 489 162 184 490 184 187 491 187 205 492 205 188 493 188 189 494 189 193 495 193 190 496 190 191 497 191 193 498 193 192 499 192 190 500 190 196 501 196 192 502 192 193 503 193 196 504 196 194 505 194 192 506 192 196 507 196 195 508 195 194 509 194 197 510 197 195 511 195 196 512 196 199 513 199 195 514 195 197 515 197 199 516 199 198 517 198 195 518 195 202 519 202 198 520 198 199 521 199 202 522 202 200 523 200 198 524 198 202 525 202 201 526 201 200 527 200 203 528 203 201 529 201 202 530 202 206 531 206 201 532 201 203 533 203 206 534 206 204 535 204 201 536 201 206 537 206 205 538 205 204 539 204 188 540 188 205 541 205 206 542 206 225 543 225 207 544 207 208 545 208 211 546 211 209 547 209 210 548 210 212 549 212 209 550 209 211 551 211 213 552 213 209 553 209 212 554 212 216 555 216 209 556 209 213 557 213 216 558 216 214 559 214 209 560 209 216 561 216 215 562 215 214 563 214 217 564 217 215 565 215 216 566 216 220 567 220 215 568 215 217 569 217 220 570 220 218 571 218 215 572 215 220 573 220 219 574 219 218 575 218 222 576 222 219 577 219 220 578 220 222 579 222 221 580 221 219 581 219 223 582 223 221 583 221 222 584 222 207 585 207 221 586 221 223 587 223 207 588 207 224 589 224 221 590 221 207 591 207 225 592 225 224 593 224 242 594 242 240 595 240 226 596 226 229 597 229 227 598 227 228 599 228 231 600 231 227 601 227 229 602 229 231 603 231 230 604 230 227 605 227 233 606 233 230 607 230 231 608 231 233 609 233 232 610 232 230 611 230 234 612 234 232 613 232 233 614 233 237 615 237 232 616 232 234 617 234 237 618 237 235 619 235 232 620 232 237 621 237 236 622 236 235 623 235 238 624 238 236 625 236 237 626 237 241 627 241 236 628 236 238 629 238 241 630 241 239 631 239 236 632 236 241 633 241 240 634 240 239 635 239 226 636 226 240 637 240 241 638 241 240 639 240 242 640 242 243 641 243 261 642 261 244 643 244 245 644 245 249 645 249 246 646 246 247 647 247 249 648 249 248 649 248 246 650 246 252 651 252 248 652 248 249 653 249 252 654 252 250 655 250 248 656 248 252 657 252 251 658 251 250 659 250 253 660 253 251 661 251 252 662 252 256 663 256 251 664 251 253 665 253 256 666 256 254 667 254 251 668 251 256 669 256 255 670 255 254 671 254 257 672 257 255 673 255 256 674 256 260 675 260 255 676 255 257 677 257 260 678 260 258 679 258 255 680 255 260 681 260 259 682 259 258 683 258 244 684 244 259 685 259 260 686 260 244 687 244 261 688 261 259 689 259 278 690 278 262 691 262 263 692 263 267 693 267 264 694 264 265 695 265 267 696 267 266 697 266 264 698 264 270 699 270 266 700 266 267 701 267 270 702 270 268 703 268 266 704 266 270 705 270 269 706 269 268 707 268 271 708 271 269 709 269 270 710 270 274 711 274 269 712 269 271 713 271 274 714 274 272 715 272 269 716 269 274 717 274 273 718 273 272 719 272 275 720 275 273 721 273 274 722 274 277 723 277 273 724 273 275 725 275 277 726 277 276 727 276 273 728 273 279 729 279 276 730 276 277 731 277 279 732 279 278 733 278 276 734 276 262 735 262 278 736 278 279 737 279 295 738 295 280 739 280 281 740 281 284 741 284 282 742 282 283 743 283 286 744 286 282 745 282 284 746 284 286 747 286 285 748 285 282 749 282 287 750 287 285 751 285 286 752 286 289 753 289 285 754 285 287 755 287 289 756 289 288 757 288 285 758 285 291 759 291 288 760 288 289 761 289 291 762 291 290 763 290 288 764 288 293 765 293 290 766 290 291 767 291 293 768 293 292 769 292 290 770 290 296 771 296 292 772 292 293 773 293 296 774 296 294 775 294 292 776 292 296 777 296 295 778 295 294 779 294 297 780 297 295 781 295 296 782 296 280 783 280 295 784 295 297 785 297 325 786 325 298 787 298 299 788 299 302 789 302 300 790 300 301 791 301 303 792 303 300 793 300 302 794 302 306 795 306 300 796 300 303 797 303 306 798 306 304 799 304 300 800 300 306 801 306 305 802 305 304 803 304 308 804 308 305 805 305 306 806 306 308 807 308 307 808 307 305 809 305 310 810 310 307 811 307 308 812 308 310 813 310 309 814 309 307 815 307 312 816 312 309 817 309 310 818 310 312 819 312 311 820 311 309 821 309 314 822 314 311 823 311 312 824 312 314 825 314 313 826 313 311 827 311 316 828 316 313 829 313 314 830 314 316 831 316 315 832 315 313 833 313 318 834 318 315 835 315 316 836 316 318 837 318 317 838 317 315 839 315 320 840 320 317 841 317 318 842 318 320 843 320 319 844 319 317 845 317 322 846 322 319 847 319 320 848 320 322 849 322 321 850 321 319 851 319 324 852 324 321 853 321 322 854 322 324 855 324 323 856 323 321 857 321 298 858 298 323 859 323 324 860 324 298 861 298 325 862 325 323 863 323 352 864 352 326 865 326 327 866 327 332 867 332 328 868 328 329 869 329 332 870 332 330 871 330 328 872 328 332 873 332 331 874 331 330 875 330 333 876 333 331 877 331 332 878 332 335 879 335 331 880 331 333 881 333 335 882 335 334 883 334 331 884 331 337 885 337 334 886 334 335 887 335 337 888 337 336 889 336 334 890 334 339 891 339 336 892 336 337 893 337 339 894 339 338 895 338 336 896 336 341 897 341 338 898 338 339 899 339 341 900 341 340 901 340 338 902 338 343 903 343 340 904 340 341 905 341 343 906 343 342 907 342 340 908 340 345 909 345 342 910 342 343 911 343 345 912 345 344 913 344 342 914 342 347 915 347 344 916 344 345 917 345 347 918 347 346 919 346 344 920 344 349 921 349 346 922 346 347 923 347 349 924 349 348 925 348 346 926 346 351 927 351 348 928 348 349 929 349 351 930 351 350 931 350 348 932 348 353 933 353 350 934 350 351 935 351 353 936 353 352 937 352 350 938 350 326 939 326 352 940 352 353 941 353 371 942 371 354 943 354 355 944 355 358 945 358 356 946 356 357 947 357 359 948 359 356 949 356 358 950 358 361 951 361 356 952 356 359 953 359 361 954 361 360 955 360 356 956 356 363 957 363 360 958 360 361 959 361 363 960 363 362 961 362 360 962 360 366 963 366 362 964 362 363 965 363 366 966 366 364 967 364 362 968 362 366 969 366 365 970 365 364 971 364 368 972 368 365 973 365 366 974 366 368 975 368 367 976 367 365 977 365 369 978 369 367 979 367 368 980 368 354 981 354 367 982 367 369 983 369 354 984 354 370 985 370 367 986 367 354 987 354 371 988 371 370 989 370 374 990 374 372 991 372 373 992 373 374 993 374 406 994 406 407 995 407 375 996 375 406 997 406 374 998 374 375 999 375 408 1000 408 406 1001 406 376 1002 376 408 1003 408 375 1004 375 376 1005 376 409 1006 409 408 1007 408 377 1008 377 409 1009 409 376 1010 376 378 1011 378 409 1012 409 377 1013 377 378 1014 378 410 1015 410 409 1016 409 379 1017 379 410 1018 410 378 1019 378 379 1020 379 411 1021 411 410 1022 410 379 1023 379 412 1024 412 411 1025 411 380 1026 380 412 1027 412 379 1028 379 381 1029 381 412 1030 412 380 1031 380 382 1032 382 412 1033 412 381 1034 381 382 1035 382 413 1036 413 412 1037 412 383 1038 383 413 1039 413 382 1040 382 384 1041 384 413 1042 413 383 1043 383 384 1044 384 414 1045 414 413 1046 413 384 1047 384 415 1048 415 414 1049 414 385 1050 385 415 1051 415 384 1052 384 385 1053 385 416 1054 416 415 1055 415 386 1056 386 416 1057 416 385 1058 385 387 1059 387 416 1060 416 386 1061 386 387 1062 387 417 1063 417 416 1064 416 388 1065 388 417 1066 417 387 1067 387 388 1068 388 418 1069 418 417 1070 417 389 1071 389 418 1072 418 388 1073 388 390 1074 390 418 1075 418 389 1076 389 390 1077 390 419 1078 419 418 1079 418 391 1080 391 419 1081 419 390 1082 390 392 1083 392 419 1084 419 391 1085 391 392 1086 392 420 1087 420 419 1088 419 393 1089 393 420 1090 420 392 1091 392 393 1092 393 421 1093 421 420 1094 420 394 1095 394 421 1096 421 393 1097 393 394 1098 394 422 1099 422 421 1100 421 395 1101 395 422 1102 422 394 1103 394 395 1104 395 423 1105 423 422 1106 422 396 1107 396 423 1108 423 395 1109 395 396 1110 396 424 1111 424 423 1112 423 397 1113 397 424 1114 424 396 1115 396 398 1116 398 424 1117 424 397 1118 397 399 1119 399 424 1120 424 398 1121 398 399 1122 399 425 1123 425 424 1124 424 400 1125 400 425 1126 425 399 1127 399 400 1128 400 426 1129 426 425 1130 425 401 1131 401 426 1132 426 400 1133 400 401 1134 401 427 1135 427 426 1136 426 402 1137 402 427 1138 427 401 1139 401 402 1140 402 428 1141 428 427 1142 427 403 1143 403 428 1144 428 402 1145 402 404 1146 404 428 1147 428 403 1148 403 404 1149 404 429 1150 429 428 1151 428 405 1152 405 429 1153 429 404 1154 404 405 1155 405 407 1156 407 429 1157 429 372 1158 372 407 1159 407 405 1160 405 372 1161 372 374 1162 374 407 1163 407 412 1164 412 430 1165 430 411 1166 411 430 1167 430 412 1168 412 413 1169 413 413 1170 413 431 1171 431 430 1172 430 431 1173 431 413 1174 413 414 1175 414 414 1176 414 432 1177 432 431 1178 431 432 1179 432 414 1180 414 415 1181 415 411 1182 411 433 1183 433 410 1184 410 433 1185 433 411 1186 411 430 1187 430 410 1188 410 434 1189 434 409 1190 409 434 1191 434 410 1192 410 433 1193 433 430 1194 430 435 1195 435 433 1196 433 435 1197 435 430 1198 430 431 1199 431 431 1200 431 436 1201 436 435 1202 435 436 1203 436 431 1204 431 432 1205 432 433 1206 433 437 1207 437 434 1208 434 437 1209 437 433 1210 433 435 1211 435 435 1212 435 438 1213 438 437 1214 437 438 1215 438 435 1216 435 436 1217 436 409 1218 409 439 1219 439 408 1220 408 439 1221 439 409 1222 409 434 1223 434 408 1224 408 440 1225 440 406 1226 406 440 1227 440 408 1228 408 439 1229 439 434 1230 434 441 1231 441 439 1232 439 441 1233 441 434 1234 434 437 1235 437 437 1236 437 442 1237 442 441 1238 441 442 1239 442 437 1240 437 438 1241 438 439 1242 439 443 1243 443 440 1244 440 443 1245 443 439 1246 439 441 1247 441 441 1248 441 444 1249 444 443 1250 443 444 1251 444 441 1252 441 442 1253 442 406 1254 406 429 1255 429 407 1256 407 429 1257 429 406 1258 406 440 1259 440 440 1260 440 428 1261 428 429 1262 429 428 1263 428 440 1264 440 443 1265 443 443 1266 443 427 1267 427 428 1268 428 427 1269 427 443 1270 443 444 1271 444 415 1272 415 445 1273 445 432 1274 432 445 1275 445 415 1276 415 416 1277 416 416 1278 416 446 1279 446 445 1280 445 446 1281 446 416 1282 416 417 1283 417 417 1284 417 419 1285 419 446 1286 446 419 1287 419 417 1288 417 418 1289 418 432 1290 432 447 1291 447 436 1292 436 447 1293 447 432 1294 432 445 1295 445 445 1296 445 448 1297 448 447 1298 447 448 1299 448 445 1300 445 446 1301 446 436 1302 436 449 1303 449 438 1304 438 449 1305 449 436 1306 436 447 1307 447 447 1308 447 450 1309 450 449 1310 449 450 1311 450 447 1312 447 448 1313 448 446 1314 446 420 1315 420 448 1316 448 420 1317 420 446 1318 446 419 1319 419 448 1320 448 421 1321 421 450 1322 450 421 1323 421 448 1324 448 420 1325 420 438 1326 438 451 1327 451 442 1328 442 451 1329 451 438 1330 438 449 1331 449 449 1332 449 452 1333 452 451 1334 451 452 1335 452 449 1336 449 450 1337 450 442 1338 442 453 1339 453 444 1340 444 453 1341 453 442 1342 442 451 1343 451 451 1344 451 454 1345 454 453 1346 453 454 1347 454 451 1348 451 452 1349 452 450 1350 450 422 1351 422 452 1352 452 422 1353 422 450 1354 450 421 1355 421 452 1356 452 423 1357 423 454 1358 454 423 1359 423 452 1360 452 422 1361 422 444 1362 444 426 1363 426 427 1364 427 426 1365 426 444 1366 444 453 1367 453 453 1368 453 425 1369 425 426 1370 426 425 1371 425 453 1372 453 454 1373 454 454 1374 454 424 1375 424 425 1376 425 424 1377 424 454 1378 454 423 1379 423 491 1380 491 461 1381 461 492 1382 492 493 1383 493 455 1384 455 468 1385 468 494 1386 494 455 1387 455 493 1388 493 494 1389 494 456 1390 456 455 1391 455 495 1392 495 456 1393 456 494 1394 494 495 1395 495 457 1396 457 456 1397 456 496 1398 496 457 1399 457 495 1400 495 496 1401 496 458 1402 458 457 1403 457 458 1404 458 459 1405 459 460 1406 460 496 1407 496 459 1408 459 458 1409 458 492 1410 492 459 1411 459 496 1412 496 492 1413 492 461 1414 461 459 1415 459 486 1416 486 462 1417 462 463 1418 463 480 1419 480 464 1420 464 465 1421 465 472 1422 472 466 1423 466 467 1424 467 468 1425 468 497 1426 497 493 1427 493 469 1428 469 497 1429 497 468 1430 468 470 1431 470 497 1432 497 469 1433 469 470 1434 470 498 1435 498 497 1436 497 471 1437 471 498 1438 498 470 1439 470 471 1440 471 499 1441 499 498 1442 498 466 1443 466 499 1444 499 471 1445 471 472 1446 472 499 1447 499 466 1448 466 473 1449 473 499 1450 499 472 1451 472 473 1452 473 500 1453 500 499 1454 499 474 1455 474 500 1456 500 473 1457 473 474 1458 474 501 1459 501 500 1460 500 475 1461 475 501 1462 501 474 1463 474 475 1464 475 502 1465 502 501 1466 501 476 1467 476 502 1468 502 475 1469 475 477 1470 477 502 1471 502 476 1472 476 477 1473 477 503 1474 503 502 1475 502 478 1476 478 503 1477 503 477 1478 477 478 1479 478 504 1480 504 503 1481 503 479 1482 479 504 1483 504 478 1484 478 479 1485 479 505 1486 505 504 1487 504 464 1488 464 505 1489 505 479 1490 479 480 1491 480 505 1492 505 464 1493 464 480 1494 480 506 1495 506 505 1496 505 481 1497 481 506 1498 506 480 1499 480 482 1500 482 506 1501 506 481 1502 481 482 1503 482 507 1504 507 506 1505 506 482 1506 482 508 1507 508 507 1508 507 483 1509 483 508 1510 508 482 1511 482 483 1512 483 509 1513 509 508 1514 508 484 1515 484 509 1516 509 483 1517 483 485 1518 485 509 1519 509 484 1520 484 485 1521 485 510 1522 510 509 1523 509 462 1524 462 510 1525 510 485 1526 485 462 1527 462 511 1528 511 510 1529 510 486 1530 486 511 1531 511 462 1532 462 487 1533 487 511 1534 511 486 1535 486 487 1536 487 512 1537 512 511 1538 511 488 1539 488 512 1540 512 487 1541 487 488 1542 488 513 1543 513 512 1544 512 489 1545 489 513 1546 513 488 1547 488 489 1548 489 514 1549 514 513 1550 513 489 1551 489 491 1552 491 514 1553 514 490 1554 490 491 1555 491 489 1556 489 461 1557 461 491 1558 491 490 1559 490 496 1560 496 515 1561 515 492 1562 492 515 1563 515 496 1564 496 495 1565 495 495 1566 495 516 1567 516 515 1568 515 516 1569 516 495 1570 495 494 1571 494 494 1572 494 517 1573 517 516 1574 516 517 1575 517 494 1576 494 493 1577 493 492 1578 492 518 1579 518 491 1580 491 518 1581 518 492 1582 492 515 1583 515 491 1584 491 519 1585 519 514 1586 514 519 1587 519 491 1588 491 518 1589 518 515 1590 515 520 1591 520 518 1592 518 520 1593 520 515 1594 515 516 1595 516 516 1596 516 521 1597 521 520 1598 520 521 1599 521 516 1600 516 517 1601 517 518 1602 518 522 1603 522 519 1604 519 522 1605 522 518 1606 518 520 1607 520 520 1608 520 523 1609 523 522 1610 522 523 1611 523 520 1612 520 521 1613 521 514 1614 514 524 1615 524 513 1616 513 524 1617 524 514 1618 514 519 1619 519 513 1620 513 525 1621 525 512 1622 512 525 1623 525 513 1624 513 524 1625 524 519 1626 519 526 1627 526 524 1628 524 526 1629 526 519 1630 519 522 1631 522 522 1632 522 527 1633 527 526 1634 526 527 1635 527 522 1636 522 523 1637 523 524 1638 524 528 1639 528 525 1640 525 528 1641 528 524 1642 524 526 1643 526 526 1644 526 529 1645 529 528 1646 528 529 1647 529 526 1648 526 527 1649 527 512 1650 512 510 1651 510 511 1652 511 510 1653 510 512 1654 512 525 1655 525 525 1656 525 509 1657 509 510 1658 510 509 1659 509 525 1660 525 528 1661 528 528 1662 528 508 1663 508 509 1664 509 508 1665 508 528 1666 528 529 1667 529 493 1668 493 530 1669 530 517 1670 517 530 1671 530 493 1672 493 497 1673 497 497 1674 497 531 1675 531 530 1676 530 531 1677 531 497 1678 497 498 1679 498 498 1680 498 500 1681 500 531 1682 531 500 1683 500 498 1684 498 499 1685 499 517 1686 517 532 1687 532 521 1688 521 532 1689 532 517 1690 517 530 1691 530 530 1692 530 533 1693 533 532 1694 532 533 1695 533 530 1696 530 531 1697 531 521 1698 521 534 1699 534 523 1700 523 534 1701 534 521 1702 521 532 1703 532 532 1704 532 535 1705 535 534 1706 534 535 1707 535 532 1708 532 533 1709 533 531 1710 531 501 1711 501 533 1712 533 501 1713 501 531 1714 531 500 1715 500 533 1716 533 502 1717 502 535 1718 535 502 1719 502 533 1720 533 501 1721 501 523 1722 523 536 1723 536 527 1724 527 536 1725 536 523 1726 523 534 1727 534 534 1728 534 537 1729 537 536 1730 536 537 1731 537 534 1732 534 535 1733 535 527 1734 527 538 1735 538 529 1736 529 538 1737 538 527 1738 527 536 1739 536 536 1740 536 539 1741 539 538 1742 538 539 1743 539 536 1744 536 537 1745 537 535 1746 535 503 1747 503 537 1748 537 503 1749 503 535 1750 535 502 1751 502 537 1752 537 504 1753 504 539 1754 539 504 1755 504 537 1756 537 503 1757 503 529 1758 529 507 1759 507 508 1760 508 507 1761 507 529 1762 529 538 1763 538 538 1764 538 506 1765 506 507 1766 507 506 1767 506 538 1768 538 539 1769 539 539 1770 539 505 1771 505 506 1772 506 505 1773 505 539 1774 539 504 1775 504 555 1776 555 545 1777 545 540 1778 540 544 1779 544 541 1780 541 542 1781 542 544 1782 544 543 1783 543 541 1784 541 540 1785 540 543 1786 543 544 1787 544 540 1788 540 545 1789 545 543 1790 543 549 1791 549 546 1792 546 547 1793 547 549 1794 549 548 1795 548 546 1796 546 552 1797 552 548 1798 548 549 1799 549 552 1800 552 550 1801 550 548 1802 548 552 1803 552 551 1804 551 550 1805 550 553 1806 553 551 1807 551 552 1808 552 556 1809 556 551 1810 551 553 1811 553 556 1812 556 554 1813 554 551 1814 551 556 1815 556 555 1816 555 554 1817 554 557 1818 557 555 1819 555 556 1820 556 545 1821 545 555 1822 555 557 1823 557 575 1824 575 558 1825 558 563 1826 563 562 1827 562 559 1828 559 560 1829 560 562 1830 562 561 1831 561 559 1832 559 575 1833 575 561 1834 561 562 1835 562 575 1836 575 563 1837 563 561 1838 561 567 1839 567 564 1840 564 565 1841 565 567 1842 567 566 1843 566 564 1844 564 569 1845 569 566 1846 566 567 1847 567 569 1848 569 568 1849 568 566 1850 566 572 1851 572 568 1852 568 569 1853 569 572 1854 572 570 1855 570 568 1856 568 572 1857 572 571 1858 571 570 1859 570 573 1860 573 571 1861 571 572 1862 572 558 1863 558 571 1864 571 573 1865 573 558 1866 558 574 1867 574 571 1868 571 558 1869 558 575 1870 575 574 1871 574 581 1872 581 576 1873 576 577 1874 577 610 1875 610 586 1876 586 611 1877 611 610 1878 610 578 1879 578 586 1880 586 610 1881 610 579 1882 579 578 1883 578 612 1884 612 579 1885 579 610 1886 610 612 1887 612 580 1888 580 579 1889 579 613 1890 613 580 1891 580 612 1892 612 613 1893 613 581 1894 581 580 1895 580 596 1896 596 582 1897 582 583 1898 583 590 1899 590 584 1900 584 585 1901 585 587 1902 587 611 1903 611 586 1904 586 587 1905 587 614 1906 614 611 1907 611 588 1908 588 614 1909 614 587 1910 587 588 1911 588 615 1912 615 614 1913 614 589 1914 589 615 1915 615 588 1916 588 589 1917 589 616 1918 616 615 1919 615 584 1920 584 616 1921 616 589 1922 589 590 1923 590 616 1924 616 584 1925 584 591 1926 591 616 1927 616 590 1928 590 591 1929 591 617 1930 617 616 1931 616 592 1932 592 617 1933 617 591 1934 591 592 1935 592 618 1936 618 617 1937 617 593 1938 593 618 1939 618 592 1940 592 593 1941 593 619 1942 619 618 1943 618 593 1944 593 620 1945 620 619 1946 619 594 1947 594 620 1948 620 593 1949 593 594 1950 594 621 1951 621 620 1952 620 595 1953 595 621 1954 621 594 1955 594 595 1956 595 622 1957 622 621 1958 621 582 1959 582 622 1960 622 595 1961 595 596 1962 596 622 1963 622 582 1964 582 596 1965 596 623 1966 623 622 1967 622 597 1968 597 623 1969 623 596 1970 596 598 1971 598 623 1972 623 597 1973 597 598 1974 598 624 1975 624 623 1976 623 598 1977 598 625 1978 625 624 1979 624 599 1980 599 625 1981 625 598 1982 598 599 1983 599 626 1984 626 625 1985 625 600 1986 600 626 1987 626 599 1988 599 601 1989 601 626 1990 626 600 1991 600 601 1992 601 627 1993 627 626 1994 626 602 1995 602 627 1996 627 601 1997 601 602 1998 602 628 1999 628 627 2000 627 603 2001 603 628 2002 628 602 2003 602 604 2004 604 628 2005 628 603 2006 603 605 2007 605 628 2008 628 604 2009 604 605 2010 605 629 2011 629 628 2012 628 606 2013 606 629 2014 629 605 2015 605 606 2016 606 630 2017 630 629 2018 629 606 2019 606 631 2020 631 630 2021 630 607 2022 607 631 2023 631 606 2024 606 607 2025 607 632 2026 632 631 2027 631 608 2028 608 632 2029 632 607 2030 607 609 2031 609 632 2032 632 608 2033 608 609 2034 609 633 2035 633 632 2036 632 576 2037 576 633 2038 633 609 2039 609 576 2040 576 613 2041 613 633 2042 633 576 2043 576 581 2044 581 613 2045 613 616 2046 616 634 2047 634 615 2048 615 634 2049 634 616 2050 616 617 2051 617 617 2052 617 635 2053 635 634 2054 634 635 2055 635 617 2056 617 618 2057 618 618 2058 618 636 2059 636 635 2060 635 636 2061 636 618 2062 618 619 2063 619 615 2064 615 637 2065 637 614 2066 614 637 2067 637 615 2068 615 634 2069 634 614 2070 614 638 2071 638 611 2072 611 638 2073 638 614 2074 614 637 2075 637 634 2076 634 639 2077 639 637 2078 637 639 2079 639 634 2080 634 635 2081 635 635 2082 635 640 2083 640 639 2084 639 640 2085 640 635 2086 635 636 2087 636 637 2088 637 641 2089 641 638 2090 638 641 2091 641 637 2092 637 639 2093 639 639 2094 639 642 2095 642 641 2096 641 642 2097 642 639 2098 639 640 2099 640 611 2100 611 643 2101 643 610 2102 610 643 2103 643 611 2104 611 638 2105 638 610 2106 610 644 2107 644 612 2108 612 644 2109 644 610 2110 610 643 2111 643 638 2112 638 645 2113 645 643 2114 643 645 2115 645 638 2116 638 641 2117 641 641 2118 641 646 2119 646 645 2120 645 646 2121 646 641 2122 641 642 2123 642 643 2124 643 647 2125 647 644 2126 644 647 2127 647 643 2128 643 645 2129 645 645 2130 645 648 2131 648 647 2132 647 648 2133 648 645 2134 645 646 2135 646 612 2136 612 633 2137 633 613 2138 613 633 2139 633 612 2140 612 644 2141 644 644 2142 644 632 2143 632 633 2144 633 632 2145 632 644 2146 644 647 2147 647 647 2148 647 631 2149 631 632 2150 632 631 2151 631 647 2152 647 648 2153 648 619 2154 619 649 2155 649 636 2156 636 649 2157 649 619 2158 619 620 2159 620 620 2160 620 650 2161 650 649 2162 649 650 2163 650 620 2164 620 621 2165 621 621 2166 621 623 2167 623 650 2168 650 623 2169 623 621 2170 621 622 2171 622 636 2172 636 651 2173 651 640 2174 640 651 2175 651 636 2176 636 649 2177 649 649 2178 649 652 2179 652 651 2180 651 652 2181 652 649 2182 649 650 2183 650 640 2184 640 653 2185 653 642 2186 642 653 2187 653 640 2188 640 651 2189 651 651 2190 651 654 2191 654 653 2192 653 654 2193 654 651 2194 651 652 2195 652 650 2196 650 624 2197 624 652 2198 652 624 2199 624 650 2200 650 623 2201 623 652 2202 652 625 2203 625 654 2204 654 625 2205 625 652 2206 652 624 2207 624 642 2208 642 655 2209 655 646 2210 646 655 2211 655 642 2212 642 653 2213 653 653 2214 653 656 2215 656 655 2216 655 656 2217 656 653 2218 653 654 2219 654 646 2220 646 657 2221 657 648 2222 648 657 2223 657 646 2224 646 655 2225 655 655 2226 655 658 2227 658 657 2228 657 658 2229 658 655 2230 655 656 2231 656 654 2232 654 626 2233 626 656 2234 656 626 2235 626 654 2236 654 625 2237 625 656 2238 656 627 2239 627 658 2240 658 627 2241 627 656 2242 656 626 2243 626 648 2244 648 630 2245 630 631 2246 631 630 2247 630 648 2248 648 657 2249 657 657 2250 657 629 2251 629 630 2252 630 629 2253 629 657 2254 657 658 2255 658 658 2256 658 628 2257 628 629 2258 629 628 2259 628 658 2260 658 627 2261 627 695 2262 695 686 2263 686 696 2264 696 697 2265 697 659 2266 659 689 2267 689 698 2268 698 659 2269 659 697 2270 697 698 2271 698 660 2272 660 659 2273 659 699 2274 699 660 2275 660 698 2276 698 699 2277 699 661 2278 661 660 2279 660 700 2280 700 661 2281 661 699 2282 699 700 2283 700 662 2284 662 661 2285 661 662 2286 662 663 2287 663 664 2288 664 700 2289 700 663 2290 663 662 2291 662 700 2292 700 665 2293 665 663 2294 663 701 2295 701 665 2296 665 700 2297 700 701 2298 701 666 2299 666 665 2300 665 702 2301 702 666 2302 666 701 2303 701 702 2304 702 667 2305 667 666 2306 666 703 2307 703 667 2308 667 702 2309 702 703 2310 703 668 2311 668 667 2312 667 703 2313 703 669 2314 669 668 2315 668 704 2316 704 669 2317 669 703 2318 703 704 2319 704 670 2320 670 669 2321 669 705 2322 705 670 2323 670 704 2324 704 705 2325 705 671 2326 671 670 2327 670 706 2328 706 671 2329 671 705 2330 705 706 2331 706 672 2332 672 671 2333 671 672 2334 672 673 2335 673 674 2336 674 706 2337 706 673 2338 673 672 2339 672 707 2340 707 673 2341 673 706 2342 706 707 2343 707 675 2344 675 673 2345 673 708 2346 708 675 2347 675 707 2348 707 708 2349 708 676 2350 676 675 2351 675 709 2352 709 676 2353 676 708 2354 708 709 2355 709 677 2356 677 676 2357 676 709 2358 709 678 2359 678 677 2360 677 710 2361 710 678 2362 678 709 2363 709 710 2364 710 679 2365 679 678 2366 678 711 2367 711 679 2368 679 710 2369 710 712 2370 712 679 2371 679 711 2372 711 712 2373 712 680 2374 680 679 2375 679 680 2376 680 681 2377 681 682 2378 682 712 2379 712 681 2380 681 680 2381 680 713 2382 713 681 2383 681 712 2384 712 713 2385 713 683 2386 683 681 2387 681 713 2388 713 684 2389 684 683 2390 683 714 2391 714 684 2392 684 713 2393 713 715 2394 715 684 2395 684 714 2396 714 715 2397 715 685 2398 685 684 2399 684 715 2400 715 686 2401 686 685 2402 685 696 2403 696 686 2404 686 715 2405 715 693 2406 693 687 2407 687 688 2408 688 689 2409 689 716 2410 716 697 2411 697 690 2412 690 716 2413 716 689 2414 689 691 2415 691 716 2416 716 690 2417 690 691 2418 691 717 2419 717 716 2420 716 692 2421 692 717 2422 717 691 2423 691 692 2424 692 718 2425 718 717 2426 717 687 2427 687 718 2428 718 692 2429 692 693 2430 693 718 2431 718 687 2432 687 693 2433 693 695 2434 695 718 2435 718 694 2436 694 695 2437 695 693 2438 693 686 2439 686 695 2440 695 694 2441 694 700 2442 700 719 2443 719 701 2444 701 719 2445 719 700 2446 700 699 2447 699 699 2448 699 720 2449 720 719 2450 719 720 2451 720 699 2452 699 698 2453 698 698 2454 698 721 2455 721 720 2456 720 721 2457 721 698 2458 698 697 2459 697 701 2460 701 722 2461 722 702 2462 702 722 2463 722 701 2464 701 719 2465 719 702 2466 702 723 2467 723 703 2468 703 723 2469 723 702 2470 702 722 2471 722 719 2472 719 724 2473 724 722 2474 722 724 2475 724 719 2476 719 720 2477 720 720 2478 720 725 2479 725 724 2480 724 725 2481 725 720 2482 720 721 2483 721 722 2484 722 726 2485 726 723 2486 723 726 2487 726 722 2488 722 724 2489 724 724 2490 724 727 2491 727 726 2492 726 727 2493 727 724 2494 724 725 2495 725 703 2496 703 728 2497 728 704 2498 704 728 2499 728 703 2500 703 723 2501 723 704 2502 704 729 2503 729 705 2504 705 729 2505 729 704 2506 704 728 2507 728 723 2508 723 730 2509 730 728 2510 728 730 2511 730 723 2512 723 726 2513 726 726 2514 726 731 2515 731 730 2516 730 731 2517 731 726 2518 726 727 2519 727 728 2520 728 732 2521 732 729 2522 729 732 2523 732 728 2524 728 730 2525 730 730 2526 730 733 2527 733 732 2528 732 733 2529 733 730 2530 730 731 2531 731 705 2532 705 707 2533 707 706 2534 706 707 2535 707 705 2536 705 729 2537 729 729 2538 729 708 2539 708 707 2540 707 708 2541 708 729 2542 729 732 2543 732 732 2544 732 709 2545 709 708 2546 708 709 2547 709 732 2548 732 733 2549 733 697 2550 697 734 2551 734 721 2552 721 734 2553 734 697 2554 697 716 2555 716 716 2556 716 735 2557 735 734 2558 734 735 2559 735 716 2560 716 717 2561 717 717 2562 717 695 2563 695 735 2564 735 695 2565 695 717 2566 717 718 2567 718 721 2568 721 736 2569 736 725 2570 725 736 2571 736 721 2572 721 734 2573 734 734 2574 734 737 2575 737 736 2576 736 737 2577 737 734 2578 734 735 2579 735 725 2580 725 738 2581 738 727 2582 727 738 2583 738 725 2584 725 736 2585 736 736 2586 736 739 2587 739 738 2588 738 739 2589 739 736 2590 736 737 2591 737 735 2592 735 696 2593 696 737 2594 737 696 2595 696 735 2596 735 695 2597 695 737 2598 737 715 2599 715 739 2600 739 715 2601 715 737 2602 737 696 2603 696 727 2604 727 740 2605 740 731 2606 731 740 2607 740 727 2608 727 738 2609 738 738 2610 738 741 2611 741 740 2612 740 741 2613 741 738 2614 738 739 2615 739 731 2616 731 742 2617 742 733 2618 733 742 2619 742 731 2620 731 740 2621 740 740 2622 740 743 2623 743 742 2624 742 743 2625 743 740 2626 740 741 2627 741 739 2628 739 714 2629 714 741 2630 741 714 2631 714 739 2632 739 715 2633 715 741 2634 741 713 2635 713 743 2636 743 713 2637 713 741 2638 741 714 2639 714 733 2640 733 710 2641 710 709 2642 709 710 2643 710 733 2644 733 742 2645 742 742 2646 742 711 2647 711 710 2648 710 711 2649 711 742 2650 742 743 2651 743 743 2652 743 712 2653 712 711 2654 711 712 2655 712 743 2656 743 713 2657 713 760 2658 760 745 2659 745 744 2660 744 747 2661 747 745 2662 745 746 2663 746 744 2664 744 745 2665 745 747 2666 747 751 2667 751 748 2668 748 749 2669 749 751 2670 751 750 2671 750 748 2672 748 753 2673 753 750 2674 750 751 2675 751 753 2676 753 752 2677 752 750 2678 750 756 2679 756 752 2680 752 753 2681 753 756 2682 756 754 2683 754 752 2684 752 756 2685 756 755 2686 755 754 2687 754 757 2688 757 755 2689 755 756 2690 756 759 2691 759 755 2692 755 757 2693 757 759 2694 759 758 2695 758 755 2696 755 761 2697 761 758 2698 758 759 2699 759 761 2700 761 760 2701 760 758 2702 758 745 2703 745 760 2704 760 761 2705 761 779 2706 779 762 2707 762 763 2708 763 766 2709 766 764 2710 764 765 2711 765 767 2712 767 764 2713 764 766 2714 766 769 2715 769 764 2716 764 767 2717 767 769 2718 769 768 2719 768 764 2720 764 771 2721 771 768 2722 768 769 2723 769 771 2724 771 770 2725 770 768 2726 768 773 2727 773 770 2728 770 771 2729 771 773 2730 773 772 2731 772 770 2732 770 775 2733 775 772 2734 772 773 2735 773 775 2736 775 774 2737 774 772 2738 772 777 2739 777 774 2740 774 775 2741 775 777 2742 777 776 2743 776 774 2744 774 762 2745 762 776 2746 776 777 2747 777 762 2748 762 778 2749 778 776 2750 776 762 2751 762 779 2752 779 778 2753 778 796 2754 796 780 2755 780 781 2756 781 784 2757 784 782 2758 782 783 2759 783 785 2760 785 782 2761 782 784 2762 784 787 2763 787 782 2764 782 785 2765 785 787 2766 787 786 2767 786 782 2768 782 789 2769 789 786 2770 786 787 2771 787 789 2772 789 788 2773 788 786 2774 786 791 2775 791 788 2776 788 789 2777 789 791 2778 791 790 2779 790 788 2780 788 793 2781 793 790 2782 790 791 2783 791 793 2784 793 792 2785 792 790 2786 790 795 2787 795 792 2788 792 793 2789 793 795 2790 795 794 2791 794 792 2792 792 797 2793 797 794 2794 794 795 2795 795 797 2796 797 796 2797 796 794 2798 794 780 2799 780 796 2800 796 797 2801 797 831 2802 831 798 2803 798 799 2804 799 832 2805 832 803 2806 803 833 2807 833 832 2808 832 800 2809 800 803 2810 803 834 2811 834 800 2812 800 832 2813 832 834 2814 834 801 2815 801 800 2816 800 835 2817 835 801 2818 801 834 2819 834 835 2820 835 802 2821 802 801 2822 801 805 2823 805 803 2824 803 804 2825 804 805 2826 805 833 2827 833 803 2828 803 805 2829 805 836 2830 836 833 2831 833 806 2832 806 836 2833 836 805 2834 805 807 2835 807 836 2836 836 806 2837 806 807 2838 807 837 2839 837 836 2840 836 807 2841 807 838 2842 838 837 2843 837 808 2844 808 838 2845 838 807 2846 807 809 2847 809 838 2848 838 808 2849 808 809 2850 809 839 2851 839 838 2852 838 810 2853 810 839 2854 839 809 2855 809 810 2856 810 840 2857 840 839 2858 839 811 2859 811 840 2860 840 810 2861 810 811 2862 811 841 2863 841 840 2864 840 812 2865 812 841 2866 841 811 2867 811 813 2868 813 841 2869 841 812 2870 812 813 2871 813 842 2872 842 841 2873 841 814 2874 814 842 2875 842 813 2876 813 815 2877 815 842 2878 842 814 2879 814 815 2880 815 843 2881 843 842 2882 842 815 2883 815 844 2884 844 843 2885 843 816 2886 816 844 2887 844 815 2888 815 817 2889 817 844 2890 844 816 2891 816 817 2892 817 845 2893 845 844 2894 844 818 2895 818 845 2896 845 817 2897 817 818 2898 818 846 2899 846 845 2900 845 819 2901 819 846 2902 846 818 2903 818 819 2904 819 847 2905 847 846 2906 846 820 2907 820 847 2908 847 819 2909 819 821 2910 821 847 2911 847 820 2912 820 822 2913 822 847 2914 847 821 2915 821 822 2916 822 848 2917 848 847 2918 847 823 2919 823 848 2920 848 822 2921 822 823 2922 823 849 2923 849 848 2924 848 824 2925 824 849 2926 849 823 2927 823 824 2928 824 850 2929 850 849 2930 849 825 2931 825 850 2932 850 824 2933 824 825 2934 825 851 2935 851 850 2936 850 826 2937 826 851 2938 851 825 2939 825 827 2940 827 851 2941 851 826 2942 826 827 2943 827 852 2944 852 851 2945 851 828 2946 828 852 2947 852 827 2948 827 828 2949 828 853 2950 853 852 2951 852 798 2952 798 853 2953 853 828 2954 828 854 2955 854 802 2956 802 835 2957 835 854 2958 854 829 2959 829 802 2960 802 854 2961 854 830 2962 830 829 2963 829 855 2964 855 830 2965 830 854 2966 854 855 2967 855 831 2968 831 830 2969 830 853 2970 853 831 2971 831 855 2972 855 798 2973 798 831 2974 831 853 2975 853 833 2976 833 856 2977 856 832 2978 832 856 2979 856 833 2980 833 836 2981 836 836 2982 836 857 2983 857 856 2984 856 857 2985 857 836 2986 836 837 2987 837 837 2988 837 858 2989 858 857 2990 857 858 2991 858 837 2992 837 838 2993 838 832 2994 832 859 2995 859 834 2996 834 859 2997 859 832 2998 832 856 2999 856 834 3000 834 860 3001 860 835 3002 835 860 3003 860 834 3004 834 859 3005 859 856 3006 856 861 3007 861 859 3008 859 861 3009 861 856 3010 856 857 3011 857 857 3012 857 862 3013 862 861 3014 861 862 3015 862 857 3016 857 858 3017 858 859 3018 859 863 3019 863 860 3020 860 863 3021 863 859 3022 859 861 3023 861 861 3024 861 864 3025 864 863 3026 863 864 3027 864 861 3028 861 862 3029 862 835 3030 835 865 3031 865 854 3032 854 865 3033 865 835 3034 835 860 3035 860 854 3036 854 866 3037 866 855 3038 855 866 3039 866 854 3040 854 865 3041 865 860 3042 860 867 3043 867 865 3044 865 867 3045 867 860 3046 860 863 3047 863 863 3048 863 868 3049 868 867 3050 867 868 3051 868 863 3052 863 864 3053 864 865 3054 865 869 3055 869 866 3056 866 869 3057 869 865 3058 865 867 3059 867 867 3060 867 870 3061 870 869 3062 869 870 3063 870 867 3064 867 868 3065 868 855 3066 855 852 3067 852 853 3068 853 852 3069 852 855 3070 855 866 3071 866 866 3072 866 851 3073 851 852 3074 852 851 3075 851 866 3076 866 869 3077 869 869 3078 869 850 3079 850 851 3080 851 850 3081 850 869 3082 869 870 3083 870 838 3084 838 871 3085 871 858 3086 858 871 3087 871 838 3088 838 839 3089 839 839 3090 839 872 3091 872 871 3092 871 872 3093 872 839 3094 839 840 3095 840 840 3096 840 842 3097 842 872 3098 872 842 3099 842 840 3100 840 841 3101 841 858 3102 858 873 3103 873 862 3104 862 873 3105 873 858 3106 858 871 3107 871 871 3108 871 874 3109 874 873 3110 873 874 3111 874 871 3112 871 872 3113 872 862 3114 862 875 3115 875 864 3116 864 875 3117 875 862 3118 862 873 3119 873 873 3120 873 876 3121 876 875 3122 875 876 3123 876 873 3124 873 874 3125 874 872 3126 872 843 3127 843 874 3128 874 843 3129 843 872 3130 872 842 3131 842 874 3132 874 844 3133 844 876 3134 876 844 3135 844 874 3136 874 843 3137 843 864 3138 864 877 3139 877 868 3140 868 877 3141 877 864 3142 864 875 3143 875 875 3144 875 878 3145 878 877 3146 877 878 3147 878 875 3148 875 876 3149 876 868 3150 868 879 3151 879 870 3152 870 879 3153 879 868 3154 868 877 3155 877 877 3156 877 880 3157 880 879 3158 879 880 3159 880 877 3160 877 878 3161 878 876 3162 876 845 3163 845 878 3164 878 845 3165 845 876 3166 876 844 3167 844 878 3168 878 846 3169 846 880 3170 880 846 3171 846 878 3172 878 845 3173 845 870 3174 870 849 3175 849 850 3176 850 849 3177 849 870 3178 870 879 3179 879 879 3180 879 848 3181 848 849 3182 849 848 3183 848 879 3184 879 880 3185 880 880 3186 880 847 3187 847 848 3188 848 847 3189 847 880 3190 880 846 3191 846 912 3192 912 913 3193 913 881 3194 881 888 3195 888 882 3196 882 883 3197 883 914 3198 914 881 3199 881 913 3200 913 914 3201 914 884 3202 884 881 3203 881 914 3204 914 885 3205 885 884 3206 884 915 3207 915 885 3208 885 914 3209 914 916 3210 916 885 3211 885 915 3212 915 916 3213 916 886 3214 886 885 3215 885 917 3216 917 886 3217 886 916 3218 916 917 3219 917 887 3220 887 886 3221 886 917 3222 917 888 3223 888 887 3224 887 918 3225 918 888 3226 888 917 3227 917 918 3228 918 882 3229 882 888 3230 888 919 3231 919 882 3232 882 918 3233 918 919 3234 919 889 3235 889 882 3236 882 920 3237 920 889 3238 889 919 3239 919 920 3240 920 890 3241 890 889 3242 889 921 3243 921 890 3244 890 920 3245 920 921 3246 921 891 3247 891 890 3248 890 922 3249 922 891 3250 891 921 3251 921 922 3252 922 892 3253 892 891 3254 891 923 3255 923 892 3256 892 922 3257 922 923 3258 923 893 3259 893 892 3260 892 924 3261 924 893 3262 893 923 3263 923 924 3264 924 894 3265 894 893 3266 893 924 3267 924 895 3268 895 894 3269 894 924 3270 924 896 3271 896 895 3272 895 925 3273 925 896 3274 896 924 3275 924 925 3276 925 897 3277 897 896 3278 896 925 3279 925 898 3280 898 897 3281 897 926 3282 926 898 3283 898 925 3284 925 926 3285 926 899 3286 899 898 3287 898 927 3288 927 899 3289 899 926 3290 926 927 3291 927 900 3292 900 899 3293 899 928 3294 928 900 3295 900 927 3296 927 929 3297 929 900 3298 900 928 3299 928 929 3300 929 901 3301 901 900 3302 900 930 3303 930 901 3304 901 929 3305 929 930 3306 930 902 3307 902 901 3308 901 930 3309 930 903 3310 903 902 3311 902 930 3312 930 904 3313 904 903 3314 903 931 3315 931 904 3316 904 930 3317 930 931 3318 931 905 3319 905 904 3320 904 932 3321 932 905 3322 905 931 3323 931 932 3324 932 906 3325 906 905 3326 905 933 3327 933 906 3328 906 932 3329 932 933 3330 933 907 3331 907 906 3332 906 934 3333 934 907 3334 907 933 3335 933 934 3336 934 908 3337 908 907 3338 907 935 3339 935 908 3340 908 934 3341 934 935 3342 935 909 3343 909 908 3344 908 936 3345 936 909 3346 909 935 3347 935 936 3348 936 910 3349 910 909 3350 909 936 3351 936 911 3352 911 910 3353 910 936 3354 936 912 3355 912 911 3356 911 913 3357 913 912 3358 912 936 3359 936 936 3360 936 937 3361 937 913 3362 913 937 3363 937 936 3364 936 935 3365 935 913 3366 913 938 3367 938 914 3368 914 938 3369 938 913 3370 913 937 3371 937 914 3372 914 939 3373 939 915 3374 915 939 3375 939 914 3376 914 938 3377 938 915 3378 915 940 3379 940 916 3380 916 940 3381 940 915 3382 915 939 3383 939 916 3384 916 941 3385 941 917 3386 917 941 3387 941 916 3388 916 940 3389 940 917 3390 917 919 3391 919 918 3392 918 919 3393 919 917 3394 917 941 3395 941 935 3396 935 942 3397 942 937 3398 937 942 3399 942 935 3400 935 934 3401 934 937 3402 937 943 3403 943 938 3404 938 943 3405 943 937 3406 937 942 3407 942 938 3408 938 944 3409 944 939 3410 939 944 3411 944 938 3412 938 943 3413 943 934 3414 934 945 3415 945 942 3416 942 945 3417 945 934 3418 934 933 3419 933 942 3420 942 946 3421 946 943 3422 943 946 3423 946 942 3424 942 945 3425 945 943 3426 943 947 3427 947 944 3428 944 947 3429 947 943 3430 943 946 3431 946 939 3432 939 948 3433 948 940 3434 940 948 3435 948 939 3436 939 944 3437 944 940 3438 940 949 3439 949 941 3440 941 949 3441 949 940 3442 940 948 3443 948 941 3444 941 920 3445 920 919 3446 919 920 3447 920 941 3448 941 949 3449 949 944 3450 944 950 3451 950 948 3452 948 950 3453 950 944 3454 944 947 3455 947 948 3456 948 951 3457 951 949 3458 949 951 3459 951 948 3460 948 950 3461 950 949 3462 949 921 3463 921 920 3464 920 921 3465 921 949 3466 949 951 3467 951 933 3468 933 952 3469 952 945 3470 945 952 3471 952 933 3472 933 932 3473 932 945 3474 945 953 3475 953 946 3476 946 953 3477 953 945 3478 945 952 3479 952 946 3480 946 954 3481 954 947 3482 947 954 3483 954 946 3484 946 953 3485 953 932 3486 932 955 3487 955 952 3488 952 955 3489 955 932 3490 932 931 3491 931 952 3492 952 956 3493 956 953 3494 953 956 3495 956 952 3496 952 955 3497 955 953 3498 953 957 3499 957 954 3500 954 957 3501 957 953 3502 953 956 3503 956 947 3504 947 958 3505 958 950 3506 950 958 3507 958 947 3508 947 954 3509 954 950 3510 950 959 3511 959 951 3512 951 959 3513 959 950 3514 950 958 3515 958 951 3516 951 922 3517 922 921 3518 921 922 3519 922 951 3520 951 959 3521 959 954 3522 954 960 3523 960 958 3524 958 960 3525 960 954 3526 954 957 3527 957 958 3528 958 961 3529 961 959 3530 959 961 3531 961 958 3532 958 960 3533 960 959 3534 959 923 3535 923 922 3536 922 923 3537 923 959 3538 959 961 3539 961 931 3540 931 929 3541 929 955 3542 955 929 3543 929 931 3544 931 930 3545 930 955 3546 955 928 3547 928 956 3548 956 928 3549 928 955 3550 955 929 3551 929 956 3552 956 927 3553 927 957 3554 957 927 3555 927 956 3556 956 928 3557 928 957 3558 957 926 3559 926 960 3560 960 926 3561 926 957 3562 957 927 3563 927 960 3564 960 925 3565 925 961 3566 961 925 3567 925 960 3568 960 926 3569 926 961 3570 961 924 3571 924 923 3572 923 924 3573 924 961 3574 961 925 3575 925 977 3576 977 962 3577 962 963 3578 963 968 3579 968 964 3580 964 965 3581 965 968 3582 968 966 3583 966 964 3584 964 968 3585 968 967 3586 967 966 3587 966 970 3588 970 967 3589 967 968 3590 968 970 3591 970 969 3592 969 967 3593 967 971 3594 971 969 3595 969 970 3596 970 973 3597 973 969 3598 969 971 3599 971 973 3600 973 972 3601 972 969 3602 969 975 3603 975 972 3604 972 973 3605 973 975 3606 975 974 3607 974 972 3608 972 978 3609 978 974 3610 974 975 3611 975 978 3612 978 976 3613 976 974 3614 974 978 3615 978 977 3616 977 976 3617 976 979 3618 979 977 3619 977 978 3620 978 962 3621 962 977 3622 977 979 3623 979 999 3624 999 992 3625 992 980 3626 980 983 3627 983 981 3628 981 982 3629 982 985 3630 985 981 3631 981 983 3632 983 985 3633 985 984 3634 984 981 3635 981 986 3636 986 984 3637 984 985 3638 985 988 3639 988 984 3640 984 986 3641 986 988 3642 988 987 3643 987 984 3644 984 990 3645 990 987 3646 987 988 3647 988 990 3648 990 989 3649 989 987 3650 987 993 3651 993 989 3652 989 990 3653 990 993 3654 993 991 3655 991 989 3656 989 993 3657 993 992 3658 992 991 3659 991 980 3660 980 992 3661 992 993 3662 993 997 3663 997 994 3664 994 995 3665 995 997 3666 997 996 3667 996 994 3668 994 1000 3669 1000 996 3670 996 997 3671 997 1000 3672 1000 998 3673 998 996 3674 996 1000 3675 1000 999 3676 999 998 3677 998 1001 3678 1001 999 3679 999 1000 3680 1000 992 3681 992 999 3682 999 1001 3683 1001 1037 3684 1037 1002 3685 1002 1003 3686 1003 1038 3687 1038 1004 3688 1004 1016 3689 1016 1039 3690 1039 1004 3691 1004 1038 3692 1038 1039 3693 1039 1005 3694 1005 1004 3695 1004 1040 3696 1040 1005 3697 1005 1039 3698 1039 1040 3699 1040 1006 3700 1006 1005 3701 1005 1041 3702 1041 1006 3703 1006 1040 3704 1040 1041 3705 1041 1007 3706 1007 1006 3707 1006 1007 3708 1007 1008 3709 1008 1009 3710 1009 1041 3711 1041 1008 3712 1008 1007 3713 1007 1042 3714 1042 1008 3715 1008 1041 3716 1041 1042 3717 1042 1010 3718 1010 1008 3719 1008 1043 3720 1043 1010 3721 1010 1042 3722 1042 1043 3723 1043 1011 3724 1011 1010 3725 1010 1044 3726 1044 1011 3727 1011 1043 3728 1043 1044 3729 1044 1012 3730 1012 1011 3731 1011 1044 3732 1044 1013 3733 1013 1012 3734 1012 1045 3735 1045 1013 3736 1013 1044 3737 1044 1020 3738 1020 1014 3739 1014 1015 3740 1015 1016 3741 1016 1046 3742 1046 1038 3743 1038 1017 3744 1017 1046 3745 1046 1016 3746 1016 1018 3747 1018 1046 3748 1046 1017 3749 1017 1018 3750 1018 1047 3751 1047 1046 3752 1046 1019 3753 1019 1047 3754 1047 1018 3755 1018 1019 3756 1019 1048 3757 1048 1047 3758 1047 1014 3759 1014 1048 3760 1048 1019 3761 1019 1020 3762 1020 1048 3763 1048 1014 3764 1014 1021 3765 1021 1048 3766 1048 1020 3767 1020 1021 3768 1021 1049 3769 1049 1048 3770 1048 1022 3771 1022 1049 3772 1049 1021 3773 1021 1022 3774 1022 1050 3775 1050 1049 3776 1049 1023 3777 1023 1050 3778 1050 1022 3779 1022 1023 3780 1023 1051 3781 1051 1050 3782 1050 1023 3783 1023 1052 3784 1052 1051 3785 1051 1024 3786 1024 1052 3787 1052 1023 3788 1023 1024 3789 1024 1053 3790 1053 1052 3791 1052 1025 3792 1025 1053 3793 1053 1024 3794 1024 1025 3795 1025 1054 3796 1054 1053 3797 1053 1002 3798 1002 1054 3799 1054 1025 3800 1025 1055 3801 1055 1013 3802 1013 1045 3803 1045 1055 3804 1055 1026 3805 1026 1013 3806 1013 1056 3807 1056 1026 3808 1026 1055 3809 1055 1056 3810 1056 1027 3811 1027 1026 3812 1026 1056 3813 1056 1028 3814 1028 1027 3815 1027 1056 3816 1056 1029 3817 1029 1028 3818 1028 1056 3819 1056 1030 3820 1030 1029 3821 1029 1057 3822 1057 1030 3823 1030 1056 3824 1056 1057 3825 1057 1031 3826 1031 1030 3827 1030 1058 3828 1058 1031 3829 1031 1057 3830 1057 1058 3831 1058 1032 3832 1032 1031 3833 1031 1059 3834 1059 1032 3835 1032 1058 3836 1058 1059 3837 1059 1033 3838 1033 1032 3839 1032 1060 3840 1060 1033 3841 1033 1059 3842 1059 1060 3843 1060 1034 3844 1034 1033 3845 1033 1060 3846 1060 1035 3847 1035 1034 3848 1034 1061 3849 1061 1035 3850 1035 1060 3851 1060 1061 3852 1061 1036 3853 1036 1035 3854 1035 1054 3855 1054 1036 3856 1036 1061 3857 1061 1054 3858 1054 1037 3859 1037 1036 3860 1036 1002 3861 1002 1037 3862 1037 1054 3863 1054 1048 3864 1048 1062 3865 1062 1047 3866 1047 1062 3867 1062 1048 3868 1048 1049 3869 1049 1049 3870 1049 1063 3871 1063 1062 3872 1062 1063 3873 1063 1049 3874 1049 1050 3875 1050 1050 3876 1050 1064 3877 1064 1063 3878 1063 1064 3879 1064 1050 3880 1050 1051 3881 1051 1047 3882 1047 1065 3883 1065 1046 3884 1046 1065 3885 1065 1047 3886 1047 1062 3887 1062 1046 3888 1046 1066 3889 1066 1038 3890 1038 1066 3891 1066 1046 3892 1046 1065 3893 1065 1062 3894 1062 1067 3895 1067 1065 3896 1065 1067 3897 1067 1062 3898 1062 1063 3899 1063 1063 3900 1063 1068 3901 1068 1067 3902 1067 1068 3903 1068 1063 3904 1063 1064 3905 1064 1065 3906 1065 1069 3907 1069 1066 3908 1066 1069 3909 1069 1065 3910 1065 1067 3911 1067 1067 3912 1067 1070 3913 1070 1069 3914 1069 1070 3915 1070 1067 3916 1067 1068 3917 1068 1038 3918 1038 1071 3919 1071 1039 3920 1039 1071 3921 1071 1038 3922 1038 1066 3923 1066 1039 3924 1039 1072 3925 1072 1040 3926 1040 1072 3927 1072 1039 3928 1039 1071 3929 1071 1066 3930 1066 1073 3931 1073 1071 3932 1071 1073 3933 1073 1066 3934 1066 1069 3935 1069 1069 3936 1069 1074 3937 1074 1073 3938 1073 1074 3939 1074 1069 3940 1069 1070 3941 1070 1071 3942 1071 1075 3943 1075 1072 3944 1072 1075 3945 1075 1071 3946 1071 1073 3947 1073 1073 3948 1073 1076 3949 1076 1075 3950 1075 1076 3951 1076 1073 3952 1073 1074 3953 1074 1040 3954 1040 1042 3955 1042 1041 3956 1041 1042 3957 1042 1040 3958 1040 1072 3959 1072 1072 3960 1072 1043 3961 1043 1042 3962 1042 1043 3963 1043 1072 3964 1072 1075 3965 1075 1075 3966 1075 1044 3967 1044 1043 3968 1043 1044 3969 1044 1075 3970 1075 1076 3971 1076 1051 3972 1051 1077 3973 1077 1064 3974 1064 1077 3975 1077 1051 3976 1051 1052 3977 1052 1052 3978 1052 1078 3979 1078 1077 3980 1077 1078 3981 1078 1052 3982 1052 1053 3983 1053 1053 3984 1053 1061 3985 1061 1078 3986 1078 1061 3987 1061 1053 3988 1053 1054 3989 1054 1064 3990 1064 1079 3991 1079 1068 3992 1068 1079 3993 1079 1064 3994 1064 1077 3995 1077 1077 3996 1077 1080 3997 1080 1079 3998 1079 1080 3999 1080 1077 4000 1077 1078 4001 1078 1068 4002 1068 1081 4003 1081 1070 4004 1070 1081 4005 1081 1068 4006 1068 1079 4007 1079 1079 4008 1079 1082 4009 1082 1081 4010 1081 1082 4011 1082 1079 4012 1079 1080 4013 1080 1078 4014 1078 1060 4015 1060 1080 4016 1080 1060 4017 1060 1078 4018 1078 1061 4019 1061 1080 4020 1080 1059 4021 1059 1082 4022 1082 1059 4023 1059 1080 4024 1080 1060 4025 1060 1070 4026 1070 1083 4027 1083 1074 4028 1074 1083 4029 1083 1070 4030 1070 1081 4031 1081 1081 4032 1081 1084 4033 1084 1083 4034 1083 1084 4035 1084 1081 4036 1081 1082 4037 1082 1074 4038 1074 1085 4039 1085 1076 4040 1076 1085 4041 1085 1074 4042 1074 1083 4043 1083 1083 4044 1083 1086 4045 1086 1085 4046 1085 1086 4047 1086 1083 4048 1083 1084 4049 1084 1082 4050 1082 1058 4051 1058 1084 4052 1084 1058 4053 1058 1082 4054 1082 1059 4055 1059 1084 4056 1084 1057 4057 1057 1086 4058 1086 1057 4059 1057 1084 4060 1084 1058 4061 1058 1076 4062 1076 1045 4063 1045 1044 4064 1044 1045 4065 1045 1076 4066 1076 1085 4067 1085 1085 4068 1085 1055 4069 1055 1045 4070 1045 1055 4071 1055 1085 4072 1085 1086 4073 1086 1086 4074 1086 1056 4075 1056 1055 4076 1055 1056 4077 1056 1086 4078 1086 1057 4079 1057 1118 4080 1118 1119 4081 1119 1087 4082 1087 1120 4083 1120 1092 4084 1092 1121 4085 1121 1120 4086 1120 1088 4087 1088 1092 4088 1092 1122 4089 1122 1088 4090 1088 1120 4091 1120 1122 4092 1122 1089 4093 1089 1088 4094 1088 1108 4095 1108 1090 4096 1090 1091 4097 1091 1093 4098 1093 1121 4099 1121 1092 4100 1092 1094 4101 1094 1121 4102 1121 1093 4103 1093 1094 4104 1094 1123 4105 1123 1121 4106 1121 1095 4107 1095 1123 4108 1123 1094 4109 1094 1095 4110 1095 1124 4111 1124 1123 4112 1123 1096 4113 1096 1124 4114 1124 1095 4115 1095 1097 4116 1097 1124 4117 1124 1096 4118 1096 1097 4119 1097 1125 4120 1125 1124 4121 1124 1097 4122 1097 1126 4123 1126 1125 4124 1125 1098 4125 1098 1126 4126 1126 1097 4127 1097 1098 4128 1098 1127 4129 1127 1126 4130 1126 1099 4131 1099 1127 4132 1127 1098 4133 1098 1099 4134 1099 1128 4135 1128 1127 4136 1127 1100 4137 1100 1128 4138 1128 1099 4139 1099 1101 4140 1101 1128 4141 1128 1100 4142 1100 1102 4143 1102 1128 4144 1128 1101 4145 1101 1103 4146 1103 1128 4147 1128 1102 4148 1102 1103 4149 1103 1129 4150 1129 1128 4151 1128 1104 4152 1104 1129 4153 1129 1103 4154 1103 1104 4155 1104 1130 4156 1130 1129 4157 1129 1105 4158 1105 1130 4159 1130 1104 4160 1104 1105 4161 1105 1131 4162 1131 1130 4163 1130 1105 4164 1105 1132 4165 1132 1131 4166 1131 1106 4167 1106 1132 4168 1132 1105 4169 1105 1107 4170 1107 1132 4171 1132 1106 4172 1106 1107 4173 1107 1133 4174 1133 1132 4175 1132 1090 4176 1090 1133 4177 1133 1107 4178 1107 1090 4179 1090 1134 4180 1134 1133 4181 1133 1108 4182 1108 1134 4183 1134 1090 4184 1090 1087 4185 1087 1134 4186 1134 1108 4187 1108 1087 4188 1087 1135 4189 1135 1134 4190 1134 1087 4191 1087 1119 4192 1119 1135 4193 1135 1136 4194 1136 1089 4195 1089 1122 4196 1122 1136 4197 1136 1109 4198 1109 1089 4199 1089 1136 4200 1136 1110 4201 1110 1109 4202 1109 1137 4203 1137 1110 4204 1110 1136 4205 1136 1138 4206 1138 1110 4207 1110 1137 4208 1137 1138 4209 1138 1111 4210 1111 1110 4211 1110 1139 4212 1139 1111 4213 1111 1138 4214 1138 1139 4215 1139 1112 4216 1112 1111 4217 1111 1139 4218 1139 1113 4219 1113 1112 4220 1112 1139 4221 1139 1114 4222 1114 1113 4223 1113 1139 4224 1139 1115 4225 1115 1114 4226 1114 1140 4227 1140 1115 4228 1115 1139 4229 1139 1140 4230 1140 1116 4231 1116 1115 4232 1115 1141 4233 1141 1116 4234 1116 1140 4235 1140 1142 4236 1142 1116 4237 1116 1141 4238 1141 1142 4239 1142 1117 4240 1117 1116 4241 1116 1142 4242 1142 1118 4243 1118 1117 4244 1117 1119 4245 1119 1118 4246 1118 1142 4247 1142 1121 4248 1121 1143 4249 1143 1120 4250 1120 1143 4251 1143 1121 4252 1121 1123 4253 1123 1120 4254 1120 1144 4255 1144 1122 4256 1122 1144 4257 1144 1120 4258 1120 1143 4259 1143 1122 4260 1122 1145 4261 1145 1136 4262 1136 1145 4263 1145 1122 4264 1122 1144 4265 1144 1136 4266 1136 1146 4267 1146 1137 4268 1137 1146 4269 1146 1136 4270 1136 1145 4271 1145 1137 4272 1137 1147 4273 1147 1138 4274 1138 1147 4275 1147 1137 4276 1137 1146 4277 1146 1138 4278 1138 1140 4279 1140 1139 4280 1139 1140 4281 1140 1138 4282 1138 1147 4283 1147 1123 4284 1123 1148 4285 1148 1143 4286 1143 1148 4287 1148 1123 4288 1123 1124 4289 1124 1143 4290 1143 1149 4291 1149 1144 4292 1144 1149 4293 1149 1143 4294 1143 1148 4295 1148 1144 4296 1144 1150 4297 1150 1145 4298 1145 1150 4299 1150 1144 4300 1144 1149 4301 1149 1124 4302 1124 1151 4303 1151 1148 4304 1148 1151 4305 1151 1124 4306 1124 1125 4307 1125 1148 4308 1148 1152 4309 1152 1149 4310 1149 1152 4311 1152 1148 4312 1148 1151 4313 1151 1149 4314 1149 1153 4315 1153 1150 4316 1150 1153 4317 1153 1149 4318 1149 1152 4319 1152 1145 4320 1145 1154 4321 1154 1146 4322 1146 1154 4323 1154 1145 4324 1145 1150 4325 1150 1146 4326 1146 1155 4327 1155 1147 4328 1147 1155 4329 1155 1146 4330 1146 1154 4331 1154 1147 4332 1147 1141 4333 1141 1140 4334 1140 1141 4335 1141 1147 4336 1147 1155 4337 1155 1150 4338 1150 1156 4339 1156 1154 4340 1154 1156 4341 1156 1150 4342 1150 1153 4343 1153 1154 4344 1154 1157 4345 1157 1155 4346 1155 1157 4347 1157 1154 4348 1154 1156 4349 1156 1155 4350 1155 1142 4351 1142 1141 4352 1141 1142 4353 1142 1155 4354 1155 1157 4355 1157 1125 4356 1125 1158 4357 1158 1151 4358 1151 1158 4359 1158 1125 4360 1125 1126 4361 1126 1151 4362 1151 1159 4363 1159 1152 4364 1152 1159 4365 1159 1151 4366 1151 1158 4367 1158 1152 4368 1152 1160 4369 1160 1153 4370 1153 1160 4371 1160 1152 4372 1152 1159 4373 1159 1126 4374 1126 1161 4375 1161 1158 4376 1158 1161 4377 1161 1126 4378 1126 1127 4379 1127 1158 4380 1158 1162 4381 1162 1159 4382 1159 1162 4383 1162 1158 4384 1158 1161 4385 1161 1159 4386 1159 1163 4387 1163 1160 4388 1160 1163 4389 1163 1159 4390 1159 1162 4391 1162 1153 4392 1153 1164 4393 1164 1156 4394 1156 1164 4395 1164 1153 4396 1153 1160 4397 1160 1156 4398 1156 1165 4399 1165 1157 4400 1157 1165 4401 1165 1156 4402 1156 1164 4403 1164 1157 4404 1157 1119 4405 1119 1142 4406 1142 1119 4407 1119 1157 4408 1157 1165 4409 1165 1160 4410 1160 1166 4411 1166 1164 4412 1164 1166 4413 1166 1160 4414 1160 1163 4415 1163 1164 4416 1164 1167 4417 1167 1165 4418 1165 1167 4419 1167 1164 4420 1164 1166 4421 1166 1165 4422 1165 1135 4423 1135 1119 4424 1119 1135 4425 1135 1165 4426 1165 1167 4427 1167 1127 4428 1127 1129 4429 1129 1161 4430 1161 1129 4431 1129 1127 4432 1127 1128 4433 1128 1161 4434 1161 1130 4435 1130 1162 4436 1162 1130 4437 1130 1161 4438 1161 1129 4439 1129 1162 4440 1162 1131 4441 1131 1163 4442 1163 1131 4443 1131 1162 4444 1162 1130 4445 1130 1163 4446 1163 1132 4447 1132 1166 4448 1166 1132 4449 1132 1163 4450 1163 1131 4451 1131 1166 4452 1166 1133 4453 1133 1167 4454 1167 1133 4455 1133 1166 4456 1166 1132 4457 1132 1167 4458 1167 1134 4459 1134 1135 4460 1135 1134 4461 1134 1167 4462 1167 1133 4463 1133 1184 4464 1184 1168 4465 1168 1169 4466 1169 1173 4467 1173 1170 4468 1170 1171 4469 1171 1173 4470 1173 1172 4471 1172 1170 4472 1170 1175 4473 1175 1172 4474 1172 1173 4475 1173 1175 4476 1175 1174 4477 1174 1172 4478 1172 1177 4479 1177 1174 4480 1174 1175 4481 1175 1177 4482 1177 1176 4483 1176 1174 4484 1174 1179 4485 1179 1176 4486 1176 1177 4487 1177 1179 4488 1179 1178 4489 1178 1176 4490 1176 1181 4491 1181 1178 4492 1178 1179 4493 1179 1181 4494 1181 1180 4495 1180 1178 4496 1178 1183 4497 1183 1180 4498 1180 1181 4499 1181 1183 4500 1183 1182 4501 1182 1180 4502 1180 1185 4503 1185 1182 4504 1182 1183 4505 1183 1185 4506 1185 1184 4507 1184 1182 4508 1182 1168 4509 1168 1184 4510 1184 1185 4511 1185 1202 4512 1202 1186 4513 1186 1187 4514 1187 1191 4515 1191 1188 4516 1188 1189 4517 1189 1191 4518 1191 1190 4519 1190 1188 4520 1188 1194 4521 1194 1190 4522 1190 1191 4523 1191 1194 4524 1194 1192 4525 1192 1190 4526 1190 1194 4527 1194 1193 4528 1193 1192 4529 1192 1195 4530 1195 1193 4531 1193 1194 4532 1194 1198 4533 1198 1193 4534 1193 1195 4535 1195 1198 4536 1198 1196 4537 1196 1193 4538 1193 1198 4539 1198 1197 4540 1197 1196 4541 1196 1200 4542 1200 1197 4543 1197 1198 4544 1198 1200 4545 1200 1199 4546 1199 1197 4547 1197 1201 4548 1201 1199 4549 1199 1200 4550 1200 1203 4551 1203 1199 4552 1199 1201 4553 1201 1203 4554 1203 1202 4555 1202 1199 4556 1199 1186 4557 1186 1202 4558 1202 1203 4559 1203

+
+
+ + + + +2.500000 0.000000 1.500000 +2.500000 0.000000 0.000000 +-2.458263 0.454908 0.000000 +-2.500000 0.000000 0.000000 +-2.500000 0.000000 1.500000 +-2.458263 0.454908 1.500000 +-2.403497 0.687896 0.000000 +-2.403497 0.687896 1.500000 +-2.324471 0.920237 0.000000 +-2.324471 0.920237 1.500000 +-2.220710 1.148237 0.000000 +-2.220710 1.148237 1.500000 +-2.092489 1.368024 0.000000 +-2.092489 1.368024 1.500000 +-1.940883 1.575745 0.000000 +-1.940883 1.575745 1.500000 +-1.767767 1.767767 0.000000 +-1.767767 1.767767 1.500000 +-1.575745 1.940883 0.000000 +-1.575745 1.940883 1.500000 +-1.368024 2.092489 0.000000 +-1.368024 2.092489 1.500000 +-1.148237 2.220710 0.000000 +-1.148237 2.220710 1.500000 +-0.920237 2.324471 0.000000 +-0.920237 2.324471 1.500000 +-0.687896 2.403497 0.000000 +-0.687896 2.403497 1.500000 +-0.454908 2.458263 0.000000 +-0.454908 2.458263 1.500000 +0.000000 2.500000 0.000000 +0.000000 2.500000 1.500000 +0.454908 2.458263 0.000000 +0.454908 2.458263 1.500000 +0.687896 2.403497 0.000000 +0.687896 2.403497 1.500000 +0.920237 2.324471 0.000000 +0.920237 2.324471 1.500000 +1.148237 2.220710 0.000000 +1.148237 2.220710 1.500000 +1.368024 2.092489 0.000000 +1.368024 2.092489 1.500000 +1.575745 1.940883 0.000000 +1.575745 1.940883 1.500000 +1.767767 1.767767 0.000000 +1.767767 1.767767 1.500000 +1.940883 1.575745 0.000000 +1.940883 1.575745 1.500000 +2.092489 1.368024 0.000000 +2.092489 1.368024 1.500000 +2.220710 1.148237 0.000000 +2.220710 1.148237 1.500000 +2.324471 0.920237 0.000000 +2.324471 0.920237 1.500000 +2.403497 0.687896 0.000000 +2.403497 0.687896 1.500000 +2.458263 0.454908 0.000000 +2.458263 0.454908 1.500000 +2.500000 0.000000 0.000000 +2.500000 0.000000 1.500000 +-2.500000 0.000000 1.500000 +-2.500000 0.000000 0.000000 +-2.458263 -0.454908 1.500000 +-2.458263 -0.454908 0.000000 +-2.403497 -0.687896 1.500000 +-2.403497 -0.687896 0.000000 +-2.324471 -0.920237 1.500000 +-2.324471 -0.920237 0.000000 +-2.220710 -1.148237 1.500000 +-2.220710 -1.148237 0.000000 +-2.092489 -1.368024 1.500000 +-2.092489 -1.368024 0.000000 +-1.940883 -1.575745 1.500000 +-1.940883 -1.575745 0.000000 +-1.767767 -1.767767 1.500000 +-1.767767 -1.767767 0.000000 +-1.575745 -1.940883 1.500000 +-1.575745 -1.940883 0.000000 +-1.368024 -2.092489 1.500000 +-1.368024 -2.092489 0.000000 +-1.148237 -2.220710 1.500000 +-1.148237 -2.220710 0.000000 +-0.920237 -2.324471 1.500000 +-0.920237 -2.324471 0.000000 +-0.687896 -2.403497 1.500000 +-0.687896 -2.403497 0.000000 +-0.454908 -2.458263 1.500000 +-0.454908 -2.458263 0.000000 +0.000000 -2.500000 1.500000 +0.000000 -2.500000 0.000000 +0.454908 -2.458263 1.500000 +0.454908 -2.458263 0.000000 +0.687896 -2.403497 1.500000 +0.687896 -2.403497 0.000000 +0.920237 -2.324471 1.500000 +0.920237 -2.324471 0.000000 +1.148237 -2.220710 1.500000 +1.148237 -2.220710 0.000000 +1.368024 -2.092489 1.500000 +1.368024 -2.092489 0.000000 +1.575745 -1.940883 1.500000 +1.575745 -1.940883 0.000000 +1.767767 -1.767767 1.500000 +1.767767 -1.767767 0.000000 +1.940883 -1.575745 1.500000 +1.940883 -1.575745 0.000000 +2.092489 -1.368024 1.500000 +2.092489 -1.368024 0.000000 +2.220710 -1.148237 1.500000 +2.220710 -1.148237 0.000000 +2.324471 -0.920237 1.500000 +2.324471 -0.920237 0.000000 +2.403497 -0.687896 1.500000 +2.403497 -0.687896 0.000000 +2.458263 -0.454908 1.500000 +2.458263 -0.454908 0.000000 +1.575745 1.940883 1.500000 +1.368024 2.092489 1.500000 +0.454908 2.458263 1.500000 +0.000000 2.500000 1.500000 +-0.454908 2.458263 1.500000 +-0.687896 2.403497 1.500000 +-0.920237 2.324471 1.500000 +-1.148237 2.220710 1.500000 +-1.368024 2.092489 1.500000 +-1.575745 1.940883 1.500000 +-1.767767 1.767767 1.500000 +-1.940883 1.575745 1.500000 +-2.092489 1.368024 1.500000 +-2.220710 1.148237 1.500000 +-2.324471 0.920237 1.500000 +0.687896 2.403497 1.500000 +-2.403497 0.687896 1.500000 +-2.458263 0.454908 1.500000 +-2.500000 0.000000 1.500000 +0.920237 2.324471 1.500000 +-2.458263 -0.454908 1.500000 +-2.403497 -0.687896 1.500000 +-2.324471 -0.920237 1.500000 +-2.220710 -1.148237 1.500000 +-2.092489 -1.368024 1.500000 +-1.940883 -1.575745 1.500000 +-1.767767 -1.767767 1.500000 +-1.575745 -1.940883 1.500000 +-1.368024 -2.092489 1.500000 +1.148237 2.220710 1.500000 +-1.148237 -2.220710 1.500000 +-0.920237 -2.324471 1.500000 +-0.687896 -2.403497 1.500000 +-0.454908 -2.458263 1.500000 +0.000000 -2.500000 1.500000 +0.454908 -2.458263 1.500000 +0.687896 -2.403497 1.500000 +0.920237 -2.324471 1.500000 +1.148237 -2.220710 1.500000 +1.368024 -2.092489 1.500000 +1.575745 -1.940883 1.500000 +1.767767 -1.767767 1.500000 +1.940883 -1.575745 1.500000 +2.092489 -1.368024 1.500000 +2.220710 -1.148237 1.500000 +2.324471 -0.920237 1.500000 +2.403497 -0.687896 1.500000 +2.458263 -0.454908 1.500000 +2.500000 0.000000 1.500000 +2.458263 0.454908 1.500000 +2.403497 0.687896 1.500000 +2.324471 0.920237 1.500000 +2.220710 1.148237 1.500000 +2.092489 1.368024 1.500000 +1.940883 1.575745 1.500000 +1.767767 1.767767 1.500000 +1.575745 -1.940883 0.000000 +1.368024 -2.092489 0.000000 +0.454908 -2.458263 0.000000 +0.000000 -2.500000 0.000000 +-0.454908 -2.458263 0.000000 +-0.687896 -2.403497 0.000000 +-0.920237 -2.324471 0.000000 +-1.148237 -2.220710 0.000000 +-1.368024 -2.092489 0.000000 +-1.575745 -1.940883 0.000000 +-1.767767 -1.767767 0.000000 +-1.940883 -1.575745 0.000000 +-2.092489 -1.368024 0.000000 +-2.220710 -1.148237 0.000000 +-2.324471 -0.920237 0.000000 +0.687896 -2.403497 0.000000 +-2.403497 -0.687896 0.000000 +-2.458263 -0.454908 0.000000 +-2.500000 0.000000 0.000000 +0.920237 -2.324471 0.000000 +-2.458263 0.454908 0.000000 +-2.403497 0.687896 0.000000 +-2.324471 0.920237 0.000000 +-2.220710 1.148237 0.000000 +-2.092489 1.368024 0.000000 +-1.940883 1.575745 0.000000 +-1.767767 1.767767 0.000000 +-1.575745 1.940883 0.000000 +-1.368024 2.092489 0.000000 +1.148237 -2.220710 0.000000 +-1.148237 2.220710 0.000000 +-0.920237 2.324471 0.000000 +-0.687896 2.403497 0.000000 +-0.454908 2.458263 0.000000 +0.000000 2.500000 0.000000 +0.454908 2.458263 0.000000 +0.687896 2.403497 0.000000 +0.920237 2.324471 0.000000 +1.148237 2.220710 0.000000 +1.368024 2.092489 0.000000 +1.575745 1.940883 0.000000 +1.767767 1.767767 0.000000 +1.940883 1.575745 0.000000 +2.092489 1.368024 0.000000 +2.220710 1.148237 0.000000 +2.324471 0.920237 0.000000 +2.403497 0.687896 0.000000 +2.458263 0.454908 0.000000 +2.500000 0.000000 0.000000 +2.458263 -0.454908 0.000000 +2.403497 -0.687896 0.000000 +2.324471 -0.920237 0.000000 +2.220710 -1.148237 0.000000 +2.092489 -1.368024 0.000000 +1.940883 -1.575745 0.000000 +1.767767 -1.767767 0.000000 + + + + + + + + + + + +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.961399 0.275158 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.961399 0.275158 0.000000 +-0.961399 0.275158 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.961399 0.275158 0.000000 +-0.961399 0.275158 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.961399 0.275158 0.000000 +-0.888284 0.459295 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.888284 0.459295 0.000000 +-0.888284 0.459295 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.888284 0.459295 0.000000 +-0.888284 0.459295 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.888284 0.459295 0.000000 +-0.776353 0.630298 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.776353 0.630298 0.000000 +-0.776353 0.630298 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.776353 0.630298 0.000000 +-0.776353 0.630298 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.776353 0.630298 0.000000 +-0.630298 0.776353 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.630298 0.776353 0.000000 +-0.630298 0.776353 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.630298 0.776353 0.000000 +-0.630298 0.776353 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.630298 0.776353 0.000000 +-0.459295 0.888284 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.459295 0.888284 0.000000 +-0.459295 0.888284 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.459295 0.888284 0.000000 +-0.459295 0.888284 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.459295 0.888284 0.000000 +-0.275158 0.961399 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.275158 0.961399 0.000000 +-0.275158 0.961399 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.275158 0.961399 0.000000 +-0.275158 0.961399 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.275158 0.961399 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.275158 0.961399 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.275158 0.961399 0.000000 +0.275158 0.961399 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.275158 0.961399 0.000000 +0.275158 0.961399 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.275158 0.961399 0.000000 +0.459295 0.888284 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.459295 0.888284 0.000000 +0.459295 0.888284 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.459295 0.888284 0.000000 +0.459295 0.888284 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.459295 0.888284 0.000000 +0.630298 0.776353 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.630298 0.776353 0.000000 +0.630298 0.776353 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.630298 0.776353 0.000000 +0.630298 0.776353 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.630298 0.776353 0.000000 +0.776353 0.630298 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.776353 0.630298 0.000000 +0.776353 0.630298 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.776353 0.630298 0.000000 +0.776353 0.630298 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.776353 0.630298 0.000000 +0.888284 0.459295 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.888284 0.459295 0.000000 +0.888284 0.459295 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.888284 0.459295 0.000000 +0.888284 0.459295 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.888284 0.459295 0.000000 +0.961399 0.275158 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.961399 0.275158 0.000000 +0.961399 0.275158 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.961399 0.275158 0.000000 +0.961399 0.275158 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.961399 0.275158 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.961399 -0.275158 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.961399 -0.275158 0.000000 +-0.961399 -0.275158 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.961399 -0.275158 0.000000 +-0.961399 -0.275158 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.961399 -0.275158 0.000000 +-0.888284 -0.459295 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.888284 -0.459295 0.000000 +-0.888284 -0.459295 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.888284 -0.459295 0.000000 +-0.888284 -0.459295 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.888284 -0.459295 0.000000 +-0.776353 -0.630298 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.776353 -0.630298 0.000000 +-0.776353 -0.630298 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.776353 -0.630298 0.000000 +-0.776353 -0.630298 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.776353 -0.630298 0.000000 +-0.630298 -0.776353 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.630298 -0.776353 0.000000 +-0.630298 -0.776353 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.630298 -0.776353 0.000000 +-0.630298 -0.776353 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.630298 -0.776353 0.000000 +-0.459295 -0.888284 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.459295 -0.888284 0.000000 +-0.459295 -0.888284 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.459295 -0.888284 0.000000 +-0.459295 -0.888284 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.459295 -0.888284 0.000000 +-0.275158 -0.961399 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.275158 -0.961399 0.000000 +-0.275158 -0.961399 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.275158 -0.961399 0.000000 +-0.275158 -0.961399 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.275158 -0.961399 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.275158 -0.961399 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.275158 -0.961399 0.000000 +0.275158 -0.961399 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.275158 -0.961399 0.000000 +0.275158 -0.961399 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.275158 -0.961399 0.000000 +0.459295 -0.888284 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.459295 -0.888284 0.000000 +0.459295 -0.888284 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.459295 -0.888284 0.000000 +0.459295 -0.888284 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.459295 -0.888284 0.000000 +0.630298 -0.776353 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.630298 -0.776353 0.000000 +0.630298 -0.776353 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.630298 -0.776353 0.000000 +0.630298 -0.776353 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.630298 -0.776353 0.000000 +0.776353 -0.630298 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.776353 -0.630298 0.000000 +0.776353 -0.630298 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.776353 -0.630298 0.000000 +0.776353 -0.630298 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.776353 -0.630298 0.000000 +0.888284 -0.459295 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.888284 -0.459295 0.000000 +0.888284 -0.459295 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.888284 -0.459295 0.000000 +0.888284 -0.459295 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.888284 -0.459295 0.000000 +0.961399 -0.275158 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.961399 -0.275158 0.000000 +0.961399 -0.275158 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.961399 -0.275158 0.000000 +0.961399 -0.275158 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.961399 -0.275158 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 + + + + + + + + + + + +0.368660 0.834280 +0.368660 0.834256 +0.357419 0.835254 +0.357325 0.834256 +0.357325 0.834280 +0.357419 0.835278 +0.357544 0.835765 +0.357544 0.835789 +0.357723 0.836275 +0.357723 0.836299 +0.357958 0.836775 +0.357958 0.836800 +0.358249 0.837258 +0.358249 0.837282 +0.358592 0.837713 +0.358592 0.837738 +0.358985 0.838135 +0.358985 0.838159 +0.359420 0.838515 +0.359420 0.838539 +0.359891 0.838847 +0.359891 0.838872 +0.360389 0.839129 +0.360389 0.839153 +0.360906 0.839356 +0.360906 0.839381 +0.361433 0.839530 +0.361433 0.839554 +0.361961 0.839650 +0.361961 0.839674 +0.362993 0.839742 +0.362993 0.839766 +0.364024 0.839650 +0.364024 0.839674 +0.364552 0.839530 +0.364552 0.839554 +0.365079 0.839356 +0.365079 0.839381 +0.365596 0.839129 +0.365596 0.839153 +0.366094 0.838847 +0.366094 0.838872 +0.366565 0.838515 +0.366565 0.838539 +0.367000 0.838135 +0.367000 0.838159 +0.367393 0.837713 +0.367393 0.837738 +0.367736 0.837258 +0.367736 0.837282 +0.368027 0.836775 +0.368027 0.836800 +0.368262 0.836275 +0.368262 0.836299 +0.368441 0.835765 +0.368441 0.835789 +0.368566 0.835254 +0.368566 0.835278 +0.368660 0.834256 +0.368660 0.834280 +0.357325 0.834280 +0.357325 0.834256 +0.357419 0.833282 +0.357419 0.833257 +0.357544 0.832770 +0.357544 0.832746 +0.357723 0.832260 +0.357723 0.832236 +0.357958 0.831760 +0.357958 0.831736 +0.358249 0.831278 +0.358249 0.831254 +0.358592 0.830822 +0.358592 0.830798 +0.358985 0.830401 +0.358985 0.830376 +0.359420 0.830021 +0.359420 0.829996 +0.359891 0.829688 +0.359891 0.829664 +0.360389 0.829407 +0.360389 0.829382 +0.360906 0.829179 +0.360906 0.829155 +0.361433 0.829005 +0.361433 0.828981 +0.361961 0.828885 +0.361961 0.828861 +0.362993 0.828794 +0.362993 0.828770 +0.364024 0.828885 +0.364024 0.828861 +0.364552 0.829005 +0.364552 0.828981 +0.365079 0.829179 +0.365079 0.829155 +0.365596 0.829407 +0.365596 0.829382 +0.366094 0.829688 +0.366094 0.829664 +0.366565 0.830021 +0.366565 0.829996 +0.367000 0.830401 +0.367000 0.830376 +0.367393 0.830822 +0.367393 0.830798 +0.367736 0.831278 +0.367736 0.831254 +0.368027 0.831760 +0.368027 0.831736 +0.368262 0.832260 +0.368262 0.832236 +0.368441 0.832770 +0.368441 0.832746 +0.368566 0.833282 +0.368566 0.833257 +0.366565 0.838539 +0.366094 0.838872 +0.364024 0.839674 +0.362993 0.839766 +0.361961 0.839674 +0.361433 0.839554 +0.360906 0.839381 +0.360389 0.839153 +0.359891 0.838872 +0.359420 0.838539 +0.358985 0.838159 +0.358592 0.837738 +0.358249 0.837282 +0.357958 0.836800 +0.357723 0.836299 +0.364552 0.839554 +0.357544 0.835789 +0.357419 0.835278 +0.357325 0.834280 +0.365079 0.839381 +0.357419 0.833282 +0.357544 0.832770 +0.357723 0.832260 +0.357958 0.831760 +0.358249 0.831278 +0.358592 0.830822 +0.358985 0.830401 +0.359420 0.830021 +0.359891 0.829688 +0.365596 0.839153 +0.360389 0.829407 +0.360906 0.829179 +0.361433 0.829005 +0.361961 0.828885 +0.362993 0.828794 +0.364024 0.828885 +0.364552 0.829005 +0.365079 0.829179 +0.365596 0.829407 +0.366094 0.829688 +0.366565 0.830021 +0.367000 0.830401 +0.367393 0.830822 +0.367736 0.831278 +0.368027 0.831760 +0.368262 0.832260 +0.368441 0.832770 +0.368566 0.833282 +0.368660 0.834280 +0.368566 0.835278 +0.368441 0.835789 +0.368262 0.836299 +0.368027 0.836800 +0.367736 0.837282 +0.367393 0.837738 +0.367000 0.838159 +0.366565 0.829996 +0.366094 0.829664 +0.364024 0.828861 +0.362993 0.828770 +0.361961 0.828861 +0.361433 0.828981 +0.360906 0.829155 +0.360389 0.829382 +0.359891 0.829664 +0.359420 0.829996 +0.358985 0.830376 +0.358592 0.830798 +0.358249 0.831254 +0.357958 0.831736 +0.357723 0.832236 +0.364552 0.828981 +0.357544 0.832746 +0.357419 0.833257 +0.357325 0.834256 +0.365079 0.829155 +0.357419 0.835254 +0.357544 0.835765 +0.357723 0.836275 +0.357958 0.836775 +0.358249 0.837258 +0.358592 0.837713 +0.358985 0.838135 +0.359420 0.838515 +0.359891 0.838847 +0.365596 0.829382 +0.360389 0.839129 +0.360906 0.839356 +0.361433 0.839530 +0.361961 0.839650 +0.362993 0.839742 +0.364024 0.839650 +0.364552 0.839530 +0.365079 0.839356 +0.365596 0.839129 +0.366094 0.838847 +0.366565 0.838515 +0.367000 0.838135 +0.367393 0.837713 +0.367736 0.837258 +0.368027 0.836775 +0.368262 0.836275 +0.368441 0.835765 +0.368566 0.835254 +0.368660 0.834256 +0.368566 0.833257 +0.368441 0.832746 +0.368262 0.832236 +0.368027 0.831736 +0.367736 0.831254 +0.367393 0.830798 +0.367000 0.830376 + + + + + + + + + + + +

56 0 56 0 1 0 1 2 1 4 3 4 2 4 2 3 5 3 5 6 5 2 7 2 4 8 4 7 9 7 2 10 2 5 11 5 7 12 7 6 13 6 2 14 2 9 15 9 6 16 6 7 17 7 9 18 9 8 19 8 6 20 6 11 21 11 8 22 8 9 23 9 11 24 11 10 25 10 8 26 8 13 27 13 10 28 10 11 29 11 13 30 13 12 31 12 10 32 10 15 33 15 12 34 12 13 35 13 15 36 15 14 37 14 12 38 12 17 39 17 14 40 14 15 41 15 17 42 17 16 43 16 14 44 14 19 45 19 16 46 16 17 47 17 19 48 19 18 49 18 16 50 16 21 51 21 18 52 18 19 53 19 21 54 21 20 55 20 18 56 18 23 57 23 20 58 20 21 59 21 23 60 23 22 61 22 20 62 20 25 63 25 22 64 22 23 65 23 25 66 25 24 67 24 22 68 22 27 69 27 24 70 24 25 71 25 27 72 27 26 73 26 24 74 24 29 75 29 26 76 26 27 77 27 29 78 29 28 79 28 26 80 26 31 81 31 28 82 28 29 83 29 31 84 31 30 85 30 28 86 28 33 87 33 30 88 30 31 89 31 33 90 33 32 91 32 30 92 30 35 93 35 32 94 32 33 95 33 35 96 35 34 97 34 32 98 32 37 99 37 34 100 34 35 101 35 37 102 37 36 103 36 34 104 34 39 105 39 36 106 36 37 107 37 39 108 39 38 109 38 36 110 36 41 111 41 38 112 38 39 113 39 41 114 41 40 115 40 38 116 38 43 117 43 40 118 40 41 119 41 43 120 43 42 121 42 40 122 40 45 123 45 42 124 42 43 125 43 45 126 45 44 127 44 42 128 42 47 129 47 44 130 44 45 131 45 47 132 47 46 133 46 44 134 44 49 135 49 46 136 46 47 137 47 49 138 49 48 139 48 46 140 46 51 141 51 48 142 48 49 143 49 51 144 51 50 145 50 48 146 48 53 147 53 50 148 50 51 149 51 53 150 53 52 151 52 50 152 50 55 153 55 52 154 52 53 155 53 55 156 55 54 157 54 52 158 52 57 159 57 54 160 54 55 161 55 57 162 57 56 163 56 54 164 54 0 165 0 56 166 56 57 167 57 114 168 114 58 169 58 59 170 59 63 171 63 60 172 60 61 173 61 63 174 63 62 175 62 60 176 60 65 177 65 62 178 62 63 179 63 65 180 65 64 181 64 62 182 62 67 183 67 64 184 64 65 185 65 67 186 67 66 187 66 64 188 64 69 189 69 66 190 66 67 191 67 69 192 69 68 193 68 66 194 66 71 195 71 68 196 68 69 197 69 71 198 71 70 199 70 68 200 68 73 201 73 70 202 70 71 203 71 73 204 73 72 205 72 70 206 70 75 207 75 72 208 72 73 209 73 75 210 75 74 211 74 72 212 72 77 213 77 74 214 74 75 215 75 77 216 77 76 217 76 74 218 74 79 219 79 76 220 76 77 221 77 79 222 79 78 223 78 76 224 76 81 225 81 78 226 78 79 227 79 81 228 81 80 229 80 78 230 78 83 231 83 80 232 80 81 233 81 83 234 83 82 235 82 80 236 80 85 237 85 82 238 82 83 239 83 85 240 85 84 241 84 82 242 82 87 243 87 84 244 84 85 245 85 87 246 87 86 247 86 84 248 84 89 249 89 86 250 86 87 251 87 89 252 89 88 253 88 86 254 86 91 255 91 88 256 88 89 257 89 91 258 91 90 259 90 88 260 88 93 261 93 90 262 90 91 263 91 93 264 93 92 265 92 90 266 90 95 267 95 92 268 92 93 269 93 95 270 95 94 271 94 92 272 92 97 273 97 94 274 94 95 275 95 97 276 97 96 277 96 94 278 94 99 279 99 96 280 96 97 281 97 99 282 99 98 283 98 96 284 96 101 285 101 98 286 98 99 287 99 101 288 101 100 289 100 98 290 98 103 291 103 100 292 100 101 293 101 103 294 103 102 295 102 100 296 100 105 297 105 102 298 102 103 299 103 105 300 105 104 301 104 102 302 102 107 303 107 104 304 104 105 305 105 107 306 107 106 307 106 104 308 104 109 309 109 106 310 106 107 311 107 109 312 109 108 313 108 106 314 106 111 315 111 108 316 108 109 317 109 111 318 111 110 319 110 108 320 108 113 321 113 110 322 110 111 323 111 113 324 113 112 325 112 110 326 110 115 327 115 112 328 112 113 329 113 115 330 115 114 331 114 112 332 112 58 333 58 114 334 114 115 335 115 145 336 145 116 337 116 117 338 117 120 339 120 118 340 118 119 341 119 121 342 121 118 343 118 120 344 120 122 345 122 118 346 118 121 347 121 123 348 123 118 349 118 122 350 122 124 351 124 118 352 118 123 353 123 125 354 125 118 355 118 124 356 124 126 357 126 118 358 118 125 359 125 127 360 127 118 361 118 126 362 126 128 363 128 118 364 118 127 365 127 129 366 129 118 367 118 128 368 128 130 369 130 118 370 118 129 371 129 132 372 132 118 373 118 130 374 130 132 375 132 131 376 131 118 377 118 133 378 133 131 379 131 132 380 132 134 381 134 131 382 131 133 383 133 136 384 136 131 385 131 134 386 134 136 387 136 135 388 135 131 389 131 137 390 137 135 391 135 136 392 136 138 393 138 135 394 135 137 395 137 139 396 139 135 397 135 138 398 138 140 399 140 135 400 135 139 401 139 141 402 141 135 403 135 140 404 140 142 405 142 135 406 135 141 407 141 143 408 143 135 409 135 142 410 142 144 411 144 135 412 135 143 413 143 146 414 146 135 415 135 144 416 144 146 417 146 145 418 145 135 419 135 147 420 147 145 421 145 146 422 146 148 423 148 145 424 145 147 425 147 149 426 149 145 427 145 148 428 148 150 429 150 145 430 145 149 431 149 151 432 151 145 433 145 150 434 150 152 435 152 145 436 145 151 437 151 153 438 153 145 439 145 152 440 152 154 441 154 145 442 145 153 443 153 155 444 155 145 445 145 154 446 154 156 447 156 145 448 145 155 449 155 157 450 157 145 451 145 156 452 156 158 453 158 145 454 145 157 455 157 159 456 159 145 457 145 158 458 158 160 459 160 145 460 145 159 461 159 161 462 161 145 463 145 160 464 160 162 465 162 145 466 145 161 467 161 163 468 163 145 469 145 162 470 162 164 471 164 145 472 145 163 473 163 165 474 165 145 475 145 164 476 164 166 477 166 145 478 145 165 479 165 167 480 167 145 481 145 166 482 166 168 483 168 145 484 145 167 485 167 169 486 169 145 487 145 168 488 168 170 489 170 145 490 145 169 491 169 171 492 171 145 493 145 170 494 170 116 495 116 145 496 145 171 497 171 201 498 201 172 499 172 173 500 173 176 501 176 174 502 174 175 503 175 177 504 177 174 505 174 176 506 176 178 507 178 174 508 174 177 509 177 179 510 179 174 511 174 178 512 178 180 513 180 174 514 174 179 515 179 181 516 181 174 517 174 180 518 180 182 519 182 174 520 174 181 521 181 183 522 183 174 523 174 182 524 182 184 525 184 174 526 174 183 527 183 185 528 185 174 529 174 184 530 184 186 531 186 174 532 174 185 533 185 188 534 188 174 535 174 186 536 186 188 537 188 187 538 187 174 539 174 189 540 189 187 541 187 188 542 188 190 543 190 187 544 187 189 545 189 192 546 192 187 547 187 190 548 190 192 549 192 191 550 191 187 551 187 193 552 193 191 553 191 192 554 192 194 555 194 191 556 191 193 557 193 195 558 195 191 559 191 194 560 194 196 561 196 191 562 191 195 563 195 197 564 197 191 565 191 196 566 196 198 567 198 191 568 191 197 569 197 199 570 199 191 571 191 198 572 198 200 573 200 191 574 191 199 575 199 202 576 202 191 577 191 200 578 200 202 579 202 201 580 201 191 581 191 203 582 203 201 583 201 202 584 202 204 585 204 201 586 201 203 587 203 205 588 205 201 589 201 204 590 204 206 591 206 201 592 201 205 593 205 207 594 207 201 595 201 206 596 206 208 597 208 201 598 201 207 599 207 209 600 209 201 601 201 208 602 208 210 603 210 201 604 201 209 605 209 211 606 211 201 607 201 210 608 210 212 609 212 201 610 201 211 611 211 213 612 213 201 613 201 212 614 212 214 615 214 201 616 201 213 617 213 215 618 215 201 619 201 214 620 214 216 621 216 201 622 201 215 623 215 217 624 217 201 625 201 216 626 216 218 627 218 201 628 201 217 629 217 219 630 219 201 631 201 218 632 218 220 633 220 201 634 201 219 635 219 221 636 221 201 637 201 220 638 220 222 639 222 201 640 201 221 641 221 223 642 223 201 643 201 222 644 222 224 645 224 201 646 201 223 647 223 225 648 225 201 649 201 224 650 224 226 651 226 201 652 201 225 653 225 227 654 227 201 655 201 226 656 226 172 657 172 201 658 201 227 659 227

+
+
+ + + + +2.500000 0.000000 1.500000 +2.500000 0.000000 0.000000 +-2.458263 0.454908 0.000000 +-2.500000 0.000000 0.000000 +-2.500000 0.000000 1.500000 +-2.458263 0.454908 1.500000 +-2.403497 0.687896 0.000000 +-2.403497 0.687896 1.500000 +-2.324471 0.920237 0.000000 +-2.324471 0.920237 1.500000 +-2.220710 1.148237 0.000000 +-2.220710 1.148237 1.500000 +-2.092489 1.368024 0.000000 +-2.092489 1.368024 1.500000 +-1.940883 1.575745 0.000000 +-1.940883 1.575745 1.500000 +-1.767767 1.767767 0.000000 +-1.767767 1.767767 1.500000 +-1.575745 1.940883 0.000000 +-1.575745 1.940883 1.500000 +-1.368024 2.092489 0.000000 +-1.368024 2.092489 1.500000 +-1.148237 2.220710 0.000000 +-1.148237 2.220710 1.500000 +-0.920237 2.324471 0.000000 +-0.920237 2.324471 1.500000 +-0.687896 2.403497 0.000000 +-0.687896 2.403497 1.500000 +-0.454908 2.458263 0.000000 +-0.454908 2.458263 1.500000 +0.000000 2.500000 0.000000 +0.000000 2.500000 1.500000 +0.454908 2.458263 0.000000 +0.454908 2.458263 1.500000 +0.687896 2.403497 0.000000 +0.687896 2.403497 1.500000 +0.920237 2.324471 0.000000 +0.920237 2.324471 1.500000 +1.148237 2.220710 0.000000 +1.148237 2.220710 1.500000 +1.368024 2.092489 0.000000 +1.368024 2.092489 1.500000 +1.575745 1.940883 0.000000 +1.575745 1.940883 1.500000 +1.767767 1.767767 0.000000 +1.767767 1.767767 1.500000 +1.940883 1.575745 0.000000 +1.940883 1.575745 1.500000 +2.092489 1.368024 0.000000 +2.092489 1.368024 1.500000 +2.220710 1.148237 0.000000 +2.220710 1.148237 1.500000 +2.324471 0.920237 0.000000 +2.324471 0.920237 1.500000 +2.403497 0.687896 0.000000 +2.403497 0.687896 1.500000 +2.458263 0.454908 0.000000 +2.458263 0.454908 1.500000 +2.500000 0.000000 0.000000 +2.500000 0.000000 1.500000 +-2.500000 0.000000 1.500000 +-2.500000 0.000000 0.000000 +-2.458263 -0.454908 1.500000 +-2.458263 -0.454908 0.000000 +-2.403497 -0.687896 1.500000 +-2.403497 -0.687896 0.000000 +-2.324471 -0.920237 1.500000 +-2.324471 -0.920237 0.000000 +-2.220710 -1.148237 1.500000 +-2.220710 -1.148237 0.000000 +-2.092489 -1.368024 1.500000 +-2.092489 -1.368024 0.000000 +-1.940883 -1.575745 1.500000 +-1.940883 -1.575745 0.000000 +-1.767767 -1.767767 1.500000 +-1.767767 -1.767767 0.000000 +-1.575745 -1.940883 1.500000 +-1.575745 -1.940883 0.000000 +-1.368024 -2.092489 1.500000 +-1.368024 -2.092489 0.000000 +-1.148237 -2.220710 1.500000 +-1.148237 -2.220710 0.000000 +-0.920237 -2.324471 1.500000 +-0.920237 -2.324471 0.000000 +-0.687896 -2.403497 1.500000 +-0.687896 -2.403497 0.000000 +-0.454908 -2.458263 1.500000 +-0.454908 -2.458263 0.000000 +0.000000 -2.500000 1.500000 +0.000000 -2.500000 0.000000 +0.454908 -2.458263 1.500000 +0.454908 -2.458263 0.000000 +0.687896 -2.403497 1.500000 +0.687896 -2.403497 0.000000 +0.920237 -2.324471 1.500000 +0.920237 -2.324471 0.000000 +1.148237 -2.220710 1.500000 +1.148237 -2.220710 0.000000 +1.368024 -2.092489 1.500000 +1.368024 -2.092489 0.000000 +1.575745 -1.940883 1.500000 +1.575745 -1.940883 0.000000 +1.767767 -1.767767 1.500000 +1.767767 -1.767767 0.000000 +1.940883 -1.575745 1.500000 +1.940883 -1.575745 0.000000 +2.092489 -1.368024 1.500000 +2.092489 -1.368024 0.000000 +2.220710 -1.148237 1.500000 +2.220710 -1.148237 0.000000 +2.324471 -0.920237 1.500000 +2.324471 -0.920237 0.000000 +2.403497 -0.687896 1.500000 +2.403497 -0.687896 0.000000 +2.458263 -0.454908 1.500000 +2.458263 -0.454908 0.000000 +1.575745 1.940883 1.500000 +1.368024 2.092489 1.500000 +0.454908 2.458263 1.500000 +0.000000 2.500000 1.500000 +-0.454908 2.458263 1.500000 +-0.687896 2.403497 1.500000 +-0.920237 2.324471 1.500000 +-1.148237 2.220710 1.500000 +-1.368024 2.092489 1.500000 +-1.575745 1.940883 1.500000 +-1.767767 1.767767 1.500000 +-1.940883 1.575745 1.500000 +-2.092489 1.368024 1.500000 +-2.220710 1.148237 1.500000 +-2.324471 0.920237 1.500000 +0.687896 2.403497 1.500000 +-2.403497 0.687896 1.500000 +-2.458263 0.454908 1.500000 +-2.500000 0.000000 1.500000 +0.920237 2.324471 1.500000 +-2.458263 -0.454908 1.500000 +-2.403497 -0.687896 1.500000 +-2.324471 -0.920237 1.500000 +-2.220710 -1.148237 1.500000 +-2.092489 -1.368024 1.500000 +-1.940883 -1.575745 1.500000 +-1.767767 -1.767767 1.500000 +-1.575745 -1.940883 1.500000 +-1.368024 -2.092489 1.500000 +1.148237 2.220710 1.500000 +-1.148237 -2.220710 1.500000 +-0.920237 -2.324471 1.500000 +-0.687896 -2.403497 1.500000 +-0.454908 -2.458263 1.500000 +0.000000 -2.500000 1.500000 +0.454908 -2.458263 1.500000 +0.687896 -2.403497 1.500000 +0.920237 -2.324471 1.500000 +1.148237 -2.220710 1.500000 +1.368024 -2.092489 1.500000 +1.575745 -1.940883 1.500000 +1.767767 -1.767767 1.500000 +1.940883 -1.575745 1.500000 +2.092489 -1.368024 1.500000 +2.220710 -1.148237 1.500000 +2.324471 -0.920237 1.500000 +2.403497 -0.687896 1.500000 +2.458263 -0.454908 1.500000 +2.500000 0.000000 1.500000 +2.458263 0.454908 1.500000 +2.403497 0.687896 1.500000 +2.324471 0.920237 1.500000 +2.220710 1.148237 1.500000 +2.092489 1.368024 1.500000 +1.940883 1.575745 1.500000 +1.767767 1.767767 1.500000 +1.575745 -1.940883 0.000000 +1.368024 -2.092489 0.000000 +0.454908 -2.458263 0.000000 +0.000000 -2.500000 0.000000 +-0.454908 -2.458263 0.000000 +-0.687896 -2.403497 0.000000 +-0.920237 -2.324471 0.000000 +-1.148237 -2.220710 0.000000 +-1.368024 -2.092489 0.000000 +-1.575745 -1.940883 0.000000 +-1.767767 -1.767767 0.000000 +-1.940883 -1.575745 0.000000 +-2.092489 -1.368024 0.000000 +-2.220710 -1.148237 0.000000 +-2.324471 -0.920237 0.000000 +0.687896 -2.403497 0.000000 +-2.403497 -0.687896 0.000000 +-2.458263 -0.454908 0.000000 +-2.500000 0.000000 0.000000 +0.920237 -2.324471 0.000000 +-2.458263 0.454908 0.000000 +-2.403497 0.687896 0.000000 +-2.324471 0.920237 0.000000 +-2.220710 1.148237 0.000000 +-2.092489 1.368024 0.000000 +-1.940883 1.575745 0.000000 +-1.767767 1.767767 0.000000 +-1.575745 1.940883 0.000000 +-1.368024 2.092489 0.000000 +1.148237 -2.220710 0.000000 +-1.148237 2.220710 0.000000 +-0.920237 2.324471 0.000000 +-0.687896 2.403497 0.000000 +-0.454908 2.458263 0.000000 +0.000000 2.500000 0.000000 +0.454908 2.458263 0.000000 +0.687896 2.403497 0.000000 +0.920237 2.324471 0.000000 +1.148237 2.220710 0.000000 +1.368024 2.092489 0.000000 +1.575745 1.940883 0.000000 +1.767767 1.767767 0.000000 +1.940883 1.575745 0.000000 +2.092489 1.368024 0.000000 +2.220710 1.148237 0.000000 +2.324471 0.920237 0.000000 +2.403497 0.687896 0.000000 +2.458263 0.454908 0.000000 +2.500000 0.000000 0.000000 +2.458263 -0.454908 0.000000 +2.403497 -0.687896 0.000000 +2.324471 -0.920237 0.000000 +2.220710 -1.148237 0.000000 +2.092489 -1.368024 0.000000 +1.940883 -1.575745 0.000000 +1.767767 -1.767767 0.000000 + + + + + + + + + + + +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.961399 0.275158 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.961399 0.275158 0.000000 +-0.961399 0.275158 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.961399 0.275158 0.000000 +-0.961399 0.275158 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.961399 0.275158 0.000000 +-0.888284 0.459295 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.888284 0.459295 0.000000 +-0.888284 0.459295 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.888284 0.459295 0.000000 +-0.888284 0.459295 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.888284 0.459295 0.000000 +-0.776353 0.630298 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.776353 0.630298 0.000000 +-0.776353 0.630298 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.776353 0.630298 0.000000 +-0.776353 0.630298 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.776353 0.630298 0.000000 +-0.630298 0.776353 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.630298 0.776353 0.000000 +-0.630298 0.776353 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.630298 0.776353 0.000000 +-0.630298 0.776353 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.630298 0.776353 0.000000 +-0.459295 0.888284 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.459295 0.888284 0.000000 +-0.459295 0.888284 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.459295 0.888284 0.000000 +-0.459295 0.888284 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.459295 0.888284 0.000000 +-0.275158 0.961399 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.275158 0.961399 0.000000 +-0.275158 0.961399 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.275158 0.961399 0.000000 +-0.275158 0.961399 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.275158 0.961399 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.275158 0.961399 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.275158 0.961399 0.000000 +0.275158 0.961399 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.275158 0.961399 0.000000 +0.275158 0.961399 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.275158 0.961399 0.000000 +0.459295 0.888284 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.459295 0.888284 0.000000 +0.459295 0.888284 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.459295 0.888284 0.000000 +0.459295 0.888284 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.459295 0.888284 0.000000 +0.630298 0.776353 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.630298 0.776353 0.000000 +0.630298 0.776353 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.630298 0.776353 0.000000 +0.630298 0.776353 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.630298 0.776353 0.000000 +0.776353 0.630298 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.776353 0.630298 0.000000 +0.776353 0.630298 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.776353 0.630298 0.000000 +0.776353 0.630298 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.776353 0.630298 0.000000 +0.888284 0.459295 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.888284 0.459295 0.000000 +0.888284 0.459295 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.888284 0.459295 0.000000 +0.888284 0.459295 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.888284 0.459295 0.000000 +0.961399 0.275158 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.961399 0.275158 0.000000 +0.961399 0.275158 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.961399 0.275158 0.000000 +0.961399 0.275158 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.961399 0.275158 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.961399 -0.275158 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.961399 -0.275158 0.000000 +-0.961399 -0.275158 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.961399 -0.275158 0.000000 +-0.961399 -0.275158 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.961399 -0.275158 0.000000 +-0.888284 -0.459295 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.888284 -0.459295 0.000000 +-0.888284 -0.459295 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.888284 -0.459295 0.000000 +-0.888284 -0.459295 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.888284 -0.459295 0.000000 +-0.776353 -0.630298 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.776353 -0.630298 0.000000 +-0.776353 -0.630298 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.776353 -0.630298 0.000000 +-0.776353 -0.630298 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.776353 -0.630298 0.000000 +-0.630298 -0.776353 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.630298 -0.776353 0.000000 +-0.630298 -0.776353 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.630298 -0.776353 0.000000 +-0.630298 -0.776353 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.630298 -0.776353 0.000000 +-0.459295 -0.888284 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.459295 -0.888284 0.000000 +-0.459295 -0.888284 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.459295 -0.888284 0.000000 +-0.459295 -0.888284 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.459295 -0.888284 0.000000 +-0.275158 -0.961399 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.275158 -0.961399 0.000000 +-0.275158 -0.961399 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.275158 -0.961399 0.000000 +-0.275158 -0.961399 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.275158 -0.961399 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.275158 -0.961399 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.275158 -0.961399 0.000000 +0.275158 -0.961399 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.275158 -0.961399 0.000000 +0.275158 -0.961399 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.275158 -0.961399 0.000000 +0.459295 -0.888284 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.459295 -0.888284 0.000000 +0.459295 -0.888284 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.459295 -0.888284 0.000000 +0.459295 -0.888284 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.459295 -0.888284 0.000000 +0.630298 -0.776353 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.630298 -0.776353 0.000000 +0.630298 -0.776353 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.630298 -0.776353 0.000000 +0.630298 -0.776353 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.630298 -0.776353 0.000000 +0.776353 -0.630298 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.776353 -0.630298 0.000000 +0.776353 -0.630298 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.776353 -0.630298 0.000000 +0.776353 -0.630298 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.776353 -0.630298 0.000000 +0.888284 -0.459295 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.888284 -0.459295 0.000000 +0.888284 -0.459295 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.888284 -0.459295 0.000000 +0.888284 -0.459295 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.888284 -0.459295 0.000000 +0.961399 -0.275158 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.961399 -0.275158 0.000000 +0.961399 -0.275158 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.961399 -0.275158 0.000000 +0.961399 -0.275158 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.961399 -0.275158 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 + + + + + + + + + + + +0.368660 0.834284 +0.368660 0.834260 +0.357419 0.835258 +0.357325 0.834260 +0.357325 0.834284 +0.357419 0.835282 +0.357544 0.835770 +0.357544 0.835794 +0.357723 0.836279 +0.357723 0.836304 +0.357958 0.836780 +0.357958 0.836804 +0.358249 0.837262 +0.358249 0.837286 +0.358592 0.837718 +0.358592 0.837742 +0.358985 0.838139 +0.358985 0.838163 +0.359420 0.838519 +0.359420 0.838543 +0.359891 0.838852 +0.359891 0.838876 +0.360389 0.839133 +0.360389 0.839157 +0.360906 0.839361 +0.360906 0.839385 +0.361433 0.839534 +0.361433 0.839558 +0.361961 0.839654 +0.361961 0.839679 +0.362993 0.839746 +0.362993 0.839770 +0.364024 0.839654 +0.364024 0.839679 +0.364552 0.839534 +0.364552 0.839558 +0.365079 0.839361 +0.365079 0.839385 +0.365596 0.839133 +0.365596 0.839157 +0.366094 0.838852 +0.366094 0.838876 +0.366565 0.838519 +0.366565 0.838543 +0.367000 0.838139 +0.367000 0.838163 +0.367393 0.837718 +0.367393 0.837742 +0.367736 0.837262 +0.367736 0.837286 +0.368027 0.836780 +0.368027 0.836804 +0.368262 0.836279 +0.368262 0.836304 +0.368441 0.835770 +0.368441 0.835794 +0.368566 0.835258 +0.368566 0.835282 +0.368660 0.834260 +0.368660 0.834284 +0.357325 0.834284 +0.357325 0.834260 +0.357419 0.833286 +0.357419 0.833262 +0.357544 0.832775 +0.357544 0.832750 +0.357723 0.832265 +0.357723 0.832241 +0.357958 0.831764 +0.357958 0.831740 +0.358249 0.831282 +0.358249 0.831258 +0.358592 0.830826 +0.358592 0.830802 +0.358985 0.830405 +0.358985 0.830381 +0.359420 0.830025 +0.359420 0.830001 +0.359891 0.829692 +0.359891 0.829668 +0.360389 0.829411 +0.360389 0.829387 +0.360906 0.829183 +0.360906 0.829159 +0.361433 0.829010 +0.361433 0.828986 +0.361961 0.828890 +0.361961 0.828866 +0.362993 0.828798 +0.362993 0.828774 +0.364024 0.828890 +0.364024 0.828866 +0.364552 0.829010 +0.364552 0.828986 +0.365079 0.829183 +0.365079 0.829159 +0.365596 0.829411 +0.365596 0.829387 +0.366094 0.829692 +0.366094 0.829668 +0.366565 0.830025 +0.366565 0.830001 +0.367000 0.830405 +0.367000 0.830381 +0.367393 0.830826 +0.367393 0.830802 +0.367736 0.831282 +0.367736 0.831258 +0.368027 0.831764 +0.368027 0.831740 +0.368262 0.832265 +0.368262 0.832241 +0.368441 0.832775 +0.368441 0.832750 +0.368566 0.833286 +0.368566 0.833262 +0.366565 0.838543 +0.366094 0.838876 +0.364024 0.839679 +0.362993 0.839770 +0.361961 0.839679 +0.361433 0.839558 +0.360906 0.839385 +0.360389 0.839157 +0.359891 0.838876 +0.359420 0.838543 +0.358985 0.838163 +0.358592 0.837742 +0.358249 0.837286 +0.357958 0.836804 +0.357723 0.836304 +0.364552 0.839558 +0.357544 0.835794 +0.357419 0.835282 +0.357325 0.834284 +0.365079 0.839385 +0.357419 0.833286 +0.357544 0.832775 +0.357723 0.832265 +0.357958 0.831764 +0.358249 0.831282 +0.358592 0.830826 +0.358985 0.830405 +0.359420 0.830025 +0.359891 0.829692 +0.365596 0.839157 +0.360389 0.829411 +0.360906 0.829183 +0.361433 0.829010 +0.361961 0.828890 +0.362993 0.828798 +0.364024 0.828890 +0.364552 0.829010 +0.365079 0.829183 +0.365596 0.829411 +0.366094 0.829692 +0.366565 0.830025 +0.367000 0.830405 +0.367393 0.830826 +0.367736 0.831282 +0.368027 0.831764 +0.368262 0.832265 +0.368441 0.832775 +0.368566 0.833286 +0.368660 0.834284 +0.368566 0.835282 +0.368441 0.835794 +0.368262 0.836304 +0.368027 0.836804 +0.367736 0.837286 +0.367393 0.837742 +0.367000 0.838163 +0.366565 0.830001 +0.366094 0.829668 +0.364024 0.828866 +0.362993 0.828774 +0.361961 0.828866 +0.361433 0.828986 +0.360906 0.829159 +0.360389 0.829387 +0.359891 0.829668 +0.359420 0.830001 +0.358985 0.830381 +0.358592 0.830802 +0.358249 0.831258 +0.357958 0.831740 +0.357723 0.832241 +0.364552 0.828986 +0.357544 0.832750 +0.357419 0.833262 +0.357325 0.834260 +0.365079 0.829159 +0.357419 0.835258 +0.357544 0.835770 +0.357723 0.836279 +0.357958 0.836780 +0.358249 0.837262 +0.358592 0.837718 +0.358985 0.838139 +0.359420 0.838519 +0.359891 0.838852 +0.365596 0.829387 +0.360389 0.839133 +0.360906 0.839361 +0.361433 0.839534 +0.361961 0.839654 +0.362993 0.839746 +0.364024 0.839654 +0.364552 0.839534 +0.365079 0.839361 +0.365596 0.839133 +0.366094 0.838852 +0.366565 0.838519 +0.367000 0.838139 +0.367393 0.837718 +0.367736 0.837262 +0.368027 0.836780 +0.368262 0.836279 +0.368441 0.835770 +0.368566 0.835258 +0.368660 0.834260 +0.368566 0.833262 +0.368441 0.832750 +0.368262 0.832241 +0.368027 0.831740 +0.367736 0.831258 +0.367393 0.830802 +0.367000 0.830381 + + + + + + + + + + + +

56 0 56 0 1 0 1 2 1 4 3 4 2 4 2 3 5 3 5 6 5 2 7 2 4 8 4 7 9 7 2 10 2 5 11 5 7 12 7 6 13 6 2 14 2 9 15 9 6 16 6 7 17 7 9 18 9 8 19 8 6 20 6 11 21 11 8 22 8 9 23 9 11 24 11 10 25 10 8 26 8 13 27 13 10 28 10 11 29 11 13 30 13 12 31 12 10 32 10 15 33 15 12 34 12 13 35 13 15 36 15 14 37 14 12 38 12 17 39 17 14 40 14 15 41 15 17 42 17 16 43 16 14 44 14 19 45 19 16 46 16 17 47 17 19 48 19 18 49 18 16 50 16 21 51 21 18 52 18 19 53 19 21 54 21 20 55 20 18 56 18 23 57 23 20 58 20 21 59 21 23 60 23 22 61 22 20 62 20 25 63 25 22 64 22 23 65 23 25 66 25 24 67 24 22 68 22 27 69 27 24 70 24 25 71 25 27 72 27 26 73 26 24 74 24 29 75 29 26 76 26 27 77 27 29 78 29 28 79 28 26 80 26 31 81 31 28 82 28 29 83 29 31 84 31 30 85 30 28 86 28 33 87 33 30 88 30 31 89 31 33 90 33 32 91 32 30 92 30 35 93 35 32 94 32 33 95 33 35 96 35 34 97 34 32 98 32 37 99 37 34 100 34 35 101 35 37 102 37 36 103 36 34 104 34 39 105 39 36 106 36 37 107 37 39 108 39 38 109 38 36 110 36 41 111 41 38 112 38 39 113 39 41 114 41 40 115 40 38 116 38 43 117 43 40 118 40 41 119 41 43 120 43 42 121 42 40 122 40 45 123 45 42 124 42 43 125 43 45 126 45 44 127 44 42 128 42 47 129 47 44 130 44 45 131 45 47 132 47 46 133 46 44 134 44 49 135 49 46 136 46 47 137 47 49 138 49 48 139 48 46 140 46 51 141 51 48 142 48 49 143 49 51 144 51 50 145 50 48 146 48 53 147 53 50 148 50 51 149 51 53 150 53 52 151 52 50 152 50 55 153 55 52 154 52 53 155 53 55 156 55 54 157 54 52 158 52 57 159 57 54 160 54 55 161 55 57 162 57 56 163 56 54 164 54 0 165 0 56 166 56 57 167 57 114 168 114 58 169 58 59 170 59 63 171 63 60 172 60 61 173 61 63 174 63 62 175 62 60 176 60 65 177 65 62 178 62 63 179 63 65 180 65 64 181 64 62 182 62 67 183 67 64 184 64 65 185 65 67 186 67 66 187 66 64 188 64 69 189 69 66 190 66 67 191 67 69 192 69 68 193 68 66 194 66 71 195 71 68 196 68 69 197 69 71 198 71 70 199 70 68 200 68 73 201 73 70 202 70 71 203 71 73 204 73 72 205 72 70 206 70 75 207 75 72 208 72 73 209 73 75 210 75 74 211 74 72 212 72 77 213 77 74 214 74 75 215 75 77 216 77 76 217 76 74 218 74 79 219 79 76 220 76 77 221 77 79 222 79 78 223 78 76 224 76 81 225 81 78 226 78 79 227 79 81 228 81 80 229 80 78 230 78 83 231 83 80 232 80 81 233 81 83 234 83 82 235 82 80 236 80 85 237 85 82 238 82 83 239 83 85 240 85 84 241 84 82 242 82 87 243 87 84 244 84 85 245 85 87 246 87 86 247 86 84 248 84 89 249 89 86 250 86 87 251 87 89 252 89 88 253 88 86 254 86 91 255 91 88 256 88 89 257 89 91 258 91 90 259 90 88 260 88 93 261 93 90 262 90 91 263 91 93 264 93 92 265 92 90 266 90 95 267 95 92 268 92 93 269 93 95 270 95 94 271 94 92 272 92 97 273 97 94 274 94 95 275 95 97 276 97 96 277 96 94 278 94 99 279 99 96 280 96 97 281 97 99 282 99 98 283 98 96 284 96 101 285 101 98 286 98 99 287 99 101 288 101 100 289 100 98 290 98 103 291 103 100 292 100 101 293 101 103 294 103 102 295 102 100 296 100 105 297 105 102 298 102 103 299 103 105 300 105 104 301 104 102 302 102 107 303 107 104 304 104 105 305 105 107 306 107 106 307 106 104 308 104 109 309 109 106 310 106 107 311 107 109 312 109 108 313 108 106 314 106 111 315 111 108 316 108 109 317 109 111 318 111 110 319 110 108 320 108 113 321 113 110 322 110 111 323 111 113 324 113 112 325 112 110 326 110 115 327 115 112 328 112 113 329 113 115 330 115 114 331 114 112 332 112 58 333 58 114 334 114 115 335 115 145 336 145 116 337 116 117 338 117 120 339 120 118 340 118 119 341 119 121 342 121 118 343 118 120 344 120 122 345 122 118 346 118 121 347 121 123 348 123 118 349 118 122 350 122 124 351 124 118 352 118 123 353 123 125 354 125 118 355 118 124 356 124 126 357 126 118 358 118 125 359 125 127 360 127 118 361 118 126 362 126 128 363 128 118 364 118 127 365 127 129 366 129 118 367 118 128 368 128 130 369 130 118 370 118 129 371 129 132 372 132 118 373 118 130 374 130 132 375 132 131 376 131 118 377 118 133 378 133 131 379 131 132 380 132 134 381 134 131 382 131 133 383 133 136 384 136 131 385 131 134 386 134 136 387 136 135 388 135 131 389 131 137 390 137 135 391 135 136 392 136 138 393 138 135 394 135 137 395 137 139 396 139 135 397 135 138 398 138 140 399 140 135 400 135 139 401 139 141 402 141 135 403 135 140 404 140 142 405 142 135 406 135 141 407 141 143 408 143 135 409 135 142 410 142 144 411 144 135 412 135 143 413 143 146 414 146 135 415 135 144 416 144 146 417 146 145 418 145 135 419 135 147 420 147 145 421 145 146 422 146 148 423 148 145 424 145 147 425 147 149 426 149 145 427 145 148 428 148 150 429 150 145 430 145 149 431 149 151 432 151 145 433 145 150 434 150 152 435 152 145 436 145 151 437 151 153 438 153 145 439 145 152 440 152 154 441 154 145 442 145 153 443 153 155 444 155 145 445 145 154 446 154 156 447 156 145 448 145 155 449 155 157 450 157 145 451 145 156 452 156 158 453 158 145 454 145 157 455 157 159 456 159 145 457 145 158 458 158 160 459 160 145 460 145 159 461 159 161 462 161 145 463 145 160 464 160 162 465 162 145 466 145 161 467 161 163 468 163 145 469 145 162 470 162 164 471 164 145 472 145 163 473 163 165 474 165 145 475 145 164 476 164 166 477 166 145 478 145 165 479 165 167 480 167 145 481 145 166 482 166 168 483 168 145 484 145 167 485 167 169 486 169 145 487 145 168 488 168 170 489 170 145 490 145 169 491 169 171 492 171 145 493 145 170 494 170 116 495 116 145 496 145 171 497 171 201 498 201 172 499 172 173 500 173 176 501 176 174 502 174 175 503 175 177 504 177 174 505 174 176 506 176 178 507 178 174 508 174 177 509 177 179 510 179 174 511 174 178 512 178 180 513 180 174 514 174 179 515 179 181 516 181 174 517 174 180 518 180 182 519 182 174 520 174 181 521 181 183 522 183 174 523 174 182 524 182 184 525 184 174 526 174 183 527 183 185 528 185 174 529 174 184 530 184 186 531 186 174 532 174 185 533 185 188 534 188 174 535 174 186 536 186 188 537 188 187 538 187 174 539 174 189 540 189 187 541 187 188 542 188 190 543 190 187 544 187 189 545 189 192 546 192 187 547 187 190 548 190 192 549 192 191 550 191 187 551 187 193 552 193 191 553 191 192 554 192 194 555 194 191 556 191 193 557 193 195 558 195 191 559 191 194 560 194 196 561 196 191 562 191 195 563 195 197 564 197 191 565 191 196 566 196 198 567 198 191 568 191 197 569 197 199 570 199 191 571 191 198 572 198 200 573 200 191 574 191 199 575 199 202 576 202 191 577 191 200 578 200 202 579 202 201 580 201 191 581 191 203 582 203 201 583 201 202 584 202 204 585 204 201 586 201 203 587 203 205 588 205 201 589 201 204 590 204 206 591 206 201 592 201 205 593 205 207 594 207 201 595 201 206 596 206 208 597 208 201 598 201 207 599 207 209 600 209 201 601 201 208 602 208 210 603 210 201 604 201 209 605 209 211 606 211 201 607 201 210 608 210 212 609 212 201 610 201 211 611 211 213 612 213 201 613 201 212 614 212 214 615 214 201 616 201 213 617 213 215 618 215 201 619 201 214 620 214 216 621 216 201 622 201 215 623 215 217 624 217 201 625 201 216 626 216 218 627 218 201 628 201 217 629 217 219 630 219 201 631 201 218 632 218 220 633 220 201 634 201 219 635 219 221 636 221 201 637 201 220 638 220 222 639 222 201 640 201 221 641 221 223 642 223 201 643 201 222 644 222 224 645 224 201 646 201 223 647 223 225 648 225 201 649 201 224 650 224 226 651 226 201 652 201 225 653 225 227 654 227 201 655 201 226 656 226 172 657 172 201 658 201 227 659 227

+
+
+ + + + +-3.500000 0.000000 -9.000000 +-4.000000 0.000000 -8.500000 +3.933222 0.727852 -8.500000 +4.000000 0.000000 -8.500000 +3.500000 0.000000 -9.000000 +3.441569 0.636871 -9.000000 +3.719153 1.472379 -8.500000 +3.254259 1.288332 -9.000000 +3.347982 2.188839 -8.500000 +2.929484 1.915234 -9.000000 +2.828427 2.828427 -8.500000 +2.474874 2.474874 -9.000000 +2.188839 3.347982 -8.500000 +1.915234 2.929484 -9.000000 +1.472379 3.719153 -8.500000 +1.288332 3.254259 -9.000000 +0.727852 3.933222 -8.500000 +0.636871 3.441569 -9.000000 +0.000000 4.000000 -8.500000 +0.000000 3.500000 -9.000000 +-0.727852 3.933222 -8.500000 +-0.636871 3.441569 -9.000000 +-1.472379 3.719153 -8.500000 +-1.288332 3.254259 -9.000000 +-2.188839 3.347982 -8.500000 +-1.915234 2.929484 -9.000000 +-2.828427 2.828427 -8.500000 +-2.474874 2.474874 -9.000000 +-3.347982 2.188839 -8.500000 +-2.929484 1.915234 -9.000000 +-3.719153 1.472379 -8.500000 +-3.254259 1.288332 -9.000000 +-3.933222 0.727852 -8.500000 +-3.441569 0.636871 -9.000000 +-5.915123 -0.819638 4.100000 +-6.000000 0.000000 4.100000 +-2.819638 -3.915124 3.100000 +-2.000000 -4.000000 3.100000 +-2.000000 -4.000000 4.100000 +-3.588710 -3.670967 3.100000 +-2.819638 -3.915124 4.100000 +-3.588710 -3.670967 4.100000 +-4.266539 -3.295877 3.100000 +-4.828427 -2.828427 3.100000 +-4.266539 -3.295877 4.100000 +-4.828427 -2.828427 4.100000 +-5.295877 -2.266538 3.100000 +-5.295877 -2.266538 4.100000 +-5.670968 -1.588709 3.100000 +-5.670968 -1.588709 4.100000 +-5.915123 -0.819638 3.100000 +-6.000000 0.000000 3.100000 +-6.000000 0.000000 1.800000 +-6.000000 0.000000 0.000000 +-2.819638 -3.915124 0.000000 +-2.000000 -4.000000 0.000000 +-2.000000 -4.000000 1.800000 +-3.588710 -3.670967 0.000000 +-2.819638 -3.915124 1.800000 +-3.588710 -3.670967 1.800000 +-4.266539 -3.295877 0.000000 +-4.266539 -3.295877 1.800000 +-4.828427 -2.828427 0.000000 +-5.295877 -2.266538 0.000000 +-4.828427 -2.828427 1.800000 +-5.670968 -1.588709 0.000000 +-5.295877 -2.266538 1.800000 +-5.670968 -1.588709 1.800000 +-5.915123 -0.819638 0.000000 +-5.915123 -0.819638 1.800000 +-3.490734 0.645969 1.800000 +-3.550000 0.000000 1.800000 +3.490734 0.645969 3.100000 +3.550000 0.000000 3.100000 +3.550000 0.000000 1.800000 +3.490734 0.645969 1.800000 +3.300749 1.306736 3.100000 +3.300749 1.306736 1.800000 +2.971334 1.942595 3.100000 +2.971334 1.942595 1.800000 +2.510229 2.510229 3.100000 +2.510229 2.510229 1.800000 +1.942595 2.971334 3.100000 +1.942595 2.971334 1.800000 +1.306736 3.300749 3.100000 +1.306736 3.300749 1.800000 +0.645969 3.490734 3.100000 +0.645969 3.490734 1.800000 +0.000000 3.550000 3.100000 +0.000000 3.550000 1.800000 +-0.645969 3.490734 3.100000 +-1.306736 3.300749 3.100000 +-0.645969 3.490734 1.800000 +-1.942595 2.971334 3.100000 +-1.306736 3.300749 1.800000 +-2.510229 2.510229 3.100000 +-1.942595 2.971334 1.800000 +-2.971334 1.942595 3.100000 +-2.510229 2.510229 1.800000 +-3.300749 1.306736 3.100000 +-2.971334 1.942595 1.800000 +-3.490734 0.645969 3.100000 +-3.300749 1.306736 1.800000 +-3.550000 0.000000 3.100000 +0.750000 -2.121320 -6.500000 +-1.231222 -1.883240 -7.500000 +-0.828213 -2.092024 -9.000000 +-0.828213 -2.092024 -7.500000 +-0.409417 -2.212437 -9.000000 +0.828213 -2.092024 -7.500000 +1.231222 -1.883240 -9.000000 +0.750000 -2.121320 -7.500000 +0.828213 -2.092024 -9.000000 +1.590990 -1.590990 -9.000000 +1.231222 -1.883240 -7.500000 +1.883240 -1.231222 -9.000000 +1.590990 -1.590990 -7.500000 +2.092024 -0.828213 -9.000000 +1.883240 -1.231222 -7.500000 +2.212437 -0.409417 -9.000000 +2.092024 -0.828213 -7.500000 +2.250000 0.000000 -9.000000 +2.212437 -0.409417 -7.500000 +2.250000 0.000000 4.100000 +2.215817 -0.390708 -7.500000 +2.212437 -0.409417 4.100000 +2.215817 -0.390708 -6.500000 +-1.231222 -1.883240 -9.000000 +-1.590990 -1.590990 -7.500000 +-2.250000 0.000000 -9.000000 +-2.250000 0.000000 4.100000 +2.212437 -0.409417 -6.500000 +2.092024 -0.828213 4.100000 +2.092024 -0.828213 -6.500000 +1.883240 -1.231222 4.100000 +1.883240 -1.231222 -6.500000 +1.590990 -1.590990 4.100000 +1.590990 -1.590990 -6.500000 +1.231222 -1.883240 4.100000 +1.231222 -1.883240 -6.500000 +0.828213 -2.092024 4.100000 +0.828213 -2.092024 -6.500000 +0.409417 -2.212437 4.100000 +-1.590990 -1.590990 -9.000000 +-1.883240 -1.231222 -7.500000 +-1.883240 -1.231222 -9.000000 +-2.092024 -0.828213 -7.500000 +-2.212437 -0.409417 -7.500000 +-2.092024 -0.828213 -9.000000 +-2.212437 -0.409417 -9.000000 +-2.215817 -0.390708 -7.500000 +-2.215817 -0.390708 -6.500000 +-2.212437 -0.409417 -6.500000 +-2.092024 -0.828213 -6.500000 +-2.212437 -0.409417 4.100000 +-1.883240 -1.231222 -6.500000 +-2.092024 -0.828213 4.100000 +-1.590990 -1.590990 -6.500000 +-1.883240 -1.231222 4.100000 +-1.590990 -1.590990 4.100000 +-1.231222 -1.883240 -6.500000 +-1.231222 -1.883240 4.100000 +-0.828213 -2.092024 -6.500000 +-0.750000 -2.121320 -6.500000 +-0.828213 -2.092024 4.100000 +-0.750000 -2.121320 -7.500000 +-0.409417 -2.212437 4.100000 +0.000000 -2.250000 -9.000000 +0.000000 -2.250000 4.100000 +0.409417 -2.212437 -9.000000 +-0.750000 3.929058 -7.500000 +-4.000000 0.000000 -8.500000 +-4.000000 0.000000 0.000000 +-2.188839 3.347982 -7.500000 +-1.472379 3.719153 -8.500000 +-1.472379 3.719153 -7.500000 +-0.727852 3.933222 -8.500000 +2.188839 3.347982 -8.500000 +1.472379 3.719153 -7.500000 +2.188839 3.347982 -7.500000 +2.828427 2.828427 -8.500000 +4.000000 0.000000 0.000000 +4.000000 0.000000 -8.500000 +1.472379 3.719153 -8.500000 +0.750000 3.929058 -7.500000 +2.828427 2.828427 -7.500000 +3.347982 2.188839 -8.500000 +3.719153 1.472379 -8.500000 +3.347982 2.188839 -7.500000 +3.719153 1.472379 -7.500000 +3.933222 0.727852 -8.500000 +3.933222 0.727852 -7.500000 +3.939231 0.694593 -7.500000 +3.933222 0.727852 0.000000 +3.939231 0.694593 -6.500000 +3.719153 1.472379 0.000000 +3.933222 0.727852 -6.500000 +3.719153 1.472379 -6.500000 +3.347982 2.188839 0.000000 +3.347982 2.188839 -6.500000 +2.828427 2.828427 0.000000 +2.188839 3.347982 0.000000 +2.828427 2.828427 -6.500000 +1.472379 3.719153 0.000000 +2.188839 3.347982 -6.500000 +1.472379 3.719153 -6.500000 +0.727852 3.933222 0.000000 +-2.188839 3.347982 -8.500000 +-2.828427 2.828427 -7.500000 +-2.828427 2.828427 -8.500000 +-3.347982 2.188839 -7.500000 +-3.347982 2.188839 -8.500000 +-3.719153 1.472379 -7.500000 +-3.719153 1.472379 -8.500000 +-3.933222 0.727852 -7.500000 +-3.933222 0.727852 -8.500000 +-3.939231 0.694593 -7.500000 +0.000000 4.000000 0.000000 +-3.939231 0.694593 -6.500000 +-3.933222 0.727852 -6.500000 +-3.719153 1.472379 -6.500000 +-3.933222 0.727852 0.000000 +-3.719153 1.472379 0.000000 +-3.347982 2.188839 -6.500000 +-3.347982 2.188839 0.000000 +-2.828427 2.828427 -6.500000 +-2.828427 2.828427 0.000000 +-2.188839 3.347982 -6.500000 +-2.188839 3.347982 0.000000 +-1.472379 3.719153 -6.500000 +-1.472379 3.719153 0.000000 +-0.750000 3.929058 -6.500000 +-0.727852 3.933222 0.000000 +0.727852 3.933222 -8.500000 +0.750000 3.929058 -6.500000 +0.000000 4.000000 -8.500000 +2.848274 -2.808440 -6.500000 +1.309482 -3.779584 -6.500000 +0.750000 -3.929058 -6.500000 +1.859484 -3.541514 -6.500000 +0.750000 -2.121320 -6.500000 +2.379266 -3.215446 -6.500000 +2.215817 -0.390708 -6.500000 +3.939231 -0.694593 -6.500000 +2.041450 -0.946036 -6.500000 +3.797651 -1.256124 -6.500000 +3.567350 -1.809424 -6.500000 +1.716908 -1.454210 -6.500000 +3.248635 -2.333747 -6.500000 +1.269065 -1.857949 -6.500000 +-2.379266 -3.215446 -6.500000 +-0.750000 -2.121320 -6.500000 +-0.750000 -3.929058 -6.500000 +-1.309482 -3.779584 -6.500000 +-1.269065 -1.857949 -6.500000 +-1.859484 -3.541514 -6.500000 +-3.797651 -1.256124 -6.500000 +-3.939231 -0.694593 -6.500000 +-2.215817 -0.390708 -6.500000 +-3.567350 -1.809424 -6.500000 +-3.248635 -2.333747 -6.500000 +-2.041450 -0.946036 -6.500000 +-2.848274 -2.808440 -6.500000 +-1.716908 -1.454210 -6.500000 +2.379266 -3.215446 -7.500000 +0.750000 -2.121320 -7.500000 +0.750000 -3.929058 -7.500000 +1.309482 -3.779584 -7.500000 +1.269065 -1.857949 -7.500000 +1.859484 -3.541514 -7.500000 +3.797651 -1.256124 -7.500000 +3.939231 -0.694593 -7.500000 +2.215817 -0.390708 -7.500000 +3.567350 -1.809424 -7.500000 +3.248635 -2.333747 -7.500000 +2.041450 -0.946036 -7.500000 +2.848274 -2.808440 -7.500000 +1.716908 -1.454210 -7.500000 +-2.848274 -2.808440 -7.500000 +-1.309482 -3.779584 -7.500000 +-0.750000 -3.929058 -7.500000 +-1.859484 -3.541514 -7.500000 +-0.750000 -2.121320 -7.500000 +-2.379266 -3.215446 -7.500000 +-2.215817 -0.390708 -7.500000 +-3.939231 -0.694593 -7.500000 +-2.041450 -0.946036 -7.500000 +-3.797651 -1.256124 -7.500000 +-3.567350 -1.809424 -7.500000 +-1.716908 -1.454210 -7.500000 +-3.248635 -2.333747 -7.500000 +-1.269065 -1.857949 -7.500000 +-2.848274 2.808440 -6.500000 +-1.309482 3.779584 -6.500000 +-0.750000 3.929058 -6.500000 +-1.859484 3.541514 -6.500000 +-0.750000 2.121320 -6.500000 +-2.379266 3.215446 -6.500000 +-2.215817 0.390708 -6.500000 +-3.939231 0.694593 -6.500000 +-2.041450 0.946036 -6.500000 +-3.797651 1.256124 -6.500000 +-3.567350 1.809424 -6.500000 +-1.716908 1.454210 -6.500000 +-3.248635 2.333747 -6.500000 +-1.269065 1.857949 -6.500000 +2.379266 3.215446 -6.500000 +0.750000 2.121320 -6.500000 +0.750000 3.929058 -6.500000 +1.309482 3.779584 -6.500000 +1.269065 1.857949 -6.500000 +1.859484 3.541514 -6.500000 +3.797651 1.256124 -6.500000 +3.939231 0.694593 -6.500000 +2.215817 0.390708 -6.500000 +3.567350 1.809424 -6.500000 +3.248635 2.333747 -6.500000 +2.041450 0.946036 -6.500000 +2.848274 2.808440 -6.500000 +1.716908 1.454210 -6.500000 +-2.379266 3.215446 -7.500000 +-0.750000 2.121320 -7.500000 +-0.750000 3.929058 -7.500000 +-1.309482 3.779584 -7.500000 +-1.269065 1.857949 -7.500000 +-1.859484 3.541514 -7.500000 +-3.797651 1.256124 -7.500000 +-3.939231 0.694593 -7.500000 +-2.215817 0.390708 -7.500000 +-3.567350 1.809424 -7.500000 +-3.248635 2.333747 -7.500000 +-2.041450 0.946036 -7.500000 +-2.848274 2.808440 -7.500000 +-1.716908 1.454210 -7.500000 +2.848274 2.808440 -7.500000 +1.309482 3.779584 -7.500000 +0.750000 3.929058 -7.500000 +1.859484 3.541514 -7.500000 +0.750000 2.121320 -7.500000 +2.379266 3.215446 -7.500000 +2.215817 0.390708 -7.500000 +3.939231 0.694593 -7.500000 +2.041450 0.946036 -7.500000 +3.797651 1.256124 -7.500000 +3.567350 1.809424 -7.500000 +1.716908 1.454210 -7.500000 +3.248635 2.333747 -7.500000 +1.269065 1.857949 -7.500000 +-0.750000 -3.929058 -6.500000 +3.719153 -1.472379 -7.500000 +3.347982 -2.188839 -8.500000 +-2.188839 -3.347982 -8.500000 +-1.472379 -3.719153 -7.500000 +-0.750000 -3.929058 -7.500000 +-1.472379 -3.719153 -8.500000 +-2.188839 -3.347982 -7.500000 +-2.828427 -2.828427 -8.500000 +-4.000000 0.000000 0.000000 +-4.000000 0.000000 -8.500000 +4.000000 0.000000 -8.500000 +4.000000 0.000000 0.000000 +3.347982 -2.188839 -7.500000 +2.828427 -2.828427 -8.500000 +2.828427 -2.828427 -7.500000 +2.188839 -3.347982 -8.500000 +1.472379 -3.719153 -8.500000 +2.188839 -3.347982 -7.500000 +1.472379 -3.719153 -7.500000 +0.727852 -3.933222 -8.500000 +-2.828427 -2.828427 -7.500000 +-3.347982 -2.188839 -8.500000 +-3.347982 -2.188839 -7.500000 +-3.719153 -1.472379 -8.500000 +-3.933222 -0.727852 -8.500000 +-3.719153 -1.472379 -7.500000 +-3.933222 -0.727852 -7.500000 +-3.939231 -0.694593 -7.500000 +-3.933222 -0.727852 0.000000 +-3.939231 -0.694593 -6.500000 +-3.933222 -0.727852 -6.500000 +-3.719153 -1.472379 0.000000 +-3.719153 -1.472379 -6.500000 +-3.347982 -2.188839 0.000000 +-2.828427 -2.828427 0.000000 +-3.347982 -2.188839 -6.500000 +-2.828427 -2.828427 -6.500000 +-2.188839 -3.347982 0.000000 +-2.188839 -3.347982 -6.500000 +-1.472379 -3.719153 0.000000 +-1.472379 -3.719153 -6.500000 +-0.727852 -3.933222 0.000000 +3.719153 -1.472379 -8.500000 +3.933222 -0.727852 -7.500000 +3.939231 -0.694593 -7.500000 +3.933222 -0.727852 -8.500000 +0.000000 -4.000000 0.000000 +3.939231 -0.694593 -6.500000 +3.933222 -0.727852 -6.500000 +3.933222 -0.727852 0.000000 +3.719153 -1.472379 -6.500000 +3.347982 -2.188839 -6.500000 +3.719153 -1.472379 0.000000 +2.828427 -2.828427 -6.500000 +3.347982 -2.188839 0.000000 +2.188839 -3.347982 -6.500000 +2.828427 -2.828427 0.000000 +2.188839 -3.347982 0.000000 +1.472379 -3.719153 -6.500000 +1.472379 -3.719153 0.000000 +0.750000 -3.929058 -6.500000 +0.727852 -3.933222 0.000000 +0.000000 -4.000000 -8.500000 +0.750000 -3.929058 -7.500000 +-0.727852 -3.933222 -8.500000 +-0.750000 2.121320 -6.500000 +1.883240 1.231222 -7.500000 +1.590990 1.590990 -9.000000 +-1.231222 1.883240 -9.000000 +-0.828213 2.092024 -7.500000 +-0.750000 2.121320 -7.500000 +-0.828213 2.092024 -9.000000 +-1.231222 1.883240 -7.500000 +-1.590990 1.590990 -9.000000 +1.883240 1.231222 -9.000000 +2.092024 0.828213 -7.500000 +-2.250000 0.000000 4.100000 +-2.250000 0.000000 -9.000000 +2.250000 0.000000 -9.000000 +2.250000 0.000000 4.100000 +1.590990 1.590990 -7.500000 +1.231222 1.883240 -9.000000 +1.231222 1.883240 -7.500000 +0.828213 2.092024 -9.000000 +0.828213 2.092024 -7.500000 +0.409417 2.212437 -9.000000 +-1.590990 1.590990 -7.500000 +-1.883240 1.231222 -9.000000 +-1.883240 1.231222 -7.500000 +-2.092024 0.828213 -9.000000 +-2.092024 0.828213 -7.500000 +-2.212437 0.409417 -9.000000 +-2.212437 0.409417 -7.500000 +-2.215817 0.390708 -7.500000 +-2.212437 0.409417 4.100000 +-2.215817 0.390708 -6.500000 +-2.212437 0.409417 -6.500000 +-2.092024 0.828213 4.100000 +-2.092024 0.828213 -6.500000 +-1.883240 1.231222 4.100000 +-1.883240 1.231222 -6.500000 +-1.590990 1.590990 4.100000 +-1.590990 1.590990 -6.500000 +-1.231222 1.883240 4.100000 +-1.231222 1.883240 -6.500000 +-0.828213 2.092024 4.100000 +-0.828213 2.092024 -6.500000 +-0.409417 2.212437 4.100000 +2.092024 0.828213 -9.000000 +2.212437 0.409417 -7.500000 +2.212437 0.409417 -9.000000 +2.215817 0.390708 -7.500000 +2.215817 0.390708 -6.500000 +2.212437 0.409417 -6.500000 +2.092024 0.828213 -6.500000 +2.212437 0.409417 4.100000 +1.883240 1.231222 -6.500000 +2.092024 0.828213 4.100000 +1.883240 1.231222 4.100000 +1.590990 1.590990 -6.500000 +1.590990 1.590990 4.100000 +1.231222 1.883240 -6.500000 +1.231222 1.883240 4.100000 +0.828213 2.092024 -6.500000 +0.750000 2.121320 -6.500000 +0.828213 2.092024 4.100000 +0.750000 2.121320 -7.500000 +0.409417 2.212437 4.100000 +0.000000 2.250000 -9.000000 +0.000000 2.250000 4.100000 +-0.409417 2.212437 -9.000000 +3.472379 3.719153 0.000000 +0.727852 3.933222 0.000000 +0.000000 4.000000 0.000000 +2.000000 -4.000000 0.000000 +0.000000 -4.000000 0.000000 +0.727852 -3.933222 0.000000 +1.472379 3.719153 0.000000 +2.188839 3.347982 0.000000 +1.472379 -3.719153 0.000000 +2.727852 -3.933222 0.000000 +2.000000 4.000000 0.000000 +2.828427 2.828427 0.000000 +2.727852 3.933222 0.000000 +2.188839 -3.347982 0.000000 +3.472379 -3.719153 0.000000 +4.188839 -3.347982 0.000000 +2.828427 -2.828427 0.000000 +4.828427 -2.828427 0.000000 +3.347982 -2.188839 0.000000 +5.347982 -2.188839 0.000000 +5.719153 -1.472379 0.000000 +3.719153 -1.472379 0.000000 +5.933221 -0.727852 0.000000 +3.933222 -0.727852 0.000000 +6.000000 0.000000 0.000000 +5.933221 0.727852 0.000000 +4.000000 0.000000 0.000000 +5.719153 1.472379 0.000000 +3.933222 0.727852 0.000000 +5.347982 2.188839 0.000000 +4.828427 2.828427 0.000000 +3.719153 1.472379 0.000000 +4.188839 3.347982 0.000000 +3.347982 2.188839 0.000000 +-3.472379 -3.719153 0.000000 +-0.727852 -3.933222 0.000000 +0.000000 -4.000000 0.000000 +-2.000000 4.000000 0.000000 +0.000000 4.000000 0.000000 +-0.727852 3.933222 0.000000 +-1.472379 -3.719153 0.000000 +-2.188839 -3.347982 0.000000 +-1.472379 3.719153 0.000000 +-2.727852 3.933222 0.000000 +-2.000000 -4.000000 0.000000 +-2.828427 -2.828427 0.000000 +-2.727852 -3.933222 0.000000 +-2.188839 3.347982 0.000000 +-3.472379 3.719153 0.000000 +-4.188839 3.347982 0.000000 +-2.828427 2.828427 0.000000 +-4.828427 2.828427 0.000000 +-3.347982 2.188839 0.000000 +-5.347982 2.188839 0.000000 +-5.719153 1.472379 0.000000 +-3.719153 1.472379 0.000000 +-5.933221 0.727852 0.000000 +-3.933222 0.727852 0.000000 +-6.000000 0.000000 0.000000 +-5.933221 -0.727852 0.000000 +-4.000000 0.000000 0.000000 +-5.719153 -1.472379 0.000000 +-3.933222 -0.727852 0.000000 +-5.347982 -2.188839 0.000000 +-4.828427 -2.828427 0.000000 +-3.719153 -1.472379 0.000000 +-4.188839 -3.347982 0.000000 +-3.347982 -2.188839 0.000000 +3.550000 0.000000 1.800000 +3.550000 0.000000 3.100000 +-3.550000 0.000000 3.100000 +-3.550000 0.000000 1.800000 +-3.490734 -0.645969 3.100000 +-3.490734 -0.645969 1.800000 +-3.300749 -1.306736 3.100000 +-3.300749 -1.306736 1.800000 +-2.971334 -1.942595 3.100000 +-2.971334 -1.942595 1.800000 +-2.510229 -2.510229 3.100000 +-2.510229 -2.510229 1.800000 +-1.942595 -2.971334 3.100000 +-1.942595 -2.971334 1.800000 +-1.306736 -3.300749 3.100000 +-1.306736 -3.300749 1.800000 +-0.645969 -3.490734 3.100000 +-0.645969 -3.490734 1.800000 +0.000000 -3.550000 3.100000 +0.000000 -3.550000 1.800000 +0.645969 -3.490734 3.100000 +0.645969 -3.490734 1.800000 +1.306736 -3.300749 3.100000 +1.306736 -3.300749 1.800000 +1.942595 -2.971334 3.100000 +1.942595 -2.971334 1.800000 +2.510229 -2.510229 3.100000 +2.510229 -2.510229 1.800000 +2.971334 -1.942595 3.100000 +2.971334 -1.942595 1.800000 +3.300749 -1.306736 3.100000 +3.300749 -1.306736 1.800000 +3.490734 -0.645969 3.100000 +3.490734 -0.645969 1.800000 +-0.645969 -3.490734 1.800000 +-1.306736 -3.300749 1.800000 +-2.727852 -3.933222 1.800000 +-1.942595 -2.971334 1.800000 +-3.472379 -3.719153 1.800000 +-4.188839 -3.347982 1.800000 +-2.510229 -2.510229 1.800000 +-4.828427 -2.828427 1.800000 +-2.971334 -1.942595 1.800000 +-5.347982 -2.188839 1.800000 +-5.719153 -1.472379 1.800000 +-3.300749 -1.306736 1.800000 +-5.933221 -0.727852 1.800000 +-3.490734 -0.645969 1.800000 +-6.000000 0.000000 1.800000 +-5.933221 0.727852 1.800000 +-3.550000 0.000000 1.800000 +-5.719153 1.472379 1.800000 +-5.347982 2.188839 1.800000 +-3.490734 0.645969 1.800000 +-4.828427 2.828427 1.800000 +-3.300749 1.306736 1.800000 +-4.188839 3.347982 1.800000 +-3.472379 3.719153 1.800000 +-2.971334 1.942595 1.800000 +-2.727852 3.933222 1.800000 +-2.510229 2.510229 1.800000 +-2.000000 4.000000 1.800000 +-1.942595 2.971334 1.800000 +-1.306736 3.300749 1.800000 +2.000000 4.000000 1.800000 +-0.645969 3.490734 1.800000 +0.000000 3.550000 1.800000 +0.645969 3.490734 1.800000 +1.306736 3.300749 1.800000 +2.727852 3.933222 1.800000 +1.942595 2.971334 1.800000 +3.472379 3.719153 1.800000 +4.188839 3.347982 1.800000 +2.510229 2.510229 1.800000 +4.828427 2.828427 1.800000 +2.971334 1.942595 1.800000 +5.347982 2.188839 1.800000 +5.719153 1.472379 1.800000 +3.300749 1.306736 1.800000 +5.933221 0.727852 1.800000 +3.490734 0.645969 1.800000 +6.000000 0.000000 1.800000 +5.933221 -0.727852 1.800000 +3.550000 0.000000 1.800000 +5.719153 -1.472379 1.800000 +5.347982 -2.188839 1.800000 +3.490734 -0.645969 1.800000 +4.828427 -2.828427 1.800000 +3.300749 -1.306736 1.800000 +4.188839 -3.347982 1.800000 +3.472379 -3.719153 1.800000 +2.971334 -1.942595 1.800000 +2.727852 -3.933222 1.800000 +2.510229 -2.510229 1.800000 +2.000000 -4.000000 1.800000 +1.942595 -2.971334 1.800000 +1.306736 -3.300749 1.800000 +-2.000000 -4.000000 1.800000 +0.645969 -3.490734 1.800000 +0.000000 -3.550000 1.800000 +2.000000 -4.000000 1.800000 +2.000000 -4.000000 0.000000 +2.727852 3.933222 0.000000 +2.000000 4.000000 0.000000 +2.000000 4.000000 1.800000 +3.472379 3.719153 0.000000 +2.727852 3.933222 1.800000 +3.472379 3.719153 1.800000 +4.188839 3.347982 0.000000 +4.188839 3.347982 1.800000 +4.828427 2.828427 0.000000 +4.828427 2.828427 1.800000 +5.347982 2.188839 0.000000 +5.347982 2.188839 1.800000 +5.719153 1.472379 0.000000 +5.719153 1.472379 1.800000 +5.933221 0.727852 0.000000 +5.933221 0.727852 1.800000 +6.000000 0.000000 0.000000 +6.000000 0.000000 1.800000 +5.933221 -0.727852 0.000000 +5.933221 -0.727852 1.800000 +5.719153 -1.472379 0.000000 +5.719153 -1.472379 1.800000 +5.347982 -2.188839 0.000000 +5.347982 -2.188839 1.800000 +4.828427 -2.828427 0.000000 +4.188839 -3.347982 0.000000 +4.828427 -2.828427 1.800000 +4.188839 -3.347982 1.800000 +3.472379 -3.719153 0.000000 +3.472379 -3.719153 1.800000 +2.727852 -3.933222 0.000000 +2.727852 -3.933222 1.800000 +0.000000 4.000000 0.000000 +-2.000000 4.000000 0.000000 +2.000000 4.000000 1.800000 +2.000000 4.000000 0.000000 +-2.000000 4.000000 1.800000 +-6.000000 0.000000 0.000000 +-6.000000 0.000000 1.800000 +-2.000000 4.000000 1.800000 +-2.000000 4.000000 0.000000 +-2.819638 3.915124 1.800000 +-2.819638 3.915124 0.000000 +-3.588710 3.670967 1.800000 +-3.588710 3.670967 0.000000 +-4.266539 3.295877 1.800000 +-4.266539 3.295877 0.000000 +-4.828427 2.828427 1.800000 +-4.828427 2.828427 0.000000 +-5.295877 2.266538 1.800000 +-5.295877 2.266538 0.000000 +-5.670968 1.588709 1.800000 +-5.915123 0.819638 1.800000 +-5.670968 1.588709 0.000000 +-5.915123 0.819638 0.000000 +0.000000 -4.000000 0.000000 +2.000000 -4.000000 0.000000 +-2.000000 -4.000000 1.800000 +-2.000000 -4.000000 0.000000 +2.000000 -4.000000 1.800000 +-1.306736 -3.300749 3.100000 +-1.942595 -2.971334 3.100000 +-2.000000 -4.000000 3.100000 +-2.510229 -2.510229 3.100000 +-2.727852 -3.933222 3.100000 +-3.472379 -3.719153 3.100000 +-2.971334 -1.942595 3.100000 +-4.188839 -3.347982 3.100000 +-3.300749 -1.306736 3.100000 +-4.828427 -2.828427 3.100000 +-5.347982 -2.188839 3.100000 +-3.490734 -0.645969 3.100000 +-5.719153 -1.472379 3.100000 +-3.550000 0.000000 3.100000 +-5.933221 -0.727852 3.100000 +-6.000000 0.000000 3.100000 +-3.490734 0.645969 3.100000 +-5.933221 0.727852 3.100000 +-5.719153 1.472379 3.100000 +-3.300749 1.306736 3.100000 +-5.347982 2.188839 3.100000 +-2.971334 1.942595 3.100000 +-4.828427 2.828427 3.100000 +-4.188839 3.347982 3.100000 +-2.510229 2.510229 3.100000 +-3.472379 3.719153 3.100000 +-1.942595 2.971334 3.100000 +-2.727852 3.933222 3.100000 +-1.306736 3.300749 3.100000 +-0.645969 3.490734 3.100000 +-2.000000 4.000000 3.100000 +0.000000 3.550000 3.100000 +0.645969 3.490734 3.100000 +1.306736 3.300749 3.100000 +1.942595 2.971334 3.100000 +2.000000 4.000000 3.100000 +2.510229 2.510229 3.100000 +2.727852 3.933222 3.100000 +3.472379 3.719153 3.100000 +2.971334 1.942595 3.100000 +4.188839 3.347982 3.100000 +3.300749 1.306736 3.100000 +4.828427 2.828427 3.100000 +5.347982 2.188839 3.100000 +3.490734 0.645969 3.100000 +5.719153 1.472379 3.100000 +3.550000 0.000000 3.100000 +5.933221 0.727852 3.100000 +6.000000 0.000000 3.100000 +3.490734 -0.645969 3.100000 +5.933221 -0.727852 3.100000 +5.719153 -1.472379 3.100000 +3.300749 -1.306736 3.100000 +5.347982 -2.188839 3.100000 +2.971334 -1.942595 3.100000 +4.828427 -2.828427 3.100000 +4.188839 -3.347982 3.100000 +2.510229 -2.510229 3.100000 +3.472379 -3.719153 3.100000 +1.942595 -2.971334 3.100000 +2.727852 -3.933222 3.100000 +1.306736 -3.300749 3.100000 +0.645969 -3.490734 3.100000 +2.000000 -4.000000 3.100000 +0.000000 -3.550000 3.100000 +-0.645969 -3.490734 3.100000 +-2.819638 3.915124 4.100000 +-2.000000 4.000000 4.100000 +-5.915123 0.819638 3.100000 +-6.000000 0.000000 3.100000 +-6.000000 0.000000 4.100000 +-5.670968 1.588709 3.100000 +-5.915123 0.819638 4.100000 +-5.295877 2.266538 3.100000 +-5.670968 1.588709 4.100000 +-4.828427 2.828427 3.100000 +-5.295877 2.266538 4.100000 +-4.828427 2.828427 4.100000 +-4.266539 3.295877 3.100000 +-3.588710 3.670967 3.100000 +-4.266539 3.295877 4.100000 +-2.819638 3.915124 3.100000 +-3.588710 3.670967 4.100000 +-2.000000 4.000000 3.100000 +2.000000 -4.000000 4.100000 +-2.000000 -4.000000 4.100000 +-2.000000 -4.000000 3.100000 +2.000000 -4.000000 3.100000 +2.000000 4.000000 3.100000 +2.000000 4.000000 4.100000 +2.727852 -3.933222 4.100000 +2.000000 -4.000000 4.100000 +2.000000 -4.000000 3.100000 +2.727852 -3.933222 3.100000 +3.472379 -3.719153 4.100000 +3.472379 -3.719153 3.100000 +4.188839 -3.347982 4.100000 +4.188839 -3.347982 3.100000 +4.828427 -2.828427 4.100000 +4.828427 -2.828427 3.100000 +5.347982 -2.188839 4.100000 +5.347982 -2.188839 3.100000 +5.719153 -1.472379 4.100000 +5.719153 -1.472379 3.100000 +5.933221 -0.727852 4.100000 +5.933221 -0.727852 3.100000 +6.000000 0.000000 4.100000 +6.000000 0.000000 3.100000 +5.933221 0.727852 4.100000 +5.933221 0.727852 3.100000 +5.719153 1.472379 4.100000 +5.719153 1.472379 3.100000 +5.347982 2.188839 4.100000 +5.347982 2.188839 3.100000 +4.828427 2.828427 4.100000 +4.828427 2.828427 3.100000 +4.188839 3.347982 4.100000 +4.188839 3.347982 3.100000 +3.472379 3.719153 4.100000 +3.472379 3.719153 3.100000 +2.727852 3.933222 4.100000 +2.727852 3.933222 3.100000 +-2.000000 4.000000 4.100000 +2.000000 4.000000 4.100000 +2.000000 4.000000 3.100000 +-2.000000 4.000000 3.100000 +1.590990 -1.590990 4.100000 +-2.000000 -4.000000 4.100000 +-0.409417 -2.212437 4.100000 +0.000000 -2.250000 4.100000 +0.409417 -2.212437 4.100000 +0.828213 -2.092024 4.100000 +1.231222 -1.883240 4.100000 +-0.828213 -2.092024 4.100000 +-2.727852 -3.933222 4.100000 +-1.231222 -1.883240 4.100000 +-3.472379 -3.719153 4.100000 +-1.590990 -1.590990 4.100000 +-4.188839 -3.347982 4.100000 +-4.828427 -2.828427 4.100000 +-1.883240 -1.231222 4.100000 +-5.347982 -2.188839 4.100000 +-5.719153 -1.472379 4.100000 +-2.092024 -0.828213 4.100000 +-5.933221 -0.727852 4.100000 +-2.212437 -0.409417 4.100000 +-6.000000 0.000000 4.100000 +-5.933221 0.727852 4.100000 +-2.250000 0.000000 4.100000 +-5.719153 1.472379 4.100000 +-5.347982 2.188839 4.100000 +-2.212437 0.409417 4.100000 +-4.828427 2.828427 4.100000 +-4.188839 3.347982 4.100000 +-2.092024 0.828213 4.100000 +-3.472379 3.719153 4.100000 +-1.883240 1.231222 4.100000 +-2.727852 3.933222 4.100000 +-2.000000 4.000000 4.100000 +-1.590990 1.590990 4.100000 +2.000000 4.000000 4.100000 +-1.231222 1.883240 4.100000 +-0.828213 2.092024 4.100000 +-0.409417 2.212437 4.100000 +0.000000 2.250000 4.100000 +0.409417 2.212437 4.100000 +0.828213 2.092024 4.100000 +2.727852 3.933222 4.100000 +1.231222 1.883240 4.100000 +3.472379 3.719153 4.100000 +1.590990 1.590990 4.100000 +4.188839 3.347982 4.100000 +4.828427 2.828427 4.100000 +1.883240 1.231222 4.100000 +5.347982 2.188839 4.100000 +5.719153 1.472379 4.100000 +2.092024 0.828213 4.100000 +5.933221 0.727852 4.100000 +2.212437 0.409417 4.100000 +6.000000 0.000000 4.100000 +5.933221 -0.727852 4.100000 +2.250000 0.000000 4.100000 +5.719153 -1.472379 4.100000 +5.347982 -2.188839 4.100000 +2.212437 -0.409417 4.100000 +4.828427 -2.828427 4.100000 +4.188839 -3.347982 4.100000 +2.092024 -0.828213 4.100000 +3.472379 -3.719153 4.100000 +1.883240 -1.231222 4.100000 +2.727852 -3.933222 4.100000 +2.000000 -4.000000 4.100000 +-1.590990 1.590990 -9.000000 +-3.254259 1.288332 -9.000000 +-1.883240 1.231222 -9.000000 +-3.441569 0.636871 -9.000000 +-2.092024 0.828213 -9.000000 +-3.500000 0.000000 -9.000000 +-2.212437 0.409417 -9.000000 +-3.441569 -0.636871 -9.000000 +-2.250000 0.000000 -9.000000 +-3.254259 -1.288332 -9.000000 +-2.212437 -0.409417 -9.000000 +-2.929484 -1.915234 -9.000000 +-2.092024 -0.828213 -9.000000 +-2.474874 -2.474874 -9.000000 +-1.883240 -1.231222 -9.000000 +-1.915234 -2.929484 -9.000000 +-1.590990 -1.590990 -9.000000 +-1.288332 -3.254259 -9.000000 +-1.231222 -1.883240 -9.000000 +-0.636871 -3.441569 -9.000000 +-0.828213 -2.092024 -9.000000 +0.000000 -3.500000 -9.000000 +-0.409417 -2.212437 -9.000000 +0.636871 -3.441569 -9.000000 +0.000000 -2.250000 -9.000000 +1.288332 -3.254259 -9.000000 +0.409417 -2.212437 -9.000000 +1.915234 -2.929484 -9.000000 +0.828213 -2.092024 -9.000000 +2.474874 -2.474874 -9.000000 +1.231222 -1.883240 -9.000000 +2.929484 -1.915234 -9.000000 +1.590990 -1.590990 -9.000000 +3.254259 -1.288332 -9.000000 +1.883240 -1.231222 -9.000000 +3.441569 -0.636871 -9.000000 +2.092024 -0.828213 -9.000000 +3.500000 0.000000 -9.000000 +2.212437 -0.409417 -9.000000 +3.441569 0.636871 -9.000000 +2.250000 0.000000 -9.000000 +3.254259 1.288332 -9.000000 +2.212437 0.409417 -9.000000 +2.929484 1.915234 -9.000000 +2.092024 0.828213 -9.000000 +2.474874 2.474874 -9.000000 +1.883240 1.231222 -9.000000 +1.915234 2.929484 -9.000000 +1.590990 1.590990 -9.000000 +1.288332 3.254259 -9.000000 +1.231222 1.883240 -9.000000 +0.636871 3.441569 -9.000000 +0.828213 2.092024 -9.000000 +0.000000 3.500000 -9.000000 +0.409417 2.212437 -9.000000 +-0.636871 3.441569 -9.000000 +0.000000 2.250000 -9.000000 +-1.288332 3.254259 -9.000000 +-0.409417 2.212437 -9.000000 +-1.915234 2.929484 -9.000000 +-0.828213 2.092024 -9.000000 +-2.474874 2.474874 -9.000000 +-1.231222 1.883240 -9.000000 +-2.929484 1.915234 -9.000000 +-4.000000 0.000000 -8.500000 +-3.500000 0.000000 -9.000000 +3.500000 0.000000 -9.000000 +4.000000 0.000000 -8.500000 +3.441569 -0.636871 -9.000000 +3.933222 -0.727852 -8.500000 +3.254259 -1.288332 -9.000000 +3.719153 -1.472379 -8.500000 +2.929484 -1.915234 -9.000000 +3.347982 -2.188839 -8.500000 +2.474874 -2.474874 -9.000000 +2.828427 -2.828427 -8.500000 +1.915234 -2.929484 -9.000000 +2.188839 -3.347982 -8.500000 +1.288332 -3.254259 -9.000000 +1.472379 -3.719153 -8.500000 +0.636871 -3.441569 -9.000000 +0.727852 -3.933222 -8.500000 +0.000000 -3.500000 -9.000000 +0.000000 -4.000000 -8.500000 +-0.636871 -3.441569 -9.000000 +-0.727852 -3.933222 -8.500000 +-1.288332 -3.254259 -9.000000 +-1.915234 -2.929484 -9.000000 +-1.472379 -3.719153 -8.500000 +-2.188839 -3.347982 -8.500000 +-2.474874 -2.474874 -9.000000 +-2.929484 -1.915234 -9.000000 +-2.828427 -2.828427 -8.500000 +-3.254259 -1.288332 -9.000000 +-3.347982 -2.188839 -8.500000 +-3.719153 -1.472379 -8.500000 +-3.441569 -0.636871 -9.000000 +-3.933222 -0.727852 -8.500000 +-3.939231 0.694593 -6.500000 +-2.215817 0.390708 -6.500000 +-2.215817 0.390708 -7.500000 +-3.939231 0.694593 -7.500000 +3.939231 0.694593 -6.500000 +3.939231 0.694593 -7.500000 +2.215817 0.390708 -7.500000 +2.215817 0.390708 -6.500000 +-2.215817 -0.390708 -7.500000 +-2.215817 -0.390708 -6.500000 +-3.939231 -0.694593 -6.500000 +-3.939231 -0.694593 -7.500000 +2.215817 -0.390708 -7.500000 +3.939231 -0.694593 -7.500000 +3.939231 -0.694593 -6.500000 +2.215817 -0.390708 -6.500000 +-0.750000 3.929058 -6.500000 +-0.750000 3.929058 -7.500000 +-0.750000 2.121320 -7.500000 +-0.750000 2.121320 -6.500000 +0.750000 2.121320 -6.500000 +0.750000 2.121320 -7.500000 +0.750000 3.929058 -7.500000 +0.750000 3.929058 -6.500000 +0.750000 -2.121320 -6.500000 +0.750000 -3.929058 -6.500000 +0.750000 -3.929058 -7.500000 +0.750000 -2.121320 -7.500000 +-0.750000 -2.121320 -6.500000 +-0.750000 -2.121320 -7.500000 +-0.750000 -3.929058 -7.500000 +-0.750000 -3.929058 -6.500000 + + + + + + + + + + + +-0.695302 0.128667 -0.707107 +-0.707107 0.000000 -0.707107 +-0.707107 0.000000 -0.707107 +0.707107 0.000000 -0.707107 +0.695302 0.128667 -0.707107 +0.707107 0.000000 -0.707107 +0.695302 0.128667 -0.707107 +0.695302 0.128667 -0.707107 +0.707107 0.000000 -0.707107 +0.657460 0.260282 -0.707107 +0.695302 0.128667 -0.707107 +0.695302 0.128667 -0.707107 +0.657460 0.260282 -0.707107 +0.657460 0.260282 -0.707107 +0.695302 0.128667 -0.707107 +0.591845 0.386936 -0.707107 +0.657460 0.260282 -0.707107 +0.657460 0.260282 -0.707107 +0.591845 0.386936 -0.707107 +0.591845 0.386936 -0.707107 +0.657460 0.260282 -0.707107 +0.500000 0.500000 -0.707107 +0.591845 0.386936 -0.707107 +0.591845 0.386936 -0.707107 +0.500000 0.500000 -0.707107 +0.500000 0.500000 -0.707107 +0.591845 0.386936 -0.707107 +0.386936 0.591845 -0.707107 +0.500000 0.500000 -0.707107 +0.500000 0.500000 -0.707107 +0.386936 0.591845 -0.707107 +0.386936 0.591845 -0.707107 +0.500000 0.500000 -0.707107 +0.260282 0.657460 -0.707107 +0.386936 0.591845 -0.707107 +0.386936 0.591845 -0.707107 +0.260282 0.657460 -0.707107 +0.260282 0.657460 -0.707107 +0.386936 0.591845 -0.707107 +0.128667 0.695302 -0.707107 +0.260282 0.657460 -0.707107 +0.260282 0.657460 -0.707107 +0.128667 0.695302 -0.707107 +0.128667 0.695302 -0.707107 +0.260282 0.657460 -0.707107 +0.000000 0.707107 -0.707107 +0.128667 0.695302 -0.707107 +0.128667 0.695302 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 +0.128667 0.695302 -0.707107 +-0.128667 0.695302 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 +-0.128667 0.695302 -0.707107 +-0.128667 0.695302 -0.707107 +0.000000 0.707107 -0.707107 +-0.260282 0.657460 -0.707107 +-0.128667 0.695302 -0.707107 +-0.128667 0.695302 -0.707107 +-0.260282 0.657460 -0.707107 +-0.260282 0.657460 -0.707107 +-0.128667 0.695302 -0.707107 +-0.386936 0.591845 -0.707107 +-0.260282 0.657460 -0.707107 +-0.260282 0.657460 -0.707107 +-0.386936 0.591845 -0.707107 +-0.386936 0.591845 -0.707107 +-0.260282 0.657460 -0.707107 +-0.500000 0.500000 -0.707107 +-0.386936 0.591845 -0.707107 +-0.386936 0.591845 -0.707107 +-0.500000 0.500000 -0.707107 +-0.500000 0.500000 -0.707107 +-0.386936 0.591845 -0.707107 +-0.591845 0.386936 -0.707107 +-0.500000 0.500000 -0.707107 +-0.500000 0.500000 -0.707107 +-0.591845 0.386936 -0.707107 +-0.591845 0.386936 -0.707107 +-0.500000 0.500000 -0.707107 +-0.657460 0.260282 -0.707107 +-0.591845 0.386936 -0.707107 +-0.591845 0.386936 -0.707107 +-0.657460 0.260282 -0.707107 +-0.657460 0.260282 -0.707107 +-0.591845 0.386936 -0.707107 +-0.695302 0.128667 -0.707107 +-0.657460 0.260282 -0.707107 +-0.657460 0.260282 -0.707107 +-0.695302 0.128667 -0.707107 +-0.695302 0.128667 -0.707107 +-0.657460 0.260282 -0.707107 +-0.707107 0.000000 -0.707107 +-0.695302 0.128667 -0.707107 +-0.695302 0.128667 -0.707107 +-1.000000 0.000000 0.000000 +-0.978781 -0.204909 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.204909 -0.978781 0.000000 +0.000000 -1.000000 0.000000 +-0.204909 -0.978781 0.000000 +-0.204909 -0.978781 0.000000 +0.000000 -1.000000 0.000000 +-0.204909 -0.978781 0.000000 +-0.397177 -0.917742 0.000000 +-0.204909 -0.978781 0.000000 +-0.397177 -0.917742 0.000000 +-0.397177 -0.917742 0.000000 +-0.204909 -0.978781 0.000000 +-0.566635 -0.823969 0.000000 +-0.397177 -0.917742 0.000000 +-0.397177 -0.917742 0.000000 +-0.566635 -0.823969 0.000000 +-0.566635 -0.823969 0.000000 +-0.397177 -0.917742 0.000000 +-0.566635 -0.823969 0.000000 +-0.707107 -0.707107 0.000000 +-0.566635 -0.823969 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.566635 -0.823969 0.000000 +-0.823969 -0.566635 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.823969 -0.566635 0.000000 +-0.823969 -0.566635 0.000000 +-0.707107 -0.707107 0.000000 +-0.917742 -0.397177 0.000000 +-0.823969 -0.566635 0.000000 +-0.823969 -0.566635 0.000000 +-0.917742 -0.397177 0.000000 +-0.917742 -0.397177 0.000000 +-0.823969 -0.566635 0.000000 +-0.978781 -0.204909 0.000000 +-0.917742 -0.397177 0.000000 +-0.917742 -0.397177 0.000000 +-0.978781 -0.204909 0.000000 +-0.978781 -0.204909 0.000000 +-0.917742 -0.397177 0.000000 +-0.978781 -0.204909 0.000000 +-1.000000 0.000000 0.000000 +-0.978781 -0.204909 0.000000 +-0.978781 -0.204909 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.204909 -0.978781 0.000000 +0.000000 -1.000000 0.000000 +-0.204909 -0.978781 0.000000 +-0.204909 -0.978781 0.000000 +0.000000 -1.000000 0.000000 +-0.204909 -0.978781 0.000000 +-0.397177 -0.917742 0.000000 +-0.204909 -0.978781 0.000000 +-0.397177 -0.917742 0.000000 +-0.397177 -0.917742 0.000000 +-0.204909 -0.978781 0.000000 +-0.566635 -0.823969 0.000000 +-0.397177 -0.917742 0.000000 +-0.397177 -0.917742 0.000000 +-0.566635 -0.823969 0.000000 +-0.566635 -0.823969 0.000000 +-0.397177 -0.917742 0.000000 +-0.707107 -0.707107 0.000000 +-0.566635 -0.823969 0.000000 +-0.566635 -0.823969 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.566635 -0.823969 0.000000 +-0.707107 -0.707107 0.000000 +-0.823969 -0.566635 0.000000 +-0.707107 -0.707107 0.000000 +-0.823969 -0.566635 0.000000 +-0.823969 -0.566635 0.000000 +-0.707107 -0.707107 0.000000 +-0.823969 -0.566635 0.000000 +-0.917742 -0.397177 0.000000 +-0.823969 -0.566635 0.000000 +-0.917742 -0.397177 0.000000 +-0.917742 -0.397177 0.000000 +-0.823969 -0.566635 0.000000 +-0.978781 -0.204909 0.000000 +-0.917742 -0.397177 0.000000 +-0.917742 -0.397177 0.000000 +-0.978781 -0.204909 0.000000 +-0.978781 -0.204909 0.000000 +-0.917742 -0.397177 0.000000 +-1.000000 0.000000 0.000000 +-0.978781 -0.204909 0.000000 +-0.978781 -0.204909 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.181963 0.983305 0.000000 +-0.333333 0.942809 0.000000 +-0.333333 0.942809 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.333333 0.942809 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.333333 0.942809 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.333333 0.942809 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.333333 0.942809 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.984808 0.173648 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.984808 0.173648 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.984808 0.173648 0.000000 +-1.000000 0.000000 0.000000 +-0.984808 0.173648 0.000000 +-0.984808 0.173648 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.984808 0.173648 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.333333 0.942809 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.333333 0.942809 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.984808 0.173648 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.984808 0.173648 0.000000 +0.984808 0.173648 0.000000 +0.983305 0.181963 0.000000 +0.984808 0.173648 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.984808 0.173648 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.333333 0.942809 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.333333 0.942809 0.000000 +0.368095 0.929788 0.000000 +0.333333 0.942809 0.000000 +0.181963 0.983305 0.000000 +0.333333 0.942809 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.333333 0.942809 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.333333 0.942809 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.187500 0.982265 0.000000 +-0.181963 0.983305 0.000000 +-0.187500 0.982265 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.187500 0.982265 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.187500 0.982265 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.187500 0.982265 0.000000 +0.368095 0.929788 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.984808 0.173648 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.984808 0.173648 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.984808 0.173648 0.000000 +1.000000 0.000000 0.000000 +0.984808 0.173648 0.000000 +0.984808 0.173648 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.984808 0.173648 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.187500 0.982265 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.187500 0.982265 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.984808 0.173648 0.000000 +-0.983305 0.181963 0.000000 +0.187500 0.982265 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +-1.000000 0.000000 0.000000 +-0.984808 0.173648 0.000000 +-0.984808 0.173648 0.000000 +-0.983305 0.181963 0.000000 +-0.984808 0.173648 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.984808 0.173648 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.187500 0.982265 0.000000 +-0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +-0.187500 0.982265 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.187500 0.982265 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.187500 0.982265 0.000000 +0.187500 0.982265 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.187500 0.982265 0.000000 +0.000000 1.000000 0.000000 +-0.187500 0.982265 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.187500 0.982265 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.181963 -0.983305 0.000000 +-0.187500 -0.982265 0.000000 +-0.187500 -0.982265 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.187500 -0.982265 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.187500 -0.982265 0.000000 +-0.368095 -0.929788 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.187500 -0.982265 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.187500 -0.982265 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.984808 -0.173648 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.984808 -0.173648 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.984808 -0.173648 0.000000 +-1.000000 0.000000 0.000000 +-0.984808 -0.173648 0.000000 +-0.984808 -0.173648 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.984808 -0.173648 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.187500 -0.982265 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.187500 -0.982265 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.984808 -0.173648 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.984808 -0.173648 0.000000 +0.983305 -0.181963 0.000000 +-0.187500 -0.982265 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +1.000000 0.000000 0.000000 +0.984808 -0.173648 0.000000 +0.984808 -0.173648 0.000000 +0.983305 -0.181963 0.000000 +0.984808 -0.173648 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.984808 -0.173648 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.187500 -0.982265 0.000000 +0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +0.187500 -0.982265 0.000000 +0.181963 -0.983305 0.000000 +0.187500 -0.982265 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.187500 -0.982265 0.000000 +0.000000 -1.000000 0.000000 +0.187500 -0.982265 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.187500 -0.982265 0.000000 +-0.187500 -0.982265 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.187500 -0.982265 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.333333 -0.942809 0.000000 +0.333333 -0.942809 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.333333 -0.942809 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.333333 -0.942809 0.000000 +0.368095 -0.929788 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.333333 -0.942809 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.333333 -0.942809 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.984808 -0.173648 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.984808 -0.173648 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.984808 -0.173648 0.000000 +1.000000 0.000000 0.000000 +0.984808 -0.173648 0.000000 +0.984808 -0.173648 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.984808 -0.173648 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.333333 -0.942809 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.333333 -0.942809 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.984808 -0.173648 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.984808 -0.173648 0.000000 +-0.984808 -0.173648 0.000000 +-0.983305 -0.181963 0.000000 +-0.984808 -0.173648 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.984808 -0.173648 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.333333 -0.942809 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.333333 -0.942809 0.000000 +-0.368095 -0.929788 0.000000 +-0.333333 -0.942809 0.000000 +-0.181963 -0.983305 0.000000 +-0.333333 -0.942809 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.333333 -0.942809 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.333333 -0.942809 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.978781 0.204909 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.204909 0.978781 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.204909 0.978781 0.000000 +-0.204909 0.978781 0.000000 +0.000000 1.000000 0.000000 +-0.397177 0.917742 0.000000 +-0.204909 0.978781 0.000000 +-0.204909 0.978781 0.000000 +-0.397177 0.917742 0.000000 +-0.397177 0.917742 0.000000 +-0.204909 0.978781 0.000000 +-0.566635 0.823969 0.000000 +-0.397177 0.917742 0.000000 +-0.397177 0.917742 0.000000 +-0.566635 0.823969 0.000000 +-0.566635 0.823969 0.000000 +-0.397177 0.917742 0.000000 +-0.707107 0.707107 0.000000 +-0.566635 0.823969 0.000000 +-0.566635 0.823969 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.566635 0.823969 0.000000 +-0.823969 0.566635 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.823969 0.566635 0.000000 +-0.823969 0.566635 0.000000 +-0.707107 0.707107 0.000000 +-0.917742 0.397177 0.000000 +-0.823969 0.566635 0.000000 +-0.823969 0.566635 0.000000 +-0.917742 0.397177 0.000000 +-0.917742 0.397177 0.000000 +-0.823969 0.566635 0.000000 +-0.917742 0.397177 0.000000 +-0.978781 0.204909 0.000000 +-0.917742 0.397177 0.000000 +-0.978781 0.204909 0.000000 +-0.978781 0.204909 0.000000 +-0.917742 0.397177 0.000000 +-1.000000 0.000000 0.000000 +-0.978781 0.204909 0.000000 +-0.978781 0.204909 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 1.000000 0.000000 +-0.204909 0.978781 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.978781 0.204909 0.000000 +-1.000000 0.000000 0.000000 +-0.978781 0.204909 0.000000 +-0.978781 0.204909 0.000000 +-1.000000 0.000000 0.000000 +-0.978781 0.204909 0.000000 +-0.917742 0.397177 0.000000 +-0.978781 0.204909 0.000000 +-0.917742 0.397177 0.000000 +-0.917742 0.397177 0.000000 +-0.978781 0.204909 0.000000 +-0.917742 0.397177 0.000000 +-0.823969 0.566635 0.000000 +-0.917742 0.397177 0.000000 +-0.823969 0.566635 0.000000 +-0.823969 0.566635 0.000000 +-0.917742 0.397177 0.000000 +-0.823969 0.566635 0.000000 +-0.707107 0.707107 0.000000 +-0.823969 0.566635 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.823969 0.566635 0.000000 +-0.566635 0.823969 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.566635 0.823969 0.000000 +-0.566635 0.823969 0.000000 +-0.707107 0.707107 0.000000 +-0.566635 0.823969 0.000000 +-0.397177 0.917742 0.000000 +-0.566635 0.823969 0.000000 +-0.397177 0.917742 0.000000 +-0.397177 0.917742 0.000000 +-0.566635 0.823969 0.000000 +-0.397177 0.917742 0.000000 +-0.204909 0.978781 0.000000 +-0.397177 0.917742 0.000000 +-0.204909 0.978781 0.000000 +-0.204909 0.978781 0.000000 +-0.397177 0.917742 0.000000 +-0.204909 0.978781 0.000000 +0.000000 1.000000 0.000000 +-0.204909 0.978781 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.695302 -0.128667 -0.707107 +-0.707107 0.000000 -0.707107 +-0.707107 0.000000 -0.707107 +0.695302 -0.128667 -0.707107 +0.707107 0.000000 -0.707107 +0.707107 0.000000 -0.707107 +0.695302 -0.128667 -0.707107 +0.695302 -0.128667 -0.707107 +0.707107 0.000000 -0.707107 +0.657460 -0.260282 -0.707107 +0.695302 -0.128667 -0.707107 +0.695302 -0.128667 -0.707107 +0.657460 -0.260282 -0.707107 +0.657460 -0.260282 -0.707107 +0.695302 -0.128667 -0.707107 +0.591845 -0.386936 -0.707107 +0.657460 -0.260282 -0.707107 +0.657460 -0.260282 -0.707107 +0.591845 -0.386936 -0.707107 +0.591845 -0.386936 -0.707107 +0.657460 -0.260282 -0.707107 +0.500000 -0.500000 -0.707107 +0.591845 -0.386936 -0.707107 +0.591845 -0.386936 -0.707107 +0.500000 -0.500000 -0.707107 +0.500000 -0.500000 -0.707107 +0.591845 -0.386936 -0.707107 +0.386936 -0.591845 -0.707107 +0.500000 -0.500000 -0.707107 +0.500000 -0.500000 -0.707107 +0.386936 -0.591845 -0.707107 +0.386936 -0.591845 -0.707107 +0.500000 -0.500000 -0.707107 +0.260282 -0.657460 -0.707107 +0.386936 -0.591845 -0.707107 +0.386936 -0.591845 -0.707107 +0.260282 -0.657460 -0.707107 +0.260282 -0.657460 -0.707107 +0.386936 -0.591845 -0.707107 +0.128667 -0.695302 -0.707107 +0.260282 -0.657460 -0.707107 +0.260282 -0.657460 -0.707107 +0.128667 -0.695302 -0.707107 +0.128667 -0.695302 -0.707107 +0.260282 -0.657460 -0.707107 +0.000000 -0.707107 -0.707107 +0.128667 -0.695302 -0.707107 +0.128667 -0.695302 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.128667 -0.695302 -0.707107 +-0.128667 -0.695302 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +-0.128667 -0.695302 -0.707107 +-0.128667 -0.695302 -0.707107 +0.000000 -0.707107 -0.707107 +-0.260282 -0.657460 -0.707107 +-0.128667 -0.695302 -0.707107 +-0.128667 -0.695302 -0.707107 +-0.260282 -0.657460 -0.707107 +-0.260282 -0.657460 -0.707107 +-0.128667 -0.695302 -0.707107 +-0.260282 -0.657460 -0.707107 +-0.386936 -0.591845 -0.707107 +-0.260282 -0.657460 -0.707107 +-0.386936 -0.591845 -0.707107 +-0.386936 -0.591845 -0.707107 +-0.260282 -0.657460 -0.707107 +-0.500000 -0.500000 -0.707107 +-0.386936 -0.591845 -0.707107 +-0.386936 -0.591845 -0.707107 +-0.500000 -0.500000 -0.707107 +-0.500000 -0.500000 -0.707107 +-0.386936 -0.591845 -0.707107 +-0.500000 -0.500000 -0.707107 +-0.591845 -0.386936 -0.707107 +-0.500000 -0.500000 -0.707107 +-0.591845 -0.386936 -0.707107 +-0.591845 -0.386936 -0.707107 +-0.500000 -0.500000 -0.707107 +-0.591845 -0.386936 -0.707107 +-0.657460 -0.260282 -0.707107 +-0.591845 -0.386936 -0.707107 +-0.657460 -0.260282 -0.707107 +-0.657460 -0.260282 -0.707107 +-0.591845 -0.386936 -0.707107 +-0.695302 -0.128667 -0.707107 +-0.657460 -0.260282 -0.707107 +-0.657460 -0.260282 -0.707107 +-0.695302 -0.128667 -0.707107 +-0.695302 -0.128667 -0.707107 +-0.657460 -0.260282 -0.707107 +-0.707107 0.000000 -0.707107 +-0.695302 -0.128667 -0.707107 +-0.695302 -0.128667 -0.707107 +0.173648 0.984808 0.000000 +0.173648 0.984808 0.000000 +0.173648 0.984808 0.000000 +0.173648 0.984808 0.000000 +0.173648 0.984808 0.000000 +0.173648 0.984808 0.000000 +-0.173648 0.984808 0.000000 +-0.173648 0.984808 0.000000 +-0.173648 0.984808 0.000000 +-0.173648 0.984808 0.000000 +-0.173648 0.984808 0.000000 +-0.173648 0.984808 0.000000 +0.173648 -0.984808 0.000000 +0.173648 -0.984808 0.000000 +0.173648 -0.984808 0.000000 +0.173648 -0.984808 0.000000 +0.173648 -0.984808 0.000000 +0.173648 -0.984808 0.000000 +-0.173648 -0.984808 0.000000 +-0.173648 -0.984808 0.000000 +-0.173648 -0.984808 0.000000 +-0.173648 -0.984808 0.000000 +-0.173648 -0.984808 0.000000 +-0.173648 -0.984808 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 + + + + + + + + + + + +0.468678 0.537843 +0.468678 0.542883 +0.537341 0.542883 +0.534759 0.542883 +0.534759 0.537843 +0.537341 0.537843 +0.540187 0.542883 +0.540187 0.537843 +0.543405 0.542883 +0.543405 0.537843 +0.547127 0.542883 +0.547127 0.537843 +0.551485 0.542883 +0.551485 0.537843 +0.556528 0.542883 +0.556528 0.537843 +0.562104 0.542883 +0.562104 0.537843 +0.567799 0.542883 +0.567799 0.537843 +0.441333 0.542883 +0.441333 0.537843 +0.446910 0.542883 +0.446910 0.537843 +0.451953 0.542883 +0.451953 0.537843 +0.456310 0.542883 +0.456310 0.537843 +0.460033 0.542883 +0.460033 0.537843 +0.463251 0.542883 +0.463251 0.537843 +0.466096 0.542883 +0.466096 0.537843 +0.435638 0.542883 +0.435638 0.537843 +0.435638 0.542883 +0.470616 0.669873 +0.468678 0.669873 +0.484387 0.659794 +0.488183 0.659794 +0.488183 0.669873 +0.481267 0.659794 +0.484387 0.669873 +0.481267 0.669873 +0.478682 0.659794 +0.476510 0.659794 +0.478682 0.669873 +0.476510 0.669873 +0.474524 0.659794 +0.474524 0.669873 +0.472562 0.659794 +0.472562 0.669873 +0.470616 0.659794 +0.468678 0.659794 +0.468678 0.646692 +0.468678 0.628551 +0.484387 0.628551 +0.488183 0.628551 +0.488183 0.646692 +0.481267 0.628551 +0.484387 0.646692 +0.481267 0.646692 +0.478682 0.628551 +0.478682 0.646692 +0.476510 0.628551 +0.474524 0.628551 +0.476510 0.646692 +0.472562 0.628551 +0.474524 0.646692 +0.472562 0.646692 +0.470616 0.628551 +0.470616 0.646692 +0.466096 0.646692 +0.468678 0.646692 +0.537341 0.659794 +0.534759 0.659794 +0.534759 0.646692 +0.537341 0.646692 +0.540187 0.659794 +0.540187 0.646692 +0.543405 0.659794 +0.543405 0.646692 +0.547127 0.659794 +0.547127 0.646692 +0.551485 0.659794 +0.551485 0.646692 +0.556528 0.659794 +0.556528 0.646692 +0.562104 0.659794 +0.562104 0.646692 +0.567799 0.659794 +0.567799 0.646692 +0.441333 0.659794 +0.446910 0.659794 +0.441333 0.646692 +0.451953 0.659794 +0.446910 0.646692 +0.456310 0.659794 +0.451953 0.646692 +0.460033 0.659794 +0.456310 0.646692 +0.463251 0.659794 +0.460033 0.646692 +0.466096 0.659794 +0.463251 0.646692 +0.468678 0.659794 +0.435638 0.659794 +0.435638 0.646692 +0.435638 0.659794 +0.511975 0.563040 +0.485404 0.552961 +0.490447 0.537843 +0.490447 0.552961 +0.496023 0.537843 +0.512990 0.552961 +0.518034 0.537843 +0.511975 0.552961 +0.512990 0.537843 +0.522391 0.537843 +0.518034 0.552961 +0.526113 0.537843 +0.522391 0.552961 +0.529331 0.537843 +0.526113 0.552961 +0.532177 0.537843 +0.529331 0.552961 +0.534759 0.537843 +0.532177 0.552961 +0.534759 0.669873 +0.532298 0.552961 +0.532177 0.669873 +0.532298 0.563040 +0.485404 0.537843 +0.481046 0.552961 +0.468678 0.537843 +0.468678 0.669873 +0.532177 0.563040 +0.529331 0.669873 +0.529331 0.563040 +0.526113 0.669873 +0.526113 0.563040 +0.522391 0.669873 +0.522391 0.563040 +0.518034 0.669873 +0.518034 0.563040 +0.512990 0.669873 +0.512990 0.563040 +0.507414 0.669873 +0.481046 0.537843 +0.477324 0.552961 +0.477324 0.537843 +0.474106 0.552961 +0.471260 0.552961 +0.474106 0.537843 +0.471260 0.537843 +0.471140 0.552961 +0.471140 0.563040 +0.471260 0.563040 +0.474106 0.563040 +0.471260 0.669873 +0.477324 0.563040 +0.474106 0.669873 +0.481046 0.563040 +0.477324 0.669873 +0.481046 0.669873 +0.485404 0.563040 +0.485404 0.669873 +0.490447 0.563040 +0.491462 0.563040 +0.490447 0.669873 +0.491462 0.552961 +0.496023 0.669873 +0.501719 0.537843 +0.501719 0.669873 +0.507414 0.537843 +0.441504 0.552961 +0.468678 0.542883 +0.468678 0.628551 +0.451953 0.552961 +0.446910 0.542883 +0.446910 0.552961 +0.441333 0.542883 +0.551485 0.542883 +0.556528 0.552961 +0.551485 0.552961 +0.547127 0.542883 +0.534759 0.628551 +0.534759 0.542883 +0.556528 0.542883 +0.561934 0.552961 +0.547127 0.552961 +0.543405 0.542883 +0.540187 0.542883 +0.543405 0.552961 +0.540187 0.552961 +0.537341 0.542883 +0.537341 0.552961 +0.537220 0.552961 +0.537341 0.628551 +0.537220 0.563040 +0.540187 0.628551 +0.537341 0.563040 +0.540187 0.563040 +0.543405 0.628551 +0.543405 0.563040 +0.547127 0.628551 +0.551485 0.628551 +0.547127 0.563040 +0.556528 0.628551 +0.551485 0.563040 +0.556528 0.563040 +0.562104 0.628551 +0.451953 0.542883 +0.456310 0.552961 +0.456310 0.542883 +0.460033 0.552961 +0.460033 0.542883 +0.463251 0.552961 +0.463251 0.542883 +0.466096 0.552961 +0.466096 0.542883 +0.466217 0.552961 +0.567799 0.628551 +0.466217 0.563040 +0.466096 0.563040 +0.463251 0.563040 +0.466096 0.628551 +0.463251 0.628551 +0.460033 0.563040 +0.460033 0.628551 +0.456310 0.563040 +0.456310 0.628551 +0.451953 0.563040 +0.451953 0.628551 +0.446910 0.563040 +0.446910 0.628551 +0.441504 0.563040 +0.441333 0.628551 +0.562104 0.542883 +0.561934 0.563040 +0.567799 0.542883 +0.435638 0.628551 +0.435638 0.542883 +0.435638 0.628551 +0.435638 0.542883 +0.532618 0.650865 +0.543303 0.625469 +0.544948 0.616236 +0.540684 0.634546 +0.525058 0.616236 +0.537097 0.643125 +0.506017 0.640427 +0.509361 0.668870 +0.512127 0.637550 +0.515539 0.666533 +0.521627 0.662732 +0.517719 0.632193 +0.527396 0.657472 +0.522161 0.624802 +0.522161 0.624802 +0.532618 0.650865 +0.537097 0.643125 +0.525058 0.616236 +0.543303 0.625469 +0.525058 0.616236 +0.540684 0.634546 +0.522161 0.624802 +0.540684 0.634546 +0.522161 0.624802 +0.515539 0.666533 +0.506017 0.640427 +0.515539 0.666533 +0.512127 0.637550 +0.521627 0.662732 +0.512127 0.637550 +0.527396 0.657472 +0.512127 0.637550 +0.527396 0.657472 +0.517719 0.632193 +0.532618 0.650865 +0.517719 0.632193 +0.537097 0.564591 +0.525058 0.591480 +0.544948 0.591480 +0.543303 0.582247 +0.522161 0.582914 +0.540684 0.573170 +0.515539 0.541183 +0.509361 0.538846 +0.506017 0.567289 +0.521627 0.544984 +0.527396 0.550244 +0.512127 0.570167 +0.532618 0.556851 +0.517719 0.575523 +0.532618 0.556851 +0.522161 0.582914 +0.537097 0.564591 +0.543303 0.582247 +0.525058 0.591480 +0.540684 0.573170 +0.525058 0.591480 +0.540684 0.573170 +0.522161 0.582914 +0.522161 0.582914 +0.506017 0.567289 +0.515539 0.541183 +0.512127 0.570167 +0.515539 0.541183 +0.512127 0.570167 +0.521627 0.544984 +0.512127 0.570167 +0.527396 0.550244 +0.517719 0.575523 +0.527396 0.550244 +0.517719 0.575523 +0.532618 0.556851 +0.537097 0.643125 +0.525058 0.616236 +0.544948 0.616236 +0.543303 0.625469 +0.522161 0.624802 +0.540684 0.634546 +0.515539 0.666533 +0.509361 0.668870 +0.506017 0.640427 +0.521627 0.662732 +0.527396 0.657472 +0.512127 0.637550 +0.532618 0.650865 +0.517719 0.632193 +0.532618 0.650865 +0.522161 0.624802 +0.537097 0.643125 +0.543303 0.625469 +0.525058 0.616236 +0.540684 0.634546 +0.525058 0.616236 +0.540684 0.634546 +0.522161 0.624802 +0.522161 0.624802 +0.506017 0.640427 +0.515539 0.666533 +0.512127 0.637550 +0.515539 0.666533 +0.512127 0.637550 +0.521627 0.662732 +0.512127 0.637550 +0.527396 0.657472 +0.517719 0.632193 +0.527396 0.657472 +0.517719 0.632193 +0.532618 0.650865 +0.532618 0.556851 +0.543303 0.582247 +0.544948 0.591480 +0.540684 0.573170 +0.525058 0.591480 +0.537097 0.564591 +0.506017 0.567289 +0.509361 0.538846 +0.512127 0.570167 +0.515539 0.541183 +0.521627 0.544984 +0.517719 0.575523 +0.527396 0.550244 +0.522161 0.582914 +0.522161 0.582914 +0.532618 0.556851 +0.537097 0.564591 +0.525058 0.591480 +0.543303 0.582247 +0.525058 0.591480 +0.540684 0.573170 +0.522161 0.582914 +0.540684 0.573170 +0.522161 0.582914 +0.515539 0.541183 +0.506017 0.567289 +0.515539 0.541183 +0.512127 0.570167 +0.521627 0.544984 +0.512127 0.570167 +0.527396 0.550244 +0.512127 0.570167 +0.527396 0.550244 +0.517719 0.575523 +0.532618 0.556851 +0.517719 0.575523 +0.470819 0.556851 +0.460134 0.582247 +0.458489 0.591480 +0.462753 0.573170 +0.478379 0.591480 +0.466341 0.564591 +0.497420 0.567289 +0.494076 0.538846 +0.491310 0.570167 +0.487898 0.541183 +0.481811 0.544984 +0.485719 0.575523 +0.476042 0.550244 +0.481277 0.582914 +0.481277 0.582914 +0.470819 0.556851 +0.466341 0.564591 +0.478379 0.591480 +0.460134 0.582247 +0.478379 0.591480 +0.462753 0.573170 +0.481277 0.582914 +0.462753 0.573170 +0.481277 0.582914 +0.487898 0.541183 +0.497420 0.567289 +0.487898 0.541183 +0.491310 0.570167 +0.481811 0.544984 +0.491310 0.570167 +0.476042 0.550244 +0.491310 0.570167 +0.476042 0.550244 +0.485719 0.575523 +0.470819 0.556851 +0.485719 0.575523 +0.466341 0.643125 +0.478379 0.616236 +0.458489 0.616236 +0.460134 0.625469 +0.481277 0.624802 +0.462753 0.634546 +0.487898 0.666533 +0.494076 0.668870 +0.497420 0.640427 +0.481811 0.662732 +0.476042 0.657473 +0.491310 0.637550 +0.470819 0.650865 +0.485719 0.632193 +0.470819 0.650865 +0.481277 0.624802 +0.466341 0.643125 +0.460134 0.625469 +0.478379 0.616236 +0.462753 0.634546 +0.478379 0.616236 +0.462753 0.634546 +0.481277 0.624802 +0.481277 0.624802 +0.497420 0.640427 +0.487898 0.666533 +0.491310 0.637550 +0.487898 0.666533 +0.491310 0.637550 +0.481811 0.662732 +0.491310 0.637550 +0.476042 0.657473 +0.485719 0.632193 +0.476042 0.657473 +0.485719 0.632193 +0.470819 0.650865 +0.466341 0.564591 +0.478379 0.591480 +0.458489 0.591480 +0.460134 0.582247 +0.481277 0.582914 +0.462753 0.573170 +0.487898 0.541183 +0.494076 0.538846 +0.497420 0.567289 +0.481811 0.544984 +0.476042 0.550244 +0.491310 0.570167 +0.470819 0.556851 +0.485719 0.575523 +0.470819 0.556851 +0.481277 0.582914 +0.466341 0.564591 +0.460134 0.582247 +0.478379 0.591480 +0.462753 0.573170 +0.478379 0.591480 +0.462753 0.573170 +0.481277 0.582914 +0.481277 0.582914 +0.497420 0.567289 +0.487898 0.541183 +0.491310 0.570167 +0.487898 0.541183 +0.491310 0.570167 +0.481811 0.544984 +0.491310 0.570167 +0.476042 0.550244 +0.485719 0.575523 +0.476042 0.550244 +0.485719 0.575523 +0.470819 0.556851 +0.470819 0.650865 +0.460134 0.625469 +0.458489 0.616236 +0.462753 0.634546 +0.478379 0.616236 +0.466341 0.643125 +0.497420 0.640427 +0.494076 0.668870 +0.491310 0.637550 +0.487898 0.666533 +0.481811 0.662732 +0.485719 0.632193 +0.476042 0.657473 +0.481277 0.624802 +0.481277 0.624802 +0.470819 0.650865 +0.466341 0.643125 +0.478379 0.616236 +0.460134 0.625469 +0.478379 0.616236 +0.462753 0.634546 +0.481277 0.624802 +0.462753 0.634546 +0.481277 0.624802 +0.487898 0.666533 +0.497420 0.640427 +0.487898 0.666533 +0.491310 0.637550 +0.481811 0.662732 +0.491310 0.637550 +0.476042 0.657473 +0.491310 0.637550 +0.476042 0.657473 +0.485719 0.632193 +0.470819 0.650865 +0.485719 0.632193 +0.495853 0.563040 +0.529331 0.552961 +0.526113 0.542883 +0.485404 0.542883 +0.490447 0.552961 +0.495853 0.552961 +0.490447 0.542883 +0.485404 0.552961 +0.481046 0.542883 +0.468678 0.628551 +0.468678 0.542883 +0.534759 0.542883 +0.534759 0.628551 +0.526113 0.552961 +0.522391 0.542883 +0.522391 0.552961 +0.518034 0.542883 +0.512990 0.542883 +0.518034 0.552961 +0.512990 0.552961 +0.507414 0.542883 +0.481046 0.552961 +0.477324 0.542883 +0.477324 0.552961 +0.474106 0.542883 +0.471260 0.542883 +0.474106 0.552961 +0.471260 0.552961 +0.471140 0.552961 +0.471260 0.628551 +0.471140 0.563040 +0.471260 0.563040 +0.474106 0.628551 +0.474106 0.563040 +0.477324 0.628551 +0.481046 0.628551 +0.477324 0.563040 +0.481046 0.563040 +0.485404 0.628551 +0.485404 0.563040 +0.490447 0.628551 +0.490447 0.563040 +0.496023 0.628551 +0.529331 0.542883 +0.532177 0.552961 +0.532298 0.552961 +0.532177 0.542883 +0.501719 0.628551 +0.532298 0.563040 +0.532177 0.563040 +0.532177 0.628551 +0.529331 0.563040 +0.526113 0.563040 +0.529331 0.628551 +0.522391 0.563040 +0.526113 0.628551 +0.518034 0.563040 +0.522391 0.628551 +0.518034 0.628551 +0.512990 0.563040 +0.512990 0.628551 +0.507584 0.563040 +0.507414 0.628551 +0.501719 0.542883 +0.507584 0.552961 +0.496023 0.542883 +0.445894 0.563040 +0.543405 0.552961 +0.547127 0.537843 +0.451953 0.537843 +0.446910 0.552961 +0.445894 0.552961 +0.446910 0.537843 +0.451953 0.552961 +0.456310 0.537843 +0.543405 0.537843 +0.540187 0.552961 +0.468678 0.669873 +0.468678 0.537843 +0.534759 0.537843 +0.534759 0.669873 +0.547127 0.552961 +0.551485 0.537843 +0.551485 0.552961 +0.556528 0.537843 +0.556528 0.552961 +0.562104 0.537843 +0.456310 0.552961 +0.460033 0.537843 +0.460033 0.552961 +0.463251 0.537843 +0.463251 0.552961 +0.466096 0.537843 +0.466096 0.552961 +0.466217 0.552961 +0.466096 0.669873 +0.466217 0.563040 +0.466096 0.563040 +0.463251 0.669873 +0.463251 0.563040 +0.460033 0.669873 +0.460033 0.563040 +0.456310 0.669873 +0.456310 0.563040 +0.451953 0.669873 +0.451953 0.563040 +0.446910 0.669873 +0.446910 0.563040 +0.441333 0.669873 +0.540187 0.537843 +0.537341 0.552961 +0.537341 0.537843 +0.537220 0.552961 +0.537220 0.563040 +0.537341 0.563040 +0.540187 0.563040 +0.537341 0.669873 +0.543405 0.563040 +0.540187 0.669873 +0.543405 0.669873 +0.547127 0.563040 +0.547127 0.669873 +0.551485 0.563040 +0.551485 0.669873 +0.556528 0.563040 +0.557543 0.563040 +0.556528 0.669873 +0.557543 0.552961 +0.562104 0.669873 +0.567799 0.537843 +0.567799 0.669873 +0.441333 0.537843 +0.435638 0.537843 +0.435638 0.669873 +0.435638 0.537843 +0.460799 0.661165 +0.458444 0.615870 +0.457709 0.603858 +0.545729 0.636865 +0.545729 0.603858 +0.544994 0.615870 +0.460799 0.628158 +0.464883 0.639982 +0.542639 0.628158 +0.544994 0.648878 +0.457709 0.636865 +0.470599 0.650538 +0.458444 0.648878 +0.538555 0.639982 +0.542639 0.661165 +0.538555 0.672989 +0.532838 0.650538 +0.532838 0.683545 +0.525801 0.659112 +0.525801 0.692119 +0.517918 0.698245 +0.517918 0.665238 +0.509727 0.701778 +0.509727 0.668771 +0.501719 0.702880 +0.493711 0.701778 +0.501719 0.669873 +0.485519 0.698245 +0.493711 0.668771 +0.477636 0.692120 +0.470599 0.683545 +0.485519 0.665238 +0.464883 0.672989 +0.477636 0.659112 +0.464883 0.672989 +0.470599 0.650538 +0.460799 0.661165 +0.457709 0.636865 +0.458444 0.615870 +0.544994 0.615870 +0.545729 0.636865 +0.542639 0.628158 +0.545729 0.636865 +0.457709 0.636865 +0.460799 0.628158 +0.457709 0.636865 +0.464883 0.639982 +0.538555 0.639982 +0.545729 0.636865 +0.538555 0.639982 +0.544994 0.648878 +0.458444 0.648878 +0.464883 0.639982 +0.458444 0.648878 +0.470599 0.650538 +0.470599 0.650538 +0.532838 0.650538 +0.544994 0.648878 +0.532838 0.650538 +0.542639 0.661165 +0.532838 0.650538 +0.538555 0.672989 +0.525801 0.659112 +0.538555 0.672989 +0.525801 0.659112 +0.532838 0.683545 +0.517918 0.665238 +0.532838 0.683545 +0.517918 0.665238 +0.525801 0.692119 +0.517918 0.665238 +0.517918 0.698245 +0.509727 0.668771 +0.517918 0.698245 +0.509727 0.668771 +0.509727 0.701778 +0.501719 0.669873 +0.509727 0.701778 +0.501719 0.669873 +0.501719 0.702880 +0.501719 0.669873 +0.493711 0.701778 +0.493711 0.668771 +0.493711 0.701778 +0.493711 0.668771 +0.485519 0.698245 +0.485519 0.665238 +0.485519 0.698245 +0.485519 0.665238 +0.477636 0.692120 +0.485519 0.665238 +0.470599 0.683545 +0.477636 0.659112 +0.470599 0.683545 +0.477636 0.659112 +0.464883 0.672989 +0.542638 0.546551 +0.544994 0.591846 +0.545729 0.603858 +0.457709 0.570851 +0.457709 0.603858 +0.458444 0.591846 +0.542639 0.579558 +0.538555 0.567734 +0.460799 0.579558 +0.458444 0.558838 +0.545729 0.570851 +0.532838 0.557179 +0.544994 0.558838 +0.464883 0.567734 +0.460799 0.546551 +0.464883 0.534727 +0.470599 0.557179 +0.470599 0.524171 +0.477636 0.548604 +0.477636 0.515597 +0.485519 0.509471 +0.485519 0.542478 +0.493710 0.505938 +0.493710 0.538945 +0.501719 0.504836 +0.509727 0.505938 +0.501719 0.537843 +0.517918 0.509471 +0.509727 0.538945 +0.525801 0.515597 +0.532838 0.524171 +0.517918 0.542478 +0.538555 0.534727 +0.525801 0.548604 +0.538555 0.534727 +0.532838 0.557179 +0.542638 0.546551 +0.545729 0.570851 +0.544994 0.591846 +0.458444 0.591846 +0.457709 0.570851 +0.460799 0.579558 +0.457709 0.570851 +0.545729 0.570851 +0.542639 0.579558 +0.545729 0.570851 +0.538555 0.567734 +0.464883 0.567734 +0.457709 0.570851 +0.464883 0.567734 +0.458444 0.558838 +0.544994 0.558838 +0.538555 0.567734 +0.544994 0.558838 +0.532838 0.557179 +0.532838 0.557179 +0.470599 0.557179 +0.458444 0.558838 +0.470599 0.557179 +0.460799 0.546551 +0.470599 0.557179 +0.464883 0.534727 +0.477636 0.548604 +0.464883 0.534727 +0.477636 0.548604 +0.470599 0.524171 +0.485519 0.542478 +0.470599 0.524171 +0.485519 0.542478 +0.477636 0.515597 +0.485519 0.542478 +0.485519 0.509471 +0.493710 0.538945 +0.485519 0.509471 +0.493710 0.538945 +0.493710 0.505938 +0.501719 0.537843 +0.493710 0.505938 +0.501719 0.537843 +0.501719 0.504836 +0.501719 0.537843 +0.509727 0.505938 +0.509727 0.538945 +0.509727 0.505938 +0.509727 0.538945 +0.517918 0.509471 +0.517918 0.542478 +0.517918 0.509471 +0.517918 0.542478 +0.525801 0.515597 +0.517918 0.542478 +0.532838 0.524171 +0.525801 0.548604 +0.532838 0.524171 +0.525801 0.548604 +0.538555 0.534727 +0.534759 0.646692 +0.534759 0.659794 +0.468678 0.659794 +0.468678 0.646692 +0.471260 0.659794 +0.471260 0.646692 +0.474106 0.659794 +0.474106 0.646692 +0.477324 0.659794 +0.477324 0.646692 +0.481046 0.659794 +0.481046 0.646692 +0.485404 0.659794 +0.485404 0.646692 +0.490447 0.659794 +0.490447 0.646692 +0.496023 0.659794 +0.496023 0.646692 +0.501719 0.659794 +0.501719 0.646692 +0.507414 0.659794 +0.507414 0.646692 +0.512990 0.659794 +0.512990 0.646692 +0.518034 0.659794 +0.518034 0.646692 +0.522391 0.659794 +0.522391 0.646692 +0.526113 0.659794 +0.526113 0.646692 +0.529331 0.659794 +0.529331 0.646692 +0.532177 0.659794 +0.532177 0.646692 +0.540125 0.593197 +0.538035 0.582292 +0.544994 0.558838 +0.534411 0.571798 +0.542638 0.546551 +0.538555 0.534727 +0.529337 0.562430 +0.532838 0.524171 +0.523092 0.554820 +0.525801 0.515597 +0.517918 0.509471 +0.516096 0.549384 +0.509727 0.505938 +0.508826 0.546248 +0.501719 0.504836 +0.493710 0.505938 +0.501719 0.545270 +0.485519 0.509471 +0.477636 0.515597 +0.494611 0.546248 +0.470599 0.524171 +0.487341 0.549384 +0.464883 0.534727 +0.460799 0.546551 +0.480345 0.554820 +0.458444 0.558838 +0.474100 0.562430 +0.457709 0.570851 +0.469027 0.571798 +0.465402 0.582292 +0.457709 0.636865 +0.463312 0.593197 +0.462660 0.603858 +0.463312 0.614519 +0.465402 0.625424 +0.458444 0.648878 +0.469027 0.635918 +0.460799 0.661165 +0.464883 0.672989 +0.474100 0.645286 +0.470599 0.683545 +0.480345 0.652896 +0.477636 0.692120 +0.485519 0.698245 +0.487341 0.658333 +0.493711 0.701778 +0.494611 0.661468 +0.501719 0.702880 +0.509727 0.701778 +0.501719 0.662446 +0.517918 0.698245 +0.525801 0.692119 +0.508826 0.661468 +0.532838 0.683545 +0.516096 0.658333 +0.538555 0.672989 +0.542639 0.661165 +0.523092 0.652896 +0.544994 0.648878 +0.529337 0.645286 +0.545729 0.636865 +0.534411 0.635918 +0.538035 0.625424 +0.545729 0.570851 +0.540125 0.614519 +0.540777 0.603858 +0.545729 0.570851 +0.540125 0.593197 +0.538035 0.582292 +0.534411 0.571798 +0.545729 0.570851 +0.534411 0.571798 +0.544994 0.558838 +0.545729 0.570851 +0.529337 0.562430 +0.544994 0.558838 +0.529337 0.562430 +0.542638 0.546551 +0.529337 0.562430 +0.538555 0.534727 +0.523092 0.554820 +0.538555 0.534727 +0.523092 0.554820 +0.532838 0.524171 +0.516096 0.549384 +0.532838 0.524171 +0.516096 0.549384 +0.525801 0.515597 +0.516096 0.549384 +0.517918 0.509471 +0.508826 0.546248 +0.517918 0.509471 +0.508826 0.546248 +0.509727 0.505938 +0.501719 0.545270 +0.509727 0.505938 +0.501719 0.545270 +0.501719 0.504836 +0.501719 0.545270 +0.493710 0.505938 +0.494611 0.546248 +0.493710 0.505938 +0.494611 0.546248 +0.485519 0.509471 +0.494611 0.546248 +0.477636 0.515597 +0.487341 0.549384 +0.477636 0.515597 +0.487341 0.549384 +0.470599 0.524171 +0.480345 0.554820 +0.470599 0.524171 +0.480345 0.554820 +0.464883 0.534727 +0.480345 0.554820 +0.460799 0.546551 +0.474100 0.562430 +0.460799 0.546551 +0.474100 0.562430 +0.458444 0.558838 +0.469027 0.571798 +0.458444 0.558838 +0.469027 0.571798 +0.457709 0.570851 +0.465402 0.582292 +0.457709 0.570851 +0.463312 0.593197 +0.457709 0.570851 +0.463312 0.593197 +0.457709 0.636865 +0.462660 0.603858 +0.457709 0.636865 +0.463312 0.614519 +0.457709 0.636865 +0.465402 0.625424 +0.457709 0.636865 +0.469027 0.635918 +0.457709 0.636865 +0.469027 0.635918 +0.458444 0.648878 +0.474100 0.645286 +0.458444 0.648878 +0.474100 0.645286 +0.460799 0.661165 +0.474100 0.645286 +0.464883 0.672989 +0.480345 0.652896 +0.464883 0.672989 +0.480345 0.652896 +0.470599 0.683545 +0.487341 0.658333 +0.470599 0.683545 +0.487341 0.658333 +0.477636 0.692120 +0.487341 0.658333 +0.485519 0.698245 +0.494611 0.661468 +0.485519 0.698245 +0.494611 0.661468 +0.493711 0.701778 +0.501719 0.662446 +0.493711 0.701778 +0.501719 0.662446 +0.501719 0.702880 +0.501719 0.662446 +0.509727 0.701778 +0.508826 0.661468 +0.509727 0.701778 +0.508826 0.661468 +0.517918 0.698245 +0.508826 0.661468 +0.525801 0.692119 +0.516096 0.658333 +0.525801 0.692119 +0.516096 0.658333 +0.532838 0.683545 +0.523092 0.652896 +0.532838 0.683545 +0.523092 0.652896 +0.538555 0.672989 +0.523092 0.652896 +0.542639 0.661165 +0.529337 0.645286 +0.542639 0.661165 +0.529337 0.645286 +0.544994 0.648878 +0.534411 0.635918 +0.544994 0.648878 +0.534411 0.635918 +0.545729 0.636865 +0.538035 0.625424 +0.545729 0.636865 +0.540125 0.614519 +0.545729 0.636865 +0.540125 0.614519 +0.545729 0.570851 +0.540777 0.603858 +0.545729 0.570851 +0.515254 0.646692 +0.515254 0.628551 +0.550864 0.628551 +0.554264 0.628551 +0.554264 0.646692 +0.547802 0.628551 +0.550864 0.646692 +0.547802 0.646692 +0.545057 0.628551 +0.545057 0.646692 +0.542590 0.628551 +0.542590 0.646692 +0.540362 0.628551 +0.540362 0.646692 +0.538334 0.628551 +0.538334 0.646692 +0.536475 0.628551 +0.536475 0.646692 +0.534759 0.628551 +0.534759 0.646692 +0.533043 0.628551 +0.533043 0.646692 +0.531184 0.628551 +0.531184 0.646692 +0.529156 0.628551 +0.529156 0.646692 +0.526928 0.628551 +0.524461 0.628551 +0.526928 0.646692 +0.524461 0.646692 +0.521716 0.628551 +0.521716 0.646692 +0.518654 0.628551 +0.518654 0.646692 +0.567799 0.628551 +0.449173 0.628551 +0.554264 0.646692 +0.554264 0.628551 +0.449173 0.646692 +0.435638 0.628551 +0.435638 0.628551 +0.422102 0.646692 +0.468678 0.628551 +0.468678 0.646692 +0.449173 0.646692 +0.449173 0.628551 +0.452969 0.646692 +0.452969 0.628551 +0.456089 0.646692 +0.456089 0.628551 +0.458675 0.646692 +0.458675 0.628551 +0.460847 0.646692 +0.460847 0.628551 +0.462832 0.646692 +0.462832 0.628551 +0.464795 0.646692 +0.466741 0.646692 +0.464795 0.628551 +0.466741 0.628551 +0.501719 0.628551 +0.515254 0.628551 +0.488183 0.646692 +0.488183 0.628551 +0.515254 0.646692 +0.538035 0.582292 +0.534411 0.571798 +0.545729 0.570851 +0.529337 0.562430 +0.544994 0.558838 +0.542638 0.546551 +0.523092 0.554820 +0.538555 0.534727 +0.516096 0.549384 +0.532838 0.524171 +0.525801 0.515597 +0.508826 0.546248 +0.517918 0.509471 +0.501719 0.545270 +0.509727 0.505938 +0.501719 0.504836 +0.494611 0.546248 +0.493710 0.505938 +0.485519 0.509471 +0.487341 0.549384 +0.477636 0.515597 +0.480345 0.554820 +0.470599 0.524171 +0.464883 0.534727 +0.474100 0.562430 +0.460799 0.546551 +0.469027 0.571798 +0.458444 0.558838 +0.465402 0.582292 +0.463312 0.593197 +0.457709 0.570851 +0.462660 0.603858 +0.463312 0.614519 +0.465402 0.625424 +0.469027 0.635918 +0.457709 0.636865 +0.474100 0.645286 +0.458444 0.648878 +0.460799 0.661165 +0.480345 0.652896 +0.464883 0.672989 +0.487341 0.658333 +0.470599 0.683545 +0.477636 0.692120 +0.494611 0.661468 +0.485519 0.698245 +0.501719 0.662446 +0.493711 0.701778 +0.501719 0.702880 +0.508826 0.661468 +0.509727 0.701778 +0.517918 0.698245 +0.516096 0.658333 +0.525801 0.692119 +0.523092 0.652896 +0.532838 0.683545 +0.538555 0.672989 +0.529337 0.645286 +0.542639 0.661165 +0.534411 0.635918 +0.544994 0.648878 +0.538035 0.625424 +0.540125 0.614519 +0.545729 0.636865 +0.540777 0.603858 +0.540125 0.593197 +0.540125 0.593197 +0.545729 0.570851 +0.538035 0.582292 +0.545729 0.570851 +0.534411 0.571798 +0.544994 0.558838 +0.534411 0.571798 +0.545729 0.570851 +0.544994 0.558838 +0.529337 0.562430 +0.542638 0.546551 +0.529337 0.562430 +0.538555 0.534727 +0.529337 0.562430 +0.538555 0.534727 +0.523092 0.554820 +0.532838 0.524171 +0.523092 0.554820 +0.532838 0.524171 +0.516096 0.549384 +0.525801 0.515597 +0.516096 0.549384 +0.517918 0.509471 +0.516096 0.549384 +0.517918 0.509471 +0.508826 0.546248 +0.509727 0.505938 +0.508826 0.546248 +0.509727 0.505938 +0.501719 0.545270 +0.501719 0.504836 +0.501719 0.545270 +0.493710 0.505938 +0.501719 0.545270 +0.493710 0.505938 +0.494611 0.546248 +0.485519 0.509471 +0.494611 0.546248 +0.477636 0.515597 +0.494611 0.546248 +0.477636 0.515597 +0.487341 0.549384 +0.470599 0.524171 +0.487341 0.549384 +0.470599 0.524171 +0.480345 0.554820 +0.464883 0.534727 +0.480345 0.554820 +0.460799 0.546551 +0.480345 0.554820 +0.460799 0.546551 +0.474100 0.562430 +0.458444 0.558838 +0.474100 0.562430 +0.458444 0.558838 +0.469027 0.571798 +0.457709 0.570851 +0.469027 0.571798 +0.457709 0.570851 +0.465402 0.582292 +0.457709 0.570851 +0.463312 0.593197 +0.457709 0.636865 +0.463312 0.593197 +0.457709 0.636865 +0.462660 0.603858 +0.457709 0.636865 +0.463312 0.614519 +0.457709 0.636865 +0.465402 0.625424 +0.457709 0.636865 +0.469027 0.635918 +0.458444 0.648878 +0.469027 0.635918 +0.458444 0.648878 +0.474100 0.645286 +0.460799 0.661165 +0.474100 0.645286 +0.464883 0.672989 +0.474100 0.645286 +0.464883 0.672989 +0.480345 0.652896 +0.470599 0.683545 +0.480345 0.652896 +0.470599 0.683545 +0.487341 0.658333 +0.477636 0.692120 +0.487341 0.658333 +0.485519 0.698245 +0.487341 0.658333 +0.485519 0.698245 +0.494611 0.661468 +0.493711 0.701778 +0.494611 0.661468 +0.493711 0.701778 +0.501719 0.662446 +0.501719 0.702880 +0.501719 0.662446 +0.509727 0.701778 +0.501719 0.662446 +0.509727 0.701778 +0.508826 0.661468 +0.517918 0.698245 +0.508826 0.661468 +0.525801 0.692119 +0.508826 0.661468 +0.525801 0.692119 +0.516096 0.658333 +0.532838 0.683545 +0.516096 0.658333 +0.532838 0.683545 +0.523092 0.652896 +0.538555 0.672989 +0.523092 0.652896 +0.542639 0.661165 +0.523092 0.652896 +0.542639 0.661165 +0.529337 0.645286 +0.544994 0.648878 +0.529337 0.645286 +0.544994 0.648878 +0.534411 0.635918 +0.545729 0.636865 +0.534411 0.635918 +0.545729 0.636865 +0.538035 0.625424 +0.545729 0.636865 +0.540125 0.614519 +0.545729 0.570851 +0.540125 0.614519 +0.545729 0.570851 +0.540777 0.603858 +0.452969 0.669873 +0.449173 0.669873 +0.466741 0.659794 +0.468678 0.659794 +0.468678 0.669873 +0.464795 0.659794 +0.466741 0.669873 +0.462832 0.659794 +0.464795 0.669873 +0.460847 0.659794 +0.462832 0.669873 +0.460847 0.669873 +0.458675 0.659794 +0.456089 0.659794 +0.458675 0.669873 +0.452969 0.659794 +0.456089 0.669873 +0.449173 0.659794 +0.515254 0.669873 +0.488183 0.669873 +0.488183 0.659794 +0.515254 0.659794 +0.554264 0.659794 +0.554264 0.669873 +0.518654 0.669873 +0.515254 0.669873 +0.515254 0.659794 +0.518654 0.659794 +0.521716 0.669873 +0.521716 0.659794 +0.524461 0.669873 +0.524461 0.659794 +0.526928 0.669873 +0.526928 0.659794 +0.529156 0.669873 +0.529156 0.659794 +0.531184 0.669873 +0.531184 0.659794 +0.533043 0.669873 +0.533043 0.659794 +0.534759 0.669873 +0.534759 0.659794 +0.536475 0.669873 +0.536475 0.659794 +0.538334 0.669873 +0.538334 0.659794 +0.540362 0.669873 +0.540362 0.659794 +0.542590 0.669873 +0.542590 0.659794 +0.545057 0.669873 +0.545057 0.659794 +0.547802 0.669873 +0.547802 0.659794 +0.550864 0.669873 +0.550864 0.659794 +0.449173 0.669873 +0.422102 0.669873 +0.422102 0.659794 +0.449173 0.659794 +0.422102 0.659794 +0.519224 0.630115 +0.545729 0.570851 +0.526061 0.597101 +0.526474 0.603858 +0.526061 0.610615 +0.524736 0.617527 +0.522439 0.624178 +0.524736 0.590190 +0.544994 0.558838 +0.522439 0.583538 +0.542638 0.546551 +0.519224 0.577601 +0.538555 0.534727 +0.532838 0.524171 +0.515265 0.572778 +0.525801 0.515597 +0.517918 0.509471 +0.510831 0.569332 +0.509727 0.505938 +0.506223 0.567345 +0.501719 0.504836 +0.493710 0.505938 +0.501719 0.566725 +0.485519 0.509471 +0.477636 0.515597 +0.497214 0.567345 +0.470599 0.524171 +0.464883 0.534727 +0.492606 0.569332 +0.460799 0.546551 +0.488172 0.572778 +0.458444 0.558838 +0.457709 0.570851 +0.484214 0.577601 +0.457709 0.636865 +0.480998 0.583538 +0.478701 0.590190 +0.477376 0.597101 +0.476963 0.603858 +0.477376 0.610615 +0.478701 0.617527 +0.458444 0.648878 +0.480998 0.624178 +0.460799 0.661165 +0.484214 0.630115 +0.464883 0.672989 +0.470599 0.683545 +0.488172 0.634938 +0.477636 0.692120 +0.485519 0.698245 +0.492606 0.638384 +0.493711 0.701778 +0.497214 0.640371 +0.501719 0.702880 +0.509727 0.701778 +0.501719 0.640991 +0.517918 0.698245 +0.525801 0.692119 +0.506223 0.640371 +0.532838 0.683545 +0.538555 0.672989 +0.510831 0.638384 +0.542639 0.661165 +0.515265 0.634938 +0.544994 0.648878 +0.545729 0.636865 +0.545729 0.636865 +0.519224 0.630115 +0.522439 0.624178 +0.545729 0.636865 +0.524736 0.590190 +0.545729 0.570851 +0.545729 0.636865 +0.526061 0.597101 +0.524736 0.590190 +0.545729 0.636865 +0.526474 0.603858 +0.545729 0.636865 +0.526061 0.610615 +0.545729 0.636865 +0.524736 0.617527 +0.545729 0.636865 +0.522439 0.583538 +0.545729 0.570851 +0.522439 0.583538 +0.544994 0.558838 +0.519224 0.577601 +0.544994 0.558838 +0.519224 0.577601 +0.542638 0.546551 +0.515265 0.572778 +0.542638 0.546551 +0.515265 0.572778 +0.538555 0.534727 +0.515265 0.572778 +0.532838 0.524171 +0.510831 0.569332 +0.532838 0.524171 +0.510831 0.569332 +0.525801 0.515597 +0.510831 0.569332 +0.517918 0.509471 +0.506223 0.567345 +0.517918 0.509471 +0.506223 0.567345 +0.509727 0.505938 +0.501719 0.566725 +0.509727 0.505938 +0.501719 0.566725 +0.501719 0.504836 +0.501719 0.566725 +0.493710 0.505938 +0.497214 0.567345 +0.493710 0.505938 +0.497214 0.567345 +0.485519 0.509471 +0.497214 0.567345 +0.477636 0.515597 +0.492606 0.569332 +0.477636 0.515597 +0.492606 0.569332 +0.470599 0.524171 +0.492606 0.569332 +0.464883 0.534727 +0.488172 0.572778 +0.464883 0.534727 +0.488172 0.572778 +0.460799 0.546551 +0.484214 0.577601 +0.460799 0.546551 +0.484214 0.577601 +0.458444 0.558838 +0.484214 0.577601 +0.457709 0.570851 +0.480998 0.583538 +0.457709 0.570851 +0.480998 0.583538 +0.457709 0.636865 +0.478701 0.590190 +0.457709 0.636865 +0.477376 0.597101 +0.457709 0.636865 +0.476963 0.603858 +0.457709 0.636865 +0.477376 0.610615 +0.457709 0.636865 +0.478701 0.617527 +0.457709 0.636865 +0.480998 0.624178 +0.457709 0.636865 +0.480998 0.624178 +0.458444 0.648878 +0.484214 0.630115 +0.458444 0.648878 +0.484214 0.630115 +0.460799 0.661165 +0.488172 0.634938 +0.460799 0.661165 +0.488172 0.634938 +0.464883 0.672989 +0.488172 0.634938 +0.470599 0.683545 +0.492606 0.638384 +0.470599 0.683545 +0.492606 0.638384 +0.477636 0.692120 +0.492606 0.638384 +0.485519 0.698245 +0.497214 0.640371 +0.485519 0.698245 +0.497214 0.640371 +0.493711 0.701778 +0.501719 0.640991 +0.493711 0.701778 +0.501719 0.640991 +0.501719 0.702880 +0.501719 0.640991 +0.509727 0.701778 +0.506223 0.640371 +0.509727 0.701778 +0.506223 0.640371 +0.517918 0.698245 +0.506223 0.640371 +0.525801 0.692119 +0.510831 0.638384 +0.525801 0.692119 +0.510831 0.638384 +0.532838 0.683545 +0.510831 0.638384 +0.538555 0.672989 +0.515265 0.634938 +0.538555 0.672989 +0.515265 0.634938 +0.542639 0.661165 +0.519224 0.630115 +0.542639 0.661165 +0.519224 0.630115 +0.544994 0.648878 +0.484214 0.577601 +0.487544 0.550151 +0.488172 0.572778 +0.494712 0.547060 +0.492606 0.569332 +0.501719 0.546095 +0.497214 0.567345 +0.508726 0.547060 +0.501719 0.566725 +0.515894 0.550151 +0.506223 0.567345 +0.522791 0.555511 +0.510831 0.569332 +0.528948 0.563014 +0.515265 0.572778 +0.533950 0.572250 +0.519224 0.577601 +0.537524 0.582596 +0.522439 0.583538 +0.539584 0.593347 +0.524736 0.590190 +0.540227 0.603858 +0.526061 0.597101 +0.539584 0.614369 +0.526474 0.603858 +0.537524 0.625120 +0.526061 0.610615 +0.533950 0.635467 +0.524736 0.617527 +0.528948 0.644703 +0.522439 0.624178 +0.522791 0.652205 +0.519224 0.630115 +0.515894 0.657565 +0.515265 0.634938 +0.508726 0.660657 +0.510831 0.638384 +0.501719 0.661621 +0.506223 0.640371 +0.494712 0.660657 +0.501719 0.640991 +0.487544 0.657565 +0.497214 0.640371 +0.480646 0.652205 +0.492606 0.638384 +0.474489 0.644703 +0.488172 0.634938 +0.469487 0.635467 +0.484214 0.630115 +0.465914 0.625120 +0.480998 0.624178 +0.463853 0.614369 +0.478701 0.617527 +0.463210 0.603858 +0.477376 0.610615 +0.463853 0.593347 +0.476963 0.603858 +0.465914 0.582596 +0.477376 0.597101 +0.469487 0.572250 +0.478701 0.590190 +0.474489 0.563014 +0.480998 0.583538 +0.480646 0.555511 +0.480646 0.555511 +0.484214 0.577601 +0.488172 0.572778 +0.488172 0.572778 +0.487544 0.550151 +0.480646 0.555511 +0.492606 0.569332 +0.487544 0.550151 +0.492606 0.569332 +0.494712 0.547060 +0.497214 0.567345 +0.494712 0.547060 +0.497214 0.567345 +0.501719 0.546095 +0.501719 0.566725 +0.501719 0.546095 +0.501719 0.566725 +0.508726 0.547060 +0.506223 0.567345 +0.508726 0.547060 +0.506223 0.567345 +0.515894 0.550151 +0.510831 0.569332 +0.515894 0.550151 +0.510831 0.569332 +0.522791 0.555511 +0.515265 0.572778 +0.522791 0.555511 +0.515265 0.572778 +0.528948 0.563014 +0.519224 0.577601 +0.528948 0.563014 +0.519224 0.577601 +0.533950 0.572250 +0.522439 0.583538 +0.533950 0.572250 +0.522439 0.583538 +0.537524 0.582596 +0.524736 0.590190 +0.537524 0.582596 +0.524736 0.590190 +0.539584 0.593347 +0.526061 0.597101 +0.539584 0.593347 +0.526061 0.597101 +0.540227 0.603858 +0.526474 0.603858 +0.540227 0.603858 +0.526474 0.603858 +0.539584 0.614369 +0.526061 0.610615 +0.539584 0.614369 +0.526061 0.610615 +0.537524 0.625120 +0.524736 0.617527 +0.537524 0.625120 +0.524736 0.617527 +0.533950 0.635467 +0.522439 0.624178 +0.533950 0.635467 +0.522439 0.624178 +0.528948 0.644703 +0.519224 0.630115 +0.528948 0.644703 +0.519224 0.630115 +0.522791 0.652205 +0.515265 0.634938 +0.522791 0.652205 +0.515265 0.634938 +0.515894 0.657565 +0.510831 0.638384 +0.515894 0.657565 +0.510831 0.638384 +0.508726 0.660657 +0.506223 0.640371 +0.508726 0.660657 +0.506223 0.640371 +0.501719 0.661621 +0.501719 0.640991 +0.501719 0.661621 +0.501719 0.640991 +0.494712 0.660657 +0.497214 0.640371 +0.494712 0.660657 +0.497214 0.640371 +0.487544 0.657565 +0.492606 0.638384 +0.487544 0.657565 +0.492606 0.638384 +0.480646 0.652205 +0.488172 0.634938 +0.480646 0.652205 +0.488172 0.634938 +0.474489 0.644703 +0.484214 0.630115 +0.474489 0.644703 +0.484214 0.630115 +0.469487 0.635467 +0.480998 0.624178 +0.469487 0.635467 +0.480998 0.624178 +0.465914 0.625120 +0.478701 0.617527 +0.465914 0.625120 +0.478701 0.617527 +0.463853 0.614369 +0.477376 0.610615 +0.463853 0.614369 +0.477376 0.610615 +0.463210 0.603858 +0.476963 0.603858 +0.463210 0.603858 +0.476963 0.603858 +0.463853 0.593347 +0.477376 0.597101 +0.463853 0.593347 +0.477376 0.597101 +0.465914 0.582596 +0.478701 0.590190 +0.465914 0.582596 +0.478701 0.590190 +0.469487 0.572250 +0.480998 0.583538 +0.469487 0.572250 +0.480998 0.583538 +0.474489 0.563014 +0.484214 0.577601 +0.474489 0.563014 +0.468678 0.542883 +0.468678 0.537843 +0.534759 0.537843 +0.534759 0.542883 +0.532177 0.537843 +0.532177 0.542883 +0.529331 0.537843 +0.529331 0.542883 +0.526113 0.537843 +0.526113 0.542883 +0.522391 0.537843 +0.522391 0.542883 +0.518034 0.537843 +0.518034 0.542883 +0.512990 0.537843 +0.512990 0.542883 +0.507414 0.537843 +0.507414 0.542883 +0.501719 0.537843 +0.501719 0.542883 +0.496023 0.537843 +0.496023 0.542883 +0.490447 0.537843 +0.485404 0.537843 +0.490447 0.542883 +0.485404 0.542883 +0.481046 0.537843 +0.477324 0.537843 +0.481046 0.542883 +0.474106 0.537843 +0.477324 0.542883 +0.474106 0.542883 +0.471260 0.537843 +0.471260 0.542883 +0.466217 0.563040 +0.466217 0.563040 +0.466217 0.552961 +0.466217 0.552961 +0.537220 0.563040 +0.537220 0.552961 +0.537220 0.552961 +0.537220 0.563040 +0.471140 0.552961 +0.471140 0.563040 +0.471140 0.563040 +0.471140 0.552961 +0.532298 0.552961 +0.532298 0.552961 +0.532298 0.563040 +0.532298 0.563040 +0.441504 0.563040 +0.441504 0.552961 +0.445894 0.552961 +0.445894 0.563040 +0.557543 0.563040 +0.557543 0.552961 +0.561934 0.552961 +0.561934 0.563040 +0.511975 0.563040 +0.507584 0.563040 +0.507584 0.552961 +0.511975 0.552961 +0.491462 0.563040 +0.491462 0.552961 +0.495853 0.552961 +0.495853 0.563040 + + + + + + + + + + + +

32 0 32 0 1 0 1 2 1 4 3 4 2 4 2 3 5 3 5 6 5 2 7 2 4 8 4 7 9 7 2 10 2 5 11 5 7 12 7 6 13 6 2 14 2 9 15 9 6 16 6 7 17 7 9 18 9 8 19 8 6 20 6 11 21 11 8 22 8 9 23 9 11 24 11 10 25 10 8 26 8 13 27 13 10 28 10 11 29 11 13 30 13 12 31 12 10 32 10 15 33 15 12 34 12 13 35 13 15 36 15 14 37 14 12 38 12 17 39 17 14 40 14 15 41 15 17 42 17 16 43 16 14 44 14 19 45 19 16 46 16 17 47 17 19 48 19 18 49 18 16 50 16 21 51 21 18 52 34 19 53 35 21 54 21 20 55 20 18 56 36 23 57 23 20 58 20 21 59 21 23 60 23 22 61 22 20 62 20 25 63 25 22 64 22 23 65 23 25 66 25 24 67 24 22 68 22 27 69 27 24 70 24 25 71 25 27 72 27 26 73 26 24 74 24 29 75 29 26 76 26 27 77 27 29 78 29 28 79 28 26 80 26 31 81 31 28 82 28 29 83 29 31 84 31 30 85 30 28 86 28 33 87 33 30 88 30 31 89 31 33 90 33 32 91 32 30 92 30 0 93 0 32 94 32 33 95 33 51 96 54 34 97 37 35 98 38 38 99 41 36 100 39 37 101 40 40 102 43 36 103 39 38 104 41 40 105 43 39 106 42 36 107 39 41 108 44 39 109 42 40 110 43 44 111 47 39 112 42 41 113 44 44 114 47 42 115 45 39 116 42 44 117 47 43 118 46 42 119 45 45 120 48 43 121 46 44 122 47 47 123 50 43 124 46 45 125 48 47 126 50 46 127 49 43 128 46 49 129 52 46 130 49 47 131 50 49 132 52 48 133 51 46 134 49 34 135 37 48 136 51 49 137 52 34 138 37 50 139 53 48 140 51 34 141 37 51 142 54 50 143 53 68 144 71 52 145 55 53 146 56 56 147 59 54 148 57 55 149 58 58 150 61 54 151 57 56 152 59 58 153 61 57 154 60 54 155 57 59 156 62 57 157 60 58 158 61 61 159 64 57 160 60 59 161 62 61 162 64 60 163 63 57 164 60 64 165 67 60 166 63 61 167 64 64 168 67 62 169 65 60 170 63 64 171 67 63 172 66 62 173 65 66 174 69 63 175 66 64 176 67 66 177 69 65 178 68 63 179 66 67 180 70 65 181 68 66 182 69 69 183 72 65 184 68 67 185 70 69 186 72 68 187 71 65 188 68 52 189 55 68 190 71 69 191 72 103 192 106 70 193 73 71 194 74 74 195 77 72 196 75 73 197 76 75 198 78 72 199 75 74 200 77 77 201 80 72 202 75 75 203 78 77 204 80 76 205 79 72 206 75 79 207 82 76 208 79 77 209 80 79 210 82 78 211 81 76 212 79 81 213 84 78 214 81 79 215 82 81 216 84 80 217 83 78 218 81 83 219 86 80 220 83 81 221 84 83 222 86 82 223 85 80 224 83 85 225 88 82 226 85 83 227 86 85 228 88 84 229 87 82 230 85 87 231 90 84 232 87 85 233 88 87 234 90 86 235 89 84 236 87 89 237 92 86 238 89 87 239 90 89 240 92 88 241 91 86 242 89 92 243 95 88 244 107 89 245 108 92 246 95 90 247 93 88 248 109 92 249 95 91 250 94 90 251 93 94 252 97 91 253 94 92 254 95 94 255 97 93 256 96 91 257 94 96 258 99 93 259 96 94 260 97 96 261 99 95 262 98 93 263 96 98 264 101 95 265 98 96 266 99 98 267 101 97 268 100 95 269 98 100 270 103 97 271 100 98 272 101 100 273 103 99 274 102 97 275 100 102 276 105 99 277 102 100 278 103 102 279 105 101 280 104 99 281 102 70 282 73 101 283 104 102 284 105 70 285 73 103 286 106 101 287 104 169 288 175 104 289 110 111 290 117 107 291 113 127 292 133 105 293 111 107 294 113 106 295 112 127 296 133 165 297 171 106 298 112 107 299 113 165 300 171 108 301 114 106 302 112 110 303 116 109 304 115 114 305 120 112 306 118 109 307 115 110 308 116 112 309 118 111 310 117 109 311 115 169 312 175 111 313 117 112 314 118 114 315 120 113 316 119 110 317 116 116 318 122 113 319 119 114 320 120 116 321 122 115 322 121 113 323 119 118 324 124 115 325 121 116 326 122 118 327 124 117 328 123 115 329 121 120 330 126 117 331 123 118 332 124 120 333 126 119 334 125 117 335 123 122 336 128 119 337 125 120 338 126 122 339 128 121 340 127 119 341 125 124 342 130 121 343 127 122 344 128 124 345 130 123 346 129 121 347 127 126 348 132 123 349 129 124 350 130 126 351 132 125 352 131 123 353 129 131 354 137 125 355 131 126 356 132 143 357 149 105 358 111 127 359 133 143 360 149 128 361 134 105 362 111 154 363 160 129 364 135 130 365 136 133 366 139 125 367 131 131 368 137 133 369 139 132 370 138 125 371 131 135 372 141 132 373 138 133 374 139 135 375 141 134 376 140 132 377 138 137 378 143 134 379 140 135 380 141 137 381 143 136 382 142 134 383 140 139 384 145 136 385 142 137 386 143 139 387 145 138 388 144 136 389 142 141 390 147 138 391 144 139 392 145 141 393 147 140 394 146 138 395 144 104 396 110 140 397 146 141 398 147 104 399 110 142 400 148 140 401 146 145 402 151 128 403 134 143 404 149 145 405 151 144 406 150 128 407 134 148 408 154 144 409 150 145 410 151 148 411 154 146 412 152 144 413 150 148 414 154 147 415 153 146 416 152 149 417 155 147 418 153 148 419 154 129 420 135 147 421 153 149 422 155 129 423 135 150 424 156 147 425 153 129 426 135 151 427 157 150 428 156 154 429 160 151 430 157 129 431 135 154 432 160 152 433 158 151 434 157 154 435 160 153 436 159 152 437 158 156 438 162 153 439 159 154 440 160 156 441 162 155 442 161 153 443 159 158 444 164 155 445 161 156 446 162 158 447 164 157 448 163 155 449 161 159 450 165 157 451 163 158 452 164 161 453 167 157 454 163 159 455 165 161 456 167 160 457 166 157 458 163 164 459 170 160 460 166 161 461 167 164 462 170 162 463 168 160 464 166 164 465 170 163 466 169 162 467 168 166 468 172 163 469 169 164 470 170 163 471 169 108 472 114 165 473 171 166 474 172 108 475 114 163 476 169 168 477 174 108 478 114 166 479 172 168 480 174 167 481 173 108 482 114 142 483 148 167 484 173 168 485 174 142 486 148 169 487 175 167 488 173 104 489 110 169 490 175 142 491 148 231 492 237 176 493 182 170 494 176 221 495 227 171 496 177 172 497 178 175 498 181 207 499 213 173 500 179 175 501 181 174 502 180 207 503 213 170 504 176 174 505 180 175 506 181 170 507 176 176 508 182 174 509 180 183 510 189 179 511 185 177 512 183 183 513 189 178 514 184 179 515 185 185 516 191 177 517 183 179 518 185 185 519 191 180 520 186 177 521 183 190 522 196 181 523 187 182 524 188 233 525 239 178 526 184 183 527 189 233 528 239 184 529 190 178 530 184 188 531 194 180 532 186 185 533 191 188 534 194 186 535 192 180 536 186 188 537 194 187 538 193 186 539 192 189 540 195 187 541 193 188 542 194 191 543 197 187 544 193 189 545 195 191 546 197 190 547 196 187 548 193 192 549 198 190 550 196 191 551 197 192 552 198 181 553 187 190 554 196 194 555 200 181 556 187 192 557 198 194 558 200 193 559 199 181 560 187 196 561 202 193 562 199 194 563 200 196 564 202 195 565 201 193 566 199 197 567 203 195 568 201 196 569 202 199 570 205 195 571 201 197 572 203 199 573 205 198 574 204 195 575 201 202 576 208 198 577 204 199 578 205 202 579 208 200 580 206 198 581 204 202 582 208 201 583 207 200 584 206 204 585 210 201 586 207 202 587 208 204 588 210 203 589 209 201 590 207 205 591 211 203 592 209 204 593 210 234 594 240 203 595 209 205 596 211 234 597 240 206 598 212 203 599 209 209 600 215 173 601 179 207 602 213 209 603 215 208 604 214 173 605 179 211 606 217 208 607 214 209 608 215 211 609 217 210 610 216 208 611 214 213 612 219 210 613 216 211 614 217 213 615 219 212 616 218 210 617 216 215 618 221 212 619 218 213 620 219 215 621 221 214 622 220 212 623 218 171 624 177 214 625 220 215 626 221 171 627 177 216 628 222 214 629 220 234 630 240 217 631 223 206 632 212 171 633 177 218 634 224 216 635 222 221 636 227 218 637 224 171 638 177 221 639 227 219 640 225 218 641 224 221 642 227 220 643 226 219 644 225 222 645 228 220 646 226 221 647 227 224 648 230 220 649 226 222 650 228 224 651 230 223 652 229 220 653 226 226 654 232 223 655 229 224 656 230 226 657 232 225 658 231 223 659 229 228 660 234 225 661 231 226 662 232 228 663 234 227 664 233 225 665 231 230 666 236 227 667 233 228 668 234 230 669 236 229 670 235 227 671 233 232 672 238 229 673 235 230 674 236 232 675 238 231 676 237 229 677 235 217 678 242 231 679 237 232 680 238 235 681 241 184 682 190 233 683 239 235 684 241 234 685 240 184 686 190 235 687 241 217 688 223 234 689 240 235 690 243 231 691 237 217 692 244 176 693 182 231 694 237 235 695 245 249 696 260 236 697 261 241 698 262 240 699 263 237 700 264 238 701 248 240 702 265 239 703 266 237 704 247 249 705 267 239 706 268 240 707 250 249 708 269 241 709 251 239 710 249 245 711 270 242 712 271 243 713 253 245 714 272 244 715 273 242 716 252 246 717 274 244 718 275 245 719 255 248 720 276 244 721 277 246 722 256 248 723 278 247 724 279 244 725 254 236 726 280 247 727 281 248 728 258 236 729 246 249 730 259 247 731 257 262 732 296 254 733 297 250 734 298 253 735 299 251 736 300 252 737 284 255 738 301 251 739 302 253 740 285 255 741 303 254 742 304 251 743 283 250 744 282 254 745 305 255 746 287 258 747 306 256 748 307 257 749 289 261 750 308 256 751 309 258 752 290 261 753 310 259 754 311 256 755 288 261 756 312 260 757 313 259 758 291 263 759 314 260 760 315 261 761 293 263 762 316 262 763 317 260 764 292 254 765 286 262 766 294 263 767 295 276 768 332 268 769 333 264 770 334 267 771 335 265 772 336 266 773 320 269 774 337 265 775 338 267 776 321 269 777 339 268 778 340 265 779 319 264 780 318 268 781 341 269 782 323 272 783 342 270 784 343 271 785 325 275 786 344 270 787 345 272 788 326 275 789 346 273 790 347 270 791 324 275 792 348 274 793 349 273 794 327 277 795 350 274 796 351 275 797 329 277 798 352 276 799 353 274 800 328 268 801 322 276 802 330 277 803 331 291 804 368 278 805 369 283 806 370 282 807 371 279 808 372 280 809 356 282 810 373 281 811 374 279 812 355 291 813 375 281 814 376 282 815 358 291 816 377 283 817 359 281 818 357 287 819 378 284 820 379 285 821 361 287 822 380 286 823 381 284 824 360 288 825 382 286 826 383 287 827 363 290 828 384 286 829 385 288 830 364 290 831 386 289 832 387 286 833 362 278 834 388 289 835 389 290 836 366 278 837 354 291 838 367 289 839 365 305 840 404 292 841 405 297 842 406 296 843 407 293 844 408 294 845 392 296 846 409 295 847 410 293 848 391 305 849 411 295 850 412 296 851 394 305 852 413 297 853 395 295 854 393 301 855 414 298 856 415 299 857 397 301 858 416 300 859 417 298 860 396 302 861 418 300 862 419 301 863 399 304 864 420 300 865 421 302 866 400 304 867 422 303 868 423 300 869 398 292 870 424 303 871 425 304 872 402 292 873 390 305 874 403 303 875 401 318 876 440 310 877 441 306 878 442 309 879 443 307 880 444 308 881 428 311 882 445 307 883 446 309 884 429 311 885 447 310 886 448 307 887 427 306 888 426 310 889 449 311 890 431 314 891 450 312 892 451 313 893 433 317 894 452 312 895 453 314 896 434 317 897 454 315 898 455 312 899 432 317 900 456 316 901 457 315 902 435 319 903 458 316 904 459 317 905 437 319 906 460 318 907 461 316 908 436 310 909 430 318 910 438 319 911 439 332 912 476 324 913 477 320 914 478 323 915 479 321 916 480 322 917 464 325 918 481 321 919 482 323 920 465 325 921 483 324 922 484 321 923 463 320 924 462 324 925 485 325 926 467 328 927 486 326 928 487 327 929 469 331 930 488 326 931 489 328 932 470 331 933 490 329 934 491 326 935 468 331 936 492 330 937 493 329 938 471 333 939 494 330 940 495 331 941 473 333 942 496 332 943 497 330 944 472 324 945 466 332 946 474 333 947 475 347 948 512 334 949 513 339 950 514 338 951 515 335 952 516 336 953 500 338 954 517 337 955 518 335 956 499 347 957 519 337 958 520 338 959 502 347 960 521 339 961 503 337 962 501 343 963 522 340 964 523 341 965 505 343 966 524 342 967 525 340 968 504 344 969 526 342 970 527 343 971 507 346 972 528 342 973 529 344 974 508 346 975 530 345 976 531 342 977 506 334 978 532 345 979 533 346 980 510 334 981 498 347 982 511 345 983 509 413 984 599 348 985 534 353 986 539 361 987 547 391 988 577 349 989 535 361 990 547 350 991 536 391 992 577 354 993 540 355 994 541 351 995 537 354 996 540 352 997 538 355 998 541 354 999 540 353 1000 539 352 1001 538 413 1002 599 353 1003 539 354 1004 540 369 1005 555 351 1006 537 355 1007 541 369 1008 555 356 1009 542 351 1010 537 373 1011 559 357 1012 543 358 1013 544 398 1014 584 359 1015 545 360 1016 546 363 1017 549 350 1018 536 361 1019 547 363 1020 549 362 1021 548 350 1022 536 366 1023 552 362 1024 548 363 1025 549 366 1026 552 364 1027 550 362 1028 548 366 1029 552 365 1030 551 364 1031 550 367 1032 553 365 1033 551 366 1034 552 412 1035 598 365 1036 551 367 1037 553 412 1038 598 368 1039 554 365 1040 551 371 1041 557 356 1042 542 369 1043 555 371 1044 557 370 1045 556 356 1046 542 374 1047 560 370 1048 556 371 1049 557 374 1050 560 372 1051 558 370 1052 556 374 1053 560 373 1054 559 372 1055 558 375 1056 561 373 1057 559 374 1058 560 376 1059 562 373 1060 559 375 1061 561 376 1062 562 357 1063 543 373 1064 559 378 1065 564 357 1066 543 376 1067 562 378 1068 564 377 1069 563 357 1070 543 379 1071 565 377 1072 563 378 1073 564 381 1074 567 377 1075 563 379 1076 565 381 1077 567 380 1078 566 377 1079 563 384 1080 570 380 1081 566 381 1082 567 384 1083 570 382 1084 568 380 1085 566 384 1086 570 383 1087 569 382 1088 568 385 1089 571 383 1090 569 384 1091 570 387 1092 573 383 1093 569 385 1094 571 387 1095 573 386 1096 572 383 1097 569 389 1098 575 386 1099 572 387 1100 573 389 1101 575 388 1102 574 386 1103 572 348 1104 534 388 1105 574 389 1106 575 348 1107 534 390 1108 576 388 1109 574 394 1110 580 349 1111 535 391 1112 577 394 1113 580 392 1114 578 349 1115 535 394 1116 580 393 1117 579 392 1118 578 359 1119 545 393 1120 579 394 1121 580 348 1122 534 395 1123 581 390 1124 576 359 1125 545 396 1126 582 393 1127 579 398 1128 584 396 1129 582 359 1130 545 398 1131 584 397 1132 583 396 1133 582 401 1134 587 397 1135 583 398 1136 584 401 1137 587 399 1138 585 397 1139 583 401 1140 587 400 1141 586 399 1142 585 403 1143 589 400 1144 586 401 1145 587 403 1146 589 402 1147 588 400 1148 586 405 1149 591 402 1150 588 403 1151 589 405 1152 591 404 1153 590 402 1154 588 406 1155 592 404 1156 590 405 1157 591 408 1158 594 404 1159 590 406 1160 592 408 1161 594 407 1162 593 404 1163 590 410 1164 596 407 1165 593 408 1166 594 410 1167 596 409 1168 595 407 1169 593 395 1170 581 409 1171 595 410 1172 596 412 1173 598 411 1174 597 368 1175 554 409 1176 595 411 1177 597 412 1178 598 395 1179 581 411 1180 597 409 1181 595 348 1182 534 411 1183 597 395 1184 581 348 1185 534 413 1186 599 411 1187 597 479 1188 665 414 1189 600 419 1190 605 429 1191 615 423 1192 609 415 1193 601 429 1194 615 416 1195 602 423 1196 609 420 1197 606 421 1198 607 417 1199 603 420 1200 606 418 1201 604 421 1202 607 420 1203 606 419 1204 605 418 1205 604 479 1206 665 419 1207 605 420 1208 606 435 1209 621 417 1210 603 421 1211 607 435 1212 621 422 1213 608 417 1214 603 457 1215 643 415 1216 601 423 1217 609 457 1218 643 424 1219 610 415 1220 601 440 1221 626 425 1222 611 426 1223 612 464 1224 650 427 1225 613 428 1226 614 431 1227 617 416 1228 602 429 1229 615 431 1230 617 430 1231 616 416 1232 602 433 1233 619 430 1234 616 431 1235 617 433 1236 619 432 1237 618 430 1238 616 475 1239 661 432 1240 618 433 1241 619 475 1242 661 434 1243 620 432 1244 618 437 1245 623 422 1246 608 435 1247 621 437 1248 623 436 1249 622 422 1250 608 439 1251 625 436 1252 622 437 1253 623 439 1254 625 438 1255 624 436 1256 622 441 1257 627 438 1258 624 439 1259 625 441 1260 627 440 1261 626 438 1262 624 442 1263 628 440 1264 626 441 1265 627 442 1266 628 425 1267 611 440 1268 626 444 1269 630 425 1270 611 442 1271 628 444 1272 630 443 1273 629 425 1274 611 445 1275 631 443 1276 629 444 1277 630 447 1278 633 443 1279 629 445 1280 631 447 1281 633 446 1282 632 443 1283 629 449 1284 635 446 1285 632 447 1286 633 449 1287 635 448 1288 634 446 1289 632 451 1290 637 448 1291 634 449 1292 635 451 1293 637 450 1294 636 448 1295 634 453 1296 639 450 1297 636 451 1298 637 453 1299 639 452 1300 638 450 1301 636 455 1302 641 452 1303 638 453 1304 639 455 1305 641 454 1306 640 452 1307 638 414 1308 600 454 1309 640 455 1310 641 414 1311 600 456 1312 642 454 1313 640 459 1314 645 424 1315 610 457 1316 643 459 1317 645 458 1318 644 424 1319 610 427 1320 613 458 1321 644 459 1322 645 427 1323 613 460 1324 646 458 1325 644 427 1326 613 461 1327 647 460 1328 646 464 1329 650 461 1330 647 427 1331 613 464 1332 650 462 1333 648 461 1334 647 464 1335 650 463 1336 649 462 1337 648 466 1338 652 463 1339 649 464 1340 650 466 1341 652 465 1342 651 463 1343 649 467 1344 653 465 1345 651 466 1346 652 469 1347 655 465 1348 651 467 1349 653 469 1350 655 468 1351 654 465 1352 651 471 1353 657 468 1354 654 469 1355 655 471 1356 657 470 1357 656 468 1358 654 474 1359 660 470 1360 656 471 1361 657 474 1362 660 472 1363 658 470 1364 656 474 1365 660 473 1366 659 472 1367 658 476 1368 662 473 1369 659 474 1370 660 473 1371 659 434 1372 620 475 1373 661 476 1374 662 434 1375 620 473 1376 659 478 1377 664 434 1378 620 476 1379 662 478 1380 664 477 1381 663 434 1382 620 456 1383 642 477 1384 666 478 1385 667 456 1386 642 479 1387 665 477 1388 668 414 1389 600 479 1390 665 456 1391 642 512 1392 703 491 1393 704 480 1394 705 490 1395 706 481 1396 707 482 1397 671 485 1398 708 483 1399 709 484 1400 673 488 1401 710 483 1402 711 485 1403 674 490 1404 712 486 1405 713 481 1406 670 490 1407 714 487 1408 715 486 1409 675 493 1410 716 483 1411 717 488 1412 677 493 1413 718 489 1414 719 483 1415 672 492 1416 720 487 1417 721 490 1418 679 492 1419 722 491 1420 723 487 1421 676 480 1422 669 491 1423 724 492 1424 681 496 1425 725 489 1426 726 493 1427 682 496 1428 727 494 1429 728 489 1430 678 496 1431 729 495 1432 730 494 1433 683 498 1434 731 495 1435 732 496 1436 685 498 1437 733 497 1438 734 495 1439 684 501 1440 735 497 1441 736 498 1442 687 501 1443 737 499 1444 738 497 1445 686 501 1446 739 500 1447 740 499 1448 688 503 1449 741 500 1450 742 501 1451 690 503 1452 743 502 1453 744 500 1454 689 506 1455 745 502 1456 746 503 1457 692 506 1458 747 504 1459 748 502 1460 691 506 1461 749 505 1462 750 504 1463 693 508 1464 751 505 1465 752 506 1466 695 508 1467 753 507 1468 754 505 1469 694 511 1470 755 507 1471 756 508 1472 697 511 1473 757 509 1474 758 507 1475 696 511 1476 759 510 1477 760 509 1478 698 513 1479 761 510 1480 762 511 1481 700 513 1482 763 512 1483 764 510 1484 699 491 1485 680 512 1486 701 513 1487 702 546 1488 799 525 1489 800 514 1490 801 524 1491 802 515 1492 803 516 1493 767 519 1494 804 517 1495 805 518 1496 769 522 1497 806 517 1498 807 519 1499 770 524 1500 808 520 1501 809 515 1502 766 524 1503 810 521 1504 811 520 1505 771 527 1506 812 517 1507 813 522 1508 773 527 1509 814 523 1510 815 517 1511 768 526 1512 816 521 1513 817 524 1514 775 526 1515 818 525 1516 819 521 1517 772 514 1518 765 525 1519 820 526 1520 777 530 1521 821 523 1522 822 527 1523 778 530 1524 823 528 1525 824 523 1526 774 530 1527 825 529 1528 826 528 1529 779 532 1530 827 529 1531 828 530 1532 781 532 1533 829 531 1534 830 529 1535 780 535 1536 831 531 1537 832 532 1538 783 535 1539 833 533 1540 834 531 1541 782 535 1542 835 534 1543 836 533 1544 784 537 1545 837 534 1546 838 535 1547 786 537 1548 839 536 1549 840 534 1550 785 540 1551 841 536 1552 842 537 1553 788 540 1554 843 538 1555 844 536 1556 787 540 1557 845 539 1558 846 538 1559 789 542 1560 847 539 1561 848 540 1562 791 542 1563 849 541 1564 850 539 1565 790 545 1566 851 541 1567 852 542 1568 793 545 1569 853 543 1570 854 541 1571 792 545 1572 855 544 1573 856 543 1574 794 547 1575 857 544 1576 858 545 1577 796 547 1578 859 546 1579 860 544 1580 795 525 1581 776 546 1582 797 547 1583 798 580 1584 893 548 1585 861 549 1586 862 553 1587 866 550 1588 863 551 1589 864 553 1590 866 552 1591 865 550 1592 863 555 1593 868 552 1594 865 553 1595 866 555 1596 868 554 1597 867 552 1598 865 557 1599 870 554 1600 867 555 1601 868 557 1602 870 556 1603 869 554 1604 867 559 1605 872 556 1606 869 557 1607 870 559 1608 872 558 1609 871 556 1610 869 561 1611 874 558 1612 871 559 1613 872 561 1614 874 560 1615 873 558 1616 871 563 1617 876 560 1618 873 561 1619 874 563 1620 876 562 1621 875 560 1622 873 565 1623 878 562 1624 875 563 1625 876 565 1626 878 564 1627 877 562 1628 875 567 1629 880 564 1630 877 565 1631 878 567 1632 880 566 1633 879 564 1634 877 569 1635 882 566 1636 879 567 1637 880 569 1638 882 568 1639 881 566 1640 879 571 1641 884 568 1642 881 569 1643 882 571 1644 884 570 1645 883 568 1646 881 573 1647 886 570 1648 883 571 1649 884 573 1650 886 572 1651 885 570 1652 883 575 1653 888 572 1654 885 573 1655 886 575 1656 888 574 1657 887 572 1658 885 577 1659 890 574 1660 887 575 1661 888 577 1662 890 576 1663 889 574 1664 887 579 1665 892 576 1666 889 577 1667 890 579 1668 892 578 1669 891 576 1670 889 581 1671 894 578 1672 891 579 1673 892 581 1674 894 580 1675 893 578 1676 891 548 1677 861 580 1678 893 581 1679 894 645 1680 961 582 1681 962 583 1682 963 585 1683 964 645 1684 965 583 1685 896 585 1686 966 584 1687 967 645 1688 968 588 1689 969 584 1690 970 585 1691 898 588 1692 971 586 1693 972 584 1694 897 588 1695 973 587 1696 974 586 1697 899 590 1698 975 587 1699 976 588 1700 901 590 1701 977 589 1702 978 587 1703 900 593 1704 979 589 1705 980 590 1706 903 593 1707 981 591 1708 982 589 1709 902 593 1710 983 592 1711 984 591 1712 904 595 1713 985 592 1714 986 593 1715 906 595 1716 987 594 1717 988 592 1718 905 598 1719 989 594 1720 990 595 1721 908 598 1722 991 596 1723 992 594 1724 907 598 1725 993 597 1726 994 596 1727 909 601 1728 995 597 1729 996 598 1730 911 601 1731 997 599 1732 998 597 1733 910 601 1734 999 600 1735 1000 599 1736 912 603 1737 1001 600 1738 1002 601 1739 914 603 1740 1003 602 1741 1004 600 1742 913 606 1743 1005 602 1744 1006 603 1745 916 606 1746 1007 604 1747 1008 602 1748 915 606 1749 1009 605 1750 1010 604 1751 917 608 1752 1011 605 1753 1012 606 1754 919 608 1755 1013 607 1756 1014 605 1757 918 610 1758 1015 607 1759 1016 608 1760 921 610 1761 1017 609 1762 1018 607 1763 920 611 1764 1019 609 1765 1020 610 1766 923 613 1767 1021 609 1768 1022 611 1769 924 613 1770 1023 612 1771 1024 609 1772 922 614 1773 1025 612 1774 1026 613 1775 926 615 1776 1027 612 1777 1028 614 1778 927 616 1779 1029 612 1780 1030 615 1781 928 618 1782 1031 612 1783 1032 616 1784 929 618 1785 1033 617 1786 1034 612 1787 925 621 1788 1035 617 1789 1036 618 1790 931 621 1791 1037 619 1792 1038 617 1793 930 621 1794 1039 620 1795 1040 619 1796 932 623 1797 1041 620 1798 1042 621 1799 934 623 1800 1043 622 1801 1044 620 1802 933 626 1803 1045 622 1804 1046 623 1805 936 626 1806 1047 624 1807 1048 622 1808 935 626 1809 1049 625 1810 1050 624 1811 937 628 1812 1051 625 1813 1052 626 1814 939 628 1815 1053 627 1816 1054 625 1817 938 631 1818 1055 627 1819 1056 628 1820 941 631 1821 1057 629 1822 1058 627 1823 940 631 1824 1059 630 1825 1060 629 1826 942 634 1827 1061 630 1828 1062 631 1829 944 634 1830 1063 632 1831 1064 630 1832 943 634 1833 1065 633 1834 1066 632 1835 945 636 1836 1067 633 1837 1068 634 1838 947 636 1839 1069 635 1840 1070 633 1841 946 639 1842 1071 635 1843 1072 636 1844 949 639 1845 1073 637 1846 1074 635 1847 948 639 1848 1075 638 1849 1076 637 1850 950 641 1851 1077 638 1852 1078 639 1853 952 641 1854 1079 640 1855 1080 638 1856 951 643 1857 1081 640 1858 1082 641 1859 954 643 1860 1083 642 1861 1084 640 1862 953 644 1863 1085 642 1864 1086 643 1865 956 646 1866 1087 642 1867 1088 644 1868 957 646 1869 1089 645 1870 1090 642 1871 955 647 1872 1091 645 1873 1092 646 1874 959 582 1875 895 645 1876 958 647 1877 960 680 1878 1125 648 1879 1093 649 1880 1094 652 1881 1097 650 1882 1095 651 1883 1096 654 1884 1099 650 1885 1095 652 1886 1097 654 1887 1099 653 1888 1098 650 1889 1095 655 1890 1100 653 1891 1098 654 1892 1099 657 1893 1102 653 1894 1098 655 1895 1100 657 1896 1102 656 1897 1101 653 1898 1098 659 1899 1104 656 1900 1101 657 1901 1102 659 1902 1104 658 1903 1103 656 1904 1101 661 1905 1106 658 1906 1103 659 1907 1104 661 1908 1106 660 1909 1105 658 1910 1103 663 1911 1108 660 1912 1105 661 1913 1106 663 1914 1108 662 1915 1107 660 1916 1105 665 1917 1110 662 1918 1107 663 1919 1108 665 1920 1110 664 1921 1109 662 1922 1107 667 1923 1112 664 1924 1109 665 1925 1110 667 1926 1112 666 1927 1111 664 1928 1109 669 1929 1114 666 1930 1111 667 1931 1112 669 1932 1114 668 1933 1113 666 1934 1111 671 1935 1116 668 1936 1113 669 1937 1114 671 1938 1116 670 1939 1115 668 1940 1113 673 1941 1118 670 1942 1115 671 1943 1116 673 1944 1118 672 1945 1117 670 1946 1115 676 1947 1121 672 1948 1117 673 1949 1118 676 1950 1121 674 1951 1119 672 1952 1117 676 1953 1121 675 1954 1120 674 1955 1119 677 1956 1122 675 1957 1120 676 1958 1121 679 1959 1124 675 1960 1120 677 1961 1122 679 1962 1124 678 1963 1123 675 1964 1120 681 1965 1126 678 1966 1123 679 1967 1124 681 1968 1126 680 1969 1125 678 1970 1123 648 1971 1093 680 1972 1125 681 1973 1126 686 1974 1131 682 1975 1132 683 1976 1128 682 1977 1127 684 1978 1129 685 1979 1130 682 1980 1133 686 1981 1131 684 1982 1134 702 1983 1150 687 1984 1135 688 1985 1136 692 1986 1140 689 1987 1137 690 1988 1138 692 1989 1140 691 1990 1139 689 1991 1137 694 1992 1142 691 1993 1139 692 1994 1140 694 1995 1142 693 1996 1141 691 1997 1139 696 1998 1144 693 1999 1141 694 2000 1142 696 2001 1144 695 2002 1143 693 2003 1141 698 2004 1146 695 2005 1143 696 2006 1144 698 2007 1146 697 2008 1145 695 2009 1143 700 2010 1148 697 2011 1145 698 2012 1146 700 2013 1148 699 2014 1147 697 2015 1145 703 2016 1151 699 2017 1147 700 2018 1148 703 2019 1151 701 2020 1149 699 2021 1147 703 2022 1151 702 2023 1150 701 2024 1149 704 2025 1152 702 2026 1150 703 2027 1151 687 2028 1135 702 2029 1150 704 2030 1152 709 2031 1157 705 2032 1153 706 2033 1154 705 2034 1153 707 2035 1155 708 2036 1156 705 2037 1153 709 2038 1157 707 2039 1155 775 2040 1224 712 2041 1225 710 2042 1226 712 2043 1227 711 2044 1228 710 2045 1158 714 2046 1229 711 2047 1230 712 2048 1231 714 2049 1232 713 2050 1233 711 2051 1159 715 2052 1234 713 2053 1235 714 2054 1162 717 2055 1236 713 2056 1237 715 2057 1163 717 2058 1238 716 2059 1239 713 2060 1161 719 2061 1240 716 2062 1241 717 2063 1165 719 2064 1242 718 2065 1243 716 2066 1164 720 2067 1244 718 2068 1245 719 2069 1167 722 2070 1246 718 2071 1247 720 2072 1168 722 2073 1248 721 2074 1249 718 2075 1166 724 2076 1250 721 2077 1251 722 2078 1170 724 2079 1252 723 2080 1253 721 2081 1169 725 2082 1254 723 2083 1255 724 2084 1172 727 2085 1256 723 2086 1257 725 2087 1173 727 2088 1258 726 2089 1259 723 2090 1171 728 2091 1260 726 2092 1261 727 2093 1175 730 2094 1262 726 2095 1263 728 2096 1176 730 2097 1264 729 2098 1265 726 2099 1174 732 2100 1266 729 2101 1267 730 2102 1178 732 2103 1268 731 2104 1269 729 2105 1177 733 2106 1270 731 2107 1271 732 2108 1180 735 2109 1272 731 2110 1273 733 2111 1181 735 2112 1274 734 2113 1275 731 2114 1179 737 2115 1276 734 2116 1277 735 2117 1183 737 2118 1278 736 2119 1279 734 2120 1182 740 2121 1280 736 2122 1281 737 2123 1185 740 2124 1282 738 2125 1283 736 2126 1184 740 2127 1284 739 2128 1285 738 2129 1186 745 2130 1286 739 2131 1287 740 2132 1188 745 2133 1288 741 2134 1289 739 2135 1187 745 2136 1290 742 2137 1291 741 2138 1189 745 2139 1292 743 2140 1293 742 2141 1190 745 2142 1294 744 2143 1295 743 2144 1191 747 2145 1296 744 2146 1297 745 2147 1193 747 2148 1298 746 2149 1299 744 2150 1192 748 2151 1300 746 2152 1301 747 2153 1195 750 2154 1302 746 2155 1303 748 2156 1196 750 2157 1304 749 2158 1305 746 2159 1194 752 2160 1306 749 2161 1307 750 2162 1198 752 2163 1308 751 2164 1309 749 2165 1197 753 2166 1310 751 2167 1311 752 2168 1200 755 2169 1312 751 2170 1313 753 2171 1201 755 2172 1314 754 2173 1315 751 2174 1199 757 2175 1316 754 2176 1317 755 2177 1203 757 2178 1318 756 2179 1319 754 2180 1202 758 2181 1320 756 2182 1321 757 2183 1205 760 2184 1322 756 2185 1323 758 2186 1206 760 2187 1324 759 2188 1325 756 2189 1204 761 2190 1326 759 2191 1327 760 2192 1208 763 2193 1328 759 2194 1329 761 2195 1209 763 2196 1330 762 2197 1331 759 2198 1207 765 2199 1332 762 2200 1333 763 2201 1211 765 2202 1334 764 2203 1335 762 2204 1210 766 2205 1336 764 2206 1337 765 2207 1213 768 2208 1338 764 2209 1339 766 2210 1214 768 2211 1340 767 2212 1341 764 2213 1212 770 2214 1342 767 2215 1343 768 2216 1216 770 2217 1344 769 2218 1345 767 2219 1215 773 2220 1346 769 2221 1347 770 2222 1218 773 2223 1348 771 2224 1349 769 2225 1217 773 2226 1350 772 2227 1351 771 2228 1219 712 2229 1352 772 2230 1353 773 2231 1221 712 2232 1354 774 2233 1355 772 2234 1220 712 2235 1160 775 2236 1223 774 2237 1222 793 2238 1373 776 2239 1356 777 2240 1357 780 2241 1360 778 2242 1358 779 2243 1359 782 2244 1362 778 2245 1358 780 2246 1360 782 2247 1362 781 2248 1361 778 2249 1358 784 2250 1364 781 2251 1361 782 2252 1362 784 2253 1364 783 2254 1363 781 2255 1361 786 2256 1366 783 2257 1363 784 2258 1364 786 2259 1366 785 2260 1365 783 2261 1363 787 2262 1367 785 2263 1365 786 2264 1366 790 2265 1370 785 2266 1365 787 2267 1367 790 2268 1370 788 2269 1368 785 2270 1365 790 2271 1370 789 2272 1369 788 2273 1368 792 2274 1372 789 2275 1369 790 2276 1370 792 2277 1372 791 2278 1371 789 2279 1369 776 2280 1356 791 2281 1371 792 2282 1372 776 2283 1356 793 2284 1373 791 2285 1371 796 2286 1376 794 2287 1374 795 2288 1375 794 2289 1374 796 2290 1376 797 2291 1377 830 2292 1410 798 2293 1378 799 2294 1379 802 2295 1382 800 2296 1380 801 2297 1381 803 2298 1383 800 2299 1380 802 2300 1382 805 2301 1385 800 2302 1380 803 2303 1383 805 2304 1385 804 2305 1384 800 2306 1380 807 2307 1387 804 2308 1384 805 2309 1385 807 2310 1387 806 2311 1386 804 2312 1384 809 2313 1389 806 2314 1386 807 2315 1387 809 2316 1389 808 2317 1388 806 2318 1386 811 2319 1391 808 2320 1388 809 2321 1389 811 2322 1391 810 2323 1390 808 2324 1388 813 2325 1393 810 2326 1390 811 2327 1391 813 2328 1393 812 2329 1392 810 2330 1390 815 2331 1395 812 2332 1392 813 2333 1393 815 2334 1395 814 2335 1394 812 2336 1392 817 2337 1397 814 2338 1394 815 2339 1395 817 2340 1397 816 2341 1396 814 2342 1394 819 2343 1399 816 2344 1396 817 2345 1397 819 2346 1399 818 2347 1398 816 2348 1396 821 2349 1401 818 2350 1398 819 2351 1399 821 2352 1401 820 2353 1400 818 2354 1398 823 2355 1403 820 2356 1400 821 2357 1401 823 2358 1403 822 2359 1402 820 2360 1400 825 2361 1405 822 2362 1402 823 2363 1403 825 2364 1405 824 2365 1404 822 2366 1402 827 2367 1407 824 2368 1404 825 2369 1405 827 2370 1407 826 2371 1406 824 2372 1404 829 2373 1409 826 2374 1406 827 2375 1407 829 2376 1409 828 2377 1408 826 2378 1406 831 2379 1411 828 2380 1408 829 2381 1409 831 2382 1411 830 2383 1410 828 2384 1408 798 2385 1378 830 2386 1410 831 2387 1411 834 2388 1416 832 2389 1412 833 2390 1413 832 2391 1412 834 2392 1414 835 2393 1415 901 2394 1483 836 2395 1484 842 2396 1485 901 2397 1486 843 2398 1487 837 2399 1488 901 2400 1489 838 2401 1490 843 2402 1491 901 2403 1492 839 2404 1493 838 2405 1419 901 2406 1494 840 2407 1495 839 2408 1420 901 2409 1496 841 2410 1497 840 2411 1421 901 2412 1498 842 2413 1423 841 2414 1422 845 2415 1499 837 2416 1500 843 2417 1424 845 2418 1501 844 2419 1502 837 2420 1418 847 2421 1503 844 2422 1504 845 2423 1426 847 2424 1505 846 2425 1506 844 2426 1425 850 2427 1507 846 2428 1508 847 2429 1428 850 2430 1509 848 2431 1510 846 2432 1427 850 2433 1511 849 2434 1512 848 2435 1429 853 2436 1513 849 2437 1514 850 2438 1431 853 2439 1515 851 2440 1516 849 2441 1430 853 2442 1517 852 2443 1518 851 2444 1432 855 2445 1519 852 2446 1520 853 2447 1434 855 2448 1521 854 2449 1522 852 2450 1433 858 2451 1523 854 2452 1524 855 2453 1436 858 2454 1525 856 2455 1526 854 2456 1435 858 2457 1527 857 2458 1528 856 2459 1437 861 2460 1529 857 2461 1530 858 2462 1439 861 2463 1531 859 2464 1532 857 2465 1438 861 2466 1533 860 2467 1534 859 2468 1440 864 2469 1535 860 2470 1536 861 2471 1442 864 2472 1537 862 2473 1538 860 2474 1441 864 2475 1539 863 2476 1540 862 2477 1443 866 2478 1541 863 2479 1542 864 2480 1445 866 2481 1543 865 2482 1544 863 2483 1444 869 2484 1545 865 2485 1546 866 2486 1447 869 2487 1547 867 2488 1548 865 2489 1446 869 2490 1549 868 2491 1550 867 2492 1448 871 2493 1551 868 2494 1552 869 2495 1450 871 2496 1553 870 2497 1554 868 2498 1449 872 2499 1555 870 2500 1556 871 2501 1452 873 2502 1557 870 2503 1558 872 2504 1453 874 2505 1559 870 2506 1560 873 2507 1454 875 2508 1561 870 2509 1562 874 2510 1455 876 2511 1563 870 2512 1564 875 2513 1456 878 2514 1565 870 2515 1566 876 2516 1457 878 2517 1567 877 2518 1568 870 2519 1451 880 2520 1569 877 2521 1570 878 2522 1459 880 2523 1571 879 2524 1572 877 2525 1458 883 2526 1573 879 2527 1574 880 2528 1461 883 2529 1575 881 2530 1576 879 2531 1460 883 2532 1577 882 2533 1578 881 2534 1462 886 2535 1579 882 2536 1580 883 2537 1464 886 2538 1581 884 2539 1582 882 2540 1463 886 2541 1583 885 2542 1584 884 2543 1465 888 2544 1585 885 2545 1586 886 2546 1467 888 2547 1587 887 2548 1588 885 2549 1466 891 2550 1589 887 2551 1590 888 2552 1469 891 2553 1591 889 2554 1592 887 2555 1468 891 2556 1593 890 2557 1594 889 2558 1470 894 2559 1595 890 2560 1596 891 2561 1472 894 2562 1597 892 2563 1598 890 2564 1471 894 2565 1599 893 2566 1600 892 2567 1473 897 2568 1601 893 2569 1602 894 2570 1475 897 2571 1603 895 2572 1604 893 2573 1474 897 2574 1605 896 2575 1606 895 2576 1476 899 2577 1607 896 2578 1608 897 2579 1478 899 2580 1609 898 2581 1610 896 2582 1477 836 2583 1611 898 2584 1612 899 2585 1480 836 2586 1613 900 2587 1614 898 2588 1479 836 2589 1417 901 2590 1482 900 2591 1481 965 2592 1679 902 2593 1680 904 2594 1681 904 2595 1682 903 2596 1683 965 2597 1684 906 2598 1685 903 2599 1686 904 2600 1617 906 2601 1687 905 2602 1688 903 2603 1616 908 2604 1689 905 2605 1690 906 2606 1619 908 2607 1691 907 2608 1692 905 2609 1618 910 2610 1693 907 2611 1694 908 2612 1621 910 2613 1695 909 2614 1696 907 2615 1620 912 2616 1697 909 2617 1698 910 2618 1623 912 2619 1699 911 2620 1700 909 2621 1622 914 2622 1701 911 2623 1702 912 2624 1625 914 2625 1703 913 2626 1704 911 2627 1624 916 2628 1705 913 2629 1706 914 2630 1627 916 2631 1707 915 2632 1708 913 2633 1626 918 2634 1709 915 2635 1710 916 2636 1629 918 2637 1711 917 2638 1712 915 2639 1628 920 2640 1713 917 2641 1714 918 2642 1631 920 2643 1715 919 2644 1716 917 2645 1630 922 2646 1717 919 2647 1718 920 2648 1633 922 2649 1719 921 2650 1720 919 2651 1632 924 2652 1721 921 2653 1722 922 2654 1635 924 2655 1723 923 2656 1724 921 2657 1634 926 2658 1725 923 2659 1726 924 2660 1637 926 2661 1727 925 2662 1728 923 2663 1636 928 2664 1729 925 2665 1730 926 2666 1639 928 2667 1731 927 2668 1732 925 2669 1638 930 2670 1733 927 2671 1734 928 2672 1641 930 2673 1735 929 2674 1736 927 2675 1640 932 2676 1737 929 2677 1738 930 2678 1643 932 2679 1739 931 2680 1740 929 2681 1642 934 2682 1741 931 2683 1742 932 2684 1645 934 2685 1743 933 2686 1744 931 2687 1644 936 2688 1745 933 2689 1746 934 2690 1647 936 2691 1747 935 2692 1748 933 2693 1646 938 2694 1749 935 2695 1750 936 2696 1649 938 2697 1751 937 2698 1752 935 2699 1648 940 2700 1753 937 2701 1754 938 2702 1651 940 2703 1755 939 2704 1756 937 2705 1650 942 2706 1757 939 2707 1758 940 2708 1653 942 2709 1759 941 2710 1760 939 2711 1652 944 2712 1761 941 2713 1762 942 2714 1655 944 2715 1763 943 2716 1764 941 2717 1654 946 2718 1765 943 2719 1766 944 2720 1657 946 2721 1767 945 2722 1768 943 2723 1656 948 2724 1769 945 2725 1770 946 2726 1659 948 2727 1771 947 2728 1772 945 2729 1658 950 2730 1773 947 2731 1774 948 2732 1661 950 2733 1775 949 2734 1776 947 2735 1660 952 2736 1777 949 2737 1778 950 2738 1663 952 2739 1779 951 2740 1780 949 2741 1662 954 2742 1781 951 2743 1782 952 2744 1665 954 2745 1783 953 2746 1784 951 2747 1664 956 2748 1785 953 2749 1786 954 2750 1667 956 2751 1787 955 2752 1788 953 2753 1666 958 2754 1789 955 2755 1790 956 2756 1669 958 2757 1791 957 2758 1792 955 2759 1668 960 2760 1793 957 2761 1794 958 2762 1671 960 2763 1795 959 2764 1796 957 2765 1670 962 2766 1797 959 2767 1798 960 2768 1673 962 2769 1799 961 2770 1800 959 2771 1672 964 2772 1801 961 2773 1802 962 2774 1675 964 2775 1803 963 2776 1804 961 2777 1674 902 2778 1805 963 2779 1806 964 2780 1677 902 2781 1615 965 2782 1678 963 2783 1676 998 2784 1839 966 2785 1807 967 2786 1808 971 2787 1812 968 2788 1809 969 2789 1810 971 2790 1812 970 2791 1811 968 2792 1809 973 2793 1814 970 2794 1811 971 2795 1812 973 2796 1814 972 2797 1813 970 2798 1811 975 2799 1816 972 2800 1813 973 2801 1814 975 2802 1816 974 2803 1815 972 2804 1813 977 2805 1818 974 2806 1815 975 2807 1816 977 2808 1818 976 2809 1817 974 2810 1815 979 2811 1820 976 2812 1817 977 2813 1818 979 2814 1820 978 2815 1819 976 2816 1817 981 2817 1822 978 2818 1819 979 2819 1820 981 2820 1822 980 2821 1821 978 2822 1819 983 2823 1824 980 2824 1821 981 2825 1822 983 2826 1824 982 2827 1823 980 2828 1821 985 2829 1826 982 2830 1823 983 2831 1824 985 2832 1826 984 2833 1825 982 2834 1823 987 2835 1828 984 2836 1825 985 2837 1826 987 2838 1828 986 2839 1827 984 2840 1825 990 2841 1831 986 2842 1827 987 2843 1828 990 2844 1831 988 2845 1829 986 2846 1827 990 2847 1831 989 2848 1830 988 2849 1829 991 2850 1832 989 2851 1830 990 2852 1831 994 2853 1835 989 2854 1830 991 2855 1832 994 2856 1835 992 2857 1833 989 2858 1830 994 2859 1835 993 2860 1834 992 2861 1833 996 2862 1837 993 2863 1834 994 2864 1835 996 2865 1837 995 2866 1836 993 2867 1834 997 2868 1838 995 2869 1836 996 2870 1837 999 2871 1840 995 2872 1836 997 2873 1838 999 2874 1840 998 2875 1839 995 2876 1836 966 2877 1807 998 2878 1839 999 2879 1840 1002 2880 1843 1000 2881 1841 1001 2882 1842 1000 2883 1841 1002 2884 1843 1003 2885 1844 1006 2886 1847 1004 2887 1845 1005 2888 1846 1004 2889 1845 1006 2890 1847 1007 2891 1848 1010 2892 1851 1008 2893 1849 1009 2894 1850 1008 2895 1849 1010 2896 1851 1011 2897 1852 1014 2898 1855 1012 2899 1853 1013 2900 1854 1012 2901 1853 1014 2902 1855 1015 2903 1856 1018 2904 1859 1016 2905 1857 1017 2906 1858 1016 2907 1857 1018 2908 1859 1019 2909 1860 1022 2910 1863 1020 2911 1861 1021 2912 1862 1020 2913 1861 1022 2914 1863 1023 2915 1864 1026 2916 1867 1024 2917 1865 1025 2918 1866 1024 2919 1865 1026 2920 1867 1027 2921 1868 1030 2922 1871 1028 2923 1869 1029 2924 1870 1028 2925 1869 1030 2926 1871 1031 2927 1872

+
+
+ + + + +-3.500000 0.000000 0.000000 +-3.500000 0.000000 1.500000 +3.500000 0.000000 1.500000 +3.500000 0.000000 0.000000 +3.441569 -0.636871 1.500000 +3.441569 -0.636871 0.000000 +3.254259 -1.288332 1.500000 +3.254259 -1.288332 0.000000 +2.929484 -1.915234 1.500000 +2.929484 -1.915234 0.000000 +2.474874 -2.474874 1.500000 +2.474874 -2.474874 0.000000 +1.915234 -2.929484 1.500000 +1.915234 -2.929484 0.000000 +1.288332 -3.254259 1.500000 +1.288332 -3.254259 0.000000 +0.636871 -3.441569 1.500000 +0.636871 -3.441569 0.000000 +0.000000 -3.500000 1.500000 +0.000000 -3.500000 0.000000 +-0.636871 -3.441569 1.500000 +-0.636871 -3.441569 0.000000 +-1.288332 -3.254259 1.500000 +-1.288332 -3.254259 0.000000 +-1.915234 -2.929484 1.500000 +-1.915234 -2.929484 0.000000 +-2.474874 -2.474874 1.500000 +-2.474874 -2.474874 0.000000 +-2.929484 -1.915234 1.500000 +-2.929484 -1.915234 0.000000 +-3.254259 -1.288332 1.500000 +-3.254259 -1.288332 0.000000 +-3.441569 -0.636871 1.500000 +-3.441569 -0.636871 0.000000 +6.000000 0.000000 1.500000 +6.000000 0.000000 0.000000 +-6.000000 0.000000 0.000000 +-6.000000 0.000000 1.500000 +-5.975729 0.539127 0.000000 +-5.975729 0.539127 1.500000 +-5.899832 1.091778 0.000000 +-5.899832 1.091778 1.500000 +-5.768394 1.650949 0.000000 +-5.768394 1.650949 1.500000 +-5.578730 2.208568 0.000000 +-5.578730 2.208568 1.500000 +-5.329704 2.755768 0.000000 +-5.329704 2.755768 1.500000 +-5.021973 3.283258 0.000000 +-5.021973 3.283258 1.500000 +-4.658119 3.781789 0.000000 +-4.658119 3.781789 1.500000 +-4.242640 4.242640 0.000000 +-4.242640 4.242640 1.500000 +-3.781789 4.658119 0.000000 +-3.781789 4.658119 1.500000 +-3.283258 5.021973 0.000000 +-3.283258 5.021973 1.500000 +-2.755768 5.329704 0.000000 +-2.755768 5.329704 1.500000 +-2.208568 5.578730 0.000000 +-2.208568 5.578730 1.500000 +-1.650949 5.768394 0.000000 +-1.650949 5.768394 1.500000 +-1.091778 5.899832 0.000000 +-1.091778 5.899832 1.500000 +-0.539127 5.975729 0.000000 +-0.539127 5.975729 1.500000 +0.000000 6.000000 0.000000 +0.000000 6.000000 1.500000 +0.539127 5.975729 0.000000 +1.091778 5.899832 0.000000 +0.539127 5.975729 1.500000 +1.650949 5.768394 0.000000 +1.091778 5.899832 1.500000 +2.208568 5.578730 0.000000 +1.650949 5.768394 1.500000 +2.755768 5.329704 0.000000 +2.208568 5.578730 1.500000 +2.755768 5.329704 1.500000 +3.283258 5.021973 0.000000 +3.283258 5.021973 1.500000 +3.781789 4.658119 0.000000 +3.781789 4.658119 1.500000 +4.242640 4.242640 0.000000 +4.242640 4.242640 1.500000 +4.658119 3.781789 0.000000 +4.658119 3.781789 1.500000 +5.021973 3.283258 0.000000 +5.021973 3.283258 1.500000 +5.329704 2.755768 0.000000 +5.329704 2.755768 1.500000 +5.578730 2.208568 0.000000 +5.578730 2.208568 1.500000 +5.768394 1.650949 0.000000 +5.768394 1.650949 1.500000 +5.899832 1.091778 0.000000 +5.899832 1.091778 1.500000 +5.975729 0.539127 0.000000 +5.975729 0.539127 1.500000 +-2.208568 -5.578730 1.500000 +-2.755768 -5.329704 1.500000 +-1.288332 -3.254259 1.500000 +-3.283258 -5.021973 1.500000 +-3.781789 -4.658119 1.500000 +-1.915234 -2.929484 1.500000 +-4.242640 -4.242640 1.500000 +-4.658119 -3.781789 1.500000 +-2.474874 -2.474874 1.500000 +-5.021973 -3.283258 1.500000 +-5.329704 -2.755768 1.500000 +-2.929484 -1.915234 1.500000 +-5.578730 -2.208568 1.500000 +-5.768394 -1.650949 1.500000 +-3.254259 -1.288332 1.500000 +-5.899832 -1.091778 1.500000 +-5.975729 -0.539127 1.500000 +-3.441569 -0.636871 1.500000 +-6.000000 0.000000 1.500000 +-5.975729 0.539127 1.500000 +-3.500000 0.000000 1.500000 +-5.899832 1.091778 1.500000 +-5.768394 1.650949 1.500000 +-3.441569 0.636871 1.500000 +-5.578730 2.208568 1.500000 +-5.329704 2.755768 1.500000 +-3.254259 1.288332 1.500000 +-5.021973 3.283258 1.500000 +-4.658119 3.781789 1.500000 +-2.929484 1.915234 1.500000 +-4.242640 4.242640 1.500000 +-3.781789 4.658119 1.500000 +-2.474874 2.474874 1.500000 +-3.283258 5.021973 1.500000 +-2.755768 5.329704 1.500000 +-1.915234 2.929484 1.500000 +-2.208568 5.578730 1.500000 +-1.650949 5.768394 1.500000 +-1.288332 3.254259 1.500000 +-1.091778 5.899832 1.500000 +-0.539127 5.975729 1.500000 +-0.636871 3.441569 1.500000 +0.539127 5.975729 1.500000 +0.000000 3.500000 1.500000 +1.091778 5.899832 1.500000 +1.650949 5.768394 1.500000 +0.636871 3.441569 1.500000 +2.208568 5.578730 1.500000 +2.755768 5.329704 1.500000 +1.288332 3.254259 1.500000 +3.283258 5.021973 1.500000 +3.781789 4.658119 1.500000 +1.915234 2.929484 1.500000 +4.242640 4.242640 1.500000 +4.658119 3.781789 1.500000 +2.474874 2.474874 1.500000 +5.021973 3.283258 1.500000 +5.329704 2.755768 1.500000 +2.929484 1.915234 1.500000 +5.578730 2.208568 1.500000 +5.768394 1.650949 1.500000 +3.254259 1.288332 1.500000 +5.899832 1.091778 1.500000 +5.975729 0.539127 1.500000 +3.441569 0.636871 1.500000 +6.000000 0.000000 1.500000 +5.975729 -0.539127 1.500000 +3.500000 0.000000 1.500000 +5.899832 -1.091778 1.500000 +5.768394 -1.650949 1.500000 +3.441569 -0.636871 1.500000 +5.578730 -2.208568 1.500000 +5.329704 -2.755768 1.500000 +3.254259 -1.288332 1.500000 +5.021973 -3.283258 1.500000 +4.658119 -3.781789 1.500000 +2.929484 -1.915234 1.500000 +4.242640 -4.242640 1.500000 +3.781789 -4.658119 1.500000 +2.474874 -2.474874 1.500000 +3.283258 -5.021973 1.500000 +2.755768 -5.329704 1.500000 +1.915234 -2.929484 1.500000 +2.208568 -5.578730 1.500000 +1.650949 -5.768394 1.500000 +1.288332 -3.254259 1.500000 +1.091778 -5.899832 1.500000 +0.539127 -5.975729 1.500000 +0.636871 -3.441569 1.500000 +-0.539127 -5.975729 1.500000 +0.000000 -3.500000 1.500000 +-1.091778 -5.899832 1.500000 +-1.650949 -5.768394 1.500000 +-0.636871 -3.441569 1.500000 +-2.208568 -5.578730 0.000000 +-1.650949 -5.768394 0.000000 +-1.288332 -3.254259 0.000000 +-1.091778 -5.899832 0.000000 +-0.539127 -5.975729 0.000000 +-0.636871 -3.441569 0.000000 +0.539127 -5.975729 0.000000 +0.000000 -3.500000 0.000000 +1.091778 -5.899832 0.000000 +1.650949 -5.768394 0.000000 +0.636871 -3.441569 0.000000 +2.208568 -5.578730 0.000000 +2.755768 -5.329704 0.000000 +1.288332 -3.254259 0.000000 +3.283258 -5.021973 0.000000 +3.781789 -4.658119 0.000000 +1.915234 -2.929484 0.000000 +4.242640 -4.242640 0.000000 +4.658119 -3.781789 0.000000 +2.474874 -2.474874 0.000000 +5.021973 -3.283258 0.000000 +5.329704 -2.755768 0.000000 +2.929484 -1.915234 0.000000 +5.578730 -2.208568 0.000000 +5.768394 -1.650949 0.000000 +3.254259 -1.288332 0.000000 +5.899832 -1.091778 0.000000 +5.975729 -0.539127 0.000000 +3.441569 -0.636871 0.000000 +6.000000 0.000000 0.000000 +5.975729 0.539127 0.000000 +3.500000 0.000000 0.000000 +5.899832 1.091778 0.000000 +5.768394 1.650949 0.000000 +3.441569 0.636871 0.000000 +5.578730 2.208568 0.000000 +5.329704 2.755768 0.000000 +3.254259 1.288332 0.000000 +5.021973 3.283258 0.000000 +4.658119 3.781789 0.000000 +2.929484 1.915234 0.000000 +4.242640 4.242640 0.000000 +3.781789 4.658119 0.000000 +2.474874 2.474874 0.000000 +3.283258 5.021973 0.000000 +2.755768 5.329704 0.000000 +1.915234 2.929484 0.000000 +2.208568 5.578730 0.000000 +1.650949 5.768394 0.000000 +1.288332 3.254259 0.000000 +1.091778 5.899832 0.000000 +0.539127 5.975729 0.000000 +0.636871 3.441569 0.000000 +-0.539127 5.975729 0.000000 +0.000000 3.500000 0.000000 +-1.091778 5.899832 0.000000 +-1.650949 5.768394 0.000000 +-0.636871 3.441569 0.000000 +-2.208568 5.578730 0.000000 +-2.755768 5.329704 0.000000 +-1.288332 3.254259 0.000000 +-3.283258 5.021973 0.000000 +-3.781789 4.658119 0.000000 +-1.915234 2.929484 0.000000 +-4.242640 4.242640 0.000000 +-4.658119 3.781789 0.000000 +-2.474874 2.474874 0.000000 +-5.021973 3.283258 0.000000 +-5.329704 2.755768 0.000000 +-2.929484 1.915234 0.000000 +-5.578730 2.208568 0.000000 +-5.768394 1.650949 0.000000 +-3.254259 1.288332 0.000000 +-5.899832 1.091778 0.000000 +-5.975729 0.539127 0.000000 +-3.441569 0.636871 0.000000 +-6.000000 0.000000 0.000000 +-5.975729 -0.539127 0.000000 +-3.500000 0.000000 0.000000 +-5.899832 -1.091778 0.000000 +-5.768394 -1.650949 0.000000 +-3.441569 -0.636871 0.000000 +-5.578730 -2.208568 0.000000 +-5.329704 -2.755768 0.000000 +-3.254259 -1.288332 0.000000 +-5.021973 -3.283258 0.000000 +-4.658119 -3.781789 0.000000 +-2.929484 -1.915234 0.000000 +-4.242640 -4.242640 0.000000 +-3.781789 -4.658119 0.000000 +-2.474874 -2.474874 0.000000 +-3.283258 -5.021973 0.000000 +-2.755768 -5.329704 0.000000 +-1.915234 -2.929484 0.000000 +6.000000 0.000000 0.000000 +6.000000 0.000000 1.500000 +-6.000000 0.000000 1.500000 +-6.000000 0.000000 0.000000 +-5.975729 -0.539127 1.500000 +-5.975729 -0.539127 0.000000 +-5.899832 -1.091778 1.500000 +-5.899832 -1.091778 0.000000 +-5.768394 -1.650949 1.500000 +-5.768394 -1.650949 0.000000 +-5.578730 -2.208568 1.500000 +-5.578730 -2.208568 0.000000 +-5.329704 -2.755768 1.500000 +-5.329704 -2.755768 0.000000 +-5.021973 -3.283258 1.500000 +-5.021973 -3.283258 0.000000 +-4.658119 -3.781789 1.500000 +-4.658119 -3.781789 0.000000 +-4.242640 -4.242640 1.500000 +-4.242640 -4.242640 0.000000 +-3.781789 -4.658119 1.500000 +-3.781789 -4.658119 0.000000 +-3.283258 -5.021973 1.500000 +-3.283258 -5.021973 0.000000 +-2.755768 -5.329704 1.500000 +-2.755768 -5.329704 0.000000 +-2.208568 -5.578730 1.500000 +-2.208568 -5.578730 0.000000 +-1.650949 -5.768394 1.500000 +-1.650949 -5.768394 0.000000 +-1.091778 -5.899832 1.500000 +-1.091778 -5.899832 0.000000 +-0.539127 -5.975729 1.500000 +-0.539127 -5.975729 0.000000 +0.000000 -6.000000 1.500000 +0.000000 -6.000000 0.000000 +0.539127 -5.975729 1.500000 +0.539127 -5.975729 0.000000 +1.091778 -5.899832 1.500000 +1.091778 -5.899832 0.000000 +1.650949 -5.768394 1.500000 +1.650949 -5.768394 0.000000 +2.208568 -5.578730 1.500000 +2.208568 -5.578730 0.000000 +2.755768 -5.329704 1.500000 +2.755768 -5.329704 0.000000 +3.283258 -5.021973 1.500000 +3.283258 -5.021973 0.000000 +3.781789 -4.658119 1.500000 +3.781789 -4.658119 0.000000 +4.242640 -4.242640 1.500000 +4.242640 -4.242640 0.000000 +4.658119 -3.781789 1.500000 +4.658119 -3.781789 0.000000 +5.021973 -3.283258 1.500000 +5.021973 -3.283258 0.000000 +5.329704 -2.755768 1.500000 +5.329704 -2.755768 0.000000 +5.578730 -2.208568 1.500000 +5.578730 -2.208568 0.000000 +5.768394 -1.650949 1.500000 +5.768394 -1.650949 0.000000 +5.899832 -1.091778 1.500000 +5.899832 -1.091778 0.000000 +5.975729 -0.539127 1.500000 +5.975729 -0.539127 0.000000 +3.500000 0.000000 0.000000 +3.500000 0.000000 1.500000 +-3.441569 0.636871 1.500000 +-3.500000 0.000000 1.500000 +-3.500000 0.000000 0.000000 +-3.441569 0.636871 0.000000 +-3.254259 1.288332 1.500000 +-3.254259 1.288332 0.000000 +-2.929484 1.915234 1.500000 +-2.929484 1.915234 0.000000 +-2.474874 2.474874 1.500000 +-2.474874 2.474874 0.000000 +-1.915234 2.929484 1.500000 +-1.915234 2.929484 0.000000 +-1.288332 3.254259 1.500000 +-1.288332 3.254259 0.000000 +-0.636871 3.441569 1.500000 +-0.636871 3.441569 0.000000 +0.000000 3.500000 1.500000 +0.000000 3.500000 0.000000 +0.636871 3.441569 1.500000 +0.636871 3.441569 0.000000 +1.288332 3.254259 1.500000 +1.288332 3.254259 0.000000 +1.915234 2.929484 1.500000 +1.915234 2.929484 0.000000 +2.474874 2.474874 1.500000 +2.474874 2.474874 0.000000 +2.929484 1.915234 1.500000 +2.929484 1.915234 0.000000 +3.254259 1.288332 1.500000 +3.254259 1.288332 0.000000 +3.441569 0.636871 1.500000 +3.441569 0.636871 0.000000 + + + + + + + + + + + +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.995955 0.089854 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.995955 0.089854 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.995955 0.089854 0.000000 +-0.995955 0.089854 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.995955 0.089854 0.000000 +-0.995955 0.089854 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.995955 0.089854 0.000000 +-0.961399 0.275158 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.961399 0.275158 0.000000 +-0.961399 0.275158 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.961399 0.275158 0.000000 +-0.961399 0.275158 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.961399 0.275158 0.000000 +-0.888284 0.459295 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.888284 0.459295 0.000000 +-0.888284 0.459295 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.888284 0.459295 0.000000 +-0.888284 0.459295 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.888284 0.459295 0.000000 +-0.776353 0.630298 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.776353 0.630298 0.000000 +-0.776353 0.630298 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.776353 0.630298 0.000000 +-0.776353 0.630298 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.776353 0.630298 0.000000 +-0.630298 0.776353 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.630298 0.776353 0.000000 +-0.630298 0.776353 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.630298 0.776353 0.000000 +-0.630298 0.776353 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.630298 0.776353 0.000000 +-0.459295 0.888284 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.459295 0.888284 0.000000 +-0.459295 0.888284 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.459295 0.888284 0.000000 +-0.459295 0.888284 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.459295 0.888284 0.000000 +-0.275158 0.961399 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.275158 0.961399 0.000000 +-0.275158 0.961399 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.275158 0.961399 0.000000 +-0.275158 0.961399 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.275158 0.961399 0.000000 +-0.089854 0.995955 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.089854 0.995955 0.000000 +-0.089854 0.995955 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.089854 0.995955 0.000000 +-0.089854 0.995955 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.089854 0.995955 0.000000 +0.089854 0.995955 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.089854 0.995955 0.000000 +0.089854 0.995955 0.000000 +0.000000 1.000000 0.000000 +0.089854 0.995955 0.000000 +0.181963 0.983305 0.000000 +0.089854 0.995955 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.089854 0.995955 0.000000 +0.181963 0.983305 0.000000 +0.275158 0.961399 0.000000 +0.181963 0.983305 0.000000 +0.275158 0.961399 0.000000 +0.275158 0.961399 0.000000 +0.181963 0.983305 0.000000 +0.275158 0.961399 0.000000 +0.368095 0.929788 0.000000 +0.275158 0.961399 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.275158 0.961399 0.000000 +0.368095 0.929788 0.000000 +0.459295 0.888284 0.000000 +0.368095 0.929788 0.000000 +0.459295 0.888284 0.000000 +0.459295 0.888284 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.459295 0.888284 0.000000 +0.459295 0.888284 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.459295 0.888284 0.000000 +0.630298 0.776353 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.630298 0.776353 0.000000 +0.630298 0.776353 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.630298 0.776353 0.000000 +0.630298 0.776353 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.630298 0.776353 0.000000 +0.776353 0.630298 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.776353 0.630298 0.000000 +0.776353 0.630298 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.776353 0.630298 0.000000 +0.776353 0.630298 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.776353 0.630298 0.000000 +0.888284 0.459295 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.888284 0.459295 0.000000 +0.888284 0.459295 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.888284 0.459295 0.000000 +0.888284 0.459295 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.888284 0.459295 0.000000 +0.961399 0.275158 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.961399 0.275158 0.000000 +0.961399 0.275158 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.961399 0.275158 0.000000 +0.961399 0.275158 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.961399 0.275158 0.000000 +0.995955 0.089854 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.995955 0.089854 0.000000 +0.995955 0.089854 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.995955 0.089854 0.000000 +0.995955 0.089854 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.995955 -0.089854 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.995955 -0.089854 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.995955 -0.089854 0.000000 +-0.995955 -0.089854 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.995955 -0.089854 0.000000 +-0.995955 -0.089854 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.995955 -0.089854 0.000000 +-0.961399 -0.275158 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.961399 -0.275158 0.000000 +-0.961399 -0.275158 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.961399 -0.275158 0.000000 +-0.961399 -0.275158 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.961399 -0.275158 0.000000 +-0.888284 -0.459295 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.888284 -0.459295 0.000000 +-0.888284 -0.459295 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.888284 -0.459295 0.000000 +-0.888284 -0.459295 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.888284 -0.459295 0.000000 +-0.776353 -0.630298 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.776353 -0.630298 0.000000 +-0.776353 -0.630298 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.776353 -0.630298 0.000000 +-0.776353 -0.630298 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.776353 -0.630298 0.000000 +-0.630298 -0.776353 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.630298 -0.776353 0.000000 +-0.630298 -0.776353 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.630298 -0.776353 0.000000 +-0.630298 -0.776353 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.630298 -0.776353 0.000000 +-0.459295 -0.888284 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.459295 -0.888284 0.000000 +-0.459295 -0.888284 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.459295 -0.888284 0.000000 +-0.459295 -0.888284 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.459295 -0.888284 0.000000 +-0.275158 -0.961399 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.275158 -0.961399 0.000000 +-0.275158 -0.961399 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.275158 -0.961399 0.000000 +-0.275158 -0.961399 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.275158 -0.961399 0.000000 +-0.089854 -0.995955 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.089854 -0.995955 0.000000 +-0.089854 -0.995955 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +-0.089854 -0.995955 0.000000 +-0.089854 -0.995955 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.089854 -0.995955 0.000000 +0.089854 -0.995955 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.089854 -0.995955 0.000000 +0.089854 -0.995955 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.089854 -0.995955 0.000000 +0.089854 -0.995955 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.089854 -0.995955 0.000000 +0.275158 -0.961399 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.275158 -0.961399 0.000000 +0.275158 -0.961399 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.275158 -0.961399 0.000000 +0.275158 -0.961399 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.275158 -0.961399 0.000000 +0.459295 -0.888284 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.459295 -0.888284 0.000000 +0.459295 -0.888284 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.459295 -0.888284 0.000000 +0.459295 -0.888284 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.459295 -0.888284 0.000000 +0.630298 -0.776353 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.630298 -0.776353 0.000000 +0.630298 -0.776353 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.630298 -0.776353 0.000000 +0.630298 -0.776353 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.630298 -0.776353 0.000000 +0.776353 -0.630298 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.776353 -0.630298 0.000000 +0.776353 -0.630298 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.776353 -0.630298 0.000000 +0.776353 -0.630298 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.776353 -0.630298 0.000000 +0.888284 -0.459295 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.888284 -0.459295 0.000000 +0.888284 -0.459295 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.888284 -0.459295 0.000000 +0.888284 -0.459295 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.888284 -0.459295 0.000000 +0.961399 -0.275158 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.961399 -0.275158 0.000000 +0.961399 -0.275158 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.961399 -0.275158 0.000000 +0.961399 -0.275158 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.961399 -0.275158 0.000000 +0.995955 -0.089854 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.995955 -0.089854 0.000000 +0.995955 -0.089854 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.995955 -0.089854 0.000000 +0.995955 -0.089854 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 + + + + + + + + + + + +0.528271 7.694943 +-0.000000 7.694943 +-0.000000 3.847472 +0.528271 3.847472 +-0.000000 4.087939 +0.528271 4.087939 +-0.000000 4.328406 +0.528271 4.328406 +-0.000000 4.568873 +0.528271 4.568873 +-0.000000 4.809340 +0.528271 4.809340 +-0.000000 5.049807 +0.528271 5.049807 +-0.000000 5.290274 +0.528271 5.290274 +-0.000000 5.530741 +0.528271 5.530741 +-0.000000 5.771208 +0.528271 5.771208 +-0.000000 6.011674 +0.528271 6.011674 +-0.000000 6.252141 +0.528271 6.252141 +-0.000000 6.492609 +0.528271 6.492609 +-0.000000 6.733076 +0.528271 6.733076 +-0.000000 6.973543 +0.528271 6.973543 +-0.000000 7.214009 +0.528271 7.214009 +-0.000000 7.454476 +0.528271 7.454476 +6.595666 0.000000 +6.595666 0.528271 +0.000000 0.528271 +0.000000 -0.000000 +0.206115 0.528271 +0.206115 -0.000000 +0.412229 0.528271 +0.412229 -0.000000 +0.618344 0.528271 +0.618344 -0.000000 +0.824458 0.528271 +0.824458 -0.000000 +1.030573 0.528271 +1.030573 -0.000000 +1.236687 0.528271 +1.236687 -0.000000 +1.442802 0.528271 +1.442802 -0.000000 +1.648916 0.528271 +1.648916 -0.000000 +1.855031 0.528271 +1.855031 -0.000000 +2.061146 0.528271 +2.061146 -0.000000 +2.267260 0.528271 +2.267260 -0.000000 +2.473375 0.528271 +2.473375 -0.000000 +2.679489 0.528271 +2.679489 -0.000000 +2.885604 0.528271 +2.885604 -0.000000 +3.091718 0.528271 +3.091718 -0.000000 +3.297833 0.528271 +3.297833 -0.000000 +3.503947 0.528271 +3.710062 0.528271 +3.503947 -0.000000 +3.916177 0.528271 +3.710062 -0.000000 +4.122291 0.528271 +3.916177 -0.000000 +4.328406 0.528271 +4.122291 -0.000000 +4.328406 -0.000000 +4.534520 0.528271 +4.534520 -0.000000 +4.740635 0.528271 +4.740635 -0.000000 +4.946749 0.528271 +4.946749 -0.000000 +5.152864 0.528271 +5.152864 -0.000000 +5.358978 0.528271 +5.358978 -0.000000 +5.565093 0.528271 +5.565093 -0.000000 +5.771208 0.528271 +5.771208 -0.000000 +5.977322 0.528271 +5.977322 -0.000000 +6.183437 0.528271 +6.183437 -0.000000 +6.389551 0.528271 +6.389551 0.000000 +-0.777814 -1.964719 +-0.970527 -1.876989 +-0.453725 -1.146086 +-1.156299 -1.768640 +-1.331857 -1.640472 +-0.674508 -1.031707 +-1.494175 -1.494175 +-1.640472 -1.331857 +-0.871602 -0.871602 +-1.768640 -1.156299 +-1.876989 -0.970527 +-1.031707 -0.674508 +-1.964719 -0.777814 +-2.031492 -0.581444 +-1.146086 -0.453725 +-2.077805 -0.384503 +-2.104522 -0.189888 +-1.212053 -0.224293 +-2.113082 -0.000000 +-2.104522 0.189888 +-1.232631 -0.000000 +-2.077805 0.384503 +-2.031492 0.581444 +-1.212053 0.224293 +-1.964719 0.777814 +-1.876989 0.970527 +-1.146086 0.453725 +-1.768640 1.156299 +-1.640472 1.331857 +-1.031707 0.674508 +-1.494175 1.494175 +-1.331857 1.640472 +-0.871602 0.871602 +-1.156299 1.768640 +-0.970527 1.876989 +-0.674508 1.031707 +-0.777814 1.964719 +-0.581444 2.031492 +-0.453725 1.146086 +-0.384503 2.077805 +-0.189888 2.104522 +-0.224293 1.212053 +0.189888 2.104522 +0.000000 1.232631 +0.384503 2.077805 +0.581444 2.031492 +0.224293 1.212053 +0.777814 1.964719 +0.970527 1.876989 +0.453725 1.146086 +1.156299 1.768640 +1.331857 1.640472 +0.674508 1.031707 +1.494175 1.494175 +1.640472 1.331857 +0.871602 0.871602 +1.768640 1.156299 +1.876989 0.970527 +1.031707 0.674508 +1.964719 0.777814 +2.031492 0.581444 +1.146086 0.453725 +2.077805 0.384503 +2.104522 0.189888 +1.212053 0.224293 +2.113082 -0.000000 +2.104522 -0.189888 +1.232631 -0.000000 +2.077805 -0.384503 +2.031492 -0.581444 +1.212053 -0.224293 +1.964719 -0.777814 +1.876989 -0.970527 +1.146086 -0.453725 +1.768640 -1.156299 +1.640472 -1.331857 +1.031707 -0.674508 +1.494175 -1.494175 +1.331857 -1.640472 +0.871602 -0.871602 +1.156299 -1.768640 +0.970527 -1.876989 +0.674508 -1.031707 +0.777814 -1.964719 +0.581444 -2.031492 +0.453725 -1.146086 +0.384503 -2.077805 +0.189888 -2.104522 +0.224293 -1.212053 +-0.189888 -2.104522 +-0.000000 -1.232631 +-0.384503 -2.077805 +-0.581444 -2.031492 +-0.224293 -1.212053 +-1.964719 -0.777814 +-2.031492 -0.581444 +-1.146086 -0.453725 +-2.077805 -0.384503 +-2.104522 -0.189888 +-1.212053 -0.224293 +-2.104522 0.189888 +-1.232631 0.000000 +-2.077805 0.384503 +-2.031492 0.581444 +-1.212053 0.224293 +-1.964719 0.777814 +-1.876989 0.970527 +-1.146086 0.453725 +-1.768640 1.156299 +-1.640472 1.331857 +-1.031707 0.674508 +-1.494175 1.494175 +-1.331857 1.640472 +-0.871602 0.871602 +-1.156299 1.768640 +-0.970527 1.876989 +-0.674508 1.031707 +-0.777814 1.964719 +-0.581444 2.031492 +-0.453725 1.146086 +-0.384503 2.077805 +-0.189888 2.104522 +-0.224293 1.212053 +-0.000000 2.113082 +0.189888 2.104522 +-0.000000 1.232631 +0.384503 2.077805 +0.581444 2.031492 +0.224293 1.212053 +0.777814 1.964719 +0.970527 1.876989 +0.453725 1.146086 +1.156299 1.768640 +1.331857 1.640472 +0.674508 1.031707 +1.494175 1.494175 +1.640472 1.331857 +0.871602 0.871602 +1.768640 1.156299 +1.876989 0.970527 +1.031707 0.674508 +1.964719 0.777814 +2.031492 0.581444 +1.146086 0.453725 +2.077805 0.384503 +2.104522 0.189888 +1.212053 0.224293 +2.104522 -0.189888 +1.232631 0.000000 +2.077805 -0.384503 +2.031492 -0.581444 +1.212053 -0.224293 +1.964719 -0.777814 +1.876989 -0.970527 +1.146086 -0.453725 +1.768640 -1.156299 +1.640472 -1.331857 +1.031707 -0.674508 +1.494175 -1.494175 +1.331857 -1.640472 +0.871602 -0.871602 +1.156299 -1.768640 +0.970527 -1.876989 +0.674508 -1.031707 +0.777814 -1.964719 +0.581444 -2.031492 +0.453725 -1.146086 +0.384503 -2.077805 +0.189888 -2.104522 +0.224293 -1.212053 +-0.000000 -2.113082 +-0.189888 -2.104522 +-0.000000 -1.232631 +-0.384503 -2.077805 +-0.581444 -2.031492 +-0.224293 -1.212053 +-0.777814 -1.964719 +-0.970527 -1.876989 +-0.453725 -1.146086 +-1.156299 -1.768640 +-1.331857 -1.640472 +-0.674508 -1.031707 +-1.494175 -1.494175 +-1.640472 -1.331857 +-0.871602 -0.871602 +-1.768640 -1.156299 +-1.876989 -0.970527 +-1.031707 -0.674508 +6.595666 0.528271 +6.595666 -0.000000 +13.191332 -0.000000 +13.191332 0.528271 +12.985217 -0.000000 +12.985217 0.528271 +12.779102 -0.000000 +12.779102 0.528271 +12.572988 -0.000000 +12.572988 0.528271 +12.366874 -0.000000 +12.366874 0.528271 +12.160759 -0.000000 +12.160759 0.528271 +11.954644 -0.000000 +11.954644 0.528271 +11.748529 -0.000000 +11.748529 0.528271 +11.542416 -0.000000 +11.542416 0.528271 +11.336301 -0.000000 +11.336301 0.528271 +11.130186 -0.000000 +11.130186 0.528271 +10.924071 -0.000000 +10.924071 0.528271 +10.717957 -0.000000 +10.717957 0.528271 +10.511843 -0.000000 +10.511843 0.528271 +10.305728 -0.000000 +10.305728 0.528271 +10.099613 -0.000000 +10.099613 0.528271 +9.893498 -0.000000 +9.893498 0.528271 +9.687385 -0.000000 +9.687385 0.528271 +9.481270 -0.000000 +9.481270 0.528271 +9.275155 -0.000000 +9.275155 0.528271 +9.069040 -0.000000 +9.069040 0.528271 +8.862926 -0.000000 +8.862926 0.528271 +8.656812 -0.000000 +8.656812 0.528271 +8.450697 -0.000000 +8.450697 0.528271 +8.244582 -0.000000 +8.244582 0.528271 +8.038467 -0.000000 +8.038467 0.528271 +7.832353 -0.000000 +7.832353 0.528271 +7.626239 -0.000000 +7.626239 0.528271 +7.420124 -0.000000 +7.420124 0.528271 +7.214009 -0.000000 +7.214009 0.528271 +7.007895 -0.000000 +7.007895 0.528271 +6.801780 -0.000000 +6.801780 0.528271 +0.528271 3.847472 +-0.000000 3.847472 +-0.000000 0.240467 +-0.000000 -0.000000 +0.528271 -0.000000 +0.528271 0.240467 +-0.000000 0.480934 +0.528271 0.480934 +-0.000000 0.721401 +0.528271 0.721401 +-0.000000 0.961868 +0.528271 0.961868 +-0.000000 1.202335 +0.528271 1.202335 +-0.000000 1.442802 +0.528271 1.442802 +-0.000000 1.683269 +0.528271 1.683269 +-0.000000 1.923736 +0.528271 1.923736 +-0.000000 2.164203 +0.528271 2.164203 +-0.000000 2.404670 +0.528271 2.404670 +-0.000000 2.645137 +0.528271 2.645137 +-0.000000 2.885604 +0.528271 2.885604 +-0.000000 3.126071 +0.528271 3.126071 +-0.000000 3.366538 +0.528271 3.366538 +-0.000000 3.607005 +0.528271 3.607005 + + + + + + + + + + + +

32 0 32 0 1 0 1 2 1 5 3 5 2 4 2 3 5 3 5 6 5 4 7 4 2 8 2 7 9 7 4 10 4 5 11 5 7 12 7 6 13 6 4 14 4 9 15 9 6 16 6 7 17 7 9 18 9 8 19 8 6 20 6 11 21 11 8 22 8 9 23 9 11 24 11 10 25 10 8 26 8 13 27 13 10 28 10 11 29 11 13 30 13 12 31 12 10 32 10 15 33 15 12 34 12 13 35 13 15 36 15 14 37 14 12 38 12 17 39 17 14 40 14 15 41 15 17 42 17 16 43 16 14 44 14 19 45 19 16 46 16 17 47 17 19 48 19 18 49 18 16 50 16 21 51 21 18 52 18 19 53 19 21 54 21 20 55 20 18 56 18 23 57 23 20 58 20 21 59 21 23 60 23 22 61 22 20 62 20 25 63 25 22 64 22 23 65 23 25 66 25 24 67 24 22 68 22 27 69 27 24 70 24 25 71 25 27 72 27 26 73 26 24 74 24 29 75 29 26 76 26 27 77 27 29 78 29 28 79 28 26 80 26 31 81 31 28 82 28 29 83 29 31 84 31 30 85 30 28 86 28 33 87 33 30 88 30 31 89 31 33 90 33 32 91 32 30 92 30 0 93 0 32 94 32 33 95 33 98 96 98 34 97 34 35 98 35 39 99 39 36 100 36 37 101 37 39 102 39 38 103 38 36 104 36 41 105 41 38 106 38 39 107 39 41 108 41 40 109 40 38 110 38 43 111 43 40 112 40 41 113 41 43 114 43 42 115 42 40 116 40 45 117 45 42 118 42 43 119 43 45 120 45 44 121 44 42 122 42 47 123 47 44 124 44 45 125 45 47 126 47 46 127 46 44 128 44 49 129 49 46 130 46 47 131 47 49 132 49 48 133 48 46 134 46 51 135 51 48 136 48 49 137 49 51 138 51 50 139 50 48 140 48 53 141 53 50 142 50 51 143 51 53 144 53 52 145 52 50 146 50 55 147 55 52 148 52 53 149 53 55 150 55 54 151 54 52 152 52 57 153 57 54 154 54 55 155 55 57 156 57 56 157 56 54 158 54 59 159 59 56 160 56 57 161 57 59 162 59 58 163 58 56 164 56 61 165 61 58 166 58 59 167 59 61 168 61 60 169 60 58 170 58 63 171 63 60 172 60 61 173 61 63 174 63 62 175 62 60 176 60 65 177 65 62 178 62 63 179 63 65 180 65 64 181 64 62 182 62 67 183 67 64 184 64 65 185 65 67 186 67 66 187 66 64 188 64 69 189 69 66 190 66 67 191 67 69 192 69 68 193 68 66 194 66 72 195 72 68 196 68 69 197 69 72 198 72 70 199 70 68 200 68 72 201 72 71 202 71 70 203 70 74 204 74 71 205 71 72 206 72 74 207 74 73 208 73 71 209 71 76 210 76 73 211 73 74 212 74 76 213 76 75 214 75 73 215 73 78 216 78 75 217 75 76 218 76 78 219 78 77 220 77 75 221 75 79 222 79 77 223 77 78 224 78 81 225 81 77 226 77 79 227 79 81 228 81 80 229 80 77 230 77 83 231 83 80 232 80 81 233 81 83 234 83 82 235 82 80 236 80 85 237 85 82 238 82 83 239 83 85 240 85 84 241 84 82 242 82 87 243 87 84 244 84 85 245 85 87 246 87 86 247 86 84 248 84 89 249 89 86 250 86 87 251 87 89 252 89 88 253 88 86 254 86 91 255 91 88 256 88 89 257 89 91 258 91 90 259 90 88 260 88 93 261 93 90 262 90 91 263 91 93 264 93 92 265 92 90 266 90 95 267 95 92 268 92 93 269 93 95 270 95 94 271 94 92 272 92 97 273 97 94 274 94 95 275 95 97 276 97 96 277 96 94 278 94 99 279 99 96 280 96 97 281 97 99 282 99 98 283 98 96 284 96 34 285 34 98 286 98 99 287 99 192 288 192 102 289 102 100 290 100 102 291 102 101 292 101 100 293 100 105 294 105 101 295 101 102 296 102 105 297 105 103 298 103 101 299 101 105 300 105 104 301 104 103 302 103 108 303 108 104 304 104 105 305 105 108 306 108 106 307 106 104 308 104 108 309 108 107 310 107 106 311 106 111 312 111 107 313 107 108 314 108 111 315 111 109 316 109 107 317 107 111 318 111 110 319 110 109 320 109 114 321 114 110 322 110 111 323 111 114 324 114 112 325 112 110 326 110 114 327 114 113 328 113 112 329 112 117 330 117 113 331 113 114 332 114 117 333 117 115 334 115 113 335 113 117 336 117 116 337 116 115 338 115 120 339 120 116 340 116 117 341 117 120 342 120 118 343 118 116 344 116 120 345 120 119 346 119 118 347 118 123 348 123 119 349 119 120 350 120 123 351 123 121 352 121 119 353 119 123 354 123 122 355 122 121 356 121 126 357 126 122 358 122 123 359 123 126 360 126 124 361 124 122 362 122 126 363 126 125 364 125 124 365 124 129 366 129 125 367 125 126 368 126 129 369 129 127 370 127 125 371 125 129 372 129 128 373 128 127 374 127 132 375 132 128 376 128 129 377 129 132 378 132 130 379 130 128 380 128 132 381 132 131 382 131 130 383 130 135 384 135 131 385 131 132 386 132 135 387 135 133 388 133 131 389 131 135 390 135 134 391 134 133 392 133 138 393 138 134 394 134 135 395 135 138 396 138 136 397 136 134 398 134 138 399 138 137 400 137 136 401 136 141 402 141 137 403 137 138 404 138 141 405 141 139 406 139 137 407 137 141 408 141 140 409 140 139 410 139 143 411 143 140 412 140 141 413 141 143 414 143 142 415 142 140 416 140 146 417 146 142 418 142 143 419 143 146 420 146 144 421 144 142 422 142 146 423 146 145 424 145 144 425 144 149 426 149 145 427 145 146 428 146 149 429 149 147 430 147 145 431 145 149 432 149 148 433 148 147 434 147 152 435 152 148 436 148 149 437 149 152 438 152 150 439 150 148 440 148 152 441 152 151 442 151 150 443 150 155 444 155 151 445 151 152 446 152 155 447 155 153 448 153 151 449 151 155 450 155 154 451 154 153 452 153 158 453 158 154 454 154 155 455 155 158 456 158 156 457 156 154 458 154 158 459 158 157 460 157 156 461 156 161 462 161 157 463 157 158 464 158 161 465 161 159 466 159 157 467 157 161 468 161 160 469 160 159 470 159 164 471 164 160 472 160 161 473 161 164 474 164 162 475 162 160 476 160 164 477 164 163 478 163 162 479 162 167 480 167 163 481 163 164 482 164 167 483 167 165 484 165 163 485 163 167 486 167 166 487 166 165 488 165 170 489 170 166 490 166 167 491 167 170 492 170 168 493 168 166 494 166 170 495 170 169 496 169 168 497 168 173 498 173 169 499 169 170 500 170 173 501 173 171 502 171 169 503 169 173 504 173 172 505 172 171 506 171 176 507 176 172 508 172 173 509 173 176 510 176 174 511 174 172 512 172 176 513 176 175 514 175 174 515 174 179 516 179 175 517 175 176 518 176 179 519 179 177 520 177 175 521 175 179 522 179 178 523 178 177 524 177 182 525 182 178 526 178 179 527 179 182 528 182 180 529 180 178 530 178 182 531 182 181 532 181 180 533 180 185 534 185 181 535 181 182 536 182 185 537 185 183 538 183 181 539 181 185 540 185 184 541 184 183 542 183 188 543 188 184 544 184 185 545 185 188 546 188 186 547 186 184 548 184 188 549 188 187 550 187 186 551 186 190 552 190 187 553 187 188 554 188 190 555 190 189 556 189 187 557 187 193 558 193 189 559 189 190 560 190 193 561 193 191 562 191 189 563 189 193 564 193 192 565 192 191 566 191 102 567 102 192 568 192 193 569 193 286 570 286 196 571 196 194 572 194 196 573 196 195 574 195 194 575 194 199 576 199 195 577 195 196 578 196 199 579 199 197 580 197 195 581 195 199 582 199 198 583 198 197 584 197 201 585 201 198 586 198 199 587 199 201 588 201 200 589 200 198 590 198 204 591 204 200 592 200 201 593 201 204 594 204 202 595 202 200 596 200 204 597 204 203 598 203 202 599 202 207 600 207 203 601 203 204 602 204 207 603 207 205 604 205 203 605 203 207 606 207 206 607 206 205 608 205 210 609 210 206 610 206 207 611 207 210 612 210 208 613 208 206 614 206 210 615 210 209 616 209 208 617 208 213 618 213 209 619 209 210 620 210 213 621 213 211 622 211 209 623 209 213 624 213 212 625 212 211 626 211 216 627 216 212 628 212 213 629 213 216 630 216 214 631 214 212 632 212 216 633 216 215 634 215 214 635 214 219 636 219 215 637 215 216 638 216 219 639 219 217 640 217 215 641 215 219 642 219 218 643 218 217 644 217 222 645 222 218 646 218 219 647 219 222 648 222 220 649 220 218 650 218 222 651 222 221 652 221 220 653 220 225 654 225 221 655 221 222 656 222 225 657 225 223 658 223 221 659 221 225 660 225 224 661 224 223 662 223 228 663 228 224 664 224 225 665 225 228 666 228 226 667 226 224 668 224 228 669 228 227 670 227 226 671 226 231 672 231 227 673 227 228 674 228 231 675 231 229 676 229 227 677 227 231 678 231 230 679 230 229 680 229 234 681 234 230 682 230 231 683 231 234 684 234 232 685 232 230 686 230 234 687 234 233 688 233 232 689 232 237 690 237 233 691 233 234 692 234 237 693 237 235 694 235 233 695 233 237 696 237 236 697 236 235 698 235 240 699 240 236 700 236 237 701 237 240 702 240 238 703 238 236 704 236 240 705 240 239 706 239 238 707 238 243 708 243 239 709 239 240 710 240 243 711 243 241 712 241 239 713 239 243 714 243 242 715 242 241 716 241 246 717 246 242 718 242 243 719 243 246 720 246 244 721 244 242 722 242 246 723 246 245 724 245 244 725 244 248 726 248 245 727 245 246 728 246 248 729 248 247 730 247 245 731 245 251 732 251 247 733 247 248 734 248 251 735 251 249 736 249 247 737 247 251 738 251 250 739 250 249 740 249 254 741 254 250 742 250 251 743 251 254 744 254 252 745 252 250 746 250 254 747 254 253 748 253 252 749 252 257 750 257 253 751 253 254 752 254 257 753 257 255 754 255 253 755 253 257 756 257 256 757 256 255 758 255 260 759 260 256 760 256 257 761 257 260 762 260 258 763 258 256 764 256 260 765 260 259 766 259 258 767 258 263 768 263 259 769 259 260 770 260 263 771 263 261 772 261 259 773 259 263 774 263 262 775 262 261 776 261 266 777 266 262 778 262 263 779 263 266 780 266 264 781 264 262 782 262 266 783 266 265 784 265 264 785 264 269 786 269 265 787 265 266 788 266 269 789 269 267 790 267 265 791 265 269 792 269 268 793 268 267 794 267 272 795 272 268 796 268 269 797 269 272 798 272 270 799 270 268 800 268 272 801 272 271 802 271 270 803 270 275 804 275 271 805 271 272 806 272 275 807 275 273 808 273 271 809 271 275 810 275 274 811 274 273 812 273 278 813 278 274 814 274 275 815 275 278 816 278 276 817 276 274 818 274 278 819 278 277 820 277 276 821 276 281 822 281 277 823 277 278 824 278 281 825 281 279 826 279 277 827 277 281 828 281 280 829 280 279 830 279 284 831 284 280 832 280 281 833 281 284 834 284 282 835 282 280 836 280 284 837 284 283 838 283 282 839 282 287 840 287 283 841 283 284 842 284 287 843 287 285 844 285 283 845 283 287 846 287 286 847 286 285 848 285 196 849 196 286 850 286 287 851 287 352 852 352 288 853 288 289 854 289 293 855 293 290 856 290 291 857 291 293 858 293 292 859 292 290 860 290 295 861 295 292 862 292 293 863 293 295 864 295 294 865 294 292 866 292 297 867 297 294 868 294 295 869 295 297 870 297 296 871 296 294 872 294 299 873 299 296 874 296 297 875 297 299 876 299 298 877 298 296 878 296 301 879 301 298 880 298 299 881 299 301 882 301 300 883 300 298 884 298 303 885 303 300 886 300 301 887 301 303 888 303 302 889 302 300 890 300 305 891 305 302 892 302 303 893 303 305 894 305 304 895 304 302 896 302 307 897 307 304 898 304 305 899 305 307 900 307 306 901 306 304 902 304 309 903 309 306 904 306 307 905 307 309 906 309 308 907 308 306 908 306 311 909 311 308 910 308 309 911 309 311 912 311 310 913 310 308 914 308 313 915 313 310 916 310 311 917 311 313 918 313 312 919 312 310 920 310 315 921 315 312 922 312 313 923 313 315 924 315 314 925 314 312 926 312 317 927 317 314 928 314 315 929 315 317 930 317 316 931 316 314 932 314 319 933 319 316 934 316 317 935 317 319 936 319 318 937 318 316 938 316 321 939 321 318 940 318 319 941 319 321 942 321 320 943 320 318 944 318 323 945 323 320 946 320 321 947 321 323 948 323 322 949 322 320 950 320 325 951 325 322 952 322 323 953 323 325 954 325 324 955 324 322 956 322 327 957 327 324 958 324 325 959 325 327 960 327 326 961 326 324 962 324 329 963 329 326 964 326 327 965 327 329 966 329 328 967 328 326 968 326 331 969 331 328 970 328 329 971 329 331 972 331 330 973 330 328 974 328 333 975 333 330 976 330 331 977 331 333 978 333 332 979 332 330 980 330 335 981 335 332 982 332 333 983 333 335 984 335 334 985 334 332 986 332 337 987 337 334 988 334 335 989 335 337 990 337 336 991 336 334 992 334 339 993 339 336 994 336 337 995 337 339 996 339 338 997 338 336 998 336 341 999 341 338 1000 338 339 1001 339 341 1002 341 340 1003 340 338 1004 338 343 1005 343 340 1006 340 341 1007 341 343 1008 343 342 1009 342 340 1010 340 345 1011 345 342 1012 342 343 1013 343 345 1014 345 344 1015 344 342 1016 342 347 1017 347 344 1018 344 345 1019 345 347 1020 347 346 1021 346 344 1022 344 349 1023 349 346 1024 346 347 1025 347 349 1026 349 348 1027 348 346 1028 346 351 1029 351 348 1030 348 349 1031 349 351 1032 351 350 1033 350 348 1034 348 353 1035 353 350 1036 350 351 1037 351 353 1038 353 352 1039 352 350 1040 350 288 1041 288 352 1042 352 353 1043 353 386 1044 386 354 1045 354 355 1046 355 358 1047 358 356 1048 356 357 1049 357 359 1050 359 356 1051 356 358 1052 358 361 1053 361 356 1054 356 359 1055 359 361 1056 361 360 1057 360 356 1058 356 363 1059 363 360 1060 360 361 1061 361 363 1062 363 362 1063 362 360 1064 360 365 1065 365 362 1066 362 363 1067 363 365 1068 365 364 1069 364 362 1070 362 367 1071 367 364 1072 364 365 1073 365 367 1074 367 366 1075 366 364 1076 364 369 1077 369 366 1078 366 367 1079 367 369 1080 369 368 1081 368 366 1082 366 371 1083 371 368 1084 368 369 1085 369 371 1086 371 370 1087 370 368 1088 368 373 1089 373 370 1090 370 371 1091 371 373 1092 373 372 1093 372 370 1094 370 375 1095 375 372 1096 372 373 1097 373 375 1098 375 374 1099 374 372 1100 372 377 1101 377 374 1102 374 375 1103 375 377 1104 377 376 1105 376 374 1106 374 379 1107 379 376 1108 376 377 1109 377 379 1110 379 378 1111 378 376 1112 376 381 1113 381 378 1114 378 379 1115 379 381 1116 381 380 1117 380 378 1118 378 383 1119 383 380 1120 380 381 1121 381 383 1122 383 382 1123 382 380 1124 380 385 1125 385 382 1126 382 383 1127 383 385 1128 385 384 1129 384 382 1130 382 387 1131 387 384 1132 384 385 1133 385 387 1134 387 386 1135 386 384 1136 384 354 1137 354 386 1138 386 387 1139 387

+
+
+ + + + +0.021304 0.500000 1.000000 +0.021304 0.500000 0.000000 +0.418849 0.010610 0.000000 +0.521304 0.000000 0.000000 +0.521304 0.000000 1.000000 +0.418849 0.010610 1.000000 +0.322715 0.041129 0.000000 +0.322715 0.041129 1.000000 +0.237987 0.088015 0.000000 +0.167751 0.146447 0.000000 +0.237987 0.088015 1.000000 +0.109320 0.216683 0.000000 +0.167751 0.146447 1.000000 +0.109320 0.216683 1.000000 +0.062433 0.301411 0.000000 +0.062433 0.301411 1.000000 +0.031914 0.397545 0.000000 +0.031914 0.397545 1.000000 +0.521304 0.000000 0.000000 +4.135448 0.000000 0.000000 +4.135448 0.000000 1.000000 +0.521304 0.000000 1.000000 +4.635013 0.479149 0.000000 +6.546594 46.279148 0.000000 +6.546594 46.279148 1.000000 +4.635013 0.479149 1.000000 +2.432885 46.799999 1.000000 +6.047029 46.799999 1.000000 +6.047029 46.799999 0.000000 +2.432885 46.799999 0.000000 +0.021739 0.520851 1.000000 +1.933320 46.320850 1.000000 +1.933320 46.320850 0.000000 +0.021739 0.520851 0.000000 +0.021739 0.520851 1.000000 +0.021304 0.500000 1.000000 +2.021891 46.584751 1.000000 +1.974224 46.499073 1.000000 +1.944994 46.409370 1.000000 +2.086782 46.660851 1.000000 +2.165519 46.722511 1.000000 +2.253112 46.766563 1.000000 +2.343956 46.792027 1.000000 +2.432885 46.799999 1.000000 +1.933320 46.320850 1.000000 +6.047029 46.799999 1.000000 +6.146117 46.790085 1.000000 +6.243177 46.759918 1.000000 +6.332133 46.710751 1.000000 +6.407879 46.646103 1.000000 +6.469311 46.567726 1.000000 +6.514728 46.476799 1.000000 +6.540818 46.378563 1.000000 +6.546594 46.279148 1.000000 +4.635013 0.479149 1.000000 +4.623340 0.390630 1.000000 +4.594109 0.300927 1.000000 +4.546442 0.215247 1.000000 +4.481551 0.139150 1.000000 +4.402814 0.077489 1.000000 +4.315221 0.033436 1.000000 +4.224378 0.007972 1.000000 +4.135448 0.000000 1.000000 +0.521304 0.000000 1.000000 +0.430323 0.008347 1.000000 +0.337257 0.035106 1.000000 +0.247699 0.081502 1.000000 +0.167751 0.146447 1.000000 +0.102806 0.226395 1.000000 +0.056410 0.315953 1.000000 +0.029651 0.409018 1.000000 +0.029651 0.409018 0.000000 +0.021304 0.500000 0.000000 +6.514728 46.476799 0.000000 +6.540818 46.378563 0.000000 +6.469311 46.567726 0.000000 +6.407879 46.646103 0.000000 +6.332133 46.710751 0.000000 +6.243177 46.759918 0.000000 +6.146117 46.790085 0.000000 +6.047029 46.799999 0.000000 +6.546594 46.279148 0.000000 +2.432885 46.799999 0.000000 +2.343956 46.792027 0.000000 +2.253112 46.766563 0.000000 +2.165519 46.722511 0.000000 +2.086782 46.660851 0.000000 +2.021891 46.584751 0.000000 +1.974224 46.499073 0.000000 +1.944994 46.409370 0.000000 +1.933320 46.320850 0.000000 +0.021739 0.520851 0.000000 +4.635013 0.479149 0.000000 +4.623340 0.390630 0.000000 +4.594109 0.300927 0.000000 +4.546442 0.215247 0.000000 +4.481551 0.139150 0.000000 +4.402814 0.077489 0.000000 +4.315221 0.033436 0.000000 +4.224378 0.007972 0.000000 +4.135448 0.000000 0.000000 +0.521304 0.000000 0.000000 +0.430323 0.008347 0.000000 +0.337257 0.035106 0.000000 +0.247699 0.081502 0.000000 +0.167751 0.146447 0.000000 +0.102806 0.226395 0.000000 +0.056410 0.315953 0.000000 +0.021304 0.500000 1.000000 +0.021739 0.520851 1.000000 +0.021739 0.520851 0.000000 +0.021413 0.510428 1.000000 +0.021413 0.510428 0.000000 +0.021304 0.500000 0.000000 +4.135448 0.000000 1.000000 +4.135448 0.000000 0.000000 +4.622595 0.387361 0.000000 +4.635013 0.479149 0.000000 +4.635013 0.479149 1.000000 +4.622595 0.387361 1.000000 +4.590077 0.291885 0.000000 +4.590077 0.291885 1.000000 +4.541434 0.208152 0.000000 +4.541434 0.208152 1.000000 +4.481551 0.139150 0.000000 +4.481551 0.139150 1.000000 +4.410111 0.082196 0.000000 +4.324424 0.037087 0.000000 +4.410111 0.082196 1.000000 +4.324424 0.037087 1.000000 +4.227674 0.008579 0.000000 +4.227674 0.008579 1.000000 +2.026899 46.591846 1.000000 +1.945738 46.412640 0.000000 +1.933320 46.320850 0.000000 +1.933320 46.320850 1.000000 +1.978256 46.508114 0.000000 +1.945738 46.412640 1.000000 +2.026899 46.591846 0.000000 +1.978256 46.508114 1.000000 +2.340659 46.791420 1.000000 +2.432885 46.799999 1.000000 +2.432885 46.799999 0.000000 +2.340659 46.791420 0.000000 +2.243910 46.762913 1.000000 +2.158221 46.717804 1.000000 +2.243910 46.762913 0.000000 +2.158221 46.717804 0.000000 +2.086782 46.660851 1.000000 +2.086782 46.660851 0.000000 +6.464833 46.574665 0.000000 +6.546594 46.279148 1.000000 +6.546594 46.279148 0.000000 +6.546920 46.289574 1.000000 +6.538450 46.392227 1.000000 +6.546920 46.289574 0.000000 +6.538450 46.392227 0.000000 +6.509942 46.488976 1.000000 +6.464833 46.574665 1.000000 +6.509942 46.488976 0.000000 +6.047029 46.799999 0.000000 +6.047029 46.799999 1.000000 +6.057456 46.799892 0.000000 +6.057456 46.799892 1.000000 +6.159668 46.787148 0.000000 +6.159668 46.787148 1.000000 +6.255145 46.754631 0.000000 +6.255145 46.754631 1.000000 +6.338877 46.705986 0.000000 +6.407879 46.646103 0.000000 +6.338877 46.705986 1.000000 +6.407879 46.646103 1.000000 + + + + + + + + + + + +-0.978781 -0.204909 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.204909 -0.978781 0.000000 +0.000000 -1.000000 0.000000 +-0.204909 -0.978781 0.000000 +-0.204909 -0.978781 0.000000 +0.000000 -1.000000 0.000000 +-0.397177 -0.917742 0.000000 +-0.204909 -0.978781 0.000000 +-0.204909 -0.978781 0.000000 +-0.397177 -0.917742 0.000000 +-0.397177 -0.917742 0.000000 +-0.204909 -0.978781 0.000000 +-0.566635 -0.823969 0.000000 +-0.397177 -0.917742 0.000000 +-0.397177 -0.917742 0.000000 +-0.566635 -0.823969 0.000000 +-0.566635 -0.823969 0.000000 +-0.397177 -0.917742 0.000000 +-0.566635 -0.823969 0.000000 +-0.707107 -0.707107 0.000000 +-0.566635 -0.823969 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.566635 -0.823969 0.000000 +-0.707107 -0.707107 0.000000 +-0.823969 -0.566635 0.000000 +-0.707107 -0.707107 0.000000 +-0.823969 -0.566635 0.000000 +-0.823969 -0.566635 0.000000 +-0.707107 -0.707107 0.000000 +-0.917742 -0.397177 0.000000 +-0.823969 -0.566635 0.000000 +-0.823969 -0.566635 0.000000 +-0.917742 -0.397177 0.000000 +-0.917742 -0.397177 0.000000 +-0.823969 -0.566635 0.000000 +-0.978781 -0.204909 0.000000 +-0.917742 -0.397177 0.000000 +-0.917742 -0.397177 0.000000 +-0.978781 -0.204909 0.000000 +-0.978781 -0.204909 0.000000 +-0.917742 -0.397177 0.000000 +-1.000000 0.000000 0.000000 +-0.978781 -0.204909 0.000000 +-0.978781 -0.204909 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.999130 -0.041701 0.000000 +0.999130 -0.041701 0.000000 +0.999130 -0.041701 0.000000 +0.999130 -0.041701 0.000000 +0.999130 -0.041701 0.000000 +0.999130 -0.041701 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999130 0.041701 0.000000 +-0.999130 0.041701 0.000000 +-0.999130 0.041701 0.000000 +-0.999130 0.041701 0.000000 +-0.999130 0.041701 0.000000 +-0.999130 0.041701 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.999783 0.020855 0.000000 +-1.000000 0.000000 0.000000 +-0.999783 0.020855 0.000000 +-0.999783 0.020855 0.000000 +-0.999130 0.041701 0.000000 +-0.999130 0.041701 0.000000 +-0.999783 0.020855 0.000000 +-0.999783 0.020855 0.000000 +-0.999130 0.041701 0.000000 +-1.000000 0.000000 0.000000 +-0.999783 0.020855 0.000000 +-1.000000 0.000000 0.000000 +0.184452 -0.982841 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.999130 -0.041701 0.000000 +0.974295 -0.225278 0.000000 +0.999130 -0.041701 0.000000 +0.974295 -0.225278 0.000000 +0.974295 -0.225278 0.000000 +0.999130 -0.041701 0.000000 +0.909259 -0.416231 0.000000 +0.974295 -0.225278 0.000000 +0.974295 -0.225278 0.000000 +0.909259 -0.416231 0.000000 +0.909259 -0.416231 0.000000 +0.974295 -0.225278 0.000000 +0.811973 -0.583695 0.000000 +0.909259 -0.416231 0.000000 +0.909259 -0.416231 0.000000 +0.811973 -0.583695 0.000000 +0.811973 -0.583695 0.000000 +0.909259 -0.416231 0.000000 +0.692206 -0.721700 0.000000 +0.811973 -0.583695 0.000000 +0.811973 -0.583695 0.000000 +0.692206 -0.721700 0.000000 +0.692206 -0.721700 0.000000 +0.811973 -0.583695 0.000000 +0.549327 -0.835607 0.000000 +0.692206 -0.721700 0.000000 +0.692206 -0.721700 0.000000 +0.549327 -0.835607 0.000000 +0.549327 -0.835607 0.000000 +0.692206 -0.721700 0.000000 +0.549327 -0.835607 0.000000 +0.377951 -0.925825 0.000000 +0.549327 -0.835607 0.000000 +0.377951 -0.925825 0.000000 +0.377951 -0.925825 0.000000 +0.549327 -0.835607 0.000000 +0.184452 -0.982841 0.000000 +0.377951 -0.925825 0.000000 +0.377951 -0.925825 0.000000 +0.184452 -0.982841 0.000000 +0.184452 -0.982841 0.000000 +0.377951 -0.925825 0.000000 +0.000000 -1.000000 0.000000 +0.184452 -0.982841 0.000000 +0.184452 -0.982841 0.000000 +-0.692206 0.721700 0.000000 +-0.811973 0.583695 0.000000 +-0.811973 0.583695 0.000000 +-0.999130 0.041701 0.000000 +-0.974295 0.225278 0.000000 +-0.999130 0.041701 0.000000 +-0.974295 0.225278 0.000000 +-0.974295 0.225278 0.000000 +-0.999130 0.041701 0.000000 +-0.974295 0.225278 0.000000 +-0.909259 0.416231 0.000000 +-0.974295 0.225278 0.000000 +-0.909259 0.416231 0.000000 +-0.909259 0.416231 0.000000 +-0.974295 0.225278 0.000000 +-0.909259 0.416231 0.000000 +-0.811973 0.583695 0.000000 +-0.909259 0.416231 0.000000 +-0.811973 0.583695 0.000000 +-0.811973 0.583695 0.000000 +-0.909259 0.416231 0.000000 +0.000000 1.000000 0.000000 +-0.184452 0.982841 0.000000 +0.000000 1.000000 0.000000 +-0.184452 0.982841 0.000000 +-0.184452 0.982841 0.000000 +0.000000 1.000000 0.000000 +-0.377951 0.925825 0.000000 +-0.184452 0.982841 0.000000 +-0.184452 0.982841 0.000000 +-0.377951 0.925825 0.000000 +-0.377951 0.925825 0.000000 +-0.184452 0.982841 0.000000 +-0.377951 0.925825 0.000000 +-0.549327 0.835607 0.000000 +-0.377951 0.925825 0.000000 +-0.549327 0.835607 0.000000 +-0.549327 0.835607 0.000000 +-0.377951 0.925825 0.000000 +-0.692206 0.721700 0.000000 +-0.549327 0.835607 0.000000 +-0.549327 0.835607 0.000000 +-0.692206 0.721700 0.000000 +-0.692206 0.721700 0.000000 +-0.549327 0.835607 0.000000 +-0.811973 0.583695 0.000000 +-0.692206 0.721700 0.000000 +-0.692206 0.721700 0.000000 +0.721700 0.692206 0.000000 +0.835607 0.549327 0.000000 +0.835607 0.549327 0.000000 +0.999783 -0.020855 0.000000 +0.999130 -0.041701 0.000000 +0.999130 -0.041701 0.000000 +0.999783 -0.020855 0.000000 +0.999783 -0.020855 0.000000 +0.999130 -0.041701 0.000000 +0.999783 -0.020855 0.000000 +0.982841 0.184452 0.000000 +0.999783 -0.020855 0.000000 +0.982841 0.184452 0.000000 +0.982841 0.184452 0.000000 +0.999783 -0.020855 0.000000 +0.925825 0.377951 0.000000 +0.982841 0.184452 0.000000 +0.982841 0.184452 0.000000 +0.925825 0.377951 0.000000 +0.925825 0.377951 0.000000 +0.982841 0.184452 0.000000 +0.925825 0.377951 0.000000 +0.835607 0.549327 0.000000 +0.925825 0.377951 0.000000 +0.835607 0.549327 0.000000 +0.835607 0.549327 0.000000 +0.925825 0.377951 0.000000 +0.020855 0.999783 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.020855 0.999783 0.000000 +0.020855 0.999783 0.000000 +0.000000 1.000000 0.000000 +0.225278 0.974295 0.000000 +0.020855 0.999783 0.000000 +0.020855 0.999783 0.000000 +0.225278 0.974295 0.000000 +0.225278 0.974295 0.000000 +0.020855 0.999783 0.000000 +0.416231 0.909259 0.000000 +0.225278 0.974295 0.000000 +0.225278 0.974295 0.000000 +0.416231 0.909259 0.000000 +0.416231 0.909259 0.000000 +0.225278 0.974295 0.000000 +0.583695 0.811973 0.000000 +0.416231 0.909259 0.000000 +0.416231 0.909259 0.000000 +0.583695 0.811973 0.000000 +0.583695 0.811973 0.000000 +0.416231 0.909259 0.000000 +0.583695 0.811973 0.000000 +0.721700 0.692206 0.000000 +0.583695 0.811973 0.000000 +0.721700 0.692206 0.000000 +0.721700 0.692206 0.000000 +0.583695 0.811973 0.000000 +0.835607 0.549327 0.000000 +0.721700 0.692206 0.000000 +0.721700 0.692206 0.000000 + + + + + + + + + + + +0.999500 0.550946 +0.000500 0.550946 +0.000500 0.549569 +0.000500 0.549539 +0.999500 0.549539 +0.999500 0.549569 +0.000500 0.549655 +0.999500 0.549655 +0.000500 0.549787 +0.000500 0.549951 +0.999500 0.549787 +0.000500 0.550149 +0.999500 0.549951 +0.999500 0.550149 +0.000500 0.550387 +0.999500 0.550387 +0.000500 0.550658 +0.999500 0.550658 +0.000500 0.549539 +0.000500 0.549539 +0.999500 0.549539 +0.999500 0.549539 +0.000500 0.550888 +0.000500 0.679791 +0.999500 0.679791 +0.999500 0.550888 +0.999500 0.681257 +0.999500 0.681257 +0.000500 0.681257 +0.000500 0.681257 +0.999500 0.551005 +0.999500 0.679908 +0.000500 0.679908 +0.000500 0.551005 +0.999500 0.551005 +0.999500 0.550946 +0.999500 0.680651 +0.999500 0.680410 +0.999500 0.680157 +0.999500 0.680865 +0.999500 0.681039 +0.999500 0.681163 +0.999500 0.681234 +0.999500 0.681257 +0.999500 0.679908 +0.999500 0.681257 +0.999500 0.681229 +0.999500 0.681144 +0.999500 0.681006 +0.999500 0.680824 +0.999500 0.680603 +0.999500 0.680347 +0.999500 0.680071 +0.999500 0.679791 +0.999500 0.550888 +0.999500 0.550639 +0.999500 0.550386 +0.999500 0.550145 +0.999500 0.549931 +0.999500 0.549757 +0.999500 0.549633 +0.999500 0.549562 +0.999500 0.549539 +0.999500 0.549539 +0.999500 0.549563 +0.999500 0.549638 +0.999500 0.549769 +0.999500 0.549951 +0.999500 0.550176 +0.999500 0.550428 +0.999500 0.550690 +0.000500 0.550690 +0.000500 0.550946 +0.000500 0.680347 +0.000500 0.680071 +0.000500 0.680603 +0.000500 0.680824 +0.000500 0.681006 +0.000500 0.681144 +0.000500 0.681229 +0.000500 0.681257 +0.000500 0.679791 +0.000500 0.681257 +0.000500 0.681234 +0.000500 0.681163 +0.000500 0.681039 +0.000500 0.680865 +0.000500 0.680651 +0.000500 0.680410 +0.000500 0.680157 +0.000500 0.679908 +0.000500 0.551005 +0.000500 0.550888 +0.000500 0.550639 +0.000500 0.550386 +0.000500 0.550145 +0.000500 0.549931 +0.000500 0.549757 +0.000500 0.549633 +0.000500 0.549562 +0.000500 0.549539 +0.000500 0.549539 +0.000500 0.549563 +0.000500 0.549638 +0.000500 0.549769 +0.000500 0.549951 +0.000500 0.550176 +0.000500 0.550428 +0.999500 0.550946 +0.999500 0.551005 +0.000500 0.551005 +0.999500 0.550976 +0.000500 0.550976 +0.000500 0.550946 +0.999500 0.549539 +0.000500 0.549539 +0.000500 0.550629 +0.000500 0.550888 +0.999500 0.550888 +0.999500 0.550629 +0.000500 0.550361 +0.999500 0.550361 +0.000500 0.550125 +0.999500 0.550125 +0.000500 0.549931 +0.999500 0.549931 +0.000500 0.549771 +0.000500 0.549644 +0.999500 0.549771 +0.999500 0.549644 +0.000500 0.549563 +0.999500 0.549563 +0.999500 0.680671 +0.000500 0.680167 +0.000500 0.679908 +0.999500 0.679908 +0.000500 0.680435 +0.999500 0.680167 +0.000500 0.680671 +0.999500 0.680435 +0.999500 0.681233 +0.999500 0.681257 +0.000500 0.681257 +0.000500 0.681233 +0.999500 0.681153 +0.999500 0.681026 +0.000500 0.681153 +0.000500 0.681026 +0.999500 0.680865 +0.000500 0.680865 +0.000500 0.680623 +0.999500 0.679791 +0.000500 0.679791 +0.999500 0.679820 +0.999500 0.680109 +0.000500 0.679820 +0.000500 0.680109 +0.999500 0.680381 +0.999500 0.680623 +0.000500 0.680381 +0.000500 0.681257 +0.999500 0.681257 +0.000500 0.681257 +0.999500 0.681257 +0.000500 0.681221 +0.999500 0.681221 +0.000500 0.681129 +0.999500 0.681129 +0.000500 0.680992 +0.000500 0.680824 +0.999500 0.680992 +0.999500 0.680824 + + + + + + + + + + + +

16 0 16 0 1 0 1 2 1 4 3 4 2 4 2 3 5 3 5 6 5 2 7 2 4 8 4 7 9 7 2 10 2 5 11 5 7 12 7 6 13 6 2 14 2 10 15 10 6 16 6 7 17 7 10 18 10 8 19 8 6 20 6 10 21 10 9 22 9 8 23 8 12 24 12 9 25 9 10 26 10 12 27 12 11 28 11 9 29 9 13 30 13 11 31 11 12 32 12 15 33 15 11 34 11 13 35 13 15 36 15 14 37 14 11 38 11 17 39 17 14 40 14 15 41 15 17 42 17 16 43 16 14 44 14 0 45 0 16 46 16 17 47 17 20 48 20 18 49 18 19 50 19 18 51 18 20 52 20 21 53 21 24 54 24 22 55 22 23 56 23 22 57 22 24 58 24 25 59 25 28 60 28 26 61 26 27 62 27 26 63 26 28 64 28 29 65 29 32 66 32 30 67 30 31 68 31 30 69 30 32 70 32 33 71 33 70 72 70 34 73 34 35 74 35 38 75 38 36 76 36 37 77 37 44 78 44 36 79 36 38 80 38 44 81 44 39 82 39 36 83 36 44 84 44 40 85 40 39 86 39 44 87 44 41 88 41 40 89 40 44 90 44 42 91 42 41 92 41 44 93 44 43 94 43 42 95 42 34 96 34 43 97 43 44 98 44 34 99 34 45 100 45 43 101 43 34 102 34 46 103 46 45 104 45 34 105 34 47 106 47 46 107 46 34 108 34 48 109 48 47 110 47 34 111 34 49 112 49 48 113 48 34 114 34 50 115 50 49 116 49 34 117 34 51 118 51 50 119 50 34 120 34 52 121 52 51 122 51 34 123 34 53 124 53 52 125 52 34 126 34 54 127 54 53 128 53 34 129 34 55 130 55 54 131 54 34 132 34 56 133 56 55 134 55 34 135 34 57 136 57 56 137 56 34 138 34 58 139 58 57 140 57 34 141 34 59 142 59 58 143 58 34 144 34 60 145 60 59 146 59 34 147 34 61 148 61 60 149 60 34 150 34 62 151 62 61 152 61 34 153 34 63 154 63 62 155 62 34 156 34 64 157 64 63 158 63 34 159 34 65 160 65 64 161 64 34 162 34 66 163 66 65 164 65 34 165 34 67 166 67 66 167 66 34 168 34 68 169 68 67 170 67 34 171 34 69 172 69 68 173 68 34 174 34 70 175 70 69 176 69 91 177 91 71 178 71 72 179 72 81 180 81 73 181 73 74 182 74 81 183 81 75 184 75 73 185 73 81 186 81 76 187 76 75 188 75 81 189 81 77 190 77 76 191 76 81 192 81 78 193 78 77 194 77 81 195 81 79 196 79 78 197 78 81 198 81 80 199 80 79 200 79 92 201 92 80 202 80 81 203 81 92 204 92 82 205 82 80 206 80 92 207 92 83 208 83 82 209 82 92 210 92 84 211 84 83 212 83 92 213 92 85 214 85 84 215 84 92 216 92 86 217 86 85 218 85 92 219 92 87 220 87 86 221 86 92 222 92 88 223 88 87 224 87 92 225 92 89 226 89 88 227 88 92 228 92 90 229 90 89 230 89 92 231 92 91 232 91 90 233 90 93 234 93 91 235 91 92 236 92 94 237 94 91 238 91 93 239 93 95 240 95 91 241 91 94 242 94 96 243 96 91 244 91 95 245 95 97 246 97 91 247 91 96 248 96 98 249 98 91 250 91 97 251 97 99 252 99 91 253 91 98 254 98 100 255 100 91 256 91 99 257 99 101 258 101 91 259 91 100 260 100 102 261 102 91 262 91 101 263 101 103 264 103 91 265 91 102 266 102 104 267 104 91 268 91 103 269 103 105 270 105 91 271 91 104 272 104 106 273 106 91 274 91 105 275 105 107 276 107 91 277 91 106 278 106 71 279 71 91 280 91 107 281 107 112 282 112 108 283 108 111 284 111 112 285 112 109 286 109 110 287 110 112 288 112 111 289 111 109 290 109 108 291 108 112 292 112 113 293 113 130 294 130 114 295 114 115 296 115 118 297 118 116 298 116 117 299 117 119 300 119 116 301 116 118 302 118 121 303 121 116 304 116 119 305 119 121 306 121 120 307 120 116 308 116 123 309 123 120 310 120 121 311 121 123 312 123 122 313 122 120 314 120 125 315 125 122 316 122 123 317 123 125 318 125 124 319 124 122 320 122 128 321 128 124 322 124 125 323 125 128 324 128 126 325 126 124 326 124 128 327 128 127 328 127 126 329 126 129 330 129 127 331 127 128 332 128 131 333 131 127 334 127 129 335 129 131 336 131 130 337 130 127 338 127 114 339 114 130 340 130 131 341 131 148 342 148 138 343 138 132 344 132 135 345 135 133 346 133 134 347 134 137 348 137 133 349 133 135 350 135 137 351 137 136 352 136 133 353 133 139 354 139 136 355 136 137 356 137 139 357 139 138 358 138 136 359 136 132 360 132 138 361 138 139 362 139 142 363 142 140 364 140 141 365 141 143 366 143 140 367 140 142 368 142 146 369 146 140 370 140 143 371 143 146 372 146 144 373 144 140 374 140 146 375 146 145 376 145 144 377 144 147 378 147 145 379 145 146 380 146 149 381 149 145 382 145 147 383 147 149 384 149 148 385 148 145 386 145 138 387 138 148 388 148 149 389 149 169 390 169 158 391 158 150 392 150 155 393 155 151 394 151 152 395 152 155 396 155 153 397 153 151 398 151 155 399 155 154 400 154 153 401 153 156 402 156 154 403 154 155 404 155 159 405 159 154 406 154 156 407 156 159 408 159 157 409 157 154 410 154 159 411 159 158 412 158 157 413 157 150 414 150 158 415 158 159 416 159 163 417 163 160 418 160 161 419 161 163 420 163 162 421 162 160 422 160 165 423 165 162 424 162 163 425 163 165 426 165 164 427 164 162 428 162 167 429 167 164 430 164 165 431 165 167 432 167 166 433 166 164 434 164 170 435 170 166 436 166 167 437 167 170 438 170 168 439 168 166 440 166 170 441 170 169 442 169 168 443 168 171 444 171 169 445 169 170 446 170 158 447 158 169 448 169 171 449 171

+
+
+ + + + +1.200000 0.000000 11.500000 +1.400000 0.000000 11.300000 +-1.376628 0.254748 11.300000 +-1.400000 0.000000 11.300000 +-1.200000 0.000000 11.500000 +-1.179966 0.218356 11.500000 +-1.301704 0.515333 11.300000 +-1.115746 0.441714 11.500000 +-1.171794 0.766094 11.300000 +-1.004395 0.656652 11.500000 +-0.989949 0.989949 11.300000 +-0.848528 0.848528 11.500000 +-0.766094 1.171794 11.300000 +-0.656652 1.004395 11.500000 +-0.515333 1.301704 11.300000 +-0.441714 1.115746 11.500000 +-0.254748 1.376628 11.300000 +-0.218356 1.179966 11.500000 +0.000000 1.400000 11.300000 +0.000000 1.200000 11.500000 +0.254748 1.376628 11.300000 +0.218356 1.179966 11.500000 +0.515333 1.301704 11.300000 +0.441714 1.115746 11.500000 +0.766094 1.171794 11.300000 +0.656652 1.004395 11.500000 +0.989949 0.989949 11.300000 +0.848528 0.848528 11.500000 +1.171794 0.766094 11.300000 +1.004395 0.656652 11.500000 +1.301704 0.515333 11.300000 +1.115746 0.441714 11.500000 +1.376628 0.254748 11.300000 +1.179966 0.218356 11.500000 +-1.798022 0.084358 0.000000 +-1.392264 1.435827 0.200000 +-1.322876 1.500000 0.200000 +-1.244990 1.300000 0.000000 +-1.642927 1.140523 0.200000 +-1.253038 1.292244 0.000000 +-1.823032 0.822530 0.200000 +-1.478634 1.026470 0.000000 +-1.640719 0.740298 0.000000 +-1.942267 0.477074 0.200000 +-1.748040 0.429367 0.000000 +-1.997802 0.093731 0.200000 +-1.800000 0.000000 0.000000 +-2.000000 0.000000 0.200000 +-2.000000 0.000000 0.200000 +-1.800000 0.000000 0.000000 +1.800000 0.000000 0.000000 +2.000000 0.000000 0.200000 +1.769950 -0.327533 0.000000 +1.966611 -0.363926 0.200000 +1.673619 -0.662570 0.000000 +1.859577 -0.736189 0.200000 +1.506592 -0.984978 0.000000 +1.673991 -1.094419 0.200000 +1.272792 -1.272792 0.000000 +1.414214 -1.414214 0.200000 +0.984978 -1.506592 0.000000 +1.094419 -1.673991 0.200000 +0.662570 -1.673619 0.000000 +0.736189 -1.859577 0.200000 +0.327533 -1.769950 0.000000 +0.363926 -1.966611 0.200000 +0.000000 -1.800000 0.000000 +0.000000 -2.000000 0.200000 +-0.327533 -1.769950 0.000000 +-0.363926 -1.966611 0.200000 +-0.662570 -1.673619 0.000000 +-0.736189 -1.859577 0.200000 +-0.984978 -1.506592 0.000000 +-1.094419 -1.673991 0.200000 +-1.272792 -1.272792 0.000000 +-1.414214 -1.414214 0.200000 +-1.506592 -0.984978 0.000000 +-1.673619 -0.662570 0.000000 +-1.673991 -1.094419 0.200000 +-1.859577 -0.736189 0.200000 +-1.769950 -0.327533 0.000000 +-1.966611 -0.363926 0.200000 +1.997785 0.094109 3.500000 +2.000000 0.000000 3.500000 +1.391992 1.436091 0.200000 +1.322876 1.500000 0.200000 +1.322876 1.500000 3.500000 +1.391992 1.436091 3.500000 +1.642710 1.140834 0.200000 +1.642710 1.140834 3.500000 +1.822876 0.822876 0.200000 +1.942176 0.477442 0.200000 +1.822876 0.822876 3.500000 +1.997785 0.094109 0.200000 +1.942176 0.477442 3.500000 +2.000000 0.000000 0.200000 +2.000000 0.000000 0.200000 +2.000000 0.000000 3.500000 +-2.000000 0.000000 3.500000 +-2.000000 0.000000 0.200000 +-1.966611 -0.363926 3.500000 +-1.966611 -0.363926 0.200000 +-1.859577 -0.736189 3.500000 +-1.859577 -0.736189 0.200000 +-1.673991 -1.094419 3.500000 +-1.673991 -1.094419 0.200000 +-1.414214 -1.414214 3.500000 +-1.414214 -1.414214 0.200000 +-1.094419 -1.673991 3.500000 +-1.094419 -1.673991 0.200000 +-0.736189 -1.859577 3.500000 +-0.736189 -1.859577 0.200000 +-0.363926 -1.966611 3.500000 +-0.363926 -1.966611 0.200000 +0.000000 -2.000000 3.500000 +0.000000 -2.000000 0.200000 +0.363926 -1.966611 3.500000 +0.363926 -1.966611 0.200000 +0.736189 -1.859577 3.500000 +0.736189 -1.859577 0.200000 +1.094419 -1.673991 3.500000 +1.094419 -1.673991 0.200000 +1.414214 -1.414214 3.500000 +1.414214 -1.414214 0.200000 +1.673991 -1.094419 3.500000 +1.673991 -1.094419 0.200000 +1.859577 -0.736189 3.500000 +1.859577 -0.736189 0.200000 +1.966611 -0.363926 3.500000 +1.966611 -0.363926 0.200000 +-1.400000 0.000000 6.500000 +-1.400000 0.000000 11.300000 +1.400000 0.000000 11.300000 +1.400000 0.000000 6.500000 +1.376628 0.254748 11.300000 +1.376628 0.254748 6.500000 +1.301704 0.515333 11.300000 +1.301704 0.515333 6.500000 +1.171794 0.766094 11.300000 +1.171794 0.766094 6.500000 +0.989949 0.989949 11.300000 +0.989949 0.989949 6.500000 +0.766094 1.171794 11.300000 +0.515333 1.301704 11.300000 +0.766094 1.171794 6.500000 +0.515333 1.301704 6.500000 +0.254748 1.376628 11.300000 +0.254748 1.376628 6.500000 +0.000000 1.400000 11.300000 +0.000000 1.400000 6.500000 +-0.254748 1.376628 11.300000 +-0.254748 1.376628 6.500000 +-0.515333 1.301704 11.300000 +-0.515333 1.301704 6.500000 +-0.766094 1.171794 11.300000 +-0.766094 1.171794 6.500000 +-0.989949 0.989949 11.300000 +-0.989949 0.989949 6.500000 +-1.171794 0.766094 11.300000 +-1.171794 0.766094 6.500000 +-1.301704 0.515333 11.300000 +-1.301704 0.515333 6.500000 +-1.376628 0.254748 11.300000 +-1.376628 0.254748 6.500000 +-0.820815 1.255493 6.500000 +-1.474958 0.272945 3.500000 +-1.500000 0.000000 3.500000 +-1.500000 0.000000 6.500000 +-1.474958 0.272945 6.500000 +-1.394682 0.552142 3.500000 +-1.394682 0.552142 6.500000 +-1.255493 0.820815 3.500000 +-1.255493 0.820815 6.500000 +-1.060660 1.060660 3.500000 +-1.060660 1.060660 6.500000 +-0.820815 1.255493 3.500000 +1.474958 0.272945 6.500000 +1.500000 0.000000 6.500000 +1.500000 0.000000 3.500000 +1.474958 0.272945 3.500000 +1.394682 0.552142 6.500000 +1.394682 0.552142 3.500000 +1.255493 0.820815 6.500000 +1.255493 0.820815 3.500000 +1.060660 1.060660 6.500000 +1.060660 1.060660 3.500000 +0.820815 1.255493 6.500000 +0.552142 1.394682 6.500000 +0.820815 1.255493 3.500000 +0.272945 1.474958 6.500000 +0.552142 1.394682 3.500000 +0.000000 1.500000 6.500000 +0.272945 1.474958 3.500000 +0.000000 1.500000 3.500000 +-0.272945 1.474958 6.500000 +-0.272945 1.474958 3.500000 +-0.552142 1.394682 6.500000 +-0.552142 1.394682 3.500000 +1.500000 0.000000 3.500000 +1.500000 0.000000 6.500000 +-1.500000 0.000000 6.500000 +-1.500000 0.000000 3.500000 +-1.474958 -0.272945 6.500000 +-1.474958 -0.272945 3.500000 +-1.394682 -0.552142 6.500000 +-1.394682 -0.552142 3.500000 +-1.255493 -0.820815 6.500000 +-1.255493 -0.820815 3.500000 +-1.060660 -1.060660 6.500000 +-1.060660 -1.060660 3.500000 +-0.820815 -1.255493 6.500000 +-0.820815 -1.255493 3.500000 +-0.552142 -1.394682 6.500000 +-0.552142 -1.394682 3.500000 +-0.272945 -1.474958 6.500000 +-0.272945 -1.474958 3.500000 +0.000000 -1.500000 6.500000 +0.000000 -1.500000 3.500000 +0.272945 -1.474958 6.500000 +0.272945 -1.474958 3.500000 +0.552142 -1.394682 6.500000 +0.552142 -1.394682 3.500000 +0.820815 -1.255493 6.500000 +0.820815 -1.255493 3.500000 +1.060660 -1.060660 6.500000 +1.060660 -1.060660 3.500000 +1.255493 -0.820815 6.500000 +1.255493 -0.820815 3.500000 +1.394682 -0.552142 6.500000 +1.394682 -0.552142 3.500000 +1.474958 -0.272945 6.500000 +1.474958 -0.272945 3.500000 +0.254748 1.376628 6.500000 +0.820815 1.255493 6.500000 +0.515333 1.301704 6.500000 +1.060660 1.060660 6.500000 +0.766094 1.171794 6.500000 +1.255493 0.820815 6.500000 +0.989949 0.989949 6.500000 +1.394682 0.552142 6.500000 +1.171794 0.766094 6.500000 +1.474958 0.272945 6.500000 +1.301704 0.515333 6.500000 +1.500000 0.000000 6.500000 +1.376628 0.254748 6.500000 +1.474958 -0.272945 6.500000 +1.400000 0.000000 6.500000 +1.394682 -0.552142 6.500000 +1.376628 -0.254748 6.500000 +1.255493 -0.820815 6.500000 +1.301704 -0.515333 6.500000 +1.060660 -1.060660 6.500000 +1.171794 -0.766094 6.500000 +0.820815 -1.255493 6.500000 +0.989949 -0.989949 6.500000 +0.552142 -1.394682 6.500000 +0.766094 -1.171794 6.500000 +0.272945 -1.474958 6.500000 +0.515333 -1.301704 6.500000 +0.000000 -1.500000 6.500000 +0.254748 -1.376628 6.500000 +-0.272945 -1.474958 6.500000 +0.000000 -1.400000 6.500000 +-0.552142 -1.394682 6.500000 +-0.254748 -1.376628 6.500000 +-0.820815 -1.255493 6.500000 +-0.515333 -1.301704 6.500000 +-1.060660 -1.060660 6.500000 +-0.766094 -1.171794 6.500000 +-1.255493 -0.820815 6.500000 +-0.989949 -0.989949 6.500000 +-1.394682 -0.552142 6.500000 +-1.171794 -0.766094 6.500000 +-1.474958 -0.272945 6.500000 +-1.301704 -0.515333 6.500000 +-1.500000 0.000000 6.500000 +-1.376628 -0.254748 6.500000 +-1.474958 0.272945 6.500000 +-1.400000 0.000000 6.500000 +-1.394682 0.552142 6.500000 +-1.376628 0.254748 6.500000 +-1.255493 0.820815 6.500000 +-1.301704 0.515333 6.500000 +-1.060660 1.060660 6.500000 +-1.171794 0.766094 6.500000 +-0.820815 1.255493 6.500000 +-0.989949 0.989949 6.500000 +-0.552142 1.394682 6.500000 +-0.766094 1.171794 6.500000 +-0.272945 1.474958 6.500000 +-0.515333 1.301704 6.500000 +0.000000 1.500000 6.500000 +-0.254748 1.376628 6.500000 +0.272945 1.474958 6.500000 +0.000000 1.400000 6.500000 +0.552142 1.394682 6.500000 +-1.400000 0.000000 11.300000 +-1.400000 0.000000 6.500000 +1.400000 0.000000 6.500000 +1.400000 0.000000 11.300000 +1.376628 -0.254748 6.500000 +1.376628 -0.254748 11.300000 +1.301704 -0.515333 6.500000 +1.301704 -0.515333 11.300000 +1.171794 -0.766094 6.500000 +1.171794 -0.766094 11.300000 +0.989949 -0.989949 6.500000 +0.989949 -0.989949 11.300000 +0.766094 -1.171794 6.500000 +0.766094 -1.171794 11.300000 +0.515333 -1.301704 6.500000 +0.515333 -1.301704 11.300000 +0.254748 -1.376628 6.500000 +0.254748 -1.376628 11.300000 +0.000000 -1.400000 6.500000 +0.000000 -1.400000 11.300000 +-0.254748 -1.376628 6.500000 +-0.254748 -1.376628 11.300000 +-0.515333 -1.301704 6.500000 +-0.515333 -1.301704 11.300000 +-0.766094 -1.171794 6.500000 +-0.766094 -1.171794 11.300000 +-0.989949 -0.989949 6.500000 +-0.989949 -0.989949 11.300000 +-1.171794 -0.766094 6.500000 +-1.171794 -0.766094 11.300000 +-1.301704 -0.515333 6.500000 +-1.301704 -0.515333 11.300000 +-1.376628 -0.254748 6.500000 +-1.376628 -0.254748 11.300000 +0.000000 1.200000 11.500000 +-0.218356 1.179966 11.500000 +-1.004395 0.656652 11.500000 +-1.115746 0.441714 11.500000 +-0.848528 0.848528 11.500000 +-0.656652 1.004395 11.500000 +-1.179966 0.218356 11.500000 +-0.441714 1.115746 11.500000 +-1.200000 0.000000 11.500000 +-1.179966 -0.218356 11.500000 +-1.115746 -0.441714 11.500000 +-1.004395 -0.656652 11.500000 +-0.848528 -0.848528 11.500000 +-0.656652 -1.004395 11.500000 +-0.441714 -1.115746 11.500000 +-0.218356 -1.179966 11.500000 +0.000000 -1.200000 11.500000 +0.218356 -1.179966 11.500000 +0.441714 -1.115746 11.500000 +0.656652 -1.004395 11.500000 +0.848528 -0.848528 11.500000 +1.004395 -0.656652 11.500000 +1.115746 -0.441714 11.500000 +1.179966 -0.218356 11.500000 +1.200000 0.000000 11.500000 +1.179966 0.218356 11.500000 +1.115746 0.441714 11.500000 +1.004395 0.656652 11.500000 +0.848528 0.848528 11.500000 +0.656652 1.004395 11.500000 +0.441714 1.115746 11.500000 +0.218356 1.179966 11.500000 +-1.474958 -0.272945 3.500000 +-0.272945 1.474958 3.500000 +0.000000 1.500000 3.500000 +1.322876 1.500000 3.500000 +0.272945 1.474958 3.500000 +-0.552142 1.394682 3.500000 +-0.820815 1.255493 3.500000 +0.552142 1.394682 3.500000 +0.820815 1.255493 3.500000 +-1.060660 1.060660 3.500000 +-1.322876 1.500000 3.500000 +-1.255493 0.820815 3.500000 +-1.606034 1.191913 3.500000 +-1.394682 0.552142 3.500000 +1.606034 1.191913 3.500000 +1.060660 1.060660 3.500000 +1.822876 0.822876 3.500000 +1.255493 0.820815 3.500000 +1.956226 0.416149 3.500000 +1.394682 0.552142 3.500000 +-1.822876 0.822876 3.500000 +-1.474958 0.272945 3.500000 +-1.956226 0.416149 3.500000 +-1.500000 0.000000 3.500000 +2.000000 0.000000 3.500000 +1.474958 0.272945 3.500000 +1.966611 -0.363926 3.500000 +1.500000 0.000000 3.500000 +1.859577 -0.736189 3.500000 +1.474958 -0.272945 3.500000 +1.673991 -1.094419 3.500000 +1.394682 -0.552142 3.500000 +1.414214 -1.414214 3.500000 +1.255493 -0.820815 3.500000 +1.094419 -1.673991 3.500000 +1.060660 -1.060660 3.500000 +0.736189 -1.859577 3.500000 +0.820815 -1.255493 3.500000 +0.363926 -1.966611 3.500000 +0.552142 -1.394682 3.500000 +0.000000 -2.000000 3.500000 +0.272945 -1.474958 3.500000 +-0.363926 -1.966611 3.500000 +0.000000 -1.500000 3.500000 +-0.736189 -1.859577 3.500000 +-0.272945 -1.474958 3.500000 +-1.094419 -1.673991 3.500000 +-0.552142 -1.394682 3.500000 +-1.414214 -1.414214 3.500000 +-0.820815 -1.255493 3.500000 +-1.673991 -1.094419 3.500000 +-1.060660 -1.060660 3.500000 +-1.859577 -0.736189 3.500000 +-1.255493 -0.820815 3.500000 +-1.966611 -0.363926 3.500000 +-1.394682 -0.552142 3.500000 +-2.000000 0.000000 3.500000 +-1.322876 1.500000 3.500000 +-1.322876 1.500000 0.200000 +-2.000000 0.000000 0.200000 +-2.000000 0.000000 3.500000 +-1.997785 0.094109 0.200000 +-1.942176 0.477442 0.200000 +-1.997785 0.094109 3.500000 +-1.942176 0.477442 3.500000 +-1.822876 0.822876 0.200000 +-1.642710 1.140834 0.200000 +-1.822876 0.822876 3.500000 +-1.642710 1.140834 3.500000 +-1.391992 1.436091 0.200000 +-1.391992 1.436091 3.500000 +-1.769950 -0.327533 0.000000 +-1.800000 0.000000 0.000000 +-1.244990 1.300000 0.000000 +1.244990 1.300000 0.000000 +1.478113 1.027221 0.000000 +1.655443 0.706760 0.000000 +1.764235 0.357037 0.000000 +1.800000 0.000000 0.000000 +1.769950 -0.327533 0.000000 +1.673619 -0.662570 0.000000 +1.506592 -0.984978 0.000000 +1.272792 -1.272792 0.000000 +0.984978 -1.506592 0.000000 +0.662570 -1.673619 0.000000 +-1.478113 1.027221 0.000000 +-1.655443 0.706760 0.000000 +-1.764235 0.357037 0.000000 +0.327533 -1.769950 0.000000 +0.000000 -1.800000 0.000000 +-0.327533 -1.769950 0.000000 +-0.662570 -1.673619 0.000000 +-0.984978 -1.506592 0.000000 +-1.272792 -1.272792 0.000000 +-1.506592 -0.984978 0.000000 +-1.673619 -0.662570 0.000000 +-1.322876 1.500000 0.200000 +-1.322876 1.500000 3.500000 +1.322876 1.500000 3.500000 +1.322876 1.500000 0.200000 +0.000000 1.500000 3.500000 +2.000000 0.000000 0.200000 +1.800000 0.000000 0.000000 +1.244990 1.300000 0.000000 +1.322876 1.500000 0.200000 +1.253038 1.292244 0.000000 +1.392264 1.435827 0.200000 +1.478634 1.026470 0.000000 +1.640719 0.740298 0.000000 +1.642927 1.140523 0.200000 +1.748040 0.429367 0.000000 +1.823032 0.822530 0.200000 +1.798022 0.084358 0.000000 +1.942267 0.477074 0.200000 +1.997802 0.093731 0.200000 +-1.322876 1.500000 0.200000 +1.322876 1.500000 0.200000 +1.244990 1.300000 0.000000 +-1.244990 1.300000 0.000000 +1.400000 0.000000 11.300000 +1.200000 0.000000 11.500000 +-1.200000 0.000000 11.500000 +-1.400000 0.000000 11.300000 +-1.179966 -0.218356 11.500000 +-1.376628 -0.254748 11.300000 +-1.115746 -0.441714 11.500000 +-1.301704 -0.515333 11.300000 +-1.004395 -0.656652 11.500000 +-1.171794 -0.766094 11.300000 +-0.848528 -0.848528 11.500000 +-0.989949 -0.989949 11.300000 +-0.656652 -1.004395 11.500000 +-0.766094 -1.171794 11.300000 +-0.441714 -1.115746 11.500000 +-0.515333 -1.301704 11.300000 +-0.218356 -1.179966 11.500000 +-0.254748 -1.376628 11.300000 +0.000000 -1.200000 11.500000 +0.000000 -1.400000 11.300000 +0.218356 -1.179966 11.500000 +0.254748 -1.376628 11.300000 +0.441714 -1.115746 11.500000 +0.515333 -1.301704 11.300000 +0.656652 -1.004395 11.500000 +0.766094 -1.171794 11.300000 +0.848528 -0.848528 11.500000 +0.989949 -0.989949 11.300000 +1.004395 -0.656652 11.500000 +1.171794 -0.766094 11.300000 +1.115746 -0.441714 11.500000 +1.301704 -0.515333 11.300000 +1.179966 -0.218356 11.500000 +1.376628 -0.254748 11.300000 +0.000000 1.500000 3.500000 + + + + + + + + + + + +0.695302 0.128667 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.695302 0.128667 0.707107 +-0.707107 0.000000 0.707107 +-0.695302 0.128667 0.707107 +-0.695302 0.128667 0.707107 +-0.707107 0.000000 0.707107 +-0.657460 0.260282 0.707107 +-0.695302 0.128667 0.707107 +-0.695302 0.128667 0.707107 +-0.657460 0.260282 0.707107 +-0.657460 0.260282 0.707107 +-0.695302 0.128667 0.707107 +-0.591845 0.386936 0.707107 +-0.657460 0.260282 0.707107 +-0.657460 0.260282 0.707107 +-0.591845 0.386936 0.707107 +-0.591845 0.386936 0.707107 +-0.657460 0.260282 0.707107 +-0.500000 0.500000 0.707107 +-0.591845 0.386936 0.707107 +-0.591845 0.386936 0.707107 +-0.500000 0.500000 0.707107 +-0.500000 0.500000 0.707107 +-0.591845 0.386936 0.707107 +-0.386936 0.591845 0.707107 +-0.500000 0.500000 0.707107 +-0.500000 0.500000 0.707107 +-0.386936 0.591845 0.707107 +-0.386936 0.591845 0.707107 +-0.500000 0.500000 0.707107 +-0.260282 0.657460 0.707107 +-0.386936 0.591845 0.707107 +-0.386936 0.591845 0.707107 +-0.260282 0.657460 0.707107 +-0.260282 0.657460 0.707107 +-0.386936 0.591845 0.707107 +-0.128667 0.695302 0.707107 +-0.260282 0.657460 0.707107 +-0.260282 0.657460 0.707107 +-0.128667 0.695302 0.707107 +-0.128667 0.695302 0.707107 +-0.260282 0.657460 0.707107 +0.000000 0.707107 0.707107 +-0.128667 0.695302 0.707107 +-0.128667 0.695302 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +-0.128667 0.695302 0.707107 +0.128667 0.695302 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.128667 0.695302 0.707107 +0.128667 0.695302 0.707107 +0.000000 0.707107 0.707107 +0.260282 0.657460 0.707107 +0.128667 0.695302 0.707107 +0.128667 0.695302 0.707107 +0.260282 0.657460 0.707107 +0.260282 0.657460 0.707107 +0.128667 0.695302 0.707107 +0.386936 0.591845 0.707107 +0.260282 0.657460 0.707107 +0.260282 0.657460 0.707107 +0.386936 0.591845 0.707107 +0.386936 0.591845 0.707107 +0.260282 0.657460 0.707107 +0.500000 0.500000 0.707107 +0.386936 0.591845 0.707107 +0.386936 0.591845 0.707107 +0.500000 0.500000 0.707107 +0.500000 0.500000 0.707107 +0.386936 0.591845 0.707107 +0.591845 0.386936 0.707107 +0.500000 0.500000 0.707107 +0.500000 0.500000 0.707107 +0.591845 0.386936 0.707107 +0.591845 0.386936 0.707107 +0.500000 0.500000 0.707107 +0.657460 0.260282 0.707107 +0.591845 0.386936 0.707107 +0.591845 0.386936 0.707107 +0.657460 0.260282 0.707107 +0.657460 0.260282 0.707107 +0.591845 0.386936 0.707107 +0.695302 0.128667 0.707107 +0.657460 0.260282 0.707107 +0.657460 0.260282 0.707107 +0.695302 0.128667 0.707107 +0.695302 0.128667 0.707107 +0.657460 0.260282 0.707107 +0.707107 0.000000 0.707107 +0.695302 0.128667 0.707107 +0.695302 0.128667 0.707107 +-0.707107 0.000000 -0.707107 +-0.706330 0.033139 -0.707107 +-0.706330 0.033139 -0.707107 +-0.489078 0.510688 -0.707107 +-0.492240 0.507642 -0.707107 +-0.467707 0.530330 -0.707107 +-0.492240 0.507642 -0.707107 +-0.492240 0.507642 -0.707107 +-0.489078 0.510688 -0.707107 +-0.492240 0.507642 -0.707107 +-0.580862 0.403236 -0.707107 +-0.492240 0.507642 -0.707107 +-0.580862 0.403236 -0.707107 +-0.580862 0.403236 -0.707107 +-0.492240 0.507642 -0.707107 +-0.580862 0.403236 -0.707107 +-0.644539 0.290808 -0.707107 +-0.580862 0.403236 -0.707107 +-0.644539 0.290808 -0.707107 +-0.644539 0.290808 -0.707107 +-0.580862 0.403236 -0.707107 +-0.686695 0.168671 -0.707107 +-0.644539 0.290808 -0.707107 +-0.644539 0.290808 -0.707107 +-0.686695 0.168671 -0.707107 +-0.686695 0.168671 -0.707107 +-0.644539 0.290808 -0.707107 +-0.706330 0.033139 -0.707107 +-0.686695 0.168671 -0.707107 +-0.686695 0.168671 -0.707107 +-0.706330 0.033139 -0.707107 +-0.706330 0.033139 -0.707107 +-0.686695 0.168671 -0.707107 +-0.706330 0.033139 -0.707107 +-0.707107 0.000000 -0.707107 +-0.707107 0.000000 -0.707107 +-0.695302 -0.128667 -0.707107 +-0.707107 0.000000 -0.707107 +-0.707107 0.000000 -0.707107 +0.695302 -0.128667 -0.707107 +0.707107 0.000000 -0.707107 +0.707107 0.000000 -0.707107 +0.695302 -0.128667 -0.707107 +0.695302 -0.128667 -0.707107 +0.707107 0.000000 -0.707107 +0.657460 -0.260282 -0.707107 +0.695302 -0.128667 -0.707107 +0.695302 -0.128667 -0.707107 +0.657460 -0.260282 -0.707107 +0.657460 -0.260282 -0.707107 +0.695302 -0.128667 -0.707107 +0.591845 -0.386936 -0.707107 +0.657460 -0.260282 -0.707107 +0.657460 -0.260282 -0.707107 +0.591845 -0.386936 -0.707107 +0.591845 -0.386936 -0.707107 +0.657460 -0.260282 -0.707107 +0.500000 -0.500000 -0.707107 +0.591845 -0.386936 -0.707107 +0.591845 -0.386936 -0.707107 +0.500000 -0.500000 -0.707107 +0.500000 -0.500000 -0.707107 +0.591845 -0.386936 -0.707107 +0.386936 -0.591845 -0.707107 +0.500000 -0.500000 -0.707107 +0.500000 -0.500000 -0.707107 +0.386936 -0.591845 -0.707107 +0.386936 -0.591845 -0.707107 +0.500000 -0.500000 -0.707107 +0.260282 -0.657460 -0.707107 +0.386936 -0.591845 -0.707107 +0.386936 -0.591845 -0.707107 +0.260282 -0.657460 -0.707107 +0.260282 -0.657460 -0.707107 +0.386936 -0.591845 -0.707107 +0.128667 -0.695302 -0.707107 +0.260282 -0.657460 -0.707107 +0.260282 -0.657460 -0.707107 +0.128667 -0.695302 -0.707107 +0.128667 -0.695302 -0.707107 +0.260282 -0.657460 -0.707107 +0.000000 -0.707107 -0.707107 +0.128667 -0.695302 -0.707107 +0.128667 -0.695302 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.128667 -0.695302 -0.707107 +-0.128667 -0.695302 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +-0.128667 -0.695302 -0.707107 +-0.128667 -0.695302 -0.707107 +0.000000 -0.707107 -0.707107 +-0.260282 -0.657460 -0.707107 +-0.128667 -0.695302 -0.707107 +-0.128667 -0.695302 -0.707107 +-0.260282 -0.657460 -0.707107 +-0.260282 -0.657460 -0.707107 +-0.128667 -0.695302 -0.707107 +-0.386936 -0.591845 -0.707107 +-0.260282 -0.657460 -0.707107 +-0.260282 -0.657460 -0.707107 +-0.386936 -0.591845 -0.707107 +-0.386936 -0.591845 -0.707107 +-0.260282 -0.657460 -0.707107 +-0.500000 -0.500000 -0.707107 +-0.386936 -0.591845 -0.707107 +-0.386936 -0.591845 -0.707107 +-0.500000 -0.500000 -0.707107 +-0.500000 -0.500000 -0.707107 +-0.386936 -0.591845 -0.707107 +-0.591845 -0.386936 -0.707107 +-0.500000 -0.500000 -0.707107 +-0.500000 -0.500000 -0.707107 +-0.591845 -0.386936 -0.707107 +-0.591845 -0.386936 -0.707107 +-0.500000 -0.500000 -0.707107 +-0.591845 -0.386936 -0.707107 +-0.657460 -0.260282 -0.707107 +-0.591845 -0.386936 -0.707107 +-0.657460 -0.260282 -0.707107 +-0.657460 -0.260282 -0.707107 +-0.591845 -0.386936 -0.707107 +-0.695302 -0.128667 -0.707107 +-0.657460 -0.260282 -0.707107 +-0.657460 -0.260282 -0.707107 +-0.695302 -0.128667 -0.707107 +-0.695302 -0.128667 -0.707107 +-0.657460 -0.260282 -0.707107 +-0.707107 0.000000 -0.707107 +-0.695302 -0.128667 -0.707107 +-0.695302 -0.128667 -0.707107 +1.000000 0.000000 0.000000 +0.998892 0.047055 0.000000 +1.000000 0.000000 0.000000 +0.661438 0.750000 0.000000 +0.695996 0.718046 0.000000 +0.661438 0.750000 0.000000 +0.695996 0.718046 0.000000 +0.695996 0.718046 0.000000 +0.661438 0.750000 0.000000 +0.821355 0.570417 0.000000 +0.695996 0.718046 0.000000 +0.695996 0.718046 0.000000 +0.821355 0.570417 0.000000 +0.821355 0.570417 0.000000 +0.695996 0.718046 0.000000 +0.911438 0.411438 0.000000 +0.821355 0.570417 0.000000 +0.821355 0.570417 0.000000 +0.911438 0.411438 0.000000 +0.911438 0.411438 0.000000 +0.821355 0.570417 0.000000 +0.911438 0.411438 0.000000 +0.971088 0.238721 0.000000 +0.911438 0.411438 0.000000 +0.971088 0.238721 0.000000 +0.971088 0.238721 0.000000 +0.911438 0.411438 0.000000 +0.971088 0.238721 0.000000 +0.998892 0.047055 0.000000 +0.971088 0.238721 0.000000 +0.998892 0.047055 0.000000 +0.998892 0.047055 0.000000 +0.971088 0.238721 0.000000 +0.998892 0.047055 0.000000 +1.000000 0.000000 0.000000 +0.998892 0.047055 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.695996 0.718046 0.000000 +-0.661438 0.750000 0.000000 +-0.661438 0.750000 0.000000 +-0.998892 0.047055 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.998892 0.047055 0.000000 +-0.998892 0.047055 0.000000 +-1.000000 0.000000 0.000000 +-0.998892 0.047055 0.000000 +-0.971088 0.238721 0.000000 +-0.998892 0.047055 0.000000 +-0.971088 0.238721 0.000000 +-0.971088 0.238721 0.000000 +-0.998892 0.047055 0.000000 +-0.911438 0.411438 0.000000 +-0.971088 0.238721 0.000000 +-0.971088 0.238721 0.000000 +-0.911438 0.411438 0.000000 +-0.911438 0.411438 0.000000 +-0.971088 0.238721 0.000000 +-0.911438 0.411438 0.000000 +-0.821355 0.570417 0.000000 +-0.911438 0.411438 0.000000 +-0.821355 0.570417 0.000000 +-0.821355 0.570417 0.000000 +-0.911438 0.411438 0.000000 +-0.695996 0.718046 0.000000 +-0.821355 0.570417 0.000000 +-0.821355 0.570417 0.000000 +-0.695996 0.718046 0.000000 +-0.695996 0.718046 0.000000 +-0.821355 0.570417 0.000000 +-0.661438 0.750000 0.000000 +-0.695996 0.718046 0.000000 +-0.695996 0.718046 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.706330 0.033139 -0.707107 +0.707107 0.000000 -0.707107 +0.707107 0.000000 -0.707107 +0.492240 0.507642 -0.707107 +0.489078 0.510688 -0.707107 +0.467707 0.530330 -0.707107 +0.492240 0.507642 -0.707107 +0.492240 0.507642 -0.707107 +0.489078 0.510688 -0.707107 +0.580862 0.403236 -0.707107 +0.492240 0.507642 -0.707107 +0.492240 0.507642 -0.707107 +0.580862 0.403236 -0.707107 +0.580862 0.403236 -0.707107 +0.492240 0.507642 -0.707107 +0.580862 0.403236 -0.707107 +0.644539 0.290808 -0.707107 +0.580862 0.403236 -0.707107 +0.644539 0.290808 -0.707107 +0.644539 0.290808 -0.707107 +0.580862 0.403236 -0.707107 +0.644539 0.290808 -0.707107 +0.686695 0.168671 -0.707107 +0.644539 0.290808 -0.707107 +0.686695 0.168671 -0.707107 +0.686695 0.168671 -0.707107 +0.644539 0.290808 -0.707107 +0.686695 0.168671 -0.707107 +0.706330 0.033139 -0.707107 +0.686695 0.168671 -0.707107 +0.706330 0.033139 -0.707107 +0.706330 0.033139 -0.707107 +0.686695 0.168671 -0.707107 +0.707107 0.000000 -0.707107 +0.706330 0.033139 -0.707107 +0.706330 0.033139 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 +0.695302 -0.128667 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +-0.695302 -0.128667 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.695302 -0.128667 0.707107 +-0.695302 -0.128667 0.707107 +-0.707107 0.000000 0.707107 +-0.657460 -0.260282 0.707107 +-0.695302 -0.128667 0.707107 +-0.695302 -0.128667 0.707107 +-0.657460 -0.260282 0.707107 +-0.657460 -0.260282 0.707107 +-0.695302 -0.128667 0.707107 +-0.591845 -0.386936 0.707107 +-0.657460 -0.260282 0.707107 +-0.657460 -0.260282 0.707107 +-0.591845 -0.386936 0.707107 +-0.591845 -0.386936 0.707107 +-0.657460 -0.260282 0.707107 +-0.500000 -0.500000 0.707107 +-0.591845 -0.386936 0.707107 +-0.591845 -0.386936 0.707107 +-0.500000 -0.500000 0.707107 +-0.500000 -0.500000 0.707107 +-0.591845 -0.386936 0.707107 +-0.386936 -0.591845 0.707107 +-0.500000 -0.500000 0.707107 +-0.500000 -0.500000 0.707107 +-0.386936 -0.591845 0.707107 +-0.386936 -0.591845 0.707107 +-0.500000 -0.500000 0.707107 +-0.260282 -0.657460 0.707107 +-0.386936 -0.591845 0.707107 +-0.386936 -0.591845 0.707107 +-0.260282 -0.657460 0.707107 +-0.260282 -0.657460 0.707107 +-0.386936 -0.591845 0.707107 +-0.128667 -0.695302 0.707107 +-0.260282 -0.657460 0.707107 +-0.260282 -0.657460 0.707107 +-0.128667 -0.695302 0.707107 +-0.128667 -0.695302 0.707107 +-0.260282 -0.657460 0.707107 +0.000000 -0.707107 0.707107 +-0.128667 -0.695302 0.707107 +-0.128667 -0.695302 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +-0.128667 -0.695302 0.707107 +0.128667 -0.695302 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.128667 -0.695302 0.707107 +0.128667 -0.695302 0.707107 +0.000000 -0.707107 0.707107 +0.260282 -0.657460 0.707107 +0.128667 -0.695302 0.707107 +0.128667 -0.695302 0.707107 +0.260282 -0.657460 0.707107 +0.260282 -0.657460 0.707107 +0.128667 -0.695302 0.707107 +0.386936 -0.591845 0.707107 +0.260282 -0.657460 0.707107 +0.260282 -0.657460 0.707107 +0.386936 -0.591845 0.707107 +0.386936 -0.591845 0.707107 +0.260282 -0.657460 0.707107 +0.500000 -0.500000 0.707107 +0.386936 -0.591845 0.707107 +0.386936 -0.591845 0.707107 +0.500000 -0.500000 0.707107 +0.500000 -0.500000 0.707107 +0.386936 -0.591845 0.707107 +0.591845 -0.386936 0.707107 +0.500000 -0.500000 0.707107 +0.500000 -0.500000 0.707107 +0.591845 -0.386936 0.707107 +0.591845 -0.386936 0.707107 +0.500000 -0.500000 0.707107 +0.657460 -0.260282 0.707107 +0.591845 -0.386936 0.707107 +0.591845 -0.386936 0.707107 +0.657460 -0.260282 0.707107 +0.657460 -0.260282 0.707107 +0.591845 -0.386936 0.707107 +0.695302 -0.128667 0.707107 +0.657460 -0.260282 0.707107 +0.657460 -0.260282 0.707107 +0.695302 -0.128667 0.707107 +0.695302 -0.128667 0.707107 +0.657460 -0.260282 0.707107 +0.707107 0.000000 0.707107 +0.695302 -0.128667 0.707107 +0.695302 -0.128667 0.707107 + + + + + + + + + + + +1.921761 -0.577681 +1.921761 -0.443726 +0.120110 -0.443726 +0.000000 -0.443726 +0.000000 -0.577681 +0.120110 -0.577681 +0.240220 -0.443726 +0.240220 -0.577681 +0.360330 -0.443726 +0.360330 -0.577681 +0.480440 -0.443726 +0.480440 -0.577681 +0.600550 -0.443726 +0.600550 -0.577681 +0.720660 -0.443726 +0.720660 -0.577681 +0.840770 -0.443726 +0.840770 -0.577681 +0.960880 -0.443726 +0.960880 -0.577681 +1.080990 -0.443726 +1.080990 -0.577681 +1.201101 -0.443726 +1.201101 -0.577681 +1.321211 -0.443726 +1.321211 -0.577681 +1.441321 -0.443726 +1.441321 -0.577681 +1.561431 -0.443726 +1.561431 -0.577681 +1.681541 -0.443726 +1.681541 -0.577681 +1.801651 -0.443726 +1.801651 -0.577681 +2.780885 -0.803730 +2.078703 -0.669775 +2.037121 -0.669775 +2.073217 -0.803730 +2.254248 -0.669775 +2.078703 -0.803730 +2.429794 -0.669775 +2.254248 -0.803730 +2.429794 -0.803730 +2.605339 -0.669775 +2.605339 -0.803730 +2.780885 -0.669775 +2.822134 -0.803730 +2.822134 -0.669775 +2.808728 -0.669775 +2.808728 -0.803730 +5.617455 -0.803730 +5.617455 -0.669775 +5.441909 -0.803730 +5.441909 -0.669775 +5.266364 -0.803730 +5.266364 -0.669775 +5.090818 -0.803730 +5.090818 -0.669775 +4.915273 -0.803730 +4.915273 -0.669775 +4.739727 -0.803730 +4.739727 -0.669775 +4.564182 -0.803730 +4.564182 -0.669775 +4.388637 -0.803730 +4.388637 -0.669775 +4.213091 -0.803730 +4.213091 -0.669775 +4.037546 -0.803730 +4.037546 -0.669775 +3.862000 -0.803730 +3.862000 -0.669775 +3.686455 -0.803730 +3.686455 -0.669775 +3.510909 -0.803730 +3.510909 -0.669775 +3.335364 -0.803730 +3.159818 -0.803730 +3.335364 -0.669775 +3.159818 -0.669775 +2.984273 -0.803730 +2.984273 -0.669775 +2.927069 -0.000000 +2.970664 -0.000000 +2.187930 1.562887 +2.144334 1.562887 +2.144334 -0.000000 +2.187930 -0.000000 +2.372715 1.562887 +2.372715 -0.000000 +2.557499 1.562887 +2.742284 1.562887 +2.557499 -0.000000 +2.927069 1.562887 +2.742284 -0.000000 +2.970664 1.562887 +2.956555 1.562887 +2.956555 -0.000000 +5.913110 -0.000000 +5.913110 1.562887 +5.728326 -0.000000 +5.728326 1.562887 +5.543541 -0.000000 +5.543541 1.562887 +5.358756 -0.000000 +5.358756 1.562887 +5.173972 -0.000000 +5.173972 1.562887 +4.989187 -0.000000 +4.989187 1.562887 +4.804402 -0.000000 +4.804402 1.562887 +4.619617 -0.000000 +4.619617 1.562887 +4.434833 -0.000000 +4.434833 1.562887 +4.250048 -0.000000 +4.250048 1.562887 +4.065263 -0.000000 +4.065263 1.562887 +3.880479 -0.000000 +3.880479 1.562887 +3.695694 -0.000000 +3.695694 1.562887 +3.510909 -0.000000 +3.510909 1.562887 +3.326125 -0.000000 +3.326125 1.562887 +3.141340 -0.000000 +3.141340 1.562887 +2.069589 0.000000 +2.069589 2.273291 +0.000000 2.273291 +0.000000 0.000000 +0.129349 2.273291 +0.129349 0.000000 +0.258699 2.273291 +0.258699 0.000000 +0.388048 2.273291 +0.388048 0.000000 +0.517397 2.273291 +0.517397 0.000000 +0.646746 2.273291 +0.776096 2.273291 +0.646746 0.000000 +0.776096 0.000000 +0.905445 2.273291 +0.905445 0.000000 +1.034794 2.273291 +1.034794 0.000000 +1.164144 2.273291 +1.164144 0.000000 +1.293493 2.273291 +1.293493 0.000000 +1.422842 2.273291 +1.422842 0.000000 +1.552191 2.273291 +1.552191 0.000000 +1.681541 2.273291 +1.681541 0.000000 +1.810890 2.273291 +1.810890 0.000000 +1.940239 2.273291 +1.940239 0.000000 +0.692943 2.368011 +0.138589 3.788818 +0.000000 3.788818 +0.000000 2.368011 +0.138589 2.368011 +0.277177 3.788818 +0.277177 2.368011 +0.415766 3.788818 +0.415766 2.368011 +0.554354 3.788818 +0.554354 2.368011 +0.692943 3.788818 +2.078828 2.368011 +2.217416 2.368011 +2.217416 3.788818 +2.078828 3.788818 +1.940239 2.368011 +1.940239 3.788818 +1.801651 2.368011 +1.801651 3.788818 +1.663062 2.368011 +1.663062 3.788818 +1.524474 2.368011 +1.385885 2.368011 +1.524474 3.788818 +1.247297 2.368011 +1.385885 3.788818 +1.108708 2.368011 +1.247297 3.788818 +1.108708 3.788818 +0.970120 2.368011 +0.970120 3.788818 +0.831531 2.368011 +0.831531 3.788818 +2.217416 3.788818 +2.217416 2.368011 +4.434833 2.368011 +4.434833 3.788818 +4.296244 2.368011 +4.296244 3.788818 +4.157656 2.368011 +4.157656 3.788818 +4.019067 2.368011 +4.019067 3.788818 +3.880479 2.368011 +3.880479 3.788818 +3.741890 2.368011 +3.741890 3.788818 +3.603302 2.368011 +3.603302 3.788818 +3.464713 2.368011 +3.464713 3.788818 +3.326125 2.368011 +3.326125 3.788818 +3.187536 2.368011 +3.187536 3.788818 +3.048948 2.368011 +3.048948 3.788818 +2.910359 2.368011 +2.910359 3.788818 +2.771770 2.368011 +2.771770 3.788818 +2.633182 2.368011 +2.633182 3.788818 +2.494593 2.368011 +2.494593 3.788818 +2.356005 2.368011 +2.356005 3.788818 +0.120649 0.651974 +0.388740 0.594604 +0.244063 0.616490 +0.502331 0.502331 +0.362824 0.554964 +0.594604 0.388740 +0.468842 0.468842 +0.660525 0.261496 +0.554964 0.362824 +0.698543 0.129267 +0.616490 0.244063 +0.710403 -0.000000 +0.651974 0.120649 +0.698543 -0.129267 +0.663043 -0.000000 +0.660525 -0.261496 +0.651974 -0.120649 +0.594604 -0.388740 +0.616490 -0.244063 +0.502331 -0.502331 +0.554964 -0.362824 +0.388740 -0.594604 +0.468842 -0.468842 +0.261496 -0.660525 +0.362824 -0.554964 +0.129267 -0.698543 +0.244063 -0.616490 +-0.000000 -0.710403 +0.120649 -0.651974 +-0.129267 -0.698543 +0.000000 -0.663043 +-0.261496 -0.660525 +-0.120649 -0.651974 +-0.388740 -0.594604 +-0.244063 -0.616490 +-0.502331 -0.502331 +-0.362824 -0.554964 +-0.594604 -0.388740 +-0.468842 -0.468842 +-0.660525 -0.261496 +-0.554964 -0.362824 +-0.698543 -0.129267 +-0.616490 -0.244063 +-0.710403 -0.000000 +-0.651974 -0.120649 +-0.698543 0.129267 +-0.663043 -0.000000 +-0.660525 0.261496 +-0.651974 0.120649 +-0.594604 0.388740 +-0.616490 0.244063 +-0.502331 0.502331 +-0.554964 0.362824 +-0.388740 0.594604 +-0.468842 0.468842 +-0.261496 0.660525 +-0.362824 0.554964 +-0.129267 0.698543 +-0.244063 0.616490 +0.000000 0.710403 +-0.120649 0.651974 +0.129267 0.698543 +0.000000 0.663043 +0.261496 0.660525 +2.069589 2.273291 +2.069589 0.000000 +4.139177 0.000000 +4.139177 2.273291 +4.009828 0.000000 +4.009828 2.273291 +3.880479 0.000000 +3.880479 2.273291 +3.751129 0.000000 +3.751129 2.273291 +3.621780 0.000000 +3.621780 2.273291 +3.492431 0.000000 +3.492431 2.273291 +3.363081 0.000000 +3.363081 2.273291 +3.233732 0.000000 +3.233732 2.273291 +3.104383 0.000000 +3.104383 2.273291 +2.975034 0.000000 +2.975034 2.273291 +2.845684 0.000000 +2.845684 2.273291 +2.716335 0.000000 +2.716335 2.273291 +2.586986 0.000000 +2.586986 2.273291 +2.457637 0.000000 +2.457637 2.273291 +2.328287 0.000000 +2.328287 2.273291 +2.198938 0.000000 +2.198938 2.273291 +-0.000000 0.568323 +-0.103414 0.558835 +-0.475684 0.310992 +-0.528420 0.209197 +-0.401865 0.401865 +-0.310992 0.475684 +-0.558835 0.103414 +-0.209197 0.528420 +-0.568323 0.000000 +-0.558835 -0.103414 +-0.528420 -0.209197 +-0.475684 -0.310992 +-0.401865 -0.401865 +-0.310992 -0.475684 +-0.209197 -0.528420 +-0.103414 -0.558835 +-0.000000 -0.568323 +0.103414 -0.558835 +0.209197 -0.528420 +0.310992 -0.475684 +0.401865 -0.401865 +0.475684 -0.310992 +0.528420 -0.209197 +0.558835 -0.103414 +0.568323 -0.000000 +0.558835 0.103414 +0.528420 0.209197 +0.475684 0.310992 +0.401865 0.401865 +0.310992 0.475684 +0.209197 0.528420 +0.103414 0.558835 +-0.129267 0.698543 +0.698543 0.129267 +0.710403 -0.000000 +0.710403 -0.626517 +0.698543 -0.129267 +0.660525 0.261496 +0.594604 0.388740 +0.660525 -0.261496 +0.594604 -0.388740 +0.502331 0.502331 +0.710403 0.626517 +0.388740 0.594604 +0.564493 0.760621 +0.261496 0.660525 +0.564493 -0.760621 +0.502331 -0.502331 +0.389716 -0.863318 +0.388740 -0.594604 +0.197089 -0.926473 +0.261496 -0.660525 +0.389716 0.863318 +0.129267 0.698543 +0.197089 0.926473 +0.000000 0.710403 +0.000000 -0.947204 +0.129267 -0.698543 +-0.172356 -0.931391 +0.000000 -0.710403 +-0.348661 -0.880700 +-0.129267 -0.698543 +-0.518319 -0.792806 +-0.261496 -0.660525 +-0.669775 -0.669775 +-0.388740 -0.594604 +-0.792806 -0.518319 +-0.502331 -0.502331 +-0.880700 -0.348661 +-0.594604 -0.388740 +-0.931391 -0.172356 +-0.660525 -0.261496 +-0.947204 -0.000000 +-0.698543 -0.129267 +-0.931391 0.172356 +-0.710403 -0.000000 +-0.880700 0.348661 +-0.698543 0.129267 +-0.792806 0.518319 +-0.660525 0.261496 +-0.669775 0.669775 +-0.594604 0.388740 +-0.518319 0.792806 +-0.502331 0.502331 +-0.348661 0.880700 +-0.388740 0.594604 +-0.172356 0.931391 +-0.261496 0.660525 +0.000000 0.947204 +0.812221 -0.000000 +0.812221 1.562887 +-0.014109 1.562887 +-0.014109 -0.000000 +0.029487 1.562887 +0.214271 1.562887 +0.029487 -0.000000 +0.214271 -0.000000 +0.399056 1.562887 +0.583841 1.562887 +0.399056 -0.000000 +0.583841 -0.000000 +0.768625 1.562887 +0.768625 -0.000000 +-0.155121 -0.838252 +-0.000000 -0.852484 +0.615683 -0.589630 +0.615683 0.589630 +0.486494 0.700038 +0.334723 0.784021 +0.169094 0.835545 +-0.000000 0.852484 +-0.155121 0.838252 +-0.313795 0.792630 +-0.466488 0.713525 +-0.602797 0.602797 +-0.713525 0.466488 +-0.792630 0.313795 +0.486494 -0.700038 +0.334723 -0.784021 +0.169094 -0.835545 +-0.838252 0.155121 +-0.852484 0.000000 +-0.838252 -0.155121 +-0.792630 -0.313795 +-0.713525 -0.466488 +-0.602797 -0.602797 +-0.466488 -0.713525 +-0.313795 -0.792630 +1.230536 -3.409936 +1.230536 -4.972823 +2.483570 -4.972823 +2.483570 -3.409936 +1.857053 -4.972823 +-0.013407 -0.669775 +-0.013407 -0.803730 +0.735510 -0.803730 +0.771606 -0.669775 +0.730025 -0.803730 +0.730025 -0.669775 +0.554479 -0.803730 +0.378934 -0.803730 +0.554479 -0.669775 +0.203388 -0.803730 +0.378934 -0.669775 +0.027843 -0.803730 +0.203388 -0.669775 +0.027843 -0.669775 +0.133955 -0.626517 +0.133955 0.626517 +-0.000000 0.589630 +-0.000000 -0.589630 +1.921761 -0.443726 +1.921761 -0.577681 +3.843522 -0.577681 +3.843522 -0.443726 +3.723412 -0.577681 +3.723412 -0.443726 +3.603302 -0.577681 +3.603302 -0.443726 +3.483191 -0.577681 +3.483191 -0.443726 +3.363081 -0.577681 +3.363081 -0.443726 +3.242971 -0.577681 +3.242971 -0.443726 +3.122861 -0.577681 +3.122861 -0.443726 +3.002751 -0.577681 +3.002751 -0.443726 +2.882641 -0.577681 +2.882641 -0.443726 +2.762531 -0.577681 +2.762531 -0.443726 +2.642421 -0.577681 +2.642421 -0.443726 +2.522311 -0.577681 +2.522311 -0.443726 +2.402201 -0.577681 +2.402201 -0.443726 +2.282091 -0.577681 +2.282091 -0.443726 +2.161981 -0.577681 +2.161981 -0.443726 +2.041871 -0.577681 +2.041871 -0.443726 + + + + + + + + + + + +

32 0 32 0 1 0 1 2 1 4 3 4 2 4 2 3 5 3 5 6 5 2 7 2 4 8 4 7 9 7 2 10 2 5 11 5 7 12 7 6 13 6 2 14 2 9 15 9 6 16 6 7 17 7 9 18 9 8 19 8 6 20 6 11 21 11 8 22 8 9 23 9 11 24 11 10 25 10 8 26 8 13 27 13 10 28 10 11 29 11 13 30 13 12 31 12 10 32 10 15 33 15 12 34 12 13 35 13 15 36 15 14 37 14 12 38 12 17 39 17 14 40 14 15 41 15 17 42 17 16 43 16 14 44 14 19 45 19 16 46 16 17 47 17 19 48 19 18 49 18 16 50 16 21 51 21 18 52 18 19 53 19 21 54 21 20 55 20 18 56 18 23 57 23 20 58 20 21 59 21 23 60 23 22 61 22 20 62 20 25 63 25 22 64 22 23 65 23 25 66 25 24 67 24 22 68 22 27 69 27 24 70 24 25 71 25 27 72 27 26 73 26 24 74 24 29 75 29 26 76 26 27 77 27 29 78 29 28 79 28 26 80 26 31 81 31 28 82 28 29 83 29 31 84 31 30 85 30 28 86 28 33 87 33 30 88 30 31 89 31 33 90 33 32 91 32 30 92 30 0 93 0 32 94 32 33 95 33 46 96 46 45 97 45 34 98 34 37 99 37 35 100 35 36 101 36 39 102 39 35 103 35 37 104 37 39 105 39 38 106 38 35 107 35 41 108 41 38 109 38 39 110 39 41 111 41 40 112 40 38 113 38 42 114 42 40 115 40 41 116 41 44 117 44 40 118 40 42 119 42 44 120 44 43 121 43 40 122 40 34 123 34 43 124 43 44 125 44 34 126 34 45 127 45 43 128 43 45 129 45 46 130 46 47 131 47 80 132 80 48 133 48 49 134 49 53 135 53 50 136 50 51 137 51 53 138 53 52 139 52 50 140 50 55 141 55 52 142 52 53 143 53 55 144 55 54 145 54 52 146 52 57 147 57 54 148 54 55 149 55 57 150 57 56 151 56 54 152 54 59 153 59 56 154 56 57 155 57 59 156 59 58 157 58 56 158 56 61 159 61 58 160 58 59 161 59 61 162 61 60 163 60 58 164 58 63 165 63 60 166 60 61 167 61 63 168 63 62 169 62 60 170 60 65 171 65 62 172 62 63 173 63 65 174 65 64 175 64 62 176 62 67 177 67 64 178 64 65 179 65 67 180 67 66 181 66 64 182 64 69 183 69 66 184 66 67 185 67 69 186 69 68 187 68 66 188 66 71 189 71 68 190 68 69 191 69 71 192 71 70 193 70 68 194 68 73 195 73 70 196 70 71 197 71 73 198 73 72 199 72 70 200 70 75 201 75 72 202 72 73 203 73 75 204 75 74 205 74 72 206 72 78 207 78 74 208 74 75 209 75 78 210 78 76 211 76 74 212 74 78 213 78 77 214 77 76 215 76 79 216 79 77 217 77 78 218 78 81 219 81 77 220 77 79 221 79 81 222 81 80 223 80 77 224 77 48 225 48 80 226 80 81 227 81 95 228 95 82 229 82 83 230 83 86 231 86 84 232 84 85 233 85 87 234 87 84 235 84 86 236 86 89 237 89 84 238 84 87 239 87 89 240 89 88 241 88 84 242 84 92 243 92 88 244 88 89 245 89 92 246 92 90 247 90 88 248 88 92 249 92 91 250 91 90 251 90 94 252 94 91 253 91 92 254 92 94 255 94 93 256 93 91 257 91 82 258 82 93 259 93 94 260 94 82 261 82 95 262 95 93 263 93 128 264 128 96 265 96 97 266 97 101 267 101 98 268 98 99 269 99 101 270 101 100 271 100 98 272 98 103 273 103 100 274 100 101 275 101 103 276 103 102 277 102 100 278 100 105 279 105 102 280 102 103 281 103 105 282 105 104 283 104 102 284 102 107 285 107 104 286 104 105 287 105 107 288 107 106 289 106 104 290 104 109 291 109 106 292 106 107 293 107 109 294 109 108 295 108 106 296 106 111 297 111 108 298 108 109 299 109 111 300 111 110 301 110 108 302 108 113 303 113 110 304 110 111 305 111 113 306 113 112 307 112 110 308 110 115 309 115 112 310 112 113 311 113 115 312 115 114 313 114 112 314 112 117 315 117 114 316 114 115 317 115 117 318 117 116 319 116 114 320 114 119 321 119 116 322 116 117 323 117 119 324 119 118 325 118 116 326 116 121 327 121 118 328 118 119 329 119 121 330 121 120 331 120 118 332 118 123 333 123 120 334 120 121 335 121 123 336 123 122 337 122 120 338 120 125 339 125 122 340 122 123 341 123 125 342 125 124 343 124 122 344 122 127 345 127 124 346 124 125 347 125 127 348 127 126 349 126 124 350 124 129 351 129 126 352 126 127 353 127 129 354 129 128 355 128 126 356 126 96 357 96 128 358 128 129 359 129 162 360 162 130 361 130 131 362 131 135 363 135 132 364 132 133 365 133 135 366 135 134 367 134 132 368 132 137 369 137 134 370 134 135 371 135 137 372 137 136 373 136 134 374 134 139 375 139 136 376 136 137 377 137 139 378 139 138 379 138 136 380 136 141 381 141 138 382 138 139 383 139 141 384 141 140 385 140 138 386 138 144 387 144 140 388 140 141 389 141 144 390 144 142 391 142 140 392 140 144 393 144 143 394 143 142 395 142 145 396 145 143 397 143 144 398 144 147 399 147 143 400 143 145 401 145 147 402 147 146 403 146 143 404 143 149 405 149 146 406 146 147 407 147 149 408 149 148 409 148 146 410 146 151 411 151 148 412 148 149 413 149 151 414 151 150 415 150 148 416 148 153 417 153 150 418 150 151 419 151 153 420 153 152 421 152 150 422 150 155 423 155 152 424 152 153 425 153 155 426 155 154 427 154 152 428 152 157 429 157 154 430 154 155 431 155 157 432 157 156 433 156 154 434 154 159 435 159 156 436 156 157 437 157 159 438 159 158 439 158 156 440 156 161 441 161 158 442 158 159 443 159 161 444 161 160 445 160 158 446 158 163 447 163 160 448 160 161 449 161 163 450 163 162 451 162 160 452 160 130 453 130 162 454 162 163 455 163 196 456 196 175 457 175 164 458 164 167 459 167 165 460 165 166 461 166 168 462 168 165 463 165 167 464 167 170 465 170 165 466 165 168 467 168 170 468 170 169 469 169 165 470 165 172 471 172 169 472 169 170 473 170 172 474 172 171 475 171 169 476 169 174 477 174 171 478 171 172 479 172 174 480 174 173 481 173 171 482 171 164 483 164 173 484 173 174 485 174 164 486 164 175 487 175 173 488 173 178 489 178 176 490 176 177 491 177 179 492 179 176 493 176 178 494 178 181 495 181 176 496 176 179 497 179 181 498 181 180 499 180 176 500 176 183 501 183 180 502 180 181 503 181 183 504 183 182 505 182 180 506 180 185 507 185 182 508 182 183 509 183 185 510 185 184 511 184 182 512 182 188 513 188 184 514 184 185 515 185 188 516 188 186 517 186 184 518 184 188 519 188 187 520 187 186 521 186 190 522 190 187 523 187 188 524 188 190 525 190 189 526 189 187 527 187 192 528 192 189 529 189 190 530 190 192 531 192 191 532 191 189 533 189 193 534 193 191 535 191 192 536 192 195 537 195 191 538 191 193 539 193 195 540 195 194 541 194 191 542 191 197 543 197 194 544 194 195 545 195 197 546 197 196 547 196 194 548 194 175 549 175 196 550 196 197 551 197 230 552 230 198 553 198 199 554 199 203 555 203 200 556 200 201 557 201 203 558 203 202 559 202 200 560 200 205 561 205 202 562 202 203 563 203 205 564 205 204 565 204 202 566 202 207 567 207 204 568 204 205 569 205 207 570 207 206 571 206 204 572 204 209 573 209 206 574 206 207 575 207 209 576 209 208 577 208 206 578 206 211 579 211 208 580 208 209 581 209 211 582 211 210 583 210 208 584 208 213 585 213 210 586 210 211 587 211 213 588 213 212 589 212 210 590 210 215 591 215 212 592 212 213 593 213 215 594 215 214 595 214 212 596 212 217 597 217 214 598 214 215 599 215 217 600 217 216 601 216 214 602 214 219 603 219 216 604 216 217 605 217 219 606 219 218 607 218 216 608 216 221 609 221 218 610 218 219 611 219 221 612 221 220 613 220 218 614 218 223 615 223 220 616 220 221 617 221 223 618 223 222 619 222 220 620 220 225 621 225 222 622 222 223 623 223 225 624 225 224 625 224 222 626 222 227 627 227 224 628 224 225 629 225 227 630 227 226 631 226 224 632 224 229 633 229 226 634 226 227 635 227 229 636 229 228 637 228 226 638 226 231 639 231 228 640 228 229 641 229 231 642 231 230 643 230 228 644 228 198 645 198 230 646 230 231 647 231 295 648 295 232 649 232 234 650 234 234 651 234 233 652 233 295 653 295 236 654 236 233 655 233 234 656 234 236 657 236 235 658 235 233 659 233 238 660 238 235 661 235 236 662 236 238 663 238 237 664 237 235 665 235 240 666 240 237 667 237 238 668 238 240 669 240 239 670 239 237 671 237 242 672 242 239 673 239 240 674 240 242 675 242 241 676 241 239 677 239 244 678 244 241 679 241 242 680 242 244 681 244 243 682 243 241 683 241 246 684 246 243 685 243 244 686 244 246 687 246 245 688 245 243 689 243 248 690 248 245 691 245 246 692 246 248 693 248 247 694 247 245 695 245 250 696 250 247 697 247 248 698 248 250 699 250 249 700 249 247 701 247 252 702 252 249 703 249 250 704 250 252 705 252 251 706 251 249 707 249 254 708 254 251 709 251 252 710 252 254 711 254 253 712 253 251 713 251 256 714 256 253 715 253 254 716 254 256 717 256 255 718 255 253 719 253 258 720 258 255 721 255 256 722 256 258 723 258 257 724 257 255 725 255 260 726 260 257 727 257 258 728 258 260 729 260 259 730 259 257 731 257 262 732 262 259 733 259 260 734 260 262 735 262 261 736 261 259 737 259 264 738 264 261 739 261 262 740 262 264 741 264 263 742 263 261 743 261 266 744 266 263 745 263 264 746 264 266 747 266 265 748 265 263 749 263 268 750 268 265 751 265 266 752 266 268 753 268 267 754 267 265 755 265 270 756 270 267 757 267 268 758 268 270 759 270 269 760 269 267 761 267 272 762 272 269 763 269 270 764 270 272 765 272 271 766 271 269 767 269 274 768 274 271 769 271 272 770 272 274 771 274 273 772 273 271 773 271 276 774 276 273 775 273 274 776 274 276 777 276 275 778 275 273 779 273 278 780 278 275 781 275 276 782 276 278 783 278 277 784 277 275 785 275 280 786 280 277 787 277 278 788 278 280 789 280 279 790 279 277 791 277 282 792 282 279 793 279 280 794 280 282 795 282 281 796 281 279 797 279 284 798 284 281 799 281 282 800 282 284 801 284 283 802 283 281 803 281 286 804 286 283 805 283 284 806 284 286 807 286 285 808 285 283 809 283 288 810 288 285 811 285 286 812 286 288 813 288 287 814 287 285 815 285 290 816 290 287 817 287 288 818 288 290 819 290 289 820 289 287 821 287 292 822 292 289 823 289 290 824 290 292 825 292 291 826 291 289 827 289 294 828 294 291 829 291 292 830 292 294 831 294 293 832 293 291 833 291 232 834 232 293 835 293 294 836 294 232 837 232 295 838 295 293 839 293 328 840 328 296 841 296 297 842 297 301 843 301 298 844 298 299 845 299 301 846 301 300 847 300 298 848 298 303 849 303 300 850 300 301 851 301 303 852 303 302 853 302 300 854 300 305 855 305 302 856 302 303 857 303 305 858 305 304 859 304 302 860 302 307 861 307 304 862 304 305 863 305 307 864 307 306 865 306 304 866 304 309 867 309 306 868 306 307 869 307 309 870 309 308 871 308 306 872 306 311 873 311 308 874 308 309 875 309 311 876 311 310 877 310 308 878 308 313 879 313 310 880 310 311 881 311 313 882 313 312 883 312 310 884 310 315 885 315 312 886 312 313 887 313 315 888 315 314 889 314 312 890 312 317 891 317 314 892 314 315 893 315 317 894 317 316 895 316 314 896 314 319 897 319 316 898 316 317 899 317 319 900 319 318 901 318 316 902 316 321 903 321 318 904 318 319 905 319 321 906 321 320 907 320 318 908 318 323 909 323 320 910 320 321 911 321 323 912 323 322 913 322 320 914 320 325 915 325 322 916 322 323 917 323 325 918 325 324 919 324 322 920 322 327 921 327 324 922 324 325 923 325 327 924 327 326 925 326 324 926 324 329 927 329 326 928 326 327 929 327 329 930 329 328 931 328 326 932 326 296 933 296 328 934 328 329 935 329 337 936 337 330 937 330 331 938 331 336 939 336 332 940 332 333 941 333 336 942 336 334 943 334 332 944 332 336 945 336 335 946 335 334 947 334 338 948 338 335 949 335 336 950 336 338 951 338 337 952 337 335 953 335 339 954 339 337 955 337 338 956 338 340 957 340 337 958 337 339 959 339 341 960 341 337 961 337 340 962 340 342 963 342 337 964 337 341 965 341 343 966 343 337 967 337 342 968 342 344 969 344 337 970 337 343 971 343 345 972 345 337 973 337 344 974 344 346 975 346 337 976 337 345 977 345 347 978 347 337 979 337 346 980 346 348 981 348 337 982 337 347 983 347 349 984 349 337 985 337 348 986 348 350 987 350 337 988 337 349 989 349 351 990 351 337 991 337 350 992 350 352 993 352 337 994 337 351 995 351 353 996 353 337 997 337 352 998 352 354 999 354 337 1000 337 353 1001 353 355 1002 355 337 1003 337 354 1004 354 356 1005 356 337 1006 337 355 1007 355 357 1008 357 337 1009 337 356 1010 356 358 1011 358 337 1012 337 357 1013 357 359 1014 359 337 1015 337 358 1016 358 360 1017 360 337 1018 337 359 1019 359 361 1020 361 337 1021 337 360 1022 360 330 1023 330 337 1024 337 361 1025 361 418 1026 418 362 1027 362 385 1028 385 372 1029 372 363 1030 363 364 1031 364 366 1032 366 365 1033 365 515 1034 364 369 1035 369 365 1036 365 366 1037 366 372 1038 372 367 1039 367 363 1040 363 372 1041 372 368 1042 368 367 1043 367 370 1044 370 365 1045 365 369 1046 369 377 1047 377 365 1048 365 370 1049 370 372 1050 372 371 1051 371 368 1052 368 374 1053 374 371 1054 371 372 1055 372 374 1056 374 373 1057 373 371 1058 371 382 1059 382 373 1060 373 374 1061 374 382 1062 382 375 1063 375 373 1064 373 377 1065 377 376 1066 376 365 1067 365 379 1068 379 376 1069 376 377 1070 377 379 1071 379 378 1072 378 376 1073 376 381 1074 381 378 1075 378 379 1076 379 381 1077 381 380 1078 380 378 1079 378 387 1080 387 380 1081 380 381 1082 381 384 1083 384 375 1084 375 382 1085 382 384 1086 384 383 1087 383 375 1088 375 418 1089 418 383 1090 383 384 1091 384 418 1092 418 385 1093 385 383 1094 383 387 1095 387 386 1096 386 380 1097 380 389 1098 389 386 1099 386 387 1100 387 389 1101 389 388 1102 388 386 1103 386 391 1104 391 388 1105 388 389 1106 389 391 1107 391 390 1108 390 388 1109 388 393 1110 393 390 1111 390 391 1112 391 393 1113 393 392 1114 392 390 1115 390 395 1116 395 392 1117 392 393 1118 393 395 1119 395 394 1120 394 392 1121 392 397 1122 397 394 1123 394 395 1124 395 397 1125 397 396 1126 396 394 1127 394 399 1128 399 396 1129 396 397 1130 397 399 1131 399 398 1132 398 396 1133 396 401 1134 401 398 1135 398 399 1136 399 401 1137 401 400 1138 400 398 1139 398 403 1140 403 400 1141 400 401 1142 401 403 1143 403 402 1144 402 400 1145 400 405 1146 405 402 1147 402 403 1148 403 405 1149 405 404 1150 404 402 1151 402 407 1152 407 404 1153 404 405 1154 405 407 1155 407 406 1156 406 404 1157 404 409 1158 409 406 1159 406 407 1160 407 409 1161 409 408 1162 408 406 1163 406 411 1164 411 408 1165 408 409 1166 409 411 1167 411 410 1168 410 408 1169 408 413 1170 413 410 1171 410 411 1172 411 413 1173 413 412 1174 412 410 1175 410 415 1176 415 412 1177 412 413 1178 413 415 1179 415 414 1180 414 412 1181 412 417 1182 417 414 1183 414 415 1184 415 417 1185 417 416 1186 416 414 1187 414 362 1188 362 416 1189 416 417 1190 417 362 1191 362 418 1192 418 416 1193 416 431 1194 431 419 1195 419 420 1196 420 425 1197 425 421 1198 421 422 1199 422 425 1200 425 423 1201 423 421 1202 421 425 1203 425 424 1204 424 423 1205 423 426 1206 426 424 1207 424 425 1208 425 429 1209 429 424 1210 424 426 1211 426 429 1212 429 427 1213 427 424 1214 424 429 1215 429 428 1216 428 427 1217 427 430 1218 430 428 1219 428 429 1220 429 432 1221 432 428 1222 428 430 1223 430 432 1224 432 431 1225 431 428 1226 428 419 1227 419 431 1228 431 432 1229 432 449 1230 449 433 1231 433 434 1232 434 437 1233 437 435 1234 435 436 1235 436 438 1236 438 435 1237 435 437 1238 437 439 1239 439 435 1240 435 438 1241 438 440 1242 440 435 1243 435 439 1244 439 441 1245 441 435 1246 435 440 1247 440 442 1248 442 435 1249 435 441 1250 441 443 1251 443 435 1252 435 442 1253 442 444 1254 444 435 1255 435 443 1256 443 445 1257 445 435 1258 435 444 1259 444 446 1260 446 435 1261 435 445 1262 445 450 1263 450 435 1264 435 446 1265 446 450 1266 450 447 1267 447 435 1268 435 450 1269 450 448 1270 448 447 1271 447 450 1272 450 449 1273 449 448 1274 448 451 1275 451 449 1276 449 450 1277 450 452 1278 452 449 1279 449 451 1280 451 453 1281 453 449 1282 449 452 1283 452 454 1284 454 449 1285 449 453 1286 453 455 1287 455 449 1288 449 454 1289 454 456 1290 456 449 1291 449 455 1292 455 457 1293 457 449 1294 449 456 1295 456 433 1296 433 449 1297 449 457 1298 457 462 1299 462 458 1300 458 459 1301 459 458 1302 458 460 1303 460 461 1304 461 458 1305 458 462 1306 462 460 1307 460 474 1308 474 463 1309 463 464 1310 464 468 1311 468 465 1312 465 466 1313 466 468 1314 468 467 1315 467 465 1316 465 471 1317 471 467 1318 467 468 1319 468 471 1320 471 469 1321 469 467 1322 467 471 1323 471 470 1324 470 469 1325 469 473 1326 473 470 1327 470 471 1328 471 473 1329 473 472 1330 472 470 1331 470 475 1332 475 472 1333 472 473 1334 473 475 1335 475 474 1336 474 472 1337 472 476 1338 476 474 1339 474 475 1340 475 463 1341 463 474 1342 474 476 1343 476 479 1344 479 477 1345 477 478 1346 478 477 1347 477 479 1348 479 480 1349 480 513 1350 513 481 1351 481 482 1352 482 486 1353 486 483 1354 483 484 1355 484 486 1356 486 485 1357 485 483 1358 483 488 1359 488 485 1360 485 486 1361 486 488 1362 488 487 1363 487 485 1364 485 490 1365 490 487 1366 487 488 1367 488 490 1368 490 489 1369 489 487 1370 487 492 1371 492 489 1372 489 490 1373 490 492 1374 492 491 1375 491 489 1376 489 494 1377 494 491 1378 491 492 1379 492 494 1380 494 493 1381 493 491 1382 491 496 1383 496 493 1384 493 494 1385 494 496 1386 496 495 1387 495 493 1388 493 498 1389 498 495 1390 495 496 1391 496 498 1392 498 497 1393 497 495 1394 495 500 1395 500 497 1396 497 498 1397 498 500 1398 500 499 1399 499 497 1400 497 502 1401 502 499 1402 499 500 1403 500 502 1404 502 501 1405 501 499 1406 499 504 1407 504 501 1408 501 502 1409 502 504 1410 504 503 1411 503 501 1412 501 506 1413 506 503 1414 503 504 1415 504 506 1416 506 505 1417 505 503 1418 503 508 1419 508 505 1420 505 506 1421 506 508 1422 508 507 1423 507 505 1424 505 510 1425 510 507 1426 507 508 1427 508 510 1428 510 509 1429 509 507 1430 507 512 1431 512 509 1432 509 510 1433 510 512 1434 512 511 1435 511 509 1436 509 514 1437 514 511 1438 511 512 1439 512 514 1440 514 513 1441 513 511 1442 511 481 1443 481 513 1444 513 514 1445 514

+
+
+ + + + +1.200000 0.000000 11.500000 +1.400000 0.000000 11.300000 +-1.376628 0.254748 11.300000 +-1.400000 0.000000 11.300000 +-1.200000 0.000000 11.500000 +-1.179966 0.218356 11.500000 +-1.301704 0.515333 11.300000 +-1.115746 0.441714 11.500000 +-1.171794 0.766094 11.300000 +-1.004395 0.656652 11.500000 +-0.989949 0.989949 11.300000 +-0.848528 0.848528 11.500000 +-0.766094 1.171794 11.300000 +-0.656652 1.004395 11.500000 +-0.515333 1.301704 11.300000 +-0.441714 1.115746 11.500000 +-0.254748 1.376628 11.300000 +-0.218356 1.179966 11.500000 +0.000000 1.400000 11.300000 +0.000000 1.200000 11.500000 +0.254748 1.376628 11.300000 +0.218356 1.179966 11.500000 +0.515333 1.301704 11.300000 +0.441714 1.115746 11.500000 +0.766094 1.171794 11.300000 +0.656652 1.004395 11.500000 +0.989949 0.989949 11.300000 +0.848528 0.848528 11.500000 +1.171794 0.766094 11.300000 +1.004395 0.656652 11.500000 +1.301704 0.515333 11.300000 +1.115746 0.441714 11.500000 +1.376628 0.254748 11.300000 +1.179966 0.218356 11.500000 +-1.798022 0.084358 0.000000 +-1.392264 1.435827 0.200000 +-1.322876 1.500000 0.200000 +-1.244990 1.300000 0.000000 +-1.642927 1.140523 0.200000 +-1.253038 1.292244 0.000000 +-1.823032 0.822530 0.200000 +-1.478634 1.026470 0.000000 +-1.640719 0.740298 0.000000 +-1.942267 0.477074 0.200000 +-1.748040 0.429367 0.000000 +-1.997802 0.093731 0.200000 +-1.800000 0.000000 0.000000 +-2.000000 0.000000 0.200000 +-2.000000 0.000000 0.200000 +-1.800000 0.000000 0.000000 +1.800000 0.000000 0.000000 +2.000000 0.000000 0.200000 +1.769950 -0.327533 0.000000 +1.966611 -0.363926 0.200000 +1.673619 -0.662570 0.000000 +1.859577 -0.736189 0.200000 +1.506592 -0.984978 0.000000 +1.673991 -1.094419 0.200000 +1.272792 -1.272792 0.000000 +1.414214 -1.414214 0.200000 +0.984978 -1.506592 0.000000 +1.094419 -1.673991 0.200000 +0.662570 -1.673619 0.000000 +0.736189 -1.859577 0.200000 +0.327533 -1.769950 0.000000 +0.363926 -1.966611 0.200000 +0.000000 -1.800000 0.000000 +0.000000 -2.000000 0.200000 +-0.327533 -1.769950 0.000000 +-0.363926 -1.966611 0.200000 +-0.662570 -1.673619 0.000000 +-0.736189 -1.859577 0.200000 +-0.984978 -1.506592 0.000000 +-1.094419 -1.673991 0.200000 +-1.272792 -1.272792 0.000000 +-1.414214 -1.414214 0.200000 +-1.506592 -0.984978 0.000000 +-1.673619 -0.662570 0.000000 +-1.673991 -1.094419 0.200000 +-1.859577 -0.736189 0.200000 +-1.769950 -0.327533 0.000000 +-1.966611 -0.363926 0.200000 +1.997785 0.094109 3.500000 +2.000000 0.000000 3.500000 +1.391992 1.436091 0.200000 +1.322876 1.500000 0.200000 +1.322876 1.500000 3.500000 +1.391992 1.436091 3.500000 +1.642710 1.140834 0.200000 +1.642710 1.140834 3.500000 +1.822876 0.822876 0.200000 +1.942176 0.477442 0.200000 +1.822876 0.822876 3.500000 +1.997785 0.094109 0.200000 +1.942176 0.477442 3.500000 +2.000000 0.000000 0.200000 +2.000000 0.000000 0.200000 +2.000000 0.000000 3.500000 +-2.000000 0.000000 3.500000 +-2.000000 0.000000 0.200000 +-1.966611 -0.363926 3.500000 +-1.966611 -0.363926 0.200000 +-1.859577 -0.736189 3.500000 +-1.859577 -0.736189 0.200000 +-1.673991 -1.094419 3.500000 +-1.673991 -1.094419 0.200000 +-1.414214 -1.414214 3.500000 +-1.414214 -1.414214 0.200000 +-1.094419 -1.673991 3.500000 +-1.094419 -1.673991 0.200000 +-0.736189 -1.859577 3.500000 +-0.736189 -1.859577 0.200000 +-0.363926 -1.966611 3.500000 +-0.363926 -1.966611 0.200000 +0.000000 -2.000000 3.500000 +0.000000 -2.000000 0.200000 +0.363926 -1.966611 3.500000 +0.363926 -1.966611 0.200000 +0.736189 -1.859577 3.500000 +0.736189 -1.859577 0.200000 +1.094419 -1.673991 3.500000 +1.094419 -1.673991 0.200000 +1.414214 -1.414214 3.500000 +1.414214 -1.414214 0.200000 +1.673991 -1.094419 3.500000 +1.673991 -1.094419 0.200000 +1.859577 -0.736189 3.500000 +1.859577 -0.736189 0.200000 +1.966611 -0.363926 3.500000 +1.966611 -0.363926 0.200000 +-1.400000 0.000000 6.500000 +-1.400000 0.000000 11.300000 +1.400000 0.000000 11.300000 +1.400000 0.000000 6.500000 +1.376628 0.254748 11.300000 +1.376628 0.254748 6.500000 +1.301704 0.515333 11.300000 +1.301704 0.515333 6.500000 +1.171794 0.766094 11.300000 +1.171794 0.766094 6.500000 +0.989949 0.989949 11.300000 +0.989949 0.989949 6.500000 +0.766094 1.171794 11.300000 +0.515333 1.301704 11.300000 +0.766094 1.171794 6.500000 +0.515333 1.301704 6.500000 +0.254748 1.376628 11.300000 +0.254748 1.376628 6.500000 +0.000000 1.400000 11.300000 +0.000000 1.400000 6.500000 +-0.254748 1.376628 11.300000 +-0.254748 1.376628 6.500000 +-0.515333 1.301704 11.300000 +-0.515333 1.301704 6.500000 +-0.766094 1.171794 11.300000 +-0.766094 1.171794 6.500000 +-0.989949 0.989949 11.300000 +-0.989949 0.989949 6.500000 +-1.171794 0.766094 11.300000 +-1.171794 0.766094 6.500000 +-1.301704 0.515333 11.300000 +-1.301704 0.515333 6.500000 +-1.376628 0.254748 11.300000 +-1.376628 0.254748 6.500000 +-0.820815 1.255493 6.500000 +-1.474958 0.272945 3.500000 +-1.500000 0.000000 3.500000 +-1.500000 0.000000 6.500000 +-1.474958 0.272945 6.500000 +-1.394682 0.552142 3.500000 +-1.394682 0.552142 6.500000 +-1.255493 0.820815 3.500000 +-1.255493 0.820815 6.500000 +-1.060660 1.060660 3.500000 +-1.060660 1.060660 6.500000 +-0.820815 1.255493 3.500000 +1.474958 0.272945 6.500000 +1.500000 0.000000 6.500000 +1.500000 0.000000 3.500000 +1.474958 0.272945 3.500000 +1.394682 0.552142 6.500000 +1.394682 0.552142 3.500000 +1.255493 0.820815 6.500000 +1.255493 0.820815 3.500000 +1.060660 1.060660 6.500000 +1.060660 1.060660 3.500000 +0.820815 1.255493 6.500000 +0.552142 1.394682 6.500000 +0.820815 1.255493 3.500000 +0.272945 1.474958 6.500000 +0.552142 1.394682 3.500000 +0.000000 1.500000 6.500000 +0.272945 1.474958 3.500000 +0.000000 1.500000 3.500000 +-0.272945 1.474958 6.500000 +-0.272945 1.474958 3.500000 +-0.552142 1.394682 6.500000 +-0.552142 1.394682 3.500000 +1.500000 0.000000 3.500000 +1.500000 0.000000 6.500000 +-1.500000 0.000000 6.500000 +-1.500000 0.000000 3.500000 +-1.474958 -0.272945 6.500000 +-1.474958 -0.272945 3.500000 +-1.394682 -0.552142 6.500000 +-1.394682 -0.552142 3.500000 +-1.255493 -0.820815 6.500000 +-1.255493 -0.820815 3.500000 +-1.060660 -1.060660 6.500000 +-1.060660 -1.060660 3.500000 +-0.820815 -1.255493 6.500000 +-0.820815 -1.255493 3.500000 +-0.552142 -1.394682 6.500000 +-0.552142 -1.394682 3.500000 +-0.272945 -1.474958 6.500000 +-0.272945 -1.474958 3.500000 +0.000000 -1.500000 6.500000 +0.000000 -1.500000 3.500000 +0.272945 -1.474958 6.500000 +0.272945 -1.474958 3.500000 +0.552142 -1.394682 6.500000 +0.552142 -1.394682 3.500000 +0.820815 -1.255493 6.500000 +0.820815 -1.255493 3.500000 +1.060660 -1.060660 6.500000 +1.060660 -1.060660 3.500000 +1.255493 -0.820815 6.500000 +1.255493 -0.820815 3.500000 +1.394682 -0.552142 6.500000 +1.394682 -0.552142 3.500000 +1.474958 -0.272945 6.500000 +1.474958 -0.272945 3.500000 +0.254748 1.376628 6.500000 +0.820815 1.255493 6.500000 +0.515333 1.301704 6.500000 +1.060660 1.060660 6.500000 +0.766094 1.171794 6.500000 +1.255493 0.820815 6.500000 +0.989949 0.989949 6.500000 +1.394682 0.552142 6.500000 +1.171794 0.766094 6.500000 +1.474958 0.272945 6.500000 +1.301704 0.515333 6.500000 +1.500000 0.000000 6.500000 +1.376628 0.254748 6.500000 +1.474958 -0.272945 6.500000 +1.400000 0.000000 6.500000 +1.394682 -0.552142 6.500000 +1.376628 -0.254748 6.500000 +1.255493 -0.820815 6.500000 +1.301704 -0.515333 6.500000 +1.060660 -1.060660 6.500000 +1.171794 -0.766094 6.500000 +0.820815 -1.255493 6.500000 +0.989949 -0.989949 6.500000 +0.552142 -1.394682 6.500000 +0.766094 -1.171794 6.500000 +0.272945 -1.474958 6.500000 +0.515333 -1.301704 6.500000 +0.000000 -1.500000 6.500000 +0.254748 -1.376628 6.500000 +-0.272945 -1.474958 6.500000 +0.000000 -1.400000 6.500000 +-0.552142 -1.394682 6.500000 +-0.254748 -1.376628 6.500000 +-0.820815 -1.255493 6.500000 +-0.515333 -1.301704 6.500000 +-1.060660 -1.060660 6.500000 +-0.766094 -1.171794 6.500000 +-1.255493 -0.820815 6.500000 +-0.989949 -0.989949 6.500000 +-1.394682 -0.552142 6.500000 +-1.171794 -0.766094 6.500000 +-1.474958 -0.272945 6.500000 +-1.301704 -0.515333 6.500000 +-1.500000 0.000000 6.500000 +-1.376628 -0.254748 6.500000 +-1.474958 0.272945 6.500000 +-1.400000 0.000000 6.500000 +-1.394682 0.552142 6.500000 +-1.376628 0.254748 6.500000 +-1.255493 0.820815 6.500000 +-1.301704 0.515333 6.500000 +-1.060660 1.060660 6.500000 +-1.171794 0.766094 6.500000 +-0.820815 1.255493 6.500000 +-0.989949 0.989949 6.500000 +-0.552142 1.394682 6.500000 +-0.766094 1.171794 6.500000 +-0.272945 1.474958 6.500000 +-0.515333 1.301704 6.500000 +0.000000 1.500000 6.500000 +-0.254748 1.376628 6.500000 +0.272945 1.474958 6.500000 +0.000000 1.400000 6.500000 +0.552142 1.394682 6.500000 +-1.400000 0.000000 11.300000 +-1.400000 0.000000 6.500000 +1.400000 0.000000 6.500000 +1.400000 0.000000 11.300000 +1.376628 -0.254748 6.500000 +1.376628 -0.254748 11.300000 +1.301704 -0.515333 6.500000 +1.301704 -0.515333 11.300000 +1.171794 -0.766094 6.500000 +1.171794 -0.766094 11.300000 +0.989949 -0.989949 6.500000 +0.989949 -0.989949 11.300000 +0.766094 -1.171794 6.500000 +0.766094 -1.171794 11.300000 +0.515333 -1.301704 6.500000 +0.515333 -1.301704 11.300000 +0.254748 -1.376628 6.500000 +0.254748 -1.376628 11.300000 +0.000000 -1.400000 6.500000 +0.000000 -1.400000 11.300000 +-0.254748 -1.376628 6.500000 +-0.254748 -1.376628 11.300000 +-0.515333 -1.301704 6.500000 +-0.515333 -1.301704 11.300000 +-0.766094 -1.171794 6.500000 +-0.766094 -1.171794 11.300000 +-0.989949 -0.989949 6.500000 +-0.989949 -0.989949 11.300000 +-1.171794 -0.766094 6.500000 +-1.171794 -0.766094 11.300000 +-1.301704 -0.515333 6.500000 +-1.301704 -0.515333 11.300000 +-1.376628 -0.254748 6.500000 +-1.376628 -0.254748 11.300000 +0.000000 1.200000 11.500000 +-0.218356 1.179966 11.500000 +-1.004395 0.656652 11.500000 +-1.115746 0.441714 11.500000 +-0.848528 0.848528 11.500000 +-0.656652 1.004395 11.500000 +-1.179966 0.218356 11.500000 +-0.441714 1.115746 11.500000 +-1.200000 0.000000 11.500000 +-1.179966 -0.218356 11.500000 +-1.115746 -0.441714 11.500000 +-1.004395 -0.656652 11.500000 +-0.848528 -0.848528 11.500000 +-0.656652 -1.004395 11.500000 +-0.441714 -1.115746 11.500000 +-0.218356 -1.179966 11.500000 +0.000000 -1.200000 11.500000 +0.218356 -1.179966 11.500000 +0.441714 -1.115746 11.500000 +0.656652 -1.004395 11.500000 +0.848528 -0.848528 11.500000 +1.004395 -0.656652 11.500000 +1.115746 -0.441714 11.500000 +1.179966 -0.218356 11.500000 +1.200000 0.000000 11.500000 +1.179966 0.218356 11.500000 +1.115746 0.441714 11.500000 +1.004395 0.656652 11.500000 +0.848528 0.848528 11.500000 +0.656652 1.004395 11.500000 +0.441714 1.115746 11.500000 +0.218356 1.179966 11.500000 +-1.474958 -0.272945 3.500000 +-0.272945 1.474958 3.500000 +0.000000 1.500000 3.500000 +1.322876 1.500000 3.500000 +0.272945 1.474958 3.500000 +-0.552142 1.394682 3.500000 +-0.820815 1.255493 3.500000 +0.552142 1.394682 3.500000 +0.820815 1.255493 3.500000 +-1.060660 1.060660 3.500000 +-1.322876 1.500000 3.500000 +-1.255493 0.820815 3.500000 +-1.606034 1.191913 3.500000 +-1.394682 0.552142 3.500000 +1.606034 1.191913 3.500000 +1.060660 1.060660 3.500000 +1.822876 0.822876 3.500000 +1.255493 0.820815 3.500000 +1.956226 0.416149 3.500000 +1.394682 0.552142 3.500000 +-1.822876 0.822876 3.500000 +-1.474958 0.272945 3.500000 +-1.956226 0.416149 3.500000 +-1.500000 0.000000 3.500000 +2.000000 0.000000 3.500000 +1.474958 0.272945 3.500000 +1.966611 -0.363926 3.500000 +1.500000 0.000000 3.500000 +1.859577 -0.736189 3.500000 +1.474958 -0.272945 3.500000 +1.673991 -1.094419 3.500000 +1.394682 -0.552142 3.500000 +1.414214 -1.414214 3.500000 +1.255493 -0.820815 3.500000 +1.094419 -1.673991 3.500000 +1.060660 -1.060660 3.500000 +0.736189 -1.859577 3.500000 +0.820815 -1.255493 3.500000 +0.363926 -1.966611 3.500000 +0.552142 -1.394682 3.500000 +0.000000 -2.000000 3.500000 +0.272945 -1.474958 3.500000 +-0.363926 -1.966611 3.500000 +0.000000 -1.500000 3.500000 +-0.736189 -1.859577 3.500000 +-0.272945 -1.474958 3.500000 +-1.094419 -1.673991 3.500000 +-0.552142 -1.394682 3.500000 +-1.414214 -1.414214 3.500000 +-0.820815 -1.255493 3.500000 +-1.673991 -1.094419 3.500000 +-1.060660 -1.060660 3.500000 +-1.859577 -0.736189 3.500000 +-1.255493 -0.820815 3.500000 +-1.966611 -0.363926 3.500000 +-1.394682 -0.552142 3.500000 +-2.000000 0.000000 3.500000 +-1.322876 1.500000 3.500000 +-1.322876 1.500000 0.200000 +-2.000000 0.000000 0.200000 +-2.000000 0.000000 3.500000 +-1.997785 0.094109 0.200000 +-1.942176 0.477442 0.200000 +-1.997785 0.094109 3.500000 +-1.942176 0.477442 3.500000 +-1.822876 0.822876 0.200000 +-1.642710 1.140834 0.200000 +-1.822876 0.822876 3.500000 +-1.642710 1.140834 3.500000 +-1.391992 1.436091 0.200000 +-1.391992 1.436091 3.500000 +-1.769950 -0.327533 0.000000 +-1.800000 0.000000 0.000000 +-1.244990 1.300000 0.000000 +1.244990 1.300000 0.000000 +1.478113 1.027221 0.000000 +1.655443 0.706760 0.000000 +1.764235 0.357037 0.000000 +1.800000 0.000000 0.000000 +1.769950 -0.327533 0.000000 +1.673619 -0.662570 0.000000 +1.506592 -0.984978 0.000000 +1.272792 -1.272792 0.000000 +0.984978 -1.506592 0.000000 +0.662570 -1.673619 0.000000 +-1.478113 1.027221 0.000000 +-1.655443 0.706760 0.000000 +-1.764235 0.357037 0.000000 +0.327533 -1.769950 0.000000 +0.000000 -1.800000 0.000000 +-0.327533 -1.769950 0.000000 +-0.662570 -1.673619 0.000000 +-0.984978 -1.506592 0.000000 +-1.272792 -1.272792 0.000000 +-1.506592 -0.984978 0.000000 +-1.673619 -0.662570 0.000000 +-1.322876 1.500000 0.200000 +-1.322876 1.500000 3.500000 +1.322876 1.500000 3.500000 +1.322876 1.500000 0.200000 +0.000000 1.500000 3.500000 +2.000000 0.000000 0.200000 +1.800000 0.000000 0.000000 +1.244990 1.300000 0.000000 +1.322876 1.500000 0.200000 +1.253038 1.292244 0.000000 +1.392264 1.435827 0.200000 +1.478634 1.026470 0.000000 +1.640719 0.740298 0.000000 +1.642927 1.140523 0.200000 +1.748040 0.429367 0.000000 +1.823032 0.822530 0.200000 +1.798022 0.084358 0.000000 +1.942267 0.477074 0.200000 +1.997802 0.093731 0.200000 +-1.322876 1.500000 0.200000 +1.322876 1.500000 0.200000 +1.244990 1.300000 0.000000 +-1.244990 1.300000 0.000000 +1.400000 0.000000 11.300000 +1.200000 0.000000 11.500000 +-1.200000 0.000000 11.500000 +-1.400000 0.000000 11.300000 +-1.179966 -0.218356 11.500000 +-1.376628 -0.254748 11.300000 +-1.115746 -0.441714 11.500000 +-1.301704 -0.515333 11.300000 +-1.004395 -0.656652 11.500000 +-1.171794 -0.766094 11.300000 +-0.848528 -0.848528 11.500000 +-0.989949 -0.989949 11.300000 +-0.656652 -1.004395 11.500000 +-0.766094 -1.171794 11.300000 +-0.441714 -1.115746 11.500000 +-0.515333 -1.301704 11.300000 +-0.218356 -1.179966 11.500000 +-0.254748 -1.376628 11.300000 +0.000000 -1.200000 11.500000 +0.000000 -1.400000 11.300000 +0.218356 -1.179966 11.500000 +0.254748 -1.376628 11.300000 +0.441714 -1.115746 11.500000 +0.515333 -1.301704 11.300000 +0.656652 -1.004395 11.500000 +0.766094 -1.171794 11.300000 +0.848528 -0.848528 11.500000 +0.989949 -0.989949 11.300000 +1.004395 -0.656652 11.500000 +1.171794 -0.766094 11.300000 +1.115746 -0.441714 11.500000 +1.301704 -0.515333 11.300000 +1.179966 -0.218356 11.500000 +1.376628 -0.254748 11.300000 +0.000000 1.500000 3.500000 + + + + + + + + + + + +0.695302 0.128667 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.695302 0.128667 0.707107 +-0.707107 0.000000 0.707107 +-0.695302 0.128667 0.707107 +-0.695302 0.128667 0.707107 +-0.707107 0.000000 0.707107 +-0.657460 0.260282 0.707107 +-0.695302 0.128667 0.707107 +-0.695302 0.128667 0.707107 +-0.657460 0.260282 0.707107 +-0.657460 0.260282 0.707107 +-0.695302 0.128667 0.707107 +-0.591845 0.386936 0.707107 +-0.657460 0.260282 0.707107 +-0.657460 0.260282 0.707107 +-0.591845 0.386936 0.707107 +-0.591845 0.386936 0.707107 +-0.657460 0.260282 0.707107 +-0.500000 0.500000 0.707107 +-0.591845 0.386936 0.707107 +-0.591845 0.386936 0.707107 +-0.500000 0.500000 0.707107 +-0.500000 0.500000 0.707107 +-0.591845 0.386936 0.707107 +-0.386936 0.591845 0.707107 +-0.500000 0.500000 0.707107 +-0.500000 0.500000 0.707107 +-0.386936 0.591845 0.707107 +-0.386936 0.591845 0.707107 +-0.500000 0.500000 0.707107 +-0.260282 0.657460 0.707107 +-0.386936 0.591845 0.707107 +-0.386936 0.591845 0.707107 +-0.260282 0.657460 0.707107 +-0.260282 0.657460 0.707107 +-0.386936 0.591845 0.707107 +-0.128667 0.695302 0.707107 +-0.260282 0.657460 0.707107 +-0.260282 0.657460 0.707107 +-0.128667 0.695302 0.707107 +-0.128667 0.695302 0.707107 +-0.260282 0.657460 0.707107 +0.000000 0.707107 0.707107 +-0.128667 0.695302 0.707107 +-0.128667 0.695302 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +-0.128667 0.695302 0.707107 +0.128667 0.695302 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.128667 0.695302 0.707107 +0.128667 0.695302 0.707107 +0.000000 0.707107 0.707107 +0.260282 0.657460 0.707107 +0.128667 0.695302 0.707107 +0.128667 0.695302 0.707107 +0.260282 0.657460 0.707107 +0.260282 0.657460 0.707107 +0.128667 0.695302 0.707107 +0.386936 0.591845 0.707107 +0.260282 0.657460 0.707107 +0.260282 0.657460 0.707107 +0.386936 0.591845 0.707107 +0.386936 0.591845 0.707107 +0.260282 0.657460 0.707107 +0.500000 0.500000 0.707107 +0.386936 0.591845 0.707107 +0.386936 0.591845 0.707107 +0.500000 0.500000 0.707107 +0.500000 0.500000 0.707107 +0.386936 0.591845 0.707107 +0.591845 0.386936 0.707107 +0.500000 0.500000 0.707107 +0.500000 0.500000 0.707107 +0.591845 0.386936 0.707107 +0.591845 0.386936 0.707107 +0.500000 0.500000 0.707107 +0.657460 0.260282 0.707107 +0.591845 0.386936 0.707107 +0.591845 0.386936 0.707107 +0.657460 0.260282 0.707107 +0.657460 0.260282 0.707107 +0.591845 0.386936 0.707107 +0.695302 0.128667 0.707107 +0.657460 0.260282 0.707107 +0.657460 0.260282 0.707107 +0.695302 0.128667 0.707107 +0.695302 0.128667 0.707107 +0.657460 0.260282 0.707107 +0.707107 0.000000 0.707107 +0.695302 0.128667 0.707107 +0.695302 0.128667 0.707107 +-0.707107 0.000000 -0.707107 +-0.706330 0.033139 -0.707107 +-0.706330 0.033139 -0.707107 +-0.489078 0.510688 -0.707107 +-0.492240 0.507642 -0.707107 +-0.467707 0.530330 -0.707107 +-0.492240 0.507642 -0.707107 +-0.492240 0.507642 -0.707107 +-0.489078 0.510688 -0.707107 +-0.492240 0.507642 -0.707107 +-0.580862 0.403236 -0.707107 +-0.492240 0.507642 -0.707107 +-0.580862 0.403236 -0.707107 +-0.580862 0.403236 -0.707107 +-0.492240 0.507642 -0.707107 +-0.580862 0.403236 -0.707107 +-0.644539 0.290808 -0.707107 +-0.580862 0.403236 -0.707107 +-0.644539 0.290808 -0.707107 +-0.644539 0.290808 -0.707107 +-0.580862 0.403236 -0.707107 +-0.686695 0.168671 -0.707107 +-0.644539 0.290808 -0.707107 +-0.644539 0.290808 -0.707107 +-0.686695 0.168671 -0.707107 +-0.686695 0.168671 -0.707107 +-0.644539 0.290808 -0.707107 +-0.706330 0.033139 -0.707107 +-0.686695 0.168671 -0.707107 +-0.686695 0.168671 -0.707107 +-0.706330 0.033139 -0.707107 +-0.706330 0.033139 -0.707107 +-0.686695 0.168671 -0.707107 +-0.706330 0.033139 -0.707107 +-0.707107 0.000000 -0.707107 +-0.707107 0.000000 -0.707107 +-0.695302 -0.128667 -0.707107 +-0.707107 0.000000 -0.707107 +-0.707107 0.000000 -0.707107 +0.695302 -0.128667 -0.707107 +0.707107 0.000000 -0.707107 +0.707107 0.000000 -0.707107 +0.695302 -0.128667 -0.707107 +0.695302 -0.128667 -0.707107 +0.707107 0.000000 -0.707107 +0.657460 -0.260282 -0.707107 +0.695302 -0.128667 -0.707107 +0.695302 -0.128667 -0.707107 +0.657460 -0.260282 -0.707107 +0.657460 -0.260282 -0.707107 +0.695302 -0.128667 -0.707107 +0.591845 -0.386936 -0.707107 +0.657460 -0.260282 -0.707107 +0.657460 -0.260282 -0.707107 +0.591845 -0.386936 -0.707107 +0.591845 -0.386936 -0.707107 +0.657460 -0.260282 -0.707107 +0.500000 -0.500000 -0.707107 +0.591845 -0.386936 -0.707107 +0.591845 -0.386936 -0.707107 +0.500000 -0.500000 -0.707107 +0.500000 -0.500000 -0.707107 +0.591845 -0.386936 -0.707107 +0.386936 -0.591845 -0.707107 +0.500000 -0.500000 -0.707107 +0.500000 -0.500000 -0.707107 +0.386936 -0.591845 -0.707107 +0.386936 -0.591845 -0.707107 +0.500000 -0.500000 -0.707107 +0.260282 -0.657460 -0.707107 +0.386936 -0.591845 -0.707107 +0.386936 -0.591845 -0.707107 +0.260282 -0.657460 -0.707107 +0.260282 -0.657460 -0.707107 +0.386936 -0.591845 -0.707107 +0.128667 -0.695302 -0.707107 +0.260282 -0.657460 -0.707107 +0.260282 -0.657460 -0.707107 +0.128667 -0.695302 -0.707107 +0.128667 -0.695302 -0.707107 +0.260282 -0.657460 -0.707107 +0.000000 -0.707107 -0.707107 +0.128667 -0.695302 -0.707107 +0.128667 -0.695302 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.128667 -0.695302 -0.707107 +-0.128667 -0.695302 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +-0.128667 -0.695302 -0.707107 +-0.128667 -0.695302 -0.707107 +0.000000 -0.707107 -0.707107 +-0.260282 -0.657460 -0.707107 +-0.128667 -0.695302 -0.707107 +-0.128667 -0.695302 -0.707107 +-0.260282 -0.657460 -0.707107 +-0.260282 -0.657460 -0.707107 +-0.128667 -0.695302 -0.707107 +-0.386936 -0.591845 -0.707107 +-0.260282 -0.657460 -0.707107 +-0.260282 -0.657460 -0.707107 +-0.386936 -0.591845 -0.707107 +-0.386936 -0.591845 -0.707107 +-0.260282 -0.657460 -0.707107 +-0.500000 -0.500000 -0.707107 +-0.386936 -0.591845 -0.707107 +-0.386936 -0.591845 -0.707107 +-0.500000 -0.500000 -0.707107 +-0.500000 -0.500000 -0.707107 +-0.386936 -0.591845 -0.707107 +-0.591845 -0.386936 -0.707107 +-0.500000 -0.500000 -0.707107 +-0.500000 -0.500000 -0.707107 +-0.591845 -0.386936 -0.707107 +-0.591845 -0.386936 -0.707107 +-0.500000 -0.500000 -0.707107 +-0.591845 -0.386936 -0.707107 +-0.657460 -0.260282 -0.707107 +-0.591845 -0.386936 -0.707107 +-0.657460 -0.260282 -0.707107 +-0.657460 -0.260282 -0.707107 +-0.591845 -0.386936 -0.707107 +-0.695302 -0.128667 -0.707107 +-0.657460 -0.260282 -0.707107 +-0.657460 -0.260282 -0.707107 +-0.695302 -0.128667 -0.707107 +-0.695302 -0.128667 -0.707107 +-0.657460 -0.260282 -0.707107 +-0.707107 0.000000 -0.707107 +-0.695302 -0.128667 -0.707107 +-0.695302 -0.128667 -0.707107 +1.000000 0.000000 0.000000 +0.998892 0.047055 0.000000 +1.000000 0.000000 0.000000 +0.661438 0.750000 0.000000 +0.695996 0.718046 0.000000 +0.661438 0.750000 0.000000 +0.695996 0.718046 0.000000 +0.695996 0.718046 0.000000 +0.661438 0.750000 0.000000 +0.821355 0.570417 0.000000 +0.695996 0.718046 0.000000 +0.695996 0.718046 0.000000 +0.821355 0.570417 0.000000 +0.821355 0.570417 0.000000 +0.695996 0.718046 0.000000 +0.911438 0.411438 0.000000 +0.821355 0.570417 0.000000 +0.821355 0.570417 0.000000 +0.911438 0.411438 0.000000 +0.911438 0.411438 0.000000 +0.821355 0.570417 0.000000 +0.911438 0.411438 0.000000 +0.971088 0.238721 0.000000 +0.911438 0.411438 0.000000 +0.971088 0.238721 0.000000 +0.971088 0.238721 0.000000 +0.911438 0.411438 0.000000 +0.971088 0.238721 0.000000 +0.998892 0.047055 0.000000 +0.971088 0.238721 0.000000 +0.998892 0.047055 0.000000 +0.998892 0.047055 0.000000 +0.971088 0.238721 0.000000 +0.998892 0.047055 0.000000 +1.000000 0.000000 0.000000 +0.998892 0.047055 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.695996 0.718046 0.000000 +-0.661438 0.750000 0.000000 +-0.661438 0.750000 0.000000 +-0.998892 0.047055 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.998892 0.047055 0.000000 +-0.998892 0.047055 0.000000 +-1.000000 0.000000 0.000000 +-0.998892 0.047055 0.000000 +-0.971088 0.238721 0.000000 +-0.998892 0.047055 0.000000 +-0.971088 0.238721 0.000000 +-0.971088 0.238721 0.000000 +-0.998892 0.047055 0.000000 +-0.911438 0.411438 0.000000 +-0.971088 0.238721 0.000000 +-0.971088 0.238721 0.000000 +-0.911438 0.411438 0.000000 +-0.911438 0.411438 0.000000 +-0.971088 0.238721 0.000000 +-0.911438 0.411438 0.000000 +-0.821355 0.570417 0.000000 +-0.911438 0.411438 0.000000 +-0.821355 0.570417 0.000000 +-0.821355 0.570417 0.000000 +-0.911438 0.411438 0.000000 +-0.695996 0.718046 0.000000 +-0.821355 0.570417 0.000000 +-0.821355 0.570417 0.000000 +-0.695996 0.718046 0.000000 +-0.695996 0.718046 0.000000 +-0.821355 0.570417 0.000000 +-0.661438 0.750000 0.000000 +-0.695996 0.718046 0.000000 +-0.695996 0.718046 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.706330 0.033139 -0.707107 +0.707107 0.000000 -0.707107 +0.707107 0.000000 -0.707107 +0.492240 0.507642 -0.707107 +0.489078 0.510688 -0.707107 +0.467707 0.530330 -0.707107 +0.492240 0.507642 -0.707107 +0.492240 0.507642 -0.707107 +0.489078 0.510688 -0.707107 +0.580862 0.403236 -0.707107 +0.492240 0.507642 -0.707107 +0.492240 0.507642 -0.707107 +0.580862 0.403236 -0.707107 +0.580862 0.403236 -0.707107 +0.492240 0.507642 -0.707107 +0.580862 0.403236 -0.707107 +0.644539 0.290808 -0.707107 +0.580862 0.403236 -0.707107 +0.644539 0.290808 -0.707107 +0.644539 0.290808 -0.707107 +0.580862 0.403236 -0.707107 +0.644539 0.290808 -0.707107 +0.686695 0.168671 -0.707107 +0.644539 0.290808 -0.707107 +0.686695 0.168671 -0.707107 +0.686695 0.168671 -0.707107 +0.644539 0.290808 -0.707107 +0.686695 0.168671 -0.707107 +0.706330 0.033139 -0.707107 +0.686695 0.168671 -0.707107 +0.706330 0.033139 -0.707107 +0.706330 0.033139 -0.707107 +0.686695 0.168671 -0.707107 +0.707107 0.000000 -0.707107 +0.706330 0.033139 -0.707107 +0.706330 0.033139 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 +0.695302 -0.128667 0.707107 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +-0.695302 -0.128667 0.707107 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.695302 -0.128667 0.707107 +-0.695302 -0.128667 0.707107 +-0.707107 0.000000 0.707107 +-0.657460 -0.260282 0.707107 +-0.695302 -0.128667 0.707107 +-0.695302 -0.128667 0.707107 +-0.657460 -0.260282 0.707107 +-0.657460 -0.260282 0.707107 +-0.695302 -0.128667 0.707107 +-0.591845 -0.386936 0.707107 +-0.657460 -0.260282 0.707107 +-0.657460 -0.260282 0.707107 +-0.591845 -0.386936 0.707107 +-0.591845 -0.386936 0.707107 +-0.657460 -0.260282 0.707107 +-0.500000 -0.500000 0.707107 +-0.591845 -0.386936 0.707107 +-0.591845 -0.386936 0.707107 +-0.500000 -0.500000 0.707107 +-0.500000 -0.500000 0.707107 +-0.591845 -0.386936 0.707107 +-0.386936 -0.591845 0.707107 +-0.500000 -0.500000 0.707107 +-0.500000 -0.500000 0.707107 +-0.386936 -0.591845 0.707107 +-0.386936 -0.591845 0.707107 +-0.500000 -0.500000 0.707107 +-0.260282 -0.657460 0.707107 +-0.386936 -0.591845 0.707107 +-0.386936 -0.591845 0.707107 +-0.260282 -0.657460 0.707107 +-0.260282 -0.657460 0.707107 +-0.386936 -0.591845 0.707107 +-0.128667 -0.695302 0.707107 +-0.260282 -0.657460 0.707107 +-0.260282 -0.657460 0.707107 +-0.128667 -0.695302 0.707107 +-0.128667 -0.695302 0.707107 +-0.260282 -0.657460 0.707107 +0.000000 -0.707107 0.707107 +-0.128667 -0.695302 0.707107 +-0.128667 -0.695302 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +-0.128667 -0.695302 0.707107 +0.128667 -0.695302 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.128667 -0.695302 0.707107 +0.128667 -0.695302 0.707107 +0.000000 -0.707107 0.707107 +0.260282 -0.657460 0.707107 +0.128667 -0.695302 0.707107 +0.128667 -0.695302 0.707107 +0.260282 -0.657460 0.707107 +0.260282 -0.657460 0.707107 +0.128667 -0.695302 0.707107 +0.386936 -0.591845 0.707107 +0.260282 -0.657460 0.707107 +0.260282 -0.657460 0.707107 +0.386936 -0.591845 0.707107 +0.386936 -0.591845 0.707107 +0.260282 -0.657460 0.707107 +0.500000 -0.500000 0.707107 +0.386936 -0.591845 0.707107 +0.386936 -0.591845 0.707107 +0.500000 -0.500000 0.707107 +0.500000 -0.500000 0.707107 +0.386936 -0.591845 0.707107 +0.591845 -0.386936 0.707107 +0.500000 -0.500000 0.707107 +0.500000 -0.500000 0.707107 +0.591845 -0.386936 0.707107 +0.591845 -0.386936 0.707107 +0.500000 -0.500000 0.707107 +0.657460 -0.260282 0.707107 +0.591845 -0.386936 0.707107 +0.591845 -0.386936 0.707107 +0.657460 -0.260282 0.707107 +0.657460 -0.260282 0.707107 +0.591845 -0.386936 0.707107 +0.695302 -0.128667 0.707107 +0.657460 -0.260282 0.707107 +0.657460 -0.260282 0.707107 +0.695302 -0.128667 0.707107 +0.695302 -0.128667 0.707107 +0.657460 -0.260282 0.707107 +0.707107 0.000000 0.707107 +0.695302 -0.128667 0.707107 +0.695302 -0.128667 0.707107 + + + + + + + + + + + +1.921761 -0.577681 +1.921761 -0.443726 +0.120110 -0.443726 +0.000000 -0.443726 +0.000000 -0.577681 +0.120110 -0.577681 +0.240220 -0.443726 +0.240220 -0.577681 +0.360330 -0.443726 +0.360330 -0.577681 +0.480440 -0.443726 +0.480440 -0.577681 +0.600550 -0.443726 +0.600550 -0.577681 +0.720660 -0.443726 +0.720660 -0.577681 +0.840770 -0.443726 +0.840770 -0.577681 +0.960880 -0.443726 +0.960880 -0.577681 +1.080990 -0.443726 +1.080990 -0.577681 +1.201101 -0.443726 +1.201101 -0.577681 +1.321211 -0.443726 +1.321211 -0.577681 +1.441321 -0.443726 +1.441321 -0.577681 +1.561431 -0.443726 +1.561431 -0.577681 +1.681541 -0.443726 +1.681541 -0.577681 +1.801651 -0.443726 +1.801651 -0.577681 +2.780885 -0.803730 +2.078703 -0.669775 +2.037121 -0.669775 +2.073217 -0.803730 +2.254248 -0.669775 +2.078703 -0.803730 +2.429794 -0.669775 +2.254248 -0.803730 +2.429794 -0.803730 +2.605339 -0.669775 +2.605339 -0.803730 +2.780885 -0.669775 +2.822134 -0.803730 +2.822134 -0.669775 +2.808728 -0.669775 +2.808728 -0.803730 +5.617455 -0.803730 +5.617455 -0.669775 +5.441909 -0.803730 +5.441909 -0.669775 +5.266364 -0.803730 +5.266364 -0.669775 +5.090818 -0.803730 +5.090818 -0.669775 +4.915273 -0.803730 +4.915273 -0.669775 +4.739727 -0.803730 +4.739727 -0.669775 +4.564182 -0.803730 +4.564182 -0.669775 +4.388637 -0.803730 +4.388637 -0.669775 +4.213091 -0.803730 +4.213091 -0.669775 +4.037546 -0.803730 +4.037546 -0.669775 +3.862000 -0.803730 +3.862000 -0.669775 +3.686455 -0.803730 +3.686455 -0.669775 +3.510909 -0.803730 +3.510909 -0.669775 +3.335364 -0.803730 +3.159818 -0.803730 +3.335364 -0.669775 +3.159818 -0.669775 +2.984273 -0.803730 +2.984273 -0.669775 +2.927069 -0.000000 +2.970664 -0.000000 +2.187930 1.562887 +2.144334 1.562887 +2.144334 -0.000000 +2.187930 -0.000000 +2.372715 1.562887 +2.372715 -0.000000 +2.557499 1.562887 +2.742284 1.562887 +2.557499 -0.000000 +2.927069 1.562887 +2.742284 -0.000000 +2.970664 1.562887 +2.956555 1.562887 +2.956555 -0.000000 +5.913110 -0.000000 +5.913110 1.562887 +5.728326 -0.000000 +5.728326 1.562887 +5.543541 -0.000000 +5.543541 1.562887 +5.358756 -0.000000 +5.358756 1.562887 +5.173972 -0.000000 +5.173972 1.562887 +4.989187 -0.000000 +4.989187 1.562887 +4.804402 -0.000000 +4.804402 1.562887 +4.619617 -0.000000 +4.619617 1.562887 +4.434833 -0.000000 +4.434833 1.562887 +4.250048 -0.000000 +4.250048 1.562887 +4.065263 -0.000000 +4.065263 1.562887 +3.880479 -0.000000 +3.880479 1.562887 +3.695694 -0.000000 +3.695694 1.562887 +3.510909 -0.000000 +3.510909 1.562887 +3.326125 -0.000000 +3.326125 1.562887 +3.141340 -0.000000 +3.141340 1.562887 +2.069589 0.000000 +2.069589 2.273291 +0.000000 2.273291 +0.000000 0.000000 +0.129349 2.273291 +0.129349 0.000000 +0.258699 2.273291 +0.258699 0.000000 +0.388048 2.273291 +0.388048 0.000000 +0.517397 2.273291 +0.517397 0.000000 +0.646746 2.273291 +0.776096 2.273291 +0.646746 0.000000 +0.776096 0.000000 +0.905445 2.273291 +0.905445 0.000000 +1.034794 2.273291 +1.034794 0.000000 +1.164144 2.273291 +1.164144 0.000000 +1.293493 2.273291 +1.293493 0.000000 +1.422842 2.273291 +1.422842 0.000000 +1.552191 2.273291 +1.552191 0.000000 +1.681541 2.273291 +1.681541 0.000000 +1.810890 2.273291 +1.810890 0.000000 +1.940239 2.273291 +1.940239 0.000000 +0.692943 2.368011 +0.138589 3.788818 +0.000000 3.788818 +0.000000 2.368011 +0.138589 2.368011 +0.277177 3.788818 +0.277177 2.368011 +0.415766 3.788818 +0.415766 2.368011 +0.554354 3.788818 +0.554354 2.368011 +0.692943 3.788818 +2.078828 2.368011 +2.217416 2.368011 +2.217416 3.788818 +2.078828 3.788818 +1.940239 2.368011 +1.940239 3.788818 +1.801651 2.368011 +1.801651 3.788818 +1.663062 2.368011 +1.663062 3.788818 +1.524474 2.368011 +1.385885 2.368011 +1.524474 3.788818 +1.247297 2.368011 +1.385885 3.788818 +1.108708 2.368011 +1.247297 3.788818 +1.108708 3.788818 +0.970120 2.368011 +0.970120 3.788818 +0.831531 2.368011 +0.831531 3.788818 +2.217416 3.788818 +2.217416 2.368011 +4.434833 2.368011 +4.434833 3.788818 +4.296244 2.368011 +4.296244 3.788818 +4.157656 2.368011 +4.157656 3.788818 +4.019067 2.368011 +4.019067 3.788818 +3.880479 2.368011 +3.880479 3.788818 +3.741890 2.368011 +3.741890 3.788818 +3.603302 2.368011 +3.603302 3.788818 +3.464713 2.368011 +3.464713 3.788818 +3.326125 2.368011 +3.326125 3.788818 +3.187536 2.368011 +3.187536 3.788818 +3.048948 2.368011 +3.048948 3.788818 +2.910359 2.368011 +2.910359 3.788818 +2.771770 2.368011 +2.771770 3.788818 +2.633182 2.368011 +2.633182 3.788818 +2.494593 2.368011 +2.494593 3.788818 +2.356005 2.368011 +2.356005 3.788818 +0.120649 0.651974 +0.388740 0.594604 +0.244063 0.616490 +0.502331 0.502331 +0.362824 0.554964 +0.594604 0.388740 +0.468842 0.468842 +0.660525 0.261496 +0.554964 0.362824 +0.698543 0.129267 +0.616490 0.244063 +0.710403 -0.000000 +0.651974 0.120649 +0.698543 -0.129267 +0.663043 -0.000000 +0.660525 -0.261496 +0.651974 -0.120649 +0.594604 -0.388740 +0.616490 -0.244063 +0.502331 -0.502331 +0.554964 -0.362824 +0.388740 -0.594604 +0.468842 -0.468842 +0.261496 -0.660525 +0.362824 -0.554964 +0.129267 -0.698543 +0.244063 -0.616490 +-0.000000 -0.710403 +0.120649 -0.651974 +-0.129267 -0.698543 +0.000000 -0.663043 +-0.261496 -0.660525 +-0.120649 -0.651974 +-0.388740 -0.594604 +-0.244063 -0.616490 +-0.502331 -0.502331 +-0.362824 -0.554964 +-0.594604 -0.388740 +-0.468842 -0.468842 +-0.660525 -0.261496 +-0.554964 -0.362824 +-0.698543 -0.129267 +-0.616490 -0.244063 +-0.710403 -0.000000 +-0.651974 -0.120649 +-0.698543 0.129267 +-0.663043 -0.000000 +-0.660525 0.261496 +-0.651974 0.120649 +-0.594604 0.388740 +-0.616490 0.244063 +-0.502331 0.502331 +-0.554964 0.362824 +-0.388740 0.594604 +-0.468842 0.468842 +-0.261496 0.660525 +-0.362824 0.554964 +-0.129267 0.698543 +-0.244063 0.616490 +0.000000 0.710403 +-0.120649 0.651974 +0.129267 0.698543 +0.000000 0.663043 +0.261496 0.660525 +2.069589 2.273291 +2.069589 0.000000 +4.139177 0.000000 +4.139177 2.273291 +4.009828 0.000000 +4.009828 2.273291 +3.880479 0.000000 +3.880479 2.273291 +3.751129 0.000000 +3.751129 2.273291 +3.621780 0.000000 +3.621780 2.273291 +3.492431 0.000000 +3.492431 2.273291 +3.363081 0.000000 +3.363081 2.273291 +3.233732 0.000000 +3.233732 2.273291 +3.104383 0.000000 +3.104383 2.273291 +2.975034 0.000000 +2.975034 2.273291 +2.845684 0.000000 +2.845684 2.273291 +2.716335 0.000000 +2.716335 2.273291 +2.586986 0.000000 +2.586986 2.273291 +2.457637 0.000000 +2.457637 2.273291 +2.328287 0.000000 +2.328287 2.273291 +2.198938 0.000000 +2.198938 2.273291 +-0.000000 0.568323 +-0.103414 0.558835 +-0.475684 0.310992 +-0.528420 0.209197 +-0.401865 0.401865 +-0.310992 0.475684 +-0.558835 0.103414 +-0.209197 0.528420 +-0.568323 0.000000 +-0.558835 -0.103414 +-0.528420 -0.209197 +-0.475684 -0.310992 +-0.401865 -0.401865 +-0.310992 -0.475684 +-0.209197 -0.528420 +-0.103414 -0.558835 +-0.000000 -0.568323 +0.103414 -0.558835 +0.209197 -0.528420 +0.310992 -0.475684 +0.401865 -0.401865 +0.475684 -0.310992 +0.528420 -0.209197 +0.558835 -0.103414 +0.568323 -0.000000 +0.558835 0.103414 +0.528420 0.209197 +0.475684 0.310992 +0.401865 0.401865 +0.310992 0.475684 +0.209197 0.528420 +0.103414 0.558835 +-0.129267 0.698543 +0.698543 0.129267 +0.710403 -0.000000 +0.710403 -0.626517 +0.698543 -0.129267 +0.660525 0.261496 +0.594604 0.388740 +0.660525 -0.261496 +0.594604 -0.388740 +0.502331 0.502331 +0.710403 0.626517 +0.388740 0.594604 +0.564493 0.760621 +0.261496 0.660525 +0.564493 -0.760621 +0.502331 -0.502331 +0.389716 -0.863318 +0.388740 -0.594604 +0.197089 -0.926473 +0.261496 -0.660525 +0.389716 0.863318 +0.129267 0.698543 +0.197089 0.926473 +0.000000 0.710403 +0.000000 -0.947204 +0.129267 -0.698543 +-0.172356 -0.931391 +0.000000 -0.710403 +-0.348661 -0.880700 +-0.129267 -0.698543 +-0.518319 -0.792806 +-0.261496 -0.660525 +-0.669775 -0.669775 +-0.388740 -0.594604 +-0.792806 -0.518319 +-0.502331 -0.502331 +-0.880700 -0.348661 +-0.594604 -0.388740 +-0.931391 -0.172356 +-0.660525 -0.261496 +-0.947204 -0.000000 +-0.698543 -0.129267 +-0.931391 0.172356 +-0.710403 -0.000000 +-0.880700 0.348661 +-0.698543 0.129267 +-0.792806 0.518319 +-0.660525 0.261496 +-0.669775 0.669775 +-0.594604 0.388740 +-0.518319 0.792806 +-0.502331 0.502331 +-0.348661 0.880700 +-0.388740 0.594604 +-0.172356 0.931391 +-0.261496 0.660525 +0.000000 0.947204 +0.812221 -0.000000 +0.812221 1.562887 +-0.014109 1.562887 +-0.014109 -0.000000 +0.029487 1.562887 +0.214271 1.562887 +0.029487 -0.000000 +0.214271 -0.000000 +0.399056 1.562887 +0.583841 1.562887 +0.399056 -0.000000 +0.583841 -0.000000 +0.768625 1.562887 +0.768625 -0.000000 +-0.155121 -0.838252 +-0.000000 -0.852484 +0.615683 -0.589630 +0.615683 0.589630 +0.486494 0.700038 +0.334723 0.784021 +0.169094 0.835545 +-0.000000 0.852484 +-0.155121 0.838252 +-0.313795 0.792630 +-0.466488 0.713525 +-0.602797 0.602797 +-0.713525 0.466488 +-0.792630 0.313795 +0.486494 -0.700038 +0.334723 -0.784021 +0.169094 -0.835545 +-0.838252 0.155121 +-0.852484 0.000000 +-0.838252 -0.155121 +-0.792630 -0.313795 +-0.713525 -0.466488 +-0.602797 -0.602797 +-0.466488 -0.713525 +-0.313795 -0.792630 +1.230536 -3.409936 +1.230536 -4.972823 +2.483570 -4.972823 +2.483570 -3.409936 +1.857053 -4.972823 +-0.013407 -0.669775 +-0.013407 -0.803730 +0.735510 -0.803730 +0.771606 -0.669775 +0.730025 -0.803730 +0.730025 -0.669775 +0.554479 -0.803730 +0.378934 -0.803730 +0.554479 -0.669775 +0.203388 -0.803730 +0.378934 -0.669775 +0.027843 -0.803730 +0.203388 -0.669775 +0.027843 -0.669775 +0.133955 -0.626517 +0.133955 0.626517 +-0.000000 0.589630 +-0.000000 -0.589630 +1.921761 -0.443726 +1.921761 -0.577681 +3.843522 -0.577681 +3.843522 -0.443726 +3.723412 -0.577681 +3.723412 -0.443726 +3.603302 -0.577681 +3.603302 -0.443726 +3.483191 -0.577681 +3.483191 -0.443726 +3.363081 -0.577681 +3.363081 -0.443726 +3.242971 -0.577681 +3.242971 -0.443726 +3.122861 -0.577681 +3.122861 -0.443726 +3.002751 -0.577681 +3.002751 -0.443726 +2.882641 -0.577681 +2.882641 -0.443726 +2.762531 -0.577681 +2.762531 -0.443726 +2.642421 -0.577681 +2.642421 -0.443726 +2.522311 -0.577681 +2.522311 -0.443726 +2.402201 -0.577681 +2.402201 -0.443726 +2.282091 -0.577681 +2.282091 -0.443726 +2.161981 -0.577681 +2.161981 -0.443726 +2.041871 -0.577681 +2.041871 -0.443726 + + + + + + + + + + + +

32 0 32 0 1 0 1 2 1 4 3 4 2 4 2 3 5 3 5 6 5 2 7 2 4 8 4 7 9 7 2 10 2 5 11 5 7 12 7 6 13 6 2 14 2 9 15 9 6 16 6 7 17 7 9 18 9 8 19 8 6 20 6 11 21 11 8 22 8 9 23 9 11 24 11 10 25 10 8 26 8 13 27 13 10 28 10 11 29 11 13 30 13 12 31 12 10 32 10 15 33 15 12 34 12 13 35 13 15 36 15 14 37 14 12 38 12 17 39 17 14 40 14 15 41 15 17 42 17 16 43 16 14 44 14 19 45 19 16 46 16 17 47 17 19 48 19 18 49 18 16 50 16 21 51 21 18 52 18 19 53 19 21 54 21 20 55 20 18 56 18 23 57 23 20 58 20 21 59 21 23 60 23 22 61 22 20 62 20 25 63 25 22 64 22 23 65 23 25 66 25 24 67 24 22 68 22 27 69 27 24 70 24 25 71 25 27 72 27 26 73 26 24 74 24 29 75 29 26 76 26 27 77 27 29 78 29 28 79 28 26 80 26 31 81 31 28 82 28 29 83 29 31 84 31 30 85 30 28 86 28 33 87 33 30 88 30 31 89 31 33 90 33 32 91 32 30 92 30 0 93 0 32 94 32 33 95 33 46 96 46 45 97 45 34 98 34 37 99 37 35 100 35 36 101 36 39 102 39 35 103 35 37 104 37 39 105 39 38 106 38 35 107 35 41 108 41 38 109 38 39 110 39 41 111 41 40 112 40 38 113 38 42 114 42 40 115 40 41 116 41 44 117 44 40 118 40 42 119 42 44 120 44 43 121 43 40 122 40 34 123 34 43 124 43 44 125 44 34 126 34 45 127 45 43 128 43 45 129 45 46 130 46 47 131 47 80 132 80 48 133 48 49 134 49 53 135 53 50 136 50 51 137 51 53 138 53 52 139 52 50 140 50 55 141 55 52 142 52 53 143 53 55 144 55 54 145 54 52 146 52 57 147 57 54 148 54 55 149 55 57 150 57 56 151 56 54 152 54 59 153 59 56 154 56 57 155 57 59 156 59 58 157 58 56 158 56 61 159 61 58 160 58 59 161 59 61 162 61 60 163 60 58 164 58 63 165 63 60 166 60 61 167 61 63 168 63 62 169 62 60 170 60 65 171 65 62 172 62 63 173 63 65 174 65 64 175 64 62 176 62 67 177 67 64 178 64 65 179 65 67 180 67 66 181 66 64 182 64 69 183 69 66 184 66 67 185 67 69 186 69 68 187 68 66 188 66 71 189 71 68 190 68 69 191 69 71 192 71 70 193 70 68 194 68 73 195 73 70 196 70 71 197 71 73 198 73 72 199 72 70 200 70 75 201 75 72 202 72 73 203 73 75 204 75 74 205 74 72 206 72 78 207 78 74 208 74 75 209 75 78 210 78 76 211 76 74 212 74 78 213 78 77 214 77 76 215 76 79 216 79 77 217 77 78 218 78 81 219 81 77 220 77 79 221 79 81 222 81 80 223 80 77 224 77 48 225 48 80 226 80 81 227 81 95 228 95 82 229 82 83 230 83 86 231 86 84 232 84 85 233 85 87 234 87 84 235 84 86 236 86 89 237 89 84 238 84 87 239 87 89 240 89 88 241 88 84 242 84 92 243 92 88 244 88 89 245 89 92 246 92 90 247 90 88 248 88 92 249 92 91 250 91 90 251 90 94 252 94 91 253 91 92 254 92 94 255 94 93 256 93 91 257 91 82 258 82 93 259 93 94 260 94 82 261 82 95 262 95 93 263 93 128 264 128 96 265 96 97 266 97 101 267 101 98 268 98 99 269 99 101 270 101 100 271 100 98 272 98 103 273 103 100 274 100 101 275 101 103 276 103 102 277 102 100 278 100 105 279 105 102 280 102 103 281 103 105 282 105 104 283 104 102 284 102 107 285 107 104 286 104 105 287 105 107 288 107 106 289 106 104 290 104 109 291 109 106 292 106 107 293 107 109 294 109 108 295 108 106 296 106 111 297 111 108 298 108 109 299 109 111 300 111 110 301 110 108 302 108 113 303 113 110 304 110 111 305 111 113 306 113 112 307 112 110 308 110 115 309 115 112 310 112 113 311 113 115 312 115 114 313 114 112 314 112 117 315 117 114 316 114 115 317 115 117 318 117 116 319 116 114 320 114 119 321 119 116 322 116 117 323 117 119 324 119 118 325 118 116 326 116 121 327 121 118 328 118 119 329 119 121 330 121 120 331 120 118 332 118 123 333 123 120 334 120 121 335 121 123 336 123 122 337 122 120 338 120 125 339 125 122 340 122 123 341 123 125 342 125 124 343 124 122 344 122 127 345 127 124 346 124 125 347 125 127 348 127 126 349 126 124 350 124 129 351 129 126 352 126 127 353 127 129 354 129 128 355 128 126 356 126 96 357 96 128 358 128 129 359 129 162 360 162 130 361 130 131 362 131 135 363 135 132 364 132 133 365 133 135 366 135 134 367 134 132 368 132 137 369 137 134 370 134 135 371 135 137 372 137 136 373 136 134 374 134 139 375 139 136 376 136 137 377 137 139 378 139 138 379 138 136 380 136 141 381 141 138 382 138 139 383 139 141 384 141 140 385 140 138 386 138 144 387 144 140 388 140 141 389 141 144 390 144 142 391 142 140 392 140 144 393 144 143 394 143 142 395 142 145 396 145 143 397 143 144 398 144 147 399 147 143 400 143 145 401 145 147 402 147 146 403 146 143 404 143 149 405 149 146 406 146 147 407 147 149 408 149 148 409 148 146 410 146 151 411 151 148 412 148 149 413 149 151 414 151 150 415 150 148 416 148 153 417 153 150 418 150 151 419 151 153 420 153 152 421 152 150 422 150 155 423 155 152 424 152 153 425 153 155 426 155 154 427 154 152 428 152 157 429 157 154 430 154 155 431 155 157 432 157 156 433 156 154 434 154 159 435 159 156 436 156 157 437 157 159 438 159 158 439 158 156 440 156 161 441 161 158 442 158 159 443 159 161 444 161 160 445 160 158 446 158 163 447 163 160 448 160 161 449 161 163 450 163 162 451 162 160 452 160 130 453 130 162 454 162 163 455 163 196 456 196 175 457 175 164 458 164 167 459 167 165 460 165 166 461 166 168 462 168 165 463 165 167 464 167 170 465 170 165 466 165 168 467 168 170 468 170 169 469 169 165 470 165 172 471 172 169 472 169 170 473 170 172 474 172 171 475 171 169 476 169 174 477 174 171 478 171 172 479 172 174 480 174 173 481 173 171 482 171 164 483 164 173 484 173 174 485 174 164 486 164 175 487 175 173 488 173 178 489 178 176 490 176 177 491 177 179 492 179 176 493 176 178 494 178 181 495 181 176 496 176 179 497 179 181 498 181 180 499 180 176 500 176 183 501 183 180 502 180 181 503 181 183 504 183 182 505 182 180 506 180 185 507 185 182 508 182 183 509 183 185 510 185 184 511 184 182 512 182 188 513 188 184 514 184 185 515 185 188 516 188 186 517 186 184 518 184 188 519 188 187 520 187 186 521 186 190 522 190 187 523 187 188 524 188 190 525 190 189 526 189 187 527 187 192 528 192 189 529 189 190 530 190 192 531 192 191 532 191 189 533 189 193 534 193 191 535 191 192 536 192 195 537 195 191 538 191 193 539 193 195 540 195 194 541 194 191 542 191 197 543 197 194 544 194 195 545 195 197 546 197 196 547 196 194 548 194 175 549 175 196 550 196 197 551 197 230 552 230 198 553 198 199 554 199 203 555 203 200 556 200 201 557 201 203 558 203 202 559 202 200 560 200 205 561 205 202 562 202 203 563 203 205 564 205 204 565 204 202 566 202 207 567 207 204 568 204 205 569 205 207 570 207 206 571 206 204 572 204 209 573 209 206 574 206 207 575 207 209 576 209 208 577 208 206 578 206 211 579 211 208 580 208 209 581 209 211 582 211 210 583 210 208 584 208 213 585 213 210 586 210 211 587 211 213 588 213 212 589 212 210 590 210 215 591 215 212 592 212 213 593 213 215 594 215 214 595 214 212 596 212 217 597 217 214 598 214 215 599 215 217 600 217 216 601 216 214 602 214 219 603 219 216 604 216 217 605 217 219 606 219 218 607 218 216 608 216 221 609 221 218 610 218 219 611 219 221 612 221 220 613 220 218 614 218 223 615 223 220 616 220 221 617 221 223 618 223 222 619 222 220 620 220 225 621 225 222 622 222 223 623 223 225 624 225 224 625 224 222 626 222 227 627 227 224 628 224 225 629 225 227 630 227 226 631 226 224 632 224 229 633 229 226 634 226 227 635 227 229 636 229 228 637 228 226 638 226 231 639 231 228 640 228 229 641 229 231 642 231 230 643 230 228 644 228 198 645 198 230 646 230 231 647 231 295 648 295 232 649 232 234 650 234 234 651 234 233 652 233 295 653 295 236 654 236 233 655 233 234 656 234 236 657 236 235 658 235 233 659 233 238 660 238 235 661 235 236 662 236 238 663 238 237 664 237 235 665 235 240 666 240 237 667 237 238 668 238 240 669 240 239 670 239 237 671 237 242 672 242 239 673 239 240 674 240 242 675 242 241 676 241 239 677 239 244 678 244 241 679 241 242 680 242 244 681 244 243 682 243 241 683 241 246 684 246 243 685 243 244 686 244 246 687 246 245 688 245 243 689 243 248 690 248 245 691 245 246 692 246 248 693 248 247 694 247 245 695 245 250 696 250 247 697 247 248 698 248 250 699 250 249 700 249 247 701 247 252 702 252 249 703 249 250 704 250 252 705 252 251 706 251 249 707 249 254 708 254 251 709 251 252 710 252 254 711 254 253 712 253 251 713 251 256 714 256 253 715 253 254 716 254 256 717 256 255 718 255 253 719 253 258 720 258 255 721 255 256 722 256 258 723 258 257 724 257 255 725 255 260 726 260 257 727 257 258 728 258 260 729 260 259 730 259 257 731 257 262 732 262 259 733 259 260 734 260 262 735 262 261 736 261 259 737 259 264 738 264 261 739 261 262 740 262 264 741 264 263 742 263 261 743 261 266 744 266 263 745 263 264 746 264 266 747 266 265 748 265 263 749 263 268 750 268 265 751 265 266 752 266 268 753 268 267 754 267 265 755 265 270 756 270 267 757 267 268 758 268 270 759 270 269 760 269 267 761 267 272 762 272 269 763 269 270 764 270 272 765 272 271 766 271 269 767 269 274 768 274 271 769 271 272 770 272 274 771 274 273 772 273 271 773 271 276 774 276 273 775 273 274 776 274 276 777 276 275 778 275 273 779 273 278 780 278 275 781 275 276 782 276 278 783 278 277 784 277 275 785 275 280 786 280 277 787 277 278 788 278 280 789 280 279 790 279 277 791 277 282 792 282 279 793 279 280 794 280 282 795 282 281 796 281 279 797 279 284 798 284 281 799 281 282 800 282 284 801 284 283 802 283 281 803 281 286 804 286 283 805 283 284 806 284 286 807 286 285 808 285 283 809 283 288 810 288 285 811 285 286 812 286 288 813 288 287 814 287 285 815 285 290 816 290 287 817 287 288 818 288 290 819 290 289 820 289 287 821 287 292 822 292 289 823 289 290 824 290 292 825 292 291 826 291 289 827 289 294 828 294 291 829 291 292 830 292 294 831 294 293 832 293 291 833 291 232 834 232 293 835 293 294 836 294 232 837 232 295 838 295 293 839 293 328 840 328 296 841 296 297 842 297 301 843 301 298 844 298 299 845 299 301 846 301 300 847 300 298 848 298 303 849 303 300 850 300 301 851 301 303 852 303 302 853 302 300 854 300 305 855 305 302 856 302 303 857 303 305 858 305 304 859 304 302 860 302 307 861 307 304 862 304 305 863 305 307 864 307 306 865 306 304 866 304 309 867 309 306 868 306 307 869 307 309 870 309 308 871 308 306 872 306 311 873 311 308 874 308 309 875 309 311 876 311 310 877 310 308 878 308 313 879 313 310 880 310 311 881 311 313 882 313 312 883 312 310 884 310 315 885 315 312 886 312 313 887 313 315 888 315 314 889 314 312 890 312 317 891 317 314 892 314 315 893 315 317 894 317 316 895 316 314 896 314 319 897 319 316 898 316 317 899 317 319 900 319 318 901 318 316 902 316 321 903 321 318 904 318 319 905 319 321 906 321 320 907 320 318 908 318 323 909 323 320 910 320 321 911 321 323 912 323 322 913 322 320 914 320 325 915 325 322 916 322 323 917 323 325 918 325 324 919 324 322 920 322 327 921 327 324 922 324 325 923 325 327 924 327 326 925 326 324 926 324 329 927 329 326 928 326 327 929 327 329 930 329 328 931 328 326 932 326 296 933 296 328 934 328 329 935 329 337 936 337 330 937 330 331 938 331 336 939 336 332 940 332 333 941 333 336 942 336 334 943 334 332 944 332 336 945 336 335 946 335 334 947 334 338 948 338 335 949 335 336 950 336 338 951 338 337 952 337 335 953 335 339 954 339 337 955 337 338 956 338 340 957 340 337 958 337 339 959 339 341 960 341 337 961 337 340 962 340 342 963 342 337 964 337 341 965 341 343 966 343 337 967 337 342 968 342 344 969 344 337 970 337 343 971 343 345 972 345 337 973 337 344 974 344 346 975 346 337 976 337 345 977 345 347 978 347 337 979 337 346 980 346 348 981 348 337 982 337 347 983 347 349 984 349 337 985 337 348 986 348 350 987 350 337 988 337 349 989 349 351 990 351 337 991 337 350 992 350 352 993 352 337 994 337 351 995 351 353 996 353 337 997 337 352 998 352 354 999 354 337 1000 337 353 1001 353 355 1002 355 337 1003 337 354 1004 354 356 1005 356 337 1006 337 355 1007 355 357 1008 357 337 1009 337 356 1010 356 358 1011 358 337 1012 337 357 1013 357 359 1014 359 337 1015 337 358 1016 358 360 1017 360 337 1018 337 359 1019 359 361 1020 361 337 1021 337 360 1022 360 330 1023 330 337 1024 337 361 1025 361 418 1026 418 362 1027 362 385 1028 385 372 1029 372 363 1030 363 364 1031 364 366 1032 366 365 1033 365 515 1034 364 369 1035 369 365 1036 365 366 1037 366 372 1038 372 367 1039 367 363 1040 363 372 1041 372 368 1042 368 367 1043 367 370 1044 370 365 1045 365 369 1046 369 377 1047 377 365 1048 365 370 1049 370 372 1050 372 371 1051 371 368 1052 368 374 1053 374 371 1054 371 372 1055 372 374 1056 374 373 1057 373 371 1058 371 382 1059 382 373 1060 373 374 1061 374 382 1062 382 375 1063 375 373 1064 373 377 1065 377 376 1066 376 365 1067 365 379 1068 379 376 1069 376 377 1070 377 379 1071 379 378 1072 378 376 1073 376 381 1074 381 378 1075 378 379 1076 379 381 1077 381 380 1078 380 378 1079 378 387 1080 387 380 1081 380 381 1082 381 384 1083 384 375 1084 375 382 1085 382 384 1086 384 383 1087 383 375 1088 375 418 1089 418 383 1090 383 384 1091 384 418 1092 418 385 1093 385 383 1094 383 387 1095 387 386 1096 386 380 1097 380 389 1098 389 386 1099 386 387 1100 387 389 1101 389 388 1102 388 386 1103 386 391 1104 391 388 1105 388 389 1106 389 391 1107 391 390 1108 390 388 1109 388 393 1110 393 390 1111 390 391 1112 391 393 1113 393 392 1114 392 390 1115 390 395 1116 395 392 1117 392 393 1118 393 395 1119 395 394 1120 394 392 1121 392 397 1122 397 394 1123 394 395 1124 395 397 1125 397 396 1126 396 394 1127 394 399 1128 399 396 1129 396 397 1130 397 399 1131 399 398 1132 398 396 1133 396 401 1134 401 398 1135 398 399 1136 399 401 1137 401 400 1138 400 398 1139 398 403 1140 403 400 1141 400 401 1142 401 403 1143 403 402 1144 402 400 1145 400 405 1146 405 402 1147 402 403 1148 403 405 1149 405 404 1150 404 402 1151 402 407 1152 407 404 1153 404 405 1154 405 407 1155 407 406 1156 406 404 1157 404 409 1158 409 406 1159 406 407 1160 407 409 1161 409 408 1162 408 406 1163 406 411 1164 411 408 1165 408 409 1166 409 411 1167 411 410 1168 410 408 1169 408 413 1170 413 410 1171 410 411 1172 411 413 1173 413 412 1174 412 410 1175 410 415 1176 415 412 1177 412 413 1178 413 415 1179 415 414 1180 414 412 1181 412 417 1182 417 414 1183 414 415 1184 415 417 1185 417 416 1186 416 414 1187 414 362 1188 362 416 1189 416 417 1190 417 362 1191 362 418 1192 418 416 1193 416 431 1194 431 419 1195 419 420 1196 420 425 1197 425 421 1198 421 422 1199 422 425 1200 425 423 1201 423 421 1202 421 425 1203 425 424 1204 424 423 1205 423 426 1206 426 424 1207 424 425 1208 425 429 1209 429 424 1210 424 426 1211 426 429 1212 429 427 1213 427 424 1214 424 429 1215 429 428 1216 428 427 1217 427 430 1218 430 428 1219 428 429 1220 429 432 1221 432 428 1222 428 430 1223 430 432 1224 432 431 1225 431 428 1226 428 419 1227 419 431 1228 431 432 1229 432 449 1230 449 433 1231 433 434 1232 434 437 1233 437 435 1234 435 436 1235 436 438 1236 438 435 1237 435 437 1238 437 439 1239 439 435 1240 435 438 1241 438 440 1242 440 435 1243 435 439 1244 439 441 1245 441 435 1246 435 440 1247 440 442 1248 442 435 1249 435 441 1250 441 443 1251 443 435 1252 435 442 1253 442 444 1254 444 435 1255 435 443 1256 443 445 1257 445 435 1258 435 444 1259 444 446 1260 446 435 1261 435 445 1262 445 450 1263 450 435 1264 435 446 1265 446 450 1266 450 447 1267 447 435 1268 435 450 1269 450 448 1270 448 447 1271 447 450 1272 450 449 1273 449 448 1274 448 451 1275 451 449 1276 449 450 1277 450 452 1278 452 449 1279 449 451 1280 451 453 1281 453 449 1282 449 452 1283 452 454 1284 454 449 1285 449 453 1286 453 455 1287 455 449 1288 449 454 1289 454 456 1290 456 449 1291 449 455 1292 455 457 1293 457 449 1294 449 456 1295 456 433 1296 433 449 1297 449 457 1298 457 462 1299 462 458 1300 458 459 1301 459 458 1302 458 460 1303 460 461 1304 461 458 1305 458 462 1306 462 460 1307 460 474 1308 474 463 1309 463 464 1310 464 468 1311 468 465 1312 465 466 1313 466 468 1314 468 467 1315 467 465 1316 465 471 1317 471 467 1318 467 468 1319 468 471 1320 471 469 1321 469 467 1322 467 471 1323 471 470 1324 470 469 1325 469 473 1326 473 470 1327 470 471 1328 471 473 1329 473 472 1330 472 470 1331 470 475 1332 475 472 1333 472 473 1334 473 475 1335 475 474 1336 474 472 1337 472 476 1338 476 474 1339 474 475 1340 475 463 1341 463 474 1342 474 476 1343 476 479 1344 479 477 1345 477 478 1346 478 477 1347 477 479 1348 479 480 1349 480 513 1350 513 481 1351 481 482 1352 482 486 1353 486 483 1354 483 484 1355 484 486 1356 486 485 1357 485 483 1358 483 488 1359 488 485 1360 485 486 1361 486 488 1362 488 487 1363 487 485 1364 485 490 1365 490 487 1366 487 488 1367 488 490 1368 490 489 1369 489 487 1370 487 492 1371 492 489 1372 489 490 1373 490 492 1374 492 491 1375 491 489 1376 489 494 1377 494 491 1378 491 492 1379 492 494 1380 494 493 1381 493 491 1382 491 496 1383 496 493 1384 493 494 1385 494 496 1386 496 495 1387 495 493 1388 493 498 1389 498 495 1390 495 496 1391 496 498 1392 498 497 1393 497 495 1394 495 500 1395 500 497 1396 497 498 1397 498 500 1398 500 499 1399 499 497 1400 497 502 1401 502 499 1402 499 500 1403 500 502 1404 502 501 1405 501 499 1406 499 504 1407 504 501 1408 501 502 1409 502 504 1410 504 503 1411 503 501 1412 501 506 1413 506 503 1414 503 504 1415 504 506 1416 506 505 1417 505 503 1418 503 508 1419 508 505 1420 505 506 1421 506 508 1422 508 507 1423 507 505 1424 505 510 1425 510 507 1426 507 508 1427 508 510 1428 510 509 1429 509 507 1430 507 512 1431 512 509 1432 509 510 1433 510 512 1434 512 511 1435 511 509 1436 509 514 1437 514 511 1438 511 512 1439 512 514 1440 514 513 1441 513 511 1442 511 481 1443 481 513 1444 513 514 1445 514

+
+
+ + + + +7.500000 0.000000 1.500000 +7.500000 0.000000 0.000000 +-7.469662 0.673908 0.000000 +-7.500000 0.000000 0.000000 +-7.500000 0.000000 1.500000 +-7.469662 0.673908 1.500000 +-7.374790 1.364723 0.000000 +-7.374790 1.364723 1.500000 +-7.210492 2.063687 0.000000 +-7.210492 2.063687 1.500000 +-6.973412 2.760710 0.000000 +-6.973412 2.760710 1.500000 +-6.662130 3.444710 0.000000 +-6.662130 3.444710 1.500000 +-6.277466 4.104073 0.000000 +-6.277466 4.104073 1.500000 +-5.822649 4.727236 0.000000 +-5.822649 4.727236 1.500000 +-5.303301 5.303301 0.000000 +-5.303301 5.303301 1.500000 +-4.727236 5.822649 0.000000 +-4.727236 5.822649 1.500000 +-4.104073 6.277466 0.000000 +-4.104073 6.277466 1.500000 +-3.444710 6.662130 0.000000 +-3.444710 6.662130 1.500000 +-2.760710 6.973412 0.000000 +-2.760710 6.973412 1.500000 +-2.063687 7.210492 0.000000 +-2.063687 7.210492 1.500000 +-1.364723 7.374790 0.000000 +-1.364723 7.374790 1.500000 +-0.673908 7.469662 0.000000 +-0.673908 7.469662 1.500000 +0.000000 7.500000 0.000000 +0.000000 7.500000 1.500000 +0.673908 7.469662 0.000000 +0.673908 7.469662 1.500000 +1.364723 7.374790 0.000000 +1.364723 7.374790 1.500000 +2.063687 7.210492 0.000000 +2.063687 7.210492 1.500000 +2.760710 6.973412 0.000000 +2.760710 6.973412 1.500000 +3.444710 6.662130 0.000000 +3.444710 6.662130 1.500000 +4.104073 6.277466 0.000000 +4.104073 6.277466 1.500000 +4.727236 5.822649 0.000000 +4.727236 5.822649 1.500000 +5.303301 5.303301 0.000000 +5.303301 5.303301 1.500000 +5.822649 4.727236 0.000000 +5.822649 4.727236 1.500000 +6.277466 4.104073 0.000000 +6.277466 4.104073 1.500000 +6.662130 3.444710 0.000000 +6.662130 3.444710 1.500000 +6.973412 2.760710 0.000000 +6.973412 2.760710 1.500000 +7.210492 2.063687 0.000000 +7.210492 2.063687 1.500000 +7.374790 1.364723 0.000000 +7.374790 1.364723 1.500000 +7.469662 0.673908 0.000000 +7.469662 0.673908 1.500000 +7.500000 0.000000 0.000000 +7.500000 0.000000 1.500000 +-7.500000 0.000000 1.500000 +-7.500000 0.000000 0.000000 +-7.469662 -0.673908 1.500000 +-7.469662 -0.673908 0.000000 +-7.374790 -1.364723 1.500000 +-7.374790 -1.364723 0.000000 +-7.210492 -2.063687 1.500000 +-7.210492 -2.063687 0.000000 +-6.973412 -2.760710 1.500000 +-6.973412 -2.760710 0.000000 +-6.662130 -3.444710 1.500000 +-6.662130 -3.444710 0.000000 +-6.277466 -4.104073 1.500000 +-6.277466 -4.104073 0.000000 +-5.822649 -4.727236 1.500000 +-5.822649 -4.727236 0.000000 +-5.303301 -5.303301 1.500000 +-5.303301 -5.303301 0.000000 +-4.727236 -5.822649 1.500000 +-4.727236 -5.822649 0.000000 +-4.104073 -6.277466 1.500000 +-4.104073 -6.277466 0.000000 +-3.444710 -6.662130 1.500000 +-3.444710 -6.662130 0.000000 +-2.760710 -6.973412 1.500000 +-2.760710 -6.973412 0.000000 +-2.063687 -7.210492 1.500000 +-2.063687 -7.210492 0.000000 +-1.364723 -7.374790 1.500000 +-1.364723 -7.374790 0.000000 +-0.673908 -7.469662 1.500000 +-0.673908 -7.469662 0.000000 +0.000000 -7.500000 1.500000 +0.000000 -7.500000 0.000000 +0.673908 -7.469662 1.500000 +0.673908 -7.469662 0.000000 +1.364723 -7.374790 1.500000 +1.364723 -7.374790 0.000000 +2.063687 -7.210492 1.500000 +2.063687 -7.210492 0.000000 +2.760710 -6.973412 1.500000 +2.760710 -6.973412 0.000000 +3.444710 -6.662130 1.500000 +3.444710 -6.662130 0.000000 +4.104073 -6.277466 1.500000 +4.104073 -6.277466 0.000000 +4.727236 -5.822649 1.500000 +4.727236 -5.822649 0.000000 +5.303301 -5.303301 1.500000 +5.303301 -5.303301 0.000000 +5.822649 -4.727236 1.500000 +5.822649 -4.727236 0.000000 +6.277466 -4.104073 1.500000 +6.277466 -4.104073 0.000000 +6.662130 -3.444710 1.500000 +6.662130 -3.444710 0.000000 +6.973412 -2.760710 1.500000 +6.973412 -2.760710 0.000000 +7.210492 -2.063687 1.500000 +7.210492 -2.063687 0.000000 +7.374790 -1.364723 1.500000 +7.374790 -1.364723 0.000000 +7.469662 -0.673908 1.500000 +7.469662 -0.673908 0.000000 +2.063687 7.210492 1.500000 +1.364723 7.374790 1.500000 +0.673908 7.469662 1.500000 +-0.673908 7.469662 1.500000 +-1.364723 7.374790 1.500000 +-2.063687 7.210492 1.500000 +-2.760710 6.973412 1.500000 +-3.444710 6.662130 1.500000 +-4.104073 6.277466 1.500000 +-4.727236 5.822649 1.500000 +-5.303301 5.303301 1.500000 +-5.822649 4.727236 1.500000 +-6.277466 4.104073 1.500000 +-6.662130 3.444710 1.500000 +-6.973412 2.760710 1.500000 +-7.210492 2.063687 1.500000 +-7.374790 1.364723 1.500000 +-7.469662 0.673908 1.500000 +-7.500000 0.000000 1.500000 +-7.469662 -0.673908 1.500000 +-7.374790 -1.364723 1.500000 +-7.210492 -2.063687 1.500000 +-6.973412 -2.760710 1.500000 +-6.662130 -3.444710 1.500000 +-6.277466 -4.104073 1.500000 +-5.822649 -4.727236 1.500000 +-5.303301 -5.303301 1.500000 +-4.727236 -5.822649 1.500000 +-4.104073 -6.277466 1.500000 +-3.444710 -6.662130 1.500000 +-2.760710 -6.973412 1.500000 +-2.063687 -7.210492 1.500000 +-1.364723 -7.374790 1.500000 +-0.673908 -7.469662 1.500000 +0.673908 -7.469662 1.500000 +1.364723 -7.374790 1.500000 +2.063687 -7.210492 1.500000 +2.760710 -6.973412 1.500000 +3.444710 -6.662130 1.500000 +4.104073 -6.277466 1.500000 +4.727236 -5.822649 1.500000 +5.303301 -5.303301 1.500000 +5.822649 -4.727236 1.500000 +6.277466 -4.104073 1.500000 +6.662130 -3.444710 1.500000 +6.973412 -2.760710 1.500000 +7.210492 -2.063687 1.500000 +7.374790 -1.364723 1.500000 +7.469662 -0.673908 1.500000 +7.500000 0.000000 1.500000 +7.469662 0.673908 1.500000 +7.374790 1.364723 1.500000 +7.210492 2.063687 1.500000 +6.973412 2.760710 1.500000 +6.662130 3.444710 1.500000 +6.277466 4.104073 1.500000 +5.822649 4.727236 1.500000 +5.303301 5.303301 1.500000 +4.727236 5.822649 1.500000 +4.104073 6.277466 1.500000 +3.444710 6.662130 1.500000 +2.760710 6.973412 1.500000 +2.063687 -7.210492 0.000000 +1.364723 -7.374790 0.000000 +0.673908 -7.469662 0.000000 +-0.673908 -7.469662 0.000000 +-1.364723 -7.374790 0.000000 +-2.063687 -7.210492 0.000000 +-2.760710 -6.973412 0.000000 +-3.444710 -6.662130 0.000000 +-4.104073 -6.277466 0.000000 +-4.727236 -5.822649 0.000000 +-5.303301 -5.303301 0.000000 +-5.822649 -4.727236 0.000000 +-6.277466 -4.104073 0.000000 +-6.662130 -3.444710 0.000000 +-6.973412 -2.760710 0.000000 +-7.210492 -2.063687 0.000000 +-7.374790 -1.364723 0.000000 +-7.469662 -0.673908 0.000000 +-7.500000 0.000000 0.000000 +-7.469662 0.673908 0.000000 +-7.374790 1.364723 0.000000 +-7.210492 2.063687 0.000000 +-6.973412 2.760710 0.000000 +-6.662130 3.444710 0.000000 +-6.277466 4.104073 0.000000 +-5.822649 4.727236 0.000000 +-5.303301 5.303301 0.000000 +-4.727236 5.822649 0.000000 +-4.104073 6.277466 0.000000 +-3.444710 6.662130 0.000000 +-2.760710 6.973412 0.000000 +-2.063687 7.210492 0.000000 +-1.364723 7.374790 0.000000 +-0.673908 7.469662 0.000000 +0.673908 7.469662 0.000000 +1.364723 7.374790 0.000000 +2.063687 7.210492 0.000000 +2.760710 6.973412 0.000000 +3.444710 6.662130 0.000000 +4.104073 6.277466 0.000000 +4.727236 5.822649 0.000000 +5.303301 5.303301 0.000000 +5.822649 4.727236 0.000000 +6.277466 4.104073 0.000000 +6.662130 3.444710 0.000000 +6.973412 2.760710 0.000000 +7.210492 2.063687 0.000000 +7.374790 1.364723 0.000000 +7.469662 0.673908 0.000000 +7.500000 0.000000 0.000000 +7.469662 -0.673908 0.000000 +7.374790 -1.364723 0.000000 +7.210492 -2.063687 0.000000 +6.973412 -2.760710 0.000000 +6.662130 -3.444710 0.000000 +6.277466 -4.104073 0.000000 +5.822649 -4.727236 0.000000 +5.303301 -5.303301 0.000000 +4.727236 -5.822649 0.000000 +4.104073 -6.277466 0.000000 +3.444710 -6.662130 0.000000 +2.760710 -6.973412 0.000000 + + + + + + + + + + + +0.995955 0.089854 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.995955 0.089854 0.000000 +-1.000000 0.000000 0.000000 +-0.995955 0.089854 0.000000 +-0.995955 0.089854 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.995955 0.089854 0.000000 +-0.995955 0.089854 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.995955 0.089854 0.000000 +-0.961399 0.275158 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.961399 0.275158 0.000000 +-0.961399 0.275158 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.961399 0.275158 0.000000 +-0.961399 0.275158 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.961399 0.275158 0.000000 +-0.888284 0.459295 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.888284 0.459295 0.000000 +-0.888284 0.459295 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.888284 0.459295 0.000000 +-0.888284 0.459295 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.888284 0.459295 0.000000 +-0.776353 0.630298 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.776353 0.630298 0.000000 +-0.776353 0.630298 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.776353 0.630298 0.000000 +-0.776353 0.630298 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.776353 0.630298 0.000000 +-0.630298 0.776353 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.630298 0.776353 0.000000 +-0.630298 0.776353 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.630298 0.776353 0.000000 +-0.630298 0.776353 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.630298 0.776353 0.000000 +-0.459295 0.888284 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.459295 0.888284 0.000000 +-0.459295 0.888284 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.459295 0.888284 0.000000 +-0.459295 0.888284 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.459295 0.888284 0.000000 +-0.275158 0.961399 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.275158 0.961399 0.000000 +-0.275158 0.961399 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.275158 0.961399 0.000000 +-0.275158 0.961399 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.275158 0.961399 0.000000 +-0.089854 0.995955 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.089854 0.995955 0.000000 +-0.089854 0.995955 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.089854 0.995955 0.000000 +-0.089854 0.995955 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.089854 0.995955 0.000000 +0.089854 0.995955 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.089854 0.995955 0.000000 +0.089854 0.995955 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.089854 0.995955 0.000000 +0.089854 0.995955 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.089854 0.995955 0.000000 +0.275158 0.961399 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.275158 0.961399 0.000000 +0.275158 0.961399 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.275158 0.961399 0.000000 +0.275158 0.961399 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.275158 0.961399 0.000000 +0.459295 0.888284 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.459295 0.888284 0.000000 +0.459295 0.888284 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.459295 0.888284 0.000000 +0.459295 0.888284 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.459295 0.888284 0.000000 +0.630298 0.776353 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.630298 0.776353 0.000000 +0.630298 0.776353 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.630298 0.776353 0.000000 +0.630298 0.776353 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.630298 0.776353 0.000000 +0.776353 0.630298 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.776353 0.630298 0.000000 +0.776353 0.630298 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.776353 0.630298 0.000000 +0.776353 0.630298 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.776353 0.630298 0.000000 +0.888284 0.459295 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.888284 0.459295 0.000000 +0.888284 0.459295 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.888284 0.459295 0.000000 +0.888284 0.459295 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.888284 0.459295 0.000000 +0.961399 0.275158 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.961399 0.275158 0.000000 +0.961399 0.275158 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.961399 0.275158 0.000000 +0.961399 0.275158 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.961399 0.275158 0.000000 +0.995955 0.089854 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.995955 0.089854 0.000000 +0.995955 0.089854 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.995955 0.089854 0.000000 +0.995955 0.089854 0.000000 +0.995955 -0.089854 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.995955 -0.089854 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.995955 -0.089854 0.000000 +-0.995955 -0.089854 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.995955 -0.089854 0.000000 +-0.995955 -0.089854 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.995955 -0.089854 0.000000 +-0.961399 -0.275158 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.961399 -0.275158 0.000000 +-0.961399 -0.275158 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.961399 -0.275158 0.000000 +-0.961399 -0.275158 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.961399 -0.275158 0.000000 +-0.888284 -0.459295 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.888284 -0.459295 0.000000 +-0.888284 -0.459295 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.888284 -0.459295 0.000000 +-0.888284 -0.459295 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.888284 -0.459295 0.000000 +-0.776353 -0.630298 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.776353 -0.630298 0.000000 +-0.776353 -0.630298 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.776353 -0.630298 0.000000 +-0.776353 -0.630298 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.776353 -0.630298 0.000000 +-0.630298 -0.776353 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.630298 -0.776353 0.000000 +-0.630298 -0.776353 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.630298 -0.776353 0.000000 +-0.630298 -0.776353 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.630298 -0.776353 0.000000 +-0.459295 -0.888284 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.459295 -0.888284 0.000000 +-0.459295 -0.888284 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.459295 -0.888284 0.000000 +-0.459295 -0.888284 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.459295 -0.888284 0.000000 +-0.275158 -0.961399 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.275158 -0.961399 0.000000 +-0.275158 -0.961399 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.275158 -0.961399 0.000000 +-0.275158 -0.961399 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.275158 -0.961399 0.000000 +-0.089854 -0.995955 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.089854 -0.995955 0.000000 +-0.089854 -0.995955 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +-0.089854 -0.995955 0.000000 +-0.089854 -0.995955 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.089854 -0.995955 0.000000 +0.089854 -0.995955 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.089854 -0.995955 0.000000 +0.089854 -0.995955 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.089854 -0.995955 0.000000 +0.089854 -0.995955 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.089854 -0.995955 0.000000 +0.275158 -0.961399 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.275158 -0.961399 0.000000 +0.275158 -0.961399 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.275158 -0.961399 0.000000 +0.275158 -0.961399 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.275158 -0.961399 0.000000 +0.459295 -0.888284 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.459295 -0.888284 0.000000 +0.459295 -0.888284 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.459295 -0.888284 0.000000 +0.459295 -0.888284 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.459295 -0.888284 0.000000 +0.630298 -0.776353 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.630298 -0.776353 0.000000 +0.630298 -0.776353 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.630298 -0.776353 0.000000 +0.630298 -0.776353 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.630298 -0.776353 0.000000 +0.776353 -0.630298 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.776353 -0.630298 0.000000 +0.776353 -0.630298 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.776353 -0.630298 0.000000 +0.776353 -0.630298 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.776353 -0.630298 0.000000 +0.888284 -0.459295 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.888284 -0.459295 0.000000 +0.888284 -0.459295 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.888284 -0.459295 0.000000 +0.888284 -0.459295 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.888284 -0.459295 0.000000 +0.961399 -0.275158 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.961399 -0.275158 0.000000 +0.961399 -0.275158 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.961399 -0.275158 0.000000 +0.961399 -0.275158 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.961399 -0.275158 0.000000 +0.995955 -0.089854 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.995955 -0.089854 0.000000 +0.995955 -0.089854 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.995955 -0.089854 0.000000 +0.995955 -0.089854 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 + + + + + + + + + + + +0.420526 0.833393 +0.420526 0.833445 +0.489537 0.840514 +0.489854 0.837387 +0.489854 0.837335 +0.489537 0.840463 +0.488919 0.843703 +0.488919 0.843652 +0.487977 0.846912 +0.487977 0.846861 +0.486699 0.850093 +0.486699 0.850041 +0.485082 0.853193 +0.485082 0.853142 +0.483132 0.856160 +0.483132 0.856108 +0.480867 0.858939 +0.480867 0.858888 +0.478316 0.861483 +0.478316 0.861432 +0.475518 0.863748 +0.475518 0.863697 +0.472519 0.865700 +0.472519 0.865649 +0.469371 0.867317 +0.469371 0.867265 +0.466129 0.868585 +0.466129 0.868534 +0.462845 0.869505 +0.462845 0.869454 +0.459572 0.870086 +0.459572 0.870034 +0.456354 0.870346 +0.456354 0.870294 +0.453232 0.870310 +0.453232 0.870258 +0.450125 0.869991 +0.450125 0.869940 +0.446957 0.869368 +0.446957 0.869317 +0.443769 0.868420 +0.443769 0.868369 +0.440610 0.867134 +0.440610 0.867083 +0.437530 0.865506 +0.437530 0.865455 +0.434583 0.863543 +0.434583 0.863492 +0.431821 0.861263 +0.431821 0.861212 +0.429294 0.858696 +0.429294 0.858644 +0.427044 0.855879 +0.427044 0.855828 +0.425105 0.852860 +0.425105 0.852809 +0.423499 0.849692 +0.423499 0.849640 +0.422239 0.846427 +0.422239 0.846376 +0.421325 0.843122 +0.421325 0.843071 +0.420748 0.839827 +0.420748 0.839776 +0.420490 0.836588 +0.420490 0.836537 +0.420526 0.833445 +0.420526 0.833393 +0.489854 0.837335 +0.489854 0.837387 +0.489889 0.834192 +0.489889 0.834243 +0.489631 0.830953 +0.489631 0.831005 +0.489054 0.827658 +0.489054 0.827709 +0.488140 0.824353 +0.488140 0.824404 +0.486880 0.821089 +0.486880 0.821140 +0.485275 0.817920 +0.485275 0.817971 +0.483335 0.814901 +0.483335 0.814952 +0.481085 0.812084 +0.481085 0.812136 +0.478558 0.809517 +0.478558 0.809568 +0.475797 0.807237 +0.475797 0.807288 +0.472850 0.805274 +0.472850 0.805325 +0.469770 0.803646 +0.469770 0.803697 +0.466610 0.802360 +0.466610 0.802411 +0.463423 0.801412 +0.463423 0.801463 +0.460255 0.800789 +0.460255 0.800840 +0.457148 0.800471 +0.457148 0.800522 +0.454025 0.800435 +0.454025 0.800486 +0.450808 0.800695 +0.450808 0.800746 +0.447534 0.801275 +0.447534 0.801327 +0.444251 0.802195 +0.444251 0.802246 +0.441008 0.803464 +0.441008 0.803515 +0.437860 0.805080 +0.437860 0.805131 +0.434861 0.807032 +0.434861 0.807084 +0.432063 0.809297 +0.432063 0.809348 +0.429513 0.811841 +0.429513 0.811892 +0.427248 0.814620 +0.427248 0.814672 +0.425298 0.817587 +0.425298 0.817638 +0.423681 0.820688 +0.423681 0.820739 +0.422403 0.823868 +0.422403 0.823920 +0.421461 0.827077 +0.421461 0.827128 +0.420842 0.830266 +0.420842 0.830317 +0.443769 0.868369 +0.446957 0.869317 +0.450125 0.869940 +0.456354 0.870294 +0.459572 0.870034 +0.462845 0.869454 +0.466129 0.868534 +0.469371 0.867265 +0.472519 0.865649 +0.475518 0.863697 +0.478316 0.861432 +0.480867 0.858888 +0.483132 0.856108 +0.485082 0.853142 +0.486699 0.850041 +0.487977 0.846861 +0.488919 0.843652 +0.489537 0.840463 +0.489854 0.837335 +0.489889 0.834192 +0.489631 0.830953 +0.489054 0.827658 +0.488140 0.824353 +0.486880 0.821089 +0.485275 0.817920 +0.483335 0.814901 +0.481085 0.812084 +0.478558 0.809517 +0.475797 0.807237 +0.472850 0.805274 +0.469770 0.803646 +0.466610 0.802360 +0.463423 0.801412 +0.460255 0.800789 +0.454025 0.800435 +0.450808 0.800695 +0.447534 0.801275 +0.444251 0.802195 +0.441008 0.803464 +0.437860 0.805080 +0.434861 0.807032 +0.432063 0.809297 +0.429513 0.811841 +0.427248 0.814620 +0.425298 0.817587 +0.423681 0.820688 +0.422403 0.823868 +0.421461 0.827077 +0.420842 0.830266 +0.420526 0.833393 +0.420490 0.836537 +0.420748 0.839776 +0.421325 0.843071 +0.422239 0.846376 +0.423499 0.849640 +0.425105 0.852809 +0.427044 0.855828 +0.429294 0.858644 +0.431821 0.861212 +0.434583 0.863492 +0.437530 0.865455 +0.440610 0.867083 +0.447534 0.801327 +0.450808 0.800746 +0.454025 0.800486 +0.460255 0.800840 +0.463423 0.801463 +0.466610 0.802411 +0.469770 0.803697 +0.472850 0.805325 +0.475797 0.807288 +0.478558 0.809568 +0.481085 0.812136 +0.483335 0.814952 +0.485275 0.817971 +0.486880 0.821140 +0.488140 0.824404 +0.489054 0.827709 +0.489631 0.831005 +0.489889 0.834243 +0.489854 0.837387 +0.489537 0.840514 +0.488919 0.843703 +0.487977 0.846912 +0.486699 0.850093 +0.485082 0.853193 +0.483132 0.856160 +0.480867 0.858939 +0.478316 0.861483 +0.475518 0.863748 +0.472519 0.865700 +0.469371 0.867317 +0.466129 0.868585 +0.462845 0.869505 +0.459572 0.870086 +0.456354 0.870346 +0.450125 0.869991 +0.446957 0.869368 +0.443769 0.868420 +0.440610 0.867134 +0.437530 0.865506 +0.434583 0.863543 +0.431821 0.861263 +0.429294 0.858696 +0.427044 0.855879 +0.425105 0.852860 +0.423499 0.849692 +0.422239 0.846427 +0.421325 0.843122 +0.420748 0.839827 +0.420490 0.836588 +0.420526 0.833445 +0.420842 0.830317 +0.421461 0.827128 +0.422403 0.823920 +0.423681 0.820739 +0.425298 0.817638 +0.427248 0.814672 +0.429513 0.811892 +0.432063 0.809348 +0.434861 0.807084 +0.437860 0.805131 +0.441008 0.803515 +0.444251 0.802246 + + + + + + + + + + + +

64 0 64 0 1 0 1 2 1 4 3 4 2 4 2 3 5 3 5 6 5 2 7 2 4 8 4 7 9 7 2 10 2 5 11 5 7 12 7 6 13 6 2 14 2 9 15 9 6 16 6 7 17 7 9 18 9 8 19 8 6 20 6 11 21 11 8 22 8 9 23 9 11 24 11 10 25 10 8 26 8 13 27 13 10 28 10 11 29 11 13 30 13 12 31 12 10 32 10 15 33 15 12 34 12 13 35 13 15 36 15 14 37 14 12 38 12 17 39 17 14 40 14 15 41 15 17 42 17 16 43 16 14 44 14 19 45 19 16 46 16 17 47 17 19 48 19 18 49 18 16 50 16 21 51 21 18 52 18 19 53 19 21 54 21 20 55 20 18 56 18 23 57 23 20 58 20 21 59 21 23 60 23 22 61 22 20 62 20 25 63 25 22 64 22 23 65 23 25 66 25 24 67 24 22 68 22 27 69 27 24 70 24 25 71 25 27 72 27 26 73 26 24 74 24 29 75 29 26 76 26 27 77 27 29 78 29 28 79 28 26 80 26 31 81 31 28 82 28 29 83 29 31 84 31 30 85 30 28 86 28 33 87 33 30 88 30 31 89 31 33 90 33 32 91 32 30 92 30 35 93 35 32 94 32 33 95 33 35 96 35 34 97 34 32 98 32 37 99 37 34 100 34 35 101 35 37 102 37 36 103 36 34 104 34 39 105 39 36 106 36 37 107 37 39 108 39 38 109 38 36 110 36 41 111 41 38 112 38 39 113 39 41 114 41 40 115 40 38 116 38 43 117 43 40 118 40 41 119 41 43 120 43 42 121 42 40 122 40 45 123 45 42 124 42 43 125 43 45 126 45 44 127 44 42 128 42 47 129 47 44 130 44 45 131 45 47 132 47 46 133 46 44 134 44 49 135 49 46 136 46 47 137 47 49 138 49 48 139 48 46 140 46 51 141 51 48 142 48 49 143 49 51 144 51 50 145 50 48 146 48 53 147 53 50 148 50 51 149 51 53 150 53 52 151 52 50 152 50 55 153 55 52 154 52 53 155 53 55 156 55 54 157 54 52 158 52 57 159 57 54 160 54 55 161 55 57 162 57 56 163 56 54 164 54 59 165 59 56 166 56 57 167 57 59 168 59 58 169 58 56 170 56 61 171 61 58 172 58 59 173 59 61 174 61 60 175 60 58 176 58 63 177 63 60 178 60 61 179 61 63 180 63 62 181 62 60 182 60 65 183 65 62 184 62 63 185 63 65 186 65 64 187 64 62 188 62 0 189 0 64 190 64 65 191 65 130 192 130 66 193 66 67 194 67 71 195 71 68 196 68 69 197 69 71 198 71 70 199 70 68 200 68 73 201 73 70 202 70 71 203 71 73 204 73 72 205 72 70 206 70 75 207 75 72 208 72 73 209 73 75 210 75 74 211 74 72 212 72 77 213 77 74 214 74 75 215 75 77 216 77 76 217 76 74 218 74 79 219 79 76 220 76 77 221 77 79 222 79 78 223 78 76 224 76 81 225 81 78 226 78 79 227 79 81 228 81 80 229 80 78 230 78 83 231 83 80 232 80 81 233 81 83 234 83 82 235 82 80 236 80 85 237 85 82 238 82 83 239 83 85 240 85 84 241 84 82 242 82 87 243 87 84 244 84 85 245 85 87 246 87 86 247 86 84 248 84 89 249 89 86 250 86 87 251 87 89 252 89 88 253 88 86 254 86 91 255 91 88 256 88 89 257 89 91 258 91 90 259 90 88 260 88 93 261 93 90 262 90 91 263 91 93 264 93 92 265 92 90 266 90 95 267 95 92 268 92 93 269 93 95 270 95 94 271 94 92 272 92 97 273 97 94 274 94 95 275 95 97 276 97 96 277 96 94 278 94 99 279 99 96 280 96 97 281 97 99 282 99 98 283 98 96 284 96 101 285 101 98 286 98 99 287 99 101 288 101 100 289 100 98 290 98 103 291 103 100 292 100 101 293 101 103 294 103 102 295 102 100 296 100 105 297 105 102 298 102 103 299 103 105 300 105 104 301 104 102 302 102 107 303 107 104 304 104 105 305 105 107 306 107 106 307 106 104 308 104 109 309 109 106 310 106 107 311 107 109 312 109 108 313 108 106 314 106 111 315 111 108 316 108 109 317 109 111 318 111 110 319 110 108 320 108 113 321 113 110 322 110 111 323 111 113 324 113 112 325 112 110 326 110 115 327 115 112 328 112 113 329 113 115 330 115 114 331 114 112 332 112 117 333 117 114 334 114 115 335 115 117 336 117 116 337 116 114 338 114 119 339 119 116 340 116 117 341 117 119 342 119 118 343 118 116 344 116 121 345 121 118 346 118 119 347 119 121 348 121 120 349 120 118 350 118 123 351 123 120 352 120 121 353 121 123 354 123 122 355 122 120 356 120 125 357 125 122 358 122 123 359 123 125 360 125 124 361 124 122 362 122 127 363 127 124 364 124 125 365 125 127 366 127 126 367 126 124 368 124 129 369 129 126 370 126 127 371 127 129 372 129 128 373 128 126 374 126 131 375 131 128 376 128 129 377 129 131 378 131 130 379 130 128 380 128 66 381 66 130 382 130 131 383 131 134 384 134 132 385 132 133 386 133 136 387 136 134 388 134 135 389 135 137 390 137 134 391 134 136 392 136 138 393 138 134 394 134 137 395 137 139 396 139 134 397 134 138 398 138 140 399 140 134 400 134 139 401 139 141 402 141 134 403 134 140 404 140 142 405 142 134 406 134 141 407 141 143 408 143 134 409 134 142 410 142 144 411 144 134 412 134 143 413 143 145 414 145 134 415 134 144 416 144 146 417 146 134 418 134 145 419 145 147 420 147 134 421 134 146 422 146 148 423 148 134 424 134 147 425 147 149 426 149 134 427 134 148 428 148 150 429 150 134 430 134 149 431 149 151 432 151 134 433 134 150 434 150 152 435 152 134 436 134 151 437 151 153 438 153 134 439 134 152 440 152 154 441 154 134 442 134 153 443 153 155 444 155 134 445 134 154 446 154 156 447 156 134 448 134 155 449 155 157 450 157 134 451 134 156 452 156 158 453 158 134 454 134 157 455 157 159 456 159 134 457 134 158 458 158 160 459 160 134 460 134 159 461 159 161 462 161 134 463 134 160 464 160 162 465 162 134 466 134 161 467 161 163 468 163 134 469 134 162 470 162 164 471 164 134 472 134 163 473 163 165 474 165 134 475 134 164 476 164 166 477 166 134 478 134 165 479 165 167 480 167 134 481 134 166 482 166 168 483 168 134 484 134 167 485 167 169 486 169 134 487 134 168 488 168 170 489 170 134 490 134 169 491 169 171 492 171 134 493 134 170 494 170 172 495 172 134 496 134 171 497 171 173 498 173 134 499 134 172 500 172 174 501 174 134 502 134 173 503 173 175 504 175 134 505 134 174 506 174 176 507 176 134 508 134 175 509 175 177 510 177 134 511 134 176 512 176 178 513 178 134 514 134 177 515 177 179 516 179 134 517 134 178 518 178 180 519 180 134 520 134 179 521 179 181 522 181 134 523 134 180 524 180 182 525 182 134 526 134 181 527 181 183 528 183 134 529 134 182 530 182 184 531 184 134 532 134 183 533 183 185 534 185 134 535 134 184 536 184 186 537 186 134 538 134 185 539 185 187 540 187 134 541 134 186 542 186 188 543 188 134 544 134 187 545 187 189 546 189 134 547 134 188 548 188 190 549 190 134 550 134 189 551 189 191 552 191 134 553 134 190 554 190 192 555 192 134 556 134 191 557 191 193 558 193 134 559 134 192 560 192 132 561 132 134 562 134 193 563 193 196 564 196 194 565 194 195 566 195 198 567 198 196 568 196 197 569 197 199 570 199 196 571 196 198 572 198 200 573 200 196 574 196 199 575 199 201 576 201 196 577 196 200 578 200 202 579 202 196 580 196 201 581 201 203 582 203 196 583 196 202 584 202 204 585 204 196 586 196 203 587 203 205 588 205 196 589 196 204 590 204 206 591 206 196 592 196 205 593 205 207 594 207 196 595 196 206 596 206 208 597 208 196 598 196 207 599 207 209 600 209 196 601 196 208 602 208 210 603 210 196 604 196 209 605 209 211 606 211 196 607 196 210 608 210 212 609 212 196 610 196 211 611 211 213 612 213 196 613 196 212 614 212 214 615 214 196 616 196 213 617 213 215 618 215 196 619 196 214 620 214 216 621 216 196 622 196 215 623 215 217 624 217 196 625 196 216 626 216 218 627 218 196 628 196 217 629 217 219 630 219 196 631 196 218 632 218 220 633 220 196 634 196 219 635 219 221 636 221 196 637 196 220 638 220 222 639 222 196 640 196 221 641 221 223 642 223 196 643 196 222 644 222 224 645 224 196 646 196 223 647 223 225 648 225 196 649 196 224 650 224 226 651 226 196 652 196 225 653 225 227 654 227 196 655 196 226 656 226 228 657 228 196 658 196 227 659 227 229 660 229 196 661 196 228 662 228 230 663 230 196 664 196 229 665 229 231 666 231 196 667 196 230 668 230 232 669 232 196 670 196 231 671 231 233 672 233 196 673 196 232 674 232 234 675 234 196 676 196 233 677 233 235 678 235 196 679 196 234 680 234 236 681 236 196 682 196 235 683 235 237 684 237 196 685 196 236 686 236 238 687 238 196 688 196 237 689 237 239 690 239 196 691 196 238 692 238 240 693 240 196 694 196 239 695 239 241 696 241 196 697 196 240 698 240 242 699 242 196 700 196 241 701 241 243 702 243 196 703 196 242 704 242 244 705 244 196 706 196 243 707 243 245 708 245 196 709 196 244 710 244 246 711 246 196 712 196 245 713 245 247 714 247 196 715 196 246 716 246 248 717 248 196 718 196 247 719 247 249 720 249 196 721 196 248 722 248 250 723 250 196 724 196 249 725 249 251 726 251 196 727 196 250 728 250 252 729 252 196 730 196 251 731 251 253 732 253 196 733 196 252 734 252 254 735 254 196 736 196 253 737 253 255 738 255 196 739 196 254 740 254 194 741 194 196 742 196 255 743 255

+
+
+ + + + +1.401116 -0.140982 5.000000 +1.396872 -0.100000 5.000000 +1.555890 -0.295756 0.000000 +1.596872 -0.300000 0.000000 +1.596872 -0.300000 5.000000 +1.517437 -0.283548 0.000000 +1.555890 -0.295756 5.000000 +1.517437 -0.283548 5.000000 +1.483545 -0.264794 0.000000 +1.483545 -0.264794 5.000000 +1.455451 -0.241421 0.000000 +1.432078 -0.213327 0.000000 +1.455451 -0.241421 5.000000 +1.432078 -0.213327 5.000000 +1.413324 -0.179435 0.000000 +1.401116 -0.140982 0.000000 +1.413324 -0.179435 5.000000 +1.396872 -0.100000 0.000000 +4.500000 0.300000 3.650000 +4.500000 -0.300000 3.650000 +4.500000 -0.300000 1.350000 +4.500000 0.300000 1.350000 +4.290742 -0.300000 1.369199 +4.290742 0.300000 1.369199 +4.076691 -0.300000 1.430743 +4.076691 0.300000 1.430743 +3.870709 -0.300000 1.537455 +3.870709 0.300000 1.537455 +3.686827 -0.300000 1.686827 +3.686827 0.300000 1.686827 +3.537455 -0.300000 1.870709 +3.537455 0.300000 1.870709 +3.430743 -0.300000 2.076691 +3.430743 0.300000 2.076691 +3.369199 -0.300000 2.290742 +3.369199 0.300000 2.290742 +3.350000 -0.300000 2.500000 +3.350000 0.300000 2.500000 +3.369199 -0.300000 2.709258 +3.369199 0.300000 2.709258 +3.430743 -0.300000 2.923309 +3.430743 0.300000 2.923309 +3.537455 -0.300000 3.129291 +3.537455 0.300000 3.129291 +3.686827 -0.300000 3.313173 +3.686827 0.300000 3.313173 +3.870709 -0.300000 3.462545 +3.870709 0.300000 3.462545 +4.076691 -0.300000 3.569257 +4.076691 0.300000 3.569257 +4.290742 -0.300000 3.630801 +4.290742 0.300000 3.630801 +1.397263 -0.087500 5.000000 +1.400000 0.000000 5.000000 +1.400000 0.000000 0.000000 +1.399316 -0.043771 5.000000 +1.399316 -0.043771 0.000000 +1.397263 -0.087500 0.000000 +1.400000 0.000000 0.000000 +1.400000 0.000000 5.000000 +-1.376628 0.254748 5.000000 +-1.400000 0.000000 5.000000 +-1.400000 0.000000 0.000000 +-1.376628 0.254748 0.000000 +-1.301704 0.515333 5.000000 +-1.301704 0.515333 0.000000 +-1.171794 0.766094 5.000000 +-1.171794 0.766094 0.000000 +-0.989949 0.989949 5.000000 +-0.989949 0.989949 0.000000 +-0.766094 1.171794 5.000000 +-0.766094 1.171794 0.000000 +-0.515333 1.301704 5.000000 +-0.515333 1.301704 0.000000 +-0.254748 1.376628 5.000000 +-0.254748 1.376628 0.000000 +0.000000 1.400000 5.000000 +0.000000 1.400000 0.000000 +0.254748 1.376628 5.000000 +0.254748 1.376628 0.000000 +0.515333 1.301704 5.000000 +0.515333 1.301704 0.000000 +0.766094 1.171794 5.000000 +0.766094 1.171794 0.000000 +0.989949 0.989949 5.000000 +0.989949 0.989949 0.000000 +1.171794 0.766094 5.000000 +1.171794 0.766094 0.000000 +1.301704 0.515333 5.000000 +1.301704 0.515333 0.000000 +1.376628 0.254748 5.000000 +1.376628 0.254748 0.000000 +-2.000000 0.000000 5.000000 +-2.000000 0.000000 0.000000 +1.675583 -1.091981 0.000000 +1.841167 -0.781091 0.000000 +1.841167 -0.781091 5.000000 +1.675583 -1.091981 5.000000 +1.422335 -1.406045 0.000000 +1.422335 -1.406045 5.000000 +1.104042 -1.667660 0.000000 +1.104042 -1.667660 5.000000 +0.738896 -1.858503 0.000000 +0.350869 -1.968982 0.000000 +0.738896 -1.858503 5.000000 +0.350869 -1.968982 5.000000 +-0.035257 -1.999689 0.000000 +-0.035257 -1.999689 5.000000 +-0.398538 -1.959890 0.000000 +-0.398538 -1.959890 5.000000 +-0.748512 -1.854651 0.000000 +-0.748512 -1.854651 5.000000 +-1.091981 -1.675583 0.000000 +-1.406045 -1.422335 0.000000 +-1.091981 -1.675583 5.000000 +-1.406045 -1.422335 5.000000 +-1.667660 -1.104042 0.000000 +-1.667660 -1.104042 5.000000 +-1.858503 -0.738896 0.000000 +-1.858503 -0.738896 5.000000 +-1.968982 -0.350869 0.000000 +-1.968982 -0.350869 5.000000 +1.397263 -0.087500 5.000000 +1.396872 -0.100000 5.000000 +1.690629 -1.068539 5.000000 +1.841167 -0.781091 5.000000 +1.288817 -0.546764 5.000000 +1.485778 -1.338829 5.000000 +1.183440 -0.747977 5.000000 +1.229884 -1.577145 5.000000 +1.040045 -0.937180 5.000000 +0.931497 -1.769834 5.000000 +0.860919 -1.104002 5.000000 +0.603730 -1.906701 5.000000 +0.652048 -1.238884 5.000000 +0.262410 -1.982710 5.000000 +0.422611 -1.334691 5.000000 +-0.076367 -1.998541 5.000000 +0.183687 -1.387897 5.000000 +-0.398538 -1.959890 5.000000 +-0.053457 -1.398979 5.000000 +-0.710219 -1.869649 5.000000 +-0.278977 -1.371923 5.000000 +-1.015909 -1.722768 5.000000 +-0.497153 -1.308755 5.000000 +-1.300437 -1.519494 5.000000 +-0.711136 -1.205937 5.000000 +-1.548721 -1.265489 5.000000 +-0.910306 -1.063646 5.000000 +-1.748157 -0.971569 5.000000 +-1.084105 -0.885842 5.000000 +-1.890657 -0.652241 5.000000 +-1.223710 -0.680098 5.000000 +-1.973678 -0.323412 5.000000 +-1.323460 -0.456568 5.000000 +-2.000000 0.000000 5.000000 +-1.381575 -0.226388 5.000000 +-1.970700 0.341092 5.000000 +-1.400000 0.000000 5.000000 +-1.877667 0.688743 5.000000 +-1.376628 0.254748 5.000000 +-1.717326 1.025082 5.000000 +-1.301704 0.515333 5.000000 +-1.492908 1.330874 5.000000 +-1.171794 0.766094 5.000000 +-1.214793 1.588797 5.000000 +-0.989949 0.989949 5.000000 +-0.899003 1.786559 5.000000 +-0.766094 1.171794 5.000000 +-0.564276 1.918748 5.000000 +-0.515333 1.301704 5.000000 +-0.228774 1.986872 5.000000 +-0.254748 1.376628 5.000000 +0.113430 1.996781 5.000000 +0.000000 1.400000 5.000000 +0.469441 1.944126 5.000000 +0.254748 1.376628 5.000000 +0.821913 1.823310 5.000000 +0.515333 1.301704 5.000000 +1.151369 1.635344 5.000000 +0.766094 1.171794 5.000000 +1.439412 1.388558 5.000000 +1.671998 1.097462 5.000000 +0.989949 0.989949 5.000000 +1.841608 0.780052 5.000000 +1.171794 0.766094 5.000000 +1.947662 0.454545 5.000000 +1.301704 0.515333 5.000000 +6.000000 -0.300000 5.000000 +6.000000 0.300000 5.000000 +1.596872 -0.300000 5.000000 +2.142429 0.300000 5.000000 +2.078438 0.310513 5.000000 +1.972444 0.394619 5.000000 +1.376628 0.254748 5.000000 +2.018112 0.343330 5.000000 +1.400000 0.000000 5.000000 +1.560479 -0.296661 5.000000 +1.523253 -0.285958 5.000000 +1.487430 -0.267399 5.000000 +1.455451 -0.241421 5.000000 +1.429473 -0.209442 5.000000 +1.410914 -0.173619 5.000000 +1.400211 -0.136393 5.000000 +1.400211 -0.136393 0.000000 +1.396872 -0.100000 0.000000 +1.288817 -0.546764 0.000000 +1.841167 -0.781091 0.000000 +1.183440 -0.747977 0.000000 +1.690629 -1.068539 0.000000 +1.040045 -0.937180 0.000000 +1.485778 -1.338829 0.000000 +0.860919 -1.104002 0.000000 +1.229884 -1.577145 0.000000 +0.652048 -1.238884 0.000000 +0.931497 -1.769834 0.000000 +0.422611 -1.334691 0.000000 +0.603730 -1.906701 0.000000 +0.183687 -1.387897 0.000000 +0.262410 -1.982710 0.000000 +-0.053457 -1.398979 0.000000 +-0.076367 -1.998541 0.000000 +-0.278977 -1.371923 0.000000 +-0.398538 -1.959890 0.000000 +-0.497153 -1.308755 0.000000 +-0.710219 -1.869649 0.000000 +-0.711136 -1.205937 0.000000 +-1.015909 -1.722768 0.000000 +-0.910306 -1.063646 0.000000 +-1.300437 -1.519494 0.000000 +-1.084105 -0.885842 0.000000 +-1.548721 -1.265489 0.000000 +-1.223710 -0.680098 0.000000 +-1.748157 -0.971569 0.000000 +-1.323460 -0.456568 0.000000 +-1.890657 -0.652241 0.000000 +-1.381575 -0.226388 0.000000 +-1.973678 -0.323412 0.000000 +-1.400000 0.000000 0.000000 +-2.000000 0.000000 0.000000 +-1.376628 0.254748 0.000000 +-1.970700 0.341092 0.000000 +-1.301704 0.515333 0.000000 +-1.877667 0.688743 0.000000 +-1.171794 0.766094 0.000000 +-1.717326 1.025082 0.000000 +-0.989949 0.989949 0.000000 +-1.492908 1.330874 0.000000 +-0.766094 1.171794 0.000000 +-1.214793 1.588797 0.000000 +-0.515333 1.301704 0.000000 +-0.899003 1.786559 0.000000 +-0.254748 1.376628 0.000000 +-0.564276 1.918748 0.000000 +0.000000 1.400000 0.000000 +-0.228774 1.986872 0.000000 +0.254748 1.376628 0.000000 +0.113430 1.996781 0.000000 +0.515333 1.301704 0.000000 +0.469441 1.944126 0.000000 +0.766094 1.171794 0.000000 +0.821913 1.823310 0.000000 +1.151369 1.635344 0.000000 +0.989949 0.989949 0.000000 +1.439412 1.388558 0.000000 +1.171794 0.766094 0.000000 +1.671998 1.097462 0.000000 +1.301704 0.515333 0.000000 +1.841608 0.780052 0.000000 +1.376628 0.254748 0.000000 +6.000000 0.300000 0.000000 +6.000000 -0.300000 0.000000 +2.142429 0.300000 0.000000 +2.078438 0.310513 0.000000 +2.018112 0.343330 0.000000 +1.947662 0.454545 0.000000 +1.400000 0.000000 0.000000 +1.972444 0.394619 0.000000 +1.397263 -0.087500 0.000000 +1.596872 -0.300000 0.000000 +1.560479 -0.296661 0.000000 +1.523253 -0.285958 0.000000 +1.487430 -0.267399 0.000000 +1.455451 -0.241421 0.000000 +1.429473 -0.209442 0.000000 +1.410914 -0.173619 0.000000 +1.912074 0.586492 5.000000 +1.947662 0.454545 5.000000 +-2.000000 0.000000 0.000000 +-2.000000 0.000000 5.000000 +-1.995331 0.136582 0.000000 +-1.931581 0.518646 0.000000 +-1.995331 0.136582 5.000000 +-1.931581 0.518646 5.000000 +-1.788191 0.895753 0.000000 +-1.566699 1.243163 0.000000 +-1.788191 0.895753 5.000000 +-1.566699 1.243163 5.000000 +-1.278719 1.537816 0.000000 +-1.278719 1.537816 5.000000 +-0.944069 1.763160 0.000000 +-0.944069 1.763160 5.000000 +-0.586492 1.912074 0.000000 +-0.586492 1.912074 5.000000 +-0.228774 1.986872 0.000000 +-0.228774 1.986872 5.000000 +0.136582 1.995331 0.000000 +0.136582 1.995331 5.000000 +0.518646 1.931581 0.000000 +0.518646 1.931581 5.000000 +0.895753 1.788191 0.000000 +0.895753 1.788191 5.000000 +1.243163 1.566699 0.000000 +1.243163 1.566699 5.000000 +1.537816 1.278719 0.000000 +1.537816 1.278719 5.000000 +1.763160 0.944069 0.000000 +1.912074 0.586492 0.000000 +1.763160 0.944069 5.000000 +1.947662 0.454545 0.000000 +-1.378288 -0.245608 0.000000 +-1.400000 0.000000 0.000000 +1.288817 -0.546764 5.000000 +1.288817 -0.546764 0.000000 +1.172908 -0.764387 5.000000 +1.172908 -0.764387 0.000000 +0.995634 -0.984232 5.000000 +0.995634 -0.984232 0.000000 +0.772830 -1.167362 5.000000 +0.772830 -1.167362 0.000000 +0.517227 -1.300952 5.000000 +0.517227 -1.300952 0.000000 +0.245608 -1.378288 5.000000 +0.245608 -1.378288 0.000000 +-0.024680 -1.399782 5.000000 +-0.024680 -1.399782 0.000000 +-0.278977 -1.371923 5.000000 +-0.523959 -1.298256 5.000000 +-0.278977 -1.371923 0.000000 +-0.523959 -1.298256 0.000000 +-0.764387 -1.172908 5.000000 +-0.984232 -0.995634 5.000000 +-0.764387 -1.172908 0.000000 +-0.984232 -0.995634 0.000000 +-1.167362 -0.772830 5.000000 +-1.300952 -0.517227 5.000000 +-1.167362 -0.772830 0.000000 +-1.300952 -0.517227 0.000000 +-1.378288 -0.245608 5.000000 +-1.400000 0.000000 5.000000 +3.537455 0.300000 3.129291 +5.129291 0.300000 3.462545 +2.142429 0.300000 5.000000 +4.923309 0.300000 3.569257 +4.709258 0.300000 3.630801 +4.500000 0.300000 3.650000 +4.290742 0.300000 3.630801 +4.076691 0.300000 3.569257 +3.870709 0.300000 3.462545 +3.686827 0.300000 3.313173 +5.313173 0.300000 3.313173 +6.000000 0.300000 5.000000 +6.181963 0.300000 4.983305 +6.368095 0.300000 4.929788 +6.547210 0.300000 4.836996 +6.707107 0.300000 4.707107 +6.836996 0.300000 4.547210 +6.929788 0.300000 4.368095 +6.983305 0.300000 4.181963 +5.462545 0.300000 3.129291 +7.000000 0.300000 4.000000 +5.569257 0.300000 2.923309 +5.630801 0.300000 2.709258 +5.650000 0.300000 2.500000 +5.630801 0.300000 2.290742 +5.569257 0.300000 2.076691 +5.462545 0.300000 1.870709 +5.313173 0.300000 1.686827 +7.000000 0.300000 1.000000 +6.983305 0.300000 0.818037 +6.929788 0.300000 0.631905 +6.836996 0.300000 0.452790 +6.707107 0.300000 0.292893 +6.547210 0.300000 0.163004 +6.368095 0.300000 0.070212 +6.181963 0.300000 0.016695 +5.129291 0.300000 1.537455 +4.923309 0.300000 1.430743 +6.000000 0.300000 0.000000 +4.709258 0.300000 1.369199 +4.500000 0.300000 1.350000 +4.290742 0.300000 1.369199 +4.076691 0.300000 1.430743 +3.870709 0.300000 1.537455 +3.686827 0.300000 1.686827 +3.537455 0.300000 1.870709 +3.430743 0.300000 2.076691 +2.142429 0.300000 0.000000 +3.369199 0.300000 2.290742 +3.350000 0.300000 2.500000 +3.369199 0.300000 2.709258 +3.430743 0.300000 2.923309 +6.368095 -0.300000 4.929788 +6.181963 -0.300000 4.983305 +4.923309 -0.300000 3.569257 +6.000000 -0.300000 5.000000 +4.709258 -0.300000 3.630801 +4.500000 -0.300000 3.650000 +4.290742 -0.300000 3.630801 +4.076691 -0.300000 3.569257 +3.870709 -0.300000 3.462545 +3.686827 -0.300000 3.313173 +3.537455 -0.300000 3.129291 +1.596872 -0.300000 5.000000 +3.430743 -0.300000 2.923309 +3.369199 -0.300000 2.709258 +3.350000 -0.300000 2.500000 +3.369199 -0.300000 2.290742 +3.430743 -0.300000 2.076691 +3.537455 -0.300000 1.870709 +3.686827 -0.300000 1.686827 +5.129291 -0.300000 3.462545 +3.870709 -0.300000 1.537455 +1.596872 -0.300000 0.000000 +4.076691 -0.300000 1.430743 +4.290742 -0.300000 1.369199 +4.500000 -0.300000 1.350000 +4.709258 -0.300000 1.369199 +4.923309 -0.300000 1.430743 +5.129291 -0.300000 1.537455 +5.313173 -0.300000 1.686827 +6.000000 -0.300000 0.000000 +6.181963 -0.300000 0.016695 +6.368095 -0.300000 0.070212 +6.547210 -0.300000 0.163004 +6.707107 -0.300000 0.292893 +6.836996 -0.300000 0.452790 +6.929788 -0.300000 0.631905 +6.983305 -0.300000 0.818037 +5.462545 -0.300000 1.870709 +7.000000 -0.300000 1.000000 +5.569257 -0.300000 2.076691 +5.630801 -0.300000 2.290742 +5.650000 -0.300000 2.500000 +5.630801 -0.300000 2.709258 +5.569257 -0.300000 2.923309 +5.462545 -0.300000 3.129291 +5.313173 -0.300000 3.313173 +7.000000 -0.300000 4.000000 +6.983305 -0.300000 4.181963 +6.929788 -0.300000 4.368095 +6.836996 -0.300000 4.547210 +6.707107 -0.300000 4.707107 +6.547210 -0.300000 4.836996 +7.000000 -0.300000 4.000000 +7.000000 -0.300000 1.000000 +7.000000 0.300000 1.000000 +7.000000 0.300000 4.000000 +1.841167 -0.781091 5.000000 +1.841167 -0.781091 0.000000 +1.288817 -0.546764 0.000000 +1.288817 -0.546764 5.000000 +4.500000 -0.300000 3.650000 +4.500000 0.300000 3.650000 +4.500000 0.300000 1.350000 +4.500000 -0.300000 1.350000 +4.709258 0.300000 1.369199 +4.709258 -0.300000 1.369199 +4.923309 0.300000 1.430743 +4.923309 -0.300000 1.430743 +5.129291 0.300000 1.537455 +5.129291 -0.300000 1.537455 +5.313173 0.300000 1.686827 +5.313173 -0.300000 1.686827 +5.462545 0.300000 1.870709 +5.462545 -0.300000 1.870709 +5.569257 0.300000 2.076691 +5.569257 -0.300000 2.076691 +5.630801 0.300000 2.290742 +5.630801 -0.300000 2.290742 +5.650000 0.300000 2.500000 +5.650000 -0.300000 2.500000 +5.630801 0.300000 2.709258 +5.630801 -0.300000 2.709258 +5.569257 0.300000 2.923309 +5.569257 -0.300000 2.923309 +5.462545 0.300000 3.129291 +5.313173 0.300000 3.313173 +5.462545 -0.300000 3.129291 +5.313173 -0.300000 3.313173 +5.129291 0.300000 3.462545 +5.129291 -0.300000 3.462545 +4.923309 0.300000 3.569257 +4.923309 -0.300000 3.569257 +4.709258 0.300000 3.630801 +4.709258 -0.300000 3.630801 +7.000000 -0.300000 4.000000 +7.000000 0.300000 4.000000 +6.000000 0.300000 5.000000 +6.000000 -0.300000 5.000000 +6.204909 0.300000 4.978781 +6.397177 0.300000 4.917742 +6.204909 -0.300000 4.978781 +6.566635 0.300000 4.823969 +6.397177 -0.300000 4.917742 +6.566635 -0.300000 4.823969 +6.707107 0.300000 4.707107 +6.707107 -0.300000 4.707107 +6.823969 0.300000 4.566635 +6.823969 -0.300000 4.566635 +6.917742 0.300000 4.397177 +6.917742 -0.300000 4.397177 +6.978781 0.300000 4.204909 +6.978781 -0.300000 4.204909 +6.000000 -0.300000 0.000000 +6.000000 0.300000 0.000000 +7.000000 0.300000 1.000000 +7.000000 -0.300000 1.000000 +6.978781 0.300000 0.795090 +6.978781 -0.300000 0.795090 +6.917742 0.300000 0.602823 +6.917742 -0.300000 0.602823 +6.823969 0.300000 0.433365 +6.707107 0.300000 0.292893 +6.823969 -0.300000 0.433365 +6.707107 -0.300000 0.292893 +6.566635 0.300000 0.176031 +6.566635 -0.300000 0.176031 +6.397177 0.300000 0.082258 +6.204909 0.300000 0.021219 +6.397177 -0.300000 0.082258 +6.204909 -0.300000 0.021219 +1.396872 -0.100000 5.000000 +1.396970 -0.093747 5.000000 +1.397263 -0.087500 5.000000 +1.397263 -0.087500 0.000000 +1.396970 -0.093747 0.000000 +1.396872 -0.100000 0.000000 +1.952645 0.436895 0.000000 +1.947662 0.454545 0.000000 +2.124108 0.300841 5.000000 +2.142429 0.300000 5.000000 +2.142429 0.300000 0.000000 +2.124108 0.300841 0.000000 +2.084510 0.308570 5.000000 +2.084510 0.308570 0.000000 +2.048696 0.323325 5.000000 +2.018112 0.343330 5.000000 +2.048696 0.323325 0.000000 +1.991680 0.368567 5.000000 +2.018112 0.343330 0.000000 +1.969171 0.400090 5.000000 +1.991680 0.368567 0.000000 +1.969171 0.400090 0.000000 +1.952645 0.436895 5.000000 +1.947662 0.454545 5.000000 + + + + + + + + + + + +-1.000000 0.000000 0.000000 +-0.978781 -0.204909 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.204909 -0.978781 0.000000 +0.000000 -1.000000 0.000000 +-0.204909 -0.978781 0.000000 +-0.204909 -0.978781 0.000000 +0.000000 -1.000000 0.000000 +-0.204909 -0.978781 0.000000 +-0.397177 -0.917742 0.000000 +-0.204909 -0.978781 0.000000 +-0.397177 -0.917742 0.000000 +-0.397177 -0.917742 0.000000 +-0.204909 -0.978781 0.000000 +-0.566635 -0.823969 0.000000 +-0.397177 -0.917742 0.000000 +-0.397177 -0.917742 0.000000 +-0.566635 -0.823969 0.000000 +-0.566635 -0.823969 0.000000 +-0.397177 -0.917742 0.000000 +-0.707107 -0.707107 0.000000 +-0.566635 -0.823969 0.000000 +-0.566635 -0.823969 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.566635 -0.823969 0.000000 +-0.707107 -0.707107 0.000000 +-0.823969 -0.566635 0.000000 +-0.707107 -0.707107 0.000000 +-0.823969 -0.566635 0.000000 +-0.823969 -0.566635 0.000000 +-0.707107 -0.707107 0.000000 +-0.917742 -0.397177 0.000000 +-0.823969 -0.566635 0.000000 +-0.823969 -0.566635 0.000000 +-0.917742 -0.397177 0.000000 +-0.917742 -0.397177 0.000000 +-0.823969 -0.566635 0.000000 +-0.917742 -0.397177 0.000000 +-0.978781 -0.204909 0.000000 +-0.917742 -0.397177 0.000000 +-0.978781 -0.204909 0.000000 +-0.978781 -0.204909 0.000000 +-0.917742 -0.397177 0.000000 +-0.978781 -0.204909 0.000000 +-1.000000 0.000000 0.000000 +-0.978781 -0.204909 0.000000 +0.181963 0.000000 -0.983305 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.181963 0.000000 0.983305 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.181963 0.000000 0.983305 +0.181963 0.000000 0.983305 +0.000000 0.000000 1.000000 +0.368095 0.000000 0.929788 +0.181963 0.000000 0.983305 +0.181963 0.000000 0.983305 +0.368095 0.000000 0.929788 +0.368095 0.000000 0.929788 +0.181963 0.000000 0.983305 +0.547210 0.000000 0.836995 +0.368095 0.000000 0.929788 +0.368095 0.000000 0.929788 +0.547210 0.000000 0.836995 +0.547210 0.000000 0.836995 +0.368095 0.000000 0.929788 +0.707107 0.000000 0.707107 +0.547210 0.000000 0.836995 +0.547210 0.000000 0.836995 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.547210 0.000000 0.836995 +0.836995 0.000000 0.547210 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.836995 0.000000 0.547210 +0.836995 0.000000 0.547210 +0.707107 0.000000 0.707107 +0.929788 0.000000 0.368095 +0.836995 0.000000 0.547210 +0.836995 0.000000 0.547210 +0.929788 0.000000 0.368095 +0.929788 0.000000 0.368095 +0.836995 0.000000 0.547210 +0.983305 0.000000 0.181963 +0.929788 0.000000 0.368095 +0.929788 0.000000 0.368095 +0.983305 0.000000 0.181963 +0.983305 0.000000 0.181963 +0.929788 0.000000 0.368095 +1.000000 0.000000 0.000000 +0.983305 0.000000 0.181963 +0.983305 0.000000 0.181963 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.000000 0.181963 +0.983305 0.000000 -0.181963 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.000000 -0.181963 +0.983305 0.000000 -0.181963 +1.000000 0.000000 0.000000 +0.929788 0.000000 -0.368095 +0.983305 0.000000 -0.181963 +0.983305 0.000000 -0.181963 +0.929788 0.000000 -0.368095 +0.929788 0.000000 -0.368095 +0.983305 0.000000 -0.181963 +0.836995 0.000000 -0.547210 +0.929788 0.000000 -0.368095 +0.929788 0.000000 -0.368095 +0.836995 0.000000 -0.547210 +0.836995 0.000000 -0.547210 +0.929788 0.000000 -0.368095 +0.707107 0.000000 -0.707107 +0.836995 0.000000 -0.547210 +0.836995 0.000000 -0.547210 +0.707107 0.000000 -0.707107 +0.707107 0.000000 -0.707107 +0.836995 0.000000 -0.547210 +0.547210 0.000000 -0.836995 +0.707107 0.000000 -0.707107 +0.707107 0.000000 -0.707107 +0.547210 0.000000 -0.836995 +0.547210 0.000000 -0.836995 +0.707107 0.000000 -0.707107 +0.368095 0.000000 -0.929788 +0.547210 0.000000 -0.836995 +0.547210 0.000000 -0.836995 +0.368095 0.000000 -0.929788 +0.368095 0.000000 -0.929788 +0.547210 0.000000 -0.836995 +0.181963 0.000000 -0.983305 +0.368095 0.000000 -0.929788 +0.368095 0.000000 -0.929788 +0.181963 0.000000 -0.983305 +0.181963 0.000000 -0.983305 +0.368095 0.000000 -0.929788 +0.000000 0.000000 -1.000000 +0.181963 0.000000 -0.983305 +0.181963 0.000000 -0.983305 +-0.999511 0.031265 0.000000 +-0.998045 0.062500 0.000000 +-0.999511 0.031265 0.000000 +-0.999511 0.031265 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.999511 0.031265 0.000000 +-0.999511 0.031265 0.000000 +-1.000000 0.000000 0.000000 +-0.998045 0.062500 0.000000 +-0.999511 0.031265 0.000000 +-0.998045 0.062500 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.984491 -0.175434 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.920584 -0.390545 0.000000 +0.837791 -0.545991 0.000000 +0.920584 -0.390545 0.000000 +0.837791 -0.545991 0.000000 +0.837791 -0.545991 0.000000 +0.920584 -0.390545 0.000000 +0.711167 -0.703023 0.000000 +0.837791 -0.545991 0.000000 +0.837791 -0.545991 0.000000 +0.711167 -0.703023 0.000000 +0.711167 -0.703023 0.000000 +0.837791 -0.545991 0.000000 +0.552021 -0.833830 0.000000 +0.711167 -0.703023 0.000000 +0.711167 -0.703023 0.000000 +0.552021 -0.833830 0.000000 +0.552021 -0.833830 0.000000 +0.711167 -0.703023 0.000000 +0.369448 -0.929251 0.000000 +0.552021 -0.833830 0.000000 +0.552021 -0.833830 0.000000 +0.369448 -0.929251 0.000000 +0.369448 -0.929251 0.000000 +0.552021 -0.833830 0.000000 +0.369448 -0.929251 0.000000 +0.175434 -0.984491 0.000000 +0.369448 -0.929251 0.000000 +0.175434 -0.984491 0.000000 +0.175434 -0.984491 0.000000 +0.369448 -0.929251 0.000000 +-0.017629 -0.999845 0.000000 +0.175434 -0.984491 0.000000 +0.175434 -0.984491 0.000000 +-0.017629 -0.999845 0.000000 +-0.017629 -0.999845 0.000000 +0.175434 -0.984491 0.000000 +-0.199269 -0.979945 0.000000 +-0.017629 -0.999845 0.000000 +-0.017629 -0.999845 0.000000 +-0.199269 -0.979945 0.000000 +-0.199269 -0.979945 0.000000 +-0.017629 -0.999845 0.000000 +-0.374256 -0.927325 0.000000 +-0.199269 -0.979945 0.000000 +-0.199269 -0.979945 0.000000 +-0.374256 -0.927325 0.000000 +-0.374256 -0.927325 0.000000 +-0.199269 -0.979945 0.000000 +-0.545991 -0.837791 0.000000 +-0.374256 -0.927325 0.000000 +-0.374256 -0.927325 0.000000 +-0.545991 -0.837791 0.000000 +-0.545991 -0.837791 0.000000 +-0.374256 -0.927325 0.000000 +-0.545991 -0.837791 0.000000 +-0.703023 -0.711167 0.000000 +-0.545991 -0.837791 0.000000 +-0.703023 -0.711167 0.000000 +-0.703023 -0.711167 0.000000 +-0.545991 -0.837791 0.000000 +-0.833830 -0.552021 0.000000 +-0.703023 -0.711167 0.000000 +-0.703023 -0.711167 0.000000 +-0.833830 -0.552021 0.000000 +-0.833830 -0.552021 0.000000 +-0.703023 -0.711167 0.000000 +-0.929251 -0.369448 0.000000 +-0.833830 -0.552021 0.000000 +-0.833830 -0.552021 0.000000 +-0.929251 -0.369448 0.000000 +-0.929251 -0.369448 0.000000 +-0.833830 -0.552021 0.000000 +-0.984491 -0.175434 0.000000 +-0.929251 -0.369448 0.000000 +-0.929251 -0.369448 0.000000 +-0.984491 -0.175434 0.000000 +-0.984491 -0.175434 0.000000 +-0.929251 -0.369448 0.000000 +-1.000000 0.000000 0.000000 +-0.984491 -0.175434 0.000000 +-0.984491 -0.175434 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.973831 0.227273 0.000000 +0.956037 0.293246 0.000000 +0.973831 0.227273 0.000000 +-0.997665 0.068291 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.997665 0.068291 0.000000 +-0.997665 0.068291 0.000000 +-1.000000 0.000000 0.000000 +-0.997665 0.068291 0.000000 +-0.965791 0.259323 0.000000 +-0.997665 0.068291 0.000000 +-0.965791 0.259323 0.000000 +-0.965791 0.259323 0.000000 +-0.997665 0.068291 0.000000 +-0.894095 0.447876 0.000000 +-0.965791 0.259323 0.000000 +-0.965791 0.259323 0.000000 +-0.894095 0.447876 0.000000 +-0.894095 0.447876 0.000000 +-0.965791 0.259323 0.000000 +-0.894095 0.447876 0.000000 +-0.783349 0.621582 0.000000 +-0.894095 0.447876 0.000000 +-0.783349 0.621582 0.000000 +-0.783349 0.621582 0.000000 +-0.894095 0.447876 0.000000 +-0.639360 0.768908 0.000000 +-0.783349 0.621582 0.000000 +-0.783349 0.621582 0.000000 +-0.639360 0.768908 0.000000 +-0.639360 0.768908 0.000000 +-0.783349 0.621582 0.000000 +-0.472034 0.881580 0.000000 +-0.639360 0.768908 0.000000 +-0.639360 0.768908 0.000000 +-0.472034 0.881580 0.000000 +-0.472034 0.881580 0.000000 +-0.639360 0.768908 0.000000 +-0.293246 0.956037 0.000000 +-0.472034 0.881580 0.000000 +-0.472034 0.881580 0.000000 +-0.293246 0.956037 0.000000 +-0.293246 0.956037 0.000000 +-0.472034 0.881580 0.000000 +-0.114387 0.993436 0.000000 +-0.293246 0.956037 0.000000 +-0.293246 0.956037 0.000000 +-0.114387 0.993436 0.000000 +-0.114387 0.993436 0.000000 +-0.293246 0.956037 0.000000 +0.068291 0.997665 0.000000 +-0.114387 0.993436 0.000000 +-0.114387 0.993436 0.000000 +0.068291 0.997665 0.000000 +0.068291 0.997665 0.000000 +-0.114387 0.993436 0.000000 +0.259323 0.965791 0.000000 +0.068291 0.997665 0.000000 +0.068291 0.997665 0.000000 +0.259323 0.965791 0.000000 +0.259323 0.965791 0.000000 +0.068291 0.997665 0.000000 +0.447876 0.894095 0.000000 +0.259323 0.965791 0.000000 +0.259323 0.965791 0.000000 +0.447876 0.894095 0.000000 +0.447876 0.894095 0.000000 +0.259323 0.965791 0.000000 +0.621582 0.783349 0.000000 +0.447876 0.894095 0.000000 +0.447876 0.894095 0.000000 +0.621582 0.783349 0.000000 +0.621582 0.783349 0.000000 +0.447876 0.894095 0.000000 +0.768908 0.639360 0.000000 +0.621582 0.783349 0.000000 +0.621582 0.783349 0.000000 +0.768908 0.639360 0.000000 +0.768908 0.639360 0.000000 +0.621582 0.783349 0.000000 +0.881580 0.472034 0.000000 +0.768908 0.639360 0.000000 +0.768908 0.639360 0.000000 +0.881580 0.472034 0.000000 +0.881580 0.472034 0.000000 +0.768908 0.639360 0.000000 +0.881580 0.472034 0.000000 +0.956037 0.293246 0.000000 +0.881580 0.472034 0.000000 +0.956037 0.293246 0.000000 +0.956037 0.293246 0.000000 +0.881580 0.472034 0.000000 +0.956037 0.293246 0.000000 +0.973831 0.227273 0.000000 +0.956037 0.293246 0.000000 +1.000000 0.000000 0.000000 +0.984491 0.175434 0.000000 +1.000000 0.000000 0.000000 +-0.837791 0.545991 0.000000 +-0.920584 0.390545 0.000000 +-0.920584 0.390545 0.000000 +-0.837791 0.545991 0.000000 +-0.837791 0.545991 0.000000 +-0.920584 0.390545 0.000000 +-0.711167 0.703023 0.000000 +-0.837791 0.545991 0.000000 +-0.837791 0.545991 0.000000 +-0.711167 0.703023 0.000000 +-0.711167 0.703023 0.000000 +-0.837791 0.545991 0.000000 +-0.552021 0.833830 0.000000 +-0.711167 0.703023 0.000000 +-0.711167 0.703023 0.000000 +-0.552021 0.833830 0.000000 +-0.552021 0.833830 0.000000 +-0.711167 0.703023 0.000000 +-0.369448 0.929251 0.000000 +-0.552021 0.833830 0.000000 +-0.552021 0.833830 0.000000 +-0.369448 0.929251 0.000000 +-0.369448 0.929251 0.000000 +-0.552021 0.833830 0.000000 +-0.175434 0.984491 0.000000 +-0.369448 0.929251 0.000000 +-0.369448 0.929251 0.000000 +-0.175434 0.984491 0.000000 +-0.175434 0.984491 0.000000 +-0.369448 0.929251 0.000000 +0.017629 0.999845 0.000000 +-0.175434 0.984491 0.000000 +-0.175434 0.984491 0.000000 +0.017629 0.999845 0.000000 +0.017629 0.999845 0.000000 +-0.175434 0.984491 0.000000 +0.199269 0.979945 0.000000 +0.017629 0.999845 0.000000 +0.017629 0.999845 0.000000 +0.199269 0.979945 0.000000 +0.199269 0.979945 0.000000 +0.017629 0.999845 0.000000 +0.199269 0.979945 0.000000 +0.374256 0.927325 0.000000 +0.199269 0.979945 0.000000 +0.374256 0.927325 0.000000 +0.374256 0.927325 0.000000 +0.199269 0.979945 0.000000 +0.545991 0.837791 0.000000 +0.374256 0.927325 0.000000 +0.374256 0.927325 0.000000 +0.545991 0.837791 0.000000 +0.545991 0.837791 0.000000 +0.374256 0.927325 0.000000 +0.545991 0.837791 0.000000 +0.703023 0.711167 0.000000 +0.545991 0.837791 0.000000 +0.703023 0.711167 0.000000 +0.703023 0.711167 0.000000 +0.545991 0.837791 0.000000 +0.833830 0.552021 0.000000 +0.703023 0.711167 0.000000 +0.703023 0.711167 0.000000 +0.833830 0.552021 0.000000 +0.833830 0.552021 0.000000 +0.703023 0.711167 0.000000 +0.833830 0.552021 0.000000 +0.929251 0.369448 0.000000 +0.833830 0.552021 0.000000 +0.929251 0.369448 0.000000 +0.929251 0.369448 0.000000 +0.833830 0.552021 0.000000 +0.984491 0.175434 0.000000 +0.929251 0.369448 0.000000 +0.929251 0.369448 0.000000 +0.984491 0.175434 0.000000 +0.984491 0.175434 0.000000 +0.929251 0.369448 0.000000 +0.984491 0.175434 0.000000 +1.000000 0.000000 0.000000 +0.984491 0.175434 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.390545 0.920584 0.000000 +0.390545 0.920584 0.000000 +0.390545 0.920584 0.000000 +0.390545 0.920584 0.000000 +0.390545 0.920584 0.000000 +0.390545 0.920584 0.000000 +-0.181963 0.000000 -0.983305 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.181963 0.000000 0.983305 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.181963 0.000000 0.983305 +-0.181963 0.000000 0.983305 +0.000000 0.000000 1.000000 +-0.368095 0.000000 0.929788 +-0.181963 0.000000 0.983305 +-0.181963 0.000000 0.983305 +-0.368095 0.000000 0.929788 +-0.368095 0.000000 0.929788 +-0.181963 0.000000 0.983305 +-0.547210 0.000000 0.836995 +-0.368095 0.000000 0.929788 +-0.368095 0.000000 0.929788 +-0.547210 0.000000 0.836995 +-0.547210 0.000000 0.836995 +-0.368095 0.000000 0.929788 +-0.707107 0.000000 0.707107 +-0.547210 0.000000 0.836995 +-0.547210 0.000000 0.836995 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.547210 0.000000 0.836995 +-0.836995 0.000000 0.547210 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.836995 0.000000 0.547210 +-0.836995 0.000000 0.547210 +-0.707107 0.000000 0.707107 +-0.929788 0.000000 0.368095 +-0.836995 0.000000 0.547210 +-0.836995 0.000000 0.547210 +-0.929788 0.000000 0.368095 +-0.929788 0.000000 0.368095 +-0.836995 0.000000 0.547210 +-0.983305 0.000000 0.181963 +-0.929788 0.000000 0.368095 +-0.929788 0.000000 0.368095 +-0.983305 0.000000 0.181963 +-0.983305 0.000000 0.181963 +-0.929788 0.000000 0.368095 +-1.000000 0.000000 0.000000 +-0.983305 0.000000 0.181963 +-0.983305 0.000000 0.181963 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.000000 0.181963 +-0.983305 0.000000 -0.181963 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.000000 -0.181963 +-0.983305 0.000000 -0.181963 +-1.000000 0.000000 0.000000 +-0.929788 0.000000 -0.368095 +-0.983305 0.000000 -0.181963 +-0.983305 0.000000 -0.181963 +-0.929788 0.000000 -0.368095 +-0.929788 0.000000 -0.368095 +-0.983305 0.000000 -0.181963 +-0.836995 0.000000 -0.547210 +-0.929788 0.000000 -0.368095 +-0.929788 0.000000 -0.368095 +-0.836995 0.000000 -0.547210 +-0.836995 0.000000 -0.547210 +-0.929788 0.000000 -0.368095 +-0.836995 0.000000 -0.547210 +-0.707107 0.000000 -0.707107 +-0.836995 0.000000 -0.547210 +-0.707107 0.000000 -0.707107 +-0.707107 0.000000 -0.707107 +-0.836995 0.000000 -0.547210 +-0.547210 0.000000 -0.836995 +-0.707107 0.000000 -0.707107 +-0.707107 0.000000 -0.707107 +-0.547210 0.000000 -0.836995 +-0.547210 0.000000 -0.836995 +-0.707107 0.000000 -0.707107 +-0.368095 0.000000 -0.929788 +-0.547210 0.000000 -0.836995 +-0.547210 0.000000 -0.836995 +-0.368095 0.000000 -0.929788 +-0.368095 0.000000 -0.929788 +-0.547210 0.000000 -0.836995 +-0.181963 0.000000 -0.983305 +-0.368095 0.000000 -0.929788 +-0.368095 0.000000 -0.929788 +-0.181963 0.000000 -0.983305 +-0.181963 0.000000 -0.983305 +-0.368095 0.000000 -0.929788 +0.000000 0.000000 -1.000000 +-0.181963 0.000000 -0.983305 +-0.181963 0.000000 -0.983305 +0.978781 0.000000 0.204909 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.204909 0.000000 0.978781 +0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +0.204909 0.000000 0.978781 +0.397177 0.000000 0.917742 +0.204909 0.000000 0.978781 +0.397177 0.000000 0.917742 +0.397177 0.000000 0.917742 +0.204909 0.000000 0.978781 +0.397177 0.000000 0.917742 +0.566635 0.000000 0.823969 +0.397177 0.000000 0.917742 +0.566635 0.000000 0.823969 +0.566635 0.000000 0.823969 +0.397177 0.000000 0.917742 +0.707107 0.000000 0.707107 +0.566635 0.000000 0.823969 +0.566635 0.000000 0.823969 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.566635 0.000000 0.823969 +0.823969 0.000000 0.566635 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.823969 0.000000 0.566635 +0.823969 0.000000 0.566635 +0.707107 0.000000 0.707107 +0.917742 0.000000 0.397177 +0.823969 0.000000 0.566635 +0.823969 0.000000 0.566635 +0.917742 0.000000 0.397177 +0.917742 0.000000 0.397177 +0.823969 0.000000 0.566635 +0.978781 0.000000 0.204909 +0.917742 0.000000 0.397177 +0.917742 0.000000 0.397177 +0.978781 0.000000 0.204909 +0.978781 0.000000 0.204909 +0.917742 0.000000 0.397177 +1.000000 0.000000 0.000000 +0.978781 0.000000 0.204909 +0.978781 0.000000 0.204909 +0.204909 0.000000 -0.978781 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.978781 0.000000 -0.204909 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.978781 0.000000 -0.204909 +0.978781 0.000000 -0.204909 +1.000000 0.000000 0.000000 +0.917742 0.000000 -0.397177 +0.978781 0.000000 -0.204909 +0.978781 0.000000 -0.204909 +0.917742 0.000000 -0.397177 +0.917742 0.000000 -0.397177 +0.978781 0.000000 -0.204909 +0.823969 0.000000 -0.566635 +0.917742 0.000000 -0.397177 +0.917742 0.000000 -0.397177 +0.823969 0.000000 -0.566635 +0.823969 0.000000 -0.566635 +0.917742 0.000000 -0.397177 +0.823969 0.000000 -0.566635 +0.707107 0.000000 -0.707107 +0.823969 0.000000 -0.566635 +0.707107 0.000000 -0.707107 +0.707107 0.000000 -0.707107 +0.823969 0.000000 -0.566635 +0.566635 0.000000 -0.823969 +0.707107 0.000000 -0.707107 +0.707107 0.000000 -0.707107 +0.566635 0.000000 -0.823969 +0.566635 0.000000 -0.823969 +0.707107 0.000000 -0.707107 +0.397177 0.000000 -0.917742 +0.566635 0.000000 -0.823969 +0.566635 0.000000 -0.823969 +0.397177 0.000000 -0.917742 +0.397177 0.000000 -0.917742 +0.566635 0.000000 -0.823969 +0.397177 0.000000 -0.917742 +0.204909 0.000000 -0.978781 +0.397177 0.000000 -0.917742 +0.204909 0.000000 -0.978781 +0.204909 0.000000 -0.978781 +0.397177 0.000000 -0.917742 +0.000000 0.000000 -1.000000 +0.204909 0.000000 -0.978781 +0.204909 0.000000 -0.978781 +-0.999511 0.031265 0.000000 +-1.000000 0.000000 0.000000 +-0.999511 0.031265 0.000000 +-0.998045 0.062500 0.000000 +-0.999511 0.031265 0.000000 +-0.998045 0.062500 0.000000 +-0.999511 0.031265 0.000000 +-0.999511 0.031265 0.000000 +-0.998045 0.062500 0.000000 +-1.000000 0.000000 0.000000 +-0.999511 0.031265 0.000000 +-1.000000 0.000000 0.000000 +0.973831 0.227273 0.000000 +0.948917 0.315524 0.000000 +0.973831 0.227273 0.000000 +0.000000 1.000000 0.000000 +0.091605 0.995795 0.000000 +0.000000 1.000000 0.000000 +0.091605 0.995795 0.000000 +0.091605 0.995795 0.000000 +0.000000 1.000000 0.000000 +0.289592 0.957150 0.000000 +0.091605 0.995795 0.000000 +0.091605 0.995795 0.000000 +0.289592 0.957150 0.000000 +0.289592 0.957150 0.000000 +0.091605 0.995795 0.000000 +0.468664 0.883377 0.000000 +0.289592 0.957150 0.000000 +0.289592 0.957150 0.000000 +0.468664 0.883377 0.000000 +0.468664 0.883377 0.000000 +0.289592 0.957150 0.000000 +0.468664 0.883377 0.000000 +0.621582 0.783349 0.000000 +0.468664 0.883377 0.000000 +0.621582 0.783349 0.000000 +0.621582 0.783349 0.000000 +0.468664 0.883377 0.000000 +0.621582 0.783349 0.000000 +0.753745 0.657167 0.000000 +0.621582 0.783349 0.000000 +0.753745 0.657167 0.000000 +0.753745 0.657167 0.000000 +0.621582 0.783349 0.000000 +0.753745 0.657167 0.000000 +0.866286 0.499548 0.000000 +0.753745 0.657167 0.000000 +0.866286 0.499548 0.000000 +0.866286 0.499548 0.000000 +0.753745 0.657167 0.000000 +0.948917 0.315524 0.000000 +0.866286 0.499548 0.000000 +0.866286 0.499548 0.000000 +0.948917 0.315524 0.000000 +0.948917 0.315524 0.000000 +0.866286 0.499548 0.000000 +0.948917 0.315524 0.000000 +0.973831 0.227273 0.000000 +0.948917 0.315524 0.000000 + + + + + + + + + + + +0.646420 0.000000 +0.667272 0.000000 +0.521307 2.672212 +0.500454 2.672212 +0.500454 0.000000 +0.542159 2.672212 +0.521307 0.000000 +0.542159 0.000000 +0.563011 2.672212 +0.563011 0.000000 +0.583863 2.672212 +0.604716 2.672212 +0.583863 0.000000 +0.604716 0.000000 +0.625568 2.672212 +0.646420 2.672212 +0.625568 0.000000 +0.667272 2.672212 +5.023758 1.918408 +5.344423 1.918408 +5.344423 3.836816 +5.023758 3.836816 +5.344423 3.716915 +5.023758 3.716915 +5.344423 3.597015 +5.023758 3.597015 +5.344423 3.477114 +5.023758 3.477114 +5.344423 3.357214 +5.023758 3.357214 +5.344423 3.237313 +5.023758 3.237313 +5.344423 3.117413 +5.023758 3.117413 +5.344423 2.997512 +5.023758 2.997512 +5.344423 2.877612 +5.023758 2.877612 +5.344423 2.757711 +5.023758 2.757711 +5.344423 2.637811 +5.023758 2.637811 +5.344423 2.517910 +5.023758 2.517910 +5.344423 2.398010 +5.023758 2.398010 +5.344423 2.278109 +5.023758 2.278109 +5.344423 2.158209 +5.023758 2.158209 +5.344423 2.038308 +5.023758 2.038308 +0.000000 2.384356 +0.000000 2.333043 +2.672212 2.333043 +0.000000 2.358700 +2.672212 2.358700 +2.672212 2.384356 +2.672212 2.335453 +-0.000000 2.335453 +-0.000000 0.145966 +-0.000000 0.000000 +2.672212 0.000000 +2.672212 0.145966 +-0.000000 0.291932 +2.672212 0.291932 +-0.000000 0.437897 +2.672212 0.437897 +-0.000000 0.583863 +2.672212 0.583863 +-0.000000 0.729829 +2.672212 0.729829 +-0.000000 0.875795 +2.672212 0.875795 +-0.000000 1.021761 +2.672212 1.021761 +-0.000000 1.167727 +2.672212 1.167727 +-0.000000 1.313692 +2.672212 1.313692 +-0.000000 1.459658 +2.672212 1.459658 +-0.000000 1.605624 +2.672212 1.605624 +-0.000000 1.751590 +2.672212 1.751590 +-0.000000 1.897556 +2.672212 1.897556 +-0.000000 2.043521 +2.672212 2.043521 +-0.000000 2.189487 +2.672212 2.189487 +6.657839 0.000000 +6.657839 2.672212 +3.966456 2.672212 +3.777344 2.672212 +3.777344 0.000000 +3.966456 0.000000 +4.174979 2.672212 +4.174979 0.000000 +4.383501 2.672212 +4.383501 0.000000 +4.592024 2.672212 +4.800547 2.672212 +4.592024 0.000000 +4.800547 0.000000 +5.009069 2.672212 +5.009069 -0.000000 +5.217592 2.672212 +5.217592 0.000000 +5.426114 2.672212 +5.426114 -0.000000 +5.634637 2.672212 +5.843160 2.672212 +5.634637 -0.000000 +5.843160 -0.000000 +6.051682 2.672212 +6.051682 -0.000000 +6.260205 2.672212 +6.260205 -0.000000 +6.468727 2.672212 +6.468727 -0.000000 +0.746756 -0.046764 +0.746548 -0.053444 +0.903544 -0.571072 +0.983998 -0.417448 +0.688798 -0.292214 +0.794063 -0.715527 +0.632480 -0.399751 +0.657302 -0.842893 +0.555844 -0.500869 +0.497831 -0.945874 +0.460111 -0.590025 +0.322659 -1.019022 +0.348482 -0.662112 +0.140243 -1.059644 +0.225861 -0.713315 +-0.040814 -1.068105 +0.098170 -0.741751 +-0.212996 -1.047448 +-0.028570 -0.747674 +-0.379571 -0.999220 +-0.149097 -0.733214 +-0.542945 -0.920720 +-0.265700 -0.699454 +-0.695009 -0.812082 +-0.380061 -0.644504 +-0.827702 -0.676331 +-0.486506 -0.568457 +-0.934289 -0.519247 +-0.579392 -0.473432 +-1.010447 -0.348585 +-0.654003 -0.363473 +-1.054817 -0.172845 +-0.707313 -0.244009 +-1.068885 -0.000000 +-0.738372 -0.120992 +-1.053225 0.182294 +-0.748219 -0.000000 +-1.003505 0.368093 +-0.735728 0.136148 +-0.917812 0.547847 +-0.695686 0.275416 +-0.797873 0.711275 +-0.626256 0.409433 +-0.649237 0.849121 +-0.529071 0.529071 +-0.480465 0.954813 +-0.409433 0.626256 +-0.301573 1.025460 +-0.275416 0.695686 +-0.122267 1.061869 +-0.136148 0.735728 +0.060622 1.067164 +-0.000000 0.748219 +0.250889 1.039023 +0.136148 0.735728 +0.439265 0.974454 +0.275416 0.695686 +0.615340 0.873997 +0.409433 0.626256 +0.769283 0.742104 +0.893587 0.586530 +0.529071 0.529071 +0.984233 0.416893 +0.626256 0.409433 +1.040913 0.242928 +0.695686 0.275416 +3.206654 -0.160333 +3.206654 0.160333 +0.853436 -0.160333 +1.145005 0.160333 +1.110805 0.165951 +1.054157 0.210901 +0.735728 0.136148 +1.078565 0.183490 +0.748219 -0.000000 +0.833986 -0.158548 +0.814091 -0.152828 +0.794946 -0.142909 +0.777854 -0.129026 +0.763971 -0.111935 +0.754052 -0.092789 +0.748332 -0.072894 +-0.072894 0.748332 +-0.053444 0.746548 +-0.292214 0.688798 +-0.417448 0.983998 +-0.399751 0.632480 +-0.571072 0.903544 +-0.500869 0.555844 +-0.715527 0.794063 +-0.590025 0.460111 +-0.842893 0.657302 +-0.662112 0.348482 +-0.945874 0.497831 +-0.713315 0.225861 +-1.019022 0.322659 +-0.741751 0.098170 +-1.059644 0.140243 +-0.747674 -0.028570 +-1.068105 -0.040814 +-0.733214 -0.149097 +-1.047448 -0.212996 +-0.699454 -0.265700 +-0.999220 -0.379571 +-0.644504 -0.380061 +-0.920720 -0.542945 +-0.568457 -0.486506 +-0.812082 -0.695009 +-0.473432 -0.579392 +-0.676331 -0.827702 +-0.363473 -0.654003 +-0.519247 -0.934289 +-0.244009 -0.707313 +-0.348585 -1.010447 +-0.120992 -0.738372 +-0.172845 -1.054817 +-0.000000 -0.748219 +-0.000000 -1.068885 +0.136148 -0.735728 +0.182294 -1.053225 +0.275416 -0.695686 +0.368093 -1.003505 +0.409433 -0.626256 +0.547847 -0.917812 +0.529071 -0.529071 +0.711275 -0.797873 +0.626256 -0.409433 +0.849121 -0.649237 +0.695686 -0.275416 +0.954813 -0.480465 +0.735728 -0.136148 +1.025460 -0.301573 +0.748219 0.000000 +1.061869 -0.122267 +0.735728 0.136148 +1.067164 0.060622 +0.695686 0.275416 +1.039023 0.250889 +0.626256 0.409433 +0.974454 0.439265 +0.873997 0.615340 +0.529071 0.529071 +0.742104 0.769283 +0.409433 0.626256 +0.586530 0.893587 +0.275416 0.695686 +0.416893 0.984233 +0.136148 0.735728 +0.160333 3.206654 +-0.160333 3.206654 +0.160333 1.145005 +0.165951 1.110805 +0.183490 1.078565 +0.242928 1.040913 +-0.000000 0.748219 +0.210901 1.054157 +-0.046764 0.746756 +-0.160333 0.853436 +-0.158548 0.833986 +-0.152828 0.814091 +-0.142909 0.794946 +-0.129026 0.777854 +-0.111935 0.763971 +-0.092789 0.754052 +3.006094 -0.000000 +3.082386 -0.000000 +0.010485 2.672212 +0.010485 -0.000000 +0.086777 2.672212 +0.295300 2.672212 +0.086777 -0.000000 +0.295300 -0.000000 +0.503823 2.672212 +0.712345 2.672212 +0.503823 -0.000000 +0.712345 -0.000000 +0.920868 2.672212 +0.920868 -0.000000 +1.129390 2.672212 +1.129390 -0.000000 +1.337913 2.672212 +1.337913 -0.000000 +1.546435 2.672212 +1.546435 -0.000000 +1.754958 2.672212 +1.754958 -0.000000 +1.963481 2.672212 +1.963481 -0.000000 +2.172003 2.672212 +2.172003 -0.000000 +2.380526 2.672212 +2.380526 -0.000000 +2.589048 2.672212 +2.589048 -0.000000 +2.797571 2.672212 +3.006094 2.672212 +2.797571 -0.000000 +3.082386 2.672212 +2.672212 -0.142797 +2.672212 -0.010419 +-0.000000 -2.026766 +2.672212 -2.026766 +-0.000000 -1.894387 +2.672212 -1.894387 +-0.000000 -1.748421 +2.672212 -1.748421 +-0.000000 -1.602455 +2.672212 -1.602455 +-0.000000 -1.456490 +2.672212 -1.456490 +-0.000000 -1.310524 +2.672212 -1.310524 +-0.000000 -1.164558 +2.672212 -1.164558 +-0.000000 -1.018592 +-0.000000 -0.872626 +2.672212 -1.018592 +2.672212 -0.872626 +-0.000000 -0.726660 +-0.000000 -0.580695 +2.672212 -0.726660 +2.672212 -0.580695 +-0.000000 -0.434729 +-0.000000 -0.288763 +2.672212 -0.434729 +2.672212 -0.288763 +-0.000000 -0.142797 +-0.000000 -0.010419 +1.672426 1.890566 +1.850531 2.741310 +2.672212 1.145005 +1.907562 2.631225 +1.940454 2.516827 +1.950715 2.404990 +1.940454 2.293154 +1.907562 2.178756 +1.850531 2.068671 +1.770700 1.970397 +1.770700 2.839585 +2.672212 3.206654 +2.663289 3.303903 +2.634688 3.403379 +2.585095 3.499106 +2.515677 3.584562 +2.430221 3.653980 +2.334495 3.703572 +2.235018 3.732174 +1.672426 2.919415 +2.137769 3.741096 +1.562340 2.976447 +1.447942 3.009339 +1.336106 3.019599 +1.224270 3.009339 +1.109872 2.976447 +0.999786 2.919415 +0.901512 2.839585 +0.534442 3.741096 +0.437194 3.732174 +0.337717 3.703572 +0.241990 3.653980 +0.156535 3.584562 +0.087117 3.499106 +0.037524 3.403379 +0.008922 3.303903 +0.821681 2.741310 +0.764650 2.631225 +-0.000000 3.206654 +0.731758 2.516827 +0.721497 2.404990 +0.731758 2.293154 +0.764650 2.178756 +0.821681 2.068671 +0.901512 1.970397 +0.999786 1.890566 +1.109872 1.833535 +-0.000000 1.145005 +1.224270 1.800642 +1.336106 1.790382 +1.447942 1.800642 +1.562340 1.833535 +3.403379 2.634688 +3.303903 2.663289 +2.631225 1.907562 +3.206654 2.672212 +2.516827 1.940454 +2.404990 1.950715 +2.293154 1.940454 +2.178756 1.907562 +2.068671 1.850531 +1.970397 1.770700 +1.890566 1.672426 +0.853436 2.672212 +1.833535 1.562340 +1.800642 1.447942 +1.790382 1.336106 +1.800642 1.224270 +1.833535 1.109872 +1.890566 0.999786 +1.970397 0.901512 +2.741310 1.850531 +2.068671 0.821681 +0.853436 0.000000 +2.178756 0.764650 +2.293154 0.731758 +2.404990 0.721497 +2.516827 0.731758 +2.631225 0.764650 +2.741310 0.821681 +2.839585 0.901512 +3.206654 0.000000 +3.303903 0.008922 +3.403379 0.037524 +3.499106 0.087117 +3.584562 0.156535 +3.653980 0.241990 +3.703572 0.337717 +3.732174 0.437194 +2.919415 0.999786 +3.741096 0.534442 +2.976447 1.109872 +3.009339 1.224270 +3.019599 1.336106 +3.009339 1.447942 +2.976447 1.562340 +2.919415 1.672426 +2.839585 1.770700 +3.741096 2.137769 +3.732174 2.235018 +3.703572 2.334495 +3.653980 2.430221 +3.584562 2.515677 +3.499106 2.585095 +-0.320665 2.137769 +-0.320665 0.534442 +-0.000000 0.534442 +-0.000000 2.137769 +5.344423 0.658349 +2.672212 0.658349 +2.672212 0.337684 +5.344423 0.337684 +5.344423 1.918408 +5.023758 1.918408 +5.023758 0.000000 +5.344423 0.000000 +5.023758 0.119900 +5.344423 0.119900 +5.023758 0.239801 +5.344423 0.239801 +5.023758 0.359701 +5.344423 0.359701 +5.023758 0.479602 +5.344423 0.479602 +5.023758 0.599503 +5.344423 0.599503 +5.023758 0.719403 +5.344423 0.719403 +5.023758 0.839303 +5.344423 0.839303 +5.023758 0.959204 +5.344423 0.959204 +5.023758 1.079104 +5.344423 1.079104 +5.023758 1.199005 +5.344423 1.199005 +5.023758 1.318905 +5.023758 1.438806 +5.344423 1.318905 +5.344423 1.438806 +5.023758 1.558706 +5.344423 1.558706 +5.023758 1.678607 +5.344423 1.678607 +5.023758 1.798507 +5.344423 1.798507 +0.834090 -0.320665 +0.834090 0.000000 +-0.000000 0.000000 +-0.000000 -0.320665 +0.104261 -0.000000 +0.208523 -0.000000 +0.104261 -0.320665 +0.312784 -0.000000 +0.208523 -0.320665 +0.312784 -0.320665 +0.417045 -0.000000 +0.417045 -0.320665 +0.521307 -0.000000 +0.521307 -0.320665 +0.625568 0.000000 +0.625568 -0.320665 +0.729829 0.000000 +0.729829 -0.320665 +-0.000000 0.160333 +-0.000000 -0.160333 +0.834090 -0.160333 +0.834090 0.160333 +0.729829 -0.160333 +0.729829 0.160333 +0.625568 -0.160333 +0.625568 0.160333 +0.521307 -0.160333 +0.417045 -0.160333 +0.521307 0.160333 +0.417045 0.160333 +0.312784 -0.160333 +0.312784 0.160333 +0.208523 -0.160333 +0.104261 -0.160333 +0.208523 0.160333 +0.104261 0.160333 +-0.000344 -0.000000 +0.003321 -0.000000 +0.006986 -0.000000 +0.006986 2.672212 +0.003321 2.672212 +-0.000344 2.672212 +2.672212 0.634246 +2.672212 0.643543 +0.000000 0.509132 +0.000000 0.499835 +2.672212 0.499835 +2.672212 0.509132 +0.000000 0.529984 +2.672212 0.529984 +0.000000 0.550837 +0.000000 0.571689 +2.672212 0.550837 +0.000000 0.592541 +2.672212 0.571689 +0.000000 0.613393 +2.672212 0.592541 +2.672212 0.613393 +-0.000000 0.634246 +0.000000 0.643543 + + + + + + + + + + + +

17 0 17 0 1 0 1 2 1 4 3 4 2 4 2 3 5 3 6 6 6 2 7 2 4 8 4 6 9 6 5 10 5 2 11 2 7 12 7 5 13 5 6 14 6 9 15 9 5 16 5 7 17 7 9 18 9 8 19 8 5 20 5 12 21 12 8 22 8 9 23 9 12 24 12 10 25 10 8 26 8 12 27 12 11 28 11 10 29 10 13 30 13 11 31 11 12 32 12 16 33 16 11 34 11 13 35 13 16 36 16 14 37 14 11 38 11 16 39 16 15 40 15 14 41 14 0 42 0 15 43 15 16 44 16 0 45 0 17 46 17 15 47 15 50 48 50 18 49 18 19 50 19 23 51 23 20 52 20 21 53 21 23 54 23 22 55 22 20 56 20 25 57 25 22 58 22 23 59 23 25 60 25 24 61 24 22 62 22 27 63 27 24 64 24 25 65 25 27 66 27 26 67 26 24 68 24 29 69 29 26 70 26 27 71 27 29 72 29 28 73 28 26 74 26 31 75 31 28 76 28 29 77 29 31 78 31 30 79 30 28 80 28 33 81 33 30 82 30 31 83 31 33 84 33 32 85 32 30 86 30 35 87 35 32 88 32 33 89 33 35 90 35 34 91 34 32 92 32 37 93 37 34 94 34 35 95 35 37 96 37 36 97 36 34 98 34 39 99 39 36 100 36 37 101 37 39 102 39 38 103 38 36 104 36 41 105 41 38 106 38 39 107 39 41 108 41 40 109 40 38 110 38 43 111 43 40 112 40 41 113 41 43 114 43 42 115 42 40 116 40 45 117 45 42 118 42 43 119 43 45 120 45 44 121 44 42 122 42 47 123 47 44 124 44 45 125 45 47 126 47 46 127 46 44 128 44 49 129 49 46 130 46 47 131 47 49 132 49 48 133 48 46 134 46 51 135 51 48 136 48 49 137 49 51 138 51 50 139 50 48 140 48 18 141 18 50 142 50 51 143 51 56 144 56 52 145 52 55 146 55 56 147 56 53 148 53 54 149 54 56 150 56 55 151 55 53 152 53 52 153 52 56 154 56 57 155 57 90 156 90 58 157 58 59 158 59 62 159 62 60 160 60 61 161 61 63 162 63 60 163 60 62 164 62 65 165 65 60 166 60 63 167 63 65 168 65 64 169 64 60 170 60 67 171 67 64 172 64 65 173 65 67 174 67 66 175 66 64 176 64 69 177 69 66 178 66 67 179 67 69 180 69 68 181 68 66 182 66 71 183 71 68 184 68 69 185 69 71 186 71 70 187 70 68 188 68 73 189 73 70 190 70 71 191 71 73 192 73 72 193 72 70 194 70 75 195 75 72 196 72 73 197 73 75 198 75 74 199 74 72 200 72 77 201 77 74 202 74 75 203 75 77 204 77 76 205 76 74 206 74 79 207 79 76 208 76 77 209 77 79 210 79 78 211 78 76 212 76 81 213 81 78 214 78 79 215 79 81 216 81 80 217 80 78 218 78 83 219 83 80 220 80 81 221 81 83 222 83 82 223 82 80 224 80 85 225 85 82 226 82 83 227 83 85 228 85 84 229 84 82 230 82 87 231 87 84 232 84 85 233 85 87 234 87 86 235 86 84 236 84 89 237 89 86 238 86 87 239 87 89 240 89 88 241 88 86 242 86 91 243 91 88 244 88 89 245 89 91 246 91 90 247 90 88 248 88 58 249 58 90 250 90 91 251 91 120 252 120 92 253 92 93 254 93 96 255 96 94 256 94 95 257 95 97 258 97 94 259 94 96 260 96 99 261 99 94 262 94 97 263 97 99 264 99 98 265 98 94 266 94 101 267 101 98 268 98 99 269 99 101 270 101 100 271 100 98 272 98 104 273 104 100 274 100 101 275 101 104 276 104 102 277 102 100 278 100 104 279 104 103 280 103 102 281 102 105 282 105 103 283 103 104 284 104 107 285 107 103 286 103 105 287 105 107 288 107 106 289 106 103 290 103 109 291 109 106 292 106 107 293 107 109 294 109 108 295 108 106 296 106 111 297 111 108 298 108 109 299 109 111 300 111 110 301 110 108 302 108 114 303 114 110 304 110 111 305 111 114 306 114 112 307 112 110 308 110 114 309 114 113 310 113 112 311 112 115 312 115 113 313 113 114 314 114 117 315 117 113 316 113 115 317 115 117 318 117 116 319 116 113 320 113 119 321 119 116 322 116 117 323 117 119 324 119 118 325 118 116 326 116 121 327 121 118 328 118 119 329 119 121 330 121 120 331 120 118 332 118 92 333 92 120 334 120 121 335 121 203 336 203 122 337 122 123 338 123 126 339 126 124 340 124 125 341 125 128 342 128 124 343 124 126 344 126 128 345 128 127 346 127 124 347 124 130 348 130 127 349 127 128 350 128 130 351 130 129 352 129 127 353 127 132 354 132 129 355 129 130 356 130 132 357 132 131 358 131 129 359 129 134 360 134 131 361 131 132 362 132 134 363 134 133 364 133 131 365 131 136 366 136 133 367 133 134 368 134 136 369 136 135 370 135 133 371 133 138 372 138 135 373 135 136 374 136 138 375 138 137 376 137 135 377 135 140 378 140 137 379 137 138 380 138 140 381 140 139 382 139 137 383 137 142 384 142 139 385 139 140 386 140 142 387 142 141 388 141 139 389 139 144 390 144 141 391 141 142 392 142 144 393 144 143 394 143 141 395 141 146 396 146 143 397 143 144 398 144 146 399 146 145 400 145 143 401 143 148 402 148 145 403 145 146 404 146 148 405 148 147 406 147 145 407 145 150 408 150 147 409 147 148 410 148 150 411 150 149 412 149 147 413 147 152 414 152 149 415 149 150 416 150 152 417 152 151 418 151 149 419 149 154 420 154 151 421 151 152 422 152 154 423 154 153 424 153 151 425 151 156 426 156 153 427 153 154 428 154 156 429 156 155 430 155 153 431 153 158 432 158 155 433 155 156 434 156 158 435 158 157 436 157 155 437 155 160 438 160 157 439 157 158 440 158 160 441 160 159 442 159 157 443 157 162 444 162 159 445 159 160 446 160 162 447 162 161 448 161 159 449 159 164 450 164 161 451 161 162 452 162 164 453 164 163 454 163 161 455 161 166 456 166 163 457 163 164 458 164 166 459 166 165 460 165 163 461 163 168 462 168 165 463 165 166 464 166 168 465 168 167 466 167 165 467 165 170 468 170 167 469 167 168 470 168 170 471 170 169 472 169 167 473 167 172 474 172 169 475 169 170 476 170 172 477 172 171 478 171 169 479 169 174 480 174 171 481 171 172 482 172 174 483 174 173 484 173 171 485 171 176 486 176 173 487 173 174 488 174 176 489 176 175 490 175 173 491 173 178 492 178 175 493 175 176 494 176 178 495 178 177 496 177 175 497 175 180 498 180 177 499 177 178 500 178 180 501 180 179 502 179 177 503 177 183 504 183 179 505 179 180 506 180 183 507 183 181 508 181 179 509 179 183 510 183 182 511 182 181 512 181 185 513 185 182 514 182 183 515 183 185 516 185 184 517 184 182 518 182 187 519 187 184 520 184 185 521 185 187 522 187 186 523 186 184 524 184 194 525 194 186 526 186 187 527 187 191 528 191 188 529 188 189 530 189 191 531 191 190 532 190 188 533 188 192 534 192 190 535 190 191 536 191 195 537 195 190 538 190 192 539 192 194 540 194 193 541 193 186 542 186 196 543 196 193 544 193 194 545 194 196 546 196 195 547 195 193 548 193 196 549 196 190 550 190 195 551 195 122 552 122 190 553 190 196 554 196 122 555 122 197 556 197 190 557 190 122 558 122 198 559 198 197 560 197 122 561 122 199 562 199 198 563 198 122 564 122 200 565 200 199 566 199 122 567 122 201 568 201 200 569 200 122 570 122 202 571 202 201 572 201 122 573 122 203 574 203 202 575 202 278 576 278 204 577 204 205 578 205 209 579 209 206 580 206 207 581 207 209 582 209 208 583 208 206 584 206 211 585 211 208 586 208 209 587 209 211 588 211 210 589 210 208 590 208 213 591 213 210 592 210 211 593 211 213 594 213 212 595 212 210 596 210 215 597 215 212 598 212 213 599 213 215 600 215 214 601 214 212 602 212 217 603 217 214 604 214 215 605 215 217 606 217 216 607 216 214 608 214 219 609 219 216 610 216 217 611 217 219 612 219 218 613 218 216 614 216 221 615 221 218 616 218 219 617 219 221 618 221 220 619 220 218 620 218 223 621 223 220 622 220 221 623 221 223 624 223 222 625 222 220 626 220 225 627 225 222 628 222 223 629 223 225 630 225 224 631 224 222 632 222 227 633 227 224 634 224 225 635 225 227 636 227 226 637 226 224 638 224 229 639 229 226 640 226 227 641 227 229 642 229 228 643 228 226 644 226 231 645 231 228 646 228 229 647 229 231 648 231 230 649 230 228 650 228 233 651 233 230 652 230 231 653 231 233 654 233 232 655 232 230 656 230 235 657 235 232 658 232 233 659 233 235 660 235 234 661 234 232 662 232 237 663 237 234 664 234 235 665 235 237 666 237 236 667 236 234 668 234 239 669 239 236 670 236 237 671 237 239 672 239 238 673 238 236 674 236 241 675 241 238 676 238 239 677 239 241 678 241 240 679 240 238 680 238 243 681 243 240 682 240 241 683 241 243 684 243 242 685 242 240 686 240 245 687 245 242 688 242 243 689 243 245 690 245 244 691 244 242 692 242 247 693 247 244 694 244 245 695 245 247 696 247 246 697 246 244 698 244 249 699 249 246 700 246 247 701 247 249 702 249 248 703 248 246 704 246 251 705 251 248 706 248 249 707 249 251 708 251 250 709 250 248 710 248 253 711 253 250 712 250 251 713 251 253 714 253 252 715 252 250 716 250 255 717 255 252 718 252 253 719 253 255 720 255 254 721 254 252 722 252 257 723 257 254 724 254 255 725 255 257 726 257 256 727 256 254 728 254 259 729 259 256 730 256 257 731 257 259 732 259 258 733 258 256 734 256 261 735 261 258 736 258 259 737 259 261 738 261 260 739 260 258 740 258 262 741 262 260 742 260 261 743 261 264 744 264 260 745 260 262 746 262 264 747 264 263 748 263 260 749 260 266 750 266 263 751 263 264 752 264 266 753 266 265 754 265 263 755 263 268 756 268 265 757 265 266 758 266 268 759 268 267 760 267 265 761 265 275 762 275 267 763 267 268 764 268 275 765 275 269 766 269 267 767 267 279 768 279 270 769 270 271 770 271 279 771 279 272 772 272 270 773 270 279 774 279 273 775 273 272 776 272 279 777 279 274 778 274 273 779 273 277 780 277 269 781 269 275 782 275 277 783 277 276 784 276 269 785 269 274 786 274 276 787 276 277 788 277 279 789 279 276 790 276 274 791 274 279 792 279 278 793 278 276 794 276 280 795 280 278 796 278 279 797 279 281 798 281 278 799 278 280 800 280 282 801 282 278 802 278 281 803 281 283 804 283 278 805 278 282 806 282 284 807 284 278 808 278 283 809 283 285 810 285 278 811 278 284 812 284 204 813 204 278 814 278 285 815 285 319 816 319 286 817 286 287 818 287 292 819 292 288 820 288 289 821 289 292 822 292 290 823 290 288 824 288 292 825 292 291 826 291 290 827 290 293 828 293 291 829 291 292 830 292 296 831 296 291 832 291 293 833 293 296 834 296 294 835 294 291 836 291 296 837 296 295 838 295 294 839 294 297 840 297 295 841 295 296 842 296 299 843 299 295 844 295 297 845 297 299 846 299 298 847 298 295 848 295 301 849 301 298 850 298 299 851 299 301 852 301 300 853 300 298 854 298 303 855 303 300 856 300 301 857 301 303 858 303 302 859 302 300 860 300 305 861 305 302 862 302 303 863 303 305 864 305 304 865 304 302 866 302 307 867 307 304 868 304 305 869 305 307 870 307 306 871 306 304 872 304 309 873 309 306 874 306 307 875 307 309 876 309 308 877 308 306 878 306 311 879 311 308 880 308 309 881 309 311 882 311 310 883 310 308 884 308 313 885 313 310 886 310 311 887 311 313 888 313 312 889 312 310 890 310 315 891 315 312 892 312 313 893 313 315 894 315 314 895 314 312 896 312 318 897 318 314 898 314 315 899 315 318 900 318 316 901 316 314 902 314 318 903 318 317 904 317 316 905 316 286 906 286 317 907 317 318 908 318 286 909 286 319 910 319 317 911 317 349 912 349 320 913 320 321 914 321 325 915 325 322 916 322 323 917 323 325 918 325 324 919 324 322 920 322 327 921 327 324 922 324 325 923 325 327 924 327 326 925 326 324 926 324 329 927 329 326 928 326 327 929 327 329 930 329 328 931 328 326 932 326 331 933 331 328 934 328 329 935 329 331 936 331 330 937 330 328 938 328 333 939 333 330 940 330 331 941 331 333 942 333 332 943 332 330 944 330 335 945 335 332 946 332 333 947 333 335 948 335 334 949 334 332 950 332 338 951 338 334 952 334 335 953 335 338 954 338 336 955 336 334 956 334 338 957 338 337 958 337 336 959 336 339 960 339 337 961 337 338 962 338 342 963 342 337 964 337 339 965 339 342 966 342 340 967 340 337 968 337 342 969 342 341 970 341 340 971 340 343 972 343 341 973 341 342 974 342 346 975 346 341 976 341 343 977 343 346 978 346 344 979 344 341 980 341 346 981 346 345 982 345 344 983 344 347 984 347 345 985 345 346 986 346 320 987 320 345 988 345 347 989 347 320 990 320 348 991 348 345 992 345 320 993 320 349 994 349 348 995 348 401 996 401 352 997 352 350 998 350 353 999 353 361 1000 361 351 1001 351 353 1002 353 352 1003 352 361 1004 361 354 1005 354 352 1006 352 353 1007 353 355 1008 355 352 1009 352 354 1010 354 356 1011 356 352 1012 352 355 1013 355 357 1014 357 352 1015 352 356 1016 356 358 1017 358 352 1018 352 357 1019 357 359 1020 359 352 1021 352 358 1022 358 350 1023 350 352 1024 352 359 1025 359 361 1026 361 360 1027 360 351 1028 351 362 1029 362 360 1030 360 361 1031 361 363 1032 363 360 1033 360 362 1034 362 364 1035 364 360 1036 360 363 1037 363 365 1038 365 360 1039 360 364 1040 364 366 1041 366 360 1042 360 365 1043 365 367 1044 367 360 1045 360 366 1046 366 368 1047 368 360 1048 360 367 1049 367 370 1050 370 360 1051 360 368 1052 368 370 1053 370 369 1054 369 360 1055 360 378 1056 378 369 1057 369 370 1058 370 378 1059 378 371 1060 371 369 1061 369 378 1062 378 372 1063 372 371 1064 371 378 1065 378 373 1066 373 372 1067 372 378 1068 378 374 1069 374 373 1070 373 378 1071 378 375 1072 375 374 1073 374 378 1074 378 376 1075 376 375 1076 375 378 1077 378 377 1078 377 376 1079 376 379 1080 379 377 1081 377 378 1082 378 380 1083 380 377 1084 377 379 1085 379 381 1086 381 377 1087 377 380 1088 380 382 1089 382 377 1090 377 381 1091 381 383 1092 383 377 1093 377 382 1094 382 384 1095 384 377 1096 377 383 1097 383 385 1098 385 377 1099 377 384 1100 384 388 1101 388 377 1102 377 385 1103 385 388 1104 388 386 1105 386 377 1106 377 388 1107 388 387 1108 387 386 1109 386 397 1110 397 387 1111 387 388 1112 388 397 1113 397 389 1114 389 387 1115 387 397 1116 397 390 1117 390 389 1118 389 397 1119 397 391 1120 391 390 1121 390 397 1122 397 392 1123 392 391 1124 391 397 1125 397 393 1126 393 392 1127 392 397 1128 397 394 1129 394 393 1130 393 397 1131 397 395 1132 395 394 1133 394 397 1134 397 396 1135 396 395 1136 395 352 1137 352 396 1138 396 397 1139 397 352 1140 352 398 1141 398 396 1142 396 352 1143 352 399 1144 399 398 1145 398 352 1146 352 400 1147 400 399 1148 399 352 1149 352 401 1150 401 400 1151 400 405 1152 405 402 1153 402 403 1154 403 405 1155 405 404 1156 404 421 1157 421 413 1158 413 404 1159 404 405 1160 405 413 1161 413 406 1162 406 404 1163 404 413 1164 413 407 1165 407 406 1166 406 413 1167 413 408 1168 408 407 1169 407 413 1170 413 409 1171 409 408 1172 408 413 1173 413 410 1174 410 409 1175 409 413 1176 413 411 1177 411 410 1178 410 413 1179 413 412 1180 412 411 1181 411 423 1182 423 412 1183 412 413 1184 413 423 1185 423 414 1186 414 412 1187 412 423 1188 423 415 1189 415 414 1190 414 423 1191 423 416 1192 416 415 1193 415 423 1194 423 417 1195 417 416 1196 416 423 1197 423 418 1198 418 417 1199 417 423 1200 423 419 1201 419 418 1202 418 423 1203 423 420 1204 420 419 1205 419 447 1206 447 405 1207 405 421 1208 421 423 1209 423 422 1210 422 420 1211 420 431 1212 431 422 1213 422 423 1214 423 431 1215 431 424 1216 424 422 1217 422 431 1218 431 425 1219 425 424 1220 424 431 1221 431 426 1222 426 425 1223 425 431 1224 431 427 1225 427 426 1226 426 431 1227 431 428 1228 428 427 1229 427 431 1230 431 429 1231 429 428 1232 428 431 1233 431 430 1234 430 429 1235 429 432 1236 432 430 1237 430 431 1238 431 433 1239 433 430 1240 430 432 1241 432 434 1242 434 430 1243 430 433 1244 433 435 1245 435 430 1246 430 434 1247 434 436 1248 436 430 1249 430 435 1250 435 437 1251 437 430 1252 430 436 1253 436 438 1254 438 430 1255 430 437 1256 437 440 1257 440 430 1258 430 438 1259 438 440 1260 440 439 1261 439 430 1262 430 448 1263 448 439 1264 439 440 1265 440 448 1266 448 441 1267 441 439 1268 439 448 1269 448 442 1270 442 441 1271 441 448 1272 448 443 1273 443 442 1274 442 448 1275 448 444 1276 444 443 1277 443 448 1278 448 445 1279 445 444 1280 444 448 1281 448 446 1282 446 445 1283 445 448 1284 448 447 1285 447 446 1286 446 448 1287 448 405 1288 405 447 1289 447 449 1290 449 405 1291 405 448 1292 448 450 1293 450 405 1294 405 449 1295 449 451 1296 451 405 1297 405 450 1298 450 452 1299 452 405 1300 405 451 1301 451 453 1302 453 405 1303 405 452 1304 452 402 1305 402 405 1306 405 453 1307 453 456 1308 456 454 1309 454 455 1310 455 454 1311 454 456 1312 456 457 1313 457 460 1314 460 458 1315 458 459 1316 459 458 1317 458 460 1318 460 461 1319 461 494 1320 494 462 1321 462 463 1322 463 467 1323 467 464 1324 464 465 1325 465 467 1326 467 466 1327 466 464 1328 464 469 1329 469 466 1330 466 467 1331 467 469 1332 469 468 1333 468 466 1334 466 471 1335 471 468 1336 468 469 1337 469 471 1338 471 470 1339 470 468 1340 468 473 1341 473 470 1342 470 471 1343 471 473 1344 473 472 1345 472 470 1346 470 475 1347 475 472 1348 472 473 1349 473 475 1350 475 474 1351 474 472 1352 472 477 1353 477 474 1354 474 475 1355 475 477 1356 477 476 1357 476 474 1358 474 479 1359 479 476 1360 476 477 1361 477 479 1362 479 478 1363 478 476 1364 476 481 1365 481 478 1366 478 479 1367 479 481 1368 481 480 1369 480 478 1370 478 483 1371 483 480 1372 480 481 1373 481 483 1374 483 482 1375 482 480 1376 480 485 1377 485 482 1378 482 483 1379 483 485 1380 485 484 1381 484 482 1382 482 488 1383 488 484 1384 484 485 1385 485 488 1386 488 486 1387 486 484 1388 484 488 1389 488 487 1390 487 486 1391 486 489 1392 489 487 1393 487 488 1394 488 491 1395 491 487 1396 487 489 1397 489 491 1398 491 490 1399 490 487 1400 487 493 1401 493 490 1402 490 491 1403 491 493 1404 493 492 1405 492 490 1406 490 495 1407 495 492 1408 492 493 1409 493 495 1410 495 494 1411 494 492 1412 492 462 1413 462 494 1414 494 495 1415 495 512 1416 512 496 1417 496 497 1418 497 502 1419 502 498 1420 498 499 1421 499 502 1422 502 500 1423 500 498 1424 498 502 1425 502 501 1426 501 500 1427 500 504 1428 504 501 1429 501 502 1430 502 504 1431 504 503 1432 503 501 1433 501 505 1434 505 503 1435 503 504 1436 504 507 1437 507 503 1438 503 505 1439 505 507 1440 507 506 1441 506 503 1442 503 509 1443 509 506 1444 506 507 1445 507 509 1446 509 508 1447 508 506 1448 506 511 1449 511 508 1450 508 509 1451 509 511 1452 511 510 1453 510 508 1454 508 513 1455 513 510 1456 510 511 1457 511 513 1458 513 512 1459 512 510 1460 510 496 1461 496 512 1462 512 513 1463 513 529 1464 529 514 1465 514 515 1466 515 519 1467 519 516 1468 516 517 1469 517 519 1470 519 518 1471 518 516 1472 516 521 1473 521 518 1474 518 519 1475 519 521 1476 521 520 1477 520 518 1478 518 524 1479 524 520 1480 520 521 1481 521 524 1482 524 522 1483 522 520 1484 520 524 1485 524 523 1486 523 522 1487 522 525 1488 525 523 1489 523 524 1490 524 527 1491 527 523 1492 523 525 1493 525 527 1494 527 526 1495 526 523 1496 523 530 1497 530 526 1498 526 527 1499 527 530 1500 530 528 1501 528 526 1502 526 530 1503 530 529 1504 529 528 1505 528 531 1506 531 529 1507 529 530 1508 530 514 1509 514 529 1510 529 531 1511 531 536 1512 536 532 1513 532 533 1514 533 535 1515 535 533 1516 533 534 1517 534 536 1518 536 533 1519 533 535 1520 535 532 1521 532 536 1522 536 537 1523 537 555 1524 555 538 1525 538 539 1526 539 542 1527 542 540 1528 540 541 1529 541 543 1530 543 540 1531 540 542 1532 542 545 1533 545 540 1534 540 543 1535 543 545 1536 545 544 1537 544 540 1538 540 548 1539 548 544 1540 544 545 1541 545 548 1542 548 546 1543 546 544 1544 544 548 1545 548 547 1546 547 546 1547 546 550 1548 550 547 1549 547 548 1550 548 550 1551 550 549 1552 549 547 1553 547 552 1554 552 549 1555 549 550 1556 550 552 1557 552 551 1558 551 549 1559 549 553 1560 553 551 1561 551 552 1562 552 538 1563 538 551 1564 551 553 1565 553 538 1566 538 554 1567 554 551 1568 551 538 1569 538 555 1570 555 554 1571 554

+
+
+ + + + +24.914858 16.828012 1.000000 +25.000000 15.900000 1.000000 +24.877054 15.900000 0.987269 +24.761694 15.900000 0.950645 +24.660019 15.900000 0.894382 +24.575735 15.900000 0.824264 +24.505619 15.900000 0.739981 +24.449354 15.900000 0.638306 +24.412731 15.900000 0.522946 +24.400000 15.900000 0.400000 +24.324875 16.718834 0.400000 +24.084047 17.556427 0.400000 +23.666479 18.362444 0.400000 +23.081980 19.081980 0.400000 +22.362444 19.666479 0.400000 +21.556427 20.084047 0.400000 +20.718834 20.324875 0.400000 +19.900000 20.400000 0.400000 +19.081165 20.324875 0.400000 +18.243574 20.084047 0.400000 +17.437555 19.666479 0.400000 +16.718019 19.081980 0.400000 +16.133520 18.362444 0.400000 +15.715953 17.556427 0.400000 +15.475126 16.718834 0.400000 +15.400000 15.900000 0.400000 +15.387269 15.900000 0.522946 +15.350645 15.900000 0.638306 +15.294381 15.900000 0.739981 +15.224264 15.900000 0.824264 +15.139980 15.900000 0.894382 +15.038306 15.900000 0.950645 +14.922946 15.900000 0.987269 +14.800000 15.900000 1.000000 +14.885142 16.828012 1.000000 +15.158080 17.777283 1.000000 +15.631323 18.690769 1.000000 +16.293755 19.506245 1.000000 +17.109230 20.168676 1.000000 +18.022717 20.641920 1.000000 +18.971989 20.914858 1.000000 +19.900000 21.000000 1.000000 +20.828012 20.914858 1.000000 +21.777283 20.641920 1.000000 +22.690769 20.168676 1.000000 +23.506245 19.506245 1.000000 +24.168676 18.690769 1.000000 +24.641920 17.777283 1.000000 +24.065773 18.623493 0.987269 +24.527607 17.732027 0.987269 +24.793964 16.805639 0.987269 +24.680529 16.784649 0.950645 +24.580553 16.766148 0.894382 +24.497677 16.750811 0.824264 +24.428730 16.738052 0.739981 +24.373405 16.727814 0.638306 +24.337393 16.721149 0.522946 +24.095884 17.561113 0.522946 +23.677135 18.369411 0.522946 +23.090982 19.090982 0.522946 +22.369411 19.677135 0.522946 +21.561113 20.095884 0.522946 +20.721149 20.337393 0.522946 +19.900000 20.412731 0.522946 +19.078850 20.337393 0.522946 +18.238888 20.095884 0.522946 +17.430590 19.677135 0.522946 +16.709017 19.090982 0.522946 +16.122864 18.369411 0.522946 +15.704115 17.561113 0.522946 +15.462607 16.721149 0.522946 +15.426595 16.727814 0.638306 +15.371270 16.738052 0.739981 +15.302323 16.750811 0.824264 +15.219447 16.766148 0.894382 +15.119471 16.784649 0.950645 +15.006036 16.805639 0.987269 +15.272393 17.732027 0.987269 +15.734228 18.623493 0.987269 +16.380692 19.419310 0.987269 +17.176508 20.065773 0.987269 +18.067972 20.527607 0.987269 +18.994360 20.793964 0.987269 +19.900000 20.877054 0.987269 +20.805639 20.793964 0.987269 +21.732027 20.527607 0.987269 +22.623493 20.065773 0.987269 +23.419310 19.419310 0.987269 +15.670063 17.574593 0.638306 +15.617750 17.595304 0.739981 +15.552555 17.621113 0.824264 +15.474190 17.652138 0.894382 +15.379654 17.689564 0.950645 +16.092211 18.389452 0.638306 +16.683121 19.116880 0.638306 +16.045118 18.420238 0.739981 +15.986430 18.458609 0.824264 +16.643335 19.156664 0.739981 +16.593756 19.206245 0.824264 +15.915885 18.504728 0.894382 +15.830784 18.560366 0.950645 +16.534159 19.265842 0.894382 +16.462263 19.337736 0.950645 +17.410549 19.707790 0.638306 +18.225407 20.129936 0.638306 +17.379761 19.754883 0.739981 +17.341393 19.813570 0.824264 +18.204697 20.182251 0.739981 +18.178886 20.247444 0.824264 +17.295271 19.884115 0.894382 +17.239634 19.969215 0.950645 +18.147861 20.325809 0.894382 +18.110435 20.420345 0.950645 +19.072186 20.373405 0.638306 +19.900000 20.449354 0.638306 +19.061947 20.428730 0.739981 +19.049189 20.497677 0.824264 +19.900000 20.505619 0.739981 +19.900000 20.575735 0.824264 +19.033852 20.580553 0.894382 +19.015352 20.680529 0.950645 +19.900000 20.660019 0.894382 +19.900000 20.761694 0.950645 +20.727814 20.373405 0.638306 +21.574593 20.129936 0.638306 +20.738052 20.428730 0.739981 +20.750811 20.497677 0.824264 +21.595304 20.182251 0.739981 +21.621113 20.247444 0.824264 +20.766148 20.580553 0.894382 +20.784649 20.680529 0.950645 +21.652138 20.325809 0.894382 +21.689564 20.420345 0.950645 +22.389452 19.707790 0.638306 +23.116880 19.116880 0.638306 +22.420238 19.754883 0.739981 +22.458609 19.813570 0.824264 +23.156664 19.156664 0.739981 +23.206245 19.206245 0.824264 +22.504728 19.884115 0.894382 +22.560366 19.969215 0.950645 +23.265842 19.265842 0.894382 +23.337736 19.337736 0.950645 +23.707790 18.389452 0.638306 +24.129936 17.574593 0.638306 +23.754883 18.420238 0.739981 +23.813570 18.458609 0.824264 +24.182251 17.595304 0.739981 +24.247444 17.621113 0.824264 +23.884115 18.504728 0.894382 +23.969215 18.560366 0.950645 +24.325809 17.652138 0.894382 +24.420345 17.689564 0.950645 +24.400000 15.900000 0.400000 +24.400000 15.900000 0.000000 +15.400000 15.900000 0.000000 +15.400000 15.900000 0.400000 +15.475126 15.081166 0.000000 +15.475126 15.081166 0.400000 +15.715953 14.243574 0.000000 +15.715953 14.243574 0.400000 +16.133520 13.437556 0.000000 +16.133520 13.437556 0.400000 +16.718019 12.718019 0.000000 +16.718019 12.718019 0.400000 +17.437555 12.133520 0.000000 +17.437555 12.133520 0.400000 +18.243574 11.715953 0.000000 +18.243574 11.715953 0.400000 +19.081165 11.475126 0.000000 +19.081165 11.475126 0.400000 +19.900000 11.400000 0.000000 +19.900000 11.400000 0.400000 +20.718834 11.475126 0.000000 +20.718834 11.475126 0.400000 +21.556427 11.715953 0.000000 +21.556427 11.715953 0.400000 +22.362444 12.133520 0.000000 +22.362444 12.133520 0.400000 +23.081980 12.718019 0.000000 +23.081980 12.718019 0.400000 +23.666479 13.437556 0.000000 +23.666479 13.437556 0.400000 +24.084047 14.243574 0.000000 +24.084047 14.243574 0.400000 +24.324875 15.081166 0.000000 +24.324875 15.081166 0.400000 +0.000000 51.299999 0.000000 +0.000000 51.299999 0.200000 +0.500000 51.799999 0.200000 +0.500000 51.799999 0.000000 +0.397545 51.789391 0.200000 +0.397545 51.789391 0.000000 +0.301411 51.758869 0.200000 +0.301411 51.758869 0.000000 +0.216683 51.711983 0.200000 +0.146447 51.653553 0.200000 +0.216683 51.711983 0.000000 +0.088015 51.583317 0.200000 +0.146447 51.653553 0.000000 +0.088015 51.583317 0.000000 +0.041129 51.498589 0.200000 +0.010610 51.402454 0.200000 +0.041129 51.498589 0.000000 +0.010610 51.402454 0.000000 +0.000000 51.299999 0.200000 +0.000000 51.299999 0.000000 +0.000000 0.500000 0.000000 +0.000000 0.500000 0.200000 +0.500000 0.000000 0.000000 +0.500000 0.000000 0.200000 +0.000000 0.500000 0.200000 +0.000000 0.500000 0.000000 +0.010610 0.397545 0.200000 +0.010610 0.397545 0.000000 +0.041129 0.301411 0.200000 +0.041129 0.301411 0.000000 +0.088015 0.216683 0.200000 +0.088015 0.216683 0.000000 +0.146447 0.146447 0.200000 +0.216683 0.088015 0.200000 +0.146447 0.146447 0.000000 +0.216683 0.088015 0.000000 +0.301411 0.041129 0.200000 +0.301411 0.041129 0.000000 +0.397545 0.010610 0.200000 +0.397545 0.010610 0.000000 +39.299999 0.000000 0.200000 +0.500000 0.000000 0.200000 +0.500000 0.000000 0.000000 +39.299999 0.000000 0.000000 +39.789391 0.397545 0.000000 +39.799999 0.500000 0.000000 +39.299999 0.000000 0.200000 +39.299999 0.000000 0.000000 +39.402454 0.010610 0.200000 +39.402454 0.010610 0.000000 +39.498589 0.041129 0.200000 +39.498589 0.041129 0.000000 +39.583317 0.088015 0.200000 +39.653553 0.146447 0.200000 +39.583317 0.088015 0.000000 +39.653553 0.146447 0.000000 +39.711983 0.216683 0.200000 +39.711983 0.216683 0.000000 +39.758869 0.301411 0.200000 +39.789391 0.397545 0.200000 +39.758869 0.301411 0.000000 +39.799999 0.500000 0.200000 +39.799999 0.500000 0.200000 +39.799999 0.500000 0.000000 +39.799999 51.299999 0.000000 +39.799999 51.299999 0.200000 +39.799999 51.299999 0.200000 +39.799999 51.299999 0.000000 +39.402454 51.789391 0.000000 +39.299999 51.799999 0.000000 +39.299999 51.799999 0.200000 +39.402454 51.789391 0.200000 +39.498589 51.758869 0.000000 +39.498589 51.758869 0.200000 +39.583317 51.711983 0.000000 +39.583317 51.711983 0.200000 +39.653553 51.653553 0.000000 +39.653553 51.653553 0.200000 +39.711983 51.583317 0.000000 +39.711983 51.583317 0.200000 +39.758869 51.498589 0.000000 +39.758869 51.498589 0.200000 +39.789391 51.402454 0.000000 +39.789391 51.402454 0.200000 +39.299999 51.799999 0.200000 +39.299999 51.799999 0.000000 +0.500000 51.799999 0.000000 +0.500000 51.799999 0.200000 +15.158080 17.777283 1.000000 +24.168676 13.109230 1.000000 +39.000000 51.000000 1.000000 +0.800000 51.000000 1.000000 +24.641920 14.022717 1.000000 +39.000000 0.800000 1.000000 +24.914858 14.971989 1.000000 +25.000000 15.900000 1.000000 +24.914858 16.828012 1.000000 +24.641920 17.777283 1.000000 +24.168676 18.690769 1.000000 +23.506245 19.506245 1.000000 +22.690769 20.168676 1.000000 +21.777283 20.641920 1.000000 +20.828012 20.914858 1.000000 +23.506245 12.293756 1.000000 +19.900000 21.000000 1.000000 +22.690769 11.631323 1.000000 +0.800000 0.800000 1.000000 +21.777283 11.158080 1.000000 +20.828012 10.885142 1.000000 +19.900000 10.800000 1.000000 +18.971989 10.885142 1.000000 +18.022717 11.158080 1.000000 +17.109230 11.631323 1.000000 +16.293755 12.293756 1.000000 +15.631323 13.109230 1.000000 +15.158080 14.022717 1.000000 +18.971989 20.914858 1.000000 +14.885142 14.971989 1.000000 +18.022717 20.641920 1.000000 +14.800000 15.900000 1.000000 +17.109230 20.168676 1.000000 +14.885142 16.828012 1.000000 +16.293755 19.506245 1.000000 +15.631323 18.690769 1.000000 +39.764893 51.484047 0.000000 +39.791653 51.390980 0.000000 +23.081980 12.718019 0.000000 +22.362444 12.133520 0.000000 +39.299999 0.000000 0.000000 +21.556427 11.715953 0.000000 +20.718834 11.475126 0.000000 +19.900000 11.400000 0.000000 +19.081165 11.475126 0.000000 +18.243574 11.715953 0.000000 +17.437555 12.133520 0.000000 +16.718019 12.718019 0.000000 +16.133520 13.437556 0.000000 +15.715953 14.243574 0.000000 +23.666479 13.437556 0.000000 +24.084047 14.243574 0.000000 +15.475126 15.081166 0.000000 +0.500000 0.000000 0.000000 +0.409018 0.008347 0.000000 +0.315953 0.035106 0.000000 +0.226395 0.081502 0.000000 +0.146447 0.146447 0.000000 +0.081502 0.226395 0.000000 +0.035106 0.315953 0.000000 +0.008347 0.409018 0.000000 +0.000000 0.500000 0.000000 +15.400000 15.900000 0.000000 +15.475126 16.718834 0.000000 +15.715953 17.556427 0.000000 +16.133520 18.362444 0.000000 +16.718019 19.081980 0.000000 +17.437555 19.666479 0.000000 +18.243574 20.084047 0.000000 +19.081165 20.324875 0.000000 +19.900000 20.400000 0.000000 +20.718834 20.324875 0.000000 +24.324875 15.081166 0.000000 +39.390980 0.008347 0.000000 +39.484047 0.035106 0.000000 +39.573605 0.081502 0.000000 +39.653553 0.146447 0.000000 +39.718498 0.226395 0.000000 +39.764893 0.315953 0.000000 +39.791653 0.409018 0.000000 +39.799999 0.500000 0.000000 +39.799999 51.299999 0.000000 +24.400000 15.900000 0.000000 +24.324875 16.718834 0.000000 +24.084047 17.556427 0.000000 +23.666479 18.362444 0.000000 +23.081980 19.081980 0.000000 +22.362444 19.666479 0.000000 +21.556427 20.084047 0.000000 +0.000000 51.299999 0.000000 +0.008347 51.390980 0.000000 +0.035106 51.484047 0.000000 +0.081502 51.573605 0.000000 +0.146447 51.653553 0.000000 +0.226395 51.718498 0.000000 +0.315953 51.764893 0.000000 +0.409018 51.791653 0.000000 +0.500000 51.799999 0.000000 +39.299999 51.799999 0.000000 +39.390980 51.791653 0.000000 +39.484047 51.764893 0.000000 +39.573605 51.718498 0.000000 +39.653553 51.653553 0.000000 +39.718498 51.573605 0.000000 +23.666479 18.362444 0.400000 +24.324875 16.718834 0.000000 +24.400000 15.900000 0.000000 +24.400000 15.900000 0.400000 +24.324875 16.718834 0.400000 +24.084047 17.556427 0.000000 +24.084047 17.556427 0.400000 +23.666479 18.362444 0.000000 +15.400000 15.900000 0.400000 +15.400000 15.900000 0.000000 +15.475126 16.718834 0.400000 +15.475126 16.718834 0.000000 +15.715953 17.556427 0.400000 +15.715953 17.556427 0.000000 +16.133520 18.362444 0.400000 +16.718019 19.081980 0.400000 +16.133520 18.362444 0.000000 +17.437555 19.666479 0.400000 +16.718019 19.081980 0.000000 +18.243574 20.084047 0.400000 +17.437555 19.666479 0.000000 +18.243574 20.084047 0.000000 +19.081165 20.324875 0.400000 +19.081165 20.324875 0.000000 +19.900000 20.400000 0.400000 +20.718834 20.324875 0.400000 +19.900000 20.400000 0.000000 +20.718834 20.324875 0.000000 +21.556427 20.084047 0.400000 +21.556427 20.084047 0.000000 +22.362444 19.666479 0.400000 +22.362444 19.666479 0.000000 +23.081980 19.081980 0.400000 +23.081980 19.081980 0.000000 +0.505008 0.013356 0.345570 +0.521064 0.056169 0.494476 +0.409018 0.008347 0.200000 +0.500000 0.000000 0.200000 +0.013356 0.505008 0.345570 +0.000000 0.500000 0.200000 +0.800000 0.800000 1.000000 +0.745411 0.654430 0.986644 +0.315953 0.035106 0.200000 +0.226395 0.081502 0.200000 +0.146447 0.146447 0.200000 +0.081502 0.226395 0.200000 +0.035106 0.315953 0.200000 +0.008347 0.409018 0.200000 +0.056169 0.521064 0.494476 +0.130404 0.548901 0.637768 +0.548901 0.130404 0.637768 +0.587868 0.234315 0.765685 +0.635837 0.362232 0.869596 +0.234315 0.587868 0.765685 +0.362232 0.635837 0.869596 +0.505524 0.689572 0.943831 +0.654430 0.745411 0.986644 +0.689572 0.505524 0.943831 +0.692245 0.692245 0.989355 +0.800000 0.800000 1.000000 +0.418380 0.026657 0.371330 +0.444736 0.078840 0.531064 +0.800000 0.800000 1.000000 +0.329076 0.055186 0.383506 +0.242970 0.101895 0.391399 +0.165600 0.165600 0.394137 +0.101895 0.242970 0.391399 +0.055186 0.329076 0.383506 +0.026657 0.418380 0.371330 +0.078840 0.444736 0.531064 +0.418737 0.194833 0.692369 +0.365208 0.111093 0.550646 +0.484006 0.297878 0.805983 +0.557044 0.413837 0.892166 +0.635271 0.538242 0.952466 +0.194833 0.418737 0.692369 +0.111093 0.365208 0.550646 +0.297878 0.484006 0.805983 +0.413837 0.557044 0.892166 +0.538242 0.635271 0.952466 +0.585817 0.585817 0.957005 +0.383744 0.383744 0.820380 +0.338412 0.432723 0.816733 +0.239839 0.353995 0.705534 +0.293541 0.293541 0.710038 +0.157835 0.288158 0.563200 +0.217770 0.217770 0.567530 +0.432723 0.338412 0.816733 +0.353995 0.239839 0.705534 +0.288158 0.157835 0.563200 +39.000000 0.800000 1.000000 +0.800000 0.800000 1.000000 +0.500000 0.000000 0.200000 +39.299999 0.000000 0.200000 +0.505008 0.013356 0.345570 +39.294991 0.013356 0.345570 +0.521064 0.056169 0.494476 +39.278938 0.056169 0.494476 +0.548901 0.130404 0.637768 +39.251099 0.130404 0.637768 +0.567094 0.178917 0.704238 +39.232906 0.178917 0.704238 +0.587868 0.234315 0.765685 +39.212132 0.234315 0.765685 +0.610911 0.295761 0.821083 +39.189091 0.295761 0.821083 +0.635837 0.362232 0.869596 +39.164162 0.362232 0.869596 +0.689572 0.505524 0.943831 +39.110428 0.505524 0.943831 +0.745411 0.654430 0.986644 +39.054588 0.654430 0.986644 +0.800000 0.800000 1.000000 +0.800000 51.000000 1.000000 +0.013356 51.294991 0.345570 +0.000000 51.299999 0.200000 +0.000000 0.500000 0.200000 +0.013356 0.505008 0.345570 +0.056169 51.278938 0.494476 +0.056169 0.521064 0.494476 +0.130404 51.251099 0.637768 +0.130404 0.548901 0.637768 +0.178917 51.232906 0.704238 +0.178917 0.567094 0.704238 +0.234315 51.212132 0.765685 +0.234315 0.587868 0.765685 +0.295761 51.189091 0.821083 +0.295761 0.610911 0.821083 +0.362232 51.164162 0.869596 +0.362232 0.635837 0.869596 +0.505524 51.110428 0.943831 +0.505524 0.689572 0.943831 +0.654430 51.054588 0.986644 +0.654430 0.745411 0.986644 +39.278938 0.056169 0.494476 +39.251099 0.130404 0.637768 +39.000000 0.800000 1.000000 +39.145569 0.745411 0.986644 +39.791653 0.409018 0.200000 +39.799999 0.500000 0.200000 +39.294991 0.013356 0.345570 +39.299999 0.000000 0.200000 +39.390980 0.008347 0.200000 +39.484047 0.035106 0.200000 +39.573605 0.081502 0.200000 +39.653553 0.146447 0.200000 +39.718498 0.226395 0.200000 +39.764893 0.315953 0.200000 +39.786644 0.505008 0.345570 +39.743832 0.521064 0.494476 +39.669598 0.548901 0.637768 +39.565685 0.587868 0.765685 +39.437767 0.635837 0.869596 +39.212132 0.234315 0.765685 +39.164162 0.362232 0.869596 +39.110428 0.505524 0.943831 +39.054588 0.654430 0.986644 +39.294476 0.689572 0.943831 +39.107754 0.692245 0.989355 +39.000000 0.800000 1.000000 +39.381618 0.026657 0.371330 +39.355263 0.078840 0.531064 +39.000000 0.800000 1.000000 +39.470924 0.055186 0.383506 +39.557030 0.101895 0.391399 +39.634399 0.165600 0.394137 +39.698105 0.242970 0.391399 +39.744812 0.329076 0.383506 +39.773342 0.418380 0.371330 +39.721161 0.444736 0.531064 +39.605167 0.418737 0.692369 +39.688908 0.365208 0.550646 +39.502121 0.484006 0.805983 +39.386162 0.557044 0.892166 +39.261757 0.635271 0.952466 +39.381264 0.194833 0.692369 +39.434792 0.111093 0.550646 +39.315994 0.297878 0.805983 +39.242958 0.413837 0.892166 +39.164730 0.538242 0.952466 +39.214184 0.585817 0.957005 +39.416256 0.383744 0.820380 +39.367275 0.338412 0.816733 +39.446007 0.239839 0.705534 +39.506458 0.293541 0.710038 +39.511841 0.157835 0.563200 +39.582230 0.217770 0.567530 +39.461590 0.432723 0.816733 +39.560162 0.353995 0.705534 +39.642166 0.288158 0.563200 +0.013356 51.294991 0.345570 +0.056169 51.278938 0.494476 +0.008347 51.390980 0.200000 +0.000000 51.299999 0.200000 +0.505008 51.786644 0.345570 +0.500000 51.799999 0.200000 +0.800000 51.000000 1.000000 +0.654430 51.054588 0.986644 +0.035106 51.484047 0.200000 +0.081502 51.573605 0.200000 +0.146447 51.653553 0.200000 +0.226395 51.718498 0.200000 +0.315953 51.764893 0.200000 +0.409018 51.791653 0.200000 +0.521064 51.743832 0.494476 +0.548901 51.669598 0.637768 +0.130404 51.251099 0.637768 +0.234315 51.212132 0.765685 +0.362232 51.164162 0.869596 +0.587868 51.565685 0.765685 +0.635837 51.437767 0.869596 +0.689572 51.294476 0.943831 +0.745411 51.145569 0.986644 +0.505524 51.110428 0.943831 +0.692245 51.107754 0.989355 +0.800000 51.000000 1.000000 +0.026657 51.381618 0.371330 +0.078840 51.355263 0.531064 +0.800000 51.000000 1.000000 +0.055186 51.470924 0.383506 +0.101895 51.557030 0.391399 +0.165600 51.634399 0.394137 +0.242970 51.698105 0.391399 +0.329076 51.744812 0.383506 +0.418380 51.773342 0.371330 +0.444736 51.721161 0.531064 +0.194833 51.381264 0.692369 +0.111093 51.434792 0.550646 +0.297878 51.315994 0.805983 +0.413837 51.242958 0.892166 +0.538242 51.164730 0.952466 +0.418737 51.605167 0.692369 +0.365208 51.688908 0.550646 +0.484006 51.502121 0.805983 +0.557044 51.386162 0.892166 +0.635271 51.261757 0.952466 +0.585817 51.214184 0.957005 +0.482310 51.317692 0.901554 +0.432723 51.461590 0.816733 +0.353995 51.560162 0.705534 +0.293541 51.506458 0.710038 +0.383744 51.416256 0.820380 +0.338412 51.367275 0.816733 +0.239839 51.446007 0.705534 +0.288158 51.642166 0.563200 +0.217770 51.582230 0.567530 +0.157835 51.511841 0.563200 +39.000000 51.000000 1.000000 +39.000000 0.800000 1.000000 +39.799999 0.500000 0.200000 +39.799999 51.299999 0.200000 +39.786644 0.505008 0.345570 +39.786644 51.294991 0.345570 +39.743832 0.521064 0.494476 +39.743832 51.278938 0.494476 +39.669598 0.548901 0.637768 +39.669598 51.251099 0.637768 +39.621082 0.567094 0.704238 +39.621082 51.232906 0.704238 +39.565685 0.587868 0.765685 +39.565685 51.212132 0.765685 +39.504238 0.610911 0.821083 +39.504238 51.189091 0.821083 +39.437767 0.635837 0.869596 +39.437767 51.164162 0.869596 +39.294476 0.689572 0.943831 +39.294476 51.110428 0.943831 +39.145569 0.745411 0.986644 +39.145569 51.054588 0.986644 +0.800000 51.000000 1.000000 +39.000000 51.000000 1.000000 +39.294991 51.786644 0.345570 +39.299999 51.799999 0.200000 +0.500000 51.799999 0.200000 +0.505008 51.786644 0.345570 +39.278938 51.743832 0.494476 +0.521064 51.743832 0.494476 +39.251099 51.669598 0.637768 +0.548901 51.669598 0.637768 +39.232906 51.621082 0.704238 +0.567094 51.621082 0.704238 +39.212132 51.565685 0.765685 +0.587868 51.565685 0.765685 +39.189091 51.504238 0.821083 +0.610911 51.504238 0.821083 +39.164162 51.437767 0.869596 +0.635837 51.437767 0.869596 +39.110428 51.294476 0.943831 +0.689572 51.294476 0.943831 +39.054588 51.145569 0.986644 +0.745411 51.145569 0.986644 +39.743832 51.278938 0.494476 +39.669598 51.251099 0.637768 +39.000000 51.000000 1.000000 +39.054588 51.145569 0.986644 +39.390980 51.791653 0.200000 +39.299999 51.799999 0.200000 +39.786644 51.294991 0.345570 +39.799999 51.299999 0.200000 +39.791653 51.390980 0.200000 +39.764893 51.484047 0.200000 +39.718498 51.573605 0.200000 +39.653553 51.653553 0.200000 +39.573605 51.718498 0.200000 +39.484047 51.764893 0.200000 +39.294991 51.786644 0.345570 +39.278938 51.743832 0.494476 +39.251099 51.669598 0.637768 +39.212132 51.565685 0.765685 +39.164162 51.437767 0.869596 +39.565685 51.212132 0.765685 +39.437767 51.164162 0.869596 +39.294476 51.110428 0.943831 +39.145569 51.054588 0.986644 +39.110428 51.294476 0.943831 +39.107754 51.107754 0.989355 +39.000000 51.000000 1.000000 +39.773342 51.381618 0.371330 +39.721161 51.355263 0.531064 +39.000000 51.000000 1.000000 +39.744812 51.470924 0.383506 +39.698105 51.557030 0.391399 +39.634399 51.634399 0.394137 +39.557030 51.698105 0.391399 +39.470924 51.744812 0.383506 +39.381618 51.773342 0.371330 +39.355263 51.721161 0.531064 +39.381264 51.605167 0.692369 +39.434792 51.688908 0.550646 +39.315994 51.502121 0.805983 +39.242958 51.386162 0.892166 +39.164730 51.261757 0.952466 +39.605167 51.381264 0.692369 +39.688908 51.434792 0.550646 +39.502121 51.315994 0.805983 +39.386162 51.242958 0.892166 +39.261757 51.164730 0.952466 +39.214184 51.214184 0.957005 +39.416256 51.416256 0.820380 +39.461590 51.367275 0.816733 +39.560162 51.446007 0.705534 +39.506458 51.506458 0.710038 +39.642166 51.511841 0.563200 +39.582230 51.582230 0.567530 +39.367275 51.461590 0.816733 +39.446007 51.560162 0.705534 +39.511841 51.642166 0.563200 +24.914858 14.971989 1.000000 +24.641920 14.022717 1.000000 +24.168676 13.109230 1.000000 +23.506245 12.293756 1.000000 +22.690769 11.631323 1.000000 +21.777283 11.158080 1.000000 +20.828012 10.885142 1.000000 +19.900000 10.800000 1.000000 +18.971989 10.885142 1.000000 +18.022717 11.158080 1.000000 +17.109230 11.631323 1.000000 +16.293755 12.293756 1.000000 +15.631323 13.109230 1.000000 +15.158080 14.022717 1.000000 +14.885142 14.971989 1.000000 +14.800000 15.900000 1.000000 +14.922946 15.900000 0.987269 +15.038306 15.900000 0.950645 +15.139980 15.900000 0.894382 +15.224264 15.900000 0.824264 +15.294381 15.900000 0.739981 +15.350645 15.900000 0.638306 +15.387269 15.900000 0.522946 +15.400000 15.900000 0.400000 +15.475126 15.081166 0.400000 +15.715953 14.243574 0.400000 +16.133520 13.437556 0.400000 +16.718019 12.718019 0.400000 +17.437555 12.133520 0.400000 +18.243574 11.715953 0.400000 +19.081165 11.475126 0.400000 +19.900000 11.400000 0.400000 +20.718834 11.475126 0.400000 +21.556427 11.715953 0.400000 +22.362444 12.133520 0.400000 +23.081980 12.718019 0.400000 +23.666479 13.437556 0.400000 +24.084047 14.243574 0.400000 +24.324875 15.081166 0.400000 +24.400000 15.900000 0.400000 +24.412731 15.900000 0.522946 +24.449354 15.900000 0.638306 +24.505619 15.900000 0.739981 +24.575735 15.900000 0.824264 +24.660019 15.900000 0.894382 +24.761694 15.900000 0.950645 +24.877054 15.900000 0.987269 +25.000000 15.900000 1.000000 +24.793964 14.994360 0.987269 +24.527607 14.067972 0.987269 +24.065773 13.176507 0.987269 +23.419310 12.380692 0.987269 +22.623493 11.734228 0.987269 +21.732027 11.272393 0.987269 +20.805639 11.006036 0.987269 +19.900000 10.922946 0.987269 +18.994360 11.006036 0.987269 +18.067972 11.272393 0.987269 +17.176508 11.734228 0.987269 +16.380692 12.380692 0.987269 +15.734228 13.176507 0.987269 +15.272393 14.067972 0.987269 +15.006036 14.994360 0.987269 +15.119471 15.015351 0.950645 +15.219447 15.033853 0.894382 +15.302323 15.049189 0.824264 +15.371270 15.061948 0.739981 +15.426595 15.072186 0.638306 +15.462607 15.078850 0.522946 +15.704115 14.238888 0.522946 +16.122864 13.430590 0.522946 +16.709017 12.709017 0.522946 +17.430590 12.122864 0.522946 +18.238888 11.704115 0.522946 +19.078850 11.462607 0.522946 +19.900000 11.387269 0.522946 +20.721149 11.462607 0.522946 +21.561113 11.704115 0.522946 +22.369411 12.122864 0.522946 +23.090982 12.709017 0.522946 +23.677135 13.430590 0.522946 +24.095884 14.238888 0.522946 +24.337393 15.078850 0.522946 +24.373405 15.072186 0.638306 +24.428730 15.061948 0.739981 +24.497677 15.049189 0.824264 +24.580553 15.033853 0.894382 +24.680529 15.015351 0.950645 +24.129936 14.225407 0.638306 +24.182251 14.204697 0.739981 +24.247444 14.178886 0.824264 +24.325809 14.147862 0.894382 +24.420345 14.110436 0.950645 +23.707790 13.410548 0.638306 +23.116880 12.683121 0.638306 +23.754883 13.379761 0.739981 +23.813570 13.341392 0.824264 +23.156664 12.643336 0.739981 +23.206245 12.593756 0.824264 +23.884115 13.295271 0.894382 +23.969215 13.239634 0.950645 +23.265842 12.534158 0.894382 +23.337736 12.462263 0.950645 +22.389452 12.092211 0.638306 +21.574593 11.670063 0.638306 +22.420238 12.045118 0.739981 +22.458609 11.986430 0.824264 +21.595304 11.617750 0.739981 +21.621113 11.552555 0.824264 +22.504728 11.915885 0.894382 +22.560366 11.830784 0.950645 +21.652138 11.474190 0.894382 +21.689564 11.379654 0.950645 +20.727814 11.426595 0.638306 +19.900000 11.350645 0.638306 +20.738052 11.371270 0.739981 +20.750811 11.302323 0.824264 +19.900000 11.294381 0.739981 +19.900000 11.224264 0.824264 +20.766148 11.219447 0.894382 +20.784649 11.119471 0.950645 +19.900000 11.139980 0.894382 +19.900000 11.038306 0.950645 +19.072186 11.426595 0.638306 +18.225407 11.670063 0.638306 +19.061947 11.371270 0.739981 +19.049189 11.302323 0.824264 +18.204697 11.617750 0.739981 +18.178886 11.552555 0.824264 +19.033852 11.219447 0.894382 +19.015352 11.119471 0.950645 +18.147861 11.474190 0.894382 +18.110435 11.379654 0.950645 +17.410549 12.092211 0.638306 +16.683121 12.683121 0.638306 +17.379761 12.045118 0.739981 +17.341393 11.986430 0.824264 +16.643335 12.643336 0.739981 +16.593756 12.593756 0.824264 +17.295271 11.915885 0.894382 +17.239634 11.830784 0.950645 +16.534159 12.534158 0.894382 +16.462263 12.462263 0.950645 +16.092211 13.410548 0.638306 +15.670063 14.225407 0.638306 +16.045118 13.379761 0.739981 +15.986430 13.341392 0.824264 +15.617750 14.204697 0.739981 +15.552555 14.178886 0.824264 +15.915885 13.295271 0.894382 +15.830784 13.239634 0.950645 +15.474190 14.147862 0.894382 +15.379654 14.110436 0.950645 + + + + + + + + + + + +0.000000 0.000000 1.000000 +-0.171508 -0.112128 0.978781 +-0.190522 -0.075426 0.978781 +-0.201489 -0.037286 0.978781 +0.000000 0.000000 1.000000 +-0.190522 -0.075426 0.978781 +-0.201489 -0.037286 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.201489 -0.037286 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.201489 -0.037286 0.978781 +-0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +-0.390547 -0.072272 0.917742 +-0.204909 0.000000 0.978781 +-0.201489 -0.037286 0.978781 +-0.390547 -0.072272 0.917742 +-0.397177 0.000000 0.917742 +-0.204909 0.000000 0.978781 +-0.557175 -0.103107 0.823969 +-0.397177 0.000000 0.917742 +-0.390547 -0.072272 0.917742 +-0.557175 -0.103107 0.823969 +-0.566635 0.000000 0.823969 +-0.397177 0.000000 0.917742 +-0.695302 -0.128667 0.707107 +-0.566635 0.000000 0.823969 +-0.557175 -0.103107 0.823969 +-0.695302 -0.128667 0.707107 +-0.707107 0.000000 0.707107 +-0.566635 0.000000 0.823969 +-0.810213 -0.149932 0.566635 +-0.707107 0.000000 0.707107 +-0.695302 -0.128667 0.707107 +-0.810213 -0.149932 0.566635 +-0.823969 0.000000 0.566635 +-0.707107 0.000000 0.707107 +-0.810213 -0.149932 0.566635 +-0.917742 0.000000 0.397177 +-0.823969 0.000000 0.566635 +-0.902421 -0.166995 0.397177 +-0.917742 0.000000 0.397177 +-0.810213 -0.149932 0.566635 +-0.962441 -0.178102 0.204909 +-0.917742 0.000000 0.397177 +-0.902421 -0.166995 0.397177 +-0.962441 -0.178102 0.204909 +-0.978781 0.000000 0.204909 +-0.917742 0.000000 0.397177 +-0.962441 -0.178102 0.204909 +-1.000000 0.000000 0.000000 +-0.978781 0.000000 0.204909 +-0.962441 -0.178102 0.204909 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.910059 -0.360284 0.204909 +-0.983305 -0.181963 0.000000 +-0.962441 -0.178102 0.204909 +-0.910059 -0.360284 0.204909 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.819235 -0.535598 0.204909 +-0.929788 -0.368095 0.000000 +-0.910059 -0.360284 0.204909 +-0.819235 -0.535598 0.204909 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.692103 -0.692103 0.204909 +-0.836995 -0.547210 0.000000 +-0.819235 -0.535598 0.204909 +-0.692103 -0.692103 0.204909 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.535598 -0.819235 0.204909 +-0.707107 -0.707107 0.000000 +-0.692103 -0.692103 0.204909 +-0.535598 -0.819235 0.204909 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.360284 -0.910059 0.204909 +-0.547210 -0.836995 0.000000 +-0.535598 -0.819235 0.204909 +-0.360284 -0.910059 0.204909 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.360284 -0.910059 0.204909 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.178102 -0.962441 0.204909 +-0.181963 -0.983305 0.000000 +-0.360284 -0.910059 0.204909 +-0.178102 -0.962441 0.204909 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -0.978781 0.204909 +0.000000 -1.000000 0.000000 +-0.178102 -0.962441 0.204909 +0.178102 -0.962441 0.204909 +0.000000 -1.000000 0.000000 +0.000000 -0.978781 0.204909 +0.178102 -0.962441 0.204909 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.360284 -0.910059 0.204909 +0.181963 -0.983305 0.000000 +0.178102 -0.962441 0.204909 +0.360284 -0.910059 0.204909 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.535598 -0.819235 0.204909 +0.368095 -0.929788 0.000000 +0.360284 -0.910059 0.204909 +0.535598 -0.819235 0.204909 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.692103 -0.692103 0.204909 +0.547210 -0.836995 0.000000 +0.535598 -0.819235 0.204909 +0.692103 -0.692103 0.204909 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.692103 -0.692103 0.204909 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.819235 -0.535598 0.204909 +0.836995 -0.547210 0.000000 +0.692103 -0.692103 0.204909 +0.819235 -0.535598 0.204909 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.910059 -0.360284 0.204909 +0.929788 -0.368095 0.000000 +0.819235 -0.535598 0.204909 +0.910059 -0.360284 0.204909 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.962441 -0.178102 0.204909 +0.983305 -0.181963 0.000000 +0.910059 -0.360284 0.204909 +0.962441 -0.178102 0.204909 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.962441 -0.178102 0.204909 +0.978781 0.000000 0.204909 +1.000000 0.000000 0.000000 +0.902421 -0.166995 0.397177 +0.978781 0.000000 0.204909 +0.962441 -0.178102 0.204909 +0.902421 -0.166995 0.397177 +0.917742 0.000000 0.397177 +0.978781 0.000000 0.204909 +0.810213 -0.149932 0.566635 +0.917742 0.000000 0.397177 +0.902421 -0.166995 0.397177 +0.810213 -0.149932 0.566635 +0.823969 0.000000 0.566635 +0.917742 0.000000 0.397177 +0.695302 -0.128667 0.707107 +0.823969 0.000000 0.566635 +0.810213 -0.149932 0.566635 +0.695302 -0.128667 0.707107 +0.707107 0.000000 0.707107 +0.823969 0.000000 0.566635 +0.557175 -0.103107 0.823969 +0.707107 0.000000 0.707107 +0.695302 -0.128667 0.707107 +0.557175 -0.103107 0.823969 +0.566635 0.000000 0.823969 +0.707107 0.000000 0.707107 +0.557175 -0.103107 0.823969 +0.397177 0.000000 0.917742 +0.566635 0.000000 0.823969 +0.390547 -0.072272 0.917742 +0.397177 0.000000 0.917742 +0.557175 -0.103107 0.823969 +0.201489 -0.037286 0.978781 +0.397177 0.000000 0.917742 +0.390547 -0.072272 0.917742 +0.201489 -0.037286 0.978781 +0.204909 0.000000 0.978781 +0.397177 0.000000 0.917742 +0.201489 -0.037286 0.978781 +0.000000 0.000000 1.000000 +0.204909 0.000000 0.978781 +0.201489 -0.037286 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.201489 -0.037286 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.190522 -0.075426 0.978781 +0.000000 0.000000 1.000000 +0.201489 -0.037286 0.978781 +0.171508 -0.112128 0.978781 +0.000000 0.000000 1.000000 +0.190522 -0.075426 0.978781 +0.171508 -0.112128 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.171508 -0.112128 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.144893 -0.144893 0.978781 +0.000000 0.000000 1.000000 +0.171508 -0.112128 0.978781 +0.144893 -0.144893 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.112128 -0.171508 0.978781 +0.000000 0.000000 1.000000 +0.144893 -0.144893 0.978781 +0.075426 -0.190522 0.978781 +0.000000 0.000000 1.000000 +0.112128 -0.171508 0.978781 +0.075426 -0.190522 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.037286 -0.201489 0.978781 +0.000000 0.000000 1.000000 +0.075426 -0.190522 0.978781 +0.037286 -0.201489 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -0.204909 0.978781 +0.000000 0.000000 1.000000 +0.037286 -0.201489 0.978781 +0.000000 -0.204909 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.037286 -0.201489 0.978781 +0.000000 0.000000 1.000000 +0.000000 -0.204909 0.978781 +-0.037286 -0.201489 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.075426 -0.190522 0.978781 +0.000000 0.000000 1.000000 +-0.037286 -0.201489 0.978781 +-0.075426 -0.190522 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.112128 -0.171508 0.978781 +0.000000 0.000000 1.000000 +-0.075426 -0.190522 0.978781 +-0.112128 -0.171508 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.144893 -0.144893 0.978781 +0.000000 0.000000 1.000000 +-0.112128 -0.171508 0.978781 +-0.144893 -0.144893 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.171508 -0.112128 0.978781 +0.000000 0.000000 1.000000 +-0.144893 -0.144893 0.978781 +-0.171508 -0.112128 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.171508 -0.112128 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.962441 -0.178102 0.204909 +0.853306 -0.337816 0.397177 +0.902421 -0.166995 0.397177 +0.853306 -0.337816 0.397177 +0.962441 -0.178102 0.204909 +0.910059 -0.360284 0.204909 +0.902421 -0.166995 0.397177 +0.766117 -0.303299 0.566635 +0.810213 -0.149932 0.566635 +0.766117 -0.303299 0.566635 +0.902421 -0.166995 0.397177 +0.853306 -0.337816 0.397177 +0.810213 -0.149932 0.566635 +0.657460 -0.260282 0.707107 +0.695302 -0.128667 0.707107 +0.657460 -0.260282 0.707107 +0.810213 -0.149932 0.566635 +0.766117 -0.303299 0.566635 +0.695302 -0.128667 0.707107 +0.526850 -0.208575 0.823969 +0.557175 -0.103107 0.823969 +0.526850 -0.208575 0.823969 +0.695302 -0.128667 0.707107 +0.657460 -0.260282 0.707107 +0.557175 -0.103107 0.823969 +0.369291 -0.146199 0.917742 +0.390547 -0.072272 0.917742 +0.369291 -0.146199 0.917742 +0.557175 -0.103107 0.823969 +0.526850 -0.208575 0.823969 +0.390547 -0.072272 0.917742 +0.190522 -0.075426 0.978781 +0.201489 -0.037286 0.978781 +0.190522 -0.075426 0.978781 +0.390547 -0.072272 0.917742 +0.369291 -0.146199 0.917742 +0.910059 -0.360284 0.204909 +0.768146 -0.502197 0.397177 +0.853306 -0.337816 0.397177 +0.768146 -0.502197 0.397177 +0.910059 -0.360284 0.204909 +0.819235 -0.535598 0.204909 +0.819235 -0.535598 0.204909 +0.648942 -0.648942 0.397177 +0.768146 -0.502197 0.397177 +0.648942 -0.648942 0.397177 +0.819235 -0.535598 0.204909 +0.692103 -0.692103 0.204909 +0.853306 -0.337816 0.397177 +0.689659 -0.450884 0.566635 +0.766117 -0.303299 0.566635 +0.689659 -0.450884 0.566635 +0.853306 -0.337816 0.397177 +0.768146 -0.502197 0.397177 +0.766117 -0.303299 0.566635 +0.591845 -0.386936 0.707107 +0.657460 -0.260282 0.707107 +0.591845 -0.386936 0.707107 +0.766117 -0.303299 0.566635 +0.689659 -0.450884 0.566635 +0.768146 -0.502197 0.397177 +0.582634 -0.582634 0.566635 +0.689659 -0.450884 0.566635 +0.582634 -0.582634 0.566635 +0.768146 -0.502197 0.397177 +0.648942 -0.648942 0.397177 +0.689659 -0.450884 0.566635 +0.500000 -0.500000 0.707107 +0.591845 -0.386936 0.707107 +0.500000 -0.500000 0.707107 +0.689659 -0.450884 0.566635 +0.582634 -0.582634 0.566635 +0.657460 -0.260282 0.707107 +0.474271 -0.310068 0.823969 +0.526850 -0.208575 0.823969 +0.474271 -0.310068 0.823969 +0.657460 -0.260282 0.707107 +0.591845 -0.386936 0.707107 +0.526850 -0.208575 0.823969 +0.332436 -0.217339 0.917742 +0.369291 -0.146199 0.917742 +0.332436 -0.217339 0.917742 +0.526850 -0.208575 0.823969 +0.474271 -0.310068 0.823969 +0.591845 -0.386936 0.707107 +0.400671 -0.400671 0.823969 +0.474271 -0.310068 0.823969 +0.400671 -0.400671 0.823969 +0.591845 -0.386936 0.707107 +0.500000 -0.500000 0.707107 +0.474271 -0.310068 0.823969 +0.280847 -0.280847 0.917742 +0.332436 -0.217339 0.917742 +0.280847 -0.280847 0.917742 +0.474271 -0.310068 0.823969 +0.400671 -0.400671 0.823969 +0.369291 -0.146199 0.917742 +0.171508 -0.112128 0.978781 +0.190522 -0.075426 0.978781 +0.171508 -0.112128 0.978781 +0.369291 -0.146199 0.917742 +0.332436 -0.217339 0.917742 +0.332436 -0.217339 0.917742 +0.144893 -0.144893 0.978781 +0.171508 -0.112128 0.978781 +0.144893 -0.144893 0.978781 +0.332436 -0.217339 0.917742 +0.280847 -0.280847 0.917742 +0.692103 -0.692103 0.204909 +0.502197 -0.768146 0.397177 +0.648942 -0.648942 0.397177 +0.502197 -0.768146 0.397177 +0.692103 -0.692103 0.204909 +0.535598 -0.819235 0.204909 +0.535598 -0.819235 0.204909 +0.337816 -0.853306 0.397177 +0.502197 -0.768146 0.397177 +0.337816 -0.853306 0.397177 +0.535598 -0.819235 0.204909 +0.360284 -0.910059 0.204909 +0.648942 -0.648942 0.397177 +0.450884 -0.689659 0.566635 +0.582634 -0.582634 0.566635 +0.450884 -0.689659 0.566635 +0.648942 -0.648942 0.397177 +0.502197 -0.768146 0.397177 +0.582634 -0.582634 0.566635 +0.386936 -0.591845 0.707107 +0.500000 -0.500000 0.707107 +0.386936 -0.591845 0.707107 +0.582634 -0.582634 0.566635 +0.450884 -0.689659 0.566635 +0.502197 -0.768146 0.397177 +0.303299 -0.766117 0.566635 +0.450884 -0.689659 0.566635 +0.303299 -0.766117 0.566635 +0.502197 -0.768146 0.397177 +0.337816 -0.853306 0.397177 +0.450884 -0.689659 0.566635 +0.260282 -0.657460 0.707107 +0.386936 -0.591845 0.707107 +0.260282 -0.657460 0.707107 +0.450884 -0.689659 0.566635 +0.303299 -0.766117 0.566635 +0.500000 -0.500000 0.707107 +0.310068 -0.474271 0.823969 +0.400671 -0.400671 0.823969 +0.310068 -0.474271 0.823969 +0.500000 -0.500000 0.707107 +0.386936 -0.591845 0.707107 +0.400671 -0.400671 0.823969 +0.217339 -0.332436 0.917742 +0.280847 -0.280847 0.917742 +0.217339 -0.332436 0.917742 +0.400671 -0.400671 0.823969 +0.310068 -0.474271 0.823969 +0.386936 -0.591845 0.707107 +0.208575 -0.526850 0.823969 +0.310068 -0.474271 0.823969 +0.208575 -0.526850 0.823969 +0.386936 -0.591845 0.707107 +0.260282 -0.657460 0.707107 +0.310068 -0.474271 0.823969 +0.146199 -0.369291 0.917742 +0.217339 -0.332436 0.917742 +0.146199 -0.369291 0.917742 +0.310068 -0.474271 0.823969 +0.208575 -0.526850 0.823969 +0.280847 -0.280847 0.917742 +0.112128 -0.171508 0.978781 +0.144893 -0.144893 0.978781 +0.112128 -0.171508 0.978781 +0.280847 -0.280847 0.917742 +0.217339 -0.332436 0.917742 +0.217339 -0.332436 0.917742 +0.075426 -0.190522 0.978781 +0.112128 -0.171508 0.978781 +0.075426 -0.190522 0.978781 +0.217339 -0.332436 0.917742 +0.146199 -0.369291 0.917742 +0.360284 -0.910059 0.204909 +0.166995 -0.902421 0.397177 +0.337816 -0.853306 0.397177 +0.166995 -0.902421 0.397177 +0.360284 -0.910059 0.204909 +0.178102 -0.962441 0.204909 +0.178102 -0.962441 0.204909 +0.000000 -0.917742 0.397177 +0.166995 -0.902421 0.397177 +0.000000 -0.917742 0.397177 +0.178102 -0.962441 0.204909 +0.000000 -0.978781 0.204909 +0.337816 -0.853306 0.397177 +0.149932 -0.810213 0.566635 +0.303299 -0.766117 0.566635 +0.149932 -0.810213 0.566635 +0.337816 -0.853306 0.397177 +0.166995 -0.902421 0.397177 +0.303299 -0.766117 0.566635 +0.128667 -0.695302 0.707107 +0.260282 -0.657460 0.707107 +0.128667 -0.695302 0.707107 +0.303299 -0.766117 0.566635 +0.149932 -0.810213 0.566635 +0.166995 -0.902421 0.397177 +0.000000 -0.823969 0.566635 +0.149932 -0.810213 0.566635 +0.000000 -0.823969 0.566635 +0.166995 -0.902421 0.397177 +0.000000 -0.917742 0.397177 +0.149932 -0.810213 0.566635 +0.000000 -0.707107 0.707107 +0.128667 -0.695302 0.707107 +0.000000 -0.707107 0.707107 +0.149932 -0.810213 0.566635 +0.000000 -0.823969 0.566635 +0.260282 -0.657460 0.707107 +0.103107 -0.557175 0.823969 +0.208575 -0.526850 0.823969 +0.103107 -0.557175 0.823969 +0.260282 -0.657460 0.707107 +0.128667 -0.695302 0.707107 +0.208575 -0.526850 0.823969 +0.072272 -0.390547 0.917742 +0.146199 -0.369291 0.917742 +0.072272 -0.390547 0.917742 +0.208575 -0.526850 0.823969 +0.103107 -0.557175 0.823969 +0.128667 -0.695302 0.707107 +0.000000 -0.566635 0.823969 +0.103107 -0.557175 0.823969 +0.000000 -0.566635 0.823969 +0.128667 -0.695302 0.707107 +0.000000 -0.707107 0.707107 +0.103107 -0.557175 0.823969 +0.000000 -0.397177 0.917742 +0.072272 -0.390547 0.917742 +0.000000 -0.397177 0.917742 +0.103107 -0.557175 0.823969 +0.000000 -0.566635 0.823969 +0.146199 -0.369291 0.917742 +0.037286 -0.201489 0.978781 +0.075426 -0.190522 0.978781 +0.037286 -0.201489 0.978781 +0.146199 -0.369291 0.917742 +0.072272 -0.390547 0.917742 +0.072272 -0.390547 0.917742 +0.000000 -0.204909 0.978781 +0.037286 -0.201489 0.978781 +0.000000 -0.204909 0.978781 +0.072272 -0.390547 0.917742 +0.000000 -0.397177 0.917742 +0.000000 -0.978781 0.204909 +-0.166995 -0.902421 0.397177 +0.000000 -0.917742 0.397177 +-0.166995 -0.902421 0.397177 +0.000000 -0.978781 0.204909 +-0.178102 -0.962441 0.204909 +-0.178102 -0.962441 0.204909 +-0.337816 -0.853306 0.397177 +-0.166995 -0.902421 0.397177 +-0.337816 -0.853306 0.397177 +-0.178102 -0.962441 0.204909 +-0.360284 -0.910059 0.204909 +0.000000 -0.917742 0.397177 +-0.149932 -0.810213 0.566635 +0.000000 -0.823969 0.566635 +-0.149932 -0.810213 0.566635 +0.000000 -0.917742 0.397177 +-0.166995 -0.902421 0.397177 +0.000000 -0.823969 0.566635 +-0.128667 -0.695302 0.707107 +0.000000 -0.707107 0.707107 +-0.128667 -0.695302 0.707107 +0.000000 -0.823969 0.566635 +-0.149932 -0.810213 0.566635 +-0.166995 -0.902421 0.397177 +-0.303299 -0.766117 0.566635 +-0.149932 -0.810213 0.566635 +-0.303299 -0.766117 0.566635 +-0.166995 -0.902421 0.397177 +-0.337816 -0.853306 0.397177 +-0.149932 -0.810213 0.566635 +-0.260282 -0.657460 0.707107 +-0.128667 -0.695302 0.707107 +-0.260282 -0.657460 0.707107 +-0.149932 -0.810213 0.566635 +-0.303299 -0.766117 0.566635 +0.000000 -0.707107 0.707107 +-0.103107 -0.557175 0.823969 +0.000000 -0.566635 0.823969 +-0.103107 -0.557175 0.823969 +0.000000 -0.707107 0.707107 +-0.128667 -0.695302 0.707107 +0.000000 -0.566635 0.823969 +-0.072272 -0.390547 0.917742 +0.000000 -0.397177 0.917742 +-0.072272 -0.390547 0.917742 +0.000000 -0.566635 0.823969 +-0.103107 -0.557175 0.823969 +-0.128667 -0.695302 0.707107 +-0.208575 -0.526850 0.823969 +-0.103107 -0.557175 0.823969 +-0.208575 -0.526850 0.823969 +-0.128667 -0.695302 0.707107 +-0.260282 -0.657460 0.707107 +-0.103107 -0.557175 0.823969 +-0.146199 -0.369291 0.917742 +-0.072272 -0.390547 0.917742 +-0.146199 -0.369291 0.917742 +-0.103107 -0.557175 0.823969 +-0.208575 -0.526850 0.823969 +0.000000 -0.397177 0.917742 +-0.037286 -0.201489 0.978781 +0.000000 -0.204909 0.978781 +-0.037286 -0.201489 0.978781 +0.000000 -0.397177 0.917742 +-0.072272 -0.390547 0.917742 +-0.072272 -0.390547 0.917742 +-0.075426 -0.190522 0.978781 +-0.037286 -0.201489 0.978781 +-0.075426 -0.190522 0.978781 +-0.072272 -0.390547 0.917742 +-0.146199 -0.369291 0.917742 +-0.360284 -0.910059 0.204909 +-0.502197 -0.768146 0.397177 +-0.337816 -0.853306 0.397177 +-0.502197 -0.768146 0.397177 +-0.360284 -0.910059 0.204909 +-0.535598 -0.819235 0.204909 +-0.535598 -0.819235 0.204909 +-0.648942 -0.648942 0.397177 +-0.502197 -0.768146 0.397177 +-0.648942 -0.648942 0.397177 +-0.535598 -0.819235 0.204909 +-0.692103 -0.692103 0.204909 +-0.337816 -0.853306 0.397177 +-0.450884 -0.689659 0.566635 +-0.303299 -0.766117 0.566635 +-0.450884 -0.689659 0.566635 +-0.337816 -0.853306 0.397177 +-0.502197 -0.768146 0.397177 +-0.303299 -0.766117 0.566635 +-0.386936 -0.591845 0.707107 +-0.260282 -0.657460 0.707107 +-0.386936 -0.591845 0.707107 +-0.303299 -0.766117 0.566635 +-0.450884 -0.689659 0.566635 +-0.502197 -0.768146 0.397177 +-0.582634 -0.582634 0.566635 +-0.450884 -0.689659 0.566635 +-0.582634 -0.582634 0.566635 +-0.502197 -0.768146 0.397177 +-0.648942 -0.648942 0.397177 +-0.450884 -0.689659 0.566635 +-0.500000 -0.500000 0.707107 +-0.386936 -0.591845 0.707107 +-0.500000 -0.500000 0.707107 +-0.450884 -0.689659 0.566635 +-0.582634 -0.582634 0.566635 +-0.260282 -0.657460 0.707107 +-0.310068 -0.474271 0.823969 +-0.208575 -0.526850 0.823969 +-0.310068 -0.474271 0.823969 +-0.260282 -0.657460 0.707107 +-0.386936 -0.591845 0.707107 +-0.208575 -0.526850 0.823969 +-0.217339 -0.332436 0.917742 +-0.146199 -0.369291 0.917742 +-0.217339 -0.332436 0.917742 +-0.208575 -0.526850 0.823969 +-0.310068 -0.474271 0.823969 +-0.386936 -0.591845 0.707107 +-0.400671 -0.400671 0.823969 +-0.310068 -0.474271 0.823969 +-0.400671 -0.400671 0.823969 +-0.386936 -0.591845 0.707107 +-0.500000 -0.500000 0.707107 +-0.310068 -0.474271 0.823969 +-0.280847 -0.280847 0.917742 +-0.217339 -0.332436 0.917742 +-0.280847 -0.280847 0.917742 +-0.310068 -0.474271 0.823969 +-0.400671 -0.400671 0.823969 +-0.146199 -0.369291 0.917742 +-0.112128 -0.171508 0.978781 +-0.075426 -0.190522 0.978781 +-0.112128 -0.171508 0.978781 +-0.146199 -0.369291 0.917742 +-0.217339 -0.332436 0.917742 +-0.217339 -0.332436 0.917742 +-0.144893 -0.144893 0.978781 +-0.112128 -0.171508 0.978781 +-0.144893 -0.144893 0.978781 +-0.217339 -0.332436 0.917742 +-0.280847 -0.280847 0.917742 +-0.692103 -0.692103 0.204909 +-0.768146 -0.502197 0.397177 +-0.648942 -0.648942 0.397177 +-0.768146 -0.502197 0.397177 +-0.692103 -0.692103 0.204909 +-0.819235 -0.535598 0.204909 +-0.819235 -0.535598 0.204909 +-0.853306 -0.337816 0.397177 +-0.768146 -0.502197 0.397177 +-0.853306 -0.337816 0.397177 +-0.819235 -0.535598 0.204909 +-0.910059 -0.360284 0.204909 +-0.648942 -0.648942 0.397177 +-0.689659 -0.450884 0.566635 +-0.582634 -0.582634 0.566635 +-0.689659 -0.450884 0.566635 +-0.648942 -0.648942 0.397177 +-0.768146 -0.502197 0.397177 +-0.582634 -0.582634 0.566635 +-0.591845 -0.386936 0.707107 +-0.500000 -0.500000 0.707107 +-0.591845 -0.386936 0.707107 +-0.582634 -0.582634 0.566635 +-0.689659 -0.450884 0.566635 +-0.768146 -0.502197 0.397177 +-0.766117 -0.303299 0.566635 +-0.689659 -0.450884 0.566635 +-0.766117 -0.303299 0.566635 +-0.768146 -0.502197 0.397177 +-0.853306 -0.337816 0.397177 +-0.689659 -0.450884 0.566635 +-0.657460 -0.260282 0.707107 +-0.591845 -0.386936 0.707107 +-0.657460 -0.260282 0.707107 +-0.689659 -0.450884 0.566635 +-0.766117 -0.303299 0.566635 +-0.500000 -0.500000 0.707107 +-0.474271 -0.310068 0.823969 +-0.400671 -0.400671 0.823969 +-0.474271 -0.310068 0.823969 +-0.500000 -0.500000 0.707107 +-0.591845 -0.386936 0.707107 +-0.400671 -0.400671 0.823969 +-0.332436 -0.217339 0.917742 +-0.280847 -0.280847 0.917742 +-0.332436 -0.217339 0.917742 +-0.400671 -0.400671 0.823969 +-0.474271 -0.310068 0.823969 +-0.591845 -0.386936 0.707107 +-0.526850 -0.208575 0.823969 +-0.474271 -0.310068 0.823969 +-0.526850 -0.208575 0.823969 +-0.591845 -0.386936 0.707107 +-0.657460 -0.260282 0.707107 +-0.474271 -0.310068 0.823969 +-0.369291 -0.146199 0.917742 +-0.332436 -0.217339 0.917742 +-0.369291 -0.146199 0.917742 +-0.474271 -0.310068 0.823969 +-0.526850 -0.208575 0.823969 +-0.280847 -0.280847 0.917742 +-0.171508 -0.112128 0.978781 +-0.144893 -0.144893 0.978781 +-0.171508 -0.112128 0.978781 +-0.280847 -0.280847 0.917742 +-0.332436 -0.217339 0.917742 +-0.332436 -0.217339 0.917742 +-0.190522 -0.075426 0.978781 +-0.171508 -0.112128 0.978781 +-0.190522 -0.075426 0.978781 +-0.332436 -0.217339 0.917742 +-0.369291 -0.146199 0.917742 +-0.910059 -0.360284 0.204909 +-0.902421 -0.166995 0.397177 +-0.853306 -0.337816 0.397177 +-0.902421 -0.166995 0.397177 +-0.910059 -0.360284 0.204909 +-0.962441 -0.178102 0.204909 +-0.853306 -0.337816 0.397177 +-0.810213 -0.149932 0.566635 +-0.766117 -0.303299 0.566635 +-0.810213 -0.149932 0.566635 +-0.853306 -0.337816 0.397177 +-0.902421 -0.166995 0.397177 +-0.766117 -0.303299 0.566635 +-0.695302 -0.128667 0.707107 +-0.657460 -0.260282 0.707107 +-0.695302 -0.128667 0.707107 +-0.766117 -0.303299 0.566635 +-0.810213 -0.149932 0.566635 +-0.657460 -0.260282 0.707107 +-0.557175 -0.103107 0.823969 +-0.526850 -0.208575 0.823969 +-0.557175 -0.103107 0.823969 +-0.657460 -0.260282 0.707107 +-0.695302 -0.128667 0.707107 +-0.526850 -0.208575 0.823969 +-0.390547 -0.072272 0.917742 +-0.369291 -0.146199 0.917742 +-0.390547 -0.072272 0.917742 +-0.526850 -0.208575 0.823969 +-0.557175 -0.103107 0.823969 +-0.369291 -0.146199 0.917742 +-0.201489 -0.037286 0.978781 +-0.190522 -0.075426 0.978781 +-0.201489 -0.037286 0.978781 +-0.369291 -0.146199 0.917742 +-0.390547 -0.072272 0.917742 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.978781 0.204909 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.204909 0.978781 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.204909 0.978781 0.000000 +-0.204909 0.978781 0.000000 +0.000000 1.000000 0.000000 +-0.397177 0.917742 0.000000 +-0.204909 0.978781 0.000000 +-0.204909 0.978781 0.000000 +-0.397177 0.917742 0.000000 +-0.397177 0.917742 0.000000 +-0.204909 0.978781 0.000000 +-0.566635 0.823969 0.000000 +-0.397177 0.917742 0.000000 +-0.397177 0.917742 0.000000 +-0.566635 0.823969 0.000000 +-0.566635 0.823969 0.000000 +-0.397177 0.917742 0.000000 +-0.566635 0.823969 0.000000 +-0.707107 0.707107 0.000000 +-0.566635 0.823969 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.566635 0.823969 0.000000 +-0.707107 0.707107 0.000000 +-0.823969 0.566635 0.000000 +-0.707107 0.707107 0.000000 +-0.823969 0.566635 0.000000 +-0.823969 0.566635 0.000000 +-0.707107 0.707107 0.000000 +-0.917742 0.397177 0.000000 +-0.823969 0.566635 0.000000 +-0.823969 0.566635 0.000000 +-0.917742 0.397177 0.000000 +-0.917742 0.397177 0.000000 +-0.823969 0.566635 0.000000 +-0.917742 0.397177 0.000000 +-0.978781 0.204909 0.000000 +-0.917742 0.397177 0.000000 +-0.978781 0.204909 0.000000 +-0.978781 0.204909 0.000000 +-0.917742 0.397177 0.000000 +-1.000000 0.000000 0.000000 +-0.978781 0.204909 0.000000 +-0.978781 0.204909 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.204909 -0.978781 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.978781 -0.204909 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.978781 -0.204909 0.000000 +-0.978781 -0.204909 0.000000 +-1.000000 0.000000 0.000000 +-0.917742 -0.397177 0.000000 +-0.978781 -0.204909 0.000000 +-0.978781 -0.204909 0.000000 +-0.917742 -0.397177 0.000000 +-0.917742 -0.397177 0.000000 +-0.978781 -0.204909 0.000000 +-0.823969 -0.566635 0.000000 +-0.917742 -0.397177 0.000000 +-0.917742 -0.397177 0.000000 +-0.823969 -0.566635 0.000000 +-0.823969 -0.566635 0.000000 +-0.917742 -0.397177 0.000000 +-0.707107 -0.707107 0.000000 +-0.823969 -0.566635 0.000000 +-0.823969 -0.566635 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.823969 -0.566635 0.000000 +-0.707107 -0.707107 0.000000 +-0.566635 -0.823969 0.000000 +-0.707107 -0.707107 0.000000 +-0.566635 -0.823969 0.000000 +-0.566635 -0.823969 0.000000 +-0.707107 -0.707107 0.000000 +-0.397177 -0.917742 0.000000 +-0.566635 -0.823969 0.000000 +-0.566635 -0.823969 0.000000 +-0.397177 -0.917742 0.000000 +-0.397177 -0.917742 0.000000 +-0.566635 -0.823969 0.000000 +-0.204909 -0.978781 0.000000 +-0.397177 -0.917742 0.000000 +-0.397177 -0.917742 0.000000 +-0.204909 -0.978781 0.000000 +-0.204909 -0.978781 0.000000 +-0.397177 -0.917742 0.000000 +0.000000 -1.000000 0.000000 +-0.204909 -0.978781 0.000000 +-0.204909 -0.978781 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 0.000000 +0.978781 -0.204909 0.000000 +1.000000 0.000000 0.000000 +0.204909 -0.978781 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.204909 -0.978781 0.000000 +0.204909 -0.978781 0.000000 +0.000000 -1.000000 0.000000 +0.397177 -0.917742 0.000000 +0.204909 -0.978781 0.000000 +0.204909 -0.978781 0.000000 +0.397177 -0.917742 0.000000 +0.397177 -0.917742 0.000000 +0.204909 -0.978781 0.000000 +0.566635 -0.823969 0.000000 +0.397177 -0.917742 0.000000 +0.397177 -0.917742 0.000000 +0.566635 -0.823969 0.000000 +0.566635 -0.823969 0.000000 +0.397177 -0.917742 0.000000 +0.566635 -0.823969 0.000000 +0.707107 -0.707107 0.000000 +0.566635 -0.823969 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.566635 -0.823969 0.000000 +0.823969 -0.566635 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.823969 -0.566635 0.000000 +0.823969 -0.566635 0.000000 +0.707107 -0.707107 0.000000 +0.917742 -0.397177 0.000000 +0.823969 -0.566635 0.000000 +0.823969 -0.566635 0.000000 +0.917742 -0.397177 0.000000 +0.917742 -0.397177 0.000000 +0.823969 -0.566635 0.000000 +0.917742 -0.397177 0.000000 +0.978781 -0.204909 0.000000 +0.917742 -0.397177 0.000000 +0.978781 -0.204909 0.000000 +0.978781 -0.204909 0.000000 +0.917742 -0.397177 0.000000 +0.978781 -0.204909 0.000000 +1.000000 0.000000 0.000000 +0.978781 -0.204909 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.978781 0.204909 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.204909 0.978781 0.000000 +0.000000 1.000000 0.000000 +0.204909 0.978781 0.000000 +0.204909 0.978781 0.000000 +0.000000 1.000000 0.000000 +0.397177 0.917742 0.000000 +0.204909 0.978781 0.000000 +0.204909 0.978781 0.000000 +0.397177 0.917742 0.000000 +0.397177 0.917742 0.000000 +0.204909 0.978781 0.000000 +0.566635 0.823969 0.000000 +0.397177 0.917742 0.000000 +0.397177 0.917742 0.000000 +0.566635 0.823969 0.000000 +0.566635 0.823969 0.000000 +0.397177 0.917742 0.000000 +0.707107 0.707107 0.000000 +0.566635 0.823969 0.000000 +0.566635 0.823969 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.566635 0.823969 0.000000 +0.823969 0.566635 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.823969 0.566635 0.000000 +0.823969 0.566635 0.000000 +0.707107 0.707107 0.000000 +0.917742 0.397177 0.000000 +0.823969 0.566635 0.000000 +0.823969 0.566635 0.000000 +0.917742 0.397177 0.000000 +0.917742 0.397177 0.000000 +0.823969 0.566635 0.000000 +0.978781 0.204909 0.000000 +0.917742 0.397177 0.000000 +0.917742 0.397177 0.000000 +0.978781 0.204909 0.000000 +0.978781 0.204909 0.000000 +0.917742 0.397177 0.000000 +1.000000 0.000000 0.000000 +0.978781 0.204909 0.000000 +0.978781 0.204909 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.098479 -0.098479 0.990254 +0.001126 -0.182453 0.983214 +0.000000 0.000000 1.000000 +-0.000073 -0.929848 0.367945 +-0.175335 -0.958317 0.225581 +-0.000504 -0.983284 0.182079 +-0.000073 -0.929848 0.367945 +-0.156201 -0.887992 0.432518 +-0.175335 -0.958317 0.225581 +0.000378 -0.837003 0.547199 +-0.156201 -0.887992 0.432518 +-0.000073 -0.929848 0.367945 +-0.000504 -0.983284 0.182079 +-0.181963 -0.983305 0.000072 +0.000000 -1.000000 0.000000 +-0.175335 -0.958317 0.225581 +-0.181963 -0.983305 0.000072 +-0.000504 -0.983284 0.182079 +-0.983305 -0.181963 0.000072 +-0.983284 -0.000504 0.182079 +-1.000000 0.000000 0.000000 +-0.182453 0.001126 0.983214 +0.000000 0.000000 1.000000 +-0.000004 0.000012 1.000000 +0.000000 0.000000 1.000000 +0.001126 -0.182453 0.983214 +0.000012 -0.000004 1.000000 +-0.353906 -0.901289 0.249858 +-0.181963 -0.983305 0.000072 +-0.175335 -0.958317 0.225581 +-0.353906 -0.901289 0.249858 +-0.368095 -0.929788 0.000216 +-0.181963 -0.983305 0.000072 +-0.526021 -0.807939 0.265587 +-0.368095 -0.929788 0.000216 +-0.353906 -0.901289 0.249858 +-0.526021 -0.807939 0.265587 +-0.547210 -0.836995 0.000344 +-0.368095 -0.929788 0.000216 +-0.526021 -0.807939 0.265587 +-0.707107 -0.707107 0.000393 +-0.547210 -0.836995 0.000344 +-0.680638 -0.680638 0.271041 +-0.707107 -0.707107 0.000393 +-0.526021 -0.807939 0.265587 +-0.807939 -0.526021 0.265587 +-0.707107 -0.707107 0.000393 +-0.680638 -0.680638 0.271041 +-0.807939 -0.526021 0.265587 +-0.836995 -0.547210 0.000344 +-0.707107 -0.707107 0.000393 +-0.901289 -0.353906 0.249858 +-0.836995 -0.547210 0.000344 +-0.807939 -0.526021 0.265587 +-0.901289 -0.353906 0.249858 +-0.929788 -0.368095 0.000216 +-0.836995 -0.547210 0.000344 +-0.901289 -0.353906 0.249858 +-0.983305 -0.181963 0.000072 +-0.929788 -0.368095 0.000216 +-0.958317 -0.175335 0.225581 +-0.983305 -0.181963 0.000072 +-0.901289 -0.353906 0.249858 +-0.958317 -0.175335 0.225581 +-0.983284 -0.000504 0.182079 +-0.983305 -0.181963 0.000072 +-0.958317 -0.175335 0.225581 +-0.929848 -0.000073 0.367945 +-0.983284 -0.000504 0.182079 +-0.887992 -0.156201 0.432518 +-0.929848 -0.000073 0.367945 +-0.958317 -0.175335 0.225581 +-0.887992 -0.156201 0.432518 +-0.837003 0.000378 0.547199 +-0.929848 -0.000073 0.367945 +-0.156201 -0.887992 0.432518 +-0.263407 -0.711538 0.651406 +-0.315257 -0.823487 0.471681 +0.000378 -0.837003 0.547199 +-0.263407 -0.711538 0.651406 +-0.156201 -0.887992 0.432518 +0.000000 -0.707107 0.707107 +-0.263407 -0.711538 0.651406 +0.000378 -0.837003 0.547199 +0.000000 -0.707107 0.707107 +-0.207724 -0.579980 0.787702 +-0.263407 -0.711538 0.651406 +0.000627 -0.547428 0.836852 +-0.207724 -0.579980 0.787702 +0.000000 -0.707107 0.707107 +0.000627 -0.547428 0.836852 +-0.152272 -0.439181 0.885400 +-0.207724 -0.579980 0.787702 +0.000627 -0.547428 0.836852 +-0.099849 -0.293905 0.950605 +-0.152272 -0.439181 0.885400 +0.000134 -0.367979 0.929834 +-0.099849 -0.293905 0.950605 +0.000627 -0.547428 0.836852 +-0.711538 -0.263407 0.651406 +-0.887992 -0.156201 0.432518 +-0.823487 -0.315257 0.471681 +-0.711538 -0.263407 0.651406 +-0.837003 0.000378 0.547199 +-0.887992 -0.156201 0.432518 +-0.711538 -0.263407 0.651406 +-0.707107 0.000000 0.707107 +-0.837003 0.000378 0.547199 +-0.579980 -0.207724 0.787702 +-0.707107 0.000000 0.707107 +-0.711538 -0.263407 0.651406 +-0.439181 -0.152272 0.885400 +-0.707107 0.000000 0.707107 +-0.579980 -0.207724 0.787702 +-0.439181 -0.152272 0.885400 +-0.547428 0.000627 0.836852 +-0.707107 0.000000 0.707107 +-0.293905 -0.099849 0.950605 +-0.547428 0.000627 0.836852 +-0.439181 -0.152272 0.885400 +-0.293905 -0.099849 0.950605 +-0.367979 0.000134 0.929834 +-0.547428 0.000627 0.836852 +-0.293905 -0.099849 0.950605 +-0.182453 0.001126 0.983214 +-0.367979 0.000134 0.929834 +0.001126 -0.182453 0.983214 +-0.099849 -0.293905 0.950605 +0.000134 -0.367979 0.929834 +0.001126 -0.182453 0.983214 +-0.198757 -0.198757 0.959683 +-0.099849 -0.293905 0.950605 +-0.198757 -0.198757 0.959683 +-0.182453 0.001126 0.983214 +-0.293905 -0.099849 0.950605 +-0.098479 -0.098479 0.990254 +-0.182453 0.001126 0.983214 +-0.198757 -0.198757 0.959683 +0.001126 -0.182453 0.983214 +-0.098479 -0.098479 0.990254 +-0.198757 -0.198757 0.959683 +-0.182453 0.001126 0.983214 +-0.098479 -0.098479 0.990254 +0.000000 0.000000 1.000000 +-0.293905 -0.099849 0.950605 +-0.408249 -0.408249 0.816496 +-0.198757 -0.198757 0.959683 +-0.498913 -0.310290 0.809201 +-0.439181 -0.152272 0.885400 +-0.579980 -0.207724 0.787702 +-0.579980 -0.207724 0.787702 +-0.621468 -0.392982 0.677748 +-0.498913 -0.310290 0.809201 +-0.621468 -0.392982 0.677748 +-0.579980 -0.207724 0.787702 +-0.711538 -0.263407 0.651406 +-0.498913 -0.310290 0.809201 +-0.513984 -0.513984 0.686762 +-0.408249 -0.408249 0.816496 +-0.513984 -0.513984 0.686762 +-0.498913 -0.310290 0.809201 +-0.621468 -0.392982 0.677748 +-0.439181 -0.152272 0.885400 +-0.408249 -0.408249 0.816496 +-0.293905 -0.099849 0.950605 +-0.439181 -0.152272 0.885400 +-0.498913 -0.310290 0.809201 +-0.408249 -0.408249 0.816496 +-0.711538 -0.263407 0.651406 +-0.730003 -0.469358 0.496788 +-0.621468 -0.392982 0.677748 +-0.730003 -0.469358 0.496788 +-0.711538 -0.263407 0.651406 +-0.823487 -0.315257 0.471681 +-0.621468 -0.392982 0.677748 +-0.610133 -0.610133 0.505447 +-0.513984 -0.513984 0.686762 +-0.610133 -0.610133 0.505447 +-0.621468 -0.392982 0.677748 +-0.730003 -0.469358 0.496788 +-0.887992 -0.156201 0.432518 +-0.901289 -0.353906 0.249858 +-0.823487 -0.315257 0.471681 +-0.901289 -0.353906 0.249858 +-0.887992 -0.156201 0.432518 +-0.958317 -0.175335 0.225581 +-0.823487 -0.315257 0.471681 +-0.807939 -0.526021 0.265587 +-0.730003 -0.469358 0.496788 +-0.807939 -0.526021 0.265587 +-0.823487 -0.315257 0.471681 +-0.901289 -0.353906 0.249858 +-0.730003 -0.469358 0.496788 +-0.680638 -0.680638 0.271041 +-0.610133 -0.610133 0.505447 +-0.680638 -0.680638 0.271041 +-0.730003 -0.469358 0.496788 +-0.807939 -0.526021 0.265587 +-0.198757 -0.198757 0.959683 +-0.152272 -0.439181 0.885400 +-0.099849 -0.293905 0.950605 +-0.198757 -0.198757 0.959683 +-0.310290 -0.498913 0.809201 +-0.207724 -0.579980 0.787702 +-0.408249 -0.408249 0.816496 +-0.392982 -0.621468 0.677748 +-0.310290 -0.498913 0.809201 +-0.392982 -0.621468 0.677748 +-0.408249 -0.408249 0.816496 +-0.513984 -0.513984 0.686762 +-0.310290 -0.498913 0.809201 +-0.263407 -0.711538 0.651406 +-0.207724 -0.579980 0.787702 +-0.263407 -0.711538 0.651406 +-0.310290 -0.498913 0.809201 +-0.392982 -0.621468 0.677748 +-0.152272 -0.439181 0.885400 +-0.198757 -0.198757 0.959683 +-0.207724 -0.579980 0.787702 +-0.310290 -0.498913 0.809201 +-0.198757 -0.198757 0.959683 +-0.408249 -0.408249 0.816496 +-0.513984 -0.513984 0.686762 +-0.469358 -0.730003 0.496788 +-0.392982 -0.621468 0.677748 +-0.469358 -0.730003 0.496788 +-0.513984 -0.513984 0.686762 +-0.610133 -0.610133 0.505447 +-0.392982 -0.621468 0.677748 +-0.315257 -0.823487 0.471681 +-0.263407 -0.711538 0.651406 +-0.315257 -0.823487 0.471681 +-0.392982 -0.621468 0.677748 +-0.469358 -0.730003 0.496788 +-0.610133 -0.610133 0.505447 +-0.526021 -0.807939 0.265587 +-0.469358 -0.730003 0.496788 +-0.526021 -0.807939 0.265587 +-0.610133 -0.610133 0.505447 +-0.680638 -0.680638 0.271041 +-0.469358 -0.730003 0.496788 +-0.353906 -0.901289 0.249858 +-0.315257 -0.823487 0.471681 +-0.353906 -0.901289 0.249858 +-0.469358 -0.730003 0.496788 +-0.526021 -0.807939 0.265587 +-0.315257 -0.823487 0.471681 +-0.175335 -0.958317 0.225581 +-0.156201 -0.887992 0.432518 +-0.175335 -0.958317 0.225581 +-0.315257 -0.823487 0.471681 +-0.353906 -0.901289 0.249858 +0.000000 -0.181963 0.983305 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -0.983305 0.181963 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -0.983305 0.181963 +0.000000 -0.983305 0.181963 +0.000000 -1.000000 0.000000 +0.000000 -0.929788 0.368095 +0.000000 -0.983305 0.181963 +0.000000 -0.983305 0.181963 +0.000000 -0.929788 0.368095 +0.000000 -0.929788 0.368095 +0.000000 -0.983305 0.181963 +0.000000 -0.836995 0.547210 +0.000000 -0.929788 0.368095 +0.000000 -0.929788 0.368095 +0.000000 -0.836995 0.547210 +0.000000 -0.836995 0.547210 +0.000000 -0.929788 0.368095 +0.000000 -0.776353 0.630298 +0.000000 -0.836995 0.547210 +0.000000 -0.836995 0.547210 +0.000000 -0.776353 0.630298 +0.000000 -0.776353 0.630298 +0.000000 -0.836995 0.547210 +0.000000 -0.707107 0.707107 +0.000000 -0.776353 0.630298 +0.000000 -0.776353 0.630298 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.776353 0.630298 +0.000000 -0.630298 0.776353 +0.000000 -0.707107 0.707107 +0.000000 -0.707107 0.707107 +0.000000 -0.630298 0.776353 +0.000000 -0.630298 0.776353 +0.000000 -0.707107 0.707107 +0.000000 -0.547210 0.836995 +0.000000 -0.630298 0.776353 +0.000000 -0.630298 0.776353 +0.000000 -0.547210 0.836995 +0.000000 -0.547210 0.836995 +0.000000 -0.630298 0.776353 +0.000000 -0.368095 0.929788 +0.000000 -0.547210 0.836995 +0.000000 -0.547210 0.836995 +0.000000 -0.368095 0.929788 +0.000000 -0.368095 0.929788 +0.000000 -0.547210 0.836995 +0.000000 -0.181963 0.983305 +0.000000 -0.368095 0.929788 +0.000000 -0.368095 0.929788 +0.000000 -0.181963 0.983305 +0.000000 -0.181963 0.983305 +0.000000 -0.368095 0.929788 +0.000000 0.000000 1.000000 +0.000000 -0.181963 0.983305 +0.000000 -0.181963 0.983305 +-0.181963 0.000000 0.983305 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.000000 0.181963 +-1.000000 0.000000 0.000000 +-0.983305 0.000000 0.181963 +-0.983305 0.000000 0.181963 +-1.000000 0.000000 0.000000 +-0.929788 0.000000 0.368095 +-0.983305 0.000000 0.181963 +-0.983305 0.000000 0.181963 +-0.929788 0.000000 0.368095 +-0.929788 0.000000 0.368095 +-0.983305 0.000000 0.181963 +-0.836995 0.000000 0.547210 +-0.929788 0.000000 0.368095 +-0.929788 0.000000 0.368095 +-0.836995 0.000000 0.547210 +-0.836995 0.000000 0.547210 +-0.929788 0.000000 0.368095 +-0.776353 0.000000 0.630298 +-0.836995 0.000000 0.547210 +-0.836995 0.000000 0.547210 +-0.776353 0.000000 0.630298 +-0.776353 0.000000 0.630298 +-0.836995 0.000000 0.547210 +-0.707107 0.000000 0.707107 +-0.776353 0.000000 0.630298 +-0.776353 0.000000 0.630298 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.776353 0.000000 0.630298 +-0.630298 0.000000 0.776353 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.630298 0.000000 0.776353 +-0.630298 0.000000 0.776353 +-0.707107 0.000000 0.707107 +-0.547210 0.000000 0.836995 +-0.630298 0.000000 0.776353 +-0.630298 0.000000 0.776353 +-0.547210 0.000000 0.836995 +-0.547210 0.000000 0.836995 +-0.630298 0.000000 0.776353 +-0.368095 0.000000 0.929788 +-0.547210 0.000000 0.836995 +-0.547210 0.000000 0.836995 +-0.368095 0.000000 0.929788 +-0.368095 0.000000 0.929788 +-0.547210 0.000000 0.836995 +-0.181963 0.000000 0.983305 +-0.368095 0.000000 0.929788 +-0.368095 0.000000 0.929788 +-0.181963 0.000000 0.983305 +-0.181963 0.000000 0.983305 +-0.368095 0.000000 0.929788 +0.000000 0.000000 1.000000 +-0.181963 0.000000 0.983305 +-0.181963 0.000000 0.983305 +0.098479 -0.098479 0.990254 +0.182453 0.001126 0.983214 +0.000000 0.000000 1.000000 +0.175335 -0.958317 0.225581 +0.000073 -0.929848 0.367945 +0.000504 -0.983284 0.182079 +0.156201 -0.887992 0.432518 +0.000073 -0.929848 0.367945 +0.175335 -0.958317 0.225581 +0.156201 -0.887992 0.432518 +-0.000378 -0.837003 0.547199 +0.000073 -0.929848 0.367945 +-0.001126 -0.182453 0.983214 +0.000000 0.000000 1.000000 +-0.000012 -0.000004 1.000000 +0.000000 0.000000 1.000000 +0.182453 0.001126 0.983214 +0.000004 0.000012 1.000000 +0.983284 -0.000504 0.182079 +0.983305 -0.181963 0.000072 +1.000000 0.000000 0.000000 +0.181963 -0.983305 0.000072 +0.000504 -0.983284 0.182079 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000072 +0.175335 -0.958317 0.225581 +0.000504 -0.983284 0.182079 +0.368095 -0.929788 0.000216 +0.175335 -0.958317 0.225581 +0.181963 -0.983305 0.000072 +0.368095 -0.929788 0.000216 +0.353906 -0.901289 0.249858 +0.175335 -0.958317 0.225581 +0.547210 -0.836995 0.000344 +0.353906 -0.901289 0.249858 +0.368095 -0.929788 0.000216 +0.547210 -0.836995 0.000344 +0.526021 -0.807939 0.265587 +0.353906 -0.901289 0.249858 +0.707107 -0.707107 0.000393 +0.526021 -0.807939 0.265587 +0.547210 -0.836995 0.000344 +0.707107 -0.707107 0.000393 +0.680638 -0.680638 0.271041 +0.526021 -0.807939 0.265587 +0.836995 -0.547210 0.000344 +0.680638 -0.680638 0.271041 +0.707107 -0.707107 0.000393 +0.836995 -0.547210 0.000344 +0.807939 -0.526021 0.265587 +0.680638 -0.680638 0.271041 +0.929788 -0.368095 0.000216 +0.807939 -0.526021 0.265587 +0.836995 -0.547210 0.000344 +0.929788 -0.368095 0.000216 +0.901289 -0.353906 0.249858 +0.807939 -0.526021 0.265587 +0.983305 -0.181963 0.000072 +0.901289 -0.353906 0.249858 +0.929788 -0.368095 0.000216 +0.983305 -0.181963 0.000072 +0.958317 -0.175335 0.225581 +0.901289 -0.353906 0.249858 +0.983284 -0.000504 0.182079 +0.958317 -0.175335 0.225581 +0.983305 -0.181963 0.000072 +0.929848 -0.000073 0.367945 +0.958317 -0.175335 0.225581 +0.983284 -0.000504 0.182079 +0.929848 -0.000073 0.367945 +0.887992 -0.156201 0.432518 +0.958317 -0.175335 0.225581 +0.837003 0.000378 0.547199 +0.887992 -0.156201 0.432518 +0.929848 -0.000073 0.367945 +0.887992 -0.156201 0.432518 +0.711538 -0.263407 0.651406 +0.823487 -0.315257 0.471681 +0.837003 0.000378 0.547199 +0.711538 -0.263407 0.651406 +0.887992 -0.156201 0.432518 +0.707107 0.000000 0.707107 +0.711538 -0.263407 0.651406 +0.837003 0.000378 0.547199 +0.707107 0.000000 0.707107 +0.579980 -0.207724 0.787702 +0.711538 -0.263407 0.651406 +0.547428 0.000627 0.836852 +0.579980 -0.207724 0.787702 +0.707107 0.000000 0.707107 +0.547428 0.000627 0.836852 +0.439181 -0.152272 0.885400 +0.579980 -0.207724 0.787702 +0.547428 0.000627 0.836852 +0.293905 -0.099849 0.950605 +0.439181 -0.152272 0.885400 +0.367979 0.000134 0.929834 +0.293905 -0.099849 0.950605 +0.547428 0.000627 0.836852 +0.263407 -0.711538 0.651406 +0.156201 -0.887992 0.432518 +0.315257 -0.823487 0.471681 +0.263407 -0.711538 0.651406 +-0.000378 -0.837003 0.547199 +0.156201 -0.887992 0.432518 +0.263407 -0.711538 0.651406 +0.000000 -0.707107 0.707107 +-0.000378 -0.837003 0.547199 +0.207724 -0.579980 0.787702 +0.000000 -0.707107 0.707107 +0.263407 -0.711538 0.651406 +0.152272 -0.439181 0.885400 +0.000000 -0.707107 0.707107 +0.207724 -0.579980 0.787702 +0.152272 -0.439181 0.885400 +-0.000627 -0.547428 0.836852 +0.000000 -0.707107 0.707107 +0.099849 -0.293905 0.950605 +-0.000627 -0.547428 0.836852 +0.152272 -0.439181 0.885400 +0.099849 -0.293905 0.950605 +-0.000134 -0.367979 0.929834 +-0.000627 -0.547428 0.836852 +0.099849 -0.293905 0.950605 +-0.001126 -0.182453 0.983214 +-0.000134 -0.367979 0.929834 +0.182453 0.001126 0.983214 +0.293905 -0.099849 0.950605 +0.367979 0.000134 0.929834 +0.182453 0.001126 0.983214 +0.198757 -0.198757 0.959683 +0.293905 -0.099849 0.950605 +0.198757 -0.198757 0.959683 +-0.001126 -0.182453 0.983214 +0.099849 -0.293905 0.950605 +0.098479 -0.098479 0.990254 +-0.001126 -0.182453 0.983214 +0.198757 -0.198757 0.959683 +0.182453 0.001126 0.983214 +0.098479 -0.098479 0.990254 +0.198757 -0.198757 0.959683 +-0.001126 -0.182453 0.983214 +0.098479 -0.098479 0.990254 +0.000000 0.000000 1.000000 +0.099849 -0.293905 0.950605 +0.408249 -0.408249 0.816496 +0.198757 -0.198757 0.959683 +0.310290 -0.498913 0.809201 +0.152272 -0.439181 0.885400 +0.207724 -0.579980 0.787702 +0.207724 -0.579980 0.787702 +0.392982 -0.621468 0.677748 +0.310290 -0.498913 0.809201 +0.392982 -0.621468 0.677748 +0.207724 -0.579980 0.787702 +0.263407 -0.711538 0.651406 +0.310290 -0.498913 0.809201 +0.513984 -0.513984 0.686762 +0.408249 -0.408249 0.816496 +0.513984 -0.513984 0.686762 +0.310290 -0.498913 0.809201 +0.392982 -0.621468 0.677748 +0.152272 -0.439181 0.885400 +0.408249 -0.408249 0.816496 +0.099849 -0.293905 0.950605 +0.152272 -0.439181 0.885400 +0.310290 -0.498913 0.809201 +0.408249 -0.408249 0.816496 +0.263407 -0.711538 0.651406 +0.469358 -0.730003 0.496788 +0.392982 -0.621468 0.677748 +0.469358 -0.730003 0.496788 +0.263407 -0.711538 0.651406 +0.315257 -0.823487 0.471681 +0.392982 -0.621468 0.677748 +0.610133 -0.610133 0.505447 +0.513984 -0.513984 0.686762 +0.610133 -0.610133 0.505447 +0.392982 -0.621468 0.677748 +0.469358 -0.730003 0.496788 +0.156201 -0.887992 0.432518 +0.353906 -0.901289 0.249858 +0.315257 -0.823487 0.471681 +0.353906 -0.901289 0.249858 +0.156201 -0.887992 0.432518 +0.175335 -0.958317 0.225581 +0.315257 -0.823487 0.471681 +0.526021 -0.807939 0.265587 +0.469358 -0.730003 0.496788 +0.526021 -0.807939 0.265587 +0.315257 -0.823487 0.471681 +0.353906 -0.901289 0.249858 +0.469358 -0.730003 0.496788 +0.680638 -0.680638 0.271041 +0.610133 -0.610133 0.505447 +0.680638 -0.680638 0.271041 +0.469358 -0.730003 0.496788 +0.526021 -0.807939 0.265587 +0.198757 -0.198757 0.959683 +0.439181 -0.152272 0.885400 +0.293905 -0.099849 0.950605 +0.198757 -0.198757 0.959683 +0.498913 -0.310290 0.809201 +0.579980 -0.207724 0.787702 +0.408249 -0.408249 0.816496 +0.621468 -0.392982 0.677748 +0.498913 -0.310290 0.809201 +0.621468 -0.392982 0.677748 +0.408249 -0.408249 0.816496 +0.513984 -0.513984 0.686762 +0.498913 -0.310290 0.809201 +0.711538 -0.263407 0.651406 +0.579980 -0.207724 0.787702 +0.711538 -0.263407 0.651406 +0.498913 -0.310290 0.809201 +0.621468 -0.392982 0.677748 +0.439181 -0.152272 0.885400 +0.198757 -0.198757 0.959683 +0.579980 -0.207724 0.787702 +0.498913 -0.310290 0.809201 +0.198757 -0.198757 0.959683 +0.408249 -0.408249 0.816496 +0.513984 -0.513984 0.686762 +0.730003 -0.469358 0.496788 +0.621468 -0.392982 0.677748 +0.730003 -0.469358 0.496788 +0.513984 -0.513984 0.686762 +0.610133 -0.610133 0.505447 +0.621468 -0.392982 0.677748 +0.823487 -0.315257 0.471681 +0.711538 -0.263407 0.651406 +0.823487 -0.315257 0.471681 +0.621468 -0.392982 0.677748 +0.730003 -0.469358 0.496788 +0.610133 -0.610133 0.505447 +0.807939 -0.526021 0.265587 +0.730003 -0.469358 0.496788 +0.807939 -0.526021 0.265587 +0.610133 -0.610133 0.505447 +0.680638 -0.680638 0.271041 +0.730003 -0.469358 0.496788 +0.901289 -0.353906 0.249858 +0.823487 -0.315257 0.471681 +0.901289 -0.353906 0.249858 +0.730003 -0.469358 0.496788 +0.807939 -0.526021 0.265587 +0.823487 -0.315257 0.471681 +0.958317 -0.175335 0.225581 +0.887992 -0.156201 0.432518 +0.958317 -0.175335 0.225581 +0.823487 -0.315257 0.471681 +0.901289 -0.353906 0.249858 +-0.098479 0.098479 0.990254 +-0.182453 -0.001126 0.983214 +0.000000 0.000000 1.000000 +-0.929848 0.000073 0.367945 +-0.958317 0.175335 0.225581 +-0.983284 0.000504 0.182079 +-0.929848 0.000073 0.367945 +-0.887992 0.156201 0.432518 +-0.958317 0.175335 0.225581 +-0.837003 -0.000378 0.547199 +-0.887992 0.156201 0.432518 +-0.929848 0.000073 0.367945 +-0.983284 0.000504 0.182079 +-0.983305 0.181963 0.000072 +-1.000000 0.000000 0.000000 +-0.958317 0.175335 0.225581 +-0.983305 0.181963 0.000072 +-0.983284 0.000504 0.182079 +-0.181963 0.983305 0.000072 +-0.000504 0.983284 0.182079 +0.000000 1.000000 0.000000 +0.001126 0.182453 0.983214 +0.000000 0.000000 1.000000 +0.000012 0.000004 1.000000 +0.000000 0.000000 1.000000 +-0.182453 -0.001126 0.983214 +-0.000004 -0.000012 1.000000 +-0.901289 0.353906 0.249858 +-0.983305 0.181963 0.000072 +-0.958317 0.175335 0.225581 +-0.901289 0.353906 0.249858 +-0.929788 0.368095 0.000216 +-0.983305 0.181963 0.000072 +-0.807939 0.526021 0.265587 +-0.929788 0.368095 0.000216 +-0.901289 0.353906 0.249858 +-0.807939 0.526021 0.265587 +-0.836995 0.547210 0.000344 +-0.929788 0.368095 0.000216 +-0.680638 0.680638 0.271041 +-0.836995 0.547210 0.000344 +-0.807939 0.526021 0.265587 +-0.680638 0.680638 0.271041 +-0.707107 0.707107 0.000393 +-0.836995 0.547210 0.000344 +-0.526021 0.807939 0.265587 +-0.707107 0.707107 0.000393 +-0.680638 0.680638 0.271041 +-0.526021 0.807939 0.265587 +-0.547210 0.836995 0.000344 +-0.707107 0.707107 0.000393 +-0.353906 0.901289 0.249858 +-0.547210 0.836995 0.000344 +-0.526021 0.807939 0.265587 +-0.353906 0.901289 0.249858 +-0.368095 0.929788 0.000216 +-0.547210 0.836995 0.000344 +-0.353906 0.901289 0.249858 +-0.181963 0.983305 0.000072 +-0.368095 0.929788 0.000216 +-0.175335 0.958317 0.225581 +-0.181963 0.983305 0.000072 +-0.353906 0.901289 0.249858 +-0.175335 0.958317 0.225581 +-0.000504 0.983284 0.182079 +-0.181963 0.983305 0.000072 +-0.175335 0.958317 0.225581 +-0.000073 0.929848 0.367945 +-0.000504 0.983284 0.182079 +-0.156201 0.887992 0.432518 +-0.000073 0.929848 0.367945 +-0.175335 0.958317 0.225581 +-0.156201 0.887992 0.432518 +0.000378 0.837003 0.547199 +-0.000073 0.929848 0.367945 +-0.887992 0.156201 0.432518 +-0.711538 0.263407 0.651406 +-0.823487 0.315257 0.471681 +-0.837003 -0.000378 0.547199 +-0.711538 0.263407 0.651406 +-0.887992 0.156201 0.432518 +-0.707107 0.000000 0.707107 +-0.711538 0.263407 0.651406 +-0.837003 -0.000378 0.547199 +-0.707107 0.000000 0.707107 +-0.579980 0.207724 0.787702 +-0.711538 0.263407 0.651406 +-0.547428 -0.000627 0.836852 +-0.579980 0.207724 0.787702 +-0.707107 0.000000 0.707107 +-0.547428 -0.000627 0.836852 +-0.439181 0.152272 0.885400 +-0.579980 0.207724 0.787702 +-0.547428 -0.000627 0.836852 +-0.293905 0.099849 0.950605 +-0.439181 0.152272 0.885400 +-0.367979 -0.000134 0.929834 +-0.293905 0.099849 0.950605 +-0.547428 -0.000627 0.836852 +-0.263407 0.711538 0.651406 +-0.156201 0.887992 0.432518 +-0.315257 0.823487 0.471681 +-0.263407 0.711538 0.651406 +0.000378 0.837003 0.547199 +-0.156201 0.887992 0.432518 +-0.263407 0.711538 0.651406 +0.000000 0.707107 0.707107 +0.000378 0.837003 0.547199 +-0.207724 0.579980 0.787702 +0.000000 0.707107 0.707107 +-0.263407 0.711538 0.651406 +-0.152272 0.439181 0.885400 +0.000000 0.707107 0.707107 +-0.207724 0.579980 0.787702 +-0.152272 0.439181 0.885400 +0.000627 0.547428 0.836852 +0.000000 0.707107 0.707107 +-0.099849 0.293905 0.950605 +0.000627 0.547428 0.836852 +-0.152272 0.439181 0.885400 +-0.099849 0.293905 0.950605 +0.000134 0.367979 0.929834 +0.000627 0.547428 0.836852 +-0.099849 0.293905 0.950605 +0.001126 0.182453 0.983214 +0.000134 0.367979 0.929834 +-0.182453 -0.001126 0.983214 +-0.293905 0.099849 0.950605 +-0.367979 -0.000134 0.929834 +-0.182453 -0.001126 0.983214 +-0.198757 0.198757 0.959683 +-0.293905 0.099849 0.950605 +-0.198757 0.198757 0.959683 +0.001126 0.182453 0.983214 +-0.099849 0.293905 0.950605 +-0.098479 0.098479 0.990254 +0.001126 0.182453 0.983214 +-0.198757 0.198757 0.959683 +-0.182453 -0.001126 0.983214 +-0.098479 0.098479 0.990254 +-0.198757 0.198757 0.959683 +0.001126 0.182453 0.983214 +-0.098479 0.098479 0.990254 +0.000000 0.000000 1.000000 +-0.099849 0.293905 0.950605 +-0.302047 0.302047 0.904176 +-0.198757 0.198757 0.959683 +-0.310290 0.498913 0.809201 +-0.152272 0.439181 0.885400 +-0.207724 0.579980 0.787702 +-0.207724 0.579980 0.787702 +-0.392982 0.621468 0.677748 +-0.310290 0.498913 0.809201 +-0.392982 0.621468 0.677748 +-0.207724 0.579980 0.787702 +-0.263407 0.711538 0.651406 +-0.310290 0.498913 0.809201 +-0.513984 0.513984 0.686762 +-0.408249 0.408249 0.816496 +-0.513984 0.513984 0.686762 +-0.310290 0.498913 0.809201 +-0.392982 0.621468 0.677748 +-0.302047 0.302047 0.904176 +-0.579980 0.207724 0.787702 +-0.439181 0.152272 0.885400 +-0.302047 0.302047 0.904176 +-0.498913 0.310290 0.809201 +-0.579980 0.207724 0.787702 +-0.408249 0.408249 0.816496 +-0.621468 0.392982 0.677748 +-0.498913 0.310290 0.809201 +-0.621468 0.392982 0.677748 +-0.408249 0.408249 0.816496 +-0.513984 0.513984 0.686762 +-0.198757 0.198757 0.959683 +-0.439181 0.152272 0.885400 +-0.293905 0.099849 0.950605 +-0.439181 0.152272 0.885400 +-0.198757 0.198757 0.959683 +-0.302047 0.302047 0.904176 +-0.498913 0.310290 0.809201 +-0.711538 0.263407 0.651406 +-0.579980 0.207724 0.787702 +-0.711538 0.263407 0.651406 +-0.498913 0.310290 0.809201 +-0.621468 0.392982 0.677748 +-0.302047 0.302047 0.904176 +-0.099849 0.293905 0.950605 +-0.408249 0.408249 0.816496 +-0.152272 0.439181 0.885400 +-0.408249 0.408249 0.816496 +-0.099849 0.293905 0.950605 +-0.152272 0.439181 0.885400 +-0.310290 0.498913 0.809201 +-0.408249 0.408249 0.816496 +-0.498913 0.310290 0.809201 +-0.302047 0.302047 0.904176 +-0.408249 0.408249 0.816496 +-0.263407 0.711538 0.651406 +-0.469358 0.730003 0.496788 +-0.392982 0.621468 0.677748 +-0.469358 0.730003 0.496788 +-0.263407 0.711538 0.651406 +-0.315257 0.823487 0.471681 +-0.392982 0.621468 0.677748 +-0.610133 0.610133 0.505447 +-0.513984 0.513984 0.686762 +-0.610133 0.610133 0.505447 +-0.392982 0.621468 0.677748 +-0.469358 0.730003 0.496788 +-0.156201 0.887992 0.432518 +-0.353906 0.901289 0.249858 +-0.315257 0.823487 0.471681 +-0.353906 0.901289 0.249858 +-0.156201 0.887992 0.432518 +-0.175335 0.958317 0.225581 +-0.315257 0.823487 0.471681 +-0.526021 0.807939 0.265587 +-0.469358 0.730003 0.496788 +-0.526021 0.807939 0.265587 +-0.315257 0.823487 0.471681 +-0.353906 0.901289 0.249858 +-0.469358 0.730003 0.496788 +-0.680638 0.680638 0.271041 +-0.610133 0.610133 0.505447 +-0.680638 0.680638 0.271041 +-0.469358 0.730003 0.496788 +-0.526021 0.807939 0.265587 +-0.513984 0.513984 0.686762 +-0.730003 0.469358 0.496788 +-0.621468 0.392982 0.677748 +-0.730003 0.469358 0.496788 +-0.513984 0.513984 0.686762 +-0.610133 0.610133 0.505447 +-0.621468 0.392982 0.677748 +-0.823487 0.315257 0.471681 +-0.711538 0.263407 0.651406 +-0.823487 0.315257 0.471681 +-0.621468 0.392982 0.677748 +-0.730003 0.469358 0.496788 +-0.610133 0.610133 0.505447 +-0.807939 0.526021 0.265587 +-0.730003 0.469358 0.496788 +-0.807939 0.526021 0.265587 +-0.610133 0.610133 0.505447 +-0.680638 0.680638 0.271041 +-0.730003 0.469358 0.496788 +-0.901289 0.353906 0.249858 +-0.823487 0.315257 0.471681 +-0.901289 0.353906 0.249858 +-0.730003 0.469358 0.496788 +-0.807939 0.526021 0.265587 +-0.823487 0.315257 0.471681 +-0.958317 0.175335 0.225581 +-0.887992 0.156201 0.432518 +-0.958317 0.175335 0.225581 +-0.823487 0.315257 0.471681 +-0.901289 0.353906 0.249858 +0.181963 0.000000 0.983305 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.983305 0.000000 0.181963 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.000000 0.181963 +0.983305 0.000000 0.181963 +1.000000 0.000000 0.000000 +0.929788 0.000000 0.368095 +0.983305 0.000000 0.181963 +0.983305 0.000000 0.181963 +0.929788 0.000000 0.368095 +0.929788 0.000000 0.368095 +0.983305 0.000000 0.181963 +0.836995 0.000000 0.547210 +0.929788 0.000000 0.368095 +0.929788 0.000000 0.368095 +0.836995 0.000000 0.547210 +0.836995 0.000000 0.547210 +0.929788 0.000000 0.368095 +0.776353 0.000000 0.630298 +0.836995 0.000000 0.547210 +0.836995 0.000000 0.547210 +0.776353 0.000000 0.630298 +0.776353 0.000000 0.630298 +0.836995 0.000000 0.547210 +0.707107 0.000000 0.707107 +0.776353 0.000000 0.630298 +0.776353 0.000000 0.630298 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.776353 0.000000 0.630298 +0.630298 0.000000 0.776353 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.630298 0.000000 0.776353 +0.630298 0.000000 0.776353 +0.707107 0.000000 0.707107 +0.547210 0.000000 0.836995 +0.630298 0.000000 0.776353 +0.630298 0.000000 0.776353 +0.547210 0.000000 0.836995 +0.547210 0.000000 0.836995 +0.630298 0.000000 0.776353 +0.368095 0.000000 0.929788 +0.547210 0.000000 0.836995 +0.547210 0.000000 0.836995 +0.368095 0.000000 0.929788 +0.368095 0.000000 0.929788 +0.547210 0.000000 0.836995 +0.181963 0.000000 0.983305 +0.368095 0.000000 0.929788 +0.368095 0.000000 0.929788 +0.181963 0.000000 0.983305 +0.181963 0.000000 0.983305 +0.368095 0.000000 0.929788 +0.000000 0.000000 1.000000 +0.181963 0.000000 0.983305 +0.181963 0.000000 0.983305 +0.000000 0.181963 0.983305 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 1.000000 0.000000 +0.000000 0.983305 0.181963 +0.000000 1.000000 0.000000 +0.000000 0.983305 0.181963 +0.000000 0.983305 0.181963 +0.000000 1.000000 0.000000 +0.000000 0.929788 0.368095 +0.000000 0.983305 0.181963 +0.000000 0.983305 0.181963 +0.000000 0.929788 0.368095 +0.000000 0.929788 0.368095 +0.000000 0.983305 0.181963 +0.000000 0.836995 0.547210 +0.000000 0.929788 0.368095 +0.000000 0.929788 0.368095 +0.000000 0.836995 0.547210 +0.000000 0.836995 0.547210 +0.000000 0.929788 0.368095 +0.000000 0.776353 0.630298 +0.000000 0.836995 0.547210 +0.000000 0.836995 0.547210 +0.000000 0.776353 0.630298 +0.000000 0.776353 0.630298 +0.000000 0.836995 0.547210 +0.000000 0.707107 0.707107 +0.000000 0.776353 0.630298 +0.000000 0.776353 0.630298 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.776353 0.630298 +0.000000 0.630298 0.776353 +0.000000 0.707107 0.707107 +0.000000 0.707107 0.707107 +0.000000 0.630298 0.776353 +0.000000 0.630298 0.776353 +0.000000 0.707107 0.707107 +0.000000 0.547210 0.836995 +0.000000 0.630298 0.776353 +0.000000 0.630298 0.776353 +0.000000 0.547210 0.836995 +0.000000 0.547210 0.836995 +0.000000 0.630298 0.776353 +0.000000 0.368095 0.929788 +0.000000 0.547210 0.836995 +0.000000 0.547210 0.836995 +0.000000 0.368095 0.929788 +0.000000 0.368095 0.929788 +0.000000 0.547210 0.836995 +0.000000 0.181963 0.983305 +0.000000 0.368095 0.929788 +0.000000 0.368095 0.929788 +0.000000 0.181963 0.983305 +0.000000 0.181963 0.983305 +0.000000 0.368095 0.929788 +0.000000 0.000000 1.000000 +0.000000 0.181963 0.983305 +0.000000 0.181963 0.983305 +0.098479 0.098479 0.990254 +-0.001126 0.182453 0.983214 +0.000000 0.000000 1.000000 +0.958317 0.175335 0.225581 +0.929848 0.000073 0.367945 +0.983284 0.000504 0.182079 +0.887992 0.156201 0.432518 +0.929848 0.000073 0.367945 +0.958317 0.175335 0.225581 +0.887992 0.156201 0.432518 +0.837003 -0.000378 0.547199 +0.929848 0.000073 0.367945 +0.182453 -0.001126 0.983214 +0.000000 0.000000 1.000000 +0.000004 -0.000012 1.000000 +0.000000 0.000000 1.000000 +-0.001126 0.182453 0.983214 +-0.000012 0.000004 1.000000 +0.000504 0.983284 0.182079 +0.181963 0.983305 0.000072 +0.000000 1.000000 0.000000 +0.983305 0.181963 0.000072 +0.983284 0.000504 0.182079 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000072 +0.958317 0.175335 0.225581 +0.983284 0.000504 0.182079 +0.983305 0.181963 0.000072 +0.901289 0.353906 0.249858 +0.958317 0.175335 0.225581 +0.929788 0.368095 0.000216 +0.901289 0.353906 0.249858 +0.983305 0.181963 0.000072 +0.929788 0.368095 0.000216 +0.807939 0.526021 0.265587 +0.901289 0.353906 0.249858 +0.836995 0.547210 0.000344 +0.807939 0.526021 0.265587 +0.929788 0.368095 0.000216 +0.707107 0.707107 0.000393 +0.807939 0.526021 0.265587 +0.836995 0.547210 0.000344 +0.707107 0.707107 0.000393 +0.680638 0.680638 0.271041 +0.807939 0.526021 0.265587 +0.547210 0.836995 0.000344 +0.680638 0.680638 0.271041 +0.707107 0.707107 0.000393 +0.547210 0.836995 0.000344 +0.526021 0.807939 0.265587 +0.680638 0.680638 0.271041 +0.368095 0.929788 0.000216 +0.526021 0.807939 0.265587 +0.547210 0.836995 0.000344 +0.368095 0.929788 0.000216 +0.353906 0.901289 0.249858 +0.526021 0.807939 0.265587 +0.181963 0.983305 0.000072 +0.353906 0.901289 0.249858 +0.368095 0.929788 0.000216 +0.181963 0.983305 0.000072 +0.175335 0.958317 0.225581 +0.353906 0.901289 0.249858 +0.000504 0.983284 0.182079 +0.175335 0.958317 0.225581 +0.181963 0.983305 0.000072 +0.000073 0.929848 0.367945 +0.175335 0.958317 0.225581 +0.000504 0.983284 0.182079 +0.000073 0.929848 0.367945 +0.156201 0.887992 0.432518 +0.175335 0.958317 0.225581 +-0.000378 0.837003 0.547199 +0.156201 0.887992 0.432518 +0.000073 0.929848 0.367945 +0.156201 0.887992 0.432518 +0.263407 0.711538 0.651406 +0.315257 0.823487 0.471681 +-0.000378 0.837003 0.547199 +0.263407 0.711538 0.651406 +0.156201 0.887992 0.432518 +0.000000 0.707107 0.707107 +0.263407 0.711538 0.651406 +-0.000378 0.837003 0.547199 +0.000000 0.707107 0.707107 +0.207724 0.579980 0.787702 +0.263407 0.711538 0.651406 +-0.000627 0.547428 0.836852 +0.207724 0.579980 0.787702 +0.000000 0.707107 0.707107 +-0.000627 0.547428 0.836852 +0.152272 0.439181 0.885400 +0.207724 0.579980 0.787702 +-0.000627 0.547428 0.836852 +0.099849 0.293905 0.950605 +0.152272 0.439181 0.885400 +-0.000134 0.367979 0.929834 +0.099849 0.293905 0.950605 +-0.000627 0.547428 0.836852 +0.711538 0.263407 0.651406 +0.887992 0.156201 0.432518 +0.823487 0.315257 0.471681 +0.711538 0.263407 0.651406 +0.837003 -0.000378 0.547199 +0.887992 0.156201 0.432518 +0.711538 0.263407 0.651406 +0.707107 0.000000 0.707107 +0.837003 -0.000378 0.547199 +0.579980 0.207724 0.787702 +0.707107 0.000000 0.707107 +0.711538 0.263407 0.651406 +0.579980 0.207724 0.787702 +0.547428 -0.000627 0.836852 +0.707107 0.000000 0.707107 +0.439181 0.152272 0.885400 +0.547428 -0.000627 0.836852 +0.579980 0.207724 0.787702 +0.293905 0.099849 0.950605 +0.547428 -0.000627 0.836852 +0.439181 0.152272 0.885400 +0.293905 0.099849 0.950605 +0.367979 -0.000134 0.929834 +0.547428 -0.000627 0.836852 +0.293905 0.099849 0.950605 +0.182453 -0.001126 0.983214 +0.367979 -0.000134 0.929834 +-0.001126 0.182453 0.983214 +0.099849 0.293905 0.950605 +-0.000134 0.367979 0.929834 +-0.001126 0.182453 0.983214 +0.198757 0.198757 0.959683 +0.099849 0.293905 0.950605 +0.198757 0.198757 0.959683 +0.182453 -0.001126 0.983214 +0.293905 0.099849 0.950605 +0.098479 0.098479 0.990254 +0.182453 -0.001126 0.983214 +0.198757 0.198757 0.959683 +-0.001126 0.182453 0.983214 +0.098479 0.098479 0.990254 +0.198757 0.198757 0.959683 +0.182453 -0.001126 0.983214 +0.098479 0.098479 0.990254 +0.000000 0.000000 1.000000 +0.293905 0.099849 0.950605 +0.408249 0.408249 0.816496 +0.198757 0.198757 0.959683 +0.498913 0.310290 0.809201 +0.439181 0.152272 0.885400 +0.579980 0.207724 0.787702 +0.579980 0.207724 0.787702 +0.621468 0.392982 0.677748 +0.498913 0.310290 0.809201 +0.621468 0.392982 0.677748 +0.579980 0.207724 0.787702 +0.711538 0.263407 0.651406 +0.498913 0.310290 0.809201 +0.513984 0.513984 0.686762 +0.408249 0.408249 0.816496 +0.513984 0.513984 0.686762 +0.498913 0.310290 0.809201 +0.621468 0.392982 0.677748 +0.439181 0.152272 0.885400 +0.408249 0.408249 0.816496 +0.293905 0.099849 0.950605 +0.439181 0.152272 0.885400 +0.498913 0.310290 0.809201 +0.408249 0.408249 0.816496 +0.711538 0.263407 0.651406 +0.730003 0.469358 0.496788 +0.621468 0.392982 0.677748 +0.730003 0.469358 0.496788 +0.711538 0.263407 0.651406 +0.823487 0.315257 0.471681 +0.621468 0.392982 0.677748 +0.610133 0.610133 0.505447 +0.513984 0.513984 0.686762 +0.610133 0.610133 0.505447 +0.621468 0.392982 0.677748 +0.730003 0.469358 0.496788 +0.887992 0.156201 0.432518 +0.901289 0.353906 0.249858 +0.823487 0.315257 0.471681 +0.901289 0.353906 0.249858 +0.887992 0.156201 0.432518 +0.958317 0.175335 0.225581 +0.823487 0.315257 0.471681 +0.807939 0.526021 0.265587 +0.730003 0.469358 0.496788 +0.807939 0.526021 0.265587 +0.823487 0.315257 0.471681 +0.901289 0.353906 0.249858 +0.730003 0.469358 0.496788 +0.680638 0.680638 0.271041 +0.610133 0.610133 0.505447 +0.680638 0.680638 0.271041 +0.730003 0.469358 0.496788 +0.807939 0.526021 0.265587 +0.198757 0.198757 0.959683 +0.152272 0.439181 0.885400 +0.099849 0.293905 0.950605 +0.198757 0.198757 0.959683 +0.310290 0.498913 0.809201 +0.207724 0.579980 0.787702 +0.408249 0.408249 0.816496 +0.392982 0.621468 0.677748 +0.310290 0.498913 0.809201 +0.392982 0.621468 0.677748 +0.408249 0.408249 0.816496 +0.513984 0.513984 0.686762 +0.310290 0.498913 0.809201 +0.263407 0.711538 0.651406 +0.207724 0.579980 0.787702 +0.263407 0.711538 0.651406 +0.310290 0.498913 0.809201 +0.392982 0.621468 0.677748 +0.152272 0.439181 0.885400 +0.198757 0.198757 0.959683 +0.207724 0.579980 0.787702 +0.310290 0.498913 0.809201 +0.198757 0.198757 0.959683 +0.408249 0.408249 0.816496 +0.513984 0.513984 0.686762 +0.469358 0.730003 0.496788 +0.392982 0.621468 0.677748 +0.469358 0.730003 0.496788 +0.513984 0.513984 0.686762 +0.610133 0.610133 0.505447 +0.392982 0.621468 0.677748 +0.315257 0.823487 0.471681 +0.263407 0.711538 0.651406 +0.315257 0.823487 0.471681 +0.392982 0.621468 0.677748 +0.469358 0.730003 0.496788 +0.610133 0.610133 0.505447 +0.526021 0.807939 0.265587 +0.469358 0.730003 0.496788 +0.526021 0.807939 0.265587 +0.610133 0.610133 0.505447 +0.680638 0.680638 0.271041 +0.469358 0.730003 0.496788 +0.353906 0.901289 0.249858 +0.315257 0.823487 0.471681 +0.353906 0.901289 0.249858 +0.469358 0.730003 0.496788 +0.526021 0.807939 0.265587 +0.315257 0.823487 0.471681 +0.175335 0.958317 0.225581 +0.156201 0.887992 0.432518 +0.175335 0.958317 0.225581 +0.315257 0.823487 0.471681 +0.353906 0.901289 0.249858 +0.000000 0.000000 1.000000 +-0.201489 0.037286 0.978781 +0.000000 0.000000 1.000000 +-0.190522 0.075426 0.978781 +0.000000 0.000000 1.000000 +-0.201489 0.037286 0.978781 +-0.190522 0.075426 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.171508 0.112128 0.978781 +0.000000 0.000000 1.000000 +-0.190522 0.075426 0.978781 +-0.171508 0.112128 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.144893 0.144893 0.978781 +0.000000 0.000000 1.000000 +-0.171508 0.112128 0.978781 +-0.144893 0.144893 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.112128 0.171508 0.978781 +0.000000 0.000000 1.000000 +-0.144893 0.144893 0.978781 +-0.112128 0.171508 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.075426 0.190522 0.978781 +0.000000 0.000000 1.000000 +-0.112128 0.171508 0.978781 +-0.075426 0.190522 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.037286 0.201489 0.978781 +0.000000 0.000000 1.000000 +-0.075426 0.190522 0.978781 +-0.037286 0.201489 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.204909 0.978781 +0.000000 0.000000 1.000000 +-0.037286 0.201489 0.978781 +0.000000 0.204909 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.037286 0.201489 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.204909 0.978781 +0.037286 0.201489 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.075426 0.190522 0.978781 +0.000000 0.000000 1.000000 +0.037286 0.201489 0.978781 +0.075426 0.190522 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.112128 0.171508 0.978781 +0.000000 0.000000 1.000000 +0.075426 0.190522 0.978781 +0.112128 0.171508 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.144893 0.144893 0.978781 +0.000000 0.000000 1.000000 +0.112128 0.171508 0.978781 +0.144893 0.144893 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.171508 0.112128 0.978781 +0.000000 0.000000 1.000000 +0.144893 0.144893 0.978781 +0.171508 0.112128 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.190522 0.075426 0.978781 +0.000000 0.000000 1.000000 +0.171508 0.112128 0.978781 +0.190522 0.075426 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.201489 0.037286 0.978781 +0.000000 0.000000 1.000000 +0.190522 0.075426 0.978781 +0.201489 0.037286 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.201489 0.037286 0.978781 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.201489 0.037286 0.978781 +0.204909 0.000000 0.978781 +0.000000 0.000000 1.000000 +0.390547 0.072272 0.917742 +0.204909 0.000000 0.978781 +0.201489 0.037286 0.978781 +0.390547 0.072272 0.917742 +0.397177 0.000000 0.917742 +0.204909 0.000000 0.978781 +0.557175 0.103107 0.823969 +0.397177 0.000000 0.917742 +0.390547 0.072272 0.917742 +0.557175 0.103107 0.823969 +0.566635 0.000000 0.823969 +0.397177 0.000000 0.917742 +0.695302 0.128667 0.707107 +0.566635 0.000000 0.823969 +0.557175 0.103107 0.823969 +0.695302 0.128667 0.707107 +0.707107 0.000000 0.707107 +0.566635 0.000000 0.823969 +0.810213 0.149932 0.566635 +0.707107 0.000000 0.707107 +0.695302 0.128667 0.707107 +0.810213 0.149932 0.566635 +0.823969 0.000000 0.566635 +0.707107 0.000000 0.707107 +0.810213 0.149932 0.566635 +0.917742 0.000000 0.397177 +0.823969 0.000000 0.566635 +0.902421 0.166995 0.397177 +0.917742 0.000000 0.397177 +0.810213 0.149932 0.566635 +0.902421 0.166995 0.397177 +0.978781 0.000000 0.204909 +0.917742 0.000000 0.397177 +0.962441 0.178102 0.204909 +0.978781 0.000000 0.204909 +0.902421 0.166995 0.397177 +0.962441 0.178102 0.204909 +1.000000 0.000000 0.000000 +0.978781 0.000000 0.204909 +0.962441 0.178102 0.204909 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.910059 0.360284 0.204909 +0.983305 0.181963 0.000000 +0.962441 0.178102 0.204909 +0.910059 0.360284 0.204909 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.819235 0.535598 0.204909 +0.929788 0.368095 0.000000 +0.910059 0.360284 0.204909 +0.819235 0.535598 0.204909 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.692103 0.692103 0.204909 +0.836995 0.547210 0.000000 +0.819235 0.535598 0.204909 +0.692103 0.692103 0.204909 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.535598 0.819235 0.204909 +0.707107 0.707107 0.000000 +0.692103 0.692103 0.204909 +0.535598 0.819235 0.204909 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.360284 0.910059 0.204909 +0.547210 0.836995 0.000000 +0.535598 0.819235 0.204909 +0.360284 0.910059 0.204909 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.178102 0.962441 0.204909 +0.368095 0.929788 0.000000 +0.360284 0.910059 0.204909 +0.178102 0.962441 0.204909 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.000000 0.978781 0.204909 +0.181963 0.983305 0.000000 +0.178102 0.962441 0.204909 +0.000000 0.978781 0.204909 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +-0.178102 0.962441 0.204909 +0.000000 1.000000 0.000000 +0.000000 0.978781 0.204909 +-0.178102 0.962441 0.204909 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.360284 0.910059 0.204909 +-0.181963 0.983305 0.000000 +-0.178102 0.962441 0.204909 +-0.360284 0.910059 0.204909 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.535598 0.819235 0.204909 +-0.368095 0.929788 0.000000 +-0.360284 0.910059 0.204909 +-0.535598 0.819235 0.204909 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.692103 0.692103 0.204909 +-0.547210 0.836995 0.000000 +-0.535598 0.819235 0.204909 +-0.692103 0.692103 0.204909 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.819235 0.535598 0.204909 +-0.707107 0.707107 0.000000 +-0.692103 0.692103 0.204909 +-0.819235 0.535598 0.204909 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.910059 0.360284 0.204909 +-0.836995 0.547210 0.000000 +-0.819235 0.535598 0.204909 +-0.910059 0.360284 0.204909 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.962441 0.178102 0.204909 +-0.929788 0.368095 0.000000 +-0.910059 0.360284 0.204909 +-0.962441 0.178102 0.204909 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.962441 0.178102 0.204909 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.962441 0.178102 0.204909 +-0.978781 0.000000 0.204909 +-1.000000 0.000000 0.000000 +-0.902421 0.166995 0.397177 +-0.978781 0.000000 0.204909 +-0.962441 0.178102 0.204909 +-0.902421 0.166995 0.397177 +-0.917742 0.000000 0.397177 +-0.978781 0.000000 0.204909 +-0.902421 0.166995 0.397177 +-0.823969 0.000000 0.566635 +-0.917742 0.000000 0.397177 +-0.810213 0.149932 0.566635 +-0.823969 0.000000 0.566635 +-0.902421 0.166995 0.397177 +-0.695302 0.128667 0.707107 +-0.823969 0.000000 0.566635 +-0.810213 0.149932 0.566635 +-0.695302 0.128667 0.707107 +-0.707107 0.000000 0.707107 +-0.823969 0.000000 0.566635 +-0.695302 0.128667 0.707107 +-0.566635 0.000000 0.823969 +-0.707107 0.000000 0.707107 +-0.557175 0.103107 0.823969 +-0.566635 0.000000 0.823969 +-0.695302 0.128667 0.707107 +-0.557175 0.103107 0.823969 +-0.397177 0.000000 0.917742 +-0.566635 0.000000 0.823969 +-0.390547 0.072272 0.917742 +-0.397177 0.000000 0.917742 +-0.557175 0.103107 0.823969 +-0.201489 0.037286 0.978781 +-0.397177 0.000000 0.917742 +-0.390547 0.072272 0.917742 +-0.201489 0.037286 0.978781 +-0.204909 0.000000 0.978781 +-0.397177 0.000000 0.917742 +-0.201489 0.037286 0.978781 +0.000000 0.000000 1.000000 +-0.204909 0.000000 0.978781 +-0.962441 0.178102 0.204909 +-0.853306 0.337816 0.397177 +-0.902421 0.166995 0.397177 +-0.853306 0.337816 0.397177 +-0.962441 0.178102 0.204909 +-0.910059 0.360284 0.204909 +-0.902421 0.166995 0.397177 +-0.766117 0.303299 0.566635 +-0.810213 0.149932 0.566635 +-0.766117 0.303299 0.566635 +-0.902421 0.166995 0.397177 +-0.853306 0.337816 0.397177 +-0.810213 0.149932 0.566635 +-0.657460 0.260282 0.707107 +-0.695302 0.128667 0.707107 +-0.657460 0.260282 0.707107 +-0.810213 0.149932 0.566635 +-0.766117 0.303299 0.566635 +-0.695302 0.128667 0.707107 +-0.526850 0.208575 0.823969 +-0.557175 0.103107 0.823969 +-0.526850 0.208575 0.823969 +-0.695302 0.128667 0.707107 +-0.657460 0.260282 0.707107 +-0.557175 0.103107 0.823969 +-0.369291 0.146199 0.917742 +-0.390547 0.072272 0.917742 +-0.369291 0.146199 0.917742 +-0.557175 0.103107 0.823969 +-0.526850 0.208575 0.823969 +-0.390547 0.072272 0.917742 +-0.190522 0.075426 0.978781 +-0.201489 0.037286 0.978781 +-0.190522 0.075426 0.978781 +-0.390547 0.072272 0.917742 +-0.369291 0.146199 0.917742 +-0.910059 0.360284 0.204909 +-0.768146 0.502197 0.397177 +-0.853306 0.337816 0.397177 +-0.768146 0.502197 0.397177 +-0.910059 0.360284 0.204909 +-0.819235 0.535598 0.204909 +-0.819235 0.535598 0.204909 +-0.648942 0.648942 0.397177 +-0.768146 0.502197 0.397177 +-0.648942 0.648942 0.397177 +-0.819235 0.535598 0.204909 +-0.692103 0.692103 0.204909 +-0.853306 0.337816 0.397177 +-0.689659 0.450884 0.566635 +-0.766117 0.303299 0.566635 +-0.689659 0.450884 0.566635 +-0.853306 0.337816 0.397177 +-0.768146 0.502197 0.397177 +-0.766117 0.303299 0.566635 +-0.591845 0.386936 0.707107 +-0.657460 0.260282 0.707107 +-0.591845 0.386936 0.707107 +-0.766117 0.303299 0.566635 +-0.689659 0.450884 0.566635 +-0.768146 0.502197 0.397177 +-0.582634 0.582634 0.566635 +-0.689659 0.450884 0.566635 +-0.582634 0.582634 0.566635 +-0.768146 0.502197 0.397177 +-0.648942 0.648942 0.397177 +-0.689659 0.450884 0.566635 +-0.500000 0.500000 0.707107 +-0.591845 0.386936 0.707107 +-0.500000 0.500000 0.707107 +-0.689659 0.450884 0.566635 +-0.582634 0.582634 0.566635 +-0.657460 0.260282 0.707107 +-0.474271 0.310068 0.823969 +-0.526850 0.208575 0.823969 +-0.474271 0.310068 0.823969 +-0.657460 0.260282 0.707107 +-0.591845 0.386936 0.707107 +-0.526850 0.208575 0.823969 +-0.332436 0.217339 0.917742 +-0.369291 0.146199 0.917742 +-0.332436 0.217339 0.917742 +-0.526850 0.208575 0.823969 +-0.474271 0.310068 0.823969 +-0.591845 0.386936 0.707107 +-0.400671 0.400671 0.823969 +-0.474271 0.310068 0.823969 +-0.400671 0.400671 0.823969 +-0.591845 0.386936 0.707107 +-0.500000 0.500000 0.707107 +-0.474271 0.310068 0.823969 +-0.280847 0.280847 0.917742 +-0.332436 0.217339 0.917742 +-0.280847 0.280847 0.917742 +-0.474271 0.310068 0.823969 +-0.400671 0.400671 0.823969 +-0.369291 0.146199 0.917742 +-0.171508 0.112128 0.978781 +-0.190522 0.075426 0.978781 +-0.171508 0.112128 0.978781 +-0.369291 0.146199 0.917742 +-0.332436 0.217339 0.917742 +-0.332436 0.217339 0.917742 +-0.144893 0.144893 0.978781 +-0.171508 0.112128 0.978781 +-0.144893 0.144893 0.978781 +-0.332436 0.217339 0.917742 +-0.280847 0.280847 0.917742 +-0.692103 0.692103 0.204909 +-0.502197 0.768146 0.397177 +-0.648942 0.648942 0.397177 +-0.502197 0.768146 0.397177 +-0.692103 0.692103 0.204909 +-0.535598 0.819235 0.204909 +-0.535598 0.819235 0.204909 +-0.337816 0.853306 0.397177 +-0.502197 0.768146 0.397177 +-0.337816 0.853306 0.397177 +-0.535598 0.819235 0.204909 +-0.360284 0.910059 0.204909 +-0.648942 0.648942 0.397177 +-0.450884 0.689659 0.566635 +-0.582634 0.582634 0.566635 +-0.450884 0.689659 0.566635 +-0.648942 0.648942 0.397177 +-0.502197 0.768146 0.397177 +-0.582634 0.582634 0.566635 +-0.386936 0.591845 0.707107 +-0.500000 0.500000 0.707107 +-0.386936 0.591845 0.707107 +-0.582634 0.582634 0.566635 +-0.450884 0.689659 0.566635 +-0.502197 0.768146 0.397177 +-0.303299 0.766117 0.566635 +-0.450884 0.689659 0.566635 +-0.303299 0.766117 0.566635 +-0.502197 0.768146 0.397177 +-0.337816 0.853306 0.397177 +-0.450884 0.689659 0.566635 +-0.260282 0.657460 0.707107 +-0.386936 0.591845 0.707107 +-0.260282 0.657460 0.707107 +-0.450884 0.689659 0.566635 +-0.303299 0.766117 0.566635 +-0.500000 0.500000 0.707107 +-0.310068 0.474271 0.823969 +-0.400671 0.400671 0.823969 +-0.310068 0.474271 0.823969 +-0.500000 0.500000 0.707107 +-0.386936 0.591845 0.707107 +-0.400671 0.400671 0.823969 +-0.217339 0.332436 0.917742 +-0.280847 0.280847 0.917742 +-0.217339 0.332436 0.917742 +-0.400671 0.400671 0.823969 +-0.310068 0.474271 0.823969 +-0.386936 0.591845 0.707107 +-0.208575 0.526850 0.823969 +-0.310068 0.474271 0.823969 +-0.208575 0.526850 0.823969 +-0.386936 0.591845 0.707107 +-0.260282 0.657460 0.707107 +-0.310068 0.474271 0.823969 +-0.146199 0.369291 0.917742 +-0.217339 0.332436 0.917742 +-0.146199 0.369291 0.917742 +-0.310068 0.474271 0.823969 +-0.208575 0.526850 0.823969 +-0.280847 0.280847 0.917742 +-0.112128 0.171508 0.978781 +-0.144893 0.144893 0.978781 +-0.112128 0.171508 0.978781 +-0.280847 0.280847 0.917742 +-0.217339 0.332436 0.917742 +-0.217339 0.332436 0.917742 +-0.075426 0.190522 0.978781 +-0.112128 0.171508 0.978781 +-0.075426 0.190522 0.978781 +-0.217339 0.332436 0.917742 +-0.146199 0.369291 0.917742 +-0.360284 0.910059 0.204909 +-0.166995 0.902421 0.397177 +-0.337816 0.853306 0.397177 +-0.166995 0.902421 0.397177 +-0.360284 0.910059 0.204909 +-0.178102 0.962441 0.204909 +-0.178102 0.962441 0.204909 +0.000000 0.917742 0.397177 +-0.166995 0.902421 0.397177 +0.000000 0.917742 0.397177 +-0.178102 0.962441 0.204909 +0.000000 0.978781 0.204909 +-0.337816 0.853306 0.397177 +-0.149932 0.810213 0.566635 +-0.303299 0.766117 0.566635 +-0.149932 0.810213 0.566635 +-0.337816 0.853306 0.397177 +-0.166995 0.902421 0.397177 +-0.303299 0.766117 0.566635 +-0.128667 0.695302 0.707107 +-0.260282 0.657460 0.707107 +-0.128667 0.695302 0.707107 +-0.303299 0.766117 0.566635 +-0.149932 0.810213 0.566635 +-0.166995 0.902421 0.397177 +0.000000 0.823969 0.566635 +-0.149932 0.810213 0.566635 +0.000000 0.823969 0.566635 +-0.166995 0.902421 0.397177 +0.000000 0.917742 0.397177 +-0.149932 0.810213 0.566635 +0.000000 0.707107 0.707107 +-0.128667 0.695302 0.707107 +0.000000 0.707107 0.707107 +-0.149932 0.810213 0.566635 +0.000000 0.823969 0.566635 +-0.260282 0.657460 0.707107 +-0.103107 0.557175 0.823969 +-0.208575 0.526850 0.823969 +-0.103107 0.557175 0.823969 +-0.260282 0.657460 0.707107 +-0.128667 0.695302 0.707107 +-0.208575 0.526850 0.823969 +-0.072272 0.390547 0.917742 +-0.146199 0.369291 0.917742 +-0.072272 0.390547 0.917742 +-0.208575 0.526850 0.823969 +-0.103107 0.557175 0.823969 +-0.128667 0.695302 0.707107 +0.000000 0.566635 0.823969 +-0.103107 0.557175 0.823969 +0.000000 0.566635 0.823969 +-0.128667 0.695302 0.707107 +0.000000 0.707107 0.707107 +-0.103107 0.557175 0.823969 +0.000000 0.397177 0.917742 +-0.072272 0.390547 0.917742 +0.000000 0.397177 0.917742 +-0.103107 0.557175 0.823969 +0.000000 0.566635 0.823969 +-0.146199 0.369291 0.917742 +-0.037286 0.201489 0.978781 +-0.075426 0.190522 0.978781 +-0.037286 0.201489 0.978781 +-0.146199 0.369291 0.917742 +-0.072272 0.390547 0.917742 +-0.072272 0.390547 0.917742 +0.000000 0.204909 0.978781 +-0.037286 0.201489 0.978781 +0.000000 0.204909 0.978781 +-0.072272 0.390547 0.917742 +0.000000 0.397177 0.917742 +0.000000 0.978781 0.204909 +0.166995 0.902421 0.397177 +0.000000 0.917742 0.397177 +0.166995 0.902421 0.397177 +0.000000 0.978781 0.204909 +0.178102 0.962441 0.204909 +0.178102 0.962441 0.204909 +0.337816 0.853306 0.397177 +0.166995 0.902421 0.397177 +0.337816 0.853306 0.397177 +0.178102 0.962441 0.204909 +0.360284 0.910059 0.204909 +0.000000 0.917742 0.397177 +0.149932 0.810213 0.566635 +0.000000 0.823969 0.566635 +0.149932 0.810213 0.566635 +0.000000 0.917742 0.397177 +0.166995 0.902421 0.397177 +0.000000 0.823969 0.566635 +0.128667 0.695302 0.707107 +0.000000 0.707107 0.707107 +0.128667 0.695302 0.707107 +0.000000 0.823969 0.566635 +0.149932 0.810213 0.566635 +0.166995 0.902421 0.397177 +0.303299 0.766117 0.566635 +0.149932 0.810213 0.566635 +0.303299 0.766117 0.566635 +0.166995 0.902421 0.397177 +0.337816 0.853306 0.397177 +0.149932 0.810213 0.566635 +0.260282 0.657460 0.707107 +0.128667 0.695302 0.707107 +0.260282 0.657460 0.707107 +0.149932 0.810213 0.566635 +0.303299 0.766117 0.566635 +0.000000 0.707107 0.707107 +0.103107 0.557175 0.823969 +0.000000 0.566635 0.823969 +0.103107 0.557175 0.823969 +0.000000 0.707107 0.707107 +0.128667 0.695302 0.707107 +0.000000 0.566635 0.823969 +0.072272 0.390547 0.917742 +0.000000 0.397177 0.917742 +0.072272 0.390547 0.917742 +0.000000 0.566635 0.823969 +0.103107 0.557175 0.823969 +0.128667 0.695302 0.707107 +0.208575 0.526850 0.823969 +0.103107 0.557175 0.823969 +0.208575 0.526850 0.823969 +0.128667 0.695302 0.707107 +0.260282 0.657460 0.707107 +0.103107 0.557175 0.823969 +0.146199 0.369291 0.917742 +0.072272 0.390547 0.917742 +0.146199 0.369291 0.917742 +0.103107 0.557175 0.823969 +0.208575 0.526850 0.823969 +0.000000 0.397177 0.917742 +0.037286 0.201489 0.978781 +0.000000 0.204909 0.978781 +0.037286 0.201489 0.978781 +0.000000 0.397177 0.917742 +0.072272 0.390547 0.917742 +0.072272 0.390547 0.917742 +0.075426 0.190522 0.978781 +0.037286 0.201489 0.978781 +0.075426 0.190522 0.978781 +0.072272 0.390547 0.917742 +0.146199 0.369291 0.917742 +0.360284 0.910059 0.204909 +0.502197 0.768146 0.397177 +0.337816 0.853306 0.397177 +0.502197 0.768146 0.397177 +0.360284 0.910059 0.204909 +0.535598 0.819235 0.204909 +0.535598 0.819235 0.204909 +0.648942 0.648942 0.397177 +0.502197 0.768146 0.397177 +0.648942 0.648942 0.397177 +0.535598 0.819235 0.204909 +0.692103 0.692103 0.204909 +0.337816 0.853306 0.397177 +0.450884 0.689659 0.566635 +0.303299 0.766117 0.566635 +0.450884 0.689659 0.566635 +0.337816 0.853306 0.397177 +0.502197 0.768146 0.397177 +0.303299 0.766117 0.566635 +0.386936 0.591845 0.707107 +0.260282 0.657460 0.707107 +0.386936 0.591845 0.707107 +0.303299 0.766117 0.566635 +0.450884 0.689659 0.566635 +0.502197 0.768146 0.397177 +0.582634 0.582634 0.566635 +0.450884 0.689659 0.566635 +0.582634 0.582634 0.566635 +0.502197 0.768146 0.397177 +0.648942 0.648942 0.397177 +0.450884 0.689659 0.566635 +0.500000 0.500000 0.707107 +0.386936 0.591845 0.707107 +0.500000 0.500000 0.707107 +0.450884 0.689659 0.566635 +0.582634 0.582634 0.566635 +0.260282 0.657460 0.707107 +0.310068 0.474271 0.823969 +0.208575 0.526850 0.823969 +0.310068 0.474271 0.823969 +0.260282 0.657460 0.707107 +0.386936 0.591845 0.707107 +0.208575 0.526850 0.823969 +0.217339 0.332436 0.917742 +0.146199 0.369291 0.917742 +0.217339 0.332436 0.917742 +0.208575 0.526850 0.823969 +0.310068 0.474271 0.823969 +0.386936 0.591845 0.707107 +0.400671 0.400671 0.823969 +0.310068 0.474271 0.823969 +0.400671 0.400671 0.823969 +0.386936 0.591845 0.707107 +0.500000 0.500000 0.707107 +0.310068 0.474271 0.823969 +0.280847 0.280847 0.917742 +0.217339 0.332436 0.917742 +0.280847 0.280847 0.917742 +0.310068 0.474271 0.823969 +0.400671 0.400671 0.823969 +0.146199 0.369291 0.917742 +0.112128 0.171508 0.978781 +0.075426 0.190522 0.978781 +0.112128 0.171508 0.978781 +0.146199 0.369291 0.917742 +0.217339 0.332436 0.917742 +0.217339 0.332436 0.917742 +0.144893 0.144893 0.978781 +0.112128 0.171508 0.978781 +0.144893 0.144893 0.978781 +0.217339 0.332436 0.917742 +0.280847 0.280847 0.917742 +0.692103 0.692103 0.204909 +0.768146 0.502197 0.397177 +0.648942 0.648942 0.397177 +0.768146 0.502197 0.397177 +0.692103 0.692103 0.204909 +0.819235 0.535598 0.204909 +0.819235 0.535598 0.204909 +0.853306 0.337816 0.397177 +0.768146 0.502197 0.397177 +0.853306 0.337816 0.397177 +0.819235 0.535598 0.204909 +0.910059 0.360284 0.204909 +0.648942 0.648942 0.397177 +0.689659 0.450884 0.566635 +0.582634 0.582634 0.566635 +0.689659 0.450884 0.566635 +0.648942 0.648942 0.397177 +0.768146 0.502197 0.397177 +0.582634 0.582634 0.566635 +0.591845 0.386936 0.707107 +0.500000 0.500000 0.707107 +0.591845 0.386936 0.707107 +0.582634 0.582634 0.566635 +0.689659 0.450884 0.566635 +0.768146 0.502197 0.397177 +0.766117 0.303299 0.566635 +0.689659 0.450884 0.566635 +0.766117 0.303299 0.566635 +0.768146 0.502197 0.397177 +0.853306 0.337816 0.397177 +0.689659 0.450884 0.566635 +0.657460 0.260282 0.707107 +0.591845 0.386936 0.707107 +0.657460 0.260282 0.707107 +0.689659 0.450884 0.566635 +0.766117 0.303299 0.566635 +0.500000 0.500000 0.707107 +0.474271 0.310068 0.823969 +0.400671 0.400671 0.823969 +0.474271 0.310068 0.823969 +0.500000 0.500000 0.707107 +0.591845 0.386936 0.707107 +0.400671 0.400671 0.823969 +0.332436 0.217339 0.917742 +0.280847 0.280847 0.917742 +0.332436 0.217339 0.917742 +0.400671 0.400671 0.823969 +0.474271 0.310068 0.823969 +0.591845 0.386936 0.707107 +0.526850 0.208575 0.823969 +0.474271 0.310068 0.823969 +0.526850 0.208575 0.823969 +0.591845 0.386936 0.707107 +0.657460 0.260282 0.707107 +0.474271 0.310068 0.823969 +0.369291 0.146199 0.917742 +0.332436 0.217339 0.917742 +0.369291 0.146199 0.917742 +0.474271 0.310068 0.823969 +0.526850 0.208575 0.823969 +0.280847 0.280847 0.917742 +0.171508 0.112128 0.978781 +0.144893 0.144893 0.978781 +0.171508 0.112128 0.978781 +0.280847 0.280847 0.917742 +0.332436 0.217339 0.917742 +0.332436 0.217339 0.917742 +0.190522 0.075426 0.978781 +0.171508 0.112128 0.978781 +0.190522 0.075426 0.978781 +0.332436 0.217339 0.917742 +0.369291 0.146199 0.917742 +0.910059 0.360284 0.204909 +0.902421 0.166995 0.397177 +0.853306 0.337816 0.397177 +0.902421 0.166995 0.397177 +0.910059 0.360284 0.204909 +0.962441 0.178102 0.204909 +0.853306 0.337816 0.397177 +0.810213 0.149932 0.566635 +0.766117 0.303299 0.566635 +0.810213 0.149932 0.566635 +0.853306 0.337816 0.397177 +0.902421 0.166995 0.397177 +0.766117 0.303299 0.566635 +0.695302 0.128667 0.707107 +0.657460 0.260282 0.707107 +0.695302 0.128667 0.707107 +0.766117 0.303299 0.566635 +0.810213 0.149932 0.566635 +0.657460 0.260282 0.707107 +0.557175 0.103107 0.823969 +0.526850 0.208575 0.823969 +0.557175 0.103107 0.823969 +0.657460 0.260282 0.707107 +0.695302 0.128667 0.707107 +0.526850 0.208575 0.823969 +0.390547 0.072272 0.917742 +0.369291 0.146199 0.917742 +0.390547 0.072272 0.917742 +0.526850 0.208575 0.823969 +0.557175 0.103107 0.823969 +0.369291 0.146199 0.917742 +0.201489 0.037286 0.978781 +0.190522 0.075426 0.978781 +0.201489 0.037286 0.978781 +0.369291 0.146199 0.917742 +0.390547 0.072272 0.917742 + + + + + + + + + + + +0.532814 0.569947 +0.533371 0.565281 +0.532566 0.565281 +0.531811 0.565281 +0.531146 0.565281 +0.530595 0.565281 +0.530136 0.565281 +0.529768 0.565281 +0.529528 0.565281 +0.529445 0.565281 +0.528953 0.569398 +0.527377 0.573609 +0.524645 0.577661 +0.520821 0.581278 +0.516112 0.584217 +0.510838 0.586316 +0.505358 0.587527 +0.500000 0.587905 +0.494642 0.587527 +0.489162 0.586316 +0.483887 0.584217 +0.479179 0.581278 +0.475355 0.577661 +0.472623 0.573609 +0.471047 0.569398 +0.470555 0.565281 +0.470472 0.565281 +0.470232 0.565281 +0.469864 0.565281 +0.469405 0.565281 +0.468854 0.565281 +0.468189 0.565281 +0.467434 0.565281 +0.466629 0.565281 +0.467186 0.569947 +0.468972 0.574719 +0.472069 0.579311 +0.476403 0.583411 +0.481739 0.586742 +0.487716 0.589121 +0.493928 0.590493 +0.500000 0.590921 +0.506072 0.590493 +0.512284 0.589121 +0.518261 0.586742 +0.523597 0.583411 +0.527931 0.579311 +0.531028 0.574719 +0.527258 0.578973 +0.530280 0.574491 +0.532023 0.569834 +0.531280 0.569728 +0.530626 0.569635 +0.530084 0.569558 +0.529633 0.569494 +0.529271 0.569443 +0.529035 0.569409 +0.527455 0.573632 +0.524715 0.577696 +0.520879 0.581324 +0.516158 0.584270 +0.510869 0.586376 +0.505373 0.587590 +0.500000 0.587969 +0.494627 0.587590 +0.489131 0.586376 +0.483842 0.584270 +0.479120 0.581324 +0.475285 0.577696 +0.472545 0.573632 +0.470965 0.569409 +0.470729 0.569443 +0.470367 0.569494 +0.469916 0.569558 +0.469374 0.569635 +0.468720 0.569728 +0.467977 0.569834 +0.469720 0.574491 +0.472742 0.578973 +0.476972 0.582974 +0.482179 0.586224 +0.488012 0.588546 +0.494074 0.589885 +0.500000 0.590303 +0.505926 0.589885 +0.511987 0.588546 +0.517821 0.586224 +0.523028 0.582974 +0.472322 0.573700 +0.471980 0.573804 +0.471553 0.573934 +0.471041 0.574090 +0.470422 0.574278 +0.475085 0.577797 +0.478951 0.581454 +0.474776 0.577951 +0.474392 0.578144 +0.478691 0.581654 +0.478366 0.581903 +0.473931 0.578376 +0.473374 0.578656 +0.477976 0.582203 +0.477506 0.582564 +0.483711 0.584424 +0.489043 0.586547 +0.483509 0.584661 +0.483258 0.584956 +0.488907 0.586810 +0.488738 0.587138 +0.482957 0.585311 +0.482592 0.585739 +0.488535 0.587532 +0.488290 0.588007 +0.494583 0.587771 +0.500000 0.588153 +0.494516 0.588049 +0.494433 0.588396 +0.500000 0.588436 +0.500000 0.588788 +0.494332 0.588812 +0.494211 0.589315 +0.500000 0.589212 +0.500000 0.589723 +0.505417 0.587771 +0.510957 0.586547 +0.505484 0.588049 +0.505567 0.588396 +0.511093 0.586810 +0.511262 0.587138 +0.505667 0.588812 +0.505789 0.589315 +0.511465 0.587532 +0.511710 0.588007 +0.516289 0.584424 +0.521049 0.581454 +0.516491 0.584661 +0.516742 0.584956 +0.521309 0.581654 +0.521634 0.581903 +0.517043 0.585311 +0.517407 0.585739 +0.522024 0.582203 +0.522494 0.582564 +0.524915 0.577797 +0.527678 0.573700 +0.525224 0.577951 +0.525608 0.578144 +0.528020 0.573804 +0.528446 0.573934 +0.526069 0.578376 +0.526626 0.578656 +0.528959 0.574090 +0.529578 0.574278 +0.529445 0.565281 +0.529445 0.565281 +0.470555 0.565281 +0.470555 0.565281 +0.471047 0.561164 +0.471047 0.561164 +0.472623 0.556953 +0.472623 0.556953 +0.475355 0.552901 +0.475355 0.552901 +0.479179 0.549284 +0.479179 0.549284 +0.483887 0.546345 +0.483887 0.546345 +0.489162 0.544246 +0.489162 0.544246 +0.494642 0.543035 +0.494642 0.543035 +0.500000 0.542657 +0.500000 0.542657 +0.505358 0.543035 +0.505358 0.543035 +0.510838 0.544246 +0.510838 0.544246 +0.516112 0.546345 +0.516112 0.546345 +0.520821 0.549284 +0.520821 0.549284 +0.524645 0.552901 +0.524645 0.552901 +0.527377 0.556953 +0.527377 0.556953 +0.528953 0.561164 +0.528953 0.561164 +0.369789 0.743253 +0.369789 0.743253 +0.373060 0.745767 +0.373060 0.745767 +0.372390 0.745713 +0.372390 0.745713 +0.371761 0.745560 +0.371761 0.745560 +0.371207 0.745324 +0.370747 0.745031 +0.371207 0.745324 +0.370365 0.744677 +0.370747 0.745031 +0.370365 0.744677 +0.370058 0.744252 +0.369858 0.743768 +0.370058 0.744252 +0.369858 0.743768 +0.369789 0.743253 +0.369789 0.743253 +0.369789 0.487858 +0.369789 0.487858 +0.373060 0.485344 +0.373060 0.485344 +0.369789 0.487858 +0.369789 0.487858 +0.369858 0.487343 +0.369858 0.487343 +0.370058 0.486860 +0.370058 0.486860 +0.370365 0.486434 +0.370365 0.486434 +0.370747 0.486081 +0.371207 0.485787 +0.370747 0.486081 +0.371207 0.485787 +0.371761 0.485551 +0.371761 0.485551 +0.372390 0.485398 +0.372390 0.485398 +0.626940 0.485344 +0.373060 0.485344 +0.373060 0.485344 +0.626940 0.485344 +0.630142 0.487343 +0.630211 0.487858 +0.626940 0.485344 +0.626940 0.485344 +0.627610 0.485398 +0.627610 0.485398 +0.628239 0.485551 +0.628239 0.485551 +0.628793 0.485787 +0.629253 0.486081 +0.628793 0.485787 +0.629253 0.486081 +0.629635 0.486434 +0.629635 0.486434 +0.629942 0.486860 +0.630142 0.487343 +0.629942 0.486860 +0.630211 0.487858 +0.630211 0.487858 +0.630211 0.487858 +0.630211 0.743253 +0.630211 0.743253 +0.630211 0.743253 +0.630211 0.743253 +0.627610 0.745713 +0.626940 0.745767 +0.626940 0.745767 +0.627610 0.745713 +0.628239 0.745560 +0.628239 0.745560 +0.628793 0.745324 +0.628793 0.745324 +0.629253 0.745031 +0.629253 0.745031 +0.629635 0.744677 +0.629635 0.744677 +0.629942 0.744251 +0.629942 0.744251 +0.630142 0.743768 +0.630142 0.743768 +0.626940 0.745767 +0.626940 0.745767 +0.373060 0.745767 +0.373060 0.745767 +0.468972 0.574719 +0.527931 0.551250 +0.624977 0.741745 +0.375023 0.741745 +0.531028 0.555843 +0.624977 0.489366 +0.532814 0.560615 +0.533371 0.565281 +0.532814 0.569947 +0.531028 0.574719 +0.527931 0.579311 +0.523597 0.583411 +0.518261 0.586742 +0.512284 0.589121 +0.506072 0.590493 +0.523597 0.547151 +0.500000 0.590921 +0.518261 0.543820 +0.375023 0.489366 +0.512284 0.541441 +0.506072 0.540069 +0.500000 0.539641 +0.493928 0.540069 +0.487716 0.541441 +0.481739 0.543820 +0.476403 0.547151 +0.472069 0.551251 +0.468972 0.555843 +0.493928 0.590493 +0.467186 0.560615 +0.487716 0.589121 +0.466629 0.565281 +0.481739 0.586742 +0.467186 0.569947 +0.476403 0.583411 +0.472069 0.579311 +0.629982 0.744178 +0.630157 0.743710 +0.520821 0.549284 +0.516112 0.546345 +0.626940 0.485344 +0.510838 0.544246 +0.505358 0.543035 +0.500000 0.542657 +0.494642 0.543035 +0.489162 0.544246 +0.483887 0.546345 +0.479179 0.549284 +0.475355 0.552901 +0.472623 0.556953 +0.524645 0.552901 +0.527377 0.556953 +0.471047 0.561164 +0.373060 0.485344 +0.372465 0.485386 +0.371856 0.485521 +0.371270 0.485754 +0.370747 0.486081 +0.370322 0.486483 +0.370018 0.486933 +0.369843 0.487401 +0.369789 0.487858 +0.470555 0.565281 +0.471047 0.569398 +0.472623 0.573609 +0.475355 0.577661 +0.479179 0.581278 +0.483887 0.584217 +0.489162 0.586316 +0.494642 0.587527 +0.500000 0.587905 +0.505358 0.587527 +0.528953 0.561164 +0.627535 0.485386 +0.628144 0.485521 +0.628730 0.485754 +0.629253 0.486081 +0.629678 0.486483 +0.629981 0.486933 +0.630157 0.487401 +0.630211 0.487858 +0.630211 0.743253 +0.529445 0.565281 +0.528953 0.569398 +0.527377 0.573609 +0.524645 0.577661 +0.520821 0.581278 +0.516112 0.584217 +0.510838 0.586316 +0.369789 0.743253 +0.369843 0.743710 +0.370019 0.744178 +0.370322 0.744629 +0.370747 0.745031 +0.371270 0.745357 +0.371856 0.745590 +0.372465 0.745725 +0.373060 0.745767 +0.626940 0.745767 +0.627535 0.745725 +0.628144 0.745590 +0.628730 0.745357 +0.629253 0.745031 +0.629678 0.744629 +0.524645 0.577661 +0.528953 0.569398 +0.529445 0.565281 +0.529445 0.565281 +0.528953 0.569398 +0.527377 0.573609 +0.527377 0.573609 +0.524645 0.577661 +0.470555 0.565281 +0.470555 0.565281 +0.471047 0.569398 +0.471047 0.569398 +0.472623 0.573609 +0.472623 0.573609 +0.475355 0.577661 +0.479179 0.581278 +0.475355 0.577661 +0.483887 0.584217 +0.479179 0.581278 +0.489162 0.586316 +0.483887 0.584217 +0.489162 0.586316 +0.494642 0.587527 +0.494642 0.587527 +0.500000 0.587905 +0.505358 0.587527 +0.500000 0.587905 +0.505358 0.587527 +0.510838 0.586316 +0.510838 0.586316 +0.516112 0.584217 +0.516112 0.584217 +0.520821 0.581278 +0.520821 0.581278 +0.373093 0.485411 +0.373198 0.485627 +0.372465 0.485386 +0.373060 0.485344 +0.369876 0.487883 +0.369789 0.487858 +0.375023 0.489366 +0.374666 0.488634 +0.371856 0.485521 +0.371270 0.485754 +0.370747 0.486081 +0.370322 0.486483 +0.370018 0.486933 +0.369843 0.487401 +0.370156 0.487964 +0.370642 0.488104 +0.373380 0.486000 +0.373635 0.486522 +0.373949 0.487165 +0.371322 0.488300 +0.372159 0.488541 +0.373097 0.488811 +0.374071 0.489092 +0.374301 0.487886 +0.374318 0.488825 +0.375023 0.489366 +0.372526 0.485478 +0.372699 0.485741 +0.375023 0.489366 +0.371942 0.485622 +0.371379 0.485857 +0.370872 0.486177 +0.370455 0.486566 +0.370150 0.486999 +0.369963 0.487448 +0.370305 0.487580 +0.372529 0.486324 +0.372178 0.485903 +0.372956 0.486842 +0.373434 0.487425 +0.373945 0.488050 +0.371064 0.487450 +0.370516 0.487180 +0.371738 0.487778 +0.372497 0.488145 +0.373311 0.488538 +0.373622 0.488290 +0.372300 0.487274 +0.372003 0.487520 +0.371358 0.487124 +0.371709 0.486820 +0.370821 0.486793 +0.371214 0.486439 +0.372620 0.487046 +0.372105 0.486550 +0.371674 0.486138 +0.624977 0.489366 +0.375023 0.489366 +0.373060 0.485344 +0.626940 0.485344 +0.373093 0.485411 +0.626907 0.485411 +0.373198 0.485627 +0.626802 0.485627 +0.373380 0.486000 +0.626620 0.486000 +0.373499 0.486244 +0.626501 0.486244 +0.373635 0.486522 +0.626365 0.486522 +0.373786 0.486831 +0.626214 0.486831 +0.373949 0.487165 +0.626051 0.487165 +0.374301 0.487886 +0.625699 0.487886 +0.374666 0.488634 +0.625334 0.488634 +0.375023 0.489366 +0.375023 0.741745 +0.369876 0.743228 +0.369789 0.743253 +0.369789 0.487858 +0.369876 0.487883 +0.370156 0.743147 +0.370156 0.487964 +0.370642 0.743007 +0.370642 0.488104 +0.370960 0.742916 +0.370959 0.488195 +0.371322 0.742811 +0.371322 0.488300 +0.371724 0.742696 +0.371724 0.488416 +0.372159 0.742570 +0.372159 0.488541 +0.373097 0.742300 +0.373097 0.488811 +0.374071 0.742019 +0.374071 0.489092 +0.626802 0.485627 +0.626620 0.486000 +0.624977 0.489366 +0.625929 0.489092 +0.630157 0.487401 +0.630211 0.487858 +0.626907 0.485411 +0.626940 0.485344 +0.627535 0.485386 +0.628144 0.485521 +0.628730 0.485754 +0.629253 0.486081 +0.629678 0.486483 +0.629981 0.486933 +0.630124 0.487883 +0.629844 0.487964 +0.629358 0.488104 +0.628678 0.488300 +0.627841 0.488541 +0.626365 0.486522 +0.626051 0.487165 +0.625699 0.487886 +0.625334 0.488634 +0.626903 0.488811 +0.625682 0.488825 +0.624977 0.489366 +0.627474 0.485478 +0.627301 0.485741 +0.624977 0.489366 +0.628058 0.485622 +0.628621 0.485857 +0.629128 0.486177 +0.629544 0.486566 +0.629850 0.486999 +0.630037 0.487448 +0.629695 0.487580 +0.628936 0.487449 +0.629484 0.487180 +0.628262 0.487778 +0.627503 0.488145 +0.626689 0.488538 +0.627471 0.486324 +0.627822 0.485903 +0.627044 0.486842 +0.626566 0.487425 +0.626054 0.488050 +0.626378 0.488289 +0.627700 0.487274 +0.627380 0.487046 +0.627895 0.486550 +0.628290 0.486820 +0.628326 0.486138 +0.628786 0.486439 +0.627997 0.487520 +0.628642 0.487124 +0.629178 0.486793 +0.369876 0.743228 +0.370156 0.743147 +0.369843 0.743710 +0.369789 0.743253 +0.373093 0.745700 +0.373060 0.745767 +0.375023 0.741745 +0.374071 0.742019 +0.370019 0.744178 +0.370322 0.744629 +0.370747 0.745031 +0.371270 0.745357 +0.371856 0.745590 +0.372465 0.745725 +0.373198 0.745484 +0.373380 0.745111 +0.370642 0.743007 +0.371322 0.742811 +0.372159 0.742570 +0.373635 0.744589 +0.373949 0.743946 +0.374301 0.743225 +0.374666 0.742477 +0.373097 0.742300 +0.374318 0.742287 +0.375023 0.741745 +0.369963 0.743663 +0.370305 0.743531 +0.375023 0.741745 +0.370150 0.744112 +0.370456 0.744545 +0.370872 0.744934 +0.371379 0.745255 +0.371942 0.745489 +0.372526 0.745633 +0.372699 0.745371 +0.371064 0.743662 +0.370516 0.743931 +0.371738 0.743334 +0.372497 0.742966 +0.373311 0.742573 +0.372529 0.744787 +0.372178 0.745208 +0.372956 0.744269 +0.373434 0.743686 +0.373946 0.743061 +0.373622 0.742822 +0.372945 0.743342 +0.372620 0.744066 +0.372105 0.744561 +0.371710 0.744291 +0.372300 0.743838 +0.372003 0.743591 +0.371358 0.743987 +0.371674 0.744973 +0.371214 0.744672 +0.370822 0.744318 +0.624977 0.741745 +0.624977 0.489366 +0.630211 0.487858 +0.630211 0.743253 +0.630124 0.487883 +0.630124 0.743228 +0.629844 0.487964 +0.629844 0.743147 +0.629358 0.488104 +0.629358 0.743007 +0.629040 0.488195 +0.629041 0.742916 +0.628678 0.488300 +0.628678 0.742811 +0.628276 0.488416 +0.628276 0.742695 +0.627841 0.488541 +0.627841 0.742570 +0.626903 0.488811 +0.626903 0.742300 +0.625929 0.489092 +0.625929 0.742019 +0.375023 0.741745 +0.624977 0.741745 +0.626907 0.745700 +0.626940 0.745767 +0.373060 0.745767 +0.373093 0.745700 +0.626802 0.745484 +0.373198 0.745484 +0.626620 0.745111 +0.373380 0.745111 +0.626501 0.744867 +0.373499 0.744867 +0.626365 0.744589 +0.373635 0.744589 +0.626214 0.744280 +0.373786 0.744280 +0.626051 0.743946 +0.373949 0.743946 +0.625699 0.743225 +0.374301 0.743225 +0.625334 0.742477 +0.374666 0.742477 +0.629844 0.743147 +0.629358 0.743007 +0.624977 0.741745 +0.625334 0.742477 +0.627535 0.745725 +0.626940 0.745767 +0.630124 0.743228 +0.630211 0.743253 +0.630157 0.743710 +0.629982 0.744178 +0.629678 0.744629 +0.629253 0.745031 +0.628730 0.745357 +0.628144 0.745590 +0.626907 0.745700 +0.626802 0.745484 +0.626620 0.745111 +0.626365 0.744589 +0.626051 0.743946 +0.628678 0.742811 +0.627841 0.742570 +0.626903 0.742300 +0.625929 0.742019 +0.625699 0.743225 +0.625682 0.742287 +0.624977 0.741745 +0.630037 0.743663 +0.629695 0.743531 +0.624977 0.741745 +0.629850 0.744112 +0.629545 0.744545 +0.629128 0.744934 +0.628621 0.745255 +0.628058 0.745489 +0.627474 0.745633 +0.627301 0.745370 +0.627471 0.744787 +0.627822 0.745208 +0.627044 0.744269 +0.626566 0.743686 +0.626054 0.743061 +0.628936 0.743662 +0.629484 0.743931 +0.628262 0.743333 +0.627503 0.742966 +0.626689 0.742573 +0.626378 0.742822 +0.627700 0.743838 +0.627997 0.743591 +0.628642 0.743987 +0.628290 0.744291 +0.629179 0.744318 +0.628786 0.744672 +0.627380 0.744065 +0.627895 0.744561 +0.628326 0.744973 +0.532814 0.560615 +0.531028 0.555843 +0.527931 0.551250 +0.523597 0.547151 +0.518261 0.543820 +0.512284 0.541441 +0.506072 0.540069 +0.500000 0.539641 +0.493928 0.540069 +0.487716 0.541441 +0.481739 0.543820 +0.476403 0.547151 +0.472069 0.551251 +0.468972 0.555843 +0.467186 0.560615 +0.466629 0.565281 +0.467434 0.565281 +0.468189 0.565281 +0.468854 0.565281 +0.469405 0.565281 +0.469864 0.565281 +0.470232 0.565281 +0.470472 0.565281 +0.470555 0.565281 +0.471047 0.561164 +0.472623 0.556953 +0.475355 0.552901 +0.479179 0.549284 +0.483887 0.546345 +0.489162 0.544246 +0.494642 0.543035 +0.500000 0.542657 +0.505358 0.543035 +0.510838 0.544246 +0.516112 0.546345 +0.520821 0.549284 +0.524645 0.552901 +0.527377 0.556953 +0.528953 0.561164 +0.529445 0.565281 +0.529528 0.565281 +0.529768 0.565281 +0.530136 0.565281 +0.530595 0.565281 +0.531146 0.565281 +0.531811 0.565281 +0.532566 0.565281 +0.533371 0.565281 +0.532023 0.560728 +0.530280 0.556071 +0.527258 0.551589 +0.523028 0.547588 +0.517821 0.544338 +0.511987 0.542016 +0.505926 0.540677 +0.500000 0.540259 +0.494074 0.540677 +0.488012 0.542016 +0.482179 0.544338 +0.476972 0.547588 +0.472742 0.551589 +0.469720 0.556071 +0.467977 0.560728 +0.468720 0.560833 +0.469374 0.560926 +0.469916 0.561004 +0.470367 0.561068 +0.470729 0.561119 +0.470965 0.561153 +0.472545 0.556930 +0.475285 0.552866 +0.479120 0.549238 +0.483842 0.546292 +0.489131 0.544186 +0.494627 0.542972 +0.500000 0.542593 +0.505373 0.542972 +0.510869 0.544186 +0.516158 0.546292 +0.520879 0.549238 +0.524715 0.552866 +0.527455 0.556930 +0.529035 0.561153 +0.529271 0.561119 +0.529633 0.561068 +0.530084 0.561004 +0.530626 0.560926 +0.531280 0.560833 +0.527678 0.556862 +0.528020 0.556758 +0.528446 0.556628 +0.528959 0.556472 +0.529578 0.556284 +0.524915 0.552765 +0.521049 0.549108 +0.525224 0.552611 +0.525608 0.552418 +0.521309 0.548908 +0.521634 0.548659 +0.526069 0.552186 +0.526626 0.551906 +0.522024 0.548359 +0.522494 0.547998 +0.516289 0.546137 +0.510957 0.544015 +0.516491 0.545901 +0.516742 0.545606 +0.511093 0.543752 +0.511262 0.543424 +0.517043 0.545251 +0.517407 0.544823 +0.511465 0.543030 +0.511710 0.542555 +0.505417 0.542791 +0.500000 0.542409 +0.505484 0.542513 +0.505567 0.542166 +0.500000 0.542126 +0.500000 0.541774 +0.505667 0.541750 +0.505789 0.541247 +0.500000 0.541350 +0.500000 0.540839 +0.494583 0.542791 +0.489043 0.544015 +0.494516 0.542513 +0.494433 0.542166 +0.488907 0.543752 +0.488738 0.543424 +0.494332 0.541750 +0.494211 0.541247 +0.488535 0.543030 +0.488290 0.542555 +0.483711 0.546138 +0.478951 0.549108 +0.483509 0.545901 +0.483258 0.545606 +0.478691 0.548908 +0.478366 0.548659 +0.482956 0.545251 +0.482592 0.544823 +0.477976 0.548359 +0.477506 0.547998 +0.475085 0.552765 +0.472322 0.556862 +0.474776 0.552611 +0.474392 0.552418 +0.471980 0.556758 +0.471553 0.556628 +0.473931 0.552186 +0.473374 0.551906 +0.471041 0.556472 +0.470422 0.556284 + + + + + + + + + + + +

47 0 47 48 1 48 49 2 49 50 3 50 47 4 47 49 5 49 50 6 50 0 7 0 47 8 47 50 9 50 1 10 1 0 11 0 50 12 50 2 13 2 1 14 1 51 15 51 2 16 2 50 17 50 51 18 51 3 19 3 2 20 2 52 21 52 3 22 3 51 23 51 52 24 52 4 25 4 3 26 3 53 27 53 4 28 4 52 29 52 53 30 53 5 31 5 4 32 4 54 33 54 5 34 5 53 35 53 54 36 54 6 37 6 5 38 5 54 39 54 7 40 7 6 41 6 55 42 55 7 43 7 54 44 54 56 45 56 7 46 7 55 47 55 56 48 56 8 49 8 7 50 7 56 51 56 9 52 9 8 53 8 56 54 56 10 55 10 9 56 9 57 57 57 10 58 10 56 59 56 57 60 57 11 61 11 10 62 10 58 63 58 11 64 11 57 65 57 58 66 58 12 67 12 11 68 11 59 69 59 12 70 12 58 71 58 59 72 59 13 73 13 12 74 12 60 75 60 13 76 13 59 77 59 60 78 60 14 79 14 13 80 13 61 81 61 14 82 14 60 83 60 61 84 61 15 85 15 14 86 14 61 87 61 16 88 16 15 89 15 62 90 62 16 91 16 61 92 61 62 93 62 17 94 17 16 95 16 63 96 63 17 97 17 62 98 62 64 99 64 17 100 17 63 101 63 64 102 64 18 103 18 17 104 17 65 105 65 18 106 18 64 107 64 65 108 65 19 109 19 18 110 18 66 111 66 19 112 19 65 113 65 66 114 66 20 115 20 19 116 19 67 117 67 20 118 20 66 119 66 67 120 67 21 121 21 20 122 20 67 123 67 22 124 22 21 125 21 68 126 68 22 127 22 67 128 67 68 129 68 23 130 23 22 131 22 69 132 69 23 133 23 68 134 68 69 135 69 24 136 24 23 137 23 70 138 70 24 139 24 69 140 69 70 141 70 25 142 25 24 143 24 70 144 70 26 145 26 25 146 25 71 147 71 26 148 26 70 149 70 71 150 71 27 151 27 26 152 26 72 153 72 27 154 27 71 155 71 72 156 72 28 157 28 27 158 27 73 159 73 28 160 28 72 161 72 73 162 73 29 163 29 28 164 28 74 165 74 29 166 29 73 167 73 74 168 74 30 169 30 29 170 29 74 171 74 31 172 31 30 173 30 75 174 75 31 175 31 74 176 74 76 177 76 31 178 31 75 179 75 76 180 76 32 181 32 31 182 31 76 183 76 33 184 33 32 185 32 76 186 76 34 187 34 33 188 33 76 189 76 35 190 35 34 191 34 77 192 77 35 193 35 76 194 76 78 195 78 35 196 35 77 197 77 78 198 78 36 199 36 35 200 35 78 201 78 37 202 37 36 203 36 79 204 79 37 205 37 78 206 78 79 207 79 38 208 38 37 209 37 80 210 80 38 211 38 79 212 79 81 213 81 38 214 38 80 215 80 81 216 81 39 217 39 38 218 38 82 219 82 39 220 39 81 221 81 82 222 82 40 223 40 39 224 39 83 225 83 40 226 40 82 227 82 83 228 83 41 229 41 40 230 40 84 231 84 41 232 41 83 233 83 84 234 84 42 235 42 41 236 41 85 237 85 42 238 42 84 239 84 85 240 85 43 241 43 42 242 42 86 243 86 43 244 43 85 245 85 86 246 86 44 247 44 43 248 43 87 249 87 44 250 44 86 251 86 87 252 87 45 253 45 44 254 44 48 255 48 45 256 45 87 257 87 48 258 48 46 259 46 45 260 45 48 261 48 47 262 47 46 263 46 70 264 70 88 265 88 71 266 71 88 267 88 70 268 70 69 269 69 71 270 71 89 271 89 72 272 72 89 273 89 71 274 71 88 275 88 72 276 72 90 277 90 73 278 73 90 279 90 72 280 72 89 281 89 73 282 73 91 283 91 74 284 74 91 285 91 73 286 73 90 287 90 74 288 74 92 289 92 75 290 75 92 291 92 74 292 74 91 293 91 75 294 75 77 295 77 76 296 76 77 297 77 75 298 75 92 299 92 69 300 69 93 301 93 88 302 88 93 303 93 69 304 69 68 305 68 68 306 68 94 307 94 93 308 93 94 309 94 68 310 68 67 311 67 88 312 88 95 313 95 89 314 89 95 315 95 88 316 88 93 317 93 89 318 89 96 319 96 90 320 90 96 321 96 89 322 89 95 323 95 93 324 93 97 325 97 95 326 95 97 327 97 93 328 93 94 329 94 95 330 95 98 331 98 96 332 96 98 333 98 95 334 95 97 335 97 90 336 90 99 337 99 91 338 91 99 339 99 90 340 90 96 341 96 91 342 91 100 343 100 92 344 92 100 345 100 91 346 91 99 347 99 96 348 96 101 349 101 99 350 99 101 351 101 96 352 96 98 353 98 99 354 99 102 355 102 100 356 100 102 357 102 99 358 99 101 359 101 92 360 92 78 361 78 77 362 77 78 363 78 92 364 92 100 365 100 100 366 100 79 367 79 78 368 78 79 369 79 100 370 100 102 371 102 67 372 67 103 373 103 94 374 94 103 375 103 67 376 67 66 377 66 66 378 66 104 379 104 103 380 103 104 381 104 66 382 66 65 383 65 94 384 94 105 385 105 97 386 97 105 387 105 94 388 94 103 389 103 97 390 97 106 391 106 98 392 98 106 393 106 97 394 97 105 395 105 103 396 103 107 397 107 105 398 105 107 399 107 103 400 103 104 401 104 105 402 105 108 403 108 106 404 106 108 405 108 105 406 105 107 407 107 98 408 98 109 409 109 101 410 101 109 411 109 98 412 98 106 413 106 101 414 101 110 415 110 102 416 102 110 417 110 101 418 101 109 419 109 106 420 106 111 421 111 109 422 109 111 423 111 106 424 106 108 425 108 109 426 109 112 427 112 110 428 110 112 429 112 109 430 109 111 431 111 102 432 102 80 433 80 79 434 79 80 435 80 102 436 102 110 437 110 110 438 110 81 439 81 80 440 80 81 441 81 110 442 110 112 443 112 65 444 65 113 445 113 104 446 104 113 447 113 65 448 65 64 449 64 64 450 64 114 451 114 113 452 113 114 453 114 64 454 64 63 455 63 104 456 104 115 457 115 107 458 107 115 459 115 104 460 104 113 461 113 107 462 107 116 463 116 108 464 108 116 465 116 107 466 107 115 467 115 113 468 113 117 469 117 115 470 115 117 471 117 113 472 113 114 473 114 115 474 115 118 475 118 116 476 116 118 477 118 115 478 115 117 479 117 108 480 108 119 481 119 111 482 111 119 483 119 108 484 108 116 485 116 111 486 111 120 487 120 112 488 112 120 489 120 111 490 111 119 491 119 116 492 116 121 493 121 119 494 119 121 495 121 116 496 116 118 497 118 119 498 119 122 499 122 120 500 120 122 501 122 119 502 119 121 503 121 112 504 112 82 505 82 81 506 81 82 507 82 112 508 112 120 509 120 120 510 120 83 511 83 82 512 82 83 513 83 120 514 120 122 515 122 63 516 63 123 517 123 114 518 114 123 519 123 63 520 63 62 521 62 62 522 62 124 523 124 123 524 123 124 525 124 62 526 62 61 527 61 114 528 114 125 529 125 117 530 117 125 531 125 114 532 114 123 533 123 117 534 117 126 535 126 118 536 118 126 537 126 117 538 117 125 539 125 123 540 123 127 541 127 125 542 125 127 543 127 123 544 123 124 545 124 125 546 125 128 547 128 126 548 126 128 549 128 125 550 125 127 551 127 118 552 118 129 553 129 121 554 121 129 555 129 118 556 118 126 557 126 121 558 121 130 559 130 122 560 122 130 561 130 121 562 121 129 563 129 126 564 126 131 565 131 129 566 129 131 567 131 126 568 126 128 569 128 129 570 129 132 571 132 130 572 130 132 573 132 129 574 129 131 575 131 122 576 122 84 577 84 83 578 83 84 579 84 122 580 122 130 581 130 130 582 130 85 583 85 84 584 84 85 585 85 130 586 130 132 587 132 61 588 61 133 589 133 124 590 124 133 591 133 61 592 61 60 593 60 60 594 60 134 595 134 133 596 133 134 597 134 60 598 60 59 599 59 124 600 124 135 601 135 127 602 127 135 603 135 124 604 124 133 605 133 127 606 127 136 607 136 128 608 128 136 609 136 127 610 127 135 611 135 133 612 133 137 613 137 135 614 135 137 615 137 133 616 133 134 617 134 135 618 135 138 619 138 136 620 136 138 621 138 135 622 135 137 623 137 128 624 128 139 625 139 131 626 131 139 627 139 128 628 128 136 629 136 131 630 131 140 631 140 132 632 132 140 633 140 131 634 131 139 635 139 136 636 136 141 637 141 139 638 139 141 639 141 136 640 136 138 641 138 139 642 139 142 643 142 140 644 140 142 645 142 139 646 139 141 647 141 132 648 132 86 649 86 85 650 85 86 651 86 132 652 132 140 653 140 140 654 140 87 655 87 86 656 86 87 657 87 140 658 140 142 659 142 59 660 59 143 661 143 134 662 134 143 663 143 59 664 59 58 665 58 58 666 58 144 667 144 143 668 143 144 669 144 58 670 58 57 671 57 134 672 134 145 673 145 137 674 137 145 675 145 134 676 134 143 677 143 137 678 137 146 679 146 138 680 138 146 681 146 137 682 137 145 683 145 143 684 143 147 685 147 145 686 145 147 687 147 143 688 143 144 689 144 145 690 145 148 691 148 146 692 146 148 693 148 145 694 145 147 695 147 138 696 138 149 697 149 141 698 141 149 699 149 138 700 138 146 701 146 141 702 141 150 703 150 142 704 142 150 705 150 141 706 141 149 707 149 146 708 146 151 709 151 149 710 149 151 711 151 146 712 146 148 713 148 149 714 149 152 715 152 150 716 150 152 717 152 149 718 149 151 719 151 142 720 142 48 721 48 87 722 87 48 723 48 142 724 142 150 725 150 150 726 150 49 727 49 48 728 48 49 729 49 150 730 150 152 731 152 57 732 57 55 733 55 144 734 144 55 735 55 57 736 57 56 737 56 144 738 144 54 739 54 147 740 147 54 741 54 144 742 144 55 743 55 147 744 147 53 745 53 148 746 148 53 747 53 147 748 147 54 749 54 148 750 148 52 751 52 151 752 151 52 753 52 148 754 148 53 755 53 151 756 151 51 757 51 152 758 152 51 759 51 151 760 151 52 761 52 152 762 152 50 763 50 49 764 49 50 765 50 152 766 152 51 767 51 185 768 185 153 769 153 154 770 154 158 771 158 155 772 155 156 773 156 158 774 158 157 775 157 155 776 155 160 777 160 157 778 157 158 779 158 160 780 160 159 781 159 157 782 157 162 783 162 159 784 159 160 785 160 162 786 162 161 787 161 159 788 159 164 789 164 161 790 161 162 791 162 164 792 164 163 793 163 161 794 161 166 795 166 163 796 163 164 797 164 166 798 166 165 799 165 163 800 163 168 801 168 165 802 165 166 803 166 168 804 168 167 805 167 165 806 165 170 807 170 167 808 167 168 809 168 170 810 170 169 811 169 167 812 167 172 813 172 169 814 169 170 815 170 172 816 172 171 817 171 169 818 169 174 819 174 171 820 171 172 821 172 174 822 174 173 823 173 171 824 171 176 825 176 173 826 173 174 827 174 176 828 176 175 829 175 173 830 173 178 831 178 175 832 175 176 833 176 178 834 178 177 835 177 175 836 175 180 837 180 177 838 177 178 839 178 180 840 180 179 841 179 177 842 177 182 843 182 179 844 179 180 845 180 182 846 182 181 847 181 179 848 179 184 849 184 181 850 181 182 851 182 184 852 184 183 853 183 181 854 181 186 855 186 183 856 183 184 857 184 186 858 186 185 859 185 183 860 183 153 861 153 185 862 185 186 863 186 202 864 202 187 865 187 188 866 188 192 867 192 189 868 189 190 869 190 192 870 192 191 871 191 189 872 189 194 873 194 191 874 191 192 875 192 194 876 194 193 877 193 191 878 191 197 879 197 193 880 193 194 881 194 197 882 197 195 883 195 193 884 193 197 885 197 196 886 196 195 887 195 199 888 199 196 889 196 197 890 197 199 891 199 198 892 198 196 893 196 200 894 200 198 895 198 199 896 199 203 897 203 198 898 198 200 899 200 203 900 203 201 901 201 198 902 198 203 903 203 202 904 202 201 905 201 204 906 204 202 907 202 203 908 203 187 909 187 202 910 202 204 911 204 207 912 207 205 913 205 206 914 206 205 915 205 207 916 207 208 917 208 225 918 225 209 919 209 210 920 210 214 921 214 211 922 211 212 923 212 214 924 214 213 925 213 211 926 211 216 927 216 213 928 213 214 929 214 216 930 216 215 931 215 213 932 213 218 933 218 215 934 215 216 935 216 218 936 218 217 937 217 215 938 215 221 939 221 217 940 217 218 941 218 221 942 221 219 943 219 217 944 217 221 945 221 220 946 220 219 947 219 222 948 222 220 949 220 221 950 221 224 951 224 220 952 220 222 953 222 224 954 224 223 955 223 220 956 220 226 957 226 223 958 223 224 959 224 226 960 226 225 961 225 223 962 223 209 963 209 225 964 225 226 965 226 229 966 229 227 967 227 228 968 228 227 969 227 229 970 229 230 971 230 248 972 248 231 973 231 232 974 232 236 975 236 233 976 233 234 977 234 236 978 236 235 979 235 233 980 233 238 981 238 235 982 235 236 983 236 238 984 238 237 985 237 235 986 235 241 987 241 237 988 237 238 989 238 241 990 241 239 991 239 237 992 237 241 993 241 240 994 240 239 995 239 242 996 242 240 997 240 241 998 241 244 999 244 240 1000 240 242 1001 242 244 1002 244 243 1003 243 240 1004 240 247 1005 247 243 1006 243 244 1007 244 247 1008 247 245 1009 245 243 1010 243 247 1011 247 246 1012 246 245 1013 245 231 1014 231 246 1015 246 247 1016 247 231 1017 231 248 1018 248 246 1019 246 251 1020 251 249 1021 249 250 1022 250 249 1023 249 251 1024 251 252 1025 252 269 1026 269 253 1027 253 254 1028 254 257 1029 257 255 1030 255 256 1031 256 258 1032 258 255 1033 255 257 1034 257 260 1035 260 255 1036 255 258 1037 258 260 1038 260 259 1039 259 255 1040 255 262 1041 262 259 1042 259 260 1043 260 262 1044 262 261 1045 261 259 1046 259 264 1047 264 261 1048 261 262 1049 262 264 1050 264 263 1051 263 261 1052 261 266 1053 266 263 1054 263 264 1055 264 266 1056 266 265 1057 265 263 1058 263 268 1059 268 265 1060 265 266 1061 266 268 1062 268 267 1063 267 265 1064 265 270 1065 270 267 1066 267 268 1067 268 270 1068 270 269 1069 269 267 1070 267 253 1071 253 269 1072 269 270 1073 270 273 1074 273 271 1075 271 272 1076 272 271 1077 271 273 1078 273 274 1079 274 310 1080 310 293 1081 293 275 1082 275 290 1083 290 280 1084 280 276 1085 276 293 1086 293 277 1087 277 278 1088 278 280 1089 280 279 1090 279 276 1091 276 277 1092 277 279 1093 279 280 1094 280 277 1095 277 281 1096 281 279 1097 279 277 1098 277 282 1099 282 281 1100 281 277 1101 277 283 1102 283 282 1103 282 277 1104 277 284 1105 284 283 1106 283 277 1107 277 285 1108 285 284 1109 284 277 1110 277 286 1111 286 285 1112 285 277 1113 277 287 1114 287 286 1115 286 277 1116 277 288 1117 288 287 1118 287 277 1119 277 289 1120 289 288 1121 288 292 1122 292 280 1123 280 290 1124 290 277 1125 277 291 1126 291 289 1127 289 294 1128 294 280 1129 280 292 1130 292 294 1131 294 293 1132 293 280 1133 280 295 1134 295 293 1135 293 294 1136 294 296 1137 296 293 1138 293 295 1139 295 297 1140 297 293 1141 293 296 1142 296 298 1143 298 293 1144 293 297 1145 297 299 1146 299 293 1147 293 298 1148 298 300 1149 300 293 1150 293 299 1151 299 301 1152 301 293 1153 293 300 1154 300 302 1155 302 293 1156 293 301 1157 301 304 1158 304 293 1159 293 302 1160 302 277 1161 277 303 1162 303 291 1163 291 306 1164 306 293 1165 293 304 1166 304 277 1167 277 305 1168 305 303 1169 303 308 1170 308 293 1171 293 306 1172 306 277 1173 277 307 1174 307 305 1175 305 275 1176 275 293 1177 293 308 1178 308 277 1179 277 309 1180 309 307 1181 307 293 1182 293 309 1183 309 277 1184 277 293 1185 293 310 1186 310 309 1187 309 356 1188 356 311 1189 311 312 1190 312 325 1191 325 315 1192 315 313 1193 313 315 1194 315 314 1195 314 313 1196 313 328 1197 328 314 1198 314 315 1199 315 328 1200 328 316 1201 316 314 1202 314 328 1203 328 317 1204 317 316 1205 316 328 1206 328 318 1207 318 317 1208 317 328 1209 328 319 1210 319 318 1211 318 328 1212 328 320 1213 320 319 1214 319 328 1215 328 321 1216 321 320 1217 320 328 1218 328 322 1219 322 321 1220 321 328 1221 328 323 1222 323 322 1223 322 328 1224 328 324 1225 324 323 1226 323 326 1227 326 315 1228 315 325 1229 325 347 1230 347 315 1231 315 326 1232 326 328 1233 328 327 1234 327 324 1235 324 329 1236 329 327 1237 327 328 1238 328 330 1239 330 327 1240 327 329 1241 329 331 1242 331 327 1243 327 330 1244 330 332 1245 332 327 1246 327 331 1247 331 333 1248 333 327 1249 327 332 1250 332 334 1251 334 327 1252 327 333 1253 333 335 1254 335 327 1255 327 334 1256 334 336 1257 336 327 1258 327 335 1259 335 364 1260 364 327 1261 327 336 1262 336 364 1263 364 337 1264 337 327 1265 327 364 1266 364 338 1267 338 337 1268 337 364 1269 364 339 1270 339 338 1271 338 364 1272 364 340 1273 340 339 1274 339 364 1275 364 341 1276 341 340 1277 340 364 1278 364 342 1279 342 341 1280 341 364 1281 364 343 1282 343 342 1283 342 364 1284 364 344 1285 344 343 1286 343 364 1287 364 345 1288 345 344 1289 344 364 1290 364 346 1291 346 345 1292 345 357 1293 357 315 1294 315 347 1295 347 357 1296 357 348 1297 348 315 1298 315 357 1299 357 349 1300 349 348 1301 348 357 1302 357 350 1303 350 349 1304 349 357 1305 357 351 1306 351 350 1307 350 357 1308 357 352 1309 352 351 1310 351 357 1311 357 353 1312 353 352 1313 352 357 1314 357 354 1315 354 353 1316 353 357 1317 357 355 1318 355 354 1319 354 357 1320 357 356 1321 356 355 1322 355 358 1323 358 356 1324 356 357 1325 357 359 1326 359 356 1327 356 358 1328 358 360 1329 360 356 1330 356 359 1331 359 361 1332 361 356 1333 356 360 1334 360 362 1335 362 356 1336 356 361 1337 361 363 1338 363 356 1339 356 362 1340 362 346 1341 346 356 1342 356 363 1343 363 364 1344 364 356 1345 356 346 1346 346 365 1347 365 356 1348 356 364 1349 364 366 1350 366 356 1351 356 365 1352 365 367 1353 367 356 1354 356 366 1355 366 368 1356 368 356 1357 356 367 1358 367 369 1359 369 356 1360 356 368 1361 368 370 1362 370 356 1363 356 369 1364 369 371 1365 371 356 1366 356 370 1367 370 372 1368 372 356 1369 356 371 1370 371 373 1371 373 356 1372 356 372 1373 372 374 1374 374 356 1375 356 373 1376 373 375 1377 375 356 1378 356 374 1379 374 376 1380 376 356 1381 356 375 1382 375 377 1383 377 356 1384 356 376 1385 376 378 1386 378 356 1387 356 377 1388 377 311 1389 311 356 1390 356 378 1391 378 411 1392 411 386 1393 386 379 1394 379 382 1395 382 380 1396 380 381 1397 381 383 1398 383 380 1399 380 382 1400 382 385 1401 385 380 1402 380 383 1403 383 385 1404 385 384 1405 384 380 1406 380 379 1407 379 384 1408 384 385 1409 385 379 1410 379 386 1411 386 384 1412 384 390 1413 390 387 1414 387 388 1415 388 390 1416 390 389 1417 389 387 1418 387 392 1419 392 389 1420 389 390 1421 390 392 1422 392 391 1423 391 389 1424 389 395 1425 395 391 1426 391 392 1427 392 395 1428 395 393 1429 393 391 1430 391 395 1431 395 394 1432 394 393 1433 393 397 1434 397 394 1435 394 395 1436 395 397 1437 397 396 1438 396 394 1439 394 399 1440 399 396 1441 396 397 1442 397 399 1443 399 398 1444 398 396 1445 396 400 1446 400 398 1447 398 399 1448 399 402 1449 402 398 1450 398 400 1451 400 402 1452 402 401 1453 401 398 1454 398 405 1455 405 401 1456 401 402 1457 402 405 1458 405 403 1459 403 401 1460 401 405 1461 405 404 1462 404 403 1463 403 406 1464 406 404 1465 404 405 1466 405 408 1467 408 404 1468 404 406 1469 406 408 1470 408 407 1471 407 404 1472 404 410 1473 410 407 1474 407 408 1475 408 410 1476 410 409 1477 409 407 1478 407 412 1479 412 409 1480 409 410 1481 410 412 1482 412 411 1483 411 409 1484 409 386 1485 386 411 1486 411 412 1487 412 437 1488 437 420 1489 420 438 1490 438 414 1491 414 439 1492 439 413 1493 413 414 1494 414 440 1495 440 439 1496 439 429 1497 429 440 1498 440 414 1499 414 413 1500 413 415 1501 415 416 1502 416 439 1503 439 415 1504 415 413 1505 413 426 1506 426 417 1507 417 418 1508 418 435 1509 435 438 1510 438 419 1511 419 438 1512 438 420 1513 420 441 1514 441 442 1515 442 415 1516 415 439 1517 439 442 1518 442 421 1519 421 415 1520 415 443 1521 443 421 1522 421 442 1523 442 443 1524 443 422 1525 422 421 1526 421 443 1527 443 423 1528 423 422 1529 422 444 1530 444 423 1531 423 443 1532 443 445 1533 445 423 1534 423 444 1535 444 445 1536 445 424 1537 424 423 1538 423 446 1539 446 424 1540 424 445 1541 445 446 1542 446 425 1543 425 424 1544 424 446 1545 446 426 1546 426 425 1547 425 447 1548 447 426 1549 426 446 1550 446 447 1551 447 417 1552 417 426 1553 426 447 1554 447 427 1555 427 417 1556 417 448 1557 448 427 1558 427 447 1559 447 448 1560 448 428 1561 428 427 1562 427 440 1563 440 449 1564 449 450 1565 450 429 1566 429 449 1567 449 440 1568 440 430 1569 430 449 1570 449 429 1571 429 430 1572 430 451 1573 451 449 1574 449 431 1575 431 451 1576 451 430 1577 430 431 1578 431 452 1579 452 451 1580 451 431 1581 431 453 1582 453 452 1583 452 436 1584 436 453 1585 453 431 1586 431 454 1587 454 448 1588 448 455 1589 455 454 1590 454 428 1591 428 448 1592 448 454 1593 454 432 1594 432 428 1595 428 456 1596 456 432 1597 432 454 1598 454 457 1599 457 432 1600 432 456 1601 456 457 1602 457 433 1603 433 432 1604 432 458 1605 458 433 1606 433 457 1607 457 458 1608 458 434 1609 434 433 1610 433 458 1611 458 435 1612 435 434 1613 434 420 1614 420 453 1615 453 436 1616 436 420 1617 420 459 1618 459 453 1619 453 459 1620 459 435 1621 435 458 1622 458 437 1623 437 435 1624 435 459 1625 459 420 1626 420 437 1627 437 459 1628 459 435 1629 435 437 1630 437 438 1631 438 458 1632 458 460 1633 460 459 1634 459 461 1635 461 457 1636 457 456 1637 456 456 1638 456 462 1639 462 461 1640 461 462 1641 462 456 1642 456 454 1643 454 461 1644 461 463 1645 463 460 1646 460 463 1647 463 461 1648 461 462 1649 462 457 1650 457 460 1651 460 458 1652 458 457 1653 457 461 1654 461 460 1655 460 454 1656 454 464 1657 464 462 1658 462 464 1659 464 454 1660 454 455 1661 455 462 1662 462 465 1663 465 463 1664 463 465 1665 465 462 1666 462 464 1667 464 448 1668 448 446 1669 446 455 1670 455 446 1671 446 448 1672 448 447 1673 447 455 1674 455 445 1675 445 464 1676 464 445 1677 445 455 1678 455 446 1679 446 464 1680 464 444 1681 444 465 1682 465 444 1683 444 464 1684 464 445 1685 445 459 1686 459 452 1687 452 453 1688 453 459 1689 459 466 1690 466 451 1691 451 460 1692 460 467 1693 467 466 1694 466 467 1695 467 460 1696 460 463 1697 463 466 1698 466 449 1699 449 451 1700 451 449 1701 449 466 1702 466 467 1703 467 452 1704 452 459 1705 459 451 1706 451 466 1707 466 459 1708 459 460 1709 460 463 1710 463 468 1711 468 467 1712 467 468 1713 468 463 1714 463 465 1715 465 467 1716 467 450 1717 450 449 1718 449 450 1719 450 467 1720 467 468 1721 468 465 1722 465 443 1723 443 468 1724 468 443 1725 443 465 1726 465 444 1727 444 468 1728 468 442 1729 442 450 1730 450 442 1731 442 468 1732 468 443 1733 443 450 1734 450 439 1735 439 440 1736 440 439 1737 439 450 1738 450 442 1739 442 489 1740 489 469 1741 469 470 1742 470 474 1743 474 471 1744 471 472 1745 472 474 1746 474 473 1747 473 471 1748 471 476 1749 476 473 1750 473 474 1751 474 476 1752 476 475 1753 475 473 1754 473 478 1755 478 475 1756 475 476 1757 476 478 1758 478 477 1759 477 475 1760 475 480 1761 480 477 1762 477 478 1763 478 480 1764 480 479 1765 479 477 1766 477 482 1767 482 479 1768 479 480 1769 480 482 1770 482 481 1771 481 479 1772 479 484 1773 484 481 1774 481 482 1775 482 484 1776 484 483 1777 483 481 1778 481 486 1779 486 483 1780 483 484 1781 484 486 1782 486 485 1783 485 483 1784 483 488 1785 488 485 1786 485 486 1787 486 488 1788 488 487 1789 487 485 1790 485 490 1791 490 487 1792 487 488 1793 488 490 1794 490 489 1795 489 487 1796 487 469 1797 469 489 1798 489 490 1799 490 511 1800 511 491 1801 491 492 1802 492 495 1803 495 493 1804 493 494 1805 494 496 1806 496 493 1807 493 495 1808 495 498 1809 498 493 1810 493 496 1811 496 498 1812 498 497 1813 497 493 1814 493 500 1815 500 497 1816 497 498 1817 498 500 1818 500 499 1819 499 497 1820 497 502 1821 502 499 1822 499 500 1823 500 502 1824 502 501 1825 501 499 1826 499 504 1827 504 501 1828 501 502 1829 502 504 1830 504 503 1831 503 501 1832 501 506 1833 506 503 1834 503 504 1835 504 506 1836 506 505 1837 505 503 1838 503 508 1839 508 505 1840 505 506 1841 506 508 1842 508 507 1843 507 505 1844 505 510 1845 510 507 1846 507 508 1847 508 510 1848 510 509 1849 509 507 1850 507 512 1851 512 509 1852 509 510 1853 510 512 1854 512 511 1855 511 509 1856 509 491 1857 491 511 1858 511 512 1859 512 537 1860 537 516 1861 516 538 1862 538 539 1863 539 513 1864 513 519 1865 519 540 1866 540 513 1867 513 539 1868 539 540 1869 540 514 1870 514 513 1871 513 535 1872 535 538 1873 538 515 1874 515 538 1875 538 516 1876 516 541 1877 541 527 1878 527 517 1879 517 518 1880 518 521 1881 521 519 1882 519 520 1883 520 521 1884 521 539 1885 539 519 1886 519 522 1887 522 539 1888 539 521 1889 521 522 1890 522 542 1891 542 539 1892 539 523 1893 523 542 1894 542 522 1895 522 523 1896 523 543 1897 543 542 1898 542 524 1899 524 543 1900 543 523 1901 523 524 1902 524 544 1903 544 543 1904 543 525 1905 525 544 1906 544 524 1907 524 525 1908 525 545 1909 545 544 1910 544 526 1911 526 545 1912 545 525 1913 525 526 1914 526 546 1915 546 545 1916 545 517 1917 517 546 1918 546 526 1919 526 517 1920 517 547 1921 547 546 1922 546 527 1923 527 547 1924 547 517 1925 517 528 1926 528 547 1927 547 527 1928 527 528 1929 528 548 1930 548 547 1931 547 529 1932 529 548 1933 548 528 1934 528 548 1935 548 549 1936 549 550 1937 550 529 1938 529 549 1939 549 548 1940 548 530 1941 530 549 1942 549 529 1943 529 530 1944 530 551 1945 551 549 1946 549 531 1947 531 551 1948 551 530 1949 530 531 1950 531 552 1951 552 551 1952 551 531 1953 531 553 1954 553 552 1955 552 536 1956 536 553 1957 553 531 1958 531 554 1959 554 540 1960 540 555 1961 555 554 1962 554 514 1963 514 540 1964 540 554 1965 554 532 1966 532 514 1967 514 556 1968 556 532 1969 532 554 1970 554 557 1971 557 532 1972 532 556 1973 556 557 1974 557 533 1975 533 532 1976 532 558 1977 558 533 1978 533 557 1979 557 558 1980 558 534 1981 534 533 1982 533 558 1983 558 535 1984 535 534 1985 534 516 1986 516 553 1987 553 536 1988 536 516 1989 516 559 1990 559 553 1991 553 559 1992 559 535 1993 535 558 1994 558 537 1995 537 535 1996 535 559 1997 559 516 1998 516 537 1999 537 559 2000 559 535 2001 535 537 2002 537 538 2003 538 558 2004 558 560 2005 560 559 2006 559 561 2007 561 557 2008 557 556 2009 556 556 2010 556 562 2011 562 561 2012 561 562 2013 562 556 2014 556 554 2015 554 561 2016 561 563 2017 563 560 2018 560 563 2019 563 561 2020 561 562 2021 562 557 2022 557 560 2023 560 558 2024 558 557 2025 557 561 2026 561 560 2027 560 554 2028 554 564 2029 564 562 2030 562 564 2031 564 554 2032 554 555 2033 555 562 2034 562 565 2035 565 563 2036 563 565 2037 565 562 2038 562 564 2039 564 540 2040 540 542 2041 542 555 2042 555 542 2043 542 540 2044 540 539 2045 539 555 2046 555 543 2047 543 564 2048 564 543 2049 543 555 2050 555 542 2051 542 564 2052 564 544 2053 544 565 2054 565 544 2055 544 564 2056 564 543 2057 543 559 2058 559 552 2059 552 553 2060 553 559 2061 559 566 2062 566 551 2063 551 560 2064 560 567 2065 567 566 2066 566 567 2067 567 560 2068 560 563 2069 563 566 2070 566 549 2071 549 551 2072 551 549 2073 549 566 2074 566 567 2075 567 552 2076 552 559 2077 559 551 2078 551 566 2079 566 559 2080 559 560 2081 560 563 2082 563 568 2083 568 567 2084 567 568 2085 568 563 2086 563 565 2087 565 567 2088 567 550 2089 550 549 2090 549 550 2091 550 567 2092 567 568 2093 568 565 2094 565 545 2095 545 568 2096 568 545 2097 545 565 2098 565 544 2099 544 568 2100 568 546 2101 546 550 2102 550 546 2103 546 568 2104 568 545 2105 545 550 2106 550 547 2107 547 548 2108 548 547 2109 547 550 2110 550 546 2111 546 593 2112 593 576 2113 576 594 2114 594 570 2115 570 595 2116 595 569 2117 569 570 2118 570 596 2119 596 595 2120 595 585 2121 585 596 2122 596 570 2123 570 569 2124 569 571 2125 571 572 2126 572 595 2127 595 571 2128 571 569 2129 569 582 2130 582 573 2131 573 574 2132 574 591 2133 591 594 2134 594 575 2135 575 594 2136 594 576 2137 576 597 2138 597 598 2139 598 571 2140 571 595 2141 595 598 2142 598 577 2143 577 571 2144 571 599 2145 599 577 2146 577 598 2147 598 599 2148 599 578 2149 578 577 2150 577 600 2151 600 578 2152 578 599 2153 599 600 2154 600 579 2155 579 578 2156 578 601 2157 601 579 2158 579 600 2159 600 601 2160 601 580 2161 580 579 2162 579 602 2163 602 580 2164 580 601 2165 601 602 2166 602 581 2167 581 580 2168 580 602 2169 602 582 2170 582 581 2171 581 603 2172 603 582 2173 582 602 2174 602 603 2175 603 573 2176 573 582 2177 582 603 2178 603 583 2179 583 573 2180 573 604 2181 604 583 2182 583 603 2183 603 604 2184 604 584 2185 584 583 2186 583 596 2187 596 605 2188 605 606 2189 606 585 2190 585 605 2191 605 596 2192 596 586 2193 586 605 2194 605 585 2195 585 586 2196 586 607 2197 607 605 2198 605 587 2199 587 607 2200 607 586 2201 586 587 2202 587 608 2203 608 607 2204 607 587 2205 587 609 2206 609 608 2207 608 592 2208 592 609 2209 609 587 2210 587 610 2211 610 604 2212 604 611 2213 611 610 2214 610 584 2215 584 604 2216 604 610 2217 610 588 2218 588 584 2219 584 612 2220 612 588 2221 588 610 2222 610 613 2223 613 588 2224 588 612 2225 612 613 2226 613 589 2227 589 588 2228 588 614 2229 614 589 2230 589 613 2231 613 614 2232 614 590 2233 590 589 2234 589 614 2235 614 591 2236 591 590 2237 590 576 2238 576 609 2239 609 592 2240 592 576 2241 576 615 2242 615 609 2243 609 615 2244 615 591 2245 591 614 2246 614 593 2247 593 591 2248 591 615 2249 615 576 2250 576 593 2251 593 615 2252 615 591 2253 591 593 2254 593 594 2255 594 614 2256 614 616 2257 616 615 2258 615 617 2259 617 613 2260 613 612 2261 612 612 2262 612 618 2263 618 617 2264 617 618 2265 618 612 2266 612 610 2267 610 617 2268 617 619 2269 619 620 2270 620 619 2271 619 617 2272 617 618 2273 618 616 2274 616 607 2275 607 608 2276 608 616 2277 616 621 2278 621 607 2279 607 620 2280 620 622 2281 622 621 2282 621 622 2283 622 620 2284 620 619 2285 619 615 2286 615 608 2287 608 609 2288 609 608 2289 608 615 2290 615 616 2291 616 621 2292 621 605 2293 605 607 2294 607 605 2295 605 621 2296 621 622 2297 622 616 2298 616 614 2299 614 620 2300 620 613 2301 613 620 2302 620 614 2303 614 613 2304 613 617 2305 617 620 2306 620 621 2307 621 616 2308 616 620 2309 620 610 2310 610 623 2311 623 618 2312 618 623 2313 623 610 2314 610 611 2315 611 618 2316 618 624 2317 624 619 2318 619 624 2319 624 618 2320 618 623 2321 623 604 2322 604 602 2323 602 611 2324 611 602 2325 602 604 2326 604 603 2327 603 611 2328 611 601 2329 601 623 2330 623 601 2331 601 611 2332 611 602 2333 602 623 2334 623 600 2335 600 624 2336 624 600 2337 600 623 2338 623 601 2339 601 619 2340 619 625 2341 625 622 2342 622 625 2343 625 619 2344 619 624 2345 624 622 2346 622 606 2347 606 605 2348 605 606 2349 606 622 2350 622 625 2351 625 624 2352 624 599 2353 599 625 2354 625 599 2355 599 624 2356 624 600 2357 600 625 2358 625 598 2359 598 606 2360 606 598 2361 598 625 2362 625 599 2363 599 606 2364 606 595 2365 595 596 2366 596 595 2367 595 606 2368 606 598 2369 598 646 2370 646 626 2371 626 627 2372 627 631 2373 631 628 2374 628 629 2375 629 631 2376 631 630 2377 630 628 2378 628 633 2379 633 630 2380 630 631 2381 631 633 2382 633 632 2383 632 630 2384 630 635 2385 635 632 2386 632 633 2387 633 635 2388 635 634 2389 634 632 2390 632 637 2391 637 634 2392 634 635 2393 635 637 2394 637 636 2395 636 634 2396 634 639 2397 639 636 2398 636 637 2399 637 639 2400 639 638 2401 638 636 2402 636 641 2403 641 638 2404 638 639 2405 639 641 2406 641 640 2407 640 638 2408 638 643 2409 643 640 2410 640 641 2411 641 643 2412 643 642 2413 642 640 2414 640 645 2415 645 642 2416 642 643 2417 643 645 2418 645 644 2419 644 642 2420 642 647 2421 647 644 2422 644 645 2423 645 647 2424 647 646 2425 646 644 2426 644 626 2427 626 646 2428 646 647 2429 647 668 2430 668 648 2431 648 649 2432 649 652 2433 652 650 2434 650 651 2435 651 653 2436 653 650 2437 650 652 2438 652 655 2439 655 650 2440 650 653 2441 653 655 2442 655 654 2443 654 650 2444 650 657 2445 657 654 2446 654 655 2447 655 657 2448 657 656 2449 656 654 2450 654 659 2451 659 656 2452 656 657 2453 657 659 2454 659 658 2455 658 656 2456 656 661 2457 661 658 2458 658 659 2459 659 661 2460 661 660 2461 660 658 2462 658 663 2463 663 660 2464 660 661 2465 661 663 2466 663 662 2467 662 660 2468 660 665 2469 665 662 2470 662 663 2471 663 665 2472 665 664 2473 664 662 2474 662 667 2475 667 664 2476 664 665 2477 665 667 2478 667 666 2479 666 664 2480 664 669 2481 669 666 2482 666 667 2483 667 669 2484 669 668 2485 668 666 2486 666 648 2487 648 668 2488 668 669 2489 669 694 2490 694 673 2491 673 695 2492 695 696 2493 696 670 2494 670 676 2495 676 697 2496 697 670 2497 670 696 2498 696 697 2499 697 671 2500 671 670 2501 670 692 2502 692 695 2503 695 672 2504 672 695 2505 695 673 2506 673 698 2507 698 684 2508 684 674 2509 674 675 2510 675 678 2511 678 676 2512 676 677 2513 677 678 2514 678 696 2515 696 676 2516 676 678 2517 678 699 2518 699 696 2519 696 679 2520 679 699 2521 699 678 2522 678 679 2523 679 700 2524 700 699 2525 699 680 2526 680 700 2527 700 679 2528 679 681 2529 681 700 2530 700 680 2531 680 681 2532 681 701 2533 701 700 2534 700 682 2535 682 701 2536 701 681 2537 681 682 2538 682 702 2539 702 701 2540 701 683 2541 683 702 2542 702 682 2543 682 683 2544 683 703 2545 703 702 2546 702 674 2547 674 703 2548 703 683 2549 683 674 2550 674 704 2551 704 703 2552 703 684 2553 684 704 2554 704 674 2555 674 685 2556 685 704 2557 704 684 2558 684 685 2559 685 705 2560 705 704 2561 704 686 2562 686 705 2563 705 685 2564 685 705 2565 705 706 2566 706 707 2567 707 686 2568 686 706 2569 706 705 2570 705 687 2571 687 706 2572 706 686 2573 686 687 2574 687 708 2575 708 706 2576 706 688 2577 688 708 2578 708 687 2579 687 688 2580 688 709 2581 709 708 2582 708 688 2583 688 710 2584 710 709 2585 709 693 2586 693 710 2587 710 688 2588 688 711 2589 711 697 2590 697 712 2591 712 711 2592 711 671 2593 671 697 2594 697 711 2595 711 689 2596 689 671 2597 671 713 2598 713 689 2599 689 711 2600 711 713 2601 713 690 2602 690 689 2603 689 714 2604 714 690 2605 690 713 2606 713 715 2607 715 690 2608 690 714 2609 714 715 2610 715 691 2611 691 690 2612 690 715 2613 715 692 2614 692 691 2615 691 673 2616 673 710 2617 710 693 2618 693 673 2619 673 716 2620 716 710 2621 710 716 2622 716 692 2623 692 715 2624 715 694 2625 694 692 2626 692 716 2627 716 673 2628 673 694 2629 694 716 2630 716 692 2631 692 694 2632 694 695 2633 695 715 2634 715 717 2635 717 716 2636 716 718 2637 718 714 2638 714 713 2639 713 713 2640 713 719 2641 719 718 2642 718 719 2643 719 713 2644 713 711 2645 711 718 2646 718 720 2647 720 717 2648 717 720 2649 720 718 2650 718 719 2651 719 714 2652 714 717 2653 717 715 2654 715 714 2655 714 718 2656 718 717 2657 717 711 2658 711 721 2659 721 719 2660 719 721 2661 721 711 2662 711 712 2663 712 719 2664 719 722 2665 722 720 2666 720 722 2667 722 719 2668 719 721 2669 721 697 2670 697 699 2671 699 712 2672 712 699 2673 699 697 2674 697 696 2675 696 712 2676 712 700 2677 700 721 2678 721 700 2679 700 712 2680 712 699 2681 699 721 2682 721 701 2683 701 722 2684 722 701 2685 701 721 2686 721 700 2687 700 716 2688 716 709 2689 709 710 2690 710 716 2691 716 723 2692 723 708 2693 708 717 2694 717 724 2695 724 723 2696 723 724 2697 724 717 2698 717 720 2699 720 723 2700 723 706 2701 706 708 2702 708 706 2703 706 723 2704 723 724 2705 724 709 2706 709 716 2707 716 708 2708 708 723 2709 723 716 2710 716 717 2711 717 720 2712 720 725 2713 725 724 2714 724 725 2715 725 720 2716 720 722 2717 722 724 2718 724 707 2719 707 706 2720 706 707 2721 707 724 2722 724 725 2723 725 722 2724 722 702 2725 702 725 2726 725 702 2727 702 722 2728 722 701 2729 701 725 2730 725 703 2731 703 707 2732 707 703 2733 703 725 2734 725 702 2735 702 707 2736 707 704 2737 704 705 2738 705 704 2739 704 707 2740 707 703 2741 703 773 2742 773 774 2743 774 726 2744 726 775 2745 775 726 2746 726 774 2747 774 775 2748 775 727 2749 727 726 2750 726 776 2751 776 727 2752 727 775 2753 775 776 2754 776 728 2755 728 727 2756 727 777 2757 777 728 2758 728 776 2759 776 777 2760 777 729 2761 729 728 2762 728 778 2763 778 729 2764 729 777 2765 777 778 2766 778 730 2767 730 729 2768 729 779 2769 779 730 2770 730 778 2771 778 779 2772 779 731 2773 731 730 2774 730 780 2775 780 731 2776 731 779 2777 779 780 2778 780 732 2779 732 731 2780 731 781 2781 781 732 2782 732 780 2783 780 781 2784 781 733 2785 733 732 2786 732 782 2787 782 733 2788 733 781 2789 781 782 2790 782 734 2791 734 733 2792 733 783 2793 783 734 2794 734 782 2795 782 783 2796 783 735 2797 735 734 2798 734 784 2799 784 735 2800 735 783 2801 783 784 2802 784 736 2803 736 735 2804 735 785 2805 785 736 2806 736 784 2807 784 785 2808 785 737 2809 737 736 2810 736 786 2811 786 737 2812 737 785 2813 785 786 2814 786 738 2815 738 737 2816 737 787 2817 787 738 2818 738 786 2819 786 787 2820 787 739 2821 739 738 2822 738 788 2823 788 739 2824 739 787 2825 787 788 2826 788 740 2827 740 739 2828 739 788 2829 788 741 2830 741 740 2831 740 788 2832 788 742 2833 742 741 2834 741 789 2835 789 742 2836 742 788 2837 788 789 2838 789 743 2839 743 742 2840 742 790 2841 790 743 2842 743 789 2843 789 790 2844 790 744 2845 744 743 2846 743 791 2847 791 744 2848 744 790 2849 790 791 2850 791 745 2851 745 744 2852 744 792 2853 792 745 2854 745 791 2855 791 792 2856 792 746 2857 746 745 2858 745 792 2859 792 747 2860 747 746 2861 746 793 2862 793 747 2863 747 792 2864 792 793 2865 793 748 2866 748 747 2867 747 794 2868 794 748 2869 748 793 2870 793 794 2871 794 749 2872 749 748 2873 748 794 2874 794 750 2875 750 749 2876 749 795 2877 795 750 2878 750 794 2879 794 795 2880 795 751 2881 751 750 2882 750 796 2883 796 751 2884 751 795 2885 795 796 2886 796 752 2887 752 751 2888 751 797 2889 797 752 2890 752 796 2891 796 797 2892 797 753 2893 753 752 2894 752 798 2895 798 753 2896 753 797 2897 797 798 2898 798 754 2899 754 753 2900 753 799 2901 799 754 2902 754 798 2903 798 799 2904 799 755 2905 755 754 2906 754 800 2907 800 755 2908 755 799 2909 799 800 2910 800 756 2911 756 755 2912 755 801 2913 801 756 2914 756 800 2915 800 801 2916 801 757 2917 757 756 2918 756 802 2919 802 757 2920 757 801 2921 801 802 2922 802 758 2923 758 757 2924 757 803 2925 803 758 2926 758 802 2927 802 803 2928 803 759 2929 759 758 2930 758 804 2931 804 759 2932 759 803 2933 803 804 2934 804 760 2935 760 759 2936 759 805 2937 805 760 2938 760 804 2939 804 805 2940 805 761 2941 761 760 2942 760 806 2943 806 761 2944 761 805 2945 805 806 2946 806 762 2947 762 761 2948 761 807 2949 807 762 2950 762 806 2951 806 807 2952 807 763 2953 763 762 2954 762 808 2955 808 763 2956 763 807 2957 807 808 2958 808 764 2959 764 763 2960 763 808 2961 808 765 2962 765 764 2963 764 808 2964 808 766 2965 766 765 2966 765 809 2967 809 766 2968 766 808 2969 808 809 2970 809 767 2971 767 766 2972 766 809 2973 809 768 2974 768 767 2975 767 810 2976 810 768 2977 768 809 2978 809 811 2979 811 768 2980 768 810 2981 810 811 2982 811 769 2983 769 768 2984 768 811 2985 811 770 2986 770 769 2987 769 812 2988 812 770 2989 770 811 2990 811 812 2991 812 771 2992 771 770 2993 770 813 2994 813 771 2995 771 812 2996 812 774 2997 774 771 2998 771 813 2999 813 774 3000 774 772 3001 772 771 3002 771 774 3003 774 773 3004 773 772 3005 772 808 3006 808 814 3007 814 809 3008 809 814 3009 814 808 3010 808 807 3011 807 809 3012 809 815 3013 815 810 3014 810 815 3015 815 809 3016 809 814 3017 814 810 3018 810 816 3019 816 811 3020 811 816 3021 816 810 3022 810 815 3023 815 811 3024 811 817 3025 817 812 3026 812 817 3027 817 811 3028 811 816 3029 816 812 3030 812 818 3031 818 813 3032 813 818 3033 818 812 3034 812 817 3035 817 813 3036 813 775 3037 775 774 3038 774 775 3039 775 813 3040 813 818 3041 818 807 3042 807 819 3043 819 814 3044 814 819 3045 819 807 3046 807 806 3047 806 806 3048 806 820 3049 820 819 3050 819 820 3051 820 806 3052 806 805 3053 805 814 3054 814 821 3055 821 815 3056 815 821 3057 821 814 3058 814 819 3059 819 815 3060 815 822 3061 822 816 3062 816 822 3063 822 815 3064 815 821 3065 821 819 3066 819 823 3067 823 821 3068 821 823 3069 823 819 3070 819 820 3071 820 821 3072 821 824 3073 824 822 3074 822 824 3075 824 821 3076 821 823 3077 823 816 3078 816 825 3079 825 817 3080 817 825 3081 825 816 3082 816 822 3083 822 817 3084 817 826 3085 826 818 3086 818 826 3087 826 817 3088 817 825 3089 825 822 3090 822 827 3091 827 825 3092 825 827 3093 827 822 3094 822 824 3095 824 825 3096 825 828 3097 828 826 3098 826 828 3099 828 825 3100 825 827 3101 827 818 3102 818 776 3103 776 775 3104 775 776 3105 776 818 3106 818 826 3107 826 826 3108 826 777 3109 777 776 3110 776 777 3111 777 826 3112 826 828 3113 828 805 3114 805 829 3115 829 820 3116 820 829 3117 829 805 3118 805 804 3119 804 804 3120 804 830 3121 830 829 3122 829 830 3123 830 804 3124 804 803 3125 803 820 3126 820 831 3127 831 823 3128 823 831 3129 831 820 3130 820 829 3131 829 823 3132 823 832 3133 832 824 3134 824 832 3135 832 823 3136 823 831 3137 831 829 3138 829 833 3139 833 831 3140 831 833 3141 833 829 3142 829 830 3143 830 831 3144 831 834 3145 834 832 3146 832 834 3147 834 831 3148 831 833 3149 833 824 3150 824 835 3151 835 827 3152 827 835 3153 835 824 3154 824 832 3155 832 827 3156 827 836 3157 836 828 3158 828 836 3159 836 827 3160 827 835 3161 835 832 3162 832 837 3163 837 835 3164 835 837 3165 837 832 3166 832 834 3167 834 835 3168 835 838 3169 838 836 3170 836 838 3171 838 835 3172 835 837 3173 837 828 3174 828 778 3175 778 777 3176 777 778 3177 778 828 3178 828 836 3179 836 836 3180 836 779 3181 779 778 3182 778 779 3183 779 836 3184 836 838 3185 838 803 3186 803 839 3187 839 830 3188 830 839 3189 839 803 3190 803 802 3191 802 802 3192 802 840 3193 840 839 3194 839 840 3195 840 802 3196 802 801 3197 801 830 3198 830 841 3199 841 833 3200 833 841 3201 841 830 3202 830 839 3203 839 833 3204 833 842 3205 842 834 3206 834 842 3207 842 833 3208 833 841 3209 841 839 3210 839 843 3211 843 841 3212 841 843 3213 843 839 3214 839 840 3215 840 841 3216 841 844 3217 844 842 3218 842 844 3219 844 841 3220 841 843 3221 843 834 3222 834 845 3223 845 837 3224 837 845 3225 845 834 3226 834 842 3227 842 837 3228 837 846 3229 846 838 3230 838 846 3231 846 837 3232 837 845 3233 845 842 3234 842 847 3235 847 845 3236 845 847 3237 847 842 3238 842 844 3239 844 845 3240 845 848 3241 848 846 3242 846 848 3243 848 845 3244 845 847 3245 847 838 3246 838 780 3247 780 779 3248 779 780 3249 780 838 3250 838 846 3251 846 846 3252 846 781 3253 781 780 3254 780 781 3255 781 846 3256 846 848 3257 848 801 3258 801 849 3259 849 840 3260 840 849 3261 849 801 3262 801 800 3263 800 800 3264 800 850 3265 850 849 3266 849 850 3267 850 800 3268 800 799 3269 799 840 3270 840 851 3271 851 843 3272 843 851 3273 851 840 3274 840 849 3275 849 843 3276 843 852 3277 852 844 3278 844 852 3279 852 843 3280 843 851 3281 851 849 3282 849 853 3283 853 851 3284 851 853 3285 853 849 3286 849 850 3287 850 851 3288 851 854 3289 854 852 3290 852 854 3291 854 851 3292 851 853 3293 853 844 3294 844 855 3295 855 847 3296 847 855 3297 855 844 3298 844 852 3299 852 847 3300 847 856 3301 856 848 3302 848 856 3303 856 847 3304 847 855 3305 855 852 3306 852 857 3307 857 855 3308 855 857 3309 857 852 3310 852 854 3311 854 855 3312 855 858 3313 858 856 3314 856 858 3315 858 855 3316 855 857 3317 857 848 3318 848 782 3319 782 781 3320 781 782 3321 782 848 3322 848 856 3323 856 856 3324 856 783 3325 783 782 3326 782 783 3327 783 856 3328 856 858 3329 858 799 3330 799 859 3331 859 850 3332 850 859 3333 859 799 3334 799 798 3335 798 798 3336 798 860 3337 860 859 3338 859 860 3339 860 798 3340 798 797 3341 797 850 3342 850 861 3343 861 853 3344 853 861 3345 861 850 3346 850 859 3347 859 853 3348 853 862 3349 862 854 3350 854 862 3351 862 853 3352 853 861 3353 861 859 3354 859 863 3355 863 861 3356 861 863 3357 863 859 3358 859 860 3359 860 861 3360 861 864 3361 864 862 3362 862 864 3363 864 861 3364 861 863 3365 863 854 3366 854 865 3367 865 857 3368 857 865 3369 865 854 3370 854 862 3371 862 857 3372 857 866 3373 866 858 3374 858 866 3375 866 857 3376 857 865 3377 865 862 3378 862 867 3379 867 865 3380 865 867 3381 867 862 3382 862 864 3383 864 865 3384 865 868 3385 868 866 3386 866 868 3387 868 865 3388 865 867 3389 867 858 3390 858 784 3391 784 783 3392 783 784 3393 784 858 3394 858 866 3395 866 866 3396 866 785 3397 785 784 3398 784 785 3399 785 866 3400 866 868 3401 868 797 3402 797 869 3403 869 860 3404 860 869 3405 869 797 3406 797 796 3407 796 796 3408 796 870 3409 870 869 3410 869 870 3411 870 796 3412 796 795 3413 795 860 3414 860 871 3415 871 863 3416 863 871 3417 871 860 3418 860 869 3419 869 863 3420 863 872 3421 872 864 3422 864 872 3423 872 863 3424 863 871 3425 871 869 3426 869 873 3427 873 871 3428 871 873 3429 873 869 3430 869 870 3431 870 871 3432 871 874 3433 874 872 3434 872 874 3435 874 871 3436 871 873 3437 873 864 3438 864 875 3439 875 867 3440 867 875 3441 875 864 3442 864 872 3443 872 867 3444 867 876 3445 876 868 3446 868 876 3447 876 867 3448 867 875 3449 875 872 3450 872 877 3451 877 875 3452 875 877 3453 877 872 3454 872 874 3455 874 875 3456 875 878 3457 878 876 3458 876 878 3459 878 875 3460 875 877 3461 877 868 3462 868 786 3463 786 785 3464 785 786 3465 786 868 3466 868 876 3467 876 876 3468 876 787 3469 787 786 3470 786 787 3471 787 876 3472 876 878 3473 878 795 3474 795 793 3475 793 870 3476 870 793 3477 793 795 3478 795 794 3479 794 870 3480 870 792 3481 792 873 3482 873 792 3483 792 870 3484 870 793 3485 793 873 3486 873 791 3487 791 874 3488 874 791 3489 791 873 3490 873 792 3491 792 874 3492 874 790 3493 790 877 3494 877 790 3495 790 874 3496 874 791 3497 791 877 3498 877 789 3499 789 878 3500 878 789 3501 789 877 3502 877 790 3503 790 878 3504 878 788 3505 788 787 3506 787 788 3507 788 878 3508 878 789 3509 789

+
+
+ + + + +80.500000 15.624551 36.799999 +80.500000 14.606982 37.799961 +76.480164 11.341559 37.799961 +76.393021 10.500000 37.799961 +75.375450 10.500000 36.799999 +76.730850 12.131200 37.799961 +75.484184 11.550069 36.799999 +77.115974 12.827158 37.799961 +75.796982 12.535356 36.799999 +77.595924 13.404075 37.799961 +76.277527 13.403748 36.799999 +76.876396 14.123605 36.799999 +78.172844 13.884027 37.799961 +77.596252 14.722471 36.799999 +78.868797 14.269149 37.799961 +78.464645 15.203014 36.799999 +79.658440 14.519835 37.799961 +79.449928 15.515812 36.799999 +126.500000 15.000000 38.400002 +126.500000 15.000000 38.299999 +123.500000 15.000000 38.299999 +123.500000 15.000000 38.400002 +123.525040 14.727056 38.299999 +123.525040 14.727056 38.400002 +123.605316 14.447858 38.299999 +123.605316 14.447858 38.400002 +123.744507 14.179185 38.299999 +123.744507 14.179185 38.400002 +123.939339 13.939340 38.299999 +123.939339 13.939340 38.400002 +124.179184 13.744507 38.299999 +124.179184 13.744507 38.400002 +124.447861 13.605317 38.299999 +124.447861 13.605317 38.400002 +124.727058 13.525042 38.299999 +124.727058 13.525042 38.400002 +125.000000 13.500000 38.299999 +125.000000 13.500000 38.400002 +125.272942 13.525042 38.299999 +125.272942 13.525042 38.400002 +125.552139 13.605317 38.299999 +125.552139 13.605317 38.400002 +125.820816 13.744507 38.299999 +125.820816 13.744507 38.400002 +126.060661 13.939340 38.299999 +126.060661 13.939340 38.400002 +126.255493 14.179185 38.299999 +126.255493 14.179185 38.400002 +126.394684 14.447858 38.299999 +126.394684 14.447858 38.400002 +126.474960 14.727056 38.299999 +126.474960 14.727056 38.400002 +38.605316 14.447858 38.299999 +38.500000 15.000000 38.299999 +38.500000 15.000000 38.400002 +38.525043 14.727056 38.299999 +41.500000 15.000000 38.400002 +41.500000 15.000000 38.299999 +41.474957 14.727056 38.400002 +41.474957 14.727056 38.299999 +41.394684 14.447858 38.400002 +41.394684 14.447858 38.299999 +41.255493 14.179185 38.400002 +41.255493 14.179185 38.299999 +41.060661 13.939340 38.400002 +41.060661 13.939340 38.299999 +40.820816 13.744507 38.400002 +40.820816 13.744507 38.299999 +40.552143 13.605317 38.400002 +40.552143 13.605317 38.299999 +40.272945 13.525042 38.400002 +40.272945 13.525042 38.299999 +40.000000 13.500000 38.400002 +40.000000 13.500000 38.299999 +39.727055 13.525042 38.400002 +39.727055 13.525042 38.299999 +39.447857 13.605317 38.400002 +39.447857 13.605317 38.299999 +39.179184 13.744507 38.400002 +39.179184 13.744507 38.299999 +38.939339 13.939340 38.400002 +38.939339 13.939340 38.299999 +38.744507 14.179185 38.400002 +38.744507 14.179185 38.299999 +38.605316 14.447858 38.400002 +38.525043 14.727056 38.400002 +91.205521 -3.000000 11.743831 +91.500000 1.000000 11.800000 +91.500000 -3.000000 11.800000 +91.354431 1.000000 11.786644 +91.354431 -3.000000 11.786644 +91.205521 1.000000 11.743831 +91.354431 -3.000000 10.213356 +91.500000 -3.000000 10.200000 +91.500000 1.000000 10.200000 +91.354431 1.000000 10.213356 +91.205521 -3.000000 10.256169 +91.062233 -3.000000 10.330403 +91.205521 1.000000 10.256169 +91.062233 1.000000 10.330403 +90.934311 -3.000000 10.434315 +90.934311 1.000000 10.434315 +90.830406 -3.000000 10.562232 +90.830406 1.000000 10.562232 +90.756172 -3.000000 10.705524 +90.756172 1.000000 10.705524 +90.713356 -3.000000 10.854429 +90.713356 1.000000 10.854429 +90.699997 -3.000000 11.000000 +90.699997 1.000000 11.000000 +90.713356 -3.000000 11.145571 +90.713356 1.000000 11.145571 +90.756172 -3.000000 11.294476 +90.756172 1.000000 11.294476 +90.830406 -3.000000 11.437768 +90.934311 -3.000000 11.565685 +90.830406 1.000000 11.437768 +90.934311 1.000000 11.565685 +91.062233 -3.000000 11.669597 +91.062233 1.000000 11.669597 +91.354431 1.000000 10.213356 +91.500000 1.000000 10.200000 +91.500000 1.480688 11.000000 +91.500000 1.000000 11.800000 +91.354431 1.000000 11.786644 +91.205521 1.000000 11.743831 +91.062233 1.000000 11.669597 +90.934311 1.000000 11.565685 +90.830406 1.000000 11.437768 +90.756172 1.000000 11.294476 +90.713356 1.000000 11.145571 +90.699997 1.000000 11.000000 +90.713356 1.000000 10.854429 +90.756172 1.000000 10.705524 +90.830406 1.000000 10.562232 +90.934311 1.000000 10.434315 +91.062233 1.000000 10.330403 +91.205521 1.000000 10.256169 +91.500000 1.480688 11.000000 +91.500000 1.480688 11.000000 +91.500000 1.480688 11.000000 +91.500000 1.480688 11.000000 +91.500000 1.480688 11.000000 +91.500000 1.480688 11.000000 +91.500000 1.480688 11.000000 +91.500000 1.480688 11.000000 +91.500000 1.480688 11.000000 +91.500000 1.480688 11.000000 +91.500000 1.480688 11.000000 +91.500000 1.480688 11.000000 +91.500000 1.480688 11.000000 +91.500000 1.480688 11.000000 +91.500000 1.480688 11.000000 +91.500000 1.480688 11.000000 +73.205521 -3.000000 11.743831 +73.354431 1.000000 11.786644 +73.500000 1.000000 11.800000 +73.500000 -3.000000 11.800000 +73.205521 1.000000 11.743831 +73.354431 -3.000000 11.786644 +73.500000 -3.000000 10.200000 +73.500000 1.000000 10.200000 +73.354431 -3.000000 10.213356 +73.205521 -3.000000 10.256169 +73.354431 1.000000 10.213356 +73.205521 1.000000 10.256169 +73.062233 -3.000000 10.330403 +73.062233 1.000000 10.330403 +72.934311 -3.000000 10.434315 +72.934311 1.000000 10.434315 +72.830406 -3.000000 10.562232 +72.830406 1.000000 10.562232 +72.756172 -3.000000 10.705524 +72.756172 1.000000 10.705524 +72.713356 -3.000000 10.854429 +72.713356 1.000000 10.854429 +72.699997 -3.000000 11.000000 +72.699997 1.000000 11.000000 +72.713356 -3.000000 11.145571 +72.713356 1.000000 11.145571 +72.756172 -3.000000 11.294476 +72.830406 -3.000000 11.437768 +72.756172 1.000000 11.294476 +72.830406 1.000000 11.437768 +72.934311 -3.000000 11.565685 +73.062233 -3.000000 11.669597 +72.934311 1.000000 11.565685 +73.062233 1.000000 11.669597 +73.354431 1.000000 10.213356 +73.500000 1.000000 10.200000 +73.500000 1.480688 11.000000 +73.500000 1.000000 11.800000 +73.354431 1.000000 11.786644 +73.205521 1.000000 11.743831 +73.062233 1.000000 11.669597 +72.934311 1.000000 11.565685 +72.830406 1.000000 11.437768 +72.756172 1.000000 11.294476 +72.713356 1.000000 11.145571 +72.699997 1.000000 11.000000 +72.713356 1.000000 10.854429 +72.756172 1.000000 10.705524 +72.830406 1.000000 10.562232 +72.934311 1.000000 10.434315 +73.062233 1.000000 10.330403 +73.205521 1.000000 10.256169 +73.500000 1.480688 11.000000 +73.500000 1.480688 11.000000 +73.500000 1.480688 11.000000 +73.500000 1.480688 11.000000 +73.500000 1.480688 11.000000 +73.500000 1.480688 11.000000 +73.500000 1.480688 11.000000 +73.500000 1.480688 11.000000 +73.500000 1.480688 11.000000 +73.500000 1.480688 11.000000 +73.500000 1.480688 11.000000 +73.500000 1.480688 11.000000 +73.500000 1.480688 11.000000 +73.500000 1.480688 11.000000 +73.500000 1.480688 11.000000 +73.500000 1.480688 11.000000 +43.000000 15.000000 38.599998 +43.000000 15.000000 38.400002 +37.000000 15.000000 38.400002 +37.000000 15.000000 38.599998 +37.050083 14.454111 38.400002 +37.210636 13.895716 38.400002 +37.050083 14.454111 38.599998 +37.489014 13.358371 38.400002 +37.210636 13.895716 38.599998 +37.489014 13.358371 38.599998 +37.878681 12.878679 38.400002 +37.878681 12.878679 38.599998 +38.358372 12.489014 38.400002 +38.358372 12.489014 38.599998 +38.895718 12.210635 38.400002 +38.895718 12.210635 38.599998 +39.454109 12.050084 38.400002 +39.454109 12.050084 38.599998 +40.000000 12.000000 38.400002 +40.000000 12.000000 38.599998 +40.545891 12.050084 38.400002 +41.104282 12.210635 38.400002 +40.545891 12.050084 38.599998 +41.104282 12.210635 38.599998 +41.641628 12.489014 38.400002 +41.641628 12.489014 38.599998 +42.121319 12.878679 38.400002 +42.121319 12.878679 38.599998 +42.510986 13.358371 38.400002 +42.510986 13.358371 38.599998 +42.789364 13.895716 38.400002 +42.789364 13.895716 38.599998 +42.949917 14.454111 38.400002 +42.949917 14.454111 38.599998 +84.500000 6.393018 37.799961 +84.500000 6.400000 38.599998 +88.599998 10.500000 38.599998 +88.606979 10.500000 37.799961 +88.513000 9.659871 38.599998 +88.262741 8.871572 38.599998 +88.519836 9.658441 37.799961 +88.269150 8.868800 37.799961 +87.878273 8.176798 38.599998 +87.399139 7.600862 38.599998 +87.884026 8.172842 37.799961 +87.404076 7.595925 37.799961 +86.823204 7.121727 38.599998 +86.827156 7.115973 37.799961 +86.128426 6.737258 38.599998 +85.340126 6.486998 38.599998 +86.131203 6.730851 37.799961 +85.341560 6.480165 37.799961 +153.358368 12.489014 35.599998 +152.000000 15.000000 35.599998 +151.973816 15.000000 38.599998 +152.050079 14.454111 35.599998 +152.024338 14.449347 38.599998 +152.210632 13.895716 35.599998 +152.489014 13.358371 35.599998 +152.186295 13.886079 38.599998 +152.878677 12.878679 35.599998 +152.467102 13.344045 38.599998 +157.975662 14.449347 38.599998 +158.026184 15.000000 38.599998 +158.000000 15.000000 35.599998 +157.949921 14.454111 35.599998 +157.813705 13.886079 38.599998 +157.532898 13.344045 38.599998 +157.789368 13.895716 35.599998 +157.510986 13.358371 35.599998 +157.139832 12.860168 38.599998 +156.655960 12.467100 38.599998 +157.121323 12.878679 35.599998 +156.641632 12.489014 35.599998 +156.113922 12.186293 38.599998 +155.550659 12.024341 38.599998 +156.104279 12.210635 35.599998 +155.545883 12.050084 35.599998 +155.000000 11.973820 38.599998 +155.000000 12.000000 35.599998 +154.449341 12.024341 38.599998 +154.454117 12.050084 35.599998 +153.886078 12.186293 38.599998 +153.895721 12.210635 35.599998 +153.344040 12.467100 38.599998 +152.860168 12.860168 38.599998 +156.500000 15.000000 9.900000 +156.500000 15.000000 7.400000 +153.500000 15.000000 7.400000 +153.500000 15.000000 9.900000 +153.525040 14.727056 7.400000 +153.525040 14.727056 9.900000 +153.605316 14.447858 7.400000 +153.605316 14.447858 9.900000 +153.744507 14.179185 7.400000 +153.744507 14.179185 9.900000 +153.939346 13.939340 7.400000 +153.939346 13.939340 9.900000 +154.179184 13.744507 7.400000 +154.179184 13.744507 9.900000 +154.447861 13.605317 7.400000 +154.447861 13.605317 9.900000 +154.727051 13.525042 7.400000 +154.727051 13.525042 9.900000 +155.000000 13.500000 7.400000 +155.000000 13.500000 9.900000 +155.272949 13.525042 7.400000 +155.272949 13.525042 9.900000 +155.552139 13.605317 7.400000 +155.552139 13.605317 9.900000 +155.820816 13.744507 7.400000 +155.820816 13.744507 9.900000 +156.060654 13.939340 7.400000 +156.060654 13.939340 9.900000 +156.255493 14.179185 7.400000 +156.255493 14.179185 9.900000 +156.394684 14.447858 7.400000 +156.394684 14.447858 9.900000 +156.474960 14.727056 7.400000 +156.474960 14.727056 9.900000 +157.828430 12.171573 36.799999 +157.377014 11.782889 36.799999 +158.781845 14.300159 7.400000 +158.846054 15.000000 7.400000 +159.000000 15.000000 36.799999 +151.000000 15.000000 36.799999 +151.153946 15.000000 7.400000 +151.066772 14.272148 36.799999 +151.218155 14.300159 7.400000 +151.280853 13.527621 36.799999 +151.423981 13.584286 7.400000 +151.652023 12.811161 36.799999 +152.171570 12.171573 36.799999 +151.780869 12.895398 7.400000 +152.280426 12.280424 7.400000 +152.811157 11.652018 36.799999 +152.895401 11.780865 7.400000 +153.527618 11.280847 36.799999 +153.584290 11.423978 7.400000 +154.272141 11.066778 36.799999 +154.300156 11.218148 7.400000 +154.999557 11.000000 36.799999 +155.727859 11.066778 36.799999 +155.000000 11.153939 7.400000 +155.699844 11.218148 7.400000 +156.472382 11.280847 36.799999 +156.597595 11.332890 36.799999 +156.650330 11.497053 12.400000 +156.415710 11.423978 7.400000 +157.119751 11.759490 12.400000 +157.104599 11.780865 7.400000 +157.208481 11.819293 12.400000 +158.933228 14.272148 36.799999 +158.576019 13.584286 7.400000 +158.719147 13.527621 36.799999 +158.219131 12.895398 7.400000 +158.347977 12.811161 36.799999 +157.719574 12.280424 7.400000 +13.026180 15.000000 38.599998 +13.000000 15.000000 35.599998 +7.000000 15.000000 35.599998 +6.973819 15.000000 38.599998 +7.050084 14.454111 35.599998 +7.024340 14.449347 38.599998 +7.210635 13.895716 35.599998 +7.186293 13.886079 38.599998 +7.489014 13.358371 35.599998 +7.467101 13.344045 38.599998 +7.878680 12.878679 35.599998 +7.860167 12.860168 38.599998 +8.358371 12.489014 35.599998 +8.895716 12.210635 35.599998 +8.344045 12.467100 38.599998 +8.886079 12.186293 38.599998 +9.454111 12.050084 35.599998 +9.449347 12.024341 38.599998 +10.000000 12.000000 35.599998 +10.000000 11.973820 38.599998 +10.545889 12.050084 35.599998 +10.550653 12.024341 38.599998 +11.104284 12.210635 35.599998 +11.113921 12.186293 38.599998 +11.641629 12.489014 35.599998 +11.655955 12.467100 38.599998 +12.121321 12.878679 35.599998 +12.139832 12.860168 38.599998 +12.510986 13.358371 35.599998 +12.532900 13.344045 38.599998 +12.789365 13.895716 35.599998 +12.813707 13.886079 38.599998 +12.949916 14.454111 35.599998 +12.975659 14.449347 38.599998 +8.500000 15.000000 7.400000 +8.500000 15.000000 9.900000 +11.500000 15.000000 9.900000 +11.500000 15.000000 7.400000 +11.474958 14.727056 9.900000 +11.474958 14.727056 7.400000 +11.394683 14.447858 9.900000 +11.255493 14.179185 9.900000 +11.394683 14.447858 7.400000 +11.060660 13.939340 9.900000 +11.255493 14.179185 7.400000 +10.820815 13.744507 9.900000 +11.060660 13.939340 7.400000 +10.820815 13.744507 7.400000 +10.552142 13.605317 9.900000 +10.552142 13.605317 7.400000 +10.272944 13.525042 9.900000 +10.272944 13.525042 7.400000 +10.000000 13.500000 9.900000 +10.000000 13.500000 7.400000 +9.727056 13.525042 9.900000 +9.727056 13.525042 7.400000 +9.447858 13.605317 9.900000 +9.179185 13.744507 9.900000 +9.447858 13.605317 7.400000 +9.179185 13.744507 7.400000 +8.939340 13.939340 9.900000 +8.939340 13.939340 7.400000 +8.744507 14.179185 9.900000 +8.744507 14.179185 7.400000 +8.605317 14.447858 9.900000 +8.605317 14.447858 7.400000 +8.525042 14.727056 9.900000 +8.525042 14.727056 7.400000 +8.527621 11.280847 36.799999 +8.402408 11.332890 36.799999 +13.781852 14.300159 7.400000 +13.846061 15.000000 7.400000 +14.000000 15.000000 36.799999 +6.000000 15.000000 36.799999 +6.153939 15.000000 7.400000 +6.066779 14.272148 36.799999 +6.280847 13.527621 36.799999 +6.218148 14.300159 7.400000 +6.423978 13.584286 7.400000 +6.652018 12.811161 36.799999 +6.780865 12.895398 7.400000 +7.171573 12.171573 36.799999 +7.622985 11.782889 36.799999 +7.791527 11.819293 12.400000 +7.280425 12.280424 7.400000 +7.880249 11.759490 12.400000 +7.895398 11.780865 7.400000 +8.349664 11.497053 12.400000 +13.933222 14.272148 36.799999 +13.576022 13.584286 7.400000 +13.719153 13.527621 36.799999 +13.219135 12.895398 7.400000 +13.347982 12.811161 36.799999 +12.719576 12.280424 7.400000 +12.828427 12.171573 36.799999 +12.104602 11.780865 7.400000 +12.188839 11.652018 36.799999 +11.415714 11.423978 7.400000 +10.699841 11.218148 7.400000 +11.472379 11.280847 36.799999 +10.727852 11.066778 36.799999 +10.000000 11.153939 7.400000 +9.999892 11.000000 36.799999 +9.300159 11.218148 7.400000 +9.272148 11.066778 36.799999 +8.584286 11.423978 7.400000 +1.394945 17.848242 0.000000 +12.151758 28.605055 0.000000 +15.000000 28.900000 0.000000 +15.000000 28.900000 2.300000 +12.151758 28.605055 2.300000 +9.479235 27.756613 0.000000 +9.479235 27.756613 2.300000 +7.123779 26.453171 0.000000 +7.123779 26.453171 2.300000 +5.171216 24.828785 0.000000 +5.171255 24.828823 2.300000 +3.546828 22.876221 0.000000 +2.243388 20.520765 0.000000 +3.546828 22.876221 2.300000 +1.107286 15.450000 1.150000 +1.100000 15.000000 1.150000 +1.100000 15.000000 0.000000 +1.394945 17.848242 2.300000 +1.107286 15.450000 2.300000 +2.243388 20.520765 2.300000 +5.442446 5.442446 39.807693 +6.480624 4.506483 39.807693 +7.603682 3.686815 39.807693 +10.024676 2.432589 39.807693 +12.540510 1.709229 39.807693 +15.000000 1.460649 39.834995 +15.000000 1.483578 39.807693 +15.000000 1.390881 39.898933 +15.000000 1.308729 39.949360 +15.000000 1.218427 39.983082 +15.000000 1.125095 39.998730 +15.000000 1.089464 40.000000 +12.149599 1.384633 40.000000 +9.475050 2.233719 40.000000 +7.117809 3.538147 40.000000 +5.163766 5.163766 40.000000 +3.538147 7.117809 40.000000 +2.233719 9.475050 40.000000 +1.384633 12.149599 40.000000 +1.089464 15.000000 40.000000 +1.125095 15.000000 39.998730 +1.218427 15.000000 39.983082 +1.308729 15.000000 39.949360 +1.390881 15.000000 39.898933 +1.460649 15.000000 39.834995 +1.483578 15.000000 39.807693 +1.709229 12.540510 39.807693 +2.432589 10.024676 39.807693 +3.686815 7.603682 39.807693 +4.506483 6.480624 39.807693 +5.424883 5.424883 39.837097 +7.327054 3.842419 39.837097 +9.621718 2.572619 39.837097 +12.225267 1.746073 39.837097 +12.210533 1.675694 39.901958 +12.194529 1.599245 39.949360 +12.177024 1.515630 39.981754 +12.157481 1.422280 39.998520 +9.490327 2.269018 39.998520 +7.139604 3.569839 39.998520 +5.190963 5.190963 39.998520 +3.569839 7.139604 39.998520 +2.269018 9.490327 39.998520 +1.422280 12.157481 39.998520 +1.515630 12.177024 39.981754 +1.599245 12.194529 39.949360 +1.675694 12.210533 39.901958 +1.746073 12.225267 39.837097 +2.572619 9.621718 39.837097 +3.842419 7.327054 39.837097 +9.593159 2.506628 39.901958 +9.562138 2.434947 39.949360 +9.528208 2.356547 39.981754 +7.286310 3.783171 39.901958 +7.242052 3.718814 39.949360 +7.193646 3.648425 39.981754 +5.374039 5.374039 39.901958 +5.318809 5.318809 39.949360 +5.258403 5.258403 39.981754 +3.783171 7.286310 39.901958 +3.718814 7.242052 39.949360 +3.648425 7.193646 39.981754 +2.506628 9.593159 39.901958 +2.434947 9.562138 39.949360 +2.356547 9.528208 39.981754 +159.056503 7.647298 38.966667 +159.763916 8.616561 38.966667 +160.846390 10.706016 38.966667 +161.470688 12.877322 38.966667 +161.665710 15.000000 38.966774 +161.665436 15.000000 38.966667 +150.000000 3.155360 39.000000 +150.000000 3.155060 39.000000 +158.248703 6.751292 38.966667 +157.352707 5.943503 38.966667 +156.383438 5.236084 38.966667 +154.293991 4.153615 38.966667 +150.000000 3.246347 38.991596 +161.753647 15.000000 38.991596 +161.647186 12.844659 39.000000 +161.844940 15.000000 39.000000 +161.844635 15.000000 39.000000 +152.122681 3.529316 38.966667 +150.000000 3.334566 38.966667 +150.000000 3.334286 38.966774 +152.155334 3.352807 39.000000 +154.360062 3.986713 39.000000 +156.481674 5.085838 39.000000 +157.465851 5.804143 39.000000 +158.375641 6.624362 39.000000 +159.195862 7.534157 39.000000 +159.914154 8.518333 39.000000 +161.013290 10.639940 39.000000 +161.504257 12.591565 38.991596 +161.418182 12.609583 38.966778 +159.612198 8.389797 38.966778 +158.248917 6.751087 38.966778 +160.706131 10.366638 38.966778 +156.610199 5.387802 38.966778 +154.633362 4.293876 38.966778 +152.390411 3.581811 38.966778 +152.408432 3.495749 38.991596 +152.427078 3.406703 39.000000 +154.704422 4.129688 39.000000 +156.711578 5.240390 39.000000 +158.375412 6.624582 39.000000 +159.759613 8.288424 39.000000 +160.870316 10.295582 39.000000 +161.593292 12.572924 39.000000 +154.668289 4.213181 38.991596 +156.660019 5.315352 38.991596 +158.311081 6.688912 38.991596 +159.684647 8.339973 38.991596 +160.786819 10.331716 38.991596 +7.647298 24.056498 38.966667 +8.616561 24.763916 38.966667 +10.706016 25.846384 38.966667 +12.877322 26.470684 38.966667 +6.751292 23.248707 38.966667 +5.943503 22.352701 38.966667 +5.236084 21.383440 38.966667 +4.153615 19.293985 38.966667 +15.000000 26.662243 38.965439 +15.000000 26.665434 38.966667 +15.000000 25.695032 38.692444 +13.236619 24.529089 38.599998 +15.000000 24.690874 38.599998 +15.000000 24.694292 38.600002 +5.305707 15.000000 38.600002 +5.309126 15.000000 38.599998 +4.304968 15.000000 38.692444 +3.529316 17.122679 38.966667 +3.334566 15.000000 38.966667 +3.337757 15.000000 38.965439 +5.470912 16.763382 38.599998 +5.989539 18.567160 38.599998 +6.888782 20.302940 38.599998 +7.476459 21.108139 38.599998 +8.147517 21.852482 38.599998 +8.891860 22.523540 38.599998 +9.697060 23.111217 38.599998 +11.432840 24.010462 38.599998 +12.808487 25.468094 38.692444 +12.610296 26.414782 38.965439 +8.391769 24.609329 38.965439 +6.753549 23.246452 38.965439 +10.368021 25.702929 38.965439 +5.390671 21.608231 38.965439 +4.297071 19.631979 38.965439 +3.585218 17.389704 38.965439 +4.531907 17.191513 38.692444 +5.511411 16.986452 38.600002 +6.103142 18.850353 38.600002 +7.012202 20.493122 38.600002 +8.145100 21.854900 38.600002 +9.506879 22.987799 38.600002 +11.149647 23.896858 38.600002 +13.013548 24.488588 38.600002 +5.184721 19.247824 38.692444 +6.187623 21.060175 38.692444 +7.437470 22.562531 38.692444 +8.939825 23.812378 38.692444 +10.752175 24.815279 38.692444 +12.841710 26.663128 39.000000 +15.000000 26.861145 39.000000 +5.791562 22.476057 39.000000 +5.072274 21.490534 39.000000 +3.971646 19.366024 39.000000 +3.336872 17.158291 39.000000 +6.612904 23.387096 39.000000 +7.523942 24.208439 39.000000 +8.509465 24.927725 39.000000 +10.633975 26.028355 39.000000 +2.977309 15.000000 39.006222 +3.138854 15.000000 39.000000 +2.576737 15.000000 39.076630 +2.217943 15.000000 39.212696 +1.889898 15.000000 39.411774 +1.587895 15.000000 39.684189 +1.483578 15.000000 39.807693 +1.709229 17.459490 39.807693 +2.432589 19.975323 39.807693 +3.686815 22.396318 39.807693 +4.506483 23.519375 39.807693 +5.442446 24.557554 39.807693 +6.480624 25.493517 39.807693 +7.603682 26.313185 39.807693 +10.024676 27.567411 39.807693 +12.540510 28.290771 39.807693 +15.000000 28.412106 39.684189 +15.000000 28.516422 39.807693 +15.000000 28.110102 39.411774 +15.000000 27.782057 39.212696 +15.000000 27.423262 39.076630 +15.000000 27.022690 39.006222 +6.498674 23.501326 39.006222 +5.093673 21.812471 39.006222 +3.966273 19.775141 39.006222 +3.232420 17.463564 39.006222 +8.187528 24.906326 39.006222 +10.224859 26.033726 39.006222 +12.536437 26.767580 39.006222 +2.840348 17.545645 39.076630 +2.489167 17.619165 39.212696 +2.168082 17.686384 39.411774 +1.872487 17.748268 39.684189 +2.691149 20.326984 39.684189 +3.948838 22.599762 39.684189 +5.516210 24.483791 39.684189 +7.400238 26.051161 39.684189 +9.673016 27.308851 39.684189 +12.251733 28.127512 39.684189 +12.313616 27.831919 39.411774 +12.380836 27.510834 39.212696 +12.454356 27.159653 39.076630 +2.968310 20.207035 39.411774 +3.269372 20.076744 39.212696 +3.598652 19.934238 39.076630 +4.197680 22.428637 39.411774 +4.467979 22.242756 39.212696 +5.729758 24.270243 39.411774 +5.961721 24.038279 39.212696 +4.763615 22.039450 39.076630 +6.215427 23.784573 39.076630 +7.571362 25.802320 39.411774 +7.757245 25.532021 39.212696 +9.792964 27.031691 39.411774 +9.923257 26.730629 39.212696 +7.960550 25.236385 39.076630 +10.065762 26.401348 39.076630 +7.650000 15.000000 9.900000 +7.425719 15.000000 35.599998 +12.574281 15.000000 35.599998 +12.350000 15.000000 9.900000 +12.531303 14.531576 35.599998 +12.310767 14.572387 9.900000 +12.393536 14.052421 35.599998 +12.154661 13.591329 35.599998 +12.185002 14.134977 9.900000 +11.820292 13.179708 35.599998 +11.966940 13.714057 9.900000 +11.661701 13.338299 9.900000 +11.408671 12.845339 35.599998 +11.285943 13.033060 9.900000 +10.947579 12.606464 35.599998 +10.468424 12.468697 35.599998 +10.865023 12.814998 9.900000 +10.427613 12.689233 9.900000 +10.000000 12.425719 35.599998 +9.531576 12.468697 35.599998 +10.000000 12.650000 9.900000 +9.572387 12.689233 9.900000 +9.052421 12.606464 35.599998 +9.134977 12.814998 9.900000 +8.591329 12.845339 35.599998 +8.179708 13.179708 35.599998 +8.714057 13.033060 9.900000 +8.338299 13.338299 9.900000 +7.845339 13.591329 35.599998 +7.606464 14.052421 35.599998 +8.033060 13.714057 9.900000 +7.814998 14.134977 9.900000 +7.468696 14.531576 35.599998 +7.689232 14.572387 9.900000 +152.649994 15.000000 9.900000 +152.425720 15.000000 35.599998 +157.574280 15.000000 35.599998 +157.350006 15.000000 9.900000 +157.531311 14.531576 35.599998 +157.310760 14.572387 9.900000 +157.393539 14.052421 35.599998 +157.184998 14.134977 9.900000 +157.154663 13.591329 35.599998 +156.966934 13.714057 9.900000 +156.820297 13.179708 35.599998 +156.661697 13.338299 9.900000 +156.408676 12.845339 35.599998 +155.947586 12.606464 35.599998 +156.285950 13.033060 9.900000 +155.865021 12.814998 9.900000 +155.468430 12.468697 35.599998 +155.000000 12.425719 35.599998 +155.427612 12.689233 9.900000 +155.000000 12.650000 9.900000 +154.531570 12.468697 35.599998 +154.572388 12.689233 9.900000 +154.052414 12.606464 35.599998 +154.134979 12.814998 9.900000 +153.591324 12.845339 35.599998 +153.179703 13.179708 35.599998 +153.714050 13.033060 9.900000 +153.338303 13.338299 9.900000 +152.845337 13.591329 35.599998 +153.033066 13.714057 9.900000 +152.606461 14.052421 35.599998 +152.815002 14.134977 9.900000 +152.468689 14.531576 35.599998 +152.689240 14.572387 9.900000 +70.550003 28.596251 5.000000 +61.989784 28.900000 2.300000 +73.550003 28.596251 5.000000 +82.110214 28.900000 2.300000 +73.550003 28.488325 5.959337 +82.098511 28.145529 9.006416 +70.550003 28.488325 5.959337 +62.001492 28.145529 9.006416 +52.650002 28.488325 5.959337 +41.089787 28.900000 2.300000 +52.650002 28.596251 5.000000 +41.101490 28.145529 9.006416 +49.650002 28.596251 5.000000 +61.198509 28.145529 9.006416 +49.650002 28.488325 5.959337 +61.210213 28.900000 2.300000 +66.050003 1.511675 5.959337 +73.110214 1.100000 2.300000 +66.050003 1.403750 5.000000 +73.098511 1.854472 9.006416 +69.050003 1.403750 5.000000 +62.001492 1.854472 9.006416 +69.050003 1.511675 5.959337 +61.989784 1.100000 2.300000 +45.150002 1.511675 5.959337 +52.210213 1.100000 2.300000 +45.150002 1.403750 5.000000 +52.198509 1.854472 9.006416 +48.150002 1.403750 5.000000 +41.101490 1.854472 9.006416 +48.150002 1.511675 5.959337 +41.089787 1.100000 2.300000 +91.449997 28.596251 5.000000 +82.889786 28.900000 2.300000 +94.449997 28.596251 5.000000 +103.010216 28.900000 2.300000 +94.449997 28.488325 5.959337 +102.998512 28.145529 9.006416 +91.449997 28.488325 5.959337 +82.901489 28.145529 9.006416 +112.349998 28.596251 5.000000 +103.789787 28.900000 2.300000 +115.349998 28.596251 5.000000 +123.910217 28.900000 2.300000 +115.349998 28.488325 5.959337 +123.898506 28.145529 9.006416 +112.349998 28.488325 5.959337 +103.801491 28.145529 9.006416 +40.250000 3.600000 36.799999 +41.150002 3.600000 36.799999 +41.137783 3.587783 29.799999 +40.262218 3.587783 29.799999 +82.050003 3.600000 36.799999 +82.949997 3.600000 36.799999 +82.937782 3.587783 29.799999 +82.062218 3.587783 29.799999 +123.849998 3.600000 36.799999 +124.750000 3.600000 36.799999 +124.737785 3.587783 29.799999 +123.862221 3.587783 29.799999 +95.949997 1.511675 5.959337 +103.010216 1.100000 2.300000 +95.949997 1.403750 5.000000 +102.998512 1.854472 9.006416 +98.949997 1.403750 5.000000 +91.901489 1.854472 9.006416 +98.949997 1.511675 5.959337 +91.889786 1.100000 2.300000 +116.849998 1.511675 5.959337 +123.910217 1.100000 2.300000 +116.849998 1.403750 5.000000 +123.898506 1.854472 9.006416 +119.849998 1.403750 5.000000 +112.801491 1.854472 9.006416 +119.849998 1.511675 5.959337 +112.789787 1.100000 2.300000 +95.395554 -5.983620 13.392825 +95.395271 -6.000000 13.212572 +95.500000 0.000000 13.047635 +95.500000 0.000000 14.594810 +95.499916 -0.004914 14.540733 +95.499641 -0.020642 14.485450 +95.499161 -0.047888 14.432207 +95.498497 -0.086025 14.384537 +95.497681 -0.133022 14.345573 +95.496758 -0.185782 14.317403 +95.395271 -6.000000 13.152365 +95.495796 -0.240782 14.300712 +95.494858 -0.294764 14.294855 +95.412422 -5.017452 14.212420 +95.409279 -5.197392 14.192897 +95.406082 -5.380726 14.137260 +95.403008 -5.556592 14.043358 +95.400276 -5.713251 13.913482 +95.398056 -5.840373 13.754580 +95.396469 -5.931192 13.577102 +69.604446 -5.983620 8.607175 +69.604729 -6.000000 8.787428 +69.500000 0.000000 8.952365 +69.500000 0.000000 7.405191 +69.500084 -0.004914 7.459267 +69.500359 -0.020642 7.514550 +69.500839 -0.047888 7.567793 +69.501503 -0.086025 7.615464 +69.502319 -0.133022 7.654427 +69.503242 -0.185782 7.682597 +69.604729 -6.000000 8.847635 +69.504204 -0.240782 7.699288 +69.505142 -0.294764 7.705145 +69.587578 -5.017452 7.787580 +69.590721 -5.197392 7.807103 +69.593918 -5.380726 7.862740 +69.596992 -5.556592 7.956642 +69.599724 -5.713251 8.086518 +69.601944 -5.840373 8.245420 +69.603531 -5.931192 8.422898 +70.510468 0.000000 13.026575 +70.454636 0.000000 13.042627 +15.000000 0.000000 0.000000 +95.500000 0.000000 7.405191 +150.000000 0.000000 0.000000 +95.500000 0.000000 8.952365 +15.000000 0.000000 40.000000 +69.500000 0.000000 7.405191 +69.500000 0.000000 8.952365 +70.400047 0.000000 8.952365 +70.454636 0.000000 8.957373 +70.510468 0.000000 8.973425 +70.564194 0.000000 9.001256 +70.612152 0.000000 9.040215 +70.651108 0.000000 9.088174 +70.678940 0.000000 9.141899 +70.694992 0.000000 9.197733 +94.599998 0.000000 8.952365 +94.545410 0.000000 8.957375 +94.489571 0.000000 8.973432 +94.435837 0.000000 9.001274 +94.387871 0.000000 9.040247 +94.348900 0.000000 9.088223 +94.321060 0.000000 9.141966 +94.305008 0.000000 9.197814 +94.300003 0.000000 9.252411 +94.348900 0.000000 12.911777 +94.321060 0.000000 12.858034 +94.387871 0.000000 12.959753 +94.435837 0.000000 12.998726 +94.305008 0.000000 12.802186 +94.489571 0.000000 13.026568 +94.545410 0.000000 13.042625 +94.599998 0.000000 13.047635 +95.500000 0.000000 13.047635 +94.300003 0.000000 12.747589 +95.500000 0.000000 14.594810 +150.000000 0.000000 40.000000 +69.500000 0.000000 14.594810 +69.500000 0.000000 13.047635 +70.699997 0.000000 9.252319 +70.400047 0.000000 13.047635 +70.699997 0.000000 12.747681 +70.694992 0.000000 12.802267 +70.678940 0.000000 12.858101 +70.651108 0.000000 12.911826 +70.612152 0.000000 12.959785 +70.564194 0.000000 12.998744 +52.198509 1.854472 9.006416 +41.101490 1.854472 9.006416 +41.150002 2.000000 36.799999 +52.150002 2.000000 36.799999 +103.801491 1.854472 9.006416 +103.849998 2.000000 36.799999 +111.949997 2.000000 36.799999 +111.998512 1.854472 9.006416 +103.789787 1.100000 2.300000 +103.801491 1.854472 9.006416 +111.998512 1.854472 9.006416 +112.010216 1.100000 2.300000 +62.001492 1.854472 9.006416 +62.049999 2.000000 36.799999 +73.050003 2.000000 36.799999 +73.098511 1.854472 9.006416 +91.098511 1.854472 9.006416 +82.901489 1.854472 9.006416 +82.949997 2.000000 36.799999 +91.050003 2.000000 36.799999 +82.889786 1.100000 2.300000 +82.901489 1.854472 9.006416 +91.098511 1.854472 9.006416 +91.110214 1.100000 2.300000 +5.278571 6.177763 12.400000 +5.435990 6.194904 36.799999 +2.176106 12.109903 9.006416 +1.860604 14.598509 9.006416 +2.007791 14.550000 36.799999 +2.318074 12.141898 36.799999 +3.017055 9.595007 9.006416 +3.149713 9.654843 36.799999 +4.283669 7.386514 9.006416 +4.402305 7.470800 36.799999 +4.815655 6.920451 36.799999 +5.847947 5.563643 9.006416 +4.833066 6.695090 12.400000 +12.531078 2.236598 36.799999 +15.000000 2.000000 36.799999 +15.000000 1.854472 9.006416 +12.503440 2.093719 9.006416 +10.019753 2.991789 36.799999 +7.798424 4.177001 36.799999 +9.964002 2.857363 9.006416 +7.717805 4.055844 9.006416 +5.949350 5.668025 36.799999 +1.107286 14.550000 2.300000 +1.106549 14.550000 2.293451 +15.000000 1.854472 9.006416 +15.000000 1.100000 2.300000 +12.487185 2.096874 9.006416 +12.514922 1.323949 2.300000 +9.948710 2.863716 9.006416 +9.975604 2.039852 2.300000 +7.704026 4.065025 9.006416 +7.528227 3.278967 2.300000 +5.836062 5.575184 9.006416 +5.331624 5.013384 2.300000 +4.274087 7.400019 9.006416 +3.010257 9.610106 9.006416 +3.527003 7.152686 2.300000 +2.172476 12.126060 9.006416 +2.209305 9.558664 2.300000 +1.860604 14.598509 9.006416 +1.411569 12.073475 2.300000 +1.104913 14.610223 2.295087 +160.166931 6.695090 12.400000 +160.184341 6.920451 36.799999 +152.347778 2.065826 9.006416 +150.000000 1.854472 9.006416 +150.000000 2.000000 36.799999 +154.746658 2.741363 9.006416 +152.445587 2.232107 36.799999 +157.058884 3.910493 9.006416 +154.958298 2.982706 36.799999 +159.134811 5.546947 9.006416 +157.181778 4.163857 36.799999 +159.034058 5.651962 36.799999 +159.564011 6.194904 36.799999 +160.841370 7.565642 9.006416 +159.721436 6.177763 12.400000 +162.992203 14.550000 36.799999 +163.137817 14.550000 9.006416 +162.676682 12.118724 36.799999 +162.846222 12.210834 9.006416 +161.840500 9.633193 36.799999 +162.088959 9.836489 9.006416 +160.583923 7.451442 36.799999 +163.137817 14.550000 9.006416 +163.892715 14.550000 2.300000 +152.485077 1.323949 2.300000 +150.000000 1.100000 2.300000 +150.000000 1.854472 9.006416 +155.024399 2.039852 2.300000 +152.484879 2.091464 9.006416 +157.471771 3.278967 2.300000 +155.025009 2.852810 9.006416 +159.668381 5.013384 2.300000 +157.272293 4.049257 9.006416 +159.143509 5.555366 9.006416 +161.472992 7.152686 2.300000 +160.709442 7.376818 9.006416 +162.790695 9.558664 2.300000 +161.978043 9.584163 9.006416 +163.588425 12.073475 2.300000 +162.821274 12.098297 9.006416 +124.750000 28.000000 36.799999 +124.701492 28.145529 9.006416 +144.798508 28.145529 9.006416 +144.750000 28.000000 36.799999 +124.701492 28.145529 9.006416 +124.689789 28.900000 2.300000 +144.810211 28.900000 2.300000 +144.798508 28.145529 9.006416 +103.849998 28.000000 36.799999 +103.801491 28.145529 9.006416 +123.898506 28.145529 9.006416 +123.849998 28.000000 36.799999 +82.949997 28.000000 36.799999 +82.901489 28.145529 9.006416 +102.998512 28.145529 9.006416 +102.949997 28.000000 36.799999 +62.049999 28.000000 36.799999 +62.001492 28.145529 9.006416 +82.098511 28.145529 9.006416 +82.050003 28.000000 36.799999 +41.150002 28.000000 36.799999 +41.101490 28.145529 9.006416 +61.198509 28.145529 9.006416 +61.150002 28.000000 36.799999 +40.250000 28.000000 36.799999 +20.250000 28.000000 36.799999 +20.201490 28.145529 9.006416 +40.298508 28.145529 9.006416 +20.201490 28.145529 9.006416 +20.189787 28.900000 2.300000 +40.310215 28.900000 2.300000 +40.298508 28.145529 9.006416 +19.350000 28.000000 36.799999 +15.000000 28.000000 36.799999 +15.000000 28.145529 9.006416 +19.398508 28.145529 9.006416 +15.000000 28.900000 2.300000 +19.410213 28.900000 2.300000 +19.398508 28.145529 9.006416 +15.000000 28.145529 9.006416 +15.000000 1.854472 9.006416 +15.000000 2.000000 36.799999 +19.350000 2.000000 36.799999 +19.398508 1.854472 9.006416 +15.000000 1.100000 2.300000 +15.000000 1.854472 9.006416 +19.398508 1.854472 9.006416 +19.410213 1.100000 2.300000 +40.250000 2.000000 36.799999 +40.298508 1.854472 9.006416 +20.201490 1.854472 9.006416 +20.250000 2.000000 36.799999 +40.298508 1.854472 9.006416 +40.310215 1.100000 2.300000 +20.189787 1.100000 2.300000 +20.201490 1.854472 9.006416 +53.049999 2.000000 36.799999 +61.150002 2.000000 36.799999 +61.198509 1.854472 9.006416 +53.001492 1.854472 9.006416 +61.198509 1.854472 9.006416 +61.210213 1.100000 2.300000 +52.989784 1.100000 2.300000 +53.001492 1.854472 9.006416 +82.050003 2.000000 36.799999 +82.098511 1.854472 9.006416 +73.901489 1.854472 9.006416 +73.949997 2.000000 36.799999 +82.098511 1.854472 9.006416 +82.110214 1.100000 2.300000 +73.889786 1.100000 2.300000 +73.901489 1.854472 9.006416 +91.949997 2.000000 36.799999 +102.949997 2.000000 36.799999 +102.998512 1.854472 9.006416 +91.901489 1.854472 9.006416 +112.849998 2.000000 36.799999 +123.849998 2.000000 36.799999 +123.898506 1.854472 9.006416 +112.801491 1.854472 9.006416 +140.970947 1.937168 24.799999 +144.798508 1.854472 9.006416 +124.701492 1.854472 9.006416 +141.750000 2.000000 36.799999 +144.750000 2.000000 36.799999 +141.729050 1.937168 24.799999 +124.750000 2.000000 36.799999 +140.949997 2.000000 36.799999 +144.798508 1.854472 9.006416 +144.810211 1.100000 2.300000 +124.689789 1.100000 2.300000 +124.701492 1.854472 9.006416 +13.881664 15.965755 36.799999 +80.500000 5.375450 36.799999 +82.949997 3.600000 36.799999 +91.050003 2.000000 36.799999 +82.949997 2.000000 36.799999 +84.500000 5.375450 36.799999 +85.432480 5.461002 36.799999 +91.050003 2.500000 36.799999 +86.386322 5.735253 36.799999 +87.304207 6.210774 36.799999 +102.949997 3.600000 36.799999 +102.949997 2.000000 36.799999 +91.949997 2.000000 36.799999 +111.949997 2.500000 36.799999 +111.949997 2.000000 36.799999 +103.849998 2.000000 36.799999 +140.949997 4.000000 36.799999 +140.949997 2.000000 36.799999 +124.750000 2.000000 36.799999 +144.750000 2.000000 36.799999 +141.750000 2.000000 36.799999 +144.750000 3.600000 36.799999 +145.649994 26.400000 36.799999 +145.649994 28.000000 36.799999 +124.750000 28.000000 36.799999 +144.750000 28.000000 36.799999 +124.750000 26.400000 36.799999 +62.049999 28.000000 36.799999 +82.050003 28.000000 36.799999 +62.049999 26.400000 36.799999 +41.150002 28.000000 36.799999 +61.150002 28.000000 36.799999 +41.150002 26.400000 36.799999 +19.350000 3.600000 36.799999 +19.350000 2.000000 36.799999 +40.250000 3.600000 36.799999 +40.250000 2.000000 36.799999 +20.250000 2.000000 36.799999 +52.150002 2.500000 36.799999 +52.150002 2.000000 36.799999 +41.150002 2.000000 36.799999 +61.150002 2.000000 36.799999 +53.049999 2.000000 36.799999 +61.150002 3.600000 36.799999 +73.050003 2.500000 36.799999 +73.050003 2.000000 36.799999 +62.049999 2.000000 36.799999 +123.849998 2.000000 36.799999 +112.849998 2.000000 36.799999 +123.849998 3.600000 36.799999 +150.000000 2.000000 36.799999 +145.649994 2.000000 36.799999 +103.849998 28.000000 36.799999 +123.849998 28.000000 36.799999 +103.849998 26.400000 36.799999 +82.949997 28.000000 36.799999 +102.949997 28.000000 36.799999 +82.949997 26.400000 36.799999 +20.250000 28.000000 36.799999 +40.250000 28.000000 36.799999 +20.250000 26.400000 36.799999 +15.000000 28.000000 36.799999 +19.350000 28.000000 36.799999 +82.050003 2.000000 36.799999 +73.949997 2.000000 36.799999 +82.050003 3.600000 36.799999 +79.567520 5.461002 36.799999 +78.613678 5.735253 36.799999 +77.695793 6.210774 36.799999 +76.876396 6.876396 36.799999 +156.597595 11.332890 36.799999 +159.564011 6.194904 36.799999 +155.664948 11.055656 36.799999 +157.577225 25.563416 36.799999 +159.564011 23.805096 36.799999 +156.597595 18.667110 36.799999 +8.402408 18.667110 36.799999 +5.435990 23.805096 36.799999 +9.335054 18.944344 36.799999 +7.422781 4.436584 36.799999 +5.435990 6.194904 36.799999 +8.402408 11.332890 36.799999 +9.335054 11.055656 36.799999 +9.778231 3.094828 36.799999 +12.360734 2.270732 36.799999 +10.337813 11.014290 36.799999 +15.000000 2.000000 36.799999 +11.319305 11.223834 36.799999 +12.191989 11.654079 36.799999 +7.422781 25.563416 36.799999 +10.337813 18.985710 36.799999 +9.778231 26.905172 36.799999 +11.319305 18.776167 36.799999 +12.360734 27.729269 36.799999 +12.191989 18.345921 36.799999 +12.934977 17.717703 36.799999 +155.664948 18.944344 36.799999 +155.221771 26.905172 36.799999 +152.639267 27.729269 36.799999 +154.662186 18.985710 36.799999 +150.000000 28.000000 36.799999 +153.680695 18.776167 36.799999 +152.808014 18.345921 36.799999 +157.577225 4.436584 36.799999 +154.662186 11.014290 36.799999 +155.221771 3.094828 36.799999 +153.680695 11.223834 36.799999 +152.639267 2.270732 36.799999 +152.808014 11.654079 36.799999 +152.065018 12.282296 36.799999 +88.123604 6.876396 36.799999 +76.210777 7.695796 36.799999 +151.480911 13.098416 36.799999 +152.065018 17.717703 36.799999 +13.519088 16.901585 36.799999 +12.934977 12.282296 36.799999 +91.949997 2.500000 36.799999 +73.949997 2.500000 36.799999 +75.735252 8.613680 36.799999 +75.460999 9.567521 36.799999 +75.375450 10.500000 36.799999 +88.789223 7.695796 36.799999 +89.264748 8.613680 36.799999 +89.539001 9.567521 36.799999 +20.250000 3.600000 36.799999 +19.350000 26.400000 36.799999 +144.750000 26.400000 36.799999 +145.649994 3.600000 36.799999 +151.118332 14.034245 36.799999 +89.624550 10.500000 36.799999 +75.460999 11.432479 36.799999 +151.480911 16.901585 36.799999 +151.118332 15.965755 36.799999 +151.000000 15.000000 36.799999 +141.750000 4.000000 36.799999 +124.750000 3.600000 36.799999 +123.849998 26.400000 36.799999 +112.849998 2.500000 36.799999 +103.849998 3.600000 36.799999 +102.949997 26.400000 36.799999 +89.539001 11.432479 36.799999 +89.264748 12.386320 36.799999 +88.789223 13.304204 36.799999 +88.123604 14.123605 36.799999 +87.304207 14.789226 36.799999 +86.386322 15.264747 36.799999 +85.432480 15.538998 36.799999 +84.500000 15.624551 36.799999 +82.050003 26.400000 36.799999 +80.500000 15.624551 36.799999 +79.567520 15.538998 36.799999 +78.613678 15.264747 36.799999 +77.695793 14.789226 36.799999 +76.876396 14.123605 36.799999 +76.210777 13.304204 36.799999 +75.735252 12.386320 36.799999 +62.049999 3.600000 36.799999 +61.150002 26.400000 36.799999 +53.049999 2.500000 36.799999 +40.250000 26.400000 36.799999 +41.150002 3.600000 36.799999 +13.519088 13.098416 36.799999 +13.881664 14.034245 36.799999 +14.000000 15.000000 36.799999 +80.500000 6.400000 38.599998 +15.000000 5.309126 38.599998 +145.300003 5.700000 38.599998 +5.309126 15.000000 38.599998 +7.024340 14.449347 38.599998 +7.186293 13.886079 38.599998 +5.470912 16.763382 38.599998 +6.973819 15.000000 38.599998 +7.024340 15.550653 38.599998 +159.690872 15.000000 38.599998 +157.975662 15.550653 38.599998 +157.813705 16.113920 38.599998 +159.529083 13.236619 38.599998 +158.026184 15.000000 38.599998 +157.975662 14.449347 38.599998 +43.000000 15.000000 38.599998 +76.400002 10.500000 38.599998 +159.010468 11.432840 38.599998 +157.813705 13.886079 38.599998 +157.532898 13.344045 38.599998 +159.529083 16.763382 38.599998 +157.532898 16.655956 38.599998 +157.139832 17.139833 38.599998 +5.989539 18.567160 38.599998 +7.186293 16.113920 38.599998 +7.467101 16.655956 38.599998 +5.470912 13.236619 38.599998 +7.467101 13.344045 38.599998 +7.860167 12.860168 38.599998 +145.300003 24.299999 38.599998 +37.210636 13.895716 38.599998 +37.489014 13.358371 38.599998 +150.000000 5.309126 38.599998 +151.763382 5.470912 38.599998 +153.567154 5.989539 38.599998 +76.468445 11.246049 38.599998 +5.989539 11.432840 38.599998 +8.344045 12.467100 38.599998 +8.886079 12.186293 38.599998 +6.888782 20.302940 38.599998 +7.860167 17.139833 38.599998 +8.344045 17.532900 38.599998 +159.010468 18.567160 38.599998 +156.655960 17.532900 38.599998 +156.113922 17.813707 38.599998 +158.111221 9.697060 38.599998 +157.139832 12.860168 38.599998 +156.655960 12.467100 38.599998 +42.949917 14.454111 38.599998 +42.949917 15.545889 38.599998 +76.468445 9.753951 38.599998 +6.888782 9.697060 38.599998 +9.449347 12.024341 38.599998 +8.147517 21.852482 38.599998 +8.886079 17.813707 38.599998 +158.111221 20.302940 38.599998 +155.550659 17.975660 38.599998 +156.852478 8.147517 38.599998 +156.113922 12.186293 38.599998 +155.550659 12.024341 38.599998 +155.302948 6.888782 38.599998 +155.000000 11.973820 38.599998 +155.000000 18.026180 38.599998 +156.852478 21.852482 38.599998 +154.449341 17.975660 38.599998 +9.449347 17.975660 38.599998 +9.697060 23.111217 38.599998 +10.000000 18.026180 38.599998 +10.000000 11.973820 38.599998 +8.147517 8.147517 38.599998 +10.550653 12.024341 38.599998 +9.697060 6.888782 38.599998 +11.113921 12.186293 38.599998 +11.432840 24.010462 38.599998 +10.550653 17.975660 38.599998 +155.302948 23.111217 38.599998 +153.886078 17.813707 38.599998 +37.050083 14.454111 38.599998 +153.567154 24.010462 38.599998 +153.344040 17.532900 38.599998 +151.763382 24.529089 38.599998 +152.860168 17.139833 38.599998 +13.236619 24.529089 38.599998 +11.113921 17.813707 38.599998 +15.000000 24.690874 38.599998 +11.655955 17.532900 38.599998 +11.432840 5.989539 38.599998 +11.655955 12.467100 38.599998 +13.236619 5.470912 38.599998 +12.139832 12.860168 38.599998 +12.532900 13.344045 38.599998 +12.813707 13.886079 38.599998 +12.975659 14.449347 38.599998 +13.026180 15.000000 38.599998 +37.000000 15.000000 38.599998 +12.975659 15.550653 38.599998 +37.050083 15.545889 38.599998 +12.813707 16.113920 38.599998 +37.878681 12.878679 38.599998 +42.789364 13.895716 38.599998 +76.687866 12.009189 38.599998 +42.789364 16.104284 38.599998 +76.687866 8.990811 38.599998 +154.449341 12.024341 38.599998 +37.210636 16.104284 38.599998 +12.532900 16.655956 38.599998 +12.139832 17.139833 38.599998 +37.489014 16.641630 38.599998 +152.467102 16.655956 38.599998 +42.510986 13.358371 38.599998 +38.358372 12.489014 38.599998 +42.510986 16.641630 38.599998 +77.068321 12.743560 38.599998 +37.878681 17.121321 38.599998 +77.068321 8.256440 38.599998 +153.886078 12.186293 38.599998 +42.121319 12.878679 38.599998 +42.121319 17.121321 38.599998 +77.600861 13.399137 38.599998 +77.600861 7.600862 38.599998 +38.358372 17.510986 38.599998 +152.186295 16.113920 38.599998 +38.895718 12.210635 38.599998 +41.641628 12.489014 38.599998 +41.641628 17.510986 38.599998 +78.256439 13.931682 38.599998 +39.454109 12.050084 38.599998 +38.895718 17.789366 38.599998 +78.256439 7.068318 38.599998 +153.344040 12.467100 38.599998 +152.024338 15.550653 38.599998 +41.104282 12.210635 38.599998 +41.104282 17.789366 38.599998 +78.990814 14.312132 38.599998 +39.454109 17.949917 38.599998 +40.000000 12.000000 38.599998 +78.990814 6.687868 38.599998 +151.973816 15.000000 38.599998 +152.860168 12.860168 38.599998 +152.467102 13.344045 38.599998 +152.186295 13.886079 38.599998 +152.024338 14.449347 38.599998 +150.000000 24.690874 38.599998 +104.699997 24.299999 38.599998 +40.000000 18.000000 38.599998 +40.545891 17.949917 38.599998 +79.753952 14.531552 38.599998 +80.500000 14.600000 38.599998 +84.500000 14.600000 38.599998 +85.246048 14.531552 38.599998 +86.009186 14.312132 38.599998 +104.699997 5.700000 38.599998 +86.743561 13.931682 38.599998 +87.399139 13.399137 38.599998 +87.931679 12.743560 38.599998 +88.312134 12.009189 38.599998 +88.531555 11.246049 38.599998 +88.599998 10.500000 38.599998 +88.531555 9.753951 38.599998 +88.312134 8.990811 38.599998 +87.931679 8.256440 38.599998 +87.399139 7.600862 38.599998 +86.743561 7.068318 38.599998 +86.009186 6.687868 38.599998 +40.545891 12.050084 38.599998 +79.753952 6.468448 38.599998 +85.246048 6.468448 38.599998 +84.500000 6.400000 38.599998 +152.689240 15.427613 9.900000 +152.468689 15.468424 35.599998 +152.425720 15.000000 35.599998 +152.649994 15.000000 9.900000 +157.350006 15.000000 9.900000 +157.574280 15.000000 35.599998 +157.310760 15.427613 9.900000 +157.531311 15.468424 35.599998 +157.184998 15.865023 9.900000 +157.393539 15.947579 35.599998 +156.966934 16.285942 9.900000 +157.154663 16.408672 35.599998 +156.661697 16.661701 9.900000 +156.820297 16.820292 35.599998 +156.285950 16.966940 9.900000 +155.865021 17.185003 9.900000 +156.408676 17.154661 35.599998 +155.947586 17.393536 35.599998 +155.427612 17.310768 9.900000 +155.468430 17.531303 35.599998 +155.000000 17.350000 9.900000 +154.572388 17.310768 9.900000 +155.000000 17.574280 35.599998 +154.134979 17.185003 9.900000 +154.531570 17.531303 35.599998 +154.052414 17.393536 35.599998 +153.714050 16.966940 9.900000 +153.591324 17.154661 35.599998 +153.338303 16.661701 9.900000 +153.179703 16.820292 35.599998 +153.033066 16.285942 9.900000 +152.845337 16.408672 35.599998 +152.815002 15.865023 9.900000 +152.606461 15.947579 35.599998 +156.500000 15.000000 7.400000 +158.576019 16.415714 7.400000 +156.474960 15.272944 7.400000 +158.219131 17.104601 7.400000 +156.394684 15.552142 7.400000 +157.719574 17.719576 7.400000 +156.255493 15.820815 7.400000 +157.104599 18.219135 7.400000 +156.060654 16.060659 7.400000 +156.415710 18.576021 7.400000 +155.820816 16.255493 7.400000 +155.699844 18.781853 7.400000 +155.552139 16.394682 7.400000 +155.000000 18.846060 7.400000 +155.272949 16.474958 7.400000 +154.300156 18.781853 7.400000 +155.000000 16.500000 7.400000 +153.584290 18.576021 7.400000 +154.727051 16.474958 7.400000 +152.895401 18.219135 7.400000 +154.447861 16.394682 7.400000 +152.280426 17.719576 7.400000 +154.179184 16.255493 7.400000 +151.780869 17.104601 7.400000 +153.939346 16.060659 7.400000 +151.423981 16.415714 7.400000 +153.744507 15.820815 7.400000 +151.218155 15.699841 7.400000 +153.605316 15.552142 7.400000 +151.153946 15.000000 7.400000 +153.525040 15.272944 7.400000 +151.218155 14.300159 7.400000 +153.500000 15.000000 7.400000 +151.423981 13.584286 7.400000 +153.525040 14.727056 7.400000 +151.780869 12.895398 7.400000 +153.605316 14.447858 7.400000 +152.280426 12.280424 7.400000 +153.744507 14.179185 7.400000 +152.895401 11.780865 7.400000 +153.939346 13.939340 7.400000 +153.584290 11.423978 7.400000 +154.179184 13.744507 7.400000 +154.300156 11.218148 7.400000 +154.447861 13.605317 7.400000 +155.000000 11.153939 7.400000 +154.727051 13.525042 7.400000 +155.699844 11.218148 7.400000 +155.000000 13.500000 7.400000 +156.415710 11.423978 7.400000 +155.272949 13.525042 7.400000 +157.104599 11.780865 7.400000 +155.552139 13.605317 7.400000 +157.719574 12.280424 7.400000 +155.820816 13.744507 7.400000 +158.219131 12.895398 7.400000 +156.060654 13.939340 7.400000 +158.576019 13.584286 7.400000 +156.255493 14.179185 7.400000 +158.781845 14.300159 7.400000 +156.394684 14.447858 7.400000 +158.846054 15.000000 7.400000 +156.474960 14.727056 7.400000 +158.781845 15.699841 7.400000 +156.500000 15.000000 9.900000 +157.184998 14.134977 9.900000 +156.474960 14.727056 9.900000 +156.966934 13.714057 9.900000 +156.394684 14.447858 9.900000 +156.661697 13.338299 9.900000 +156.255493 14.179185 9.900000 +156.285950 13.033060 9.900000 +156.060654 13.939340 9.900000 +155.865021 12.814998 9.900000 +155.820816 13.744507 9.900000 +155.427612 12.689233 9.900000 +155.552139 13.605317 9.900000 +155.000000 12.650000 9.900000 +155.272949 13.525042 9.900000 +154.572388 12.689233 9.900000 +155.000000 13.500000 9.900000 +154.134979 12.814998 9.900000 +154.727051 13.525042 9.900000 +153.714050 13.033060 9.900000 +154.447861 13.605317 9.900000 +153.338303 13.338299 9.900000 +154.179184 13.744507 9.900000 +153.033066 13.714057 9.900000 +153.939346 13.939340 9.900000 +152.815002 14.134977 9.900000 +153.744507 14.179185 9.900000 +152.689240 14.572387 9.900000 +153.605316 14.447858 9.900000 +152.649994 15.000000 9.900000 +153.525040 14.727056 9.900000 +152.689240 15.427613 9.900000 +153.500000 15.000000 9.900000 +152.815002 15.865023 9.900000 +153.525040 15.272944 9.900000 +153.033066 16.285942 9.900000 +153.605316 15.552142 9.900000 +153.338303 16.661701 9.900000 +153.744507 15.820815 9.900000 +153.714050 16.966940 9.900000 +153.939346 16.060659 9.900000 +154.134979 17.185003 9.900000 +154.179184 16.255493 9.900000 +154.572388 17.310768 9.900000 +154.447861 16.394682 9.900000 +155.000000 17.350000 9.900000 +154.727051 16.474958 9.900000 +155.427612 17.310768 9.900000 +155.000000 16.500000 9.900000 +155.865021 17.185003 9.900000 +155.272949 16.474958 9.900000 +156.285950 16.966940 9.900000 +155.552139 16.394682 9.900000 +156.661697 16.661701 9.900000 +155.820816 16.255493 9.900000 +156.966934 16.285942 9.900000 +156.060654 16.060659 9.900000 +157.184998 15.865023 9.900000 +156.255493 15.820815 9.900000 +157.310760 15.427613 9.900000 +156.394684 15.552142 9.900000 +157.350006 15.000000 9.900000 +156.474960 15.272944 9.900000 +157.310760 14.572387 9.900000 +162.500000 15.450000 36.799999 +157.377014 18.217110 36.799999 +160.184341 23.079550 36.799999 +158.048843 17.589317 36.799999 +162.200027 10.510086 36.799999 +160.184341 6.920451 36.799999 +157.377014 11.782889 36.799999 +162.992203 14.550000 36.799999 +162.500000 14.550000 36.799999 +158.048843 12.410682 36.799999 +158.571274 13.198342 36.799999 +158.894318 14.086596 36.799999 +162.200027 19.489914 36.799999 +162.992203 15.450000 36.799999 +158.571274 16.801657 36.799999 +158.894318 15.913404 36.799999 +159.000000 15.000000 36.799999 +9.052421 17.393536 35.599998 +12.310767 15.427613 9.900000 +12.350000 15.000000 9.900000 +12.574281 15.000000 35.599998 +12.185002 15.865023 9.900000 +12.531303 15.468424 35.599998 +12.393536 15.947579 35.599998 +11.966940 16.285942 9.900000 +12.154661 16.408672 35.599998 +11.661701 16.661701 9.900000 +11.820292 16.820292 35.599998 +11.285943 16.966940 9.900000 +10.865023 17.185003 9.900000 +11.408671 17.154661 35.599998 +10.947579 17.393536 35.599998 +10.427613 17.310768 9.900000 +10.000000 17.350000 9.900000 +10.468424 17.531303 35.599998 +9.572387 17.310768 9.900000 +10.000000 17.574280 35.599998 +9.531576 17.531303 35.599998 +9.134977 17.185003 9.900000 +7.468696 15.468424 35.599998 +7.425719 15.000000 35.599998 +7.650000 15.000000 9.900000 +7.606464 15.947579 35.599998 +7.689232 15.427613 9.900000 +7.814998 15.865023 9.900000 +7.845339 16.408672 35.599998 +8.033060 16.285942 9.900000 +8.179708 16.820292 35.599998 +8.591329 17.154661 35.599998 +8.338299 16.661701 9.900000 +8.714057 16.966940 9.900000 +15.000000 30.000000 0.000000 +164.500000 13.500000 0.000000 +164.924805 13.500000 0.000000 +164.444336 19.044872 0.000000 +164.924805 16.500000 0.000000 +0.500000 16.500000 0.000000 +0.075188 16.500000 0.000000 +0.555658 10.955129 0.000000 +0.075188 13.500000 0.000000 +152.580170 0.223574 0.000000 +150.000000 1.100000 0.000000 +155.211075 0.934274 0.000000 +152.529282 1.332055 0.000000 +157.754730 2.160054 0.000000 +155.116516 2.075943 0.000000 +160.062302 3.875702 0.000000 +157.606216 3.365762 0.000000 +162.000107 6.000150 0.000000 +159.828781 5.171216 0.000000 +163.474106 8.408468 0.000000 +161.634232 7.393785 0.000000 +164.444336 10.955129 0.000000 +162.924057 9.883484 0.000000 +163.667938 12.470714 0.000000 +164.500000 16.500000 0.000000 +163.899994 15.000000 0.000000 +163.667938 17.529287 0.000000 +163.474106 21.591532 0.000000 +162.924057 20.116516 0.000000 +162.000107 23.999849 0.000000 +161.634232 22.606216 0.000000 +160.062302 26.124298 0.000000 +159.828781 24.828785 0.000000 +157.754730 27.839947 0.000000 +157.606216 26.634237 0.000000 +155.211075 29.065725 0.000000 +155.116516 27.924057 0.000000 +152.580170 29.776426 0.000000 +152.529282 28.667944 0.000000 +150.000000 30.000000 0.000000 +150.000000 0.000000 0.000000 +15.000000 1.100000 0.000000 +15.000000 0.000000 0.000000 +12.470714 1.332055 0.000000 +12.419838 0.223574 0.000000 +9.883484 2.075943 0.000000 +9.788919 0.934274 0.000000 +7.393785 3.365762 0.000000 +7.245274 2.160054 0.000000 +5.171216 5.171216 0.000000 +4.937694 3.875702 0.000000 +3.365762 7.393785 0.000000 +2.999888 6.000150 0.000000 +2.075943 9.883484 0.000000 +1.525888 8.408468 0.000000 +1.332055 12.470714 0.000000 +1.100000 15.000000 0.000000 +0.500000 13.500000 0.000000 +1.332055 17.529287 0.000000 +2.075943 20.116516 0.000000 +0.555658 19.044872 0.000000 +3.365762 22.606216 0.000000 +1.525888 21.591532 0.000000 +5.171216 24.828785 0.000000 +2.999888 23.999849 0.000000 +7.393785 26.634237 0.000000 +4.937694 26.124298 0.000000 +9.883484 27.924057 0.000000 +7.245274 27.839947 0.000000 +12.470714 28.667944 0.000000 +9.788919 29.065725 0.000000 +15.000000 28.900000 0.000000 +12.419838 29.776426 0.000000 +150.000000 28.900000 0.000000 +150.000000 1.089464 40.000000 +0.500000 13.500000 40.000000 +0.075188 13.500000 40.000000 +0.555658 19.044872 40.000000 +0.075188 16.500000 40.000000 +164.500000 16.500000 40.000000 +164.924805 16.500000 40.000000 +164.444336 10.955129 40.000000 +164.924805 13.500000 40.000000 +12.419838 0.223574 40.000000 +15.000000 1.089464 40.000000 +9.788919 0.934274 40.000000 +12.468797 1.321695 40.000000 +7.245274 2.160054 40.000000 +9.879605 2.066147 40.000000 +4.937694 3.875702 40.000000 +7.388019 3.356944 40.000000 +2.999888 6.000150 40.000000 +5.163766 5.163766 40.000000 +1.525888 8.408468 40.000000 +3.356944 7.388019 40.000000 +0.555658 10.955129 40.000000 +2.066147 9.879605 40.000000 +1.321695 12.468797 40.000000 +0.500000 16.500000 40.000000 +1.089464 15.000000 40.000000 +1.321695 17.531204 40.000000 +1.525888 21.591532 40.000000 +2.066147 20.120394 40.000000 +2.999888 23.999849 40.000000 +3.356944 22.611980 40.000000 +4.937694 26.124298 40.000000 +5.163766 24.836235 40.000000 +7.245274 27.839947 40.000000 +7.388019 26.643057 40.000000 +9.788919 29.065725 40.000000 +9.879605 27.933853 40.000000 +12.419838 29.776426 40.000000 +12.468797 28.678305 40.000000 +15.000000 30.000000 40.000000 +15.000000 28.910536 40.000000 +150.000000 30.000000 40.000000 +152.580170 29.776426 40.000000 +150.000000 28.910536 40.000000 +155.211075 29.065725 40.000000 +152.531204 28.678305 40.000000 +157.754730 27.839947 40.000000 +155.120392 27.933853 40.000000 +160.062302 26.124298 40.000000 +157.611984 26.643057 40.000000 +162.000107 23.999849 40.000000 +159.836227 24.836235 40.000000 +163.474106 21.591532 40.000000 +161.643051 22.611980 40.000000 +164.444336 19.044872 40.000000 +162.933853 20.120394 40.000000 +163.678299 17.531204 40.000000 +164.500000 13.500000 40.000000 +163.910538 15.000000 40.000000 +163.678299 12.468797 40.000000 +163.474106 8.408468 40.000000 +162.933853 9.879605 40.000000 +162.000107 6.000150 40.000000 +161.643051 7.388019 40.000000 +160.062302 3.875702 40.000000 +159.836227 5.163766 40.000000 +157.754730 2.160054 40.000000 +157.611984 3.356944 40.000000 +155.211075 0.934274 40.000000 +155.120392 2.066147 40.000000 +152.580170 0.223574 40.000000 +152.531204 1.321695 40.000000 +150.000000 0.000000 40.000000 +15.000000 0.000000 40.000000 +3.081470 24.107615 0.000000 +0.075188 16.500000 0.000000 +0.075188 16.500000 40.000000 +0.490571 18.804796 0.000000 +1.549391 21.639360 0.000000 +0.490571 18.804796 40.000000 +15.000000 30.000000 40.000000 +15.000000 30.000000 0.000000 +12.665219 29.817179 40.000000 +9.738981 29.047123 40.000000 +12.665219 29.817179 0.000000 +7.129892 27.769550 40.000000 +9.738981 29.047123 0.000000 +7.129892 27.769550 0.000000 +4.937694 26.124298 40.000000 +4.937694 26.124298 0.000000 +3.081470 24.107615 40.000000 +1.549391 21.639360 40.000000 +12.665219 0.182821 0.000000 +15.000000 0.000000 0.000000 +0.075188 13.500000 40.000000 +0.075188 13.500000 0.000000 +0.490571 11.195205 40.000000 +1.549391 8.360640 40.000000 +0.490571 11.195205 0.000000 +1.549391 8.360640 0.000000 +3.081470 5.892386 40.000000 +3.081470 5.892386 0.000000 +4.937694 3.875702 40.000000 +7.129892 2.230450 40.000000 +4.937694 3.875702 0.000000 +9.738981 0.952877 40.000000 +7.129892 2.230450 0.000000 +12.665219 0.182821 40.000000 +9.738981 0.952877 0.000000 +15.000000 0.000000 40.000000 +15.000000 30.000000 0.000000 +15.000000 30.000000 40.000000 +150.000000 30.000000 40.000000 +150.000000 30.000000 0.000000 +164.509430 18.804796 40.000000 +164.924805 16.500000 40.000000 +150.000000 30.000000 0.000000 +150.000000 30.000000 40.000000 +152.334778 29.817179 0.000000 +155.261017 29.047123 0.000000 +152.334778 29.817179 40.000000 +155.261017 29.047123 40.000000 +157.870102 27.769550 0.000000 +157.870102 27.769550 40.000000 +160.062302 26.124298 0.000000 +161.918533 24.107615 0.000000 +160.062302 26.124298 40.000000 +163.450607 21.639360 0.000000 +161.918533 24.107615 40.000000 +163.450607 21.639360 40.000000 +164.509430 18.804796 0.000000 +164.924805 16.500000 0.000000 +160.062302 3.875702 40.000000 +150.000000 0.000000 40.000000 +150.000000 0.000000 0.000000 +152.334778 0.182821 40.000000 +152.334778 0.182821 0.000000 +155.261017 0.952877 40.000000 +157.870102 2.230450 40.000000 +155.261017 0.952877 0.000000 +164.924805 13.500000 0.000000 +164.924805 13.500000 40.000000 +164.509430 11.195205 0.000000 +164.509430 11.195205 40.000000 +163.450607 8.360640 0.000000 +163.450607 8.360640 40.000000 +161.918533 5.892386 0.000000 +160.062302 3.875702 0.000000 +161.918533 5.892386 40.000000 +157.870102 2.230450 0.000000 +15.000000 3.138854 39.000000 +150.000000 3.138854 39.000000 +152.155334 3.352807 39.000000 +152.158295 3.336872 39.000000 +154.360062 3.986713 39.000000 +154.366028 3.971646 39.000000 +156.481674 5.085838 39.000000 +156.490540 5.072274 39.000000 +158.375641 6.624362 39.000000 +158.387100 6.612904 39.000000 +159.914154 8.518333 39.000000 +159.927719 8.509465 39.000000 +161.013290 10.639940 39.000000 +161.028351 10.633975 39.000000 +161.647186 12.844659 39.000000 +161.663132 12.841710 39.000000 +161.844940 15.000000 39.000000 +161.861145 15.000000 39.000000 +161.647186 17.155342 39.000000 +161.663132 17.158291 39.000000 +161.013290 19.360060 39.000000 +161.028351 19.366024 39.000000 +159.914154 21.481667 39.000000 +159.927719 21.490534 39.000000 +158.375641 23.375637 39.000000 +158.387100 23.387096 39.000000 +156.481674 24.914162 39.000000 +156.490540 24.927725 39.000000 +154.360062 26.013287 39.000000 +154.366028 26.028355 39.000000 +152.155334 26.647194 39.000000 +152.158295 26.663128 39.000000 +150.000000 26.844940 39.000000 +150.000000 26.861145 39.000000 +15.000000 26.844940 39.000000 +15.000000 26.861145 39.000000 +12.844659 26.647194 39.000000 +12.841710 26.663128 39.000000 +10.639940 26.013287 39.000000 +10.633975 26.028355 39.000000 +8.518333 24.914162 39.000000 +8.509465 24.927725 39.000000 +6.624362 23.375637 39.000000 +6.612904 23.387096 39.000000 +5.085838 21.481667 39.000000 +5.072274 21.490534 39.000000 +3.986713 19.360060 39.000000 +3.971646 19.366024 39.000000 +3.352807 17.155342 39.000000 +3.336872 17.158291 39.000000 +3.155060 15.000000 39.000000 +3.138854 15.000000 39.000000 +3.352807 12.844659 39.000000 +3.336872 12.841710 39.000000 +3.986713 10.639940 39.000000 +3.971646 10.633975 39.000000 +5.085838 8.518333 39.000000 +5.072274 8.509465 39.000000 +6.624362 6.624362 39.000000 +6.612904 6.612904 39.000000 +8.518333 5.085838 39.000000 +8.509465 5.072274 39.000000 +10.639940 3.986713 39.000000 +10.633975 3.971646 39.000000 +12.844659 3.352807 39.000000 +12.841710 3.336872 39.000000 +15.000000 3.155060 39.000000 +150.000000 3.155060 39.000000 +15.000000 28.412106 39.684189 +150.000000 28.516422 39.807693 +15.000000 28.516422 39.807693 +150.000000 28.412106 39.684189 +15.000000 27.022690 39.006222 +15.000000 26.861145 39.000000 +150.000000 26.861145 39.000000 +150.000000 27.022690 39.006222 +15.000000 27.423262 39.076630 +150.000000 27.423262 39.076630 +15.000000 27.782057 39.212696 +150.000000 27.782057 39.212696 +15.000000 28.110102 39.411774 +150.000000 28.110102 39.411774 +3.336872 12.841710 39.000000 +3.138854 15.000000 39.000000 +7.523942 5.791562 39.000000 +8.509465 5.072274 39.000000 +10.633975 3.971646 39.000000 +12.841710 3.336872 39.000000 +6.612904 6.612904 39.000000 +5.791562 7.523942 39.000000 +5.072274 8.509465 39.000000 +3.971646 10.633975 39.000000 +15.000000 2.977309 39.006222 +15.000000 3.138854 39.000000 +15.000000 2.576737 39.076630 +15.000000 2.217943 39.212696 +15.000000 1.889898 39.411774 +15.000000 1.587895 39.684189 +15.000000 1.483578 39.807693 +12.540510 1.709229 39.807693 +10.024676 2.432589 39.807693 +7.603682 3.686815 39.807693 +6.480624 4.506483 39.807693 +5.442446 5.442446 39.807693 +4.506483 6.480624 39.807693 +3.686815 7.603682 39.807693 +2.432589 10.024676 39.807693 +1.709229 12.540510 39.807693 +1.587895 15.000000 39.684189 +1.483578 15.000000 39.807693 +1.889898 15.000000 39.411774 +2.217943 15.000000 39.212696 +2.576737 15.000000 39.076630 +2.977309 15.000000 39.006222 +6.498674 6.498674 39.006222 +8.187528 5.093673 39.006222 +10.224859 3.966273 39.006222 +12.536437 3.232420 39.006222 +5.093673 8.187528 39.006222 +3.966273 10.224859 39.006222 +3.232420 12.536437 39.006222 +12.454356 2.840348 39.076630 +12.380836 2.489167 39.212696 +12.313616 2.168082 39.411774 +12.251733 1.872487 39.684189 +9.673016 2.691149 39.684189 +7.400238 3.948838 39.684189 +5.516210 5.516210 39.684189 +3.948838 7.400238 39.684189 +2.691149 9.673016 39.684189 +1.872487 12.251733 39.684189 +2.168082 12.313616 39.411774 +2.489167 12.380836 39.212696 +2.840348 12.454356 39.076630 +9.792964 2.968310 39.411774 +9.923257 3.269372 39.212696 +10.065762 3.598652 39.076630 +7.571362 4.197680 39.411774 +7.757245 4.467979 39.212696 +5.729758 5.729758 39.411774 +5.961721 5.961721 39.212696 +7.960550 4.763615 39.076630 +6.215427 6.215427 39.076630 +4.197680 7.571362 39.411774 +4.467979 7.757245 39.212696 +2.968310 9.792964 39.411774 +3.269372 9.923257 39.212696 +4.763615 7.960550 39.076630 +3.598652 10.065762 39.076630 +161.313187 22.396318 39.807693 +150.000000 1.587895 39.684189 +150.000000 1.483578 39.807693 +150.000000 27.022690 39.006222 +150.000000 26.861145 39.000000 +162.567413 19.975323 39.807693 +163.290771 17.459490 39.807693 +163.516418 15.000000 39.807693 +163.290771 12.540510 39.807693 +162.567413 10.024676 39.807693 +161.313187 7.603682 39.807693 +159.557556 5.442446 39.807693 +157.396317 3.686815 39.807693 +154.975327 2.432589 39.807693 +152.459488 1.709229 39.807693 +150.000000 1.889898 39.411774 +150.000000 2.217943 39.212696 +150.000000 2.576737 39.076630 +150.000000 2.977309 39.006222 +150.000000 3.138854 39.000000 +152.158295 3.336872 39.000000 +154.366028 3.971646 39.000000 +156.490540 5.072274 39.000000 +158.387100 6.612904 39.000000 +159.927719 8.509465 39.000000 +161.028351 10.633975 39.000000 +161.663132 12.841710 39.000000 +161.861145 15.000000 39.000000 +161.663132 17.158291 39.000000 +161.028351 19.366024 39.000000 +159.927719 21.490534 39.000000 +158.387100 23.387096 39.000000 +156.490540 24.927725 39.000000 +154.366028 26.028355 39.000000 +152.158295 26.663128 39.000000 +150.000000 27.423262 39.076630 +150.000000 27.782057 39.212696 +150.000000 28.110102 39.411774 +150.000000 28.412106 39.684189 +150.000000 28.516422 39.807693 +152.459488 28.290771 39.807693 +154.975327 27.567411 39.807693 +157.396317 26.313185 39.807693 +159.557556 24.557554 39.807693 +161.225876 22.339235 39.684189 +162.470413 19.936924 39.684189 +163.188202 17.440508 39.684189 +163.412109 15.000000 39.684189 +163.188202 12.559492 39.684189 +162.470413 10.063075 39.684189 +161.225876 7.660765 39.684189 +159.483795 5.516210 39.684189 +157.339233 3.774128 39.684189 +154.936920 2.529582 39.684189 +152.440506 1.811805 39.684189 +152.385559 2.108766 39.411774 +152.325867 2.431335 39.212696 +152.260574 2.784139 39.076630 +152.187683 3.178024 39.006222 +154.425491 3.821443 39.006222 +156.578934 4.937062 39.006222 +158.501328 6.498674 39.006222 +160.062943 8.421066 39.006222 +161.178558 10.574512 39.006222 +161.821976 12.812315 39.006222 +162.022690 15.000000 39.006222 +161.821976 17.187685 39.006222 +161.178558 19.425489 39.006222 +160.062943 21.578934 39.006222 +158.501328 23.501326 39.006222 +156.578934 25.062939 39.006222 +154.425491 26.178556 39.006222 +152.187683 26.821976 39.006222 +152.260574 27.215860 39.076630 +152.325867 27.568665 39.212696 +152.385559 27.891233 39.411774 +152.440506 28.188194 39.684189 +154.936920 27.470419 39.684189 +157.339233 26.225872 39.684189 +159.483795 24.483791 39.684189 +154.825760 27.189619 39.411774 +154.705002 26.884607 39.212696 +154.572937 26.551004 39.076630 +157.173981 25.973097 39.411774 +156.994461 25.698524 39.212696 +159.270248 24.270243 39.411774 +159.038284 24.038279 39.212696 +156.798126 25.398214 39.076630 +158.784576 23.784573 39.076630 +160.973099 22.173975 39.411774 +160.698517 21.994467 39.212696 +162.189621 19.825760 39.411774 +161.884613 19.705008 39.212696 +160.398209 21.798130 39.076630 +161.551010 19.572937 39.076630 +162.891235 17.385553 39.411774 +162.568665 17.325863 39.212696 +163.110107 15.000000 39.411774 +162.782059 15.000000 39.212696 +162.215866 17.260574 39.076630 +162.423264 15.000000 39.076630 +162.891235 12.614446 39.411774 +162.568665 12.674138 39.212696 +162.189621 10.174241 39.411774 +161.884613 10.294992 39.212696 +162.215866 12.739426 39.076630 +161.551010 10.427063 39.076630 +160.973099 7.826024 39.411774 +160.698517 8.005534 39.212696 +159.270248 5.729758 39.411774 +159.038284 5.961721 39.212696 +160.398209 8.201870 39.076630 +158.784576 6.215427 39.076630 +157.173981 4.026903 39.411774 +156.994461 4.301476 39.212696 +154.825760 2.810380 39.411774 +154.705002 3.115393 39.212696 +156.798126 4.601785 39.076630 +154.572937 3.448996 39.076630 +15.000000 2.576737 39.076630 +15.000000 1.587895 39.684189 +15.000000 1.483578 39.807693 +150.000000 1.483578 39.807693 +15.000000 1.889898 39.411774 +150.000000 1.587895 39.684189 +150.000000 1.889898 39.411774 +15.000000 2.217943 39.212696 +150.000000 2.977309 39.006222 +150.000000 3.138854 39.000000 +15.000000 3.138854 39.000000 +150.000000 2.576737 39.076630 +15.000000 2.977309 39.006222 +150.000000 2.217943 39.212696 +15.000000 26.662361 38.965485 +150.000000 26.662361 38.965485 +150.000000 26.665434 38.966667 +15.000000 26.665434 38.966667 +15.000000 24.694168 38.600002 +15.000000 24.690874 38.599998 +150.000000 24.690874 38.599998 +150.000000 24.694168 38.600002 +15.000000 25.695032 38.692444 +150.000000 25.695032 38.692444 +5.943503 7.647298 38.966667 +5.236084 8.616561 38.966667 +4.153615 10.706016 38.966667 +3.529316 12.877322 38.966667 +6.751292 6.751292 38.966667 +7.647298 5.943503 38.966667 +8.616561 5.236084 38.966667 +10.706016 4.153615 38.966667 +3.337757 15.000000 38.965439 +3.334566 15.000000 38.966667 +4.304968 15.000000 38.692444 +5.470912 13.236619 38.599998 +5.309126 15.000000 38.599998 +5.305707 15.000000 38.600002 +15.000000 5.305707 38.600002 +15.000000 5.309126 38.599998 +15.000000 4.304968 38.692444 +12.877322 3.529316 38.966667 +15.000000 3.334566 38.966667 +15.000000 3.337757 38.965439 +13.236619 5.470912 38.599998 +11.432840 5.989539 38.599998 +9.697060 6.888782 38.599998 +8.891860 7.476459 38.599998 +8.147517 8.147517 38.599998 +7.476459 8.891860 38.599998 +6.888782 9.697060 38.599998 +5.989539 11.432840 38.599998 +4.531907 12.808487 38.692444 +3.585218 12.610296 38.965439 +5.390671 8.391769 38.965439 +6.753549 6.753549 38.965439 +4.297071 10.368021 38.965439 +8.391769 5.390671 38.965439 +10.368021 4.297071 38.965439 +12.610296 3.585218 38.965439 +12.808487 4.531907 38.692444 +13.013548 5.511411 38.600002 +11.149647 6.103142 38.600002 +9.506879 7.012202 38.600002 +8.145100 8.145100 38.600002 +7.012202 9.506879 38.600002 +6.103142 11.149647 38.600002 +5.511411 13.013548 38.600002 +10.752175 5.184721 38.692444 +8.939825 6.187623 38.692444 +7.437470 7.437470 38.692444 +6.187623 8.939825 38.692444 +5.184721 10.752175 38.692444 +152.122681 26.470684 38.966667 +150.000000 26.665434 38.966667 +150.000000 26.662361 38.965485 +150.000000 25.695032 38.692444 +150.000000 24.694168 38.600002 +150.000000 24.690874 38.599998 +151.763382 24.529089 38.599998 +153.567154 24.010462 38.599998 +155.302948 23.111217 38.599998 +156.852478 21.852482 38.599998 +158.111221 20.302940 38.599998 +159.010468 18.567160 38.599998 +159.529083 16.763382 38.599998 +159.690872 15.000000 38.599998 +159.529083 13.236619 38.599998 +159.010468 11.432840 38.599998 +158.111221 9.697060 38.599998 +156.852478 8.147517 38.599998 +155.302948 6.888782 38.599998 +153.567154 5.989539 38.599998 +151.763382 5.470912 38.599998 +150.000000 5.309126 38.599998 +150.000000 5.305833 38.600002 +150.000000 4.304968 38.692444 +150.000000 3.337640 38.965485 +150.000000 3.334566 38.966667 +152.122681 3.529316 38.966667 +154.293991 4.153615 38.966667 +156.383438 5.236084 38.966667 +158.248703 6.751292 38.966667 +159.763916 8.616561 38.966667 +160.846390 10.706016 38.966667 +161.470688 12.877322 38.966667 +161.665436 15.000000 38.966667 +161.470688 17.122679 38.966667 +160.846390 19.293985 38.966667 +159.763916 21.383440 38.966667 +158.248703 23.248707 38.966667 +156.383438 24.763916 38.966667 +154.293991 25.846384 38.966667 +154.292816 25.843418 38.965439 +152.122101 26.467546 38.965439 +151.946106 25.516483 38.692444 +151.764008 24.532450 38.600002 +153.568420 24.013639 38.600002 +155.304810 23.114079 38.600002 +156.854904 21.854900 38.600002 +158.114075 20.304811 38.600002 +159.013641 18.568419 38.600002 +159.532455 16.764004 38.600002 +159.694290 15.000000 38.600002 +159.532455 13.235997 38.600002 +159.013641 11.431582 38.600002 +158.114075 9.695189 38.600002 +156.854904 8.145100 38.600002 +155.304810 6.885921 38.600002 +153.568420 5.986360 38.600002 +151.764008 5.467550 38.600002 +151.946106 4.483518 38.692444 +152.122101 3.532454 38.965439 +154.292816 4.156582 38.965439 +156.381699 5.238755 38.965439 +158.246445 6.753549 38.965439 +159.761246 8.618307 38.965439 +160.843414 10.707190 38.965439 +161.467545 12.877903 38.965439 +161.662247 15.000000 38.965439 +161.467545 17.122097 38.965439 +160.843414 19.292810 38.965439 +159.761246 21.381693 38.965439 +158.246445 23.246452 38.965439 +156.381699 24.761246 38.965439 +153.936783 24.944115 38.692444 +155.852432 23.951694 38.692444 +157.562531 22.562531 38.692444 +158.951691 20.852427 38.692444 +159.944122 18.936785 38.692444 +160.516479 16.946100 38.692444 +160.695038 15.000000 38.692444 +160.516479 13.053900 38.692444 +159.944122 11.063215 38.692444 +158.951691 9.147574 38.692444 +157.562531 7.437470 38.692444 +155.852432 6.048306 38.692444 +153.936783 5.055884 38.692444 +15.000000 3.334566 38.966667 +150.000000 3.334566 38.966667 +150.000000 5.305833 38.600002 +150.000000 5.309126 38.599998 +15.000000 5.309126 38.599998 +150.000000 4.304968 38.692444 +15.000000 5.305833 38.600002 +15.000000 4.304968 38.692444 +150.000000 3.337640 38.965485 +15.000000 3.337640 38.965485 +150.000000 26.844940 39.000000 +15.000000 26.844940 39.000000 +15.000000 26.665434 38.966667 +150.000000 26.665434 38.966667 +15.000000 26.665714 38.966774 +150.000000 26.665714 38.966774 +15.000000 26.753653 38.991596 +150.000000 26.753653 38.991596 +15.000000 26.844641 39.000000 +150.000000 26.844641 39.000000 +15.000000 26.844641 39.000000 +15.000000 26.844940 39.000000 +15.000000 3.334286 38.966774 +15.000000 3.334566 38.966667 +12.844659 3.352807 39.000000 +15.000000 3.155060 39.000000 +15.000000 3.155360 39.000000 +15.000000 3.246347 38.991596 +12.877322 3.529316 38.966667 +10.706016 4.153615 38.966667 +8.616561 5.236084 38.966667 +6.751292 6.751292 38.966667 +5.236084 8.616561 38.966667 +4.153615 10.706016 38.966667 +3.529316 12.877322 38.966667 +3.334566 15.000000 38.966667 +3.529316 17.122679 38.966667 +4.153615 19.293985 38.966667 +5.236084 21.383440 38.966667 +6.751292 23.248707 38.966667 +8.616561 24.763916 38.966667 +10.706016 25.846384 38.966667 +12.877322 26.470684 38.966667 +15.000000 26.665434 38.966667 +15.000000 26.665714 38.966774 +15.000000 26.753653 38.991596 +12.844659 26.647194 39.000000 +10.639940 26.013287 39.000000 +8.518333 24.914162 39.000000 +6.624362 23.375637 39.000000 +5.085838 21.481667 39.000000 +3.986713 19.360060 39.000000 +3.352807 17.155342 39.000000 +3.155060 15.000000 39.000000 +3.352807 12.844659 39.000000 +3.986713 10.639940 39.000000 +5.085838 8.518333 39.000000 +6.624362 6.624362 39.000000 +8.518333 5.085838 39.000000 +10.639940 3.986713 39.000000 +10.640055 3.987002 39.000000 +12.844715 3.353113 39.000000 +12.861269 3.442570 38.991596 +12.877269 3.529031 38.966778 +10.705909 4.153346 38.966778 +8.616402 5.235841 38.966778 +6.751087 6.751087 38.966778 +5.235841 8.616402 38.966778 +4.153346 10.705909 38.966778 +3.529031 12.877269 38.966778 +3.334275 15.000000 38.966778 +3.529031 17.122730 38.966778 +4.153346 19.294092 38.966778 +5.235841 21.383598 38.966778 +6.751087 23.248913 38.966778 +8.616402 24.764158 38.966778 +10.705909 25.846655 38.966778 +12.877269 26.470970 38.966778 +12.861269 26.557430 38.991596 +12.844715 26.646887 39.000000 +10.640055 26.012997 39.000000 +8.518503 24.913902 39.000000 +6.624582 23.375418 39.000000 +5.086099 21.481497 39.000000 +3.987002 19.359945 39.000000 +3.353113 17.155285 39.000000 +3.155371 15.000000 39.000000 +3.353113 12.844715 39.000000 +3.987002 10.640055 39.000000 +5.086099 8.518503 39.000000 +6.624582 6.624582 39.000000 +8.518503 5.086099 39.000000 +10.673543 25.928410 38.991596 +8.568287 24.837755 38.991596 +6.688912 23.311087 38.991596 +5.162245 21.431713 38.991596 +4.071591 19.326458 38.991596 +3.442570 17.138731 38.991596 +3.246347 15.000000 38.991596 +3.442570 12.861269 38.991596 +4.071591 10.673543 38.991596 +5.162245 8.568287 38.991596 +6.688912 6.688912 38.991596 +8.568287 5.162245 38.991596 +10.673543 4.071591 38.991596 +157.352707 24.056498 38.966667 +156.383438 24.763916 38.966667 +154.293991 25.846384 38.966667 +152.122681 26.470684 38.966667 +150.000000 26.665714 38.966774 +150.000000 26.665434 38.966667 +161.844635 15.000000 39.000000 +161.844940 15.000000 39.000000 +158.248703 23.248707 38.966667 +159.056503 22.352701 38.966667 +159.763916 21.383440 38.966667 +160.846390 19.293985 38.966667 +161.753647 15.000000 38.991596 +150.000000 26.753653 38.991596 +152.155334 26.647194 39.000000 +150.000000 26.844940 39.000000 +150.000000 26.844641 39.000000 +161.470688 17.122679 38.966667 +161.665436 15.000000 38.966667 +161.665710 15.000000 38.966774 +161.647186 17.155342 39.000000 +161.013290 19.360060 39.000000 +159.914154 21.481667 39.000000 +159.195862 22.465843 39.000000 +158.375641 23.375637 39.000000 +157.465851 24.195856 39.000000 +156.481674 24.914162 39.000000 +154.360062 26.013287 39.000000 +152.408432 26.504251 38.991596 +152.390411 26.418188 38.966778 +158.248917 23.248913 38.966778 +156.610199 24.612198 38.966778 +154.633362 25.706123 38.966778 +159.612198 21.610203 38.966778 +160.706131 19.633362 38.966778 +161.418182 17.390417 38.966778 +161.504257 17.408434 38.991596 +161.593292 17.427076 39.000000 +160.870316 19.704418 39.000000 +159.759613 21.711576 39.000000 +158.375412 23.375418 39.000000 +156.711578 24.759609 39.000000 +154.704422 25.870312 39.000000 +152.427078 26.593298 39.000000 +160.786819 19.668285 38.991596 +159.684647 21.660027 38.991596 +158.311081 23.311087 38.991596 +156.660019 24.684649 38.991596 +154.668289 25.786819 38.991596 +150.000000 3.334286 38.966774 +15.000000 3.155060 39.000000 +150.000000 3.155060 39.000000 +15.000000 3.155360 39.000000 +150.000000 3.155360 39.000000 +15.000000 3.246347 38.991596 +150.000000 3.246347 38.991596 +15.000000 3.334286 38.966774 +150.000000 3.334566 38.966667 +15.000000 3.334566 38.966667 +150.000000 28.539351 39.834995 +15.000000 28.539351 39.834995 +15.000000 28.516422 39.807693 +150.000000 28.516422 39.807693 +150.000000 28.874905 39.998730 +150.000000 28.910536 40.000000 +15.000000 28.910536 40.000000 +15.000000 28.874905 39.998730 +150.000000 28.781572 39.983082 +15.000000 28.781572 39.983082 +150.000000 28.691271 39.949360 +15.000000 28.691271 39.949360 +150.000000 28.609119 39.898933 +15.000000 28.609119 39.898933 +2.233719 20.524950 40.000000 +3.538147 22.882191 40.000000 +5.163766 24.836235 40.000000 +7.117809 26.461853 40.000000 +1.460649 15.000000 39.834995 +1.483578 15.000000 39.807693 +1.384633 17.850401 40.000000 +1.089464 15.000000 40.000000 +9.475050 27.766281 40.000000 +12.149599 28.615368 40.000000 +15.000000 28.910536 40.000000 +15.000000 28.874905 39.998730 +15.000000 28.781572 39.983082 +15.000000 28.691271 39.949360 +15.000000 28.609119 39.898933 +15.000000 28.539351 39.834995 +15.000000 28.516422 39.807693 +12.540510 28.290771 39.807693 +10.024676 27.567411 39.807693 +7.603682 26.313185 39.807693 +6.480624 25.493517 39.807693 +5.442446 24.557554 39.807693 +4.506483 23.519375 39.807693 +3.686815 22.396318 39.807693 +2.432589 19.975323 39.807693 +1.709229 17.459490 39.807693 +1.390881 15.000000 39.898933 +1.308729 15.000000 39.949360 +1.218427 15.000000 39.983082 +1.125095 15.000000 39.998730 +2.269018 20.509672 39.998520 +3.569839 22.860395 39.998520 +5.190963 24.809036 39.998520 +7.139604 26.430161 39.998520 +9.490327 27.730982 39.998520 +12.157481 28.577721 39.998520 +12.177024 28.484369 39.981754 +12.194529 28.400755 39.949360 +12.210533 28.324306 39.901958 +12.225267 28.253927 39.837097 +9.621718 27.427382 39.837097 +7.327054 26.157581 39.837097 +5.424883 24.575117 39.837097 +3.842419 22.672947 39.837097 +2.572619 20.378283 39.837097 +1.746073 17.774733 39.837097 +1.675694 17.789467 39.901958 +1.599245 17.805471 39.949360 +1.515630 17.822975 39.981754 +1.422280 17.842520 39.998520 +2.506628 20.406841 39.901958 +2.434947 20.437862 39.949360 +2.356547 20.471792 39.981754 +3.783171 22.713690 39.901958 +3.718814 22.757948 39.949360 +3.648425 22.806355 39.981754 +5.374039 24.625961 39.901958 +5.318809 24.681190 39.949360 +5.258403 24.741596 39.981754 +7.286310 26.216829 39.901958 +7.242052 26.281185 39.949360 +7.193646 26.351576 39.981754 +9.593159 27.493372 39.901958 +9.562138 27.565054 39.949360 +9.528208 27.643454 39.981754 +152.531204 28.678305 40.000000 +150.000000 28.910536 40.000000 +155.120392 27.933853 40.000000 +157.611984 26.643057 40.000000 +159.836227 24.836235 40.000000 +161.643051 22.611980 40.000000 +162.933853 20.120394 40.000000 +163.678299 17.531204 40.000000 +163.910538 15.000000 40.000000 +163.678299 12.468797 40.000000 +162.933853 9.879605 40.000000 +161.643051 7.388019 40.000000 +159.836227 5.163766 40.000000 +157.611984 3.356944 40.000000 +155.120392 2.066147 40.000000 +152.531204 1.321695 40.000000 +150.000000 1.089464 40.000000 +150.000000 1.125095 39.998730 +150.000000 1.218427 39.983082 +150.000000 1.308729 39.949360 +150.000000 1.390881 39.898933 +150.000000 1.460649 39.834995 +150.000000 1.483578 39.807693 +152.459488 1.709229 39.807693 +154.975327 2.432589 39.807693 +157.396317 3.686815 39.807693 +159.557556 5.442446 39.807693 +161.313187 7.603682 39.807693 +162.567413 10.024676 39.807693 +163.290771 12.540510 39.807693 +163.516418 15.000000 39.807693 +163.290771 17.459490 39.807693 +162.567413 19.975323 39.807693 +161.313187 22.396318 39.807693 +159.557556 24.557554 39.807693 +157.396317 26.313185 39.807693 +154.975327 27.567411 39.807693 +152.459488 28.290771 39.807693 +150.000000 28.516422 39.807693 +150.000000 28.539351 39.834995 +150.000000 28.609119 39.898933 +150.000000 28.691271 39.949360 +150.000000 28.781572 39.983082 +150.000000 28.874905 39.998730 +155.106232 27.898090 39.998520 +152.524200 28.640484 39.998520 +157.590927 26.610863 39.998520 +159.809036 24.809036 39.998520 +161.610855 22.590933 39.998520 +162.898087 20.106237 39.998520 +163.640488 17.524204 39.998520 +163.872070 15.000000 39.998520 +163.640488 12.475796 39.998520 +162.898087 9.893764 39.998520 +161.610855 7.409067 39.998520 +159.809036 5.190963 39.998520 +157.590927 3.389138 39.998520 +155.106232 2.101909 39.998520 +152.524200 1.359517 39.998520 +152.506851 1.453298 39.981754 +152.491302 1.537300 39.949360 +152.477097 1.614102 39.901958 +152.464005 1.684807 39.837097 +154.984467 2.409495 39.837097 +157.409912 3.666026 39.837097 +159.575119 5.424883 39.837097 +161.333969 7.590091 39.837097 +162.590500 10.015534 39.837097 +163.315201 12.535991 39.837097 +163.541260 15.000000 39.837097 +163.315201 17.464008 39.837097 +162.590500 19.984467 39.837097 +161.333969 22.409910 39.837097 +159.575119 24.575117 39.837097 +157.409912 26.333973 39.837097 +154.984467 27.590506 39.837097 +152.464005 28.315193 39.837097 +152.477097 28.385899 39.901958 +152.491302 28.462700 39.949360 +152.506851 28.546701 39.981754 +155.010941 27.657362 39.901958 +155.039688 27.729984 39.949360 +155.071136 27.809414 39.981754 +157.449249 26.394157 39.901958 +157.492004 26.459532 39.949360 +157.538742 26.531034 39.981754 +159.625961 24.625961 39.901958 +159.681198 24.681190 39.949360 +159.741592 24.741596 39.981754 +161.394165 22.449257 39.901958 +161.459534 22.491997 39.949360 +161.531036 22.538744 39.981754 +162.657364 20.010935 39.901958 +162.729980 20.039684 39.949360 +162.809418 20.071131 39.981754 +163.385895 17.477093 39.901958 +163.462708 17.491306 39.949360 +163.546707 17.506849 39.981754 +163.613159 15.000000 39.901958 +163.691269 15.000000 39.949360 +163.776703 15.000000 39.981754 +163.385895 12.522907 39.901958 +163.462708 12.508695 39.949360 +163.546707 12.493150 39.981754 +162.657364 9.989066 39.901958 +162.729980 9.960316 39.949360 +162.809418 9.928870 39.981754 +161.394165 7.550743 39.901958 +161.459534 7.508003 39.949360 +161.531036 7.461256 39.981754 +159.625961 5.374039 39.901958 +159.681198 5.318809 39.949360 +159.741592 5.258403 39.981754 +157.449249 3.605842 39.901958 +157.492004 3.540468 39.949360 +157.538742 3.468965 39.981754 +155.010941 2.342638 39.901958 +155.039688 2.270016 39.949360 +155.071136 2.190587 39.981754 +15.000000 1.089464 40.000000 +150.000000 1.089464 40.000000 +150.000000 1.483578 39.807693 +15.000000 1.483578 39.807693 +150.000000 1.460649 39.834995 +15.000000 1.460649 39.834995 +150.000000 1.390881 39.898933 +15.000000 1.390881 39.898933 +150.000000 1.308729 39.949360 +15.000000 1.308729 39.949360 +150.000000 1.218427 39.983082 +15.000000 1.218427 39.983082 +150.000000 1.125095 39.998730 +15.000000 1.125095 39.998730 +150.000000 28.900000 0.000000 +150.000000 28.900000 2.300000 +19.410213 28.900000 2.300000 +15.000000 28.900000 2.300000 +15.000000 28.900000 0.000000 +20.189787 28.900000 2.300000 +40.310215 28.900000 2.300000 +41.089787 28.900000 2.300000 +61.210213 28.900000 2.300000 +61.989784 28.900000 2.300000 +82.110214 28.900000 2.300000 +82.889786 28.900000 2.300000 +103.010216 28.900000 2.300000 +103.789787 28.900000 2.300000 +123.910217 28.900000 2.300000 +124.689789 28.900000 2.300000 +144.810211 28.900000 2.300000 +145.589783 28.900000 2.300000 +1.100000 15.000000 0.000000 +1.100000 15.000000 1.150000 +12.151758 1.394945 2.300000 +15.000000 1.100000 2.300000 +15.000000 1.100000 0.000000 +12.151758 1.394945 0.000000 +9.479235 2.243388 2.300000 +9.479235 2.243388 0.000000 +7.123779 3.546829 2.300000 +7.123779 3.546828 0.000000 +5.171255 5.171177 2.300000 +5.171216 5.171216 0.000000 +3.546828 7.123779 2.300000 +3.546828 7.123779 0.000000 +2.243388 9.479235 2.300000 +2.243388 9.479235 0.000000 +1.394945 12.151758 2.300000 +1.394945 12.151758 0.000000 +1.107286 14.550000 1.150000 +1.107286 14.550000 2.300000 +145.589783 1.100000 2.300000 +150.000000 1.100000 2.300000 +15.000000 1.100000 0.000000 +15.000000 1.100000 2.300000 +150.000000 1.100000 0.000000 +19.410213 1.100000 2.300000 +20.189787 1.100000 2.300000 +40.310215 1.100000 2.300000 +41.089787 1.100000 2.300000 +52.210213 1.100000 2.300000 +52.989784 1.100000 2.300000 +61.210213 1.100000 2.300000 +61.989784 1.100000 2.300000 +73.110214 1.100000 2.300000 +73.889786 1.100000 2.300000 +82.110214 1.100000 2.300000 +82.889786 1.100000 2.300000 +91.110214 1.100000 2.300000 +91.889786 1.100000 2.300000 +103.010216 1.100000 2.300000 +103.789787 1.100000 2.300000 +112.010216 1.100000 2.300000 +112.789787 1.100000 2.300000 +123.910217 1.100000 2.300000 +124.689789 1.100000 2.300000 +144.810211 1.100000 2.300000 +163.667938 12.470714 2.300000 +163.892715 14.550000 2.300000 +150.000000 28.900000 2.300000 +150.000000 28.900000 0.000000 +152.529282 28.667944 2.300000 +155.116516 27.924057 2.300000 +152.529282 28.667944 0.000000 +157.606216 26.634237 2.300000 +155.116516 27.924057 0.000000 +159.828781 24.828785 2.300000 +157.606216 26.634237 0.000000 +159.828781 24.828785 0.000000 +161.634232 22.606216 2.300000 +161.634232 22.606216 0.000000 +162.924057 20.116516 2.300000 +162.924057 20.116516 0.000000 +163.667938 17.529287 2.300000 +163.892715 15.450000 2.300000 +163.892715 15.450000 2.292714 +163.892715 15.450000 1.150000 +163.667938 17.529287 0.000000 +163.899994 15.000000 1.150000 +163.899994 15.000000 0.000000 +163.892715 14.550000 1.150000 +152.529282 1.332055 0.000000 +150.000000 1.100000 0.000000 +150.000000 1.100000 2.300000 +152.529282 1.332055 2.300000 +155.116516 2.075943 0.000000 +155.116516 2.075943 2.300000 +157.606216 3.365762 0.000000 +157.606216 3.365762 2.300000 +159.828781 5.171216 0.000000 +161.634232 7.393785 0.000000 +159.828781 5.171216 2.300000 +161.634232 7.393785 2.300000 +162.924057 9.883484 0.000000 +162.924057 9.883484 2.300000 +163.667938 12.470714 0.000000 +163.892715 14.550000 2.292714 +160.583923 22.548557 36.799999 +160.184341 23.079550 36.799999 +162.818588 17.913530 9.006416 +163.137817 15.450000 9.006416 +162.992203 15.450000 36.799999 +162.676682 17.881277 36.799999 +161.973053 20.426886 9.006416 +150.000000 28.000000 36.799999 +150.000000 28.145529 9.006416 +152.445587 27.767893 36.799999 +154.958298 27.017294 36.799999 +152.472961 27.910824 9.006416 +155.013794 27.151821 9.006416 +157.181778 25.836143 36.799999 +159.034058 24.348038 36.799999 +157.262177 25.957449 9.006416 +159.564011 23.805096 36.799999 +159.721436 23.822237 12.400000 +159.134796 24.453070 9.006416 +160.166931 23.304911 12.400000 +161.840500 20.366808 36.799999 +160.702393 22.633060 9.006416 +145.649994 2.000000 36.799999 +150.000000 2.000000 36.799999 +150.000000 1.854472 9.006416 +145.601486 1.854472 9.006416 +2.007791 15.450000 36.799999 +1.860604 15.401491 9.006416 +2.318074 17.858101 36.799999 +2.176106 17.890097 9.006416 +3.149713 20.345156 36.799999 +3.017055 20.404993 9.006416 +4.402305 22.529200 36.799999 +4.815655 23.079550 36.799999 +4.833066 23.304911 12.400000 +4.283669 22.613485 9.006416 +5.278571 23.822237 12.400000 +5.949350 24.331974 36.799999 +5.435990 23.805096 36.799999 +15.000000 28.145529 9.006416 +15.000000 28.000000 36.799999 +12.503440 27.906281 9.006416 +12.531078 27.763401 36.799999 +9.964002 27.142637 9.006416 +7.717805 25.944157 9.006416 +10.019753 27.008211 36.799999 +7.798424 25.822998 36.799999 +5.847947 24.436357 9.006416 +150.000000 28.145529 9.006416 +150.000000 28.000000 36.799999 +145.649994 28.000000 36.799999 +145.601486 28.145529 9.006416 +2.500000 14.550000 36.799999 +2.799973 19.489914 36.799999 +4.815655 23.079550 36.799999 +7.622985 18.217110 36.799999 +7.622985 11.782889 36.799999 +4.815655 6.920451 36.799999 +6.951159 12.410682 36.799999 +2.799973 10.510086 36.799999 +2.007791 14.550000 36.799999 +6.428721 13.198342 36.799999 +6.105684 14.086596 36.799999 +6.000000 15.000000 36.799999 +2.007791 15.450000 36.799999 +2.500000 15.450000 36.799999 +6.951159 17.589317 36.799999 +6.428721 16.801657 36.799999 +6.105684 15.913404 36.799999 +0.075188 13.500000 0.000000 +0.075188 13.500000 40.000000 +0.500000 13.500000 40.000000 +0.500000 13.500000 0.000000 +0.075188 16.500000 40.000000 +0.075188 16.500000 0.000000 +0.500000 16.500000 0.000000 +0.500000 16.500000 40.000000 +0.500000 16.500000 40.000000 +0.500000 16.500000 0.000000 +0.500000 13.500000 0.000000 +0.500000 13.500000 40.000000 +7.171573 17.828426 36.799999 +7.622985 18.217110 36.799999 +6.218148 15.699841 7.400000 +6.153939 15.000000 7.400000 +6.000000 15.000000 36.799999 +6.066779 15.727852 36.799999 +6.423978 16.415714 7.400000 +14.000000 15.000000 36.799999 +13.846061 15.000000 7.400000 +13.933222 15.727852 36.799999 +13.719153 16.472380 36.799999 +13.781852 15.699841 7.400000 +13.347982 17.188839 36.799999 +13.576022 16.415714 7.400000 +13.219135 17.104601 7.400000 +12.828427 17.828426 36.799999 +12.719576 17.719576 7.400000 +12.188839 18.347982 36.799999 +11.472379 18.719152 36.799999 +12.104602 18.219135 7.400000 +11.415714 18.576021 7.400000 +10.727852 18.933222 36.799999 +10.699841 18.781853 7.400000 +9.999892 19.000000 36.799999 +10.000000 18.846060 7.400000 +9.272148 18.933222 36.799999 +9.300159 18.781853 7.400000 +8.527621 18.719152 36.799999 +8.402408 18.667110 36.799999 +8.349664 18.502947 12.400000 +8.584286 18.576021 7.400000 +7.880249 18.240509 12.400000 +7.895398 18.219135 7.400000 +7.791527 18.180706 12.400000 +6.280847 16.472380 36.799999 +6.780865 17.104601 7.400000 +6.652018 17.188839 36.799999 +7.280425 17.719576 7.400000 +11.474958 15.272944 7.400000 +13.219135 17.104601 7.400000 +11.394683 15.552142 7.400000 +12.719576 17.719576 7.400000 +11.255493 15.820815 7.400000 +12.104602 18.219135 7.400000 +11.060660 16.060659 7.400000 +11.415714 18.576021 7.400000 +10.820815 16.255493 7.400000 +10.699841 18.781853 7.400000 +10.552142 16.394682 7.400000 +10.000000 18.846060 7.400000 +10.272944 16.474958 7.400000 +9.300159 18.781853 7.400000 +10.000000 16.500000 7.400000 +8.584286 18.576021 7.400000 +9.727056 16.474958 7.400000 +7.895398 18.219135 7.400000 +9.447858 16.394682 7.400000 +7.280425 17.719576 7.400000 +9.179185 16.255493 7.400000 +6.780865 17.104601 7.400000 +8.939340 16.060659 7.400000 +6.423978 16.415714 7.400000 +8.744507 15.820815 7.400000 +6.218148 15.699841 7.400000 +8.605317 15.552142 7.400000 +6.153939 15.000000 7.400000 +8.525042 15.272944 7.400000 +6.218148 14.300159 7.400000 +8.500000 15.000000 7.400000 +6.423978 13.584286 7.400000 +8.525042 14.727056 7.400000 +6.780865 12.895398 7.400000 +8.605317 14.447858 7.400000 +7.280425 12.280424 7.400000 +8.744507 14.179185 7.400000 +7.895398 11.780865 7.400000 +8.939340 13.939340 7.400000 +8.584286 11.423978 7.400000 +9.179185 13.744507 7.400000 +9.300159 11.218148 7.400000 +9.447858 13.605317 7.400000 +10.000000 11.153939 7.400000 +9.727056 13.525042 7.400000 +10.699841 11.218148 7.400000 +10.000000 13.500000 7.400000 +11.415714 11.423978 7.400000 +10.272944 13.525042 7.400000 +12.104602 11.780865 7.400000 +10.552142 13.605317 7.400000 +12.719576 12.280424 7.400000 +10.820815 13.744507 7.400000 +13.219135 12.895398 7.400000 +11.060660 13.939340 7.400000 +13.576022 13.584286 7.400000 +11.255493 14.179185 7.400000 +13.781852 14.300159 7.400000 +11.394683 14.447858 7.400000 +13.846061 15.000000 7.400000 +11.474958 14.727056 7.400000 +13.781852 15.699841 7.400000 +11.500000 15.000000 7.400000 +13.576022 16.415714 7.400000 +11.255493 15.820815 9.900000 +12.310767 15.427613 9.900000 +11.394683 15.552142 9.900000 +12.350000 15.000000 9.900000 +11.474958 15.272944 9.900000 +12.310767 14.572387 9.900000 +11.500000 15.000000 9.900000 +12.185002 14.134977 9.900000 +11.474958 14.727056 9.900000 +11.966940 13.714057 9.900000 +11.394683 14.447858 9.900000 +11.661701 13.338299 9.900000 +11.255493 14.179185 9.900000 +11.285943 13.033060 9.900000 +11.060660 13.939340 9.900000 +10.865023 12.814998 9.900000 +10.820815 13.744507 9.900000 +10.427613 12.689233 9.900000 +10.552142 13.605317 9.900000 +10.000000 12.650000 9.900000 +10.272944 13.525042 9.900000 +9.572387 12.689233 9.900000 +10.000000 13.500000 9.900000 +9.134977 12.814998 9.900000 +9.727056 13.525042 9.900000 +8.714057 13.033060 9.900000 +9.447858 13.605317 9.900000 +8.338299 13.338299 9.900000 +9.179185 13.744507 9.900000 +8.033060 13.714057 9.900000 +8.939340 13.939340 9.900000 +7.814998 14.134977 9.900000 +8.744507 14.179185 9.900000 +7.689232 14.572387 9.900000 +8.605317 14.447858 9.900000 +7.650000 15.000000 9.900000 +8.525042 14.727056 9.900000 +7.689232 15.427613 9.900000 +8.500000 15.000000 9.900000 +7.814998 15.865023 9.900000 +8.525042 15.272944 9.900000 +8.033060 16.285942 9.900000 +8.605317 15.552142 9.900000 +8.338299 16.661701 9.900000 +8.744507 15.820815 9.900000 +8.714057 16.966940 9.900000 +8.939340 16.060659 9.900000 +9.134977 17.185003 9.900000 +9.179185 16.255493 9.900000 +9.572387 17.310768 9.900000 +9.447858 16.394682 9.900000 +10.000000 17.350000 9.900000 +9.727056 16.474958 9.900000 +10.427613 17.310768 9.900000 +10.000000 16.500000 9.900000 +10.865023 17.185003 9.900000 +10.272944 16.474958 9.900000 +11.285943 16.966940 9.900000 +10.552142 16.394682 9.900000 +11.661701 16.661701 9.900000 +10.820815 16.255493 9.900000 +11.966940 16.285942 9.900000 +11.060660 16.060659 9.900000 +12.185002 15.865023 9.900000 +8.525042 15.272944 7.400000 +8.525042 15.272944 9.900000 +8.500000 15.000000 9.900000 +8.500000 15.000000 7.400000 +11.500000 15.000000 7.400000 +11.500000 15.000000 9.900000 +11.474958 15.272944 7.400000 +11.474958 15.272944 9.900000 +11.394683 15.552142 7.400000 +11.394683 15.552142 9.900000 +11.255493 15.820815 7.400000 +11.060660 16.060659 7.400000 +11.255493 15.820815 9.900000 +10.820815 16.255493 7.400000 +11.060660 16.060659 9.900000 +10.820815 16.255493 9.900000 +10.552142 16.394682 7.400000 +10.552142 16.394682 9.900000 +10.272944 16.474958 7.400000 +10.272944 16.474958 9.900000 +10.000000 16.500000 7.400000 +10.000000 16.500000 9.900000 +9.727056 16.474958 7.400000 +9.727056 16.474958 9.900000 +9.447858 16.394682 7.400000 +9.447858 16.394682 9.900000 +9.179185 16.255493 7.400000 +8.939340 16.060659 7.400000 +9.179185 16.255493 9.900000 +8.939340 16.060659 9.900000 +8.744507 15.820815 7.400000 +8.744507 15.820815 9.900000 +8.605317 15.552142 7.400000 +8.605317 15.552142 9.900000 +10.468424 17.531303 35.599998 +11.641629 17.510986 35.599998 +10.947579 17.393536 35.599998 +12.121321 17.121321 35.599998 +11.408671 17.154661 35.599998 +12.510986 16.641630 35.599998 +11.820292 16.820292 35.599998 +12.789365 16.104284 35.599998 +12.154661 16.408672 35.599998 +12.949916 15.545889 35.599998 +12.393536 15.947579 35.599998 +13.000000 15.000000 35.599998 +12.531303 15.468424 35.599998 +12.949916 14.454111 35.599998 +12.574281 15.000000 35.599998 +12.789365 13.895716 35.599998 +12.531303 14.531576 35.599998 +12.510986 13.358371 35.599998 +12.393536 14.052421 35.599998 +12.121321 12.878679 35.599998 +12.154661 13.591329 35.599998 +11.641629 12.489014 35.599998 +11.820292 13.179708 35.599998 +11.104284 12.210635 35.599998 +11.408671 12.845339 35.599998 +10.545889 12.050084 35.599998 +10.947579 12.606464 35.599998 +10.000000 12.000000 35.599998 +10.468424 12.468697 35.599998 +9.454111 12.050084 35.599998 +10.000000 12.425719 35.599998 +8.895716 12.210635 35.599998 +9.531576 12.468697 35.599998 +8.358371 12.489014 35.599998 +9.052421 12.606464 35.599998 +7.878680 12.878679 35.599998 +8.591329 12.845339 35.599998 +7.489014 13.358371 35.599998 +8.179708 13.179708 35.599998 +7.210635 13.895716 35.599998 +7.845339 13.591329 35.599998 +7.050084 14.454111 35.599998 +7.606464 14.052421 35.599998 +7.000000 15.000000 35.599998 +7.468696 14.531576 35.599998 +7.050084 15.545889 35.599998 +7.425719 15.000000 35.599998 +7.210635 16.104284 35.599998 +7.468696 15.468424 35.599998 +7.489014 16.641630 35.599998 +7.606464 15.947579 35.599998 +7.878680 17.121321 35.599998 +7.845339 16.408672 35.599998 +8.358371 17.510986 35.599998 +8.179708 16.820292 35.599998 +8.895716 17.789366 35.599998 +8.591329 17.154661 35.599998 +9.454111 17.949917 35.599998 +9.052421 17.393536 35.599998 +10.000000 18.000000 35.599998 +9.531576 17.531303 35.599998 +10.545889 17.949917 35.599998 +10.000000 17.574280 35.599998 +11.104284 17.789366 35.599998 +8.895716 17.789366 35.599998 +12.949916 15.545889 35.599998 +13.000000 15.000000 35.599998 +13.026180 15.000000 38.599998 +12.789365 16.104284 35.599998 +12.975659 15.550653 38.599998 +12.813707 16.113920 38.599998 +12.510986 16.641630 35.599998 +12.121321 17.121321 35.599998 +12.532900 16.655956 38.599998 +11.641629 17.510986 35.599998 +12.139832 17.139833 38.599998 +11.104284 17.789366 35.599998 +11.655955 17.532900 38.599998 +10.545889 17.949917 35.599998 +11.113921 17.813707 38.599998 +10.000000 18.000000 35.599998 +10.550653 17.975660 38.599998 +9.454111 17.949917 35.599998 +10.000000 18.026180 38.599998 +7.024340 15.550653 38.599998 +6.973819 15.000000 38.599998 +7.000000 15.000000 35.599998 +7.050084 15.545889 35.599998 +7.186293 16.113920 38.599998 +7.210635 16.104284 35.599998 +7.467101 16.655956 38.599998 +7.489014 16.641630 35.599998 +7.860167 17.139833 38.599998 +7.878680 17.121321 35.599998 +8.344045 17.532900 38.599998 +8.886079 17.813707 38.599998 +8.358371 17.510986 35.599998 +9.449347 17.975660 38.599998 +19.363962 26.413963 28.799999 +19.363962 27.501745 28.799999 +20.236038 27.501745 28.799999 +20.236038 26.413963 28.799999 +19.412001 27.563797 1.276128 +19.411936 27.553051 1.313298 +19.363962 26.413963 28.799999 +19.350000 26.400000 36.799999 +19.363962 27.501745 28.799999 +19.350000 28.000000 36.799999 +19.411873 27.549656 1.349651 +19.398508 28.145529 9.006416 +19.410213 28.900000 2.300000 +19.411261 28.299999 1.700000 +19.412222 28.299999 1.150000 +19.412222 27.749655 1.150000 +19.412216 27.713297 1.153333 +19.412197 27.676107 1.164014 +19.412165 27.640316 1.182533 +19.412119 27.608356 1.208455 +19.412064 27.582378 1.240370 +20.187803 27.676107 1.164014 +20.187784 27.713297 1.153333 +20.250000 28.000000 36.799999 +20.250000 26.400000 36.799999 +20.236038 26.413963 28.799999 +20.201490 28.145529 9.006416 +20.236038 27.501745 28.799999 +20.189787 28.900000 2.300000 +20.188740 28.299999 1.700000 +20.187778 28.299999 1.150000 +20.187778 27.749655 1.150000 +20.188128 27.549656 1.349651 +20.188065 27.553051 1.313298 +20.188000 27.563797 1.276128 +20.187937 27.582378 1.240370 +20.187881 27.608356 1.208455 +20.187836 27.640316 1.182533 +19.350000 26.400000 36.799999 +19.363962 26.413963 28.799999 +20.236038 26.413963 28.799999 +20.250000 26.400000 36.799999 +61.163963 26.413963 28.799999 +61.163963 27.501745 28.799999 +62.036037 27.501745 28.799999 +62.036037 26.413963 28.799999 +61.212002 27.563797 1.276128 +61.211937 27.553051 1.313298 +61.163963 26.413963 28.799999 +61.150002 26.400000 36.799999 +61.163963 27.501745 28.799999 +61.150002 28.000000 36.799999 +61.211872 27.549656 1.349651 +61.198509 28.145529 9.006416 +61.210213 28.900000 2.300000 +61.211262 28.299999 1.700000 +61.212219 28.299999 1.150000 +61.212219 27.749655 1.150000 +61.212215 27.713297 1.153333 +61.212196 27.676107 1.164014 +61.212166 27.640316 1.182533 +61.212120 27.608356 1.208455 +61.212063 27.582378 1.240370 +61.987804 27.676107 1.164014 +61.987785 27.713297 1.153333 +62.049999 28.000000 36.799999 +62.049999 26.400000 36.799999 +62.036037 26.413963 28.799999 +62.001492 28.145529 9.006416 +62.036037 27.501745 28.799999 +61.989784 28.900000 2.300000 +61.988739 28.299999 1.700000 +61.987778 28.299999 1.150000 +61.987778 27.749655 1.150000 +61.988129 27.549656 1.349651 +61.988064 27.553051 1.313298 +61.987999 27.563797 1.276128 +61.987938 27.582378 1.240370 +61.987881 27.608356 1.208455 +61.987835 27.640316 1.182533 +61.163963 26.413963 28.799999 +62.036037 26.413963 28.799999 +62.049999 26.400000 36.799999 +61.150002 26.400000 36.799999 +40.312000 27.563797 1.276128 +40.311935 27.553051 1.313298 +40.262218 26.412218 29.799999 +40.250000 26.400000 36.799999 +40.262218 27.500000 29.799999 +40.250000 28.000000 36.799999 +40.311874 27.549656 1.349651 +40.298508 28.145529 9.006416 +40.310215 28.900000 2.300000 +40.311260 28.299999 1.700000 +40.312222 28.299999 1.150000 +40.312222 27.749655 1.150000 +40.312214 27.713297 1.153333 +40.312195 27.676107 1.164014 +40.312164 27.640316 1.182533 +40.312119 27.608356 1.208455 +40.312065 27.582378 1.240370 +41.087803 27.676107 1.164014 +41.087784 27.713297 1.153333 +41.150002 28.000000 36.799999 +41.150002 26.400000 36.799999 +41.137783 26.412218 29.799999 +41.101490 28.145529 9.006416 +41.137783 27.500000 29.799999 +41.089787 28.900000 2.300000 +41.088737 28.299999 1.700000 +41.087780 28.299999 1.150000 +41.087780 27.749655 1.150000 +41.088127 27.549656 1.349651 +41.088062 27.553051 1.313298 +41.087997 27.563797 1.276128 +41.087936 27.582378 1.240370 +41.087879 27.608356 1.208455 +41.087837 27.640316 1.182533 +40.250000 26.400000 36.799999 +40.262218 26.412218 29.799999 +41.137783 26.412218 29.799999 +41.150002 26.400000 36.799999 +124.687805 27.676107 1.164014 +124.687782 27.713297 1.153333 +124.750000 28.000000 36.799999 +124.750000 26.400000 36.799999 +124.737785 26.412218 29.799999 +124.701492 28.145529 9.006416 +124.737785 27.500000 29.799999 +124.689789 28.900000 2.300000 +124.688736 28.299999 1.700000 +124.687782 28.299999 1.150000 +124.687782 27.749655 1.150000 +124.688126 27.549656 1.349651 +124.688065 27.553051 1.313298 +124.687996 27.563797 1.276128 +124.687935 27.582378 1.240370 +124.687881 27.608356 1.208455 +124.687836 27.640316 1.182533 +123.912003 27.563797 1.276128 +123.911934 27.553051 1.313298 +123.862221 26.412218 29.799999 +123.849998 26.400000 36.799999 +123.862221 27.500000 29.799999 +123.849998 28.000000 36.799999 +123.911873 27.549656 1.349651 +123.898506 28.145529 9.006416 +123.910217 28.900000 2.300000 +123.911263 28.299999 1.700000 +123.912224 28.299999 1.150000 +123.912224 27.749655 1.150000 +123.912216 27.713297 1.153333 +123.912193 27.676107 1.164014 +123.912163 27.640316 1.182533 +123.912117 27.608356 1.208455 +123.912064 27.582378 1.240370 +123.849998 26.400000 36.799999 +123.862221 26.412218 29.799999 +124.737785 26.412218 29.799999 +124.750000 26.400000 36.799999 +103.836037 26.413963 28.799999 +102.963966 26.413963 28.799999 +102.963966 27.501745 28.799999 +103.836037 27.501745 28.799999 +103.787804 27.676107 1.164014 +103.787788 27.713297 1.153333 +103.849998 28.000000 36.799999 +103.849998 26.400000 36.799999 +103.836037 26.413963 28.799999 +103.801491 28.145529 9.006416 +103.836037 27.501745 28.799999 +103.789787 28.900000 2.300000 +103.788742 28.299999 1.700000 +103.787781 28.299999 1.150000 +103.787781 27.749655 1.150000 +103.788124 27.549656 1.349651 +103.788063 27.553051 1.313298 +103.788002 27.563797 1.276128 +103.787933 27.582378 1.240370 +103.787880 27.608356 1.208455 +103.787834 27.640316 1.182533 +103.012001 27.563797 1.276128 +103.011932 27.553051 1.313298 +102.963966 26.413963 28.799999 +102.949997 26.400000 36.799999 +102.963966 27.501745 28.799999 +102.949997 28.000000 36.799999 +103.011871 27.549656 1.349651 +102.998512 28.145529 9.006416 +103.010216 28.900000 2.300000 +103.011261 28.299999 1.700000 +103.012222 28.299999 1.150000 +103.012222 27.749655 1.150000 +103.012215 27.713297 1.153333 +103.012199 27.676107 1.164014 +103.012161 27.640316 1.182533 +103.012115 27.608356 1.208455 +103.012062 27.582378 1.240370 +102.949997 26.400000 36.799999 +102.963966 26.413963 28.799999 +103.836037 26.413963 28.799999 +103.849998 26.400000 36.799999 +144.763962 26.413963 28.799999 +144.763962 27.501745 28.799999 +145.636032 27.501745 28.799999 +145.636032 26.413963 28.799999 +145.587799 27.676107 1.164014 +145.587784 27.713297 1.153333 +145.649994 28.000000 36.799999 +145.649994 26.400000 36.799999 +145.636032 26.413963 28.799999 +145.601486 28.145529 9.006416 +145.636032 27.501745 28.799999 +145.589783 28.900000 2.300000 +145.588745 28.299999 1.700000 +145.587784 28.299999 1.150000 +145.587784 27.749655 1.150000 +145.588135 27.549656 1.349651 +145.588058 27.553051 1.313298 +145.587997 27.563797 1.276128 +145.587936 27.582378 1.240370 +145.587875 27.608356 1.208455 +145.587830 27.640316 1.182533 +144.811996 27.563797 1.276128 +144.811935 27.553051 1.313298 +144.763962 26.413963 28.799999 +144.750000 26.400000 36.799999 +144.763962 27.501745 28.799999 +144.750000 28.000000 36.799999 +144.811874 27.549656 1.349651 +144.798508 28.145529 9.006416 +144.810211 28.900000 2.300000 +144.811264 28.299999 1.700000 +144.812225 28.299999 1.150000 +144.812225 27.749655 1.150000 +144.812210 27.713297 1.153333 +144.812195 27.676107 1.164014 +144.812164 27.640316 1.182533 +144.812119 27.608356 1.208455 +144.812057 27.582378 1.240370 +144.750000 26.400000 36.799999 +144.763962 26.413963 28.799999 +145.636032 26.413963 28.799999 +145.649994 26.400000 36.799999 +82.112000 27.563797 1.276128 +82.111938 27.553051 1.313298 +82.062218 26.412218 29.799999 +82.050003 26.400000 36.799999 +82.062218 27.500000 29.799999 +82.050003 28.000000 36.799999 +82.111870 27.549656 1.349651 +82.098511 28.145529 9.006416 +82.110214 28.900000 2.300000 +82.111259 28.299999 1.700000 +82.112221 28.299999 1.150000 +82.112221 27.749655 1.150000 +82.112213 27.713297 1.153333 +82.112198 27.676107 1.164014 +82.112167 27.640316 1.182533 +82.112122 27.608356 1.208455 +82.112061 27.582378 1.240370 +82.887802 27.676107 1.164014 +82.887787 27.713297 1.153333 +82.949997 28.000000 36.799999 +82.949997 26.400000 36.799999 +82.937782 26.412218 29.799999 +82.901489 28.145529 9.006416 +82.937782 27.500000 29.799999 +82.889786 28.900000 2.300000 +82.888741 28.299999 1.700000 +82.887779 28.299999 1.150000 +82.887779 27.749655 1.150000 +82.888130 27.549656 1.349651 +82.888062 27.553051 1.313298 +82.888000 27.563797 1.276128 +82.887939 27.582378 1.240370 +82.887878 27.608356 1.208455 +82.887833 27.640316 1.182533 +82.050003 26.400000 36.799999 +82.062218 26.412218 29.799999 +82.937782 26.412218 29.799999 +82.949997 26.400000 36.799999 +4.833066 6.695090 12.400000 +7.791527 11.819293 12.400000 +8.349664 11.497053 12.400000 +5.278571 6.177763 12.400000 +7.791527 11.819293 12.400000 +4.833066 6.695090 12.400000 +4.815655 6.920451 36.799999 +7.622985 11.782889 36.799999 +8.402408 11.332890 36.799999 +5.435990 6.194904 36.799999 +5.278571 6.177763 12.400000 +8.349664 11.497053 12.400000 +8.349664 18.502947 12.400000 +7.791527 18.180706 12.400000 +4.833066 23.304911 12.400000 +5.278571 23.822237 12.400000 +8.402408 18.667110 36.799999 +8.349664 18.502947 12.400000 +5.278571 23.822237 12.400000 +5.435990 23.805096 36.799999 +7.791527 18.180706 12.400000 +7.622985 18.217110 36.799999 +4.815655 23.079550 36.799999 +4.833066 23.304911 12.400000 +82.112198 2.323893 1.164014 +82.112213 2.286704 1.153333 +82.050003 2.000000 36.799999 +82.050003 3.600000 36.799999 +82.062218 3.587783 29.799999 +82.098511 1.854472 9.006416 +82.062218 2.500000 29.799999 +82.110214 1.100000 2.300000 +82.111259 1.700000 1.700000 +82.112221 1.700000 1.150000 +82.112221 2.250345 1.150000 +82.111870 2.450345 1.349651 +82.111938 2.446949 1.313298 +82.112000 2.436202 1.276128 +82.112061 2.417621 1.240370 +82.112122 2.391643 1.208455 +82.112167 2.359683 1.182533 +82.888000 2.436202 1.276128 +82.888062 2.446949 1.313298 +82.937782 3.587783 29.799999 +82.949997 3.600000 36.799999 +82.937782 2.500000 29.799999 +82.949997 2.000000 36.799999 +82.888130 2.450345 1.349651 +82.901489 1.854472 9.006416 +82.889786 1.100000 2.300000 +82.888741 1.700000 1.700000 +82.887779 1.700000 1.150000 +82.887779 2.250345 1.150000 +82.887787 2.286704 1.153333 +82.887802 2.323893 1.164014 +82.887833 2.359683 1.182533 +82.887878 2.391643 1.208455 +82.887939 2.417621 1.240370 +19.412197 2.323893 1.164014 +19.412216 2.286704 1.153333 +19.350000 2.000000 36.799999 +19.350000 3.600000 36.799999 +19.363962 3.586037 28.799999 +19.398508 1.854472 9.006416 +19.363962 2.498255 28.799999 +19.410213 1.100000 2.300000 +19.411261 1.700000 1.700000 +19.412222 1.700000 1.150000 +19.412222 2.250345 1.150000 +19.411873 2.450345 1.349651 +19.411936 2.446949 1.313298 +19.412001 2.436202 1.276128 +19.412064 2.417621 1.240370 +19.412119 2.391643 1.208455 +19.412165 2.359683 1.182533 +20.236038 3.586037 28.799999 +20.236038 2.498255 28.799999 +19.363962 2.498255 28.799999 +19.363962 3.586037 28.799999 +20.188000 2.436202 1.276128 +20.188065 2.446949 1.313298 +20.236038 3.586037 28.799999 +20.250000 3.600000 36.799999 +20.236038 2.498255 28.799999 +20.250000 2.000000 36.799999 +20.188128 2.450345 1.349651 +20.201490 1.854472 9.006416 +20.189787 1.100000 2.300000 +20.188740 1.700000 1.700000 +20.187778 1.700000 1.150000 +20.187778 2.250345 1.150000 +20.187784 2.286704 1.153333 +20.187803 2.323893 1.164014 +20.187836 2.359683 1.182533 +20.187881 2.391643 1.208455 +20.187937 2.417621 1.240370 +19.350000 3.600000 36.799999 +20.250000 3.600000 36.799999 +20.236038 3.586037 28.799999 +19.363962 3.586037 28.799999 +61.212196 2.323893 1.164014 +61.212215 2.286704 1.153333 +61.150002 2.000000 36.799999 +61.150002 3.600000 36.799999 +61.163963 3.586037 28.799999 +61.198509 1.854472 9.006416 +61.163963 2.498255 28.799999 +61.210213 1.100000 2.300000 +61.211262 1.700000 1.700000 +61.212219 1.700000 1.150000 +61.212219 2.250345 1.150000 +61.211872 2.450345 1.349651 +61.211937 2.446949 1.313298 +61.212002 2.436202 1.276128 +61.212063 2.417621 1.240370 +61.212120 2.391643 1.208455 +61.212166 2.359683 1.182533 +61.163963 3.586037 28.799999 +62.036037 3.586037 28.799999 +62.036037 2.498255 28.799999 +61.163963 2.498255 28.799999 +61.987999 2.436202 1.276128 +61.988064 2.446949 1.313298 +62.036037 3.586037 28.799999 +62.049999 3.600000 36.799999 +62.036037 2.498255 28.799999 +62.049999 2.000000 36.799999 +61.988129 2.450345 1.349651 +62.001492 1.854472 9.006416 +61.989784 1.100000 2.300000 +61.988739 1.700000 1.700000 +61.987778 1.700000 1.150000 +61.987778 2.250345 1.150000 +61.987785 2.286704 1.153333 +61.987804 2.323893 1.164014 +61.987835 2.359683 1.182533 +61.987881 2.391643 1.208455 +61.987938 2.417621 1.240370 +61.150002 3.600000 36.799999 +62.049999 3.600000 36.799999 +62.036037 3.586037 28.799999 +61.163963 3.586037 28.799999 +40.312195 2.323893 1.164014 +40.312214 2.286704 1.153333 +40.250000 2.000000 36.799999 +40.250000 3.600000 36.799999 +40.262218 3.587783 29.799999 +40.298508 1.854472 9.006416 +40.262218 2.500000 29.799999 +40.310215 1.100000 2.300000 +40.311260 1.700000 1.700000 +40.312222 1.700000 1.150000 +40.312222 2.250345 1.150000 +40.311874 2.450345 1.349651 +40.311935 2.446949 1.313298 +40.312000 2.436202 1.276128 +40.312065 2.417621 1.240370 +40.312119 2.391643 1.208455 +40.312164 2.359683 1.182533 +41.087997 2.436202 1.276128 +41.088062 2.446949 1.313298 +41.137783 3.587783 29.799999 +41.150002 3.600000 36.799999 +41.137783 2.500000 29.799999 +41.150002 2.000000 36.799999 +41.088127 2.450345 1.349651 +41.101490 1.854472 9.006416 +41.089787 1.100000 2.300000 +41.088737 1.700000 1.700000 +41.087780 1.700000 1.150000 +41.087780 2.250345 1.150000 +41.087784 2.286704 1.153333 +41.087803 2.323893 1.164014 +41.087837 2.359683 1.182533 +41.087879 2.391643 1.208455 +41.087936 2.417621 1.240370 +124.687996 2.436202 1.276128 +124.688065 2.446949 1.313298 +124.737785 3.587783 29.799999 +124.750000 3.600000 36.799999 +124.737785 2.500000 29.799999 +124.750000 2.000000 36.799999 +124.688126 2.450345 1.349651 +124.701492 1.854472 9.006416 +124.689789 1.100000 2.300000 +124.688736 1.700000 1.700000 +124.687782 1.700000 1.150000 +124.687782 2.250345 1.150000 +124.687782 2.286704 1.153333 +124.687805 2.323893 1.164014 +124.687836 2.359683 1.182533 +124.687881 2.391643 1.208455 +124.687935 2.417621 1.240370 +123.912193 2.323893 1.164014 +123.912216 2.286704 1.153333 +123.849998 2.000000 36.799999 +123.849998 3.600000 36.799999 +123.862221 3.587783 29.799999 +123.898506 1.854472 9.006416 +123.862221 2.500000 29.799999 +123.910217 1.100000 2.300000 +123.911263 1.700000 1.700000 +123.912224 1.700000 1.150000 +123.912224 2.250345 1.150000 +123.911873 2.450345 1.349651 +123.911934 2.446949 1.313298 +123.912003 2.436202 1.276128 +123.912064 2.417621 1.240370 +123.912117 2.391643 1.208455 +123.912163 2.359683 1.182533 +103.788002 2.436202 1.276128 +103.788063 2.446949 1.313298 +103.836037 3.586037 28.799999 +103.849998 3.600000 36.799999 +103.836037 2.498255 28.799999 +103.849998 2.000000 36.799999 +103.788124 2.450345 1.349651 +103.801491 1.854472 9.006416 +103.789787 1.100000 2.300000 +103.788742 1.700000 1.700000 +103.787781 1.700000 1.150000 +103.787781 2.250345 1.150000 +103.787788 2.286704 1.153333 +103.787804 2.323893 1.164014 +103.787834 2.359683 1.182533 +103.787880 2.391643 1.208455 +103.787933 2.417621 1.240370 +103.836037 3.586037 28.799999 +103.836037 2.498255 28.799999 +102.963966 2.498255 28.799999 +102.963966 3.586037 28.799999 +103.012199 2.323893 1.164014 +103.012215 2.286704 1.153333 +102.949997 2.000000 36.799999 +102.949997 3.600000 36.799999 +102.963966 3.586037 28.799999 +102.998512 1.854472 9.006416 +102.963966 2.498255 28.799999 +103.010216 1.100000 2.300000 +103.011261 1.700000 1.700000 +103.012222 1.700000 1.150000 +103.012222 2.250345 1.150000 +103.011871 2.450345 1.349651 +103.011932 2.446949 1.313298 +103.012001 2.436202 1.276128 +103.012062 2.417621 1.240370 +103.012115 2.391643 1.208455 +103.012161 2.359683 1.182533 +102.949997 3.600000 36.799999 +103.849998 3.600000 36.799999 +103.836037 3.586037 28.799999 +102.963966 3.586037 28.799999 +145.587997 2.436202 1.276128 +145.588058 2.446949 1.313298 +145.636032 3.586037 28.799999 +145.649994 3.600000 36.799999 +145.636032 2.498255 28.799999 +145.649994 2.000000 36.799999 +145.588135 2.450345 1.349651 +145.601486 1.854472 9.006416 +145.589783 1.100000 2.300000 +145.588745 1.700000 1.700000 +145.587784 1.700000 1.150000 +145.587784 2.250345 1.150000 +145.587784 2.286704 1.153333 +145.587799 2.323893 1.164014 +145.587830 2.359683 1.182533 +145.587875 2.391643 1.208455 +145.587936 2.417621 1.240370 +145.636032 3.586037 28.799999 +145.636032 2.498255 28.799999 +144.763962 2.498255 28.799999 +144.763962 3.586037 28.799999 +144.812195 2.323893 1.164014 +144.812210 2.286704 1.153333 +144.750000 2.000000 36.799999 +144.750000 3.600000 36.799999 +144.763962 3.586037 28.799999 +144.798508 1.854472 9.006416 +144.763962 2.498255 28.799999 +144.810211 1.100000 2.300000 +144.811264 1.700000 1.700000 +144.812225 1.700000 1.150000 +144.812225 2.250345 1.150000 +144.811874 2.450345 1.349651 +144.811935 2.446949 1.313298 +144.811996 2.436202 1.276128 +144.812057 2.417621 1.240370 +144.812119 2.391643 1.208455 +144.812164 2.359683 1.182533 +144.750000 3.600000 36.799999 +145.649994 3.600000 36.799999 +145.636032 3.586037 28.799999 +144.763962 3.586037 28.799999 +164.500000 16.500000 40.000000 +164.500000 16.500000 0.000000 +164.924805 16.500000 0.000000 +164.924805 16.500000 40.000000 +164.500000 13.500000 0.000000 +164.500000 13.500000 40.000000 +164.924805 13.500000 40.000000 +164.924805 13.500000 0.000000 +164.500000 13.500000 0.000000 +164.500000 16.500000 0.000000 +164.500000 16.500000 40.000000 +164.500000 13.500000 40.000000 +156.472382 18.719152 36.799999 +156.597595 18.667110 36.799999 +151.218155 15.699841 7.400000 +151.153946 15.000000 7.400000 +151.000000 15.000000 36.799999 +151.066772 15.727852 36.799999 +151.423981 16.415714 7.400000 +151.780869 17.104601 7.400000 +151.280853 16.472380 36.799999 +151.652023 17.188839 36.799999 +152.280426 17.719576 7.400000 +152.895401 18.219135 7.400000 +152.171570 17.828426 36.799999 +153.584290 18.576021 7.400000 +152.811157 18.347982 36.799999 +154.300156 18.781853 7.400000 +153.527618 18.719152 36.799999 +155.000000 18.846060 7.400000 +154.272141 18.933222 36.799999 +159.000000 15.000000 36.799999 +158.846054 15.000000 7.400000 +158.933228 15.727852 36.799999 +158.781845 15.699841 7.400000 +158.719147 16.472380 36.799999 +158.576019 16.415714 7.400000 +158.347977 17.188839 36.799999 +158.219131 17.104601 7.400000 +157.828430 17.828426 36.799999 +157.377014 18.217110 36.799999 +157.208481 18.180706 12.400000 +157.719574 17.719576 7.400000 +157.119751 18.240509 12.400000 +157.104599 18.219135 7.400000 +156.650330 18.502947 12.400000 +154.999557 19.000000 36.799999 +155.699844 18.781853 7.400000 +155.727859 18.933222 36.799999 +156.415710 18.576021 7.400000 +153.605316 15.552142 9.900000 +153.500000 15.000000 9.900000 +153.500000 15.000000 7.400000 +153.525040 15.272944 9.900000 +156.500000 15.000000 7.400000 +156.500000 15.000000 9.900000 +156.474960 15.272944 7.400000 +156.394684 15.552142 7.400000 +156.474960 15.272944 9.900000 +156.255493 15.820815 7.400000 +156.394684 15.552142 9.900000 +156.060654 16.060659 7.400000 +156.255493 15.820815 9.900000 +155.820816 16.255493 7.400000 +156.060654 16.060659 9.900000 +155.552139 16.394682 7.400000 +155.820816 16.255493 9.900000 +155.272949 16.474958 7.400000 +155.552139 16.394682 9.900000 +155.000000 16.500000 7.400000 +155.272949 16.474958 9.900000 +154.727051 16.474958 7.400000 +155.000000 16.500000 9.900000 +154.447861 16.394682 7.400000 +154.727051 16.474958 9.900000 +154.179184 16.255493 7.400000 +154.447861 16.394682 9.900000 +153.939346 16.060659 7.400000 +154.179184 16.255493 9.900000 +153.939346 16.060659 9.900000 +153.744507 15.820815 7.400000 +153.744507 15.820815 9.900000 +153.605316 15.552142 7.400000 +153.525040 15.272944 7.400000 +152.210632 16.104284 35.599998 +152.024338 15.550653 38.599998 +151.973816 15.000000 38.599998 +152.000000 15.000000 35.599998 +152.186295 16.113920 38.599998 +152.050079 15.545889 35.599998 +158.000000 15.000000 35.599998 +158.026184 15.000000 38.599998 +157.949921 15.545889 35.599998 +157.789368 16.104284 35.599998 +157.975662 15.550653 38.599998 +157.813705 16.113920 38.599998 +157.510986 16.641630 35.599998 +157.121323 17.121321 35.599998 +157.532898 16.655956 38.599998 +156.641632 17.510986 35.599998 +157.139832 17.139833 38.599998 +156.655960 17.532900 38.599998 +156.104279 17.789366 35.599998 +156.113922 17.813707 38.599998 +155.545883 17.949917 35.599998 +155.550659 17.975660 38.599998 +155.000000 18.000000 35.599998 +155.000000 18.026180 38.599998 +154.454117 17.949917 35.599998 +154.449341 17.975660 38.599998 +153.895721 17.789366 35.599998 +153.886078 17.813707 38.599998 +153.358368 17.510986 35.599998 +153.344040 17.532900 38.599998 +152.878677 17.121321 35.599998 +152.860168 17.139833 38.599998 +152.489014 16.641630 35.599998 +152.467102 16.655956 38.599998 +157.574280 15.000000 35.599998 +157.789368 13.895716 35.599998 +157.531311 14.531576 35.599998 +157.510986 13.358371 35.599998 +157.393539 14.052421 35.599998 +157.121323 12.878679 35.599998 +157.154663 13.591329 35.599998 +156.641632 12.489014 35.599998 +156.820297 13.179708 35.599998 +156.104279 12.210635 35.599998 +156.408676 12.845339 35.599998 +155.545883 12.050084 35.599998 +155.947586 12.606464 35.599998 +155.000000 12.000000 35.599998 +155.468430 12.468697 35.599998 +154.454117 12.050084 35.599998 +155.000000 12.425719 35.599998 +153.895721 12.210635 35.599998 +154.531570 12.468697 35.599998 +153.358368 12.489014 35.599998 +154.052414 12.606464 35.599998 +152.878677 12.878679 35.599998 +153.591324 12.845339 35.599998 +152.489014 13.358371 35.599998 +153.179703 13.179708 35.599998 +152.210632 13.895716 35.599998 +152.845337 13.591329 35.599998 +152.050079 14.454111 35.599998 +152.606461 14.052421 35.599998 +152.000000 15.000000 35.599998 +152.468689 14.531576 35.599998 +152.050079 15.545889 35.599998 +152.425720 15.000000 35.599998 +152.210632 16.104284 35.599998 +152.468689 15.468424 35.599998 +152.489014 16.641630 35.599998 +152.606461 15.947579 35.599998 +152.878677 17.121321 35.599998 +152.845337 16.408672 35.599998 +153.358368 17.510986 35.599998 +153.179703 16.820292 35.599998 +153.895721 17.789366 35.599998 +153.591324 17.154661 35.599998 +154.454117 17.949917 35.599998 +154.052414 17.393536 35.599998 +155.000000 18.000000 35.599998 +154.531570 17.531303 35.599998 +155.545883 17.949917 35.599998 +155.000000 17.574280 35.599998 +156.104279 17.789366 35.599998 +155.468430 17.531303 35.599998 +156.641632 17.510986 35.599998 +155.947586 17.393536 35.599998 +157.121323 17.121321 35.599998 +156.408676 17.154661 35.599998 +157.510986 16.641630 35.599998 +156.820297 16.820292 35.599998 +157.789368 16.104284 35.599998 +157.154663 16.408672 35.599998 +157.949921 15.545889 35.599998 +157.393539 15.947579 35.599998 +158.000000 15.000000 35.599998 +157.531311 15.468424 35.599998 +157.949921 14.454111 35.599998 +156.650330 18.502947 12.400000 +159.721436 23.822237 12.400000 +160.166931 23.304911 12.400000 +157.208481 18.180706 12.400000 +157.208481 18.180706 12.400000 +160.166931 23.304911 12.400000 +160.184341 23.079550 36.799999 +157.377014 18.217110 36.799999 +156.597595 18.667110 36.799999 +159.564011 23.805096 36.799999 +159.721436 23.822237 12.400000 +156.650330 18.502947 12.400000 +156.650330 11.497053 12.400000 +157.208481 11.819293 12.400000 +160.166931 6.695090 12.400000 +159.721436 6.177763 12.400000 +156.597595 11.332890 36.799999 +156.650330 11.497053 12.400000 +159.721436 6.177763 12.400000 +159.564011 6.194904 36.799999 +157.208481 11.819293 12.400000 +157.377014 11.782889 36.799999 +160.184341 6.920451 36.799999 +160.166931 6.695090 12.400000 +150.000000 28.900000 2.300000 +150.000000 28.145529 9.006416 +145.601486 28.145529 9.006416 +145.589783 28.900000 2.300000 +150.000000 28.145529 9.006416 +150.000000 28.900000 2.300000 +163.588425 17.926525 2.300000 +163.892715 15.450000 2.300000 +163.137817 15.450000 9.006416 +162.790695 20.441336 2.300000 +162.821274 17.901703 9.006416 +161.472992 22.847315 2.300000 +161.978043 20.415836 9.006416 +159.668381 24.986616 2.300000 +160.709442 22.623182 9.006416 +157.471771 26.721033 2.300000 +159.143509 24.444633 9.006416 +157.272293 25.950743 9.006416 +155.024399 27.960148 2.300000 +155.025009 27.147190 9.006416 +152.485077 28.676052 2.300000 +152.484879 27.908535 9.006416 +1.860604 15.401491 9.006416 +12.514922 28.676052 2.300000 +15.000000 28.900000 2.300000 +15.000000 28.145529 9.006416 +9.975604 27.960148 2.300000 +12.487185 27.903126 9.006416 +7.528227 26.721033 2.300000 +9.948710 27.136284 9.006416 +5.331624 24.986616 2.300000 +7.704026 25.934975 9.006416 +3.527003 22.847315 2.300000 +5.836062 24.424816 9.006416 +4.274087 22.599981 9.006416 +2.209305 20.441336 2.300000 +3.010257 20.389894 9.006416 +1.411569 17.926525 2.300000 +2.172476 17.873941 9.006416 +1.104913 15.389777 2.295087 +1.106549 15.450000 2.293451 +1.107286 15.450000 2.300000 +150.000000 1.100000 2.300000 +145.589783 1.100000 2.300000 +145.601486 1.854472 9.006416 +150.000000 1.854472 9.006416 +145.587784 1.700000 1.150000 +144.812225 1.700000 1.150000 +144.812225 2.250345 1.150000 +145.587784 2.250345 1.150000 +144.763962 2.498255 28.799999 +145.636032 2.498255 28.799999 +145.588135 2.450345 1.349651 +144.811874 2.450345 1.349651 +124.687782 1.700000 1.150000 +123.912224 1.700000 1.150000 +123.912224 2.250345 1.150000 +124.687782 2.250345 1.150000 +123.862221 2.500000 29.799999 +124.737785 2.500000 29.799999 +124.688126 2.450345 1.349651 +123.911873 2.450345 1.349651 +103.787781 1.700000 1.150000 +103.012222 1.700000 1.150000 +103.012222 2.250345 1.150000 +103.787781 2.250345 1.150000 +102.963966 2.498255 28.799999 +103.836037 2.498255 28.799999 +103.788124 2.450345 1.349651 +103.011871 2.450345 1.349651 +82.887779 2.250345 1.150000 +82.887779 1.700000 1.150000 +82.112221 1.700000 1.150000 +82.112221 2.250345 1.150000 +82.062218 2.500000 29.799999 +82.937782 2.500000 29.799999 +82.888130 2.450345 1.349651 +82.111870 2.450345 1.349651 +61.987778 1.700000 1.150000 +61.212219 1.700000 1.150000 +61.212219 2.250345 1.150000 +61.987778 2.250345 1.150000 +61.163963 2.498255 28.799999 +62.036037 2.498255 28.799999 +61.988129 2.450345 1.349651 +61.211872 2.450345 1.349651 +41.087780 1.700000 1.150000 +40.312222 1.700000 1.150000 +40.312222 2.250345 1.150000 +41.087780 2.250345 1.150000 +40.262218 2.500000 29.799999 +41.137783 2.500000 29.799999 +41.088127 2.450345 1.349651 +40.311874 2.450345 1.349651 +20.187778 2.250345 1.150000 +20.187778 1.700000 1.150000 +19.412222 1.700000 1.150000 +19.412222 2.250345 1.150000 +19.363962 2.498255 28.799999 +20.236038 2.498255 28.799999 +20.188128 2.450345 1.349651 +19.411873 2.450345 1.349651 +19.412222 28.299999 1.150000 +20.187778 28.299999 1.150000 +20.187778 27.749655 1.150000 +19.412222 27.749655 1.150000 +20.236038 27.501745 28.799999 +19.363962 27.501745 28.799999 +19.411873 27.549656 1.349651 +20.188128 27.549656 1.349651 +40.312222 28.299999 1.150000 +41.087780 28.299999 1.150000 +41.087780 27.749655 1.150000 +40.312222 27.749655 1.150000 +41.137783 27.500000 29.799999 +40.262218 27.500000 29.799999 +40.311874 27.549656 1.349651 +41.088127 27.549656 1.349651 +61.212219 28.299999 1.150000 +61.987778 28.299999 1.150000 +61.987778 27.749655 1.150000 +61.212219 27.749655 1.150000 +62.036037 27.501745 28.799999 +61.163963 27.501745 28.799999 +61.211872 27.549656 1.349651 +61.988129 27.549656 1.349651 +82.112221 28.299999 1.150000 +82.887779 28.299999 1.150000 +82.887779 27.749655 1.150000 +82.112221 27.749655 1.150000 +82.937782 27.500000 29.799999 +82.062218 27.500000 29.799999 +82.111870 27.549656 1.349651 +82.888130 27.549656 1.349651 +103.012222 28.299999 1.150000 +103.787781 28.299999 1.150000 +103.787781 27.749655 1.150000 +103.012222 27.749655 1.150000 +103.836037 27.501745 28.799999 +102.963966 27.501745 28.799999 +103.011871 27.549656 1.349651 +103.788124 27.549656 1.349651 +123.912224 27.749655 1.150000 +123.912224 28.299999 1.150000 +124.687782 28.299999 1.150000 +124.687782 27.749655 1.150000 +124.737785 27.500000 29.799999 +123.862221 27.500000 29.799999 +123.911873 27.549656 1.349651 +124.688126 27.549656 1.349651 +144.812225 27.749655 1.150000 +144.812225 28.299999 1.150000 +145.587784 28.299999 1.150000 +145.587784 27.749655 1.150000 +145.636032 27.501745 28.799999 +144.763962 27.501745 28.799999 +144.811874 27.549656 1.349651 +145.588135 27.549656 1.349651 +162.500000 14.550000 36.799999 +162.500000 15.450000 36.799999 +162.500000 15.450000 1.350000 +162.500000 14.550000 1.350000 +163.300003 15.450000 1.150000 +163.300003 14.550000 1.150000 +162.699997 14.550000 1.150000 +162.699997 15.450000 1.150000 +162.626389 14.550000 1.164042 +162.663605 14.550000 1.153339 +162.699997 14.550000 1.150000 +163.300003 14.550000 1.150000 +162.992203 14.550000 36.799999 +162.500000 14.550000 36.799999 +163.137817 14.550000 9.006416 +163.892715 14.550000 2.300000 +163.892715 14.550000 2.292714 +163.300003 14.550000 1.700000 +162.500000 14.550000 1.350000 +162.503342 14.550000 1.313607 +162.514038 14.550000 1.276381 +162.532608 14.550000 1.240558 +162.558578 14.550000 1.208579 +162.590561 14.550000 1.182601 +162.514038 15.450000 1.276381 +162.503342 15.450000 1.313607 +162.500000 15.450000 1.350000 +162.500000 15.450000 36.799999 +162.992203 15.450000 36.799999 +163.137817 15.450000 9.006416 +163.892715 15.450000 2.300000 +163.892715 15.450000 2.292714 +163.300003 15.450000 1.700000 +163.300003 15.450000 1.150000 +162.699997 15.450000 1.150000 +162.663605 15.450000 1.153339 +162.626389 15.450000 1.164042 +162.590561 15.450000 1.182601 +162.558578 15.450000 1.208579 +162.532608 15.450000 1.240558 +1.700000 14.612221 1.150000 +1.700000 15.387779 1.150000 +2.238128 15.387779 1.150000 +2.238128 14.612221 1.150000 +2.500000 15.450000 36.799999 +2.500000 14.550000 36.799999 +2.438128 14.611873 1.349651 +2.438128 15.388127 1.349651 +2.423985 14.612000 1.276128 +2.434731 14.611936 1.313298 +2.438128 14.611873 1.349651 +2.500000 14.550000 36.799999 +2.007791 14.550000 36.799999 +1.860604 14.598509 9.006416 +1.104913 14.610223 2.295087 +1.700000 14.611261 1.700000 +1.700000 14.612221 1.150000 +2.238128 14.612221 1.150000 +2.274486 14.612215 1.153333 +2.311676 14.612197 1.164014 +2.347466 14.612164 1.182533 +2.379426 14.612119 1.208455 +2.405404 14.612063 1.240370 +2.311676 15.387803 1.164014 +2.274486 15.387785 1.153333 +2.007791 15.450000 36.799999 +2.500000 15.450000 36.799999 +1.860604 15.401491 9.006416 +1.104913 15.389777 2.295087 +1.700000 15.388739 1.700000 +1.700000 15.387779 1.150000 +2.238128 15.387779 1.150000 +2.438128 15.388127 1.349651 +2.434731 15.388064 1.313298 +2.423985 15.388000 1.276128 +2.405404 15.387937 1.240370 +2.379426 15.387881 1.208455 +2.347466 15.387836 1.182533 +91.050003 2.500000 36.799999 +91.949997 2.500000 36.799999 +91.888130 2.438128 1.349651 +91.111870 2.438128 1.349651 +91.887779 2.238128 1.150000 +91.887779 1.700000 1.150000 +91.112221 1.700000 1.150000 +91.112221 2.238128 1.150000 +91.112198 2.311676 1.164014 +91.112213 2.274486 1.153333 +91.050003 2.000000 36.799999 +91.050003 2.500000 36.799999 +91.098511 1.854472 9.006416 +91.110214 1.100000 2.300000 +91.111259 1.700000 1.700000 +91.112221 1.700000 1.150000 +91.112221 2.238128 1.150000 +91.111870 2.438128 1.349651 +91.111938 2.434731 1.313298 +91.112000 2.423985 1.276128 +91.112061 2.405404 1.240370 +91.112122 2.379426 1.208455 +91.112167 2.347466 1.182533 +91.888000 2.423985 1.276128 +91.888062 2.434731 1.313298 +91.888130 2.438128 1.349651 +91.949997 2.500000 36.799999 +91.949997 2.000000 36.799999 +91.901489 1.854472 9.006416 +91.889786 1.100000 2.300000 +91.888741 1.700000 1.700000 +91.887779 1.700000 1.150000 +91.887779 2.238128 1.150000 +91.887787 2.274486 1.153333 +91.887802 2.311676 1.164014 +91.887833 2.347466 1.182533 +91.887878 2.379426 1.208455 +91.887939 2.405404 1.240370 +73.050003 2.500000 36.799999 +73.949997 2.500000 36.799999 +73.888130 2.438128 1.349651 +73.111870 2.438128 1.349651 +73.887779 1.700000 1.150000 +73.112221 1.700000 1.150000 +73.112221 2.238128 1.150000 +73.887779 2.238128 1.150000 +73.112198 2.311676 1.164014 +73.112213 2.274486 1.153333 +73.050003 2.000000 36.799999 +73.050003 2.500000 36.799999 +73.098511 1.854472 9.006416 +73.110214 1.100000 2.300000 +73.111259 1.700000 1.700000 +73.112221 1.700000 1.150000 +73.112221 2.238128 1.150000 +73.111870 2.438128 1.349651 +73.111938 2.434731 1.313298 +73.112000 2.423985 1.276128 +73.112061 2.405404 1.240370 +73.112122 2.379426 1.208455 +73.112167 2.347466 1.182533 +73.888000 2.423985 1.276128 +73.888062 2.434731 1.313298 +73.888130 2.438128 1.349651 +73.949997 2.500000 36.799999 +73.949997 2.000000 36.799999 +73.901489 1.854472 9.006416 +73.889786 1.100000 2.300000 +73.888741 1.700000 1.700000 +73.887779 1.700000 1.150000 +73.887779 2.238128 1.150000 +73.887787 2.274486 1.153333 +73.887802 2.311676 1.164014 +73.887833 2.347466 1.182533 +73.887878 2.379426 1.208455 +73.887939 2.405404 1.240370 +111.949997 2.500000 36.799999 +112.849998 2.500000 36.799999 +112.788124 2.438128 1.349651 +112.011871 2.438128 1.349651 +112.787781 2.238128 1.150000 +112.787781 1.700000 1.150000 +112.012222 1.700000 1.150000 +112.012222 2.238128 1.150000 +112.012199 2.311676 1.164014 +112.012215 2.274486 1.153333 +111.949997 2.000000 36.799999 +111.949997 2.500000 36.799999 +111.998512 1.854472 9.006416 +112.010216 1.100000 2.300000 +112.011261 1.700000 1.700000 +112.012222 1.700000 1.150000 +112.012222 2.238128 1.150000 +112.011871 2.438128 1.349651 +112.011932 2.434731 1.313298 +112.012001 2.423985 1.276128 +112.012062 2.405404 1.240370 +112.012115 2.379426 1.208455 +112.012161 2.347466 1.182533 +112.788002 2.423985 1.276128 +112.788063 2.434731 1.313298 +112.788124 2.438128 1.349651 +112.849998 2.500000 36.799999 +112.849998 2.000000 36.799999 +112.801491 1.854472 9.006416 +112.789787 1.100000 2.300000 +112.788742 1.700000 1.700000 +112.787781 1.700000 1.150000 +112.787781 2.238128 1.150000 +112.787788 2.274486 1.153333 +112.787804 2.311676 1.164014 +112.787834 2.347466 1.182533 +112.787880 2.379426 1.208455 +112.787933 2.405404 1.240370 +52.150002 2.500000 36.799999 +53.049999 2.500000 36.799999 +52.988129 2.438128 1.349651 +52.211872 2.438128 1.349651 +52.987778 1.700000 1.150000 +52.212219 1.700000 1.150000 +52.212219 2.238128 1.150000 +52.987778 2.238128 1.150000 +52.212196 2.311676 1.164014 +52.212215 2.274486 1.153333 +52.150002 2.000000 36.799999 +52.150002 2.500000 36.799999 +52.198509 1.854472 9.006416 +52.210213 1.100000 2.300000 +52.211262 1.700000 1.700000 +52.212219 1.700000 1.150000 +52.212219 2.238128 1.150000 +52.211872 2.438128 1.349651 +52.211937 2.434731 1.313298 +52.212002 2.423985 1.276128 +52.212063 2.405404 1.240370 +52.212120 2.379426 1.208455 +52.212166 2.347466 1.182533 +52.987999 2.423985 1.276128 +52.988064 2.434731 1.313298 +52.988129 2.438128 1.349651 +53.049999 2.500000 36.799999 +53.049999 2.000000 36.799999 +53.001492 1.854472 9.006416 +52.989784 1.100000 2.300000 +52.988739 1.700000 1.700000 +52.987778 1.700000 1.150000 +52.987778 2.238128 1.150000 +52.987785 2.274486 1.153333 +52.987804 2.311676 1.164014 +52.987835 2.347466 1.182533 +52.987881 2.379426 1.208455 +52.987938 2.405404 1.240370 +145.588745 1.700000 1.700000 +144.811264 1.700000 1.700000 +144.812225 1.700000 1.150000 +145.587784 1.700000 1.150000 +123.911263 1.700000 1.700000 +123.912224 1.700000 1.150000 +124.687782 1.700000 1.150000 +124.688736 1.700000 1.700000 +103.011261 1.700000 1.700000 +103.012222 1.700000 1.150000 +103.787781 1.700000 1.150000 +103.788742 1.700000 1.700000 +82.888741 1.700000 1.700000 +82.111259 1.700000 1.700000 +82.112221 1.700000 1.150000 +82.887779 1.700000 1.150000 +61.211262 1.700000 1.700000 +61.212219 1.700000 1.150000 +61.987778 1.700000 1.150000 +61.988739 1.700000 1.700000 +41.088737 1.700000 1.700000 +40.311260 1.700000 1.700000 +40.312222 1.700000 1.150000 +41.087780 1.700000 1.150000 +19.411261 1.700000 1.700000 +19.412222 1.700000 1.150000 +20.187778 1.700000 1.150000 +20.188740 1.700000 1.700000 +20.188740 28.299999 1.700000 +20.187778 28.299999 1.150000 +19.412222 28.299999 1.150000 +19.411261 28.299999 1.700000 +40.311260 28.299999 1.700000 +41.088737 28.299999 1.700000 +41.087780 28.299999 1.150000 +40.312222 28.299999 1.150000 +61.988739 28.299999 1.700000 +61.987778 28.299999 1.150000 +61.212219 28.299999 1.150000 +61.211262 28.299999 1.700000 +82.888741 28.299999 1.700000 +82.887779 28.299999 1.150000 +82.112221 28.299999 1.150000 +82.111259 28.299999 1.700000 +103.788742 28.299999 1.700000 +103.787781 28.299999 1.150000 +103.012222 28.299999 1.150000 +103.011261 28.299999 1.700000 +124.688736 28.299999 1.700000 +124.687782 28.299999 1.150000 +123.912224 28.299999 1.150000 +123.911263 28.299999 1.700000 +145.588745 28.299999 1.700000 +145.587784 28.299999 1.150000 +144.812225 28.299999 1.150000 +144.811264 28.299999 1.700000 +163.892715 14.550000 2.292714 +163.899994 14.550000 2.300000 +163.899994 14.550000 1.150000 +163.892715 14.550000 1.150000 +163.892715 15.450000 2.292714 +163.892715 15.450000 1.150000 +163.899994 15.450000 1.150000 +163.899994 15.450000 2.300000 +163.899994 14.550000 1.150000 +163.899994 15.000000 1.150000 +163.898178 14.774970 1.150000 +163.892715 14.550000 1.150000 +163.899994 15.450000 1.150000 +163.892715 15.450000 1.150000 +163.898178 15.225030 1.150000 +163.899994 15.000000 1.150000 +163.300003 15.450000 1.700000 +163.300003 14.550000 1.700000 +163.300003 14.550000 1.150000 +163.300003 15.450000 1.150000 +163.899994 15.450000 2.300000 +163.899994 15.450000 1.150000 +163.899994 15.000000 1.150000 +163.899994 14.550000 1.150000 +163.899994 14.550000 2.300000 +1.100000 15.450000 1.150000 +1.107286 15.450000 1.150000 +1.107286 15.450000 2.300000 +1.106549 15.450000 2.293451 +1.100000 15.450000 2.300000 +1.107286 14.550000 1.150000 +1.106549 14.550000 2.293451 +1.107286 14.550000 2.300000 +1.100000 14.550000 1.150000 +1.100000 14.550000 2.300000 +1.107286 14.550000 1.150000 +1.100000 15.000000 1.150000 +1.100000 14.550000 1.150000 +1.100000 15.000000 1.150000 +1.107286 15.450000 1.150000 +1.100000 15.450000 1.150000 +1.700000 15.388739 1.700000 +1.700000 15.387779 1.150000 +1.700000 14.612221 1.150000 +1.700000 14.611261 1.700000 +1.100000 14.550000 2.300000 +1.100000 14.550000 1.150000 +1.100000 15.450000 1.150000 +1.100000 15.450000 2.300000 +1.100000 15.000000 1.150000 +112.011261 1.700000 1.700000 +112.012222 1.700000 1.150000 +112.787781 1.700000 1.150000 +112.788742 1.700000 1.700000 +91.111259 1.700000 1.700000 +91.112221 1.700000 1.150000 +91.887779 1.700000 1.150000 +91.888741 1.700000 1.700000 +73.111259 1.700000 1.700000 +73.112221 1.700000 1.150000 +73.887779 1.700000 1.150000 +73.888741 1.700000 1.700000 +52.988739 1.700000 1.700000 +52.211262 1.700000 1.700000 +52.212219 1.700000 1.150000 +52.987778 1.700000 1.150000 +79.753952 14.531552 38.599998 +79.752678 14.538417 37.799961 +80.500000 14.606982 37.799961 +80.500000 14.600000 38.599998 +79.753952 6.468448 38.599998 +80.500000 6.400000 38.599998 +80.500000 6.393018 37.799961 +79.752678 6.461583 37.799961 +78.990814 6.687868 38.599998 +78.988243 6.681376 37.799961 +78.256439 7.068318 38.599998 +78.252617 7.062475 37.799961 +77.600861 7.600862 38.599998 +77.595924 7.595925 37.799961 +77.068321 8.256440 38.599998 +77.062477 8.252620 37.799961 +76.687866 8.990811 38.599998 +76.681374 8.988242 37.799961 +76.468445 9.753951 38.599998 +76.461586 9.752681 37.799961 +76.400002 10.500000 38.599998 +76.468445 11.246049 38.599998 +76.393021 10.500000 37.799961 +76.461586 11.247319 37.799961 +76.687866 12.009189 38.599998 +77.068321 12.743560 38.599998 +76.681374 12.011758 37.799961 +77.062477 12.747380 37.799961 +77.600861 13.399137 38.599998 +77.595924 13.404075 37.799961 +78.256439 13.931682 38.599998 +78.252617 13.937526 37.799961 +78.990814 14.312132 38.599998 +78.988243 14.318624 37.799961 +84.500000 14.606982 37.799961 +84.500000 14.600000 38.599998 +80.500000 14.600000 38.599998 +80.500000 14.606982 37.799961 +88.519836 11.341559 37.799961 +88.606979 10.500000 37.799961 +85.340126 14.513001 38.599998 +84.500000 14.600000 38.599998 +84.500000 14.606982 37.799961 +85.341560 14.519835 37.799961 +86.128426 14.262742 38.599998 +86.823204 13.878274 38.599998 +86.131203 14.269149 37.799961 +87.399139 13.399137 38.599998 +86.827156 13.884027 37.799961 +87.404076 13.404075 37.799961 +87.878273 12.823202 38.599998 +87.884026 12.827158 37.799961 +88.262741 12.128428 38.599998 +88.513000 11.340129 38.599998 +88.269150 12.131200 37.799961 +88.599998 10.500000 38.599998 +80.500000 6.393018 37.799961 +80.500000 6.400000 38.599998 +84.500000 6.400000 38.599998 +84.500000 6.393018 37.799961 +145.300003 24.299999 38.400002 +145.300003 5.700000 38.400002 +145.300003 5.700000 38.599998 +145.300003 24.299999 38.599998 +145.300003 5.700000 38.400002 +104.699997 5.700000 38.400002 +104.699997 5.700000 38.599998 +145.300003 5.700000 38.599998 +104.699997 5.700000 38.400002 +104.699997 24.299999 38.400002 +104.699997 24.299999 38.599998 +104.699997 5.700000 38.599998 +104.699997 24.299999 38.400002 +145.300003 24.299999 38.400002 +145.300003 24.299999 38.599998 +104.699997 24.299999 38.599998 +125.552139 16.394682 38.400002 +145.300003 5.700000 38.400002 +126.474960 14.727056 38.400002 +126.500000 15.000000 38.400002 +126.474960 15.272944 38.400002 +126.394684 15.552142 38.400002 +126.255493 15.820815 38.400002 +126.394684 14.447858 38.400002 +126.255493 14.179185 38.400002 +126.060661 16.060659 38.400002 +125.820816 16.255493 38.400002 +126.060661 13.939340 38.400002 +125.820816 13.744507 38.400002 +104.699997 5.700000 38.400002 +125.552139 13.605317 38.400002 +125.272942 13.525042 38.400002 +125.000000 13.500000 38.400002 +124.727058 13.525042 38.400002 +124.447861 13.605317 38.400002 +124.179184 13.744507 38.400002 +104.699997 24.299999 38.400002 +123.939339 13.939340 38.400002 +123.744507 14.179185 38.400002 +123.605316 14.447858 38.400002 +123.525040 14.727056 38.400002 +123.500000 15.000000 38.400002 +123.525040 15.272944 38.400002 +123.605316 15.552142 38.400002 +123.744507 15.820815 38.400002 +123.939339 16.060659 38.400002 +124.179184 16.255493 38.400002 +145.300003 24.299999 38.400002 +124.447861 16.394682 38.400002 +124.727058 16.474958 38.400002 +125.000000 16.500000 38.400002 +125.272942 16.474958 38.400002 +40.545891 17.949917 38.400002 +42.949917 15.545889 38.400002 +43.000000 15.000000 38.400002 +43.000000 15.000000 38.599998 +42.949917 15.545889 38.599998 +42.789364 16.104284 38.400002 +42.789364 16.104284 38.599998 +42.510986 16.641630 38.400002 +42.121319 17.121321 38.400002 +42.510986 16.641630 38.599998 +41.641628 17.510986 38.400002 +42.121319 17.121321 38.599998 +41.104282 17.789366 38.400002 +41.641628 17.510986 38.599998 +37.000000 15.000000 38.599998 +37.000000 15.000000 38.400002 +37.050083 15.545889 38.599998 +37.050083 15.545889 38.400002 +37.210636 16.104284 38.599998 +37.210636 16.104284 38.400002 +37.489014 16.641630 38.599998 +37.489014 16.641630 38.400002 +37.878681 17.121321 38.599998 +37.878681 17.121321 38.400002 +38.358372 17.510986 38.599998 +38.895718 17.789366 38.599998 +38.358372 17.510986 38.400002 +38.895718 17.789366 38.400002 +39.454109 17.949917 38.599998 +39.454109 17.949917 38.400002 +40.000000 18.000000 38.599998 +40.545891 17.949917 38.599998 +40.000000 18.000000 38.400002 +41.104282 17.789366 38.599998 +41.255493 14.179185 38.400002 +41.641628 12.489014 38.400002 +41.060661 13.939340 38.400002 +41.104282 12.210635 38.400002 +40.820816 13.744507 38.400002 +40.545891 12.050084 38.400002 +40.552143 13.605317 38.400002 +40.000000 12.000000 38.400002 +40.272945 13.525042 38.400002 +39.454109 12.050084 38.400002 +40.000000 13.500000 38.400002 +38.895718 12.210635 38.400002 +39.727055 13.525042 38.400002 +38.358372 12.489014 38.400002 +39.447857 13.605317 38.400002 +37.878681 12.878679 38.400002 +39.179184 13.744507 38.400002 +37.489014 13.358371 38.400002 +38.939339 13.939340 38.400002 +37.210636 13.895716 38.400002 +38.744507 14.179185 38.400002 +37.050083 14.454111 38.400002 +38.605316 14.447858 38.400002 +37.000000 15.000000 38.400002 +38.525043 14.727056 38.400002 +37.050083 15.545889 38.400002 +38.500000 15.000000 38.400002 +37.210636 16.104284 38.400002 +38.525043 15.272944 38.400002 +37.489014 16.641630 38.400002 +38.605316 15.552142 38.400002 +37.878681 17.121321 38.400002 +38.744507 15.820815 38.400002 +38.358372 17.510986 38.400002 +38.939339 16.060659 38.400002 +38.895718 17.789366 38.400002 +39.179184 16.255493 38.400002 +39.454109 17.949917 38.400002 +39.447857 16.394682 38.400002 +40.000000 18.000000 38.400002 +39.727055 16.474958 38.400002 +40.545891 17.949917 38.400002 +40.000000 16.500000 38.400002 +41.104282 17.789366 38.400002 +40.272945 16.474958 38.400002 +41.641628 17.510986 38.400002 +40.552143 16.394682 38.400002 +42.121319 17.121321 38.400002 +40.820816 16.255493 38.400002 +42.510986 16.641630 38.400002 +41.060661 16.060659 38.400002 +42.789364 16.104284 38.400002 +41.255493 15.820815 38.400002 +42.949917 15.545889 38.400002 +41.394684 15.552142 38.400002 +43.000000 15.000000 38.400002 +41.474957 15.272944 38.400002 +42.949917 14.454111 38.400002 +41.500000 15.000000 38.400002 +42.789364 13.895716 38.400002 +41.474957 14.727056 38.400002 +42.510986 13.358371 38.400002 +41.394684 14.447858 38.400002 +42.121319 12.878679 38.400002 +95.395271 -6.000000 8.847635 +95.395271 -6.000000 8.787428 +95.499916 -0.004914 7.459267 +95.500000 0.000000 7.405191 +95.499641 -0.020642 7.514550 +95.499161 -0.047888 7.567793 +95.498497 -0.086025 7.615464 +95.497681 -0.133022 7.654427 +95.496758 -0.185782 7.682597 +95.495796 -0.240782 7.699288 +95.500000 0.000000 8.952365 +95.494858 -0.294764 7.705145 +95.412422 -5.017452 7.787580 +95.409279 -5.197392 7.807103 +95.406082 -5.380726 7.862740 +95.403008 -5.556592 7.956642 +95.400276 -5.713251 8.086518 +95.398056 -5.840373 8.245420 +95.396469 -5.931192 8.422898 +95.395554 -5.983620 8.607175 +69.587578 -5.017452 14.212420 +95.412422 -5.017452 14.212420 +95.494858 -0.294764 14.294855 +69.505142 -0.294764 14.294855 +69.604729 -6.000000 13.152365 +69.604729 -6.000000 13.212572 +69.500084 -0.004914 14.540733 +69.500000 0.000000 14.594810 +69.500359 -0.020642 14.485450 +69.500839 -0.047888 14.432207 +69.501503 -0.086025 14.384537 +69.502319 -0.133022 14.345573 +69.503242 -0.185782 14.317403 +69.504204 -0.240782 14.300712 +69.500000 0.000000 13.047635 +69.505142 -0.294764 14.294855 +69.587578 -5.017452 14.212420 +69.590721 -5.197392 14.192897 +69.593918 -5.380726 14.137260 +69.596992 -5.556592 14.043358 +69.599724 -5.713251 13.913482 +69.601944 -5.840373 13.754580 +69.603531 -5.931192 13.577102 +69.604446 -5.983620 13.392825 +95.494858 -0.294764 7.705145 +95.412422 -5.017452 7.787580 +69.587578 -5.017452 7.787580 +69.505142 -0.294764 7.705145 +77.395271 -6.000000 9.095224 +76.552368 -6.000000 12.852411 +82.104729 -6.000000 12.904776 +82.895271 -6.000000 9.095224 +69.604729 -6.000000 13.212572 +69.604729 -6.000000 13.152365 +88.747589 -6.000000 13.152365 +95.395271 -6.000000 13.152365 +95.395271 -6.000000 8.787428 +95.395271 -6.000000 8.847635 +76.252411 -6.000000 8.847635 +69.604729 -6.000000 8.847635 +76.547356 -6.000000 12.906998 +76.552368 -6.000000 9.147589 +77.400276 -6.000000 9.040637 +77.395271 -6.000000 12.904776 +82.104729 -6.000000 9.095224 +82.900276 -6.000000 9.040637 +82.895271 -6.000000 12.904776 +82.099724 -6.000000 12.959363 +76.531303 -6.000000 12.962831 +76.547356 -6.000000 9.093002 +77.416328 -6.000000 8.984804 +77.400276 -6.000000 12.959363 +82.900276 -6.000000 12.959363 +82.083672 -6.000000 13.015196 +82.099724 -6.000000 9.040637 +82.916328 -6.000000 8.984804 +76.503471 -6.000000 13.016557 +76.531303 -6.000000 9.037169 +77.444160 -6.000000 8.931078 +77.416328 -6.000000 13.015196 +82.083672 -6.000000 8.984804 +82.944160 -6.000000 8.931078 +82.916328 -6.000000 13.015196 +82.055840 -6.000000 13.068922 +76.464516 -6.000000 13.064516 +76.503471 -6.000000 8.983443 +77.483116 -6.000000 8.883119 +77.444160 -6.000000 13.068922 +82.944160 -6.000000 13.068922 +82.016884 -6.000000 13.116881 +82.055840 -6.000000 8.931078 +82.983116 -6.000000 8.883119 +76.416557 -6.000000 13.103475 +76.464516 -6.000000 8.935484 +82.016884 -6.000000 8.883119 +83.031075 -6.000000 8.844161 +82.983116 -6.000000 13.116881 +81.968925 -6.000000 13.155839 +77.531075 -6.000000 8.844161 +77.483116 -6.000000 13.116881 +76.362831 -6.000000 13.131306 +76.416557 -6.000000 8.896525 +83.031075 -6.000000 13.155839 +81.915199 -6.000000 13.183671 +81.968925 -6.000000 8.844161 +83.084801 -6.000000 8.816329 +77.584801 -6.000000 8.816329 +77.531075 -6.000000 13.155839 +76.306999 -6.000000 13.147358 +76.362831 -6.000000 8.868694 +81.915199 -6.000000 8.816329 +83.140640 -6.000000 8.800277 +83.084801 -6.000000 13.183671 +81.859360 -6.000000 13.199723 +77.640640 -6.000000 8.800277 +77.584801 -6.000000 13.183671 +76.252411 -6.000000 13.152365 +76.306999 -6.000000 8.852642 +83.140640 -6.000000 13.199723 +81.804779 -6.000000 13.204730 +81.859360 -6.000000 8.800277 +83.195221 -6.000000 8.795270 +77.695221 -6.000000 8.795270 +77.640640 -6.000000 13.199723 +95.395271 -6.000000 13.212572 +77.695221 -6.000000 13.204730 +83.195221 -6.000000 13.204730 +87.304779 -6.000000 13.204730 +88.693001 -6.000000 13.147358 +87.359360 -6.000000 13.199723 +88.637169 -6.000000 13.131306 +87.415199 -6.000000 13.183671 +88.583443 -6.000000 13.103475 +87.468925 -6.000000 13.155839 +88.535484 -6.000000 13.064516 +87.516884 -6.000000 13.116881 +88.496529 -6.000000 13.016557 +87.555840 -6.000000 13.068922 +88.468697 -6.000000 12.962831 +87.583672 -6.000000 13.015196 +88.452644 -6.000000 12.906998 +87.599724 -6.000000 12.959363 +88.447632 -6.000000 12.852411 +87.604729 -6.000000 12.904776 +88.447632 -6.000000 9.147589 +88.452644 -6.000000 9.093002 +87.604729 -6.000000 9.095224 +88.468697 -6.000000 9.037169 +87.599724 -6.000000 9.040637 +88.496529 -6.000000 8.983443 +87.583672 -6.000000 8.984804 +88.535484 -6.000000 8.935484 +87.555840 -6.000000 8.931078 +88.583443 -6.000000 8.896525 +87.516884 -6.000000 8.883119 +88.637169 -6.000000 8.868694 +87.468925 -6.000000 8.844161 +88.693001 -6.000000 8.852642 +87.415199 -6.000000 8.816329 +88.747589 -6.000000 8.847635 +87.359360 -6.000000 8.800277 +69.604729 -6.000000 8.787428 +87.304779 -6.000000 8.795270 +81.804779 -6.000000 8.795270 +69.500000 0.000000 13.047635 +70.400047 0.000000 13.047635 +76.200043 -3.000000 13.100000 +76.252411 -6.000000 13.152365 +70.452408 -3.000000 13.100000 +69.604729 -6.000000 13.152365 +76.500000 -3.000000 9.199954 +76.552368 -6.000000 9.147589 +76.552368 -6.000000 12.852411 +76.500000 -3.000000 12.800046 +70.452408 -3.000000 8.900000 +70.400047 0.000000 8.952365 +69.604729 -6.000000 8.847635 +76.252411 -6.000000 8.847635 +76.200043 -3.000000 8.900000 +69.500000 0.000000 8.952365 +76.478943 -3.000000 9.089534 +76.494995 -3.000000 9.145368 +76.200043 -3.000000 13.100000 +70.452408 -3.000000 13.100000 +70.506996 -3.000000 8.905007 +70.452408 -3.000000 8.900000 +70.562828 -3.000000 8.921060 +70.506996 -3.000000 13.094993 +70.562828 -3.000000 13.078940 +70.616554 -3.000000 8.948891 +70.664513 -3.000000 8.987849 +70.616554 -3.000000 13.051109 +70.664513 -3.000000 13.012151 +70.703476 -3.000000 9.035809 +70.752365 -3.000000 12.800046 +72.756172 -3.000000 11.294476 +72.713356 -3.000000 11.145571 +72.699997 -3.000000 11.000000 +72.713356 -3.000000 10.854429 +70.731308 -3.000000 9.089534 +70.703476 -3.000000 12.964191 +72.756172 -3.000000 10.705524 +70.731308 -3.000000 12.910466 +70.747360 -3.000000 9.145368 +72.830406 -3.000000 10.562232 +70.752365 -3.000000 9.199954 +70.747360 -3.000000 12.854632 +72.934311 -3.000000 10.434315 +72.830406 -3.000000 11.437768 +72.934311 -3.000000 11.565685 +73.062233 -3.000000 10.330403 +73.205521 -3.000000 10.256169 +73.354431 -3.000000 10.213356 +73.500000 -3.000000 10.200000 +73.645569 -3.000000 10.213356 +73.794479 -3.000000 10.256169 +73.937767 -3.000000 10.330403 +74.065689 -3.000000 10.434315 +74.169594 -3.000000 10.562232 +74.243828 -3.000000 10.705524 +74.286644 -3.000000 10.854429 +73.062233 -3.000000 11.669597 +73.205521 -3.000000 11.743831 +73.354431 -3.000000 11.786644 +73.500000 -3.000000 11.800000 +73.645569 -3.000000 11.786644 +73.794479 -3.000000 11.743831 +73.937767 -3.000000 11.669597 +74.065689 -3.000000 11.565685 +74.169594 -3.000000 11.437768 +74.243828 -3.000000 11.294476 +76.254631 -3.000000 13.094993 +76.310463 -3.000000 13.078940 +76.364189 -3.000000 13.051109 +76.412148 -3.000000 13.012151 +76.451111 -3.000000 12.964191 +76.478943 -3.000000 12.910466 +76.494995 -3.000000 12.854632 +76.500000 -3.000000 12.800046 +76.500000 -3.000000 9.199954 +74.286644 -3.000000 11.145571 +74.300003 -3.000000 11.000000 +76.200043 -3.000000 8.900000 +76.254631 -3.000000 8.905007 +76.310463 -3.000000 8.921060 +76.364189 -3.000000 8.948891 +76.412148 -3.000000 8.987849 +76.451111 -3.000000 9.035809 +95.500000 0.000000 8.952365 +94.599998 0.000000 8.952365 +88.799957 -3.000000 8.900000 +88.747589 -6.000000 8.847635 +94.599998 -3.000000 8.900000 +95.395271 -6.000000 8.847635 +88.447632 -6.000000 12.852411 +88.447632 -6.000000 9.147589 +88.500000 -3.000000 9.199954 +88.500000 -3.000000 12.800046 +94.599998 -3.000000 13.100000 +94.599998 0.000000 13.047635 +95.395271 -6.000000 13.152365 +88.747589 -6.000000 13.152365 +88.799957 -3.000000 13.100000 +95.500000 0.000000 13.047635 +88.689537 -3.000000 8.921060 +88.745369 -3.000000 8.905007 +88.799957 -3.000000 8.900000 +94.599998 -3.000000 8.900000 +94.545410 -3.000000 13.094991 +94.599998 -3.000000 13.100000 +94.489571 -3.000000 13.078934 +94.545410 -3.000000 8.905009 +94.489571 -3.000000 8.921066 +94.435837 -3.000000 13.051091 +94.387871 -3.000000 13.012118 +94.435837 -3.000000 8.948909 +94.387871 -3.000000 8.987882 +94.348900 -3.000000 12.964142 +94.300003 -3.000000 9.200046 +92.169594 -3.000000 11.437768 +92.243828 -3.000000 11.294476 +92.286644 -3.000000 11.145571 +92.300003 -3.000000 11.000000 +94.321060 -3.000000 12.910399 +94.348900 -3.000000 9.035858 +92.286644 -3.000000 10.854429 +94.321060 -3.000000 9.089601 +94.305008 -3.000000 12.854551 +92.243828 -3.000000 10.705524 +94.300003 -3.000000 12.799954 +94.305008 -3.000000 9.145449 +92.169594 -3.000000 10.562232 +92.065689 -3.000000 11.565685 +91.937767 -3.000000 11.669597 +92.065689 -3.000000 10.434315 +91.937767 -3.000000 10.330403 +91.794479 -3.000000 10.256169 +91.645569 -3.000000 10.213356 +91.500000 -3.000000 10.200000 +91.354431 -3.000000 10.213356 +91.205521 -3.000000 10.256169 +91.062233 -3.000000 10.330403 +90.934311 -3.000000 10.434315 +90.830406 -3.000000 10.562232 +90.756172 -3.000000 10.705524 +91.794479 -3.000000 11.743831 +91.645569 -3.000000 11.786644 +91.500000 -3.000000 11.800000 +91.354431 -3.000000 11.786644 +91.205521 -3.000000 11.743831 +91.062233 -3.000000 11.669597 +90.934311 -3.000000 11.565685 +90.830406 -3.000000 11.437768 +90.756172 -3.000000 11.294476 +90.713356 -3.000000 11.145571 +88.799957 -3.000000 13.100000 +88.745369 -3.000000 13.094993 +88.689537 -3.000000 13.078940 +88.635811 -3.000000 13.051109 +88.587852 -3.000000 13.012151 +88.548889 -3.000000 12.964191 +88.521057 -3.000000 12.910466 +88.505005 -3.000000 12.854632 +88.500000 -3.000000 12.800046 +90.699997 -3.000000 11.000000 +90.713356 -3.000000 10.854429 +88.500000 -3.000000 9.199954 +88.505005 -3.000000 9.145368 +88.521057 -3.000000 9.089534 +88.548889 -3.000000 9.035809 +88.587852 -3.000000 8.987849 +88.635811 -3.000000 8.948891 +77.695221 -6.000000 13.204730 +77.799957 0.000000 13.100000 +81.700043 0.000000 13.100000 +81.804779 -6.000000 13.204730 +82.104729 -6.000000 12.904776 +82.000000 0.000000 12.800046 +82.000000 0.000000 9.199954 +82.104729 -6.000000 9.095224 +77.799957 0.000000 8.900000 +77.695221 -6.000000 8.795270 +81.804779 -6.000000 8.795270 +81.700043 0.000000 8.900000 +77.395271 -6.000000 12.904776 +77.395271 -6.000000 9.095224 +77.500000 0.000000 9.199954 +77.500000 0.000000 12.800046 +83.195221 -6.000000 13.204730 +83.299957 0.000000 13.100000 +87.200043 0.000000 13.100000 +87.304779 -6.000000 13.204730 +87.604729 -6.000000 9.095224 +87.604729 -6.000000 12.904776 +87.500000 0.000000 12.800046 +87.500000 0.000000 9.199954 +83.299957 0.000000 8.900000 +83.195221 -6.000000 8.795270 +87.304779 -6.000000 8.795270 +87.200043 0.000000 8.900000 +82.895271 -6.000000 12.904776 +82.895271 -6.000000 9.095224 +83.000000 0.000000 9.199954 +83.000000 0.000000 12.800046 +73.645569 1.000000 11.786644 +73.500000 1.000000 11.800000 +73.500000 1.480688 11.000000 +73.500000 1.000000 10.200000 +73.645569 1.000000 10.213356 +73.794479 1.000000 10.256169 +73.937767 1.000000 10.330403 +74.065689 1.000000 10.434315 +74.169594 1.000000 10.562232 +74.243828 1.000000 10.705524 +74.286644 1.000000 10.854429 +74.300003 1.000000 11.000000 +74.286644 1.000000 11.145571 +74.243828 1.000000 11.294476 +74.169594 1.000000 11.437768 +74.065689 1.000000 11.565685 +73.937767 1.000000 11.669597 +73.794479 1.000000 11.743831 +73.500000 1.480688 11.000000 +73.500000 1.480688 11.000000 +73.500000 1.480688 11.000000 +73.500000 1.480688 11.000000 +73.500000 1.480688 11.000000 +73.500000 1.480688 11.000000 +73.500000 1.480688 11.000000 +73.500000 1.480688 11.000000 +73.500000 1.480688 11.000000 +73.500000 1.480688 11.000000 +73.500000 1.480688 11.000000 +73.500000 1.480688 11.000000 +73.500000 1.480688 11.000000 +73.500000 1.480688 11.000000 +73.500000 1.480688 11.000000 +73.500000 1.480688 11.000000 +74.243828 -3.000000 10.705524 +73.645569 1.000000 10.213356 +73.500000 1.000000 10.200000 +73.500000 -3.000000 10.200000 +73.645569 -3.000000 10.213356 +73.794479 1.000000 10.256169 +73.794479 -3.000000 10.256169 +73.937767 1.000000 10.330403 +73.937767 -3.000000 10.330403 +74.065689 1.000000 10.434315 +74.065689 -3.000000 10.434315 +74.169594 1.000000 10.562232 +74.243828 1.000000 10.705524 +74.169594 -3.000000 10.562232 +73.500000 -3.000000 11.800000 +73.500000 1.000000 11.800000 +73.645569 -3.000000 11.786644 +73.794479 -3.000000 11.743831 +73.645569 1.000000 11.786644 +73.794479 1.000000 11.743831 +73.937767 -3.000000 11.669597 +73.937767 1.000000 11.669597 +74.065689 -3.000000 11.565685 +74.065689 1.000000 11.565685 +74.169594 -3.000000 11.437768 +74.169594 1.000000 11.437768 +74.243828 -3.000000 11.294476 +74.243828 1.000000 11.294476 +74.286644 -3.000000 11.145571 +74.286644 1.000000 11.145571 +74.300003 -3.000000 11.000000 +74.286644 -3.000000 10.854429 +74.300003 1.000000 11.000000 +74.286644 1.000000 10.854429 +91.500000 1.000000 11.800000 +91.645569 1.000000 11.786644 +91.794479 1.000000 11.743831 +91.500000 1.480688 11.000000 +91.500000 1.000000 10.200000 +91.645569 1.000000 10.213356 +91.794479 1.000000 10.256169 +91.937767 1.000000 10.330403 +92.065689 1.000000 10.434315 +92.169594 1.000000 10.562232 +92.243828 1.000000 10.705524 +92.286644 1.000000 10.854429 +92.300003 1.000000 11.000000 +92.286644 1.000000 11.145571 +92.243828 1.000000 11.294476 +92.169594 1.000000 11.437768 +92.065689 1.000000 11.565685 +91.937767 1.000000 11.669597 +91.500000 1.480688 11.000000 +91.500000 1.480688 11.000000 +91.500000 1.480688 11.000000 +91.500000 1.480688 11.000000 +91.500000 1.480688 11.000000 +91.500000 1.480688 11.000000 +91.500000 1.480688 11.000000 +91.500000 1.480688 11.000000 +91.500000 1.480688 11.000000 +91.500000 1.480688 11.000000 +91.500000 1.480688 11.000000 +91.500000 1.480688 11.000000 +91.500000 1.480688 11.000000 +91.500000 1.480688 11.000000 +91.500000 1.480688 11.000000 +91.500000 1.480688 11.000000 +92.065689 1.000000 11.565685 +91.500000 -3.000000 11.800000 +91.500000 1.000000 11.800000 +91.645569 -3.000000 11.786644 +91.645569 1.000000 11.786644 +91.794479 -3.000000 11.743831 +91.794479 1.000000 11.743831 +91.937767 -3.000000 11.669597 +92.065689 -3.000000 11.565685 +91.937767 1.000000 11.669597 +91.500000 1.000000 10.200000 +91.500000 -3.000000 10.200000 +91.645569 1.000000 10.213356 +91.645569 -3.000000 10.213356 +91.794479 1.000000 10.256169 +91.794479 -3.000000 10.256169 +91.937767 1.000000 10.330403 +91.937767 -3.000000 10.330403 +92.065689 1.000000 10.434315 +92.065689 -3.000000 10.434315 +92.169594 1.000000 10.562232 +92.169594 -3.000000 10.562232 +92.243828 1.000000 10.705524 +92.243828 -3.000000 10.705524 +92.286644 1.000000 10.854429 +92.286644 -3.000000 10.854429 +92.300003 1.000000 11.000000 +92.300003 -3.000000 11.000000 +92.286644 1.000000 11.145571 +92.286644 -3.000000 11.145571 +92.243828 1.000000 11.294476 +92.243828 -3.000000 11.294476 +92.169594 1.000000 11.437768 +92.169594 -3.000000 11.437768 +70.699997 0.000000 9.252319 +70.752365 -3.000000 9.199954 +70.752365 -3.000000 12.800046 +70.699997 0.000000 12.747681 +81.810463 0.000000 13.078940 +81.754631 0.000000 13.094993 +77.548889 0.000000 12.964191 +77.521057 0.000000 12.910466 +77.587852 0.000000 13.012151 +77.635811 0.000000 13.051109 +77.505005 0.000000 12.854632 +77.689537 0.000000 13.078940 +77.745369 0.000000 13.094993 +77.799957 0.000000 13.100000 +77.500000 0.000000 12.800046 +81.700043 0.000000 13.100000 +77.500000 0.000000 9.199954 +77.505005 0.000000 9.145368 +77.521057 0.000000 9.089534 +77.548889 0.000000 9.035809 +77.587852 0.000000 8.987849 +77.635811 0.000000 8.948891 +77.689537 0.000000 8.921060 +77.745369 0.000000 8.905007 +77.799957 0.000000 8.900000 +81.700043 0.000000 8.900000 +81.754631 0.000000 8.905007 +81.810463 0.000000 8.921060 +81.864189 0.000000 8.948891 +81.912148 0.000000 8.987849 +81.951111 0.000000 9.035809 +81.978943 0.000000 9.089534 +81.994995 0.000000 9.145368 +82.000000 0.000000 9.199954 +82.000000 0.000000 12.800046 +81.994995 0.000000 12.854632 +81.978943 0.000000 12.910466 +81.951111 0.000000 12.964191 +81.912148 0.000000 13.012151 +81.864189 0.000000 13.051109 +87.310463 0.000000 13.078940 +87.254631 0.000000 13.094993 +83.048889 0.000000 12.964191 +83.021057 0.000000 12.910466 +83.087852 0.000000 13.012151 +83.135811 0.000000 13.051109 +83.005005 0.000000 12.854632 +83.189537 0.000000 13.078940 +83.245369 0.000000 13.094993 +83.299957 0.000000 13.100000 +83.000000 0.000000 12.800046 +87.200043 0.000000 13.100000 +83.000000 0.000000 9.199954 +83.005005 0.000000 9.145368 +83.021057 0.000000 9.089534 +83.048889 0.000000 9.035809 +83.087852 0.000000 8.987849 +83.135811 0.000000 8.948891 +83.189537 0.000000 8.921060 +83.245369 0.000000 8.905007 +83.299957 0.000000 8.900000 +87.200043 0.000000 8.900000 +87.254631 0.000000 8.905007 +87.310463 0.000000 8.921060 +87.364189 0.000000 8.948891 +87.412148 0.000000 8.987849 +87.451111 0.000000 9.035809 +87.478943 0.000000 9.089534 +87.494995 0.000000 9.145368 +87.500000 0.000000 9.199954 +87.500000 0.000000 12.800046 +87.494995 0.000000 12.854632 +87.478943 0.000000 12.910466 +87.451111 0.000000 12.964191 +87.412148 0.000000 13.012151 +87.364189 0.000000 13.051109 +94.300003 0.000000 12.747589 +94.300003 -3.000000 12.799954 +94.300003 -3.000000 9.200046 +94.300003 0.000000 9.252411 +140.970947 3.979056 24.799999 +140.970947 1.937168 24.799999 +140.949997 2.000000 36.799999 +140.949997 4.000000 36.799999 +140.970947 3.979056 24.799999 +140.949997 4.000000 36.799999 +141.750000 4.000000 36.799999 +141.729050 3.979056 24.799999 +141.729050 3.979056 24.799999 +141.750000 4.000000 36.799999 +141.750000 2.000000 36.799999 +141.729050 1.937168 24.799999 +140.970947 1.937168 24.799999 +140.970947 3.979056 24.799999 +141.729050 3.979056 24.799999 +141.729050 1.937168 24.799999 +116.849998 2.200000 5.221214 +119.849998 2.200000 5.221214 +119.849998 1.990889 5.221214 +116.849998 1.990889 5.221214 +119.849998 2.200000 5.778786 +119.849998 2.200000 5.221214 +116.849998 2.200000 5.221214 +116.849998 2.200000 5.778786 +119.849998 1.990889 5.778786 +119.849998 2.200000 5.778786 +116.849998 2.200000 5.778786 +116.849998 1.990889 5.778786 +119.849998 1.990889 5.778786 +116.849998 1.990889 5.778786 +116.849998 1.511675 5.959337 +119.849998 1.511675 5.959337 +119.849998 1.990889 5.221214 +119.849998 1.403750 5.000000 +116.849998 1.403750 5.000000 +116.849998 1.990889 5.221214 +119.849998 1.990889 5.221214 +119.849998 2.200000 5.221214 +119.849998 1.511675 5.959337 +119.849998 1.403750 5.000000 +119.849998 1.990889 5.778786 +119.849998 2.200000 5.778786 +116.849998 2.200000 5.778786 +116.849998 2.200000 5.221214 +116.849998 1.990889 5.221214 +116.849998 1.403750 5.000000 +116.849998 1.511675 5.959337 +116.849998 1.990889 5.778786 +98.949997 2.200000 5.221214 +98.949997 1.990889 5.221214 +95.949997 1.990889 5.221214 +95.949997 2.200000 5.221214 +98.949997 2.200000 5.778786 +98.949997 2.200000 5.221214 +95.949997 2.200000 5.221214 +95.949997 2.200000 5.778786 +98.949997 1.990889 5.778786 +98.949997 2.200000 5.778786 +95.949997 2.200000 5.778786 +95.949997 1.990889 5.778786 +98.949997 1.990889 5.778786 +95.949997 1.990889 5.778786 +95.949997 1.511675 5.959337 +98.949997 1.511675 5.959337 +98.949997 1.990889 5.221214 +98.949997 1.403750 5.000000 +95.949997 1.403750 5.000000 +95.949997 1.990889 5.221214 +98.949997 2.200000 5.221214 +98.949997 2.200000 5.778786 +98.949997 1.511675 5.959337 +98.949997 1.403750 5.000000 +98.949997 1.990889 5.778786 +98.949997 1.990889 5.221214 +95.949997 2.200000 5.778786 +95.949997 2.200000 5.221214 +95.949997 1.990889 5.221214 +95.949997 1.403750 5.000000 +95.949997 1.511675 5.959337 +95.949997 1.990889 5.778786 +123.862221 26.412218 29.799999 +123.862221 27.500000 29.799999 +124.737785 27.500000 29.799999 +124.737785 26.412218 29.799999 +123.862221 3.587783 29.799999 +124.737785 3.587783 29.799999 +124.737785 2.500000 29.799999 +123.862221 2.500000 29.799999 +82.062218 26.412218 29.799999 +82.062218 27.500000 29.799999 +82.937782 27.500000 29.799999 +82.937782 26.412218 29.799999 +82.062218 3.587783 29.799999 +82.937782 3.587783 29.799999 +82.937782 2.500000 29.799999 +82.062218 2.500000 29.799999 +40.262218 26.412218 29.799999 +40.262218 27.500000 29.799999 +41.137783 27.500000 29.799999 +41.137783 26.412218 29.799999 +40.262218 3.587783 29.799999 +41.137783 3.587783 29.799999 +41.137783 2.500000 29.799999 +40.262218 2.500000 29.799999 +112.349998 28.596251 5.000000 +115.349998 28.596251 5.000000 +115.349998 28.009111 5.221214 +112.349998 28.009111 5.221214 +115.349998 28.009111 5.778786 +115.349998 28.488325 5.959337 +112.349998 28.488325 5.959337 +112.349998 28.009111 5.778786 +115.349998 27.799999 5.778786 +115.349998 28.009111 5.778786 +112.349998 28.009111 5.778786 +112.349998 27.799999 5.778786 +112.349998 27.799999 5.221214 +115.349998 27.799999 5.221214 +115.349998 27.799999 5.778786 +112.349998 27.799999 5.778786 +115.349998 28.009111 5.221214 +115.349998 27.799999 5.221214 +112.349998 27.799999 5.221214 +112.349998 28.009111 5.221214 +115.349998 27.799999 5.778786 +115.349998 27.799999 5.221214 +115.349998 28.009111 5.221214 +115.349998 28.596251 5.000000 +115.349998 28.488325 5.959337 +115.349998 28.009111 5.778786 +112.349998 27.799999 5.221214 +112.349998 27.799999 5.778786 +112.349998 28.488325 5.959337 +112.349998 28.596251 5.000000 +112.349998 28.009111 5.778786 +112.349998 28.009111 5.221214 +91.449997 28.596251 5.000000 +94.449997 28.596251 5.000000 +94.449997 28.009111 5.221214 +91.449997 28.009111 5.221214 +91.449997 28.009111 5.778786 +94.449997 28.009111 5.778786 +94.449997 28.488325 5.959337 +91.449997 28.488325 5.959337 +94.449997 27.799999 5.778786 +94.449997 28.009111 5.778786 +91.449997 28.009111 5.778786 +91.449997 27.799999 5.778786 +94.449997 27.799999 5.221214 +94.449997 27.799999 5.778786 +91.449997 27.799999 5.778786 +91.449997 27.799999 5.221214 +94.449997 28.009111 5.221214 +94.449997 27.799999 5.221214 +91.449997 27.799999 5.221214 +91.449997 28.009111 5.221214 +94.449997 27.799999 5.778786 +94.449997 27.799999 5.221214 +94.449997 28.009111 5.221214 +94.449997 28.596251 5.000000 +94.449997 28.488325 5.959337 +94.449997 28.009111 5.778786 +91.449997 27.799999 5.221214 +91.449997 27.799999 5.778786 +91.449997 28.488325 5.959337 +91.449997 28.596251 5.000000 +91.449997 28.009111 5.778786 +91.449997 28.009111 5.221214 +48.150002 1.990889 5.221214 +45.150002 1.990889 5.221214 +45.150002 2.200000 5.221214 +48.150002 2.200000 5.221214 +48.150002 1.990889 5.221214 +48.150002 1.403750 5.000000 +45.150002 1.403750 5.000000 +45.150002 1.990889 5.221214 +48.150002 1.990889 5.778786 +45.150002 1.990889 5.778786 +45.150002 1.511675 5.959337 +48.150002 1.511675 5.959337 +48.150002 2.200000 5.778786 +45.150002 2.200000 5.778786 +45.150002 1.990889 5.778786 +48.150002 1.990889 5.778786 +48.150002 2.200000 5.221214 +45.150002 2.200000 5.221214 +45.150002 2.200000 5.778786 +48.150002 2.200000 5.778786 +45.150002 2.200000 5.778786 +45.150002 2.200000 5.221214 +45.150002 1.990889 5.221214 +45.150002 1.403750 5.000000 +45.150002 1.511675 5.959337 +45.150002 1.990889 5.778786 +48.150002 1.990889 5.221214 +48.150002 1.511675 5.959337 +48.150002 1.403750 5.000000 +48.150002 1.990889 5.778786 +48.150002 2.200000 5.221214 +48.150002 2.200000 5.778786 +69.050003 1.990889 5.221214 +66.050003 1.990889 5.221214 +66.050003 2.200000 5.221214 +69.050003 2.200000 5.221214 +69.050003 1.990889 5.221214 +69.050003 1.403750 5.000000 +66.050003 1.403750 5.000000 +66.050003 1.990889 5.221214 +69.050003 1.990889 5.778786 +66.050003 1.990889 5.778786 +66.050003 1.511675 5.959337 +69.050003 1.511675 5.959337 +69.050003 2.200000 5.778786 +66.050003 2.200000 5.778786 +66.050003 1.990889 5.778786 +69.050003 1.990889 5.778786 +69.050003 2.200000 5.221214 +66.050003 2.200000 5.221214 +66.050003 2.200000 5.778786 +69.050003 2.200000 5.778786 +66.050003 2.200000 5.778786 +66.050003 2.200000 5.221214 +66.050003 1.990889 5.221214 +66.050003 1.403750 5.000000 +66.050003 1.511675 5.959337 +66.050003 1.990889 5.778786 +69.050003 2.200000 5.221214 +69.050003 2.200000 5.778786 +69.050003 1.511675 5.959337 +69.050003 1.403750 5.000000 +69.050003 1.990889 5.778786 +69.050003 1.990889 5.221214 +52.650002 28.596251 5.000000 +52.650002 28.009111 5.221214 +49.650002 28.009111 5.221214 +49.650002 28.596251 5.000000 +52.650002 27.799999 5.221214 +49.650002 27.799999 5.221214 +49.650002 28.009111 5.221214 +52.650002 28.009111 5.221214 +52.650002 27.799999 5.221214 +52.650002 27.799999 5.778786 +49.650002 27.799999 5.778786 +49.650002 27.799999 5.221214 +52.650002 27.799999 5.778786 +52.650002 28.009111 5.778786 +49.650002 28.009111 5.778786 +49.650002 27.799999 5.778786 +52.650002 28.488325 5.959337 +49.650002 28.488325 5.959337 +49.650002 28.009111 5.778786 +52.650002 28.009111 5.778786 +49.650002 27.799999 5.221214 +49.650002 27.799999 5.778786 +49.650002 28.488325 5.959337 +49.650002 28.596251 5.000000 +49.650002 28.009111 5.778786 +49.650002 28.009111 5.221214 +52.650002 27.799999 5.778786 +52.650002 27.799999 5.221214 +52.650002 28.009111 5.221214 +52.650002 28.596251 5.000000 +52.650002 28.488325 5.959337 +52.650002 28.009111 5.778786 +73.550003 28.596251 5.000000 +73.550003 28.009111 5.221214 +70.550003 28.009111 5.221214 +70.550003 28.596251 5.000000 +73.550003 27.799999 5.221214 +70.550003 27.799999 5.221214 +70.550003 28.009111 5.221214 +73.550003 28.009111 5.221214 +73.550003 27.799999 5.778786 +70.550003 27.799999 5.778786 +70.550003 27.799999 5.221214 +73.550003 27.799999 5.221214 +73.550003 28.009111 5.778786 +70.550003 28.009111 5.778786 +70.550003 27.799999 5.778786 +73.550003 27.799999 5.778786 +73.550003 28.009111 5.778786 +73.550003 28.488325 5.959337 +70.550003 28.488325 5.959337 +70.550003 28.009111 5.778786 +70.550003 27.799999 5.221214 +70.550003 27.799999 5.778786 +70.550003 28.488325 5.959337 +70.550003 28.596251 5.000000 +70.550003 28.009111 5.778786 +70.550003 28.009111 5.221214 +73.550003 27.799999 5.778786 +73.550003 27.799999 5.221214 +73.550003 28.009111 5.221214 +73.550003 28.596251 5.000000 +73.550003 28.488325 5.959337 +73.550003 28.009111 5.778786 +38.605316 15.552142 38.299999 +38.500000 15.000000 38.400002 +38.500000 15.000000 38.299999 +38.525043 15.272944 38.400002 +38.525043 15.272944 38.299999 +38.605316 15.552142 38.400002 +41.500000 15.000000 38.299999 +41.500000 15.000000 38.400002 +41.474957 15.272944 38.299999 +41.394684 15.552142 38.299999 +41.474957 15.272944 38.400002 +41.255493 15.820815 38.299999 +41.394684 15.552142 38.400002 +41.060661 16.060659 38.299999 +41.255493 15.820815 38.400002 +41.060661 16.060659 38.400002 +40.820816 16.255493 38.299999 +40.552143 16.394682 38.299999 +40.820816 16.255493 38.400002 +40.552143 16.394682 38.400002 +40.272945 16.474958 38.299999 +40.272945 16.474958 38.400002 +40.000000 16.500000 38.299999 +40.000000 16.500000 38.400002 +39.727055 16.474958 38.299999 +39.727055 16.474958 38.400002 +39.447857 16.394682 38.299999 +39.447857 16.394682 38.400002 +39.179184 16.255493 38.299999 +38.939339 16.060659 38.299999 +39.179184 16.255493 38.400002 +38.939339 16.060659 38.400002 +38.744507 15.820815 38.299999 +38.744507 15.820815 38.400002 +40.000000 13.500000 38.299999 +40.272945 13.525042 38.299999 +41.255493 14.179185 38.299999 +41.394684 14.447858 38.299999 +41.060661 13.939340 38.299999 +40.820816 13.744507 38.299999 +41.474957 14.727056 38.299999 +40.552143 13.605317 38.299999 +41.500000 15.000000 38.299999 +41.474957 15.272944 38.299999 +41.394684 15.552142 38.299999 +41.255493 15.820815 38.299999 +41.060661 16.060659 38.299999 +40.820816 16.255493 38.299999 +40.552143 16.394682 38.299999 +40.272945 16.474958 38.299999 +40.000000 16.500000 38.299999 +39.727055 16.474958 38.299999 +39.447857 16.394682 38.299999 +39.179184 16.255493 38.299999 +38.939339 16.060659 38.299999 +38.744507 15.820815 38.299999 +38.605316 15.552142 38.299999 +38.525043 15.272944 38.299999 +38.500000 15.000000 38.299999 +38.525043 14.727056 38.299999 +38.605316 14.447858 38.299999 +38.744507 14.179185 38.299999 +38.939339 13.939340 38.299999 +39.179184 13.744507 38.299999 +39.447857 13.605317 38.299999 +39.727055 13.525042 38.299999 +125.000000 16.500000 38.400002 +126.474960 15.272944 38.299999 +126.500000 15.000000 38.299999 +126.500000 15.000000 38.400002 +126.394684 15.552142 38.299999 +126.474960 15.272944 38.400002 +126.394684 15.552142 38.400002 +126.255493 15.820815 38.299999 +126.060661 16.060659 38.299999 +126.255493 15.820815 38.400002 +126.060661 16.060659 38.400002 +125.820816 16.255493 38.299999 +125.552139 16.394682 38.299999 +125.820816 16.255493 38.400002 +125.272942 16.474958 38.299999 +125.552139 16.394682 38.400002 +125.000000 16.500000 38.299999 +125.272942 16.474958 38.400002 +123.525040 15.272944 38.400002 +123.500000 15.000000 38.400002 +123.500000 15.000000 38.299999 +123.525040 15.272944 38.299999 +123.605316 15.552142 38.400002 +123.605316 15.552142 38.299999 +123.744507 15.820815 38.400002 +123.939339 16.060659 38.400002 +123.744507 15.820815 38.299999 +123.939339 16.060659 38.299999 +124.179184 16.255493 38.400002 +124.179184 16.255493 38.299999 +124.447861 16.394682 38.400002 +124.447861 16.394682 38.299999 +124.727058 16.474958 38.400002 +124.727058 16.474958 38.299999 +124.727058 13.525042 38.299999 +125.000000 13.500000 38.299999 +126.255493 14.179185 38.299999 +126.394684 14.447858 38.299999 +126.060661 13.939340 38.299999 +125.820816 13.744507 38.299999 +126.474960 14.727056 38.299999 +125.552139 13.605317 38.299999 +126.500000 15.000000 38.299999 +125.272942 13.525042 38.299999 +126.474960 15.272944 38.299999 +126.394684 15.552142 38.299999 +126.255493 15.820815 38.299999 +126.060661 16.060659 38.299999 +125.820816 16.255493 38.299999 +125.552139 16.394682 38.299999 +125.272942 16.474958 38.299999 +125.000000 16.500000 38.299999 +124.727058 16.474958 38.299999 +124.447861 16.394682 38.299999 +124.179184 16.255493 38.299999 +123.939339 16.060659 38.299999 +123.744507 15.820815 38.299999 +123.605316 15.552142 38.299999 +123.525040 15.272944 38.299999 +123.500000 15.000000 38.299999 +123.525040 14.727056 38.299999 +123.605316 14.447858 38.299999 +123.744507 14.179185 38.299999 +123.939339 13.939340 38.299999 +124.179184 13.744507 38.299999 +124.447861 13.605317 38.299999 +95.395271 -6.000000 8.787428 +69.604729 -6.000000 8.787428 +69.587578 -5.017452 7.787580 +95.412422 -5.017452 7.787580 +69.590721 -5.197392 7.807103 +95.409279 -5.197392 7.807103 +69.593918 -5.380726 7.862740 +95.406082 -5.380726 7.862740 +69.596992 -5.556592 7.956642 +95.403008 -5.556592 7.956642 +69.599724 -5.713251 8.086518 +95.400276 -5.713251 8.086518 +69.601944 -5.840373 8.245420 +95.398056 -5.840373 8.245420 +69.603531 -5.931192 8.422898 +95.396469 -5.931192 8.422898 +69.604446 -5.983620 8.607175 +95.395554 -5.983620 8.607175 +69.604729 -6.000000 13.212572 +95.395271 -6.000000 13.212572 +95.412422 -5.017452 14.212420 +69.587578 -5.017452 14.212420 +95.409279 -5.197392 14.192897 +69.590721 -5.197392 14.192897 +95.406082 -5.380726 14.137260 +69.593918 -5.380726 14.137260 +95.403008 -5.556592 14.043358 +69.596992 -5.556592 14.043358 +95.400276 -5.713251 13.913482 +69.599724 -5.713251 13.913482 +95.398056 -5.840373 13.754580 +69.601944 -5.840373 13.754580 +95.396469 -5.931192 13.577102 +69.603531 -5.931192 13.577102 +95.395554 -5.983620 13.392825 +69.604446 -5.983620 13.392825 +82.104729 -6.000000 9.095224 +82.000000 0.000000 9.199954 +81.754631 0.000000 8.905007 +81.700043 0.000000 8.900000 +81.804779 -6.000000 8.795270 +81.810463 0.000000 8.921060 +81.859360 -6.000000 8.800277 +81.864189 0.000000 8.948891 +81.915199 -6.000000 8.816329 +81.889114 0.000000 8.967080 +81.968925 -6.000000 8.844161 +81.912148 0.000000 8.987849 +81.993843 -6.000000 8.862350 +82.016884 -6.000000 8.883119 +81.932922 0.000000 9.010887 +82.037651 -6.000000 8.906157 +81.951111 0.000000 9.035809 +82.055840 -6.000000 8.931078 +81.978943 0.000000 9.089534 +82.083672 -6.000000 8.984804 +81.994995 0.000000 9.145368 +82.099724 -6.000000 9.040637 +95.494858 -0.294764 7.705145 +69.505142 -0.294764 7.705145 +69.500000 0.000000 7.405191 +95.500000 0.000000 7.405191 +69.500084 -0.004914 7.459267 +95.499916 -0.004914 7.459267 +69.500359 -0.020642 7.514550 +95.499641 -0.020642 7.514550 +69.500839 -0.047888 7.567793 +95.499161 -0.047888 7.567793 +69.501503 -0.086025 7.615464 +95.498497 -0.086025 7.615464 +69.502319 -0.133022 7.654427 +95.497681 -0.133022 7.654427 +69.503242 -0.185782 7.682597 +95.496758 -0.185782 7.682597 +69.504204 -0.240782 7.699288 +95.495796 -0.240782 7.699288 +69.505142 -0.294764 14.294855 +95.494858 -0.294764 14.294855 +95.500000 0.000000 14.594810 +69.500000 0.000000 14.594810 +95.499916 -0.004914 14.540733 +69.500084 -0.004914 14.540733 +95.499641 -0.020642 14.485450 +69.500359 -0.020642 14.485450 +95.499161 -0.047888 14.432207 +69.500839 -0.047888 14.432207 +95.498497 -0.086025 14.384537 +69.501503 -0.086025 14.384537 +95.497681 -0.133022 14.345573 +69.502319 -0.133022 14.345573 +95.496758 -0.185782 14.317403 +69.503242 -0.185782 14.317403 +95.495796 -0.240782 14.300712 +69.504204 -0.240782 14.300712 +94.300003 -3.000000 12.799954 +94.300003 0.000000 12.747589 +94.599998 0.000000 13.047635 +94.599998 -3.000000 13.100000 +94.545410 0.000000 13.042625 +94.545410 -3.000000 13.094991 +94.489571 0.000000 13.026568 +94.489571 -3.000000 13.078934 +94.435837 0.000000 12.998726 +94.435837 -3.000000 13.051091 +94.410912 0.000000 12.980531 +94.410912 -3.000000 13.032896 +94.387871 0.000000 12.959753 +94.387871 -3.000000 13.012118 +94.367096 0.000000 12.936707 +94.367096 -3.000000 12.989073 +94.348900 0.000000 12.911777 +94.348900 -3.000000 12.964142 +94.321060 0.000000 12.858034 +94.321060 -3.000000 12.910399 +94.305008 0.000000 12.802186 +94.305008 -3.000000 12.854551 +94.545410 -3.000000 8.905009 +94.599998 -3.000000 8.900000 +94.305008 0.000000 9.197814 +94.300003 0.000000 9.252411 +94.300003 -3.000000 9.200046 +94.321060 0.000000 9.141966 +94.305008 -3.000000 9.145449 +94.348900 0.000000 9.088223 +94.321060 -3.000000 9.089601 +94.367096 0.000000 9.063293 +94.348900 -3.000000 9.035858 +94.387871 0.000000 9.040247 +94.367096 -3.000000 9.010927 +94.410912 0.000000 9.019469 +94.387871 -3.000000 8.987882 +94.435837 0.000000 9.001274 +94.410912 -3.000000 8.967104 +94.489571 0.000000 8.973432 +94.435837 -3.000000 8.948909 +94.545410 0.000000 8.957375 +94.489571 -3.000000 8.921066 +94.599998 0.000000 8.952365 +70.452408 -3.000000 13.100000 +70.400047 0.000000 13.047635 +70.694992 0.000000 12.802267 +70.699997 0.000000 12.747681 +70.752365 -3.000000 12.800046 +70.678940 0.000000 12.858101 +70.747360 -3.000000 12.854632 +70.651108 0.000000 12.911826 +70.731308 -3.000000 12.910466 +70.632919 0.000000 12.936748 +70.703476 -3.000000 12.964191 +70.612152 0.000000 12.959785 +70.685287 -3.000000 12.989113 +70.664513 -3.000000 13.012151 +70.589111 0.000000 12.980556 +70.641479 -3.000000 13.032920 +70.564194 0.000000 12.998744 +70.616554 -3.000000 13.051109 +70.510468 0.000000 13.026575 +70.562828 -3.000000 13.078940 +70.454636 0.000000 13.042627 +70.506996 -3.000000 13.094993 +70.752365 -3.000000 9.199954 +70.699997 0.000000 9.252319 +70.454636 0.000000 8.957373 +70.400047 0.000000 8.952365 +70.452408 -3.000000 8.900000 +70.510468 0.000000 8.973425 +70.506996 -3.000000 8.905007 +70.564194 0.000000 9.001256 +70.562828 -3.000000 8.921060 +70.589111 0.000000 9.019444 +70.616554 -3.000000 8.948891 +70.612152 0.000000 9.040215 +70.641479 -3.000000 8.967080 +70.664513 -3.000000 8.987849 +70.632919 0.000000 9.063252 +70.685287 -3.000000 9.010887 +70.651108 0.000000 9.088174 +70.703476 -3.000000 9.035809 +70.678940 0.000000 9.141899 +70.731308 -3.000000 9.089534 +70.694992 0.000000 9.197733 +70.747360 -3.000000 9.145368 +87.604729 -6.000000 9.095224 +87.500000 0.000000 9.199954 +87.254631 0.000000 8.905007 +87.200043 0.000000 8.900000 +87.304779 -6.000000 8.795270 +87.310463 0.000000 8.921060 +87.359360 -6.000000 8.800277 +87.364189 0.000000 8.948891 +87.415199 -6.000000 8.816329 +87.389114 0.000000 8.967080 +87.468925 -6.000000 8.844161 +87.412148 0.000000 8.987849 +87.493843 -6.000000 8.862350 +87.516884 -6.000000 8.883119 +87.432922 0.000000 9.010887 +87.537651 -6.000000 8.906157 +87.451111 0.000000 9.035809 +87.555840 -6.000000 8.931078 +87.478943 0.000000 9.089534 +87.583672 -6.000000 8.984804 +87.494995 0.000000 9.145368 +87.599724 -6.000000 9.040637 +87.304779 -6.000000 13.204730 +87.200043 0.000000 13.100000 +87.494995 0.000000 12.854632 +87.500000 0.000000 12.800046 +87.604729 -6.000000 12.904776 +87.478943 0.000000 12.910466 +87.599724 -6.000000 12.959363 +87.451111 0.000000 12.964191 +87.583672 -6.000000 13.015196 +87.432922 0.000000 12.989113 +87.555840 -6.000000 13.068922 +87.412148 0.000000 13.012151 +87.537651 -6.000000 13.093843 +87.516884 -6.000000 13.116881 +87.389114 0.000000 13.032920 +87.493843 -6.000000 13.137650 +87.364189 0.000000 13.051109 +87.468925 -6.000000 13.155839 +87.310463 0.000000 13.078940 +87.415199 -6.000000 13.183671 +87.254631 0.000000 13.094993 +87.359360 -6.000000 13.199723 +81.804779 -6.000000 13.204730 +81.700043 0.000000 13.100000 +81.994995 0.000000 12.854632 +82.000000 0.000000 12.800046 +82.104729 -6.000000 12.904776 +81.978943 0.000000 12.910466 +82.099724 -6.000000 12.959363 +81.951111 0.000000 12.964191 +82.083672 -6.000000 13.015196 +81.932922 0.000000 12.989113 +82.055840 -6.000000 13.068922 +81.912148 0.000000 13.012151 +82.037651 -6.000000 13.093843 +82.016884 -6.000000 13.116881 +81.889114 0.000000 13.032920 +81.993843 -6.000000 13.137650 +81.864189 0.000000 13.051109 +81.968925 -6.000000 13.155839 +81.810463 0.000000 13.078940 +81.915199 -6.000000 13.183671 +81.754631 0.000000 13.094993 +81.859360 -6.000000 13.199723 +77.395271 -6.000000 12.904776 +77.500000 0.000000 12.800046 +77.745369 0.000000 13.094993 +77.799957 0.000000 13.100000 +77.695221 -6.000000 13.204730 +77.689537 0.000000 13.078940 +77.640640 -6.000000 13.199723 +77.635811 0.000000 13.051109 +77.584801 -6.000000 13.183671 +77.610886 0.000000 13.032920 +77.531075 -6.000000 13.155839 +77.587852 0.000000 13.012151 +77.506157 -6.000000 13.137650 +77.483116 -6.000000 13.116881 +77.567078 0.000000 12.989113 +77.462349 -6.000000 13.093843 +77.548889 0.000000 12.964191 +77.444160 -6.000000 13.068922 +77.521057 0.000000 12.910466 +77.416328 -6.000000 13.015196 +77.505005 0.000000 12.854632 +77.400276 -6.000000 12.959363 +82.895271 -6.000000 12.904776 +83.000000 0.000000 12.800046 +83.245369 0.000000 13.094993 +83.299957 0.000000 13.100000 +83.195221 -6.000000 13.204730 +83.189537 0.000000 13.078940 +83.140640 -6.000000 13.199723 +83.135811 0.000000 13.051109 +83.084801 -6.000000 13.183671 +83.110886 0.000000 13.032920 +83.031075 -6.000000 13.155839 +83.087852 0.000000 13.012151 +83.006157 -6.000000 13.137650 +82.983116 -6.000000 13.116881 +83.067078 0.000000 12.989113 +82.962349 -6.000000 13.093843 +83.048889 0.000000 12.964191 +82.944160 -6.000000 13.068922 +83.021057 0.000000 12.910466 +82.916328 -6.000000 13.015196 +83.005005 0.000000 12.854632 +82.900276 -6.000000 12.959363 +88.447632 -6.000000 12.852411 +88.500000 -3.000000 12.800046 +88.745369 -3.000000 13.094993 +88.799957 -3.000000 13.100000 +88.747589 -6.000000 13.152365 +88.689537 -3.000000 13.078940 +88.693001 -6.000000 13.147358 +88.635811 -3.000000 13.051109 +88.637169 -6.000000 13.131306 +88.610886 -3.000000 13.032920 +88.583443 -6.000000 13.103475 +88.587852 -3.000000 13.012151 +88.558525 -6.000000 13.085285 +88.535484 -6.000000 13.064516 +88.567078 -3.000000 12.989113 +88.514717 -6.000000 13.041478 +88.548889 -3.000000 12.964191 +88.496529 -6.000000 13.016557 +88.521057 -3.000000 12.910466 +88.468697 -6.000000 12.962831 +88.505005 -3.000000 12.854632 +88.452644 -6.000000 12.906998 +88.747589 -6.000000 8.847635 +88.799957 -3.000000 8.900000 +88.505005 -3.000000 9.145368 +88.500000 -3.000000 9.199954 +88.447632 -6.000000 9.147589 +88.521057 -3.000000 9.089534 +88.452644 -6.000000 9.093002 +88.548889 -3.000000 9.035809 +88.468697 -6.000000 9.037169 +88.567078 -3.000000 9.010887 +88.496529 -6.000000 8.983443 +88.587852 -3.000000 8.987849 +88.514717 -6.000000 8.958522 +88.535484 -6.000000 8.935484 +88.610886 -3.000000 8.967080 +88.558525 -6.000000 8.914715 +88.635811 -3.000000 8.948891 +88.583443 -6.000000 8.896525 +88.689537 -3.000000 8.921060 +88.637169 -6.000000 8.868694 +88.745369 -3.000000 8.905007 +88.693001 -6.000000 8.852642 +83.195221 -6.000000 8.795270 +83.299957 0.000000 8.900000 +83.005005 0.000000 9.145368 +83.000000 0.000000 9.199954 +82.895271 -6.000000 9.095224 +83.021057 0.000000 9.089534 +82.900276 -6.000000 9.040637 +83.048889 0.000000 9.035809 +82.916328 -6.000000 8.984804 +83.067078 0.000000 9.010887 +82.944160 -6.000000 8.931078 +83.087852 0.000000 8.987849 +82.962349 -6.000000 8.906157 +82.983116 -6.000000 8.883119 +83.110886 0.000000 8.967080 +83.006157 -6.000000 8.862350 +83.135811 0.000000 8.948891 +83.031075 -6.000000 8.844161 +83.189537 0.000000 8.921060 +83.084801 -6.000000 8.816329 +83.245369 0.000000 8.905007 +83.140640 -6.000000 8.800277 +77.695221 -6.000000 8.795270 +77.799957 0.000000 8.900000 +77.505005 0.000000 9.145368 +77.500000 0.000000 9.199954 +77.395271 -6.000000 9.095224 +77.521057 0.000000 9.089534 +77.400276 -6.000000 9.040637 +77.548889 0.000000 9.035809 +77.416328 -6.000000 8.984804 +77.567078 0.000000 9.010887 +77.444160 -6.000000 8.931078 +77.587852 0.000000 8.987849 +77.462349 -6.000000 8.906157 +77.483116 -6.000000 8.883119 +77.610886 0.000000 8.967080 +77.506157 -6.000000 8.862350 +77.635811 0.000000 8.948891 +77.531075 -6.000000 8.844161 +77.689537 0.000000 8.921060 +77.584801 -6.000000 8.816329 +77.745369 0.000000 8.905007 +77.640640 -6.000000 8.800277 +76.252411 -6.000000 13.152365 +76.200043 -3.000000 13.100000 +76.494995 -3.000000 12.854632 +76.500000 -3.000000 12.800046 +76.552368 -6.000000 12.852411 +76.478943 -3.000000 12.910466 +76.547356 -6.000000 12.906998 +76.451111 -3.000000 12.964191 +76.531303 -6.000000 12.962831 +76.432922 -3.000000 12.989113 +76.503471 -6.000000 13.016557 +76.412148 -3.000000 13.012151 +76.485283 -6.000000 13.041478 +76.464516 -6.000000 13.064516 +76.389114 -3.000000 13.032920 +76.441475 -6.000000 13.085285 +76.364189 -3.000000 13.051109 +76.416557 -6.000000 13.103475 +76.310463 -3.000000 13.078940 +76.362831 -6.000000 13.131306 +76.254631 -3.000000 13.094993 +76.306999 -6.000000 13.147358 +76.552368 -6.000000 9.147589 +76.500000 -3.000000 9.199954 +76.254631 -3.000000 8.905007 +76.200043 -3.000000 8.900000 +76.252411 -6.000000 8.847635 +76.310463 -3.000000 8.921060 +76.306999 -6.000000 8.852642 +76.364189 -3.000000 8.948891 +76.362831 -6.000000 8.868694 +76.389114 -3.000000 8.967080 +76.416557 -6.000000 8.896525 +76.412148 -3.000000 8.987849 +76.441475 -6.000000 8.914715 +76.464516 -6.000000 8.935484 +76.432922 -3.000000 9.010887 +76.485283 -6.000000 8.958522 +76.451111 -3.000000 9.035809 +76.503471 -6.000000 8.983443 +76.478943 -3.000000 9.089534 +76.531303 -6.000000 9.037169 +76.494995 -3.000000 9.145368 +76.547356 -6.000000 9.093002 +80.500000 15.624551 36.799999 +84.500000 15.624551 36.799999 +84.500000 14.606982 37.799961 +80.500000 14.606982 37.799961 +75.375450 10.500000 36.799999 +76.393021 10.500000 37.799961 +79.658440 6.480165 37.799961 +80.500000 6.393018 37.799961 +80.500000 5.375450 36.799999 +78.868797 6.730851 37.799961 +79.449928 5.484188 36.799999 +78.172844 7.115973 37.799961 +78.464645 5.796986 36.799999 +77.595924 7.595925 37.799961 +77.596252 6.277528 36.799999 +76.876396 6.876396 36.799999 +77.115974 8.172842 37.799961 +76.277527 7.596252 36.799999 +76.730850 8.868800 37.799961 +75.796982 8.464644 36.799999 +76.480164 9.658441 37.799961 +75.484184 9.449931 36.799999 +86.386322 5.735253 36.799999 +85.432480 5.461002 36.799999 +84.500000 5.375450 36.799999 +84.500000 6.393018 37.799961 +84.500000 14.606982 37.799961 +84.500000 15.624551 36.799999 +85.247322 14.538417 37.799961 +86.011757 14.318624 37.799961 +85.432480 15.538998 36.799999 +86.747383 13.937526 37.799961 +86.386322 15.264747 36.799999 +87.304207 14.789226 36.799999 +87.404076 13.404075 37.799961 +88.123604 14.123605 36.799999 +87.937523 12.747380 37.799961 +88.318626 12.011758 37.799961 +88.789223 13.304204 36.799999 +88.538414 11.247319 37.799961 +89.264748 12.386320 36.799999 +88.606979 10.500000 37.799961 +89.539001 11.432479 36.799999 +89.624550 10.500000 36.799999 +88.538414 9.752681 37.799961 +88.318626 8.988242 37.799961 +89.539001 9.567521 36.799999 +89.264748 8.613680 36.799999 +87.937523 8.252620 37.799961 +87.404076 7.595925 37.799961 +88.789223 7.695796 36.799999 +88.123604 6.876396 36.799999 +86.747383 7.062475 37.799961 +87.304207 6.210774 36.799999 +86.011757 6.681376 37.799961 +85.247322 6.461583 37.799961 +84.500000 6.393018 37.799961 +84.500000 5.375450 36.799999 +80.500000 5.375450 36.799999 +80.500000 6.393018 37.799961 +112.787781 2.238128 1.150000 +112.012222 2.238128 1.150000 +112.011871 2.438128 1.349651 +112.788124 2.438128 1.349651 +112.011940 2.433784 1.308747 +112.788055 2.433784 1.308747 +112.012009 2.421576 1.270333 +112.787994 2.421576 1.270333 +112.012070 2.402799 1.236535 +112.787933 2.402799 1.236535 +112.012115 2.379426 1.208455 +112.787880 2.379426 1.208455 +112.012161 2.351305 1.185131 +112.787842 2.351305 1.185131 +112.012192 2.317475 1.166413 +112.787804 2.317475 1.166413 +112.012215 2.279039 1.154272 +112.787788 2.279039 1.154272 +91.887779 2.238128 1.150000 +91.112221 2.238128 1.150000 +91.111870 2.438128 1.349651 +91.888130 2.438128 1.349651 +91.111946 2.433784 1.308747 +91.888054 2.433784 1.308747 +91.112007 2.421576 1.270333 +91.887993 2.421576 1.270333 +91.112068 2.402799 1.236535 +91.887932 2.402799 1.236535 +91.112122 2.379426 1.208455 +91.887878 2.379426 1.208455 +91.112160 2.351305 1.185131 +91.887840 2.351305 1.185131 +91.112190 2.317475 1.166413 +91.887810 2.317475 1.166413 +91.112213 2.279039 1.154272 +91.887787 2.279039 1.154272 +73.887779 2.238128 1.150000 +73.112221 2.238128 1.150000 +73.111870 2.438128 1.349651 +73.888130 2.438128 1.349651 +73.111946 2.433784 1.308747 +73.888054 2.433784 1.308747 +73.112007 2.421576 1.270333 +73.887993 2.421576 1.270333 +73.112068 2.402799 1.236535 +73.887932 2.402799 1.236535 +73.112122 2.379426 1.208455 +73.887878 2.379426 1.208455 +73.112160 2.351305 1.185131 +73.887840 2.351305 1.185131 +73.112190 2.317475 1.166413 +73.887810 2.317475 1.166413 +73.112213 2.279039 1.154272 +73.887787 2.279039 1.154272 +52.987778 2.238128 1.150000 +52.212219 2.238128 1.150000 +52.211872 2.438128 1.349651 +52.988129 2.438128 1.349651 +52.211945 2.433784 1.308747 +52.988056 2.433784 1.308747 +52.212009 2.421576 1.270333 +52.987991 2.421576 1.270333 +52.212067 2.402799 1.236535 +52.987934 2.402799 1.236535 +52.212120 2.379426 1.208455 +52.987881 2.379426 1.208455 +52.212162 2.351305 1.185131 +52.987839 2.351305 1.185131 +52.212193 2.317475 1.166413 +52.987804 2.317475 1.166413 +52.212215 2.279039 1.154272 +52.987785 2.279039 1.154272 +2.238128 14.612221 1.150000 +2.238128 15.387779 1.150000 +2.438128 15.388127 1.349651 +2.438128 14.611873 1.349651 +2.434731 15.388064 1.313298 +2.434731 14.611936 1.313298 +2.423985 15.388000 1.276128 +2.423985 14.612000 1.276128 +2.405404 15.387937 1.240370 +2.405404 14.612063 1.240370 +2.379426 15.387881 1.208455 +2.379426 14.612119 1.208455 +2.347466 15.387836 1.182533 +2.347466 14.612164 1.182533 +2.311676 15.387803 1.164014 +2.311676 14.612197 1.164014 +2.274486 15.387785 1.153333 +2.274486 14.612215 1.153333 +162.699997 15.450000 1.150000 +162.699997 14.550000 1.150000 +162.500000 14.550000 1.350000 +162.500000 15.450000 1.350000 +162.503342 14.550000 1.313607 +162.503342 15.450000 1.313607 +162.514038 14.550000 1.276381 +162.514038 15.450000 1.276381 +162.532608 14.550000 1.240558 +162.532608 15.450000 1.240558 +162.558578 14.550000 1.208579 +162.558578 15.450000 1.208579 +162.590561 14.550000 1.182601 +162.590561 15.450000 1.182601 +162.626389 14.550000 1.164042 +162.626389 15.450000 1.164042 +162.663605 14.550000 1.153339 +162.663605 15.450000 1.153339 +144.812241 27.749655 1.150000 +145.587784 27.749655 1.150000 +145.588150 27.549656 1.349651 +144.811874 27.549656 1.349651 +145.588074 27.553051 1.313298 +144.811935 27.553051 1.313298 +145.588013 27.563797 1.276128 +144.811996 27.563797 1.276128 +145.587936 27.582378 1.240370 +144.812057 27.582378 1.240370 +145.587875 27.608356 1.208455 +144.812119 27.608356 1.208455 +145.587830 27.640316 1.182533 +144.812164 27.640316 1.182533 +145.587799 27.676107 1.164014 +144.812210 27.676107 1.164014 +145.587784 27.713297 1.153333 +144.812225 27.713297 1.153333 +123.912239 27.749655 1.150000 +124.687782 27.749655 1.150000 +124.688148 27.549656 1.349651 +123.911873 27.549656 1.349651 +124.688080 27.553051 1.313298 +123.911934 27.553051 1.313298 +124.688004 27.563797 1.276128 +123.911995 27.563797 1.276128 +124.687943 27.582378 1.240370 +123.912064 27.582378 1.240370 +124.687881 27.608356 1.208455 +123.912117 27.608356 1.208455 +124.687836 27.640316 1.182533 +123.912170 27.640316 1.182533 +124.687798 27.676107 1.164014 +123.912201 27.676107 1.164014 +124.687782 27.713297 1.153333 +123.912224 27.713297 1.153333 +103.012222 27.749655 1.150000 +103.787781 27.749655 1.150000 +103.788124 27.549656 1.349651 +103.011871 27.549656 1.349651 +103.788055 27.553999 1.308747 +103.011940 27.553999 1.308747 +103.787994 27.566208 1.270333 +103.012009 27.566208 1.270333 +103.787933 27.584984 1.236535 +103.012070 27.584984 1.236535 +103.787880 27.608356 1.208455 +103.012115 27.608356 1.208455 +103.787842 27.636477 1.185131 +103.012161 27.636477 1.185131 +103.787804 27.670307 1.166413 +103.012192 27.670307 1.166413 +103.787788 27.708744 1.154272 +103.012215 27.708744 1.154272 +82.112221 27.749655 1.150000 +82.887779 27.749655 1.150000 +82.888130 27.549656 1.349651 +82.111870 27.549656 1.349651 +82.888054 27.553999 1.308747 +82.111946 27.553999 1.308747 +82.887993 27.566208 1.270333 +82.112007 27.566208 1.270333 +82.887932 27.584984 1.236535 +82.112068 27.584984 1.236535 +82.887878 27.608356 1.208455 +82.112122 27.608356 1.208455 +82.887840 27.636477 1.185131 +82.112160 27.636477 1.185131 +82.887810 27.670307 1.166413 +82.112190 27.670307 1.166413 +82.887787 27.708744 1.154272 +82.112213 27.708744 1.154272 +61.212219 27.749655 1.150000 +61.987778 27.749655 1.150000 +61.988129 27.549656 1.349651 +61.211872 27.549656 1.349651 +61.988056 27.553999 1.308747 +61.211945 27.553999 1.308747 +61.987991 27.566208 1.270333 +61.212009 27.566208 1.270333 +61.987934 27.584984 1.236535 +61.212067 27.584984 1.236535 +61.987881 27.608356 1.208455 +61.212120 27.608356 1.208455 +61.987839 27.636477 1.185131 +61.212162 27.636477 1.185131 +61.987804 27.670307 1.166413 +61.212193 27.670307 1.166413 +61.987785 27.708744 1.154272 +61.212215 27.708744 1.154272 +40.312222 27.749655 1.150000 +41.087780 27.749655 1.150000 +41.088127 27.549656 1.349651 +40.311874 27.549656 1.349651 +41.088062 27.553051 1.313298 +40.311935 27.553051 1.313298 +41.087997 27.563797 1.276128 +40.312000 27.563797 1.276128 +41.087936 27.582378 1.240370 +40.312065 27.582378 1.240370 +41.087879 27.608356 1.208455 +40.312119 27.608356 1.208455 +41.087837 27.640316 1.182533 +40.312164 27.640316 1.182533 +41.087803 27.676107 1.164014 +40.312195 27.676107 1.164014 +41.087784 27.713297 1.153333 +40.312214 27.713297 1.153333 +19.412222 27.749655 1.150000 +20.187778 27.749655 1.150000 +20.188128 27.549656 1.349651 +19.411873 27.549656 1.349651 +20.188065 27.553051 1.313298 +19.411936 27.553051 1.313298 +20.188000 27.563797 1.276128 +19.412001 27.563797 1.276128 +20.187937 27.582378 1.240370 +19.412064 27.582378 1.240370 +20.187881 27.608356 1.208455 +19.412119 27.608356 1.208455 +20.187836 27.640316 1.182533 +19.412165 27.640316 1.182533 +20.187803 27.676107 1.164014 +19.412197 27.676107 1.164014 +20.187784 27.713297 1.153333 +19.412216 27.713297 1.153333 +20.187778 2.250345 1.150000 +19.412222 2.250345 1.150000 +19.411873 2.450345 1.349651 +20.188128 2.450345 1.349651 +19.411936 2.446949 1.313298 +20.188065 2.446949 1.313298 +19.412001 2.436202 1.276128 +20.188000 2.436202 1.276128 +19.412064 2.417621 1.240370 +20.187937 2.417621 1.240370 +19.412119 2.391643 1.208455 +20.187881 2.391643 1.208455 +19.412165 2.359683 1.182533 +20.187836 2.359683 1.182533 +19.412197 2.323893 1.164014 +20.187803 2.323893 1.164014 +19.412216 2.286704 1.153333 +20.187784 2.286704 1.153333 +41.087780 2.250345 1.150000 +40.312222 2.250345 1.150000 +40.311874 2.450345 1.349651 +41.088127 2.450345 1.349651 +40.311935 2.446949 1.313298 +41.088062 2.446949 1.313298 +40.312000 2.436202 1.276128 +41.087997 2.436202 1.276128 +40.312065 2.417621 1.240370 +41.087936 2.417621 1.240370 +40.312119 2.391643 1.208455 +41.087879 2.391643 1.208455 +40.312164 2.359683 1.182533 +41.087837 2.359683 1.182533 +40.312195 2.323893 1.164014 +41.087803 2.323893 1.164014 +40.312214 2.286704 1.153333 +41.087784 2.286704 1.153333 +61.987778 2.250345 1.150000 +61.212219 2.250345 1.150000 +61.211872 2.450345 1.349651 +61.988129 2.450345 1.349651 +61.211945 2.446002 1.308747 +61.988056 2.446002 1.308747 +61.212009 2.433793 1.270333 +61.987991 2.433793 1.270333 +61.212067 2.415016 1.236535 +61.987934 2.415016 1.236535 +61.212120 2.391643 1.208455 +61.987881 2.391643 1.208455 +61.212162 2.363523 1.185131 +61.987839 2.363523 1.185131 +61.212193 2.329692 1.166413 +61.987804 2.329692 1.166413 +61.212215 2.291257 1.154272 +61.987785 2.291257 1.154272 +82.887779 2.250345 1.150000 +82.112221 2.250345 1.150000 +82.111870 2.450345 1.349651 +82.888130 2.450345 1.349651 +82.111946 2.446002 1.308747 +82.888054 2.446002 1.308747 +82.112007 2.433793 1.270333 +82.887993 2.433793 1.270333 +82.112068 2.415016 1.236535 +82.887932 2.415016 1.236535 +82.112122 2.391643 1.208455 +82.887878 2.391643 1.208455 +82.112160 2.363523 1.185131 +82.887840 2.363523 1.185131 +82.112190 2.329692 1.166413 +82.887810 2.329692 1.166413 +82.112213 2.291257 1.154272 +82.887787 2.291257 1.154272 +103.787781 2.250345 1.150000 +103.012222 2.250345 1.150000 +103.011871 2.450345 1.349651 +103.788124 2.450345 1.349651 +103.011940 2.446002 1.308747 +103.788055 2.446002 1.308747 +103.012009 2.433793 1.270333 +103.787994 2.433793 1.270333 +103.012070 2.415016 1.236535 +103.787933 2.415016 1.236535 +103.012115 2.391643 1.208455 +103.787880 2.391643 1.208455 +103.012161 2.363523 1.185131 +103.787842 2.363523 1.185131 +103.012192 2.329692 1.166413 +103.787804 2.329692 1.166413 +103.012215 2.291257 1.154272 +103.787788 2.291257 1.154272 +124.687759 2.250345 1.150000 +123.912224 2.250345 1.150000 +123.911858 2.450345 1.349651 +124.688126 2.450345 1.349651 +123.911926 2.446949 1.313298 +124.688065 2.446949 1.313298 +123.911995 2.436202 1.276128 +124.688004 2.436202 1.276128 +123.912064 2.417621 1.240370 +124.687935 2.417621 1.240370 +123.912117 2.391643 1.208455 +124.687881 2.391643 1.208455 +123.912163 2.359683 1.182533 +124.687836 2.359683 1.182533 +123.912201 2.323893 1.164014 +124.687798 2.323893 1.164014 +123.912216 2.286704 1.153333 +124.687775 2.286704 1.153333 +145.587769 2.250345 1.150000 +144.812225 2.250345 1.150000 +144.811859 2.450345 1.349651 +145.588135 2.450345 1.349651 +144.811920 2.446949 1.313298 +145.588058 2.446949 1.313298 +144.811996 2.436202 1.276128 +145.587997 2.436202 1.276128 +144.812057 2.417621 1.240370 +145.587936 2.417621 1.240370 +144.812119 2.391643 1.208455 +145.587875 2.391643 1.208455 +144.812164 2.359683 1.182533 +145.587830 2.359683 1.182533 +144.812195 2.323893 1.164014 +145.587799 2.323893 1.164014 +144.812210 2.286704 1.153333 +145.587769 2.286704 1.153333 +145.588745 1.700000 1.700000 +145.589783 1.100000 2.300000 +144.810211 1.100000 2.300000 +144.811264 1.700000 1.700000 +163.899994 15.450000 2.300000 +163.899994 14.550000 2.300000 +163.892715 14.550000 2.292714 +163.300003 14.550000 1.700000 +163.300003 15.450000 1.700000 +163.892715 15.450000 2.292714 +124.688736 1.700000 1.700000 +124.689789 1.100000 2.300000 +123.910217 1.100000 2.300000 +123.911263 1.700000 1.700000 +112.788742 1.700000 1.700000 +112.789787 1.100000 2.300000 +112.010216 1.100000 2.300000 +112.011261 1.700000 1.700000 +103.788742 1.700000 1.700000 +103.789787 1.100000 2.300000 +103.010216 1.100000 2.300000 +103.011261 1.700000 1.700000 +91.888741 1.700000 1.700000 +91.889786 1.100000 2.300000 +91.110214 1.100000 2.300000 +91.111259 1.700000 1.700000 +82.888741 1.700000 1.700000 +82.889786 1.100000 2.300000 +82.110214 1.100000 2.300000 +82.111259 1.700000 1.700000 +73.888741 1.700000 1.700000 +73.889786 1.100000 2.300000 +73.110214 1.100000 2.300000 +73.111259 1.700000 1.700000 +61.988739 1.700000 1.700000 +61.989784 1.100000 2.300000 +61.210213 1.100000 2.300000 +61.211262 1.700000 1.700000 +52.988739 1.700000 1.700000 +52.989784 1.100000 2.300000 +52.210213 1.100000 2.300000 +52.211262 1.700000 1.700000 +41.088737 1.700000 1.700000 +41.089787 1.100000 2.300000 +40.310215 1.100000 2.300000 +40.311260 1.700000 1.700000 +20.188740 1.700000 1.700000 +20.189787 1.100000 2.300000 +19.410213 1.100000 2.300000 +19.411261 1.700000 1.700000 +1.700000 15.388739 1.700000 +1.700000 14.611261 1.700000 +1.104913 14.610223 2.295087 +1.106549 14.550000 2.293451 +1.100000 14.550000 2.300000 +1.100000 15.450000 2.300000 +1.106549 15.450000 2.293451 +1.104913 15.389777 2.295087 +20.188740 28.299999 1.700000 +19.411261 28.299999 1.700000 +19.410213 28.900000 2.300000 +20.189787 28.900000 2.300000 +40.311260 28.299999 1.700000 +40.310215 28.900000 2.300000 +41.089787 28.900000 2.300000 +41.088737 28.299999 1.700000 +61.211262 28.299999 1.700000 +61.210213 28.900000 2.300000 +61.989784 28.900000 2.300000 +61.988739 28.299999 1.700000 +82.888741 28.299999 1.700000 +82.111259 28.299999 1.700000 +82.110214 28.900000 2.300000 +82.889786 28.900000 2.300000 +103.788742 28.299999 1.700000 +103.011261 28.299999 1.700000 +103.010216 28.900000 2.300000 +103.789787 28.900000 2.300000 +123.911263 28.299999 1.700000 +123.910217 28.900000 2.300000 +124.689789 28.900000 2.300000 +124.688736 28.299999 1.700000 +144.811264 28.299999 1.700000 +144.810211 28.900000 2.300000 +145.589783 28.900000 2.300000 +145.588745 28.299999 1.700000 + + + + + + + + + + + +0.143623 -0.686037 -0.713250 +0.000000 -0.700909 -0.713250 +0.000000 -0.700909 -0.713250 +0.700909 0.000000 -0.713250 +0.686037 -0.143623 -0.713250 +0.700909 0.000000 -0.713250 +0.686037 -0.143623 -0.713250 +0.686037 -0.143623 -0.713250 +0.700909 0.000000 -0.713250 +0.686037 -0.143623 -0.713250 +0.643254 -0.278385 -0.713250 +0.686037 -0.143623 -0.713250 +0.643254 -0.278385 -0.713250 +0.643254 -0.278385 -0.713250 +0.686037 -0.143623 -0.713250 +0.643254 -0.278385 -0.713250 +0.577528 -0.397159 -0.713250 +0.643254 -0.278385 -0.713250 +0.577528 -0.397159 -0.713250 +0.577528 -0.397159 -0.713250 +0.643254 -0.278385 -0.713250 +0.577528 -0.397159 -0.713250 +0.495618 -0.495618 -0.713250 +0.577528 -0.397159 -0.713250 +0.495618 -0.495618 -0.713250 +0.495618 -0.495618 -0.713250 +0.577528 -0.397159 -0.713250 +0.397159 -0.577528 -0.713250 +0.495618 -0.495618 -0.713250 +0.495618 -0.495618 -0.713250 +0.397159 -0.577528 -0.713250 +0.397159 -0.577528 -0.713250 +0.495618 -0.495618 -0.713250 +0.278385 -0.643254 -0.713250 +0.397159 -0.577528 -0.713250 +0.397159 -0.577528 -0.713250 +0.278385 -0.643254 -0.713250 +0.278385 -0.643254 -0.713250 +0.397159 -0.577528 -0.713250 +0.143623 -0.686037 -0.713250 +0.278385 -0.643254 -0.713250 +0.278385 -0.643254 -0.713250 +0.143623 -0.686037 -0.713250 +0.143623 -0.686037 -0.713250 +0.278385 -0.643254 -0.713250 +0.000000 -0.700909 -0.713250 +0.143623 -0.686037 -0.713250 +0.143623 -0.686037 -0.713250 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.547210 0.000000 -0.836995 +0.368095 0.000000 -0.929788 +0.368095 0.000000 -0.929788 +0.181963 0.000000 -0.983305 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.181963 0.000000 -0.983305 +0.181963 0.000000 -0.983305 +0.000000 0.000000 -1.000000 +0.368095 0.000000 -0.929788 +0.181963 0.000000 -0.983305 +0.181963 0.000000 -0.983305 +0.368095 0.000000 -0.929788 +0.368095 0.000000 -0.929788 +0.181963 0.000000 -0.983305 +0.000000 0.000000 1.000000 +0.181963 0.000000 0.983305 +0.000000 0.000000 1.000000 +0.181963 0.000000 0.983305 +0.181963 0.000000 0.983305 +0.000000 0.000000 1.000000 +0.368095 0.000000 0.929788 +0.181963 0.000000 0.983305 +0.181963 0.000000 0.983305 +0.368095 0.000000 0.929788 +0.368095 0.000000 0.929788 +0.181963 0.000000 0.983305 +0.368095 0.000000 0.929788 +0.547210 0.000000 0.836995 +0.368095 0.000000 0.929788 +0.547210 0.000000 0.836995 +0.547210 0.000000 0.836995 +0.368095 0.000000 0.929788 +0.707107 0.000000 0.707107 +0.547210 0.000000 0.836995 +0.547210 0.000000 0.836995 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.547210 0.000000 0.836995 +0.836995 0.000000 0.547210 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.836995 0.000000 0.547210 +0.836995 0.000000 0.547210 +0.707107 0.000000 0.707107 +0.929788 0.000000 0.368095 +0.836995 0.000000 0.547210 +0.836995 0.000000 0.547210 +0.929788 0.000000 0.368095 +0.929788 0.000000 0.368095 +0.836995 0.000000 0.547210 +0.983305 0.000000 0.181963 +0.929788 0.000000 0.368095 +0.929788 0.000000 0.368095 +0.983305 0.000000 0.181963 +0.983305 0.000000 0.181963 +0.929788 0.000000 0.368095 +1.000000 0.000000 0.000000 +0.983305 0.000000 0.181963 +0.983305 0.000000 0.181963 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.000000 0.181963 +0.983305 0.000000 -0.181963 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.000000 -0.181963 +0.983305 0.000000 -0.181963 +1.000000 0.000000 0.000000 +0.929788 0.000000 -0.368095 +0.983305 0.000000 -0.181963 +0.983305 0.000000 -0.181963 +0.929788 0.000000 -0.368095 +0.929788 0.000000 -0.368095 +0.983305 0.000000 -0.181963 +0.836995 0.000000 -0.547210 +0.929788 0.000000 -0.368095 +0.929788 0.000000 -0.368095 +0.836995 0.000000 -0.547210 +0.836995 0.000000 -0.547210 +0.929788 0.000000 -0.368095 +0.836995 0.000000 -0.547210 +0.707107 0.000000 -0.707107 +0.836995 0.000000 -0.547210 +0.707107 0.000000 -0.707107 +0.707107 0.000000 -0.707107 +0.836995 0.000000 -0.547210 +0.547210 0.000000 -0.836995 +0.707107 0.000000 -0.707107 +0.707107 0.000000 -0.707107 +0.547210 0.000000 -0.836995 +0.547210 0.000000 -0.836995 +0.707107 0.000000 -0.707107 +0.368095 0.000000 -0.929788 +0.547210 0.000000 -0.836995 +0.547210 0.000000 -0.836995 +0.188061 -0.857166 0.479478 +0.093718 -0.857167 0.506440 +0.092188 -0.857166 0.506722 +0.000000 -0.857167 0.515038 +0.093718 -0.857167 0.506440 +0.000000 -0.857167 0.515038 +0.092188 -0.857166 0.506722 +0.093718 -0.857167 0.506440 +0.000000 -0.857167 0.515038 +0.093718 -0.857167 -0.506440 +0.001458 -0.857166 -0.515038 +0.000000 -0.857167 -0.515038 +0.093718 -0.857167 -0.506440 +0.095249 -0.857166 -0.506156 +0.001458 -0.857166 -0.515038 +0.189583 -0.857167 -0.478876 +0.095249 -0.857166 -0.506156 +0.093718 -0.857167 -0.506440 +0.189583 -0.857167 -0.478876 +0.191105 -0.857166 -0.478273 +0.095249 -0.857166 -0.506156 +0.281834 -0.857167 -0.431085 +0.191105 -0.857166 -0.478273 +0.189583 -0.857167 -0.478876 +0.281834 -0.857167 -0.431085 +0.283247 -0.857166 -0.430160 +0.191105 -0.857166 -0.478273 +0.364187 -0.857167 -0.364187 +0.283247 -0.857166 -0.430160 +0.281834 -0.857167 -0.431085 +0.364187 -0.857167 -0.364187 +0.365393 -0.857166 -0.362980 +0.283247 -0.857166 -0.430160 +0.431085 -0.857167 -0.281834 +0.365393 -0.857166 -0.362980 +0.364187 -0.857167 -0.364187 +0.431085 -0.857167 -0.281834 +0.432008 -0.857166 -0.280420 +0.365393 -0.857166 -0.362980 +0.478876 -0.857167 -0.189583 +0.432008 -0.857166 -0.280420 +0.431085 -0.857167 -0.281834 +0.478876 -0.857167 -0.189583 +0.479478 -0.857166 -0.188061 +0.432008 -0.857166 -0.280420 +0.506440 -0.857167 -0.093718 +0.479478 -0.857166 -0.188061 +0.478876 -0.857167 -0.189583 +0.506440 -0.857167 -0.093718 +0.506722 -0.857166 -0.092188 +0.479478 -0.857166 -0.188061 +0.515038 -0.857167 0.000000 +0.506722 -0.857166 -0.092188 +0.506440 -0.857167 -0.093718 +0.515038 -0.857167 0.000000 +0.515038 -0.857166 0.001458 +0.506722 -0.857166 -0.092188 +0.506440 -0.857167 0.093718 +0.515038 -0.857166 0.001458 +0.515038 -0.857167 0.000000 +0.506440 -0.857167 0.093718 +0.506156 -0.857166 0.095249 +0.515038 -0.857166 0.001458 +0.478876 -0.857167 0.189583 +0.506156 -0.857166 0.095249 +0.506440 -0.857167 0.093718 +0.478876 -0.857167 0.189583 +0.478273 -0.857166 0.191105 +0.506156 -0.857166 0.095249 +0.431085 -0.857167 0.281834 +0.478273 -0.857166 0.191105 +0.478876 -0.857167 0.189583 +0.431085 -0.857167 0.281834 +0.430160 -0.857166 0.283247 +0.478273 -0.857166 0.191105 +0.364187 -0.857167 0.364187 +0.430160 -0.857166 0.283247 +0.431085 -0.857167 0.281834 +0.364187 -0.857167 0.364187 +0.362980 -0.857166 0.365393 +0.430160 -0.857166 0.283247 +0.364187 -0.857167 0.364187 +0.280420 -0.857166 0.432008 +0.362980 -0.857166 0.365393 +0.281834 -0.857167 0.431085 +0.280420 -0.857166 0.432008 +0.364187 -0.857167 0.364187 +0.189583 -0.857167 0.478876 +0.280420 -0.857166 0.432008 +0.281834 -0.857167 0.431085 +0.189583 -0.857167 0.478876 +0.188061 -0.857166 0.479478 +0.280420 -0.857166 0.432008 +0.093718 -0.857167 0.506440 +0.188061 -0.857166 0.479478 +0.189583 -0.857167 0.478876 +0.547210 0.000000 -0.836995 +0.368095 0.000000 -0.929788 +0.368095 0.000000 -0.929788 +0.000000 0.000000 -1.000000 +0.181963 0.000000 -0.983305 +0.000000 0.000000 -1.000000 +0.181963 0.000000 -0.983305 +0.181963 0.000000 -0.983305 +0.000000 0.000000 -1.000000 +0.181963 0.000000 -0.983305 +0.368095 0.000000 -0.929788 +0.181963 0.000000 -0.983305 +0.368095 0.000000 -0.929788 +0.368095 0.000000 -0.929788 +0.181963 0.000000 -0.983305 +0.181963 0.000000 0.983305 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.181963 0.000000 0.983305 +0.181963 0.000000 0.983305 +0.000000 0.000000 1.000000 +0.181963 0.000000 0.983305 +0.368095 0.000000 0.929788 +0.181963 0.000000 0.983305 +0.368095 0.000000 0.929788 +0.368095 0.000000 0.929788 +0.181963 0.000000 0.983305 +0.547210 0.000000 0.836995 +0.368095 0.000000 0.929788 +0.368095 0.000000 0.929788 +0.547210 0.000000 0.836995 +0.547210 0.000000 0.836995 +0.368095 0.000000 0.929788 +0.707107 0.000000 0.707107 +0.547210 0.000000 0.836995 +0.547210 0.000000 0.836995 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.547210 0.000000 0.836995 +0.836995 0.000000 0.547210 +0.707107 0.000000 0.707107 +0.707107 0.000000 0.707107 +0.836995 0.000000 0.547210 +0.836995 0.000000 0.547210 +0.707107 0.000000 0.707107 +0.929788 0.000000 0.368095 +0.836995 0.000000 0.547210 +0.836995 0.000000 0.547210 +0.929788 0.000000 0.368095 +0.929788 0.000000 0.368095 +0.836995 0.000000 0.547210 +0.983305 0.000000 0.181963 +0.929788 0.000000 0.368095 +0.929788 0.000000 0.368095 +0.983305 0.000000 0.181963 +0.983305 0.000000 0.181963 +0.929788 0.000000 0.368095 +1.000000 0.000000 0.000000 +0.983305 0.000000 0.181963 +0.983305 0.000000 0.181963 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.000000 0.181963 +0.983305 0.000000 -0.181963 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.000000 -0.181963 +0.983305 0.000000 -0.181963 +1.000000 0.000000 0.000000 +0.929788 0.000000 -0.368095 +0.983305 0.000000 -0.181963 +0.983305 0.000000 -0.181963 +0.929788 0.000000 -0.368095 +0.929788 0.000000 -0.368095 +0.983305 0.000000 -0.181963 +0.929788 0.000000 -0.368095 +0.836995 0.000000 -0.547210 +0.929788 0.000000 -0.368095 +0.836995 0.000000 -0.547210 +0.836995 0.000000 -0.547210 +0.929788 0.000000 -0.368095 +0.707107 0.000000 -0.707107 +0.836995 0.000000 -0.547210 +0.836995 0.000000 -0.547210 +0.707107 0.000000 -0.707107 +0.707107 0.000000 -0.707107 +0.836995 0.000000 -0.547210 +0.707107 0.000000 -0.707107 +0.547210 0.000000 -0.836995 +0.707107 0.000000 -0.707107 +0.547210 0.000000 -0.836995 +0.547210 0.000000 -0.836995 +0.707107 0.000000 -0.707107 +0.368095 0.000000 -0.929788 +0.547210 0.000000 -0.836995 +0.547210 0.000000 -0.836995 +0.188061 -0.857166 0.479478 +0.093718 -0.857167 0.506440 +0.092188 -0.857166 0.506722 +0.000000 -0.857167 0.515038 +0.093718 -0.857167 0.506440 +0.000000 -0.857167 0.515038 +0.092188 -0.857166 0.506722 +0.093718 -0.857167 0.506440 +0.000000 -0.857167 0.515038 +0.093718 -0.857167 -0.506440 +0.001458 -0.857166 -0.515038 +0.000000 -0.857167 -0.515038 +0.093718 -0.857167 -0.506440 +0.095249 -0.857166 -0.506156 +0.001458 -0.857166 -0.515038 +0.189583 -0.857167 -0.478876 +0.095249 -0.857166 -0.506156 +0.093718 -0.857167 -0.506440 +0.189583 -0.857167 -0.478876 +0.191105 -0.857166 -0.478273 +0.095249 -0.857166 -0.506156 +0.281834 -0.857167 -0.431085 +0.191105 -0.857166 -0.478273 +0.189583 -0.857167 -0.478876 +0.281834 -0.857167 -0.431085 +0.283247 -0.857166 -0.430160 +0.191105 -0.857166 -0.478273 +0.364187 -0.857167 -0.364187 +0.283247 -0.857166 -0.430160 +0.281834 -0.857167 -0.431085 +0.364187 -0.857167 -0.364187 +0.365393 -0.857166 -0.362980 +0.283247 -0.857166 -0.430160 +0.431085 -0.857167 -0.281834 +0.365393 -0.857166 -0.362980 +0.364187 -0.857167 -0.364187 +0.431085 -0.857167 -0.281834 +0.432008 -0.857166 -0.280420 +0.365393 -0.857166 -0.362980 +0.478876 -0.857167 -0.189583 +0.432008 -0.857166 -0.280420 +0.431085 -0.857167 -0.281834 +0.478876 -0.857167 -0.189583 +0.479478 -0.857166 -0.188061 +0.432008 -0.857166 -0.280420 +0.506440 -0.857167 -0.093718 +0.479478 -0.857166 -0.188061 +0.478876 -0.857167 -0.189583 +0.506440 -0.857167 -0.093718 +0.506722 -0.857166 -0.092188 +0.479478 -0.857166 -0.188061 +0.515038 -0.857167 0.000000 +0.506722 -0.857166 -0.092188 +0.506440 -0.857167 -0.093718 +0.515038 -0.857167 0.000000 +0.515038 -0.857166 0.001458 +0.506722 -0.857166 -0.092188 +0.506440 -0.857167 0.093718 +0.515038 -0.857166 0.001458 +0.515038 -0.857167 0.000000 +0.506440 -0.857167 0.093718 +0.506156 -0.857166 0.095249 +0.515038 -0.857166 0.001458 +0.478876 -0.857167 0.189583 +0.506156 -0.857166 0.095249 +0.506440 -0.857167 0.093718 +0.478876 -0.857167 0.189583 +0.478273 -0.857166 0.191105 +0.506156 -0.857166 0.095249 +0.431085 -0.857167 0.281834 +0.478273 -0.857166 0.191105 +0.478876 -0.857167 0.189583 +0.431085 -0.857167 0.281834 +0.430160 -0.857166 0.283247 +0.478273 -0.857166 0.191105 +0.364187 -0.857167 0.364187 +0.430160 -0.857166 0.283247 +0.431085 -0.857167 0.281834 +0.364187 -0.857167 0.364187 +0.362980 -0.857166 0.365393 +0.430160 -0.857166 0.283247 +0.364187 -0.857167 0.364187 +0.280420 -0.857166 0.432008 +0.362980 -0.857166 0.365393 +0.281834 -0.857167 0.431085 +0.280420 -0.857166 0.432008 +0.364187 -0.857167 0.364187 +0.189583 -0.857167 0.478876 +0.280420 -0.857166 0.432008 +0.281834 -0.857167 0.431085 +0.189583 -0.857167 0.478876 +0.188061 -0.857166 0.479478 +0.280420 -0.857166 0.432008 +0.093718 -0.857167 0.506440 +0.188061 -0.857166 0.479478 +0.189583 -0.857167 0.478876 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.204902 0.978744 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +-0.978744 0.204902 -0.008727 +-0.999962 0.000000 -0.008727 +-0.999962 0.000000 -0.008727 +-0.978744 0.204902 -0.008727 +-0.978744 0.204902 -0.008727 +-0.999962 0.000000 -0.008727 +-0.978744 0.204902 -0.008727 +-0.917707 0.397162 -0.008727 +-0.978744 0.204902 -0.008727 +-0.917707 0.397162 -0.008727 +-0.917707 0.397162 -0.008727 +-0.978744 0.204902 -0.008727 +-0.823938 0.566613 -0.008727 +-0.917707 0.397162 -0.008727 +-0.917707 0.397162 -0.008727 +-0.823938 0.566613 -0.008727 +-0.823938 0.566613 -0.008727 +-0.917707 0.397162 -0.008727 +-0.823938 0.566613 -0.008727 +-0.707080 0.707080 -0.008727 +-0.823938 0.566613 -0.008727 +-0.707080 0.707080 -0.008727 +-0.707080 0.707080 -0.008727 +-0.823938 0.566613 -0.008727 +-0.566613 0.823938 -0.008727 +-0.707080 0.707080 -0.008727 +-0.707080 0.707080 -0.008727 +-0.566613 0.823938 -0.008727 +-0.566613 0.823938 -0.008727 +-0.707080 0.707080 -0.008727 +-0.397162 0.917707 -0.008727 +-0.566613 0.823938 -0.008727 +-0.566613 0.823938 -0.008727 +-0.397162 0.917707 -0.008727 +-0.397162 0.917707 -0.008727 +-0.566613 0.823938 -0.008727 +-0.397162 0.917707 -0.008727 +-0.204902 0.978744 -0.008727 +-0.397162 0.917707 -0.008727 +-0.204902 0.978744 -0.008727 +-0.204902 0.978744 -0.008727 +-0.397162 0.917707 -0.008727 +0.000000 0.999962 -0.008727 +-0.204902 0.978744 -0.008727 +-0.204902 0.978744 -0.008727 +0.707080 0.707080 0.008727 +0.547189 0.836964 0.008727 +0.707080 0.707080 0.008727 +0.983268 0.181956 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.983268 0.181956 0.008727 +0.983268 0.181956 0.008727 +0.999962 0.000000 0.008727 +0.929753 0.368081 0.008727 +0.983268 0.181956 0.008727 +0.983268 0.181956 0.008727 +0.929753 0.368081 0.008727 +0.929753 0.368081 0.008727 +0.983268 0.181956 0.008727 +0.929753 0.368081 0.008727 +0.836964 0.547189 0.008727 +0.929753 0.368081 0.008727 +0.836964 0.547189 0.008727 +0.836964 0.547189 0.008727 +0.929753 0.368081 0.008727 +0.836964 0.547189 0.008727 +0.707080 0.707080 0.008727 +0.836964 0.547189 0.008727 +0.707080 0.707080 0.008727 +0.707080 0.707080 0.008727 +0.836964 0.547189 0.008727 +-0.999962 0.000000 0.008727 +-0.983268 0.181956 0.008727 +-0.999962 0.000000 0.008727 +-0.983268 0.181956 0.008727 +-0.983268 0.181956 0.008727 +-0.999962 0.000000 0.008727 +-0.929753 0.368081 0.008727 +-0.983268 0.181956 0.008727 +-0.983268 0.181956 0.008727 +-0.929753 0.368081 0.008727 +-0.929753 0.368081 0.008727 +-0.983268 0.181956 0.008727 +-0.929753 0.368081 0.008727 +-0.836964 0.547189 0.008727 +-0.929753 0.368081 0.008727 +-0.836964 0.547189 0.008727 +-0.836964 0.547189 0.008727 +-0.929753 0.368081 0.008727 +-0.707080 0.707080 0.008727 +-0.836964 0.547189 0.008727 +-0.836964 0.547189 0.008727 +-0.707080 0.707080 0.008727 +-0.707080 0.707080 0.008727 +-0.836964 0.547189 0.008727 +-0.707080 0.707080 0.008727 +-0.547189 0.836964 0.008727 +-0.707080 0.707080 0.008727 +-0.547189 0.836964 0.008727 +-0.547189 0.836964 0.008727 +-0.707080 0.707080 0.008727 +-0.368081 0.929753 0.008727 +-0.547189 0.836964 0.008727 +-0.547189 0.836964 0.008727 +-0.368081 0.929753 0.008727 +-0.368081 0.929753 0.008727 +-0.547189 0.836964 0.008727 +-0.368081 0.929753 0.008727 +-0.181956 0.983268 0.008727 +-0.368081 0.929753 0.008727 +-0.181956 0.983268 0.008727 +-0.181956 0.983268 0.008727 +-0.368081 0.929753 0.008727 +0.000000 0.999962 0.008727 +-0.181956 0.983268 0.008727 +-0.181956 0.983268 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +-0.181956 0.983268 0.008727 +0.181956 0.983268 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.181956 0.983268 0.008727 +0.181956 0.983268 0.008727 +0.000000 0.999962 0.008727 +0.368081 0.929753 0.008727 +0.181956 0.983268 0.008727 +0.181956 0.983268 0.008727 +0.368081 0.929753 0.008727 +0.368081 0.929753 0.008727 +0.181956 0.983268 0.008727 +0.547189 0.836964 0.008727 +0.368081 0.929753 0.008727 +0.368081 0.929753 0.008727 +0.547189 0.836964 0.008727 +0.547189 0.836964 0.008727 +0.368081 0.929753 0.008727 +0.547189 0.836964 0.008727 +0.707080 0.707080 0.008727 +0.547189 0.836964 0.008727 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +0.570327 -0.821401 -0.005236 +0.707097 -0.707097 -0.005236 +0.594246 -0.804267 -0.005236 +0.999986 0.000000 -0.005236 +0.983292 -0.181961 -0.005236 +0.999986 0.000000 -0.005236 +0.983292 -0.181961 -0.005236 +0.983292 -0.181961 -0.005236 +0.999986 0.000000 -0.005236 +-0.983292 -0.181961 -0.005236 +-0.999986 0.000000 -0.005236 +-0.999986 0.000000 -0.005236 +-0.983292 -0.181961 -0.005236 +-0.983292 -0.181961 -0.005236 +-0.999986 0.000000 -0.005236 +-0.929776 -0.368090 -0.005236 +-0.983292 -0.181961 -0.005236 +-0.983292 -0.181961 -0.005236 +-0.929776 -0.368090 -0.005236 +-0.929776 -0.368090 -0.005236 +-0.983292 -0.181961 -0.005236 +-0.836984 -0.547202 -0.005236 +-0.929776 -0.368090 -0.005236 +-0.929776 -0.368090 -0.005236 +-0.836984 -0.547202 -0.005236 +-0.836984 -0.547202 -0.005236 +-0.929776 -0.368090 -0.005236 +-0.836984 -0.547202 -0.005236 +-0.707097 -0.707097 -0.005236 +-0.836984 -0.547202 -0.005236 +-0.707097 -0.707097 -0.005236 +-0.707097 -0.707097 -0.005236 +-0.836984 -0.547202 -0.005236 +-0.547202 -0.836984 -0.005236 +-0.707097 -0.707097 -0.005236 +-0.707097 -0.707097 -0.005236 +-0.547202 -0.836984 -0.005236 +-0.547202 -0.836984 -0.005236 +-0.707097 -0.707097 -0.005236 +-0.368090 -0.929776 -0.005236 +-0.547202 -0.836984 -0.005236 +-0.547202 -0.836984 -0.005236 +-0.368090 -0.929776 -0.005236 +-0.368090 -0.929776 -0.005236 +-0.547202 -0.836984 -0.005236 +-0.181961 -0.983292 -0.005236 +-0.368090 -0.929776 -0.005236 +-0.368090 -0.929776 -0.005236 +-0.181961 -0.983292 -0.005236 +-0.181961 -0.983292 -0.005236 +-0.368090 -0.929776 -0.005236 +0.000000 -0.999986 -0.005236 +-0.181961 -0.983292 -0.005236 +-0.181961 -0.983292 -0.005236 +0.000000 -0.999986 -0.005236 +0.000000 -0.999986 -0.005236 +-0.181961 -0.983292 -0.005236 +0.000000 -0.999986 -0.005236 +0.181961 -0.983292 -0.005236 +0.000000 -0.999986 -0.005236 +0.181961 -0.983292 -0.005236 +0.181961 -0.983292 -0.005236 +0.000000 -0.999986 -0.005236 +0.368090 -0.929776 -0.005236 +0.181961 -0.983292 -0.005236 +0.181961 -0.983292 -0.005236 +0.368090 -0.929776 -0.005236 +0.368090 -0.929776 -0.005236 +0.181961 -0.983292 -0.005236 +0.368090 -0.929776 -0.005236 +0.399393 -0.916765 -0.005236 +0.368090 -0.929776 -0.005236 +0.368090 -0.929776 -0.005236 +0.426191 -0.904618 -0.005236 +0.399393 -0.916765 -0.005236 +0.547202 -0.836984 -0.005236 +0.426191 -0.904618 -0.005236 +0.368090 -0.929776 -0.005236 +0.547202 -0.836984 -0.005236 +0.547202 -0.836984 -0.005236 +0.426191 -0.904618 -0.005236 +0.707097 -0.707097 -0.005236 +0.547202 -0.836984 -0.005236 +0.547202 -0.836984 -0.005236 +0.707097 -0.707097 -0.005236 +0.570327 -0.821401 -0.005236 +0.547202 -0.836984 -0.005236 +0.929776 -0.368090 -0.005236 +0.983292 -0.181961 -0.005236 +0.983292 -0.181961 -0.005236 +0.929776 -0.368090 -0.005236 +0.929776 -0.368090 -0.005236 +0.983292 -0.181961 -0.005236 +0.836984 -0.547202 -0.005236 +0.929776 -0.368090 -0.005236 +0.929776 -0.368090 -0.005236 +0.836984 -0.547202 -0.005236 +0.836984 -0.547202 -0.005236 +0.929776 -0.368090 -0.005236 +0.707097 -0.707097 -0.005236 +0.836984 -0.547202 -0.005236 +0.836984 -0.547202 -0.005236 +0.707097 -0.707097 -0.005236 +0.707097 -0.707097 -0.005236 +0.836984 -0.547202 -0.005236 +0.707097 -0.707097 -0.005236 +0.570327 -0.821401 -0.005236 +0.707097 -0.707097 -0.005236 +-0.983268 0.181956 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +0.983268 0.181956 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +0.983268 0.181956 0.008727 +0.983268 0.181956 0.008727 +0.999962 0.000000 0.008727 +0.929753 0.368081 0.008727 +0.983268 0.181956 0.008727 +0.983268 0.181956 0.008727 +0.929753 0.368081 0.008727 +0.929753 0.368081 0.008727 +0.983268 0.181956 0.008727 +0.836964 0.547189 0.008727 +0.929753 0.368081 0.008727 +0.929753 0.368081 0.008727 +0.836964 0.547189 0.008727 +0.836964 0.547189 0.008727 +0.929753 0.368081 0.008727 +0.707080 0.707080 0.008727 +0.836964 0.547189 0.008727 +0.836964 0.547189 0.008727 +0.707080 0.707080 0.008727 +0.707080 0.707080 0.008727 +0.836964 0.547189 0.008727 +0.547189 0.836964 0.008727 +0.707080 0.707080 0.008727 +0.707080 0.707080 0.008727 +0.547189 0.836964 0.008727 +0.547189 0.836964 0.008727 +0.707080 0.707080 0.008727 +0.547189 0.836964 0.008727 +0.368081 0.929753 0.008727 +0.547189 0.836964 0.008727 +0.368081 0.929753 0.008727 +0.368081 0.929753 0.008727 +0.547189 0.836964 0.008727 +0.181956 0.983268 0.008727 +0.368081 0.929753 0.008727 +0.368081 0.929753 0.008727 +0.181956 0.983268 0.008727 +0.181956 0.983268 0.008727 +0.368081 0.929753 0.008727 +0.000000 0.999962 0.008727 +0.181956 0.983268 0.008727 +0.181956 0.983268 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.181956 0.983268 0.008727 +-0.181956 0.983268 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +-0.181956 0.983268 0.008727 +-0.181956 0.983268 0.008727 +0.000000 0.999962 0.008727 +-0.368081 0.929753 0.008727 +-0.181956 0.983268 0.008727 +-0.181956 0.983268 0.008727 +-0.368081 0.929753 0.008727 +-0.368081 0.929753 0.008727 +-0.181956 0.983268 0.008727 +-0.547189 0.836964 0.008727 +-0.368081 0.929753 0.008727 +-0.368081 0.929753 0.008727 +-0.547189 0.836964 0.008727 +-0.547189 0.836964 0.008727 +-0.368081 0.929753 0.008727 +-0.707080 0.707080 0.008727 +-0.547189 0.836964 0.008727 +-0.547189 0.836964 0.008727 +-0.707080 0.707080 0.008727 +-0.707080 0.707080 0.008727 +-0.547189 0.836964 0.008727 +-0.836964 0.547189 0.008727 +-0.707080 0.707080 0.008727 +-0.707080 0.707080 0.008727 +-0.836964 0.547189 0.008727 +-0.836964 0.547189 0.008727 +-0.707080 0.707080 0.008727 +-0.929753 0.368081 0.008727 +-0.836964 0.547189 0.008727 +-0.836964 0.547189 0.008727 +-0.929753 0.368081 0.008727 +-0.929753 0.368081 0.008727 +-0.836964 0.547189 0.008727 +-0.983268 0.181956 0.008727 +-0.929753 0.368081 0.008727 +-0.929753 0.368081 0.008727 +-0.983268 0.181956 0.008727 +-0.983268 0.181956 0.008727 +-0.929753 0.368081 0.008727 +-0.999962 0.000000 0.008727 +-0.983268 0.181956 0.008727 +-0.983268 0.181956 0.008727 +0.983305 0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.368095 0.929788 0.000000 +0.181963 0.983305 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.368095 0.929788 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.547210 0.836995 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.547210 0.836995 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.707107 0.707107 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.836995 0.547210 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.836995 0.547210 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +0.929788 0.368095 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +0.929788 0.368095 0.000000 +1.000000 0.000000 0.000000 +0.983305 0.181963 0.000000 +0.983305 0.181963 0.000000 +-0.426191 -0.904618 -0.005236 +-0.368090 -0.929776 -0.005236 +-0.399393 -0.916765 -0.005236 +0.999986 0.000000 -0.005236 +0.983292 -0.181961 -0.005236 +0.999986 0.000000 -0.005236 +0.983292 -0.181961 -0.005236 +0.983292 -0.181961 -0.005236 +0.999986 0.000000 -0.005236 +-0.983292 -0.181961 -0.005236 +-0.999986 0.000000 -0.005236 +-0.999986 0.000000 -0.005236 +-0.983292 -0.181961 -0.005236 +-0.983292 -0.181961 -0.005236 +-0.999986 0.000000 -0.005236 +-0.983292 -0.181961 -0.005236 +-0.929776 -0.368090 -0.005236 +-0.983292 -0.181961 -0.005236 +-0.929776 -0.368090 -0.005236 +-0.929776 -0.368090 -0.005236 +-0.983292 -0.181961 -0.005236 +-0.836984 -0.547202 -0.005236 +-0.929776 -0.368090 -0.005236 +-0.929776 -0.368090 -0.005236 +-0.836984 -0.547202 -0.005236 +-0.836984 -0.547202 -0.005236 +-0.929776 -0.368090 -0.005236 +-0.707097 -0.707097 -0.005236 +-0.836984 -0.547202 -0.005236 +-0.836984 -0.547202 -0.005236 +-0.707097 -0.707097 -0.005236 +-0.707097 -0.707097 -0.005236 +-0.836984 -0.547202 -0.005236 +-0.707097 -0.707097 -0.005236 +-0.594246 -0.804267 -0.005236 +-0.707097 -0.707097 -0.005236 +-0.707097 -0.707097 -0.005236 +-0.570327 -0.821401 -0.005236 +-0.594246 -0.804267 -0.005236 +-0.547202 -0.836984 -0.005236 +-0.570327 -0.821401 -0.005236 +-0.707097 -0.707097 -0.005236 +-0.547202 -0.836984 -0.005236 +-0.547202 -0.836984 -0.005236 +-0.570327 -0.821401 -0.005236 +-0.368090 -0.929776 -0.005236 +-0.547202 -0.836984 -0.005236 +-0.547202 -0.836984 -0.005236 +-0.368090 -0.929776 -0.005236 +-0.426191 -0.904618 -0.005236 +-0.547202 -0.836984 -0.005236 +0.929776 -0.368090 -0.005236 +0.983292 -0.181961 -0.005236 +0.983292 -0.181961 -0.005236 +0.929776 -0.368090 -0.005236 +0.929776 -0.368090 -0.005236 +0.983292 -0.181961 -0.005236 +0.836984 -0.547202 -0.005236 +0.929776 -0.368090 -0.005236 +0.929776 -0.368090 -0.005236 +0.836984 -0.547202 -0.005236 +0.836984 -0.547202 -0.005236 +0.929776 -0.368090 -0.005236 +0.707097 -0.707097 -0.005236 +0.836984 -0.547202 -0.005236 +0.836984 -0.547202 -0.005236 +0.707097 -0.707097 -0.005236 +0.707097 -0.707097 -0.005236 +0.836984 -0.547202 -0.005236 +0.547202 -0.836984 -0.005236 +0.707097 -0.707097 -0.005236 +0.707097 -0.707097 -0.005236 +0.547202 -0.836984 -0.005236 +0.547202 -0.836984 -0.005236 +0.707097 -0.707097 -0.005236 +0.368090 -0.929776 -0.005236 +0.547202 -0.836984 -0.005236 +0.547202 -0.836984 -0.005236 +0.368090 -0.929776 -0.005236 +0.368090 -0.929776 -0.005236 +0.547202 -0.836984 -0.005236 +0.368090 -0.929776 -0.005236 +0.181961 -0.983292 -0.005236 +0.368090 -0.929776 -0.005236 +0.181961 -0.983292 -0.005236 +0.181961 -0.983292 -0.005236 +0.368090 -0.929776 -0.005236 +0.000000 -0.999986 -0.005236 +0.181961 -0.983292 -0.005236 +0.181961 -0.983292 -0.005236 +0.000000 -0.999986 -0.005236 +0.000000 -0.999986 -0.005236 +0.181961 -0.983292 -0.005236 +-0.181961 -0.983292 -0.005236 +0.000000 -0.999986 -0.005236 +0.000000 -0.999986 -0.005236 +-0.181961 -0.983292 -0.005236 +-0.181961 -0.983292 -0.005236 +0.000000 -0.999986 -0.005236 +-0.368090 -0.929776 -0.005236 +-0.181961 -0.983292 -0.005236 +-0.181961 -0.983292 -0.005236 +-0.368090 -0.929776 -0.005236 +-0.368090 -0.929776 -0.005236 +-0.181961 -0.983292 -0.005236 +-0.368090 -0.929776 -0.005236 +-0.426191 -0.904618 -0.005236 +-0.368090 -0.929776 -0.005236 +0.917742 -0.397177 0.000000 +0.978781 -0.204909 0.000000 +0.917742 -0.397177 0.000000 +0.000000 -1.000000 0.000000 +0.204909 -0.978781 0.000000 +0.000000 -1.000000 0.000000 +0.204909 -0.978781 0.000000 +0.204909 -0.978781 0.000000 +0.000000 -1.000000 0.000000 +0.397177 -0.917742 0.000000 +0.204909 -0.978781 0.000000 +0.204909 -0.978781 0.000000 +0.397177 -0.917742 0.000000 +0.397177 -0.917742 0.000000 +0.204909 -0.978781 0.000000 +0.566635 -0.823969 0.000000 +0.397177 -0.917742 0.000000 +0.397177 -0.917742 0.000000 +0.566635 -0.823969 0.000000 +0.566635 -0.823969 0.000000 +0.397177 -0.917742 0.000000 +0.707107 -0.707107 0.000000 +0.566635 -0.823969 0.000000 +0.566635 -0.823969 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.566635 -0.823969 0.000000 +0.823969 -0.566635 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.823969 -0.566635 0.000000 +0.823969 -0.566635 0.000000 +0.707107 -0.707107 0.000000 +0.823969 -0.566635 0.000000 +0.917742 -0.397177 0.000000 +0.823969 -0.566635 0.000000 +0.917742 -0.397177 0.000000 +0.917742 -0.397177 0.000000 +0.823969 -0.566635 0.000000 +1.000000 0.000000 0.000000 +0.999476 -0.032374 0.000000 +1.000000 0.000000 0.000000 +0.978781 -0.204909 0.000000 +0.999476 -0.032374 0.000000 +1.000000 0.000000 0.000000 +0.999476 -0.032374 0.000000 +0.978781 -0.204909 0.000000 +0.999476 -0.032374 0.000000 +0.978781 -0.204909 0.000000 +0.978781 -0.204909 0.000000 +0.999476 -0.032374 0.000000 +0.978781 -0.204909 0.000000 +0.917742 -0.397177 0.000000 +0.978781 -0.204909 0.000000 +0.611943 0.496818 0.615385 +0.522235 0.522235 0.674196 +0.557361 0.557361 0.615385 +0.522235 0.522235 0.674196 +0.496818 0.611943 0.615385 +0.557361 0.557361 0.615385 +0.418489 0.608544 0.674196 +0.496818 0.611943 0.615385 +0.522235 0.522235 0.674196 +0.418489 0.608544 0.674196 +0.431325 0.659742 0.615385 +0.496818 0.611943 0.615385 +0.293336 0.677800 0.674196 +0.431325 0.659742 0.615385 +0.418489 0.608544 0.674196 +0.293336 0.677800 0.674196 +0.290142 0.732884 0.615385 +0.431325 0.659742 0.615385 +0.151336 0.722881 0.674196 +0.290142 0.732884 0.615385 +0.293336 0.677800 0.674196 +0.151336 0.722881 0.674196 +0.143428 0.775068 0.615385 +0.290142 0.732884 0.615385 +0.143428 0.775068 0.615385 +0.000000 0.738552 0.674196 +0.000000 0.788227 0.615385 +0.151336 0.722881 0.674196 +0.000000 0.738552 0.674196 +0.143428 0.775068 0.615385 +0.121868 0.582121 0.803917 +0.000000 0.738552 0.674196 +0.151336 0.722881 0.674196 +0.121868 0.582121 0.803917 +0.000000 0.594741 0.803917 +0.000000 0.738552 0.674196 +0.089859 0.429224 0.898717 +0.000000 0.594741 0.803917 +0.121868 0.582121 0.803917 +0.089859 0.429224 0.898717 +0.000000 0.438529 0.898717 +0.000000 0.594741 0.803917 +0.054849 0.261995 0.963509 +0.000000 0.438529 0.898717 +0.089859 0.429224 0.898717 +0.054849 0.261995 0.963509 +0.000000 0.267675 0.963509 +0.000000 0.438529 0.898717 +0.015763 0.075294 0.997037 +0.000000 0.267675 0.963509 +0.054849 0.261995 0.963509 +0.015763 0.075294 0.997037 +0.000000 0.076926 0.997037 +0.000000 0.267675 0.963509 +0.015763 0.075294 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.076926 0.997037 +0.015763 0.075294 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.030553 0.070598 0.997037 +0.000000 0.000000 1.000000 +0.015763 0.075294 0.997037 +0.030553 0.070598 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.043589 0.063385 0.997037 +0.000000 0.000000 1.000000 +0.030553 0.070598 0.997037 +0.043589 0.063385 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.054395 0.054395 0.997037 +0.000000 0.000000 1.000000 +0.043589 0.063385 0.997037 +0.054395 0.054395 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.063385 0.043589 0.997037 +0.000000 0.000000 1.000000 +0.054395 0.054395 0.997037 +0.063385 0.043589 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.063385 0.043589 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.070598 0.030553 0.997037 +0.000000 0.000000 1.000000 +0.063385 0.043589 0.997037 +0.075294 0.015763 0.997037 +0.000000 0.000000 1.000000 +0.070598 0.030553 0.997037 +0.075294 0.015763 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.075294 0.015763 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.075294 0.015763 0.997037 +0.076926 0.000000 0.997037 +0.000000 0.000000 1.000000 +0.261995 0.054849 0.963509 +0.076926 0.000000 0.997037 +0.075294 0.015763 0.997037 +0.261995 0.054849 0.963509 +0.267675 0.000000 0.963509 +0.076926 0.000000 0.997037 +0.429224 0.089859 0.898717 +0.267675 0.000000 0.963509 +0.261995 0.054849 0.963509 +0.429224 0.089859 0.898717 +0.438529 0.000000 0.898717 +0.267675 0.000000 0.963509 +0.582121 0.121868 0.803917 +0.438529 0.000000 0.898717 +0.429224 0.089859 0.898717 +0.582121 0.121868 0.803917 +0.594741 0.000000 0.803917 +0.438529 0.000000 0.898717 +0.722881 0.151336 0.674196 +0.594741 0.000000 0.803917 +0.582121 0.121868 0.803917 +0.722881 0.151336 0.674196 +0.738552 0.000000 0.674196 +0.594741 0.000000 0.803917 +0.722881 0.151336 0.674196 +0.788227 0.000000 0.615385 +0.738552 0.000000 0.674196 +0.722881 0.151336 0.674196 +0.775068 0.143428 0.615385 +0.788227 0.000000 0.615385 +0.722881 0.151336 0.674196 +0.732884 0.290142 0.615385 +0.775068 0.143428 0.615385 +0.677800 0.293336 0.674196 +0.732884 0.290142 0.615385 +0.722881 0.151336 0.674196 +0.677800 0.293336 0.674196 +0.659742 0.431325 0.615385 +0.732884 0.290142 0.615385 +0.608544 0.418489 0.674196 +0.659742 0.431325 0.615385 +0.677800 0.293336 0.674196 +0.608544 0.418489 0.674196 +0.611943 0.496818 0.615385 +0.659742 0.431325 0.615385 +0.522235 0.522235 0.674196 +0.611943 0.496818 0.615385 +0.608544 0.418489 0.674196 +0.151336 0.722881 0.674196 +0.236218 0.545819 0.803917 +0.121868 0.582121 0.803917 +0.236218 0.545819 0.803917 +0.151336 0.722881 0.674196 +0.293336 0.677800 0.674196 +0.121868 0.582121 0.803917 +0.174174 0.402456 0.898717 +0.089859 0.429224 0.898717 +0.174174 0.402456 0.898717 +0.121868 0.582121 0.803917 +0.236218 0.545819 0.803917 +0.089859 0.429224 0.898717 +0.106314 0.245656 0.963509 +0.054849 0.261995 0.963509 +0.106314 0.245656 0.963509 +0.089859 0.429224 0.898717 +0.174174 0.402456 0.898717 +0.054849 0.261995 0.963509 +0.030553 0.070598 0.997037 +0.015763 0.075294 0.997037 +0.030553 0.070598 0.997037 +0.054849 0.261995 0.963509 +0.106314 0.245656 0.963509 +0.293336 0.677800 0.674196 +0.337001 0.490048 0.803917 +0.236218 0.545819 0.803917 +0.337001 0.490048 0.803917 +0.293336 0.677800 0.674196 +0.418489 0.608544 0.674196 +0.236218 0.545819 0.803917 +0.248486 0.361334 0.898717 +0.174174 0.402456 0.898717 +0.248486 0.361334 0.898717 +0.236218 0.545819 0.803917 +0.337001 0.490048 0.803917 +0.174174 0.402456 0.898717 +0.151674 0.220556 0.963509 +0.106314 0.245656 0.963509 +0.151674 0.220556 0.963509 +0.174174 0.402456 0.898717 +0.248486 0.361334 0.898717 +0.106314 0.245656 0.963509 +0.043589 0.063385 0.997037 +0.030553 0.070598 0.997037 +0.043589 0.063385 0.997037 +0.106314 0.245656 0.963509 +0.151674 0.220556 0.963509 +0.418489 0.608544 0.674196 +0.420546 0.420546 0.803917 +0.337001 0.490048 0.803917 +0.420546 0.420546 0.803917 +0.418489 0.608544 0.674196 +0.522235 0.522235 0.674196 +0.337001 0.490048 0.803917 +0.310087 0.310087 0.898717 +0.248486 0.361334 0.898717 +0.310087 0.310087 0.898717 +0.337001 0.490048 0.803917 +0.420546 0.420546 0.803917 +0.248486 0.361334 0.898717 +0.189275 0.189275 0.963509 +0.151674 0.220556 0.963509 +0.189275 0.189275 0.963509 +0.248486 0.361334 0.898717 +0.310087 0.310087 0.898717 +0.151674 0.220556 0.963509 +0.054395 0.054395 0.997037 +0.043589 0.063385 0.997037 +0.054395 0.054395 0.997037 +0.151674 0.220556 0.963509 +0.189275 0.189275 0.963509 +0.522235 0.522235 0.674196 +0.490048 0.337001 0.803917 +0.420546 0.420546 0.803917 +0.490048 0.337001 0.803917 +0.522235 0.522235 0.674196 +0.608544 0.418489 0.674196 +0.420546 0.420546 0.803917 +0.361334 0.248486 0.898717 +0.310087 0.310087 0.898717 +0.361334 0.248486 0.898717 +0.420546 0.420546 0.803917 +0.490048 0.337001 0.803917 +0.310087 0.310087 0.898717 +0.220556 0.151674 0.963509 +0.189275 0.189275 0.963509 +0.220556 0.151674 0.963509 +0.310087 0.310087 0.898717 +0.361334 0.248486 0.898717 +0.189275 0.189275 0.963509 +0.063385 0.043589 0.997037 +0.054395 0.054395 0.997037 +0.063385 0.043589 0.997037 +0.189275 0.189275 0.963509 +0.220556 0.151674 0.963509 +0.608544 0.418489 0.674196 +0.545819 0.236218 0.803917 +0.490048 0.337001 0.803917 +0.545819 0.236218 0.803917 +0.608544 0.418489 0.674196 +0.677800 0.293336 0.674196 +0.490048 0.337001 0.803917 +0.402456 0.174174 0.898717 +0.361334 0.248486 0.898717 +0.402456 0.174174 0.898717 +0.490048 0.337001 0.803917 +0.545819 0.236218 0.803917 +0.361334 0.248486 0.898717 +0.245656 0.106314 0.963509 +0.220556 0.151674 0.963509 +0.245656 0.106314 0.963509 +0.361334 0.248486 0.898717 +0.402456 0.174174 0.898717 +0.220556 0.151674 0.963509 +0.070598 0.030553 0.997037 +0.063385 0.043589 0.997037 +0.070598 0.030553 0.997037 +0.220556 0.151674 0.963509 +0.245656 0.106314 0.963509 +0.677800 0.293336 0.674196 +0.582121 0.121868 0.803917 +0.545819 0.236218 0.803917 +0.582121 0.121868 0.803917 +0.677800 0.293336 0.674196 +0.722881 0.151336 0.674196 +0.545819 0.236218 0.803917 +0.429224 0.089859 0.898717 +0.402456 0.174174 0.898717 +0.429224 0.089859 0.898717 +0.545819 0.236218 0.803917 +0.582121 0.121868 0.803917 +0.402456 0.174174 0.898717 +0.261995 0.054849 0.963509 +0.245656 0.106314 0.963509 +0.261995 0.054849 0.963509 +0.402456 0.174174 0.898717 +0.429224 0.089859 0.898717 +0.245656 0.106314 0.963509 +0.075294 0.015763 0.997037 +0.070598 0.030553 0.997037 +0.075294 0.015763 0.997037 +0.245656 0.106314 0.963509 +0.261995 0.054849 0.963509 +-0.178700 0.037411 0.983192 +-0.353017 0.065327 0.933333 +-0.350825 0.073446 0.933556 +-0.295336 0.203099 0.933556 +-0.253859 0.253859 0.933333 +-0.253449 0.253449 0.933556 +-0.295336 0.203099 0.933556 +-0.278719 0.226284 0.933333 +-0.253859 0.253859 0.933333 +-0.295336 0.203099 0.933556 +-0.300491 0.196454 0.933333 +-0.278719 0.226284 0.933333 +-0.328947 0.142361 0.933556 +-0.300491 0.196454 0.933333 +-0.295336 0.203099 0.933556 +-0.328947 0.142361 0.933556 +-0.333804 0.132150 0.933333 +-0.300491 0.196454 0.933333 +-0.350825 0.073446 0.933556 +-0.333804 0.132150 0.933333 +-0.328947 0.142361 0.933556 +-0.350825 0.073446 0.933556 +-0.353017 0.065327 0.933333 +-0.333804 0.132150 0.933333 +-0.353017 0.065327 0.933333 +-0.358431 0.000000 0.933556 +-0.359011 0.000000 0.933333 +0.000000 0.000000 1.000000 +0.000000 0.000622 1.000000 +0.000000 0.000000 1.000000 +-0.226284 0.278719 0.933333 +-0.253449 0.253449 0.933556 +-0.253859 0.253859 0.933333 +-0.226284 0.278719 0.933333 +-0.203099 0.295336 0.933556 +-0.253449 0.253449 0.933556 +-0.196454 0.300491 0.933333 +-0.203099 0.295336 0.933556 +-0.226284 0.278719 0.933333 +-0.196454 0.300491 0.933333 +-0.142361 0.328947 0.933556 +-0.203099 0.295336 0.933556 +-0.132150 0.333804 0.933333 +-0.142361 0.328947 0.933556 +-0.196454 0.300491 0.933333 +-0.132150 0.333804 0.933333 +-0.073446 0.350825 0.933556 +-0.142361 0.328947 0.933556 +-0.065327 0.353017 0.933333 +-0.073446 0.350825 0.933556 +-0.132150 0.333804 0.933333 +0.000000 0.000000 1.000000 +0.000000 0.182574 0.983192 +0.000000 0.000622 1.000000 +-0.353017 0.065327 0.933333 +-0.182574 0.000000 0.983192 +-0.358431 0.000000 0.933556 +-0.000622 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.182574 0.000000 0.983192 +0.000000 0.000000 1.000000 +-0.000622 0.000000 1.000000 +0.000000 0.358431 0.933556 +-0.065327 0.353017 0.933333 +0.000000 0.359011 0.933333 +0.000000 0.182574 0.983192 +-0.065327 0.353017 0.933333 +0.000000 0.358431 0.933556 +-0.065327 0.353017 0.933333 +-0.037411 0.178700 0.983192 +-0.073446 0.350825 0.933556 +0.000000 0.182574 0.983192 +-0.037411 0.178700 0.983192 +-0.065327 0.353017 0.933333 +0.000000 0.000000 1.000000 +-0.037411 0.178700 0.983192 +0.000000 0.182574 0.983192 +0.000000 0.000000 1.000000 +-0.000127 0.000608 1.000000 +-0.037411 0.178700 0.983192 +0.000000 0.000000 1.000000 +-0.000127 0.000608 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.000247 0.000570 1.000000 +-0.000127 0.000608 1.000000 +0.000000 0.000000 1.000000 +-0.000247 0.000570 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.000352 0.000512 1.000000 +-0.000247 0.000570 1.000000 +0.000000 0.000000 1.000000 +-0.000352 0.000512 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.000439 0.000439 1.000000 +-0.000352 0.000512 1.000000 +0.000000 0.000000 1.000000 +-0.000439 0.000439 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.000439 0.000439 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.000512 0.000352 1.000000 +-0.000439 0.000439 1.000000 +0.000000 0.000000 1.000000 +-0.000512 0.000352 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.000570 0.000247 1.000000 +-0.000512 0.000352 1.000000 +0.000000 0.000000 1.000000 +-0.000570 0.000247 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.000608 0.000127 1.000000 +-0.000570 0.000247 1.000000 +0.000000 0.000000 1.000000 +-0.000608 0.000127 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.178700 0.037411 0.983192 +-0.000608 0.000127 1.000000 +-0.182574 0.000000 0.983192 +-0.178700 0.037411 0.983192 +0.000000 0.000000 1.000000 +-0.353017 0.065327 0.933333 +-0.178700 0.037411 0.983192 +-0.182574 0.000000 0.983192 +-0.000127 0.000608 1.000000 +-0.072514 0.167556 0.983192 +-0.037411 0.178700 0.983192 +-0.072514 0.167556 0.983192 +-0.000127 0.000608 1.000000 +-0.000247 0.000570 1.000000 +-0.037411 0.178700 0.983192 +-0.142361 0.328947 0.933556 +-0.073446 0.350825 0.933556 +-0.142361 0.328947 0.933556 +-0.037411 0.178700 0.983192 +-0.072514 0.167556 0.983192 +-0.000247 0.000570 1.000000 +-0.103453 0.150436 0.983192 +-0.072514 0.167556 0.983192 +-0.103453 0.150436 0.983192 +-0.000247 0.000570 1.000000 +-0.000352 0.000512 1.000000 +-0.000352 0.000512 1.000000 +-0.129099 0.129099 0.983192 +-0.103453 0.150436 0.983192 +-0.129099 0.129099 0.983192 +-0.000352 0.000512 1.000000 +-0.000439 0.000439 1.000000 +-0.072514 0.167556 0.983192 +-0.203099 0.295336 0.933556 +-0.142361 0.328947 0.933556 +-0.203099 0.295336 0.933556 +-0.072514 0.167556 0.983192 +-0.103453 0.150436 0.983192 +-0.103453 0.150436 0.983192 +-0.253449 0.253449 0.933556 +-0.203099 0.295336 0.933556 +-0.253449 0.253449 0.933556 +-0.103453 0.150436 0.983192 +-0.129099 0.129099 0.983192 +-0.000439 0.000439 1.000000 +-0.150436 0.103453 0.983192 +-0.129099 0.129099 0.983192 +-0.150436 0.103453 0.983192 +-0.000439 0.000439 1.000000 +-0.000512 0.000352 1.000000 +-0.000512 0.000352 1.000000 +-0.167556 0.072514 0.983192 +-0.150436 0.103453 0.983192 +-0.167556 0.072514 0.983192 +-0.000512 0.000352 1.000000 +-0.000570 0.000247 1.000000 +-0.129099 0.129099 0.983192 +-0.295336 0.203099 0.933556 +-0.253449 0.253449 0.933556 +-0.295336 0.203099 0.933556 +-0.129099 0.129099 0.983192 +-0.150436 0.103453 0.983192 +-0.150436 0.103453 0.983192 +-0.328947 0.142361 0.933556 +-0.295336 0.203099 0.933556 +-0.328947 0.142361 0.933556 +-0.150436 0.103453 0.983192 +-0.167556 0.072514 0.983192 +-0.000570 0.000247 1.000000 +-0.178700 0.037411 0.983192 +-0.167556 0.072514 0.983192 +-0.178700 0.037411 0.983192 +-0.000570 0.000247 1.000000 +-0.000608 0.000127 1.000000 +-0.167556 0.072514 0.983192 +-0.350825 0.073446 0.933556 +-0.328947 0.142361 0.933556 +-0.350825 0.073446 0.933556 +-0.167556 0.072514 0.983192 +-0.178700 0.037411 0.983192 +0.037411 -0.178700 0.983192 +0.065327 -0.353017 0.933333 +0.073446 -0.350825 0.933556 +0.203099 -0.295336 0.933556 +0.253859 -0.253859 0.933333 +0.253449 -0.253449 0.933556 +0.203099 -0.295336 0.933556 +0.226284 -0.278719 0.933333 +0.253859 -0.253859 0.933333 +0.203099 -0.295336 0.933556 +0.196454 -0.300491 0.933333 +0.226284 -0.278719 0.933333 +0.142361 -0.328947 0.933556 +0.196454 -0.300491 0.933333 +0.203099 -0.295336 0.933556 +0.142361 -0.328947 0.933556 +0.132150 -0.333804 0.933333 +0.196454 -0.300491 0.933333 +0.073446 -0.350825 0.933556 +0.132150 -0.333804 0.933333 +0.142361 -0.328947 0.933556 +0.073446 -0.350825 0.933556 +0.065327 -0.353017 0.933333 +0.132150 -0.333804 0.933333 +0.278719 -0.226284 0.933333 +0.253449 -0.253449 0.933556 +0.253859 -0.253859 0.933333 +0.278719 -0.226284 0.933333 +0.295336 -0.203099 0.933556 +0.253449 -0.253449 0.933556 +0.300491 -0.196454 0.933333 +0.295336 -0.203099 0.933556 +0.278719 -0.226284 0.933333 +0.300491 -0.196454 0.933333 +0.328947 -0.142361 0.933556 +0.295336 -0.203099 0.933556 +0.333804 -0.132150 0.933333 +0.328947 -0.142361 0.933556 +0.300491 -0.196454 0.933333 +0.333804 -0.132150 0.933333 +0.350825 -0.073446 0.933556 +0.328947 -0.142361 0.933556 +0.353017 -0.065327 0.933333 +0.350825 -0.073446 0.933556 +0.333804 -0.132150 0.933333 +0.065327 -0.353017 0.933333 +0.000000 -0.358431 0.933556 +0.000000 -0.359011 0.933333 +0.065327 -0.353017 0.933333 +0.000000 -0.182574 0.983192 +0.000000 -0.358431 0.933556 +0.000000 -0.000622 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -0.182574 0.983192 +0.000000 0.000000 1.000000 +0.000000 -0.000622 1.000000 +0.000000 0.000000 1.000000 +0.000622 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.182574 0.000000 0.983192 +0.000622 0.000000 1.000000 +0.358431 0.000000 0.933556 +0.353017 -0.065327 0.933333 +0.359011 0.000000 0.933333 +0.182574 0.000000 0.983192 +0.353017 -0.065327 0.933333 +0.358431 0.000000 0.933556 +0.353017 -0.065327 0.933333 +0.178700 -0.037411 0.983192 +0.350825 -0.073446 0.933556 +0.182574 0.000000 0.983192 +0.178700 -0.037411 0.983192 +0.353017 -0.065327 0.933333 +0.000000 0.000000 1.000000 +0.178700 -0.037411 0.983192 +0.182574 0.000000 0.983192 +0.000000 0.000000 1.000000 +0.000608 -0.000127 1.000000 +0.178700 -0.037411 0.983192 +0.000000 0.000000 1.000000 +0.000608 -0.000127 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000570 -0.000247 1.000000 +0.000608 -0.000127 1.000000 +0.000000 0.000000 1.000000 +0.000570 -0.000247 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000512 -0.000352 1.000000 +0.000570 -0.000247 1.000000 +0.000000 0.000000 1.000000 +0.000512 -0.000352 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000439 -0.000439 1.000000 +0.000512 -0.000352 1.000000 +0.000000 0.000000 1.000000 +0.000439 -0.000439 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000439 -0.000439 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000352 -0.000512 1.000000 +0.000439 -0.000439 1.000000 +0.000000 0.000000 1.000000 +0.000352 -0.000512 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000247 -0.000570 1.000000 +0.000352 -0.000512 1.000000 +0.000000 0.000000 1.000000 +0.000247 -0.000570 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000127 -0.000608 1.000000 +0.000247 -0.000570 1.000000 +0.000000 0.000000 1.000000 +0.000127 -0.000608 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.037411 -0.178700 0.983192 +0.000127 -0.000608 1.000000 +0.000000 -0.182574 0.983192 +0.037411 -0.178700 0.983192 +0.000000 0.000000 1.000000 +0.065327 -0.353017 0.933333 +0.037411 -0.178700 0.983192 +0.000000 -0.182574 0.983192 +0.350825 -0.073446 0.933556 +0.167556 -0.072514 0.983192 +0.328947 -0.142361 0.933556 +0.167556 -0.072514 0.983192 +0.350825 -0.073446 0.933556 +0.178700 -0.037411 0.983192 +0.328947 -0.142361 0.933556 +0.150436 -0.103453 0.983192 +0.295336 -0.203099 0.933556 +0.150436 -0.103453 0.983192 +0.328947 -0.142361 0.933556 +0.167556 -0.072514 0.983192 +0.295336 -0.203099 0.933556 +0.129099 -0.129099 0.983192 +0.253449 -0.253449 0.933556 +0.129099 -0.129099 0.983192 +0.295336 -0.203099 0.933556 +0.150436 -0.103453 0.983192 +0.178700 -0.037411 0.983192 +0.000570 -0.000247 1.000000 +0.167556 -0.072514 0.983192 +0.000570 -0.000247 1.000000 +0.178700 -0.037411 0.983192 +0.000608 -0.000127 1.000000 +0.167556 -0.072514 0.983192 +0.000512 -0.000352 1.000000 +0.150436 -0.103453 0.983192 +0.000512 -0.000352 1.000000 +0.167556 -0.072514 0.983192 +0.000570 -0.000247 1.000000 +0.150436 -0.103453 0.983192 +0.000439 -0.000439 1.000000 +0.129099 -0.129099 0.983192 +0.000439 -0.000439 1.000000 +0.150436 -0.103453 0.983192 +0.000512 -0.000352 1.000000 +0.253449 -0.253449 0.933556 +0.103453 -0.150436 0.983192 +0.203099 -0.295336 0.933556 +0.103453 -0.150436 0.983192 +0.253449 -0.253449 0.933556 +0.129099 -0.129099 0.983192 +0.203099 -0.295336 0.933556 +0.072514 -0.167556 0.983192 +0.142361 -0.328947 0.933556 +0.072514 -0.167556 0.983192 +0.203099 -0.295336 0.933556 +0.103453 -0.150436 0.983192 +0.142361 -0.328947 0.933556 +0.037411 -0.178700 0.983192 +0.073446 -0.350825 0.933556 +0.037411 -0.178700 0.983192 +0.142361 -0.328947 0.933556 +0.072514 -0.167556 0.983192 +0.129099 -0.129099 0.983192 +0.000352 -0.000512 1.000000 +0.103453 -0.150436 0.983192 +0.000352 -0.000512 1.000000 +0.129099 -0.129099 0.983192 +0.000439 -0.000439 1.000000 +0.103453 -0.150436 0.983192 +0.000247 -0.000570 1.000000 +0.072514 -0.167556 0.983192 +0.000247 -0.000570 1.000000 +0.103453 -0.150436 0.983192 +0.000352 -0.000512 1.000000 +0.072514 -0.167556 0.983192 +0.000127 -0.000608 1.000000 +0.037411 -0.178700 0.983192 +0.000127 -0.000608 1.000000 +0.072514 -0.167556 0.983192 +0.000247 -0.000570 1.000000 +0.000000 -0.076926 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.054395 -0.054395 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.063385 -0.043589 0.997037 +0.000000 0.000000 1.000000 +0.054395 -0.054395 0.997037 +0.063385 -0.043589 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.070598 -0.030553 0.997037 +0.000000 0.000000 1.000000 +0.063385 -0.043589 0.997037 +0.070598 -0.030553 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.075294 -0.015763 0.997037 +0.000000 0.000000 1.000000 +0.070598 -0.030553 0.997037 +0.075294 -0.015763 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.043589 -0.063385 0.997037 +0.054395 -0.054395 0.997037 +0.000000 0.000000 1.000000 +0.043589 -0.063385 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.043589 -0.063385 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.030553 -0.070598 0.997037 +0.043589 -0.063385 0.997037 +0.000000 0.000000 1.000000 +0.030553 -0.070598 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.015763 -0.075294 0.997037 +0.030553 -0.070598 0.997037 +0.000000 0.000000 1.000000 +0.015763 -0.075294 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.076926 0.000000 0.997037 +0.000000 0.000000 1.000000 +0.075294 -0.015763 0.997037 +0.076926 0.000000 0.997037 +0.000000 0.000000 1.000000 +0.261995 -0.054849 0.963509 +0.076926 0.000000 0.997037 +0.075294 -0.015763 0.997037 +0.261995 -0.054849 0.963509 +0.267675 0.000000 0.963509 +0.076926 0.000000 0.997037 +0.429224 -0.089859 0.898717 +0.267675 0.000000 0.963509 +0.261995 -0.054849 0.963509 +0.429224 -0.089859 0.898717 +0.438529 0.000000 0.898717 +0.267675 0.000000 0.963509 +0.582121 -0.121868 0.803917 +0.438529 0.000000 0.898717 +0.429224 -0.089859 0.898717 +0.582121 -0.121868 0.803917 +0.594741 0.000000 0.803917 +0.438529 0.000000 0.898717 +0.722881 -0.151336 0.674196 +0.594741 0.000000 0.803917 +0.582121 -0.121868 0.803917 +0.722881 -0.151336 0.674196 +0.738552 0.000000 0.674196 +0.594741 0.000000 0.803917 +0.722881 -0.151336 0.674196 +0.788227 0.000000 0.615385 +0.738552 0.000000 0.674196 +0.722881 -0.151336 0.674196 +0.775068 -0.143428 0.615385 +0.788227 0.000000 0.615385 +0.722881 -0.151336 0.674196 +0.732884 -0.290142 0.615385 +0.775068 -0.143428 0.615385 +0.677800 -0.293336 0.674196 +0.732884 -0.290142 0.615385 +0.722881 -0.151336 0.674196 +0.677800 -0.293336 0.674196 +0.659742 -0.431325 0.615385 +0.732884 -0.290142 0.615385 +0.608544 -0.418489 0.674196 +0.659742 -0.431325 0.615385 +0.677800 -0.293336 0.674196 +0.608544 -0.418489 0.674196 +0.611943 -0.496818 0.615385 +0.659742 -0.431325 0.615385 +0.522235 -0.522235 0.674196 +0.611943 -0.496818 0.615385 +0.608544 -0.418489 0.674196 +0.522235 -0.522235 0.674196 +0.557361 -0.557361 0.615385 +0.611943 -0.496818 0.615385 +0.418489 -0.608544 0.674196 +0.557361 -0.557361 0.615385 +0.522235 -0.522235 0.674196 +0.418489 -0.608544 0.674196 +0.496818 -0.611943 0.615385 +0.557361 -0.557361 0.615385 +0.418489 -0.608544 0.674196 +0.431325 -0.659742 0.615385 +0.496818 -0.611943 0.615385 +0.293336 -0.677800 0.674196 +0.431325 -0.659742 0.615385 +0.418489 -0.608544 0.674196 +0.293336 -0.677800 0.674196 +0.290142 -0.732884 0.615385 +0.431325 -0.659742 0.615385 +0.151336 -0.722881 0.674196 +0.290142 -0.732884 0.615385 +0.293336 -0.677800 0.674196 +0.151336 -0.722881 0.674196 +0.143428 -0.775068 0.615385 +0.290142 -0.732884 0.615385 +0.143428 -0.775068 0.615385 +0.000000 -0.738552 0.674196 +0.000000 -0.788227 0.615385 +0.151336 -0.722881 0.674196 +0.000000 -0.738552 0.674196 +0.143428 -0.775068 0.615385 +0.121868 -0.582121 0.803917 +0.000000 -0.738552 0.674196 +0.151336 -0.722881 0.674196 +0.121868 -0.582121 0.803917 +0.000000 -0.594741 0.803917 +0.000000 -0.738552 0.674196 +0.089859 -0.429224 0.898717 +0.000000 -0.594741 0.803917 +0.121868 -0.582121 0.803917 +0.089859 -0.429224 0.898717 +0.000000 -0.438529 0.898717 +0.000000 -0.594741 0.803917 +0.054849 -0.261995 0.963509 +0.000000 -0.438529 0.898717 +0.089859 -0.429224 0.898717 +0.054849 -0.261995 0.963509 +0.000000 -0.267675 0.963509 +0.000000 -0.438529 0.898717 +0.015763 -0.075294 0.997037 +0.000000 -0.267675 0.963509 +0.054849 -0.261995 0.963509 +0.015763 -0.075294 0.997037 +0.000000 -0.076926 0.997037 +0.000000 -0.267675 0.963509 +0.000000 0.000000 1.000000 +0.000000 -0.076926 0.997037 +0.015763 -0.075294 0.997037 +0.722881 -0.151336 0.674196 +0.545819 -0.236218 0.803917 +0.677800 -0.293336 0.674196 +0.545819 -0.236218 0.803917 +0.722881 -0.151336 0.674196 +0.582121 -0.121868 0.803917 +0.582121 -0.121868 0.803917 +0.402456 -0.174174 0.898717 +0.545819 -0.236218 0.803917 +0.402456 -0.174174 0.898717 +0.582121 -0.121868 0.803917 +0.429224 -0.089859 0.898717 +0.429224 -0.089859 0.898717 +0.245656 -0.106314 0.963509 +0.402456 -0.174174 0.898717 +0.245656 -0.106314 0.963509 +0.429224 -0.089859 0.898717 +0.261995 -0.054849 0.963509 +0.261995 -0.054849 0.963509 +0.070598 -0.030553 0.997037 +0.245656 -0.106314 0.963509 +0.070598 -0.030553 0.997037 +0.261995 -0.054849 0.963509 +0.075294 -0.015763 0.997037 +0.677800 -0.293336 0.674196 +0.490048 -0.337001 0.803917 +0.608544 -0.418489 0.674196 +0.490048 -0.337001 0.803917 +0.677800 -0.293336 0.674196 +0.545819 -0.236218 0.803917 +0.545819 -0.236218 0.803917 +0.361334 -0.248486 0.898717 +0.490048 -0.337001 0.803917 +0.361334 -0.248486 0.898717 +0.545819 -0.236218 0.803917 +0.402456 -0.174174 0.898717 +0.608544 -0.418489 0.674196 +0.420546 -0.420546 0.803917 +0.522235 -0.522235 0.674196 +0.420546 -0.420546 0.803917 +0.608544 -0.418489 0.674196 +0.490048 -0.337001 0.803917 +0.490048 -0.337001 0.803917 +0.310087 -0.310087 0.898717 +0.420546 -0.420546 0.803917 +0.310087 -0.310087 0.898717 +0.490048 -0.337001 0.803917 +0.361334 -0.248486 0.898717 +0.402456 -0.174174 0.898717 +0.220556 -0.151674 0.963509 +0.361334 -0.248486 0.898717 +0.220556 -0.151674 0.963509 +0.402456 -0.174174 0.898717 +0.245656 -0.106314 0.963509 +0.245656 -0.106314 0.963509 +0.063385 -0.043589 0.997037 +0.220556 -0.151674 0.963509 +0.063385 -0.043589 0.997037 +0.245656 -0.106314 0.963509 +0.070598 -0.030553 0.997037 +0.361334 -0.248486 0.898717 +0.189275 -0.189275 0.963509 +0.310087 -0.310087 0.898717 +0.189275 -0.189275 0.963509 +0.361334 -0.248486 0.898717 +0.220556 -0.151674 0.963509 +0.220556 -0.151674 0.963509 +0.054395 -0.054395 0.997037 +0.189275 -0.189275 0.963509 +0.054395 -0.054395 0.997037 +0.220556 -0.151674 0.963509 +0.063385 -0.043589 0.997037 +0.522235 -0.522235 0.674196 +0.337001 -0.490048 0.803917 +0.418489 -0.608544 0.674196 +0.337001 -0.490048 0.803917 +0.522235 -0.522235 0.674196 +0.420546 -0.420546 0.803917 +0.420546 -0.420546 0.803917 +0.248486 -0.361334 0.898717 +0.337001 -0.490048 0.803917 +0.248486 -0.361334 0.898717 +0.420546 -0.420546 0.803917 +0.310087 -0.310087 0.898717 +0.418489 -0.608544 0.674196 +0.236218 -0.545819 0.803917 +0.293336 -0.677800 0.674196 +0.236218 -0.545819 0.803917 +0.418489 -0.608544 0.674196 +0.337001 -0.490048 0.803917 +0.337001 -0.490048 0.803917 +0.174174 -0.402456 0.898717 +0.236218 -0.545819 0.803917 +0.174174 -0.402456 0.898717 +0.337001 -0.490048 0.803917 +0.248486 -0.361334 0.898717 +0.310087 -0.310087 0.898717 +0.151674 -0.220556 0.963509 +0.248486 -0.361334 0.898717 +0.151674 -0.220556 0.963509 +0.310087 -0.310087 0.898717 +0.189275 -0.189275 0.963509 +0.189275 -0.189275 0.963509 +0.043589 -0.063385 0.997037 +0.151674 -0.220556 0.963509 +0.043589 -0.063385 0.997037 +0.189275 -0.189275 0.963509 +0.054395 -0.054395 0.997037 +0.248486 -0.361334 0.898717 +0.106314 -0.245656 0.963509 +0.174174 -0.402456 0.898717 +0.106314 -0.245656 0.963509 +0.248486 -0.361334 0.898717 +0.151674 -0.220556 0.963509 +0.151674 -0.220556 0.963509 +0.030553 -0.070598 0.997037 +0.106314 -0.245656 0.963509 +0.030553 -0.070598 0.997037 +0.151674 -0.220556 0.963509 +0.043589 -0.063385 0.997037 +0.293336 -0.677800 0.674196 +0.121868 -0.582121 0.803917 +0.151336 -0.722881 0.674196 +0.121868 -0.582121 0.803917 +0.293336 -0.677800 0.674196 +0.236218 -0.545819 0.803917 +0.236218 -0.545819 0.803917 +0.089859 -0.429224 0.898717 +0.121868 -0.582121 0.803917 +0.089859 -0.429224 0.898717 +0.236218 -0.545819 0.803917 +0.174174 -0.402456 0.898717 +0.174174 -0.402456 0.898717 +0.054849 -0.261995 0.963509 +0.089859 -0.429224 0.898717 +0.054849 -0.261995 0.963509 +0.174174 -0.402456 0.898717 +0.106314 -0.245656 0.963509 +0.106314 -0.245656 0.963509 +0.015763 -0.075294 0.997037 +0.054849 -0.261995 0.963509 +0.015763 -0.075294 0.997037 +0.106314 -0.245656 0.963509 +0.030553 -0.070598 0.997037 +0.983268 0.181956 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +-0.983268 0.181956 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.983268 0.181956 0.008727 +-0.983268 0.181956 0.008727 +-0.999962 0.000000 0.008727 +-0.929753 0.368081 0.008727 +-0.983268 0.181956 0.008727 +-0.983268 0.181956 0.008727 +-0.929753 0.368081 0.008727 +-0.929753 0.368081 0.008727 +-0.983268 0.181956 0.008727 +-0.929753 0.368081 0.008727 +-0.836964 0.547189 0.008727 +-0.929753 0.368081 0.008727 +-0.836964 0.547189 0.008727 +-0.836964 0.547189 0.008727 +-0.929753 0.368081 0.008727 +-0.836964 0.547189 0.008727 +-0.707080 0.707080 0.008727 +-0.836964 0.547189 0.008727 +-0.707080 0.707080 0.008727 +-0.707080 0.707080 0.008727 +-0.836964 0.547189 0.008727 +-0.547189 0.836964 0.008727 +-0.707080 0.707080 0.008727 +-0.707080 0.707080 0.008727 +-0.547189 0.836964 0.008727 +-0.547189 0.836964 0.008727 +-0.707080 0.707080 0.008727 +-0.368081 0.929753 0.008727 +-0.547189 0.836964 0.008727 +-0.547189 0.836964 0.008727 +-0.368081 0.929753 0.008727 +-0.368081 0.929753 0.008727 +-0.547189 0.836964 0.008727 +-0.368081 0.929753 0.008727 +-0.181956 0.983268 0.008727 +-0.368081 0.929753 0.008727 +-0.181956 0.983268 0.008727 +-0.181956 0.983268 0.008727 +-0.368081 0.929753 0.008727 +0.000000 0.999962 0.008727 +-0.181956 0.983268 0.008727 +-0.181956 0.983268 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +-0.181956 0.983268 0.008727 +0.000000 0.999962 0.008727 +0.181956 0.983268 0.008727 +0.000000 0.999962 0.008727 +0.181956 0.983268 0.008727 +0.181956 0.983268 0.008727 +0.000000 0.999962 0.008727 +0.368081 0.929753 0.008727 +0.181956 0.983268 0.008727 +0.181956 0.983268 0.008727 +0.368081 0.929753 0.008727 +0.368081 0.929753 0.008727 +0.181956 0.983268 0.008727 +0.547189 0.836964 0.008727 +0.368081 0.929753 0.008727 +0.368081 0.929753 0.008727 +0.547189 0.836964 0.008727 +0.547189 0.836964 0.008727 +0.368081 0.929753 0.008727 +0.547189 0.836964 0.008727 +0.707080 0.707080 0.008727 +0.547189 0.836964 0.008727 +0.707080 0.707080 0.008727 +0.707080 0.707080 0.008727 +0.547189 0.836964 0.008727 +0.836964 0.547189 0.008727 +0.707080 0.707080 0.008727 +0.707080 0.707080 0.008727 +0.836964 0.547189 0.008727 +0.836964 0.547189 0.008727 +0.707080 0.707080 0.008727 +0.836964 0.547189 0.008727 +0.929753 0.368081 0.008727 +0.836964 0.547189 0.008727 +0.929753 0.368081 0.008727 +0.929753 0.368081 0.008727 +0.836964 0.547189 0.008727 +0.983268 0.181956 0.008727 +0.929753 0.368081 0.008727 +0.929753 0.368081 0.008727 +0.983268 0.181956 0.008727 +0.983268 0.181956 0.008727 +0.929753 0.368081 0.008727 +0.999962 0.000000 0.008727 +0.983268 0.181956 0.008727 +0.983268 0.181956 0.008727 +0.983268 0.181956 0.008727 +0.999962 0.000000 0.008727 +0.999962 0.000000 0.008727 +-0.983268 0.181956 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.983268 0.181956 0.008727 +-0.983268 0.181956 0.008727 +-0.999962 0.000000 0.008727 +-0.929753 0.368081 0.008727 +-0.983268 0.181956 0.008727 +-0.983268 0.181956 0.008727 +-0.929753 0.368081 0.008727 +-0.929753 0.368081 0.008727 +-0.983268 0.181956 0.008727 +-0.836964 0.547189 0.008727 +-0.929753 0.368081 0.008727 +-0.929753 0.368081 0.008727 +-0.836964 0.547189 0.008727 +-0.836964 0.547189 0.008727 +-0.929753 0.368081 0.008727 +-0.707080 0.707080 0.008727 +-0.836964 0.547189 0.008727 +-0.836964 0.547189 0.008727 +-0.707080 0.707080 0.008727 +-0.707080 0.707080 0.008727 +-0.836964 0.547189 0.008727 +-0.547189 0.836964 0.008727 +-0.707080 0.707080 0.008727 +-0.707080 0.707080 0.008727 +-0.547189 0.836964 0.008727 +-0.547189 0.836964 0.008727 +-0.707080 0.707080 0.008727 +-0.547189 0.836964 0.008727 +-0.368081 0.929753 0.008727 +-0.547189 0.836964 0.008727 +-0.368081 0.929753 0.008727 +-0.368081 0.929753 0.008727 +-0.547189 0.836964 0.008727 +-0.181956 0.983268 0.008727 +-0.368081 0.929753 0.008727 +-0.368081 0.929753 0.008727 +-0.181956 0.983268 0.008727 +-0.181956 0.983268 0.008727 +-0.368081 0.929753 0.008727 +-0.181956 0.983268 0.008727 +0.000000 0.999962 0.008727 +-0.181956 0.983268 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +-0.181956 0.983268 0.008727 +0.181956 0.983268 0.008727 +0.000000 0.999962 0.008727 +0.000000 0.999962 0.008727 +0.181956 0.983268 0.008727 +0.181956 0.983268 0.008727 +0.000000 0.999962 0.008727 +0.368081 0.929753 0.008727 +0.181956 0.983268 0.008727 +0.181956 0.983268 0.008727 +0.368081 0.929753 0.008727 +0.368081 0.929753 0.008727 +0.181956 0.983268 0.008727 +0.547189 0.836964 0.008727 +0.368081 0.929753 0.008727 +0.368081 0.929753 0.008727 +0.547189 0.836964 0.008727 +0.547189 0.836964 0.008727 +0.368081 0.929753 0.008727 +0.547189 0.836964 0.008727 +0.707080 0.707080 0.008727 +0.547189 0.836964 0.008727 +0.707080 0.707080 0.008727 +0.707080 0.707080 0.008727 +0.547189 0.836964 0.008727 +0.836964 0.547189 0.008727 +0.707080 0.707080 0.008727 +0.707080 0.707080 0.008727 +0.836964 0.547189 0.008727 +0.836964 0.547189 0.008727 +0.707080 0.707080 0.008727 +0.929753 0.368081 0.008727 +0.836964 0.547189 0.008727 +0.836964 0.547189 0.008727 +0.929753 0.368081 0.008727 +0.929753 0.368081 0.008727 +0.836964 0.547189 0.008727 +0.983268 0.181956 0.008727 +0.929753 0.368081 0.008727 +0.929753 0.368081 0.008727 +0.983268 0.181956 0.008727 +0.983268 0.181956 0.008727 +0.929753 0.368081 0.008727 +0.999962 0.000000 0.008727 +0.983268 0.181956 0.008727 +0.983268 0.181956 0.008727 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.696201 0.717828 -0.005236 +0.740515 0.672020 -0.005236 +0.735683 0.677306 -0.005236 +0.999387 0.034615 -0.005236 +0.975519 0.219851 -0.005236 +0.999520 0.030542 -0.005236 +0.975519 0.219851 -0.005236 +0.975519 0.219851 -0.005236 +0.999387 0.034615 -0.005236 +0.911548 0.411160 -0.005236 +0.975519 0.219851 -0.005236 +0.975519 0.219851 -0.005236 +0.911548 0.411160 -0.005236 +0.911548 0.411160 -0.005236 +0.975519 0.219851 -0.005236 +0.815196 0.579161 -0.005236 +0.911548 0.411160 -0.005236 +0.911548 0.411160 -0.005236 +0.815196 0.579161 -0.005236 +0.815196 0.579161 -0.005236 +0.911548 0.411160 -0.005236 +0.783400 0.621495 -0.005236 +0.815196 0.579161 -0.005236 +0.815196 0.579161 -0.005236 +0.774450 0.632613 -0.005236 +0.815196 0.579161 -0.005236 +0.783400 0.621495 -0.005236 +0.774450 0.632613 -0.005236 +0.696201 0.717828 -0.005236 +0.815196 0.579161 -0.005236 +0.740515 0.672020 -0.005236 +0.696201 0.717828 -0.005236 +0.774450 0.632613 -0.005236 +0.000000 0.999986 -0.005236 +0.189914 0.981787 -0.005236 +0.000000 0.999986 -0.005236 +0.189914 0.981787 -0.005236 +0.189914 0.981787 -0.005236 +0.000000 0.999986 -0.005236 +0.383091 0.923696 -0.005236 +0.189914 0.981787 -0.005236 +0.189914 0.981787 -0.005236 +0.383091 0.923696 -0.005236 +0.383091 0.923696 -0.005236 +0.189914 0.981787 -0.005236 +0.383091 0.923696 -0.005236 +0.553960 0.832527 -0.005236 +0.383091 0.923696 -0.005236 +0.553960 0.832527 -0.005236 +0.553960 0.832527 -0.005236 +0.383091 0.923696 -0.005236 +0.696201 0.717828 -0.005236 +0.553960 0.832527 -0.005236 +0.553960 0.832527 -0.005236 +0.696201 0.717828 -0.005236 +0.696201 0.717828 -0.005236 +0.553960 0.832527 -0.005236 +0.740515 0.672020 -0.005236 +0.696201 0.717828 -0.005236 +0.696201 0.717828 -0.005236 +0.993341 0.027865 -0.111795 +0.993210 0.032171 -0.111795 +0.993210 0.032169 -0.111795 +0.177662 0.977721 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.177662 0.977721 -0.111795 +0.189955 0.975407 -0.111795 +0.000000 0.993731 -0.111795 +0.359201 0.926540 -0.111795 +0.189955 0.975407 -0.111795 +0.177662 0.977721 -0.111795 +0.359201 0.926540 -0.111795 +0.381850 0.917438 -0.111795 +0.189955 0.975407 -0.111795 +0.534168 0.837954 -0.111795 +0.381850 0.917438 -0.111795 +0.359201 0.926540 -0.111795 +0.534168 0.837954 -0.111795 +0.551536 0.826625 -0.111795 +0.381850 0.917438 -0.111795 +0.691206 0.713958 -0.111795 +0.551536 0.826625 -0.111795 +0.534168 0.837954 -0.111795 +0.691206 0.713958 -0.111795 +0.692744 0.712466 -0.111795 +0.551536 0.826625 -0.111795 +0.820221 0.561016 -0.111795 +0.692744 0.712466 -0.111795 +0.691206 0.713958 -0.111795 +0.820221 0.561016 -0.111795 +0.810821 0.574518 -0.111795 +0.692744 0.712466 -0.111795 +0.820221 0.561016 -0.111795 +0.906360 0.407447 -0.111795 +0.810821 0.574518 -0.111795 +0.914425 0.389009 -0.111795 +0.906360 0.407447 -0.111795 +0.820221 0.561016 -0.111795 +0.914425 0.389009 -0.111795 +0.969692 0.217254 -0.111795 +0.906360 0.407447 -0.111795 +0.971457 0.209222 -0.111795 +0.969692 0.217254 -0.111795 +0.914425 0.389009 -0.111795 +0.971457 0.209222 -0.111795 +0.993268 0.030351 -0.111795 +0.969692 0.217254 -0.111795 +0.993210 0.032171 -0.111795 +0.993268 0.030351 -0.111795 +0.971457 0.209222 -0.111795 +0.993210 0.032171 -0.111795 +0.993341 0.027865 -0.111795 +0.993268 0.030351 -0.111795 +-0.814136 0.580650 -0.005236 +-0.774450 0.632613 -0.005236 +-0.783400 0.621495 -0.005236 +0.000000 0.999986 -0.005236 +-0.178596 0.983908 -0.005236 +0.000000 0.999986 -0.005236 +-0.188120 0.982132 -0.005236 +-0.178596 0.983908 -0.005236 +0.000000 0.999986 -0.005236 +-0.188120 0.982132 -0.005236 +-0.361080 0.932520 -0.005236 +-0.178596 0.983908 -0.005236 +-0.381402 0.924395 -0.005236 +-0.361080 0.932520 -0.005236 +-0.188120 0.982132 -0.005236 +-0.381402 0.924395 -0.005236 +-0.536972 0.843584 -0.005236 +-0.361080 0.932520 -0.005236 +-0.552437 0.833538 -0.005236 +-0.536972 0.843584 -0.005236 +-0.381402 0.924395 -0.005236 +-0.552437 0.833538 -0.005236 +-0.694889 0.719098 -0.005236 +-0.536972 0.843584 -0.005236 +-0.694888 0.719099 -0.005236 +-0.694889 0.719098 -0.005236 +-0.552437 0.833538 -0.005236 +-0.735683 0.677306 -0.005236 +-0.694889 0.719098 -0.005236 +-0.694888 0.719099 -0.005236 +-0.740515 0.672020 -0.005236 +-0.694889 0.719098 -0.005236 +-0.735683 0.677306 -0.005236 +-0.740515 0.672020 -0.005236 +-0.824708 0.565535 -0.005236 +-0.694889 0.719098 -0.005236 +-0.774450 0.632613 -0.005236 +-0.824708 0.565535 -0.005236 +-0.740515 0.672020 -0.005236 +-0.977218 0.212173 -0.005236 +-0.999387 0.034615 -0.005236 +-0.999400 0.034232 -0.005236 +-0.977218 0.212173 -0.005236 +-0.975116 0.221634 -0.005236 +-0.999387 0.034615 -0.005236 +-0.919613 0.392791 -0.005236 +-0.975116 0.221634 -0.005236 +-0.977218 0.212173 -0.005236 +-0.919613 0.392791 -0.005236 +-0.910795 0.412826 -0.005236 +-0.975116 0.221634 -0.005236 +-0.824708 0.565535 -0.005236 +-0.910795 0.412826 -0.005236 +-0.919613 0.392791 -0.005236 +-0.824708 0.565535 -0.005236 +-0.814136 0.580650 -0.005236 +-0.910795 0.412826 -0.005236 +-0.774450 0.632613 -0.005236 +-0.814136 0.580650 -0.005236 +-0.824708 0.565535 -0.005236 +-0.971457 0.209222 -0.111795 +-0.993149 0.034018 -0.111795 +-0.993210 0.032171 -0.111795 +0.000000 0.993731 -0.111795 +-0.177662 0.977721 -0.111795 +0.000000 0.993731 -0.111795 +-0.187843 0.975816 -0.111795 +-0.177662 0.977721 -0.111795 +0.000000 0.993731 -0.111795 +-0.187843 0.975816 -0.111795 +-0.359201 0.926540 -0.111795 +-0.177662 0.977721 -0.111795 +-0.379863 0.918262 -0.111795 +-0.359201 0.926540 -0.111795 +-0.187843 0.975816 -0.111795 +-0.379863 0.918262 -0.111795 +-0.534168 0.837954 -0.111795 +-0.359201 0.926540 -0.111795 +-0.549746 0.827817 -0.111795 +-0.534168 0.837954 -0.111795 +-0.379863 0.918262 -0.111795 +-0.549746 0.827817 -0.111795 +-0.691206 0.713958 -0.111795 +-0.534168 0.837954 -0.111795 +-0.691200 0.713964 -0.111795 +-0.691206 0.713958 -0.111795 +-0.549746 0.827817 -0.111795 +-0.809576 0.576272 -0.111795 +-0.691206 0.713958 -0.111795 +-0.691200 0.713964 -0.111795 +-0.809576 0.576272 -0.111795 +-0.820221 0.561016 -0.111795 +-0.691206 0.713958 -0.111795 +-0.905476 0.409408 -0.111795 +-0.820221 0.561016 -0.111795 +-0.809576 0.576272 -0.111795 +-0.905476 0.409408 -0.111795 +-0.914425 0.389009 -0.111795 +-0.820221 0.561016 -0.111795 +-0.969219 0.219353 -0.111795 +-0.914425 0.389009 -0.111795 +-0.905476 0.409408 -0.111795 +-0.969219 0.219353 -0.111795 +-0.971457 0.209222 -0.111795 +-0.914425 0.389009 -0.111795 +-0.993149 0.034018 -0.111795 +-0.971457 0.209222 -0.111795 +-0.969219 0.219353 -0.111795 +0.000000 -0.999986 -0.005236 +0.000000 -0.999986 -0.005236 +0.000000 -0.999986 -0.005236 +0.000000 -0.999986 -0.005236 +0.000000 -0.999986 -0.005236 +0.000000 -0.999986 -0.005236 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.999986 -0.005236 +0.000000 -0.999986 -0.005236 +0.000000 -0.999986 -0.005236 +0.000000 -0.999986 -0.005236 +0.000000 -0.999986 -0.005236 +0.000000 -0.999986 -0.005236 +0.000000 -0.999986 -0.005236 +0.000000 -0.999986 -0.005236 +0.000000 -0.999986 -0.005236 +0.000000 -0.999986 -0.005236 +0.000000 -0.999986 -0.005236 +0.000000 -0.999986 -0.005236 +0.000000 -0.999986 -0.005236 +0.000000 -0.999986 -0.005236 +0.000000 -0.999986 -0.005236 +0.000000 -0.999986 -0.005236 +0.000000 -0.999986 -0.005236 +0.000000 -0.999986 -0.005236 +0.000000 -0.999986 -0.005236 +0.000000 -0.999986 -0.005236 +0.000000 -0.999986 -0.005236 +0.000000 -0.999986 -0.005236 +0.000000 -0.999986 -0.005236 +0.000000 -0.999986 -0.005236 +0.000000 -0.999986 -0.005236 +0.000000 -0.999986 -0.005236 +0.000000 -0.999986 -0.005236 +0.000000 -0.999986 -0.005236 +0.000000 -0.999986 -0.005236 +0.000000 -0.999986 -0.005236 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.999986 -0.005236 +0.000000 -0.999986 -0.005236 +0.000000 -0.999986 -0.005236 +0.000000 -0.999986 -0.005236 +0.000000 -0.999986 -0.005236 +0.000000 -0.999986 -0.005236 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.929753 -0.368081 0.008727 +0.983268 -0.181956 0.008727 +0.983268 -0.181956 0.008727 +0.999962 0.000000 0.008727 +0.983268 -0.181956 0.008727 +0.999962 0.000000 0.008727 +0.983268 -0.181956 0.008727 +0.983268 -0.181956 0.008727 +0.999962 0.000000 0.008727 +-0.983268 -0.181956 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.983268 -0.181956 0.008727 +-0.983268 -0.181956 0.008727 +-0.999962 0.000000 0.008727 +-0.929753 -0.368081 0.008727 +-0.983268 -0.181956 0.008727 +-0.983268 -0.181956 0.008727 +-0.929753 -0.368081 0.008727 +-0.929753 -0.368081 0.008727 +-0.983268 -0.181956 0.008727 +-0.836964 -0.547189 0.008727 +-0.929753 -0.368081 0.008727 +-0.929753 -0.368081 0.008727 +-0.836964 -0.547189 0.008727 +-0.836964 -0.547189 0.008727 +-0.929753 -0.368081 0.008727 +-0.707080 -0.707080 0.008727 +-0.836964 -0.547189 0.008727 +-0.836964 -0.547189 0.008727 +-0.707080 -0.707080 0.008727 +-0.707080 -0.707080 0.008727 +-0.836964 -0.547189 0.008727 +-0.547189 -0.836964 0.008727 +-0.707080 -0.707080 0.008727 +-0.707080 -0.707080 0.008727 +-0.547189 -0.836964 0.008727 +-0.547189 -0.836964 0.008727 +-0.707080 -0.707080 0.008727 +-0.547189 -0.836964 0.008727 +-0.368081 -0.929753 0.008727 +-0.547189 -0.836964 0.008727 +-0.368081 -0.929753 0.008727 +-0.368081 -0.929753 0.008727 +-0.547189 -0.836964 0.008727 +-0.181956 -0.983268 0.008727 +-0.368081 -0.929753 0.008727 +-0.368081 -0.929753 0.008727 +-0.181956 -0.983268 0.008727 +-0.181956 -0.983268 0.008727 +-0.368081 -0.929753 0.008727 +0.000000 -0.999962 0.008727 +-0.181956 -0.983268 0.008727 +-0.181956 -0.983268 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +-0.181956 -0.983268 0.008727 +0.000000 -0.999962 0.008727 +0.181956 -0.983268 0.008727 +0.000000 -0.999962 0.008727 +0.181956 -0.983268 0.008727 +0.181956 -0.983268 0.008727 +0.000000 -0.999962 0.008727 +0.181956 -0.983268 0.008727 +0.368081 -0.929753 0.008727 +0.181956 -0.983268 0.008727 +0.368081 -0.929753 0.008727 +0.368081 -0.929753 0.008727 +0.181956 -0.983268 0.008727 +0.547189 -0.836964 0.008727 +0.368081 -0.929753 0.008727 +0.368081 -0.929753 0.008727 +0.547189 -0.836964 0.008727 +0.547189 -0.836964 0.008727 +0.368081 -0.929753 0.008727 +0.707080 -0.707080 0.008727 +0.547189 -0.836964 0.008727 +0.547189 -0.836964 0.008727 +0.707080 -0.707080 0.008727 +0.707080 -0.707080 0.008727 +0.547189 -0.836964 0.008727 +0.836964 -0.547189 0.008727 +0.707080 -0.707080 0.008727 +0.707080 -0.707080 0.008727 +0.836964 -0.547189 0.008727 +0.836964 -0.547189 0.008727 +0.707080 -0.707080 0.008727 +0.929753 -0.368081 0.008727 +0.836964 -0.547189 0.008727 +0.836964 -0.547189 0.008727 +0.929753 -0.368081 0.008727 +0.929753 -0.368081 0.008727 +0.836964 -0.547189 0.008727 +0.983268 -0.181956 0.008727 +0.929753 -0.368081 0.008727 +0.929753 -0.368081 0.008727 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.547189 -0.836964 0.008727 +0.368081 -0.929753 0.008727 +0.368081 -0.929753 0.008727 +-0.999962 0.000000 0.008727 +-0.983268 -0.181956 0.008727 +-0.999962 0.000000 0.008727 +-0.983268 -0.181956 0.008727 +-0.983268 -0.181956 0.008727 +-0.999962 0.000000 0.008727 +-0.983268 -0.181956 0.008727 +-0.929753 -0.368081 0.008727 +-0.983268 -0.181956 0.008727 +-0.929753 -0.368081 0.008727 +-0.929753 -0.368081 0.008727 +-0.983268 -0.181956 0.008727 +-0.836964 -0.547189 0.008727 +-0.929753 -0.368081 0.008727 +-0.929753 -0.368081 0.008727 +-0.836964 -0.547189 0.008727 +-0.836964 -0.547189 0.008727 +-0.929753 -0.368081 0.008727 +-0.707080 -0.707080 0.008727 +-0.836964 -0.547189 0.008727 +-0.836964 -0.547189 0.008727 +-0.707080 -0.707080 0.008727 +-0.707080 -0.707080 0.008727 +-0.836964 -0.547189 0.008727 +-0.547189 -0.836964 0.008727 +-0.707080 -0.707080 0.008727 +-0.707080 -0.707080 0.008727 +-0.547189 -0.836964 0.008727 +-0.547189 -0.836964 0.008727 +-0.707080 -0.707080 0.008727 +-0.547189 -0.836964 0.008727 +-0.368081 -0.929753 0.008727 +-0.547189 -0.836964 0.008727 +-0.368081 -0.929753 0.008727 +-0.368081 -0.929753 0.008727 +-0.547189 -0.836964 0.008727 +-0.181956 -0.983268 0.008727 +-0.368081 -0.929753 0.008727 +-0.368081 -0.929753 0.008727 +-0.181956 -0.983268 0.008727 +-0.181956 -0.983268 0.008727 +-0.368081 -0.929753 0.008727 +-0.181956 -0.983268 0.008727 +0.000000 -0.999962 0.008727 +-0.181956 -0.983268 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +-0.181956 -0.983268 0.008727 +0.000000 -0.999962 0.008727 +0.181956 -0.983268 0.008727 +0.000000 -0.999962 0.008727 +0.181956 -0.983268 0.008727 +0.181956 -0.983268 0.008727 +0.000000 -0.999962 0.008727 +0.368081 -0.929753 0.008727 +0.181956 -0.983268 0.008727 +0.181956 -0.983268 0.008727 +0.368081 -0.929753 0.008727 +0.368081 -0.929753 0.008727 +0.181956 -0.983268 0.008727 +0.999962 0.000000 0.008727 +0.983268 -0.181956 0.008727 +0.999962 0.000000 0.008727 +0.983268 -0.181956 0.008727 +0.983268 -0.181956 0.008727 +0.999962 0.000000 0.008727 +0.983268 -0.181956 0.008727 +0.929753 -0.368081 0.008727 +0.983268 -0.181956 0.008727 +0.929753 -0.368081 0.008727 +0.929753 -0.368081 0.008727 +0.983268 -0.181956 0.008727 +0.836964 -0.547189 0.008727 +0.929753 -0.368081 0.008727 +0.929753 -0.368081 0.008727 +0.836964 -0.547189 0.008727 +0.836964 -0.547189 0.008727 +0.929753 -0.368081 0.008727 +0.707080 -0.707080 0.008727 +0.836964 -0.547189 0.008727 +0.836964 -0.547189 0.008727 +0.707080 -0.707080 0.008727 +0.707080 -0.707080 0.008727 +0.836964 -0.547189 0.008727 +0.707080 -0.707080 0.008727 +0.547189 -0.836964 0.008727 +0.707080 -0.707080 0.008727 +0.547189 -0.836964 0.008727 +0.547189 -0.836964 0.008727 +0.707080 -0.707080 0.008727 +0.368081 -0.929753 0.008727 +0.547189 -0.836964 0.008727 +0.547189 -0.836964 0.008727 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.896707 0.442624 0.000000 +-0.794569 0.607174 0.000000 +-0.896707 0.442624 0.000000 +-0.967295 0.253653 0.000000 +-0.994987 0.100000 0.000000 +-0.994987 0.100000 0.000000 +-0.967295 0.253653 0.000000 +-0.967295 0.253653 0.000000 +-0.994987 0.100000 0.000000 +-0.967295 0.253653 0.000000 +-0.896707 0.442624 0.000000 +-0.967295 0.253653 0.000000 +-0.896707 0.442624 0.000000 +-0.896707 0.442624 0.000000 +-0.967295 0.253653 0.000000 +-0.155652 0.987812 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.155652 0.987812 0.000000 +-0.155652 0.987812 0.000000 +0.000000 1.000000 0.000000 +-0.155652 0.987812 0.000000 +-0.350735 0.936475 0.000000 +-0.155652 0.987812 0.000000 +-0.350735 0.936475 0.000000 +-0.350735 0.936475 0.000000 +-0.155652 0.987812 0.000000 +-0.350735 0.936475 0.000000 +-0.524674 0.851303 0.000000 +-0.350735 0.936475 0.000000 +-0.524674 0.851303 0.000000 +-0.524674 0.851303 0.000000 +-0.350735 0.936475 0.000000 +-0.670820 0.741620 0.000000 +-0.524674 0.851303 0.000000 +-0.524674 0.851303 0.000000 +-0.670820 0.741620 0.000000 +-0.670820 0.741620 0.000000 +-0.524674 0.851303 0.000000 +-0.794569 0.607174 0.000000 +-0.670820 0.741620 0.000000 +-0.670820 0.741620 0.000000 +-0.794569 0.607174 0.000000 +-0.794569 0.607174 0.000000 +-0.670820 0.741620 0.000000 +-0.794569 0.607174 0.000000 +-0.896707 0.442624 0.000000 +-0.794569 0.607174 0.000000 +0.000000 -1.000000 0.000000 +-0.155652 -0.987812 0.000000 +0.000000 -1.000000 0.000000 +-0.967295 -0.253653 0.000000 +-0.994987 -0.100000 0.000000 +-0.994987 -0.100000 0.000000 +-0.967295 -0.253653 0.000000 +-0.967295 -0.253653 0.000000 +-0.994987 -0.100000 0.000000 +-0.967295 -0.253653 0.000000 +-0.896707 -0.442624 0.000000 +-0.967295 -0.253653 0.000000 +-0.896707 -0.442624 0.000000 +-0.896707 -0.442624 0.000000 +-0.967295 -0.253653 0.000000 +-0.794569 -0.607174 0.000000 +-0.896707 -0.442624 0.000000 +-0.896707 -0.442624 0.000000 +-0.794569 -0.607174 0.000000 +-0.794569 -0.607174 0.000000 +-0.896707 -0.442624 0.000000 +-0.670820 -0.741620 0.000000 +-0.794569 -0.607174 0.000000 +-0.794569 -0.607174 0.000000 +-0.670820 -0.741620 0.000000 +-0.670820 -0.741620 0.000000 +-0.794569 -0.607174 0.000000 +-0.670820 -0.741620 0.000000 +-0.524674 -0.851303 0.000000 +-0.670820 -0.741620 0.000000 +-0.524674 -0.851303 0.000000 +-0.524674 -0.851303 0.000000 +-0.670820 -0.741620 0.000000 +-0.524674 -0.851303 0.000000 +-0.350735 -0.936475 0.000000 +-0.524674 -0.851303 0.000000 +-0.350735 -0.936475 0.000000 +-0.350735 -0.936475 0.000000 +-0.524674 -0.851303 0.000000 +-0.350735 -0.936475 0.000000 +-0.155652 -0.987812 0.000000 +-0.350735 -0.936475 0.000000 +-0.155652 -0.987812 0.000000 +-0.155652 -0.987812 0.000000 +-0.350735 -0.936475 0.000000 +-0.155652 -0.987812 0.000000 +0.000000 -1.000000 0.000000 +-0.155652 -0.987812 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.994987 0.100000 0.000000 +0.967295 0.253653 0.000000 +0.994987 0.100000 0.000000 +0.155652 0.987812 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.155652 0.987812 0.000000 +0.155652 0.987812 0.000000 +0.000000 1.000000 0.000000 +0.155652 0.987812 0.000000 +0.350735 0.936475 0.000000 +0.155652 0.987812 0.000000 +0.350735 0.936475 0.000000 +0.350735 0.936475 0.000000 +0.155652 0.987812 0.000000 +0.524674 0.851303 0.000000 +0.350735 0.936475 0.000000 +0.350735 0.936475 0.000000 +0.524674 0.851303 0.000000 +0.524674 0.851303 0.000000 +0.350735 0.936475 0.000000 +0.670820 0.741620 0.000000 +0.524674 0.851303 0.000000 +0.524674 0.851303 0.000000 +0.670820 0.741620 0.000000 +0.670820 0.741620 0.000000 +0.524674 0.851303 0.000000 +0.670820 0.741620 0.000000 +0.794569 0.607174 0.000000 +0.670820 0.741620 0.000000 +0.794569 0.607174 0.000000 +0.794569 0.607174 0.000000 +0.670820 0.741620 0.000000 +0.794569 0.607174 0.000000 +0.896707 0.442624 0.000000 +0.794569 0.607174 0.000000 +0.896707 0.442624 0.000000 +0.896707 0.442624 0.000000 +0.794569 0.607174 0.000000 +0.967295 0.253653 0.000000 +0.896707 0.442624 0.000000 +0.896707 0.442624 0.000000 +0.967295 0.253653 0.000000 +0.967295 0.253653 0.000000 +0.896707 0.442624 0.000000 +0.967295 0.253653 0.000000 +0.994987 0.100000 0.000000 +0.967295 0.253653 0.000000 +0.524674 -0.851303 0.000000 +0.670820 -0.741620 0.000000 +0.524674 -0.851303 0.000000 +0.155652 -0.987812 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.155652 -0.987812 0.000000 +0.155652 -0.987812 0.000000 +0.000000 -1.000000 0.000000 +0.350735 -0.936475 0.000000 +0.155652 -0.987812 0.000000 +0.155652 -0.987812 0.000000 +0.350735 -0.936475 0.000000 +0.350735 -0.936475 0.000000 +0.155652 -0.987812 0.000000 +0.350735 -0.936475 0.000000 +0.524674 -0.851303 0.000000 +0.350735 -0.936475 0.000000 +0.524674 -0.851303 0.000000 +0.524674 -0.851303 0.000000 +0.350735 -0.936475 0.000000 +0.967295 -0.253653 0.000000 +0.994987 -0.100000 0.000000 +0.994987 -0.100000 0.000000 +0.967295 -0.253653 0.000000 +0.967295 -0.253653 0.000000 +0.994987 -0.100000 0.000000 +0.896707 -0.442624 0.000000 +0.967295 -0.253653 0.000000 +0.967295 -0.253653 0.000000 +0.896707 -0.442624 0.000000 +0.896707 -0.442624 0.000000 +0.967295 -0.253653 0.000000 +0.794569 -0.607174 0.000000 +0.896707 -0.442624 0.000000 +0.896707 -0.442624 0.000000 +0.794569 -0.607174 0.000000 +0.794569 -0.607174 0.000000 +0.896707 -0.442624 0.000000 +0.794569 -0.607174 0.000000 +0.670820 -0.741620 0.000000 +0.794569 -0.607174 0.000000 +0.670820 -0.741620 0.000000 +0.670820 -0.741620 0.000000 +0.794569 -0.607174 0.000000 +0.670820 -0.741620 0.000000 +0.524674 -0.851303 0.000000 +0.670820 -0.741620 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -0.594741 0.803917 +0.000000 -0.738552 0.674196 +0.000000 -0.738552 0.674196 +0.000000 -0.738552 0.674196 +0.000000 -0.788227 0.615385 +0.000000 -0.788227 0.615385 +0.000000 -0.738552 0.674196 +0.000000 -0.738552 0.674196 +0.000000 -0.788227 0.615385 +0.000000 0.000000 1.000000 +0.000000 -0.076926 0.997037 +0.000000 0.000000 1.000000 +0.000000 -0.076926 0.997037 +0.000000 -0.076926 0.997037 +0.000000 0.000000 1.000000 +0.000000 -0.267675 0.963509 +0.000000 -0.076926 0.997037 +0.000000 -0.076926 0.997037 +0.000000 -0.267675 0.963509 +0.000000 -0.267675 0.963509 +0.000000 -0.076926 0.997037 +0.000000 -0.438529 0.898717 +0.000000 -0.267675 0.963509 +0.000000 -0.267675 0.963509 +0.000000 -0.438529 0.898717 +0.000000 -0.438529 0.898717 +0.000000 -0.267675 0.963509 +0.000000 -0.594741 0.803917 +0.000000 -0.438529 0.898717 +0.000000 -0.438529 0.898717 +0.000000 -0.594741 0.803917 +0.000000 -0.594741 0.803917 +0.000000 -0.438529 0.898717 +0.000000 -0.738552 0.674196 +0.000000 -0.594741 0.803917 +0.000000 -0.594741 0.803917 +0.076926 0.000000 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.054395 0.054395 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.043589 0.063385 0.997037 +0.000000 0.000000 1.000000 +0.054395 0.054395 0.997037 +0.043589 0.063385 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.030553 0.070598 0.997037 +0.000000 0.000000 1.000000 +0.043589 0.063385 0.997037 +0.030553 0.070598 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.015763 0.075294 0.997037 +0.000000 0.000000 1.000000 +0.030553 0.070598 0.997037 +0.015763 0.075294 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.063385 0.043589 0.997037 +0.054395 0.054395 0.997037 +0.000000 0.000000 1.000000 +0.063385 0.043589 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.063385 0.043589 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.070598 0.030553 0.997037 +0.063385 0.043589 0.997037 +0.000000 0.000000 1.000000 +0.070598 0.030553 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.075294 0.015763 0.997037 +0.070598 0.030553 0.997037 +0.000000 0.000000 1.000000 +0.075294 0.015763 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.076926 0.997037 +0.000000 0.000000 1.000000 +0.015763 0.075294 0.997037 +0.000000 0.076926 0.997037 +0.000000 0.000000 1.000000 +0.015763 0.075294 0.997037 +0.000000 0.267675 0.963509 +0.000000 0.076926 0.997037 +0.054849 0.261995 0.963509 +0.000000 0.267675 0.963509 +0.015763 0.075294 0.997037 +0.089859 0.429224 0.898717 +0.000000 0.267675 0.963509 +0.054849 0.261995 0.963509 +0.089859 0.429224 0.898717 +0.000000 0.438529 0.898717 +0.000000 0.267675 0.963509 +0.089859 0.429224 0.898717 +0.000000 0.594741 0.803917 +0.000000 0.438529 0.898717 +0.121868 0.582121 0.803917 +0.000000 0.594741 0.803917 +0.089859 0.429224 0.898717 +0.151336 0.722881 0.674196 +0.000000 0.594741 0.803917 +0.121868 0.582121 0.803917 +0.151336 0.722881 0.674196 +0.000000 0.738552 0.674196 +0.000000 0.594741 0.803917 +0.151336 0.722881 0.674196 +0.000000 0.788227 0.615385 +0.000000 0.738552 0.674196 +0.151336 0.722881 0.674196 +0.143428 0.775068 0.615385 +0.000000 0.788227 0.615385 +0.151336 0.722881 0.674196 +0.290142 0.732884 0.615385 +0.143428 0.775068 0.615385 +0.293336 0.677800 0.674196 +0.290142 0.732884 0.615385 +0.151336 0.722881 0.674196 +0.293336 0.677800 0.674196 +0.431325 0.659742 0.615385 +0.290142 0.732884 0.615385 +0.418489 0.608544 0.674196 +0.431325 0.659742 0.615385 +0.293336 0.677800 0.674196 +0.418489 0.608544 0.674196 +0.496818 0.611943 0.615385 +0.431325 0.659742 0.615385 +0.522235 0.522235 0.674196 +0.496818 0.611943 0.615385 +0.418489 0.608544 0.674196 +0.522235 0.522235 0.674196 +0.557361 0.557361 0.615385 +0.496818 0.611943 0.615385 +0.608544 0.418489 0.674196 +0.557361 0.557361 0.615385 +0.522235 0.522235 0.674196 +0.608544 0.418489 0.674196 +0.611943 0.496818 0.615385 +0.557361 0.557361 0.615385 +0.608544 0.418489 0.674196 +0.659742 0.431325 0.615385 +0.611943 0.496818 0.615385 +0.677800 0.293336 0.674196 +0.659742 0.431325 0.615385 +0.608544 0.418489 0.674196 +0.677800 0.293336 0.674196 +0.732884 0.290142 0.615385 +0.659742 0.431325 0.615385 +0.722881 0.151336 0.674196 +0.732884 0.290142 0.615385 +0.677800 0.293336 0.674196 +0.722881 0.151336 0.674196 +0.775068 0.143428 0.615385 +0.732884 0.290142 0.615385 +0.775068 0.143428 0.615385 +0.738552 0.000000 0.674196 +0.788227 0.000000 0.615385 +0.722881 0.151336 0.674196 +0.738552 0.000000 0.674196 +0.775068 0.143428 0.615385 +0.582121 0.121868 0.803917 +0.738552 0.000000 0.674196 +0.722881 0.151336 0.674196 +0.582121 0.121868 0.803917 +0.594741 0.000000 0.803917 +0.738552 0.000000 0.674196 +0.429224 0.089859 0.898717 +0.594741 0.000000 0.803917 +0.582121 0.121868 0.803917 +0.429224 0.089859 0.898717 +0.438529 0.000000 0.898717 +0.594741 0.000000 0.803917 +0.261995 0.054849 0.963509 +0.438529 0.000000 0.898717 +0.429224 0.089859 0.898717 +0.261995 0.054849 0.963509 +0.267675 0.000000 0.963509 +0.438529 0.000000 0.898717 +0.261995 0.054849 0.963509 +0.076926 0.000000 0.997037 +0.267675 0.000000 0.963509 +0.075294 0.015763 0.997037 +0.076926 0.000000 0.997037 +0.261995 0.054849 0.963509 +0.000000 0.000000 1.000000 +0.076926 0.000000 0.997037 +0.075294 0.015763 0.997037 +0.151336 0.722881 0.674196 +0.236218 0.545819 0.803917 +0.293336 0.677800 0.674196 +0.236218 0.545819 0.803917 +0.151336 0.722881 0.674196 +0.121868 0.582121 0.803917 +0.121868 0.582121 0.803917 +0.174174 0.402456 0.898717 +0.236218 0.545819 0.803917 +0.174174 0.402456 0.898717 +0.121868 0.582121 0.803917 +0.089859 0.429224 0.898717 +0.089859 0.429224 0.898717 +0.106314 0.245656 0.963509 +0.174174 0.402456 0.898717 +0.106314 0.245656 0.963509 +0.089859 0.429224 0.898717 +0.054849 0.261995 0.963509 +0.054849 0.261995 0.963509 +0.030553 0.070598 0.997037 +0.106314 0.245656 0.963509 +0.030553 0.070598 0.997037 +0.054849 0.261995 0.963509 +0.015763 0.075294 0.997037 +0.293336 0.677800 0.674196 +0.337001 0.490048 0.803917 +0.418489 0.608544 0.674196 +0.337001 0.490048 0.803917 +0.293336 0.677800 0.674196 +0.236218 0.545819 0.803917 +0.236218 0.545819 0.803917 +0.248486 0.361334 0.898717 +0.337001 0.490048 0.803917 +0.248486 0.361334 0.898717 +0.236218 0.545819 0.803917 +0.174174 0.402456 0.898717 +0.418489 0.608544 0.674196 +0.420546 0.420546 0.803917 +0.522235 0.522235 0.674196 +0.420546 0.420546 0.803917 +0.418489 0.608544 0.674196 +0.337001 0.490048 0.803917 +0.337001 0.490048 0.803917 +0.310087 0.310087 0.898717 +0.420546 0.420546 0.803917 +0.310087 0.310087 0.898717 +0.337001 0.490048 0.803917 +0.248486 0.361334 0.898717 +0.174174 0.402456 0.898717 +0.151674 0.220556 0.963509 +0.248486 0.361334 0.898717 +0.151674 0.220556 0.963509 +0.174174 0.402456 0.898717 +0.106314 0.245656 0.963509 +0.106314 0.245656 0.963509 +0.043589 0.063385 0.997037 +0.151674 0.220556 0.963509 +0.043589 0.063385 0.997037 +0.106314 0.245656 0.963509 +0.030553 0.070598 0.997037 +0.248486 0.361334 0.898717 +0.189275 0.189275 0.963509 +0.310087 0.310087 0.898717 +0.189275 0.189275 0.963509 +0.248486 0.361334 0.898717 +0.151674 0.220556 0.963509 +0.151674 0.220556 0.963509 +0.054395 0.054395 0.997037 +0.189275 0.189275 0.963509 +0.054395 0.054395 0.997037 +0.151674 0.220556 0.963509 +0.043589 0.063385 0.997037 +0.522235 0.522235 0.674196 +0.490048 0.337001 0.803917 +0.608544 0.418489 0.674196 +0.490048 0.337001 0.803917 +0.522235 0.522235 0.674196 +0.420546 0.420546 0.803917 +0.420546 0.420546 0.803917 +0.361334 0.248486 0.898717 +0.490048 0.337001 0.803917 +0.361334 0.248486 0.898717 +0.420546 0.420546 0.803917 +0.310087 0.310087 0.898717 +0.608544 0.418489 0.674196 +0.545819 0.236218 0.803917 +0.677800 0.293336 0.674196 +0.545819 0.236218 0.803917 +0.608544 0.418489 0.674196 +0.490048 0.337001 0.803917 +0.490048 0.337001 0.803917 +0.402456 0.174174 0.898717 +0.545819 0.236218 0.803917 +0.402456 0.174174 0.898717 +0.490048 0.337001 0.803917 +0.361334 0.248486 0.898717 +0.310087 0.310087 0.898717 +0.220556 0.151674 0.963509 +0.361334 0.248486 0.898717 +0.220556 0.151674 0.963509 +0.310087 0.310087 0.898717 +0.189275 0.189275 0.963509 +0.189275 0.189275 0.963509 +0.063385 0.043589 0.997037 +0.220556 0.151674 0.963509 +0.063385 0.043589 0.997037 +0.189275 0.189275 0.963509 +0.054395 0.054395 0.997037 +0.361334 0.248486 0.898717 +0.245656 0.106314 0.963509 +0.402456 0.174174 0.898717 +0.245656 0.106314 0.963509 +0.361334 0.248486 0.898717 +0.220556 0.151674 0.963509 +0.220556 0.151674 0.963509 +0.070598 0.030553 0.997037 +0.245656 0.106314 0.963509 +0.070598 0.030553 0.997037 +0.220556 0.151674 0.963509 +0.063385 0.043589 0.997037 +0.677800 0.293336 0.674196 +0.582121 0.121868 0.803917 +0.722881 0.151336 0.674196 +0.582121 0.121868 0.803917 +0.677800 0.293336 0.674196 +0.545819 0.236218 0.803917 +0.545819 0.236218 0.803917 +0.429224 0.089859 0.898717 +0.582121 0.121868 0.803917 +0.429224 0.089859 0.898717 +0.545819 0.236218 0.803917 +0.402456 0.174174 0.898717 +0.402456 0.174174 0.898717 +0.261995 0.054849 0.963509 +0.429224 0.089859 0.898717 +0.261995 0.054849 0.963509 +0.402456 0.174174 0.898717 +0.245656 0.106314 0.963509 +0.245656 0.106314 0.963509 +0.075294 0.015763 0.997037 +0.261995 0.054849 0.963509 +0.075294 0.015763 0.997037 +0.245656 0.106314 0.963509 +0.070598 0.030553 0.997037 +-0.557361 -0.557361 0.615385 +-0.618165 -0.404143 0.674196 +-0.659742 -0.431325 0.615385 +-0.143428 0.775068 0.615385 +0.000000 0.738552 0.674196 +0.000000 0.788227 0.615385 +0.000000 0.000000 1.000000 +0.000000 -0.076926 0.997037 +0.000000 0.000000 1.000000 +-0.686697 -0.271857 0.674196 +-0.659742 -0.431325 0.615385 +-0.618165 -0.404143 0.674196 +-0.686697 -0.271857 0.674196 +-0.732884 -0.290142 0.615385 +-0.659742 -0.431325 0.615385 +-0.726222 -0.134389 0.674196 +-0.732884 -0.290142 0.615385 +-0.686697 -0.271857 0.674196 +-0.726222 -0.134389 0.674196 +-0.775068 -0.143428 0.615385 +-0.732884 -0.290142 0.615385 +-0.738552 0.000000 0.674196 +-0.775068 -0.143428 0.615385 +-0.726222 -0.134389 0.674196 +-0.738552 0.000000 0.674196 +-0.788227 0.000000 0.615385 +-0.775068 -0.143428 0.615385 +-0.726222 0.134389 0.674196 +-0.788227 0.000000 0.615385 +-0.738552 0.000000 0.674196 +-0.726222 0.134389 0.674196 +-0.775068 0.143428 0.615385 +-0.788227 0.000000 0.615385 +-0.686697 0.271857 0.674196 +-0.775068 0.143428 0.615385 +-0.726222 0.134389 0.674196 +-0.686697 0.271857 0.674196 +-0.732884 0.290142 0.615385 +-0.775068 0.143428 0.615385 +-0.618165 0.404143 0.674196 +-0.732884 0.290142 0.615385 +-0.686697 0.271857 0.674196 +-0.618165 0.404143 0.674196 +-0.659742 0.431325 0.615385 +-0.732884 0.290142 0.615385 +-0.522235 0.522235 0.674196 +-0.659742 0.431325 0.615385 +-0.618165 0.404143 0.674196 +-0.522235 0.522235 0.674196 +-0.557361 0.557361 0.615385 +-0.659742 0.431325 0.615385 +-0.404143 0.618165 0.674196 +-0.557361 0.557361 0.615385 +-0.522235 0.522235 0.674196 +-0.404143 0.618165 0.674196 +-0.431325 0.659742 0.615385 +-0.557361 0.557361 0.615385 +-0.404143 0.618165 0.674196 +-0.290142 0.732884 0.615385 +-0.431325 0.659742 0.615385 +-0.271857 0.686697 0.674196 +-0.290142 0.732884 0.615385 +-0.404143 0.618165 0.674196 +-0.271857 0.686697 0.674196 +-0.143428 0.775068 0.615385 +-0.290142 0.732884 0.615385 +-0.134389 0.726222 0.674196 +-0.143428 0.775068 0.615385 +-0.271857 0.686697 0.674196 +-0.134389 0.726222 0.674196 +0.000000 0.738552 0.674196 +-0.143428 0.775068 0.615385 +-0.108221 0.584812 0.803917 +0.000000 0.738552 0.674196 +-0.134389 0.726222 0.674196 +-0.108221 0.584812 0.803917 +0.000000 0.594741 0.803917 +0.000000 0.738552 0.674196 +-0.079796 0.431208 0.898717 +0.000000 0.594741 0.803917 +-0.108221 0.584812 0.803917 +-0.079796 0.431208 0.898717 +0.000000 0.438529 0.898717 +0.000000 0.594741 0.803917 +-0.079796 0.431208 0.898717 +0.000000 0.267675 0.963509 +0.000000 0.438529 0.898717 +-0.048707 0.263206 0.963509 +0.000000 0.267675 0.963509 +-0.079796 0.431208 0.898717 +-0.048707 0.263206 0.963509 +0.000000 0.076926 0.997037 +0.000000 0.267675 0.963509 +-0.013998 0.075642 0.997037 +0.000000 0.076926 0.997037 +-0.048707 0.263206 0.963509 +-0.013998 0.075642 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.076926 0.997037 +-0.013998 0.075642 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.028316 0.071525 0.997037 +0.000000 0.000000 1.000000 +-0.013998 0.075642 0.997037 +-0.028316 0.071525 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.042095 0.064387 0.997037 +0.000000 0.000000 1.000000 +-0.028316 0.071525 0.997037 +-0.042095 0.064387 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.054395 0.054395 0.997037 +0.000000 0.000000 1.000000 +-0.042095 0.064387 0.997037 +-0.054395 0.054395 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.064387 0.042095 0.997037 +0.000000 0.000000 1.000000 +-0.054395 0.054395 0.997037 +-0.064387 0.042095 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.071525 0.028316 0.997037 +0.000000 0.000000 1.000000 +-0.064387 0.042095 0.997037 +-0.071525 0.028316 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.075642 0.013998 0.997037 +0.000000 0.000000 1.000000 +-0.071525 0.028316 0.997037 +-0.075642 0.013998 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.076926 0.000000 0.997037 +0.000000 0.000000 1.000000 +-0.075642 0.013998 0.997037 +-0.076926 0.000000 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.075642 -0.013998 0.997037 +0.000000 0.000000 1.000000 +-0.076926 0.000000 0.997037 +-0.075642 -0.013998 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.071525 -0.028316 0.997037 +0.000000 0.000000 1.000000 +-0.075642 -0.013998 0.997037 +-0.071525 -0.028316 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.064387 -0.042095 0.997037 +0.000000 0.000000 1.000000 +-0.071525 -0.028316 0.997037 +-0.064387 -0.042095 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.054395 -0.054395 0.997037 +0.000000 0.000000 1.000000 +-0.064387 -0.042095 0.997037 +-0.054395 -0.054395 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.042095 -0.064387 0.997037 +0.000000 0.000000 1.000000 +-0.054395 -0.054395 0.997037 +-0.042095 -0.064387 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.028316 -0.071525 0.997037 +0.000000 0.000000 1.000000 +-0.042095 -0.064387 0.997037 +-0.028316 -0.071525 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.013998 -0.075642 0.997037 +0.000000 0.000000 1.000000 +-0.028316 -0.071525 0.997037 +-0.013998 -0.075642 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.013998 -0.075642 0.997037 +0.000000 -0.076926 0.997037 +0.000000 0.000000 1.000000 +-0.048707 -0.263206 0.963509 +0.000000 -0.076926 0.997037 +-0.013998 -0.075642 0.997037 +-0.048707 -0.263206 0.963509 +0.000000 -0.267675 0.963509 +0.000000 -0.076926 0.997037 +-0.079796 -0.431208 0.898717 +0.000000 -0.267675 0.963509 +-0.048707 -0.263206 0.963509 +-0.079796 -0.431208 0.898717 +0.000000 -0.438529 0.898717 +0.000000 -0.267675 0.963509 +-0.108221 -0.584812 0.803917 +0.000000 -0.438529 0.898717 +-0.079796 -0.431208 0.898717 +-0.108221 -0.584812 0.803917 +0.000000 -0.594741 0.803917 +0.000000 -0.438529 0.898717 +-0.134389 -0.726222 0.674196 +0.000000 -0.594741 0.803917 +-0.108221 -0.584812 0.803917 +-0.134389 -0.726222 0.674196 +0.000000 -0.738552 0.674196 +0.000000 -0.594741 0.803917 +-0.134389 -0.726222 0.674196 +0.000000 -0.788227 0.615385 +0.000000 -0.738552 0.674196 +-0.134389 -0.726222 0.674196 +-0.143428 -0.775068 0.615385 +0.000000 -0.788227 0.615385 +-0.271857 -0.686697 0.674196 +-0.143428 -0.775068 0.615385 +-0.134389 -0.726222 0.674196 +-0.271857 -0.686697 0.674196 +-0.290142 -0.732884 0.615385 +-0.143428 -0.775068 0.615385 +-0.404143 -0.618165 0.674196 +-0.290142 -0.732884 0.615385 +-0.271857 -0.686697 0.674196 +-0.404143 -0.618165 0.674196 +-0.431325 -0.659742 0.615385 +-0.290142 -0.732884 0.615385 +-0.522235 -0.522235 0.674196 +-0.431325 -0.659742 0.615385 +-0.404143 -0.618165 0.674196 +-0.522235 -0.522235 0.674196 +-0.557361 -0.557361 0.615385 +-0.431325 -0.659742 0.615385 +-0.618165 -0.404143 0.674196 +-0.557361 -0.557361 0.615385 +-0.522235 -0.522235 0.674196 +-0.134389 -0.726222 0.674196 +-0.218921 -0.552983 0.803917 +-0.271857 -0.686697 0.674196 +-0.218921 -0.552983 0.803917 +-0.134389 -0.726222 0.674196 +-0.108221 -0.584812 0.803917 +-0.108221 -0.584812 0.803917 +-0.161420 -0.407739 0.898717 +-0.218921 -0.552983 0.803917 +-0.161420 -0.407739 0.898717 +-0.108221 -0.584812 0.803917 +-0.079796 -0.431208 0.898717 +-0.079796 -0.431208 0.898717 +-0.098530 -0.248881 0.963509 +-0.161420 -0.407739 0.898717 +-0.098530 -0.248881 0.963509 +-0.079796 -0.431208 0.898717 +-0.048707 -0.263206 0.963509 +-0.048707 -0.263206 0.963509 +-0.028316 -0.071525 0.997037 +-0.098530 -0.248881 0.963509 +-0.028316 -0.071525 0.997037 +-0.048707 -0.263206 0.963509 +-0.013998 -0.075642 0.997037 +-0.271857 -0.686697 0.674196 +-0.325448 -0.497796 0.803917 +-0.404143 -0.618165 0.674196 +-0.325448 -0.497796 0.803917 +-0.271857 -0.686697 0.674196 +-0.218921 -0.552983 0.803917 +-0.218921 -0.552983 0.803917 +-0.239967 -0.367047 0.898717 +-0.325448 -0.497796 0.803917 +-0.239967 -0.367047 0.898717 +-0.218921 -0.552983 0.803917 +-0.161420 -0.407739 0.898717 +-0.404143 -0.618165 0.674196 +-0.420546 -0.420546 0.803917 +-0.522235 -0.522235 0.674196 +-0.420546 -0.420546 0.803917 +-0.404143 -0.618165 0.674196 +-0.325448 -0.497796 0.803917 +-0.325448 -0.497796 0.803917 +-0.310087 -0.310087 0.898717 +-0.420546 -0.420546 0.803917 +-0.310087 -0.310087 0.898717 +-0.325448 -0.497796 0.803917 +-0.239967 -0.367047 0.898717 +-0.161420 -0.407739 0.898717 +-0.146474 -0.224042 0.963509 +-0.239967 -0.367047 0.898717 +-0.146474 -0.224042 0.963509 +-0.161420 -0.407739 0.898717 +-0.098530 -0.248881 0.963509 +-0.098530 -0.248881 0.963509 +-0.042095 -0.064387 0.997037 +-0.146474 -0.224042 0.963509 +-0.042095 -0.064387 0.997037 +-0.098530 -0.248881 0.963509 +-0.028316 -0.071525 0.997037 +-0.239967 -0.367047 0.898717 +-0.189275 -0.189275 0.963509 +-0.310087 -0.310087 0.898717 +-0.189275 -0.189275 0.963509 +-0.239967 -0.367047 0.898717 +-0.146474 -0.224042 0.963509 +-0.146474 -0.224042 0.963509 +-0.054395 -0.054395 0.997037 +-0.189275 -0.189275 0.963509 +-0.054395 -0.054395 0.997037 +-0.146474 -0.224042 0.963509 +-0.042095 -0.064387 0.997037 +-0.522235 -0.522235 0.674196 +-0.497796 -0.325448 0.803917 +-0.618165 -0.404143 0.674196 +-0.497796 -0.325448 0.803917 +-0.522235 -0.522235 0.674196 +-0.420546 -0.420546 0.803917 +-0.420546 -0.420546 0.803917 +-0.367047 -0.239967 0.898717 +-0.497796 -0.325448 0.803917 +-0.367047 -0.239967 0.898717 +-0.420546 -0.420546 0.803917 +-0.310087 -0.310087 0.898717 +-0.618165 -0.404143 0.674196 +-0.552983 -0.218921 0.803917 +-0.686697 -0.271857 0.674196 +-0.552983 -0.218921 0.803917 +-0.618165 -0.404143 0.674196 +-0.497796 -0.325448 0.803917 +-0.497796 -0.325448 0.803917 +-0.407739 -0.161420 0.898717 +-0.552983 -0.218921 0.803917 +-0.407739 -0.161420 0.898717 +-0.497796 -0.325448 0.803917 +-0.367047 -0.239967 0.898717 +-0.310087 -0.310087 0.898717 +-0.224042 -0.146474 0.963509 +-0.367047 -0.239967 0.898717 +-0.224042 -0.146474 0.963509 +-0.310087 -0.310087 0.898717 +-0.189275 -0.189275 0.963509 +-0.189275 -0.189275 0.963509 +-0.064387 -0.042095 0.997037 +-0.224042 -0.146474 0.963509 +-0.064387 -0.042095 0.997037 +-0.189275 -0.189275 0.963509 +-0.054395 -0.054395 0.997037 +-0.367047 -0.239967 0.898717 +-0.248881 -0.098530 0.963509 +-0.407739 -0.161420 0.898717 +-0.248881 -0.098530 0.963509 +-0.367047 -0.239967 0.898717 +-0.224042 -0.146474 0.963509 +-0.224042 -0.146474 0.963509 +-0.071525 -0.028316 0.997037 +-0.248881 -0.098530 0.963509 +-0.071525 -0.028316 0.997037 +-0.224042 -0.146474 0.963509 +-0.064387 -0.042095 0.997037 +-0.686697 -0.271857 0.674196 +-0.584812 -0.108221 0.803917 +-0.726222 -0.134389 0.674196 +-0.584812 -0.108221 0.803917 +-0.686697 -0.271857 0.674196 +-0.552983 -0.218921 0.803917 +-0.552983 -0.218921 0.803917 +-0.431208 -0.079796 0.898717 +-0.584812 -0.108221 0.803917 +-0.431208 -0.079796 0.898717 +-0.552983 -0.218921 0.803917 +-0.407739 -0.161420 0.898717 +-0.726222 -0.134389 0.674196 +-0.594741 0.000000 0.803917 +-0.738552 0.000000 0.674196 +-0.594741 0.000000 0.803917 +-0.726222 -0.134389 0.674196 +-0.584812 -0.108221 0.803917 +-0.584812 -0.108221 0.803917 +-0.438529 0.000000 0.898717 +-0.594741 0.000000 0.803917 +-0.438529 0.000000 0.898717 +-0.584812 -0.108221 0.803917 +-0.431208 -0.079796 0.898717 +-0.407739 -0.161420 0.898717 +-0.263206 -0.048707 0.963509 +-0.431208 -0.079796 0.898717 +-0.263206 -0.048707 0.963509 +-0.407739 -0.161420 0.898717 +-0.248881 -0.098530 0.963509 +-0.248881 -0.098530 0.963509 +-0.075642 -0.013998 0.997037 +-0.263206 -0.048707 0.963509 +-0.075642 -0.013998 0.997037 +-0.248881 -0.098530 0.963509 +-0.071525 -0.028316 0.997037 +-0.431208 -0.079796 0.898717 +-0.267675 0.000000 0.963509 +-0.438529 0.000000 0.898717 +-0.267675 0.000000 0.963509 +-0.431208 -0.079796 0.898717 +-0.263206 -0.048707 0.963509 +-0.263206 -0.048707 0.963509 +-0.076926 0.000000 0.997037 +-0.267675 0.000000 0.963509 +-0.076926 0.000000 0.997037 +-0.263206 -0.048707 0.963509 +-0.075642 -0.013998 0.997037 +-0.738552 0.000000 0.674196 +-0.584812 0.108221 0.803917 +-0.726222 0.134389 0.674196 +-0.584812 0.108221 0.803917 +-0.738552 0.000000 0.674196 +-0.594741 0.000000 0.803917 +-0.594741 0.000000 0.803917 +-0.431208 0.079796 0.898717 +-0.584812 0.108221 0.803917 +-0.431208 0.079796 0.898717 +-0.594741 0.000000 0.803917 +-0.438529 0.000000 0.898717 +-0.726222 0.134389 0.674196 +-0.552983 0.218921 0.803917 +-0.686697 0.271857 0.674196 +-0.552983 0.218921 0.803917 +-0.726222 0.134389 0.674196 +-0.584812 0.108221 0.803917 +-0.584812 0.108221 0.803917 +-0.407739 0.161420 0.898717 +-0.552983 0.218921 0.803917 +-0.407739 0.161420 0.898717 +-0.584812 0.108221 0.803917 +-0.431208 0.079796 0.898717 +-0.438529 0.000000 0.898717 +-0.263206 0.048707 0.963509 +-0.431208 0.079796 0.898717 +-0.263206 0.048707 0.963509 +-0.438529 0.000000 0.898717 +-0.267675 0.000000 0.963509 +-0.267675 0.000000 0.963509 +-0.075642 0.013998 0.997037 +-0.263206 0.048707 0.963509 +-0.075642 0.013998 0.997037 +-0.267675 0.000000 0.963509 +-0.076926 0.000000 0.997037 +-0.431208 0.079796 0.898717 +-0.248881 0.098530 0.963509 +-0.407739 0.161420 0.898717 +-0.248881 0.098530 0.963509 +-0.431208 0.079796 0.898717 +-0.263206 0.048707 0.963509 +-0.263206 0.048707 0.963509 +-0.071525 0.028316 0.997037 +-0.248881 0.098530 0.963509 +-0.071525 0.028316 0.997037 +-0.263206 0.048707 0.963509 +-0.075642 0.013998 0.997037 +-0.686697 0.271857 0.674196 +-0.497796 0.325448 0.803917 +-0.618165 0.404143 0.674196 +-0.497796 0.325448 0.803917 +-0.686697 0.271857 0.674196 +-0.552983 0.218921 0.803917 +-0.552983 0.218921 0.803917 +-0.367047 0.239967 0.898717 +-0.497796 0.325448 0.803917 +-0.367047 0.239967 0.898717 +-0.552983 0.218921 0.803917 +-0.407739 0.161420 0.898717 +-0.618165 0.404143 0.674196 +-0.420546 0.420546 0.803917 +-0.522235 0.522235 0.674196 +-0.420546 0.420546 0.803917 +-0.618165 0.404143 0.674196 +-0.497796 0.325448 0.803917 +-0.497796 0.325448 0.803917 +-0.310087 0.310087 0.898717 +-0.420546 0.420546 0.803917 +-0.310087 0.310087 0.898717 +-0.497796 0.325448 0.803917 +-0.367047 0.239967 0.898717 +-0.407739 0.161420 0.898717 +-0.224042 0.146474 0.963509 +-0.367047 0.239967 0.898717 +-0.224042 0.146474 0.963509 +-0.407739 0.161420 0.898717 +-0.248881 0.098530 0.963509 +-0.248881 0.098530 0.963509 +-0.064387 0.042095 0.997037 +-0.224042 0.146474 0.963509 +-0.064387 0.042095 0.997037 +-0.248881 0.098530 0.963509 +-0.071525 0.028316 0.997037 +-0.367047 0.239967 0.898717 +-0.189275 0.189275 0.963509 +-0.310087 0.310087 0.898717 +-0.189275 0.189275 0.963509 +-0.367047 0.239967 0.898717 +-0.224042 0.146474 0.963509 +-0.224042 0.146474 0.963509 +-0.054395 0.054395 0.997037 +-0.189275 0.189275 0.963509 +-0.054395 0.054395 0.997037 +-0.224042 0.146474 0.963509 +-0.064387 0.042095 0.997037 +-0.522235 0.522235 0.674196 +-0.325448 0.497796 0.803917 +-0.404143 0.618165 0.674196 +-0.325448 0.497796 0.803917 +-0.522235 0.522235 0.674196 +-0.420546 0.420546 0.803917 +-0.420546 0.420546 0.803917 +-0.239967 0.367047 0.898717 +-0.325448 0.497796 0.803917 +-0.239967 0.367047 0.898717 +-0.420546 0.420546 0.803917 +-0.310087 0.310087 0.898717 +-0.404143 0.618165 0.674196 +-0.218921 0.552983 0.803917 +-0.271857 0.686697 0.674196 +-0.218921 0.552983 0.803917 +-0.404143 0.618165 0.674196 +-0.325448 0.497796 0.803917 +-0.325448 0.497796 0.803917 +-0.161420 0.407739 0.898717 +-0.218921 0.552983 0.803917 +-0.161420 0.407739 0.898717 +-0.325448 0.497796 0.803917 +-0.239967 0.367047 0.898717 +-0.310087 0.310087 0.898717 +-0.146474 0.224042 0.963509 +-0.239967 0.367047 0.898717 +-0.146474 0.224042 0.963509 +-0.310087 0.310087 0.898717 +-0.189275 0.189275 0.963509 +-0.189275 0.189275 0.963509 +-0.042095 0.064387 0.997037 +-0.146474 0.224042 0.963509 +-0.042095 0.064387 0.997037 +-0.189275 0.189275 0.963509 +-0.054395 0.054395 0.997037 +-0.239967 0.367047 0.898717 +-0.098530 0.248881 0.963509 +-0.161420 0.407739 0.898717 +-0.098530 0.248881 0.963509 +-0.239967 0.367047 0.898717 +-0.146474 0.224042 0.963509 +-0.146474 0.224042 0.963509 +-0.028316 0.071525 0.997037 +-0.098530 0.248881 0.963509 +-0.028316 0.071525 0.997037 +-0.146474 0.224042 0.963509 +-0.042095 0.064387 0.997037 +-0.271857 0.686697 0.674196 +-0.108221 0.584812 0.803917 +-0.134389 0.726222 0.674196 +-0.108221 0.584812 0.803917 +-0.271857 0.686697 0.674196 +-0.218921 0.552983 0.803917 +-0.218921 0.552983 0.803917 +-0.079796 0.431208 0.898717 +-0.108221 0.584812 0.803917 +-0.079796 0.431208 0.898717 +-0.218921 0.552983 0.803917 +-0.161420 0.407739 0.898717 +-0.161420 0.407739 0.898717 +-0.048707 0.263206 0.963509 +-0.079796 0.431208 0.898717 +-0.048707 0.263206 0.963509 +-0.161420 0.407739 0.898717 +-0.098530 0.248881 0.963509 +-0.098530 0.248881 0.963509 +-0.013998 0.075642 0.997037 +-0.048707 0.263206 0.963509 +-0.013998 0.075642 0.997037 +-0.098530 0.248881 0.963509 +-0.028316 0.071525 0.997037 +0.000000 0.438529 0.898717 +0.000000 0.267675 0.963509 +0.000000 0.438529 0.898717 +0.000000 0.788227 0.615385 +0.000000 0.738552 0.674196 +0.000000 0.788227 0.615385 +0.000000 0.738552 0.674196 +0.000000 0.738552 0.674196 +0.000000 0.788227 0.615385 +0.000000 0.738552 0.674196 +0.000000 0.594741 0.803917 +0.000000 0.738552 0.674196 +0.000000 0.594741 0.803917 +0.000000 0.594741 0.803917 +0.000000 0.738552 0.674196 +0.000000 0.438529 0.898717 +0.000000 0.594741 0.803917 +0.000000 0.594741 0.803917 +0.000000 0.438529 0.898717 +0.000000 0.438529 0.898717 +0.000000 0.594741 0.803917 +0.000000 0.000000 1.000000 +0.000000 0.076926 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.076926 0.997037 +0.000000 0.076926 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.076926 0.997037 +0.000000 0.267675 0.963509 +0.000000 0.076926 0.997037 +0.000000 0.267675 0.963509 +0.000000 0.267675 0.963509 +0.000000 0.076926 0.997037 +0.000000 0.267675 0.963509 +0.000000 0.438529 0.898717 +0.000000 0.267675 0.963509 +0.000000 -0.182574 0.983192 +0.000000 -0.358431 0.933556 +0.000000 -0.358431 0.933556 +0.000000 -0.359011 0.933333 +0.000000 -0.358431 0.933556 +0.000000 -0.359011 0.933333 +0.000000 -0.358431 0.933556 +0.000000 -0.358431 0.933556 +0.000000 -0.359011 0.933333 +0.000000 0.000000 1.000000 +0.000000 -0.000622 1.000000 +0.000000 0.000000 1.000000 +0.000000 -0.000622 1.000000 +0.000000 -0.000622 1.000000 +0.000000 0.000000 1.000000 +0.000000 -0.182574 0.983192 +0.000000 -0.000622 1.000000 +0.000000 -0.000622 1.000000 +0.000000 -0.182574 0.983192 +0.000000 -0.182574 0.983192 +0.000000 -0.000622 1.000000 +0.000000 -0.358431 0.933556 +0.000000 -0.182574 0.983192 +0.000000 -0.182574 0.983192 +0.178700 0.037411 0.983192 +0.353017 0.065327 0.933333 +0.350825 0.073446 0.933556 +0.295336 0.203099 0.933556 +0.253859 0.253859 0.933333 +0.253449 0.253449 0.933556 +0.295336 0.203099 0.933556 +0.278719 0.226284 0.933333 +0.253859 0.253859 0.933333 +0.295336 0.203099 0.933556 +0.300491 0.196454 0.933333 +0.278719 0.226284 0.933333 +0.328947 0.142361 0.933556 +0.300491 0.196454 0.933333 +0.295336 0.203099 0.933556 +0.328947 0.142361 0.933556 +0.333804 0.132150 0.933333 +0.300491 0.196454 0.933333 +0.350825 0.073446 0.933556 +0.333804 0.132150 0.933333 +0.328947 0.142361 0.933556 +0.350825 0.073446 0.933556 +0.353017 0.065327 0.933333 +0.333804 0.132150 0.933333 +0.226284 0.278719 0.933333 +0.253449 0.253449 0.933556 +0.253859 0.253859 0.933333 +0.226284 0.278719 0.933333 +0.203099 0.295336 0.933556 +0.253449 0.253449 0.933556 +0.196454 0.300491 0.933333 +0.203099 0.295336 0.933556 +0.226284 0.278719 0.933333 +0.196454 0.300491 0.933333 +0.142361 0.328947 0.933556 +0.203099 0.295336 0.933556 +0.132150 0.333804 0.933333 +0.142361 0.328947 0.933556 +0.196454 0.300491 0.933333 +0.132150 0.333804 0.933333 +0.073446 0.350825 0.933556 +0.142361 0.328947 0.933556 +0.065327 0.353017 0.933333 +0.073446 0.350825 0.933556 +0.132150 0.333804 0.933333 +0.353017 0.065327 0.933333 +0.358431 0.000000 0.933556 +0.359011 0.000000 0.933333 +0.353017 0.065327 0.933333 +0.182574 0.000000 0.983192 +0.358431 0.000000 0.933556 +0.000622 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.182574 0.000000 0.983192 +0.000000 0.000000 1.000000 +0.000622 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000622 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.182574 0.983192 +0.000000 0.000622 1.000000 +0.000000 0.358431 0.933556 +0.065327 0.353017 0.933333 +0.000000 0.359011 0.933333 +0.000000 0.182574 0.983192 +0.065327 0.353017 0.933333 +0.000000 0.358431 0.933556 +0.065327 0.353017 0.933333 +0.037411 0.178700 0.983192 +0.073446 0.350825 0.933556 +0.000000 0.182574 0.983192 +0.037411 0.178700 0.983192 +0.065327 0.353017 0.933333 +0.000000 0.000000 1.000000 +0.037411 0.178700 0.983192 +0.000000 0.182574 0.983192 +0.000000 0.000000 1.000000 +0.000127 0.000608 1.000000 +0.037411 0.178700 0.983192 +0.000000 0.000000 1.000000 +0.000127 0.000608 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000247 0.000570 1.000000 +0.000127 0.000608 1.000000 +0.000000 0.000000 1.000000 +0.000247 0.000570 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000352 0.000512 1.000000 +0.000247 0.000570 1.000000 +0.000000 0.000000 1.000000 +0.000352 0.000512 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000439 0.000439 1.000000 +0.000352 0.000512 1.000000 +0.000000 0.000000 1.000000 +0.000439 0.000439 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000512 0.000352 1.000000 +0.000439 0.000439 1.000000 +0.000000 0.000000 1.000000 +0.000512 0.000352 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000512 0.000352 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000570 0.000247 1.000000 +0.000512 0.000352 1.000000 +0.000000 0.000000 1.000000 +0.000570 0.000247 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000608 0.000127 1.000000 +0.000570 0.000247 1.000000 +0.000000 0.000000 1.000000 +0.000608 0.000127 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.178700 0.037411 0.983192 +0.000608 0.000127 1.000000 +0.182574 0.000000 0.983192 +0.178700 0.037411 0.983192 +0.000000 0.000000 1.000000 +0.353017 0.065327 0.933333 +0.178700 0.037411 0.983192 +0.182574 0.000000 0.983192 +0.073446 0.350825 0.933556 +0.072514 0.167556 0.983192 +0.142361 0.328947 0.933556 +0.072514 0.167556 0.983192 +0.073446 0.350825 0.933556 +0.037411 0.178700 0.983192 +0.142361 0.328947 0.933556 +0.103453 0.150436 0.983192 +0.203099 0.295336 0.933556 +0.103453 0.150436 0.983192 +0.142361 0.328947 0.933556 +0.072514 0.167556 0.983192 +0.203099 0.295336 0.933556 +0.129099 0.129099 0.983192 +0.253449 0.253449 0.933556 +0.129099 0.129099 0.983192 +0.203099 0.295336 0.933556 +0.103453 0.150436 0.983192 +0.037411 0.178700 0.983192 +0.000247 0.000570 1.000000 +0.072514 0.167556 0.983192 +0.000247 0.000570 1.000000 +0.037411 0.178700 0.983192 +0.000127 0.000608 1.000000 +0.072514 0.167556 0.983192 +0.000352 0.000512 1.000000 +0.103453 0.150436 0.983192 +0.000352 0.000512 1.000000 +0.072514 0.167556 0.983192 +0.000247 0.000570 1.000000 +0.103453 0.150436 0.983192 +0.000439 0.000439 1.000000 +0.129099 0.129099 0.983192 +0.000439 0.000439 1.000000 +0.103453 0.150436 0.983192 +0.000352 0.000512 1.000000 +0.253449 0.253449 0.933556 +0.150436 0.103453 0.983192 +0.295336 0.203099 0.933556 +0.150436 0.103453 0.983192 +0.253449 0.253449 0.933556 +0.129099 0.129099 0.983192 +0.295336 0.203099 0.933556 +0.167556 0.072514 0.983192 +0.328947 0.142361 0.933556 +0.167556 0.072514 0.983192 +0.295336 0.203099 0.933556 +0.150436 0.103453 0.983192 +0.328947 0.142361 0.933556 +0.178700 0.037411 0.983192 +0.350825 0.073446 0.933556 +0.178700 0.037411 0.983192 +0.328947 0.142361 0.933556 +0.167556 0.072514 0.983192 +0.129099 0.129099 0.983192 +0.000512 0.000352 1.000000 +0.150436 0.103453 0.983192 +0.000512 0.000352 1.000000 +0.129099 0.129099 0.983192 +0.000439 0.000439 1.000000 +0.150436 0.103453 0.983192 +0.000570 0.000247 1.000000 +0.167556 0.072514 0.983192 +0.000570 0.000247 1.000000 +0.150436 0.103453 0.983192 +0.000512 0.000352 1.000000 +0.167556 0.072514 0.983192 +0.000608 0.000127 1.000000 +0.178700 0.037411 0.983192 +0.000608 0.000127 1.000000 +0.167556 0.072514 0.983192 +0.000570 0.000247 1.000000 +-0.131936 -0.333265 0.933556 +-0.065327 -0.353017 0.933333 +-0.065221 -0.352447 0.933556 +0.000000 -0.358431 0.933556 +-0.065327 -0.353017 0.933333 +0.000000 -0.359011 0.933333 +0.000000 -0.358431 0.933556 +-0.065221 -0.352447 0.933556 +-0.065327 -0.353017 0.933333 +0.000000 -0.358431 0.933556 +-0.033222 -0.179526 0.983192 +-0.065221 -0.352447 0.933556 +0.000000 -0.182574 0.983192 +-0.033222 -0.179526 0.983192 +0.000000 -0.358431 0.933556 +0.000000 -0.182574 0.983192 +-0.000113 -0.000611 1.000000 +-0.033222 -0.179526 0.983192 +0.000000 -0.000622 1.000000 +-0.000113 -0.000611 1.000000 +0.000000 -0.182574 0.983192 +0.000000 0.000000 1.000000 +-0.000113 -0.000611 1.000000 +0.000000 -0.000622 1.000000 +0.000000 0.000000 1.000000 +-0.000113 -0.000611 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.000113 -0.000611 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.000229 -0.000578 1.000000 +-0.000113 -0.000611 1.000000 +0.000000 0.000000 1.000000 +-0.000340 -0.000520 1.000000 +-0.000229 -0.000578 1.000000 +0.000000 0.000000 1.000000 +-0.000340 -0.000520 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.000340 -0.000520 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.000439 -0.000439 1.000000 +-0.000340 -0.000520 1.000000 +0.000000 0.000000 1.000000 +-0.000439 -0.000439 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.000520 -0.000340 1.000000 +-0.000439 -0.000439 1.000000 +0.000000 0.000000 1.000000 +-0.000520 -0.000340 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.000578 -0.000229 1.000000 +-0.000520 -0.000340 1.000000 +0.000000 0.000000 1.000000 +-0.000578 -0.000229 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.000611 -0.000113 1.000000 +-0.000578 -0.000229 1.000000 +0.000000 0.000000 1.000000 +-0.000611 -0.000113 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.000622 0.000000 1.000000 +-0.000611 -0.000113 1.000000 +0.000000 0.000000 1.000000 +-0.000622 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.000611 0.000113 1.000000 +-0.000622 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.000611 0.000113 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.000578 0.000229 1.000000 +-0.000611 0.000113 1.000000 +0.000000 0.000000 1.000000 +-0.000578 0.000229 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.000520 0.000340 1.000000 +-0.000578 0.000229 1.000000 +0.000000 0.000000 1.000000 +-0.000520 0.000340 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.000439 0.000439 1.000000 +-0.000520 0.000340 1.000000 +0.000000 0.000000 1.000000 +-0.000439 0.000439 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.000340 0.000520 1.000000 +-0.000439 0.000439 1.000000 +0.000000 0.000000 1.000000 +-0.000340 0.000520 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.000229 0.000578 1.000000 +-0.000340 0.000520 1.000000 +0.000000 0.000000 1.000000 +-0.000113 0.000611 1.000000 +-0.000229 0.000578 1.000000 +0.000000 0.000000 1.000000 +-0.000113 0.000611 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.000113 0.000611 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000622 1.000000 +-0.000113 0.000611 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.182574 0.983192 +-0.000113 0.000611 1.000000 +0.000000 0.000622 1.000000 +0.000000 0.182574 0.983192 +-0.033222 0.179526 0.983192 +-0.000113 0.000611 1.000000 +0.000000 0.358431 0.933556 +-0.033222 0.179526 0.983192 +0.000000 0.182574 0.983192 +0.000000 0.358431 0.933556 +-0.065221 0.352447 0.933556 +-0.033222 0.179526 0.983192 +0.000000 0.359011 0.933333 +-0.065221 0.352447 0.933556 +0.000000 0.358431 0.933556 +-0.065327 0.353017 0.933333 +-0.065221 0.352447 0.933556 +0.000000 0.359011 0.933333 +-0.132150 0.333804 0.933333 +-0.065221 0.352447 0.933556 +-0.065327 0.353017 0.933333 +-0.132150 0.333804 0.933333 +-0.131936 0.333265 0.933556 +-0.065221 0.352447 0.933556 +-0.196454 0.300491 0.933333 +-0.131936 0.333265 0.933556 +-0.132150 0.333804 0.933333 +-0.196454 0.300491 0.933333 +-0.196137 0.300005 0.933556 +-0.131936 0.333265 0.933556 +-0.253859 0.253859 0.933333 +-0.196137 0.300005 0.933556 +-0.196454 0.300491 0.933333 +-0.253859 0.253859 0.933333 +-0.253449 0.253449 0.933556 +-0.196137 0.300005 0.933556 +-0.300491 0.196454 0.933333 +-0.253449 0.253449 0.933556 +-0.253859 0.253859 0.933333 +-0.300491 0.196454 0.933333 +-0.300005 0.196137 0.933556 +-0.253449 0.253449 0.933556 +-0.333804 0.132150 0.933333 +-0.300005 0.196137 0.933556 +-0.300491 0.196454 0.933333 +-0.333804 0.132150 0.933333 +-0.333265 0.131936 0.933556 +-0.300005 0.196137 0.933556 +-0.353017 0.065327 0.933333 +-0.333265 0.131936 0.933556 +-0.333804 0.132150 0.933333 +-0.353017 0.065327 0.933333 +-0.352447 0.065221 0.933556 +-0.333265 0.131936 0.933556 +-0.359011 0.000000 0.933333 +-0.352447 0.065221 0.933556 +-0.353017 0.065327 0.933333 +-0.359011 0.000000 0.933333 +-0.358431 0.000000 0.933556 +-0.352447 0.065221 0.933556 +-0.359011 0.000000 0.933333 +-0.352447 -0.065221 0.933556 +-0.358431 0.000000 0.933556 +-0.353017 -0.065327 0.933333 +-0.352447 -0.065221 0.933556 +-0.359011 0.000000 0.933333 +-0.333804 -0.132150 0.933333 +-0.352447 -0.065221 0.933556 +-0.353017 -0.065327 0.933333 +-0.333804 -0.132150 0.933333 +-0.333265 -0.131936 0.933556 +-0.352447 -0.065221 0.933556 +-0.300491 -0.196454 0.933333 +-0.333265 -0.131936 0.933556 +-0.333804 -0.132150 0.933333 +-0.300491 -0.196454 0.933333 +-0.300005 -0.196137 0.933556 +-0.333265 -0.131936 0.933556 +-0.253859 -0.253859 0.933333 +-0.300005 -0.196137 0.933556 +-0.300491 -0.196454 0.933333 +-0.253859 -0.253859 0.933333 +-0.253449 -0.253449 0.933556 +-0.300005 -0.196137 0.933556 +-0.196454 -0.300491 0.933333 +-0.253449 -0.253449 0.933556 +-0.253859 -0.253859 0.933333 +-0.196454 -0.300491 0.933333 +-0.196137 -0.300005 0.933556 +-0.253449 -0.253449 0.933556 +-0.132150 -0.333804 0.933333 +-0.196137 -0.300005 0.933556 +-0.196454 -0.300491 0.933333 +-0.132150 -0.333804 0.933333 +-0.131936 -0.333265 0.933556 +-0.196137 -0.300005 0.933556 +-0.065327 -0.353017 0.933333 +-0.131936 -0.333265 0.933556 +-0.132150 -0.333804 0.933333 +-0.065221 -0.352447 0.933556 +-0.067205 -0.169755 0.983192 +-0.131936 -0.333265 0.933556 +-0.067205 -0.169755 0.983192 +-0.065221 -0.352447 0.933556 +-0.033222 -0.179526 0.983192 +-0.131936 -0.333265 0.933556 +-0.099906 -0.152814 0.983192 +-0.196137 -0.300005 0.933556 +-0.099906 -0.152814 0.983192 +-0.131936 -0.333265 0.933556 +-0.067205 -0.169755 0.983192 +-0.196137 -0.300005 0.933556 +-0.129099 -0.129099 0.983192 +-0.253449 -0.253449 0.933556 +-0.129099 -0.129099 0.983192 +-0.196137 -0.300005 0.933556 +-0.099906 -0.152814 0.983192 +-0.033222 -0.179526 0.983192 +-0.000229 -0.000578 1.000000 +-0.067205 -0.169755 0.983192 +-0.000229 -0.000578 1.000000 +-0.033222 -0.179526 0.983192 +-0.000113 -0.000611 1.000000 +-0.067205 -0.169755 0.983192 +-0.000340 -0.000520 1.000000 +-0.099906 -0.152814 0.983192 +-0.000340 -0.000520 1.000000 +-0.067205 -0.169755 0.983192 +-0.000229 -0.000578 1.000000 +-0.099906 -0.152814 0.983192 +-0.000439 -0.000439 1.000000 +-0.129099 -0.129099 0.983192 +-0.000439 -0.000439 1.000000 +-0.099906 -0.152814 0.983192 +-0.000340 -0.000520 1.000000 +-0.253449 -0.253449 0.933556 +-0.152814 -0.099906 0.983192 +-0.300005 -0.196137 0.933556 +-0.152814 -0.099906 0.983192 +-0.253449 -0.253449 0.933556 +-0.129099 -0.129099 0.983192 +-0.300005 -0.196137 0.933556 +-0.169755 -0.067205 0.983192 +-0.333265 -0.131936 0.933556 +-0.169755 -0.067205 0.983192 +-0.300005 -0.196137 0.933556 +-0.152814 -0.099906 0.983192 +-0.333265 -0.131936 0.933556 +-0.179526 -0.033222 0.983192 +-0.352447 -0.065221 0.933556 +-0.179526 -0.033222 0.983192 +-0.333265 -0.131936 0.933556 +-0.169755 -0.067205 0.983192 +-0.352447 -0.065221 0.933556 +-0.182574 0.000000 0.983192 +-0.358431 0.000000 0.933556 +-0.182574 0.000000 0.983192 +-0.352447 -0.065221 0.933556 +-0.179526 -0.033222 0.983192 +-0.129099 -0.129099 0.983192 +-0.000520 -0.000340 1.000000 +-0.152814 -0.099906 0.983192 +-0.000520 -0.000340 1.000000 +-0.129099 -0.129099 0.983192 +-0.000439 -0.000439 1.000000 +-0.152814 -0.099906 0.983192 +-0.000578 -0.000229 1.000000 +-0.169755 -0.067205 0.983192 +-0.000578 -0.000229 1.000000 +-0.152814 -0.099906 0.983192 +-0.000520 -0.000340 1.000000 +-0.169755 -0.067205 0.983192 +-0.000611 -0.000113 1.000000 +-0.179526 -0.033222 0.983192 +-0.000611 -0.000113 1.000000 +-0.169755 -0.067205 0.983192 +-0.000578 -0.000229 1.000000 +-0.179526 -0.033222 0.983192 +-0.000622 0.000000 1.000000 +-0.182574 0.000000 0.983192 +-0.000622 0.000000 1.000000 +-0.179526 -0.033222 0.983192 +-0.000611 -0.000113 1.000000 +-0.358431 0.000000 0.933556 +-0.179526 0.033222 0.983192 +-0.352447 0.065221 0.933556 +-0.179526 0.033222 0.983192 +-0.358431 0.000000 0.933556 +-0.182574 0.000000 0.983192 +-0.352447 0.065221 0.933556 +-0.169755 0.067205 0.983192 +-0.333265 0.131936 0.933556 +-0.169755 0.067205 0.983192 +-0.352447 0.065221 0.933556 +-0.179526 0.033222 0.983192 +-0.333265 0.131936 0.933556 +-0.152814 0.099906 0.983192 +-0.300005 0.196137 0.933556 +-0.152814 0.099906 0.983192 +-0.333265 0.131936 0.933556 +-0.169755 0.067205 0.983192 +-0.300005 0.196137 0.933556 +-0.129099 0.129099 0.983192 +-0.253449 0.253449 0.933556 +-0.129099 0.129099 0.983192 +-0.300005 0.196137 0.933556 +-0.152814 0.099906 0.983192 +-0.182574 0.000000 0.983192 +-0.000611 0.000113 1.000000 +-0.179526 0.033222 0.983192 +-0.000611 0.000113 1.000000 +-0.182574 0.000000 0.983192 +-0.000622 0.000000 1.000000 +-0.179526 0.033222 0.983192 +-0.000578 0.000229 1.000000 +-0.169755 0.067205 0.983192 +-0.000578 0.000229 1.000000 +-0.179526 0.033222 0.983192 +-0.000611 0.000113 1.000000 +-0.169755 0.067205 0.983192 +-0.000520 0.000340 1.000000 +-0.152814 0.099906 0.983192 +-0.000520 0.000340 1.000000 +-0.169755 0.067205 0.983192 +-0.000578 0.000229 1.000000 +-0.152814 0.099906 0.983192 +-0.000439 0.000439 1.000000 +-0.129099 0.129099 0.983192 +-0.000439 0.000439 1.000000 +-0.152814 0.099906 0.983192 +-0.000520 0.000340 1.000000 +-0.253449 0.253449 0.933556 +-0.099906 0.152814 0.983192 +-0.196137 0.300005 0.933556 +-0.099906 0.152814 0.983192 +-0.253449 0.253449 0.933556 +-0.129099 0.129099 0.983192 +-0.196137 0.300005 0.933556 +-0.067205 0.169755 0.983192 +-0.131936 0.333265 0.933556 +-0.067205 0.169755 0.983192 +-0.196137 0.300005 0.933556 +-0.099906 0.152814 0.983192 +-0.131936 0.333265 0.933556 +-0.033222 0.179526 0.983192 +-0.065221 0.352447 0.933556 +-0.033222 0.179526 0.983192 +-0.131936 0.333265 0.933556 +-0.067205 0.169755 0.983192 +-0.129099 0.129099 0.983192 +-0.000340 0.000520 1.000000 +-0.099906 0.152814 0.983192 +-0.000340 0.000520 1.000000 +-0.129099 0.129099 0.983192 +-0.000439 0.000439 1.000000 +-0.099906 0.152814 0.983192 +-0.000229 0.000578 1.000000 +-0.067205 0.169755 0.983192 +-0.000229 0.000578 1.000000 +-0.099906 0.152814 0.983192 +-0.000340 0.000520 1.000000 +-0.067205 0.169755 0.983192 +-0.000113 0.000611 1.000000 +-0.033222 0.179526 0.983192 +-0.000113 0.000611 1.000000 +-0.067205 0.169755 0.983192 +-0.000229 0.000578 1.000000 +0.000000 0.358431 0.933556 +0.000000 0.359011 0.933333 +0.000000 0.359011 0.933333 +0.000000 0.000000 1.000000 +0.000000 0.000622 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000622 1.000000 +0.000000 0.000622 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000622 1.000000 +0.000000 0.182574 0.983192 +0.000000 0.000622 1.000000 +0.000000 0.182574 0.983192 +0.000000 0.182574 0.983192 +0.000000 0.000622 1.000000 +0.000000 0.358431 0.933556 +0.000000 0.182574 0.983192 +0.000000 0.182574 0.983192 +0.000000 0.358431 0.933556 +0.000000 0.358431 0.933556 +0.000000 0.182574 0.983192 +0.000000 0.359011 0.933333 +0.000000 0.358431 0.933556 +0.000000 0.358431 0.933556 +0.000000 -0.000622 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -0.358431 0.933556 +0.000000 -0.359011 0.933333 +0.000000 -0.359011 0.933333 +0.000000 -0.358431 0.933556 +0.000000 -0.358431 0.933556 +0.000000 -0.359011 0.933333 +0.000000 -0.182574 0.983192 +0.000000 -0.358431 0.933556 +0.000000 -0.358431 0.933556 +0.000000 -0.182574 0.983192 +0.000000 -0.182574 0.983192 +0.000000 -0.358431 0.933556 +0.000000 -0.000622 1.000000 +0.000000 -0.182574 0.983192 +0.000000 -0.182574 0.983192 +0.000000 -0.000622 1.000000 +0.000000 -0.000622 1.000000 +0.000000 -0.182574 0.983192 +0.000000 0.000000 1.000000 +0.000000 -0.000622 1.000000 +0.000000 -0.000622 1.000000 +0.000229 0.000578 1.000000 +0.000000 0.000000 1.000000 +0.000113 0.000611 1.000000 +0.000000 0.000000 1.000000 +0.000000 -0.000622 1.000000 +0.000000 0.000000 1.000000 +0.065327 0.353017 0.933333 +0.000000 0.358431 0.933556 +0.000000 0.359011 0.933333 +0.000000 0.000000 1.000000 +0.000113 0.000611 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000622 1.000000 +0.000113 0.000611 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.182574 0.983192 +0.000113 0.000611 1.000000 +0.000000 0.000622 1.000000 +0.000000 0.182574 0.983192 +0.033222 0.179526 0.983192 +0.000113 0.000611 1.000000 +0.000000 0.358431 0.933556 +0.033222 0.179526 0.983192 +0.000000 0.182574 0.983192 +0.000000 0.358431 0.933556 +0.065221 0.352447 0.933556 +0.033222 0.179526 0.983192 +0.065327 0.353017 0.933333 +0.065221 0.352447 0.933556 +0.000000 0.358431 0.933556 +0.132150 0.333804 0.933333 +0.065221 0.352447 0.933556 +0.065327 0.353017 0.933333 +0.132150 0.333804 0.933333 +0.131936 0.333265 0.933556 +0.065221 0.352447 0.933556 +0.196454 0.300491 0.933333 +0.131936 0.333265 0.933556 +0.132150 0.333804 0.933333 +0.196454 0.300491 0.933333 +0.196137 0.300005 0.933556 +0.131936 0.333265 0.933556 +0.253859 0.253859 0.933333 +0.196137 0.300005 0.933556 +0.196454 0.300491 0.933333 +0.253859 0.253859 0.933333 +0.253449 0.253449 0.933556 +0.196137 0.300005 0.933556 +0.300491 0.196454 0.933333 +0.253449 0.253449 0.933556 +0.253859 0.253859 0.933333 +0.300491 0.196454 0.933333 +0.300005 0.196137 0.933556 +0.253449 0.253449 0.933556 +0.333804 0.132150 0.933333 +0.300005 0.196137 0.933556 +0.300491 0.196454 0.933333 +0.333804 0.132150 0.933333 +0.333265 0.131936 0.933556 +0.300005 0.196137 0.933556 +0.353017 0.065327 0.933333 +0.333265 0.131936 0.933556 +0.333804 0.132150 0.933333 +0.353017 0.065327 0.933333 +0.352447 0.065221 0.933556 +0.333265 0.131936 0.933556 +0.359011 0.000000 0.933333 +0.352447 0.065221 0.933556 +0.353017 0.065327 0.933333 +0.359011 0.000000 0.933333 +0.358431 0.000000 0.933556 +0.352447 0.065221 0.933556 +0.353017 -0.065327 0.933333 +0.358431 0.000000 0.933556 +0.359011 0.000000 0.933333 +0.353017 -0.065327 0.933333 +0.352447 -0.065221 0.933556 +0.358431 0.000000 0.933556 +0.333804 -0.132150 0.933333 +0.352447 -0.065221 0.933556 +0.353017 -0.065327 0.933333 +0.333804 -0.132150 0.933333 +0.333265 -0.131936 0.933556 +0.352447 -0.065221 0.933556 +0.300491 -0.196454 0.933333 +0.333265 -0.131936 0.933556 +0.333804 -0.132150 0.933333 +0.300491 -0.196454 0.933333 +0.300005 -0.196137 0.933556 +0.333265 -0.131936 0.933556 +0.253859 -0.253859 0.933333 +0.300005 -0.196137 0.933556 +0.300491 -0.196454 0.933333 +0.253859 -0.253859 0.933333 +0.253449 -0.253449 0.933556 +0.300005 -0.196137 0.933556 +0.196454 -0.300491 0.933333 +0.253449 -0.253449 0.933556 +0.253859 -0.253859 0.933333 +0.196454 -0.300491 0.933333 +0.196137 -0.300005 0.933556 +0.253449 -0.253449 0.933556 +0.132150 -0.333804 0.933333 +0.196137 -0.300005 0.933556 +0.196454 -0.300491 0.933333 +0.132150 -0.333804 0.933333 +0.131936 -0.333265 0.933556 +0.196137 -0.300005 0.933556 +0.065327 -0.353017 0.933333 +0.131936 -0.333265 0.933556 +0.132150 -0.333804 0.933333 +0.065327 -0.353017 0.933333 +0.065221 -0.352447 0.933556 +0.131936 -0.333265 0.933556 +0.000000 -0.359011 0.933333 +0.065221 -0.352447 0.933556 +0.065327 -0.353017 0.933333 +0.000000 -0.358431 0.933556 +0.065221 -0.352447 0.933556 +0.000000 -0.359011 0.933333 +0.000000 -0.182574 0.983192 +0.065221 -0.352447 0.933556 +0.000000 -0.358431 0.933556 +0.000000 -0.182574 0.983192 +0.033222 -0.179526 0.983192 +0.065221 -0.352447 0.933556 +0.000000 -0.000622 1.000000 +0.033222 -0.179526 0.983192 +0.000000 -0.182574 0.983192 +0.000000 -0.000622 1.000000 +0.000113 -0.000611 1.000000 +0.033222 -0.179526 0.983192 +0.000000 0.000000 1.000000 +0.000113 -0.000611 1.000000 +0.000000 -0.000622 1.000000 +0.000000 0.000000 1.000000 +0.000113 -0.000611 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000229 -0.000578 1.000000 +0.000113 -0.000611 1.000000 +0.000000 0.000000 1.000000 +0.000229 -0.000578 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000340 -0.000520 1.000000 +0.000229 -0.000578 1.000000 +0.000000 0.000000 1.000000 +0.000340 -0.000520 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000439 -0.000439 1.000000 +0.000340 -0.000520 1.000000 +0.000000 0.000000 1.000000 +0.000439 -0.000439 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000520 -0.000340 1.000000 +0.000439 -0.000439 1.000000 +0.000000 0.000000 1.000000 +0.000520 -0.000340 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000578 -0.000229 1.000000 +0.000520 -0.000340 1.000000 +0.000000 0.000000 1.000000 +0.000578 -0.000229 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000611 -0.000113 1.000000 +0.000578 -0.000229 1.000000 +0.000000 0.000000 1.000000 +0.000611 -0.000113 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000622 0.000000 1.000000 +0.000611 -0.000113 1.000000 +0.000000 0.000000 1.000000 +0.000622 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000611 0.000113 1.000000 +0.000622 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000611 0.000113 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000578 0.000229 1.000000 +0.000611 0.000113 1.000000 +0.000000 0.000000 1.000000 +0.000578 0.000229 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000520 0.000340 1.000000 +0.000578 0.000229 1.000000 +0.000000 0.000000 1.000000 +0.000520 0.000340 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000439 0.000439 1.000000 +0.000520 0.000340 1.000000 +0.000000 0.000000 1.000000 +0.000439 0.000439 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000340 0.000520 1.000000 +0.000439 0.000439 1.000000 +0.000000 0.000000 1.000000 +0.000340 0.000520 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000229 0.000578 1.000000 +0.000340 0.000520 1.000000 +0.000000 0.000000 1.000000 +0.000229 0.000578 1.000000 +0.000000 0.000000 1.000000 +0.000113 -0.000611 1.000000 +0.067205 -0.169755 0.983192 +0.033222 -0.179526 0.983192 +0.067205 -0.169755 0.983192 +0.000113 -0.000611 1.000000 +0.000229 -0.000578 1.000000 +0.033222 -0.179526 0.983192 +0.131936 -0.333265 0.933556 +0.065221 -0.352447 0.933556 +0.131936 -0.333265 0.933556 +0.033222 -0.179526 0.983192 +0.067205 -0.169755 0.983192 +0.000229 -0.000578 1.000000 +0.099906 -0.152814 0.983192 +0.067205 -0.169755 0.983192 +0.099906 -0.152814 0.983192 +0.000229 -0.000578 1.000000 +0.000340 -0.000520 1.000000 +0.067205 -0.169755 0.983192 +0.196137 -0.300005 0.933556 +0.131936 -0.333265 0.933556 +0.196137 -0.300005 0.933556 +0.067205 -0.169755 0.983192 +0.099906 -0.152814 0.983192 +0.000340 -0.000520 1.000000 +0.129099 -0.129099 0.983192 +0.099906 -0.152814 0.983192 +0.129099 -0.129099 0.983192 +0.000340 -0.000520 1.000000 +0.000439 -0.000439 1.000000 +0.099906 -0.152814 0.983192 +0.253449 -0.253449 0.933556 +0.196137 -0.300005 0.933556 +0.253449 -0.253449 0.933556 +0.099906 -0.152814 0.983192 +0.129099 -0.129099 0.983192 +0.000439 -0.000439 1.000000 +0.152814 -0.099906 0.983192 +0.129099 -0.129099 0.983192 +0.152814 -0.099906 0.983192 +0.000439 -0.000439 1.000000 +0.000520 -0.000340 1.000000 +0.129099 -0.129099 0.983192 +0.300005 -0.196137 0.933556 +0.253449 -0.253449 0.933556 +0.300005 -0.196137 0.933556 +0.129099 -0.129099 0.983192 +0.152814 -0.099906 0.983192 +0.000520 -0.000340 1.000000 +0.169755 -0.067205 0.983192 +0.152814 -0.099906 0.983192 +0.169755 -0.067205 0.983192 +0.000520 -0.000340 1.000000 +0.000578 -0.000229 1.000000 +0.152814 -0.099906 0.983192 +0.333265 -0.131936 0.933556 +0.300005 -0.196137 0.933556 +0.333265 -0.131936 0.933556 +0.152814 -0.099906 0.983192 +0.169755 -0.067205 0.983192 +0.000578 -0.000229 1.000000 +0.179526 -0.033222 0.983192 +0.169755 -0.067205 0.983192 +0.179526 -0.033222 0.983192 +0.000578 -0.000229 1.000000 +0.000611 -0.000113 1.000000 +0.000611 -0.000113 1.000000 +0.182574 0.000000 0.983192 +0.179526 -0.033222 0.983192 +0.182574 0.000000 0.983192 +0.000611 -0.000113 1.000000 +0.000622 0.000000 1.000000 +0.169755 -0.067205 0.983192 +0.352447 -0.065221 0.933556 +0.333265 -0.131936 0.933556 +0.352447 -0.065221 0.933556 +0.169755 -0.067205 0.983192 +0.179526 -0.033222 0.983192 +0.179526 -0.033222 0.983192 +0.358431 0.000000 0.933556 +0.352447 -0.065221 0.933556 +0.358431 0.000000 0.933556 +0.179526 -0.033222 0.983192 +0.182574 0.000000 0.983192 +0.000622 0.000000 1.000000 +0.179526 0.033222 0.983192 +0.182574 0.000000 0.983192 +0.179526 0.033222 0.983192 +0.000622 0.000000 1.000000 +0.000611 0.000113 1.000000 +0.000611 0.000113 1.000000 +0.169755 0.067205 0.983192 +0.179526 0.033222 0.983192 +0.169755 0.067205 0.983192 +0.000611 0.000113 1.000000 +0.000578 0.000229 1.000000 +0.182574 0.000000 0.983192 +0.352447 0.065221 0.933556 +0.358431 0.000000 0.933556 +0.352447 0.065221 0.933556 +0.182574 0.000000 0.983192 +0.179526 0.033222 0.983192 +0.179526 0.033222 0.983192 +0.333265 0.131936 0.933556 +0.352447 0.065221 0.933556 +0.333265 0.131936 0.933556 +0.179526 0.033222 0.983192 +0.169755 0.067205 0.983192 +0.000578 0.000229 1.000000 +0.152814 0.099906 0.983192 +0.169755 0.067205 0.983192 +0.152814 0.099906 0.983192 +0.000578 0.000229 1.000000 +0.000520 0.000340 1.000000 +0.169755 0.067205 0.983192 +0.300005 0.196137 0.933556 +0.333265 0.131936 0.933556 +0.300005 0.196137 0.933556 +0.169755 0.067205 0.983192 +0.152814 0.099906 0.983192 +0.000520 0.000340 1.000000 +0.129099 0.129099 0.983192 +0.152814 0.099906 0.983192 +0.129099 0.129099 0.983192 +0.000520 0.000340 1.000000 +0.000439 0.000439 1.000000 +0.152814 0.099906 0.983192 +0.253449 0.253449 0.933556 +0.300005 0.196137 0.933556 +0.253449 0.253449 0.933556 +0.152814 0.099906 0.983192 +0.129099 0.129099 0.983192 +0.000439 0.000439 1.000000 +0.099906 0.152814 0.983192 +0.129099 0.129099 0.983192 +0.099906 0.152814 0.983192 +0.000439 0.000439 1.000000 +0.000340 0.000520 1.000000 +0.129099 0.129099 0.983192 +0.196137 0.300005 0.933556 +0.253449 0.253449 0.933556 +0.196137 0.300005 0.933556 +0.129099 0.129099 0.983192 +0.099906 0.152814 0.983192 +0.000340 0.000520 1.000000 +0.067205 0.169755 0.983192 +0.099906 0.152814 0.983192 +0.067205 0.169755 0.983192 +0.000340 0.000520 1.000000 +0.000229 0.000578 1.000000 +0.099906 0.152814 0.983192 +0.131936 0.333265 0.933556 +0.196137 0.300005 0.933556 +0.131936 0.333265 0.933556 +0.099906 0.152814 0.983192 +0.067205 0.169755 0.983192 +0.000229 0.000578 1.000000 +0.033222 0.179526 0.983192 +0.067205 0.169755 0.983192 +0.033222 0.179526 0.983192 +0.000229 0.000578 1.000000 +0.000113 0.000611 1.000000 +0.067205 0.169755 0.983192 +0.065221 0.352447 0.933556 +0.131936 0.333265 0.933556 +0.065221 0.352447 0.933556 +0.067205 0.169755 0.983192 +0.033222 0.179526 0.983192 +-0.037411 -0.178700 0.983192 +-0.065327 -0.353017 0.933333 +-0.073446 -0.350825 0.933556 +-0.253449 -0.253449 0.933556 +-0.226284 -0.278719 0.933333 +-0.253859 -0.253859 0.933333 +-0.203099 -0.295336 0.933556 +-0.226284 -0.278719 0.933333 +-0.253449 -0.253449 0.933556 +-0.203099 -0.295336 0.933556 +-0.196454 -0.300491 0.933333 +-0.226284 -0.278719 0.933333 +-0.142361 -0.328947 0.933556 +-0.196454 -0.300491 0.933333 +-0.203099 -0.295336 0.933556 +-0.142361 -0.328947 0.933556 +-0.132150 -0.333804 0.933333 +-0.196454 -0.300491 0.933333 +-0.073446 -0.350825 0.933556 +-0.132150 -0.333804 0.933333 +-0.142361 -0.328947 0.933556 +-0.073446 -0.350825 0.933556 +-0.065327 -0.353017 0.933333 +-0.132150 -0.333804 0.933333 +-0.065327 -0.353017 0.933333 +0.000000 -0.358431 0.933556 +0.000000 -0.359011 0.933333 +0.000000 0.000000 1.000000 +-0.000622 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.253859 -0.253859 0.933333 +-0.295336 -0.203099 0.933556 +-0.253449 -0.253449 0.933556 +-0.278719 -0.226284 0.933333 +-0.295336 -0.203099 0.933556 +-0.253859 -0.253859 0.933333 +-0.300491 -0.196454 0.933333 +-0.295336 -0.203099 0.933556 +-0.278719 -0.226284 0.933333 +-0.300491 -0.196454 0.933333 +-0.328947 -0.142361 0.933556 +-0.295336 -0.203099 0.933556 +-0.333804 -0.132150 0.933333 +-0.328947 -0.142361 0.933556 +-0.300491 -0.196454 0.933333 +-0.333804 -0.132150 0.933333 +-0.350825 -0.073446 0.933556 +-0.328947 -0.142361 0.933556 +-0.353017 -0.065327 0.933333 +-0.350825 -0.073446 0.933556 +-0.333804 -0.132150 0.933333 +0.000000 0.000000 1.000000 +-0.182574 0.000000 0.983192 +-0.000622 0.000000 1.000000 +-0.065327 -0.353017 0.933333 +0.000000 -0.182574 0.983192 +0.000000 -0.358431 0.933556 +0.000000 -0.000622 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -0.182574 0.983192 +0.000000 0.000000 1.000000 +0.000000 -0.000622 1.000000 +-0.358431 0.000000 0.933556 +-0.353017 -0.065327 0.933333 +-0.359011 0.000000 0.933333 +-0.182574 0.000000 0.983192 +-0.353017 -0.065327 0.933333 +-0.358431 0.000000 0.933556 +-0.353017 -0.065327 0.933333 +-0.178700 -0.037411 0.983192 +-0.350825 -0.073446 0.933556 +-0.182574 0.000000 0.983192 +-0.178700 -0.037411 0.983192 +-0.353017 -0.065327 0.933333 +0.000000 0.000000 1.000000 +-0.178700 -0.037411 0.983192 +-0.182574 0.000000 0.983192 +0.000000 0.000000 1.000000 +-0.000608 -0.000127 1.000000 +-0.178700 -0.037411 0.983192 +0.000000 0.000000 1.000000 +-0.000608 -0.000127 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.000570 -0.000247 1.000000 +-0.000608 -0.000127 1.000000 +0.000000 0.000000 1.000000 +-0.000570 -0.000247 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.000512 -0.000352 1.000000 +-0.000570 -0.000247 1.000000 +0.000000 0.000000 1.000000 +-0.000512 -0.000352 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.000439 -0.000439 1.000000 +-0.000512 -0.000352 1.000000 +0.000000 0.000000 1.000000 +-0.000439 -0.000439 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.000439 -0.000439 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.000352 -0.000512 1.000000 +-0.000439 -0.000439 1.000000 +0.000000 0.000000 1.000000 +-0.000352 -0.000512 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.000247 -0.000570 1.000000 +-0.000352 -0.000512 1.000000 +0.000000 0.000000 1.000000 +-0.000247 -0.000570 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.000127 -0.000608 1.000000 +-0.000247 -0.000570 1.000000 +0.000000 0.000000 1.000000 +-0.000127 -0.000608 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.037411 -0.178700 0.983192 +-0.000127 -0.000608 1.000000 +0.000000 -0.182574 0.983192 +-0.037411 -0.178700 0.983192 +0.000000 0.000000 1.000000 +-0.065327 -0.353017 0.933333 +-0.037411 -0.178700 0.983192 +0.000000 -0.182574 0.983192 +-0.000608 -0.000127 1.000000 +-0.167556 -0.072514 0.983192 +-0.178700 -0.037411 0.983192 +-0.167556 -0.072514 0.983192 +-0.000608 -0.000127 1.000000 +-0.000570 -0.000247 1.000000 +-0.178700 -0.037411 0.983192 +-0.328947 -0.142361 0.933556 +-0.350825 -0.073446 0.933556 +-0.328947 -0.142361 0.933556 +-0.178700 -0.037411 0.983192 +-0.167556 -0.072514 0.983192 +-0.000570 -0.000247 1.000000 +-0.150436 -0.103453 0.983192 +-0.167556 -0.072514 0.983192 +-0.150436 -0.103453 0.983192 +-0.000570 -0.000247 1.000000 +-0.000512 -0.000352 1.000000 +-0.000512 -0.000352 1.000000 +-0.129099 -0.129099 0.983192 +-0.150436 -0.103453 0.983192 +-0.129099 -0.129099 0.983192 +-0.000512 -0.000352 1.000000 +-0.000439 -0.000439 1.000000 +-0.167556 -0.072514 0.983192 +-0.295336 -0.203099 0.933556 +-0.328947 -0.142361 0.933556 +-0.295336 -0.203099 0.933556 +-0.167556 -0.072514 0.983192 +-0.150436 -0.103453 0.983192 +-0.150436 -0.103453 0.983192 +-0.253449 -0.253449 0.933556 +-0.295336 -0.203099 0.933556 +-0.253449 -0.253449 0.933556 +-0.150436 -0.103453 0.983192 +-0.129099 -0.129099 0.983192 +-0.000439 -0.000439 1.000000 +-0.103453 -0.150436 0.983192 +-0.129099 -0.129099 0.983192 +-0.103453 -0.150436 0.983192 +-0.000439 -0.000439 1.000000 +-0.000352 -0.000512 1.000000 +-0.000352 -0.000512 1.000000 +-0.072514 -0.167556 0.983192 +-0.103453 -0.150436 0.983192 +-0.072514 -0.167556 0.983192 +-0.000352 -0.000512 1.000000 +-0.000247 -0.000570 1.000000 +-0.129099 -0.129099 0.983192 +-0.203099 -0.295336 0.933556 +-0.253449 -0.253449 0.933556 +-0.203099 -0.295336 0.933556 +-0.129099 -0.129099 0.983192 +-0.103453 -0.150436 0.983192 +-0.103453 -0.150436 0.983192 +-0.142361 -0.328947 0.933556 +-0.203099 -0.295336 0.933556 +-0.142361 -0.328947 0.933556 +-0.103453 -0.150436 0.983192 +-0.072514 -0.167556 0.983192 +-0.000247 -0.000570 1.000000 +-0.037411 -0.178700 0.983192 +-0.072514 -0.167556 0.983192 +-0.037411 -0.178700 0.983192 +-0.000247 -0.000570 1.000000 +-0.000127 -0.000608 1.000000 +-0.072514 -0.167556 0.983192 +-0.073446 -0.350825 0.933556 +-0.142361 -0.328947 0.933556 +-0.073446 -0.350825 0.933556 +-0.072514 -0.167556 0.983192 +-0.037411 -0.178700 0.983192 +0.000000 0.359011 0.933333 +0.000000 0.358431 0.933556 +0.000000 0.358431 0.933556 +0.000000 0.000622 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000622 1.000000 +0.000000 0.000622 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.182574 0.983192 +0.000000 0.000622 1.000000 +0.000000 0.000622 1.000000 +0.000000 0.182574 0.983192 +0.000000 0.182574 0.983192 +0.000000 0.000622 1.000000 +0.000000 0.358431 0.933556 +0.000000 0.182574 0.983192 +0.000000 0.182574 0.983192 +0.000000 0.358431 0.933556 +0.000000 0.358431 0.933556 +0.000000 0.182574 0.983192 +0.000000 0.358431 0.933556 +0.000000 0.359011 0.933333 +0.000000 0.359011 0.933333 +0.000000 -0.594741 0.803917 +0.000000 -0.738552 0.674196 +0.000000 -0.738552 0.674196 +0.000000 -0.788227 0.615385 +0.000000 -0.738552 0.674196 +0.000000 -0.788227 0.615385 +0.000000 -0.738552 0.674196 +0.000000 -0.738552 0.674196 +0.000000 -0.788227 0.615385 +0.000000 0.000000 1.000000 +0.000000 -0.076926 0.997037 +0.000000 0.000000 1.000000 +0.000000 -0.076926 0.997037 +0.000000 -0.076926 0.997037 +0.000000 0.000000 1.000000 +0.000000 -0.267675 0.963509 +0.000000 -0.076926 0.997037 +0.000000 -0.076926 0.997037 +0.000000 -0.267675 0.963509 +0.000000 -0.267675 0.963509 +0.000000 -0.076926 0.997037 +0.000000 -0.438529 0.898717 +0.000000 -0.267675 0.963509 +0.000000 -0.267675 0.963509 +0.000000 -0.438529 0.898717 +0.000000 -0.438529 0.898717 +0.000000 -0.267675 0.963509 +0.000000 -0.594741 0.803917 +0.000000 -0.438529 0.898717 +0.000000 -0.438529 0.898717 +0.000000 -0.594741 0.803917 +0.000000 -0.594741 0.803917 +0.000000 -0.438529 0.898717 +0.000000 -0.738552 0.674196 +0.000000 -0.594741 0.803917 +0.000000 -0.594741 0.803917 +0.000000 0.000000 1.000000 +0.070598 -0.030553 0.997037 +0.000000 0.000000 1.000000 +0.063385 -0.043589 0.997037 +0.000000 0.000000 1.000000 +0.070598 -0.030553 0.997037 +0.063385 -0.043589 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.054395 -0.054395 0.997037 +0.000000 0.000000 1.000000 +0.063385 -0.043589 0.997037 +0.054395 -0.054395 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.054395 -0.054395 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.043589 -0.063385 0.997037 +0.000000 0.000000 1.000000 +0.054395 -0.054395 0.997037 +0.775068 -0.143428 0.615385 +0.738552 0.000000 0.674196 +0.788227 0.000000 0.615385 +0.076926 0.000000 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.030553 -0.070598 0.997037 +0.000000 0.000000 1.000000 +0.043589 -0.063385 0.997037 +0.030553 -0.070598 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.030553 -0.070598 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.015763 -0.075294 0.997037 +0.000000 0.000000 1.000000 +0.030553 -0.070598 0.997037 +0.015763 -0.075294 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.015763 -0.075294 0.997037 +0.000000 -0.076926 0.997037 +0.000000 0.000000 1.000000 +0.054849 -0.261995 0.963509 +0.000000 -0.076926 0.997037 +0.015763 -0.075294 0.997037 +0.054849 -0.261995 0.963509 +0.000000 -0.267675 0.963509 +0.000000 -0.076926 0.997037 +0.089859 -0.429224 0.898717 +0.000000 -0.267675 0.963509 +0.054849 -0.261995 0.963509 +0.089859 -0.429224 0.898717 +0.000000 -0.438529 0.898717 +0.000000 -0.267675 0.963509 +0.121868 -0.582121 0.803917 +0.000000 -0.438529 0.898717 +0.089859 -0.429224 0.898717 +0.121868 -0.582121 0.803917 +0.000000 -0.594741 0.803917 +0.000000 -0.438529 0.898717 +0.151336 -0.722881 0.674196 +0.000000 -0.594741 0.803917 +0.121868 -0.582121 0.803917 +0.151336 -0.722881 0.674196 +0.000000 -0.738552 0.674196 +0.000000 -0.594741 0.803917 +0.151336 -0.722881 0.674196 +0.000000 -0.788227 0.615385 +0.000000 -0.738552 0.674196 +0.151336 -0.722881 0.674196 +0.143428 -0.775068 0.615385 +0.000000 -0.788227 0.615385 +0.151336 -0.722881 0.674196 +0.290142 -0.732884 0.615385 +0.143428 -0.775068 0.615385 +0.293336 -0.677800 0.674196 +0.290142 -0.732884 0.615385 +0.151336 -0.722881 0.674196 +0.293336 -0.677800 0.674196 +0.431325 -0.659742 0.615385 +0.290142 -0.732884 0.615385 +0.418489 -0.608544 0.674196 +0.431325 -0.659742 0.615385 +0.293336 -0.677800 0.674196 +0.418489 -0.608544 0.674196 +0.496818 -0.611943 0.615385 +0.431325 -0.659742 0.615385 +0.522235 -0.522235 0.674196 +0.496818 -0.611943 0.615385 +0.418489 -0.608544 0.674196 +0.522235 -0.522235 0.674196 +0.557361 -0.557361 0.615385 +0.496818 -0.611943 0.615385 +0.522235 -0.522235 0.674196 +0.611943 -0.496818 0.615385 +0.557361 -0.557361 0.615385 +0.608544 -0.418489 0.674196 +0.611943 -0.496818 0.615385 +0.522235 -0.522235 0.674196 +0.608544 -0.418489 0.674196 +0.659742 -0.431325 0.615385 +0.611943 -0.496818 0.615385 +0.677800 -0.293336 0.674196 +0.659742 -0.431325 0.615385 +0.608544 -0.418489 0.674196 +0.677800 -0.293336 0.674196 +0.732884 -0.290142 0.615385 +0.659742 -0.431325 0.615385 +0.722881 -0.151336 0.674196 +0.732884 -0.290142 0.615385 +0.677800 -0.293336 0.674196 +0.722881 -0.151336 0.674196 +0.775068 -0.143428 0.615385 +0.732884 -0.290142 0.615385 +0.722881 -0.151336 0.674196 +0.738552 0.000000 0.674196 +0.775068 -0.143428 0.615385 +0.582121 -0.121868 0.803917 +0.738552 0.000000 0.674196 +0.722881 -0.151336 0.674196 +0.582121 -0.121868 0.803917 +0.594741 0.000000 0.803917 +0.738552 0.000000 0.674196 +0.429224 -0.089859 0.898717 +0.594741 0.000000 0.803917 +0.582121 -0.121868 0.803917 +0.429224 -0.089859 0.898717 +0.438529 0.000000 0.898717 +0.594741 0.000000 0.803917 +0.261995 -0.054849 0.963509 +0.438529 0.000000 0.898717 +0.429224 -0.089859 0.898717 +0.261995 -0.054849 0.963509 +0.267675 0.000000 0.963509 +0.438529 0.000000 0.898717 +0.075294 -0.015763 0.997037 +0.267675 0.000000 0.963509 +0.261995 -0.054849 0.963509 +0.075294 -0.015763 0.997037 +0.076926 0.000000 0.997037 +0.267675 0.000000 0.963509 +0.075294 -0.015763 0.997037 +0.000000 0.000000 1.000000 +0.076926 0.000000 0.997037 +0.070598 -0.030553 0.997037 +0.000000 0.000000 1.000000 +0.075294 -0.015763 0.997037 +0.722881 -0.151336 0.674196 +0.545819 -0.236218 0.803917 +0.582121 -0.121868 0.803917 +0.545819 -0.236218 0.803917 +0.722881 -0.151336 0.674196 +0.677800 -0.293336 0.674196 +0.582121 -0.121868 0.803917 +0.402456 -0.174174 0.898717 +0.429224 -0.089859 0.898717 +0.402456 -0.174174 0.898717 +0.582121 -0.121868 0.803917 +0.545819 -0.236218 0.803917 +0.429224 -0.089859 0.898717 +0.245656 -0.106314 0.963509 +0.261995 -0.054849 0.963509 +0.245656 -0.106314 0.963509 +0.429224 -0.089859 0.898717 +0.402456 -0.174174 0.898717 +0.261995 -0.054849 0.963509 +0.070598 -0.030553 0.997037 +0.075294 -0.015763 0.997037 +0.070598 -0.030553 0.997037 +0.261995 -0.054849 0.963509 +0.245656 -0.106314 0.963509 +0.677800 -0.293336 0.674196 +0.490048 -0.337001 0.803917 +0.545819 -0.236218 0.803917 +0.490048 -0.337001 0.803917 +0.677800 -0.293336 0.674196 +0.608544 -0.418489 0.674196 +0.545819 -0.236218 0.803917 +0.361334 -0.248486 0.898717 +0.402456 -0.174174 0.898717 +0.361334 -0.248486 0.898717 +0.545819 -0.236218 0.803917 +0.490048 -0.337001 0.803917 +0.402456 -0.174174 0.898717 +0.220556 -0.151674 0.963509 +0.245656 -0.106314 0.963509 +0.220556 -0.151674 0.963509 +0.402456 -0.174174 0.898717 +0.361334 -0.248486 0.898717 +0.245656 -0.106314 0.963509 +0.063385 -0.043589 0.997037 +0.070598 -0.030553 0.997037 +0.063385 -0.043589 0.997037 +0.245656 -0.106314 0.963509 +0.220556 -0.151674 0.963509 +0.608544 -0.418489 0.674196 +0.420546 -0.420546 0.803917 +0.490048 -0.337001 0.803917 +0.420546 -0.420546 0.803917 +0.608544 -0.418489 0.674196 +0.522235 -0.522235 0.674196 +0.490048 -0.337001 0.803917 +0.310087 -0.310087 0.898717 +0.361334 -0.248486 0.898717 +0.310087 -0.310087 0.898717 +0.490048 -0.337001 0.803917 +0.420546 -0.420546 0.803917 +0.361334 -0.248486 0.898717 +0.189275 -0.189275 0.963509 +0.220556 -0.151674 0.963509 +0.189275 -0.189275 0.963509 +0.361334 -0.248486 0.898717 +0.310087 -0.310087 0.898717 +0.220556 -0.151674 0.963509 +0.054395 -0.054395 0.997037 +0.063385 -0.043589 0.997037 +0.054395 -0.054395 0.997037 +0.220556 -0.151674 0.963509 +0.189275 -0.189275 0.963509 +0.522235 -0.522235 0.674196 +0.337001 -0.490048 0.803917 +0.420546 -0.420546 0.803917 +0.337001 -0.490048 0.803917 +0.522235 -0.522235 0.674196 +0.418489 -0.608544 0.674196 +0.420546 -0.420546 0.803917 +0.248486 -0.361334 0.898717 +0.310087 -0.310087 0.898717 +0.248486 -0.361334 0.898717 +0.420546 -0.420546 0.803917 +0.337001 -0.490048 0.803917 +0.310087 -0.310087 0.898717 +0.151674 -0.220556 0.963509 +0.189275 -0.189275 0.963509 +0.151674 -0.220556 0.963509 +0.310087 -0.310087 0.898717 +0.248486 -0.361334 0.898717 +0.189275 -0.189275 0.963509 +0.043589 -0.063385 0.997037 +0.054395 -0.054395 0.997037 +0.043589 -0.063385 0.997037 +0.189275 -0.189275 0.963509 +0.151674 -0.220556 0.963509 +0.418489 -0.608544 0.674196 +0.236218 -0.545819 0.803917 +0.337001 -0.490048 0.803917 +0.236218 -0.545819 0.803917 +0.418489 -0.608544 0.674196 +0.293336 -0.677800 0.674196 +0.337001 -0.490048 0.803917 +0.174174 -0.402456 0.898717 +0.248486 -0.361334 0.898717 +0.174174 -0.402456 0.898717 +0.337001 -0.490048 0.803917 +0.236218 -0.545819 0.803917 +0.248486 -0.361334 0.898717 +0.106314 -0.245656 0.963509 +0.151674 -0.220556 0.963509 +0.106314 -0.245656 0.963509 +0.248486 -0.361334 0.898717 +0.174174 -0.402456 0.898717 +0.151674 -0.220556 0.963509 +0.030553 -0.070598 0.997037 +0.043589 -0.063385 0.997037 +0.030553 -0.070598 0.997037 +0.151674 -0.220556 0.963509 +0.106314 -0.245656 0.963509 +0.293336 -0.677800 0.674196 +0.121868 -0.582121 0.803917 +0.236218 -0.545819 0.803917 +0.121868 -0.582121 0.803917 +0.293336 -0.677800 0.674196 +0.151336 -0.722881 0.674196 +0.236218 -0.545819 0.803917 +0.089859 -0.429224 0.898717 +0.174174 -0.402456 0.898717 +0.089859 -0.429224 0.898717 +0.236218 -0.545819 0.803917 +0.121868 -0.582121 0.803917 +0.174174 -0.402456 0.898717 +0.054849 -0.261995 0.963509 +0.106314 -0.245656 0.963509 +0.054849 -0.261995 0.963509 +0.174174 -0.402456 0.898717 +0.089859 -0.429224 0.898717 +0.106314 -0.245656 0.963509 +0.015763 -0.075294 0.997037 +0.030553 -0.070598 0.997037 +0.015763 -0.075294 0.997037 +0.106314 -0.245656 0.963509 +0.054849 -0.261995 0.963509 +0.000000 -0.076926 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.028316 -0.071525 0.997037 +0.000000 0.000000 1.000000 +-0.013998 -0.075642 0.997037 +-0.028316 -0.071525 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.042095 -0.064387 0.997037 +0.000000 0.000000 1.000000 +-0.028316 -0.071525 0.997037 +-0.042095 -0.064387 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.054395 -0.054395 0.997037 +0.000000 0.000000 1.000000 +-0.042095 -0.064387 0.997037 +-0.054395 -0.054395 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.064387 -0.042095 0.997037 +0.000000 0.000000 1.000000 +-0.054395 -0.054395 0.997037 +-0.064387 -0.042095 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.071525 -0.028316 0.997037 +0.000000 0.000000 1.000000 +-0.064387 -0.042095 0.997037 +-0.071525 -0.028316 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.075642 -0.013998 0.997037 +0.000000 0.000000 1.000000 +-0.071525 -0.028316 0.997037 +-0.075642 -0.013998 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.075642 -0.013998 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.076926 0.000000 0.997037 +0.000000 0.000000 1.000000 +-0.075642 -0.013998 0.997037 +-0.076926 0.000000 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.075642 0.013998 0.997037 +0.000000 0.000000 1.000000 +-0.076926 0.000000 0.997037 +-0.071525 0.028316 0.997037 +0.000000 0.000000 1.000000 +-0.075642 0.013998 0.997037 +-0.071525 0.028316 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.064387 0.042095 0.997037 +0.000000 0.000000 1.000000 +-0.071525 0.028316 0.997037 +-0.064387 0.042095 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.054395 0.054395 0.997037 +0.000000 0.000000 1.000000 +-0.064387 0.042095 0.997037 +-0.054395 0.054395 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.042095 0.064387 0.997037 +0.000000 0.000000 1.000000 +-0.054395 0.054395 0.997037 +-0.042095 0.064387 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.028316 0.071525 0.997037 +0.000000 0.000000 1.000000 +-0.042095 0.064387 0.997037 +-0.028316 0.071525 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.013998 0.075642 0.997037 +0.000000 0.000000 1.000000 +-0.028316 0.071525 0.997037 +-0.013998 0.075642 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.013998 0.075642 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.013998 0.075642 0.997037 +0.000000 0.076926 0.997037 +0.000000 0.000000 1.000000 +-0.048707 0.263206 0.963509 +0.000000 0.076926 0.997037 +-0.013998 0.075642 0.997037 +-0.048707 0.263206 0.963509 +0.000000 0.267675 0.963509 +0.000000 0.076926 0.997037 +-0.079796 0.431208 0.898717 +0.000000 0.267675 0.963509 +-0.048707 0.263206 0.963509 +-0.079796 0.431208 0.898717 +0.000000 0.438529 0.898717 +0.000000 0.267675 0.963509 +-0.108221 0.584812 0.803917 +0.000000 0.438529 0.898717 +-0.079796 0.431208 0.898717 +-0.108221 0.584812 0.803917 +0.000000 0.594741 0.803917 +0.000000 0.438529 0.898717 +-0.134389 0.726222 0.674196 +0.000000 0.594741 0.803917 +-0.108221 0.584812 0.803917 +-0.134389 0.726222 0.674196 +0.000000 0.738552 0.674196 +0.000000 0.594741 0.803917 +-0.134389 0.726222 0.674196 +0.000000 0.788227 0.615385 +0.000000 0.738552 0.674196 +-0.134389 0.726222 0.674196 +-0.143428 0.775068 0.615385 +0.000000 0.788227 0.615385 +-0.271857 0.686697 0.674196 +-0.143428 0.775068 0.615385 +-0.134389 0.726222 0.674196 +-0.271857 0.686697 0.674196 +-0.290142 0.732884 0.615385 +-0.143428 0.775068 0.615385 +-0.404143 0.618165 0.674196 +-0.290142 0.732884 0.615385 +-0.271857 0.686697 0.674196 +-0.404143 0.618165 0.674196 +-0.431325 0.659742 0.615385 +-0.290142 0.732884 0.615385 +-0.404143 0.618165 0.674196 +-0.557361 0.557361 0.615385 +-0.431325 0.659742 0.615385 +-0.522235 0.522235 0.674196 +-0.557361 0.557361 0.615385 +-0.404143 0.618165 0.674196 +-0.618165 0.404143 0.674196 +-0.557361 0.557361 0.615385 +-0.522235 0.522235 0.674196 +-0.618165 0.404143 0.674196 +-0.659742 0.431325 0.615385 +-0.557361 0.557361 0.615385 +-0.686697 0.271857 0.674196 +-0.659742 0.431325 0.615385 +-0.618165 0.404143 0.674196 +-0.686697 0.271857 0.674196 +-0.732884 0.290142 0.615385 +-0.659742 0.431325 0.615385 +-0.726222 0.134389 0.674196 +-0.732884 0.290142 0.615385 +-0.686697 0.271857 0.674196 +-0.726222 0.134389 0.674196 +-0.775068 0.143428 0.615385 +-0.732884 0.290142 0.615385 +-0.738552 0.000000 0.674196 +-0.775068 0.143428 0.615385 +-0.726222 0.134389 0.674196 +-0.738552 0.000000 0.674196 +-0.788227 0.000000 0.615385 +-0.775068 0.143428 0.615385 +-0.726222 -0.134389 0.674196 +-0.788227 0.000000 0.615385 +-0.738552 0.000000 0.674196 +-0.726222 -0.134389 0.674196 +-0.775068 -0.143428 0.615385 +-0.788227 0.000000 0.615385 +-0.686697 -0.271857 0.674196 +-0.775068 -0.143428 0.615385 +-0.726222 -0.134389 0.674196 +-0.686697 -0.271857 0.674196 +-0.732884 -0.290142 0.615385 +-0.775068 -0.143428 0.615385 +-0.618165 -0.404143 0.674196 +-0.732884 -0.290142 0.615385 +-0.686697 -0.271857 0.674196 +-0.618165 -0.404143 0.674196 +-0.659742 -0.431325 0.615385 +-0.732884 -0.290142 0.615385 +-0.618165 -0.404143 0.674196 +-0.557361 -0.557361 0.615385 +-0.659742 -0.431325 0.615385 +-0.522235 -0.522235 0.674196 +-0.557361 -0.557361 0.615385 +-0.618165 -0.404143 0.674196 +-0.404143 -0.618165 0.674196 +-0.557361 -0.557361 0.615385 +-0.522235 -0.522235 0.674196 +-0.404143 -0.618165 0.674196 +-0.431325 -0.659742 0.615385 +-0.557361 -0.557361 0.615385 +-0.271857 -0.686697 0.674196 +-0.431325 -0.659742 0.615385 +-0.404143 -0.618165 0.674196 +-0.271857 -0.686697 0.674196 +-0.290142 -0.732884 0.615385 +-0.431325 -0.659742 0.615385 +-0.134389 -0.726222 0.674196 +-0.290142 -0.732884 0.615385 +-0.271857 -0.686697 0.674196 +-0.134389 -0.726222 0.674196 +-0.143428 -0.775068 0.615385 +-0.290142 -0.732884 0.615385 +-0.134389 -0.726222 0.674196 +0.000000 -0.788227 0.615385 +-0.143428 -0.775068 0.615385 +-0.134389 -0.726222 0.674196 +0.000000 -0.738552 0.674196 +0.000000 -0.788227 0.615385 +-0.108221 -0.584812 0.803917 +0.000000 -0.738552 0.674196 +-0.134389 -0.726222 0.674196 +-0.108221 -0.584812 0.803917 +0.000000 -0.594741 0.803917 +0.000000 -0.738552 0.674196 +-0.079796 -0.431208 0.898717 +0.000000 -0.594741 0.803917 +-0.108221 -0.584812 0.803917 +-0.079796 -0.431208 0.898717 +0.000000 -0.438529 0.898717 +0.000000 -0.594741 0.803917 +-0.048707 -0.263206 0.963509 +0.000000 -0.438529 0.898717 +-0.079796 -0.431208 0.898717 +-0.048707 -0.263206 0.963509 +0.000000 -0.267675 0.963509 +0.000000 -0.438529 0.898717 +-0.013998 -0.075642 0.997037 +0.000000 -0.267675 0.963509 +-0.048707 -0.263206 0.963509 +-0.013998 -0.075642 0.997037 +0.000000 -0.076926 0.997037 +0.000000 -0.267675 0.963509 +0.000000 0.000000 1.000000 +0.000000 -0.076926 0.997037 +-0.013998 -0.075642 0.997037 +-0.134389 -0.726222 0.674196 +-0.218921 -0.552983 0.803917 +-0.108221 -0.584812 0.803917 +-0.218921 -0.552983 0.803917 +-0.134389 -0.726222 0.674196 +-0.271857 -0.686697 0.674196 +-0.108221 -0.584812 0.803917 +-0.161420 -0.407739 0.898717 +-0.079796 -0.431208 0.898717 +-0.161420 -0.407739 0.898717 +-0.108221 -0.584812 0.803917 +-0.218921 -0.552983 0.803917 +-0.079796 -0.431208 0.898717 +-0.098530 -0.248881 0.963509 +-0.048707 -0.263206 0.963509 +-0.098530 -0.248881 0.963509 +-0.079796 -0.431208 0.898717 +-0.161420 -0.407739 0.898717 +-0.048707 -0.263206 0.963509 +-0.028316 -0.071525 0.997037 +-0.013998 -0.075642 0.997037 +-0.028316 -0.071525 0.997037 +-0.048707 -0.263206 0.963509 +-0.098530 -0.248881 0.963509 +-0.271857 -0.686697 0.674196 +-0.325448 -0.497796 0.803917 +-0.218921 -0.552983 0.803917 +-0.325448 -0.497796 0.803917 +-0.271857 -0.686697 0.674196 +-0.404143 -0.618165 0.674196 +-0.218921 -0.552983 0.803917 +-0.239967 -0.367047 0.898717 +-0.161420 -0.407739 0.898717 +-0.239967 -0.367047 0.898717 +-0.218921 -0.552983 0.803917 +-0.325448 -0.497796 0.803917 +-0.161420 -0.407739 0.898717 +-0.146474 -0.224042 0.963509 +-0.098530 -0.248881 0.963509 +-0.146474 -0.224042 0.963509 +-0.161420 -0.407739 0.898717 +-0.239967 -0.367047 0.898717 +-0.098530 -0.248881 0.963509 +-0.042095 -0.064387 0.997037 +-0.028316 -0.071525 0.997037 +-0.042095 -0.064387 0.997037 +-0.098530 -0.248881 0.963509 +-0.146474 -0.224042 0.963509 +-0.404143 -0.618165 0.674196 +-0.420546 -0.420546 0.803917 +-0.325448 -0.497796 0.803917 +-0.420546 -0.420546 0.803917 +-0.404143 -0.618165 0.674196 +-0.522235 -0.522235 0.674196 +-0.325448 -0.497796 0.803917 +-0.310087 -0.310087 0.898717 +-0.239967 -0.367047 0.898717 +-0.310087 -0.310087 0.898717 +-0.325448 -0.497796 0.803917 +-0.420546 -0.420546 0.803917 +-0.239967 -0.367047 0.898717 +-0.189275 -0.189275 0.963509 +-0.146474 -0.224042 0.963509 +-0.189275 -0.189275 0.963509 +-0.239967 -0.367047 0.898717 +-0.310087 -0.310087 0.898717 +-0.146474 -0.224042 0.963509 +-0.054395 -0.054395 0.997037 +-0.042095 -0.064387 0.997037 +-0.054395 -0.054395 0.997037 +-0.146474 -0.224042 0.963509 +-0.189275 -0.189275 0.963509 +-0.522235 -0.522235 0.674196 +-0.497796 -0.325448 0.803917 +-0.420546 -0.420546 0.803917 +-0.497796 -0.325448 0.803917 +-0.522235 -0.522235 0.674196 +-0.618165 -0.404143 0.674196 +-0.420546 -0.420546 0.803917 +-0.367047 -0.239967 0.898717 +-0.310087 -0.310087 0.898717 +-0.367047 -0.239967 0.898717 +-0.420546 -0.420546 0.803917 +-0.497796 -0.325448 0.803917 +-0.310087 -0.310087 0.898717 +-0.224042 -0.146474 0.963509 +-0.189275 -0.189275 0.963509 +-0.224042 -0.146474 0.963509 +-0.310087 -0.310087 0.898717 +-0.367047 -0.239967 0.898717 +-0.189275 -0.189275 0.963509 +-0.064387 -0.042095 0.997037 +-0.054395 -0.054395 0.997037 +-0.064387 -0.042095 0.997037 +-0.189275 -0.189275 0.963509 +-0.224042 -0.146474 0.963509 +-0.618165 -0.404143 0.674196 +-0.552983 -0.218921 0.803917 +-0.497796 -0.325448 0.803917 +-0.552983 -0.218921 0.803917 +-0.618165 -0.404143 0.674196 +-0.686697 -0.271857 0.674196 +-0.497796 -0.325448 0.803917 +-0.407739 -0.161420 0.898717 +-0.367047 -0.239967 0.898717 +-0.407739 -0.161420 0.898717 +-0.497796 -0.325448 0.803917 +-0.552983 -0.218921 0.803917 +-0.367047 -0.239967 0.898717 +-0.248881 -0.098530 0.963509 +-0.224042 -0.146474 0.963509 +-0.248881 -0.098530 0.963509 +-0.367047 -0.239967 0.898717 +-0.407739 -0.161420 0.898717 +-0.224042 -0.146474 0.963509 +-0.071525 -0.028316 0.997037 +-0.064387 -0.042095 0.997037 +-0.071525 -0.028316 0.997037 +-0.224042 -0.146474 0.963509 +-0.248881 -0.098530 0.963509 +-0.686697 -0.271857 0.674196 +-0.584812 -0.108221 0.803917 +-0.552983 -0.218921 0.803917 +-0.584812 -0.108221 0.803917 +-0.686697 -0.271857 0.674196 +-0.726222 -0.134389 0.674196 +-0.552983 -0.218921 0.803917 +-0.431208 -0.079796 0.898717 +-0.407739 -0.161420 0.898717 +-0.431208 -0.079796 0.898717 +-0.552983 -0.218921 0.803917 +-0.584812 -0.108221 0.803917 +-0.407739 -0.161420 0.898717 +-0.263206 -0.048707 0.963509 +-0.248881 -0.098530 0.963509 +-0.263206 -0.048707 0.963509 +-0.407739 -0.161420 0.898717 +-0.431208 -0.079796 0.898717 +-0.248881 -0.098530 0.963509 +-0.075642 -0.013998 0.997037 +-0.071525 -0.028316 0.997037 +-0.075642 -0.013998 0.997037 +-0.248881 -0.098530 0.963509 +-0.263206 -0.048707 0.963509 +-0.726222 -0.134389 0.674196 +-0.594741 0.000000 0.803917 +-0.584812 -0.108221 0.803917 +-0.594741 0.000000 0.803917 +-0.726222 -0.134389 0.674196 +-0.738552 0.000000 0.674196 +-0.584812 -0.108221 0.803917 +-0.438529 0.000000 0.898717 +-0.431208 -0.079796 0.898717 +-0.438529 0.000000 0.898717 +-0.584812 -0.108221 0.803917 +-0.594741 0.000000 0.803917 +-0.431208 -0.079796 0.898717 +-0.267675 0.000000 0.963509 +-0.263206 -0.048707 0.963509 +-0.267675 0.000000 0.963509 +-0.431208 -0.079796 0.898717 +-0.438529 0.000000 0.898717 +-0.263206 -0.048707 0.963509 +-0.076926 0.000000 0.997037 +-0.075642 -0.013998 0.997037 +-0.076926 0.000000 0.997037 +-0.263206 -0.048707 0.963509 +-0.267675 0.000000 0.963509 +-0.738552 0.000000 0.674196 +-0.584812 0.108221 0.803917 +-0.594741 0.000000 0.803917 +-0.584812 0.108221 0.803917 +-0.738552 0.000000 0.674196 +-0.726222 0.134389 0.674196 +-0.594741 0.000000 0.803917 +-0.431208 0.079796 0.898717 +-0.438529 0.000000 0.898717 +-0.431208 0.079796 0.898717 +-0.594741 0.000000 0.803917 +-0.584812 0.108221 0.803917 +-0.438529 0.000000 0.898717 +-0.263206 0.048707 0.963509 +-0.267675 0.000000 0.963509 +-0.263206 0.048707 0.963509 +-0.438529 0.000000 0.898717 +-0.431208 0.079796 0.898717 +-0.267675 0.000000 0.963509 +-0.075642 0.013998 0.997037 +-0.076926 0.000000 0.997037 +-0.075642 0.013998 0.997037 +-0.267675 0.000000 0.963509 +-0.263206 0.048707 0.963509 +-0.726222 0.134389 0.674196 +-0.552983 0.218921 0.803917 +-0.584812 0.108221 0.803917 +-0.552983 0.218921 0.803917 +-0.726222 0.134389 0.674196 +-0.686697 0.271857 0.674196 +-0.584812 0.108221 0.803917 +-0.407739 0.161420 0.898717 +-0.431208 0.079796 0.898717 +-0.407739 0.161420 0.898717 +-0.584812 0.108221 0.803917 +-0.552983 0.218921 0.803917 +-0.431208 0.079796 0.898717 +-0.248881 0.098530 0.963509 +-0.263206 0.048707 0.963509 +-0.248881 0.098530 0.963509 +-0.431208 0.079796 0.898717 +-0.407739 0.161420 0.898717 +-0.263206 0.048707 0.963509 +-0.071525 0.028316 0.997037 +-0.075642 0.013998 0.997037 +-0.071525 0.028316 0.997037 +-0.263206 0.048707 0.963509 +-0.248881 0.098530 0.963509 +-0.686697 0.271857 0.674196 +-0.497796 0.325448 0.803917 +-0.552983 0.218921 0.803917 +-0.497796 0.325448 0.803917 +-0.686697 0.271857 0.674196 +-0.618165 0.404143 0.674196 +-0.552983 0.218921 0.803917 +-0.367047 0.239967 0.898717 +-0.407739 0.161420 0.898717 +-0.367047 0.239967 0.898717 +-0.552983 0.218921 0.803917 +-0.497796 0.325448 0.803917 +-0.407739 0.161420 0.898717 +-0.224042 0.146474 0.963509 +-0.248881 0.098530 0.963509 +-0.224042 0.146474 0.963509 +-0.407739 0.161420 0.898717 +-0.367047 0.239967 0.898717 +-0.248881 0.098530 0.963509 +-0.064387 0.042095 0.997037 +-0.071525 0.028316 0.997037 +-0.064387 0.042095 0.997037 +-0.248881 0.098530 0.963509 +-0.224042 0.146474 0.963509 +-0.618165 0.404143 0.674196 +-0.420546 0.420546 0.803917 +-0.497796 0.325448 0.803917 +-0.420546 0.420546 0.803917 +-0.618165 0.404143 0.674196 +-0.522235 0.522235 0.674196 +-0.497796 0.325448 0.803917 +-0.310087 0.310087 0.898717 +-0.367047 0.239967 0.898717 +-0.310087 0.310087 0.898717 +-0.497796 0.325448 0.803917 +-0.420546 0.420546 0.803917 +-0.367047 0.239967 0.898717 +-0.189275 0.189275 0.963509 +-0.224042 0.146474 0.963509 +-0.189275 0.189275 0.963509 +-0.367047 0.239967 0.898717 +-0.310087 0.310087 0.898717 +-0.224042 0.146474 0.963509 +-0.054395 0.054395 0.997037 +-0.064387 0.042095 0.997037 +-0.054395 0.054395 0.997037 +-0.224042 0.146474 0.963509 +-0.189275 0.189275 0.963509 +-0.522235 0.522235 0.674196 +-0.325448 0.497796 0.803917 +-0.420546 0.420546 0.803917 +-0.325448 0.497796 0.803917 +-0.522235 0.522235 0.674196 +-0.404143 0.618165 0.674196 +-0.420546 0.420546 0.803917 +-0.239967 0.367047 0.898717 +-0.310087 0.310087 0.898717 +-0.239967 0.367047 0.898717 +-0.420546 0.420546 0.803917 +-0.325448 0.497796 0.803917 +-0.310087 0.310087 0.898717 +-0.146474 0.224042 0.963509 +-0.189275 0.189275 0.963509 +-0.146474 0.224042 0.963509 +-0.310087 0.310087 0.898717 +-0.239967 0.367047 0.898717 +-0.189275 0.189275 0.963509 +-0.042095 0.064387 0.997037 +-0.054395 0.054395 0.997037 +-0.042095 0.064387 0.997037 +-0.189275 0.189275 0.963509 +-0.146474 0.224042 0.963509 +-0.404143 0.618165 0.674196 +-0.218921 0.552983 0.803917 +-0.325448 0.497796 0.803917 +-0.218921 0.552983 0.803917 +-0.404143 0.618165 0.674196 +-0.271857 0.686697 0.674196 +-0.325448 0.497796 0.803917 +-0.161420 0.407739 0.898717 +-0.239967 0.367047 0.898717 +-0.161420 0.407739 0.898717 +-0.325448 0.497796 0.803917 +-0.218921 0.552983 0.803917 +-0.239967 0.367047 0.898717 +-0.098530 0.248881 0.963509 +-0.146474 0.224042 0.963509 +-0.098530 0.248881 0.963509 +-0.239967 0.367047 0.898717 +-0.161420 0.407739 0.898717 +-0.146474 0.224042 0.963509 +-0.028316 0.071525 0.997037 +-0.042095 0.064387 0.997037 +-0.028316 0.071525 0.997037 +-0.146474 0.224042 0.963509 +-0.098530 0.248881 0.963509 +-0.271857 0.686697 0.674196 +-0.108221 0.584812 0.803917 +-0.218921 0.552983 0.803917 +-0.108221 0.584812 0.803917 +-0.271857 0.686697 0.674196 +-0.134389 0.726222 0.674196 +-0.218921 0.552983 0.803917 +-0.079796 0.431208 0.898717 +-0.161420 0.407739 0.898717 +-0.079796 0.431208 0.898717 +-0.218921 0.552983 0.803917 +-0.108221 0.584812 0.803917 +-0.161420 0.407739 0.898717 +-0.048707 0.263206 0.963509 +-0.098530 0.248881 0.963509 +-0.048707 0.263206 0.963509 +-0.161420 0.407739 0.898717 +-0.079796 0.431208 0.898717 +-0.098530 0.248881 0.963509 +-0.013998 0.075642 0.997037 +-0.028316 0.071525 0.997037 +-0.013998 0.075642 0.997037 +-0.098530 0.248881 0.963509 +-0.048707 0.263206 0.963509 +0.000000 0.076926 0.997037 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.738552 0.674196 +0.000000 0.788227 0.615385 +0.000000 0.788227 0.615385 +0.000000 0.738552 0.674196 +0.000000 0.738552 0.674196 +0.000000 0.788227 0.615385 +0.000000 0.594741 0.803917 +0.000000 0.738552 0.674196 +0.000000 0.738552 0.674196 +0.000000 0.594741 0.803917 +0.000000 0.594741 0.803917 +0.000000 0.738552 0.674196 +0.000000 0.438529 0.898717 +0.000000 0.594741 0.803917 +0.000000 0.594741 0.803917 +0.000000 0.438529 0.898717 +0.000000 0.438529 0.898717 +0.000000 0.594741 0.803917 +0.000000 0.267675 0.963509 +0.000000 0.438529 0.898717 +0.000000 0.438529 0.898717 +0.000000 0.267675 0.963509 +0.000000 0.267675 0.963509 +0.000000 0.438529 0.898717 +0.000000 0.076926 0.997037 +0.000000 0.267675 0.963509 +0.000000 0.267675 0.963509 +0.000000 0.076926 0.997037 +0.000000 0.076926 0.997037 +0.000000 0.267675 0.963509 +0.000000 0.000000 1.000000 +0.000000 0.076926 0.997037 +0.000000 0.076926 0.997037 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.999476 0.032374 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.204909 0.978781 0.000000 +0.000000 1.000000 0.000000 +0.204909 0.978781 0.000000 +0.204909 0.978781 0.000000 +0.000000 1.000000 0.000000 +0.397177 0.917742 0.000000 +0.204909 0.978781 0.000000 +0.204909 0.978781 0.000000 +0.397177 0.917742 0.000000 +0.397177 0.917742 0.000000 +0.204909 0.978781 0.000000 +0.566635 0.823969 0.000000 +0.397177 0.917742 0.000000 +0.397177 0.917742 0.000000 +0.566635 0.823969 0.000000 +0.566635 0.823969 0.000000 +0.397177 0.917742 0.000000 +0.707107 0.707107 0.000000 +0.566635 0.823969 0.000000 +0.566635 0.823969 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.566635 0.823969 0.000000 +0.823969 0.566635 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.823969 0.566635 0.000000 +0.823969 0.566635 0.000000 +0.707107 0.707107 0.000000 +0.917742 0.397177 0.000000 +0.823969 0.566635 0.000000 +0.823969 0.566635 0.000000 +0.917742 0.397177 0.000000 +0.917742 0.397177 0.000000 +0.823969 0.566635 0.000000 +0.978781 0.204909 0.000000 +0.917742 0.397177 0.000000 +0.917742 0.397177 0.000000 +0.978781 0.204909 0.000000 +0.978781 0.204909 0.000000 +0.917742 0.397177 0.000000 +1.000000 0.000000 0.000000 +0.978781 0.204909 0.000000 +0.978781 0.204909 0.000000 +0.978781 0.204909 0.000000 +0.999476 0.032374 0.000000 +0.999476 0.032374 0.000000 +1.000000 0.000000 0.000000 +0.999476 0.032374 0.000000 +0.978781 0.204909 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.999476 0.032374 0.000000 +-0.983305 0.181963 0.000000 +-0.999476 0.032374 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.999476 -0.032374 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.999476 -0.032374 0.000000 +-0.999476 -0.032374 0.000000 +-0.983305 -0.181963 0.000000 +-0.999476 -0.032374 0.000000 +-0.999476 -0.032374 0.000000 +-1.000000 0.000000 0.000000 +-0.999476 -0.032374 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.999476 -0.032374 0.000000 +-0.983305 0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.181963 0.000000 +-0.999476 0.032374 0.000000 +-1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +0.000000 1.000000 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.181963 0.983305 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.181963 0.983305 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.368095 0.929788 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.368095 0.929788 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.547210 0.836995 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.707107 0.707107 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.836995 0.547210 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.836995 0.547210 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.929788 0.368095 0.000000 +-0.983305 0.181963 0.000000 +-0.999476 0.032374 0.000000 +-0.983305 0.181963 0.000000 +-0.983305 0.181963 0.000000 +-0.999476 0.032374 0.000000 +-0.999476 0.032374 0.000000 +-0.774450 -0.632613 -0.005236 +-0.814136 -0.580650 -0.005236 +-0.783400 -0.621495 -0.005236 +-0.999387 -0.034615 -0.005236 +-0.975116 -0.221634 -0.005236 +-0.999400 -0.034232 -0.005236 +-0.975116 -0.221634 -0.005236 +-0.975116 -0.221634 -0.005236 +-0.999387 -0.034615 -0.005236 +-0.910795 -0.412826 -0.005236 +-0.975116 -0.221634 -0.005236 +-0.975116 -0.221634 -0.005236 +-0.910795 -0.412826 -0.005236 +-0.910795 -0.412826 -0.005236 +-0.975116 -0.221634 -0.005236 +-0.188120 -0.982132 -0.005236 +0.000000 -0.999986 -0.005236 +0.000000 -0.999986 -0.005236 +-0.188120 -0.982132 -0.005236 +-0.188120 -0.982132 -0.005236 +0.000000 -0.999986 -0.005236 +-0.188120 -0.982132 -0.005236 +-0.381402 -0.924395 -0.005236 +-0.188120 -0.982132 -0.005236 +-0.381402 -0.924395 -0.005236 +-0.381402 -0.924395 -0.005236 +-0.188120 -0.982132 -0.005236 +-0.552437 -0.833538 -0.005236 +-0.381402 -0.924395 -0.005236 +-0.381402 -0.924395 -0.005236 +-0.552437 -0.833538 -0.005236 +-0.552437 -0.833538 -0.005236 +-0.381402 -0.924395 -0.005236 +-0.552437 -0.833538 -0.005236 +-0.694888 -0.719099 -0.005236 +-0.552437 -0.833538 -0.005236 +-0.694888 -0.719099 -0.005236 +-0.694888 -0.719099 -0.005236 +-0.552437 -0.833538 -0.005236 +-0.694888 -0.719099 -0.005236 +-0.735683 -0.677306 -0.005236 +-0.694888 -0.719099 -0.005236 +-0.694888 -0.719099 -0.005236 +-0.740515 -0.672020 -0.005236 +-0.735683 -0.677306 -0.005236 +-0.814136 -0.580650 -0.005236 +-0.740515 -0.672020 -0.005236 +-0.694888 -0.719099 -0.005236 +-0.814136 -0.580650 -0.005236 +-0.774450 -0.632613 -0.005236 +-0.740515 -0.672020 -0.005236 +-0.814136 -0.580650 -0.005236 +-0.910795 -0.412826 -0.005236 +-0.910795 -0.412826 -0.005236 +-0.814136 -0.580650 -0.005236 +-0.814136 -0.580650 -0.005236 +-0.910795 -0.412826 -0.005236 +-0.814136 -0.580650 -0.005236 +-0.774450 -0.632613 -0.005236 +-0.814136 -0.580650 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.696201 -0.717828 -0.005236 +0.696201 -0.717828 -0.005236 +0.740515 -0.672020 -0.005236 +0.975519 -0.219851 -0.005236 +0.999387 -0.034615 -0.005236 +0.999520 -0.030542 -0.005236 +0.975519 -0.219851 -0.005236 +0.975519 -0.219851 -0.005236 +0.999387 -0.034615 -0.005236 +0.911548 -0.411160 -0.005236 +0.975519 -0.219851 -0.005236 +0.975519 -0.219851 -0.005236 +0.911548 -0.411160 -0.005236 +0.911548 -0.411160 -0.005236 +0.975519 -0.219851 -0.005236 +0.815196 -0.579161 -0.005236 +0.911548 -0.411160 -0.005236 +0.911548 -0.411160 -0.005236 +0.815196 -0.579161 -0.005236 +0.815196 -0.579161 -0.005236 +0.911548 -0.411160 -0.005236 +0.815196 -0.579161 -0.005236 +0.783400 -0.621495 -0.005236 +0.815196 -0.579161 -0.005236 +0.815196 -0.579161 -0.005236 +0.774450 -0.632613 -0.005236 +0.783400 -0.621495 -0.005236 +0.696201 -0.717828 -0.005236 +0.774450 -0.632613 -0.005236 +0.815196 -0.579161 -0.005236 +0.696201 -0.717828 -0.005236 +0.740515 -0.672020 -0.005236 +0.774450 -0.632613 -0.005236 +0.740515 -0.672020 -0.005236 +0.696201 -0.717828 -0.005236 +0.735683 -0.677306 -0.005236 +0.189914 -0.981787 -0.005236 +0.000000 -0.999986 -0.005236 +0.000000 -0.999986 -0.005236 +0.189914 -0.981787 -0.005236 +0.189914 -0.981787 -0.005236 +0.000000 -0.999986 -0.005236 +0.383091 -0.923696 -0.005236 +0.189914 -0.981787 -0.005236 +0.189914 -0.981787 -0.005236 +0.383091 -0.923696 -0.005236 +0.383091 -0.923696 -0.005236 +0.189914 -0.981787 -0.005236 +0.383091 -0.923696 -0.005236 +0.553960 -0.832527 -0.005236 +0.383091 -0.923696 -0.005236 +0.553960 -0.832527 -0.005236 +0.553960 -0.832527 -0.005236 +0.383091 -0.923696 -0.005236 +0.696201 -0.717828 -0.005236 +0.553960 -0.832527 -0.005236 +0.553960 -0.832527 -0.005236 +0.696201 -0.717828 -0.005236 +0.696201 -0.717828 -0.005236 +0.553960 -0.832527 -0.005236 +0.000000 -0.999986 -0.005236 +0.000000 -0.999986 -0.005236 +0.000000 -0.999986 -0.005236 +0.000000 -0.999986 -0.005236 +0.000000 -0.999986 -0.005236 +0.000000 -0.999986 -0.005236 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.570327 0.821401 -0.005236 +-0.707097 0.707097 -0.005236 +-0.594246 0.804267 -0.005236 +-0.999986 0.000000 -0.005236 +-0.983292 0.181961 -0.005236 +-0.999986 0.000000 -0.005236 +-0.983292 0.181961 -0.005236 +-0.983292 0.181961 -0.005236 +-0.999986 0.000000 -0.005236 +-0.929776 0.368090 -0.005236 +-0.983292 0.181961 -0.005236 +-0.983292 0.181961 -0.005236 +-0.929776 0.368090 -0.005236 +-0.929776 0.368090 -0.005236 +-0.983292 0.181961 -0.005236 +0.983292 0.181961 -0.005236 +0.999986 0.000000 -0.005236 +0.999986 0.000000 -0.005236 +0.983292 0.181961 -0.005236 +0.983292 0.181961 -0.005236 +0.999986 0.000000 -0.005236 +0.983292 0.181961 -0.005236 +0.929776 0.368090 -0.005236 +0.983292 0.181961 -0.005236 +0.929776 0.368090 -0.005236 +0.929776 0.368090 -0.005236 +0.983292 0.181961 -0.005236 +0.929776 0.368090 -0.005236 +0.836984 0.547202 -0.005236 +0.929776 0.368090 -0.005236 +0.836984 0.547202 -0.005236 +0.836984 0.547202 -0.005236 +0.929776 0.368090 -0.005236 +0.707097 0.707097 -0.005236 +0.836984 0.547202 -0.005236 +0.836984 0.547202 -0.005236 +0.707097 0.707097 -0.005236 +0.707097 0.707097 -0.005236 +0.836984 0.547202 -0.005236 +0.547202 0.836984 -0.005236 +0.707097 0.707097 -0.005236 +0.707097 0.707097 -0.005236 +0.547202 0.836984 -0.005236 +0.547202 0.836984 -0.005236 +0.707097 0.707097 -0.005236 +0.547202 0.836984 -0.005236 +0.368090 0.929776 -0.005236 +0.547202 0.836984 -0.005236 +0.368090 0.929776 -0.005236 +0.368090 0.929776 -0.005236 +0.547202 0.836984 -0.005236 +0.181961 0.983292 -0.005236 +0.368090 0.929776 -0.005236 +0.368090 0.929776 -0.005236 +0.181961 0.983292 -0.005236 +0.181961 0.983292 -0.005236 +0.368090 0.929776 -0.005236 +0.000000 0.999986 -0.005236 +0.181961 0.983292 -0.005236 +0.181961 0.983292 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.181961 0.983292 -0.005236 +-0.181961 0.983292 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +-0.181961 0.983292 -0.005236 +-0.181961 0.983292 -0.005236 +0.000000 0.999986 -0.005236 +-0.368090 0.929776 -0.005236 +-0.181961 0.983292 -0.005236 +-0.181961 0.983292 -0.005236 +-0.368090 0.929776 -0.005236 +-0.368090 0.929776 -0.005236 +-0.181961 0.983292 -0.005236 +-0.368090 0.929776 -0.005236 +-0.399393 0.916765 -0.005236 +-0.368090 0.929776 -0.005236 +-0.368090 0.929776 -0.005236 +-0.426191 0.904618 -0.005236 +-0.399393 0.916765 -0.005236 +-0.547202 0.836984 -0.005236 +-0.426191 0.904618 -0.005236 +-0.368090 0.929776 -0.005236 +-0.547202 0.836984 -0.005236 +-0.547202 0.836984 -0.005236 +-0.426191 0.904618 -0.005236 +-0.707097 0.707097 -0.005236 +-0.547202 0.836984 -0.005236 +-0.547202 0.836984 -0.005236 +-0.707097 0.707097 -0.005236 +-0.570327 0.821401 -0.005236 +-0.547202 0.836984 -0.005236 +-0.836984 0.547202 -0.005236 +-0.929776 0.368090 -0.005236 +-0.929776 0.368090 -0.005236 +-0.836984 0.547202 -0.005236 +-0.836984 0.547202 -0.005236 +-0.929776 0.368090 -0.005236 +-0.707097 0.707097 -0.005236 +-0.836984 0.547202 -0.005236 +-0.836984 0.547202 -0.005236 +-0.707097 0.707097 -0.005236 +-0.707097 0.707097 -0.005236 +-0.836984 0.547202 -0.005236 +-0.707097 0.707097 -0.005236 +-0.570327 0.821401 -0.005236 +-0.707097 0.707097 -0.005236 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.181956 -0.983268 0.008727 +0.368081 -0.929753 0.008727 +0.181956 -0.983268 0.008727 +-0.999962 0.000000 0.008727 +-0.983268 -0.181956 0.008727 +-0.999962 0.000000 0.008727 +-0.983268 -0.181956 0.008727 +-0.983268 -0.181956 0.008727 +-0.999962 0.000000 0.008727 +-0.983268 -0.181956 0.008727 +-0.929753 -0.368081 0.008727 +-0.983268 -0.181956 0.008727 +-0.929753 -0.368081 0.008727 +-0.929753 -0.368081 0.008727 +-0.983268 -0.181956 0.008727 +-0.836964 -0.547189 0.008727 +-0.929753 -0.368081 0.008727 +-0.929753 -0.368081 0.008727 +-0.836964 -0.547189 0.008727 +-0.836964 -0.547189 0.008727 +-0.929753 -0.368081 0.008727 +-0.836964 -0.547189 0.008727 +-0.707080 -0.707080 0.008727 +-0.836964 -0.547189 0.008727 +-0.707080 -0.707080 0.008727 +-0.707080 -0.707080 0.008727 +-0.836964 -0.547189 0.008727 +-0.707080 -0.707080 0.008727 +-0.547189 -0.836964 0.008727 +-0.707080 -0.707080 0.008727 +-0.547189 -0.836964 0.008727 +-0.547189 -0.836964 0.008727 +-0.707080 -0.707080 0.008727 +-0.547189 -0.836964 0.008727 +-0.368081 -0.929753 0.008727 +-0.547189 -0.836964 0.008727 +-0.368081 -0.929753 0.008727 +-0.368081 -0.929753 0.008727 +-0.547189 -0.836964 0.008727 +-0.368081 -0.929753 0.008727 +-0.181956 -0.983268 0.008727 +-0.368081 -0.929753 0.008727 +-0.181956 -0.983268 0.008727 +-0.181956 -0.983268 0.008727 +-0.368081 -0.929753 0.008727 +-0.181956 -0.983268 0.008727 +0.000000 -0.999962 0.008727 +-0.181956 -0.983268 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +-0.181956 -0.983268 0.008727 +0.000000 -0.999962 0.008727 +0.181956 -0.983268 0.008727 +0.000000 -0.999962 0.008727 +0.181956 -0.983268 0.008727 +0.181956 -0.983268 0.008727 +0.000000 -0.999962 0.008727 +0.999962 0.000000 0.008727 +0.983268 -0.181956 0.008727 +0.999962 0.000000 0.008727 +0.983268 -0.181956 0.008727 +0.983268 -0.181956 0.008727 +0.999962 0.000000 0.008727 +0.929753 -0.368081 0.008727 +0.983268 -0.181956 0.008727 +0.983268 -0.181956 0.008727 +0.929753 -0.368081 0.008727 +0.929753 -0.368081 0.008727 +0.983268 -0.181956 0.008727 +0.836964 -0.547189 0.008727 +0.929753 -0.368081 0.008727 +0.929753 -0.368081 0.008727 +0.836964 -0.547189 0.008727 +0.836964 -0.547189 0.008727 +0.929753 -0.368081 0.008727 +0.707080 -0.707080 0.008727 +0.836964 -0.547189 0.008727 +0.836964 -0.547189 0.008727 +0.707080 -0.707080 0.008727 +0.707080 -0.707080 0.008727 +0.836964 -0.547189 0.008727 +0.547189 -0.836964 0.008727 +0.707080 -0.707080 0.008727 +0.707080 -0.707080 0.008727 +0.547189 -0.836964 0.008727 +0.547189 -0.836964 0.008727 +0.707080 -0.707080 0.008727 +0.547189 -0.836964 0.008727 +0.368081 -0.929753 0.008727 +0.547189 -0.836964 0.008727 +0.368081 -0.929753 0.008727 +0.368081 -0.929753 0.008727 +0.547189 -0.836964 0.008727 +0.368081 -0.929753 0.008727 +0.181956 -0.983268 0.008727 +0.368081 -0.929753 0.008727 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.866014 0.499993 -0.005236 +-0.866014 0.499993 -0.005236 +-0.866014 0.499993 -0.005236 +-0.866014 0.499993 -0.005236 +-0.866014 0.499993 -0.005236 +-0.866014 0.499993 -0.005236 +0.866014 -0.499993 -0.005236 +0.866014 -0.499993 -0.005236 +0.866014 -0.499993 -0.005236 +0.866014 -0.499993 -0.005236 +0.866014 -0.499993 -0.005236 +0.866014 -0.499993 -0.005236 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.866014 0.499993 -0.005236 +0.866014 0.499993 -0.005236 +0.866014 0.499993 -0.005236 +0.866014 0.499993 -0.005236 +0.866014 0.499993 -0.005236 +0.866014 0.499993 -0.005236 +-0.866014 -0.499993 -0.005236 +-0.866014 -0.499993 -0.005236 +-0.866014 -0.499993 -0.005236 +-0.866014 -0.499993 -0.005236 +-0.866014 -0.499993 -0.005236 +-0.866014 -0.499993 -0.005236 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.426191 0.904618 -0.005236 +0.368090 0.929776 -0.005236 +0.399393 0.916765 -0.005236 +-0.999986 0.000000 -0.005236 +-0.983292 0.181961 -0.005236 +-0.999986 0.000000 -0.005236 +-0.983292 0.181961 -0.005236 +-0.983292 0.181961 -0.005236 +-0.999986 0.000000 -0.005236 +-0.929776 0.368090 -0.005236 +-0.983292 0.181961 -0.005236 +-0.983292 0.181961 -0.005236 +-0.929776 0.368090 -0.005236 +-0.929776 0.368090 -0.005236 +-0.983292 0.181961 -0.005236 +-0.929776 0.368090 -0.005236 +-0.836984 0.547202 -0.005236 +-0.929776 0.368090 -0.005236 +-0.836984 0.547202 -0.005236 +-0.836984 0.547202 -0.005236 +-0.929776 0.368090 -0.005236 +-0.707097 0.707097 -0.005236 +-0.836984 0.547202 -0.005236 +-0.836984 0.547202 -0.005236 +-0.707097 0.707097 -0.005236 +-0.707097 0.707097 -0.005236 +-0.836984 0.547202 -0.005236 +-0.707097 0.707097 -0.005236 +-0.547202 0.836984 -0.005236 +-0.707097 0.707097 -0.005236 +-0.547202 0.836984 -0.005236 +-0.547202 0.836984 -0.005236 +-0.707097 0.707097 -0.005236 +-0.547202 0.836984 -0.005236 +-0.368090 0.929776 -0.005236 +-0.547202 0.836984 -0.005236 +-0.368090 0.929776 -0.005236 +-0.368090 0.929776 -0.005236 +-0.547202 0.836984 -0.005236 +-0.368090 0.929776 -0.005236 +-0.181961 0.983292 -0.005236 +-0.368090 0.929776 -0.005236 +-0.181961 0.983292 -0.005236 +-0.181961 0.983292 -0.005236 +-0.368090 0.929776 -0.005236 +-0.181961 0.983292 -0.005236 +0.000000 0.999986 -0.005236 +-0.181961 0.983292 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +-0.181961 0.983292 -0.005236 +0.983292 0.181961 -0.005236 +0.999986 0.000000 -0.005236 +0.999986 0.000000 -0.005236 +0.983292 0.181961 -0.005236 +0.983292 0.181961 -0.005236 +0.999986 0.000000 -0.005236 +0.929776 0.368090 -0.005236 +0.983292 0.181961 -0.005236 +0.983292 0.181961 -0.005236 +0.929776 0.368090 -0.005236 +0.929776 0.368090 -0.005236 +0.983292 0.181961 -0.005236 +0.836984 0.547202 -0.005236 +0.929776 0.368090 -0.005236 +0.929776 0.368090 -0.005236 +0.836984 0.547202 -0.005236 +0.836984 0.547202 -0.005236 +0.929776 0.368090 -0.005236 +0.707097 0.707097 -0.005236 +0.836984 0.547202 -0.005236 +0.836984 0.547202 -0.005236 +0.707097 0.707097 -0.005236 +0.707097 0.707097 -0.005236 +0.836984 0.547202 -0.005236 +0.707097 0.707097 -0.005236 +0.594246 0.804267 -0.005236 +0.707097 0.707097 -0.005236 +0.707097 0.707097 -0.005236 +0.570327 0.821401 -0.005236 +0.594246 0.804267 -0.005236 +0.547202 0.836984 -0.005236 +0.570327 0.821401 -0.005236 +0.707097 0.707097 -0.005236 +0.547202 0.836984 -0.005236 +0.547202 0.836984 -0.005236 +0.570327 0.821401 -0.005236 +0.368090 0.929776 -0.005236 +0.547202 0.836984 -0.005236 +0.547202 0.836984 -0.005236 +0.368090 0.929776 -0.005236 +0.426191 0.904618 -0.005236 +0.547202 0.836984 -0.005236 +0.181961 0.983292 -0.005236 +0.000000 0.999986 -0.005236 +0.000000 0.999986 -0.005236 +0.181961 0.983292 -0.005236 +0.181961 0.983292 -0.005236 +0.000000 0.999986 -0.005236 +0.368090 0.929776 -0.005236 +0.181961 0.983292 -0.005236 +0.181961 0.983292 -0.005236 +0.368090 0.929776 -0.005236 +0.368090 0.929776 -0.005236 +0.181961 0.983292 -0.005236 +0.368090 0.929776 -0.005236 +0.426191 0.904618 -0.005236 +0.368090 0.929776 -0.005236 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.836964 -0.547189 0.008727 +0.929753 -0.368081 0.008727 +0.929753 -0.368081 0.008727 +0.999962 0.000000 0.008727 +0.983268 -0.181956 0.008727 +0.999962 0.000000 0.008727 +0.983268 -0.181956 0.008727 +0.983268 -0.181956 0.008727 +0.999962 0.000000 0.008727 +0.983268 -0.181956 0.008727 +0.929753 -0.368081 0.008727 +0.983268 -0.181956 0.008727 +0.929753 -0.368081 0.008727 +0.929753 -0.368081 0.008727 +0.983268 -0.181956 0.008727 +-0.983268 -0.181956 0.008727 +-0.999962 0.000000 0.008727 +-0.999962 0.000000 0.008727 +-0.983268 -0.181956 0.008727 +-0.983268 -0.181956 0.008727 +-0.999962 0.000000 0.008727 +-0.983268 -0.181956 0.008727 +-0.929753 -0.368081 0.008727 +-0.983268 -0.181956 0.008727 +-0.929753 -0.368081 0.008727 +-0.929753 -0.368081 0.008727 +-0.983268 -0.181956 0.008727 +-0.836964 -0.547189 0.008727 +-0.929753 -0.368081 0.008727 +-0.929753 -0.368081 0.008727 +-0.836964 -0.547189 0.008727 +-0.836964 -0.547189 0.008727 +-0.929753 -0.368081 0.008727 +-0.836964 -0.547189 0.008727 +-0.707080 -0.707080 0.008727 +-0.836964 -0.547189 0.008727 +-0.707080 -0.707080 0.008727 +-0.707080 -0.707080 0.008727 +-0.836964 -0.547189 0.008727 +-0.707080 -0.707080 0.008727 +-0.547189 -0.836964 0.008727 +-0.707080 -0.707080 0.008727 +-0.547189 -0.836964 0.008727 +-0.547189 -0.836964 0.008727 +-0.707080 -0.707080 0.008727 +-0.368081 -0.929753 0.008727 +-0.547189 -0.836964 0.008727 +-0.547189 -0.836964 0.008727 +-0.368081 -0.929753 0.008727 +-0.368081 -0.929753 0.008727 +-0.547189 -0.836964 0.008727 +-0.181956 -0.983268 0.008727 +-0.368081 -0.929753 0.008727 +-0.368081 -0.929753 0.008727 +-0.181956 -0.983268 0.008727 +-0.181956 -0.983268 0.008727 +-0.368081 -0.929753 0.008727 +0.000000 -0.999962 0.008727 +-0.181956 -0.983268 0.008727 +-0.181956 -0.983268 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +-0.181956 -0.983268 0.008727 +0.181956 -0.983268 0.008727 +0.000000 -0.999962 0.008727 +0.000000 -0.999962 0.008727 +0.181956 -0.983268 0.008727 +0.181956 -0.983268 0.008727 +0.000000 -0.999962 0.008727 +0.368081 -0.929753 0.008727 +0.181956 -0.983268 0.008727 +0.181956 -0.983268 0.008727 +0.368081 -0.929753 0.008727 +0.368081 -0.929753 0.008727 +0.181956 -0.983268 0.008727 +0.547189 -0.836964 0.008727 +0.368081 -0.929753 0.008727 +0.368081 -0.929753 0.008727 +0.547189 -0.836964 0.008727 +0.547189 -0.836964 0.008727 +0.368081 -0.929753 0.008727 +0.707080 -0.707080 0.008727 +0.547189 -0.836964 0.008727 +0.547189 -0.836964 0.008727 +0.707080 -0.707080 0.008727 +0.707080 -0.707080 0.008727 +0.547189 -0.836964 0.008727 +0.836964 -0.547189 0.008727 +0.707080 -0.707080 0.008727 +0.707080 -0.707080 0.008727 +0.836964 -0.547189 0.008727 +0.836964 -0.547189 0.008727 +0.707080 -0.707080 0.008727 +0.929753 -0.368081 0.008727 +0.836964 -0.547189 0.008727 +0.836964 -0.547189 0.008727 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.866014 -0.499993 -0.005236 +0.866014 -0.499993 -0.005236 +0.866014 -0.499993 -0.005236 +0.866014 -0.499993 -0.005236 +0.866014 -0.499993 -0.005236 +0.866014 -0.499993 -0.005236 +-0.866014 0.499993 -0.005236 +-0.866014 0.499993 -0.005236 +-0.866014 0.499993 -0.005236 +-0.866014 0.499993 -0.005236 +-0.866014 0.499993 -0.005236 +-0.866014 0.499993 -0.005236 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.866014 -0.499993 -0.005236 +-0.866014 -0.499993 -0.005236 +-0.866014 -0.499993 -0.005236 +-0.866014 -0.499993 -0.005236 +-0.866014 -0.499993 -0.005236 +-0.866014 -0.499993 -0.005236 +0.866014 0.499993 -0.005236 +0.866014 0.499993 -0.005236 +0.866014 0.499993 -0.005236 +0.866014 0.499993 -0.005236 +0.866014 0.499993 -0.005236 +0.866014 0.499993 -0.005236 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +-0.177662 -0.977721 -0.111795 +0.000000 -0.993731 -0.111795 +0.000000 -0.993731 -0.111795 +-0.993149 -0.034018 -0.111795 +-0.971457 -0.209222 -0.111795 +-0.993210 -0.032171 -0.111795 +-0.969219 -0.219353 -0.111795 +-0.971457 -0.209222 -0.111795 +-0.993149 -0.034018 -0.111795 +-0.969219 -0.219353 -0.111795 +-0.914425 -0.389009 -0.111795 +-0.971457 -0.209222 -0.111795 +-0.905476 -0.409408 -0.111795 +-0.914425 -0.389009 -0.111795 +-0.969219 -0.219353 -0.111795 +-0.905476 -0.409408 -0.111795 +-0.820221 -0.561016 -0.111795 +-0.914425 -0.389009 -0.111795 +-0.809576 -0.576272 -0.111795 +-0.820221 -0.561016 -0.111795 +-0.905476 -0.409408 -0.111795 +-0.809576 -0.576272 -0.111795 +-0.691206 -0.713958 -0.111795 +-0.820221 -0.561016 -0.111795 +-0.691200 -0.713964 -0.111795 +-0.691206 -0.713958 -0.111795 +-0.809576 -0.576272 -0.111795 +-0.691200 -0.713964 -0.111795 +-0.534168 -0.837954 -0.111795 +-0.691206 -0.713958 -0.111795 +-0.549746 -0.827817 -0.111795 +-0.534168 -0.837954 -0.111795 +-0.691200 -0.713964 -0.111795 +-0.379863 -0.918262 -0.111795 +-0.534168 -0.837954 -0.111795 +-0.549746 -0.827817 -0.111795 +-0.379863 -0.918262 -0.111795 +-0.359201 -0.926540 -0.111795 +-0.534168 -0.837954 -0.111795 +-0.187843 -0.975816 -0.111795 +-0.359201 -0.926540 -0.111795 +-0.379863 -0.918262 -0.111795 +-0.187843 -0.975816 -0.111795 +-0.177662 -0.977721 -0.111795 +-0.359201 -0.926540 -0.111795 +0.000000 -0.993731 -0.111795 +-0.177662 -0.977721 -0.111795 +-0.187843 -0.975816 -0.111795 +0.993210 -0.032171 -0.111795 +0.993268 -0.030351 -0.111795 +0.993341 -0.027865 -0.111795 +0.000000 -0.993731 -0.111795 +0.177662 -0.977721 -0.111795 +0.000000 -0.993731 -0.111795 +0.189955 -0.975407 -0.111795 +0.177662 -0.977721 -0.111795 +0.000000 -0.993731 -0.111795 +0.189955 -0.975407 -0.111795 +0.359201 -0.926540 -0.111795 +0.177662 -0.977721 -0.111795 +0.381850 -0.917438 -0.111795 +0.359201 -0.926540 -0.111795 +0.189955 -0.975407 -0.111795 +0.381850 -0.917438 -0.111795 +0.534168 -0.837954 -0.111795 +0.359201 -0.926540 -0.111795 +0.551536 -0.826625 -0.111795 +0.534168 -0.837954 -0.111795 +0.381850 -0.917438 -0.111795 +0.551536 -0.826625 -0.111795 +0.691206 -0.713958 -0.111795 +0.534168 -0.837954 -0.111795 +0.692744 -0.712466 -0.111795 +0.691206 -0.713958 -0.111795 +0.551536 -0.826625 -0.111795 +0.692744 -0.712466 -0.111795 +0.820221 -0.561016 -0.111795 +0.691206 -0.713958 -0.111795 +0.810821 -0.574518 -0.111795 +0.820221 -0.561016 -0.111795 +0.692744 -0.712466 -0.111795 +0.906360 -0.407447 -0.111795 +0.820221 -0.561016 -0.111795 +0.810821 -0.574518 -0.111795 +0.906360 -0.407447 -0.111795 +0.914425 -0.389009 -0.111795 +0.820221 -0.561016 -0.111795 +0.969692 -0.217254 -0.111795 +0.914425 -0.389009 -0.111795 +0.906360 -0.407447 -0.111795 +0.969692 -0.217254 -0.111795 +0.971457 -0.209222 -0.111795 +0.914425 -0.389009 -0.111795 +0.993268 -0.030351 -0.111795 +0.971457 -0.209222 -0.111795 +0.969692 -0.217254 -0.111795 +0.993210 -0.032171 -0.111795 +0.993341 -0.027865 -0.111795 +0.993210 -0.032169 -0.111795 +0.993268 -0.030351 -0.111795 +0.993210 -0.032171 -0.111795 +0.971457 -0.209222 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.993731 -0.111795 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.368081 -0.929753 -0.008727 +0.181956 -0.983268 -0.008727 +0.181956 -0.983268 -0.008727 +0.000000 -0.999962 -0.008727 +0.181956 -0.983268 -0.008727 +0.000000 -0.999962 -0.008727 +0.181956 -0.983268 -0.008727 +0.181956 -0.983268 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.181956 0.983268 -0.008727 +0.000000 0.999962 -0.008727 +0.181956 0.983268 -0.008727 +0.181956 0.983268 -0.008727 +0.000000 0.999962 -0.008727 +0.368081 0.929753 -0.008727 +0.181956 0.983268 -0.008727 +0.181956 0.983268 -0.008727 +0.368081 0.929753 -0.008727 +0.368081 0.929753 -0.008727 +0.181956 0.983268 -0.008727 +0.547189 0.836964 -0.008727 +0.368081 0.929753 -0.008727 +0.368081 0.929753 -0.008727 +0.547189 0.836964 -0.008727 +0.547189 0.836964 -0.008727 +0.368081 0.929753 -0.008727 +0.707080 0.707080 -0.008727 +0.547189 0.836964 -0.008727 +0.547189 0.836964 -0.008727 +0.707080 0.707080 -0.008727 +0.707080 0.707080 -0.008727 +0.547189 0.836964 -0.008727 +0.836964 0.547189 -0.008727 +0.707080 0.707080 -0.008727 +0.707080 0.707080 -0.008727 +0.836964 0.547189 -0.008727 +0.836964 0.547189 -0.008727 +0.707080 0.707080 -0.008727 +0.929753 0.368081 -0.008727 +0.836964 0.547189 -0.008727 +0.836964 0.547189 -0.008727 +0.929753 0.368081 -0.008727 +0.929753 0.368081 -0.008727 +0.836964 0.547189 -0.008727 +0.983268 0.181956 -0.008727 +0.929753 0.368081 -0.008727 +0.929753 0.368081 -0.008727 +0.983268 0.181956 -0.008727 +0.983268 0.181956 -0.008727 +0.929753 0.368081 -0.008727 +0.999962 0.000000 -0.008727 +0.983268 0.181956 -0.008727 +0.983268 0.181956 -0.008727 +0.999962 0.000000 -0.008727 +0.999962 0.000000 -0.008727 +0.983268 0.181956 -0.008727 +0.999962 0.000000 -0.008727 +0.983268 -0.181956 -0.008727 +0.999962 0.000000 -0.008727 +0.983268 -0.181956 -0.008727 +0.983268 -0.181956 -0.008727 +0.999962 0.000000 -0.008727 +0.929753 -0.368081 -0.008727 +0.983268 -0.181956 -0.008727 +0.983268 -0.181956 -0.008727 +0.929753 -0.368081 -0.008727 +0.929753 -0.368081 -0.008727 +0.983268 -0.181956 -0.008727 +0.929753 -0.368081 -0.008727 +0.836964 -0.547189 -0.008727 +0.929753 -0.368081 -0.008727 +0.836964 -0.547189 -0.008727 +0.836964 -0.547189 -0.008727 +0.929753 -0.368081 -0.008727 +0.707080 -0.707080 -0.008727 +0.836964 -0.547189 -0.008727 +0.836964 -0.547189 -0.008727 +0.707080 -0.707080 -0.008727 +0.707080 -0.707080 -0.008727 +0.836964 -0.547189 -0.008727 +0.547189 -0.836964 -0.008727 +0.707080 -0.707080 -0.008727 +0.707080 -0.707080 -0.008727 +0.547189 -0.836964 -0.008727 +0.547189 -0.836964 -0.008727 +0.707080 -0.707080 -0.008727 +0.368081 -0.929753 -0.008727 +0.547189 -0.836964 -0.008727 +0.547189 -0.836964 -0.008727 +0.368081 -0.929753 -0.008727 +0.368081 -0.929753 -0.008727 +0.547189 -0.836964 -0.008727 +0.181956 -0.983268 -0.008727 +0.368081 -0.929753 -0.008727 +0.368081 -0.929753 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +0.000000 -0.999962 -0.008727 +-0.999962 0.000000 -0.008727 +-0.978744 -0.204902 -0.008727 +-0.999962 0.000000 -0.008727 +0.000000 -0.999962 -0.008727 +-0.204902 -0.978744 -0.008727 +0.000000 -0.999962 -0.008727 +-0.204902 -0.978744 -0.008727 +-0.204902 -0.978744 -0.008727 +0.000000 -0.999962 -0.008727 +-0.397162 -0.917707 -0.008727 +-0.204902 -0.978744 -0.008727 +-0.204902 -0.978744 -0.008727 +-0.397162 -0.917707 -0.008727 +-0.397162 -0.917707 -0.008727 +-0.204902 -0.978744 -0.008727 +-0.397162 -0.917707 -0.008727 +-0.566613 -0.823938 -0.008727 +-0.397162 -0.917707 -0.008727 +-0.566613 -0.823938 -0.008727 +-0.566613 -0.823938 -0.008727 +-0.397162 -0.917707 -0.008727 +-0.566613 -0.823938 -0.008727 +-0.707080 -0.707080 -0.008727 +-0.566613 -0.823938 -0.008727 +-0.707080 -0.707080 -0.008727 +-0.707080 -0.707080 -0.008727 +-0.566613 -0.823938 -0.008727 +-0.823938 -0.566613 -0.008727 +-0.707080 -0.707080 -0.008727 +-0.707080 -0.707080 -0.008727 +-0.823938 -0.566613 -0.008727 +-0.823938 -0.566613 -0.008727 +-0.707080 -0.707080 -0.008727 +-0.917707 -0.397162 -0.008727 +-0.823938 -0.566613 -0.008727 +-0.823938 -0.566613 -0.008727 +-0.917707 -0.397162 -0.008727 +-0.917707 -0.397162 -0.008727 +-0.823938 -0.566613 -0.008727 +-0.917707 -0.397162 -0.008727 +-0.978744 -0.204902 -0.008727 +-0.917707 -0.397162 -0.008727 +-0.978744 -0.204902 -0.008727 +-0.978744 -0.204902 -0.008727 +-0.917707 -0.397162 -0.008727 +-0.978744 -0.204902 -0.008727 +-0.999962 0.000000 -0.008727 +-0.978744 -0.204902 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +0.000000 0.999962 -0.008727 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.000000 -0.017452 0.999848 +0.000000 -0.017452 0.999848 +0.000000 -0.017452 0.999848 +0.000000 -0.017452 0.999848 +0.000000 -0.017452 0.999848 +0.000000 -0.017452 0.999848 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +0.000000 -0.017452 -0.999848 +0.000000 -0.017452 -0.999848 +0.000000 -0.017452 -0.999848 +0.000000 -0.017452 -0.999848 +0.000000 -0.017452 -0.999848 +0.000000 -0.017452 -0.999848 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -0.017452 -0.999848 +0.000000 -0.017452 -0.999848 +0.000000 -0.017452 -0.999848 +0.000000 -0.017452 -0.999848 +0.000000 -0.017452 -0.999848 +0.000000 -0.017452 -0.999848 +0.000000 -0.017452 -0.999848 +0.000000 -0.017452 -0.999848 +0.000000 -0.017452 -0.999848 +0.000000 -0.017452 -0.999848 +0.000000 -0.017452 -0.999848 +0.000000 -0.017452 -0.999848 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +0.000000 -0.017452 0.999848 +0.000000 -0.017452 0.999848 +0.000000 -0.017452 0.999848 +0.000000 -0.017452 0.999848 +0.000000 -0.017452 0.999848 +0.000000 -0.017452 0.999848 +0.000000 -0.017452 0.999848 +0.000000 -0.017452 0.999848 +0.000000 -0.017452 0.999848 +0.000000 -0.017452 0.999848 +0.000000 -0.017452 0.999848 +0.000000 -0.017452 0.999848 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -0.017452 0.999848 +0.000000 -0.017452 0.999848 +0.000000 -0.017452 0.999848 +0.000000 -0.017452 0.999848 +0.000000 -0.017452 0.999848 +0.000000 -0.017452 0.999848 +0.000000 -0.017452 0.999848 +0.000000 -0.017452 0.999848 +0.000000 -0.017452 0.999848 +0.000000 -0.017452 0.999848 +0.000000 -0.017452 0.999848 +0.000000 -0.017452 0.999848 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.000000 -0.017452 -0.999848 +0.000000 -0.017452 -0.999848 +0.000000 -0.017452 -0.999848 +0.000000 -0.017452 -0.999848 +0.000000 -0.017452 -0.999848 +0.000000 -0.017452 -0.999848 +0.000000 -0.017452 -0.999848 +0.000000 -0.017452 -0.999848 +0.000000 -0.017452 -0.999848 +0.000000 -0.017452 -0.999848 +0.000000 -0.017452 -0.999848 +0.000000 -0.017452 -0.999848 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -0.017452 -0.999848 +0.000000 -0.017452 -0.999848 +0.000000 -0.017452 -0.999848 +0.000000 -0.017452 -0.999848 +0.000000 -0.017452 -0.999848 +0.000000 -0.017452 -0.999848 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +0.000000 -0.017452 0.999848 +0.000000 -0.017452 0.999848 +0.000000 -0.017452 0.999848 +0.000000 -0.017452 0.999848 +0.000000 -0.017452 0.999848 +0.000000 -0.017452 0.999848 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.000000 -0.017452 -0.999848 +0.000000 -0.017452 -0.999848 +0.000000 -0.017452 -0.999848 +0.000000 -0.017452 -0.999848 +0.000000 -0.017452 -0.999848 +0.000000 -0.017452 -0.999848 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +0.000000 -0.017452 0.999848 +0.000000 -0.017452 0.999848 +0.000000 -0.017452 0.999848 +0.000000 -0.017452 0.999848 +0.000000 -0.017452 0.999848 +0.000000 -0.017452 0.999848 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +-0.188061 -0.857166 -0.479478 +-0.093718 -0.857167 -0.506440 +-0.092188 -0.857166 -0.506722 +0.000000 -0.857167 -0.515038 +-0.093718 -0.857167 -0.506440 +0.000000 -0.857167 -0.515038 +-0.092188 -0.857166 -0.506722 +-0.093718 -0.857167 -0.506440 +0.000000 -0.857167 -0.515038 +-0.093718 -0.857167 0.506440 +-0.001458 -0.857166 0.515038 +0.000000 -0.857167 0.515038 +-0.093718 -0.857167 0.506440 +-0.095249 -0.857166 0.506156 +-0.001458 -0.857166 0.515038 +-0.189583 -0.857167 0.478876 +-0.095249 -0.857166 0.506156 +-0.093718 -0.857167 0.506440 +-0.189583 -0.857167 0.478876 +-0.191105 -0.857166 0.478273 +-0.095249 -0.857166 0.506156 +-0.281834 -0.857167 0.431085 +-0.191105 -0.857166 0.478273 +-0.189583 -0.857167 0.478876 +-0.281834 -0.857167 0.431085 +-0.283247 -0.857166 0.430160 +-0.191105 -0.857166 0.478273 +-0.364187 -0.857167 0.364187 +-0.283247 -0.857166 0.430160 +-0.281834 -0.857167 0.431085 +-0.364187 -0.857167 0.364187 +-0.365393 -0.857166 0.362980 +-0.283247 -0.857166 0.430160 +-0.431085 -0.857167 0.281834 +-0.365393 -0.857166 0.362980 +-0.364187 -0.857167 0.364187 +-0.431085 -0.857167 0.281834 +-0.432008 -0.857166 0.280420 +-0.365393 -0.857166 0.362980 +-0.478876 -0.857167 0.189583 +-0.432008 -0.857166 0.280420 +-0.431085 -0.857167 0.281834 +-0.478876 -0.857167 0.189583 +-0.479478 -0.857166 0.188061 +-0.432008 -0.857166 0.280420 +-0.506440 -0.857167 0.093718 +-0.479478 -0.857166 0.188061 +-0.478876 -0.857167 0.189583 +-0.506440 -0.857167 0.093718 +-0.506722 -0.857166 0.092188 +-0.479478 -0.857166 0.188061 +-0.506440 -0.857167 0.093718 +-0.515038 -0.857166 -0.001458 +-0.506722 -0.857166 0.092188 +-0.515038 -0.857167 0.000000 +-0.515038 -0.857166 -0.001458 +-0.506440 -0.857167 0.093718 +-0.506440 -0.857167 -0.093718 +-0.515038 -0.857166 -0.001458 +-0.515038 -0.857167 0.000000 +-0.506440 -0.857167 -0.093718 +-0.506156 -0.857166 -0.095249 +-0.515038 -0.857166 -0.001458 +-0.506440 -0.857167 -0.093718 +-0.478273 -0.857166 -0.191105 +-0.506156 -0.857166 -0.095249 +-0.478876 -0.857167 -0.189583 +-0.478273 -0.857166 -0.191105 +-0.506440 -0.857167 -0.093718 +-0.431085 -0.857167 -0.281834 +-0.478273 -0.857166 -0.191105 +-0.478876 -0.857167 -0.189583 +-0.431085 -0.857167 -0.281834 +-0.430160 -0.857166 -0.283247 +-0.478273 -0.857166 -0.191105 +-0.431085 -0.857167 -0.281834 +-0.362980 -0.857166 -0.365393 +-0.430160 -0.857166 -0.283247 +-0.364187 -0.857167 -0.364187 +-0.362980 -0.857166 -0.365393 +-0.431085 -0.857167 -0.281834 +-0.281834 -0.857167 -0.431085 +-0.362980 -0.857166 -0.365393 +-0.364187 -0.857167 -0.364187 +-0.281834 -0.857167 -0.431085 +-0.280420 -0.857166 -0.432008 +-0.362980 -0.857166 -0.365393 +-0.189583 -0.857167 -0.478876 +-0.280420 -0.857166 -0.432008 +-0.281834 -0.857167 -0.431085 +-0.189583 -0.857167 -0.478876 +-0.188061 -0.857166 -0.479478 +-0.280420 -0.857166 -0.432008 +-0.093718 -0.857167 -0.506440 +-0.188061 -0.857166 -0.479478 +-0.189583 -0.857167 -0.478876 +-0.983305 0.000000 0.181963 +-0.929788 0.000000 0.368095 +-0.929788 0.000000 0.368095 +0.000000 0.000000 1.000000 +-0.181963 0.000000 0.983305 +0.000000 0.000000 1.000000 +-0.181963 0.000000 0.983305 +-0.181963 0.000000 0.983305 +0.000000 0.000000 1.000000 +-0.368095 0.000000 0.929788 +-0.181963 0.000000 0.983305 +-0.181963 0.000000 0.983305 +-0.368095 0.000000 0.929788 +-0.368095 0.000000 0.929788 +-0.181963 0.000000 0.983305 +-0.547210 0.000000 0.836995 +-0.368095 0.000000 0.929788 +-0.368095 0.000000 0.929788 +-0.547210 0.000000 0.836995 +-0.547210 0.000000 0.836995 +-0.368095 0.000000 0.929788 +-0.707107 0.000000 0.707107 +-0.547210 0.000000 0.836995 +-0.547210 0.000000 0.836995 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.547210 0.000000 0.836995 +-0.836995 0.000000 0.547210 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.836995 0.000000 0.547210 +-0.836995 0.000000 0.547210 +-0.707107 0.000000 0.707107 +-0.836995 0.000000 0.547210 +-0.929788 0.000000 0.368095 +-0.836995 0.000000 0.547210 +-0.929788 0.000000 0.368095 +-0.929788 0.000000 0.368095 +-0.836995 0.000000 0.547210 +-0.181963 0.000000 -0.983305 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.181963 0.000000 -0.983305 +-0.181963 0.000000 -0.983305 +0.000000 0.000000 -1.000000 +-0.181963 0.000000 -0.983305 +-0.368095 0.000000 -0.929788 +-0.181963 0.000000 -0.983305 +-0.368095 0.000000 -0.929788 +-0.368095 0.000000 -0.929788 +-0.181963 0.000000 -0.983305 +-0.547210 0.000000 -0.836995 +-0.368095 0.000000 -0.929788 +-0.368095 0.000000 -0.929788 +-0.547210 0.000000 -0.836995 +-0.547210 0.000000 -0.836995 +-0.368095 0.000000 -0.929788 +-0.707107 0.000000 -0.707107 +-0.547210 0.000000 -0.836995 +-0.547210 0.000000 -0.836995 +-0.707107 0.000000 -0.707107 +-0.707107 0.000000 -0.707107 +-0.547210 0.000000 -0.836995 +-0.836995 0.000000 -0.547210 +-0.707107 0.000000 -0.707107 +-0.707107 0.000000 -0.707107 +-0.836995 0.000000 -0.547210 +-0.836995 0.000000 -0.547210 +-0.707107 0.000000 -0.707107 +-0.929788 0.000000 -0.368095 +-0.836995 0.000000 -0.547210 +-0.836995 0.000000 -0.547210 +-0.929788 0.000000 -0.368095 +-0.929788 0.000000 -0.368095 +-0.836995 0.000000 -0.547210 +-0.983305 0.000000 -0.181963 +-0.929788 0.000000 -0.368095 +-0.929788 0.000000 -0.368095 +-0.983305 0.000000 -0.181963 +-0.983305 0.000000 -0.181963 +-0.929788 0.000000 -0.368095 +-1.000000 0.000000 0.000000 +-0.983305 0.000000 -0.181963 +-0.983305 0.000000 -0.181963 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.000000 -0.181963 +-1.000000 0.000000 0.000000 +-0.983305 0.000000 0.181963 +-1.000000 0.000000 0.000000 +-0.983305 0.000000 0.181963 +-0.983305 0.000000 0.181963 +-1.000000 0.000000 0.000000 +-0.929788 0.000000 0.368095 +-0.983305 0.000000 0.181963 +-0.983305 0.000000 0.181963 +-0.280420 -0.857166 -0.432008 +-0.189583 -0.857167 -0.478876 +-0.188061 -0.857166 -0.479478 +-0.092188 -0.857166 -0.506722 +0.000000 -0.857167 -0.515038 +0.000000 -0.857167 -0.515038 +-0.092188 -0.857166 -0.506722 +-0.093718 -0.857167 -0.506440 +0.000000 -0.857167 -0.515038 +-0.188061 -0.857166 -0.479478 +-0.093718 -0.857167 -0.506440 +-0.092188 -0.857166 -0.506722 +-0.188061 -0.857166 -0.479478 +-0.189583 -0.857167 -0.478876 +-0.093718 -0.857167 -0.506440 +-0.093718 -0.857167 0.506440 +-0.001458 -0.857166 0.515038 +0.000000 -0.857167 0.515038 +-0.093718 -0.857167 0.506440 +-0.095249 -0.857166 0.506156 +-0.001458 -0.857166 0.515038 +-0.189583 -0.857167 0.478876 +-0.095249 -0.857166 0.506156 +-0.093718 -0.857167 0.506440 +-0.189583 -0.857167 0.478876 +-0.191105 -0.857166 0.478273 +-0.095249 -0.857166 0.506156 +-0.281834 -0.857167 0.431085 +-0.191105 -0.857166 0.478273 +-0.189583 -0.857167 0.478876 +-0.281834 -0.857167 0.431085 +-0.283247 -0.857166 0.430160 +-0.191105 -0.857166 0.478273 +-0.364187 -0.857167 0.364187 +-0.283247 -0.857166 0.430160 +-0.281834 -0.857167 0.431085 +-0.364187 -0.857167 0.364187 +-0.365393 -0.857166 0.362980 +-0.283247 -0.857166 0.430160 +-0.431085 -0.857167 0.281834 +-0.365393 -0.857166 0.362980 +-0.364187 -0.857167 0.364187 +-0.431085 -0.857167 0.281834 +-0.432008 -0.857166 0.280420 +-0.365393 -0.857166 0.362980 +-0.478876 -0.857167 0.189583 +-0.432008 -0.857166 0.280420 +-0.431085 -0.857167 0.281834 +-0.478876 -0.857167 0.189583 +-0.479478 -0.857166 0.188061 +-0.432008 -0.857166 0.280420 +-0.506440 -0.857167 0.093718 +-0.479478 -0.857166 0.188061 +-0.478876 -0.857167 0.189583 +-0.506440 -0.857167 0.093718 +-0.506722 -0.857166 0.092188 +-0.479478 -0.857166 0.188061 +-0.506440 -0.857167 0.093718 +-0.515038 -0.857166 -0.001458 +-0.506722 -0.857166 0.092188 +-0.515038 -0.857167 0.000000 +-0.515038 -0.857166 -0.001458 +-0.506440 -0.857167 0.093718 +-0.506440 -0.857167 -0.093718 +-0.515038 -0.857166 -0.001458 +-0.515038 -0.857167 0.000000 +-0.506440 -0.857167 -0.093718 +-0.506156 -0.857166 -0.095249 +-0.515038 -0.857166 -0.001458 +-0.478876 -0.857167 -0.189583 +-0.506156 -0.857166 -0.095249 +-0.506440 -0.857167 -0.093718 +-0.478876 -0.857167 -0.189583 +-0.478273 -0.857166 -0.191105 +-0.506156 -0.857166 -0.095249 +-0.431085 -0.857167 -0.281834 +-0.478273 -0.857166 -0.191105 +-0.478876 -0.857167 -0.189583 +-0.431085 -0.857167 -0.281834 +-0.430160 -0.857166 -0.283247 +-0.478273 -0.857166 -0.191105 +-0.364187 -0.857167 -0.364187 +-0.430160 -0.857166 -0.283247 +-0.431085 -0.857167 -0.281834 +-0.364187 -0.857167 -0.364187 +-0.362980 -0.857166 -0.365393 +-0.430160 -0.857166 -0.283247 +-0.364187 -0.857167 -0.364187 +-0.280420 -0.857166 -0.432008 +-0.362980 -0.857166 -0.365393 +-0.281834 -0.857167 -0.431085 +-0.280420 -0.857166 -0.432008 +-0.364187 -0.857167 -0.364187 +-0.189583 -0.857167 -0.478876 +-0.280420 -0.857166 -0.432008 +-0.281834 -0.857167 -0.431085 +-0.836995 0.000000 -0.547210 +-0.707107 0.000000 -0.707107 +-0.707107 0.000000 -0.707107 +-0.181963 0.000000 -0.983305 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.181963 0.000000 -0.983305 +-0.181963 0.000000 -0.983305 +0.000000 0.000000 -1.000000 +-0.368095 0.000000 -0.929788 +-0.181963 0.000000 -0.983305 +-0.181963 0.000000 -0.983305 +-0.368095 0.000000 -0.929788 +-0.368095 0.000000 -0.929788 +-0.181963 0.000000 -0.983305 +-0.547210 0.000000 -0.836995 +-0.368095 0.000000 -0.929788 +-0.368095 0.000000 -0.929788 +-0.547210 0.000000 -0.836995 +-0.547210 0.000000 -0.836995 +-0.368095 0.000000 -0.929788 +-0.547210 0.000000 -0.836995 +-0.707107 0.000000 -0.707107 +-0.547210 0.000000 -0.836995 +-0.707107 0.000000 -0.707107 +-0.707107 0.000000 -0.707107 +-0.547210 0.000000 -0.836995 +-0.181963 0.000000 0.983305 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.181963 0.000000 0.983305 +-0.181963 0.000000 0.983305 +0.000000 0.000000 1.000000 +-0.368095 0.000000 0.929788 +-0.181963 0.000000 0.983305 +-0.181963 0.000000 0.983305 +-0.368095 0.000000 0.929788 +-0.368095 0.000000 0.929788 +-0.181963 0.000000 0.983305 +-0.547210 0.000000 0.836995 +-0.368095 0.000000 0.929788 +-0.368095 0.000000 0.929788 +-0.547210 0.000000 0.836995 +-0.547210 0.000000 0.836995 +-0.368095 0.000000 0.929788 +-0.707107 0.000000 0.707107 +-0.547210 0.000000 0.836995 +-0.547210 0.000000 0.836995 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.547210 0.000000 0.836995 +-0.836995 0.000000 0.547210 +-0.707107 0.000000 0.707107 +-0.707107 0.000000 0.707107 +-0.836995 0.000000 0.547210 +-0.836995 0.000000 0.547210 +-0.707107 0.000000 0.707107 +-0.929788 0.000000 0.368095 +-0.836995 0.000000 0.547210 +-0.836995 0.000000 0.547210 +-0.929788 0.000000 0.368095 +-0.929788 0.000000 0.368095 +-0.836995 0.000000 0.547210 +-0.983305 0.000000 0.181963 +-0.929788 0.000000 0.368095 +-0.929788 0.000000 0.368095 +-0.983305 0.000000 0.181963 +-0.983305 0.000000 0.181963 +-0.929788 0.000000 0.368095 +-1.000000 0.000000 0.000000 +-0.983305 0.000000 0.181963 +-0.983305 0.000000 0.181963 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.000000 0.181963 +-0.983305 0.000000 -0.181963 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 0.000000 -0.181963 +-0.983305 0.000000 -0.181963 +-1.000000 0.000000 0.000000 +-0.929788 0.000000 -0.368095 +-0.983305 0.000000 -0.181963 +-0.983305 0.000000 -0.181963 +-0.929788 0.000000 -0.368095 +-0.929788 0.000000 -0.368095 +-0.983305 0.000000 -0.181963 +-0.836995 0.000000 -0.547210 +-0.929788 0.000000 -0.368095 +-0.929788 0.000000 -0.368095 +-0.836995 0.000000 -0.547210 +-0.836995 0.000000 -0.547210 +-0.929788 0.000000 -0.368095 +-0.707107 0.000000 -0.707107 +-0.836995 0.000000 -0.547210 +-0.836995 0.000000 -0.547210 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +-0.999998 0.000000 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.352572 0.935785 +0.000000 0.352572 0.935785 +0.000000 0.352572 0.935785 +0.000000 0.352572 0.935785 +0.000000 0.352572 0.935785 +0.000000 0.352572 0.935785 +0.000000 0.352572 -0.935785 +0.000000 0.352572 -0.935785 +0.000000 0.352572 -0.935785 +0.000000 0.352572 -0.935785 +0.000000 0.352572 -0.935785 +0.000000 0.352572 -0.935785 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.352572 0.935785 +0.000000 0.352572 0.935785 +0.000000 0.352572 0.935785 +0.000000 0.352572 0.935785 +0.000000 0.352572 0.935785 +0.000000 0.352572 0.935785 +0.000000 0.352572 -0.935785 +0.000000 0.352572 -0.935785 +0.000000 0.352572 -0.935785 +0.000000 0.352572 -0.935785 +0.000000 0.352572 -0.935785 +0.000000 0.352572 -0.935785 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -0.352572 -0.935785 +0.000000 -0.352572 -0.935785 +0.000000 -0.352572 -0.935785 +0.000000 -0.352572 -0.935785 +0.000000 -0.352572 -0.935785 +0.000000 -0.352572 -0.935785 +0.000000 -0.352572 0.935785 +0.000000 -0.352572 0.935785 +0.000000 -0.352572 0.935785 +0.000000 -0.352572 0.935785 +0.000000 -0.352572 0.935785 +0.000000 -0.352572 0.935785 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -0.352572 -0.935785 +0.000000 -0.352572 -0.935785 +0.000000 -0.352572 -0.935785 +0.000000 -0.352572 -0.935785 +0.000000 -0.352572 -0.935785 +0.000000 -0.352572 -0.935785 +0.000000 -0.352572 0.935785 +0.000000 -0.352572 0.935785 +0.000000 -0.352572 0.935785 +0.000000 -0.352572 0.935785 +0.000000 -0.352572 0.935785 +0.000000 -0.352572 0.935785 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.352572 -0.935785 +0.000000 0.352572 -0.935785 +0.000000 0.352572 -0.935785 +0.000000 0.352572 -0.935785 +0.000000 0.352572 -0.935785 +0.000000 0.352572 -0.935785 +0.000000 0.352572 0.935785 +0.000000 0.352572 0.935785 +0.000000 0.352572 0.935785 +0.000000 0.352572 0.935785 +0.000000 0.352572 0.935785 +0.000000 0.352572 0.935785 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.352572 -0.935785 +0.000000 0.352572 -0.935785 +0.000000 0.352572 -0.935785 +0.000000 0.352572 -0.935785 +0.000000 0.352572 -0.935785 +0.000000 0.352572 -0.935785 +0.000000 0.352572 0.935785 +0.000000 0.352572 0.935785 +0.000000 0.352572 0.935785 +0.000000 0.352572 0.935785 +0.000000 0.352572 0.935785 +0.000000 0.352572 0.935785 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 -0.352572 -0.935785 +0.000000 -0.352572 -0.935785 +0.000000 -0.352572 -0.935785 +0.000000 -0.352572 -0.935785 +0.000000 -0.352572 -0.935785 +0.000000 -0.352572 -0.935785 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -0.352572 0.935785 +0.000000 -0.352572 0.935785 +0.000000 -0.352572 0.935785 +0.000000 -0.352572 0.935785 +0.000000 -0.352572 0.935785 +0.000000 -0.352572 0.935785 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 -0.352572 -0.935785 +0.000000 -0.352572 -0.935785 +0.000000 -0.352572 -0.935785 +0.000000 -0.352572 -0.935785 +0.000000 -0.352572 -0.935785 +0.000000 -0.352572 -0.935785 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -0.352572 0.935785 +0.000000 -0.352572 0.935785 +0.000000 -0.352572 0.935785 +0.000000 -0.352572 0.935785 +0.000000 -0.352572 0.935785 +0.000000 -0.352572 0.935785 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.983305 -0.181963 0.000000 +-1.000000 0.000000 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.983305 -0.181963 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.836995 -0.547210 0.000000 +-0.929788 -0.368095 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836995 -0.547210 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.547210 -0.836995 0.000000 +-0.707107 -0.707107 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.368095 -0.929788 0.000000 +-0.547210 -0.836995 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +-0.181963 -0.983305 0.000000 +-0.368095 -0.929788 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.181963 -0.983305 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +1.000000 0.000000 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.983305 -0.181963 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.983305 -0.181963 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.836995 -0.547210 0.000000 +0.929788 -0.368095 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836995 -0.547210 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.707107 -0.707107 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.547210 -0.836995 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.547210 -0.836995 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.368095 -0.929788 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.368095 -0.929788 0.000000 +0.000000 -1.000000 0.000000 +0.181963 -0.983305 0.000000 +0.181963 -0.983305 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -0.983620 -0.180253 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -0.197392 -0.980325 +0.000000 -0.017452 -0.999848 +0.000000 -0.017452 -0.999848 +0.000000 -0.197392 -0.980325 +0.000000 -0.197392 -0.980325 +0.000000 -0.017452 -0.999848 +0.000000 -0.380726 -0.924688 +0.000000 -0.197392 -0.980325 +0.000000 -0.197392 -0.980325 +0.000000 -0.380726 -0.924688 +0.000000 -0.380726 -0.924688 +0.000000 -0.197392 -0.980325 +0.000000 -0.556592 -0.830786 +0.000000 -0.380726 -0.924688 +0.000000 -0.380726 -0.924688 +0.000000 -0.556592 -0.830786 +0.000000 -0.556592 -0.830786 +0.000000 -0.380726 -0.924688 +0.000000 -0.713250 -0.700909 +0.000000 -0.556592 -0.830786 +0.000000 -0.556592 -0.830786 +0.000000 -0.713250 -0.700909 +0.000000 -0.713250 -0.700909 +0.000000 -0.556592 -0.830786 +0.000000 -0.840373 -0.542008 +0.000000 -0.713250 -0.700909 +0.000000 -0.713250 -0.700909 +0.000000 -0.840373 -0.542008 +0.000000 -0.840373 -0.542008 +0.000000 -0.713250 -0.700909 +0.000000 -0.931192 -0.364530 +0.000000 -0.840373 -0.542008 +0.000000 -0.840373 -0.542008 +0.000000 -0.931192 -0.364530 +0.000000 -0.931192 -0.364530 +0.000000 -0.840373 -0.542008 +0.000000 -0.983620 -0.180253 +0.000000 -0.931192 -0.364530 +0.000000 -0.931192 -0.364530 +0.000000 -0.983620 -0.180253 +0.000000 -0.983620 -0.180253 +0.000000 -0.931192 -0.364530 +0.000000 -1.000000 0.000000 +0.000000 -0.983620 -0.180253 +0.000000 -0.983620 -0.180253 +0.000000 -0.983620 0.180253 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -0.197392 0.980325 +0.000000 -0.017452 0.999848 +0.000000 -0.017452 0.999848 +0.000000 -0.197392 0.980325 +0.000000 -0.197392 0.980325 +0.000000 -0.017452 0.999848 +0.000000 -0.380726 0.924688 +0.000000 -0.197392 0.980325 +0.000000 -0.197392 0.980325 +0.000000 -0.380726 0.924688 +0.000000 -0.380726 0.924688 +0.000000 -0.197392 0.980325 +0.000000 -0.556592 0.830786 +0.000000 -0.380726 0.924688 +0.000000 -0.380726 0.924688 +0.000000 -0.556592 0.830786 +0.000000 -0.556592 0.830786 +0.000000 -0.380726 0.924688 +0.000000 -0.713250 0.700909 +0.000000 -0.556592 0.830786 +0.000000 -0.556592 0.830786 +0.000000 -0.713250 0.700909 +0.000000 -0.713250 0.700909 +0.000000 -0.556592 0.830786 +0.000000 -0.840373 0.542008 +0.000000 -0.713250 0.700909 +0.000000 -0.713250 0.700909 +0.000000 -0.840373 0.542008 +0.000000 -0.840373 0.542008 +0.000000 -0.713250 0.700909 +0.000000 -0.931192 0.364530 +0.000000 -0.840373 0.542008 +0.000000 -0.840373 0.542008 +0.000000 -0.931192 0.364530 +0.000000 -0.931192 0.364530 +0.000000 -0.840373 0.542008 +0.000000 -0.983620 0.180253 +0.000000 -0.931192 0.364530 +0.000000 -0.931192 0.364530 +0.000000 -0.983620 0.180253 +0.000000 -0.983620 0.180253 +0.000000 -0.931192 0.364530 +0.000000 -1.000000 0.000000 +0.000000 -0.983620 0.180253 +0.000000 -0.983620 0.180253 +-0.983106 -0.020335 0.181906 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +0.000000 -0.017452 0.999848 +-0.181906 -0.020335 0.983106 +0.000000 -0.017452 0.999848 +-0.181906 -0.020335 0.983106 +-0.181906 -0.020335 0.983106 +0.000000 -0.017452 0.999848 +-0.181906 -0.020335 0.983106 +-0.367977 -0.022649 0.929559 +-0.181906 -0.020335 0.983106 +-0.367977 -0.022649 0.929559 +-0.367977 -0.022649 0.929559 +-0.181906 -0.020335 0.983106 +-0.367977 -0.022649 0.929559 +-0.547036 -0.024154 0.836761 +-0.367977 -0.022649 0.929559 +-0.547036 -0.024154 0.836761 +-0.547036 -0.024154 0.836761 +-0.367977 -0.022649 0.929559 +-0.547036 -0.024154 0.836761 +-0.630101 -0.024546 0.776125 +-0.547036 -0.024154 0.836761 +-0.630101 -0.024546 0.776125 +-0.630101 -0.024546 0.776125 +-0.547036 -0.024154 0.836761 +-0.630101 -0.024546 0.776125 +-0.706891 -0.024678 0.706891 +-0.630101 -0.024546 0.776125 +-0.706891 -0.024678 0.706891 +-0.706891 -0.024678 0.706891 +-0.630101 -0.024546 0.776125 +-0.776125 -0.024546 0.630101 +-0.706891 -0.024678 0.706891 +-0.706891 -0.024678 0.706891 +-0.776125 -0.024546 0.630101 +-0.776125 -0.024546 0.630101 +-0.706891 -0.024678 0.706891 +-0.836761 -0.024154 0.547036 +-0.776125 -0.024546 0.630101 +-0.776125 -0.024546 0.630101 +-0.836761 -0.024154 0.547036 +-0.836761 -0.024154 0.547036 +-0.776125 -0.024546 0.630101 +-0.929559 -0.022649 0.367977 +-0.836761 -0.024154 0.547036 +-0.836761 -0.024154 0.547036 +-0.929559 -0.022649 0.367977 +-0.929559 -0.022649 0.367977 +-0.836761 -0.024154 0.547036 +-0.983106 -0.020335 0.181906 +-0.929559 -0.022649 0.367977 +-0.929559 -0.022649 0.367977 +-0.983106 -0.020335 0.181906 +-0.983106 -0.020335 0.181906 +-0.929559 -0.022649 0.367977 +-0.999848 -0.017452 0.000000 +-0.983106 -0.020335 0.181906 +-0.983106 -0.020335 0.181906 +0.000000 -0.197392 -0.980325 +0.000000 -0.017452 -0.999848 +0.000000 -0.017452 -0.999848 +0.000000 -0.983620 -0.180253 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -0.983620 -0.180253 +0.000000 -0.983620 -0.180253 +0.000000 -1.000000 0.000000 +0.000000 -0.931192 -0.364530 +0.000000 -0.983620 -0.180253 +0.000000 -0.983620 -0.180253 +0.000000 -0.931192 -0.364530 +0.000000 -0.931192 -0.364530 +0.000000 -0.983620 -0.180253 +0.000000 -0.840373 -0.542008 +0.000000 -0.931192 -0.364530 +0.000000 -0.931192 -0.364530 +0.000000 -0.840373 -0.542008 +0.000000 -0.840373 -0.542008 +0.000000 -0.931192 -0.364530 +0.000000 -0.713250 -0.700909 +0.000000 -0.840373 -0.542008 +0.000000 -0.840373 -0.542008 +0.000000 -0.713250 -0.700909 +0.000000 -0.713250 -0.700909 +0.000000 -0.840373 -0.542008 +0.000000 -0.556592 -0.830786 +0.000000 -0.713250 -0.700909 +0.000000 -0.713250 -0.700909 +0.000000 -0.556592 -0.830786 +0.000000 -0.556592 -0.830786 +0.000000 -0.713250 -0.700909 +0.000000 -0.380726 -0.924688 +0.000000 -0.556592 -0.830786 +0.000000 -0.556592 -0.830786 +0.000000 -0.380726 -0.924688 +0.000000 -0.380726 -0.924688 +0.000000 -0.556592 -0.830786 +0.000000 -0.197392 -0.980325 +0.000000 -0.380726 -0.924688 +0.000000 -0.380726 -0.924688 +0.000000 -0.197392 -0.980325 +0.000000 -0.197392 -0.980325 +0.000000 -0.380726 -0.924688 +0.000000 -0.017452 -0.999848 +0.000000 -0.197392 -0.980325 +0.000000 -0.197392 -0.980325 +0.000000 -0.197392 0.980325 +0.000000 -0.017452 0.999848 +0.000000 -0.017452 0.999848 +0.000000 -0.983620 0.180253 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -0.983620 0.180253 +0.000000 -0.983620 0.180253 +0.000000 -1.000000 0.000000 +0.000000 -0.931192 0.364530 +0.000000 -0.983620 0.180253 +0.000000 -0.983620 0.180253 +0.000000 -0.931192 0.364530 +0.000000 -0.931192 0.364530 +0.000000 -0.983620 0.180253 +0.000000 -0.840373 0.542008 +0.000000 -0.931192 0.364530 +0.000000 -0.931192 0.364530 +0.000000 -0.840373 0.542008 +0.000000 -0.840373 0.542008 +0.000000 -0.931192 0.364530 +0.000000 -0.713250 0.700909 +0.000000 -0.840373 0.542008 +0.000000 -0.840373 0.542008 +0.000000 -0.713250 0.700909 +0.000000 -0.713250 0.700909 +0.000000 -0.840373 0.542008 +0.000000 -0.556592 0.830786 +0.000000 -0.713250 0.700909 +0.000000 -0.713250 0.700909 +0.000000 -0.556592 0.830786 +0.000000 -0.556592 0.830786 +0.000000 -0.713250 0.700909 +0.000000 -0.380726 0.924688 +0.000000 -0.556592 0.830786 +0.000000 -0.556592 0.830786 +0.000000 -0.380726 0.924688 +0.000000 -0.380726 0.924688 +0.000000 -0.556592 0.830786 +0.000000 -0.197392 0.980325 +0.000000 -0.380726 0.924688 +0.000000 -0.380726 0.924688 +0.000000 -0.197392 0.980325 +0.000000 -0.197392 0.980325 +0.000000 -0.380726 0.924688 +0.000000 -0.017452 0.999848 +0.000000 -0.197392 0.980325 +0.000000 -0.197392 0.980325 +0.983305 -0.003176 -0.181935 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.181963 -0.017161 -0.983156 +0.000000 -0.017452 -0.999848 +0.000000 -0.017452 -0.999848 +0.181963 -0.017161 -0.983156 +0.181963 -0.017161 -0.983156 +0.000000 -0.017452 -0.999848 +0.368095 -0.016227 -0.929647 +0.181963 -0.017161 -0.983156 +0.181963 -0.017161 -0.983156 +0.368095 -0.016227 -0.929647 +0.368095 -0.016227 -0.929647 +0.181963 -0.017161 -0.983156 +0.547210 -0.014608 -0.836868 +0.368095 -0.016227 -0.929647 +0.368095 -0.016227 -0.929647 +0.547210 -0.014608 -0.836868 +0.547210 -0.014608 -0.836868 +0.368095 -0.016227 -0.929647 +0.630298 -0.013549 -0.776235 +0.547210 -0.014608 -0.836868 +0.547210 -0.014608 -0.836868 +0.630298 -0.013549 -0.776235 +0.630298 -0.013549 -0.776235 +0.547210 -0.014608 -0.836868 +0.707107 -0.012341 -0.706999 +0.630298 -0.013549 -0.776235 +0.630298 -0.013549 -0.776235 +0.707107 -0.012341 -0.706999 +0.707107 -0.012341 -0.706999 +0.630298 -0.013549 -0.776235 +0.776353 -0.011000 -0.630202 +0.707107 -0.012341 -0.706999 +0.707107 -0.012341 -0.706999 +0.776353 -0.011000 -0.630202 +0.776353 -0.011000 -0.630202 +0.707107 -0.012341 -0.706999 +0.836995 -0.009550 -0.547126 +0.776353 -0.011000 -0.630202 +0.776353 -0.011000 -0.630202 +0.836995 -0.009550 -0.547126 +0.836995 -0.009550 -0.547126 +0.776353 -0.011000 -0.630202 +0.929788 -0.006424 -0.368039 +0.836995 -0.009550 -0.547126 +0.836995 -0.009550 -0.547126 +0.929788 -0.006424 -0.368039 +0.929788 -0.006424 -0.368039 +0.836995 -0.009550 -0.547126 +0.983305 -0.003176 -0.181935 +0.929788 -0.006424 -0.368039 +0.929788 -0.006424 -0.368039 +0.983305 -0.003176 -0.181935 +0.983305 -0.003176 -0.181935 +0.929788 -0.006424 -0.368039 +1.000000 0.000000 0.000000 +0.983305 -0.003176 -0.181935 +0.983305 -0.003176 -0.181935 +0.000000 -0.017452 0.999848 +0.181963 -0.017161 0.983156 +0.000000 -0.017452 0.999848 +1.000000 0.000000 0.000000 +0.983305 -0.003176 0.181935 +1.000000 0.000000 0.000000 +0.983305 -0.003176 0.181935 +0.983305 -0.003176 0.181935 +1.000000 0.000000 0.000000 +0.983305 -0.003176 0.181935 +0.929788 -0.006424 0.368039 +0.983305 -0.003176 0.181935 +0.929788 -0.006424 0.368039 +0.929788 -0.006424 0.368039 +0.983305 -0.003176 0.181935 +0.929788 -0.006424 0.368039 +0.836995 -0.009550 0.547126 +0.929788 -0.006424 0.368039 +0.836995 -0.009550 0.547126 +0.836995 -0.009550 0.547126 +0.929788 -0.006424 0.368039 +0.836995 -0.009550 0.547126 +0.776353 -0.011000 0.630202 +0.836995 -0.009550 0.547126 +0.776353 -0.011000 0.630202 +0.776353 -0.011000 0.630202 +0.836995 -0.009550 0.547126 +0.776353 -0.011000 0.630202 +0.707107 -0.012341 0.706999 +0.776353 -0.011000 0.630202 +0.707107 -0.012341 0.706999 +0.707107 -0.012341 0.706999 +0.776353 -0.011000 0.630202 +0.707107 -0.012341 0.706999 +0.630298 -0.013549 0.776235 +0.707107 -0.012341 0.706999 +0.630298 -0.013549 0.776235 +0.630298 -0.013549 0.776235 +0.707107 -0.012341 0.706999 +0.630298 -0.013549 0.776235 +0.547210 -0.014608 0.836868 +0.630298 -0.013549 0.776235 +0.547210 -0.014608 0.836868 +0.547210 -0.014608 0.836868 +0.630298 -0.013549 0.776235 +0.547210 -0.014608 0.836868 +0.368095 -0.016227 0.929647 +0.547210 -0.014608 0.836868 +0.368095 -0.016227 0.929647 +0.368095 -0.016227 0.929647 +0.547210 -0.014608 0.836868 +0.368095 -0.016227 0.929647 +0.181963 -0.017161 0.983156 +0.368095 -0.016227 0.929647 +0.181963 -0.017161 0.983156 +0.181963 -0.017161 0.983156 +0.368095 -0.016227 0.929647 +0.181963 -0.017161 0.983156 +0.000000 -0.017452 0.999848 +0.181963 -0.017161 0.983156 +-0.181906 -0.020335 -0.983106 +0.000000 -0.017452 -0.999848 +0.000000 -0.017452 -0.999848 +-0.999848 -0.017452 0.000000 +-0.983106 -0.020335 -0.181906 +-0.999848 -0.017452 0.000000 +-0.983106 -0.020335 -0.181906 +-0.983106 -0.020335 -0.181906 +-0.999848 -0.017452 0.000000 +-0.983106 -0.020335 -0.181906 +-0.929559 -0.022649 -0.367977 +-0.983106 -0.020335 -0.181906 +-0.929559 -0.022649 -0.367977 +-0.929559 -0.022649 -0.367977 +-0.983106 -0.020335 -0.181906 +-0.929559 -0.022649 -0.367977 +-0.836761 -0.024154 -0.547036 +-0.929559 -0.022649 -0.367977 +-0.836761 -0.024154 -0.547036 +-0.836761 -0.024154 -0.547036 +-0.929559 -0.022649 -0.367977 +-0.836761 -0.024154 -0.547036 +-0.776125 -0.024546 -0.630101 +-0.836761 -0.024154 -0.547036 +-0.776125 -0.024546 -0.630101 +-0.776125 -0.024546 -0.630101 +-0.836761 -0.024154 -0.547036 +-0.776125 -0.024546 -0.630101 +-0.706891 -0.024678 -0.706891 +-0.776125 -0.024546 -0.630101 +-0.706891 -0.024678 -0.706891 +-0.706891 -0.024678 -0.706891 +-0.776125 -0.024546 -0.630101 +-0.630101 -0.024546 -0.776125 +-0.706891 -0.024678 -0.706891 +-0.706891 -0.024678 -0.706891 +-0.630101 -0.024546 -0.776125 +-0.630101 -0.024546 -0.776125 +-0.706891 -0.024678 -0.706891 +-0.547036 -0.024154 -0.836761 +-0.630101 -0.024546 -0.776125 +-0.630101 -0.024546 -0.776125 +-0.547036 -0.024154 -0.836761 +-0.547036 -0.024154 -0.836761 +-0.630101 -0.024546 -0.776125 +-0.367977 -0.022649 -0.929559 +-0.547036 -0.024154 -0.836761 +-0.547036 -0.024154 -0.836761 +-0.367977 -0.022649 -0.929559 +-0.367977 -0.022649 -0.929559 +-0.547036 -0.024154 -0.836761 +-0.181906 -0.020335 -0.983106 +-0.367977 -0.022649 -0.929559 +-0.367977 -0.022649 -0.929559 +-0.181906 -0.020335 -0.983106 +-0.181906 -0.020335 -0.983106 +-0.367977 -0.022649 -0.929559 +0.000000 -0.017452 -0.999848 +-0.181906 -0.020335 -0.983106 +-0.181906 -0.020335 -0.983106 +-0.983106 -0.020335 0.181906 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +0.000000 -0.017452 0.999848 +-0.181906 -0.020335 0.983106 +0.000000 -0.017452 0.999848 +-0.181906 -0.020335 0.983106 +-0.181906 -0.020335 0.983106 +0.000000 -0.017452 0.999848 +-0.181906 -0.020335 0.983106 +-0.367977 -0.022649 0.929559 +-0.181906 -0.020335 0.983106 +-0.367977 -0.022649 0.929559 +-0.367977 -0.022649 0.929559 +-0.181906 -0.020335 0.983106 +-0.367977 -0.022649 0.929559 +-0.547036 -0.024154 0.836761 +-0.367977 -0.022649 0.929559 +-0.547036 -0.024154 0.836761 +-0.547036 -0.024154 0.836761 +-0.367977 -0.022649 0.929559 +-0.547036 -0.024154 0.836761 +-0.630101 -0.024546 0.776125 +-0.547036 -0.024154 0.836761 +-0.630101 -0.024546 0.776125 +-0.630101 -0.024546 0.776125 +-0.547036 -0.024154 0.836761 +-0.630101 -0.024546 0.776125 +-0.706891 -0.024678 0.706891 +-0.630101 -0.024546 0.776125 +-0.706891 -0.024678 0.706891 +-0.706891 -0.024678 0.706891 +-0.630101 -0.024546 0.776125 +-0.776125 -0.024546 0.630101 +-0.706891 -0.024678 0.706891 +-0.706891 -0.024678 0.706891 +-0.776125 -0.024546 0.630101 +-0.776125 -0.024546 0.630101 +-0.706891 -0.024678 0.706891 +-0.836761 -0.024154 0.547036 +-0.776125 -0.024546 0.630101 +-0.776125 -0.024546 0.630101 +-0.836761 -0.024154 0.547036 +-0.836761 -0.024154 0.547036 +-0.776125 -0.024546 0.630101 +-0.929559 -0.022649 0.367977 +-0.836761 -0.024154 0.547036 +-0.836761 -0.024154 0.547036 +-0.929559 -0.022649 0.367977 +-0.929559 -0.022649 0.367977 +-0.836761 -0.024154 0.547036 +-0.983106 -0.020335 0.181906 +-0.929559 -0.022649 0.367977 +-0.929559 -0.022649 0.367977 +-0.983106 -0.020335 0.181906 +-0.983106 -0.020335 0.181906 +-0.929559 -0.022649 0.367977 +-0.999848 -0.017452 0.000000 +-0.983106 -0.020335 0.181906 +-0.983106 -0.020335 0.181906 +-0.983106 -0.020335 0.181906 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +0.000000 -0.017452 0.999848 +-0.181906 -0.020335 0.983106 +0.000000 -0.017452 0.999848 +-0.181906 -0.020335 0.983106 +-0.181906 -0.020335 0.983106 +0.000000 -0.017452 0.999848 +-0.181906 -0.020335 0.983106 +-0.367977 -0.022649 0.929559 +-0.181906 -0.020335 0.983106 +-0.367977 -0.022649 0.929559 +-0.367977 -0.022649 0.929559 +-0.181906 -0.020335 0.983106 +-0.367977 -0.022649 0.929559 +-0.547036 -0.024154 0.836761 +-0.367977 -0.022649 0.929559 +-0.547036 -0.024154 0.836761 +-0.547036 -0.024154 0.836761 +-0.367977 -0.022649 0.929559 +-0.547036 -0.024154 0.836761 +-0.630101 -0.024546 0.776125 +-0.547036 -0.024154 0.836761 +-0.630101 -0.024546 0.776125 +-0.630101 -0.024546 0.776125 +-0.547036 -0.024154 0.836761 +-0.630101 -0.024546 0.776125 +-0.706891 -0.024678 0.706891 +-0.630101 -0.024546 0.776125 +-0.706891 -0.024678 0.706891 +-0.706891 -0.024678 0.706891 +-0.630101 -0.024546 0.776125 +-0.776125 -0.024546 0.630101 +-0.706891 -0.024678 0.706891 +-0.706891 -0.024678 0.706891 +-0.776125 -0.024546 0.630101 +-0.776125 -0.024546 0.630101 +-0.706891 -0.024678 0.706891 +-0.836761 -0.024154 0.547036 +-0.776125 -0.024546 0.630101 +-0.776125 -0.024546 0.630101 +-0.836761 -0.024154 0.547036 +-0.836761 -0.024154 0.547036 +-0.776125 -0.024546 0.630101 +-0.929559 -0.022649 0.367977 +-0.836761 -0.024154 0.547036 +-0.836761 -0.024154 0.547036 +-0.929559 -0.022649 0.367977 +-0.929559 -0.022649 0.367977 +-0.836761 -0.024154 0.547036 +-0.983106 -0.020335 0.181906 +-0.929559 -0.022649 0.367977 +-0.929559 -0.022649 0.367977 +-0.983106 -0.020335 0.181906 +-0.983106 -0.020335 0.181906 +-0.929559 -0.022649 0.367977 +-0.999848 -0.017452 0.000000 +-0.983106 -0.020335 0.181906 +-0.983106 -0.020335 0.181906 +-0.181906 -0.020335 -0.983106 +0.000000 -0.017452 -0.999848 +0.000000 -0.017452 -0.999848 +-0.999848 -0.017452 0.000000 +-0.983106 -0.020335 -0.181906 +-0.999848 -0.017452 0.000000 +-0.983106 -0.020335 -0.181906 +-0.983106 -0.020335 -0.181906 +-0.999848 -0.017452 0.000000 +-0.983106 -0.020335 -0.181906 +-0.929559 -0.022649 -0.367977 +-0.983106 -0.020335 -0.181906 +-0.929559 -0.022649 -0.367977 +-0.929559 -0.022649 -0.367977 +-0.983106 -0.020335 -0.181906 +-0.929559 -0.022649 -0.367977 +-0.836761 -0.024154 -0.547036 +-0.929559 -0.022649 -0.367977 +-0.836761 -0.024154 -0.547036 +-0.836761 -0.024154 -0.547036 +-0.929559 -0.022649 -0.367977 +-0.836761 -0.024154 -0.547036 +-0.776125 -0.024546 -0.630101 +-0.836761 -0.024154 -0.547036 +-0.776125 -0.024546 -0.630101 +-0.776125 -0.024546 -0.630101 +-0.836761 -0.024154 -0.547036 +-0.776125 -0.024546 -0.630101 +-0.706891 -0.024678 -0.706891 +-0.776125 -0.024546 -0.630101 +-0.706891 -0.024678 -0.706891 +-0.706891 -0.024678 -0.706891 +-0.776125 -0.024546 -0.630101 +-0.630101 -0.024546 -0.776125 +-0.706891 -0.024678 -0.706891 +-0.706891 -0.024678 -0.706891 +-0.630101 -0.024546 -0.776125 +-0.630101 -0.024546 -0.776125 +-0.706891 -0.024678 -0.706891 +-0.547036 -0.024154 -0.836761 +-0.630101 -0.024546 -0.776125 +-0.630101 -0.024546 -0.776125 +-0.547036 -0.024154 -0.836761 +-0.547036 -0.024154 -0.836761 +-0.630101 -0.024546 -0.776125 +-0.367977 -0.022649 -0.929559 +-0.547036 -0.024154 -0.836761 +-0.547036 -0.024154 -0.836761 +-0.367977 -0.022649 -0.929559 +-0.367977 -0.022649 -0.929559 +-0.547036 -0.024154 -0.836761 +-0.181906 -0.020335 -0.983106 +-0.367977 -0.022649 -0.929559 +-0.367977 -0.022649 -0.929559 +-0.181906 -0.020335 -0.983106 +-0.181906 -0.020335 -0.983106 +-0.367977 -0.022649 -0.929559 +0.000000 -0.017452 -0.999848 +-0.181906 -0.020335 -0.983106 +-0.181906 -0.020335 -0.983106 +-0.181906 -0.020335 -0.983106 +0.000000 -0.017452 -0.999848 +0.000000 -0.017452 -0.999848 +-0.999848 -0.017452 0.000000 +-0.983106 -0.020335 -0.181906 +-0.999848 -0.017452 0.000000 +-0.983106 -0.020335 -0.181906 +-0.983106 -0.020335 -0.181906 +-0.999848 -0.017452 0.000000 +-0.983106 -0.020335 -0.181906 +-0.929559 -0.022649 -0.367977 +-0.983106 -0.020335 -0.181906 +-0.929559 -0.022649 -0.367977 +-0.929559 -0.022649 -0.367977 +-0.983106 -0.020335 -0.181906 +-0.929559 -0.022649 -0.367977 +-0.836761 -0.024154 -0.547036 +-0.929559 -0.022649 -0.367977 +-0.836761 -0.024154 -0.547036 +-0.836761 -0.024154 -0.547036 +-0.929559 -0.022649 -0.367977 +-0.836761 -0.024154 -0.547036 +-0.776125 -0.024546 -0.630101 +-0.836761 -0.024154 -0.547036 +-0.776125 -0.024546 -0.630101 +-0.776125 -0.024546 -0.630101 +-0.836761 -0.024154 -0.547036 +-0.776125 -0.024546 -0.630101 +-0.706891 -0.024678 -0.706891 +-0.776125 -0.024546 -0.630101 +-0.706891 -0.024678 -0.706891 +-0.706891 -0.024678 -0.706891 +-0.776125 -0.024546 -0.630101 +-0.630101 -0.024546 -0.776125 +-0.706891 -0.024678 -0.706891 +-0.706891 -0.024678 -0.706891 +-0.630101 -0.024546 -0.776125 +-0.630101 -0.024546 -0.776125 +-0.706891 -0.024678 -0.706891 +-0.547036 -0.024154 -0.836761 +-0.630101 -0.024546 -0.776125 +-0.630101 -0.024546 -0.776125 +-0.547036 -0.024154 -0.836761 +-0.547036 -0.024154 -0.836761 +-0.630101 -0.024546 -0.776125 +-0.367977 -0.022649 -0.929559 +-0.547036 -0.024154 -0.836761 +-0.547036 -0.024154 -0.836761 +-0.367977 -0.022649 -0.929559 +-0.367977 -0.022649 -0.929559 +-0.547036 -0.024154 -0.836761 +-0.181906 -0.020335 -0.983106 +-0.367977 -0.022649 -0.929559 +-0.367977 -0.022649 -0.929559 +-0.181906 -0.020335 -0.983106 +-0.181906 -0.020335 -0.983106 +-0.367977 -0.022649 -0.929559 +0.000000 -0.017452 -0.999848 +-0.181906 -0.020335 -0.983106 +-0.181906 -0.020335 -0.983106 +0.983106 -0.020335 -0.181906 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.000000 -0.017452 -0.999848 +0.181906 -0.020335 -0.983106 +0.000000 -0.017452 -0.999848 +0.181906 -0.020335 -0.983106 +0.181906 -0.020335 -0.983106 +0.000000 -0.017452 -0.999848 +0.181906 -0.020335 -0.983106 +0.367977 -0.022649 -0.929559 +0.181906 -0.020335 -0.983106 +0.367977 -0.022649 -0.929559 +0.367977 -0.022649 -0.929559 +0.181906 -0.020335 -0.983106 +0.367977 -0.022649 -0.929559 +0.547036 -0.024154 -0.836761 +0.367977 -0.022649 -0.929559 +0.547036 -0.024154 -0.836761 +0.547036 -0.024154 -0.836761 +0.367977 -0.022649 -0.929559 +0.547036 -0.024154 -0.836761 +0.630101 -0.024546 -0.776125 +0.547036 -0.024154 -0.836761 +0.630101 -0.024546 -0.776125 +0.630101 -0.024546 -0.776125 +0.547036 -0.024154 -0.836761 +0.630101 -0.024546 -0.776125 +0.706891 -0.024678 -0.706891 +0.630101 -0.024546 -0.776125 +0.706891 -0.024678 -0.706891 +0.706891 -0.024678 -0.706891 +0.630101 -0.024546 -0.776125 +0.776125 -0.024546 -0.630101 +0.706891 -0.024678 -0.706891 +0.706891 -0.024678 -0.706891 +0.776125 -0.024546 -0.630101 +0.776125 -0.024546 -0.630101 +0.706891 -0.024678 -0.706891 +0.836761 -0.024154 -0.547036 +0.776125 -0.024546 -0.630101 +0.776125 -0.024546 -0.630101 +0.836761 -0.024154 -0.547036 +0.836761 -0.024154 -0.547036 +0.776125 -0.024546 -0.630101 +0.929559 -0.022649 -0.367977 +0.836761 -0.024154 -0.547036 +0.836761 -0.024154 -0.547036 +0.929559 -0.022649 -0.367977 +0.929559 -0.022649 -0.367977 +0.836761 -0.024154 -0.547036 +0.983106 -0.020335 -0.181906 +0.929559 -0.022649 -0.367977 +0.929559 -0.022649 -0.367977 +0.983106 -0.020335 -0.181906 +0.983106 -0.020335 -0.181906 +0.929559 -0.022649 -0.367977 +0.999848 -0.017452 0.000000 +0.983106 -0.020335 -0.181906 +0.983106 -0.020335 -0.181906 +0.983106 -0.020335 -0.181906 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.000000 -0.017452 -0.999848 +0.181906 -0.020335 -0.983106 +0.000000 -0.017452 -0.999848 +0.181906 -0.020335 -0.983106 +0.181906 -0.020335 -0.983106 +0.000000 -0.017452 -0.999848 +0.181906 -0.020335 -0.983106 +0.367977 -0.022649 -0.929559 +0.181906 -0.020335 -0.983106 +0.367977 -0.022649 -0.929559 +0.367977 -0.022649 -0.929559 +0.181906 -0.020335 -0.983106 +0.367977 -0.022649 -0.929559 +0.547036 -0.024154 -0.836761 +0.367977 -0.022649 -0.929559 +0.547036 -0.024154 -0.836761 +0.547036 -0.024154 -0.836761 +0.367977 -0.022649 -0.929559 +0.547036 -0.024154 -0.836761 +0.630101 -0.024546 -0.776125 +0.547036 -0.024154 -0.836761 +0.630101 -0.024546 -0.776125 +0.630101 -0.024546 -0.776125 +0.547036 -0.024154 -0.836761 +0.630101 -0.024546 -0.776125 +0.706891 -0.024678 -0.706891 +0.630101 -0.024546 -0.776125 +0.706891 -0.024678 -0.706891 +0.706891 -0.024678 -0.706891 +0.630101 -0.024546 -0.776125 +0.776125 -0.024546 -0.630101 +0.706891 -0.024678 -0.706891 +0.706891 -0.024678 -0.706891 +0.776125 -0.024546 -0.630101 +0.776125 -0.024546 -0.630101 +0.706891 -0.024678 -0.706891 +0.836761 -0.024154 -0.547036 +0.776125 -0.024546 -0.630101 +0.776125 -0.024546 -0.630101 +0.836761 -0.024154 -0.547036 +0.836761 -0.024154 -0.547036 +0.776125 -0.024546 -0.630101 +0.929559 -0.022649 -0.367977 +0.836761 -0.024154 -0.547036 +0.836761 -0.024154 -0.547036 +0.929559 -0.022649 -0.367977 +0.929559 -0.022649 -0.367977 +0.836761 -0.024154 -0.547036 +0.983106 -0.020335 -0.181906 +0.929559 -0.022649 -0.367977 +0.929559 -0.022649 -0.367977 +0.983106 -0.020335 -0.181906 +0.983106 -0.020335 -0.181906 +0.929559 -0.022649 -0.367977 +0.999848 -0.017452 0.000000 +0.983106 -0.020335 -0.181906 +0.983106 -0.020335 -0.181906 +0.983106 -0.020335 -0.181906 +0.999848 -0.017452 0.000000 +0.999848 -0.017452 0.000000 +0.000000 -0.017452 -0.999848 +0.181906 -0.020335 -0.983106 +0.000000 -0.017452 -0.999848 +0.181906 -0.020335 -0.983106 +0.181906 -0.020335 -0.983106 +0.000000 -0.017452 -0.999848 +0.181906 -0.020335 -0.983106 +0.367977 -0.022649 -0.929559 +0.181906 -0.020335 -0.983106 +0.367977 -0.022649 -0.929559 +0.367977 -0.022649 -0.929559 +0.181906 -0.020335 -0.983106 +0.367977 -0.022649 -0.929559 +0.547036 -0.024154 -0.836761 +0.367977 -0.022649 -0.929559 +0.547036 -0.024154 -0.836761 +0.547036 -0.024154 -0.836761 +0.367977 -0.022649 -0.929559 +0.547036 -0.024154 -0.836761 +0.630101 -0.024546 -0.776125 +0.547036 -0.024154 -0.836761 +0.630101 -0.024546 -0.776125 +0.630101 -0.024546 -0.776125 +0.547036 -0.024154 -0.836761 +0.630101 -0.024546 -0.776125 +0.706891 -0.024678 -0.706891 +0.630101 -0.024546 -0.776125 +0.706891 -0.024678 -0.706891 +0.706891 -0.024678 -0.706891 +0.630101 -0.024546 -0.776125 +0.776125 -0.024546 -0.630101 +0.706891 -0.024678 -0.706891 +0.706891 -0.024678 -0.706891 +0.776125 -0.024546 -0.630101 +0.776125 -0.024546 -0.630101 +0.706891 -0.024678 -0.706891 +0.836761 -0.024154 -0.547036 +0.776125 -0.024546 -0.630101 +0.776125 -0.024546 -0.630101 +0.836761 -0.024154 -0.547036 +0.836761 -0.024154 -0.547036 +0.776125 -0.024546 -0.630101 +0.929559 -0.022649 -0.367977 +0.836761 -0.024154 -0.547036 +0.836761 -0.024154 -0.547036 +0.929559 -0.022649 -0.367977 +0.929559 -0.022649 -0.367977 +0.836761 -0.024154 -0.547036 +0.983106 -0.020335 -0.181906 +0.929559 -0.022649 -0.367977 +0.929559 -0.022649 -0.367977 +0.983106 -0.020335 -0.181906 +0.983106 -0.020335 -0.181906 +0.929559 -0.022649 -0.367977 +0.999848 -0.017452 0.000000 +0.983106 -0.020335 -0.181906 +0.983106 -0.020335 -0.181906 +0.181906 -0.020335 0.983106 +0.000000 -0.017452 0.999848 +0.000000 -0.017452 0.999848 +0.999848 -0.017452 0.000000 +0.983106 -0.020335 0.181906 +0.999848 -0.017452 0.000000 +0.983106 -0.020335 0.181906 +0.983106 -0.020335 0.181906 +0.999848 -0.017452 0.000000 +0.983106 -0.020335 0.181906 +0.929559 -0.022649 0.367977 +0.983106 -0.020335 0.181906 +0.929559 -0.022649 0.367977 +0.929559 -0.022649 0.367977 +0.983106 -0.020335 0.181906 +0.929559 -0.022649 0.367977 +0.836761 -0.024154 0.547036 +0.929559 -0.022649 0.367977 +0.836761 -0.024154 0.547036 +0.836761 -0.024154 0.547036 +0.929559 -0.022649 0.367977 +0.836761 -0.024154 0.547036 +0.776125 -0.024546 0.630101 +0.836761 -0.024154 0.547036 +0.776125 -0.024546 0.630101 +0.776125 -0.024546 0.630101 +0.836761 -0.024154 0.547036 +0.776125 -0.024546 0.630101 +0.706891 -0.024678 0.706891 +0.776125 -0.024546 0.630101 +0.706891 -0.024678 0.706891 +0.706891 -0.024678 0.706891 +0.776125 -0.024546 0.630101 +0.630101 -0.024546 0.776125 +0.706891 -0.024678 0.706891 +0.706891 -0.024678 0.706891 +0.630101 -0.024546 0.776125 +0.630101 -0.024546 0.776125 +0.706891 -0.024678 0.706891 +0.547036 -0.024154 0.836761 +0.630101 -0.024546 0.776125 +0.630101 -0.024546 0.776125 +0.547036 -0.024154 0.836761 +0.547036 -0.024154 0.836761 +0.630101 -0.024546 0.776125 +0.367977 -0.022649 0.929559 +0.547036 -0.024154 0.836761 +0.547036 -0.024154 0.836761 +0.367977 -0.022649 0.929559 +0.367977 -0.022649 0.929559 +0.547036 -0.024154 0.836761 +0.181906 -0.020335 0.983106 +0.367977 -0.022649 0.929559 +0.367977 -0.022649 0.929559 +0.181906 -0.020335 0.983106 +0.181906 -0.020335 0.983106 +0.367977 -0.022649 0.929559 +0.000000 -0.017452 0.999848 +0.181906 -0.020335 0.983106 +0.181906 -0.020335 0.983106 +0.181906 -0.020335 0.983106 +0.000000 -0.017452 0.999848 +0.000000 -0.017452 0.999848 +0.999848 -0.017452 0.000000 +0.983106 -0.020335 0.181906 +0.999848 -0.017452 0.000000 +0.983106 -0.020335 0.181906 +0.983106 -0.020335 0.181906 +0.999848 -0.017452 0.000000 +0.983106 -0.020335 0.181906 +0.929559 -0.022649 0.367977 +0.983106 -0.020335 0.181906 +0.929559 -0.022649 0.367977 +0.929559 -0.022649 0.367977 +0.983106 -0.020335 0.181906 +0.929559 -0.022649 0.367977 +0.836761 -0.024154 0.547036 +0.929559 -0.022649 0.367977 +0.836761 -0.024154 0.547036 +0.836761 -0.024154 0.547036 +0.929559 -0.022649 0.367977 +0.836761 -0.024154 0.547036 +0.776125 -0.024546 0.630101 +0.836761 -0.024154 0.547036 +0.776125 -0.024546 0.630101 +0.776125 -0.024546 0.630101 +0.836761 -0.024154 0.547036 +0.776125 -0.024546 0.630101 +0.706891 -0.024678 0.706891 +0.776125 -0.024546 0.630101 +0.706891 -0.024678 0.706891 +0.706891 -0.024678 0.706891 +0.776125 -0.024546 0.630101 +0.630101 -0.024546 0.776125 +0.706891 -0.024678 0.706891 +0.706891 -0.024678 0.706891 +0.630101 -0.024546 0.776125 +0.630101 -0.024546 0.776125 +0.706891 -0.024678 0.706891 +0.547036 -0.024154 0.836761 +0.630101 -0.024546 0.776125 +0.630101 -0.024546 0.776125 +0.547036 -0.024154 0.836761 +0.547036 -0.024154 0.836761 +0.630101 -0.024546 0.776125 +0.367977 -0.022649 0.929559 +0.547036 -0.024154 0.836761 +0.547036 -0.024154 0.836761 +0.367977 -0.022649 0.929559 +0.367977 -0.022649 0.929559 +0.547036 -0.024154 0.836761 +0.181906 -0.020335 0.983106 +0.367977 -0.022649 0.929559 +0.367977 -0.022649 0.929559 +0.181906 -0.020335 0.983106 +0.181906 -0.020335 0.983106 +0.367977 -0.022649 0.929559 +0.000000 -0.017452 0.999848 +0.181906 -0.020335 0.983106 +0.181906 -0.020335 0.983106 +0.181906 -0.020335 0.983106 +0.000000 -0.017452 0.999848 +0.000000 -0.017452 0.999848 +0.999848 -0.017452 0.000000 +0.983106 -0.020335 0.181906 +0.999848 -0.017452 0.000000 +0.983106 -0.020335 0.181906 +0.983106 -0.020335 0.181906 +0.999848 -0.017452 0.000000 +0.983106 -0.020335 0.181906 +0.929559 -0.022649 0.367977 +0.983106 -0.020335 0.181906 +0.929559 -0.022649 0.367977 +0.929559 -0.022649 0.367977 +0.983106 -0.020335 0.181906 +0.929559 -0.022649 0.367977 +0.836761 -0.024154 0.547036 +0.929559 -0.022649 0.367977 +0.836761 -0.024154 0.547036 +0.836761 -0.024154 0.547036 +0.929559 -0.022649 0.367977 +0.836761 -0.024154 0.547036 +0.776125 -0.024546 0.630101 +0.836761 -0.024154 0.547036 +0.776125 -0.024546 0.630101 +0.776125 -0.024546 0.630101 +0.836761 -0.024154 0.547036 +0.776125 -0.024546 0.630101 +0.706891 -0.024678 0.706891 +0.776125 -0.024546 0.630101 +0.706891 -0.024678 0.706891 +0.706891 -0.024678 0.706891 +0.776125 -0.024546 0.630101 +0.630101 -0.024546 0.776125 +0.706891 -0.024678 0.706891 +0.706891 -0.024678 0.706891 +0.630101 -0.024546 0.776125 +0.630101 -0.024546 0.776125 +0.706891 -0.024678 0.706891 +0.547036 -0.024154 0.836761 +0.630101 -0.024546 0.776125 +0.630101 -0.024546 0.776125 +0.547036 -0.024154 0.836761 +0.547036 -0.024154 0.836761 +0.630101 -0.024546 0.776125 +0.367977 -0.022649 0.929559 +0.547036 -0.024154 0.836761 +0.547036 -0.024154 0.836761 +0.367977 -0.022649 0.929559 +0.367977 -0.022649 0.929559 +0.547036 -0.024154 0.836761 +0.181906 -0.020335 0.983106 +0.367977 -0.022649 0.929559 +0.367977 -0.022649 0.929559 +0.181906 -0.020335 0.983106 +0.181906 -0.020335 0.983106 +0.367977 -0.022649 0.929559 +0.000000 -0.017452 0.999848 +0.181906 -0.020335 0.983106 +0.181906 -0.020335 0.983106 +-0.181906 -0.020335 -0.983106 +0.000000 -0.017452 -0.999848 +0.000000 -0.017452 -0.999848 +-0.999848 -0.017452 0.000000 +-0.983106 -0.020335 -0.181906 +-0.999848 -0.017452 0.000000 +-0.983106 -0.020335 -0.181906 +-0.983106 -0.020335 -0.181906 +-0.999848 -0.017452 0.000000 +-0.983106 -0.020335 -0.181906 +-0.929559 -0.022649 -0.367977 +-0.983106 -0.020335 -0.181906 +-0.929559 -0.022649 -0.367977 +-0.929559 -0.022649 -0.367977 +-0.983106 -0.020335 -0.181906 +-0.929559 -0.022649 -0.367977 +-0.836761 -0.024154 -0.547036 +-0.929559 -0.022649 -0.367977 +-0.836761 -0.024154 -0.547036 +-0.836761 -0.024154 -0.547036 +-0.929559 -0.022649 -0.367977 +-0.836761 -0.024154 -0.547036 +-0.776125 -0.024546 -0.630101 +-0.836761 -0.024154 -0.547036 +-0.776125 -0.024546 -0.630101 +-0.776125 -0.024546 -0.630101 +-0.836761 -0.024154 -0.547036 +-0.776125 -0.024546 -0.630101 +-0.706891 -0.024678 -0.706891 +-0.776125 -0.024546 -0.630101 +-0.706891 -0.024678 -0.706891 +-0.706891 -0.024678 -0.706891 +-0.776125 -0.024546 -0.630101 +-0.630101 -0.024546 -0.776125 +-0.706891 -0.024678 -0.706891 +-0.706891 -0.024678 -0.706891 +-0.630101 -0.024546 -0.776125 +-0.630101 -0.024546 -0.776125 +-0.706891 -0.024678 -0.706891 +-0.547036 -0.024154 -0.836761 +-0.630101 -0.024546 -0.776125 +-0.630101 -0.024546 -0.776125 +-0.547036 -0.024154 -0.836761 +-0.547036 -0.024154 -0.836761 +-0.630101 -0.024546 -0.776125 +-0.367977 -0.022649 -0.929559 +-0.547036 -0.024154 -0.836761 +-0.547036 -0.024154 -0.836761 +-0.367977 -0.022649 -0.929559 +-0.367977 -0.022649 -0.929559 +-0.547036 -0.024154 -0.836761 +-0.181906 -0.020335 -0.983106 +-0.367977 -0.022649 -0.929559 +-0.367977 -0.022649 -0.929559 +-0.181906 -0.020335 -0.983106 +-0.181906 -0.020335 -0.983106 +-0.367977 -0.022649 -0.929559 +0.000000 -0.017452 -0.999848 +-0.181906 -0.020335 -0.983106 +-0.181906 -0.020335 -0.983106 +-0.983106 -0.020335 0.181906 +-0.999848 -0.017452 0.000000 +-0.999848 -0.017452 0.000000 +0.000000 -0.017452 0.999848 +-0.181906 -0.020335 0.983106 +0.000000 -0.017452 0.999848 +-0.181906 -0.020335 0.983106 +-0.181906 -0.020335 0.983106 +0.000000 -0.017452 0.999848 +-0.181906 -0.020335 0.983106 +-0.367977 -0.022649 0.929559 +-0.181906 -0.020335 0.983106 +-0.367977 -0.022649 0.929559 +-0.367977 -0.022649 0.929559 +-0.181906 -0.020335 0.983106 +-0.367977 -0.022649 0.929559 +-0.547036 -0.024154 0.836761 +-0.367977 -0.022649 0.929559 +-0.547036 -0.024154 0.836761 +-0.547036 -0.024154 0.836761 +-0.367977 -0.022649 0.929559 +-0.547036 -0.024154 0.836761 +-0.630101 -0.024546 0.776125 +-0.547036 -0.024154 0.836761 +-0.630101 -0.024546 0.776125 +-0.630101 -0.024546 0.776125 +-0.547036 -0.024154 0.836761 +-0.630101 -0.024546 0.776125 +-0.706891 -0.024678 0.706891 +-0.630101 -0.024546 0.776125 +-0.706891 -0.024678 0.706891 +-0.706891 -0.024678 0.706891 +-0.630101 -0.024546 0.776125 +-0.776125 -0.024546 0.630101 +-0.706891 -0.024678 0.706891 +-0.706891 -0.024678 0.706891 +-0.776125 -0.024546 0.630101 +-0.776125 -0.024546 0.630101 +-0.706891 -0.024678 0.706891 +-0.836761 -0.024154 0.547036 +-0.776125 -0.024546 0.630101 +-0.776125 -0.024546 0.630101 +-0.836761 -0.024154 0.547036 +-0.836761 -0.024154 0.547036 +-0.776125 -0.024546 0.630101 +-0.929559 -0.022649 0.367977 +-0.836761 -0.024154 0.547036 +-0.836761 -0.024154 0.547036 +-0.929559 -0.022649 0.367977 +-0.929559 -0.022649 0.367977 +-0.836761 -0.024154 0.547036 +-0.983106 -0.020335 0.181906 +-0.929559 -0.022649 0.367977 +-0.929559 -0.022649 0.367977 +-0.983106 -0.020335 0.181906 +-0.983106 -0.020335 0.181906 +-0.929559 -0.022649 0.367977 +-0.999848 -0.017452 0.000000 +-0.983106 -0.020335 0.181906 +-0.983106 -0.020335 0.181906 +0.000000 -0.700909 -0.713250 +0.000000 -0.700909 -0.713250 +0.000000 -0.700909 -0.713250 +0.000000 -0.700909 -0.713250 +0.000000 -0.700909 -0.713250 +0.000000 -0.700909 -0.713250 +0.686037 0.143623 -0.713250 +0.700909 0.000000 -0.713250 +0.700909 0.000000 -0.713250 +0.000000 0.700909 -0.713250 +0.143623 0.686037 -0.713250 +0.000000 0.700909 -0.713250 +0.143623 0.686037 -0.713250 +0.143623 0.686037 -0.713250 +0.000000 0.700909 -0.713250 +0.143623 0.686037 -0.713250 +0.278385 0.643254 -0.713250 +0.143623 0.686037 -0.713250 +0.278385 0.643254 -0.713250 +0.278385 0.643254 -0.713250 +0.143623 0.686037 -0.713250 +0.278385 0.643254 -0.713250 +0.397159 0.577528 -0.713250 +0.278385 0.643254 -0.713250 +0.397159 0.577528 -0.713250 +0.397159 0.577528 -0.713250 +0.278385 0.643254 -0.713250 +0.397159 0.577528 -0.713250 +0.495618 0.495618 -0.713250 +0.397159 0.577528 -0.713250 +0.495618 0.495618 -0.713250 +0.495618 0.495618 -0.713250 +0.397159 0.577528 -0.713250 +0.577528 0.397159 -0.713250 +0.495618 0.495618 -0.713250 +0.495618 0.495618 -0.713250 +0.577528 0.397159 -0.713250 +0.577528 0.397159 -0.713250 +0.495618 0.495618 -0.713250 +0.643254 0.278385 -0.713250 +0.577528 0.397159 -0.713250 +0.577528 0.397159 -0.713250 +0.643254 0.278385 -0.713250 +0.643254 0.278385 -0.713250 +0.577528 0.397159 -0.713250 +0.686037 0.143623 -0.713250 +0.643254 0.278385 -0.713250 +0.643254 0.278385 -0.713250 +0.686037 0.143623 -0.713250 +0.686037 0.143623 -0.713250 +0.643254 0.278385 -0.713250 +0.700909 0.000000 -0.713250 +0.686037 0.143623 -0.713250 +0.686037 0.143623 -0.713250 +-0.127540 0.689208 -0.713250 +-0.258001 0.651697 -0.713250 +-0.127540 0.689208 -0.713250 +0.000000 0.700909 -0.713250 +-0.127540 0.689208 -0.713250 +0.000000 0.700909 -0.713250 +-0.127540 0.689208 -0.713250 +-0.127540 0.689208 -0.713250 +0.000000 0.700909 -0.713250 +-0.127540 -0.689208 -0.713250 +0.000000 -0.700909 -0.713250 +0.000000 -0.700909 -0.713250 +-0.127540 -0.689208 -0.713250 +-0.127540 -0.689208 -0.713250 +0.000000 -0.700909 -0.713250 +-0.127540 -0.689208 -0.713250 +-0.258001 -0.651697 -0.713250 +-0.127540 -0.689208 -0.713250 +-0.258001 -0.651697 -0.713250 +-0.258001 -0.651697 -0.713250 +-0.127540 -0.689208 -0.713250 +-0.258001 -0.651697 -0.713250 +-0.383544 -0.586658 -0.713250 +-0.258001 -0.651697 -0.713250 +-0.383544 -0.586658 -0.713250 +-0.383544 -0.586658 -0.713250 +-0.258001 -0.651697 -0.713250 +-0.495618 -0.495618 -0.713250 +-0.383544 -0.586658 -0.713250 +-0.383544 -0.586658 -0.713250 +-0.495618 -0.495618 -0.713250 +-0.495618 -0.495618 -0.713250 +-0.383544 -0.586658 -0.713250 +-0.586658 -0.383544 -0.713250 +-0.495618 -0.495618 -0.713250 +-0.495618 -0.495618 -0.713250 +-0.586658 -0.383544 -0.713250 +-0.586658 -0.383544 -0.713250 +-0.495618 -0.495618 -0.713250 +-0.586658 -0.383544 -0.713250 +-0.651697 -0.258001 -0.713250 +-0.586658 -0.383544 -0.713250 +-0.651697 -0.258001 -0.713250 +-0.651697 -0.258001 -0.713250 +-0.586658 -0.383544 -0.713250 +-0.651697 -0.258001 -0.713250 +-0.689208 -0.127540 -0.713250 +-0.651697 -0.258001 -0.713250 +-0.689208 -0.127540 -0.713250 +-0.689208 -0.127540 -0.713250 +-0.651697 -0.258001 -0.713250 +-0.689208 -0.127540 -0.713250 +-0.700909 0.000000 -0.713250 +-0.689208 -0.127540 -0.713250 +-0.700909 0.000000 -0.713250 +-0.700909 0.000000 -0.713250 +-0.689208 -0.127540 -0.713250 +-0.689208 0.127540 -0.713250 +-0.700909 0.000000 -0.713250 +-0.700909 0.000000 -0.713250 +-0.689208 0.127540 -0.713250 +-0.689208 0.127540 -0.713250 +-0.700909 0.000000 -0.713250 +-0.689208 0.127540 -0.713250 +-0.651697 0.258001 -0.713250 +-0.689208 0.127540 -0.713250 +-0.651697 0.258001 -0.713250 +-0.651697 0.258001 -0.713250 +-0.689208 0.127540 -0.713250 +-0.586658 0.383544 -0.713250 +-0.651697 0.258001 -0.713250 +-0.651697 0.258001 -0.713250 +-0.586658 0.383544 -0.713250 +-0.586658 0.383544 -0.713250 +-0.651697 0.258001 -0.713250 +-0.586658 0.383544 -0.713250 +-0.495618 0.495618 -0.713250 +-0.586658 0.383544 -0.713250 +-0.495618 0.495618 -0.713250 +-0.495618 0.495618 -0.713250 +-0.586658 0.383544 -0.713250 +-0.383544 0.586658 -0.713250 +-0.495618 0.495618 -0.713250 +-0.495618 0.495618 -0.713250 +-0.383544 0.586658 -0.713250 +-0.383544 0.586658 -0.713250 +-0.495618 0.495618 -0.713250 +-0.258001 0.651697 -0.713250 +-0.383544 0.586658 -0.713250 +-0.383544 0.586658 -0.713250 +-0.258001 0.651697 -0.713250 +-0.258001 0.651697 -0.713250 +-0.383544 0.586658 -0.713250 +-0.258001 0.651697 -0.713250 +-0.127540 0.689208 -0.713250 +-0.258001 0.651697 -0.713250 +0.000000 0.700909 -0.713250 +0.000000 0.700909 -0.713250 +0.000000 0.700909 -0.713250 +0.000000 0.700909 -0.713250 +0.000000 0.700909 -0.713250 +0.000000 0.700909 -0.713250 +0.000000 0.204665 -0.978832 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.978473 -0.206373 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.978473 -0.206373 +0.000000 0.978473 -0.206373 +0.000000 0.999998 -0.001745 +0.000000 0.917239 -0.398337 +0.000000 0.978473 -0.206373 +0.000000 0.978473 -0.206373 +0.000000 0.917239 -0.398337 +0.000000 0.917239 -0.398337 +0.000000 0.978473 -0.206373 +0.000000 0.823371 -0.567504 +0.000000 0.917239 -0.398337 +0.000000 0.917239 -0.398337 +0.000000 0.823371 -0.567504 +0.000000 0.823371 -0.567504 +0.000000 0.917239 -0.398337 +0.000000 0.706489 -0.707724 +0.000000 0.823371 -0.567504 +0.000000 0.823371 -0.567504 +0.000000 0.706489 -0.707724 +0.000000 0.706489 -0.707724 +0.000000 0.823371 -0.567504 +0.000000 0.566066 -0.824360 +0.000000 0.706489 -0.707724 +0.000000 0.706489 -0.707724 +0.000000 0.566066 -0.824360 +0.000000 0.566066 -0.824360 +0.000000 0.706489 -0.707724 +0.000000 0.396736 -0.917933 +0.000000 0.566066 -0.824360 +0.000000 0.566066 -0.824360 +0.000000 0.396736 -0.917933 +0.000000 0.396736 -0.917933 +0.000000 0.566066 -0.824360 +0.000000 0.204665 -0.978832 +0.000000 0.396736 -0.917933 +0.000000 0.396736 -0.917933 +0.000000 0.204665 -0.978832 +0.000000 0.204665 -0.978832 +0.000000 0.396736 -0.917933 +0.000000 0.000000 -1.000000 +0.000000 0.204665 -0.978832 +0.000000 0.204665 -0.978832 +0.000000 0.204665 -0.978832 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.978473 -0.206373 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.978473 -0.206373 +0.000000 0.978473 -0.206373 +0.000000 0.999998 -0.001745 +0.000000 0.917239 -0.398337 +0.000000 0.978473 -0.206373 +0.000000 0.978473 -0.206373 +0.000000 0.917239 -0.398337 +0.000000 0.917239 -0.398337 +0.000000 0.978473 -0.206373 +0.000000 0.823371 -0.567504 +0.000000 0.917239 -0.398337 +0.000000 0.917239 -0.398337 +0.000000 0.823371 -0.567504 +0.000000 0.823371 -0.567504 +0.000000 0.917239 -0.398337 +0.000000 0.706489 -0.707724 +0.000000 0.823371 -0.567504 +0.000000 0.823371 -0.567504 +0.000000 0.706489 -0.707724 +0.000000 0.706489 -0.707724 +0.000000 0.823371 -0.567504 +0.000000 0.566066 -0.824360 +0.000000 0.706489 -0.707724 +0.000000 0.706489 -0.707724 +0.000000 0.566066 -0.824360 +0.000000 0.566066 -0.824360 +0.000000 0.706489 -0.707724 +0.000000 0.396736 -0.917933 +0.000000 0.566066 -0.824360 +0.000000 0.566066 -0.824360 +0.000000 0.396736 -0.917933 +0.000000 0.396736 -0.917933 +0.000000 0.566066 -0.824360 +0.000000 0.204665 -0.978832 +0.000000 0.396736 -0.917933 +0.000000 0.396736 -0.917933 +0.000000 0.204665 -0.978832 +0.000000 0.204665 -0.978832 +0.000000 0.396736 -0.917933 +0.000000 0.000000 -1.000000 +0.000000 0.204665 -0.978832 +0.000000 0.204665 -0.978832 +0.000000 0.204665 -0.978832 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.978473 -0.206373 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.978473 -0.206373 +0.000000 0.978473 -0.206373 +0.000000 0.999998 -0.001745 +0.000000 0.917239 -0.398337 +0.000000 0.978473 -0.206373 +0.000000 0.978473 -0.206373 +0.000000 0.917239 -0.398337 +0.000000 0.917239 -0.398337 +0.000000 0.978473 -0.206373 +0.000000 0.823371 -0.567504 +0.000000 0.917239 -0.398337 +0.000000 0.917239 -0.398337 +0.000000 0.823371 -0.567504 +0.000000 0.823371 -0.567504 +0.000000 0.917239 -0.398337 +0.000000 0.706489 -0.707724 +0.000000 0.823371 -0.567504 +0.000000 0.823371 -0.567504 +0.000000 0.706489 -0.707724 +0.000000 0.706489 -0.707724 +0.000000 0.823371 -0.567504 +0.000000 0.566066 -0.824360 +0.000000 0.706489 -0.707724 +0.000000 0.706489 -0.707724 +0.000000 0.566066 -0.824360 +0.000000 0.566066 -0.824360 +0.000000 0.706489 -0.707724 +0.000000 0.396736 -0.917933 +0.000000 0.566066 -0.824360 +0.000000 0.566066 -0.824360 +0.000000 0.396736 -0.917933 +0.000000 0.396736 -0.917933 +0.000000 0.566066 -0.824360 +0.000000 0.204665 -0.978832 +0.000000 0.396736 -0.917933 +0.000000 0.396736 -0.917933 +0.000000 0.204665 -0.978832 +0.000000 0.204665 -0.978832 +0.000000 0.396736 -0.917933 +0.000000 0.000000 -1.000000 +0.000000 0.204665 -0.978832 +0.000000 0.204665 -0.978832 +0.000000 0.204665 -0.978832 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.978473 -0.206373 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.978473 -0.206373 +0.000000 0.978473 -0.206373 +0.000000 0.999998 -0.001745 +0.000000 0.917239 -0.398337 +0.000000 0.978473 -0.206373 +0.000000 0.978473 -0.206373 +0.000000 0.917239 -0.398337 +0.000000 0.917239 -0.398337 +0.000000 0.978473 -0.206373 +0.000000 0.823371 -0.567504 +0.000000 0.917239 -0.398337 +0.000000 0.917239 -0.398337 +0.000000 0.823371 -0.567504 +0.000000 0.823371 -0.567504 +0.000000 0.917239 -0.398337 +0.000000 0.706489 -0.707724 +0.000000 0.823371 -0.567504 +0.000000 0.823371 -0.567504 +0.000000 0.706489 -0.707724 +0.000000 0.706489 -0.707724 +0.000000 0.823371 -0.567504 +0.000000 0.566066 -0.824360 +0.000000 0.706489 -0.707724 +0.000000 0.706489 -0.707724 +0.000000 0.566066 -0.824360 +0.000000 0.566066 -0.824360 +0.000000 0.706489 -0.707724 +0.000000 0.396736 -0.917933 +0.000000 0.566066 -0.824360 +0.000000 0.566066 -0.824360 +0.000000 0.396736 -0.917933 +0.000000 0.396736 -0.917933 +0.000000 0.566066 -0.824360 +0.000000 0.204665 -0.978832 +0.000000 0.396736 -0.917933 +0.000000 0.396736 -0.917933 +0.000000 0.204665 -0.978832 +0.000000 0.204665 -0.978832 +0.000000 0.396736 -0.917933 +0.000000 0.000000 -1.000000 +0.000000 0.204665 -0.978832 +0.000000 0.204665 -0.978832 +0.181793 0.000000 -0.983337 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.983018 0.000000 -0.183509 +0.999998 0.000000 -0.001745 +0.999998 0.000000 -0.001745 +0.983018 0.000000 -0.183509 +0.983018 0.000000 -0.183509 +0.999998 0.000000 -0.001745 +0.929286 0.000000 -0.369361 +0.983018 0.000000 -0.183509 +0.983018 0.000000 -0.183509 +0.929286 0.000000 -0.369361 +0.929286 0.000000 -0.369361 +0.983018 0.000000 -0.183509 +0.836379 0.000000 -0.548151 +0.929286 0.000000 -0.369361 +0.929286 0.000000 -0.369361 +0.836379 0.000000 -0.548151 +0.836379 0.000000 -0.548151 +0.929286 0.000000 -0.369361 +0.706489 0.000000 -0.707724 +0.836379 0.000000 -0.548151 +0.836379 0.000000 -0.548151 +0.706489 0.000000 -0.707724 +0.706489 0.000000 -0.707724 +0.836379 0.000000 -0.548151 +0.546691 0.000000 -0.837335 +0.706489 0.000000 -0.707724 +0.706489 0.000000 -0.707724 +0.546691 0.000000 -0.837335 +0.546691 0.000000 -0.837335 +0.706489 0.000000 -0.707724 +0.367739 0.000000 -0.929929 +0.546691 0.000000 -0.837335 +0.546691 0.000000 -0.837335 +0.367739 0.000000 -0.929929 +0.367739 0.000000 -0.929929 +0.546691 0.000000 -0.837335 +0.181793 0.000000 -0.983337 +0.367739 0.000000 -0.929929 +0.367739 0.000000 -0.929929 +0.181793 0.000000 -0.983337 +0.181793 0.000000 -0.983337 +0.367739 0.000000 -0.929929 +0.000000 0.000000 -1.000000 +0.181793 0.000000 -0.983337 +0.181793 0.000000 -0.983337 +-0.204909 0.000000 -0.978781 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.978781 0.000000 -0.204909 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.978781 0.000000 -0.204909 +-0.978781 0.000000 -0.204909 +-1.000000 0.000000 0.000000 +-0.917742 0.000000 -0.397177 +-0.978781 0.000000 -0.204909 +-0.978781 0.000000 -0.204909 +-0.917742 0.000000 -0.397177 +-0.917742 0.000000 -0.397177 +-0.978781 0.000000 -0.204909 +-0.823969 0.000000 -0.566635 +-0.917742 0.000000 -0.397177 +-0.917742 0.000000 -0.397177 +-0.823969 0.000000 -0.566635 +-0.823969 0.000000 -0.566635 +-0.917742 0.000000 -0.397177 +-0.707107 0.000000 -0.707107 +-0.823969 0.000000 -0.566635 +-0.823969 0.000000 -0.566635 +-0.707107 0.000000 -0.707107 +-0.707107 0.000000 -0.707107 +-0.823969 0.000000 -0.566635 +-0.566635 0.000000 -0.823969 +-0.707107 0.000000 -0.707107 +-0.707107 0.000000 -0.707107 +-0.566635 0.000000 -0.823969 +-0.566635 0.000000 -0.823969 +-0.707107 0.000000 -0.707107 +-0.397177 0.000000 -0.917742 +-0.566635 0.000000 -0.823969 +-0.566635 0.000000 -0.823969 +-0.397177 0.000000 -0.917742 +-0.397177 0.000000 -0.917742 +-0.566635 0.000000 -0.823969 +-0.204909 0.000000 -0.978781 +-0.397177 0.000000 -0.917742 +-0.397177 0.000000 -0.917742 +-0.204909 0.000000 -0.978781 +-0.204909 0.000000 -0.978781 +-0.397177 0.000000 -0.917742 +0.000000 0.000000 -1.000000 +-0.204909 0.000000 -0.978781 +-0.204909 0.000000 -0.978781 +0.000000 -0.204665 -0.978832 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -0.978473 -0.206373 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.978473 -0.206373 +0.000000 -0.978473 -0.206373 +0.000000 -0.999998 -0.001745 +0.000000 -0.917239 -0.398337 +0.000000 -0.978473 -0.206373 +0.000000 -0.978473 -0.206373 +0.000000 -0.917239 -0.398337 +0.000000 -0.917239 -0.398337 +0.000000 -0.978473 -0.206373 +0.000000 -0.823371 -0.567504 +0.000000 -0.917239 -0.398337 +0.000000 -0.917239 -0.398337 +0.000000 -0.823371 -0.567504 +0.000000 -0.823371 -0.567504 +0.000000 -0.917239 -0.398337 +0.000000 -0.706489 -0.707724 +0.000000 -0.823371 -0.567504 +0.000000 -0.823371 -0.567504 +0.000000 -0.706489 -0.707724 +0.000000 -0.706489 -0.707724 +0.000000 -0.823371 -0.567504 +0.000000 -0.566066 -0.824360 +0.000000 -0.706489 -0.707724 +0.000000 -0.706489 -0.707724 +0.000000 -0.566066 -0.824360 +0.000000 -0.566066 -0.824360 +0.000000 -0.706489 -0.707724 +0.000000 -0.396736 -0.917933 +0.000000 -0.566066 -0.824360 +0.000000 -0.566066 -0.824360 +0.000000 -0.396736 -0.917933 +0.000000 -0.396736 -0.917933 +0.000000 -0.566066 -0.824360 +0.000000 -0.204665 -0.978832 +0.000000 -0.396736 -0.917933 +0.000000 -0.396736 -0.917933 +0.000000 -0.204665 -0.978832 +0.000000 -0.204665 -0.978832 +0.000000 -0.396736 -0.917933 +0.000000 0.000000 -1.000000 +0.000000 -0.204665 -0.978832 +0.000000 -0.204665 -0.978832 +0.000000 -0.204665 -0.978832 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -0.978473 -0.206373 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.978473 -0.206373 +0.000000 -0.978473 -0.206373 +0.000000 -0.999998 -0.001745 +0.000000 -0.917239 -0.398337 +0.000000 -0.978473 -0.206373 +0.000000 -0.978473 -0.206373 +0.000000 -0.917239 -0.398337 +0.000000 -0.917239 -0.398337 +0.000000 -0.978473 -0.206373 +0.000000 -0.823371 -0.567504 +0.000000 -0.917239 -0.398337 +0.000000 -0.917239 -0.398337 +0.000000 -0.823371 -0.567504 +0.000000 -0.823371 -0.567504 +0.000000 -0.917239 -0.398337 +0.000000 -0.706489 -0.707724 +0.000000 -0.823371 -0.567504 +0.000000 -0.823371 -0.567504 +0.000000 -0.706489 -0.707724 +0.000000 -0.706489 -0.707724 +0.000000 -0.823371 -0.567504 +0.000000 -0.566066 -0.824360 +0.000000 -0.706489 -0.707724 +0.000000 -0.706489 -0.707724 +0.000000 -0.566066 -0.824360 +0.000000 -0.566066 -0.824360 +0.000000 -0.706489 -0.707724 +0.000000 -0.396736 -0.917933 +0.000000 -0.566066 -0.824360 +0.000000 -0.566066 -0.824360 +0.000000 -0.396736 -0.917933 +0.000000 -0.396736 -0.917933 +0.000000 -0.566066 -0.824360 +0.000000 -0.204665 -0.978832 +0.000000 -0.396736 -0.917933 +0.000000 -0.396736 -0.917933 +0.000000 -0.204665 -0.978832 +0.000000 -0.204665 -0.978832 +0.000000 -0.396736 -0.917933 +0.000000 0.000000 -1.000000 +0.000000 -0.204665 -0.978832 +0.000000 -0.204665 -0.978832 +0.000000 -0.204665 -0.978832 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -0.978473 -0.206373 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.978473 -0.206373 +0.000000 -0.978473 -0.206373 +0.000000 -0.999998 -0.001745 +0.000000 -0.917239 -0.398337 +0.000000 -0.978473 -0.206373 +0.000000 -0.978473 -0.206373 +0.000000 -0.917239 -0.398337 +0.000000 -0.917239 -0.398337 +0.000000 -0.978473 -0.206373 +0.000000 -0.823371 -0.567504 +0.000000 -0.917239 -0.398337 +0.000000 -0.917239 -0.398337 +0.000000 -0.823371 -0.567504 +0.000000 -0.823371 -0.567504 +0.000000 -0.917239 -0.398337 +0.000000 -0.706489 -0.707724 +0.000000 -0.823371 -0.567504 +0.000000 -0.823371 -0.567504 +0.000000 -0.706489 -0.707724 +0.000000 -0.706489 -0.707724 +0.000000 -0.823371 -0.567504 +0.000000 -0.566066 -0.824360 +0.000000 -0.706489 -0.707724 +0.000000 -0.706489 -0.707724 +0.000000 -0.566066 -0.824360 +0.000000 -0.566066 -0.824360 +0.000000 -0.706489 -0.707724 +0.000000 -0.396736 -0.917933 +0.000000 -0.566066 -0.824360 +0.000000 -0.566066 -0.824360 +0.000000 -0.396736 -0.917933 +0.000000 -0.396736 -0.917933 +0.000000 -0.566066 -0.824360 +0.000000 -0.204665 -0.978832 +0.000000 -0.396736 -0.917933 +0.000000 -0.396736 -0.917933 +0.000000 -0.204665 -0.978832 +0.000000 -0.204665 -0.978832 +0.000000 -0.396736 -0.917933 +0.000000 0.000000 -1.000000 +0.000000 -0.204665 -0.978832 +0.000000 -0.204665 -0.978832 +0.000000 -0.204665 -0.978832 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -0.978473 -0.206373 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.978473 -0.206373 +0.000000 -0.978473 -0.206373 +0.000000 -0.999998 -0.001745 +0.000000 -0.917239 -0.398337 +0.000000 -0.978473 -0.206373 +0.000000 -0.978473 -0.206373 +0.000000 -0.917239 -0.398337 +0.000000 -0.917239 -0.398337 +0.000000 -0.978473 -0.206373 +0.000000 -0.823371 -0.567504 +0.000000 -0.917239 -0.398337 +0.000000 -0.917239 -0.398337 +0.000000 -0.823371 -0.567504 +0.000000 -0.823371 -0.567504 +0.000000 -0.917239 -0.398337 +0.000000 -0.706489 -0.707724 +0.000000 -0.823371 -0.567504 +0.000000 -0.823371 -0.567504 +0.000000 -0.706489 -0.707724 +0.000000 -0.706489 -0.707724 +0.000000 -0.823371 -0.567504 +0.000000 -0.566066 -0.824360 +0.000000 -0.706489 -0.707724 +0.000000 -0.706489 -0.707724 +0.000000 -0.566066 -0.824360 +0.000000 -0.566066 -0.824360 +0.000000 -0.706489 -0.707724 +0.000000 -0.396736 -0.917933 +0.000000 -0.566066 -0.824360 +0.000000 -0.566066 -0.824360 +0.000000 -0.396736 -0.917933 +0.000000 -0.396736 -0.917933 +0.000000 -0.566066 -0.824360 +0.000000 -0.204665 -0.978832 +0.000000 -0.396736 -0.917933 +0.000000 -0.396736 -0.917933 +0.000000 -0.204665 -0.978832 +0.000000 -0.204665 -0.978832 +0.000000 -0.396736 -0.917933 +0.000000 0.000000 -1.000000 +0.000000 -0.204665 -0.978832 +0.000000 -0.204665 -0.978832 +0.000000 -0.204665 -0.978832 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -0.978473 -0.206373 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.978473 -0.206373 +0.000000 -0.978473 -0.206373 +0.000000 -0.999998 -0.001745 +0.000000 -0.917239 -0.398337 +0.000000 -0.978473 -0.206373 +0.000000 -0.978473 -0.206373 +0.000000 -0.917239 -0.398337 +0.000000 -0.917239 -0.398337 +0.000000 -0.978473 -0.206373 +0.000000 -0.823371 -0.567504 +0.000000 -0.917239 -0.398337 +0.000000 -0.917239 -0.398337 +0.000000 -0.823371 -0.567504 +0.000000 -0.823371 -0.567504 +0.000000 -0.917239 -0.398337 +0.000000 -0.706489 -0.707724 +0.000000 -0.823371 -0.567504 +0.000000 -0.823371 -0.567504 +0.000000 -0.706489 -0.707724 +0.000000 -0.706489 -0.707724 +0.000000 -0.823371 -0.567504 +0.000000 -0.566066 -0.824360 +0.000000 -0.706489 -0.707724 +0.000000 -0.706489 -0.707724 +0.000000 -0.566066 -0.824360 +0.000000 -0.566066 -0.824360 +0.000000 -0.706489 -0.707724 +0.000000 -0.396736 -0.917933 +0.000000 -0.566066 -0.824360 +0.000000 -0.566066 -0.824360 +0.000000 -0.396736 -0.917933 +0.000000 -0.396736 -0.917933 +0.000000 -0.566066 -0.824360 +0.000000 -0.204665 -0.978832 +0.000000 -0.396736 -0.917933 +0.000000 -0.396736 -0.917933 +0.000000 -0.204665 -0.978832 +0.000000 -0.204665 -0.978832 +0.000000 -0.396736 -0.917933 +0.000000 0.000000 -1.000000 +0.000000 -0.204665 -0.978832 +0.000000 -0.204665 -0.978832 +0.000000 -0.181793 -0.983337 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -0.983018 -0.183509 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.983018 -0.183509 +0.000000 -0.983018 -0.183509 +0.000000 -0.999998 -0.001745 +0.000000 -0.929286 -0.369361 +0.000000 -0.983018 -0.183509 +0.000000 -0.983018 -0.183509 +0.000000 -0.929286 -0.369361 +0.000000 -0.929286 -0.369361 +0.000000 -0.983018 -0.183509 +0.000000 -0.836379 -0.548151 +0.000000 -0.929286 -0.369361 +0.000000 -0.929286 -0.369361 +0.000000 -0.836379 -0.548151 +0.000000 -0.836379 -0.548151 +0.000000 -0.929286 -0.369361 +0.000000 -0.706489 -0.707724 +0.000000 -0.836379 -0.548151 +0.000000 -0.836379 -0.548151 +0.000000 -0.706489 -0.707724 +0.000000 -0.706489 -0.707724 +0.000000 -0.836379 -0.548151 +0.000000 -0.546691 -0.837335 +0.000000 -0.706489 -0.707724 +0.000000 -0.706489 -0.707724 +0.000000 -0.546691 -0.837335 +0.000000 -0.546691 -0.837335 +0.000000 -0.706489 -0.707724 +0.000000 -0.367739 -0.929929 +0.000000 -0.546691 -0.837335 +0.000000 -0.546691 -0.837335 +0.000000 -0.367739 -0.929929 +0.000000 -0.367739 -0.929929 +0.000000 -0.546691 -0.837335 +0.000000 -0.181793 -0.983337 +0.000000 -0.367739 -0.929929 +0.000000 -0.367739 -0.929929 +0.000000 -0.181793 -0.983337 +0.000000 -0.181793 -0.983337 +0.000000 -0.367739 -0.929929 +0.000000 0.000000 -1.000000 +0.000000 -0.181793 -0.983337 +0.000000 -0.181793 -0.983337 +0.000000 -0.181793 -0.983337 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -0.983018 -0.183509 +0.000000 -0.999998 -0.001745 +0.000000 -0.999998 -0.001745 +0.000000 -0.983018 -0.183509 +0.000000 -0.983018 -0.183509 +0.000000 -0.999998 -0.001745 +0.000000 -0.929286 -0.369361 +0.000000 -0.983018 -0.183509 +0.000000 -0.983018 -0.183509 +0.000000 -0.929286 -0.369361 +0.000000 -0.929286 -0.369361 +0.000000 -0.983018 -0.183509 +0.000000 -0.836379 -0.548151 +0.000000 -0.929286 -0.369361 +0.000000 -0.929286 -0.369361 +0.000000 -0.836379 -0.548151 +0.000000 -0.836379 -0.548151 +0.000000 -0.929286 -0.369361 +0.000000 -0.706489 -0.707724 +0.000000 -0.836379 -0.548151 +0.000000 -0.836379 -0.548151 +0.000000 -0.706489 -0.707724 +0.000000 -0.706489 -0.707724 +0.000000 -0.836379 -0.548151 +0.000000 -0.546691 -0.837335 +0.000000 -0.706489 -0.707724 +0.000000 -0.706489 -0.707724 +0.000000 -0.546691 -0.837335 +0.000000 -0.546691 -0.837335 +0.000000 -0.706489 -0.707724 +0.000000 -0.367739 -0.929929 +0.000000 -0.546691 -0.837335 +0.000000 -0.546691 -0.837335 +0.000000 -0.367739 -0.929929 +0.000000 -0.367739 -0.929929 +0.000000 -0.546691 -0.837335 +0.000000 -0.181793 -0.983337 +0.000000 -0.367739 -0.929929 +0.000000 -0.367739 -0.929929 +0.000000 -0.181793 -0.983337 +0.000000 -0.181793 -0.983337 +0.000000 -0.367739 -0.929929 +0.000000 0.000000 -1.000000 +0.000000 -0.181793 -0.983337 +0.000000 -0.181793 -0.983337 +0.000000 0.181793 -0.983337 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.983018 -0.183509 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.983018 -0.183509 +0.000000 0.983018 -0.183509 +0.000000 0.999998 -0.001745 +0.000000 0.929286 -0.369361 +0.000000 0.983018 -0.183509 +0.000000 0.983018 -0.183509 +0.000000 0.929286 -0.369361 +0.000000 0.929286 -0.369361 +0.000000 0.983018 -0.183509 +0.000000 0.836379 -0.548151 +0.000000 0.929286 -0.369361 +0.000000 0.929286 -0.369361 +0.000000 0.836379 -0.548151 +0.000000 0.836379 -0.548151 +0.000000 0.929286 -0.369361 +0.000000 0.706489 -0.707724 +0.000000 0.836379 -0.548151 +0.000000 0.836379 -0.548151 +0.000000 0.706489 -0.707724 +0.000000 0.706489 -0.707724 +0.000000 0.836379 -0.548151 +0.000000 0.546691 -0.837335 +0.000000 0.706489 -0.707724 +0.000000 0.706489 -0.707724 +0.000000 0.546691 -0.837335 +0.000000 0.546691 -0.837335 +0.000000 0.706489 -0.707724 +0.000000 0.367739 -0.929929 +0.000000 0.546691 -0.837335 +0.000000 0.546691 -0.837335 +0.000000 0.367739 -0.929929 +0.000000 0.367739 -0.929929 +0.000000 0.546691 -0.837335 +0.000000 0.181793 -0.983337 +0.000000 0.367739 -0.929929 +0.000000 0.367739 -0.929929 +0.000000 0.181793 -0.983337 +0.000000 0.181793 -0.983337 +0.000000 0.367739 -0.929929 +0.000000 0.000000 -1.000000 +0.000000 0.181793 -0.983337 +0.000000 0.181793 -0.983337 +0.000000 0.181793 -0.983337 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.983018 -0.183509 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.983018 -0.183509 +0.000000 0.983018 -0.183509 +0.000000 0.999998 -0.001745 +0.000000 0.929286 -0.369361 +0.000000 0.983018 -0.183509 +0.000000 0.983018 -0.183509 +0.000000 0.929286 -0.369361 +0.000000 0.929286 -0.369361 +0.000000 0.983018 -0.183509 +0.000000 0.836379 -0.548151 +0.000000 0.929286 -0.369361 +0.000000 0.929286 -0.369361 +0.000000 0.836379 -0.548151 +0.000000 0.836379 -0.548151 +0.000000 0.929286 -0.369361 +0.000000 0.706489 -0.707724 +0.000000 0.836379 -0.548151 +0.000000 0.836379 -0.548151 +0.000000 0.706489 -0.707724 +0.000000 0.706489 -0.707724 +0.000000 0.836379 -0.548151 +0.000000 0.546691 -0.837335 +0.000000 0.706489 -0.707724 +0.000000 0.706489 -0.707724 +0.000000 0.546691 -0.837335 +0.000000 0.546691 -0.837335 +0.000000 0.706489 -0.707724 +0.000000 0.367739 -0.929929 +0.000000 0.546691 -0.837335 +0.000000 0.546691 -0.837335 +0.000000 0.367739 -0.929929 +0.000000 0.367739 -0.929929 +0.000000 0.546691 -0.837335 +0.000000 0.181793 -0.983337 +0.000000 0.367739 -0.929929 +0.000000 0.367739 -0.929929 +0.000000 0.181793 -0.983337 +0.000000 0.181793 -0.983337 +0.000000 0.367739 -0.929929 +0.000000 0.000000 -1.000000 +0.000000 0.181793 -0.983337 +0.000000 0.181793 -0.983337 +0.000000 0.204665 -0.978832 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.978473 -0.206373 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.978473 -0.206373 +0.000000 0.978473 -0.206373 +0.000000 0.999998 -0.001745 +0.000000 0.917239 -0.398337 +0.000000 0.978473 -0.206373 +0.000000 0.978473 -0.206373 +0.000000 0.917239 -0.398337 +0.000000 0.917239 -0.398337 +0.000000 0.978473 -0.206373 +0.000000 0.823371 -0.567504 +0.000000 0.917239 -0.398337 +0.000000 0.917239 -0.398337 +0.000000 0.823371 -0.567504 +0.000000 0.823371 -0.567504 +0.000000 0.917239 -0.398337 +0.000000 0.706489 -0.707724 +0.000000 0.823371 -0.567504 +0.000000 0.823371 -0.567504 +0.000000 0.706489 -0.707724 +0.000000 0.706489 -0.707724 +0.000000 0.823371 -0.567504 +0.000000 0.566066 -0.824360 +0.000000 0.706489 -0.707724 +0.000000 0.706489 -0.707724 +0.000000 0.566066 -0.824360 +0.000000 0.566066 -0.824360 +0.000000 0.706489 -0.707724 +0.000000 0.396736 -0.917933 +0.000000 0.566066 -0.824360 +0.000000 0.566066 -0.824360 +0.000000 0.396736 -0.917933 +0.000000 0.396736 -0.917933 +0.000000 0.566066 -0.824360 +0.000000 0.204665 -0.978832 +0.000000 0.396736 -0.917933 +0.000000 0.396736 -0.917933 +0.000000 0.204665 -0.978832 +0.000000 0.204665 -0.978832 +0.000000 0.396736 -0.917933 +0.000000 0.000000 -1.000000 +0.000000 0.204665 -0.978832 +0.000000 0.204665 -0.978832 +0.000000 0.204665 -0.978832 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.978473 -0.206373 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.978473 -0.206373 +0.000000 0.978473 -0.206373 +0.000000 0.999998 -0.001745 +0.000000 0.917239 -0.398337 +0.000000 0.978473 -0.206373 +0.000000 0.978473 -0.206373 +0.000000 0.917239 -0.398337 +0.000000 0.917239 -0.398337 +0.000000 0.978473 -0.206373 +0.000000 0.823371 -0.567504 +0.000000 0.917239 -0.398337 +0.000000 0.917239 -0.398337 +0.000000 0.823371 -0.567504 +0.000000 0.823371 -0.567504 +0.000000 0.917239 -0.398337 +0.000000 0.706489 -0.707724 +0.000000 0.823371 -0.567504 +0.000000 0.823371 -0.567504 +0.000000 0.706489 -0.707724 +0.000000 0.706489 -0.707724 +0.000000 0.823371 -0.567504 +0.000000 0.566066 -0.824360 +0.000000 0.706489 -0.707724 +0.000000 0.706489 -0.707724 +0.000000 0.566066 -0.824360 +0.000000 0.566066 -0.824360 +0.000000 0.706489 -0.707724 +0.000000 0.396736 -0.917933 +0.000000 0.566066 -0.824360 +0.000000 0.566066 -0.824360 +0.000000 0.396736 -0.917933 +0.000000 0.396736 -0.917933 +0.000000 0.566066 -0.824360 +0.000000 0.204665 -0.978832 +0.000000 0.396736 -0.917933 +0.000000 0.396736 -0.917933 +0.000000 0.204665 -0.978832 +0.000000 0.204665 -0.978832 +0.000000 0.396736 -0.917933 +0.000000 0.000000 -1.000000 +0.000000 0.204665 -0.978832 +0.000000 0.204665 -0.978832 +0.000000 0.204665 -0.978832 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.978473 -0.206373 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.978473 -0.206373 +0.000000 0.978473 -0.206373 +0.000000 0.999998 -0.001745 +0.000000 0.917239 -0.398337 +0.000000 0.978473 -0.206373 +0.000000 0.978473 -0.206373 +0.000000 0.917239 -0.398337 +0.000000 0.917239 -0.398337 +0.000000 0.978473 -0.206373 +0.000000 0.823371 -0.567504 +0.000000 0.917239 -0.398337 +0.000000 0.917239 -0.398337 +0.000000 0.823371 -0.567504 +0.000000 0.823371 -0.567504 +0.000000 0.917239 -0.398337 +0.000000 0.706489 -0.707724 +0.000000 0.823371 -0.567504 +0.000000 0.823371 -0.567504 +0.000000 0.706489 -0.707724 +0.000000 0.706489 -0.707724 +0.000000 0.823371 -0.567504 +0.000000 0.566066 -0.824360 +0.000000 0.706489 -0.707724 +0.000000 0.706489 -0.707724 +0.000000 0.566066 -0.824360 +0.000000 0.566066 -0.824360 +0.000000 0.706489 -0.707724 +0.000000 0.396736 -0.917933 +0.000000 0.566066 -0.824360 +0.000000 0.566066 -0.824360 +0.000000 0.396736 -0.917933 +0.000000 0.396736 -0.917933 +0.000000 0.566066 -0.824360 +0.000000 0.204665 -0.978832 +0.000000 0.396736 -0.917933 +0.000000 0.396736 -0.917933 +0.000000 0.204665 -0.978832 +0.000000 0.204665 -0.978832 +0.000000 0.396736 -0.917933 +0.000000 0.000000 -1.000000 +0.000000 0.204665 -0.978832 +0.000000 0.204665 -0.978832 +0.000000 0.204665 -0.978832 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.978473 -0.206373 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.978473 -0.206373 +0.000000 0.978473 -0.206373 +0.000000 0.999998 -0.001745 +0.000000 0.917239 -0.398337 +0.000000 0.978473 -0.206373 +0.000000 0.978473 -0.206373 +0.000000 0.917239 -0.398337 +0.000000 0.917239 -0.398337 +0.000000 0.978473 -0.206373 +0.000000 0.823371 -0.567504 +0.000000 0.917239 -0.398337 +0.000000 0.917239 -0.398337 +0.000000 0.823371 -0.567504 +0.000000 0.823371 -0.567504 +0.000000 0.917239 -0.398337 +0.000000 0.706489 -0.707724 +0.000000 0.823371 -0.567504 +0.000000 0.823371 -0.567504 +0.000000 0.706489 -0.707724 +0.000000 0.706489 -0.707724 +0.000000 0.823371 -0.567504 +0.000000 0.566066 -0.824360 +0.000000 0.706489 -0.707724 +0.000000 0.706489 -0.707724 +0.000000 0.566066 -0.824360 +0.000000 0.566066 -0.824360 +0.000000 0.706489 -0.707724 +0.000000 0.396736 -0.917933 +0.000000 0.566066 -0.824360 +0.000000 0.566066 -0.824360 +0.000000 0.396736 -0.917933 +0.000000 0.396736 -0.917933 +0.000000 0.566066 -0.824360 +0.000000 0.204665 -0.978832 +0.000000 0.396736 -0.917933 +0.000000 0.396736 -0.917933 +0.000000 0.204665 -0.978832 +0.000000 0.204665 -0.978832 +0.000000 0.396736 -0.917933 +0.000000 0.000000 -1.000000 +0.000000 0.204665 -0.978832 +0.000000 0.204665 -0.978832 +0.000000 0.204665 -0.978832 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.978473 -0.206373 +0.000000 0.999998 -0.001745 +0.000000 0.999998 -0.001745 +0.000000 0.978473 -0.206373 +0.000000 0.978473 -0.206373 +0.000000 0.999998 -0.001745 +0.000000 0.917239 -0.398337 +0.000000 0.978473 -0.206373 +0.000000 0.978473 -0.206373 +0.000000 0.917239 -0.398337 +0.000000 0.917239 -0.398337 +0.000000 0.978473 -0.206373 +0.000000 0.823371 -0.567504 +0.000000 0.917239 -0.398337 +0.000000 0.917239 -0.398337 +0.000000 0.823371 -0.567504 +0.000000 0.823371 -0.567504 +0.000000 0.917239 -0.398337 +0.000000 0.706489 -0.707724 +0.000000 0.823371 -0.567504 +0.000000 0.823371 -0.567504 +0.000000 0.706489 -0.707724 +0.000000 0.706489 -0.707724 +0.000000 0.823371 -0.567504 +0.000000 0.566066 -0.824360 +0.000000 0.706489 -0.707724 +0.000000 0.706489 -0.707724 +0.000000 0.566066 -0.824360 +0.000000 0.566066 -0.824360 +0.000000 0.706489 -0.707724 +0.000000 0.396736 -0.917933 +0.000000 0.566066 -0.824360 +0.000000 0.566066 -0.824360 +0.000000 0.396736 -0.917933 +0.000000 0.396736 -0.917933 +0.000000 0.566066 -0.824360 +0.000000 0.204665 -0.978832 +0.000000 0.396736 -0.917933 +0.000000 0.396736 -0.917933 +0.000000 0.204665 -0.978832 +0.000000 0.204665 -0.978832 +0.000000 0.396736 -0.917933 +0.000000 0.000000 -1.000000 +0.000000 0.204665 -0.978832 +0.000000 0.204665 -0.978832 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.707107 0.000000 -0.707107 +0.707107 0.000000 -0.707107 +0.707107 0.000000 -0.707107 +0.707107 0.000000 -0.707107 +0.707107 0.000000 -0.707107 +0.707107 0.000000 -0.707107 +0.707107 0.000000 -0.707107 +0.707107 0.000000 -0.707107 +0.707107 0.000000 -0.707107 +0.707107 0.000000 -0.707107 +0.707107 0.000000 -0.707107 +0.707107 0.000000 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +0.000000 -0.707107 -0.707107 +-0.707107 0.000000 -0.707107 +-0.707107 0.000000 -0.707107 +-0.707107 0.000000 -0.707107 +-0.707107 0.000000 -0.707107 +-0.707107 0.000000 -0.707107 +-0.707107 0.000000 -0.707107 +-0.707107 0.000000 -0.707107 +-0.707107 0.000000 -0.707107 +-0.707107 0.000000 -0.707107 +-0.707107 0.000000 -0.707107 +-0.707107 0.000000 -0.707107 +-0.707107 0.000000 -0.707107 +-0.707107 0.000000 -0.707107 +-0.707107 0.000000 -0.707107 +-0.707107 0.000000 -0.707107 +-0.707107 0.000000 -0.707107 +-0.707107 0.000000 -0.707107 +-0.707107 0.000000 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 +0.000000 0.707107 -0.707107 + + + + + + + + + + + +0.189884 0.655220 +0.196743 0.658443 +0.384008 0.658267 +0.423378 0.658222 +0.415347 0.654944 +0.336096 0.658310 +0.369208 0.655001 +0.292714 0.658347 +0.316993 0.655054 +0.261413 0.658378 +0.275041 0.655101 +0.247069 0.655140 +0.238939 0.658404 +0.227491 0.655172 +0.221676 0.658425 +0.212390 0.655198 +0.208063 0.658439 +0.200249 0.655215 +0.733994 0.660431 +0.733990 0.660103 +0.735789 0.660103 +0.735793 0.660431 +0.733443 0.660089 +0.733448 0.660417 +0.730996 0.660074 +0.731000 0.660402 +0.728600 0.660059 +0.728605 0.660387 +0.726430 0.660046 +0.726434 0.660374 +0.724641 0.660036 +0.724645 0.660364 +0.723336 0.660028 +0.723340 0.660356 +0.722548 0.660024 +0.722553 0.660352 +0.722245 0.660023 +0.722249 0.660350 +0.722371 0.660024 +0.722375 0.660352 +0.722959 0.660028 +0.722963 0.660356 +0.724036 0.660036 +0.724040 0.660364 +0.725569 0.660046 +0.725573 0.660374 +0.727467 0.660059 +0.727471 0.660387 +0.729599 0.660074 +0.729603 0.660402 +0.731817 0.660089 +0.731821 0.660417 +0.329078 0.660074 +0.324687 0.660103 +0.324683 0.660431 +0.326860 0.660089 +0.322884 0.660431 +0.322888 0.660103 +0.325229 0.660417 +0.325233 0.660089 +0.327676 0.660402 +0.327681 0.660074 +0.330072 0.660387 +0.330077 0.660059 +0.332243 0.660374 +0.332247 0.660046 +0.334032 0.660364 +0.334036 0.660036 +0.335336 0.660356 +0.335341 0.660028 +0.336124 0.660352 +0.336128 0.660024 +0.336428 0.660350 +0.336432 0.660023 +0.336302 0.660352 +0.336306 0.660024 +0.335713 0.660356 +0.335718 0.660028 +0.334637 0.660364 +0.334641 0.660036 +0.333104 0.660374 +0.333108 0.660046 +0.331205 0.660387 +0.331210 0.660059 +0.329074 0.660402 +0.326856 0.660417 +0.549516 0.572090 +0.557472 0.572489 +0.550184 0.572274 +0.557034 0.572445 +0.549854 0.572230 +0.556586 0.572305 +0.549844 0.567073 +0.550173 0.567029 +0.557452 0.567245 +0.557015 0.567289 +0.549506 0.567213 +0.549181 0.567457 +0.556568 0.567429 +0.556137 0.567672 +0.548892 0.567797 +0.555752 0.568013 +0.548656 0.568217 +0.555439 0.568432 +0.548488 0.568686 +0.555216 0.568902 +0.548392 0.569174 +0.555088 0.569390 +0.548362 0.569651 +0.555050 0.569867 +0.548393 0.570129 +0.555092 0.570344 +0.548492 0.570617 +0.555223 0.570832 +0.548662 0.571086 +0.548899 0.571506 +0.555449 0.571302 +0.555765 0.571721 +0.549190 0.571846 +0.556153 0.572062 +0.557015 0.567289 +0.557452 0.567245 +0.558687 0.569893 +0.557472 0.572489 +0.557034 0.572445 +0.556586 0.572305 +0.556153 0.572062 +0.555765 0.571721 +0.555449 0.571302 +0.555223 0.570832 +0.555092 0.570344 +0.555050 0.569867 +0.555088 0.569390 +0.555216 0.568902 +0.555439 0.568432 +0.555752 0.568013 +0.556137 0.567672 +0.556568 0.567429 +0.558687 0.569893 +0.558687 0.569893 +0.558687 0.569893 +0.558687 0.569893 +0.558687 0.569893 +0.558687 0.569893 +0.558687 0.569893 +0.558687 0.569893 +0.558687 0.569893 +0.558687 0.569893 +0.558687 0.569893 +0.558687 0.569893 +0.558687 0.569893 +0.558687 0.569893 +0.558687 0.569893 +0.558687 0.569893 +0.507827 0.572090 +0.500769 0.572445 +0.501205 0.572489 +0.508492 0.572274 +0.500324 0.572305 +0.508163 0.572230 +0.508503 0.567029 +0.501225 0.567245 +0.508174 0.567073 +0.507837 0.567213 +0.500789 0.567289 +0.500343 0.567429 +0.507513 0.567457 +0.499914 0.567672 +0.507224 0.567797 +0.499532 0.568013 +0.506989 0.568217 +0.499221 0.568432 +0.506821 0.568686 +0.498999 0.568902 +0.506723 0.569174 +0.498870 0.569390 +0.506692 0.569651 +0.498828 0.569867 +0.506721 0.570129 +0.498866 0.570344 +0.506816 0.570617 +0.506982 0.571086 +0.498991 0.570832 +0.499210 0.571302 +0.507216 0.571506 +0.507504 0.571846 +0.499517 0.571721 +0.499897 0.572062 +0.500789 0.567289 +0.501225 0.567245 +0.499990 0.569893 +0.501205 0.572489 +0.500769 0.572445 +0.500324 0.572305 +0.499897 0.572062 +0.499517 0.571721 +0.499210 0.571302 +0.498991 0.570832 +0.498866 0.570344 +0.498828 0.569867 +0.498870 0.569390 +0.498999 0.568902 +0.499221 0.568432 +0.499532 0.568013 +0.499914 0.567672 +0.500343 0.567429 +0.499990 0.569893 +0.499990 0.569893 +0.499990 0.569893 +0.499990 0.569893 +0.499990 0.569893 +0.499990 0.569893 +0.499990 0.569893 +0.499990 0.569893 +0.499990 0.569893 +0.499990 0.569893 +0.499990 0.569893 +0.499990 0.569893 +0.499990 0.569893 +0.499990 0.569893 +0.499990 0.569893 +0.499990 0.569893 +0.321879 0.661087 +0.321888 0.660431 +0.325497 0.660431 +0.325490 0.661087 +0.329732 0.660402 +0.334096 0.660372 +0.329724 0.661057 +0.338337 0.660343 +0.334087 0.661027 +0.338329 0.660998 +0.342172 0.660317 +0.342163 0.660973 +0.345333 0.660296 +0.345324 0.660952 +0.347627 0.660281 +0.347618 0.660937 +0.348970 0.660272 +0.348961 0.660928 +0.349389 0.660270 +0.349380 0.660925 +0.348938 0.660272 +0.347490 0.660281 +0.348929 0.660928 +0.347480 0.660937 +0.344942 0.660296 +0.344933 0.660952 +0.341331 0.660317 +0.341322 0.660973 +0.336860 0.660343 +0.336851 0.660998 +0.331869 0.660372 +0.331860 0.661027 +0.326759 0.660402 +0.326750 0.661057 +0.542059 0.658001 +0.542084 0.660624 +0.635394 0.660844 +0.635299 0.658222 +0.608155 0.660799 +0.589856 0.660757 +0.608082 0.658177 +0.589800 0.658134 +0.577145 0.660719 +0.567897 0.660688 +0.577099 0.658097 +0.567858 0.658066 +0.560388 0.660662 +0.560354 0.658040 +0.553696 0.660642 +0.547647 0.660628 +0.553667 0.658019 +0.547620 0.658006 +0.711436 0.651118 +0.724720 0.651254 +0.724806 0.661087 +0.721860 0.651224 +0.721920 0.661057 +0.718905 0.651194 +0.716047 0.651165 +0.718938 0.661027 +0.713497 0.651139 +0.716055 0.660998 +0.720869 0.661057 +0.723513 0.661087 +0.723445 0.651254 +0.720822 0.651224 +0.718160 0.661027 +0.715544 0.660998 +0.718136 0.651194 +0.715542 0.651165 +0.713195 0.660972 +0.711271 0.660950 +0.713212 0.651139 +0.711305 0.651118 +0.709884 0.660935 +0.709077 0.660927 +0.709930 0.651103 +0.709130 0.651095 +0.708824 0.660924 +0.708880 0.651092 +0.709086 0.660927 +0.709140 0.651095 +0.709928 0.660935 +0.709975 0.651103 +0.711402 0.660950 +0.713481 0.660972 +0.723105 0.567015 +0.723043 0.558821 +0.723651 0.558821 +0.723716 0.567015 +0.722250 0.558806 +0.722315 0.567001 +0.720804 0.558791 +0.720869 0.566986 +0.719402 0.558777 +0.719468 0.566971 +0.718144 0.558764 +0.718209 0.566958 +0.717114 0.558753 +0.717179 0.566948 +0.716372 0.558746 +0.716437 0.566940 +0.715933 0.558742 +0.715998 0.566936 +0.715778 0.558740 +0.715842 0.566935 +0.715877 0.558742 +0.715941 0.566936 +0.716253 0.558746 +0.716317 0.566940 +0.716922 0.558753 +0.716985 0.566948 +0.717866 0.558764 +0.717929 0.566958 +0.719033 0.558777 +0.719096 0.566971 +0.720342 0.558791 +0.720405 0.566986 +0.721706 0.558806 +0.721768 0.567001 +0.709735 0.655035 +0.707827 0.655014 +0.719265 0.558783 +0.722600 0.558821 +0.723280 0.655187 +0.724986 0.655187 +0.724163 0.558821 +0.721116 0.655148 +0.720445 0.558783 +0.717116 0.655108 +0.716605 0.558745 +0.713259 0.655069 +0.709837 0.655035 +0.712904 0.558708 +0.709622 0.558675 +0.707097 0.655007 +0.706992 0.558648 +0.705183 0.654987 +0.705154 0.558628 +0.704117 0.654975 +0.704130 0.558617 +0.703822 0.654971 +0.704204 0.654975 +0.703846 0.558614 +0.704213 0.558617 +0.705314 0.654987 +0.705579 0.654989 +0.705781 0.575021 +0.705281 0.558628 +0.707096 0.575035 +0.707076 0.558648 +0.707393 0.575038 +0.719824 0.655148 +0.715843 0.558745 +0.716276 0.655108 +0.712528 0.558708 +0.712837 0.655069 +0.709539 0.558675 +0.333871 0.661087 +0.333956 0.651254 +0.335232 0.651254 +0.335164 0.661087 +0.337855 0.651224 +0.337808 0.661057 +0.340541 0.651194 +0.340516 0.661027 +0.343135 0.651165 +0.343133 0.660998 +0.345465 0.651139 +0.345482 0.660972 +0.347372 0.651118 +0.348747 0.651103 +0.347406 0.660950 +0.348793 0.660935 +0.349547 0.651095 +0.349600 0.660927 +0.349797 0.651092 +0.349853 0.660924 +0.349537 0.651095 +0.349591 0.660927 +0.348702 0.651103 +0.348749 0.660935 +0.347241 0.651118 +0.347275 0.660950 +0.345179 0.651139 +0.345195 0.660972 +0.342629 0.651165 +0.342622 0.660998 +0.339772 0.651194 +0.339739 0.661027 +0.336817 0.651224 +0.336757 0.661057 +0.335634 0.558821 +0.335572 0.567015 +0.334961 0.567015 +0.335026 0.558821 +0.336362 0.567001 +0.336427 0.558806 +0.337808 0.566986 +0.339209 0.566971 +0.337873 0.558791 +0.340468 0.566958 +0.339274 0.558777 +0.341497 0.566948 +0.340533 0.558764 +0.341562 0.558753 +0.342240 0.566940 +0.342305 0.558746 +0.342679 0.566936 +0.342744 0.558742 +0.342834 0.566935 +0.342899 0.558740 +0.342735 0.566936 +0.342799 0.558742 +0.342360 0.566940 +0.341691 0.566948 +0.342424 0.558746 +0.341755 0.558753 +0.340747 0.566958 +0.340811 0.558764 +0.339581 0.566971 +0.339644 0.558777 +0.338272 0.566986 +0.338335 0.558791 +0.336909 0.567001 +0.336971 0.558806 +0.353363 0.654987 +0.353098 0.654989 +0.338232 0.558783 +0.334514 0.558821 +0.333690 0.655187 +0.335396 0.655187 +0.336077 0.558821 +0.338853 0.655148 +0.342401 0.655108 +0.339411 0.558783 +0.342834 0.558745 +0.345840 0.655069 +0.346149 0.558708 +0.348942 0.655035 +0.350850 0.655014 +0.351284 0.575038 +0.349138 0.558675 +0.351581 0.575035 +0.351601 0.558648 +0.352896 0.575021 +0.337561 0.655148 +0.342072 0.558745 +0.341561 0.655108 +0.345773 0.558708 +0.345418 0.655069 +0.349055 0.558675 +0.348839 0.655035 +0.351685 0.558648 +0.351579 0.655007 +0.353523 0.558628 +0.354547 0.558617 +0.353494 0.654987 +0.354559 0.654975 +0.354831 0.558614 +0.354855 0.654971 +0.354464 0.558617 +0.354473 0.654975 +0.353396 0.558628 +0.324490 0.534719 +0.276134 0.535298 +0.272867 0.535314 +0.272828 0.542853 +0.276095 0.542837 +0.281016 0.535253 +0.280976 0.542791 +0.287213 0.535182 +0.287171 0.542721 +0.294377 0.535095 +0.294333 0.542634 +0.302764 0.534990 +0.312869 0.534863 +0.302718 0.542529 +0.335077 0.538359 +0.337088 0.538335 +0.337114 0.534566 +0.324439 0.542258 +0.335051 0.542129 +0.312821 0.542402 +0.380405 0.664531 +0.384979 0.664480 +0.389096 0.664436 +0.395818 0.664369 +0.400444 0.664330 +0.403128 0.664406 +0.403028 0.664317 +0.403431 0.664611 +0.403787 0.664772 +0.404179 0.664878 +0.404582 0.664924 +0.404736 0.664926 +0.401583 0.664942 +0.396358 0.664988 +0.389506 0.665058 +0.381533 0.665146 +0.372270 0.665251 +0.361310 0.665378 +0.349057 0.665522 +0.336208 0.665676 +0.336202 0.665671 +0.336186 0.665620 +0.336171 0.665510 +0.336159 0.665344 +0.336148 0.665135 +0.336145 0.665045 +0.347272 0.664913 +0.358827 0.664777 +0.370115 0.664647 +0.375427 0.664586 +0.380476 0.664626 +0.388282 0.664541 +0.394987 0.664472 +0.400087 0.664428 +0.400379 0.664637 +0.400696 0.664788 +0.401043 0.664890 +0.401428 0.664940 +0.396216 0.664985 +0.389379 0.665055 +0.381423 0.665143 +0.372180 0.665247 +0.361245 0.665374 +0.349021 0.665518 +0.348931 0.665464 +0.348851 0.665359 +0.348777 0.665204 +0.348710 0.664992 +0.360689 0.664852 +0.371410 0.664728 +0.395255 0.664681 +0.395545 0.664833 +0.395862 0.664935 +0.388521 0.664750 +0.388780 0.664902 +0.389063 0.665004 +0.380682 0.664836 +0.380906 0.664988 +0.381151 0.665091 +0.371577 0.664939 +0.371759 0.665092 +0.371958 0.665195 +0.360810 0.665063 +0.360941 0.665217 +0.361085 0.665321 +0.688170 0.661893 +0.692870 0.661945 +0.702838 0.662057 +0.713025 0.662174 +0.722838 0.662289 +0.722838 0.662289 +0.663178 0.661760 +0.663177 0.661760 +0.683762 0.661844 +0.679710 0.661801 +0.676065 0.661763 +0.670141 0.661705 +0.663602 0.661737 +0.722822 0.662370 +0.712864 0.662282 +0.722806 0.662398 +0.722806 0.662398 +0.666135 0.661671 +0.664013 0.661660 +0.664012 0.661661 +0.665344 0.661771 +0.669412 0.661805 +0.675417 0.661864 +0.679109 0.661903 +0.683215 0.661947 +0.687680 0.661996 +0.692441 0.662049 +0.702541 0.662163 +0.711690 0.662241 +0.711777 0.662160 +0.691776 0.661933 +0.683761 0.661845 +0.701231 0.662039 +0.676857 0.661771 +0.670949 0.661712 +0.666524 0.661674 +0.666139 0.661751 +0.665742 0.661774 +0.670234 0.661812 +0.676222 0.661872 +0.683215 0.661947 +0.691334 0.662036 +0.700914 0.662144 +0.711600 0.662267 +0.670598 0.661789 +0.676544 0.661849 +0.683493 0.661923 +0.691559 0.662012 +0.701075 0.662119 +0.295020 0.662776 +0.291687 0.662814 +0.286201 0.662873 +0.282312 0.662906 +0.298721 0.662733 +0.302758 0.662685 +0.307088 0.662632 +0.316405 0.662520 +0.279963 0.662913 +0.279951 0.662917 +0.283570 0.661966 +0.289418 0.661600 +0.287478 0.661609 +0.287464 0.661609 +0.335485 0.661087 +0.335485 0.661087 +0.335669 0.661390 +0.326167 0.662403 +0.335839 0.662289 +0.335839 0.662285 +0.327236 0.661182 +0.318873 0.661279 +0.310844 0.661372 +0.307098 0.661416 +0.303597 0.661456 +0.300383 0.661492 +0.297488 0.661524 +0.292738 0.661572 +0.286092 0.661954 +0.282718 0.662899 +0.292423 0.662802 +0.298729 0.662729 +0.286971 0.662861 +0.306084 0.662641 +0.314894 0.662534 +0.324959 0.662413 +0.325563 0.661508 +0.326200 0.661194 +0.317565 0.661294 +0.309964 0.661383 +0.303588 0.661456 +0.298109 0.661517 +0.293382 0.661566 +0.289738 0.661598 +0.316188 0.661619 +0.307959 0.661716 +0.301073 0.661797 +0.295160 0.661864 +0.290054 0.661918 +0.281642 0.663026 +0.279241 0.663037 +0.302345 0.662800 +0.306730 0.662747 +0.316169 0.662633 +0.326064 0.662514 +0.298258 0.662850 +0.294512 0.662894 +0.291139 0.662933 +0.285584 0.662992 +0.335902 0.662418 +0.335873 0.662398 +0.335971 0.662649 +0.336031 0.663095 +0.336084 0.663748 +0.336130 0.664640 +0.336145 0.665045 +0.325204 0.665178 +0.314212 0.665313 +0.303781 0.665444 +0.298956 0.665504 +0.294468 0.665560 +0.290362 0.665610 +0.286666 0.665655 +0.280570 0.665722 +0.276204 0.665761 +0.273823 0.665363 +0.273471 0.665773 +0.274850 0.664454 +0.275981 0.663783 +0.277235 0.663318 +0.278659 0.663066 +0.297879 0.662876 +0.305402 0.662785 +0.314423 0.662675 +0.324740 0.662551 +0.291432 0.662952 +0.285857 0.663012 +0.281500 0.663052 +0.324498 0.662786 +0.324281 0.663236 +0.324084 0.663892 +0.323902 0.664788 +0.312643 0.664927 +0.302843 0.665050 +0.294701 0.665151 +0.287741 0.665236 +0.281719 0.665303 +0.276981 0.665347 +0.277940 0.664439 +0.278996 0.663769 +0.280169 0.663304 +0.313026 0.664028 +0.313444 0.663368 +0.313904 0.662915 +0.303391 0.664148 +0.303991 0.663485 +0.295380 0.664247 +0.296124 0.663582 +0.304654 0.663028 +0.296947 0.663122 +0.288527 0.664329 +0.289391 0.663662 +0.282599 0.664396 +0.283566 0.663727 +0.290348 0.663200 +0.284639 0.663263 +0.335736 0.567015 +0.335148 0.651254 +0.334054 0.651254 +0.334778 0.567015 +0.336493 0.651228 +0.337001 0.566992 +0.339012 0.651202 +0.341451 0.651178 +0.339295 0.566969 +0.343633 0.651155 +0.341515 0.566946 +0.343501 0.566926 +0.345403 0.651137 +0.345115 0.566909 +0.346664 0.651125 +0.347393 0.651117 +0.346266 0.566898 +0.346934 0.566891 +0.347630 0.651115 +0.347429 0.651117 +0.347153 0.566889 +0.346972 0.566891 +0.346755 0.651125 +0.346359 0.566898 +0.345585 0.651137 +0.343954 0.651155 +0.345292 0.566909 +0.343801 0.566926 +0.341955 0.651178 +0.339723 0.651202 +0.341972 0.566946 +0.339929 0.566969 +0.337410 0.651228 +0.337809 0.566992 +0.723898 0.567015 +0.724623 0.651254 +0.723529 0.651254 +0.722941 0.567015 +0.721267 0.651228 +0.720867 0.566992 +0.718953 0.651202 +0.718747 0.566969 +0.716722 0.651178 +0.716705 0.566946 +0.714723 0.651155 +0.714876 0.566926 +0.713091 0.651137 +0.711921 0.651125 +0.713385 0.566909 +0.712318 0.566898 +0.711248 0.651117 +0.711047 0.651115 +0.711705 0.566891 +0.711524 0.566889 +0.711284 0.651117 +0.711743 0.566891 +0.712013 0.651125 +0.712410 0.566898 +0.713274 0.651137 +0.715044 0.651155 +0.713562 0.566909 +0.715175 0.566926 +0.717225 0.651178 +0.717162 0.566946 +0.719664 0.651202 +0.719382 0.566969 +0.722184 0.651228 +0.721676 0.566992 +0.196136 0.551687 +0.212172 0.542853 +0.189975 0.551687 +0.171879 0.542853 +0.190091 0.554825 +0.171941 0.564794 +0.196289 0.554825 +0.213825 0.564794 +0.229430 0.554825 +0.245251 0.542853 +0.229126 0.551687 +0.247656 0.564794 +0.233887 0.551687 +0.215340 0.564794 +0.234206 0.554825 +0.213596 0.542853 +0.478183 0.553372 +0.499907 0.541356 +0.478655 0.550222 +0.497705 0.563378 +0.486995 0.550222 +0.465980 0.563378 +0.486584 0.553372 +0.469692 0.541356 +0.434718 0.553372 +0.448897 0.541356 +0.435322 0.550222 +0.444662 0.563378 +0.440092 0.550222 +0.426984 0.563378 +0.439486 0.553372 +0.431138 0.541356 +0.868702 0.551687 +0.886798 0.542853 +0.862540 0.551687 +0.846505 0.542853 +0.862388 0.554825 +0.844851 0.564794 +0.868585 0.554825 +0.886735 0.564794 +0.829551 0.551687 +0.845081 0.542853 +0.824789 0.551687 +0.813425 0.542853 +0.824471 0.554825 +0.811020 0.564794 +0.829247 0.554825 +0.843337 0.564794 +0.414884 0.654573 +0.416001 0.654573 +0.416285 0.631628 +0.415195 0.631628 +0.527432 0.654573 +0.531245 0.654573 +0.531183 0.631628 +0.527494 0.631628 +0.642676 0.654573 +0.643793 0.654573 +0.643482 0.631628 +0.642392 0.631628 +0.572093 0.553372 +0.588985 0.541356 +0.571681 0.550222 +0.592697 0.563378 +0.580022 0.550222 +0.560972 0.563378 +0.580493 0.553372 +0.558770 0.541356 +0.619191 0.553372 +0.627539 0.541356 +0.618585 0.550222 +0.631693 0.563378 +0.623355 0.550222 +0.614014 0.563378 +0.623959 0.553372 +0.609780 0.541356 +0.554156 0.577334 +0.554133 0.576742 +0.566070 0.576525 +0.566092 0.581596 +0.566077 0.581418 +0.566031 0.581236 +0.565952 0.581060 +0.565842 0.580902 +0.565708 0.580772 +0.565558 0.580677 +0.554132 0.576545 +0.565404 0.580619 +0.565253 0.580597 +0.555554 0.580072 +0.555284 0.579999 +0.555013 0.579806 +0.554758 0.579489 +0.554535 0.579055 +0.554356 0.578527 +0.554230 0.577941 +0.504553 0.561648 +0.504574 0.562238 +0.492666 0.563101 +0.492688 0.558030 +0.492701 0.558207 +0.492746 0.558388 +0.492823 0.558561 +0.492931 0.558715 +0.493064 0.558840 +0.493212 0.558929 +0.504573 0.562435 +0.493365 0.558981 +0.493514 0.558998 +0.503171 0.559013 +0.503440 0.559068 +0.503709 0.559240 +0.503962 0.559538 +0.504182 0.559956 +0.504358 0.560470 +0.504482 0.561047 +0.495289 0.576456 +0.495140 0.576508 +0.410165 0.533758 +0.565989 0.558030 +0.648511 0.533758 +0.566011 0.563101 +0.409331 0.664868 +0.492688 0.558030 +0.492666 0.563101 +0.495049 0.563101 +0.495195 0.563118 +0.495344 0.563170 +0.495487 0.563262 +0.495615 0.563389 +0.495718 0.563547 +0.495792 0.563723 +0.495834 0.563906 +0.563627 0.563101 +0.563482 0.563118 +0.563333 0.563170 +0.563190 0.563262 +0.563062 0.563390 +0.562959 0.563547 +0.562885 0.563723 +0.562843 0.563906 +0.562830 0.564085 +0.563010 0.576079 +0.562934 0.575903 +0.563115 0.576237 +0.563244 0.576364 +0.562891 0.575720 +0.563388 0.576456 +0.563537 0.576508 +0.563683 0.576525 +0.566070 0.576525 +0.562876 0.575541 +0.566092 0.581596 +0.649346 0.664868 +0.492584 0.581596 +0.492607 0.576525 +0.495847 0.564085 +0.494994 0.576525 +0.495800 0.575542 +0.495786 0.575720 +0.495742 0.575903 +0.495667 0.576080 +0.495562 0.576237 +0.495433 0.576364 +0.444662 0.563378 +0.426984 0.563378 +0.425469 0.654487 +0.442951 0.654487 +0.594677 0.563378 +0.596285 0.654487 +0.614014 0.654487 +0.612490 0.563378 +0.590843 0.541356 +0.594677 0.563378 +0.612490 0.563378 +0.608315 0.541356 +0.465980 0.563378 +0.464637 0.654487 +0.496680 0.654487 +0.497705 0.563378 +0.558390 0.563378 +0.530725 0.563378 +0.530937 0.654487 +0.559032 0.654487 +0.530588 0.541356 +0.530725 0.563378 +0.558390 0.563378 +0.556421 0.541356 +0.377672 0.574735 +0.377089 0.654713 +0.349952 0.563931 +0.338601 0.564065 +0.338160 0.655163 +0.349154 0.655033 +0.361591 0.563795 +0.360684 0.654899 +0.371969 0.563676 +0.370972 0.654781 +0.373598 0.654752 +0.380715 0.563578 +0.375189 0.574762 +0.398207 0.654499 +0.400813 0.654487 +0.402085 0.563378 +0.399432 0.563391 +0.393445 0.654540 +0.387093 0.654604 +0.394620 0.563433 +0.388216 0.563497 +0.379650 0.654684 +0.339078 0.542080 +0.339079 0.542059 +0.402085 0.563378 +0.405512 0.541356 +0.399408 0.563392 +0.402887 0.541368 +0.394584 0.563433 +0.398285 0.541407 +0.388169 0.563498 +0.391655 0.541473 +0.380659 0.563579 +0.383106 0.541567 +0.371904 0.563677 +0.361520 0.563796 +0.372970 0.541682 +0.349877 0.563932 +0.361797 0.541811 +0.338601 0.564065 +0.350275 0.541947 +0.338808 0.542067 +0.683488 0.574762 +0.685079 0.654752 +0.659031 0.563390 +0.656592 0.563378 +0.657863 0.654487 +0.663391 0.563426 +0.660436 0.654499 +0.669714 0.563489 +0.665180 0.654540 +0.677880 0.563577 +0.671516 0.654603 +0.678948 0.654683 +0.681588 0.654713 +0.687557 0.563686 +0.681004 0.574735 +0.720517 0.655163 +0.719856 0.564062 +0.709416 0.655032 +0.709189 0.563936 +0.697892 0.654898 +0.698211 0.563808 +0.687612 0.654780 +0.719856 0.564062 +0.719598 0.542080 +0.655790 0.541368 +0.653164 0.541356 +0.656592 0.563378 +0.660391 0.541407 +0.659228 0.563391 +0.667022 0.541473 +0.664031 0.563432 +0.675571 0.541567 +0.670427 0.563497 +0.677921 0.563578 +0.685706 0.541682 +0.686662 0.563676 +0.696879 0.541811 +0.697035 0.563795 +0.708402 0.541947 +0.708672 0.563930 +0.809871 0.655887 +0.809951 0.564794 +0.787884 0.564794 +0.787912 0.655887 +0.809951 0.564794 +0.812398 0.542853 +0.790340 0.542853 +0.787884 0.564794 +0.843235 0.655887 +0.843337 0.564794 +0.811020 0.564794 +0.811070 0.655887 +0.886629 0.655887 +0.886735 0.564794 +0.844851 0.564794 +0.844933 0.655887 +0.213744 0.655887 +0.213825 0.564794 +0.171941 0.564794 +0.172048 0.655887 +0.247607 0.655887 +0.247656 0.564794 +0.215340 0.564794 +0.215442 0.655887 +0.248805 0.655887 +0.270765 0.655887 +0.270793 0.564794 +0.248726 0.564794 +0.270793 0.564794 +0.268337 0.542853 +0.246279 0.542853 +0.248726 0.564794 +0.271569 0.655887 +0.275272 0.655887 +0.275257 0.564794 +0.271511 0.564794 +0.272828 0.542853 +0.269039 0.542853 +0.271511 0.564794 +0.275257 0.564794 +0.402085 0.563378 +0.400813 0.654487 +0.403821 0.654487 +0.405181 0.563378 +0.405512 0.541356 +0.402085 0.563378 +0.405181 0.563378 +0.408750 0.541356 +0.424283 0.654487 +0.425918 0.563378 +0.405783 0.563378 +0.404485 0.654487 +0.425918 0.563378 +0.430088 0.541356 +0.409359 0.541356 +0.405783 0.563378 +0.444663 0.654487 +0.462391 0.654487 +0.464000 0.563378 +0.446186 0.563378 +0.464000 0.563378 +0.467834 0.541356 +0.450361 0.541356 +0.446186 0.563378 +0.527739 0.654487 +0.527952 0.563378 +0.500286 0.563378 +0.499645 0.654487 +0.527952 0.563378 +0.528089 0.541356 +0.502255 0.541356 +0.500286 0.563378 +0.561997 0.654487 +0.594040 0.654487 +0.592697 0.563378 +0.560972 0.563378 +0.615726 0.654487 +0.633208 0.654487 +0.631693 0.563378 +0.614014 0.563378 +0.650632 0.615150 +0.652894 0.563378 +0.632759 0.563378 +0.651865 0.654487 +0.654192 0.654487 +0.651254 0.615150 +0.634394 0.654487 +0.651214 0.654487 +0.652894 0.563378 +0.649318 0.541356 +0.628589 0.541356 +0.632759 0.563378 +0.328667 0.655239 +0.518595 0.654669 +0.531245 0.654573 +0.559032 0.654487 +0.530937 0.654487 +0.540082 0.654669 +0.545244 0.654673 +0.560533 0.654514 +0.551224 0.654688 +0.558370 0.654714 +0.603440 0.654573 +0.594040 0.654487 +0.561997 0.654487 +0.616959 0.654514 +0.614014 0.654487 +0.596285 0.654487 +0.661368 0.654594 +0.651214 0.654487 +0.634394 0.654487 +0.654192 0.654487 +0.651865 0.654487 +0.661939 0.654573 +0.781311 0.655801 +0.787107 0.655887 +0.809871 0.655887 +0.787912 0.655887 +0.803972 0.655801 +0.213744 0.655887 +0.172048 0.655887 +0.217966 0.655801 +0.247607 0.655887 +0.215442 0.655887 +0.253485 0.655801 +0.396145 0.654573 +0.403821 0.654487 +0.414884 0.654573 +0.424283 0.654487 +0.404485 0.654487 +0.440002 0.654514 +0.442951 0.654487 +0.425469 0.654487 +0.462391 0.654487 +0.444663 0.654487 +0.452857 0.654573 +0.495046 0.654514 +0.496680 0.654487 +0.464637 0.654487 +0.633208 0.654487 +0.615726 0.654487 +0.642676 0.654573 +0.657863 0.654487 +0.654856 0.654487 +0.843235 0.655887 +0.811070 0.655887 +0.838884 0.655801 +0.886629 0.655887 +0.844933 0.655887 +0.886520 0.655801 +0.270765 0.655887 +0.248805 0.655887 +0.276581 0.655801 +0.275272 0.655887 +0.271569 0.655887 +0.527739 0.654487 +0.499645 0.654487 +0.527432 0.654573 +0.513433 0.654673 +0.507453 0.654688 +0.500307 0.654714 +0.491469 0.654749 +0.705579 0.654989 +0.681588 0.654713 +0.704144 0.654974 +0.769133 0.655756 +0.761299 0.655661 +0.741188 0.655384 +0.317489 0.655384 +0.297378 0.655661 +0.315815 0.655399 +0.385769 0.654618 +0.377089 0.654713 +0.353098 0.654989 +0.354532 0.654974 +0.392862 0.654546 +0.397954 0.654501 +0.354804 0.654972 +0.400813 0.654487 +0.353782 0.654984 +0.351569 0.655007 +0.289543 0.655756 +0.315174 0.655401 +0.283099 0.655828 +0.315709 0.655390 +0.278301 0.655872 +0.317372 0.655367 +0.320125 0.655333 +0.742862 0.655399 +0.775578 0.655828 +0.780376 0.655872 +0.743503 0.655401 +0.783405 0.655887 +0.742968 0.655390 +0.741304 0.655367 +0.672908 0.654618 +0.703873 0.654972 +0.665815 0.654546 +0.704895 0.654984 +0.660723 0.654501 +0.707108 0.655007 +0.710427 0.655041 +0.567208 0.654749 +0.480118 0.654793 +0.714804 0.655084 +0.738552 0.655333 +0.323986 0.655289 +0.348250 0.655041 +0.563631 0.654514 +0.498144 0.654514 +0.464971 0.654843 +0.444119 0.654894 +0.415347 0.654944 +0.578558 0.654793 +0.593706 0.654843 +0.614558 0.654894 +0.396738 0.654573 +0.277366 0.655801 +0.782096 0.655801 +0.662532 0.654573 +0.719841 0.655135 +0.643330 0.654944 +0.375087 0.654995 +0.734691 0.655289 +0.730010 0.655239 +0.724986 0.655187 +0.661935 0.654594 +0.643793 0.654573 +0.805192 0.655801 +0.618675 0.654514 +0.605819 0.654573 +0.840710 0.655801 +0.683590 0.654995 +0.733787 0.655046 +0.779275 0.655096 +0.811608 0.655140 +0.833258 0.655175 +0.848368 0.655201 +0.859679 0.655216 +0.868793 0.655220 +0.172157 0.655801 +0.189884 0.655220 +0.198997 0.655216 +0.210309 0.655201 +0.225419 0.655175 +0.247069 0.655140 +0.279402 0.655096 +0.324890 0.655046 +0.455236 0.654573 +0.219792 0.655801 +0.441718 0.654514 +0.254705 0.655801 +0.416001 0.654573 +0.343872 0.655084 +0.338836 0.655135 +0.333690 0.655187 +0.169968 0.655801 +0.152241 0.655220 +0.169968 0.655801 +0.516593 0.660624 +0.385139 0.660565 +0.673173 0.660586 +0.335485 0.661087 +0.337808 0.661057 +0.340516 0.661027 +0.327236 0.661182 +0.335164 0.661087 +0.332516 0.661116 +0.723192 0.661087 +0.726161 0.661116 +0.728882 0.661147 +0.714848 0.660992 +0.723513 0.661087 +0.720869 0.661057 +0.321879 0.661087 +0.423283 0.660844 +0.706196 0.660895 +0.718160 0.661027 +0.715544 0.660998 +0.731441 0.661182 +0.731528 0.661176 +0.733932 0.661202 +0.318873 0.661279 +0.329794 0.661147 +0.327149 0.661176 +0.343828 0.660992 +0.343133 0.660998 +0.345482 0.660972 +0.773308 0.661588 +0.334087 0.661027 +0.338329 0.660998 +0.673538 0.660565 +0.675164 0.660574 +0.678460 0.660601 +0.388995 0.660885 +0.352481 0.660895 +0.347406 0.660950 +0.348793 0.660935 +0.310844 0.661372 +0.324745 0.661202 +0.322732 0.661223 +0.739804 0.661279 +0.735945 0.661223 +0.737462 0.661238 +0.697726 0.660801 +0.713195 0.660972 +0.711271 0.660950 +0.326750 0.661057 +0.317179 0.661116 +0.447942 0.660804 +0.360950 0.660801 +0.349600 0.660927 +0.303597 0.661456 +0.321215 0.661238 +0.747832 0.661372 +0.738441 0.661247 +0.689983 0.660718 +0.709884 0.660935 +0.709077 0.660927 +0.683449 0.660650 +0.708824 0.660924 +0.738897 0.661250 +0.755080 0.661456 +0.738878 0.661247 +0.320236 0.661247 +0.297488 0.661524 +0.319780 0.661250 +0.349853 0.660924 +0.368694 0.660718 +0.349591 0.660927 +0.375228 0.660650 +0.348749 0.660935 +0.292738 0.661572 +0.319799 0.661247 +0.761188 0.661524 +0.738327 0.661238 +0.329724 0.661057 +0.765939 0.661572 +0.737176 0.661223 +0.769259 0.661600 +0.735425 0.661202 +0.289418 0.661600 +0.320350 0.661238 +0.287478 0.661609 +0.321500 0.661223 +0.380217 0.660601 +0.347275 0.660950 +0.383513 0.660574 +0.345195 0.660972 +0.342622 0.660998 +0.339739 0.661027 +0.336757 0.661057 +0.333871 0.661087 +0.325490 0.661087 +0.331029 0.661116 +0.321271 0.661116 +0.328186 0.661147 +0.342163 0.660973 +0.331860 0.661027 +0.343627 0.660926 +0.312595 0.661146 +0.466372 0.660763 +0.709086 0.660927 +0.316953 0.661146 +0.325530 0.661176 +0.323252 0.661202 +0.312765 0.661175 +0.733147 0.661176 +0.336851 0.660998 +0.345324 0.660952 +0.308452 0.661175 +0.297382 0.660965 +0.308950 0.661201 +0.480183 0.660724 +0.709928 0.660935 +0.341322 0.660973 +0.305037 0.661201 +0.261389 0.661001 +0.490780 0.660688 +0.305725 0.661222 +0.730491 0.661147 +0.347618 0.660937 +0.344933 0.660952 +0.302541 0.661222 +0.236558 0.661029 +0.348961 0.660928 +0.303238 0.661237 +0.499155 0.660660 +0.711402 0.660950 +0.727647 0.661116 +0.347480 0.660937 +0.301026 0.661237 +0.219333 0.661050 +0.301550 0.661246 +0.349380 0.660925 +0.505975 0.660639 +0.724806 0.661087 +0.713481 0.660972 +0.716055 0.660998 +0.718938 0.661027 +0.721920 0.661057 +0.771199 0.661609 +0.829975 0.661588 +0.300641 0.661248 +0.300437 0.661246 +0.206699 0.661062 +0.196770 0.661065 +0.861907 0.661065 +0.851978 0.661062 +0.839344 0.661050 +0.624603 0.660586 +0.822119 0.661029 +0.797287 0.661001 +0.761295 0.660965 +0.715050 0.660926 +0.669682 0.660885 +0.635394 0.660844 +0.610735 0.660804 +0.592305 0.660763 +0.578493 0.660724 +0.567897 0.660688 +0.559522 0.660660 +0.552702 0.660639 +0.348929 0.660928 +0.511686 0.660627 +0.546991 0.660627 +0.542084 0.660624 +0.056756 0.661588 +0.054647 0.661609 +0.113423 0.661588 +0.056756 0.661588 +0.113423 0.661588 +0.113423 0.661588 +0.113423 0.661588 +0.113423 0.661588 +0.113423 0.661588 +0.145354 0.661065 +0.113423 0.661588 +0.726092 0.567038 +0.727028 0.651279 +0.724623 0.651254 +0.723898 0.567015 +0.722941 0.567015 +0.723529 0.651254 +0.725019 0.567038 +0.725796 0.651279 +0.727157 0.567062 +0.728127 0.651305 +0.729236 0.567085 +0.730393 0.651329 +0.731122 0.567105 +0.732452 0.651352 +0.732698 0.567121 +0.733878 0.567133 +0.734173 0.651370 +0.735466 0.651382 +0.734630 0.567140 +0.736294 0.651390 +0.734968 0.567142 +0.734930 0.567140 +0.736673 0.651392 +0.734471 0.567133 +0.736641 0.651390 +0.736154 0.651382 +0.733545 0.567121 +0.735155 0.651370 +0.732155 0.567105 +0.733648 0.651352 +0.730366 0.567085 +0.731700 0.651329 +0.728296 0.567062 +0.729440 0.651305 +0.723043 0.558821 +0.729356 0.558897 +0.724385 0.558836 +0.732680 0.558934 +0.725768 0.558851 +0.735702 0.558967 +0.727111 0.558865 +0.738237 0.558994 +0.728329 0.558878 +0.740157 0.559014 +0.729343 0.558889 +0.741407 0.559025 +0.730097 0.558896 +0.742007 0.559028 +0.730570 0.558900 +0.742013 0.559025 +0.730774 0.558902 +0.741351 0.559014 +0.730733 0.558900 +0.739930 0.558994 +0.730421 0.558896 +0.737735 0.558967 +0.729810 0.558889 +0.734853 0.558934 +0.728907 0.558878 +0.731467 0.558897 +0.727756 0.558865 +0.727820 0.558859 +0.726435 0.558851 +0.724163 0.558821 +0.725037 0.558836 +0.720445 0.558783 +0.723651 0.558821 +0.716605 0.558745 +0.722250 0.558806 +0.712904 0.558708 +0.720804 0.558791 +0.709622 0.558675 +0.719402 0.558777 +0.706992 0.558648 +0.718144 0.558764 +0.705154 0.558628 +0.717114 0.558753 +0.704130 0.558617 +0.716372 0.558746 +0.703846 0.558614 +0.715933 0.558742 +0.704213 0.558617 +0.715778 0.558740 +0.705281 0.558628 +0.715877 0.558742 +0.707076 0.558648 +0.716253 0.558746 +0.709539 0.558675 +0.716922 0.558753 +0.712528 0.558708 +0.717866 0.558764 +0.715843 0.558745 +0.719033 0.558777 +0.719265 0.558783 +0.720342 0.558791 +0.722600 0.558821 +0.721706 0.558806 +0.725933 0.558859 +0.723105 0.567015 +0.718747 0.566969 +0.721768 0.567001 +0.716705 0.566946 +0.720405 0.566986 +0.714876 0.566926 +0.719096 0.566971 +0.713385 0.566909 +0.717929 0.566958 +0.712318 0.566898 +0.716985 0.566948 +0.711705 0.566891 +0.716317 0.566940 +0.711524 0.566889 +0.715941 0.566936 +0.711743 0.566891 +0.715842 0.566935 +0.712410 0.566898 +0.715998 0.566936 +0.713562 0.566909 +0.716437 0.566940 +0.715175 0.566926 +0.717179 0.566948 +0.717162 0.566946 +0.718209 0.566958 +0.719382 0.566969 +0.719468 0.566971 +0.721676 0.566992 +0.720869 0.566986 +0.723898 0.567015 +0.722315 0.567001 +0.726092 0.567038 +0.723716 0.567015 +0.728296 0.567062 +0.725102 0.567030 +0.730366 0.567085 +0.726499 0.567045 +0.732155 0.567105 +0.727820 0.567060 +0.733545 0.567121 +0.728970 0.567072 +0.734471 0.567133 +0.729873 0.567083 +0.734930 0.567140 +0.730484 0.567090 +0.734968 0.567142 +0.730796 0.567095 +0.734630 0.567140 +0.730836 0.567096 +0.733878 0.567133 +0.730632 0.567095 +0.732698 0.567121 +0.730159 0.567090 +0.731122 0.567105 +0.729405 0.567083 +0.729236 0.567085 +0.728391 0.567072 +0.727157 0.567062 +0.727173 0.567060 +0.725019 0.567038 +0.725830 0.567045 +0.722941 0.567015 +0.724447 0.567030 +0.720867 0.566992 +0.724679 0.655211 +0.738811 0.655360 +0.758133 0.655622 +0.735675 0.655326 +0.701978 0.654945 +0.685079 0.654752 +0.707827 0.655014 +0.720517 0.655163 +0.720590 0.655163 +0.710899 0.655047 +0.714699 0.655090 +0.718942 0.655138 +0.742514 0.655429 +0.724581 0.655211 +0.731857 0.655284 +0.727616 0.655236 +0.723280 0.655187 +0.323210 0.651382 +0.332585 0.567038 +0.334778 0.567015 +0.334054 0.651254 +0.330381 0.567062 +0.331649 0.651279 +0.329237 0.651305 +0.328311 0.567085 +0.326977 0.651329 +0.326522 0.567105 +0.325029 0.651352 +0.325132 0.567121 +0.324206 0.567133 +0.323521 0.651370 +0.322523 0.651382 +0.323747 0.567140 +0.323709 0.567142 +0.322035 0.651390 +0.324047 0.567140 +0.322004 0.651392 +0.322383 0.651390 +0.324798 0.567133 +0.332881 0.651279 +0.335148 0.651254 +0.335736 0.567015 +0.330550 0.651305 +0.333657 0.567038 +0.331519 0.567062 +0.328283 0.651329 +0.329441 0.567085 +0.326225 0.651352 +0.324504 0.651370 +0.327554 0.567105 +0.325979 0.567121 +0.269311 0.535373 +0.714766 0.534485 +0.714733 0.534485 +0.739004 0.534783 +0.727982 0.534646 +0.330595 0.534646 +0.330694 0.534646 +0.355361 0.534348 +0.343944 0.534485 +0.651252 0.533770 +0.653114 0.533817 +0.655863 0.533808 +0.655804 0.533830 +0.662395 0.533874 +0.660549 0.533870 +0.670765 0.533967 +0.667413 0.533939 +0.680708 0.534081 +0.676278 0.534036 +0.691762 0.534211 +0.686782 0.534156 +0.703316 0.534348 +0.698323 0.534290 +0.710155 0.534429 +0.728081 0.534646 +0.721563 0.534566 +0.732786 0.534702 +0.749826 0.534921 +0.744063 0.534841 +0.759924 0.535050 +0.754758 0.534975 +0.768858 0.535165 +0.764300 0.535095 +0.776341 0.535257 +0.772288 0.535192 +0.782241 0.535323 +0.778528 0.535262 +0.786555 0.535361 +0.783002 0.535302 +0.789365 0.535373 +0.648511 0.533758 +0.405562 0.533817 +0.410165 0.533758 +0.402873 0.533830 +0.407425 0.533770 +0.398128 0.533870 +0.402813 0.533808 +0.391264 0.533939 +0.396282 0.533874 +0.382399 0.534036 +0.387912 0.533967 +0.371895 0.534156 +0.377968 0.534081 +0.360354 0.534290 +0.366915 0.534211 +0.348521 0.534429 +0.337114 0.534566 +0.343911 0.534485 +0.325891 0.534702 +0.314614 0.534841 +0.319673 0.534783 +0.303919 0.534975 +0.308851 0.534921 +0.294377 0.535095 +0.298753 0.535050 +0.286388 0.535192 +0.289819 0.535165 +0.280148 0.535262 +0.282336 0.535257 +0.275675 0.535302 +0.276436 0.535323 +0.272867 0.535314 +0.272122 0.535361 +0.785810 0.535314 +0.069258 0.535314 +0.072813 0.535373 +0.069258 0.535314 +0.653941 0.664926 +0.343000 0.665595 +0.343037 0.665595 +0.318824 0.665893 +0.329812 0.665756 +0.728968 0.665756 +0.728864 0.665756 +0.704229 0.665458 +0.715639 0.665595 +0.406599 0.664880 +0.404736 0.664926 +0.401984 0.664918 +0.402055 0.664939 +0.395437 0.664984 +0.397304 0.664979 +0.387045 0.665077 +0.390422 0.665049 +0.377079 0.665191 +0.381533 0.665146 +0.366008 0.665321 +0.371004 0.665266 +0.354448 0.665458 +0.359445 0.665400 +0.347607 0.665539 +0.329709 0.665756 +0.336208 0.665676 +0.325005 0.665812 +0.308044 0.666031 +0.313760 0.665951 +0.297992 0.666160 +0.303104 0.666086 +0.289101 0.666275 +0.293602 0.666205 +0.281655 0.666367 +0.285647 0.666303 +0.275782 0.666433 +0.279432 0.666372 +0.271483 0.666471 +0.274971 0.666412 +0.268675 0.666483 +0.272162 0.666425 +0.790002 0.666483 +0.787193 0.666471 +0.786515 0.666425 +0.782894 0.666433 +0.783706 0.666412 +0.777021 0.666367 +0.779245 0.666372 +0.769575 0.666275 +0.773029 0.666303 +0.760685 0.666160 +0.765075 0.666205 +0.750633 0.666031 +0.755573 0.666086 +0.739853 0.665893 +0.744917 0.665951 +0.733672 0.665812 +0.715676 0.665595 +0.722469 0.665676 +0.711069 0.665539 +0.692669 0.665321 +0.699232 0.665400 +0.681598 0.665191 +0.687673 0.665266 +0.671632 0.665077 +0.677144 0.665146 +0.663240 0.664984 +0.668254 0.665049 +0.656693 0.664918 +0.661373 0.664979 +0.652078 0.664880 +0.656622 0.664939 +0.649346 0.664868 +0.409331 0.664868 +0.069962 0.666425 +0.069962 0.666425 +0.073449 0.666483 +0.298302 0.535056 +0.330694 0.534646 +0.329812 0.665756 +0.320704 0.534771 +0.308649 0.534923 +0.319851 0.665881 +0.268675 0.666483 +0.269311 0.535373 +0.271159 0.666474 +0.275880 0.666432 +0.271797 0.535364 +0.281972 0.666363 +0.276534 0.535322 +0.282654 0.535253 +0.289101 0.666275 +0.289819 0.535165 +0.297543 0.666166 +0.307843 0.666033 +0.407759 0.533768 +0.410165 0.533758 +0.343037 0.665595 +0.343944 0.534485 +0.353365 0.665471 +0.366227 0.665318 +0.354278 0.534361 +0.367133 0.534208 +0.377578 0.665185 +0.378467 0.534075 +0.387045 0.665077 +0.395081 0.664988 +0.387912 0.533967 +0.401877 0.664919 +0.395927 0.533878 +0.406933 0.664878 +0.402707 0.533809 +0.409331 0.664868 +0.269311 0.535373 +0.268675 0.666483 +0.073449 0.666483 +0.072813 0.535373 +0.073449 0.666483 +0.738826 0.665881 +0.728864 0.665756 +0.789365 0.535373 +0.790002 0.666483 +0.786879 0.535364 +0.782143 0.535322 +0.787518 0.666474 +0.782797 0.666432 +0.776023 0.535253 +0.776705 0.666363 +0.768858 0.535165 +0.760374 0.535056 +0.769575 0.666275 +0.750028 0.534923 +0.761133 0.666166 +0.750834 0.666033 +0.737973 0.534771 +0.727982 0.534646 +0.671632 0.665077 +0.649346 0.664868 +0.648511 0.533758 +0.651744 0.664878 +0.650918 0.533768 +0.656800 0.664919 +0.663596 0.664988 +0.655970 0.533809 +0.714733 0.534485 +0.715639 0.665595 +0.704399 0.534361 +0.705312 0.665471 +0.691543 0.534208 +0.692450 0.665318 +0.680210 0.534075 +0.670765 0.533967 +0.681098 0.665185 +0.662750 0.533878 +0.395575 0.661759 +0.663101 0.661759 +0.665344 0.661771 +0.665272 0.661770 +0.669412 0.661805 +0.669346 0.661804 +0.675417 0.661864 +0.675359 0.661863 +0.683215 0.661947 +0.683165 0.661946 +0.692441 0.662049 +0.692402 0.662048 +0.702541 0.662163 +0.702514 0.662163 +0.712864 0.662282 +0.712849 0.662282 +0.722806 0.662398 +0.722803 0.662398 +0.732604 0.662514 +0.732612 0.662514 +0.742488 0.662633 +0.742508 0.662633 +0.751918 0.662747 +0.751947 0.662747 +0.760381 0.662849 +0.760419 0.662850 +0.767493 0.662932 +0.767538 0.662933 +0.773042 0.662991 +0.773093 0.662992 +0.776979 0.663025 +0.777034 0.663026 +0.779377 0.663036 +0.779436 0.663037 +0.279299 0.663036 +0.279241 0.663037 +0.281698 0.663025 +0.281642 0.663026 +0.285635 0.662991 +0.285584 0.662992 +0.291184 0.662932 +0.291139 0.662933 +0.298296 0.662849 +0.298258 0.662850 +0.306759 0.662747 +0.306730 0.662747 +0.316188 0.662633 +0.316169 0.662633 +0.326073 0.662514 +0.326064 0.662514 +0.335870 0.662398 +0.335873 0.662398 +0.345813 0.662282 +0.345828 0.662282 +0.356136 0.662163 +0.356163 0.662163 +0.366236 0.662049 +0.366274 0.662048 +0.375462 0.661947 +0.375512 0.661946 +0.383260 0.661864 +0.383318 0.661863 +0.389265 0.661805 +0.389331 0.661804 +0.393333 0.661771 +0.393404 0.661770 +0.395500 0.661760 +0.663177 0.661760 +0.062825 0.663036 +0.062884 0.663037 +0.062825 0.663036 +0.273823 0.665363 +0.068653 0.665773 +0.273471 0.665773 +0.068301 0.665363 +0.278659 0.663066 +0.279241 0.663037 +0.062884 0.663037 +0.063465 0.663066 +0.277235 0.663318 +0.064889 0.663318 +0.275981 0.663783 +0.066144 0.663783 +0.274850 0.664454 +0.067274 0.664454 +0.068301 0.665363 +0.068653 0.665773 +0.068301 0.665363 +0.062884 0.663037 +0.063465 0.663066 +0.064889 0.663318 +0.064889 0.663318 +0.066144 0.663783 +0.066144 0.663783 +0.067274 0.664454 +0.067274 0.664454 +0.345828 0.662282 +0.335873 0.662398 +0.379622 0.661902 +0.383318 0.661863 +0.389331 0.661804 +0.393404 0.661770 +0.375512 0.661946 +0.371041 0.661995 +0.366274 0.662048 +0.356163 0.662163 +0.396324 0.661771 +0.395575 0.661759 +0.398161 0.661980 +0.399782 0.662407 +0.401245 0.663042 +0.402573 0.663918 +0.403028 0.664317 +0.400444 0.664330 +0.395818 0.664369 +0.389096 0.664436 +0.384979 0.664480 +0.380405 0.664531 +0.375427 0.664586 +0.370115 0.664647 +0.358827 0.664777 +0.347272 0.664913 +0.336130 0.664640 +0.336145 0.665045 +0.336084 0.663748 +0.336031 0.663095 +0.335971 0.662649 +0.335902 0.662418 +0.376002 0.661960 +0.383085 0.661885 +0.389150 0.661824 +0.393709 0.661785 +0.367781 0.662051 +0.358078 0.662161 +0.347253 0.662286 +0.395430 0.661994 +0.396949 0.662421 +0.398318 0.663057 +0.399561 0.663934 +0.394505 0.663978 +0.387852 0.664045 +0.380106 0.664130 +0.371109 0.664231 +0.360473 0.664354 +0.348590 0.664492 +0.348307 0.663603 +0.347994 0.662954 +0.347646 0.662512 +0.393367 0.663100 +0.392115 0.662463 +0.390725 0.662035 +0.386838 0.663166 +0.385722 0.662528 +0.379232 0.663248 +0.378271 0.662608 +0.384485 0.662098 +0.377207 0.662176 +0.370400 0.663348 +0.369620 0.662705 +0.359963 0.663467 +0.359401 0.662822 +0.368757 0.662270 +0.358780 0.662383 +0.754895 0.665444 +0.656103 0.663918 +0.655649 0.664317 +0.780017 0.663066 +0.779436 0.663037 +0.744465 0.665313 +0.733473 0.665178 +0.722532 0.665045 +0.711405 0.664913 +0.699850 0.664777 +0.688561 0.664647 +0.678271 0.664531 +0.669581 0.664436 +0.662859 0.664369 +0.658233 0.664330 +0.657432 0.663042 +0.658894 0.662407 +0.660516 0.661980 +0.662353 0.661771 +0.663101 0.661759 +0.665272 0.661770 +0.669346 0.661804 +0.675359 0.661863 +0.683165 0.661946 +0.692402 0.662048 +0.702514 0.662163 +0.712849 0.662282 +0.722803 0.662398 +0.732612 0.662514 +0.742508 0.662633 +0.751947 0.662747 +0.760419 0.662850 +0.767538 0.662933 +0.773093 0.662992 +0.777034 0.663026 +0.781441 0.663318 +0.782696 0.663783 +0.783827 0.664454 +0.784854 0.665363 +0.785205 0.665773 +0.782472 0.665761 +0.778106 0.665722 +0.772011 0.665655 +0.764208 0.665560 +0.754713 0.665036 +0.744343 0.664906 +0.733418 0.664772 +0.722547 0.664640 +0.711493 0.664509 +0.700013 0.664375 +0.688797 0.664245 +0.678571 0.664130 +0.669934 0.664036 +0.663254 0.663969 +0.658662 0.663930 +0.659916 0.663053 +0.661296 0.662418 +0.662828 0.661991 +0.664564 0.661782 +0.668694 0.661816 +0.674779 0.661876 +0.682675 0.661960 +0.692018 0.662064 +0.702247 0.662180 +0.712704 0.662300 +0.722775 0.662418 +0.732696 0.662536 +0.742702 0.662657 +0.752241 0.662773 +0.760798 0.662876 +0.767987 0.662960 +0.773598 0.663020 +0.777582 0.663055 +0.778925 0.663307 +0.780108 0.663772 +0.781173 0.664442 +0.782141 0.665351 +0.777800 0.665312 +0.771737 0.665245 +0.763975 0.665151 +0.776907 0.664404 +0.775925 0.663735 +0.774835 0.663271 +0.770938 0.664338 +0.770061 0.663671 +0.763297 0.664247 +0.762553 0.663582 +0.769089 0.663209 +0.761729 0.663122 +0.754183 0.664134 +0.753603 0.663472 +0.743989 0.664007 +0.743603 0.663348 +0.752963 0.663015 +0.743179 0.662895 +0.733261 0.663876 +0.733090 0.663220 +0.722593 0.663748 +0.722646 0.663095 +0.732904 0.662771 +0.722705 0.662649 +0.711749 0.663619 +0.712033 0.662970 +0.700489 0.663488 +0.701012 0.662842 +0.712348 0.662527 +0.701592 0.662403 +0.689483 0.663361 +0.690238 0.662718 +0.679445 0.663248 +0.680406 0.662608 +0.691073 0.662283 +0.681470 0.662176 +0.670964 0.663157 +0.672098 0.662519 +0.664410 0.663091 +0.665682 0.662455 +0.673355 0.662089 +0.667094 0.662027 +0.398161 0.661980 +0.402573 0.663918 +0.403028 0.664317 +0.655649 0.664317 +0.401245 0.663042 +0.656103 0.663918 +0.657432 0.663042 +0.399782 0.662407 +0.662353 0.661771 +0.663101 0.661759 +0.395575 0.661759 +0.660516 0.661980 +0.396324 0.661771 +0.658894 0.662407 +0.279962 0.662913 +0.062162 0.662913 +0.062173 0.662917 +0.279951 0.662917 +0.287464 0.661609 +0.287478 0.661609 +0.054647 0.661609 +0.054660 0.661609 +0.283570 0.661966 +0.058554 0.661966 +0.062162 0.662913 +0.062162 0.662913 +0.062162 0.662913 +0.054647 0.661609 +0.054660 0.661609 +0.058554 0.661966 +0.058554 0.661966 +0.370506 0.661893 +0.365807 0.661945 +0.355839 0.662057 +0.345652 0.662174 +0.374915 0.661844 +0.378967 0.661801 +0.382611 0.661763 +0.388536 0.661705 +0.335839 0.662285 +0.335839 0.662289 +0.335669 0.661390 +0.343828 0.660992 +0.335485 0.661087 +0.335485 0.661087 +0.385156 0.660565 +0.385139 0.660565 +0.390057 0.660814 +0.392542 0.661671 +0.394664 0.661660 +0.394649 0.661657 +0.383513 0.660574 +0.380217 0.660601 +0.375228 0.660650 +0.372137 0.660682 +0.368694 0.660718 +0.364946 0.660758 +0.360950 0.660801 +0.352481 0.660895 +0.345925 0.661272 +0.346896 0.662156 +0.366892 0.661929 +0.374905 0.661840 +0.357439 0.662035 +0.381807 0.661767 +0.387713 0.661708 +0.392138 0.661670 +0.387827 0.660826 +0.383214 0.660576 +0.379554 0.660608 +0.374569 0.660657 +0.368705 0.660718 +0.361889 0.660791 +0.353852 0.660879 +0.344892 0.660980 +0.383772 0.660861 +0.378308 0.660915 +0.371905 0.660982 +0.364469 0.661063 +0.355701 0.661161 +0.776364 0.662906 +0.778726 0.662917 +0.778714 0.662913 +0.775107 0.661966 +0.771212 0.661609 +0.771199 0.661609 +0.769259 0.661600 +0.765939 0.661572 +0.761188 0.661524 +0.755080 0.661456 +0.747832 0.661372 +0.739804 0.661279 +0.731441 0.661182 +0.723192 0.661087 +0.714848 0.660992 +0.706196 0.660895 +0.697726 0.660801 +0.689983 0.660718 +0.683449 0.660650 +0.678460 0.660601 +0.675164 0.660574 +0.673538 0.660565 +0.673522 0.660565 +0.668620 0.660814 +0.664027 0.661657 +0.664013 0.661660 +0.666135 0.661671 +0.670141 0.661705 +0.676065 0.661763 +0.683762 0.661844 +0.692870 0.661945 +0.702838 0.662057 +0.713025 0.662174 +0.722838 0.662289 +0.732510 0.662403 +0.742271 0.662520 +0.751589 0.662632 +0.759956 0.662733 +0.766989 0.662814 +0.772476 0.662873 +0.772466 0.662869 +0.776353 0.662902 +0.772950 0.661956 +0.769272 0.661600 +0.765950 0.661572 +0.761199 0.661524 +0.755089 0.661456 +0.747839 0.661372 +0.739808 0.661279 +0.731442 0.661182 +0.723192 0.661087 +0.714845 0.660992 +0.706190 0.660895 +0.697718 0.660801 +0.689972 0.660718 +0.683436 0.660650 +0.678445 0.660601 +0.675148 0.660573 +0.670497 0.660823 +0.666149 0.661667 +0.670154 0.661701 +0.676077 0.661759 +0.683772 0.661840 +0.692878 0.661941 +0.702843 0.662053 +0.713028 0.662170 +0.722838 0.662285 +0.732508 0.662399 +0.742267 0.662516 +0.751583 0.662628 +0.759948 0.662729 +0.766980 0.662810 +0.769333 0.661925 +0.764197 0.661872 +0.757604 0.661797 +0.749773 0.661705 +0.741075 0.661602 +0.731989 0.661495 +0.723007 0.661390 +0.713908 0.661285 +0.704465 0.661178 +0.695222 0.661075 +0.686772 0.660982 +0.679634 0.660908 +0.674159 0.660854 +0.394664 0.661660 +0.664013 0.661660 +0.673522 0.660565 +0.673538 0.660565 +0.385139 0.660565 +0.668620 0.660814 +0.385155 0.660565 +0.390057 0.660814 +0.664027 0.661657 +0.394649 0.661657 +0.062825 0.663036 +0.279299 0.663036 +0.279951 0.662917 +0.062173 0.662917 +0.279950 0.662917 +0.062174 0.662917 +0.279630 0.663003 +0.062494 0.663003 +0.279300 0.663036 +0.062824 0.663036 +0.062825 0.663036 +0.062174 0.662917 +0.062174 0.662917 +0.062494 0.663003 +0.062494 0.663003 +0.062824 0.663036 +0.062824 0.663036 +0.279300 0.663036 +0.279299 0.663036 +0.394665 0.661661 +0.394664 0.661660 +0.393333 0.661771 +0.395500 0.661760 +0.395499 0.661760 +0.395075 0.661737 +0.392542 0.661671 +0.388536 0.661705 +0.382611 0.661763 +0.374915 0.661844 +0.365807 0.661945 +0.355839 0.662057 +0.345652 0.662174 +0.335839 0.662289 +0.326167 0.662403 +0.316405 0.662520 +0.307088 0.662632 +0.298721 0.662733 +0.291687 0.662814 +0.286201 0.662873 +0.282312 0.662906 +0.279951 0.662917 +0.279950 0.662917 +0.279630 0.663003 +0.281698 0.663025 +0.285635 0.662991 +0.291184 0.662932 +0.298296 0.662849 +0.306759 0.662747 +0.316188 0.662633 +0.326073 0.662514 +0.335870 0.662398 +0.345813 0.662282 +0.356136 0.662163 +0.366236 0.662049 +0.375462 0.661947 +0.383260 0.661864 +0.389265 0.661805 +0.389264 0.661805 +0.393332 0.661771 +0.392931 0.661748 +0.392543 0.661671 +0.388537 0.661705 +0.382612 0.661763 +0.374916 0.661845 +0.365808 0.661945 +0.355839 0.662058 +0.345652 0.662175 +0.335839 0.662289 +0.326167 0.662403 +0.316405 0.662520 +0.307088 0.662633 +0.298720 0.662733 +0.291687 0.662815 +0.286200 0.662873 +0.282311 0.662907 +0.282010 0.662993 +0.281699 0.663025 +0.285636 0.662991 +0.291185 0.662932 +0.298297 0.662849 +0.306760 0.662747 +0.316189 0.662633 +0.326073 0.662514 +0.335870 0.662398 +0.345813 0.662282 +0.356135 0.662163 +0.366235 0.662049 +0.375461 0.661947 +0.383258 0.661864 +0.285922 0.662959 +0.291439 0.662900 +0.298512 0.662818 +0.306926 0.662717 +0.316298 0.662603 +0.326120 0.662486 +0.335854 0.662370 +0.345731 0.662255 +0.355985 0.662137 +0.366018 0.662024 +0.375184 0.661923 +0.382930 0.661840 +0.388895 0.661782 +0.763657 0.662776 +0.766989 0.662814 +0.772476 0.662873 +0.776364 0.662906 +0.778727 0.662917 +0.778726 0.662917 +0.722806 0.662398 +0.722806 0.662398 +0.759956 0.662733 +0.755919 0.662685 +0.751589 0.662632 +0.742271 0.662520 +0.722822 0.662370 +0.779047 0.663003 +0.776979 0.663025 +0.779377 0.663036 +0.779376 0.663036 +0.732510 0.662403 +0.722838 0.662289 +0.722838 0.662289 +0.732604 0.662514 +0.742488 0.662633 +0.751918 0.662747 +0.756298 0.662800 +0.760381 0.662849 +0.764123 0.662893 +0.767493 0.662932 +0.773042 0.662991 +0.776270 0.662990 +0.775970 0.662904 +0.759956 0.662733 +0.766264 0.662807 +0.771716 0.662866 +0.752600 0.662645 +0.743788 0.662538 +0.733720 0.662418 +0.733774 0.662500 +0.733829 0.662529 +0.744022 0.662651 +0.752939 0.662759 +0.760380 0.662849 +0.766758 0.662923 +0.772272 0.662983 +0.776578 0.663022 +0.743903 0.662622 +0.752767 0.662729 +0.760165 0.662818 +0.766507 0.662892 +0.771990 0.662951 +0.664012 0.661661 +0.395500 0.661760 +0.663177 0.661760 +0.395499 0.661760 +0.663178 0.661760 +0.395075 0.661737 +0.663602 0.661737 +0.394665 0.661661 +0.664013 0.661660 +0.394664 0.661660 +0.068730 0.665864 +0.273394 0.665864 +0.273471 0.665773 +0.068653 0.665773 +0.069845 0.666419 +0.069962 0.666425 +0.272162 0.666425 +0.272279 0.666419 +0.069537 0.666362 +0.272587 0.666362 +0.069238 0.666247 +0.272886 0.666247 +0.068964 0.666077 +0.273160 0.666077 +0.068964 0.666077 +0.068730 0.665864 +0.068653 0.665773 +0.069845 0.666419 +0.069845 0.666419 +0.069845 0.666419 +0.069537 0.666362 +0.069537 0.666362 +0.069238 0.666247 +0.069238 0.666247 +0.068964 0.666077 +0.312021 0.665973 +0.301953 0.666100 +0.293602 0.666205 +0.286468 0.666293 +0.336148 0.665135 +0.336145 0.665045 +0.323607 0.665829 +0.336208 0.665676 +0.280296 0.666363 +0.275429 0.666409 +0.272162 0.666425 +0.272279 0.666419 +0.272587 0.666362 +0.272886 0.666247 +0.273160 0.666077 +0.273394 0.665864 +0.273471 0.665773 +0.276204 0.665761 +0.280570 0.665722 +0.286666 0.665655 +0.290362 0.665610 +0.294468 0.665560 +0.298956 0.665504 +0.303781 0.665444 +0.314212 0.665313 +0.325204 0.665178 +0.336159 0.665344 +0.336171 0.665510 +0.336186 0.665620 +0.336202 0.665671 +0.312068 0.665968 +0.302021 0.666094 +0.293685 0.666199 +0.286565 0.666286 +0.280404 0.666356 +0.275547 0.666402 +0.275841 0.666342 +0.276105 0.666231 +0.276349 0.666072 +0.276574 0.665855 +0.281346 0.665811 +0.287407 0.665743 +0.294413 0.665657 +0.302609 0.665555 +0.312479 0.665431 +0.323823 0.665291 +0.323780 0.665504 +0.323734 0.665661 +0.323684 0.665768 +0.323629 0.665824 +0.312389 0.665645 +0.312292 0.665802 +0.312186 0.665910 +0.302480 0.665770 +0.302341 0.665927 +0.302189 0.666036 +0.294254 0.665873 +0.294081 0.666031 +0.293894 0.666140 +0.287223 0.665958 +0.287023 0.666117 +0.286806 0.666227 +0.281139 0.666027 +0.280916 0.666186 +0.280674 0.666297 +0.783706 0.666412 +0.786515 0.666425 +0.779245 0.666372 +0.773029 0.666303 +0.765075 0.666205 +0.755573 0.666086 +0.744917 0.665951 +0.733672 0.665812 +0.722469 0.665676 +0.711069 0.665539 +0.699232 0.665400 +0.687673 0.665266 +0.677144 0.665146 +0.668254 0.665049 +0.661373 0.664979 +0.656622 0.664939 +0.653941 0.664926 +0.654095 0.664924 +0.654498 0.664878 +0.654889 0.664772 +0.655246 0.664611 +0.655549 0.664406 +0.655649 0.664317 +0.658233 0.664330 +0.662859 0.664369 +0.669581 0.664436 +0.678271 0.664531 +0.688561 0.664647 +0.699850 0.664777 +0.711405 0.664913 +0.722532 0.665045 +0.733473 0.665178 +0.744465 0.665313 +0.754895 0.665444 +0.764208 0.665560 +0.772011 0.665655 +0.778106 0.665722 +0.782472 0.665761 +0.785205 0.665773 +0.785283 0.665864 +0.785516 0.666077 +0.785790 0.666247 +0.786090 0.666362 +0.786398 0.666419 +0.779135 0.666365 +0.783587 0.666405 +0.772931 0.666296 +0.764991 0.666199 +0.755507 0.666080 +0.744873 0.665946 +0.733653 0.665807 +0.722476 0.665671 +0.711102 0.665535 +0.699292 0.665396 +0.687759 0.665262 +0.677253 0.665143 +0.668383 0.665045 +0.661517 0.664976 +0.656778 0.664936 +0.657167 0.664886 +0.657516 0.664785 +0.657836 0.664633 +0.658131 0.664425 +0.662765 0.664464 +0.669497 0.664531 +0.678200 0.664626 +0.688505 0.664743 +0.699811 0.664873 +0.711384 0.665009 +0.722528 0.665142 +0.733486 0.665274 +0.744494 0.665410 +0.754939 0.665541 +0.764264 0.665657 +0.772076 0.665752 +0.778179 0.665820 +0.782551 0.665859 +0.782778 0.666075 +0.783024 0.666235 +0.783291 0.666345 +0.778389 0.666036 +0.778615 0.666195 +0.778861 0.666306 +0.772263 0.665968 +0.772466 0.666127 +0.772686 0.666237 +0.764423 0.665873 +0.764596 0.666031 +0.764783 0.666140 +0.755063 0.665755 +0.755198 0.665913 +0.755345 0.666022 +0.744577 0.665624 +0.744667 0.665781 +0.744765 0.665889 +0.733523 0.665488 +0.733562 0.665644 +0.733605 0.665751 +0.722518 0.665354 +0.722505 0.665510 +0.722491 0.665616 +0.711323 0.665221 +0.711257 0.665375 +0.711184 0.665481 +0.699698 0.665084 +0.699576 0.665238 +0.699442 0.665343 +0.688343 0.664953 +0.688167 0.665106 +0.687974 0.665210 +0.677994 0.664836 +0.677770 0.664988 +0.677526 0.665091 +0.669255 0.664741 +0.668991 0.664892 +0.668704 0.664995 +0.662493 0.664673 +0.662198 0.664824 +0.661876 0.664926 +0.404736 0.664926 +0.653941 0.664926 +0.655649 0.664317 +0.403028 0.664317 +0.655549 0.664406 +0.403128 0.664406 +0.655246 0.664611 +0.403431 0.664611 +0.654889 0.664772 +0.403787 0.664772 +0.654498 0.664878 +0.404179 0.664878 +0.654095 0.664924 +0.404582 0.664924 +0.785810 0.535314 +0.785849 0.542853 +0.269039 0.542853 +0.272828 0.542853 +0.272867 0.535314 +0.268337 0.542853 +0.246279 0.542853 +0.245251 0.542853 +0.213596 0.542853 +0.212172 0.542853 +0.171879 0.542853 +0.886798 0.542853 +0.846505 0.542853 +0.845081 0.542853 +0.813425 0.542853 +0.812398 0.542853 +0.790340 0.542853 +0.789638 0.542853 +0.069258 0.535314 +0.069258 0.535314 +0.069258 0.535314 +0.069258 0.535314 +0.069258 0.535314 +0.069258 0.535314 +0.069258 0.535314 +0.069258 0.535314 +0.170245 0.542853 +0.337114 0.534566 +0.337088 0.538335 +0.402352 0.541372 +0.405512 0.541356 +0.405562 0.533817 +0.402401 0.533833 +0.397134 0.541417 +0.397184 0.533879 +0.390299 0.541488 +0.390350 0.533949 +0.382348 0.541575 +0.382399 0.534036 +0.373106 0.541680 +0.373158 0.534141 +0.362164 0.541807 +0.362217 0.534268 +0.349919 0.541951 +0.349972 0.534412 +0.339104 0.538311 +0.339078 0.542080 +0.649926 0.541356 +0.653164 0.541356 +0.405562 0.533817 +0.405512 0.541356 +0.653114 0.533817 +0.408750 0.541356 +0.409359 0.541356 +0.430088 0.541356 +0.431138 0.541356 +0.448897 0.541356 +0.450361 0.541356 +0.467834 0.541356 +0.469692 0.541356 +0.499907 0.541356 +0.502255 0.541356 +0.528089 0.541356 +0.530588 0.541356 +0.556421 0.541356 +0.558770 0.541356 +0.588985 0.541356 +0.590843 0.541356 +0.608315 0.541356 +0.609780 0.541356 +0.627539 0.541356 +0.628589 0.541356 +0.649318 0.541356 +0.710208 0.541968 +0.719598 0.542080 +0.785849 0.542853 +0.785810 0.535314 +0.783041 0.542841 +0.778568 0.542800 +0.783002 0.535302 +0.772329 0.542731 +0.778528 0.535262 +0.764343 0.542634 +0.772288 0.535192 +0.764300 0.535095 +0.754804 0.542514 +0.754758 0.534975 +0.744111 0.542380 +0.744063 0.534841 +0.732837 0.542241 +0.723626 0.542129 +0.723626 0.542105 +0.723600 0.538359 +0.732786 0.534702 +0.721589 0.538335 +0.721563 0.534566 +0.719572 0.538311 +0.655804 0.533830 +0.653114 0.533817 +0.653164 0.541356 +0.655853 0.541368 +0.660549 0.533870 +0.660598 0.541408 +0.667413 0.533939 +0.667463 0.541478 +0.676278 0.534036 +0.686782 0.534156 +0.676329 0.541575 +0.686834 0.541695 +0.698323 0.534290 +0.698376 0.541829 +0.710155 0.534429 +0.719598 0.542056 +0.755825 0.655593 +0.758133 0.655622 +0.734914 0.564243 +0.723919 0.564111 +0.724581 0.655211 +0.735433 0.655342 +0.745949 0.564379 +0.783405 0.655887 +0.783420 0.564794 +0.780659 0.655874 +0.776163 0.655834 +0.780644 0.564782 +0.776099 0.564741 +0.770390 0.655770 +0.763685 0.655690 +0.770264 0.564677 +0.761299 0.655661 +0.760797 0.575685 +0.763487 0.564596 +0.758539 0.575657 +0.746345 0.655476 +0.755537 0.564497 +0.654856 0.654487 +0.657863 0.654487 +0.656592 0.563378 +0.653496 0.563378 +0.334095 0.655211 +0.334976 0.564108 +0.323346 0.655341 +0.323866 0.564242 +0.312427 0.655475 +0.312823 0.564377 +0.302936 0.655592 +0.300543 0.655622 +0.300138 0.575657 +0.303224 0.564496 +0.297880 0.575685 +0.295062 0.655689 +0.297378 0.655661 +0.275257 0.564794 +0.275272 0.655887 +0.278067 0.564781 +0.278051 0.655874 +0.282626 0.564740 +0.288474 0.564676 +0.282562 0.655833 +0.288347 0.655770 +0.295263 0.564595 +0.783420 0.564794 +0.783405 0.655887 +0.787107 0.655887 +0.787166 0.564794 +0.338086 0.655163 +0.316163 0.655429 +0.300543 0.655622 +0.319866 0.655360 +0.350850 0.655014 +0.373598 0.654752 +0.347777 0.655047 +0.356699 0.654945 +0.338160 0.655163 +0.343978 0.655090 +0.339735 0.655138 +0.335396 0.655187 +0.334095 0.655211 +0.333998 0.655211 +0.323001 0.655326 +0.326819 0.655284 +0.331060 0.655236 +0.343944 0.534485 +0.343037 0.665595 +0.343000 0.665595 +0.343911 0.534485 +0.329812 0.665756 +0.330694 0.534646 +0.330595 0.534646 +0.329709 0.665756 +0.329709 0.665756 +0.330595 0.534646 +0.343911 0.534485 +0.343000 0.665595 +0.321821 0.655339 +0.319866 0.655360 +0.332743 0.558859 +0.336077 0.558821 +0.335396 0.655187 +0.331942 0.655226 +0.329321 0.558897 +0.333690 0.655187 +0.334514 0.558821 +0.329889 0.655226 +0.326105 0.655266 +0.330857 0.558859 +0.322599 0.655305 +0.327210 0.558897 +0.323824 0.558934 +0.319622 0.655339 +0.320941 0.558967 +0.317364 0.655367 +0.315909 0.655387 +0.318747 0.558994 +0.317325 0.559014 +0.315241 0.655399 +0.316664 0.559025 +0.315261 0.655402 +0.316670 0.559028 +0.315894 0.655399 +0.317270 0.559025 +0.317198 0.655387 +0.317489 0.655384 +0.318835 0.575398 +0.318520 0.559014 +0.320229 0.575384 +0.320439 0.558994 +0.320539 0.575381 +0.328397 0.655266 +0.325997 0.558934 +0.324953 0.655305 +0.322975 0.558967 +0.333640 0.558836 +0.323824 0.558934 +0.332242 0.558851 +0.320941 0.558967 +0.330921 0.558865 +0.318747 0.558994 +0.329770 0.558878 +0.317325 0.559014 +0.328867 0.558889 +0.316664 0.559025 +0.328256 0.558896 +0.316670 0.559028 +0.327944 0.558900 +0.317270 0.559025 +0.327902 0.558902 +0.318520 0.559014 +0.328106 0.558900 +0.320439 0.558994 +0.328580 0.558896 +0.322975 0.558967 +0.329334 0.558889 +0.325997 0.558934 +0.330347 0.558878 +0.329321 0.558897 +0.331565 0.558865 +0.332743 0.558859 +0.332909 0.558851 +0.336077 0.558821 +0.334291 0.558836 +0.339411 0.558783 +0.335634 0.558821 +0.342834 0.558745 +0.336971 0.558806 +0.346149 0.558708 +0.338335 0.558791 +0.349138 0.558675 +0.339644 0.558777 +0.351601 0.558648 +0.340811 0.558764 +0.353396 0.558628 +0.341755 0.558753 +0.354464 0.558617 +0.342424 0.558746 +0.354831 0.558614 +0.342799 0.558742 +0.354547 0.558617 +0.342899 0.558740 +0.353523 0.558628 +0.342744 0.558742 +0.351685 0.558648 +0.342305 0.558746 +0.349055 0.558675 +0.341562 0.558753 +0.345773 0.558708 +0.340533 0.558764 +0.342072 0.558745 +0.339274 0.558777 +0.338232 0.558783 +0.337873 0.558791 +0.334514 0.558821 +0.336427 0.558806 +0.330857 0.558859 +0.335026 0.558821 +0.327210 0.558897 +0.330857 0.567060 +0.332585 0.567038 +0.332177 0.567045 +0.334778 0.567015 +0.333575 0.567030 +0.337001 0.566992 +0.334961 0.567015 +0.339295 0.566969 +0.336362 0.567001 +0.341515 0.566946 +0.337808 0.566986 +0.343501 0.566926 +0.339209 0.566971 +0.345115 0.566909 +0.340468 0.566958 +0.346266 0.566898 +0.341497 0.566948 +0.346934 0.566891 +0.342240 0.566940 +0.347153 0.566889 +0.342679 0.566936 +0.346972 0.566891 +0.342834 0.566935 +0.346359 0.566898 +0.342735 0.566936 +0.345292 0.566909 +0.342360 0.566940 +0.343801 0.566926 +0.341691 0.566948 +0.341972 0.566946 +0.340747 0.566958 +0.339929 0.566969 +0.339581 0.566971 +0.337809 0.566992 +0.338272 0.566986 +0.335736 0.567015 +0.336909 0.567001 +0.333657 0.567038 +0.335572 0.567015 +0.331519 0.567062 +0.334229 0.567030 +0.329441 0.567085 +0.332847 0.567045 +0.327554 0.567105 +0.331503 0.567060 +0.325979 0.567121 +0.330286 0.567072 +0.324798 0.567133 +0.329272 0.567083 +0.324047 0.567140 +0.328518 0.567090 +0.323709 0.567142 +0.328044 0.567095 +0.323747 0.567140 +0.327840 0.567096 +0.324206 0.567133 +0.327881 0.567095 +0.325132 0.567121 +0.328193 0.567090 +0.326522 0.567105 +0.328804 0.567083 +0.328311 0.567085 +0.329707 0.567072 +0.330381 0.567062 +0.334291 0.558836 +0.334229 0.567030 +0.335572 0.567015 +0.335634 0.558821 +0.335026 0.558821 +0.334961 0.567015 +0.333640 0.558836 +0.333575 0.567030 +0.332242 0.558851 +0.332177 0.567045 +0.330921 0.558865 +0.329770 0.558878 +0.330857 0.567060 +0.328867 0.558889 +0.329707 0.567072 +0.328804 0.567083 +0.328256 0.558896 +0.328193 0.567090 +0.327944 0.558900 +0.327881 0.567095 +0.327902 0.558902 +0.327840 0.567096 +0.328106 0.558900 +0.328044 0.567095 +0.328580 0.558896 +0.328518 0.567090 +0.329334 0.558889 +0.330347 0.558878 +0.329272 0.567083 +0.330286 0.567072 +0.331565 0.558865 +0.331503 0.567060 +0.332909 0.558851 +0.332847 0.567045 +0.322035 0.651390 +0.321687 0.651389 +0.322523 0.651382 +0.323426 0.651368 +0.323521 0.651370 +0.325686 0.651342 +0.325029 0.651352 +0.328320 0.651313 +0.326977 0.651329 +0.331140 0.651283 +0.329237 0.651305 +0.333956 0.651254 +0.331649 0.651279 +0.336817 0.651224 +0.334054 0.651254 +0.339772 0.651194 +0.336493 0.651228 +0.342629 0.651165 +0.339012 0.651202 +0.345179 0.651139 +0.341451 0.651178 +0.347241 0.651118 +0.343633 0.651155 +0.348702 0.651103 +0.345403 0.651137 +0.349537 0.651095 +0.346664 0.651125 +0.349797 0.651092 +0.347393 0.651117 +0.349547 0.651095 +0.347630 0.651115 +0.348747 0.651103 +0.347429 0.651117 +0.347372 0.651118 +0.346755 0.651125 +0.345465 0.651139 +0.345585 0.651137 +0.343135 0.651165 +0.343954 0.651155 +0.340541 0.651194 +0.341955 0.651178 +0.337855 0.651224 +0.339723 0.651202 +0.335232 0.651254 +0.337410 0.651228 +0.332606 0.651283 +0.335148 0.651254 +0.329906 0.651313 +0.332881 0.651279 +0.327282 0.651342 +0.330550 0.651305 +0.324898 0.651368 +0.328283 0.651329 +0.322901 0.651389 +0.326225 0.651352 +0.321397 0.651404 +0.324504 0.651370 +0.320427 0.651412 +0.323210 0.651382 +0.319976 0.651415 +0.322383 0.651390 +0.319996 0.651412 +0.322004 0.651392 +0.320545 0.651404 +0.321397 0.651404 +0.331140 0.651283 +0.333956 0.651254 +0.333871 0.661087 +0.328320 0.651313 +0.331029 0.661116 +0.328186 0.661147 +0.325686 0.651342 +0.323426 0.651368 +0.325530 0.661176 +0.321687 0.651389 +0.323252 0.661202 +0.320545 0.651404 +0.321500 0.661223 +0.319996 0.651412 +0.320350 0.661238 +0.319976 0.651415 +0.319799 0.661247 +0.320427 0.651412 +0.319780 0.661250 +0.332516 0.661116 +0.335164 0.661087 +0.335232 0.651254 +0.332606 0.651283 +0.329794 0.661147 +0.329906 0.651313 +0.327149 0.661176 +0.327282 0.651342 +0.324745 0.661202 +0.324898 0.651368 +0.322732 0.661223 +0.321215 0.661238 +0.322901 0.651389 +0.320236 0.661247 +0.277454 0.629579 +0.273458 0.629638 +0.272684 0.629638 +0.276694 0.629579 +0.273694 0.539425 +0.273732 0.539546 +0.277454 0.629579 +0.277366 0.655801 +0.273458 0.629638 +0.271569 0.655887 +0.273743 0.539665 +0.271511 0.564794 +0.269039 0.542853 +0.271092 0.540854 +0.271101 0.539051 +0.273032 0.539022 +0.273161 0.539031 +0.273294 0.539064 +0.273421 0.539122 +0.273535 0.539206 +0.273628 0.539309 +0.272605 0.539064 +0.272472 0.539031 +0.270765 0.655887 +0.276581 0.655801 +0.276694 0.629579 +0.270793 0.564794 +0.272684 0.629638 +0.268337 0.542853 +0.270396 0.540854 +0.270407 0.539051 +0.272342 0.539022 +0.273055 0.539665 +0.273044 0.539546 +0.273006 0.539425 +0.272939 0.539309 +0.272847 0.539206 +0.272733 0.539122 +0.277366 0.655801 +0.277454 0.629579 +0.276694 0.629579 +0.276581 0.655801 +0.219844 0.629579 +0.216796 0.629638 +0.215110 0.629638 +0.218072 0.629579 +0.216909 0.539425 +0.216937 0.539546 +0.219844 0.629579 +0.219792 0.655801 +0.216796 0.629638 +0.215442 0.655887 +0.216946 0.539665 +0.215340 0.564794 +0.213596 0.542853 +0.215026 0.540854 +0.215031 0.539051 +0.216422 0.539022 +0.216516 0.539031 +0.216614 0.539064 +0.216707 0.539122 +0.216791 0.539206 +0.216860 0.539309 +0.215117 0.539064 +0.215022 0.539031 +0.213744 0.655887 +0.217966 0.655801 +0.218072 0.629579 +0.213825 0.564794 +0.215110 0.629638 +0.212172 0.542853 +0.213568 0.540854 +0.213576 0.539051 +0.214930 0.539022 +0.215439 0.539665 +0.215431 0.539546 +0.215404 0.539425 +0.215356 0.539309 +0.215290 0.539206 +0.215208 0.539122 +0.219844 0.629579 +0.218072 0.629579 +0.217966 0.655801 +0.219792 0.655801 +0.250912 0.539425 +0.250950 0.539546 +0.254780 0.632857 +0.254705 0.655801 +0.250685 0.632916 +0.248805 0.655887 +0.250962 0.539665 +0.248726 0.564794 +0.246279 0.542853 +0.248304 0.540854 +0.248312 0.539051 +0.250243 0.539022 +0.250374 0.539031 +0.250507 0.539064 +0.250636 0.539122 +0.250751 0.539206 +0.250845 0.539309 +0.249468 0.539064 +0.249335 0.539031 +0.247607 0.655887 +0.253485 0.655801 +0.253593 0.632857 +0.247656 0.564794 +0.249511 0.632916 +0.245251 0.542853 +0.247270 0.540854 +0.247281 0.539051 +0.249205 0.539022 +0.249920 0.539665 +0.249909 0.539546 +0.249870 0.539425 +0.249804 0.539309 +0.249711 0.539206 +0.249596 0.539122 +0.254705 0.655801 +0.254780 0.632857 +0.253593 0.632857 +0.253485 0.655801 +0.808169 0.539064 +0.808303 0.539031 +0.809871 0.655887 +0.803972 0.655801 +0.803897 0.632857 +0.809951 0.564794 +0.807992 0.632916 +0.812398 0.542853 +0.810373 0.540854 +0.810365 0.539051 +0.808433 0.539022 +0.807715 0.539665 +0.807726 0.539546 +0.807765 0.539425 +0.807832 0.539309 +0.807925 0.539206 +0.808040 0.539122 +0.808806 0.539425 +0.808768 0.539546 +0.805084 0.632857 +0.805192 0.655801 +0.809166 0.632916 +0.811070 0.655887 +0.808757 0.539665 +0.811020 0.564794 +0.813425 0.542853 +0.811407 0.540854 +0.811396 0.539051 +0.809472 0.539022 +0.809342 0.539031 +0.809209 0.539064 +0.809081 0.539122 +0.808966 0.539206 +0.808873 0.539309 +0.805192 0.655801 +0.805084 0.632857 +0.803897 0.632857 +0.803972 0.655801 +0.838833 0.629579 +0.840605 0.629579 +0.843567 0.629638 +0.841881 0.629638 +0.842063 0.539064 +0.842160 0.539031 +0.843235 0.655887 +0.838884 0.655801 +0.838833 0.629579 +0.843337 0.564794 +0.841881 0.629638 +0.845081 0.542853 +0.843650 0.540854 +0.843645 0.539051 +0.842255 0.539022 +0.841731 0.539665 +0.841740 0.539546 +0.841768 0.539425 +0.841817 0.539309 +0.841885 0.539206 +0.841969 0.539122 +0.843273 0.539425 +0.843246 0.539546 +0.840605 0.629579 +0.840710 0.655801 +0.843567 0.629638 +0.844933 0.655887 +0.843238 0.539665 +0.844851 0.564794 +0.846505 0.542853 +0.845109 0.540854 +0.845101 0.539051 +0.843747 0.539022 +0.843655 0.539031 +0.843560 0.539064 +0.843469 0.539122 +0.843387 0.539206 +0.843321 0.539309 +0.840710 0.655801 +0.840605 0.629579 +0.838833 0.629579 +0.838884 0.655801 +0.781983 0.629579 +0.785993 0.629638 +0.785219 0.629638 +0.781223 0.629579 +0.785383 0.539064 +0.785516 0.539031 +0.787107 0.655887 +0.781311 0.655801 +0.781223 0.629579 +0.787166 0.564794 +0.785219 0.629638 +0.789638 0.542853 +0.787584 0.540854 +0.787576 0.539051 +0.785645 0.539022 +0.784933 0.539665 +0.784945 0.539546 +0.784983 0.539425 +0.785049 0.539309 +0.785141 0.539206 +0.785256 0.539122 +0.785671 0.539425 +0.785633 0.539546 +0.781983 0.629579 +0.782096 0.655801 +0.785993 0.629638 +0.787912 0.655887 +0.785622 0.539665 +0.787884 0.564794 +0.790340 0.542853 +0.788280 0.540854 +0.788270 0.539051 +0.786335 0.539022 +0.786205 0.539031 +0.786072 0.539064 +0.785944 0.539122 +0.785830 0.539206 +0.785737 0.539309 +0.782096 0.655801 +0.781983 0.629579 +0.781223 0.629579 +0.781311 0.655801 +0.171946 0.539425 +0.171947 0.539546 +0.172129 0.632857 +0.172157 0.655801 +0.172054 0.632916 +0.172048 0.655887 +0.171947 0.539665 +0.171941 0.564794 +0.171879 0.542853 +0.171907 0.540854 +0.171905 0.539051 +0.171935 0.539022 +0.171937 0.539031 +0.171939 0.539064 +0.171941 0.539122 +0.171943 0.539206 +0.171945 0.539309 +0.886738 0.539064 +0.886740 0.539031 +0.886629 0.655887 +0.886520 0.655801 +0.886548 0.632857 +0.886735 0.564794 +0.886623 0.632916 +0.886798 0.542853 +0.886769 0.540854 +0.886771 0.539051 +0.886742 0.539022 +0.886730 0.539665 +0.886730 0.539546 +0.886731 0.539425 +0.886732 0.539309 +0.886734 0.539206 +0.886736 0.539122 +0.172157 0.655801 +0.172129 0.632857 +0.169996 0.632857 +0.169968 0.655801 +0.169996 0.632857 +0.375189 0.574762 +0.351284 0.575038 +0.352896 0.575021 +0.377672 0.574735 +0.351284 0.575038 +0.375189 0.574762 +0.373598 0.654752 +0.350850 0.655014 +0.353098 0.654989 +0.377089 0.654713 +0.377672 0.574735 +0.352896 0.575021 +0.318835 0.575398 +0.320539 0.575381 +0.300138 0.575657 +0.297880 0.575685 +0.317489 0.655384 +0.318835 0.575398 +0.297880 0.575685 +0.297378 0.655661 +0.320539 0.575381 +0.319866 0.655360 +0.300543 0.655622 +0.300138 0.575657 +0.527940 0.537698 +0.527946 0.537661 +0.527739 0.654487 +0.527432 0.654573 +0.527494 0.631628 +0.527952 0.563378 +0.527706 0.631569 +0.528089 0.541356 +0.528021 0.539422 +0.528024 0.537619 +0.527951 0.537648 +0.527920 0.538314 +0.527921 0.538194 +0.527923 0.538072 +0.527926 0.537954 +0.527930 0.537848 +0.527935 0.537761 +0.530754 0.538072 +0.530755 0.538194 +0.531183 0.631628 +0.531245 0.654573 +0.530970 0.631569 +0.530937 0.654487 +0.530756 0.538314 +0.530725 0.563378 +0.530588 0.541356 +0.530656 0.539422 +0.530653 0.537619 +0.530726 0.537648 +0.530731 0.537661 +0.530737 0.537698 +0.530742 0.537761 +0.530747 0.537848 +0.530751 0.537954 +0.403200 0.537698 +0.403374 0.537661 +0.403821 0.654487 +0.396145 0.654573 +0.396424 0.628350 +0.405181 0.563378 +0.401685 0.628292 +0.408750 0.541356 +0.406066 0.539422 +0.406080 0.537619 +0.403543 0.537648 +0.402602 0.538314 +0.402619 0.538194 +0.402671 0.538072 +0.402759 0.537954 +0.402881 0.537848 +0.403032 0.537761 +0.397001 0.628350 +0.402310 0.628292 +0.401685 0.628292 +0.396424 0.628350 +0.403234 0.538072 +0.403182 0.538194 +0.397001 0.628350 +0.396738 0.654573 +0.402310 0.628292 +0.404485 0.654487 +0.403166 0.538314 +0.405783 0.563378 +0.409359 0.541356 +0.406655 0.539422 +0.406668 0.537619 +0.404113 0.537648 +0.403942 0.537661 +0.403767 0.537698 +0.403598 0.537761 +0.403446 0.537848 +0.403323 0.537954 +0.396145 0.654573 +0.396738 0.654573 +0.397001 0.628350 +0.396424 0.628350 +0.461779 0.537698 +0.461980 0.537661 +0.462391 0.654487 +0.452857 0.654573 +0.453257 0.628350 +0.464000 0.563378 +0.459919 0.628292 +0.467834 0.541356 +0.464994 0.539422 +0.465010 0.537619 +0.462175 0.537648 +0.461084 0.538314 +0.461104 0.538194 +0.461164 0.538072 +0.461267 0.537954 +0.461410 0.537848 +0.461585 0.537761 +0.453257 0.628350 +0.455558 0.628350 +0.462135 0.628292 +0.459919 0.628292 +0.463120 0.538072 +0.463061 0.538194 +0.455558 0.628350 +0.455236 0.654573 +0.462135 0.628292 +0.464637 0.654487 +0.463042 0.538314 +0.465980 0.563378 +0.469692 0.541356 +0.466895 0.539422 +0.466907 0.537619 +0.464116 0.537648 +0.463924 0.537661 +0.463726 0.537698 +0.463534 0.537761 +0.463362 0.537848 +0.463222 0.537954 +0.452857 0.654573 +0.455236 0.654573 +0.455558 0.628350 +0.453257 0.628350 +0.423567 0.537698 +0.423776 0.537661 +0.424283 0.654487 +0.414884 0.654573 +0.415195 0.631628 +0.425918 0.563378 +0.421681 0.631569 +0.430088 0.541356 +0.426967 0.539422 +0.426983 0.537619 +0.423979 0.537648 +0.422850 0.538314 +0.422870 0.538194 +0.422932 0.538072 +0.423038 0.537954 +0.423185 0.537848 +0.423366 0.537761 +0.423948 0.538072 +0.423886 0.538194 +0.416285 0.631628 +0.416001 0.654573 +0.422819 0.631569 +0.425469 0.654487 +0.423865 0.538314 +0.426984 0.563378 +0.431138 0.541356 +0.428003 0.539422 +0.428016 0.537619 +0.424999 0.537648 +0.424795 0.537661 +0.424586 0.537698 +0.424383 0.537761 +0.424202 0.537848 +0.424054 0.537954 +0.635745 0.538072 +0.635806 0.538194 +0.643482 0.631628 +0.643793 0.654573 +0.636996 0.631569 +0.634394 0.654487 +0.635827 0.538314 +0.632759 0.563378 +0.628589 0.541356 +0.631710 0.539422 +0.631694 0.537619 +0.634698 0.537648 +0.634901 0.537661 +0.635109 0.537698 +0.635311 0.537761 +0.635491 0.537848 +0.635639 0.537954 +0.634091 0.537698 +0.633882 0.537661 +0.633208 0.654487 +0.642676 0.654573 +0.642392 0.631628 +0.631693 0.563378 +0.635857 0.631569 +0.627539 0.541356 +0.630674 0.539422 +0.630660 0.537619 +0.633678 0.537648 +0.634811 0.538314 +0.634791 0.538194 +0.634729 0.538072 +0.634623 0.537954 +0.634475 0.537848 +0.634293 0.537761 +0.597513 0.538072 +0.597573 0.538194 +0.605420 0.628350 +0.605819 0.654573 +0.598758 0.628292 +0.596285 0.654487 +0.597593 0.538314 +0.594677 0.563378 +0.590843 0.541356 +0.593683 0.539422 +0.593667 0.537619 +0.596501 0.537648 +0.596696 0.537661 +0.596897 0.537698 +0.597092 0.537761 +0.597267 0.537848 +0.597410 0.537954 +0.605420 0.628350 +0.598758 0.628292 +0.596542 0.628292 +0.603119 0.628350 +0.594951 0.537698 +0.594753 0.537661 +0.594040 0.654487 +0.603440 0.654573 +0.603119 0.628350 +0.592697 0.563378 +0.596542 0.628292 +0.588985 0.541356 +0.591781 0.539422 +0.591770 0.537619 +0.594561 0.537648 +0.595635 0.538314 +0.595616 0.538194 +0.595556 0.538072 +0.595455 0.537954 +0.595314 0.537848 +0.595142 0.537761 +0.603440 0.654573 +0.605819 0.654573 +0.605420 0.628350 +0.603119 0.628350 +0.656006 0.538072 +0.656058 0.538194 +0.662253 0.628350 +0.662532 0.654573 +0.656992 0.628292 +0.654856 0.654487 +0.656075 0.538314 +0.653496 0.563378 +0.649926 0.541356 +0.652610 0.539422 +0.652597 0.537619 +0.655133 0.537648 +0.655303 0.537661 +0.655477 0.537698 +0.655645 0.537761 +0.655795 0.537848 +0.655918 0.537954 +0.662253 0.628350 +0.656992 0.628292 +0.656367 0.628292 +0.661676 0.628350 +0.654910 0.537698 +0.654734 0.537661 +0.654192 0.654487 +0.661939 0.654573 +0.661676 0.628350 +0.652894 0.563378 +0.656367 0.628292 +0.649318 0.541356 +0.652021 0.539422 +0.652009 0.537619 +0.654564 0.537648 +0.655511 0.538314 +0.655494 0.538194 +0.655443 0.538072 +0.655354 0.537954 +0.655230 0.537848 +0.655079 0.537761 +0.661939 0.654573 +0.662532 0.654573 +0.662253 0.628350 +0.661676 0.628350 +0.728968 0.665756 +0.728081 0.534646 +0.727982 0.534646 +0.728864 0.665756 +0.714766 0.534485 +0.715676 0.665595 +0.715639 0.665595 +0.714733 0.534485 +0.714766 0.534485 +0.728081 0.534646 +0.728968 0.665756 +0.715676 0.665595 +0.741479 0.655387 +0.741188 0.655384 +0.727820 0.558859 +0.724163 0.558821 +0.724986 0.655187 +0.728787 0.655226 +0.731467 0.558897 +0.734853 0.558934 +0.732572 0.655266 +0.736078 0.655305 +0.737735 0.558967 +0.739930 0.558994 +0.739054 0.655339 +0.741351 0.559014 +0.741313 0.655367 +0.742013 0.559025 +0.742768 0.655387 +0.742007 0.559028 +0.743436 0.655399 +0.723280 0.655187 +0.722600 0.558821 +0.726735 0.655226 +0.725933 0.558859 +0.730280 0.655266 +0.729356 0.558897 +0.733724 0.655305 +0.732680 0.558934 +0.736855 0.655339 +0.738811 0.655360 +0.738137 0.575381 +0.735702 0.558967 +0.738447 0.575384 +0.738237 0.558994 +0.739842 0.575398 +0.743416 0.655402 +0.741407 0.559025 +0.742783 0.655399 +0.740157 0.559014 +0.726499 0.567045 +0.723716 0.567015 +0.723651 0.558821 +0.725102 0.567030 +0.723043 0.558821 +0.723105 0.567015 +0.724385 0.558836 +0.725768 0.558851 +0.724447 0.567030 +0.727111 0.558865 +0.725830 0.567045 +0.728329 0.558878 +0.727173 0.567060 +0.729343 0.558889 +0.728391 0.567072 +0.730097 0.558896 +0.729405 0.567083 +0.730570 0.558900 +0.730159 0.567090 +0.730774 0.558902 +0.730632 0.567095 +0.730733 0.558900 +0.730836 0.567096 +0.730421 0.558896 +0.730796 0.567095 +0.729810 0.558889 +0.730484 0.567090 +0.728907 0.558878 +0.729873 0.567083 +0.728970 0.567072 +0.727756 0.558865 +0.727820 0.567060 +0.726435 0.558851 +0.725037 0.558836 +0.730357 0.651313 +0.727647 0.661116 +0.724806 0.661087 +0.724720 0.651254 +0.730491 0.661147 +0.727537 0.651283 +0.723445 0.651254 +0.723513 0.661087 +0.726071 0.651283 +0.728771 0.651313 +0.726161 0.661116 +0.728882 0.661147 +0.731395 0.651342 +0.733779 0.651368 +0.731528 0.661176 +0.735775 0.651389 +0.733932 0.661202 +0.735945 0.661223 +0.737280 0.651404 +0.737462 0.661238 +0.738249 0.651412 +0.738441 0.661247 +0.738701 0.651415 +0.738897 0.661250 +0.738680 0.651412 +0.738878 0.661247 +0.738132 0.651404 +0.738327 0.661238 +0.736989 0.651389 +0.737176 0.661223 +0.735250 0.651368 +0.735425 0.661202 +0.732991 0.651342 +0.733147 0.661176 +0.723529 0.651254 +0.718136 0.651194 +0.721267 0.651228 +0.715542 0.651165 +0.718953 0.651202 +0.713212 0.651139 +0.716722 0.651178 +0.711305 0.651118 +0.714723 0.651155 +0.709930 0.651103 +0.713091 0.651137 +0.709130 0.651095 +0.711921 0.651125 +0.708880 0.651092 +0.711248 0.651117 +0.709140 0.651095 +0.711047 0.651115 +0.709975 0.651103 +0.711284 0.651117 +0.711436 0.651118 +0.712013 0.651125 +0.713497 0.651139 +0.713274 0.651137 +0.716047 0.651165 +0.715044 0.651155 +0.718905 0.651194 +0.717225 0.651178 +0.721860 0.651224 +0.719664 0.651202 +0.724720 0.651254 +0.722184 0.651228 +0.727537 0.651283 +0.724623 0.651254 +0.730357 0.651313 +0.727028 0.651279 +0.732991 0.651342 +0.729440 0.651305 +0.735250 0.651368 +0.731700 0.651329 +0.736989 0.651389 +0.733648 0.651352 +0.738132 0.651404 +0.735155 0.651370 +0.738680 0.651412 +0.736154 0.651382 +0.738701 0.651415 +0.736641 0.651390 +0.738249 0.651412 +0.736673 0.651392 +0.737280 0.651404 +0.736294 0.651390 +0.735775 0.651389 +0.735466 0.651382 +0.733779 0.651368 +0.734173 0.651370 +0.731395 0.651342 +0.732452 0.651352 +0.728771 0.651313 +0.730393 0.651329 +0.726071 0.651283 +0.728127 0.651305 +0.723445 0.651254 +0.725796 0.651279 +0.720822 0.651224 +0.739842 0.575398 +0.760797 0.575685 +0.758539 0.575657 +0.738137 0.575381 +0.738137 0.575381 +0.758539 0.575657 +0.758133 0.655622 +0.738811 0.655360 +0.741188 0.655384 +0.761299 0.655661 +0.760797 0.575685 +0.739842 0.575398 +0.705781 0.575021 +0.707393 0.575038 +0.683488 0.574762 +0.681004 0.574735 +0.705579 0.654989 +0.705781 0.575021 +0.681004 0.574735 +0.681588 0.654713 +0.707393 0.575038 +0.707827 0.655014 +0.685079 0.654752 +0.683488 0.574762 +0.785849 0.542853 +0.783420 0.564794 +0.787166 0.564794 +0.789638 0.542853 +0.783420 0.564794 +0.785849 0.542853 +0.734581 0.542262 +0.723626 0.542129 +0.723919 0.564111 +0.745513 0.542398 +0.734862 0.564243 +0.755835 0.542527 +0.745901 0.564378 +0.765027 0.542642 +0.755494 0.564497 +0.772727 0.542736 +0.763450 0.564595 +0.770233 0.564676 +0.778759 0.542802 +0.776075 0.564741 +0.783102 0.542841 +0.780627 0.564782 +0.334976 0.564108 +0.275574 0.542841 +0.272828 0.542853 +0.275257 0.564794 +0.279918 0.542802 +0.278090 0.564781 +0.285949 0.542736 +0.282659 0.564740 +0.293649 0.542642 +0.288517 0.564675 +0.302842 0.542527 +0.295314 0.564594 +0.303283 0.564496 +0.313164 0.542398 +0.312889 0.564377 +0.324096 0.542262 +0.323938 0.564241 +0.335320 0.542109 +0.335051 0.542107 +0.335051 0.542129 +0.653164 0.541356 +0.649926 0.541356 +0.653496 0.563378 +0.656592 0.563378 +0.652597 0.537619 +0.652009 0.537619 +0.654564 0.537648 +0.655133 0.537648 +0.656367 0.628292 +0.656992 0.628292 +0.656075 0.538314 +0.655511 0.538314 +0.631694 0.537619 +0.630660 0.537619 +0.633678 0.537648 +0.634698 0.537648 +0.635857 0.631569 +0.636996 0.631569 +0.635827 0.538314 +0.634811 0.538314 +0.593667 0.537619 +0.591770 0.537619 +0.594561 0.537648 +0.596501 0.537648 +0.596542 0.628292 +0.598758 0.628292 +0.597593 0.538314 +0.595635 0.538314 +0.530726 0.537648 +0.530653 0.537619 +0.528024 0.537619 +0.527951 0.537648 +0.527706 0.631569 +0.530970 0.631569 +0.530756 0.538314 +0.527920 0.538314 +0.466907 0.537619 +0.465010 0.537619 +0.462175 0.537648 +0.464116 0.537648 +0.459919 0.628292 +0.462135 0.628292 +0.463042 0.538314 +0.461084 0.538314 +0.428016 0.537619 +0.426983 0.537619 +0.423979 0.537648 +0.424999 0.537648 +0.421681 0.631569 +0.422819 0.631569 +0.423865 0.538314 +0.422850 0.538314 +0.404113 0.537648 +0.406668 0.537619 +0.406080 0.537619 +0.403543 0.537648 +0.401685 0.628292 +0.402310 0.628292 +0.403166 0.538314 +0.402602 0.538314 +0.271101 0.539051 +0.270407 0.539051 +0.272342 0.539022 +0.273032 0.539022 +0.272684 0.629638 +0.273458 0.629638 +0.273743 0.539665 +0.273055 0.539665 +0.248312 0.539051 +0.247281 0.539051 +0.249205 0.539022 +0.250243 0.539022 +0.249511 0.632916 +0.250685 0.632916 +0.250962 0.539665 +0.249920 0.539665 +0.215031 0.539051 +0.213576 0.539051 +0.214930 0.539022 +0.216422 0.539022 +0.215110 0.629638 +0.216796 0.629638 +0.216946 0.539665 +0.215439 0.539665 +0.171905 0.539051 +0.170219 0.539051 +0.170189 0.539022 +0.171935 0.539022 +0.170189 0.539022 +0.170070 0.632916 +0.172054 0.632916 +0.171947 0.539665 +0.170177 0.539665 +0.170070 0.632916 +0.845101 0.539051 +0.843645 0.539051 +0.842255 0.539022 +0.843747 0.539022 +0.841881 0.629638 +0.843567 0.629638 +0.843238 0.539665 +0.841731 0.539665 +0.809472 0.539022 +0.811396 0.539051 +0.810365 0.539051 +0.808433 0.539022 +0.807992 0.632916 +0.809166 0.632916 +0.808757 0.539665 +0.807715 0.539665 +0.786335 0.539022 +0.788270 0.539051 +0.787576 0.539051 +0.785645 0.539022 +0.785219 0.629638 +0.785993 0.629638 +0.785622 0.539665 +0.784933 0.539665 +0.720590 0.655163 +0.724679 0.655211 +0.723865 0.539015 +0.719769 0.538966 +0.723709 0.538359 +0.719653 0.538311 +0.719736 0.538311 +0.723822 0.538359 +0.719747 0.538357 +0.719741 0.538322 +0.719736 0.538311 +0.719653 0.538311 +0.720517 0.655163 +0.720590 0.655163 +0.719856 0.564062 +0.719598 0.542080 +0.719598 0.542056 +0.719666 0.540114 +0.719769 0.538966 +0.719767 0.538847 +0.719765 0.538725 +0.719762 0.538608 +0.719757 0.538503 +0.719752 0.538418 +0.723860 0.538774 +0.723863 0.538896 +0.723865 0.539015 +0.724679 0.655211 +0.724581 0.655211 +0.723919 0.564111 +0.723626 0.542129 +0.723626 0.542105 +0.723722 0.540162 +0.723709 0.538359 +0.723822 0.538359 +0.723829 0.538370 +0.723836 0.538405 +0.723844 0.538466 +0.723850 0.538551 +0.723856 0.538656 +0.338742 0.538314 +0.335247 0.538356 +0.335147 0.538356 +0.338666 0.538314 +0.333998 0.655211 +0.338086 0.655163 +0.338634 0.538969 +0.335104 0.539010 +0.338637 0.538728 +0.338635 0.538849 +0.338634 0.538969 +0.338086 0.655163 +0.338160 0.655163 +0.338601 0.564065 +0.338808 0.542067 +0.338734 0.540117 +0.338742 0.538314 +0.338666 0.538314 +0.338661 0.538325 +0.338655 0.538360 +0.338650 0.538421 +0.338645 0.538506 +0.338641 0.538610 +0.335133 0.538402 +0.335141 0.538367 +0.334095 0.655211 +0.333998 0.655211 +0.334976 0.564108 +0.335320 0.542109 +0.335230 0.540159 +0.335247 0.538356 +0.335147 0.538356 +0.335104 0.539010 +0.335106 0.538891 +0.335109 0.538769 +0.335114 0.538652 +0.335119 0.538548 +0.335126 0.538463 +0.560533 0.654514 +0.563631 0.654514 +0.562614 0.538313 +0.559999 0.538313 +0.561971 0.537648 +0.560366 0.537619 +0.557913 0.537619 +0.559404 0.537648 +0.559619 0.537698 +0.559510 0.537661 +0.559032 0.654487 +0.560533 0.654514 +0.558390 0.563378 +0.556421 0.541356 +0.557918 0.539422 +0.557913 0.537619 +0.559404 0.537648 +0.559999 0.538313 +0.559988 0.538194 +0.559955 0.538071 +0.559899 0.537953 +0.559821 0.537847 +0.559726 0.537760 +0.562567 0.538071 +0.562602 0.538194 +0.562614 0.538313 +0.563631 0.654514 +0.561997 0.654487 +0.560972 0.563378 +0.558770 0.541356 +0.560377 0.539422 +0.560366 0.537619 +0.561971 0.537648 +0.562086 0.537661 +0.562204 0.537698 +0.562318 0.537760 +0.562421 0.537847 +0.562506 0.537953 +0.495046 0.654514 +0.498144 0.654514 +0.498678 0.538313 +0.496063 0.538313 +0.500763 0.537619 +0.498311 0.537619 +0.496705 0.537648 +0.499273 0.537648 +0.496473 0.537698 +0.496591 0.537661 +0.496680 0.654487 +0.495046 0.654514 +0.497705 0.563378 +0.499907 0.541356 +0.498300 0.539422 +0.498311 0.537619 +0.496705 0.537648 +0.496063 0.538313 +0.496074 0.538194 +0.496110 0.538071 +0.496171 0.537953 +0.496256 0.537847 +0.496359 0.537760 +0.498721 0.538071 +0.498688 0.538194 +0.498678 0.538313 +0.498144 0.654514 +0.499645 0.654487 +0.500286 0.563378 +0.502255 0.541356 +0.500759 0.539422 +0.500763 0.537619 +0.499273 0.537648 +0.499167 0.537661 +0.499057 0.537698 +0.498951 0.537760 +0.498856 0.537847 +0.498778 0.537953 +0.616959 0.654514 +0.618675 0.654514 +0.617113 0.538313 +0.615634 0.538313 +0.615938 0.537648 +0.612917 0.537619 +0.611449 0.537619 +0.614462 0.537648 +0.614889 0.537698 +0.614673 0.537661 +0.614014 0.654487 +0.616959 0.654514 +0.612490 0.563378 +0.608315 0.541356 +0.611462 0.539422 +0.611449 0.537619 +0.614462 0.537648 +0.615634 0.538313 +0.615613 0.538194 +0.615549 0.538071 +0.615438 0.537953 +0.615285 0.537847 +0.615098 0.537760 +0.617027 0.538071 +0.617092 0.538194 +0.617113 0.538313 +0.618675 0.654514 +0.615726 0.654487 +0.614014 0.563378 +0.609780 0.541356 +0.612934 0.539422 +0.612917 0.537619 +0.615938 0.537648 +0.616149 0.537661 +0.616365 0.537698 +0.616575 0.537760 +0.616763 0.537847 +0.616916 0.537953 +0.440002 0.654514 +0.441718 0.654514 +0.443043 0.538313 +0.441564 0.538313 +0.447228 0.537619 +0.445759 0.537619 +0.442738 0.537648 +0.444214 0.537648 +0.442311 0.537698 +0.442528 0.537661 +0.442951 0.654487 +0.440002 0.654514 +0.444662 0.563378 +0.448897 0.541356 +0.445742 0.539422 +0.445759 0.537619 +0.442738 0.537648 +0.441564 0.538313 +0.441585 0.538194 +0.441650 0.538071 +0.441760 0.537953 +0.441914 0.537847 +0.442102 0.537760 +0.443128 0.538071 +0.443064 0.538194 +0.443043 0.538313 +0.441718 0.654514 +0.444663 0.654487 +0.446186 0.563378 +0.450361 0.541356 +0.447215 0.539422 +0.447228 0.537619 +0.444214 0.537648 +0.444004 0.537661 +0.443788 0.537698 +0.443579 0.537760 +0.443392 0.537847 +0.443238 0.537953 +0.652610 0.539422 +0.652021 0.539422 +0.652009 0.537619 +0.652597 0.537619 +0.630674 0.539422 +0.630660 0.537619 +0.631694 0.537619 +0.631710 0.539422 +0.591781 0.539422 +0.591770 0.537619 +0.593667 0.537619 +0.593683 0.539422 +0.530656 0.539422 +0.528021 0.539422 +0.528024 0.537619 +0.530653 0.537619 +0.464994 0.539422 +0.465010 0.537619 +0.466907 0.537619 +0.466895 0.539422 +0.428003 0.539422 +0.426967 0.539422 +0.426983 0.537619 +0.428016 0.537619 +0.406066 0.539422 +0.406080 0.537619 +0.406668 0.537619 +0.406655 0.539422 +0.270396 0.540854 +0.270407 0.539051 +0.271101 0.539051 +0.271092 0.540854 +0.248304 0.540854 +0.247270 0.540854 +0.247281 0.539051 +0.248312 0.539051 +0.213568 0.540854 +0.213576 0.539051 +0.215031 0.539051 +0.215026 0.540854 +0.170217 0.540854 +0.170219 0.539051 +0.171905 0.539051 +0.171907 0.540854 +0.170217 0.540854 +0.843650 0.540854 +0.843645 0.539051 +0.845101 0.539051 +0.845109 0.540854 +0.810373 0.540854 +0.810365 0.539051 +0.811396 0.539051 +0.811407 0.540854 +0.787584 0.540854 +0.787576 0.539051 +0.788270 0.539051 +0.788280 0.540854 +0.719598 0.542056 +0.719597 0.542080 +0.719571 0.538311 +0.719572 0.538311 +0.723626 0.542105 +0.723600 0.538359 +0.723599 0.538359 +0.723624 0.542129 +0.719571 0.538311 +0.721589 0.538335 +0.720581 0.538323 +0.719572 0.538311 +0.723599 0.538359 +0.723600 0.538359 +0.722595 0.538347 +0.721589 0.538335 +0.723722 0.540162 +0.719666 0.540114 +0.719653 0.538311 +0.723709 0.538359 +0.723624 0.542129 +0.723599 0.538359 +0.721589 0.538335 +0.719571 0.538311 +0.719597 0.542080 +0.335078 0.538359 +0.335077 0.538359 +0.335051 0.542129 +0.335051 0.542107 +0.335052 0.542129 +0.339104 0.538311 +0.339079 0.542059 +0.339078 0.542080 +0.339105 0.538311 +0.339079 0.542080 +0.339104 0.538311 +0.337088 0.538335 +0.339105 0.538311 +0.337088 0.538335 +0.335077 0.538359 +0.335078 0.538359 +0.335230 0.540159 +0.335247 0.538356 +0.338742 0.538314 +0.338734 0.540117 +0.339079 0.542080 +0.339105 0.538311 +0.335078 0.538359 +0.335052 0.542129 +0.337088 0.538335 +0.611462 0.539422 +0.611449 0.537619 +0.612917 0.537619 +0.612934 0.539422 +0.557918 0.539422 +0.557913 0.537619 +0.560366 0.537619 +0.560377 0.539422 +0.498300 0.539422 +0.498311 0.537619 +0.500763 0.537619 +0.500759 0.539422 +0.447215 0.539422 +0.445742 0.539422 +0.445759 0.537619 +0.447228 0.537619 +0.206699 0.661062 +0.206679 0.658440 +0.196743 0.658443 +0.196770 0.661065 +0.511686 0.660627 +0.516593 0.660624 +0.516618 0.658001 +0.511713 0.658005 +0.505975 0.660639 +0.506004 0.658016 +0.499155 0.660660 +0.499188 0.658037 +0.490780 0.660688 +0.490819 0.658066 +0.480183 0.660724 +0.480230 0.658101 +0.466372 0.660763 +0.466430 0.658141 +0.447942 0.660804 +0.448017 0.658182 +0.423283 0.660844 +0.388995 0.660885 +0.423378 0.658222 +0.389106 0.658262 +0.343627 0.660926 +0.297382 0.660965 +0.343728 0.658303 +0.297444 0.658343 +0.261389 0.661001 +0.261413 0.658378 +0.236558 0.661029 +0.236559 0.658407 +0.219333 0.661050 +0.219321 0.658428 +0.145381 0.658443 +0.145354 0.661065 +0.196770 0.661065 +0.196743 0.658443 +0.145381 0.658443 +0.674668 0.658267 +0.635299 0.658222 +0.850595 0.661061 +0.861907 0.661065 +0.861934 0.658443 +0.850614 0.658439 +0.836990 0.661047 +0.819741 0.661026 +0.837000 0.658425 +0.797287 0.661001 +0.819738 0.658404 +0.797263 0.658378 +0.766020 0.660970 +0.765963 0.658347 +0.722678 0.660932 +0.674780 0.660890 +0.722581 0.658310 +0.635394 0.660844 +0.516618 0.658001 +0.516593 0.660624 +0.542084 0.660624 +0.542059 0.658001 +0.773304 0.660932 +0.673167 0.659930 +0.673173 0.660586 +0.773308 0.661588 +0.673167 0.659930 +0.624593 0.659930 +0.624603 0.660586 +0.673173 0.660586 +0.624593 0.659930 +0.829971 0.660932 +0.829975 0.661588 +0.624603 0.660586 +0.829971 0.660932 +0.773304 0.660932 +0.773308 0.661588 +0.829975 0.661588 +0.745590 0.660506 +0.673167 0.659930 +0.731821 0.660417 +0.733994 0.660431 +0.736177 0.660446 +0.738426 0.660461 +0.740619 0.660475 +0.729603 0.660402 +0.727471 0.660387 +0.742620 0.660488 +0.744306 0.660499 +0.725573 0.660374 +0.724040 0.660364 +0.624593 0.659930 +0.722963 0.660356 +0.722375 0.660352 +0.722249 0.660350 +0.722553 0.660352 +0.723340 0.660356 +0.724645 0.660364 +0.829971 0.660932 +0.726434 0.660374 +0.728605 0.660387 +0.731000 0.660402 +0.733448 0.660417 +0.735793 0.660431 +0.738083 0.660446 +0.740357 0.660461 +0.742465 0.660475 +0.744258 0.660488 +0.745621 0.660499 +0.773304 0.660932 +0.746497 0.660506 +0.746890 0.660511 +0.746855 0.660512 +0.746435 0.660511 +0.300445 0.660590 +0.317187 0.660461 +0.321888 0.660431 +0.321879 0.661087 +0.317179 0.661116 +0.312604 0.660491 +0.312595 0.661146 +0.308461 0.660520 +0.305045 0.660545 +0.308452 0.661175 +0.302549 0.660566 +0.305037 0.661201 +0.301033 0.660581 +0.302541 0.661222 +0.325490 0.661087 +0.325497 0.660431 +0.321271 0.661116 +0.321279 0.660461 +0.316953 0.661146 +0.316961 0.660491 +0.312765 0.661175 +0.312772 0.660520 +0.308950 0.661201 +0.308958 0.660545 +0.305725 0.661222 +0.303238 0.661237 +0.305733 0.660566 +0.303245 0.660581 +0.301550 0.661246 +0.301558 0.660590 +0.300641 0.661248 +0.300437 0.661246 +0.300649 0.660593 +0.301026 0.661237 +0.330072 0.660387 +0.344942 0.660296 +0.332243 0.660374 +0.347490 0.660281 +0.334032 0.660364 +0.348938 0.660272 +0.335336 0.660356 +0.349389 0.660270 +0.336124 0.660352 +0.348970 0.660272 +0.336428 0.660350 +0.347627 0.660281 +0.336302 0.660352 +0.345333 0.660296 +0.335713 0.660356 +0.342172 0.660317 +0.334637 0.660364 +0.338337 0.660343 +0.333104 0.660374 +0.334096 0.660372 +0.331205 0.660387 +0.329732 0.660402 +0.329074 0.660402 +0.325497 0.660431 +0.326856 0.660417 +0.321279 0.660461 +0.324683 0.660431 +0.316961 0.660491 +0.322500 0.660446 +0.312772 0.660520 +0.320251 0.660461 +0.308958 0.660545 +0.318057 0.660475 +0.305733 0.660566 +0.316056 0.660488 +0.303245 0.660581 +0.314371 0.660499 +0.301558 0.660590 +0.313087 0.660506 +0.300649 0.660593 +0.312241 0.660511 +0.300445 0.660590 +0.311821 0.660512 +0.301033 0.660581 +0.311787 0.660511 +0.302549 0.660566 +0.312180 0.660506 +0.305045 0.660545 +0.313055 0.660499 +0.308461 0.660520 +0.314419 0.660488 +0.312604 0.660491 +0.316211 0.660475 +0.317187 0.660461 +0.318319 0.660461 +0.321888 0.660431 +0.320594 0.660446 +0.326759 0.660402 +0.322884 0.660431 +0.331869 0.660372 +0.325229 0.660417 +0.336860 0.660343 +0.327676 0.660402 +0.341331 0.660317 +0.554103 0.562435 +0.554103 0.562238 +0.565975 0.558207 +0.565989 0.558030 +0.565931 0.558388 +0.565854 0.558561 +0.565746 0.558715 +0.565613 0.558840 +0.565465 0.558929 +0.565312 0.558981 +0.566011 0.563101 +0.565163 0.558998 +0.555506 0.559013 +0.555237 0.559068 +0.554968 0.559240 +0.554715 0.559538 +0.554495 0.559956 +0.554318 0.560470 +0.554195 0.561047 +0.554124 0.561648 +0.503122 0.580072 +0.555554 0.580072 +0.565253 0.580597 +0.493423 0.580597 +0.504544 0.576545 +0.504544 0.576742 +0.492599 0.581418 +0.492584 0.581596 +0.492645 0.581236 +0.492725 0.581060 +0.492835 0.580902 +0.492969 0.580772 +0.493119 0.580677 +0.493273 0.580619 +0.492607 0.576525 +0.493423 0.580597 +0.503122 0.580072 +0.503393 0.579999 +0.503664 0.579806 +0.503918 0.579489 +0.504142 0.579055 +0.504320 0.578527 +0.504447 0.577941 +0.504520 0.577334 +0.565163 0.558998 +0.555506 0.559013 +0.503171 0.559013 +0.493514 0.558998 +0.519402 0.563247 +0.517760 0.575562 +0.528566 0.575733 +0.530110 0.563247 +0.504544 0.576742 +0.504544 0.576545 +0.541497 0.576545 +0.554132 0.576545 +0.554103 0.562238 +0.554103 0.562435 +0.517194 0.562435 +0.504573 0.562435 +0.517750 0.575741 +0.517772 0.563418 +0.519412 0.563068 +0.519392 0.575733 +0.528567 0.563247 +0.530119 0.563068 +0.530110 0.575733 +0.528556 0.575912 +0.517719 0.575924 +0.517762 0.563239 +0.519443 0.562885 +0.519401 0.575912 +0.530120 0.575912 +0.528525 0.576095 +0.528557 0.563068 +0.530151 0.562885 +0.517665 0.576100 +0.517732 0.563056 +0.519498 0.562709 +0.519432 0.576095 +0.528526 0.562885 +0.530205 0.562709 +0.530152 0.576095 +0.528471 0.576271 +0.517589 0.576257 +0.517678 0.562880 +0.519573 0.562551 +0.519486 0.576271 +0.530206 0.576271 +0.528395 0.576429 +0.528472 0.562709 +0.530281 0.562551 +0.517497 0.576385 +0.517603 0.562723 +0.528396 0.562551 +0.530375 0.562424 +0.530282 0.576429 +0.528301 0.576556 +0.519666 0.562424 +0.519561 0.576429 +0.517393 0.576476 +0.517511 0.562595 +0.530376 0.576556 +0.528196 0.576647 +0.528302 0.562424 +0.530479 0.562332 +0.519770 0.562332 +0.519654 0.576556 +0.517285 0.576528 +0.517407 0.562504 +0.528197 0.562332 +0.530588 0.562280 +0.530481 0.576647 +0.528087 0.576700 +0.519878 0.562280 +0.519758 0.576647 +0.517179 0.576545 +0.517299 0.562451 +0.530590 0.576700 +0.527980 0.576716 +0.528088 0.562280 +0.530695 0.562263 +0.519984 0.562263 +0.519867 0.576700 +0.554133 0.576742 +0.519973 0.576716 +0.530697 0.576716 +0.538704 0.576716 +0.541392 0.576528 +0.538810 0.576700 +0.541284 0.576476 +0.538918 0.576647 +0.541180 0.576385 +0.539022 0.576556 +0.541087 0.576257 +0.539115 0.576429 +0.541012 0.576100 +0.539191 0.576271 +0.540958 0.575924 +0.539245 0.576095 +0.540927 0.575741 +0.539275 0.575912 +0.540917 0.575562 +0.539285 0.575733 +0.540905 0.563418 +0.540914 0.563239 +0.539274 0.563247 +0.540945 0.563056 +0.539265 0.563068 +0.540999 0.562880 +0.539233 0.562885 +0.541074 0.562723 +0.539179 0.562709 +0.541166 0.562595 +0.539104 0.562551 +0.541270 0.562504 +0.539011 0.562424 +0.541378 0.562451 +0.538907 0.562332 +0.541483 0.562435 +0.538798 0.562280 +0.504574 0.562238 +0.538692 0.562263 +0.527982 0.562263 +0.492607 0.576525 +0.494994 0.576525 +0.514657 0.576535 +0.517179 0.576545 +0.501663 0.576535 +0.504544 0.576545 +0.515367 0.563751 +0.517772 0.563418 +0.517760 0.575562 +0.515350 0.575552 +0.501700 0.562768 +0.495049 0.563101 +0.504573 0.562435 +0.517194 0.562435 +0.514677 0.562768 +0.492666 0.563101 +0.515319 0.563389 +0.515356 0.563573 +0.514657 0.576535 +0.501663 0.576535 +0.501821 0.562785 +0.501700 0.562768 +0.501944 0.562837 +0.501783 0.576518 +0.501907 0.576466 +0.502062 0.562928 +0.502168 0.563056 +0.502026 0.576375 +0.502132 0.576247 +0.502254 0.563213 +0.502329 0.575552 +0.506816 0.570617 +0.506721 0.570129 +0.506692 0.569651 +0.506723 0.569174 +0.502315 0.563389 +0.502219 0.576090 +0.506821 0.568686 +0.502281 0.575913 +0.502350 0.563573 +0.506989 0.568217 +0.502360 0.563751 +0.502317 0.575731 +0.507224 0.567797 +0.506982 0.571086 +0.507216 0.571506 +0.507513 0.567457 +0.507837 0.567213 +0.508174 0.567073 +0.508503 0.567029 +0.508833 0.567073 +0.509170 0.567213 +0.509495 0.567457 +0.509785 0.567797 +0.510021 0.568217 +0.510189 0.568686 +0.510285 0.569174 +0.507504 0.571846 +0.507827 0.572090 +0.508163 0.572230 +0.508492 0.572274 +0.508822 0.572230 +0.509161 0.572090 +0.509486 0.571846 +0.509778 0.571506 +0.510015 0.571086 +0.510185 0.570617 +0.514783 0.576518 +0.514911 0.576466 +0.515036 0.576375 +0.515146 0.576247 +0.515236 0.576090 +0.515301 0.575913 +0.515338 0.575731 +0.515350 0.575552 +0.515367 0.563751 +0.510283 0.570129 +0.510315 0.569651 +0.514677 0.562768 +0.514803 0.562785 +0.514931 0.562837 +0.515055 0.562928 +0.515165 0.563056 +0.515255 0.563213 +0.566011 0.563101 +0.563627 0.563101 +0.543999 0.562768 +0.541483 0.562435 +0.557092 0.562768 +0.554103 0.562435 +0.540917 0.575562 +0.540905 0.563418 +0.543310 0.563751 +0.543327 0.575552 +0.557130 0.576535 +0.563683 0.576525 +0.554132 0.576545 +0.541497 0.576545 +0.544020 0.576535 +0.566070 0.576525 +0.543745 0.562837 +0.543874 0.562785 +0.543999 0.562768 +0.557092 0.562768 +0.557009 0.576518 +0.557130 0.576535 +0.556886 0.576466 +0.556972 0.562785 +0.556849 0.562837 +0.556767 0.576374 +0.556660 0.576247 +0.556730 0.562929 +0.556625 0.563056 +0.556574 0.576090 +0.556432 0.563752 +0.551694 0.571086 +0.551861 0.570617 +0.551956 0.570129 +0.551985 0.569651 +0.556512 0.575913 +0.556539 0.563214 +0.551954 0.569174 +0.556478 0.563390 +0.556476 0.575730 +0.551856 0.568686 +0.556464 0.575551 +0.556443 0.563573 +0.551688 0.568217 +0.551461 0.571506 +0.551173 0.571846 +0.551453 0.567797 +0.551164 0.567457 +0.550840 0.567213 +0.550503 0.567073 +0.550173 0.567029 +0.549844 0.567073 +0.549506 0.567213 +0.549181 0.567457 +0.548892 0.567797 +0.548656 0.568217 +0.548488 0.568686 +0.550850 0.572090 +0.550514 0.572230 +0.550184 0.572274 +0.549854 0.572230 +0.549516 0.572090 +0.549190 0.571846 +0.548899 0.571506 +0.548662 0.571086 +0.548492 0.570617 +0.548393 0.570129 +0.544020 0.576535 +0.543894 0.576518 +0.543765 0.576466 +0.543641 0.576375 +0.543530 0.576247 +0.543440 0.576090 +0.543376 0.575913 +0.543338 0.575731 +0.543327 0.575552 +0.548362 0.569651 +0.548392 0.569174 +0.543310 0.563751 +0.543321 0.563573 +0.543358 0.563389 +0.543422 0.563213 +0.543511 0.563056 +0.543622 0.562928 +0.519973 0.576716 +0.515645 0.576696 +0.526997 0.576696 +0.527980 0.576716 +0.528566 0.575733 +0.527875 0.575713 +0.527877 0.563913 +0.528567 0.563247 +0.515669 0.562930 +0.519984 0.562263 +0.527982 0.562263 +0.527001 0.562930 +0.519392 0.575733 +0.519402 0.563247 +0.514804 0.563913 +0.514782 0.575713 +0.530697 0.576716 +0.531680 0.576696 +0.543032 0.576696 +0.538704 0.576716 +0.539274 0.563247 +0.539285 0.575733 +0.543895 0.575713 +0.543873 0.563913 +0.531676 0.562930 +0.530695 0.562263 +0.538692 0.562263 +0.543008 0.562930 +0.530110 0.575733 +0.530110 0.563247 +0.530800 0.563913 +0.530802 0.575713 +0.501642 0.572445 +0.501205 0.572489 +0.499990 0.569893 +0.501225 0.567245 +0.501662 0.567289 +0.502109 0.567429 +0.502540 0.567672 +0.502925 0.568013 +0.503237 0.568432 +0.503460 0.568902 +0.503588 0.569390 +0.503627 0.569867 +0.503585 0.570344 +0.503454 0.570832 +0.503227 0.571302 +0.502912 0.571721 +0.502524 0.572062 +0.502091 0.572305 +0.499990 0.569893 +0.499990 0.569893 +0.499990 0.569893 +0.499990 0.569893 +0.499990 0.569893 +0.499990 0.569893 +0.499990 0.569893 +0.499990 0.569893 +0.499990 0.569893 +0.499990 0.569893 +0.499990 0.569893 +0.499990 0.569893 +0.499990 0.569893 +0.499990 0.569893 +0.499990 0.569893 +0.499990 0.569893 +0.510189 0.568686 +0.501662 0.567289 +0.501225 0.567245 +0.508503 0.567029 +0.508833 0.567073 +0.502109 0.567429 +0.509170 0.567213 +0.502540 0.567672 +0.509495 0.567457 +0.502925 0.568013 +0.509785 0.567797 +0.503237 0.568432 +0.503460 0.568902 +0.510021 0.568217 +0.508492 0.572274 +0.501205 0.572489 +0.508822 0.572230 +0.509161 0.572090 +0.501642 0.572445 +0.502091 0.572305 +0.509486 0.571846 +0.502524 0.572062 +0.509778 0.571506 +0.502912 0.571721 +0.510015 0.571086 +0.503227 0.571302 +0.510185 0.570617 +0.503454 0.570832 +0.510283 0.570129 +0.503585 0.570344 +0.510315 0.569651 +0.510285 0.569174 +0.503627 0.569867 +0.503588 0.569390 +0.557472 0.572489 +0.557908 0.572445 +0.558353 0.572305 +0.558687 0.569893 +0.557452 0.567245 +0.557888 0.567289 +0.558334 0.567429 +0.558762 0.567672 +0.559145 0.568013 +0.559455 0.568432 +0.559678 0.568902 +0.559807 0.569390 +0.559848 0.569867 +0.559811 0.570344 +0.559686 0.570832 +0.559467 0.571302 +0.559160 0.571721 +0.558780 0.572062 +0.558687 0.569893 +0.558687 0.569893 +0.558687 0.569893 +0.558687 0.569893 +0.558687 0.569893 +0.558687 0.569893 +0.558687 0.569893 +0.558687 0.569893 +0.558687 0.569893 +0.558687 0.569893 +0.558687 0.569893 +0.558687 0.569893 +0.558687 0.569893 +0.558687 0.569893 +0.558687 0.569893 +0.558687 0.569893 +0.559160 0.571721 +0.550184 0.572274 +0.557472 0.572489 +0.550514 0.572230 +0.557908 0.572445 +0.550850 0.572090 +0.558353 0.572305 +0.551173 0.571846 +0.551461 0.571506 +0.558780 0.572062 +0.557452 0.567245 +0.550173 0.567029 +0.557888 0.567289 +0.550503 0.567073 +0.558334 0.567429 +0.550840 0.567213 +0.558762 0.567672 +0.551164 0.567457 +0.559145 0.568013 +0.551453 0.567797 +0.559455 0.568432 +0.551688 0.568217 +0.559678 0.568902 +0.551856 0.568686 +0.559807 0.569390 +0.551954 0.569174 +0.559848 0.569867 +0.551985 0.569651 +0.559811 0.570344 +0.551956 0.570129 +0.559686 0.570832 +0.551861 0.570617 +0.559467 0.571302 +0.551694 0.571086 +0.495847 0.564085 +0.502360 0.563751 +0.502329 0.575552 +0.495800 0.575542 +0.527320 0.576627 +0.527157 0.576680 +0.514922 0.576251 +0.514842 0.576075 +0.515034 0.576408 +0.515172 0.576536 +0.514796 0.575892 +0.515327 0.576627 +0.515488 0.576680 +0.515645 0.576696 +0.514782 0.575713 +0.526997 0.576696 +0.514804 0.563913 +0.514819 0.563734 +0.514865 0.563551 +0.514946 0.563375 +0.515058 0.563218 +0.515196 0.563090 +0.515351 0.562999 +0.515512 0.562946 +0.515669 0.562930 +0.527001 0.562930 +0.527160 0.562946 +0.527323 0.562999 +0.527480 0.563090 +0.527621 0.563218 +0.527734 0.563375 +0.527816 0.563551 +0.527862 0.563734 +0.527877 0.563913 +0.527875 0.575713 +0.527860 0.575892 +0.527813 0.576075 +0.527732 0.576251 +0.527618 0.576408 +0.527477 0.576536 +0.543350 0.576627 +0.543189 0.576680 +0.530945 0.576251 +0.530864 0.576075 +0.531059 0.576408 +0.531200 0.576536 +0.530816 0.575892 +0.531357 0.576627 +0.531520 0.576680 +0.531680 0.576696 +0.530802 0.575713 +0.543032 0.576696 +0.530800 0.563913 +0.530814 0.563734 +0.530861 0.563551 +0.530942 0.563375 +0.531056 0.563218 +0.531196 0.563090 +0.531353 0.562999 +0.531516 0.562946 +0.531676 0.562930 +0.543008 0.562930 +0.543165 0.562946 +0.543326 0.562999 +0.543481 0.563090 +0.543619 0.563218 +0.543731 0.563375 +0.543812 0.563551 +0.543858 0.563734 +0.543873 0.563913 +0.543895 0.575713 +0.543880 0.575892 +0.543835 0.576075 +0.543755 0.576251 +0.543643 0.576408 +0.543505 0.576536 +0.562876 0.575541 +0.556464 0.575551 +0.556432 0.563752 +0.562830 0.564085 +0.660950 0.615260 +0.650632 0.615150 +0.651214 0.654487 +0.661368 0.654594 +0.660950 0.615260 +0.661368 0.654594 +0.661935 0.654594 +0.661491 0.615260 +0.661491 0.615260 +0.661935 0.654594 +0.651865 0.654487 +0.651254 0.615150 +0.650632 0.615150 +0.660950 0.615260 +0.661491 0.615260 +0.651254 0.615150 +0.623009 0.550990 +0.627751 0.550990 +0.626569 0.550979 +0.621817 0.550979 +0.627768 0.552818 +0.627751 0.550990 +0.623009 0.550990 +0.623026 0.552818 +0.626585 0.552806 +0.627768 0.552818 +0.623026 0.552818 +0.621833 0.552806 +0.626585 0.552806 +0.621833 0.552806 +0.619191 0.553372 +0.623959 0.553372 +0.626569 0.550979 +0.623355 0.550222 +0.618585 0.550222 +0.621817 0.550979 +0.626569 0.550979 +0.627751 0.550990 +0.623959 0.553372 +0.623355 0.550222 +0.626585 0.552806 +0.627768 0.552818 +0.623026 0.552818 +0.623009 0.550990 +0.621817 0.550979 +0.618585 0.550222 +0.619191 0.553372 +0.621833 0.552806 +0.583542 0.550990 +0.582576 0.550979 +0.573913 0.550979 +0.574761 0.550990 +0.583556 0.552818 +0.583542 0.550990 +0.574761 0.550990 +0.574773 0.552818 +0.582589 0.552806 +0.583556 0.552818 +0.574773 0.552818 +0.573925 0.552806 +0.582589 0.552806 +0.573925 0.552806 +0.572093 0.553372 +0.580493 0.553372 +0.582576 0.550979 +0.580022 0.550222 +0.571681 0.550222 +0.573913 0.550979 +0.583542 0.550990 +0.583556 0.552818 +0.580493 0.553372 +0.580022 0.550222 +0.582589 0.552806 +0.582576 0.550979 +0.574773 0.552818 +0.574761 0.550990 +0.573913 0.550979 +0.571681 0.550222 +0.572093 0.553372 +0.573925 0.552806 +0.805084 0.632857 +0.809166 0.632916 +0.807992 0.632916 +0.803897 0.632857 +0.642392 0.631628 +0.643482 0.631628 +0.636996 0.631569 +0.635857 0.631569 +0.172129 0.632857 +0.172054 0.632916 +0.170070 0.632916 +0.169996 0.632857 +0.170070 0.632916 +0.527494 0.631628 +0.531183 0.631628 +0.530970 0.631569 +0.527706 0.631569 +0.254780 0.632857 +0.250685 0.632916 +0.249511 0.632916 +0.253593 0.632857 +0.415195 0.631628 +0.416285 0.631628 +0.422819 0.631569 +0.421681 0.631569 +0.829551 0.551687 +0.824789 0.551687 +0.822938 0.552380 +0.827782 0.552380 +0.822947 0.554208 +0.824471 0.554825 +0.829247 0.554825 +0.827790 0.554208 +0.822263 0.554196 +0.822947 0.554208 +0.827790 0.554208 +0.827135 0.554196 +0.827126 0.552369 +0.822253 0.552369 +0.822263 0.554196 +0.827135 0.554196 +0.822938 0.552380 +0.822253 0.552369 +0.827126 0.552369 +0.827782 0.552380 +0.822263 0.554196 +0.822253 0.552369 +0.822938 0.552380 +0.824789 0.551687 +0.824471 0.554825 +0.822947 0.554208 +0.827126 0.552369 +0.827135 0.554196 +0.829247 0.554825 +0.829551 0.551687 +0.827790 0.554208 +0.827782 0.552380 +0.868702 0.551687 +0.862540 0.551687 +0.861649 0.552380 +0.868020 0.552380 +0.868023 0.554208 +0.861654 0.554208 +0.862388 0.554825 +0.868585 0.554825 +0.861321 0.554196 +0.861654 0.554208 +0.868023 0.554208 +0.867768 0.554196 +0.861316 0.552369 +0.861321 0.554196 +0.867768 0.554196 +0.867764 0.552369 +0.861649 0.552380 +0.861316 0.552369 +0.867764 0.552369 +0.868020 0.552380 +0.861321 0.554196 +0.861316 0.552369 +0.861649 0.552380 +0.862540 0.551687 +0.862388 0.554825 +0.861654 0.554208 +0.867764 0.552369 +0.867768 0.554196 +0.868585 0.554825 +0.868702 0.551687 +0.868023 0.554208 +0.868020 0.552380 +0.436860 0.550979 +0.432108 0.550979 +0.430925 0.550990 +0.435668 0.550990 +0.436860 0.550979 +0.440092 0.550222 +0.435322 0.550222 +0.432108 0.550979 +0.436844 0.552806 +0.432092 0.552806 +0.434718 0.553372 +0.439486 0.553372 +0.435651 0.552818 +0.430909 0.552818 +0.432092 0.552806 +0.436844 0.552806 +0.435668 0.550990 +0.430925 0.550990 +0.430909 0.552818 +0.435651 0.552818 +0.430909 0.552818 +0.430925 0.550990 +0.432108 0.550979 +0.435322 0.550222 +0.434718 0.553372 +0.432092 0.552806 +0.436860 0.550979 +0.439486 0.553372 +0.440092 0.550222 +0.436844 0.552806 +0.435668 0.550990 +0.435651 0.552818 +0.484763 0.550979 +0.476101 0.550979 +0.475134 0.550990 +0.483915 0.550990 +0.484763 0.550979 +0.486995 0.550222 +0.478655 0.550222 +0.476101 0.550979 +0.484752 0.552806 +0.476088 0.552806 +0.478183 0.553372 +0.486584 0.553372 +0.483904 0.552818 +0.475121 0.552818 +0.476088 0.552806 +0.484752 0.552806 +0.483915 0.550990 +0.475134 0.550990 +0.475121 0.552818 +0.483904 0.552818 +0.475121 0.552818 +0.475134 0.550990 +0.476101 0.550979 +0.478655 0.550222 +0.478183 0.553372 +0.476088 0.552806 +0.483915 0.550990 +0.483904 0.552818 +0.486584 0.553372 +0.486995 0.550222 +0.484752 0.552806 +0.484763 0.550979 +0.229126 0.551687 +0.230895 0.552380 +0.235739 0.552380 +0.233887 0.551687 +0.231550 0.552369 +0.236424 0.552369 +0.235739 0.552380 +0.230895 0.552380 +0.231550 0.552369 +0.231542 0.554196 +0.236414 0.554196 +0.236424 0.552369 +0.231542 0.554196 +0.230886 0.554208 +0.235730 0.554208 +0.236414 0.554196 +0.229430 0.554825 +0.234206 0.554825 +0.235730 0.554208 +0.230886 0.554208 +0.236424 0.552369 +0.236414 0.554196 +0.234206 0.554825 +0.233887 0.551687 +0.235730 0.554208 +0.235739 0.552380 +0.231542 0.554196 +0.231550 0.552369 +0.230895 0.552380 +0.229126 0.551687 +0.229430 0.554825 +0.230886 0.554208 +0.189975 0.551687 +0.190657 0.552380 +0.197027 0.552380 +0.196136 0.551687 +0.190912 0.552369 +0.197361 0.552369 +0.197027 0.552380 +0.190657 0.552380 +0.190909 0.554196 +0.197356 0.554196 +0.197361 0.552369 +0.190912 0.552369 +0.190654 0.554208 +0.197023 0.554208 +0.197356 0.554196 +0.190909 0.554196 +0.190654 0.554208 +0.190091 0.554825 +0.196289 0.554825 +0.197023 0.554208 +0.197361 0.552369 +0.197356 0.554196 +0.196289 0.554825 +0.196136 0.551687 +0.197023 0.554208 +0.197027 0.552380 +0.190909 0.554196 +0.190912 0.552369 +0.190657 0.552380 +0.189975 0.551687 +0.190091 0.554825 +0.190654 0.554208 +0.320255 0.660133 +0.324683 0.660431 +0.324687 0.660103 +0.322500 0.660446 +0.322504 0.660118 +0.320251 0.660461 +0.322888 0.660103 +0.322884 0.660431 +0.320598 0.660118 +0.318324 0.660133 +0.320594 0.660446 +0.316216 0.660148 +0.318319 0.660461 +0.314423 0.660161 +0.316211 0.660475 +0.314419 0.660488 +0.313059 0.660171 +0.312184 0.660179 +0.313055 0.660499 +0.312180 0.660506 +0.311791 0.660183 +0.311787 0.660511 +0.311825 0.660184 +0.311821 0.660512 +0.312245 0.660183 +0.312241 0.660511 +0.313091 0.660179 +0.313087 0.660506 +0.314374 0.660171 +0.316060 0.660161 +0.314371 0.660499 +0.316056 0.660488 +0.318061 0.660148 +0.318057 0.660475 +0.336432 0.660023 +0.336128 0.660024 +0.330077 0.660059 +0.327681 0.660074 +0.332247 0.660046 +0.334036 0.660036 +0.325233 0.660089 +0.335341 0.660028 +0.322888 0.660103 +0.320598 0.660118 +0.318324 0.660133 +0.316216 0.660148 +0.314423 0.660161 +0.313059 0.660171 +0.312184 0.660179 +0.311791 0.660183 +0.311825 0.660184 +0.312245 0.660183 +0.313091 0.660179 +0.314374 0.660171 +0.316060 0.660161 +0.318061 0.660148 +0.320255 0.660133 +0.322504 0.660118 +0.324687 0.660103 +0.326860 0.660089 +0.329078 0.660074 +0.331210 0.660059 +0.333108 0.660046 +0.334641 0.660036 +0.335718 0.660028 +0.336306 0.660024 +0.746855 0.660512 +0.736173 0.660118 +0.733990 0.660103 +0.733994 0.660431 +0.738422 0.660133 +0.736177 0.660446 +0.738426 0.660461 +0.740615 0.660148 +0.742616 0.660161 +0.740619 0.660475 +0.742620 0.660488 +0.744302 0.660171 +0.745586 0.660179 +0.744306 0.660499 +0.746432 0.660183 +0.745590 0.660506 +0.746851 0.660184 +0.746435 0.660511 +0.738083 0.660446 +0.735793 0.660431 +0.735789 0.660103 +0.738079 0.660118 +0.740357 0.660461 +0.740353 0.660133 +0.742465 0.660475 +0.744258 0.660488 +0.742461 0.660148 +0.744254 0.660161 +0.745621 0.660499 +0.745617 0.660171 +0.746497 0.660506 +0.746493 0.660179 +0.746890 0.660511 +0.746886 0.660183 +0.722548 0.660024 +0.722245 0.660023 +0.727467 0.660059 +0.729599 0.660074 +0.725569 0.660046 +0.724036 0.660036 +0.731817 0.660089 +0.722959 0.660028 +0.733990 0.660103 +0.722371 0.660024 +0.736173 0.660118 +0.738422 0.660133 +0.740615 0.660148 +0.742616 0.660161 +0.744302 0.660171 +0.745586 0.660179 +0.746432 0.660183 +0.746851 0.660184 +0.746886 0.660183 +0.746493 0.660179 +0.745617 0.660171 +0.744254 0.660161 +0.742461 0.660148 +0.740353 0.660133 +0.738079 0.660118 +0.735789 0.660103 +0.733443 0.660089 +0.730996 0.660074 +0.728600 0.660059 +0.726430 0.660046 +0.724641 0.660036 +0.723336 0.660028 +0.554103 0.562238 +0.504574 0.562238 +0.503171 0.559013 +0.555506 0.559013 +0.503440 0.559068 +0.555237 0.559068 +0.503709 0.559240 +0.554968 0.559240 +0.503962 0.559538 +0.554715 0.559538 +0.504182 0.559956 +0.554495 0.559956 +0.504358 0.560470 +0.554318 0.560470 +0.504482 0.561047 +0.554195 0.561047 +0.504553 0.561648 +0.554124 0.561648 +0.504544 0.576742 +0.554133 0.576742 +0.555554 0.580072 +0.503122 0.580072 +0.555284 0.579999 +0.503393 0.579999 +0.555013 0.579806 +0.503664 0.579806 +0.554758 0.579489 +0.503918 0.579489 +0.554535 0.579055 +0.504142 0.579055 +0.554356 0.578527 +0.504320 0.578527 +0.554230 0.577941 +0.504447 0.577941 +0.554156 0.577334 +0.504520 0.577334 +0.528567 0.563247 +0.527877 0.563913 +0.527160 0.562946 +0.527001 0.562930 +0.527982 0.562263 +0.527323 0.562999 +0.528088 0.562280 +0.527480 0.563090 +0.528197 0.562332 +0.527553 0.563150 +0.528302 0.562424 +0.527621 0.563218 +0.528351 0.562483 +0.528396 0.562551 +0.527681 0.563293 +0.528436 0.562627 +0.527734 0.563375 +0.528472 0.562709 +0.527816 0.563551 +0.528526 0.562885 +0.527862 0.563734 +0.528557 0.563068 +0.565163 0.558998 +0.493514 0.558998 +0.492688 0.558030 +0.565989 0.558030 +0.492701 0.558207 +0.565975 0.558207 +0.492746 0.558388 +0.565931 0.558388 +0.492823 0.558561 +0.565854 0.558561 +0.492931 0.558715 +0.565746 0.558715 +0.493064 0.558840 +0.565613 0.558840 +0.493212 0.558929 +0.565465 0.558929 +0.493365 0.558981 +0.565312 0.558981 +0.493423 0.580597 +0.565253 0.580597 +0.566092 0.581596 +0.492584 0.581596 +0.566077 0.581418 +0.492599 0.581418 +0.566031 0.581236 +0.492645 0.581236 +0.565952 0.581060 +0.492725 0.581060 +0.565842 0.580902 +0.492835 0.580902 +0.565708 0.580772 +0.492969 0.580772 +0.565558 0.580677 +0.493119 0.580677 +0.565404 0.580619 +0.493273 0.580619 +0.556464 0.575551 +0.562876 0.575541 +0.563683 0.576525 +0.557130 0.576535 +0.563537 0.576508 +0.557009 0.576518 +0.563388 0.576456 +0.556886 0.576466 +0.563244 0.576364 +0.556767 0.576374 +0.563177 0.576305 +0.556711 0.576315 +0.563115 0.576237 +0.556660 0.576247 +0.563059 0.576161 +0.556614 0.576171 +0.563010 0.576079 +0.556574 0.576090 +0.562934 0.575903 +0.556512 0.575913 +0.562891 0.575720 +0.556476 0.575730 +0.556972 0.562785 +0.557092 0.562768 +0.562843 0.563906 +0.562830 0.564085 +0.556432 0.563752 +0.562885 0.563723 +0.556443 0.563573 +0.562959 0.563547 +0.556478 0.563390 +0.563007 0.563465 +0.556539 0.563214 +0.563062 0.563390 +0.556579 0.563132 +0.563124 0.563321 +0.556625 0.563056 +0.563190 0.563262 +0.556675 0.562988 +0.563333 0.563170 +0.556730 0.562929 +0.563482 0.563118 +0.556849 0.562837 +0.563627 0.563101 +0.501663 0.576535 +0.494994 0.576525 +0.495786 0.575720 +0.495800 0.575542 +0.502329 0.575552 +0.495742 0.575903 +0.502317 0.575731 +0.495667 0.576080 +0.502281 0.575913 +0.495618 0.576161 +0.502219 0.576090 +0.495562 0.576237 +0.502178 0.576171 +0.502132 0.576247 +0.495500 0.576305 +0.502081 0.576315 +0.495433 0.576364 +0.502026 0.576375 +0.495289 0.576456 +0.501907 0.576466 +0.495140 0.576508 +0.501783 0.576518 +0.502360 0.563751 +0.495847 0.564085 +0.495195 0.563118 +0.495049 0.563101 +0.501700 0.562768 +0.495344 0.563170 +0.501821 0.562785 +0.495487 0.563262 +0.501944 0.562837 +0.495553 0.563321 +0.502062 0.562928 +0.495615 0.563389 +0.502117 0.562988 +0.502168 0.563056 +0.495670 0.563465 +0.502213 0.563132 +0.495718 0.563547 +0.502254 0.563213 +0.495792 0.563723 +0.502315 0.563389 +0.495834 0.563906 +0.502350 0.563573 +0.539274 0.563247 +0.543873 0.563913 +0.543165 0.562946 +0.543008 0.562930 +0.538692 0.562263 +0.543326 0.562999 +0.538798 0.562280 +0.543481 0.563090 +0.538907 0.562332 +0.543552 0.563150 +0.539011 0.562424 +0.543619 0.563218 +0.539059 0.562483 +0.539104 0.562551 +0.543679 0.563293 +0.539144 0.562627 +0.543731 0.563375 +0.539179 0.562709 +0.543812 0.563551 +0.539233 0.562885 +0.543858 0.563734 +0.539265 0.563068 +0.538704 0.576716 +0.543032 0.576696 +0.543880 0.575892 +0.543895 0.575713 +0.539285 0.575733 +0.543835 0.576075 +0.539275 0.575912 +0.543755 0.576251 +0.539245 0.576095 +0.543702 0.576333 +0.539191 0.576271 +0.543643 0.576408 +0.539155 0.576353 +0.539115 0.576429 +0.543576 0.576476 +0.539071 0.576497 +0.543505 0.576536 +0.539022 0.576556 +0.543350 0.576627 +0.538918 0.576647 +0.543189 0.576680 +0.538810 0.576700 +0.527980 0.576716 +0.526997 0.576696 +0.527860 0.575892 +0.527875 0.575713 +0.528566 0.575733 +0.527813 0.576075 +0.528556 0.575912 +0.527732 0.576251 +0.528525 0.576095 +0.527678 0.576333 +0.528471 0.576271 +0.527618 0.576408 +0.528435 0.576353 +0.528395 0.576429 +0.527550 0.576476 +0.528350 0.576497 +0.527477 0.576536 +0.528301 0.576556 +0.527320 0.576627 +0.528196 0.576647 +0.527157 0.576680 +0.528087 0.576700 +0.519392 0.575733 +0.514782 0.575713 +0.515488 0.576680 +0.515645 0.576696 +0.519973 0.576716 +0.515327 0.576627 +0.519867 0.576700 +0.515172 0.576536 +0.519758 0.576647 +0.515100 0.576476 +0.519654 0.576556 +0.515034 0.576408 +0.519606 0.576497 +0.519561 0.576429 +0.514974 0.576333 +0.519521 0.576353 +0.514922 0.576251 +0.519486 0.576271 +0.514842 0.576075 +0.519432 0.576095 +0.514796 0.575892 +0.519401 0.575912 +0.530110 0.575733 +0.530802 0.575713 +0.531520 0.576680 +0.531680 0.576696 +0.530697 0.576716 +0.531357 0.576627 +0.530590 0.576700 +0.531200 0.576536 +0.530481 0.576647 +0.531126 0.576476 +0.530376 0.576556 +0.531059 0.576408 +0.530327 0.576497 +0.530282 0.576429 +0.530998 0.576333 +0.530242 0.576353 +0.530945 0.576251 +0.530206 0.576271 +0.530864 0.576075 +0.530152 0.576095 +0.530816 0.575892 +0.530120 0.575912 +0.540917 0.575562 +0.543327 0.575552 +0.543894 0.576518 +0.544020 0.576535 +0.541497 0.576545 +0.543765 0.576466 +0.541392 0.576528 +0.543641 0.576375 +0.541284 0.576476 +0.543584 0.576315 +0.541180 0.576385 +0.543530 0.576247 +0.541132 0.576325 +0.541087 0.576257 +0.543482 0.576171 +0.541047 0.576181 +0.543440 0.576090 +0.541012 0.576100 +0.543376 0.575913 +0.540958 0.575924 +0.543338 0.575731 +0.540927 0.575741 +0.541483 0.562435 +0.543999 0.562768 +0.543321 0.563573 +0.543310 0.563751 +0.540905 0.563418 +0.543358 0.563389 +0.540914 0.563239 +0.543422 0.563213 +0.540945 0.563056 +0.543464 0.563132 +0.540999 0.562880 +0.543511 0.563056 +0.541034 0.562798 +0.541074 0.562723 +0.543564 0.562988 +0.541118 0.562655 +0.543622 0.562928 +0.541166 0.562595 +0.543745 0.562837 +0.541270 0.562504 +0.543874 0.562785 +0.541378 0.562451 +0.530695 0.562263 +0.531676 0.562930 +0.530814 0.563734 +0.530800 0.563913 +0.530110 0.563247 +0.530861 0.563551 +0.530119 0.563068 +0.530942 0.563375 +0.530151 0.562885 +0.530995 0.563293 +0.530205 0.562709 +0.531056 0.563218 +0.530241 0.562627 +0.530281 0.562551 +0.531123 0.563150 +0.530326 0.562483 +0.531196 0.563090 +0.530375 0.562424 +0.531353 0.562999 +0.530479 0.562332 +0.531516 0.562946 +0.530588 0.562280 +0.519984 0.562263 +0.515669 0.562930 +0.514819 0.563734 +0.514804 0.563913 +0.519402 0.563247 +0.514865 0.563551 +0.519412 0.563068 +0.514946 0.563375 +0.519443 0.562885 +0.514998 0.563293 +0.519498 0.562709 +0.515058 0.563218 +0.519533 0.562627 +0.519573 0.562551 +0.515124 0.563150 +0.519618 0.562483 +0.515196 0.563090 +0.519666 0.562424 +0.515351 0.562999 +0.519770 0.562332 +0.515512 0.562946 +0.519878 0.562280 +0.517179 0.576545 +0.514657 0.576535 +0.515338 0.575731 +0.515350 0.575552 +0.517760 0.575562 +0.515301 0.575913 +0.517750 0.575741 +0.515236 0.576090 +0.517719 0.575924 +0.515194 0.576171 +0.517665 0.576100 +0.515146 0.576247 +0.517630 0.576181 +0.517589 0.576257 +0.515093 0.576315 +0.517545 0.576325 +0.515036 0.576375 +0.517497 0.576385 +0.514911 0.576466 +0.517393 0.576476 +0.514783 0.576518 +0.517285 0.576528 +0.517772 0.563418 +0.515367 0.563751 +0.514803 0.562785 +0.514677 0.562768 +0.517194 0.562435 +0.514931 0.562837 +0.517299 0.562451 +0.515055 0.562928 +0.517407 0.562504 +0.515112 0.562988 +0.517511 0.562595 +0.515165 0.563056 +0.517559 0.562655 +0.517603 0.562723 +0.515213 0.563132 +0.517643 0.562798 +0.515255 0.563213 +0.517678 0.562880 +0.515319 0.563389 +0.517732 0.563056 +0.515356 0.563573 +0.517762 0.563239 +0.189884 0.655220 +0.152241 0.655220 +0.145381 0.658443 +0.196743 0.658443 +0.145381 0.658443 +0.415347 0.654944 +0.423378 0.658222 +0.511057 0.658006 +0.516618 0.658001 +0.518595 0.654669 +0.505010 0.658019 +0.512745 0.654674 +0.498322 0.658040 +0.506412 0.654691 +0.490819 0.658066 +0.499397 0.654717 +0.491469 0.654749 +0.481578 0.658097 +0.481575 0.654788 +0.468877 0.658134 +0.467688 0.654835 +0.450595 0.658177 +0.447078 0.654888 +0.551224 0.654688 +0.545244 0.654673 +0.540082 0.654669 +0.542059 0.658001 +0.861934 0.658443 +0.868793 0.655220 +0.851998 0.658440 +0.839356 0.658428 +0.859679 0.655216 +0.822118 0.658407 +0.848368 0.655201 +0.833258 0.655175 +0.797263 0.658378 +0.811608 0.655140 +0.761233 0.658343 +0.714948 0.658303 +0.779275 0.655096 +0.669571 0.658262 +0.733787 0.655046 +0.635299 0.658222 +0.683590 0.654995 +0.643330 0.654944 +0.610660 0.658182 +0.592246 0.658141 +0.614558 0.654894 +0.593706 0.654843 +0.578446 0.658101 +0.567858 0.658066 +0.578558 0.654793 +0.567208 0.654749 +0.559489 0.658037 +0.558370 0.654714 +0.552673 0.658016 +0.546964 0.658005 +0.542059 0.658001 +0.540082 0.654669 +0.518595 0.654669 +0.516618 0.658001 +0.615938 0.537648 +0.614462 0.537648 +0.615634 0.538313 +0.617113 0.538313 +0.615607 0.538179 +0.617086 0.538179 +0.615534 0.538052 +0.617013 0.538052 +0.615423 0.537940 +0.616901 0.537940 +0.615285 0.537847 +0.616763 0.537847 +0.615120 0.537769 +0.616597 0.537769 +0.614923 0.537706 +0.616399 0.537706 +0.614699 0.537664 +0.616175 0.537664 +0.561971 0.537648 +0.559404 0.537648 +0.559999 0.538313 +0.562614 0.538313 +0.559985 0.538179 +0.562599 0.538179 +0.559948 0.538052 +0.562559 0.538052 +0.559891 0.537940 +0.562497 0.537940 +0.559821 0.537847 +0.562421 0.537847 +0.559737 0.537769 +0.562330 0.537769 +0.559636 0.537706 +0.562222 0.537706 +0.559523 0.537664 +0.562100 0.537664 +0.499273 0.537648 +0.496705 0.537648 +0.496063 0.538313 +0.498678 0.538313 +0.496078 0.538179 +0.498691 0.538179 +0.496118 0.538052 +0.498729 0.538052 +0.496180 0.537940 +0.498785 0.537940 +0.496256 0.537847 +0.498856 0.537847 +0.496346 0.537769 +0.498940 0.537769 +0.496455 0.537706 +0.499040 0.537706 +0.496577 0.537664 +0.499153 0.537664 +0.444214 0.537648 +0.442738 0.537648 +0.441564 0.538313 +0.443043 0.538313 +0.441591 0.538179 +0.443070 0.538179 +0.441664 0.538052 +0.443142 0.538052 +0.441776 0.537940 +0.443254 0.537940 +0.441914 0.537847 +0.443392 0.537847 +0.442079 0.537769 +0.443557 0.537769 +0.442277 0.537706 +0.443754 0.537706 +0.442501 0.537664 +0.443978 0.537664 +0.338666 0.538314 +0.335147 0.538356 +0.335104 0.539010 +0.338634 0.538969 +0.335106 0.538891 +0.338635 0.538849 +0.335109 0.538769 +0.338637 0.538728 +0.335114 0.538652 +0.338641 0.538610 +0.335119 0.538548 +0.338645 0.538506 +0.335126 0.538463 +0.338650 0.538421 +0.335133 0.538402 +0.338655 0.538360 +0.335141 0.538367 +0.338661 0.538325 +0.723822 0.538359 +0.719736 0.538311 +0.719769 0.538966 +0.723865 0.539015 +0.719767 0.538847 +0.723863 0.538896 +0.719765 0.538725 +0.723860 0.538774 +0.719762 0.538608 +0.723856 0.538656 +0.719757 0.538503 +0.723850 0.538551 +0.719752 0.538418 +0.723844 0.538466 +0.719747 0.538357 +0.723836 0.538405 +0.719741 0.538322 +0.723829 0.538370 +0.786335 0.539022 +0.785645 0.539022 +0.784933 0.539665 +0.785622 0.539665 +0.784945 0.539546 +0.785633 0.539546 +0.784983 0.539425 +0.785671 0.539425 +0.785049 0.539309 +0.785737 0.539309 +0.785141 0.539206 +0.785830 0.539206 +0.785256 0.539122 +0.785944 0.539122 +0.785383 0.539064 +0.786072 0.539064 +0.785516 0.539031 +0.786205 0.539031 +0.809472 0.539022 +0.808433 0.539022 +0.807715 0.539665 +0.808757 0.539665 +0.807726 0.539546 +0.808768 0.539546 +0.807765 0.539425 +0.808806 0.539425 +0.807832 0.539309 +0.808873 0.539309 +0.807925 0.539206 +0.808966 0.539206 +0.808040 0.539122 +0.809081 0.539122 +0.808169 0.539064 +0.809209 0.539064 +0.808303 0.539031 +0.809342 0.539031 +0.843747 0.539022 +0.842255 0.539022 +0.841731 0.539665 +0.843238 0.539665 +0.841742 0.539532 +0.843248 0.539532 +0.841774 0.539406 +0.843279 0.539406 +0.841824 0.539296 +0.843327 0.539296 +0.841885 0.539206 +0.843387 0.539206 +0.841959 0.539131 +0.843459 0.539131 +0.842048 0.539071 +0.843545 0.539071 +0.842149 0.539033 +0.843643 0.539033 +0.171935 0.539022 +0.170189 0.539022 +0.170177 0.539665 +0.171947 0.539665 +0.170178 0.539532 +0.171947 0.539532 +0.170179 0.539406 +0.171946 0.539406 +0.170180 0.539296 +0.171945 0.539296 +0.170181 0.539206 +0.171943 0.539206 +0.170183 0.539131 +0.171941 0.539131 +0.170185 0.539071 +0.171939 0.539071 +0.170187 0.539033 +0.171937 0.539033 +0.170187 0.539033 +0.170177 0.539665 +0.170178 0.539532 +0.170178 0.539532 +0.170179 0.539406 +0.170179 0.539406 +0.170180 0.539296 +0.170180 0.539296 +0.170181 0.539206 +0.170181 0.539206 +0.170183 0.539131 +0.170183 0.539131 +0.170185 0.539071 +0.170185 0.539071 +0.170187 0.539033 +0.216422 0.539022 +0.214930 0.539022 +0.215439 0.539665 +0.216946 0.539665 +0.215428 0.539532 +0.216934 0.539532 +0.215397 0.539406 +0.216902 0.539406 +0.215349 0.539296 +0.216853 0.539296 +0.215290 0.539206 +0.216791 0.539206 +0.215218 0.539131 +0.216717 0.539131 +0.215132 0.539071 +0.216629 0.539071 +0.215034 0.539033 +0.216528 0.539033 +0.250243 0.539022 +0.249205 0.539022 +0.249920 0.539665 +0.250962 0.539665 +0.249909 0.539546 +0.250950 0.539546 +0.249870 0.539425 +0.250912 0.539425 +0.249804 0.539309 +0.250845 0.539309 +0.249711 0.539206 +0.250751 0.539206 +0.249596 0.539122 +0.250636 0.539122 +0.249468 0.539064 +0.250507 0.539064 +0.249335 0.539031 +0.250374 0.539031 +0.273032 0.539022 +0.272342 0.539022 +0.273055 0.539665 +0.273743 0.539665 +0.273044 0.539546 +0.273732 0.539546 +0.273006 0.539425 +0.273694 0.539425 +0.272939 0.539309 +0.273628 0.539309 +0.272847 0.539206 +0.273535 0.539206 +0.272733 0.539122 +0.273421 0.539122 +0.272605 0.539064 +0.273294 0.539064 +0.272472 0.539031 +0.273161 0.539031 +0.404113 0.537648 +0.403543 0.537648 +0.402602 0.538314 +0.403166 0.538314 +0.402619 0.538194 +0.403182 0.538194 +0.402671 0.538072 +0.403234 0.538072 +0.402759 0.537954 +0.403323 0.537954 +0.402881 0.537848 +0.403446 0.537848 +0.403032 0.537761 +0.403598 0.537761 +0.403200 0.537698 +0.403767 0.537698 +0.403374 0.537661 +0.403942 0.537661 +0.424999 0.537648 +0.423979 0.537648 +0.422850 0.538314 +0.423865 0.538314 +0.422870 0.538194 +0.423886 0.538194 +0.422932 0.538072 +0.423948 0.538072 +0.423038 0.537954 +0.424054 0.537954 +0.423185 0.537848 +0.424202 0.537848 +0.423366 0.537761 +0.424383 0.537761 +0.423567 0.537698 +0.424586 0.537698 +0.423776 0.537661 +0.424795 0.537661 +0.464116 0.537648 +0.462175 0.537648 +0.461084 0.538314 +0.463042 0.538314 +0.461109 0.538179 +0.463066 0.538179 +0.461177 0.538053 +0.463133 0.538053 +0.461281 0.537941 +0.463236 0.537941 +0.461410 0.537848 +0.463362 0.537848 +0.461564 0.537770 +0.463514 0.537770 +0.461748 0.537706 +0.463695 0.537706 +0.461956 0.537665 +0.463900 0.537665 +0.530726 0.537648 +0.527951 0.537648 +0.527920 0.538314 +0.530756 0.538314 +0.527921 0.538179 +0.530755 0.538179 +0.527923 0.538053 +0.530753 0.538053 +0.527926 0.537941 +0.530750 0.537941 +0.527930 0.537848 +0.530747 0.537848 +0.527934 0.537770 +0.530742 0.537770 +0.527939 0.537706 +0.530737 0.537706 +0.527945 0.537665 +0.530732 0.537665 +0.596501 0.537648 +0.594561 0.537648 +0.595635 0.538314 +0.597593 0.538314 +0.595610 0.538179 +0.597568 0.538179 +0.595543 0.538053 +0.597499 0.538053 +0.595441 0.537941 +0.597395 0.537941 +0.595314 0.537848 +0.597267 0.537848 +0.595163 0.537770 +0.597113 0.537770 +0.594982 0.537706 +0.596929 0.537706 +0.594777 0.537665 +0.596721 0.537665 +0.634698 0.537648 +0.633678 0.537648 +0.634811 0.538314 +0.635827 0.538314 +0.634791 0.538194 +0.635806 0.538194 +0.634729 0.538072 +0.635745 0.538072 +0.634623 0.537954 +0.635639 0.537954 +0.634475 0.537848 +0.635491 0.537848 +0.634293 0.537761 +0.635311 0.537761 +0.634091 0.537698 +0.635109 0.537698 +0.633882 0.537661 +0.634901 0.537661 +0.655133 0.537648 +0.654564 0.537648 +0.655511 0.538314 +0.656075 0.538314 +0.655494 0.538194 +0.656058 0.538194 +0.655443 0.538072 +0.656006 0.538072 +0.655354 0.537954 +0.655918 0.537954 +0.655230 0.537848 +0.655795 0.537848 +0.655079 0.537761 +0.655645 0.537761 +0.654910 0.537698 +0.655477 0.537698 +0.654734 0.537661 +0.655303 0.537661 +0.652610 0.539422 +0.649926 0.541356 +0.649318 0.541356 +0.652021 0.539422 +0.723624 0.542129 +0.719597 0.542080 +0.719598 0.542056 +0.719666 0.540114 +0.723722 0.540162 +0.723626 0.542105 +0.631710 0.539422 +0.628589 0.541356 +0.627539 0.541356 +0.630674 0.539422 +0.612934 0.539422 +0.609780 0.541356 +0.608315 0.541356 +0.611462 0.539422 +0.593683 0.539422 +0.590843 0.541356 +0.588985 0.541356 +0.591781 0.539422 +0.560377 0.539422 +0.558770 0.541356 +0.556421 0.541356 +0.557918 0.539422 +0.530656 0.539422 +0.530588 0.541356 +0.528089 0.541356 +0.528021 0.539422 +0.500759 0.539422 +0.502255 0.541356 +0.499907 0.541356 +0.498300 0.539422 +0.466895 0.539422 +0.469692 0.541356 +0.467834 0.541356 +0.464994 0.539422 +0.447215 0.539422 +0.450361 0.541356 +0.448897 0.541356 +0.445742 0.539422 +0.428003 0.539422 +0.431138 0.541356 +0.430088 0.541356 +0.426967 0.539422 +0.406655 0.539422 +0.409359 0.541356 +0.408750 0.541356 +0.406066 0.539422 +0.335230 0.540159 +0.338734 0.540117 +0.338808 0.542067 +0.339079 0.542059 +0.339079 0.542080 +0.335052 0.542129 +0.335051 0.542107 +0.335320 0.542109 +0.270396 0.540854 +0.271092 0.540854 +0.269039 0.542853 +0.268337 0.542853 +0.248304 0.540854 +0.246279 0.542853 +0.245251 0.542853 +0.247270 0.540854 +0.215026 0.540854 +0.213596 0.542853 +0.212172 0.542853 +0.213568 0.540854 +0.170217 0.540854 +0.171907 0.540854 +0.171879 0.542853 +0.170245 0.542853 +0.170217 0.540854 +0.843650 0.540854 +0.845109 0.540854 +0.846505 0.542853 +0.845081 0.542853 +0.811407 0.540854 +0.813425 0.542853 +0.812398 0.542853 +0.810373 0.540854 +0.788280 0.540854 +0.790340 0.542853 +0.789638 0.542853 +0.787584 0.540854 + + + + + + + + + + + +

16 0 16 0 1 0 1 2 1 4 3 4 2 4 2 3 5 3 6 6 6 2 7 2 4 8 4 6 9 6 5 10 5 2 11 2 8 12 8 5 13 5 6 14 6 8 15 8 7 16 7 5 17 5 10 18 10 7 19 7 8 20 8 10 21 10 9 22 9 7 23 7 11 24 11 9 25 9 10 26 10 13 27 13 9 28 9 11 29 11 13 30 13 12 31 12 9 32 9 15 33 15 12 34 12 13 35 13 15 36 15 14 37 14 12 38 12 17 39 17 14 40 14 15 41 15 17 42 17 16 43 16 14 44 14 0 45 0 16 46 16 17 47 17 50 48 50 18 49 18 19 50 19 23 51 23 20 52 20 21 53 21 23 54 23 22 55 22 20 56 20 25 57 25 22 58 22 23 59 23 25 60 25 24 61 24 22 62 22 27 63 27 24 64 24 25 65 25 27 66 27 26 67 26 24 68 24 29 69 29 26 70 26 27 71 27 29 72 29 28 73 28 26 74 26 31 75 31 28 76 28 29 77 29 31 78 31 30 79 30 28 80 28 33 81 33 30 82 30 31 83 31 33 84 33 32 85 32 30 86 30 35 87 35 32 88 32 33 89 33 35 90 35 34 91 34 32 92 32 37 93 37 34 94 34 35 95 35 37 96 37 36 97 36 34 98 34 39 99 39 36 100 36 37 101 37 39 102 39 38 103 38 36 104 36 41 105 41 38 106 38 39 107 39 41 108 41 40 109 40 38 110 38 43 111 43 40 112 40 41 113 41 43 114 43 42 115 42 40 116 40 45 117 45 42 118 42 43 119 43 45 120 45 44 121 44 42 122 42 47 123 47 44 124 44 45 125 45 47 126 47 46 127 46 44 128 44 49 129 49 46 130 46 47 131 47 49 132 49 48 133 48 46 134 46 51 135 51 48 136 48 49 137 49 51 138 51 50 139 50 48 140 48 18 141 18 50 142 50 51 143 51 85 144 85 52 145 52 55 146 55 85 147 85 53 148 53 54 149 54 85 150 85 55 151 55 53 152 53 59 153 59 56 154 56 57 155 57 59 156 59 58 157 58 56 158 56 61 159 61 58 160 58 59 161 59 61 162 61 60 163 60 58 164 58 63 165 63 60 166 60 61 167 61 63 168 63 62 169 62 60 170 60 65 171 65 62 172 62 63 173 63 65 174 65 64 175 64 62 176 62 67 177 67 64 178 64 65 179 65 67 180 67 66 181 66 64 182 64 69 183 69 66 184 66 67 185 67 69 186 69 68 187 68 66 188 66 71 189 71 68 190 68 69 191 69 71 192 71 70 193 70 68 194 68 73 195 73 70 196 70 71 197 71 73 198 73 72 199 72 70 200 70 75 201 75 72 202 72 73 203 73 75 204 75 74 205 74 72 206 72 77 207 77 74 208 74 75 209 75 77 210 77 76 211 76 74 212 74 79 213 79 76 214 76 77 215 77 79 216 79 78 217 78 76 218 76 81 219 81 78 220 78 79 221 79 81 222 81 80 223 80 78 224 78 83 225 83 80 226 80 81 227 81 83 228 83 82 229 82 80 230 80 52 231 52 82 232 82 83 233 83 52 234 52 84 235 84 82 236 82 52 237 52 85 238 85 84 239 84 118 240 118 91 241 91 86 242 86 90 243 90 87 244 87 88 245 88 90 246 90 89 247 89 87 248 87 86 249 86 89 250 89 90 251 90 86 252 86 91 253 91 89 254 89 94 255 94 92 256 92 93 257 93 95 258 95 92 259 92 94 260 94 98 261 98 92 262 92 95 263 95 98 264 98 96 265 96 92 266 92 98 267 98 97 268 97 96 269 96 99 270 99 97 271 97 98 272 98 101 273 101 97 274 97 99 275 99 101 276 101 100 277 100 97 278 97 103 279 103 100 280 100 101 281 101 103 282 103 102 283 102 100 284 100 105 285 105 102 286 102 103 287 103 105 288 105 104 289 104 102 290 102 107 291 107 104 292 104 105 293 105 107 294 107 106 295 106 104 296 104 109 297 109 106 298 106 107 299 107 109 300 109 108 301 108 106 302 106 111 303 111 108 304 108 109 305 109 111 306 111 110 307 110 108 308 108 113 309 113 110 310 110 111 311 111 113 312 113 112 313 112 110 314 110 116 315 116 112 316 112 113 317 113 116 318 116 114 319 114 112 320 112 116 321 116 115 322 115 114 323 114 117 324 117 115 325 115 116 326 116 119 327 119 115 328 115 117 329 117 119 330 119 118 331 118 115 332 115 91 333 91 118 334 118 119 335 119 138 336 138 120 337 120 139 338 139 140 339 140 120 340 120 121 341 121 139 342 139 120 343 120 140 344 140 124 345 124 122 346 122 123 347 123 124 348 124 141 349 141 122 350 122 125 351 125 141 352 141 124 353 124 125 354 125 142 355 142 141 356 141 126 357 126 142 358 142 125 359 125 126 360 126 143 361 143 142 362 142 127 363 127 143 364 143 126 365 126 127 366 127 144 367 144 143 368 143 128 369 128 144 370 144 127 371 127 128 372 128 145 373 145 144 374 144 129 375 129 145 376 145 128 377 128 129 378 129 146 379 146 145 380 145 130 381 130 146 382 146 129 383 129 130 384 130 147 385 147 146 386 146 131 387 131 147 388 147 130 389 130 131 390 131 148 391 148 147 392 147 132 393 132 148 394 148 131 395 131 132 396 132 149 397 149 148 398 148 133 399 133 149 400 149 132 401 132 133 402 133 150 403 150 149 404 149 134 405 134 150 406 150 133 407 133 134 408 134 151 409 151 150 410 150 135 411 135 151 412 151 134 413 134 135 414 135 152 415 152 151 416 151 135 417 135 153 418 153 152 419 152 136 420 136 153 421 153 135 422 135 137 423 137 153 424 153 136 425 136 137 426 137 138 427 138 153 428 153 120 429 120 138 430 138 137 431 137 185 432 185 158 433 158 154 434 154 157 435 157 155 436 155 156 437 156 159 438 159 155 439 155 157 440 157 159 441 159 158 442 158 155 443 155 154 444 154 158 445 158 159 446 159 164 447 164 160 448 160 161 449 161 164 450 164 162 451 162 160 452 160 164 453 164 163 454 163 162 455 162 165 456 165 163 457 163 164 458 164 167 459 167 163 460 163 165 461 165 167 462 167 166 463 166 163 464 163 169 465 169 166 466 166 167 467 167 169 468 169 168 469 168 166 470 166 171 471 171 168 472 168 169 473 169 171 474 171 170 475 170 168 476 168 173 477 173 170 478 170 171 479 171 173 480 173 172 481 172 170 482 170 175 483 175 172 484 172 173 485 173 175 486 175 174 487 174 172 488 172 177 489 177 174 490 174 175 491 175 177 492 177 176 493 176 174 494 174 179 495 179 176 496 176 177 497 177 179 498 179 178 499 178 176 500 176 182 501 182 178 502 178 179 503 179 182 504 182 180 505 180 178 506 178 182 507 182 181 508 181 180 509 180 183 510 183 181 511 181 182 512 182 186 513 186 181 514 181 183 515 183 186 516 186 184 517 184 181 518 181 186 519 186 185 520 185 184 521 184 187 522 187 185 523 185 186 524 186 158 525 158 185 526 185 187 527 187 206 528 206 188 529 188 207 530 207 208 531 208 188 532 188 189 533 189 207 534 207 188 535 188 208 536 208 192 537 192 190 538 190 191 539 191 192 540 192 209 541 209 190 542 190 193 543 193 209 544 209 192 545 192 193 546 193 210 547 210 209 548 209 194 549 194 210 550 210 193 551 193 194 552 194 211 553 211 210 554 210 195 555 195 211 556 211 194 557 194 195 558 195 212 559 212 211 560 211 196 561 196 212 562 212 195 563 195 196 564 196 213 565 213 212 566 212 197 567 197 213 568 213 196 569 196 197 570 197 214 571 214 213 572 213 198 573 198 214 574 214 197 575 197 198 576 198 215 577 215 214 578 214 199 579 199 215 580 215 198 581 198 199 582 199 216 583 216 215 584 215 200 585 200 216 586 216 199 587 199 200 588 200 217 589 217 216 590 216 201 591 201 217 592 217 200 593 200 201 594 201 218 595 218 217 596 217 202 597 202 218 598 218 201 599 201 202 600 202 219 601 219 218 602 218 203 603 203 219 604 219 202 605 202 203 606 203 220 607 220 219 608 219 203 609 203 221 610 221 220 611 220 204 612 204 221 613 221 203 614 203 205 615 205 221 616 221 204 617 204 205 618 205 206 619 206 221 620 221 188 621 188 206 622 206 205 623 205 254 624 254 222 625 222 223 626 223 228 627 228 224 628 224 225 629 225 228 630 228 226 631 226 224 632 224 228 633 228 227 634 227 226 635 226 230 636 230 227 637 227 228 638 228 230 639 230 229 640 229 227 641 227 231 642 231 229 643 229 230 644 230 233 645 233 229 646 229 231 647 231 233 648 233 232 649 232 229 650 229 235 651 235 232 652 232 233 653 233 235 654 235 234 655 234 232 656 232 237 657 237 234 658 234 235 659 235 237 660 237 236 661 236 234 662 234 239 663 239 236 664 236 237 665 237 239 666 239 238 667 238 236 668 236 241 669 241 238 670 238 239 671 239 241 672 241 240 673 240 238 674 238 244 675 244 240 676 240 241 677 241 244 678 244 242 679 242 240 680 240 244 681 244 243 682 243 242 683 242 245 684 245 243 685 243 244 686 244 247 687 247 243 688 243 245 689 245 247 690 247 246 691 246 243 692 243 249 693 249 246 694 246 247 695 247 249 696 249 248 697 248 246 698 246 251 699 251 248 700 248 249 701 249 251 702 251 250 703 250 248 704 248 253 705 253 250 706 250 251 707 251 253 708 253 252 709 252 250 710 250 255 711 255 252 712 252 253 713 253 255 714 255 254 715 254 252 716 252 222 717 222 254 718 254 255 719 255 271 720 271 256 721 256 257 722 257 262 723 262 258 724 258 259 725 259 262 726 262 260 727 260 258 728 258 262 729 262 261 730 261 260 731 260 263 732 263 261 733 261 262 734 262 266 735 266 261 736 261 263 737 263 266 738 266 264 739 264 261 740 261 266 741 266 265 742 265 264 743 264 267 744 267 265 745 265 266 746 266 269 747 269 265 748 265 267 749 267 269 750 269 268 751 268 265 752 265 272 753 272 268 754 268 269 755 269 272 756 272 270 757 270 268 758 268 272 759 272 271 760 271 270 761 270 273 762 273 271 763 271 272 764 272 256 765 256 271 766 271 273 767 273 307 768 307 274 769 274 282 770 282 278 771 278 275 772 275 276 773 276 278 774 278 277 775 277 275 776 275 281 777 281 277 778 277 278 779 278 281 780 281 279 781 279 277 782 277 281 783 281 280 784 280 279 785 279 283 786 283 280 787 280 281 788 281 283 789 283 282 790 282 280 791 280 307 792 307 282 793 282 283 794 283 286 795 286 284 796 284 285 797 285 287 798 287 284 799 284 286 800 286 290 801 290 284 802 284 287 803 287 290 804 290 288 805 288 284 806 284 290 807 290 289 808 289 288 809 288 291 810 291 289 811 289 290 812 290 294 813 294 289 814 289 291 815 291 294 816 294 292 817 292 289 818 289 294 819 294 293 820 293 292 821 292 295 822 295 293 823 293 294 824 294 298 825 298 293 826 293 295 827 295 298 828 298 296 829 296 293 830 293 298 831 298 297 832 297 296 833 296 299 834 299 297 835 297 298 836 298 301 837 301 297 838 297 299 839 299 301 840 301 300 841 300 297 842 297 303 843 303 300 844 300 301 845 301 303 846 303 302 847 302 300 848 300 305 849 305 302 850 302 303 851 303 305 852 305 304 853 304 302 854 302 274 855 274 304 856 304 305 857 305 274 858 274 306 859 306 304 860 304 274 861 274 307 862 307 306 863 306 340 864 340 308 865 308 309 866 309 313 867 313 310 868 310 311 869 311 313 870 313 312 871 312 310 872 310 315 873 315 312 874 312 313 875 313 315 876 315 314 877 314 312 878 312 317 879 317 314 880 314 315 881 315 317 882 317 316 883 316 314 884 314 319 885 319 316 886 316 317 887 317 319 888 319 318 889 318 316 890 316 321 891 321 318 892 318 319 893 319 321 894 321 320 895 320 318 896 318 323 897 323 320 898 320 321 899 321 323 900 323 322 901 322 320 902 320 325 903 325 322 904 322 323 905 323 325 906 325 324 907 324 322 908 322 327 909 327 324 910 324 325 911 325 327 912 327 326 913 326 324 914 324 329 915 329 326 916 326 327 917 327 329 918 329 328 919 328 326 920 326 331 921 331 328 922 328 329 923 329 331 924 331 330 925 330 328 926 328 333 927 333 330 928 330 331 929 331 333 930 333 332 931 332 330 932 330 335 933 335 332 934 332 333 935 333 335 936 335 334 937 334 332 938 332 337 939 337 334 940 334 335 941 335 337 942 337 336 943 336 334 944 334 339 945 339 336 946 336 337 947 337 339 948 339 338 949 338 336 950 336 341 951 341 338 952 338 339 953 339 341 954 341 340 955 340 338 956 338 308 957 308 340 958 340 341 959 341 373 960 373 342 961 342 343 962 343 346 963 346 344 964 344 345 965 345 374 966 374 344 967 344 346 968 346 350 969 350 347 970 347 348 971 348 350 972 350 349 973 349 347 974 347 352 975 352 349 976 349 350 977 350 352 978 352 351 979 351 349 980 349 355 981 355 351 982 351 352 983 352 355 984 355 353 985 353 351 986 351 355 987 355 354 988 354 353 989 353 356 990 356 354 991 354 355 992 355 358 993 358 354 994 354 356 995 356 358 996 358 357 997 357 354 998 354 360 999 360 357 1000 357 358 1001 358 360 1002 360 359 1003 359 357 1004 357 362 1005 362 359 1006 359 360 1007 360 362 1008 362 361 1009 361 359 1010 359 365 1011 365 361 1012 361 362 1013 362 365 1014 365 363 1015 363 361 1016 361 365 1017 365 364 1018 364 363 1019 363 366 1020 366 364 1021 364 365 1022 365 370 1023 370 364 1024 364 366 1025 366 370 1026 370 367 1027 367 364 1028 364 370 1029 370 368 1030 368 367 1031 367 370 1032 370 369 1033 369 368 1034 368 372 1035 372 369 1036 369 370 1037 370 372 1038 372 371 1039 371 369 1040 369 379 1041 379 371 1042 371 372 1043 372 379 1044 379 373 1045 373 371 1046 371 376 1047 376 344 1048 344 374 1049 374 376 1050 376 375 1051 375 344 1052 344 378 1053 378 375 1054 375 376 1055 376 378 1056 378 377 1057 377 375 1058 375 342 1059 342 377 1060 377 378 1061 378 342 1062 342 379 1063 379 377 1064 377 342 1065 342 373 1066 373 379 1067 379 412 1068 412 380 1069 380 381 1070 381 385 1071 385 382 1072 382 383 1073 383 385 1074 385 384 1075 384 382 1076 382 387 1077 387 384 1078 384 385 1079 385 387 1080 387 386 1081 386 384 1082 384 389 1083 389 386 1084 386 387 1085 387 389 1086 389 388 1087 388 386 1088 386 391 1089 391 388 1090 388 389 1091 389 391 1092 391 390 1093 390 388 1094 388 394 1095 394 390 1096 390 391 1097 391 394 1098 394 392 1099 392 390 1100 390 394 1101 394 393 1102 393 392 1103 392 395 1104 395 393 1105 393 394 1106 394 397 1107 397 393 1108 393 395 1109 395 397 1110 397 396 1111 396 393 1112 393 399 1113 399 396 1114 396 397 1115 397 399 1116 399 398 1117 398 396 1118 396 401 1119 401 398 1120 398 399 1121 399 401 1122 401 400 1123 400 398 1124 398 403 1125 403 400 1126 400 401 1127 401 403 1128 403 402 1129 402 400 1130 400 405 1131 405 402 1132 402 403 1133 403 405 1134 405 404 1135 404 402 1136 402 407 1137 407 404 1138 404 405 1139 405 407 1140 407 406 1141 406 404 1142 404 409 1143 409 406 1144 406 407 1145 407 409 1146 409 408 1147 408 406 1148 406 411 1149 411 408 1150 408 409 1151 409 411 1152 411 410 1153 410 408 1154 408 413 1155 413 410 1156 410 411 1157 411 413 1158 413 412 1159 412 410 1160 410 380 1161 380 412 1162 412 413 1163 413 446 1164 446 414 1165 414 415 1166 415 419 1167 419 416 1168 416 417 1169 417 419 1170 419 418 1171 418 416 1172 416 422 1173 422 418 1174 418 419 1175 419 422 1176 422 420 1177 420 418 1178 418 422 1179 422 421 1180 421 420 1181 420 424 1182 424 421 1183 421 422 1184 422 424 1185 424 423 1186 423 421 1187 421 426 1188 426 423 1189 423 424 1190 424 426 1191 426 425 1192 425 423 1193 423 427 1194 427 425 1195 425 426 1196 426 429 1197 429 425 1198 425 427 1199 427 429 1200 429 428 1201 428 425 1202 425 431 1203 431 428 1204 428 429 1205 429 431 1206 431 430 1207 430 428 1208 428 433 1209 433 430 1210 430 431 1211 431 433 1212 433 432 1213 432 430 1214 430 435 1215 435 432 1216 432 433 1217 433 435 1218 435 434 1219 434 432 1220 432 438 1221 438 434 1222 434 435 1223 435 438 1224 438 436 1225 436 434 1226 434 438 1227 438 437 1228 437 436 1229 436 439 1230 439 437 1231 437 438 1232 438 441 1233 441 437 1234 437 439 1235 439 441 1236 441 440 1237 440 437 1238 437 443 1239 443 440 1240 440 441 1241 441 443 1242 443 442 1243 442 440 1244 440 445 1245 445 442 1246 442 443 1247 443 445 1248 445 444 1249 444 442 1250 442 447 1251 447 444 1252 444 445 1253 445 447 1254 447 446 1255 446 444 1256 444 414 1257 414 446 1258 446 447 1259 447 467 1260 467 448 1261 448 449 1262 449 452 1263 452 450 1264 450 451 1265 451 468 1266 468 450 1267 450 452 1268 452 457 1269 457 453 1270 453 454 1271 454 457 1272 457 455 1273 455 453 1274 453 457 1275 457 456 1276 456 455 1277 455 458 1278 458 456 1279 456 457 1280 457 460 1281 460 456 1282 456 458 1283 458 460 1284 460 459 1285 459 456 1286 456 464 1287 464 459 1288 459 460 1289 460 464 1290 464 461 1291 461 459 1292 459 464 1293 464 462 1294 462 461 1295 461 464 1296 464 463 1297 463 462 1298 462 466 1299 466 463 1300 463 464 1301 464 466 1302 466 465 1303 465 463 1304 463 485 1305 485 465 1306 465 466 1307 466 485 1308 485 467 1309 467 465 1310 465 470 1311 470 450 1312 450 468 1313 468 470 1314 470 469 1315 469 450 1316 450 472 1317 472 469 1318 469 470 1319 470 472 1320 472 471 1321 471 469 1322 469 474 1323 474 471 1324 471 472 1325 472 474 1326 474 473 1327 473 471 1328 471 476 1329 476 473 1330 473 474 1331 474 476 1332 476 475 1333 475 473 1334 473 479 1335 479 475 1336 475 476 1337 476 479 1338 479 477 1339 477 475 1340 475 479 1341 479 478 1342 478 477 1343 477 480 1344 480 478 1345 478 479 1346 479 482 1347 482 478 1348 478 480 1349 480 482 1350 482 481 1351 481 478 1352 478 484 1353 484 481 1354 481 482 1355 482 484 1356 484 483 1357 483 481 1358 481 448 1359 448 483 1360 483 484 1361 484 448 1362 448 485 1363 485 483 1364 483 448 1365 448 467 1366 467 485 1367 485 505 1368 505 486 1369 486 498 1370 498 489 1371 489 487 1372 487 488 1373 488 490 1374 490 487 1375 487 489 1376 489 492 1377 492 487 1378 487 490 1379 490 492 1380 492 491 1381 491 487 1382 487 494 1383 494 491 1384 491 492 1385 492 494 1386 494 493 1387 493 491 1388 491 496 1389 496 493 1390 493 494 1391 494 496 1392 496 495 1393 495 493 1394 493 499 1395 499 495 1396 495 496 1397 496 499 1398 499 497 1399 497 495 1400 495 499 1401 499 498 1402 498 497 1403 497 505 1404 505 498 1405 498 499 1406 499 502 1407 502 500 1408 500 501 1409 501 486 1410 486 500 1411 500 502 1412 502 500 1413 500 503 1414 503 504 1415 504 486 1416 486 503 1417 503 500 1418 500 486 1419 486 505 1420 505 503 1421 503 535 1422 535 536 1423 536 506 1424 506 536 1425 536 507 1426 507 506 1427 506 537 1428 537 507 1429 507 536 1430 536 537 1431 537 508 1432 508 507 1433 507 538 1434 538 508 1435 508 537 1436 537 538 1437 538 509 1438 509 508 1439 508 539 1440 539 509 1441 509 538 1442 538 539 1443 539 510 1444 510 509 1445 509 510 1446 510 511 1447 511 512 1448 512 539 1449 539 511 1450 511 510 1451 510 540 1452 540 511 1453 511 539 1454 539 540 1455 540 513 1456 513 511 1457 511 541 1458 541 513 1459 513 540 1460 540 541 1461 541 514 1462 514 513 1463 513 542 1464 542 514 1465 514 541 1466 541 542 1467 542 515 1468 515 514 1469 514 543 1470 543 515 1471 515 542 1472 542 543 1473 543 516 1474 516 515 1475 515 543 1476 543 517 1477 517 516 1478 516 543 1479 543 518 1480 518 517 1481 517 544 1482 544 518 1483 518 543 1484 543 544 1485 544 519 1486 519 518 1487 518 545 1488 545 519 1489 519 544 1490 544 545 1491 545 520 1492 520 519 1493 519 546 1494 546 520 1495 520 545 1496 545 546 1497 546 521 1498 521 520 1499 520 547 1500 547 521 1501 521 546 1502 546 547 1503 547 522 1504 522 521 1505 521 547 1506 547 523 1507 523 522 1508 522 548 1509 548 523 1510 523 547 1511 547 549 1512 549 523 1513 523 548 1514 548 549 1515 549 524 1516 524 523 1517 523 549 1518 549 525 1519 525 524 1520 524 549 1521 549 526 1522 526 525 1523 525 550 1524 550 526 1525 526 549 1526 549 550 1527 550 527 1528 527 526 1529 526 551 1530 551 527 1531 527 550 1532 550 551 1533 551 528 1534 528 527 1535 527 552 1536 552 528 1537 528 551 1538 551 552 1539 552 529 1540 529 528 1541 528 553 1542 553 529 1543 529 552 1544 552 553 1545 553 530 1546 530 529 1547 529 553 1548 553 531 1549 531 530 1550 530 553 1551 553 532 1552 532 531 1553 531 553 1554 553 533 1555 533 532 1556 532 554 1557 554 533 1558 533 553 1559 553 554 1560 554 534 1561 534 533 1562 533 555 1563 555 534 1564 534 554 1565 554 555 1566 555 535 1567 535 534 1568 534 536 1569 536 535 1570 535 555 1571 555 539 1572 539 556 1573 556 540 1574 540 556 1575 556 539 1576 539 538 1577 538 540 1578 540 557 1579 557 541 1580 541 557 1581 557 540 1582 540 556 1583 556 541 1584 541 558 1585 558 542 1586 542 558 1587 558 541 1588 541 557 1589 557 542 1590 542 544 1591 544 543 1592 543 544 1593 544 542 1594 542 558 1595 558 538 1596 538 559 1597 559 556 1598 556 559 1599 559 538 1600 538 537 1601 537 556 1602 556 560 1603 560 557 1604 557 560 1605 560 556 1606 556 559 1607 559 557 1608 557 561 1609 561 558 1610 558 561 1611 561 557 1612 557 560 1613 560 558 1614 558 545 1615 545 544 1616 544 545 1617 545 558 1618 558 561 1619 561 537 1620 537 562 1621 562 559 1622 559 562 1623 562 537 1624 537 536 1625 536 559 1626 559 563 1627 563 560 1628 560 563 1629 563 559 1630 559 562 1631 562 560 1632 560 564 1633 564 561 1634 561 564 1635 564 560 1636 560 563 1637 563 561 1638 561 546 1639 546 545 1640 545 546 1641 546 561 1642 561 564 1643 564 536 1644 536 565 1645 565 562 1646 562 565 1647 565 536 1648 536 555 1649 555 562 1650 562 566 1651 566 563 1652 563 566 1653 566 562 1654 562 565 1655 565 563 1656 563 567 1657 567 564 1658 564 567 1659 567 563 1660 563 566 1661 566 564 1662 564 547 1663 547 546 1664 546 547 1665 547 564 1666 564 567 1667 567 555 1668 555 568 1669 568 565 1670 565 568 1671 568 555 1672 555 554 1673 554 565 1674 565 569 1675 569 566 1676 566 569 1677 569 565 1678 565 568 1679 568 566 1680 566 570 1681 570 567 1682 567 570 1683 570 566 1684 566 569 1685 569 567 1686 567 548 1687 548 547 1688 547 548 1689 548 567 1690 567 570 1691 570 554 1692 554 552 1693 552 568 1694 568 552 1695 552 554 1696 554 553 1697 553 568 1698 568 551 1699 551 569 1700 569 551 1701 551 568 1702 568 552 1703 552 569 1704 569 550 1705 550 570 1706 570 550 1707 550 569 1708 569 551 1709 551 570 1710 570 549 1711 549 548 1712 548 549 1713 549 570 1714 570 550 1715 550 599 1716 599 574 1717 574 600 1718 600 601 1719 601 579 1720 579 602 1721 602 601 1722 601 571 1723 571 579 1724 579 601 1725 601 572 1726 572 571 1727 571 603 1728 603 572 1729 572 601 1730 601 603 1731 603 573 1732 573 572 1733 572 600 1734 600 573 1735 573 603 1736 603 600 1737 600 574 1738 574 573 1739 573 574 1740 574 575 1741 575 576 1742 576 591 1743 591 577 1744 577 578 1745 578 580 1746 580 602 1747 602 579 1748 579 580 1749 580 604 1750 604 602 1751 602 581 1752 581 604 1753 604 580 1754 580 581 1755 581 605 1756 605 604 1757 604 582 1758 582 605 1759 605 581 1760 581 582 1761 582 606 1762 606 605 1763 605 588 1764 588 606 1765 606 582 1766 582 591 1767 591 583 1768 583 577 1769 577 574 1770 574 584 1771 584 575 1772 575 587 1773 587 585 1774 585 586 1775 586 584 1776 584 585 1777 585 587 1778 587 590 1779 590 588 1780 588 589 1781 589 583 1782 583 588 1783 588 590 1784 590 588 1785 588 607 1786 607 606 1787 606 583 1788 583 607 1789 607 588 1790 588 591 1791 591 607 1792 607 583 1793 583 591 1794 591 608 1795 608 607 1796 607 592 1797 592 608 1798 608 591 1799 591 592 1800 592 609 1801 609 608 1802 608 593 1803 593 609 1804 609 592 1805 592 593 1806 593 610 1807 610 609 1808 609 594 1809 594 610 1810 610 593 1811 593 594 1812 594 611 1813 611 610 1814 610 595 1815 595 611 1816 611 594 1817 594 596 1818 596 611 1819 611 595 1820 595 596 1821 596 612 1822 612 611 1823 611 597 1824 597 612 1825 612 596 1826 596 597 1827 597 613 1828 613 612 1829 612 598 1830 598 613 1831 613 597 1832 597 598 1833 598 614 1834 614 613 1835 613 585 1836 585 614 1837 614 598 1838 598 585 1839 585 599 1840 599 614 1841 614 584 1842 584 599 1843 599 585 1844 585 574 1845 574 599 1846 599 584 1847 584 608 1848 608 615 1849 615 607 1850 607 615 1851 615 608 1852 608 609 1853 609 607 1854 607 605 1855 605 606 1856 606 605 1857 605 607 1858 607 615 1859 615 609 1860 609 616 1861 616 615 1862 615 616 1863 616 609 1864 609 610 1865 610 610 1866 610 617 1867 617 616 1868 616 617 1869 617 610 1870 610 611 1871 611 615 1872 615 604 1873 604 605 1874 605 604 1875 604 615 1876 615 616 1877 616 616 1878 616 602 1879 602 604 1880 604 602 1881 602 616 1882 616 617 1883 617 611 1884 611 618 1885 618 617 1886 617 618 1887 618 611 1888 611 612 1889 612 612 1890 612 619 1891 619 618 1892 618 619 1893 619 612 1894 612 613 1895 613 617 1896 617 601 1897 601 602 1898 602 601 1899 601 617 1900 617 618 1901 618 618 1902 618 603 1903 603 601 1904 601 603 1905 603 618 1906 618 619 1907 619 613 1908 613 599 1909 599 619 1910 619 599 1911 599 613 1912 613 614 1913 614 619 1914 619 600 1915 600 603 1916 603 600 1917 600 619 1918 619 599 1919 599 648 1920 648 623 1921 623 649 1922 649 650 1923 650 624 1924 624 651 1925 651 650 1926 650 620 1927 620 624 1928 624 650 1929 650 621 1930 621 620 1931 620 652 1932 652 621 1933 621 650 1934 650 652 1935 652 622 1936 622 621 1937 621 649 1938 649 622 1939 622 652 1940 652 649 1941 649 623 1942 623 622 1943 622 625 1944 625 651 1945 651 624 1946 624 625 1947 625 653 1948 653 651 1949 651 626 1950 626 653 1951 653 625 1952 625 626 1953 626 654 1954 654 653 1955 653 627 1956 627 654 1957 654 626 1958 626 627 1959 627 655 1960 655 654 1961 654 637 1962 637 655 1963 655 627 1964 627 623 1965 623 628 1966 628 629 1967 629 623 1968 623 630 1969 630 628 1970 628 633 1971 633 631 1972 631 632 1973 632 630 1974 630 631 1975 631 633 1976 633 640 1977 640 634 1978 634 635 1979 635 640 1980 640 636 1981 636 634 1982 634 639 1983 639 637 1984 637 638 1985 638 636 1986 636 637 1987 637 639 1988 639 637 1989 637 656 1990 656 655 1991 655 636 1992 636 656 1993 656 637 1994 637 640 1995 640 656 1996 656 636 1997 636 640 1998 640 657 1999 657 656 2000 656 641 2001 641 657 2002 657 640 2003 640 641 2004 641 658 2005 658 657 2006 657 642 2007 642 658 2008 658 641 2009 641 642 2010 642 659 2011 659 658 2012 658 643 2013 643 659 2014 659 642 2015 642 643 2016 643 660 2017 660 659 2018 659 644 2019 644 660 2020 660 643 2021 643 645 2022 645 660 2023 660 644 2024 644 645 2025 645 661 2026 661 660 2027 660 646 2028 646 661 2029 661 645 2030 645 646 2031 646 662 2032 662 661 2033 661 647 2034 647 662 2035 662 646 2036 646 647 2037 647 663 2038 663 662 2039 662 631 2040 631 663 2041 663 647 2042 647 631 2043 631 648 2044 648 663 2045 663 630 2046 630 648 2047 648 631 2048 631 623 2049 623 648 2050 648 630 2051 630 655 2052 655 664 2053 664 654 2054 654 664 2055 664 655 2056 655 656 2057 656 654 2058 654 665 2059 665 653 2060 653 665 2061 665 654 2062 654 664 2063 664 653 2064 653 666 2065 666 651 2066 651 666 2067 666 653 2068 653 665 2069 665 656 2070 656 658 2071 658 664 2072 664 658 2073 658 656 2074 656 657 2075 657 664 2076 664 659 2077 659 665 2078 665 659 2079 659 664 2080 664 658 2081 658 665 2082 665 660 2083 660 666 2084 666 660 2085 660 665 2086 665 659 2087 659 651 2088 651 667 2089 667 650 2090 650 667 2091 667 651 2092 651 666 2093 666 650 2094 650 668 2095 668 652 2096 652 668 2097 668 650 2098 650 667 2099 667 652 2100 652 648 2101 648 649 2102 649 648 2103 648 652 2104 652 668 2105 668 666 2106 666 661 2107 661 667 2108 667 661 2109 661 666 2110 666 660 2111 660 667 2112 667 662 2113 662 668 2114 668 662 2115 662 667 2116 667 661 2117 661 668 2118 668 663 2119 663 648 2120 648 663 2121 663 668 2122 668 662 2123 662 700 2124 700 669 2125 669 670 2126 670 701 2127 701 671 2128 671 675 2129 675 702 2130 702 671 2131 671 701 2132 701 702 2133 702 672 2134 672 671 2135 671 703 2136 703 672 2137 672 702 2138 702 703 2139 703 673 2140 673 672 2141 672 704 2142 704 673 2143 673 703 2144 703 704 2145 704 674 2146 674 673 2147 673 675 2148 675 705 2149 705 701 2150 701 676 2151 676 705 2152 705 675 2153 675 677 2154 677 705 2155 705 676 2156 676 677 2157 677 706 2158 706 705 2159 705 678 2160 678 706 2161 706 677 2162 677 678 2163 678 707 2164 707 706 2165 706 669 2166 669 707 2167 707 678 2168 678 674 2169 674 679 2170 679 680 2171 680 704 2172 704 679 2173 679 674 2174 674 708 2175 708 679 2176 679 704 2177 704 708 2178 708 681 2179 681 679 2180 679 709 2181 709 681 2182 681 708 2183 708 709 2184 709 682 2185 682 681 2186 681 710 2187 710 682 2188 682 709 2189 709 710 2190 710 683 2191 683 682 2192 682 711 2193 711 683 2194 683 710 2195 710 711 2196 711 684 2197 684 683 2198 683 711 2199 711 685 2200 685 684 2201 684 711 2202 711 686 2203 686 685 2204 685 711 2205 711 687 2206 687 686 2207 686 712 2208 712 687 2209 687 711 2210 711 712 2211 712 688 2212 688 687 2213 687 713 2214 713 688 2215 688 712 2216 712 713 2217 713 689 2218 689 688 2219 688 714 2220 714 689 2221 689 713 2222 713 714 2223 714 690 2224 690 689 2225 689 715 2226 715 690 2227 690 714 2228 714 715 2229 715 691 2230 691 690 2231 690 715 2232 715 692 2233 692 691 2234 691 716 2235 716 692 2236 692 715 2237 715 716 2238 716 693 2239 693 692 2240 692 717 2241 717 693 2242 693 716 2243 716 717 2244 717 694 2245 694 693 2246 693 694 2247 694 695 2248 695 696 2249 696 717 2250 717 695 2251 695 694 2252 694 718 2253 718 695 2254 695 717 2255 717 718 2256 718 697 2257 697 695 2258 695 719 2259 719 697 2260 697 718 2261 718 719 2262 719 698 2263 698 697 2264 697 720 2265 720 698 2266 698 719 2267 719 720 2268 720 699 2269 699 698 2270 698 707 2271 707 699 2272 699 720 2273 720 707 2274 707 700 2275 700 699 2276 699 669 2277 669 700 2278 700 707 2279 707 711 2280 711 721 2281 721 712 2282 712 721 2283 721 711 2284 711 710 2285 710 710 2286 710 722 2287 722 721 2288 721 722 2289 722 710 2290 710 709 2291 709 709 2292 709 723 2293 723 722 2294 722 723 2295 723 709 2296 709 708 2297 708 708 2298 708 703 2299 703 723 2300 723 703 2301 703 708 2302 708 704 2303 704 712 2304 712 724 2305 724 713 2306 713 724 2307 724 712 2308 712 721 2309 721 721 2310 721 725 2311 725 724 2312 724 725 2313 725 721 2314 721 722 2315 722 713 2316 713 726 2317 726 714 2318 714 726 2319 726 713 2320 713 724 2321 724 724 2322 724 727 2323 727 726 2324 726 727 2325 727 724 2326 724 725 2327 725 722 2328 722 728 2329 728 725 2330 725 728 2331 728 722 2332 722 723 2333 723 723 2334 723 702 2335 702 728 2336 728 702 2337 702 723 2338 723 703 2339 703 725 2340 725 729 2341 729 727 2342 727 729 2343 729 725 2344 725 728 2345 728 728 2346 728 701 2347 701 729 2348 729 701 2349 701 728 2350 728 702 2351 702 714 2352 714 730 2353 730 715 2354 715 730 2355 730 714 2356 714 726 2357 726 726 2358 726 731 2359 731 730 2360 730 731 2361 731 726 2362 726 727 2363 727 715 2364 715 732 2365 732 716 2366 716 732 2367 732 715 2368 715 730 2369 730 730 2370 730 733 2371 733 732 2372 732 733 2373 733 730 2374 730 731 2375 731 727 2376 727 734 2377 734 731 2378 731 734 2379 734 727 2380 727 729 2381 729 729 2382 729 705 2383 705 734 2384 734 705 2385 705 729 2386 729 701 2387 701 731 2388 731 735 2389 735 733 2390 733 735 2391 735 731 2392 731 734 2393 734 734 2394 734 706 2395 706 735 2396 735 706 2397 706 734 2398 734 705 2399 705 716 2400 716 718 2401 718 717 2402 717 718 2403 718 716 2404 716 732 2405 732 732 2406 732 719 2407 719 718 2408 718 719 2409 719 732 2410 732 733 2411 733 733 2412 733 720 2413 720 719 2414 719 720 2415 720 733 2416 733 735 2417 735 735 2418 735 707 2419 707 720 2420 720 707 2421 707 735 2422 735 706 2423 706 768 2424 768 736 2425 736 737 2426 737 741 2427 741 738 2428 738 739 2429 739 741 2430 741 740 2431 740 738 2432 738 744 2433 744 740 2434 740 741 2435 741 744 2436 744 742 2437 742 740 2438 740 744 2439 744 743 2440 743 742 2441 742 746 2442 746 743 2443 743 744 2444 744 746 2445 746 745 2446 745 743 2447 743 747 2448 747 745 2449 745 746 2450 746 749 2451 749 745 2452 745 747 2453 747 749 2454 749 748 2455 748 745 2456 745 752 2457 752 748 2458 748 749 2459 749 752 2460 752 750 2461 750 748 2462 748 752 2463 752 751 2464 751 750 2465 750 753 2466 753 751 2467 751 752 2468 752 756 2469 756 751 2470 751 753 2471 753 756 2472 756 754 2473 754 751 2474 751 756 2475 756 755 2476 755 754 2477 754 757 2478 757 755 2479 755 756 2480 756 759 2481 759 755 2482 755 757 2483 757 759 2484 759 758 2485 758 755 2486 755 762 2487 762 758 2488 758 759 2489 759 762 2490 762 760 2491 760 758 2492 758 762 2493 762 761 2494 761 760 2495 760 763 2496 763 761 2497 761 762 2498 762 766 2499 766 761 2500 761 763 2501 763 766 2502 766 764 2503 764 761 2504 761 766 2505 766 765 2506 765 764 2507 764 767 2508 767 765 2509 765 766 2510 766 769 2511 769 765 2512 765 767 2513 767 769 2514 769 768 2515 768 765 2516 765 736 2517 736 768 2518 768 769 2519 769 802 2520 802 770 2521 770 771 2522 771 775 2523 775 772 2524 772 773 2525 773 775 2526 775 774 2527 774 772 2528 772 777 2529 777 774 2530 774 775 2531 775 777 2532 777 776 2533 776 774 2534 774 779 2535 779 776 2536 776 777 2537 777 779 2538 779 778 2539 778 776 2540 776 781 2541 781 778 2542 778 779 2543 779 781 2544 781 780 2545 780 778 2546 778 784 2547 784 780 2548 780 781 2549 781 784 2550 784 782 2551 782 780 2552 780 784 2553 784 783 2554 783 782 2555 782 785 2556 785 783 2557 783 784 2558 784 788 2559 788 783 2560 783 785 2561 785 788 2562 788 786 2563 786 783 2564 783 788 2565 788 787 2566 787 786 2567 786 789 2568 789 787 2569 787 788 2570 788 791 2571 791 787 2572 787 789 2573 789 791 2574 791 790 2575 790 787 2576 787 793 2577 793 790 2578 790 791 2579 791 793 2580 793 792 2581 792 790 2582 790 796 2583 796 792 2584 792 793 2585 793 796 2586 796 794 2587 794 792 2588 792 796 2589 796 795 2590 795 794 2591 794 797 2592 797 795 2593 795 796 2594 796 799 2595 799 795 2596 795 797 2597 797 799 2598 799 798 2599 798 795 2600 795 801 2601 801 798 2602 798 799 2603 799 801 2604 801 800 2605 800 798 2606 798 803 2607 803 800 2608 800 801 2609 801 803 2610 803 802 2611 802 800 2612 800 770 2613 770 802 2614 802 803 2615 803 810 2616 810 805 2617 805 804 2618 804 807 2619 807 804 2620 804 805 2621 805 807 2622 807 806 2623 806 804 2624 804 809 2625 809 806 2626 806 807 2627 807 809 2628 809 808 2629 808 806 2630 806 811 2631 811 808 2632 808 809 2633 809 811 2634 811 810 2635 810 808 2636 808 805 2637 805 810 2638 810 811 2639 811 819 2640 819 812 2641 812 814 2642 814 814 2643 814 813 2644 813 819 2645 819 816 2646 816 813 2647 813 814 2648 814 816 2649 816 815 2650 815 813 2651 813 818 2652 818 815 2653 815 816 2654 816 818 2655 818 817 2656 817 815 2657 815 812 2658 812 817 2659 817 818 2660 818 812 2661 812 819 2662 819 817 2663 817 827 2664 827 820 2665 820 822 2666 822 822 2667 822 821 2668 821 827 2669 827 824 2670 824 821 2671 821 822 2672 822 824 2673 824 823 2674 823 821 2675 821 826 2676 826 823 2677 823 824 2678 824 826 2679 826 825 2680 825 823 2681 823 820 2682 820 825 2683 825 826 2684 826 820 2685 820 827 2686 827 825 2687 825 835 2688 835 828 2689 828 830 2690 830 830 2691 830 829 2692 829 835 2693 835 832 2694 832 829 2695 829 830 2696 830 832 2697 832 831 2698 831 829 2699 829 834 2700 834 831 2701 831 832 2702 832 834 2703 834 833 2704 833 831 2705 831 828 2706 828 833 2707 833 834 2708 834 828 2709 828 835 2710 835 833 2711 833 842 2712 842 837 2713 837 836 2714 836 839 2715 839 836 2716 836 837 2717 837 839 2718 839 838 2719 838 836 2720 836 841 2721 841 838 2722 838 839 2723 839 841 2724 841 840 2725 840 838 2726 838 843 2727 843 840 2728 840 841 2729 841 843 2730 843 842 2731 842 840 2732 840 837 2733 837 842 2734 842 843 2735 843 850 2736 850 845 2737 845 844 2738 844 847 2739 847 844 2740 844 845 2741 845 847 2742 847 846 2743 846 844 2744 844 849 2745 849 846 2746 846 847 2747 847 849 2748 849 848 2749 848 846 2750 846 851 2751 851 848 2752 848 849 2753 849 851 2754 851 850 2755 850 848 2756 848 845 2757 845 850 2758 850 851 2759 851 854 2760 854 852 2761 852 853 2762 853 852 2763 852 854 2764 854 855 2765 855 858 2766 858 856 2767 856 857 2768 857 856 2769 856 858 2770 858 859 2771 859 862 2772 862 860 2773 860 861 2774 861 860 2775 860 862 2776 862 863 2777 863 871 2778 871 864 2779 864 866 2780 866 866 2781 866 865 2782 865 871 2783 871 868 2784 868 865 2785 865 866 2786 866 868 2787 868 867 2788 867 865 2789 865 870 2790 870 867 2791 867 868 2792 868 870 2793 870 869 2794 869 867 2795 867 864 2796 864 869 2797 869 870 2798 870 864 2799 864 871 2800 871 869 2801 869 879 2802 879 872 2803 872 874 2804 874 874 2805 874 873 2806 873 879 2807 879 876 2808 876 873 2809 873 874 2810 874 876 2811 876 875 2812 875 873 2813 873 878 2814 878 875 2815 875 876 2816 876 878 2817 878 877 2818 877 875 2819 875 872 2820 872 877 2821 877 878 2822 878 872 2823 872 879 2824 879 877 2825 877 890 2826 890 880 2827 880 881 2828 881 884 2829 884 882 2830 882 883 2831 883 885 2832 885 882 2833 882 884 2834 884 886 2835 886 882 2836 882 885 2837 885 887 2838 887 882 2839 882 886 2840 886 888 2841 888 882 2842 882 887 2843 887 889 2844 889 882 2845 882 888 2846 888 891 2847 891 882 2848 882 889 2849 889 891 2850 891 890 2851 890 882 2852 882 892 2853 892 890 2854 890 891 2855 891 893 2856 893 890 2857 890 892 2858 892 894 2859 894 890 2860 890 893 2861 893 895 2862 895 890 2863 890 894 2864 894 896 2865 896 890 2866 890 895 2867 895 897 2868 897 890 2869 890 896 2870 896 898 2871 898 890 2872 890 897 2873 897 899 2874 899 890 2875 890 898 2876 898 880 2877 880 890 2878 890 899 2879 899 910 2880 910 900 2881 900 901 2882 901 904 2883 904 902 2884 902 903 2885 903 905 2886 905 902 2887 902 904 2888 904 906 2889 906 902 2890 902 905 2891 905 907 2892 907 902 2893 902 906 2894 906 908 2895 908 902 2896 902 907 2897 907 909 2898 909 902 2899 902 908 2900 908 911 2901 911 902 2902 902 909 2903 909 911 2904 911 910 2905 910 902 2906 902 912 2907 912 910 2908 910 911 2909 911 913 2910 913 910 2911 910 912 2912 912 914 2913 914 910 2914 910 913 2915 913 915 2916 915 910 2917 910 914 2918 914 916 2919 916 910 2920 910 915 2921 915 917 2922 917 910 2923 910 916 2924 916 918 2925 918 910 2926 910 917 2927 917 919 2928 919 910 2929 910 918 2930 918 900 2931 900 910 2932 910 919 2933 919 961 2934 961 920 2935 920 921 2936 921 924 2937 924 927 2938 927 922 2939 922 924 2940 924 923 2941 923 927 2942 927 957 2943 957 923 2944 923 924 2945 924 957 2946 957 925 2947 925 923 2948 923 927 2949 927 926 2950 926 922 2951 922 928 2952 928 926 2953 926 927 2954 927 929 2955 929 926 2956 926 928 2957 928 930 2958 930 926 2959 926 929 2960 929 931 2961 931 926 2962 926 930 2963 930 932 2964 932 926 2965 926 931 2966 931 933 2967 933 926 2968 926 932 2969 932 934 2970 934 926 2971 926 933 2972 933 935 2973 935 926 2974 926 934 2975 934 936 2976 936 926 2977 926 935 2978 935 960 2979 960 926 2980 926 936 2981 936 957 2982 957 937 2983 937 925 2984 925 957 2985 957 938 2986 938 937 2987 937 957 2988 957 939 2989 939 938 2990 938 957 2991 957 940 2992 940 939 2993 939 957 2994 957 941 2995 941 940 2996 940 957 2997 957 942 2998 942 941 2999 941 957 3000 957 943 3001 943 942 3002 942 957 3003 957 944 3004 944 943 3005 943 957 3006 957 945 3007 945 944 3008 944 950 3009 950 946 3010 946 947 3011 947 950 3012 950 948 3013 948 946 3014 946 950 3015 950 949 3016 949 948 3017 948 955 3018 955 949 3019 949 950 3020 950 955 3021 955 951 3022 951 949 3023 949 955 3024 955 952 3025 952 951 3026 951 955 3027 955 953 3028 953 952 3029 952 955 3030 955 954 3031 954 953 3032 953 945 3033 945 954 3034 954 955 3035 955 957 3036 957 954 3037 954 945 3038 945 957 3039 957 956 3040 956 954 3041 954 926 3042 926 956 3043 956 957 3044 957 926 3045 926 958 3046 958 956 3047 956 926 3048 926 959 3049 959 958 3050 958 960 3051 960 959 3052 959 926 3053 926 962 3054 962 959 3055 959 960 3056 960 962 3057 962 961 3058 961 959 3059 959 963 3060 963 961 3061 961 962 3062 962 964 3063 964 961 3064 961 963 3065 963 965 3066 965 961 3067 961 964 3068 964 966 3069 966 961 3070 961 965 3071 965 967 3072 967 961 3073 961 966 3074 966 920 3075 920 961 3076 961 967 3077 967 970 3078 970 968 3079 968 969 3080 969 968 3081 968 970 3082 970 971 3083 971 974 3084 974 972 3085 972 973 3086 973 972 3087 972 974 3088 974 975 3089 975 978 3090 978 976 3091 976 977 3092 977 976 3093 976 978 3094 978 979 3095 979 982 3096 982 980 3097 980 981 3098 981 980 3099 980 982 3100 982 983 3101 983 986 3102 986 984 3103 984 985 3104 985 984 3105 984 986 3106 986 987 3107 987 990 3108 990 988 3109 988 989 3110 989 988 3111 988 990 3112 990 991 3113 991 1013 3114 1013 992 3115 992 993 3116 993 996 3117 996 994 3118 994 995 3119 995 997 3120 997 994 3121 994 996 3122 996 999 3123 999 994 3124 994 997 3125 997 999 3126 999 998 3127 998 994 3128 994 1001 3129 1001 998 3130 998 999 3131 999 1001 3132 1001 1000 3133 1000 998 3134 998 1002 3135 1002 1000 3136 1000 1001 3137 1001 1004 3138 1004 1000 3139 1000 1002 3140 1002 1004 3141 1004 1003 3142 1003 1000 3143 1000 992 3144 992 1003 3145 1003 1004 3146 1004 1007 3147 1007 1005 3148 1005 1006 3149 1006 1008 3150 1008 1005 3151 1005 1007 3152 1007 1011 3153 1011 1005 3154 1005 1008 3155 1008 1011 3156 1011 1009 3157 1009 1005 3158 1005 1011 3159 1011 1010 3160 1010 1009 3161 1009 1012 3162 1012 1010 3163 1010 1011 3164 1011 1003 3165 1003 1010 3166 1010 1012 3167 1012 1003 3168 1003 1013 3169 1013 1010 3170 1010 992 3171 992 1013 3172 1013 1003 3173 1003 1033 3174 1033 1014 3175 1014 1015 3176 1015 1019 3177 1019 1016 3178 1016 1017 3179 1017 1019 3180 1019 1018 3181 1018 1016 3182 1016 1021 3183 1021 1018 3184 1018 1019 3185 1019 1021 3186 1021 1020 3187 1020 1018 3188 1018 1023 3189 1023 1020 3190 1020 1021 3191 1021 1023 3192 1023 1022 3193 1022 1020 3194 1020 1025 3195 1025 1022 3196 1022 1023 3197 1023 1025 3198 1025 1024 3199 1024 1022 3200 1022 1028 3201 1028 1024 3202 1024 1025 3203 1025 1028 3204 1028 1026 3205 1026 1024 3206 1024 1028 3207 1028 1027 3208 1027 1026 3209 1026 1030 3210 1030 1027 3211 1027 1028 3212 1028 1030 3213 1030 1029 3214 1029 1027 3215 1027 1032 3216 1032 1029 3217 1029 1030 3218 1030 1032 3219 1032 1031 3220 1031 1029 3221 1029 1014 3222 1014 1031 3223 1031 1032 3224 1032 1014 3225 1014 1033 3226 1033 1031 3227 1031 1055 3228 1055 1034 3229 1034 1035 3230 1035 1038 3231 1038 1036 3232 1036 1037 3233 1037 1040 3234 1040 1036 3235 1036 1038 3236 1038 1040 3237 1040 1039 3238 1039 1036 3239 1036 1042 3240 1042 1039 3241 1039 1040 3242 1040 1042 3243 1042 1041 3244 1041 1039 3245 1039 1044 3246 1044 1041 3247 1041 1042 3248 1042 1044 3249 1044 1043 3250 1043 1041 3251 1041 1045 3252 1045 1043 3253 1043 1044 3254 1044 1046 3255 1046 1043 3256 1043 1045 3257 1045 1048 3258 1048 1043 3259 1043 1046 3260 1046 1048 3261 1048 1047 3262 1047 1043 3263 1043 1034 3264 1034 1047 3265 1047 1048 3266 1048 1052 3267 1052 1049 3268 1049 1050 3269 1050 1052 3270 1052 1051 3271 1051 1049 3272 1049 1054 3273 1054 1051 3274 1051 1052 3275 1052 1054 3276 1054 1053 3277 1053 1051 3278 1051 1047 3279 1047 1053 3280 1053 1054 3281 1054 1047 3282 1047 1055 3283 1055 1053 3284 1053 1034 3285 1034 1055 3286 1055 1047 3287 1047 1072 3288 1072 1056 3289 1056 1057 3290 1057 1060 3291 1060 1058 3292 1058 1059 3293 1059 1062 3294 1062 1058 3295 1058 1060 3296 1060 1062 3297 1062 1061 3298 1061 1058 3299 1058 1064 3300 1064 1061 3301 1061 1062 3302 1062 1064 3303 1064 1063 3304 1063 1061 3305 1061 1066 3306 1066 1063 3307 1063 1064 3308 1064 1066 3309 1066 1065 3310 1065 1063 3311 1063 1067 3312 1067 1065 3313 1065 1066 3314 1066 1069 3315 1069 1065 3316 1065 1067 3317 1067 1069 3318 1069 1068 3319 1068 1065 3320 1065 1071 3321 1071 1068 3322 1068 1069 3323 1069 1071 3324 1071 1070 3325 1070 1068 3326 1068 1073 3327 1073 1070 3328 1070 1071 3329 1071 1073 3330 1073 1072 3331 1072 1070 3332 1070 1056 3333 1056 1072 3334 1072 1073 3335 1073 1076 3336 1076 1074 3337 1074 1075 3338 1075 1074 3339 1074 1076 3340 1076 1077 3341 1077 1080 3342 1080 1078 3343 1078 1079 3344 1079 1078 3345 1078 1080 3346 1080 1081 3347 1081 1084 3348 1084 1082 3349 1082 1083 3350 1083 1082 3351 1082 1084 3352 1084 1085 3353 1085 1088 3354 1088 1086 3355 1086 1087 3356 1087 1086 3357 1086 1088 3358 1088 1089 3359 1089 1092 3360 1092 1090 3361 1090 1091 3362 1091 1090 3363 1090 1092 3364 1092 1093 3365 1093 1096 3366 1096 1094 3367 1094 1095 3368 1095 1094 3369 1094 1096 3370 1096 1097 3371 1097 1100 3372 1100 1098 3373 1098 1099 3374 1099 1098 3375 1098 1100 3376 1100 1101 3377 1101 1104 3378 1104 1102 3379 1102 1103 3380 1103 1102 3381 1102 1104 3382 1104 1105 3383 1105 1108 3384 1108 1106 3385 1106 1107 3386 1107 1106 3387 1106 1108 3388 1108 1109 3389 1109 1112 3390 1112 1110 3391 1110 1111 3392 1111 1110 3393 1110 1112 3394 1112 1113 3395 1113 1116 3396 1116 1114 3397 1114 1115 3398 1115 1114 3399 1114 1116 3400 1116 1117 3401 1117 1120 3402 1120 1118 3403 1118 1119 3404 1119 1118 3405 1118 1120 3406 1120 1121 3407 1121 1124 3408 1124 1122 3409 1122 1123 3410 1123 1122 3411 1122 1124 3412 1124 1125 3413 1125 1128 3414 1128 1126 3415 1126 1127 3416 1127 1126 3417 1126 1128 3418 1128 1129 3419 1129 1132 3420 1132 1130 3421 1130 1131 3422 1131 1130 3423 1130 1132 3424 1132 1133 3425 1133 1136 3426 1136 1134 3427 1134 1135 3428 1135 1134 3429 1134 1136 3430 1136 1137 3431 1137 1140 3432 1140 1138 3433 1138 1139 3434 1139 1138 3435 1138 1140 3436 1140 1141 3437 1141 1144 3438 1144 1142 3439 1142 1143 3440 1143 1142 3441 1142 1144 3442 1144 1145 3443 1145 1148 3444 1148 1146 3445 1146 1147 3446 1147 1146 3447 1146 1148 3448 1148 1149 3449 1149 1152 3450 1152 1150 3451 1150 1151 3452 1151 1150 3453 1150 1152 3454 1152 1153 3455 1153 1155 3456 1155 1154 3457 1154 1159 3458 1159 1160 3459 1160 1155 3460 1155 1156 3461 1156 1155 3462 1155 1157 3463 1157 1158 3464 1158 1155 3465 1155 1159 3466 1159 1157 3467 1157 1154 3468 1154 1160 3469 1160 1161 3470 1161 1154 3471 1154 1155 3472 1155 1160 3473 1160 1164 3474 1164 1162 3475 1162 1163 3476 1163 1162 3477 1162 1164 3478 1164 1165 3479 1165 1226 3480 1226 1166 3481 1166 1280 3482 1280 1168 3483 1168 1167 3484 1167 1171 3485 1171 1231 3486 1231 1167 3487 1167 1168 3488 1168 1168 3489 1168 1169 3490 1169 1170 3491 1170 1171 3492 1171 1169 3493 1169 1168 3494 1168 1172 3495 1172 1169 3496 1169 1171 3497 1171 1174 3498 1174 1169 3499 1169 1172 3500 1172 1174 3501 1174 1173 3502 1173 1169 3503 1169 1175 3504 1175 1173 3505 1173 1174 3506 1174 1276 3507 1276 1173 3508 1173 1175 3509 1175 1178 3510 1178 1176 3511 1176 1177 3512 1177 1282 3513 1282 1176 3514 1176 1178 3515 1178 1181 3516 1181 1179 3517 1179 1180 3518 1180 1304 3519 1304 1179 3520 1179 1181 3521 1181 1184 3522 1184 1182 3523 1182 1183 3524 1183 1301 3525 1301 1182 3526 1182 1184 3527 1184 1300 3528 1300 1185 3529 1185 1186 3530 1186 1300 3531 1300 1187 3532 1187 1185 3533 1185 1266 3534 1266 1188 3535 1188 1189 3536 1189 1292 3537 1292 1190 3538 1190 1191 3539 1191 1292 3540 1292 1192 3541 1192 1190 3542 1190 1314 3543 1314 1193 3544 1193 1194 3545 1194 1314 3546 1314 1195 3547 1195 1193 3548 1193 1323 3549 1323 1196 3550 1196 1197 3551 1197 1323 3552 1323 1198 3553 1198 1196 3554 1196 1252 3555 1252 1199 3556 1199 1200 3557 1200 1203 3558 1203 1201 3559 1201 1202 3560 1202 1290 3561 1290 1201 3562 1201 1203 3563 1203 1206 3564 1206 1204 3565 1204 1205 3566 1205 1326 3567 1326 1204 3568 1204 1206 3569 1206 1324 3570 1324 1207 3571 1207 1208 3572 1208 1324 3573 1324 1209 3574 1209 1207 3575 1207 1212 3576 1212 1210 3577 1210 1211 3578 1211 1322 3579 1322 1210 3580 1210 1212 3581 1212 1303 3582 1303 1213 3583 1213 1214 3584 1214 1303 3585 1303 1215 3586 1215 1213 3587 1213 1293 3588 1293 1216 3589 1216 1217 3590 1217 1302 3591 1302 1218 3592 1218 1219 3593 1219 1302 3594 1302 1220 3595 1220 1218 3596 1218 1305 3597 1305 1221 3598 1221 1222 3599 1222 1305 3600 1305 1223 3601 1223 1221 3602 1221 1325 3603 1325 1224 3604 1224 1225 3605 1225 1325 3606 1325 1226 3607 1226 1224 3608 1224 1291 3609 1291 1227 3610 1227 1228 3611 1228 1283 3612 1283 1229 3613 1229 1230 3614 1230 1283 3615 1283 1231 3616 1231 1229 3617 1229 1283 3618 1283 1167 3619 1167 1231 3620 1231 1283 3621 1283 1232 3622 1232 1167 3623 1167 1283 3624 1283 1233 3625 1233 1232 3626 1232 1283 3627 1283 1234 3628 1234 1233 3629 1233 1283 3630 1283 1235 3631 1235 1234 3632 1234 1269 3633 1269 1236 3634 1236 1237 3635 1237 1269 3636 1269 1238 3637 1238 1236 3638 1236 1241 3639 1241 1239 3640 1239 1240 3641 1240 1262 3642 1262 1239 3643 1239 1241 3644 1241 1255 3645 1255 1242 3646 1242 1243 3647 1243 1255 3648 1255 1244 3649 1244 1242 3650 1242 1247 3651 1247 1245 3652 1245 1246 3653 1246 1248 3654 1248 1245 3655 1245 1247 3656 1247 1251 3657 1251 1245 3658 1245 1248 3659 1248 1251 3660 1251 1249 3661 1249 1245 3662 1245 1251 3663 1251 1250 3664 1250 1249 3665 1249 1253 3666 1253 1250 3667 1250 1251 3668 1251 1253 3669 1253 1252 3670 1252 1250 3671 1250 1253 3672 1253 1199 3673 1199 1252 3674 1252 1254 3675 1254 1199 3676 1199 1253 3677 1253 1281 3678 1281 1199 3679 1199 1254 3680 1254 1257 3681 1257 1244 3682 1244 1255 3683 1255 1257 3684 1257 1256 3685 1256 1244 3686 1244 1259 3687 1259 1256 3688 1256 1257 3689 1257 1259 3690 1259 1258 3691 1258 1256 3692 1256 1227 3693 1227 1258 3694 1258 1259 3695 1259 1291 3696 1291 1258 3697 1258 1227 3698 1227 1291 3699 1291 1260 3700 1260 1258 3701 1258 1291 3702 1291 1261 3703 1261 1260 3704 1260 1265 3705 1265 1239 3706 1239 1262 3707 1262 1265 3708 1265 1263 3709 1263 1239 3710 1239 1265 3711 1265 1264 3712 1264 1263 3713 1263 1267 3714 1267 1264 3715 1264 1265 3716 1265 1267 3717 1267 1266 3718 1266 1264 3719 1264 1267 3720 1267 1188 3721 1188 1266 3722 1266 1268 3723 1268 1188 3724 1188 1267 3725 1267 1279 3726 1279 1188 3727 1188 1268 3728 1268 1271 3729 1271 1238 3730 1238 1269 3731 1269 1271 3732 1271 1270 3733 1270 1238 3734 1238 1273 3735 1273 1270 3736 1270 1271 3737 1271 1273 3738 1273 1272 3739 1272 1270 3740 1270 1216 3741 1216 1272 3742 1272 1273 3743 1273 1293 3744 1293 1272 3745 1272 1216 3746 1216 1293 3747 1293 1274 3748 1274 1272 3749 1272 1293 3750 1293 1275 3751 1275 1274 3752 1274 1287 3753 1287 1173 3754 1173 1276 3755 1276 1283 3756 1283 1277 3757 1277 1235 3758 1235 1293 3759 1293 1278 3760 1278 1275 3761 1275 1297 3762 1297 1188 3763 1188 1279 3764 1279 1291 3765 1291 1280 3766 1280 1261 3767 1261 1327 3768 1327 1199 3769 1199 1281 3770 1281 1287 3771 1287 1282 3772 1282 1173 3773 1173 1210 3774 1210 1277 3775 1277 1283 3776 1283 1322 3777 1322 1277 3778 1277 1210 3779 1210 1322 3780 1322 1284 3781 1284 1277 3782 1277 1322 3783 1322 1285 3784 1285 1284 3785 1284 1322 3786 1322 1286 3787 1286 1285 3788 1285 1287 3789 1287 1176 3790 1176 1282 3791 1282 1288 3792 1288 1176 3793 1176 1287 3794 1287 1289 3795 1289 1176 3796 1176 1288 3797 1288 1295 3798 1295 1176 3799 1176 1289 3800 1289 1327 3801 1327 1290 3802 1290 1199 3803 1199 1226 3804 1226 1280 3805 1280 1291 3806 1291 1297 3807 1297 1292 3808 1292 1188 3809 1188 1187 3810 1187 1278 3811 1278 1293 3812 1293 1300 3813 1300 1278 3814 1278 1187 3815 1187 1300 3816 1300 1294 3817 1294 1278 3818 1278 1306 3819 1306 1176 3820 1176 1295 3821 1295 1322 3822 1322 1296 3823 1296 1286 3824 1286 1298 3825 1298 1292 3826 1292 1297 3827 1297 1298 3828 1298 1192 3829 1192 1292 3830 1292 1299 3831 1299 1192 3832 1192 1298 3833 1298 1294 3834 1294 1192 3835 1192 1299 3836 1299 1300 3837 1300 1192 3838 1192 1294 3839 1294 1182 3840 1182 1192 3841 1192 1300 3842 1300 1301 3843 1301 1192 3844 1192 1182 3845 1182 1215 3846 1215 1192 3847 1192 1301 3848 1301 1215 3849 1215 1302 3850 1302 1192 3851 1192 1215 3852 1215 1220 3853 1220 1302 3854 1302 1303 3855 1303 1220 3856 1220 1215 3857 1215 1179 3858 1179 1220 3859 1220 1303 3860 1303 1304 3861 1304 1220 3862 1220 1179 3863 1179 1176 3864 1176 1220 3865 1220 1304 3866 1304 1306 3867 1306 1220 3868 1220 1176 3869 1176 1306 3870 1306 1305 3871 1305 1220 3872 1220 1307 3873 1307 1305 3874 1305 1306 3875 1306 1307 3876 1307 1223 3877 1223 1305 3878 1305 1308 3879 1308 1223 3880 1223 1307 3881 1307 1309 3882 1309 1223 3883 1223 1308 3884 1308 1310 3885 1310 1223 3886 1223 1309 3887 1309 1311 3888 1311 1223 3889 1223 1310 3890 1310 1312 3891 1312 1223 3892 1223 1311 3893 1311 1313 3894 1313 1223 3895 1223 1312 3896 1312 1315 3897 1315 1223 3898 1330 1313 3899 1331 1315 3900 1315 1314 3901 1314 1223 3902 1332 1315 3903 1315 1195 3904 1195 1314 3905 1314 1316 3906 1316 1195 3907 1195 1315 3908 1315 1317 3909 1317 1195 3910 1195 1316 3911 1316 1318 3912 1318 1195 3913 1195 1317 3914 1317 1319 3915 1319 1195 3916 1195 1318 3917 1318 1320 3918 1320 1195 3919 1195 1319 3920 1319 1321 3921 1321 1195 3922 1195 1320 3923 1320 1296 3924 1296 1195 3925 1195 1321 3926 1321 1322 3927 1322 1195 3928 1195 1296 3929 1296 1209 3930 1209 1195 3931 1195 1322 3932 1322 1209 3933 1209 1323 3934 1323 1195 3935 1195 1209 3936 1209 1198 3937 1198 1323 3938 1323 1324 3939 1324 1198 3940 1198 1209 3941 1209 1204 3942 1204 1198 3943 1198 1324 3944 1324 1326 3945 1326 1198 3946 1198 1204 3947 1204 1326 3948 1326 1325 3949 1325 1198 3950 1198 1201 3951 1201 1325 3952 1325 1326 3953 1326 1201 3954 1201 1226 3955 1226 1325 3956 1325 1290 3957 1290 1226 3958 1226 1201 3959 1201 1327 3960 1327 1226 3961 1226 1290 3962 1290 1328 3963 1328 1226 3964 1226 1327 3965 1327 1329 3966 1329 1226 3967 1226 1328 3968 1328 1166 3969 1166 1226 3970 1226 1329 3971 1329 1331 3972 1334 1330 3973 1333 1495 3974 1498 1332 3975 1335 1331 3976 1334 1362 3977 1365 1481 3978 1484 1331 3979 1334 1332 3980 1335 1356 3981 1359 1337 3982 1340 1333 3983 1336 1356 3984 1359 1334 3985 1337 1337 3986 1340 1356 3987 1359 1335 3988 1338 1334 3989 1337 1337 3990 1340 1336 3991 1339 1333 3992 1336 1338 3993 1341 1336 3994 1339 1337 3995 1340 1354 3996 1357 1336 3997 1339 1338 3998 1341 1350 3999 1353 1343 4000 1346 1339 4001 1342 1350 4002 1353 1340 4003 1343 1343 4004 1346 1350 4005 1353 1341 4006 1344 1340 4007 1343 1343 4008 1346 1342 4009 1345 1339 4010 1342 1344 4011 1347 1342 4012 1345 1343 4013 1346 1348 4014 1351 1342 4015 1345 1344 4016 1347 1365 4017 1368 1345 4018 1348 1378 4019 1381 1378 4020 1381 1346 4021 1349 1365 4022 1368 1348 4023 1351 1347 4024 1350 1342 4025 1345 1349 4026 1352 1347 4027 1350 1348 4028 1351 1376 4029 1379 1347 4030 1350 1349 4031 1352 1372 4032 1375 1341 4033 1344 1350 4034 1353 1372 4035 1375 1351 4036 1354 1341 4037 1344 1372 4038 1375 1352 4039 1355 1351 4040 1354 1354 4041 1357 1353 4042 1356 1336 4043 1339 1355 4044 1358 1353 4045 1356 1354 4046 1357 1370 4047 1373 1353 4048 1356 1355 4049 1358 1366 4050 1369 1335 4051 1338 1356 4052 1359 1366 4053 1369 1357 4054 1360 1335 4055 1338 1366 4056 1369 1358 4057 1361 1357 4058 1360 1362 4059 1365 1359 4060 1362 1332 4061 1335 1407 4062 1410 1331 4063 1334 1360 4064 1363 1331 4065 1334 1361 4066 1364 1360 4067 1363 1363 4068 1366 1359 4069 1362 1362 4070 1365 1364 4071 1367 1359 4072 1362 1363 4073 1366 1390 4074 1393 1359 4075 1362 1364 4076 1367 1430 4077 1433 1345 4078 1348 1365 4079 1368 1381 4080 1384 1358 4081 1361 1366 4082 1369 1381 4083 1384 1367 4084 1370 1358 4085 1361 1381 4086 1384 1368 4087 1371 1367 4088 1370 1370 4089 1373 1369 4090 1372 1353 4091 1356 1371 4092 1374 1369 4093 1372 1370 4094 1373 1384 4095 1387 1369 4096 1372 1371 4097 1374 1385 4098 1388 1352 4099 1355 1372 4100 1375 1385 4101 1388 1373 4102 1376 1352 4103 1355 1385 4104 1388 1374 4105 1377 1373 4106 1376 1376 4107 1379 1375 4108 1378 1347 4109 1350 1377 4110 1380 1375 4111 1378 1376 4112 1379 1388 4113 1391 1375 4114 1378 1377 4115 1380 1429 4116 1432 1346 4117 1349 1378 4118 1381 1430 4119 1433 1379 4120 1382 1345 4121 1348 1429 4122 1432 1380 4123 1383 1346 4124 1349 1399 4125 1402 1368 4126 1371 1381 4127 1384 1399 4128 1402 1382 4129 1385 1368 4130 1371 1384 4131 1387 1383 4132 1386 1369 4133 1372 1395 4134 1398 1383 4135 1386 1384 4136 1387 1393 4137 1396 1374 4138 1377 1385 4139 1388 1393 4140 1396 1386 4141 1389 1374 4142 1377 1388 4143 1391 1387 4144 1390 1375 4145 1378 1389 4146 1392 1387 4147 1390 1388 4148 1391 1391 4149 1394 1387 4150 1390 1389 4151 1392 1391 4152 1394 1390 4153 1393 1387 4154 1390 1433 4155 1436 1390 4156 1393 1391 4157 1394 1393 4158 1396 1392 4159 1395 1386 4160 1389 1405 4161 1408 1392 4162 1395 1393 4163 1396 1405 4164 1408 1394 4165 1397 1392 4166 1395 1397 4167 1400 1383 4168 1386 1395 4169 1398 1397 4170 1400 1396 4171 1399 1383 4172 1386 1404 4173 1407 1396 4174 1399 1397 4175 1400 1399 4176 1402 1398 4177 1401 1382 4178 1385 1401 4179 1404 1398 4180 1401 1399 4181 1402 1401 4182 1404 1400 4183 1403 1398 4184 1401 1416 4185 1419 1400 4186 1403 1401 4187 1404 1416 4188 1419 1402 4189 1405 1400 4190 1403 1404 4191 1407 1403 4192 1406 1396 4193 1399 1413 4194 1416 1403 4195 1406 1404 4196 1407 1408 4197 1411 1394 4198 1397 1405 4199 1408 1408 4200 1411 1406 4201 1409 1394 4202 1397 1424 4203 1427 1331 4204 1334 1407 4205 1410 1410 4206 1413 1406 4207 1409 1408 4208 1411 1410 4209 1413 1409 4210 1412 1406 4211 1409 1472 4212 1475 1409 4213 1412 1410 4214 1413 1472 4215 1475 1411 4216 1414 1409 4217 1412 1413 4218 1416 1412 4219 1415 1403 4220 1406 1415 4221 1418 1412 4222 1415 1413 4223 1416 1415 4224 1418 1414 4225 1417 1412 4226 1415 1436 4227 1439 1414 4228 1417 1415 4229 1418 1418 4230 1421 1402 4231 1405 1416 4232 1419 1418 4233 1421 1417 4234 1420 1402 4235 1405 1331 4236 1334 1417 4237 1420 1418 4238 1421 1424 4239 1427 1417 4240 1420 1331 4241 1334 1424 4242 1427 1419 4243 1422 1417 4244 1420 1424 4245 1427 1420 4246 1423 1419 4247 1422 1424 4248 1427 1421 4249 1424 1420 4250 1423 1424 4251 1427 1422 4252 1425 1421 4253 1424 1424 4254 1427 1423 4255 1426 1422 4256 1425 1426 4257 1429 1423 4258 1426 1424 4259 1427 1426 4260 1429 1425 4261 1428 1423 4262 1426 1434 4263 1437 1425 4264 1428 1426 4265 1429 1434 4266 1437 1427 4267 1430 1425 4268 1428 1331 4269 1334 1428 4270 1431 1361 4271 1364 1439 4272 1442 1380 4273 1383 1429 4274 1432 1442 4275 1445 1379 4276 1382 1430 4277 1433 1442 4278 1445 1431 4279 1434 1379 4280 1382 1439 4281 1442 1432 4282 1435 1380 4283 1383 1445 4284 1448 1390 4285 1393 1433 4286 1436 1437 4287 1440 1427 4288 1430 1434 4289 1437 1437 4290 1440 1435 4291 1438 1427 4292 1430 1435 4293 1438 1414 4294 1417 1436 4295 1439 1437 4296 1440 1414 4297 1417 1435 4298 1438 1443 4299 1446 1414 4300 1417 1437 4301 1440 1472 4302 1475 1438 4303 1441 1411 4304 1414 1446 4305 1449 1432 4306 1435 1439 4307 1442 1331 4308 1334 1440 4309 1443 1428 4310 1431 1442 4311 1445 1441 4312 1444 1431 4313 1434 1448 4314 1451 1441 4315 1444 1442 4316 1445 1450 4317 1453 1414 4318 1417 1443 4319 1446 1446 4320 1449 1444 4321 1447 1432 4322 1435 1459 4323 1462 1390 4324 1393 1445 4325 1448 1453 4326 1456 1444 4327 1447 1446 4328 1449 1448 4329 1451 1447 4330 1450 1441 4331 1444 1455 4332 1458 1447 4333 1450 1448 4334 1451 1453 4335 1456 1449 4336 1452 1444 4337 1447 1457 4338 1460 1414 4339 1417 1450 4340 1453 1472 4341 1475 1451 4342 1454 1438 4343 1441 1331 4344 1334 1452 4345 1455 1440 4346 1443 1461 4347 1464 1449 4348 1452 1453 4349 1456 1455 4350 1458 1454 4351 1457 1447 4352 1450 1463 4353 1466 1454 4354 1457 1455 4355 1458 1331 4356 1334 1456 4357 1459 1452 4358 1455 1464 4359 1467 1414 4360 1417 1457 4361 1460 1461 4362 1464 1458 4363 1461 1449 4364 1452 1468 4365 1471 1390 4366 1393 1459 4367 1462 1472 4368 1475 1460 4369 1463 1451 4370 1454 1494 4371 1497 1458 4372 1461 1461 4373 1464 1463 4374 1466 1462 4375 1465 1454 4376 1457 1476 4377 1479 1462 4378 1465 1463 4379 1466 1474 4380 1477 1414 4381 1417 1464 4382 1467 1331 4383 1334 1465 4384 1468 1456 4385 1459 1494 4386 1497 1466 4387 1469 1458 4388 1461 1472 4389 1475 1467 4390 1470 1460 4391 1463 1469 4392 1472 1390 4393 1393 1468 4394 1471 1469 4395 1472 1359 4396 1362 1390 4397 1393 1470 4398 1473 1359 4399 1362 1469 4400 1472 1471 4401 1474 1359 4402 1362 1470 4403 1473 1467 4404 1470 1359 4405 1362 1471 4406 1474 1472 4407 1475 1359 4408 1362 1467 4409 1470 1414 4410 1417 1359 4411 1501 1472 4412 1502 1414 4413 1417 1473 4414 1503 1359 4415 1504 1474 4416 1477 1473 4417 1505 1414 4418 1417 1475 4419 1478 1473 4420 1506 1474 4421 1477 1462 4422 1465 1473 4423 1507 1475 4424 1478 1476 4425 1479 1473 4426 1508 1462 4427 1465 1477 4428 1480 1473 4429 1509 1476 4430 1479 1478 4431 1510 1473 4432 1511 1477 4433 1480 1479 4434 1482 1473 4435 1476 1478 4436 1481 1480 4437 1483 1473 4438 1476 1479 4439 1482 1482 4440 1485 1473 4441 1476 1480 4442 1483 1482 4443 1485 1481 4444 1484 1473 4445 1476 1483 4446 1486 1481 4447 1484 1482 4448 1485 1484 4449 1487 1481 4450 1484 1483 4451 1486 1485 4452 1488 1481 4453 1484 1484 4454 1487 1486 4455 1489 1481 4456 1484 1485 4457 1488 1487 4458 1490 1481 4459 1484 1486 4460 1489 1488 4461 1491 1481 4462 1484 1487 4463 1490 1489 4464 1492 1481 4465 1484 1488 4466 1491 1490 4467 1493 1481 4468 1484 1489 4469 1492 1491 4470 1494 1481 4471 1484 1490 4472 1493 1492 4473 1495 1481 4474 1484 1491 4475 1494 1493 4476 1496 1481 4477 1484 1492 4478 1495 1496 4479 1499 1481 4480 1484 1493 4481 1496 1465 4482 1468 1466 4483 1469 1494 4484 1497 1331 4485 1334 1466 4486 1469 1465 4487 1468 1331 4488 1334 1495 4489 1498 1466 4490 1469 1497 4491 1500 1481 4492 1484 1496 4493 1499 1497 4494 1500 1331 4495 1334 1481 4496 1484 1330 4497 1333 1331 4498 1334 1497 4499 1500 1530 4500 1544 1499 4501 1513 1498 4502 1512 1501 4503 1515 1499 4504 1513 1500 4505 1514 1498 4506 1512 1499 4507 1513 1501 4508 1515 1505 4509 1519 1502 4510 1516 1503 4511 1517 1505 4512 1519 1504 4513 1518 1502 4514 1516 1507 4515 1521 1504 4516 1518 1505 4517 1519 1507 4518 1521 1506 4519 1520 1504 4520 1518 1509 4521 1523 1506 4522 1520 1507 4523 1521 1509 4524 1523 1508 4525 1522 1506 4526 1520 1511 4527 1525 1508 4528 1522 1509 4529 1523 1511 4530 1525 1510 4531 1524 1508 4532 1522 1514 4533 1528 1510 4534 1524 1511 4535 1525 1514 4536 1528 1512 4537 1526 1510 4538 1524 1514 4539 1528 1513 4540 1527 1512 4541 1526 1515 4542 1529 1513 4543 1527 1514 4544 1528 1517 4545 1531 1513 4546 1527 1515 4547 1529 1517 4548 1531 1516 4549 1530 1513 4550 1527 1520 4551 1534 1516 4552 1530 1517 4553 1531 1520 4554 1534 1518 4555 1532 1516 4556 1530 1520 4557 1534 1519 4558 1533 1518 4559 1532 1522 4560 1536 1519 4561 1533 1520 4562 1534 1522 4563 1536 1521 4564 1535 1519 4565 1533 1523 4566 1537 1521 4567 1535 1522 4568 1536 1525 4569 1539 1521 4570 1535 1523 4571 1537 1525 4572 1539 1524 4573 1538 1521 4574 1535 1527 4575 1541 1524 4576 1538 1525 4577 1539 1527 4578 1541 1526 4579 1540 1524 4580 1538 1529 4581 1543 1526 4582 1540 1527 4583 1541 1529 4584 1543 1528 4585 1542 1526 4586 1540 1531 4587 1545 1528 4588 1542 1529 4589 1543 1531 4590 1545 1530 4591 1544 1528 4592 1542 1499 4593 1513 1530 4594 1544 1531 4595 1545 1595 4596 1609 1532 4597 1546 1534 4598 1548 1534 4599 1548 1533 4600 1547 1595 4601 1609 1536 4602 1550 1533 4603 1547 1534 4604 1548 1536 4605 1550 1535 4606 1549 1533 4607 1547 1538 4608 1552 1535 4609 1549 1536 4610 1550 1538 4611 1552 1537 4612 1551 1535 4613 1549 1540 4614 1554 1537 4615 1551 1538 4616 1552 1540 4617 1554 1539 4618 1553 1537 4619 1551 1542 4620 1556 1539 4621 1553 1540 4622 1554 1542 4623 1556 1541 4624 1555 1539 4625 1553 1544 4626 1558 1541 4627 1555 1542 4628 1556 1544 4629 1558 1543 4630 1557 1541 4631 1555 1546 4632 1560 1543 4633 1557 1544 4634 1558 1546 4635 1560 1545 4636 1559 1543 4637 1557 1548 4638 1562 1545 4639 1559 1546 4640 1560 1548 4641 1562 1547 4642 1561 1545 4643 1559 1550 4644 1564 1547 4645 1561 1548 4646 1562 1550 4647 1564 1549 4648 1563 1547 4649 1561 1552 4650 1566 1549 4651 1563 1550 4652 1564 1552 4653 1566 1551 4654 1565 1549 4655 1563 1554 4656 1568 1551 4657 1565 1552 4658 1566 1554 4659 1568 1553 4660 1567 1551 4661 1565 1556 4662 1570 1553 4663 1567 1554 4664 1568 1556 4665 1570 1555 4666 1569 1553 4667 1567 1558 4668 1572 1555 4669 1569 1556 4670 1570 1558 4671 1572 1557 4672 1571 1555 4673 1569 1560 4674 1574 1557 4675 1571 1558 4676 1572 1560 4677 1574 1559 4678 1573 1557 4679 1571 1562 4680 1576 1559 4681 1573 1560 4682 1574 1562 4683 1576 1561 4684 1575 1559 4685 1573 1564 4686 1578 1561 4687 1575 1562 4688 1576 1564 4689 1578 1563 4690 1577 1561 4691 1575 1566 4692 1580 1563 4693 1577 1564 4694 1578 1566 4695 1580 1565 4696 1579 1563 4697 1577 1568 4698 1582 1565 4699 1579 1566 4700 1580 1568 4701 1582 1567 4702 1581 1565 4703 1579 1570 4704 1584 1567 4705 1581 1568 4706 1582 1570 4707 1584 1569 4708 1583 1567 4709 1581 1572 4710 1586 1569 4711 1583 1570 4712 1584 1572 4713 1586 1571 4714 1585 1569 4715 1583 1574 4716 1588 1571 4717 1585 1572 4718 1586 1574 4719 1588 1573 4720 1587 1571 4721 1585 1576 4722 1590 1573 4723 1587 1574 4724 1588 1576 4725 1590 1575 4726 1589 1573 4727 1587 1578 4728 1592 1575 4729 1589 1576 4730 1590 1578 4731 1592 1577 4732 1591 1575 4733 1589 1580 4734 1594 1577 4735 1591 1578 4736 1592 1580 4737 1594 1579 4738 1593 1577 4739 1591 1582 4740 1596 1579 4741 1593 1580 4742 1594 1582 4743 1596 1581 4744 1595 1579 4745 1593 1584 4746 1598 1581 4747 1595 1582 4748 1596 1584 4749 1598 1583 4750 1597 1581 4751 1595 1586 4752 1600 1583 4753 1597 1584 4754 1598 1586 4755 1600 1585 4756 1599 1583 4757 1597 1588 4758 1602 1585 4759 1599 1586 4760 1600 1588 4761 1602 1587 4762 1601 1585 4763 1599 1590 4764 1604 1587 4765 1601 1588 4766 1602 1590 4767 1604 1589 4768 1603 1587 4769 1601 1592 4770 1606 1589 4771 1603 1590 4772 1604 1592 4773 1606 1591 4774 1605 1589 4775 1603 1594 4776 1608 1591 4777 1605 1592 4778 1606 1594 4779 1608 1593 4780 1607 1591 4781 1605 1532 4782 1546 1593 4783 1607 1594 4784 1608 1532 4785 1546 1595 4786 1609 1593 4787 1607 1659 4788 1673 1596 4789 1610 1598 4790 1612 1598 4791 1612 1597 4792 1611 1659 4793 1673 1600 4794 1614 1597 4795 1611 1598 4796 1612 1600 4797 1614 1599 4798 1613 1597 4799 1611 1602 4800 1616 1599 4801 1613 1600 4802 1614 1602 4803 1616 1601 4804 1615 1599 4805 1613 1604 4806 1618 1601 4807 1615 1602 4808 1616 1604 4809 1618 1603 4810 1617 1601 4811 1615 1606 4812 1620 1603 4813 1617 1604 4814 1618 1606 4815 1620 1605 4816 1619 1603 4817 1617 1608 4818 1622 1605 4819 1619 1606 4820 1620 1608 4821 1622 1607 4822 1621 1605 4823 1619 1610 4824 1624 1607 4825 1621 1608 4826 1622 1610 4827 1624 1609 4828 1623 1607 4829 1621 1612 4830 1626 1609 4831 1623 1610 4832 1624 1612 4833 1626 1611 4834 1625 1609 4835 1623 1614 4836 1628 1611 4837 1625 1612 4838 1626 1614 4839 1628 1613 4840 1627 1611 4841 1625 1616 4842 1630 1613 4843 1627 1614 4844 1628 1616 4845 1630 1615 4846 1629 1613 4847 1627 1618 4848 1632 1615 4849 1629 1616 4850 1630 1618 4851 1632 1617 4852 1631 1615 4853 1629 1620 4854 1634 1617 4855 1631 1618 4856 1632 1620 4857 1634 1619 4858 1633 1617 4859 1631 1622 4860 1636 1619 4861 1633 1620 4862 1634 1622 4863 1636 1621 4864 1635 1619 4865 1633 1624 4866 1638 1621 4867 1635 1622 4868 1636 1624 4869 1638 1623 4870 1637 1621 4871 1635 1626 4872 1640 1623 4873 1637 1624 4874 1638 1626 4875 1640 1625 4876 1639 1623 4877 1637 1628 4878 1642 1625 4879 1639 1626 4880 1640 1628 4881 1642 1627 4882 1641 1625 4883 1639 1630 4884 1644 1627 4885 1641 1628 4886 1642 1630 4887 1644 1629 4888 1643 1627 4889 1641 1632 4890 1646 1629 4891 1643 1630 4892 1644 1632 4893 1646 1631 4894 1645 1629 4895 1643 1634 4896 1648 1631 4897 1645 1632 4898 1646 1634 4899 1648 1633 4900 1647 1631 4901 1645 1636 4902 1650 1633 4903 1647 1634 4904 1648 1636 4905 1650 1635 4906 1649 1633 4907 1647 1638 4908 1652 1635 4909 1649 1636 4910 1650 1638 4911 1652 1637 4912 1651 1635 4913 1649 1640 4914 1654 1637 4915 1651 1638 4916 1652 1640 4917 1654 1639 4918 1653 1637 4919 1651 1642 4920 1656 1639 4921 1653 1640 4922 1654 1642 4923 1656 1641 4924 1655 1639 4925 1653 1644 4926 1658 1641 4927 1655 1642 4928 1656 1644 4929 1658 1643 4930 1657 1641 4931 1655 1646 4932 1660 1643 4933 1657 1644 4934 1658 1646 4935 1660 1645 4936 1659 1643 4937 1657 1648 4938 1662 1645 4939 1659 1646 4940 1660 1648 4941 1662 1647 4942 1661 1645 4943 1659 1650 4944 1664 1647 4945 1661 1648 4946 1662 1650 4947 1664 1649 4948 1663 1647 4949 1661 1652 4950 1666 1649 4951 1663 1650 4952 1664 1652 4953 1666 1651 4954 1665 1649 4955 1663 1654 4956 1668 1651 4957 1665 1652 4958 1666 1654 4959 1668 1653 4960 1667 1651 4961 1665 1656 4962 1670 1653 4963 1667 1654 4964 1668 1656 4965 1670 1655 4966 1669 1653 4967 1667 1658 4968 1672 1655 4969 1669 1656 4970 1670 1658 4971 1672 1657 4972 1671 1655 4973 1669 1596 4974 1610 1657 4975 1671 1658 4976 1672 1596 4977 1610 1659 4978 1673 1657 4979 1671 1676 4980 1690 1660 4981 1674 1668 4982 1682 1672 4983 1686 1661 4984 1675 1662 4985 1676 1672 4986 1686 1663 4987 1677 1661 4988 1675 1666 4989 1680 1664 4990 1678 1665 4991 1679 1669 4992 1683 1664 4993 1678 1666 4994 1680 1669 4995 1683 1667 4996 1681 1664 4997 1678 1669 4998 1683 1668 4999 1682 1667 5000 1681 1670 5001 1684 1668 5002 1682 1669 5003 1683 1671 5004 1685 1668 5005 1682 1670 5006 1684 1676 5007 1690 1668 5008 1682 1671 5009 1685 1673 5010 1687 1663 5011 1677 1672 5012 1686 1660 5013 1674 1663 5014 1677 1673 5015 1687 1660 5016 1674 1674 5017 1688 1663 5018 1677 1660 5019 1674 1675 5020 1689 1674 5021 1688 1660 5022 1674 1676 5023 1690 1675 5024 1689 1708 5025 1722 1698 5026 1712 1677 5027 1691 1680 5028 1694 1678 5029 1692 1679 5030 1693 1682 5031 1696 1678 5032 1692 1680 5033 1694 1682 5034 1696 1681 5035 1695 1678 5036 1692 1683 5037 1697 1681 5038 1695 1682 5039 1696 1685 5040 1699 1681 5041 1695 1683 5042 1697 1685 5043 1699 1684 5044 1698 1681 5045 1695 1687 5046 1701 1684 5047 1698 1685 5048 1699 1687 5049 1701 1686 5050 1700 1684 5051 1698 1690 5052 1704 1686 5053 1700 1687 5054 1701 1690 5055 1704 1688 5056 1702 1686 5057 1700 1690 5058 1704 1689 5059 1703 1688 5060 1702 1691 5061 1705 1689 5062 1703 1690 5063 1704 1694 5064 1708 1689 5065 1703 1691 5066 1705 1694 5067 1708 1692 5068 1706 1689 5069 1703 1694 5070 1708 1693 5071 1707 1692 5072 1706 1696 5073 1710 1693 5074 1707 1694 5075 1708 1696 5076 1710 1695 5077 1709 1693 5078 1707 1697 5079 1711 1695 5080 1709 1696 5081 1710 1677 5082 1691 1695 5083 1709 1697 5084 1711 1677 5085 1691 1698 5086 1712 1695 5087 1709 1701 5088 1715 1699 5089 1713 1700 5090 1714 1703 5091 1717 1699 5092 1713 1701 5093 1715 1703 5094 1717 1702 5095 1716 1699 5096 1713 1704 5097 1718 1702 5098 1716 1703 5099 1717 1706 5100 1720 1702 5101 1716 1704 5102 1718 1706 5103 1720 1705 5104 1719 1702 5105 1716 1709 5106 1723 1705 5107 1719 1706 5108 1720 1709 5109 1723 1707 5110 1721 1705 5111 1719 1709 5112 1723 1708 5113 1722 1707 5114 1721 1710 5115 1724 1708 5116 1722 1709 5117 1723 1698 5118 1712 1708 5119 1722 1710 5120 1724 1784 5121 1799 1711 5122 1725 1750 5123 1800 1732 5124 1746 1712 5125 1726 1713 5126 1727 1735 5127 1749 1714 5128 1728 1715 5129 1729 1771 5130 1785 1716 5131 1730 1717 5132 1731 1768 5133 1782 1718 5134 1732 1719 5135 1733 1721 5136 1735 1720 5137 1734 1751 5138 1765 1723 5139 1737 1720 5140 1734 1721 5141 1735 1723 5142 1737 1722 5143 1736 1720 5144 1734 1725 5145 1739 1722 5146 1736 1723 5147 1737 1725 5148 1739 1724 5149 1738 1722 5150 1736 1727 5151 1741 1724 5152 1738 1725 5153 1739 1727 5154 1741 1726 5155 1740 1724 5156 1738 1729 5157 1743 1726 5158 1740 1727 5159 1741 1729 5160 1743 1728 5161 1742 1726 5162 1740 1731 5163 1745 1728 5164 1742 1729 5165 1743 1731 5166 1745 1730 5167 1744 1728 5168 1742 1733 5169 1747 1730 5170 1744 1731 5171 1745 1733 5172 1747 1732 5173 1746 1730 5174 1744 1734 5175 1748 1732 5176 1746 1733 5177 1747 1734 5178 1748 1712 5179 1726 1732 5180 1746 1736 5181 1750 1712 5182 1726 1734 5183 1748 1736 5184 1750 1735 5185 1749 1712 5186 1726 1737 5187 1751 1735 5188 1749 1736 5189 1750 1737 5190 1751 1714 5191 1728 1735 5192 1749 1739 5193 1753 1714 5194 1728 1737 5195 1751 1739 5196 1753 1738 5197 1752 1714 5198 1728 1741 5199 1755 1738 5200 1752 1739 5201 1753 1741 5202 1755 1740 5203 1754 1738 5204 1752 1743 5205 1757 1740 5206 1754 1741 5207 1755 1743 5208 1757 1742 5209 1756 1740 5210 1754 1745 5211 1759 1742 5212 1756 1743 5213 1757 1745 5214 1759 1744 5215 1758 1742 5216 1756 1747 5217 1761 1744 5218 1758 1745 5219 1759 1747 5220 1761 1746 5221 1760 1744 5222 1758 1749 5223 1763 1746 5224 1760 1747 5225 1761 1749 5226 1763 1748 5227 1762 1746 5228 1760 1784 5229 1798 1748 5230 1762 1749 5231 1763 1784 5232 1798 1750 5233 1764 1748 5234 1762 1753 5235 1767 1721 5236 1735 1751 5237 1765 1753 5238 1767 1752 5239 1766 1721 5240 1735 1755 5241 1769 1752 5242 1766 1753 5243 1767 1755 5244 1769 1754 5245 1768 1752 5246 1766 1757 5247 1771 1754 5248 1768 1755 5249 1769 1757 5250 1771 1756 5251 1770 1754 5252 1768 1759 5253 1773 1756 5254 1770 1757 5255 1771 1759 5256 1773 1758 5257 1772 1756 5258 1770 1761 5259 1775 1758 5260 1772 1759 5261 1773 1761 5262 1775 1760 5263 1774 1758 5264 1772 1763 5265 1777 1760 5266 1774 1761 5267 1775 1763 5268 1777 1762 5269 1776 1760 5270 1774 1765 5271 1779 1762 5272 1776 1763 5273 1777 1765 5274 1779 1764 5275 1778 1762 5276 1776 1718 5277 1732 1764 5278 1778 1765 5279 1779 1718 5280 1732 1766 5281 1780 1764 5282 1778 1768 5283 1782 1766 5284 1780 1718 5285 1732 1768 5286 1782 1767 5287 1781 1766 5288 1780 1716 5289 1730 1767 5290 1781 1768 5291 1782 1716 5292 1730 1769 5293 1783 1767 5294 1781 1771 5295 1785 1769 5296 1783 1716 5297 1730 1771 5298 1785 1770 5299 1784 1769 5300 1783 1773 5301 1787 1770 5302 1784 1771 5303 1785 1773 5304 1787 1772 5305 1786 1770 5306 1784 1775 5307 1789 1772 5308 1786 1773 5309 1787 1775 5310 1789 1774 5311 1788 1772 5312 1786 1777 5313 1791 1774 5314 1788 1775 5315 1789 1777 5316 1791 1776 5317 1790 1774 5318 1788 1779 5319 1793 1776 5320 1790 1777 5321 1791 1779 5322 1793 1778 5323 1792 1776 5324 1790 1781 5325 1795 1778 5326 1792 1779 5327 1793 1781 5328 1795 1780 5329 1794 1778 5330 1792 1783 5331 1797 1780 5332 1794 1781 5333 1795 1783 5334 1797 1782 5335 1796 1780 5336 1794 1711 5337 1725 1782 5338 1796 1783 5339 1797 1711 5340 1725 1784 5341 1801 1782 5342 1796 1795 5343 1812 1857 5344 1874 1785 5345 1802 1806 5346 1823 1786 5347 1803 1787 5348 1804 1809 5349 1826 1788 5350 1805 1789 5351 1806 1839 5352 1856 1790 5353 1807 1791 5354 1808 1842 5355 1859 1792 5356 1809 1793 5357 1810 1795 5358 1812 1794 5359 1811 1858 5360 1875 1797 5361 1814 1794 5362 1811 1795 5363 1812 1797 5364 1814 1796 5365 1813 1794 5366 1811 1799 5367 1816 1796 5368 1813 1797 5369 1814 1799 5370 1816 1798 5371 1815 1796 5372 1813 1801 5373 1818 1798 5374 1815 1799 5375 1816 1801 5376 1818 1800 5377 1817 1798 5378 1815 1803 5379 1820 1800 5380 1817 1801 5381 1818 1803 5382 1820 1802 5383 1819 1800 5384 1817 1805 5385 1822 1802 5386 1819 1803 5387 1820 1805 5388 1822 1804 5389 1821 1802 5390 1819 1807 5391 1824 1804 5392 1821 1805 5393 1822 1807 5394 1824 1806 5395 1823 1804 5396 1821 1808 5397 1825 1806 5398 1823 1807 5399 1824 1808 5400 1825 1786 5401 1803 1806 5402 1823 1810 5403 1827 1786 5404 1803 1808 5405 1825 1810 5406 1827 1809 5407 1826 1786 5408 1803 1811 5409 1828 1809 5410 1826 1810 5411 1827 1811 5412 1828 1788 5413 1805 1809 5414 1826 1813 5415 1830 1788 5416 1805 1811 5417 1828 1813 5418 1830 1812 5419 1829 1788 5420 1805 1815 5421 1832 1812 5422 1829 1813 5423 1830 1815 5424 1832 1814 5425 1831 1812 5426 1829 1817 5427 1834 1814 5428 1831 1815 5429 1832 1817 5430 1834 1816 5431 1833 1814 5432 1831 1819 5433 1836 1816 5434 1833 1817 5435 1834 1819 5436 1836 1818 5437 1835 1816 5438 1833 1821 5439 1838 1818 5440 1835 1819 5441 1836 1821 5442 1838 1820 5443 1837 1818 5444 1835 1823 5445 1840 1820 5446 1837 1821 5447 1838 1823 5448 1840 1822 5449 1839 1820 5450 1837 1825 5451 1842 1822 5452 1839 1823 5453 1840 1825 5454 1842 1824 5455 1841 1822 5456 1839 1828 5457 1876 1824 5458 1841 1825 5459 1842 1828 5460 1877 1826 5461 1878 1824 5462 1841 1828 5463 1845 1827 5464 1844 1826 5465 1843 1830 5466 1847 1827 5467 1844 1828 5468 1845 1830 5469 1847 1829 5470 1846 1827 5471 1844 1832 5472 1849 1829 5473 1846 1830 5474 1847 1832 5475 1849 1831 5476 1848 1829 5477 1846 1834 5478 1851 1831 5479 1848 1832 5480 1849 1834 5481 1851 1833 5482 1850 1831 5483 1848 1836 5484 1853 1833 5485 1850 1834 5486 1851 1836 5487 1853 1835 5488 1852 1833 5489 1850 1838 5490 1855 1835 5491 1852 1836 5492 1853 1838 5493 1855 1837 5494 1854 1835 5495 1852 1840 5496 1857 1837 5497 1854 1838 5498 1855 1840 5499 1857 1839 5500 1856 1837 5501 1854 1841 5502 1858 1839 5503 1856 1840 5504 1857 1841 5505 1858 1790 5506 1807 1839 5507 1856 1843 5508 1860 1790 5509 1807 1841 5510 1858 1843 5511 1860 1842 5512 1859 1790 5513 1807 1844 5514 1861 1842 5515 1859 1843 5516 1860 1844 5517 1861 1792 5518 1809 1842 5519 1859 1846 5520 1863 1792 5521 1809 1844 5522 1861 1846 5523 1863 1845 5524 1862 1792 5525 1809 1848 5526 1865 1845 5527 1862 1846 5528 1863 1848 5529 1865 1847 5530 1864 1845 5531 1862 1850 5532 1867 1847 5533 1864 1848 5534 1865 1850 5535 1867 1849 5536 1866 1847 5537 1864 1852 5538 1869 1849 5539 1866 1850 5540 1867 1852 5541 1869 1851 5542 1868 1849 5543 1866 1854 5544 1871 1851 5545 1868 1852 5546 1869 1854 5547 1871 1853 5548 1870 1851 5549 1868 1856 5550 1873 1853 5551 1870 1854 5552 1871 1856 5553 1873 1855 5554 1872 1853 5555 1870 1785 5556 1802 1855 5557 1872 1856 5558 1873 1785 5559 1802 1857 5560 1874 1855 5561 1872 1857 5562 1874 1795 5563 1812 1858 5564 1875 1876 5565 1896 1859 5566 1879 1863 5567 1883 1864 5568 1884 1860 5569 1880 1861 5570 1881 1864 5571 1884 1862 5572 1882 1860 5573 1880 1864 5574 1884 1863 5575 1883 1862 5576 1882 1876 5577 1896 1863 5578 1883 1864 5579 1884 1869 5580 1889 1865 5581 1885 1866 5582 1886 1869 5583 1889 1867 5584 1887 1865 5585 1885 1869 5586 1889 1868 5587 1888 1867 5588 1887 1871 5589 1891 1868 5590 1888 1869 5591 1889 1871 5592 1891 1870 5593 1890 1868 5594 1888 1872 5595 1892 1870 5596 1890 1871 5597 1891 1874 5598 1894 1870 5599 1890 1872 5600 1892 1874 5601 1894 1873 5602 1893 1870 5603 1890 1859 5604 1879 1873 5605 1893 1874 5606 1894 1859 5607 1879 1875 5608 1895 1873 5609 1893 1859 5610 1879 1876 5611 1896 1875 5612 1895 1894 5613 1914 1877 5614 1897 1878 5615 1898 1883 5616 1903 1879 5617 1899 1880 5618 1900 1883 5619 1903 1881 5620 1901 1879 5621 1899 1883 5622 1903 1882 5623 1902 1881 5624 1901 1884 5625 1904 1882 5626 1902 1883 5627 1903 1886 5628 1906 1882 5629 1902 1884 5630 1904 1886 5631 1906 1885 5632 1905 1882 5633 1902 1889 5634 1909 1885 5635 1905 1886 5636 1906 1889 5637 1909 1887 5638 1907 1885 5639 1905 1889 5640 1909 1888 5641 1908 1887 5642 1907 1891 5643 1911 1888 5644 1908 1889 5645 1909 1891 5646 1911 1890 5647 1910 1888 5648 1908 1893 5649 1913 1890 5650 1910 1891 5651 1911 1893 5652 1913 1892 5653 1912 1890 5654 1910 1877 5655 1897 1892 5656 1912 1893 5657 1913 1877 5658 1897 1894 5659 1914 1892 5660 1912 1897 5661 1919 1895 5662 1915 1896 5663 1916 1895 5664 1915 1897 5665 1917 1898 5666 1918 1916 5667 1937 1899 5668 1920 1900 5669 1921 1905 5670 1926 1901 5671 1922 1902 5672 1923 1905 5673 1926 1903 5674 1924 1901 5675 1922 1905 5676 1926 1904 5677 1925 1903 5678 1924 1906 5679 1927 1904 5680 1925 1905 5681 1926 1908 5682 1929 1904 5683 1925 1906 5684 1927 1908 5685 1929 1907 5686 1928 1904 5687 1925 1911 5688 1932 1907 5689 1928 1908 5690 1929 1911 5691 1932 1909 5692 1930 1907 5693 1928 1911 5694 1932 1910 5695 1931 1909 5696 1930 1913 5697 1934 1910 5698 1931 1911 5699 1932 1913 5700 1934 1912 5701 1933 1910 5702 1931 1914 5703 1935 1912 5704 1933 1913 5705 1934 1899 5706 1920 1912 5707 1933 1914 5708 1935 1899 5709 1920 1915 5710 1936 1912 5711 1933 1899 5712 1920 1916 5713 1937 1915 5714 1936 1934 5715 1955 1917 5716 1938 1923 5717 1944 1921 5718 1942 1918 5719 1939 1919 5720 1940 1921 5721 1942 1920 5722 1941 1918 5723 1939 1924 5724 1945 1920 5725 1941 1921 5726 1942 1924 5727 1945 1922 5728 1943 1920 5729 1941 1924 5730 1945 1923 5731 1944 1922 5732 1943 1934 5733 1955 1923 5734 1944 1924 5735 1945 1928 5736 1949 1925 5737 1946 1926 5738 1947 1928 5739 1949 1927 5740 1948 1925 5741 1946 1930 5742 1951 1927 5743 1948 1928 5744 1949 1930 5745 1951 1929 5746 1950 1927 5747 1948 1933 5748 1954 1929 5749 1950 1930 5750 1951 1933 5751 1954 1931 5752 1952 1929 5753 1950 1933 5754 1954 1932 5755 1953 1931 5756 1952 1917 5757 1938 1932 5758 1953 1933 5759 1954 1917 5760 1938 1934 5761 1955 1932 5762 1953 2002 5763 2023 1935 5764 1956 1936 5765 1957 1938 5766 1959 2002 5767 2023 1936 5768 1957 1938 5769 1959 1937 5770 1958 2002 5771 2023 1940 5772 1961 1937 5773 1958 1938 5774 1959 1940 5775 1961 1939 5776 1960 1937 5777 1958 1942 5778 1963 1939 5779 1960 1940 5780 1961 1942 5781 1963 1941 5782 1962 1939 5783 1960 1944 5784 1965 1941 5785 1962 1942 5786 1963 1944 5787 1965 1943 5788 1964 1941 5789 1962 1946 5790 1967 1943 5791 1964 1944 5792 1965 1946 5793 1967 1945 5794 1966 1943 5795 1964 1948 5796 1969 1945 5797 1966 1946 5798 1967 1948 5799 1969 1947 5800 1968 1945 5801 1966 1950 5802 1971 1947 5803 1968 1948 5804 1969 1950 5805 1971 1949 5806 1970 1947 5807 1968 1952 5808 1973 1949 5809 1970 1950 5810 1971 1952 5811 1973 1951 5812 1972 1949 5813 1970 1954 5814 1975 1951 5815 1972 1952 5816 1973 1954 5817 1975 1953 5818 1974 1951 5819 1972 1956 5820 1977 1953 5821 1974 1954 5822 1975 1956 5823 1977 1955 5824 1976 1953 5825 1974 1958 5826 1979 1955 5827 1976 1956 5828 1977 1958 5829 1979 1957 5830 1978 1955 5831 1976 1960 5832 1981 1957 5833 1978 1958 5834 1979 1960 5835 1981 1959 5836 1980 1957 5837 1978 1962 5838 1983 1959 5839 1980 1960 5840 1981 1962 5841 1983 1961 5842 1982 1959 5843 1980 1964 5844 1985 1961 5845 1982 1962 5846 1983 1964 5847 1985 1963 5848 1984 1961 5849 1982 1966 5850 1987 1963 5851 1984 1964 5852 1985 1966 5853 1987 1965 5854 1986 1963 5855 1984 1968 5856 1989 1965 5857 1986 1966 5858 1987 1968 5859 1989 1967 5860 1988 1965 5861 1986 1970 5862 1991 1967 5863 2024 1968 5864 2025 1970 5865 1991 1969 5866 1990 1967 5867 2026 1972 5868 1993 1969 5869 1990 1970 5870 1991 1972 5871 1993 1971 5872 1992 1969 5873 1990 1974 5874 1995 1971 5875 1992 1972 5876 1993 1974 5877 1995 1973 5878 1994 1971 5879 1992 1976 5880 1997 1973 5881 1994 1974 5882 1995 1976 5883 1997 1975 5884 1996 1973 5885 1994 1978 5886 1999 1975 5887 1996 1976 5888 1997 1978 5889 1999 1977 5890 1998 1975 5891 1996 1980 5892 2001 1977 5893 1998 1978 5894 1999 1980 5895 2001 1979 5896 2000 1977 5897 1998 1982 5898 2003 1979 5899 2000 1980 5900 2001 1982 5901 2003 1981 5902 2002 1979 5903 2000 1984 5904 2005 1981 5905 2002 1982 5906 2003 1984 5907 2005 1983 5908 2004 1981 5909 2002 1986 5910 2007 1983 5911 2004 1984 5912 2005 1986 5913 2007 1985 5914 2006 1983 5915 2004 1988 5916 2009 1985 5917 2006 1986 5918 2007 1988 5919 2009 1987 5920 2008 1985 5921 2006 1990 5922 2011 1987 5923 2008 1988 5924 2009 1990 5925 2011 1989 5926 2010 1987 5927 2008 1992 5928 2013 1989 5929 2010 1990 5930 2011 1992 5931 2013 1991 5932 2012 1989 5933 2010 1994 5934 2015 1991 5935 2012 1992 5936 2013 1994 5937 2015 1993 5938 2014 1991 5939 2012 1996 5940 2017 1993 5941 2014 1994 5942 2015 1996 5943 2017 1995 5944 2016 1993 5945 2014 1998 5946 2019 1995 5947 2016 1996 5948 2017 1998 5949 2019 1997 5950 2018 1995 5951 2016 2000 5952 2021 1997 5953 2018 1998 5954 2019 2000 5955 2021 1999 5956 2020 1997 5957 2018 1935 5958 1956 1999 5959 2020 2000 5960 2021 1935 5961 1956 2001 5962 2022 1999 5963 2020 1935 5964 1956 2002 5965 2023 2001 5966 2022 2015 5967 2039 2006 5968 2041 2003 5969 2027 2003 5970 2027 2004 5971 2042 2005 5972 2029 2003 5973 2027 2006 5974 2043 2004 5975 2028 2009 5976 2044 2007 5977 2031 2008 5978 2032 2010 5979 2045 2007 5980 2031 2009 5981 2033 2012 5982 2046 2007 5983 2031 2010 5984 2034 2012 5985 2047 2011 5986 2035 2007 5987 2031 2014 5988 2048 2011 5989 2035 2012 5990 2036 2014 5991 2049 2013 5992 2037 2011 5993 2035 2016 5994 2050 2013 5995 2037 2014 5996 2038 2016 5997 2051 2015 5998 2039 2013 5999 2037 2006 6000 2030 2015 6001 2039 2016 6002 2040 2048 6003 2083 2017 6004 2052 2018 6005 2053 2049 6006 2084 2019 6007 2054 2023 6008 2058 2050 6009 2085 2019 6010 2054 2049 6011 2084 2050 6012 2085 2020 6013 2055 2019 6014 2054 2051 6015 2086 2020 6016 2055 2050 6017 2085 2051 6018 2086 2021 6019 2056 2020 6020 2055 2052 6021 2087 2021 6022 2056 2051 6023 2086 2052 6024 2087 2022 6025 2057 2021 6026 2056 2023 6027 2058 2053 6028 2088 2049 6029 2084 2024 6030 2059 2053 6031 2088 2023 6032 2058 2025 6033 2060 2053 6034 2088 2024 6035 2059 2025 6036 2060 2054 6037 2089 2053 6038 2088 2026 6039 2061 2054 6040 2089 2025 6041 2060 2026 6042 2061 2055 6043 2090 2054 6044 2089 2017 6045 2052 2055 6046 2090 2026 6047 2061 2022 6048 2057 2027 6049 2062 2028 6050 2063 2052 6051 2087 2027 6052 2062 2022 6053 2057 2052 6054 2087 2029 6055 2064 2027 6056 2062 2056 6057 2091 2029 6058 2064 2052 6059 2087 2057 6060 2092 2029 6061 2064 2056 6062 2091 2057 6063 2092 2030 6064 2065 2029 6065 2064 2057 6066 2092 2031 6067 2066 2030 6068 2065 2058 6069 2093 2031 6070 2066 2057 6071 2092 2059 6072 2094 2031 6073 2066 2058 6074 2093 2059 6075 2094 2032 6076 2067 2031 6077 2066 2059 6078 2094 2033 6079 2068 2032 6080 2067 2059 6081 2094 2034 6082 2069 2033 6083 2068 2059 6084 2094 2035 6085 2070 2034 6086 2069 2060 6087 2095 2035 6088 2070 2059 6089 2094 2060 6090 2095 2036 6091 2071 2035 6092 2070 2061 6093 2096 2036 6094 2071 2060 6095 2095 2061 6096 2096 2037 6097 2072 2036 6098 2071 2062 6099 2097 2037 6100 2072 2061 6101 2096 2062 6102 2097 2038 6103 2073 2037 6104 2072 2063 6105 2098 2038 6106 2073 2062 6107 2097 2063 6108 2098 2039 6109 2074 2038 6110 2073 2063 6111 2098 2040 6112 2075 2039 6113 2074 2064 6114 2099 2040 6115 2075 2063 6116 2098 2064 6117 2099 2041 6118 2076 2040 6119 2075 2065 6120 2100 2041 6121 2076 2064 6122 2099 2065 6123 2100 2042 6124 2077 2041 6125 2076 2042 6126 2077 2043 6127 2078 2044 6128 2079 2065 6129 2100 2043 6130 2078 2042 6131 2077 2066 6132 2101 2043 6133 2078 2065 6134 2100 2066 6135 2101 2045 6136 2080 2043 6137 2078 2067 6138 2102 2045 6139 2080 2066 6140 2101 2067 6141 2102 2046 6142 2081 2045 6143 2080 2068 6144 2103 2046 6145 2081 2067 6146 2102 2068 6147 2103 2047 6148 2082 2046 6149 2081 2068 6150 2103 2048 6151 2083 2047 6152 2082 2055 6153 2090 2048 6154 2083 2068 6155 2103 2017 6156 2052 2048 6157 2083 2055 6158 2090 2059 6159 2094 2069 6160 2104 2060 6161 2095 2069 6162 2104 2059 6163 2094 2058 6164 2093 2058 6165 2093 2070 6166 2105 2069 6167 2104 2070 6168 2105 2058 6169 2093 2057 6170 2092 2057 6171 2092 2071 6172 2106 2070 6173 2105 2071 6174 2106 2057 6175 2092 2056 6176 2091 2056 6177 2091 2051 6178 2086 2071 6179 2106 2051 6180 2086 2056 6181 2091 2052 6182 2087 2060 6183 2095 2072 6184 2107 2061 6185 2096 2072 6186 2107 2060 6187 2095 2069 6188 2104 2069 6189 2104 2073 6190 2108 2072 6191 2107 2073 6192 2108 2069 6193 2104 2070 6194 2105 2061 6195 2096 2074 6196 2109 2062 6197 2097 2074 6198 2109 2061 6199 2096 2072 6200 2107 2072 6201 2107 2075 6202 2110 2074 6203 2109 2075 6204 2110 2072 6205 2107 2073 6206 2108 2070 6207 2105 2076 6208 2111 2073 6209 2108 2076 6210 2111 2070 6211 2105 2071 6212 2106 2071 6213 2106 2050 6214 2085 2076 6215 2111 2050 6216 2085 2071 6217 2106 2051 6218 2086 2073 6219 2108 2077 6220 2112 2075 6221 2110 2077 6222 2112 2073 6223 2108 2076 6224 2111 2076 6225 2111 2049 6226 2084 2077 6227 2112 2049 6228 2084 2076 6229 2111 2050 6230 2085 2062 6231 2097 2078 6232 2113 2063 6233 2098 2078 6234 2113 2062 6235 2097 2074 6236 2109 2074 6237 2109 2079 6238 2114 2078 6239 2113 2079 6240 2114 2074 6241 2109 2075 6242 2110 2063 6243 2098 2080 6244 2115 2064 6245 2099 2080 6246 2115 2063 6247 2098 2078 6248 2113 2078 6249 2113 2081 6250 2116 2080 6251 2115 2081 6252 2116 2078 6253 2113 2079 6254 2114 2075 6255 2110 2082 6256 2117 2079 6257 2114 2082 6258 2117 2075 6259 2110 2077 6260 2112 2077 6261 2112 2053 6262 2088 2082 6263 2117 2053 6264 2088 2077 6265 2112 2049 6266 2084 2079 6267 2114 2083 6268 2118 2081 6269 2116 2083 6270 2118 2079 6271 2114 2082 6272 2117 2082 6273 2117 2054 6274 2089 2083 6275 2118 2054 6276 2089 2082 6277 2117 2053 6278 2088 2064 6279 2099 2066 6280 2101 2065 6281 2100 2066 6282 2101 2064 6283 2099 2080 6284 2115 2080 6285 2115 2067 6286 2102 2066 6287 2101 2067 6288 2102 2080 6289 2115 2081 6290 2116 2081 6291 2116 2068 6292 2103 2067 6293 2102 2068 6294 2103 2081 6295 2116 2083 6296 2118 2083 6297 2118 2055 6298 2090 2068 6299 2103 2055 6300 2090 2083 6301 2118 2054 6302 2089 2127 6303 2162 2128 6304 2163 2084 6305 2119 2098 6306 2133 2085 6307 2120 2086 6308 2121 2118 6309 2153 2087 6310 2122 2088 6311 2123 2129 6312 2164 2084 6313 2119 2128 6314 2163 2129 6315 2164 2089 6316 2124 2084 6317 2119 2130 6318 2165 2089 6319 2124 2129 6320 2164 2130 6321 2165 2090 6322 2125 2089 6323 2124 2131 6324 2166 2090 6325 2125 2130 6326 2165 2131 6327 2166 2091 6328 2126 2090 6329 2125 2132 6330 2167 2091 6331 2126 2131 6332 2166 2132 6333 2167 2092 6334 2127 2091 6335 2126 2133 6336 2168 2092 6337 2127 2132 6338 2167 2133 6339 2168 2093 6340 2128 2092 6341 2127 2134 6342 2169 2093 6343 2128 2133 6344 2168 2134 6345 2169 2094 6346 2129 2093 6347 2128 2135 6348 2170 2094 6349 2129 2134 6350 2169 2135 6351 2170 2095 6352 2130 2094 6353 2129 2136 6354 2171 2095 6355 2130 2135 6356 2170 2136 6357 2171 2096 6358 2131 2095 6359 2130 2136 6360 2171 2097 6361 2132 2096 6362 2131 2137 6363 2172 2097 6364 2132 2136 6365 2171 2137 6366 2172 2098 6367 2133 2097 6368 2132 2138 6369 2173 2098 6370 2133 2137 6371 2172 2138 6372 2173 2085 6373 2120 2098 6374 2133 2139 6375 2174 2085 6376 2120 2138 6377 2173 2139 6378 2174 2099 6379 2134 2085 6380 2120 2140 6381 2175 2099 6382 2134 2139 6383 2174 2140 6384 2175 2100 6385 2135 2099 6386 2134 2140 6387 2175 2101 6388 2136 2100 6389 2135 2141 6390 2176 2101 6391 2136 2140 6392 2175 2141 6393 2176 2102 6394 2137 2101 6395 2136 2142 6396 2177 2102 6397 2137 2141 6398 2176 2142 6399 2177 2103 6400 2138 2102 6401 2137 2142 6402 2177 2104 6403 2139 2103 6404 2138 2143 6405 2178 2104 6406 2139 2142 6407 2177 2143 6408 2178 2105 6409 2140 2104 6410 2139 2144 6411 2179 2105 6412 2140 2143 6413 2178 2144 6414 2179 2106 6415 2141 2105 6416 2140 2145 6417 2180 2106 6418 2141 2144 6419 2179 2145 6420 2180 2107 6421 2142 2106 6422 2141 2146 6423 2181 2107 6424 2142 2145 6425 2180 2146 6426 2181 2108 6427 2143 2107 6428 2142 2147 6429 2182 2108 6430 2143 2146 6431 2181 2147 6432 2182 2109 6433 2144 2108 6434 2143 2148 6435 2183 2109 6436 2144 2147 6437 2182 2148 6438 2183 2110 6439 2145 2109 6440 2144 2149 6441 2184 2110 6442 2145 2148 6443 2183 2149 6444 2184 2111 6445 2146 2110 6446 2145 2150 6447 2185 2111 6448 2146 2149 6449 2184 2150 6450 2185 2112 6451 2147 2111 6452 2146 2151 6453 2186 2112 6454 2147 2150 6455 2185 2151 6456 2186 2113 6457 2148 2112 6458 2147 2152 6459 2187 2113 6460 2148 2151 6461 2186 2152 6462 2187 2114 6463 2149 2113 6464 2148 2153 6465 2188 2114 6466 2149 2152 6467 2187 2153 6468 2188 2115 6469 2150 2114 6470 2149 2154 6471 2189 2115 6472 2150 2153 6473 2188 2154 6474 2189 2116 6475 2151 2115 6476 2150 2155 6477 2190 2116 6478 2151 2154 6479 2189 2155 6480 2190 2117 6481 2152 2116 6482 2151 2156 6483 2191 2117 6484 2152 2155 6485 2190 2156 6486 2191 2118 6487 2153 2117 6488 2152 2156 6489 2191 2087 6490 2122 2118 6491 2153 2157 6492 2192 2087 6493 2122 2156 6494 2191 2157 6495 2192 2119 6496 2154 2087 6497 2122 2158 6498 2193 2119 6499 2154 2157 6500 2192 2158 6501 2193 2120 6502 2155 2119 6503 2154 2159 6504 2194 2120 6505 2155 2158 6506 2193 2159 6507 2194 2121 6508 2156 2120 6509 2155 2160 6510 2195 2121 6511 2156 2159 6512 2194 2160 6513 2195 2122 6514 2157 2121 6515 2156 2160 6516 2195 2123 6517 2158 2122 6518 2157 2160 6519 2195 2124 6520 2159 2123 6521 2158 2161 6522 2196 2124 6523 2159 2160 6524 2195 2161 6525 2196 2125 6526 2160 2124 6527 2159 2162 6528 2197 2125 6529 2160 2161 6530 2196 2162 6531 2197 2126 6532 2161 2125 6533 2160 2163 6534 2198 2126 6535 2161 2162 6536 2197 2163 6537 2198 2127 6538 2162 2126 6539 2161 2128 6540 2163 2127 6541 2162 2163 6542 2198 2160 6543 2195 2164 6544 2199 2161 6545 2196 2164 6546 2199 2160 6547 2195 2159 6548 2194 2159 6549 2194 2165 6550 2200 2164 6551 2199 2165 6552 2200 2159 6553 2194 2158 6554 2193 2158 6555 2193 2166 6556 2201 2165 6557 2200 2166 6558 2201 2158 6559 2193 2157 6560 2192 2157 6561 2192 2155 6562 2190 2166 6563 2201 2155 6564 2190 2157 6565 2192 2156 6566 2191 2161 6567 2196 2167 6568 2202 2162 6569 2197 2167 6570 2202 2161 6571 2196 2164 6572 2199 2164 6573 2199 2168 6574 2203 2167 6575 2202 2168 6576 2203 2164 6577 2199 2165 6578 2200 2162 6579 2197 2169 6580 2204 2163 6581 2198 2169 6582 2204 2162 6583 2197 2167 6584 2202 2167 6585 2202 2170 6586 2205 2169 6587 2204 2170 6588 2205 2167 6589 2202 2168 6590 2203 2165 6591 2200 2171 6592 2206 2168 6593 2203 2171 6594 2206 2165 6595 2200 2166 6596 2201 2166 6597 2201 2154 6598 2189 2171 6599 2206 2154 6600 2189 2166 6601 2201 2155 6602 2190 2168 6603 2203 2172 6604 2207 2170 6605 2205 2172 6606 2207 2168 6607 2203 2171 6608 2206 2171 6609 2206 2153 6610 2188 2172 6611 2207 2153 6612 2188 2171 6613 2206 2154 6614 2189 2163 6615 2198 2173 6616 2208 2128 6617 2163 2173 6618 2208 2163 6619 2198 2169 6620 2204 2169 6621 2204 2174 6622 2209 2173 6623 2208 2174 6624 2209 2169 6625 2204 2170 6626 2205 2128 6627 2163 2175 6628 2210 2129 6629 2164 2175 6630 2210 2128 6631 2163 2173 6632 2208 2173 6633 2208 2176 6634 2211 2175 6635 2210 2176 6636 2211 2173 6637 2208 2174 6638 2209 2170 6639 2205 2177 6640 2212 2174 6641 2209 2177 6642 2212 2170 6643 2205 2172 6644 2207 2172 6645 2207 2152 6646 2187 2177 6647 2212 2152 6648 2187 2172 6649 2207 2153 6650 2188 2174 6651 2209 2178 6652 2213 2176 6653 2211 2178 6654 2213 2174 6655 2209 2177 6656 2212 2177 6657 2212 2151 6658 2186 2178 6659 2213 2151 6660 2186 2177 6661 2212 2152 6662 2187 2129 6663 2164 2179 6664 2214 2130 6665 2165 2179 6666 2214 2129 6667 2164 2175 6668 2210 2175 6669 2210 2180 6670 2215 2179 6671 2214 2180 6672 2215 2175 6673 2210 2176 6674 2211 2130 6675 2165 2181 6676 2216 2131 6677 2166 2181 6678 2216 2130 6679 2165 2179 6680 2214 2179 6681 2214 2182 6682 2217 2181 6683 2216 2182 6684 2217 2179 6685 2214 2180 6686 2215 2176 6687 2211 2183 6688 2218 2180 6689 2215 2183 6690 2218 2176 6691 2211 2178 6692 2213 2178 6693 2213 2150 6694 2185 2183 6695 2218 2150 6696 2185 2178 6697 2213 2151 6698 2186 2180 6699 2215 2184 6700 2219 2182 6701 2217 2184 6702 2219 2180 6703 2215 2183 6704 2218 2183 6705 2218 2149 6706 2184 2184 6707 2219 2149 6708 2184 2183 6709 2218 2150 6710 2185 2131 6711 2166 2185 6712 2220 2132 6713 2167 2185 6714 2220 2131 6715 2166 2181 6716 2216 2181 6717 2216 2186 6718 2221 2185 6719 2220 2186 6720 2221 2181 6721 2216 2182 6722 2217 2132 6723 2167 2187 6724 2222 2133 6725 2168 2187 6726 2222 2132 6727 2167 2185 6728 2220 2185 6729 2220 2188 6730 2223 2187 6731 2222 2188 6732 2223 2185 6733 2220 2186 6734 2221 2182 6735 2217 2189 6736 2224 2186 6737 2221 2189 6738 2224 2182 6739 2217 2184 6740 2219 2184 6741 2219 2148 6742 2183 2189 6743 2224 2148 6744 2183 2184 6745 2219 2149 6746 2184 2186 6747 2221 2190 6748 2225 2188 6749 2223 2190 6750 2225 2186 6751 2221 2189 6752 2224 2189 6753 2224 2147 6754 2182 2190 6755 2225 2147 6756 2182 2189 6757 2224 2148 6758 2183 2133 6759 2168 2191 6760 2226 2134 6761 2169 2191 6762 2226 2133 6763 2168 2187 6764 2222 2187 6765 2222 2192 6766 2227 2191 6767 2226 2192 6768 2227 2187 6769 2222 2188 6770 2223 2134 6771 2169 2193 6772 2228 2135 6773 2170 2193 6774 2228 2134 6775 2169 2191 6776 2226 2191 6777 2226 2194 6778 2229 2193 6779 2228 2194 6780 2229 2191 6781 2226 2192 6782 2227 2188 6783 2223 2195 6784 2230 2192 6785 2227 2195 6786 2230 2188 6787 2223 2190 6788 2225 2190 6789 2225 2146 6790 2181 2195 6791 2230 2146 6792 2181 2190 6793 2225 2147 6794 2182 2192 6795 2227 2196 6796 2231 2194 6797 2229 2196 6798 2231 2192 6799 2227 2195 6800 2230 2195 6801 2230 2145 6802 2180 2196 6803 2231 2145 6804 2180 2195 6805 2230 2146 6806 2181 2135 6807 2170 2197 6808 2232 2136 6809 2171 2197 6810 2232 2135 6811 2170 2193 6812 2228 2193 6813 2228 2198 6814 2233 2197 6815 2232 2198 6816 2233 2193 6817 2228 2194 6818 2229 2136 6819 2171 2199 6820 2234 2137 6821 2172 2199 6822 2234 2136 6823 2171 2197 6824 2232 2197 6825 2232 2200 6826 2235 2199 6827 2234 2200 6828 2235 2197 6829 2232 2198 6830 2233 2194 6831 2229 2201 6832 2236 2198 6833 2233 2201 6834 2236 2194 6835 2229 2196 6836 2231 2196 6837 2231 2144 6838 2179 2201 6839 2236 2144 6840 2179 2196 6841 2231 2145 6842 2180 2198 6843 2233 2202 6844 2237 2200 6845 2235 2202 6846 2237 2198 6847 2233 2201 6848 2236 2201 6849 2236 2143 6850 2178 2202 6851 2237 2143 6852 2178 2201 6853 2236 2144 6854 2179 2137 6855 2172 2139 6856 2174 2138 6857 2173 2139 6858 2174 2137 6859 2172 2199 6860 2234 2199 6861 2234 2140 6862 2175 2139 6863 2174 2140 6864 2175 2199 6865 2234 2200 6866 2235 2200 6867 2235 2141 6868 2176 2140 6869 2175 2141 6870 2176 2200 6871 2235 2202 6872 2237 2202 6873 2237 2142 6874 2177 2141 6875 2176 2142 6876 2177 2202 6877 2237 2143 6878 2178 2216 6879 2251 2203 6880 2238 2210 6881 2245 2206 6882 2241 2204 6883 2239 2205 6884 2240 2208 6885 2243 2204 6886 2239 2206 6887 2241 2208 6888 2243 2207 6889 2242 2204 6890 2239 2209 6891 2244 2207 6892 2242 2208 6893 2243 2216 6894 2251 2207 6895 2242 2209 6896 2244 2216 6897 2251 2210 6898 2245 2207 6899 2242 2213 6900 2248 2211 6901 2246 2212 6902 2247 2215 6903 2250 2211 6904 2246 2213 6905 2248 2215 6906 2250 2214 6907 2249 2211 6908 2246 2203 6909 2238 2214 6910 2249 2215 6911 2250 2203 6912 2238 2216 6913 2251 2214 6914 2249 2225 6915 2260 2218 6916 2262 2217 6917 2252 2220 6918 2255 2218 6919 2263 2219 6920 2254 2217 6921 2252 2218 6922 2264 2220 6923 2255 2223 6924 2265 2221 6925 2256 2222 6926 2257 2224 6927 2266 2221 6928 2256 2223 6929 2258 2226 6930 2267 2221 6931 2256 2224 6932 2259 2226 6933 2268 2225 6934 2260 2221 6935 2256 2218 6936 2253 2225 6937 2260 2226 6938 2261 2255 6939 2297 2230 6940 2272 2256 6941 2298 2257 6942 2299 2231 6943 2273 2258 6944 2300 2257 6945 2299 2227 6946 2269 2231 6947 2273 2257 6948 2299 2228 6949 2270 2227 6950 2269 2259 6951 2301 2228 6952 2270 2257 6953 2299 2259 6954 2301 2229 6955 2271 2228 6956 2270 2256 6957 2298 2229 6958 2271 2259 6959 2301 2256 6960 2298 2230 6961 2272 2229 6962 2271 2232 6963 2274 2258 6964 2300 2231 6965 2273 2232 6966 2274 2260 6967 2302 2258 6968 2300 2233 6969 2275 2260 6970 2302 2232 6971 2274 2233 6972 2275 2261 6973 2303 2260 6974 2302 2234 6975 2276 2261 6976 2303 2233 6977 2275 2234 6978 2276 2262 6979 2304 2261 6980 2303 2244 6981 2286 2262 6982 2304 2234 6983 2276 2230 6984 2272 2235 6985 2277 2236 6986 2278 2230 6987 2272 2237 6988 2279 2235 6989 2277 2240 6990 2282 2238 6991 2280 2239 6992 2281 2237 6993 2279 2238 6994 2280 2240 6995 2282 2247 6996 2289 2241 6997 2283 2242 6998 2284 2247 6999 2289 2243 7000 2285 2241 7001 2283 2246 7002 2288 2244 7003 2286 2245 7004 2287 2243 7005 2285 2244 7006 2286 2246 7007 2288 2244 7008 2286 2263 7009 2305 2262 7010 2304 2243 7011 2285 2263 7012 2305 2244 7013 2286 2247 7014 2289 2263 7015 2305 2243 7016 2285 2247 7017 2289 2264 7018 2306 2263 7019 2305 2248 7020 2290 2264 7021 2306 2247 7022 2289 2248 7023 2290 2265 7024 2307 2264 7025 2306 2249 7026 2291 2265 7027 2307 2248 7028 2290 2249 7029 2291 2266 7030 2308 2265 7031 2307 2250 7032 2292 2266 7033 2308 2249 7034 2291 2250 7035 2292 2267 7036 2309 2266 7037 2308 2251 7038 2293 2267 7039 2309 2250 7040 2292 2251 7041 2293 2268 7042 2310 2267 7043 2309 2252 7044 2294 2268 7045 2310 2251 7046 2293 2253 7047 2295 2268 7048 2310 2252 7049 2294 2253 7050 2295 2269 7051 2311 2268 7052 2310 2254 7053 2296 2269 7054 2311 2253 7055 2295 2254 7056 2296 2270 7057 2312 2269 7058 2311 2238 7059 2280 2270 7060 2312 2254 7061 2296 2238 7062 2280 2255 7063 2297 2270 7064 2312 2237 7065 2279 2255 7066 2297 2238 7067 2280 2230 7068 2272 2255 7069 2297 2237 7070 2279 2262 7071 2304 2271 7072 2313 2261 7073 2303 2271 7074 2313 2262 7075 2304 2263 7076 2305 2261 7077 2303 2272 7078 2314 2260 7079 2302 2272 7080 2314 2261 7081 2303 2271 7082 2313 2260 7083 2302 2273 7084 2315 2258 7085 2300 2273 7086 2315 2260 7087 2302 2272 7088 2314 2263 7089 2305 2265 7090 2307 2271 7091 2313 2265 7092 2307 2263 7093 2305 2264 7094 2306 2271 7095 2313 2266 7096 2308 2272 7097 2314 2266 7098 2308 2271 7099 2313 2265 7100 2307 2272 7101 2314 2267 7102 2309 2273 7103 2315 2267 7104 2309 2272 7105 2314 2266 7106 2308 2258 7107 2300 2274 7108 2316 2257 7109 2299 2274 7110 2316 2258 7111 2300 2273 7112 2315 2257 7113 2299 2275 7114 2317 2259 7115 2301 2275 7116 2317 2257 7117 2299 2274 7118 2316 2259 7119 2301 2255 7120 2297 2256 7121 2298 2255 7122 2297 2259 7123 2301 2275 7124 2317 2273 7125 2315 2268 7126 2310 2274 7127 2316 2268 7128 2310 2273 7129 2315 2267 7130 2309 2274 7131 2316 2269 7132 2311 2275 7133 2317 2269 7134 2311 2274 7135 2316 2268 7136 2310 2275 7137 2317 2270 7138 2312 2255 7139 2297 2270 7140 2312 2275 7141 2317 2269 7142 2311 2316 7143 2358 2276 7144 2318 2317 7145 2359 2278 7146 2320 2276 7147 2318 2277 7148 2319 2278 7149 2320 2317 7150 2359 2276 7151 2318 2278 7152 2320 2318 7153 2360 2317 7154 2359 2279 7155 2321 2318 7156 2360 2278 7157 2320 2279 7158 2321 2319 7159 2361 2318 7160 2360 2280 7161 2322 2319 7162 2361 2279 7163 2321 2281 7164 2323 2319 7165 2361 2280 7166 2322 2282 7167 2324 2319 7168 2361 2281 7169 2323 2283 7170 2325 2319 7171 2361 2282 7172 2324 2283 7173 2325 2320 7174 2362 2319 7175 2361 2283 7176 2325 2321 7177 2363 2320 7178 2362 2284 7179 2326 2321 7180 2363 2283 7181 2325 2285 7182 2327 2321 7183 2363 2284 7184 2326 2285 7185 2327 2322 7186 2364 2321 7187 2363 2286 7188 2328 2322 7189 2364 2285 7190 2327 2286 7191 2328 2323 7192 2365 2322 7193 2364 2287 7194 2329 2323 7195 2365 2286 7196 2328 2287 7197 2329 2324 7198 2366 2323 7199 2365 2288 7200 2330 2324 7201 2366 2287 7202 2329 2288 7203 2330 2325 7204 2367 2324 7205 2366 2289 7206 2331 2325 7207 2367 2288 7208 2330 2289 7209 2331 2326 7210 2368 2325 7211 2367 2290 7212 2332 2326 7213 2368 2289 7214 2331 2290 7215 2332 2327 7216 2369 2326 7217 2368 2291 7218 2333 2327 7219 2369 2290 7220 2332 2291 7221 2333 2328 7222 2370 2327 7223 2369 2292 7224 2334 2328 7225 2370 2291 7226 2333 2292 7227 2334 2329 7228 2371 2328 7229 2370 2293 7230 2335 2329 7231 2371 2292 7232 2334 2293 7233 2335 2330 7234 2372 2329 7235 2371 2294 7236 2336 2330 7237 2372 2293 7238 2335 2294 7239 2336 2331 7240 2373 2330 7241 2372 2295 7242 2337 2331 7243 2373 2294 7244 2336 2295 7245 2337 2332 7246 2374 2331 7247 2373 2295 7248 2337 2333 7249 2375 2332 7250 2374 2296 7251 2338 2333 7252 2375 2295 7253 2337 2297 7254 2339 2333 7255 2375 2296 7256 2338 2298 7257 2340 2333 7258 2375 2297 7259 2339 2299 7260 2341 2333 7261 2375 2298 7262 2340 2299 7263 2341 2334 7264 2376 2333 7265 2375 2300 7266 2342 2334 7267 2376 2299 7268 2341 2300 7269 2342 2335 7270 2377 2334 7271 2376 2301 7272 2343 2335 7273 2377 2300 7274 2342 2302 7275 2344 2335 7276 2377 2301 7277 2343 2303 7278 2345 2335 7279 2377 2302 7280 2344 2303 7281 2345 2336 7282 2378 2335 7283 2377 2304 7284 2346 2336 7285 2378 2303 7286 2345 2304 7287 2346 2337 7288 2379 2336 7289 2378 2305 7290 2347 2337 7291 2379 2304 7292 2346 2305 7293 2347 2338 7294 2380 2337 7295 2379 2306 7296 2348 2338 7297 2380 2305 7298 2347 2306 7299 2348 2339 7300 2381 2338 7301 2380 2307 7302 2349 2339 7303 2381 2306 7304 2348 2307 7305 2349 2340 7306 2382 2339 7307 2381 2308 7308 2350 2340 7309 2382 2307 7310 2349 2308 7311 2350 2341 7312 2383 2340 7313 2382 2309 7314 2351 2341 7315 2383 2308 7316 2350 2309 7317 2351 2342 7318 2384 2341 7319 2383 2309 7320 2351 2343 7321 2385 2342 7322 2384 2310 7323 2352 2343 7324 2385 2309 7325 2351 2311 7326 2353 2343 7327 2385 2310 7328 2352 2311 7329 2353 2344 7330 2386 2343 7331 2385 2312 7332 2354 2344 7333 2386 2311 7334 2353 2312 7335 2354 2345 7336 2387 2344 7337 2386 2313 7338 2355 2345 7339 2387 2312 7340 2354 2313 7341 2355 2346 7342 2388 2345 7343 2387 2314 7344 2356 2346 7345 2388 2313 7346 2355 2314 7347 2356 2347 7348 2389 2346 7349 2388 2315 7350 2357 2347 7351 2389 2314 7352 2356 2315 7353 2357 2316 7354 2358 2347 7355 2389 2276 7356 2318 2316 7357 2358 2315 7358 2357 2317 7359 2359 2348 7360 2390 2316 7361 2358 2348 7362 2390 2317 7363 2359 2318 7364 2360 2316 7365 2358 2349 7366 2391 2347 7367 2389 2349 7368 2391 2316 7369 2358 2348 7370 2390 2347 7371 2389 2350 7372 2392 2346 7373 2388 2350 7374 2392 2347 7375 2389 2349 7376 2391 2318 7377 2360 2320 7378 2362 2348 7379 2390 2320 7380 2362 2318 7381 2360 2319 7382 2361 2348 7383 2390 2321 7384 2363 2349 7385 2391 2321 7386 2363 2348 7387 2390 2320 7388 2362 2349 7389 2391 2322 7390 2364 2350 7391 2392 2322 7392 2364 2349 7393 2391 2321 7394 2363 2346 7395 2388 2351 7396 2393 2345 7397 2387 2351 7398 2393 2346 7399 2388 2350 7400 2392 2345 7401 2387 2352 7402 2394 2344 7403 2386 2352 7404 2394 2345 7405 2387 2351 7406 2393 2344 7407 2386 2353 7408 2395 2343 7409 2385 2353 7410 2395 2344 7411 2386 2352 7412 2394 2343 7413 2385 2354 7414 2396 2342 7415 2384 2354 7416 2396 2343 7417 2385 2353 7418 2395 2350 7419 2392 2323 7420 2365 2351 7421 2393 2323 7422 2365 2350 7423 2392 2322 7424 2364 2351 7425 2393 2324 7426 2366 2352 7427 2394 2324 7428 2366 2351 7429 2393 2323 7430 2365 2352 7431 2394 2325 7432 2367 2353 7433 2395 2325 7434 2367 2352 7435 2394 2324 7436 2366 2353 7437 2395 2326 7438 2368 2354 7439 2396 2326 7440 2368 2353 7441 2395 2325 7442 2367 2342 7443 2384 2355 7444 2397 2341 7445 2383 2355 7446 2397 2342 7447 2384 2354 7448 2396 2341 7449 2383 2356 7450 2398 2340 7451 2382 2356 7452 2398 2341 7453 2383 2355 7454 2397 2340 7455 2382 2357 7456 2399 2339 7457 2381 2357 7458 2399 2340 7459 2382 2356 7460 2398 2339 7461 2381 2358 7462 2400 2338 7463 2380 2358 7464 2400 2339 7465 2381 2357 7466 2399 2354 7467 2396 2327 7468 2369 2355 7469 2397 2327 7470 2369 2354 7471 2396 2326 7472 2368 2355 7473 2397 2328 7474 2370 2356 7475 2398 2328 7476 2370 2355 7477 2397 2327 7478 2369 2356 7479 2398 2329 7480 2371 2357 7481 2399 2329 7482 2371 2356 7483 2398 2328 7484 2370 2357 7485 2399 2330 7486 2372 2358 7487 2400 2330 7488 2372 2357 7489 2399 2329 7490 2371 2338 7491 2380 2359 7492 2401 2337 7493 2379 2359 7494 2401 2338 7495 2380 2358 7496 2400 2337 7497 2379 2360 7498 2402 2336 7499 2378 2360 7500 2402 2337 7501 2379 2359 7502 2401 2336 7503 2378 2334 7504 2376 2335 7505 2377 2334 7506 2376 2336 7507 2378 2360 7508 2402 2358 7509 2400 2331 7510 2373 2359 7511 2401 2331 7512 2373 2358 7513 2400 2330 7514 2372 2359 7515 2401 2332 7516 2374 2360 7517 2402 2332 7518 2374 2359 7519 2401 2331 7520 2373 2360 7521 2402 2333 7522 2375 2334 7523 2376 2333 7524 2375 2360 7525 2402 2332 7526 2374 2369 7527 2411 2361 7528 2403 2362 7529 2404 2365 7530 2407 2363 7531 2405 2364 7532 2406 2367 7533 2409 2363 7534 2405 2365 7535 2407 2367 7536 2409 2366 7537 2408 2363 7538 2405 2368 7539 2410 2366 7540 2408 2367 7541 2409 2370 7542 2412 2366 7543 2408 2368 7544 2410 2370 7545 2412 2369 7546 2411 2366 7547 2408 2361 7548 2403 2369 7549 2411 2370 7550 2412 2379 7551 2421 2371 7552 2423 2372 7553 2414 2376 7554 2424 2373 7555 2415 2374 7556 2416 2376 7557 2425 2375 7558 2417 2373 7559 2415 2378 7560 2426 2375 7561 2417 2376 7562 2418 2378 7563 2427 2377 7564 2419 2375 7565 2417 2380 7566 2428 2377 7567 2419 2378 7568 2420 2380 7569 2429 2379 7570 2421 2377 7571 2419 2371 7572 2413 2379 7573 2421 2380 7574 2422 2421 7575 2470 2385 7576 2434 2422 7577 2471 2407 7578 2456 2381 7579 2430 2382 7580 2431 2389 7581 2438 2383 7582 2432 2384 7583 2433 2386 7584 2435 2422 7585 2471 2385 7586 2434 2387 7587 2436 2422 7588 2471 2386 7589 2435 2388 7590 2437 2422 7591 2471 2387 7592 2436 2388 7593 2437 2423 7594 2472 2422 7595 2471 2383 7596 2432 2423 7597 2472 2388 7598 2437 2383 7599 2432 2424 7600 2473 2423 7601 2472 2389 7602 2438 2424 7603 2473 2383 7604 2432 2390 7605 2439 2424 7606 2473 2389 7607 2438 2390 7608 2439 2425 7609 2474 2424 7610 2473 2391 7611 2440 2425 7612 2474 2390 7613 2439 2391 7614 2440 2426 7615 2475 2425 7616 2474 2392 7617 2441 2426 7618 2475 2391 7619 2440 2392 7620 2441 2427 7621 2476 2426 7622 2475 2393 7623 2442 2427 7624 2476 2392 7625 2441 2393 7626 2442 2428 7627 2477 2427 7628 2476 2394 7629 2443 2428 7630 2477 2393 7631 2442 2394 7632 2443 2429 7633 2478 2428 7634 2477 2395 7635 2444 2429 7636 2478 2394 7637 2443 2395 7638 2444 2430 7639 2479 2429 7640 2478 2396 7641 2445 2430 7642 2479 2395 7643 2444 2396 7644 2445 2431 7645 2480 2430 7646 2479 2397 7647 2446 2431 7648 2480 2396 7649 2445 2397 7650 2446 2432 7651 2481 2431 7652 2480 2398 7653 2447 2432 7654 2481 2397 7655 2446 2398 7656 2447 2433 7657 2482 2432 7658 2481 2399 7659 2448 2433 7660 2482 2398 7661 2447 2399 7662 2448 2434 7663 2483 2433 7664 2482 2400 7665 2449 2434 7666 2483 2399 7667 2448 2400 7668 2449 2435 7669 2484 2434 7670 2483 2401 7671 2450 2435 7672 2484 2400 7673 2449 2401 7674 2450 2436 7675 2485 2435 7676 2484 2402 7677 2451 2436 7678 2485 2401 7679 2450 2402 7680 2451 2437 7681 2486 2436 7682 2485 2403 7683 2452 2437 7684 2486 2402 7685 2451 2403 7686 2452 2438 7687 2487 2437 7688 2486 2404 7689 2453 2438 7690 2487 2403 7691 2452 2405 7692 2454 2438 7693 2487 2404 7694 2453 2406 7695 2455 2438 7696 2487 2405 7697 2454 2406 7698 2455 2439 7699 2488 2438 7700 2487 2381 7701 2430 2439 7702 2488 2406 7703 2455 2381 7704 2430 2440 7705 2489 2439 7706 2488 2407 7707 2456 2440 7708 2489 2381 7709 2430 2408 7710 2457 2440 7711 2489 2407 7712 2456 2408 7713 2457 2441 7714 2490 2440 7715 2489 2409 7716 2458 2441 7717 2490 2408 7718 2457 2409 7719 2458 2442 7720 2491 2441 7721 2490 2410 7722 2459 2442 7723 2491 2409 7724 2458 2410 7725 2459 2443 7726 2492 2442 7727 2491 2411 7728 2460 2443 7729 2492 2410 7730 2459 2411 7731 2460 2444 7732 2493 2443 7733 2492 2412 7734 2461 2444 7735 2493 2411 7736 2460 2412 7737 2461 2445 7738 2494 2444 7739 2493 2413 7740 2462 2445 7741 2494 2412 7742 2461 2413 7743 2462 2446 7744 2495 2445 7745 2494 2414 7746 2463 2446 7747 2495 2413 7748 2462 2414 7749 2463 2447 7750 2496 2446 7751 2495 2415 7752 2464 2447 7753 2496 2414 7754 2463 2415 7755 2464 2448 7756 2497 2447 7757 2496 2416 7758 2465 2448 7759 2497 2415 7760 2464 2416 7761 2465 2449 7762 2498 2448 7763 2497 2417 7764 2466 2449 7765 2498 2416 7766 2465 2417 7767 2466 2450 7768 2499 2449 7769 2498 2418 7770 2467 2450 7771 2499 2417 7772 2466 2418 7773 2467 2451 7774 2500 2450 7775 2499 2419 7776 2468 2451 7777 2500 2418 7778 2467 2419 7779 2468 2452 7780 2501 2451 7781 2500 2420 7782 2469 2452 7783 2501 2419 7784 2468 2420 7785 2469 2421 7786 2470 2452 7787 2501 2385 7788 2434 2421 7789 2470 2420 7790 2469 2440 7791 2489 2453 7792 2502 2439 7793 2488 2453 7794 2502 2440 7795 2489 2441 7796 2490 2439 7797 2488 2437 7798 2486 2438 7799 2487 2437 7800 2486 2439 7801 2488 2453 7802 2502 2441 7803 2490 2454 7804 2503 2453 7805 2502 2454 7806 2503 2441 7807 2490 2442 7808 2491 2453 7809 2502 2436 7810 2485 2437 7811 2486 2436 7812 2485 2453 7813 2502 2454 7814 2503 2442 7815 2491 2455 7816 2504 2454 7817 2503 2455 7818 2504 2442 7819 2491 2443 7820 2492 2454 7821 2503 2435 7822 2484 2436 7823 2485 2435 7824 2484 2454 7825 2503 2455 7826 2504 2443 7827 2492 2456 7828 2505 2455 7829 2504 2456 7830 2505 2443 7831 2492 2444 7832 2493 2455 7833 2504 2434 7834 2483 2435 7835 2484 2434 7836 2483 2455 7837 2504 2456 7838 2505 2444 7839 2493 2457 7840 2506 2456 7841 2505 2457 7842 2506 2444 7843 2493 2445 7844 2494 2456 7845 2505 2433 7846 2482 2434 7847 2483 2433 7848 2482 2456 7849 2505 2457 7850 2506 2445 7851 2494 2458 7852 2507 2457 7853 2506 2458 7854 2507 2445 7855 2494 2446 7856 2495 2446 7857 2495 2459 7858 2508 2458 7859 2507 2459 7860 2508 2446 7861 2495 2447 7862 2496 2457 7863 2506 2432 7864 2481 2433 7865 2482 2432 7866 2481 2457 7867 2506 2458 7868 2507 2458 7869 2507 2431 7870 2480 2432 7871 2481 2431 7872 2480 2458 7873 2507 2459 7874 2508 2447 7875 2496 2460 7876 2509 2459 7877 2508 2460 7878 2509 2447 7879 2496 2448 7880 2497 2448 7881 2497 2461 7882 2510 2460 7883 2509 2461 7884 2510 2448 7885 2497 2449 7886 2498 2459 7887 2508 2430 7888 2479 2431 7889 2480 2430 7890 2479 2459 7891 2508 2460 7892 2509 2460 7893 2509 2429 7894 2478 2430 7895 2479 2429 7896 2478 2460 7897 2509 2461 7898 2510 2449 7899 2498 2462 7900 2511 2461 7901 2510 2462 7902 2511 2449 7903 2498 2450 7904 2499 2461 7905 2510 2428 7906 2477 2429 7907 2478 2428 7908 2477 2461 7909 2510 2462 7910 2511 2450 7911 2499 2463 7912 2512 2462 7913 2511 2463 7914 2512 2450 7915 2499 2451 7916 2500 2462 7917 2511 2427 7918 2476 2428 7919 2477 2427 7920 2476 2462 7921 2511 2463 7922 2512 2451 7923 2500 2464 7924 2513 2463 7925 2512 2464 7926 2513 2451 7927 2500 2452 7928 2501 2463 7929 2512 2426 7930 2475 2427 7931 2476 2426 7932 2475 2463 7933 2512 2464 7934 2513 2452 7935 2501 2465 7936 2514 2464 7937 2513 2465 7938 2514 2452 7939 2501 2421 7940 2470 2464 7941 2513 2425 7942 2474 2426 7943 2475 2425 7944 2474 2464 7945 2513 2465 7946 2514 2421 7947 2470 2423 7948 2472 2465 7949 2514 2423 7950 2472 2421 7951 2470 2422 7952 2471 2465 7953 2514 2424 7954 2473 2425 7955 2474 2424 7956 2473 2465 7957 2514 2423 7958 2472 2494 7959 2543 2469 7960 2518 2495 7961 2544 2496 7962 2545 2466 7963 2515 2474 7964 2523 2497 7965 2546 2466 7966 2515 2496 7967 2545 2497 7968 2546 2467 7969 2516 2466 7970 2515 2498 7971 2547 2467 7972 2516 2497 7973 2546 2498 7974 2547 2468 7975 2517 2467 7976 2516 2495 7977 2544 2468 7978 2517 2498 7979 2547 2495 7980 2544 2469 7981 2518 2468 7982 2517 2469 7983 2518 2470 7984 2519 2471 7985 2520 2486 7986 2535 2472 7987 2521 2473 7988 2522 2474 7989 2523 2499 7990 2548 2496 7991 2545 2475 7992 2524 2499 7993 2548 2474 7994 2523 2476 7995 2525 2499 7996 2548 2475 7997 2524 2476 7998 2525 2500 7999 2549 2499 8000 2548 2477 8001 2526 2500 8002 2549 2476 8003 2525 2477 8004 2526 2501 8005 2550 2500 8006 2549 2483 8007 2532 2501 8008 2550 2477 8009 2526 2486 8010 2535 2478 8011 2527 2472 8012 2521 2469 8013 2518 2479 8014 2528 2470 8015 2519 2482 8016 2531 2480 8017 2529 2481 8018 2530 2479 8019 2528 2480 8020 2529 2482 8021 2531 2485 8022 2534 2483 8023 2532 2484 8024 2533 2478 8025 2527 2483 8026 2532 2485 8027 2534 2483 8028 2532 2502 8029 2551 2501 8030 2550 2478 8031 2527 2502 8032 2551 2483 8033 2532 2486 8034 2535 2502 8035 2551 2478 8036 2527 2486 8037 2535 2503 8038 2552 2502 8039 2551 2487 8040 2536 2503 8041 2552 2486 8042 2535 2487 8043 2536 2504 8044 2553 2503 8045 2552 2488 8046 2537 2504 8047 2553 2487 8048 2536 2488 8049 2537 2505 8050 2554 2504 8051 2553 2489 8052 2538 2505 8053 2554 2488 8054 2537 2489 8055 2538 2506 8056 2555 2505 8057 2554 2490 8058 2539 2506 8059 2555 2489 8060 2538 2491 8061 2540 2506 8062 2555 2490 8063 2539 2491 8064 2540 2507 8065 2556 2506 8066 2555 2492 8067 2541 2507 8068 2556 2491 8069 2540 2492 8070 2541 2508 8071 2557 2507 8072 2556 2493 8073 2542 2508 8074 2557 2492 8075 2541 2493 8076 2542 2509 8077 2558 2508 8078 2557 2480 8079 2529 2509 8080 2558 2493 8081 2542 2480 8082 2529 2494 8083 2543 2509 8084 2558 2479 8085 2528 2494 8086 2543 2480 8087 2529 2469 8088 2518 2494 8089 2543 2479 8090 2528 2503 8091 2552 2510 8092 2559 2502 8093 2551 2510 8094 2559 2503 8095 2552 2504 8096 2553 2502 8097 2551 2500 8098 2549 2501 8099 2550 2500 8100 2549 2502 8101 2551 2510 8102 2559 2504 8103 2553 2511 8104 2560 2510 8105 2559 2511 8106 2560 2504 8107 2553 2505 8108 2554 2505 8109 2554 2512 8110 2561 2511 8111 2560 2512 8112 2561 2505 8113 2554 2506 8114 2555 2510 8115 2559 2499 8116 2548 2500 8117 2549 2499 8118 2548 2510 8119 2559 2511 8120 2560 2511 8121 2560 2496 8122 2545 2499 8123 2548 2496 8124 2545 2511 8125 2560 2512 8126 2561 2506 8127 2555 2513 8128 2562 2512 8129 2561 2513 8130 2562 2506 8131 2555 2507 8132 2556 2507 8133 2556 2514 8134 2563 2513 8135 2562 2514 8136 2563 2507 8137 2556 2508 8138 2557 2512 8139 2561 2497 8140 2546 2496 8141 2545 2497 8142 2546 2512 8143 2561 2513 8144 2562 2513 8145 2562 2498 8146 2547 2497 8147 2546 2498 8148 2547 2513 8149 2562 2514 8150 2563 2508 8151 2557 2494 8152 2543 2514 8153 2563 2494 8154 2543 2508 8155 2557 2509 8156 2558 2514 8157 2563 2495 8158 2544 2498 8159 2547 2495 8160 2544 2514 8161 2563 2494 8162 2543 2523 8163 2572 2522 8164 2571 2515 8165 2564 2519 8166 2568 2516 8167 2565 2517 8168 2566 2519 8169 2568 2518 8170 2567 2516 8171 2565 2521 8172 2570 2518 8173 2567 2519 8174 2568 2521 8175 2570 2520 8176 2569 2518 8177 2567 2515 8178 2564 2520 8179 2569 2521 8180 2570 2515 8181 2564 2522 8182 2571 2520 8183 2569 2522 8184 2571 2523 8185 2572 2524 8186 2573 2537 8187 2588 2526 8188 2575 2525 8189 2589 2528 8190 2590 2526 8191 2575 2527 8192 2576 2525 8193 2574 2526 8194 2575 2528 8195 2577 2531 8196 2580 2529 8197 2591 2530 8198 2579 2532 8199 2581 2529 8200 2592 2531 8201 2580 2534 8202 2583 2529 8203 2593 2532 8204 2581 2534 8205 2583 2533 8206 2594 2529 8207 2578 2536 8208 2585 2533 8209 2595 2534 8210 2583 2536 8211 2585 2535 8212 2596 2533 8213 2582 2538 8214 2587 2535 8215 2597 2536 8216 2585 2538 8217 2587 2537 8218 2598 2535 8219 2584 2526 8220 2575 2537 8221 2586 2538 8222 2587 2545 8223 2605 2569 8224 2629 2539 8225 2599 2570 8226 2630 2539 8227 2599 2569 8228 2629 2570 8229 2630 2540 8230 2600 2539 8231 2599 2571 8232 2631 2540 8233 2600 2570 8234 2630 2571 8235 2631 2541 8236 2601 2540 8237 2600 2571 8238 2631 2542 8239 2602 2541 8240 2601 2572 8241 2632 2542 8242 2602 2571 8243 2631 2564 8244 2624 2543 8245 2603 2544 8246 2604 2568 8247 2628 2545 8248 2605 2546 8249 2606 2573 8250 2633 2542 8251 2602 2572 8252 2632 2573 8253 2633 2547 8254 2607 2542 8255 2602 2573 8256 2633 2548 8257 2608 2547 8258 2607 2574 8259 2634 2548 8260 2608 2573 8261 2633 2574 8262 2634 2549 8263 2609 2548 8264 2608 2574 8265 2634 2550 8266 2610 2549 8267 2609 2575 8268 2635 2550 8269 2610 2574 8270 2634 2575 8271 2635 2551 8272 2611 2550 8273 2610 2576 8274 2636 2551 8275 2611 2575 8276 2635 2576 8277 2636 2552 8278 2612 2551 8279 2611 2577 8280 2637 2552 8281 2612 2576 8282 2636 2577 8283 2637 2553 8284 2613 2552 8285 2612 2578 8286 2638 2553 8287 2613 2577 8288 2637 2578 8289 2638 2554 8290 2614 2553 8291 2613 2578 8292 2638 2555 8293 2615 2554 8294 2614 2578 8295 2638 2556 8296 2616 2555 8297 2615 2578 8298 2638 2557 8299 2617 2556 8300 2616 2579 8301 2639 2557 8302 2617 2578 8303 2638 2579 8304 2639 2558 8305 2618 2557 8306 2617 2580 8307 2640 2558 8308 2618 2579 8309 2639 2580 8310 2640 2559 8311 2619 2558 8312 2618 2581 8313 2641 2559 8314 2619 2580 8315 2640 2581 8316 2641 2560 8317 2620 2559 8318 2619 2581 8319 2641 2561 8320 2621 2560 8321 2620 2582 8322 2642 2561 8323 2621 2581 8324 2641 2582 8325 2642 2562 8326 2622 2561 8327 2621 2583 8328 2643 2562 8329 2622 2582 8330 2642 2583 8331 2643 2563 8332 2623 2562 8333 2622 2584 8334 2644 2563 8335 2623 2583 8336 2643 2584 8337 2644 2564 8338 2624 2563 8339 2623 2584 8340 2644 2543 8341 2603 2564 8342 2624 2585 8343 2645 2543 8344 2603 2584 8345 2644 2585 8346 2645 2565 8347 2625 2543 8348 2603 2586 8349 2646 2565 8350 2625 2585 8351 2645 2586 8352 2646 2566 8353 2626 2565 8354 2625 2587 8355 2647 2566 8356 2626 2586 8357 2646 2587 8358 2647 2567 8359 2627 2566 8360 2626 2588 8361 2648 2567 8362 2627 2587 8363 2647 2588 8364 2648 2568 8365 2628 2567 8366 2627 2588 8367 2648 2545 8368 2605 2568 8369 2628 2569 8370 2629 2545 8371 2605 2588 8372 2648 2584 8373 2644 2589 8374 2649 2585 8375 2645 2589 8376 2649 2584 8377 2644 2583 8378 2643 2585 8379 2645 2590 8380 2650 2586 8381 2646 2590 8382 2650 2585 8383 2645 2589 8384 2649 2586 8385 2646 2591 8386 2651 2587 8387 2647 2591 8388 2651 2586 8389 2646 2590 8390 2650 2587 8391 2647 2569 8392 2629 2588 8393 2648 2569 8394 2629 2587 8395 2647 2591 8396 2651 2583 8397 2643 2592 8398 2652 2589 8399 2649 2592 8400 2652 2583 8401 2643 2582 8402 2642 2589 8403 2649 2593 8404 2653 2590 8405 2650 2593 8406 2653 2589 8407 2649 2592 8408 2652 2590 8409 2650 2594 8410 2654 2591 8411 2651 2594 8412 2654 2590 8413 2650 2593 8414 2653 2591 8415 2651 2570 8416 2630 2569 8417 2629 2570 8418 2630 2591 8419 2651 2594 8420 2654 2582 8421 2642 2595 8422 2655 2592 8423 2652 2595 8424 2655 2582 8425 2642 2581 8426 2641 2592 8427 2652 2596 8428 2656 2593 8429 2653 2596 8430 2656 2592 8431 2652 2595 8432 2655 2593 8433 2653 2597 8434 2657 2594 8435 2654 2597 8436 2657 2593 8437 2653 2596 8438 2656 2594 8439 2654 2571 8440 2631 2570 8441 2630 2571 8442 2631 2594 8443 2654 2597 8444 2657 2581 8445 2641 2598 8446 2658 2595 8447 2655 2598 8448 2658 2581 8449 2641 2580 8450 2640 2595 8451 2655 2599 8452 2659 2596 8453 2656 2599 8454 2659 2595 8455 2655 2598 8456 2658 2596 8457 2656 2600 8458 2660 2597 8459 2657 2600 8460 2660 2596 8461 2656 2599 8462 2659 2597 8463 2657 2572 8464 2632 2571 8465 2631 2572 8466 2632 2597 8467 2657 2600 8468 2660 2580 8469 2640 2601 8470 2661 2598 8471 2658 2601 8472 2661 2580 8473 2640 2579 8474 2639 2598 8475 2658 2602 8476 2662 2599 8477 2659 2602 8478 2662 2598 8479 2658 2601 8480 2661 2599 8481 2659 2603 8482 2663 2600 8483 2660 2603 8484 2663 2599 8485 2659 2602 8486 2662 2600 8487 2660 2573 8488 2633 2572 8489 2632 2573 8490 2633 2600 8491 2660 2603 8492 2663 2579 8493 2639 2577 8494 2637 2601 8495 2661 2577 8496 2637 2579 8497 2639 2578 8498 2638 2601 8499 2661 2576 8500 2636 2602 8501 2662 2576 8502 2636 2601 8503 2661 2577 8504 2637 2602 8505 2662 2575 8506 2635 2603 8507 2663 2575 8508 2635 2602 8509 2662 2576 8510 2636 2603 8511 2663 2574 8512 2634 2573 8513 2633 2574 8514 2634 2603 8515 2663 2575 8516 2635 2647 8517 2707 2604 8518 2664 2605 8519 2665 2648 8520 2708 2604 8521 2664 2649 8522 2709 2648 8523 2708 2606 8524 2666 2604 8525 2664 2650 8526 2710 2606 8527 2666 2648 8528 2708 2650 8529 2710 2607 8530 2667 2606 8531 2666 2651 8532 2711 2607 8533 2667 2650 8534 2710 2651 8535 2711 2608 8536 2668 2607 8537 2667 2652 8538 2712 2608 8539 2668 2651 8540 2711 2652 8541 2712 2609 8542 2669 2608 8543 2668 2653 8544 2713 2609 8545 2669 2652 8546 2712 2653 8547 2713 2610 8548 2670 2609 8549 2669 2654 8550 2714 2610 8551 2670 2653 8552 2713 2654 8553 2714 2611 8554 2671 2610 8555 2670 2654 8556 2714 2612 8557 2672 2611 8558 2671 2655 8559 2715 2612 8560 2672 2654 8561 2714 2655 8562 2715 2613 8563 2673 2612 8564 2672 2656 8565 2716 2613 8566 2673 2655 8567 2715 2657 8568 2717 2613 8569 2673 2656 8570 2716 2657 8571 2717 2614 8572 2674 2613 8573 2673 2658 8574 2718 2614 8575 2674 2657 8576 2717 2658 8577 2718 2615 8578 2675 2614 8579 2674 2659 8580 2719 2615 8581 2675 2658 8582 2718 2659 8583 2719 2616 8584 2676 2615 8585 2675 2660 8586 2720 2616 8587 2676 2659 8588 2719 2660 8589 2720 2617 8590 2677 2616 8591 2676 2661 8592 2721 2617 8593 2677 2660 8594 2720 2661 8595 2721 2618 8596 2678 2617 8597 2677 2662 8598 2722 2618 8599 2678 2661 8600 2721 2662 8601 2722 2619 8602 2679 2618 8603 2678 2662 8604 2722 2620 8605 2680 2619 8606 2679 2662 8607 2722 2621 8608 2681 2620 8609 2680 2663 8610 2723 2621 8611 2681 2662 8612 2722 2663 8613 2723 2622 8614 2682 2621 8615 2681 2664 8616 2724 2622 8617 2682 2663 8618 2723 2664 8619 2724 2623 8620 2683 2622 8621 2682 2665 8622 2725 2623 8623 2683 2664 8624 2724 2665 8625 2725 2624 8626 2684 2623 8627 2683 2666 8628 2726 2624 8629 2684 2665 8630 2725 2666 8631 2726 2625 8632 2685 2624 8633 2684 2666 8634 2726 2626 8635 2686 2625 8636 2685 2666 8637 2726 2627 8638 2687 2626 8639 2686 2667 8640 2727 2627 8641 2687 2666 8642 2726 2667 8643 2727 2628 8644 2688 2627 8645 2687 2668 8646 2728 2628 8647 2688 2667 8648 2727 2668 8649 2728 2629 8650 2689 2628 8651 2688 2668 8652 2728 2630 8653 2690 2629 8654 2689 2669 8655 2729 2630 8656 2690 2668 8657 2728 2670 8658 2730 2630 8659 2690 2669 8660 2729 2670 8661 2730 2631 8662 2691 2630 8663 2690 2671 8664 2731 2631 8665 2691 2670 8666 2730 2671 8667 2731 2632 8668 2692 2631 8669 2691 2672 8670 2732 2632 8671 2692 2671 8672 2731 2672 8673 2732 2633 8674 2693 2632 8675 2692 2673 8676 2733 2633 8677 2693 2672 8678 2732 2673 8679 2733 2634 8680 2694 2633 8681 2693 2674 8682 2734 2634 8683 2694 2673 8684 2733 2674 8685 2734 2635 8686 2695 2634 8687 2694 2675 8688 2735 2635 8689 2695 2674 8690 2734 2675 8691 2735 2636 8692 2696 2635 8693 2695 2676 8694 2736 2636 8695 2696 2675 8696 2735 2676 8697 2736 2637 8698 2697 2636 8699 2696 2676 8700 2736 2638 8701 2698 2637 8702 2697 2677 8703 2737 2638 8704 2698 2676 8705 2736 2678 8706 2738 2638 8707 2698 2677 8708 2737 2678 8709 2738 2639 8710 2699 2638 8711 2698 2679 8712 2739 2639 8713 2699 2678 8714 2738 2679 8715 2739 2640 8716 2700 2639 8717 2699 2680 8718 2740 2640 8719 2700 2679 8720 2739 2680 8721 2740 2641 8722 2701 2640 8723 2700 2680 8724 2740 2642 8725 2702 2641 8726 2701 2680 8727 2740 2643 8728 2703 2642 8729 2702 2681 8730 2741 2643 8731 2703 2680 8732 2740 2681 8733 2741 2644 8734 2704 2643 8735 2703 2682 8736 2742 2644 8737 2704 2681 8738 2741 2682 8739 2742 2645 8740 2705 2644 8741 2704 2683 8742 2743 2645 8743 2705 2682 8744 2742 2683 8745 2743 2646 8746 2706 2645 8747 2705 2649 8748 2709 2646 8749 2706 2683 8750 2743 2649 8751 2709 2647 8752 2707 2646 8753 2706 2604 8754 2664 2647 8755 2707 2649 8756 2709 2680 8757 2740 2684 8758 2744 2681 8759 2741 2684 8760 2744 2680 8761 2740 2679 8762 2739 2681 8763 2741 2685 8764 2745 2682 8765 2742 2685 8766 2745 2681 8767 2741 2684 8768 2744 2682 8769 2742 2686 8770 2746 2683 8771 2743 2686 8772 2746 2682 8773 2742 2685 8774 2745 2683 8775 2743 2648 8776 2708 2649 8777 2709 2648 8778 2708 2683 8779 2743 2686 8780 2746 2679 8781 2739 2687 8782 2747 2684 8783 2744 2687 8784 2747 2679 8785 2739 2678 8786 2738 2684 8787 2744 2688 8788 2748 2685 8789 2745 2688 8790 2748 2684 8791 2744 2687 8792 2747 2685 8793 2745 2689 8794 2749 2686 8795 2746 2689 8796 2749 2685 8797 2745 2688 8798 2748 2686 8799 2746 2650 8800 2710 2648 8801 2708 2650 8802 2710 2686 8803 2746 2689 8804 2749 2678 8805 2738 2690 8806 2750 2687 8807 2747 2690 8808 2750 2678 8809 2738 2677 8810 2737 2687 8811 2747 2691 8812 2751 2688 8813 2748 2691 8814 2751 2687 8815 2747 2690 8816 2750 2688 8817 2748 2692 8818 2752 2689 8819 2749 2692 8820 2752 2688 8821 2748 2691 8822 2751 2689 8823 2749 2651 8824 2711 2650 8825 2710 2651 8826 2711 2689 8827 2749 2692 8828 2752 2677 8829 2737 2693 8830 2753 2690 8831 2750 2693 8832 2753 2677 8833 2737 2676 8834 2736 2690 8835 2750 2694 8836 2754 2691 8837 2751 2694 8838 2754 2690 8839 2750 2693 8840 2753 2691 8841 2751 2695 8842 2755 2692 8843 2752 2695 8844 2755 2691 8845 2751 2694 8846 2754 2692 8847 2752 2652 8848 2712 2651 8849 2711 2652 8850 2712 2692 8851 2752 2695 8852 2755 2676 8853 2736 2696 8854 2756 2693 8855 2753 2696 8856 2756 2676 8857 2736 2675 8858 2735 2693 8859 2753 2697 8860 2757 2694 8861 2754 2697 8862 2757 2693 8863 2753 2696 8864 2756 2694 8865 2754 2698 8866 2758 2695 8867 2755 2698 8868 2758 2694 8869 2754 2697 8870 2757 2695 8871 2755 2653 8872 2713 2652 8873 2712 2653 8874 2713 2695 8875 2755 2698 8876 2758 2675 8877 2735 2699 8878 2759 2696 8879 2756 2699 8880 2759 2675 8881 2735 2674 8882 2734 2696 8883 2756 2700 8884 2760 2697 8885 2757 2700 8886 2760 2696 8887 2756 2699 8888 2759 2697 8889 2757 2701 8890 2761 2698 8891 2758 2701 8892 2761 2697 8893 2757 2700 8894 2760 2698 8895 2758 2654 8896 2714 2653 8897 2713 2654 8898 2714 2698 8899 2758 2701 8900 2761 2674 8901 2734 2702 8902 2762 2699 8903 2759 2702 8904 2762 2674 8905 2734 2673 8906 2733 2699 8907 2759 2703 8908 2763 2700 8909 2760 2703 8910 2763 2699 8911 2759 2702 8912 2762 2700 8913 2760 2704 8914 2764 2701 8915 2761 2704 8916 2764 2700 8917 2760 2703 8918 2763 2701 8919 2761 2655 8920 2715 2654 8921 2714 2655 8922 2715 2701 8923 2761 2704 8924 2764 2673 8925 2733 2705 8926 2765 2702 8927 2762 2705 8928 2765 2673 8929 2733 2672 8930 2732 2702 8931 2762 2706 8932 2766 2703 8933 2763 2706 8934 2766 2702 8935 2762 2705 8936 2765 2703 8937 2763 2707 8938 2767 2704 8939 2764 2707 8940 2767 2703 8941 2763 2706 8942 2766 2704 8943 2764 2656 8944 2716 2655 8945 2715 2656 8946 2716 2704 8947 2764 2707 8948 2767 2672 8949 2732 2708 8950 2768 2705 8951 2765 2708 8952 2768 2672 8953 2732 2671 8954 2731 2705 8955 2765 2709 8956 2769 2706 8957 2766 2709 8958 2769 2705 8959 2765 2708 8960 2768 2706 8961 2766 2710 8962 2770 2707 8963 2767 2710 8964 2770 2706 8965 2766 2709 8966 2769 2707 8967 2767 2657 8968 2717 2656 8969 2716 2657 8970 2717 2707 8971 2767 2710 8972 2770 2671 8973 2731 2711 8974 2771 2708 8975 2768 2711 8976 2771 2671 8977 2731 2670 8978 2730 2708 8979 2768 2712 8980 2772 2709 8981 2769 2712 8982 2772 2708 8983 2768 2711 8984 2771 2709 8985 2769 2713 8986 2773 2710 8987 2770 2713 8988 2773 2709 8989 2769 2712 8990 2772 2710 8991 2770 2658 8992 2718 2657 8993 2717 2658 8994 2718 2710 8995 2770 2713 8996 2773 2670 8997 2730 2714 8998 2774 2711 8999 2771 2714 9000 2774 2670 9001 2730 2669 9002 2729 2711 9003 2771 2715 9004 2775 2712 9005 2772 2715 9006 2775 2711 9007 2771 2714 9008 2774 2712 9009 2772 2716 9010 2776 2713 9011 2773 2716 9012 2776 2712 9013 2772 2715 9014 2775 2713 9015 2773 2659 9016 2719 2658 9017 2718 2659 9018 2719 2713 9019 2773 2716 9020 2776 2669 9021 2729 2717 9022 2777 2714 9023 2774 2717 9024 2777 2669 9025 2729 2668 9026 2728 2714 9027 2774 2718 9028 2778 2715 9029 2775 2718 9030 2778 2714 9031 2774 2717 9032 2777 2715 9033 2775 2719 9034 2779 2716 9035 2776 2719 9036 2779 2715 9037 2775 2718 9038 2778 2716 9039 2776 2660 9040 2720 2659 9041 2719 2660 9042 2720 2716 9043 2776 2719 9044 2779 2668 9045 2728 2720 9046 2780 2717 9047 2777 2720 9048 2780 2668 9049 2728 2667 9050 2727 2717 9051 2777 2721 9052 2781 2718 9053 2778 2721 9054 2781 2717 9055 2777 2720 9056 2780 2718 9057 2778 2722 9058 2782 2719 9059 2779 2722 9060 2782 2718 9061 2778 2721 9062 2781 2719 9063 2779 2661 9064 2721 2660 9065 2720 2661 9066 2721 2719 9067 2779 2722 9068 2782 2667 9069 2727 2665 9070 2725 2720 9071 2780 2665 9072 2725 2667 9073 2727 2666 9074 2726 2720 9075 2780 2664 9076 2724 2721 9077 2781 2664 9078 2724 2720 9079 2780 2665 9080 2725 2721 9081 2781 2663 9082 2723 2722 9083 2782 2663 9084 2723 2721 9085 2781 2664 9086 2724 2722 9087 2782 2662 9088 2722 2661 9089 2721 2662 9090 2722 2722 9091 2782 2663 9092 2723 2735 9093 2795 2723 9094 2783 2724 9095 2784 2728 9096 2788 2725 9097 2785 2726 9098 2786 2728 9099 2788 2727 9100 2787 2725 9101 2785 2730 9102 2790 2727 9103 2787 2728 9104 2788 2730 9105 2790 2729 9106 2789 2727 9107 2787 2732 9108 2792 2729 9109 2789 2730 9110 2790 2732 9111 2792 2731 9112 2791 2729 9113 2789 2734 9114 2794 2731 9115 2791 2732 9116 2792 2734 9117 2794 2733 9118 2793 2731 9119 2791 2736 9120 2796 2733 9121 2793 2734 9122 2794 2736 9123 2796 2735 9124 2795 2733 9125 2793 2723 9126 2783 2735 9127 2795 2736 9128 2796 2754 9129 2814 2737 9130 2797 2738 9131 2798 2741 9132 2801 2739 9133 2799 2740 9134 2800 2737 9135 2815 2739 9136 2799 2741 9137 2801 2737 9138 2816 2742 9139 2802 2739 9140 2799 2737 9141 2817 2743 9142 2803 2742 9143 2802 2737 9144 2818 2744 9145 2804 2743 9146 2803 2737 9147 2819 2745 9148 2805 2744 9149 2804 2737 9150 2820 2746 9151 2806 2745 9152 2805 2737 9153 2821 2747 9154 2807 2746 9155 2806 2737 9156 2822 2748 9157 2823 2747 9158 2807 2737 9159 2797 2749 9160 2809 2748 9161 2808 2737 9162 2797 2750 9163 2810 2749 9164 2809 2737 9165 2797 2751 9166 2811 2750 9167 2810 2737 9168 2797 2752 9169 2812 2751 9170 2811 2737 9171 2797 2753 9172 2813 2752 9173 2812 2737 9174 2797 2754 9175 2814 2753 9176 2813 2773 9177 2842 2755 9178 2824 2756 9179 2825 2759 9180 2828 2757 9181 2826 2758 9182 2827 2760 9183 2829 2757 9184 2826 2759 9185 2828 2762 9186 2831 2757 9187 2826 2760 9188 2829 2762 9189 2831 2761 9190 2830 2757 9191 2826 2764 9192 2833 2761 9193 2830 2762 9194 2831 2764 9195 2833 2763 9196 2832 2761 9197 2830 2766 9198 2835 2763 9199 2832 2764 9200 2833 2766 9201 2835 2765 9202 2834 2763 9203 2832 2768 9204 2837 2765 9205 2834 2766 9206 2835 2768 9207 2837 2767 9208 2836 2765 9209 2834 2770 9210 2839 2767 9211 2836 2768 9212 2837 2770 9213 2839 2769 9214 2838 2767 9215 2836 2772 9216 2841 2769 9217 2838 2770 9218 2839 2772 9219 2841 2771 9220 2840 2769 9221 2838 2755 9222 2824 2771 9223 2840 2772 9224 2841 2771 9225 2840 2773 9226 2842 2774 9227 2843 2755 9228 2824 2773 9229 2842 2771 9230 2840 2779 9231 2848 2775 9232 2844 2776 9233 2845 2780 9234 2849 2777 9235 2846 2778 9236 2847 2780 9237 2849 2779 9238 2848 2777 9239 2846 2781 9240 2850 2779 9241 2848 2780 9242 2849 2782 9243 2851 2779 9244 2848 2781 9245 2850 2783 9246 2852 2779 9247 2848 2782 9248 2851 2784 9249 2853 2779 9250 2848 2783 9251 2852 2785 9252 2854 2779 9253 2848 2784 9254 2853 2786 9255 2855 2779 9256 2848 2785 9257 2854 2787 9258 2856 2779 9259 2848 2786 9260 2855 2788 9261 2857 2779 9262 2848 2787 9263 2856 2789 9264 2858 2779 9265 2848 2788 9266 2857 2790 9267 2859 2779 9268 2848 2789 9269 2858 2791 9270 2860 2779 9271 2848 2790 9272 2859 2792 9273 2861 2779 9274 2848 2791 9275 2860 2793 9276 2862 2779 9277 2848 2792 9278 2861 2794 9279 2863 2779 9280 2848 2793 9281 2862 2795 9282 2864 2779 9283 2848 2794 9284 2863 2796 9285 2865 2779 9286 2848 2795 9287 2864 2797 9288 2866 2779 9289 2848 2796 9290 2865 2798 9291 2867 2779 9292 2848 2797 9293 2866 2799 9294 2868 2779 9295 2848 2798 9296 2867 2800 9297 2869 2779 9298 2848 2799 9299 2868 2775 9300 2844 2779 9301 2848 2800 9302 2869 2840 9303 2909 2801 9304 2870 2802 9305 2871 2807 9306 2876 2803 9307 2872 2804 9308 2873 2807 9309 2876 2805 9310 2874 2803 9311 2872 2807 9312 2876 2806 9313 2875 2805 9314 2874 2809 9315 2878 2806 9316 2875 2807 9317 2876 2809 9318 2878 2808 9319 2877 2806 9320 2875 2811 9321 2880 2808 9322 2877 2809 9323 2878 2811 9324 2880 2810 9325 2879 2808 9326 2877 2812 9327 2881 2810 9328 2879 2811 9329 2880 2814 9330 2883 2810 9331 2879 2812 9332 2881 2814 9333 2883 2813 9334 2882 2810 9335 2879 2816 9336 2885 2813 9337 2882 2814 9338 2883 2816 9339 2885 2815 9340 2884 2813 9341 2882 2821 9342 2890 2815 9343 2884 2816 9344 2885 2821 9345 2890 2817 9346 2886 2815 9347 2884 2821 9348 2890 2818 9349 2887 2817 9350 2886 2821 9351 2890 2819 9352 2888 2818 9353 2887 2821 9354 2890 2820 9355 2889 2819 9356 2888 2823 9357 2892 2820 9358 2889 2821 9359 2890 2823 9360 2892 2822 9361 2891 2820 9362 2889 2839 9363 2908 2822 9364 2891 2823 9365 2892 2839 9366 2908 2824 9367 2893 2822 9368 2891 2827 9369 2896 2825 9370 2894 2826 9371 2895 2828 9372 2897 2825 9373 2894 2827 9374 2896 2830 9375 2899 2825 9376 2894 2828 9377 2897 2830 9378 2899 2829 9379 2898 2825 9380 2894 2832 9381 2901 2829 9382 2898 2830 9383 2899 2832 9384 2901 2831 9385 2900 2829 9386 2898 2835 9387 2904 2831 9388 2900 2832 9389 2901 2835 9390 2904 2833 9391 2902 2831 9392 2900 2835 9393 2904 2834 9394 2903 2833 9395 2902 2836 9396 2905 2834 9397 2903 2835 9398 2904 2838 9399 2907 2834 9400 2903 2836 9401 2905 2838 9402 2907 2837 9403 2906 2834 9404 2903 2801 9405 2870 2837 9406 2906 2838 9407 2907 2801 9408 2870 2839 9409 2908 2837 9410 2906 2801 9411 2870 2824 9412 2893 2839 9413 2908 2801 9414 2870 2840 9415 2909 2824 9416 2893 2860 9417 2929 2841 9418 2910 2842 9419 2911 2845 9420 2914 2843 9421 2912 2844 9422 2913 2846 9423 2915 2843 9424 2912 2845 9425 2914 2861 9426 2930 2843 9427 2912 2846 9428 2915 2861 9429 2930 2847 9430 2916 2843 9431 2912 2852 9432 2921 2848 9433 2917 2849 9434 2918 2852 9435 2921 2850 9436 2919 2848 9437 2917 2852 9438 2921 2851 9439 2920 2850 9440 2919 2853 9441 2922 2851 9442 2920 2852 9443 2921 2856 9444 2925 2851 9445 2920 2853 9446 2922 2856 9447 2925 2854 9448 2923 2851 9449 2920 2856 9450 2925 2855 9451 2924 2854 9452 2923 2859 9453 2928 2855 9454 2924 2856 9455 2925 2859 9456 2928 2857 9457 2926 2855 9458 2924 2859 9459 2928 2858 9460 2927 2857 9461 2926 2862 9462 2931 2858 9463 2927 2859 9464 2928 2862 9465 2931 2860 9466 2929 2858 9467 2927 2841 9468 2910 2847 9469 2916 2861 9470 2930 2841 9471 2910 2862 9472 2931 2847 9473 2916 2841 9474 2910 2860 9475 2929 2862 9476 2931 2865 9477 2934 2863 9478 2932 2864 9479 2933 2863 9480 2932 2865 9481 2934 2866 9482 2935 2888 9483 2957 2878 9484 2947 2877 9485 2946 2870 9486 2939 2867 9487 2936 2868 9488 2937 2870 9489 2939 2869 9490 2938 2867 9491 2936 2872 9492 2941 2869 9493 2938 2870 9494 2939 2872 9495 2941 2871 9496 2940 2869 9497 2938 2876 9498 2945 2871 9499 2940 2872 9500 2941 2876 9501 2945 2873 9502 2942 2871 9503 2940 2876 9504 2945 2874 9505 2943 2873 9506 2942 2876 9507 2945 2875 9508 2944 2874 9509 2943 2888 9510 2957 2875 9511 2944 2876 9512 2945 2888 9513 2957 2877 9514 2946 2875 9515 2944 2877 9516 2946 2878 9517 2947 2879 9518 2948 2883 9519 2952 2880 9520 2949 2881 9521 2950 2883 9522 2952 2882 9523 2951 2880 9524 2949 2886 9525 2955 2882 9526 2951 2883 9527 2952 2886 9528 2955 2884 9529 2953 2882 9530 2951 2886 9531 2955 2885 9532 2954 2884 9533 2953 2887 9534 2956 2885 9535 2954 2886 9536 2955 2878 9537 2947 2885 9538 2954 2887 9539 2956 2878 9540 2947 2888 9541 2957 2885 9542 2954 2891 9543 2960 2889 9544 2958 2890 9545 2959 2889 9546 2958 2891 9547 2960 2892 9548 2961 2906 9549 2975 2904 9550 2973 2893 9551 2962 2896 9552 2965 2894 9553 2963 2895 9554 2964 2907 9555 2976 2894 9556 2963 2896 9557 2965 2900 9558 2969 2897 9559 2966 2898 9560 2967 2900 9561 2969 2899 9562 2968 2897 9563 2966 2901 9564 2970 2899 9565 2968 2900 9566 2969 2893 9567 2962 2899 9568 2968 2901 9569 2970 2893 9570 2962 2902 9571 2971 2899 9572 2968 2893 9573 2962 2903 9574 2972 2902 9575 2971 2893 9576 2962 2904 9577 2973 2903 9578 2972 2907 9579 2976 2905 9580 2974 2894 9581 2963 2907 9582 2976 2906 9583 2975 2905 9584 2974 2908 9585 2977 2906 9586 2975 2907 9587 2976 2909 9588 2978 2906 9589 2975 2908 9590 2977 2904 9591 2973 2906 9592 2975 2909 9593 2978 2912 9594 2981 2910 9595 2979 2911 9596 2980 2910 9597 2979 2912 9598 2981 2913 9599 2982 2916 9600 2985 2914 9601 2983 2915 9602 2984 2914 9603 2983 2916 9604 2985 2917 9605 2986 2920 9606 2989 2918 9607 2987 2919 9608 2988 2918 9609 2987 2920 9610 2989 2921 9611 2990 2955 9612 3024 2922 9613 2991 2923 9614 2992 2926 9615 2995 2924 9616 2993 2925 9617 2994 2927 9618 2996 2924 9619 2993 2926 9620 2995 2956 9621 3025 2924 9622 2993 2927 9623 2996 2956 9624 3025 2928 9625 2997 2924 9626 2993 2933 9627 3002 2929 9628 2998 2930 9629 2999 2933 9630 3002 2931 9631 3000 2929 9632 2998 2933 9633 3002 2932 9634 3001 2931 9635 3000 2935 9636 3004 2932 9637 3001 2933 9638 3002 2935 9639 3004 2934 9640 3003 2932 9641 3001 2936 9642 3005 2934 9643 3003 2935 9644 3004 2938 9645 3007 2934 9646 3003 2936 9647 3005 2938 9648 3007 2937 9649 3006 2934 9650 3003 2941 9651 3010 2937 9652 3006 2938 9653 3007 2941 9654 3010 2939 9655 3008 2937 9656 3006 2941 9657 3010 2940 9658 3009 2939 9659 3008 2942 9660 3011 2940 9661 3009 2941 9662 3010 2944 9663 3013 2940 9664 3009 2942 9665 3011 2944 9666 3013 2943 9667 3012 2940 9668 3009 2946 9669 3015 2943 9670 3012 2944 9671 3013 2946 9672 3015 2945 9673 3014 2943 9674 3012 2948 9675 3017 2945 9676 3014 2946 9677 3015 2948 9678 3017 2947 9679 3016 2945 9680 3014 2952 9681 3021 2947 9682 3016 2948 9683 3017 2952 9684 3021 2949 9685 3018 2947 9686 3016 2952 9687 3021 2950 9688 3019 2949 9689 3018 2952 9690 3021 2951 9691 3020 2950 9692 3019 2954 9693 3023 2951 9694 3020 2952 9695 3021 2954 9696 3023 2953 9697 3022 2951 9698 3020 2959 9699 3028 2953 9700 3022 2954 9701 3023 2959 9702 3028 2955 9703 3024 2953 9704 3022 2958 9705 3027 2928 9706 2997 2956 9707 3025 2958 9708 3027 2957 9709 3026 2928 9710 2997 2922 9711 2991 2957 9712 3026 2958 9713 3027 2922 9714 2991 2959 9715 3028 2957 9716 3026 2922 9717 2991 2955 9718 3024 2959 9719 3028 3023 9720 3092 2960 9721 3029 2962 9722 3031 2962 9723 3031 2961 9724 3030 3023 9725 3092 2964 9726 3033 2961 9727 3030 2962 9728 3031 2964 9729 3033 2963 9730 3032 2961 9731 3030 2966 9732 3035 2963 9733 3032 2964 9734 3033 2966 9735 3035 2965 9736 3034 2963 9737 3032 2968 9738 3037 2965 9739 3034 2966 9740 3035 2968 9741 3037 2967 9742 3036 2965 9743 3034 2970 9744 3039 2967 9745 3036 2968 9746 3037 2970 9747 3039 2969 9748 3038 2967 9749 3036 2972 9750 3041 2969 9751 3038 2970 9752 3039 2972 9753 3041 2971 9754 3040 2969 9755 3038 2974 9756 3043 2971 9757 3040 2972 9758 3041 2974 9759 3043 2973 9760 3042 2971 9761 3040 2976 9762 3045 2973 9763 3042 2974 9764 3043 2976 9765 3045 2975 9766 3044 2973 9767 3042 2978 9768 3047 2975 9769 3044 2976 9770 3045 2978 9771 3047 2977 9772 3046 2975 9773 3044 2980 9774 3049 2977 9775 3046 2978 9776 3047 2980 9777 3049 2979 9778 3048 2977 9779 3046 2982 9780 3051 2979 9781 3048 2980 9782 3049 2982 9783 3051 2981 9784 3050 2979 9785 3048 2984 9786 3053 2981 9787 3050 2982 9788 3051 2984 9789 3053 2983 9790 3052 2981 9791 3050 2986 9792 3055 2983 9793 3052 2984 9794 3053 2986 9795 3055 2985 9796 3054 2983 9797 3052 2988 9798 3057 2985 9799 3054 2986 9800 3055 2988 9801 3057 2987 9802 3056 2985 9803 3054 2990 9804 3059 2987 9805 3056 2988 9806 3057 2990 9807 3059 2989 9808 3058 2987 9809 3056 2992 9810 3061 2989 9811 3058 2990 9812 3059 2992 9813 3061 2991 9814 3060 2989 9815 3058 2994 9816 3063 2991 9817 3060 2992 9818 3061 2994 9819 3063 2993 9820 3062 2991 9821 3060 2996 9822 3065 2993 9823 3062 2994 9824 3063 2996 9825 3065 2995 9826 3064 2993 9827 3062 2998 9828 3067 2995 9829 3064 2996 9830 3065 2998 9831 3067 2997 9832 3066 2995 9833 3064 3000 9834 3069 2997 9835 3066 2998 9836 3067 3000 9837 3069 2999 9838 3068 2997 9839 3066 3002 9840 3071 2999 9841 3068 3000 9842 3069 3002 9843 3071 3001 9844 3070 2999 9845 3068 3004 9846 3073 3001 9847 3070 3002 9848 3071 3004 9849 3073 3003 9850 3072 3001 9851 3070 3006 9852 3075 3003 9853 3072 3004 9854 3073 3006 9855 3075 3005 9856 3074 3003 9857 3072 3008 9858 3077 3005 9859 3074 3006 9860 3075 3008 9861 3077 3007 9862 3076 3005 9863 3074 3010 9864 3079 3007 9865 3076 3008 9866 3077 3010 9867 3079 3009 9868 3078 3007 9869 3076 3012 9870 3081 3009 9871 3078 3010 9872 3079 3012 9873 3081 3011 9874 3080 3009 9875 3078 3014 9876 3083 3011 9877 3080 3012 9878 3081 3014 9879 3083 3013 9880 3082 3011 9881 3080 3016 9882 3085 3013 9883 3082 3014 9884 3083 3016 9885 3085 3015 9886 3084 3013 9887 3082 3018 9888 3087 3015 9889 3084 3016 9890 3085 3018 9891 3087 3017 9892 3086 3015 9893 3084 3020 9894 3089 3017 9895 3086 3018 9896 3087 3020 9897 3089 3019 9898 3088 3017 9899 3086 3022 9900 3091 3019 9901 3088 3020 9902 3089 3022 9903 3091 3021 9904 3090 3019 9905 3088 2960 9906 3029 3021 9907 3090 3022 9908 3091 2960 9909 3029 3023 9910 3092 3021 9911 3090 3087 9912 3156 3024 9913 3093 3026 9914 3095 3026 9915 3095 3025 9916 3094 3087 9917 3156 3028 9918 3097 3025 9919 3094 3026 9920 3095 3028 9921 3097 3027 9922 3096 3025 9923 3094 3030 9924 3099 3027 9925 3096 3028 9926 3097 3030 9927 3099 3029 9928 3098 3027 9929 3096 3032 9930 3101 3029 9931 3098 3030 9932 3099 3032 9933 3101 3031 9934 3100 3029 9935 3098 3034 9936 3103 3031 9937 3100 3032 9938 3101 3034 9939 3103 3033 9940 3102 3031 9941 3100 3036 9942 3105 3033 9943 3102 3034 9944 3103 3036 9945 3105 3035 9946 3104 3033 9947 3102 3038 9948 3107 3035 9949 3104 3036 9950 3105 3038 9951 3107 3037 9952 3106 3035 9953 3104 3040 9954 3109 3037 9955 3106 3038 9956 3107 3040 9957 3109 3039 9958 3108 3037 9959 3106 3042 9960 3111 3039 9961 3108 3040 9962 3109 3042 9963 3111 3041 9964 3110 3039 9965 3108 3044 9966 3113 3041 9967 3110 3042 9968 3111 3044 9969 3113 3043 9970 3112 3041 9971 3110 3046 9972 3115 3043 9973 3112 3044 9974 3113 3046 9975 3115 3045 9976 3114 3043 9977 3112 3048 9978 3117 3045 9979 3114 3046 9980 3115 3048 9981 3117 3047 9982 3116 3045 9983 3114 3050 9984 3119 3047 9985 3116 3048 9986 3117 3050 9987 3119 3049 9988 3118 3047 9989 3116 3052 9990 3121 3049 9991 3118 3050 9992 3119 3052 9993 3121 3051 9994 3120 3049 9995 3118 3054 9996 3123 3051 9997 3120 3052 9998 3121 3054 9999 3123 3053 10000 3122 3051 10001 3120 3056 10002 3125 3053 10003 3122 3054 10004 3123 3056 10005 3125 3055 10006 3124 3053 10007 3122 3058 10008 3127 3055 10009 3124 3056 10010 3125 3058 10011 3127 3057 10012 3126 3055 10013 3124 3060 10014 3129 3057 10015 3126 3058 10016 3127 3060 10017 3129 3059 10018 3128 3057 10019 3126 3062 10020 3131 3059 10021 3128 3060 10022 3129 3062 10023 3131 3061 10024 3130 3059 10025 3128 3064 10026 3133 3061 10027 3130 3062 10028 3131 3064 10029 3133 3063 10030 3132 3061 10031 3130 3066 10032 3135 3063 10033 3132 3064 10034 3133 3066 10035 3135 3065 10036 3134 3063 10037 3132 3068 10038 3137 3065 10039 3134 3066 10040 3135 3068 10041 3137 3067 10042 3136 3065 10043 3134 3070 10044 3139 3067 10045 3136 3068 10046 3137 3070 10047 3139 3069 10048 3138 3067 10049 3136 3072 10050 3141 3069 10051 3138 3070 10052 3139 3072 10053 3141 3071 10054 3140 3069 10055 3138 3074 10056 3143 3071 10057 3140 3072 10058 3141 3074 10059 3143 3073 10060 3142 3071 10061 3140 3076 10062 3145 3073 10063 3142 3074 10064 3143 3076 10065 3145 3075 10066 3144 3073 10067 3142 3078 10068 3147 3075 10069 3144 3076 10070 3145 3078 10071 3147 3077 10072 3146 3075 10073 3144 3080 10074 3149 3077 10075 3146 3078 10076 3147 3080 10077 3149 3079 10078 3148 3077 10079 3146 3082 10080 3151 3079 10081 3148 3080 10082 3149 3082 10083 3151 3081 10084 3150 3079 10085 3148 3084 10086 3153 3081 10087 3150 3082 10088 3151 3084 10089 3153 3083 10090 3152 3081 10091 3150 3086 10092 3155 3083 10093 3152 3084 10094 3153 3086 10095 3155 3085 10096 3154 3083 10097 3152 3024 10098 3093 3085 10099 3154 3086 10100 3155 3024 10101 3093 3087 10102 3156 3085 10103 3154 3120 10104 3189 3089 10105 3158 3088 10106 3157 3091 10107 3160 3089 10108 3158 3090 10109 3159 3088 10110 3157 3089 10111 3158 3091 10112 3160 3095 10113 3164 3092 10114 3161 3093 10115 3162 3095 10116 3164 3094 10117 3163 3092 10118 3161 3097 10119 3166 3094 10120 3163 3095 10121 3164 3097 10122 3166 3096 10123 3165 3094 10124 3163 3100 10125 3169 3096 10126 3165 3097 10127 3166 3100 10128 3169 3098 10129 3167 3096 10130 3165 3100 10131 3169 3099 10132 3168 3098 10133 3167 3102 10134 3171 3099 10135 3168 3100 10136 3169 3102 10137 3171 3101 10138 3170 3099 10139 3168 3103 10140 3172 3101 10141 3170 3102 10142 3171 3105 10143 3174 3101 10144 3170 3103 10145 3172 3105 10146 3174 3104 10147 3173 3101 10148 3170 3107 10149 3176 3104 10150 3173 3105 10151 3174 3107 10152 3176 3106 10153 3175 3104 10154 3173 3109 10155 3178 3106 10156 3175 3107 10157 3176 3109 10158 3178 3108 10159 3177 3106 10160 3175 3111 10161 3180 3108 10162 3177 3109 10163 3178 3111 10164 3180 3110 10165 3179 3108 10166 3177 3113 10167 3182 3110 10168 3179 3111 10169 3180 3113 10170 3182 3112 10171 3181 3110 10172 3179 3116 10173 3185 3112 10174 3181 3113 10175 3182 3116 10176 3185 3114 10177 3183 3112 10178 3181 3116 10179 3185 3115 10180 3184 3114 10181 3183 3117 10182 3186 3115 10183 3184 3116 10184 3185 3119 10185 3188 3115 10186 3184 3117 10187 3186 3119 10188 3188 3118 10189 3187 3115 10190 3184 3121 10191 3190 3118 10192 3187 3119 10193 3188 3121 10194 3190 3120 10195 3189 3118 10196 3187 3089 10197 3158 3120 10198 3189 3121 10199 3190 3185 10200 3254 3122 10201 3191 3124 10202 3193 3124 10203 3193 3123 10204 3192 3185 10205 3254 3126 10206 3195 3123 10207 3192 3124 10208 3193 3126 10209 3195 3125 10210 3194 3123 10211 3192 3128 10212 3197 3125 10213 3194 3126 10214 3195 3128 10215 3197 3127 10216 3196 3125 10217 3194 3130 10218 3199 3127 10219 3196 3128 10220 3197 3130 10221 3199 3129 10222 3198 3127 10223 3196 3132 10224 3201 3129 10225 3198 3130 10226 3199 3132 10227 3201 3131 10228 3200 3129 10229 3198 3134 10230 3203 3131 10231 3200 3132 10232 3201 3134 10233 3203 3133 10234 3202 3131 10235 3200 3136 10236 3205 3133 10237 3202 3134 10238 3203 3136 10239 3205 3135 10240 3204 3133 10241 3202 3138 10242 3207 3135 10243 3204 3136 10244 3205 3138 10245 3207 3137 10246 3206 3135 10247 3204 3140 10248 3209 3137 10249 3206 3138 10250 3207 3140 10251 3209 3139 10252 3208 3137 10253 3206 3142 10254 3211 3139 10255 3208 3140 10256 3209 3142 10257 3211 3141 10258 3210 3139 10259 3208 3144 10260 3213 3141 10261 3210 3142 10262 3211 3144 10263 3213 3143 10264 3212 3141 10265 3210 3146 10266 3215 3143 10267 3212 3144 10268 3213 3146 10269 3215 3145 10270 3214 3143 10271 3212 3148 10272 3217 3145 10273 3214 3146 10274 3215 3148 10275 3217 3147 10276 3216 3145 10277 3214 3150 10278 3219 3147 10279 3216 3148 10280 3217 3150 10281 3219 3149 10282 3218 3147 10283 3216 3152 10284 3221 3149 10285 3218 3150 10286 3219 3152 10287 3221 3151 10288 3220 3149 10289 3218 3154 10290 3223 3151 10291 3220 3152 10292 3221 3154 10293 3223 3153 10294 3222 3151 10295 3220 3156 10296 3225 3153 10297 3222 3154 10298 3223 3156 10299 3225 3155 10300 3224 3153 10301 3222 3158 10302 3227 3155 10303 3224 3156 10304 3225 3158 10305 3227 3157 10306 3226 3155 10307 3224 3160 10308 3229 3157 10309 3226 3158 10310 3227 3160 10311 3229 3159 10312 3228 3157 10313 3226 3162 10314 3231 3159 10315 3228 3160 10316 3229 3162 10317 3231 3161 10318 3230 3159 10319 3228 3164 10320 3233 3161 10321 3230 3162 10322 3231 3164 10323 3233 3163 10324 3232 3161 10325 3230 3166 10326 3235 3163 10327 3232 3164 10328 3233 3166 10329 3235 3165 10330 3234 3163 10331 3232 3168 10332 3237 3165 10333 3234 3166 10334 3235 3168 10335 3237 3167 10336 3236 3165 10337 3234 3170 10338 3239 3167 10339 3236 3168 10340 3237 3170 10341 3239 3169 10342 3238 3167 10343 3236 3172 10344 3241 3169 10345 3238 3170 10346 3239 3172 10347 3241 3171 10348 3240 3169 10349 3238 3174 10350 3243 3171 10351 3240 3172 10352 3241 3174 10353 3243 3173 10354 3242 3171 10355 3240 3176 10356 3245 3173 10357 3242 3174 10358 3243 3176 10359 3245 3175 10360 3244 3173 10361 3242 3178 10362 3247 3175 10363 3244 3176 10364 3245 3178 10365 3247 3177 10366 3246 3175 10367 3244 3180 10368 3249 3177 10369 3246 3178 10370 3247 3180 10371 3249 3179 10372 3248 3177 10373 3246 3182 10374 3251 3179 10375 3248 3180 10376 3249 3182 10377 3251 3181 10378 3250 3179 10379 3248 3184 10380 3253 3181 10381 3250 3182 10382 3251 3184 10383 3253 3183 10384 3252 3181 10385 3250 3122 10386 3191 3183 10387 3252 3184 10388 3253 3122 10389 3191 3185 10390 3254 3183 10391 3252 3219 10392 3288 3186 10393 3255 3204 10394 3273 3189 10395 3258 3187 10396 3256 3188 10397 3257 3191 10398 3260 3187 10399 3256 3189 10400 3258 3191 10401 3260 3190 10402 3259 3187 10403 3256 3192 10404 3261 3190 10405 3259 3191 10406 3260 3195 10407 3264 3190 10408 3259 3192 10409 3261 3195 10410 3264 3193 10411 3262 3190 10412 3259 3195 10413 3264 3194 10414 3263 3193 10415 3262 3197 10416 3266 3194 10417 3263 3195 10418 3264 3197 10419 3266 3196 10420 3265 3194 10421 3263 3199 10422 3268 3196 10423 3265 3197 10424 3266 3199 10425 3268 3198 10426 3267 3196 10427 3265 3201 10428 3270 3198 10429 3267 3199 10430 3268 3201 10431 3270 3200 10432 3269 3198 10433 3267 3203 10434 3272 3200 10435 3269 3201 10436 3270 3203 10437 3272 3202 10438 3271 3200 10439 3269 3205 10440 3274 3202 10441 3271 3203 10442 3272 3205 10443 3274 3204 10444 3273 3202 10445 3271 3219 10446 3288 3204 10447 3273 3205 10448 3274 3208 10449 3277 3206 10450 3275 3207 10451 3276 3209 10452 3278 3206 10453 3275 3208 10454 3277 3211 10455 3280 3206 10456 3275 3209 10457 3278 3211 10458 3280 3210 10459 3279 3206 10460 3275 3213 10461 3282 3210 10462 3279 3211 10463 3280 3213 10464 3282 3212 10465 3281 3210 10466 3279 3215 10467 3284 3212 10468 3281 3213 10469 3282 3215 10470 3284 3214 10471 3283 3212 10472 3281 3218 10473 3287 3214 10474 3283 3215 10475 3284 3218 10476 3287 3216 10477 3285 3214 10478 3283 3218 10479 3287 3217 10480 3286 3216 10481 3285 3186 10482 3255 3217 10483 3286 3218 10484 3287 3186 10485 3255 3219 10486 3288 3217 10487 3286 3222 10488 3291 3220 10489 3289 3221 10490 3290 3220 10491 3289 3222 10492 3291 3223 10493 3292 3230 10494 3299 3224 10495 3293 3225 10496 3294 3229 10497 3298 3226 10498 3295 3227 10499 3296 3229 10500 3298 3228 10501 3297 3226 10502 3295 3231 10503 3300 3228 10504 3297 3229 10505 3298 3231 10506 3300 3230 10507 3299 3228 10508 3297 3232 10509 3301 3230 10510 3299 3231 10511 3300 3233 10512 3302 3230 10513 3299 3232 10514 3301 3234 10515 3303 3230 10516 3299 3233 10517 3302 3235 10518 3304 3230 10519 3299 3234 10520 3303 3236 10521 3305 3230 10522 3299 3235 10523 3304 3237 10524 3306 3230 10525 3299 3236 10526 3305 3238 10527 3307 3230 10528 3299 3237 10529 3306 3239 10530 3308 3230 10531 3299 3238 10532 3307 3240 10533 3309 3230 10534 3299 3239 10535 3308 3224 10536 3293 3230 10537 3299 3240 10538 3309 3251 10539 3320 3241 10540 3310 3242 10541 3311 3245 10542 3314 3243 10543 3312 3244 10544 3313 3247 10545 3316 3243 10546 3312 3245 10547 3314 3247 10548 3316 3246 10549 3315 3243 10550 3312 3252 10551 3321 3246 10552 3315 3247 10553 3316 3252 10554 3321 3248 10555 3317 3246 10556 3315 3252 10557 3321 3249 10558 3318 3248 10559 3317 3252 10560 3321 3250 10561 3319 3249 10562 3318 3252 10563 3321 3251 10564 3320 3250 10565 3319 3253 10566 3322 3251 10567 3320 3252 10568 3321 3254 10569 3323 3251 10570 3320 3253 10571 3322 3255 10572 3324 3251 10573 3320 3254 10574 3323 3256 10575 3325 3251 10576 3320 3255 10577 3324 3257 10578 3326 3251 10579 3320 3256 10580 3325 3241 10581 3310 3251 10582 3320 3257 10583 3326 3260 10584 3329 3258 10585 3327 3259 10586 3328 3258 10587 3327 3260 10588 3329 3261 10589 3330 3264 10590 3333 3262 10591 3331 3263 10592 3332 3262 10593 3331 3264 10594 3333 3265 10595 3334 3272 10596 3341 3266 10597 3335 3267 10598 3336 3271 10599 3340 3268 10600 3337 3269 10601 3338 3271 10602 3340 3270 10603 3339 3268 10604 3337 3273 10605 3342 3270 10606 3339 3271 10607 3340 3273 10608 3342 3272 10609 3341 3270 10610 3339 3274 10611 3343 3272 10612 3341 3273 10613 3342 3275 10614 3344 3272 10615 3341 3274 10616 3343 3276 10617 3345 3272 10618 3341 3275 10619 3344 3277 10620 3346 3272 10621 3341 3276 10622 3345 3278 10623 3347 3272 10624 3341 3277 10625 3346 3279 10626 3348 3272 10627 3341 3278 10628 3347 3280 10629 3349 3272 10630 3341 3279 10631 3348 3281 10632 3350 3272 10633 3341 3280 10634 3349 3282 10635 3351 3272 10636 3341 3281 10637 3350 3266 10638 3335 3272 10639 3341 3282 10640 3351 3293 10641 3362 3283 10642 3352 3284 10643 3353 3287 10644 3356 3285 10645 3354 3286 10646 3355 3289 10647 3358 3285 10648 3354 3287 10649 3356 3289 10650 3358 3288 10651 3357 3285 10652 3354 3294 10653 3363 3288 10654 3357 3289 10655 3358 3294 10656 3363 3290 10657 3359 3288 10658 3357 3294 10659 3363 3291 10660 3360 3290 10661 3359 3294 10662 3363 3292 10663 3361 3291 10664 3360 3294 10665 3363 3293 10666 3362 3292 10667 3361 3295 10668 3364 3293 10669 3362 3294 10670 3363 3296 10671 3365 3293 10672 3362 3295 10673 3364 3297 10674 3366 3293 10675 3362 3296 10676 3365 3298 10677 3367 3293 10678 3362 3297 10679 3366 3299 10680 3368 3293 10681 3362 3298 10682 3367 3283 10683 3352 3293 10684 3362 3299 10685 3368 3302 10686 3371 3300 10687 3369 3301 10688 3370 3300 10689 3369 3302 10690 3371 3303 10691 3372 3310 10692 3379 3304 10693 3373 3305 10694 3374 3309 10695 3378 3306 10696 3375 3307 10697 3376 3309 10698 3378 3308 10699 3377 3306 10700 3375 3311 10701 3380 3308 10702 3377 3309 10703 3378 3311 10704 3380 3310 10705 3379 3308 10706 3377 3312 10707 3381 3310 10708 3379 3311 10709 3380 3313 10710 3382 3310 10711 3379 3312 10712 3381 3314 10713 3383 3310 10714 3379 3313 10715 3382 3315 10716 3384 3310 10717 3379 3314 10718 3383 3316 10719 3385 3310 10720 3379 3315 10721 3384 3317 10722 3386 3310 10723 3379 3316 10724 3385 3318 10725 3387 3310 10726 3379 3317 10727 3386 3319 10728 3388 3310 10729 3379 3318 10730 3387 3320 10731 3389 3310 10732 3379 3319 10733 3388 3304 10734 3373 3310 10735 3379 3320 10736 3389 3331 10737 3400 3321 10738 3390 3322 10739 3391 3325 10740 3394 3323 10741 3392 3324 10742 3393 3327 10743 3396 3323 10744 3392 3325 10745 3394 3327 10746 3396 3326 10747 3395 3323 10748 3392 3332 10749 3401 3326 10750 3395 3327 10751 3396 3332 10752 3401 3328 10753 3397 3326 10754 3395 3332 10755 3401 3329 10756 3398 3328 10757 3397 3332 10758 3401 3330 10759 3399 3329 10760 3398 3332 10761 3401 3331 10762 3400 3330 10763 3399 3333 10764 3402 3331 10765 3400 3332 10766 3401 3334 10767 3403 3331 10768 3400 3333 10769 3402 3335 10770 3404 3331 10771 3400 3334 10772 3403 3336 10773 3405 3331 10774 3400 3335 10775 3404 3337 10776 3406 3331 10777 3400 3336 10778 3405 3321 10779 3390 3331 10780 3400 3337 10781 3406 3340 10782 3409 3338 10783 3407 3339 10784 3408 3338 10785 3407 3340 10786 3409 3341 10787 3410 3352 10788 3421 3342 10789 3411 3343 10790 3412 3346 10791 3415 3344 10792 3413 3345 10793 3414 3348 10794 3417 3344 10795 3413 3346 10796 3415 3348 10797 3417 3347 10798 3416 3344 10799 3413 3353 10800 3422 3347 10801 3416 3348 10802 3417 3353 10803 3422 3349 10804 3418 3347 10805 3416 3353 10806 3422 3350 10807 3419 3349 10808 3418 3353 10809 3422 3351 10810 3420 3350 10811 3419 3353 10812 3422 3352 10813 3421 3351 10814 3420 3354 10815 3423 3352 10816 3421 3353 10817 3422 3355 10818 3424 3352 10819 3421 3354 10820 3423 3356 10821 3425 3352 10822 3421 3355 10823 3424 3357 10824 3426 3352 10825 3421 3356 10826 3425 3358 10827 3427 3352 10828 3421 3357 10829 3426 3342 10830 3411 3352 10831 3421 3358 10832 3427 3365 10833 3434 3359 10834 3428 3360 10835 3429 3364 10836 3433 3361 10837 3430 3362 10838 3431 3364 10839 3433 3363 10840 3432 3361 10841 3430 3366 10842 3435 3363 10843 3432 3364 10844 3433 3366 10845 3435 3365 10846 3434 3363 10847 3432 3367 10848 3436 3365 10849 3434 3366 10850 3435 3368 10851 3437 3365 10852 3434 3367 10853 3436 3369 10854 3438 3365 10855 3434 3368 10856 3437 3370 10857 3439 3365 10858 3434 3369 10859 3438 3371 10860 3440 3365 10861 3434 3370 10862 3439 3372 10863 3441 3365 10864 3434 3371 10865 3440 3373 10866 3442 3365 10867 3434 3372 10868 3441 3374 10869 3443 3365 10870 3434 3373 10871 3442 3375 10872 3444 3365 10873 3434 3374 10874 3443 3359 10875 3428 3365 10876 3434 3375 10877 3444 3378 10878 3447 3376 10879 3445 3377 10880 3446 3376 10881 3445 3378 10882 3447 3379 10883 3448 3382 10884 3451 3380 10885 3449 3381 10886 3450 3380 10887 3449 3382 10888 3451 3383 10889 3452 3394 10890 3463 3384 10891 3453 3385 10892 3454 3388 10893 3457 3386 10894 3455 3387 10895 3456 3390 10896 3459 3386 10897 3455 3388 10898 3457 3390 10899 3459 3389 10900 3458 3386 10901 3455 3395 10902 3464 3389 10903 3458 3390 10904 3459 3395 10905 3464 3391 10906 3460 3389 10907 3458 3395 10908 3464 3392 10909 3461 3391 10910 3460 3395 10911 3464 3393 10912 3462 3392 10913 3461 3395 10914 3464 3394 10915 3463 3393 10916 3462 3396 10917 3465 3394 10918 3463 3395 10919 3464 3397 10920 3466 3394 10921 3463 3396 10922 3465 3398 10923 3467 3394 10924 3463 3397 10925 3466 3399 10926 3468 3394 10927 3463 3398 10928 3467 3400 10929 3469 3394 10930 3463 3399 10931 3468 3384 10932 3453 3394 10933 3463 3400 10934 3469 3407 10935 3476 3401 10936 3470 3402 10937 3471 3406 10938 3475 3403 10939 3472 3404 10940 3473 3406 10941 3475 3405 10942 3474 3403 10943 3472 3408 10944 3477 3405 10945 3474 3406 10946 3475 3408 10947 3477 3407 10948 3476 3405 10949 3474 3409 10950 3478 3407 10951 3476 3408 10952 3477 3410 10953 3479 3407 10954 3476 3409 10955 3478 3411 10956 3480 3407 10957 3476 3410 10958 3479 3412 10959 3481 3407 10960 3476 3411 10961 3480 3413 10962 3482 3407 10963 3476 3412 10964 3481 3414 10965 3483 3407 10966 3476 3413 10967 3482 3415 10968 3484 3407 10969 3476 3414 10970 3483 3416 10971 3485 3407 10972 3476 3415 10973 3484 3417 10974 3486 3407 10975 3476 3416 10976 3485 3401 10977 3470 3407 10978 3476 3417 10979 3486 3420 10980 3489 3418 10981 3487 3419 10982 3488 3418 10983 3487 3420 10984 3489 3421 10985 3490 3424 10986 3493 3422 10987 3491 3423 10988 3492 3422 10989 3491 3424 10990 3493 3425 10991 3494 3436 10992 3505 3426 10993 3495 3427 10994 3496 3430 10995 3499 3428 10996 3497 3429 10997 3498 3432 10998 3501 3428 10999 3497 3430 11000 3499 3432 11001 3501 3431 11002 3500 3428 11003 3497 3437 11004 3506 3431 11005 3500 3432 11006 3501 3437 11007 3506 3433 11008 3502 3431 11009 3500 3437 11010 3506 3434 11011 3503 3433 11012 3502 3437 11013 3506 3435 11014 3504 3434 11015 3503 3437 11016 3506 3436 11017 3505 3435 11018 3504 3438 11019 3507 3436 11020 3505 3437 11021 3506 3439 11022 3508 3436 11023 3505 3438 11024 3507 3440 11025 3509 3436 11026 3505 3439 11027 3508 3441 11028 3510 3436 11029 3505 3440 11030 3509 3442 11031 3511 3436 11032 3505 3441 11033 3510 3426 11034 3495 3436 11035 3505 3442 11036 3511 3449 11037 3518 3443 11038 3512 3444 11039 3513 3448 11040 3517 3445 11041 3514 3446 11042 3515 3448 11043 3517 3447 11044 3516 3445 11045 3514 3450 11046 3519 3447 11047 3516 3448 11048 3517 3450 11049 3519 3449 11050 3518 3447 11051 3516 3451 11052 3520 3449 11053 3518 3450 11054 3519 3452 11055 3521 3449 11056 3518 3451 11057 3520 3453 11058 3522 3449 11059 3518 3452 11060 3521 3454 11061 3523 3449 11062 3518 3453 11063 3522 3455 11064 3524 3449 11065 3518 3454 11066 3523 3456 11067 3525 3449 11068 3518 3455 11069 3524 3457 11070 3526 3449 11071 3518 3456 11072 3525 3458 11073 3527 3449 11074 3518 3457 11075 3526 3459 11076 3528 3449 11077 3518 3458 11078 3527 3443 11079 3512 3449 11080 3518 3459 11081 3528 3462 11082 3531 3460 11083 3529 3461 11084 3530 3460 11085 3529 3462 11086 3531 3463 11087 3532 3470 11088 3539 3464 11089 3533 3465 11090 3534 3469 11091 3538 3466 11092 3535 3467 11093 3536 3469 11094 3538 3468 11095 3537 3466 11096 3535 3471 11097 3540 3468 11098 3537 3469 11099 3538 3471 11100 3540 3470 11101 3539 3468 11102 3537 3472 11103 3541 3470 11104 3539 3471 11105 3540 3473 11106 3542 3470 11107 3539 3472 11108 3541 3474 11109 3543 3470 11110 3539 3473 11111 3542 3475 11112 3544 3470 11113 3539 3474 11114 3543 3476 11115 3545 3470 11116 3539 3475 11117 3544 3477 11118 3546 3470 11119 3539 3476 11120 3545 3478 11121 3547 3470 11122 3539 3477 11123 3546 3479 11124 3548 3470 11125 3539 3478 11126 3547 3480 11127 3549 3470 11128 3539 3479 11129 3548 3464 11130 3533 3470 11131 3539 3480 11132 3549 3491 11133 3560 3481 11134 3550 3482 11135 3551 3485 11136 3554 3483 11137 3552 3484 11138 3553 3487 11139 3556 3483 11140 3552 3485 11141 3554 3487 11142 3556 3486 11143 3555 3483 11144 3552 3492 11145 3561 3486 11146 3555 3487 11147 3556 3492 11148 3561 3488 11149 3557 3486 11150 3555 3492 11151 3561 3489 11152 3558 3488 11153 3557 3492 11154 3561 3490 11155 3559 3489 11156 3558 3492 11157 3561 3491 11158 3560 3490 11159 3559 3493 11160 3562 3491 11161 3560 3492 11162 3561 3494 11163 3563 3491 11164 3560 3493 11165 3562 3495 11166 3564 3491 11167 3560 3494 11168 3563 3496 11169 3565 3491 11170 3560 3495 11171 3564 3497 11172 3566 3491 11173 3560 3496 11174 3565 3481 11175 3550 3491 11176 3560 3497 11177 3566 3500 11178 3571 3498 11179 3567 3499 11180 3568 3498 11181 3567 3500 11182 3569 3501 11183 3570 3504 11184 3574 3502 11185 3572 3503 11186 3573 3502 11187 3572 3504 11188 3574 3505 11189 3575 3508 11190 3578 3506 11191 3576 3507 11192 3577 3506 11193 3576 3508 11194 3578 3509 11195 3579 3512 11196 3582 3510 11197 3580 3511 11198 3581 3510 11199 3580 3512 11200 3582 3513 11201 3583 3516 11202 3586 3514 11203 3584 3515 11204 3585 3514 11205 3584 3516 11206 3586 3517 11207 3587 3520 11208 3590 3518 11209 3588 3519 11210 3589 3518 11211 3588 3520 11212 3590 3521 11213 3591 3524 11214 3594 3522 11215 3592 3523 11216 3593 3522 11217 3592 3524 11218 3594 3525 11219 3595 3536 11220 3606 3526 11221 3596 3527 11222 3597 3530 11223 3600 3528 11224 3598 3529 11225 3599 3532 11226 3602 3528 11227 3598 3530 11228 3600 3532 11229 3602 3531 11230 3601 3528 11231 3598 3537 11232 3607 3531 11233 3601 3532 11234 3602 3537 11235 3607 3533 11236 3603 3531 11237 3601 3537 11238 3607 3534 11239 3604 3533 11240 3603 3537 11241 3607 3535 11242 3605 3534 11243 3604 3537 11244 3607 3536 11245 3606 3535 11246 3605 3538 11247 3608 3536 11248 3606 3537 11249 3607 3539 11250 3609 3536 11251 3606 3538 11252 3608 3540 11253 3610 3536 11254 3606 3539 11255 3609 3541 11256 3611 3536 11257 3606 3540 11258 3610 3542 11259 3612 3536 11260 3606 3541 11261 3611 3526 11262 3596 3536 11263 3606 3542 11264 3612 3549 11265 3619 3543 11266 3613 3544 11267 3614 3548 11268 3618 3545 11269 3615 3546 11270 3616 3548 11271 3618 3547 11272 3617 3545 11273 3615 3550 11274 3620 3547 11275 3617 3548 11276 3618 3550 11277 3620 3549 11278 3619 3547 11279 3617 3551 11280 3621 3549 11281 3619 3550 11282 3620 3552 11283 3622 3549 11284 3619 3551 11285 3621 3553 11286 3623 3549 11287 3619 3552 11288 3622 3554 11289 3624 3549 11290 3619 3553 11291 3623 3555 11292 3625 3549 11293 3619 3554 11294 3624 3556 11295 3626 3549 11296 3619 3555 11297 3625 3557 11298 3627 3549 11299 3619 3556 11300 3626 3558 11301 3628 3549 11302 3619 3557 11303 3627 3559 11304 3629 3549 11305 3619 3558 11306 3628 3543 11307 3613 3549 11308 3619 3559 11309 3629 3570 11310 3640 3560 11311 3630 3561 11312 3631 3564 11313 3634 3562 11314 3632 3563 11315 3633 3566 11316 3636 3562 11317 3632 3564 11318 3634 3566 11319 3636 3565 11320 3635 3562 11321 3632 3571 11322 3641 3565 11323 3635 3566 11324 3636 3571 11325 3641 3567 11326 3637 3565 11327 3635 3571 11328 3641 3568 11329 3638 3567 11330 3637 3571 11331 3641 3569 11332 3639 3568 11333 3638 3571 11334 3641 3570 11335 3640 3569 11336 3639 3572 11337 3642 3570 11338 3640 3571 11339 3641 3573 11340 3643 3570 11341 3640 3572 11342 3642 3574 11343 3644 3570 11344 3640 3573 11345 3643 3575 11346 3645 3570 11347 3640 3574 11348 3644 3576 11349 3646 3570 11350 3640 3575 11351 3645 3560 11352 3630 3570 11353 3640 3576 11354 3646 3579 11355 3649 3577 11356 3647 3578 11357 3648 3577 11358 3647 3579 11359 3649 3580 11360 3650 3587 11361 3657 3581 11362 3651 3582 11363 3652 3586 11364 3656 3583 11365 3653 3584 11366 3654 3586 11367 3656 3585 11368 3655 3583 11369 3653 3588 11370 3658 3585 11371 3655 3586 11372 3656 3588 11373 3658 3587 11374 3657 3585 11375 3655 3589 11376 3659 3587 11377 3657 3588 11378 3658 3590 11379 3660 3587 11380 3657 3589 11381 3659 3591 11382 3661 3587 11383 3657 3590 11384 3660 3592 11385 3662 3587 11386 3657 3591 11387 3661 3593 11388 3663 3587 11389 3657 3592 11390 3662 3594 11391 3664 3587 11392 3657 3593 11393 3663 3595 11394 3665 3587 11395 3657 3594 11396 3664 3596 11397 3666 3587 11398 3657 3595 11399 3665 3597 11400 3667 3587 11401 3657 3596 11402 3666 3581 11403 3651 3587 11404 3657 3597 11405 3667 3600 11406 3670 3598 11407 3668 3599 11408 3669 3598 11409 3668 3600 11410 3670 3601 11411 3671 3612 11412 3682 3602 11413 3672 3603 11414 3673 3606 11415 3676 3604 11416 3674 3605 11417 3675 3608 11418 3678 3604 11419 3674 3606 11420 3676 3608 11421 3678 3607 11422 3677 3604 11423 3674 3613 11424 3683 3607 11425 3677 3608 11426 3678 3613 11427 3683 3609 11428 3679 3607 11429 3677 3613 11430 3683 3610 11431 3680 3609 11432 3679 3613 11433 3683 3611 11434 3681 3610 11435 3680 3613 11436 3683 3612 11437 3682 3611 11438 3681 3614 11439 3684 3612 11440 3682 3613 11441 3683 3615 11442 3685 3612 11443 3682 3614 11444 3684 3616 11445 3686 3612 11446 3682 3615 11447 3685 3617 11448 3687 3612 11449 3682 3616 11450 3686 3618 11451 3688 3612 11452 3682 3617 11453 3687 3602 11454 3672 3612 11455 3682 3618 11456 3688 3621 11457 3691 3619 11458 3689 3620 11459 3690 3619 11460 3689 3621 11461 3691 3622 11462 3692 3629 11463 3699 3623 11464 3693 3624 11465 3694 3628 11466 3698 3625 11467 3695 3626 11468 3696 3628 11469 3698 3627 11470 3697 3625 11471 3695 3630 11472 3700 3627 11473 3697 3628 11474 3698 3630 11475 3700 3629 11476 3699 3627 11477 3697 3631 11478 3701 3629 11479 3699 3630 11480 3700 3632 11481 3702 3629 11482 3699 3631 11483 3701 3633 11484 3703 3629 11485 3699 3632 11486 3702 3634 11487 3704 3629 11488 3699 3633 11489 3703 3635 11490 3705 3629 11491 3699 3634 11492 3704 3636 11493 3706 3629 11494 3699 3635 11495 3705 3637 11496 3707 3629 11497 3699 3636 11498 3706 3638 11499 3708 3629 11500 3699 3637 11501 3707 3639 11502 3709 3629 11503 3699 3638 11504 3708 3623 11505 3693 3629 11506 3699 3639 11507 3709 3642 11508 3712 3640 11509 3710 3641 11510 3711 3640 11511 3710 3642 11512 3712 3643 11513 3713 3654 11514 3724 3644 11515 3714 3645 11516 3715 3648 11517 3718 3646 11518 3716 3647 11519 3717 3650 11520 3720 3646 11521 3716 3648 11522 3718 3650 11523 3720 3649 11524 3719 3646 11525 3716 3655 11526 3725 3649 11527 3719 3650 11528 3720 3655 11529 3725 3651 11530 3721 3649 11531 3719 3655 11532 3725 3652 11533 3722 3651 11534 3721 3655 11535 3725 3653 11536 3723 3652 11537 3722 3655 11538 3725 3654 11539 3724 3653 11540 3723 3656 11541 3726 3654 11542 3724 3655 11543 3725 3657 11544 3727 3654 11545 3724 3656 11546 3726 3658 11547 3728 3654 11548 3724 3657 11549 3727 3659 11550 3729 3654 11551 3724 3658 11552 3728 3660 11553 3730 3654 11554 3724 3659 11555 3729 3644 11556 3714 3654 11557 3724 3660 11558 3730 3667 11559 3737 3661 11560 3731 3662 11561 3732 3666 11562 3736 3663 11563 3733 3664 11564 3734 3666 11565 3736 3665 11566 3735 3663 11567 3733 3668 11568 3738 3665 11569 3735 3666 11570 3736 3668 11571 3738 3667 11572 3737 3665 11573 3735 3669 11574 3739 3667 11575 3737 3668 11576 3738 3670 11577 3740 3667 11578 3737 3669 11579 3739 3671 11580 3741 3667 11581 3737 3670 11582 3740 3672 11583 3742 3667 11584 3737 3671 11585 3741 3673 11586 3743 3667 11587 3737 3672 11588 3742 3674 11589 3744 3667 11590 3737 3673 11591 3743 3675 11592 3745 3667 11593 3737 3674 11594 3744 3676 11595 3746 3667 11596 3737 3675 11597 3745 3677 11598 3747 3667 11599 3737 3676 11600 3746 3661 11601 3731 3667 11602 3737 3677 11603 3747 3684 11604 3754 3678 11605 3748 3679 11606 3749 3683 11607 3753 3680 11608 3750 3681 11609 3751 3683 11610 3753 3682 11611 3752 3680 11612 3750 3685 11613 3755 3682 11614 3752 3683 11615 3753 3685 11616 3755 3684 11617 3754 3682 11618 3752 3686 11619 3756 3684 11620 3754 3685 11621 3755 3687 11622 3757 3684 11623 3754 3686 11624 3756 3688 11625 3758 3684 11626 3754 3687 11627 3757 3689 11628 3759 3684 11629 3754 3688 11630 3758 3690 11631 3760 3684 11632 3754 3689 11633 3759 3691 11634 3761 3684 11635 3754 3690 11636 3760 3692 11637 3762 3684 11638 3754 3691 11639 3761 3693 11640 3763 3684 11641 3754 3692 11642 3762 3694 11643 3764 3684 11644 3754 3693 11645 3763 3678 11646 3748 3684 11647 3754 3694 11648 3764 3705 11649 3775 3695 11650 3765 3696 11651 3766 3699 11652 3769 3697 11653 3767 3698 11654 3768 3701 11655 3771 3697 11656 3767 3699 11657 3769 3701 11658 3771 3700 11659 3770 3697 11660 3767 3706 11661 3776 3700 11662 3770 3701 11663 3771 3706 11664 3776 3702 11665 3772 3700 11666 3770 3706 11667 3776 3703 11668 3773 3702 11669 3772 3706 11670 3776 3704 11671 3774 3703 11672 3773 3706 11673 3776 3705 11674 3775 3704 11675 3774 3707 11676 3777 3705 11677 3775 3706 11678 3776 3708 11679 3778 3705 11680 3775 3707 11681 3777 3709 11682 3779 3705 11683 3775 3708 11684 3778 3710 11685 3780 3705 11686 3775 3709 11687 3779 3711 11688 3781 3705 11689 3775 3710 11690 3780 3695 11691 3765 3705 11692 3775 3711 11693 3781 3718 11694 3788 3712 11695 3782 3713 11696 3783 3717 11697 3787 3714 11698 3784 3715 11699 3785 3717 11700 3787 3716 11701 3786 3714 11702 3784 3719 11703 3789 3716 11704 3786 3717 11705 3787 3719 11706 3789 3718 11707 3788 3716 11708 3786 3720 11709 3790 3718 11710 3788 3719 11711 3789 3721 11712 3791 3718 11713 3788 3720 11714 3790 3722 11715 3792 3718 11716 3788 3721 11717 3791 3723 11718 3793 3718 11719 3788 3722 11720 3792 3724 11721 3794 3718 11722 3788 3723 11723 3793 3725 11724 3795 3718 11725 3788 3724 11726 3794 3726 11727 3796 3718 11728 3788 3725 11729 3795 3727 11730 3797 3718 11731 3788 3726 11732 3796 3728 11733 3798 3718 11734 3788 3727 11735 3797 3712 11736 3782 3718 11737 3788 3728 11738 3798 3731 11739 3801 3729 11740 3799 3730 11741 3800 3729 11742 3799 3731 11743 3801 3732 11744 3802 3743 11745 3813 3733 11746 3803 3734 11747 3804 3737 11748 3807 3735 11749 3805 3736 11750 3806 3739 11751 3809 3735 11752 3805 3737 11753 3807 3739 11754 3809 3738 11755 3808 3735 11756 3805 3744 11757 3814 3738 11758 3808 3739 11759 3809 3744 11760 3814 3740 11761 3810 3738 11762 3808 3744 11763 3814 3741 11764 3811 3740 11765 3810 3744 11766 3814 3742 11767 3812 3741 11768 3811 3744 11769 3814 3743 11770 3813 3742 11771 3812 3745 11772 3815 3743 11773 3813 3744 11774 3814 3746 11775 3816 3743 11776 3813 3745 11777 3815 3747 11778 3817 3743 11779 3813 3746 11780 3816 3748 11781 3818 3743 11782 3813 3747 11783 3817 3749 11784 3819 3743 11785 3813 3748 11786 3818 3733 11787 3803 3743 11788 3813 3749 11789 3819 3752 11790 3822 3750 11791 3820 3751 11792 3821 3750 11793 3820 3752 11794 3822 3753 11795 3823 3760 11796 3830 3754 11797 3824 3755 11798 3825 3759 11799 3829 3756 11800 3826 3757 11801 3827 3759 11802 3829 3758 11803 3828 3756 11804 3826 3761 11805 3831 3758 11806 3828 3759 11807 3829 3761 11808 3831 3760 11809 3830 3758 11810 3828 3762 11811 3832 3760 11812 3830 3761 11813 3831 3763 11814 3833 3760 11815 3830 3762 11816 3832 3764 11817 3834 3760 11818 3830 3763 11819 3833 3765 11820 3835 3760 11821 3830 3764 11822 3834 3766 11823 3836 3760 11824 3830 3765 11825 3835 3767 11826 3837 3760 11827 3830 3766 11828 3836 3768 11829 3838 3760 11830 3830 3767 11831 3837 3769 11832 3839 3760 11833 3830 3768 11834 3838 3770 11835 3840 3760 11836 3830 3769 11837 3839 3754 11838 3824 3760 11839 3830 3770 11840 3840 3773 11841 3843 3771 11842 3841 3772 11843 3842 3771 11844 3841 3773 11845 3843 3774 11846 3844 3785 11847 3855 3775 11848 3845 3776 11849 3846 3779 11850 3849 3777 11851 3847 3778 11852 3848 3781 11853 3851 3777 11854 3847 3779 11855 3849 3781 11856 3851 3780 11857 3850 3777 11858 3847 3786 11859 3856 3780 11860 3850 3781 11861 3851 3786 11862 3856 3782 11863 3852 3780 11864 3850 3786 11865 3856 3783 11866 3853 3782 11867 3852 3786 11868 3856 3784 11869 3854 3783 11870 3853 3786 11871 3856 3785 11872 3855 3784 11873 3854 3787 11874 3857 3785 11875 3855 3786 11876 3856 3788 11877 3858 3785 11878 3855 3787 11879 3857 3789 11880 3859 3785 11881 3855 3788 11882 3858 3790 11883 3860 3785 11884 3855 3789 11885 3859 3791 11886 3861 3785 11887 3855 3790 11888 3860 3775 11889 3845 3785 11890 3855 3791 11891 3861 3794 11892 3864 3792 11893 3862 3793 11894 3863 3792 11895 3862 3794 11896 3864 3795 11897 3865 3798 11898 3868 3796 11899 3866 3797 11900 3867 3796 11901 3866 3798 11902 3868 3799 11903 3869 3802 11904 3872 3800 11905 3870 3801 11906 3871 3800 11907 3870 3802 11908 3872 3803 11909 3873 3806 11910 3876 3804 11911 3874 3805 11912 3875 3804 11913 3874 3806 11914 3876 3807 11915 3877 3841 11916 3911 3808 11917 3878 3809 11918 3879 3812 11919 3882 3810 11920 3880 3811 11921 3881 3813 11922 3883 3810 11923 3880 3812 11924 3882 3816 11925 3886 3810 11926 3880 3813 11927 3883 3816 11928 3886 3814 11929 3884 3810 11930 3880 3816 11931 3886 3815 11932 3885 3814 11933 3884 3817 11934 3887 3815 11935 3885 3816 11936 3886 3820 11937 3890 3815 11938 3885 3817 11939 3887 3820 11940 3890 3818 11941 3888 3815 11942 3885 3820 11943 3890 3819 11944 3889 3818 11945 3888 3822 11946 3892 3819 11947 3889 3820 11948 3890 3822 11949 3892 3821 11950 3891 3819 11951 3889 3824 11952 3894 3821 11953 3891 3822 11954 3892 3824 11955 3894 3823 11956 3893 3821 11957 3891 3826 11958 3896 3823 11959 3893 3824 11960 3894 3826 11961 3896 3825 11962 3895 3823 11963 3893 3842 11964 3912 3825 11965 3895 3826 11966 3896 3830 11967 3900 3827 11968 3897 3828 11969 3898 3830 11970 3900 3829 11971 3899 3827 11972 3897 3832 11973 3902 3829 11974 3899 3830 11975 3900 3832 11976 3902 3831 11977 3901 3829 11978 3899 3834 11979 3904 3831 11980 3901 3832 11981 3902 3834 11982 3904 3833 11983 3903 3831 11984 3901 3838 11985 3908 3833 11986 3903 3834 11987 3904 3838 11988 3908 3835 11989 3905 3833 11990 3903 3838 11991 3908 3836 11992 3906 3835 11993 3905 3838 11994 3908 3837 11995 3907 3836 11996 3906 3840 11997 3910 3837 11998 3907 3838 11999 3908 3840 12000 3910 3839 12001 3909 3837 12002 3907 3845 12003 3915 3839 12004 3909 3840 12005 3910 3845 12006 3915 3841 12007 3911 3839 12008 3909 3844 12009 3914 3825 12010 3895 3842 12011 3912 3844 12012 3914 3843 12013 3913 3825 12014 3895 3808 12015 3878 3843 12016 3913 3844 12017 3914 3808 12018 3878 3845 12019 3915 3843 12020 3913 3808 12021 3878 3841 12022 3911 3845 12023 3915 3879 12024 3949 3846 12025 3916 3849 12026 3919 3879 12027 3949 3847 12028 3917 3848 12029 3918 3879 12030 3949 3849 12031 3919 3847 12032 3917 3854 12033 3924 3850 12034 3920 3851 12035 3921 3854 12036 3924 3852 12037 3922 3850 12038 3920 3854 12039 3924 3853 12040 3923 3852 12041 3922 3856 12042 3926 3853 12043 3923 3854 12044 3924 3856 12045 3926 3855 12046 3925 3853 12047 3923 3858 12048 3928 3855 12049 3925 3856 12050 3926 3858 12051 3928 3857 12052 3927 3855 12053 3925 3860 12054 3930 3857 12055 3927 3858 12056 3928 3860 12057 3930 3859 12058 3929 3857 12059 3927 3862 12060 3932 3859 12061 3929 3860 12062 3930 3862 12063 3932 3861 12064 3931 3859 12065 3929 3864 12066 3934 3861 12067 3931 3862 12068 3932 3864 12069 3934 3863 12070 3933 3861 12071 3931 3866 12072 3936 3863 12073 3933 3864 12074 3934 3866 12075 3936 3865 12076 3935 3863 12077 3933 3868 12078 3938 3865 12079 3935 3866 12080 3936 3868 12081 3938 3867 12082 3937 3865 12083 3935 3870 12084 3940 3867 12085 3937 3868 12086 3938 3870 12087 3940 3869 12088 3939 3867 12089 3937 3872 12090 3942 3869 12091 3939 3870 12092 3940 3872 12093 3942 3871 12094 3941 3869 12095 3939 3874 12096 3944 3871 12097 3941 3872 12098 3942 3874 12099 3944 3873 12100 3943 3871 12101 3941 3875 12102 3945 3873 12103 3943 3874 12104 3944 3877 12105 3947 3873 12106 3943 3875 12107 3945 3877 12108 3947 3876 12109 3946 3873 12110 3943 3846 12111 3916 3876 12112 3946 3877 12113 3947 3846 12114 3916 3878 12115 3948 3876 12116 3946 3846 12117 3916 3879 12118 3949 3878 12119 3948 3912 12120 3982 3884 12121 3954 3880 12122 3950 3883 12123 3953 3881 12124 3951 3882 12125 3952 3885 12126 3955 3881 12127 3951 3883 12128 3953 3885 12129 3955 3884 12130 3954 3881 12131 3951 3880 12132 3950 3884 12133 3954 3885 12134 3955 3890 12135 3960 3886 12136 3956 3887 12137 3957 3890 12138 3960 3888 12139 3958 3886 12140 3956 3890 12141 3960 3889 12142 3959 3888 12143 3958 3891 12144 3961 3889 12145 3959 3890 12146 3960 3894 12147 3964 3889 12148 3959 3891 12149 3961 3894 12150 3964 3892 12151 3962 3889 12152 3959 3894 12153 3964 3893 12154 3963 3892 12155 3962 3896 12156 3966 3893 12157 3963 3894 12158 3964 3896 12159 3966 3895 12160 3965 3893 12161 3963 3897 12162 3967 3895 12163 3965 3896 12164 3966 3899 12165 3969 3895 12166 3965 3897 12167 3967 3899 12168 3969 3898 12169 3968 3895 12170 3965 3901 12171 3971 3898 12172 3968 3899 12173 3969 3901 12174 3971 3900 12175 3970 3898 12176 3968 3903 12177 3973 3900 12178 3970 3901 12179 3971 3903 12180 3973 3902 12181 3972 3900 12182 3970 3905 12183 3975 3902 12184 3972 3903 12185 3973 3905 12186 3975 3904 12187 3974 3902 12188 3972 3907 12189 3977 3904 12190 3974 3905 12191 3975 3907 12192 3977 3906 12193 3976 3904 12194 3974 3909 12195 3979 3906 12196 3976 3907 12197 3977 3909 12198 3979 3908 12199 3978 3906 12200 3976 3911 12201 3981 3908 12202 3978 3909 12203 3979 3911 12204 3981 3910 12205 3980 3908 12206 3978 3913 12207 3983 3910 12208 3980 3911 12209 3981 3913 12210 3983 3912 12211 3982 3910 12212 3980 3884 12213 3954 3912 12214 3982 3913 12215 3983 3977 12216 4047 3914 12217 3984 3916 12218 3986 3916 12219 3986 3915 12220 3985 3977 12221 4047 3918 12222 3988 3915 12223 3985 3916 12224 3986 3918 12225 3988 3917 12226 3987 3915 12227 3985 3920 12228 3990 3917 12229 3987 3918 12230 3988 3920 12231 3990 3919 12232 3989 3917 12233 3987 3922 12234 3992 3919 12235 3989 3920 12236 3990 3922 12237 3992 3921 12238 3991 3919 12239 3989 3924 12240 3994 3921 12241 3991 3922 12242 3992 3924 12243 3994 3923 12244 3993 3921 12245 3991 3926 12246 3996 3923 12247 3993 3924 12248 3994 3926 12249 3996 3925 12250 3995 3923 12251 3993 3928 12252 3998 3925 12253 3995 3926 12254 3996 3928 12255 3998 3927 12256 3997 3925 12257 3995 3930 12258 4000 3927 12259 3997 3928 12260 3998 3930 12261 4000 3929 12262 3999 3927 12263 3997 3932 12264 4002 3929 12265 3999 3930 12266 4000 3932 12267 4002 3931 12268 4001 3929 12269 3999 3934 12270 4004 3931 12271 4001 3932 12272 4002 3934 12273 4004 3933 12274 4003 3931 12275 4001 3936 12276 4006 3933 12277 4003 3934 12278 4004 3936 12279 4006 3935 12280 4005 3933 12281 4003 3938 12282 4008 3935 12283 4005 3936 12284 4006 3938 12285 4008 3937 12286 4007 3935 12287 4005 3940 12288 4010 3937 12289 4007 3938 12290 4008 3940 12291 4010 3939 12292 4009 3937 12293 4007 3942 12294 4012 3939 12295 4009 3940 12296 4010 3942 12297 4012 3941 12298 4011 3939 12299 4009 3944 12300 4014 3941 12301 4011 3942 12302 4012 3944 12303 4014 3943 12304 4013 3941 12305 4011 3946 12306 4016 3943 12307 4013 3944 12308 4014 3946 12309 4016 3945 12310 4015 3943 12311 4013 3948 12312 4018 3945 12313 4015 3946 12314 4016 3948 12315 4018 3947 12316 4017 3945 12317 4015 3950 12318 4020 3947 12319 4017 3948 12320 4018 3950 12321 4020 3949 12322 4019 3947 12323 4017 3952 12324 4022 3949 12325 4019 3950 12326 4020 3952 12327 4022 3951 12328 4021 3949 12329 4019 3954 12330 4024 3951 12331 4021 3952 12332 4022 3954 12333 4024 3953 12334 4023 3951 12335 4021 3956 12336 4026 3953 12337 4023 3954 12338 4024 3956 12339 4026 3955 12340 4025 3953 12341 4023 3958 12342 4028 3955 12343 4025 3956 12344 4026 3958 12345 4028 3957 12346 4027 3955 12347 4025 3960 12348 4030 3957 12349 4027 3958 12350 4028 3960 12351 4030 3959 12352 4029 3957 12353 4027 3962 12354 4032 3959 12355 4029 3960 12356 4030 3962 12357 4032 3961 12358 4031 3959 12359 4029 3964 12360 4034 3961 12361 4031 3962 12362 4032 3964 12363 4034 3963 12364 4033 3961 12365 4031 3966 12366 4036 3963 12367 4033 3964 12368 4034 3966 12369 4036 3965 12370 4035 3963 12371 4033 3968 12372 4038 3965 12373 4035 3966 12374 4036 3968 12375 4038 3967 12376 4037 3965 12377 4035 3970 12378 4040 3967 12379 4037 3968 12380 4038 3970 12381 4040 3969 12382 4039 3967 12383 4037 3972 12384 4042 3969 12385 4039 3970 12386 4040 3972 12387 4042 3971 12388 4041 3969 12389 4039 3974 12390 4044 3971 12391 4041 3972 12392 4042 3974 12393 4044 3973 12394 4043 3971 12395 4041 3976 12396 4046 3973 12397 4043 3974 12398 4044 3976 12399 4046 3975 12400 4045 3973 12401 4043 3914 12402 3984 3975 12403 4045 3976 12404 4046 3914 12405 3984 3977 12406 4047 3975 12407 4045 3980 12408 4050 3978 12409 4048 3979 12410 4049 3978 12411 4048 3980 12412 4050 3981 12413 4051 3984 12414 4054 3982 12415 4052 3983 12416 4053 3982 12417 4052 3984 12418 4054 3985 12419 4055 3988 12420 4058 3986 12421 4056 3987 12422 4057 3986 12423 4056 3988 12424 4058 3989 12425 4059 3992 12426 4062 3990 12427 4060 3991 12428 4061 3990 12429 4060 3992 12430 4062 3993 12431 4063 3996 12432 4066 3994 12433 4064 3995 12434 4065 3994 12435 4064 3996 12436 4066 3997 12437 4067 4000 12438 4070 3998 12439 4068 3999 12440 4069 3998 12441 4068 4000 12442 4070 4001 12443 4071 4004 12444 4074 4002 12445 4072 4003 12446 4073 4002 12447 4072 4004 12448 4074 4005 12449 4075 4022 12450 4092 4006 12451 4076 4007 12452 4077 4010 12453 4080 4008 12454 4078 4009 12455 4079 4012 12456 4082 4008 12457 4078 4010 12458 4080 4012 12459 4082 4011 12460 4081 4008 12461 4078 4014 12462 4084 4011 12463 4081 4012 12464 4082 4014 12465 4084 4013 12466 4083 4011 12467 4081 4016 12468 4086 4013 12469 4083 4014 12470 4084 4016 12471 4086 4015 12472 4085 4013 12473 4083 4018 12474 4088 4015 12475 4085 4016 12476 4086 4018 12477 4088 4017 12478 4087 4015 12479 4085 4019 12480 4089 4017 12481 4087 4018 12482 4088 4021 12483 4091 4017 12484 4087 4019 12485 4089 4021 12486 4091 4020 12487 4090 4017 12488 4087 4023 12489 4093 4020 12490 4090 4021 12491 4091 4023 12492 4093 4022 12493 4092 4020 12494 4090 4006 12495 4076 4022 12496 4092 4023 12497 4093 4043 12498 4113 4024 12499 4094 4041 12500 4111 4027 12501 4097 4025 12502 4095 4026 12503 4096 4029 12504 4099 4025 12505 4095 4027 12506 4097 4029 12507 4099 4028 12508 4098 4025 12509 4095 4031 12510 4101 4028 12511 4098 4029 12512 4099 4031 12513 4101 4030 12514 4100 4028 12515 4098 4033 12516 4103 4030 12517 4100 4031 12518 4101 4033 12519 4103 4032 12520 4102 4030 12521 4100 4035 12522 4105 4032 12523 4102 4033 12524 4103 4035 12525 4105 4034 12526 4104 4032 12527 4102 4036 12528 4106 4034 12529 4104 4035 12530 4105 4038 12531 4108 4034 12532 4104 4036 12533 4106 4038 12534 4108 4037 12535 4107 4034 12536 4104 4040 12537 4110 4037 12538 4107 4038 12539 4108 4040 12540 4110 4039 12541 4109 4037 12542 4107 4024 12543 4094 4039 12544 4109 4040 12545 4110 4043 12546 4113 4041 12547 4111 4042 12548 4112 4024 12549 4094 4043 12550 4113 4039 12551 4109 4046 12552 4116 4044 12553 4114 4045 12554 4115 4044 12555 4114 4046 12556 4116 4047 12557 4117 4050 12558 4120 4048 12559 4118 4049 12560 4119 4048 12561 4118 4050 12562 4120 4051 12563 4121 4054 12564 4124 4052 12565 4122 4053 12566 4123 4052 12567 4122 4054 12568 4124 4055 12569 4125 4058 12570 4128 4056 12571 4126 4057 12572 4127 4056 12573 4126 4058 12574 4128 4059 12575 4129 4062 12576 4132 4060 12577 4130 4061 12578 4131 4060 12579 4130 4062 12580 4132 4063 12581 4133 4066 12582 4136 4064 12583 4134 4065 12584 4135 4064 12585 4134 4066 12586 4136 4067 12587 4137 4070 12588 4140 4068 12589 4138 4069 12590 4139 4068 12591 4138 4070 12592 4140 4071 12593 4141 4074 12594 4144 4072 12595 4142 4073 12596 4143 4072 12597 4142 4074 12598 4144 4075 12599 4145 4078 12600 4148 4076 12601 4146 4077 12602 4147 4076 12603 4146 4078 12604 4148 4079 12605 4149 4082 12606 4152 4080 12607 4150 4081 12608 4151 4080 12609 4150 4082 12610 4152 4083 12611 4153 4086 12612 4156 4084 12613 4154 4085 12614 4155 4084 12615 4154 4086 12616 4156 4087 12617 4157 4090 12618 4160 4088 12619 4158 4089 12620 4159 4088 12621 4158 4090 12622 4160 4091 12623 4161 4094 12624 4164 4092 12625 4162 4093 12626 4163 4092 12627 4162 4094 12628 4164 4095 12629 4165 4098 12630 4168 4096 12631 4166 4097 12632 4167 4096 12633 4166 4098 12634 4168 4099 12635 4169 4102 12636 4172 4100 12637 4170 4101 12638 4171 4100 12639 4170 4102 12640 4172 4103 12641 4173 4106 12642 4176 4104 12643 4174 4105 12644 4175 4104 12645 4174 4106 12646 4176 4107 12647 4177 4110 12648 4180 4108 12649 4178 4109 12650 4179 4108 12651 4178 4110 12652 4180 4111 12653 4181 4114 12654 4184 4112 12655 4182 4113 12656 4183 4112 12657 4182 4114 12658 4184 4115 12659 4185 4118 12660 4188 4116 12661 4186 4117 12662 4187 4116 12663 4186 4118 12664 4188 4119 12665 4189 4122 12666 4192 4120 12667 4190 4121 12668 4191 4120 12669 4190 4122 12670 4192 4123 12671 4193 4126 12672 4196 4124 12673 4194 4125 12674 4195 4124 12675 4194 4126 12676 4196 4127 12677 4197 4130 12678 4202 4128 12679 4198 4129 12680 4199 4128 12681 4198 4130 12682 4200 4131 12683 4201 4134 12684 4205 4132 12685 4207 4133 12686 4204 4132 12687 4203 4134 12688 4205 4135 12689 4206 4138 12690 4210 4136 12691 4208 4137 12692 4209 4136 12693 4208 4138 12694 4210 4139 12695 4211 4142 12696 4214 4140 12697 4212 4141 12698 4213 4140 12699 4212 4142 12700 4214 4143 12701 4215 4146 12702 4218 4144 12703 4216 4145 12704 4217 4144 12705 4216 4146 12706 4218 4147 12707 4219 4150 12708 4222 4148 12709 4220 4149 12710 4221 4148 12711 4220 4150 12712 4222 4151 12713 4223 4154 12714 4226 4152 12715 4224 4153 12716 4225 4152 12717 4224 4154 12718 4226 4155 12719 4227 4158 12720 4230 4156 12721 4228 4157 12722 4229 4156 12723 4228 4158 12724 4230 4159 12725 4231 4162 12726 4234 4160 12727 4232 4161 12728 4233 4160 12729 4232 4162 12730 4234 4163 12731 4235 4166 12732 4238 4164 12733 4236 4165 12734 4237 4164 12735 4236 4166 12736 4238 4167 12737 4239 4170 12738 4242 4168 12739 4240 4169 12740 4241 4177 12741 4249 4170 12742 4242 4171 12743 4243 4178 12744 4250 4172 12745 4244 4173 12746 4245 4178 12747 4250 4174 12748 4246 4172 12749 4244 4178 12750 4250 4175 12751 4247 4174 12752 4246 4178 12753 4250 4176 12754 4248 4175 12755 4247 4178 12756 4250 4177 12757 4249 4176 12758 4248 4178 12759 4250 4170 12760 4242 4177 12761 4249 4179 12762 4251 4170 12763 4242 4178 12764 4250 4180 12765 4252 4170 12766 4242 4179 12767 4251 4181 12768 4253 4170 12769 4242 4180 12770 4252 4182 12771 4254 4170 12772 4242 4181 12773 4253 4183 12774 4255 4170 12775 4242 4182 12776 4254 4168 12777 4240 4170 12778 4242 4183 12779 4255 4186 12780 4258 4184 12781 4256 4185 12782 4257 4188 12783 4260 4186 12784 4258 4187 12785 4259 4189 12786 4261 4186 12787 4258 4188 12788 4260 4190 12789 4262 4186 12790 4258 4189 12791 4261 4191 12792 4263 4186 12793 4258 4190 12794 4262 4192 12795 4264 4186 12796 4258 4191 12797 4263 4193 12798 4265 4186 12799 4258 4192 12800 4264 4194 12801 4266 4186 12802 4258 4193 12803 4265 4195 12804 4267 4186 12805 4258 4194 12806 4266 4196 12807 4268 4186 12808 4258 4195 12809 4267 4197 12810 4269 4186 12811 4258 4196 12812 4268 4198 12813 4270 4186 12814 4258 4197 12815 4269 4199 12816 4271 4186 12817 4258 4198 12818 4270 4184 12819 4256 4186 12820 4258 4199 12821 4271 4202 12822 4274 4200 12823 4272 4201 12824 4273 4200 12825 4272 4202 12826 4274 4203 12827 4275 4206 12828 4278 4204 12829 4276 4205 12830 4277 4204 12831 4276 4206 12832 4278 4207 12833 4279 4210 12834 4282 4208 12835 4280 4209 12836 4281 4212 12837 4284 4210 12838 4282 4211 12839 4283 4213 12840 4285 4210 12841 4282 4212 12842 4284 4214 12843 4286 4210 12844 4282 4213 12845 4285 4215 12846 4287 4210 12847 4282 4214 12848 4286 4216 12849 4288 4210 12850 4282 4215 12851 4287 4217 12852 4289 4210 12853 4282 4216 12854 4288 4218 12855 4290 4210 12856 4282 4217 12857 4289 4219 12858 4291 4210 12859 4282 4218 12860 4290 4220 12861 4292 4210 12862 4282 4219 12863 4291 4221 12864 4293 4210 12865 4282 4220 12866 4292 4222 12867 4294 4210 12868 4282 4221 12869 4293 4208 12870 4280 4210 12871 4282 4222 12872 4294 4231 12873 4303 4223 12874 4295 4224 12875 4296 4232 12876 4304 4225 12877 4297 4226 12878 4298 4232 12879 4304 4227 12880 4299 4225 12881 4297 4232 12882 4304 4228 12883 4300 4227 12884 4299 4232 12885 4304 4229 12886 4301 4228 12887 4300 4232 12888 4304 4230 12889 4302 4229 12890 4301 4232 12891 4304 4231 12892 4303 4230 12893 4302 4233 12894 4305 4231 12895 4303 4232 12896 4304 4234 12897 4306 4231 12898 4303 4233 12899 4305 4235 12900 4307 4231 12901 4303 4234 12902 4306 4236 12903 4308 4231 12904 4303 4235 12905 4307 4237 12906 4309 4231 12907 4303 4236 12908 4308 4223 12909 4295 4231 12910 4303 4237 12911 4309 4240 12912 4312 4238 12913 4310 4239 12914 4311 4238 12915 4310 4240 12916 4312 4241 12917 4313 4244 12918 4316 4242 12919 4314 4243 12920 4315 4242 12921 4314 4244 12922 4316 4245 12923 4317 4254 12924 4326 4246 12925 4318 4247 12926 4319 4255 12927 4327 4248 12928 4320 4249 12929 4321 4255 12930 4327 4250 12931 4322 4248 12932 4320 4255 12933 4327 4251 12934 4323 4250 12935 4322 4255 12936 4327 4252 12937 4324 4251 12938 4323 4255 12939 4327 4253 12940 4325 4252 12941 4324 4255 12942 4327 4254 12943 4326 4253 12944 4325 4256 12945 4328 4254 12946 4326 4255 12947 4327 4257 12948 4329 4254 12949 4326 4256 12950 4328 4258 12951 4330 4254 12952 4326 4257 12953 4329 4259 12954 4331 4254 12955 4326 4258 12956 4330 4260 12957 4332 4254 12958 4326 4259 12959 4331 4246 12960 4318 4254 12961 4326 4260 12962 4332 4263 12963 4335 4261 12964 4333 4262 12965 4334 4265 12966 4337 4263 12967 4335 4264 12968 4336 4266 12969 4338 4263 12970 4335 4265 12971 4337 4267 12972 4339 4263 12973 4335 4266 12974 4338 4268 12975 4340 4263 12976 4335 4267 12977 4339 4269 12978 4341 4263 12979 4335 4268 12980 4340 4270 12981 4342 4263 12982 4335 4269 12983 4341 4271 12984 4343 4263 12985 4335 4270 12986 4342 4272 12987 4344 4263 12988 4335 4271 12989 4343 4273 12990 4345 4263 12991 4335 4272 12992 4344 4274 12993 4346 4263 12994 4335 4273 12995 4345 4275 12996 4347 4263 12997 4335 4274 12998 4346 4261 12999 4333 4263 13000 4335 4275 13001 4347 4278 13002 4350 4276 13003 4348 4277 13004 4349 4276 13005 4348 4278 13006 4350 4279 13007 4351 4282 13008 4354 4280 13009 4352 4281 13010 4353 4280 13011 4352 4282 13012 4354 4283 13013 4355 4292 13014 4364 4284 13015 4356 4285 13016 4357 4293 13017 4365 4286 13018 4358 4287 13019 4359 4293 13020 4365 4288 13021 4360 4286 13022 4358 4293 13023 4365 4289 13024 4361 4288 13025 4360 4293 13026 4365 4290 13027 4362 4289 13028 4361 4293 13029 4365 4291 13030 4363 4290 13031 4362 4293 13032 4365 4292 13033 4364 4291 13034 4363 4294 13035 4366 4292 13036 4364 4293 13037 4365 4295 13038 4367 4292 13039 4364 4294 13040 4366 4296 13041 4368 4292 13042 4364 4295 13043 4367 4297 13044 4369 4292 13045 4364 4296 13046 4368 4298 13047 4370 4292 13048 4364 4297 13049 4369 4284 13050 4356 4292 13051 4364 4298 13052 4370 4301 13053 4373 4299 13054 4371 4300 13055 4372 4303 13056 4375 4301 13057 4373 4302 13058 4374 4304 13059 4376 4301 13060 4373 4303 13061 4375 4305 13062 4377 4301 13063 4373 4304 13064 4376 4306 13065 4378 4301 13066 4373 4305 13067 4377 4307 13068 4379 4301 13069 4373 4306 13070 4378 4308 13071 4380 4301 13072 4373 4307 13073 4379 4309 13074 4381 4301 13075 4373 4308 13076 4380 4310 13077 4382 4301 13078 4373 4309 13079 4381 4311 13080 4383 4301 13081 4373 4310 13082 4382 4312 13083 4384 4301 13084 4373 4311 13085 4383 4313 13086 4385 4301 13087 4373 4312 13088 4384 4299 13089 4371 4301 13090 4373 4313 13091 4385 4316 13092 4388 4314 13093 4386 4315 13094 4387 4314 13095 4386 4316 13096 4388 4317 13097 4389 4320 13098 4392 4318 13099 4390 4319 13100 4391 4318 13101 4390 4320 13102 4392 4321 13103 4393 4330 13104 4402 4322 13105 4394 4323 13106 4395 4331 13107 4403 4324 13108 4396 4325 13109 4397 4331 13110 4403 4326 13111 4398 4324 13112 4396 4331 13113 4403 4327 13114 4399 4326 13115 4398 4331 13116 4403 4328 13117 4400 4327 13118 4399 4331 13119 4403 4329 13120 4401 4328 13121 4400 4331 13122 4403 4330 13123 4402 4329 13124 4401 4332 13125 4404 4330 13126 4402 4331 13127 4403 4333 13128 4405 4330 13129 4402 4332 13130 4404 4334 13131 4406 4330 13132 4402 4333 13133 4405 4335 13134 4407 4330 13135 4402 4334 13136 4406 4336 13137 4408 4330 13138 4402 4335 13139 4407 4322 13140 4394 4330 13141 4402 4336 13142 4408 4339 13143 4411 4337 13144 4409 4338 13145 4410 4341 13146 4413 4339 13147 4411 4340 13148 4412 4342 13149 4414 4339 13150 4411 4341 13151 4413 4343 13152 4415 4339 13153 4411 4342 13154 4414 4344 13155 4416 4339 13156 4411 4343 13157 4415 4345 13158 4417 4339 13159 4411 4344 13160 4416 4346 13161 4418 4339 13162 4411 4345 13163 4417 4347 13164 4419 4339 13165 4411 4346 13166 4418 4348 13167 4420 4339 13168 4411 4347 13169 4419 4349 13170 4421 4339 13171 4411 4348 13172 4420 4350 13173 4422 4339 13174 4411 4349 13175 4421 4351 13176 4423 4339 13177 4411 4350 13178 4422 4337 13179 4409 4339 13180 4411 4351 13181 4423 4354 13182 4426 4352 13183 4424 4353 13184 4425 4352 13185 4424 4354 13186 4426 4355 13187 4427 4358 13188 4430 4356 13189 4428 4357 13190 4429 4356 13191 4428 4358 13192 4430 4359 13193 4431 4368 13194 4440 4360 13195 4432 4361 13196 4433 4369 13197 4441 4362 13198 4434 4363 13199 4435 4369 13200 4441 4364 13201 4436 4362 13202 4434 4369 13203 4441 4365 13204 4437 4364 13205 4436 4369 13206 4441 4366 13207 4438 4365 13208 4437 4369 13209 4441 4367 13210 4439 4366 13211 4438 4369 13212 4441 4368 13213 4440 4367 13214 4439 4370 13215 4442 4368 13216 4440 4369 13217 4441 4371 13218 4443 4368 13219 4440 4370 13220 4442 4372 13221 4444 4368 13222 4440 4371 13223 4443 4373 13224 4445 4368 13225 4440 4372 13226 4444 4374 13227 4446 4368 13228 4440 4373 13229 4445 4360 13230 4432 4368 13231 4440 4374 13232 4446 4377 13233 4449 4375 13234 4447 4376 13235 4448 4379 13236 4451 4377 13237 4449 4378 13238 4450 4380 13239 4452 4377 13240 4449 4379 13241 4451 4381 13242 4453 4377 13243 4449 4380 13244 4452 4382 13245 4454 4377 13246 4449 4381 13247 4453 4383 13248 4455 4377 13249 4449 4382 13250 4454 4384 13251 4456 4377 13252 4449 4383 13253 4455 4385 13254 4457 4377 13255 4449 4384 13256 4456 4386 13257 4458 4377 13258 4449 4385 13259 4457 4387 13260 4459 4377 13261 4449 4386 13262 4458 4388 13263 4460 4377 13264 4449 4387 13265 4459 4389 13266 4461 4377 13267 4449 4388 13268 4460 4375 13269 4447 4377 13270 4449 4389 13271 4461 4392 13272 4464 4390 13273 4462 4391 13274 4463 4390 13275 4462 4392 13276 4464 4393 13277 4465 4396 13278 4468 4394 13279 4466 4395 13280 4467 4394 13281 4466 4396 13282 4468 4397 13283 4469 4400 13284 4472 4398 13285 4470 4399 13286 4471 4398 13287 4470 4400 13288 4472 4401 13289 4473 4404 13290 4476 4402 13291 4474 4403 13292 4475 4402 13293 4474 4404 13294 4476 4405 13295 4477 4408 13296 4480 4406 13297 4478 4407 13298 4479 4406 13299 4478 4408 13300 4480 4409 13301 4481 4412 13302 4484 4410 13303 4482 4411 13304 4483 4410 13305 4482 4412 13306 4484 4413 13307 4485 4416 13308 4488 4414 13309 4486 4415 13310 4487 4414 13311 4486 4416 13312 4488 4417 13313 4489 4420 13314 4492 4418 13315 4490 4419 13316 4491 4418 13317 4490 4420 13318 4492 4421 13319 4493 4424 13320 4496 4422 13321 4494 4423 13322 4495 4422 13323 4494 4424 13324 4496 4425 13325 4497 4428 13326 4500 4426 13327 4498 4427 13328 4499 4426 13329 4498 4428 13330 4500 4429 13331 4501 4432 13332 4504 4430 13333 4506 4431 13334 4503 4430 13335 4502 4432 13336 4504 4433 13337 4505 4436 13338 4509 4434 13339 4507 4435 13340 4508 4434 13341 4507 4436 13342 4509 4437 13343 4510 4440 13344 4513 4438 13345 4511 4439 13346 4512 4438 13347 4511 4440 13348 4513 4441 13349 4514 4444 13350 4517 4442 13351 4515 4443 13352 4516 4442 13353 4515 4444 13354 4517 4445 13355 4518 4448 13356 4521 4446 13357 4519 4447 13358 4520 4446 13359 4519 4448 13360 4521 4449 13361 4522 4452 13362 4525 4450 13363 4523 4451 13364 4524 4450 13365 4523 4452 13366 4525 4453 13367 4526 4456 13368 4529 4454 13369 4527 4455 13370 4528 4454 13371 4527 4456 13372 4529 4457 13373 4530 4460 13374 4533 4458 13375 4531 4459 13376 4532 4458 13377 4531 4460 13378 4533 4461 13379 4534 4464 13380 4537 4462 13381 4535 4463 13382 4536 4462 13383 4535 4464 13384 4537 4465 13385 4538 4468 13386 4541 4466 13387 4539 4467 13388 4540 4470 13389 4543 4468 13390 4541 4469 13391 4542 4466 13392 4539 4468 13393 4541 4470 13394 4543 4474 13395 4547 4471 13396 4544 4472 13397 4545 4474 13398 4547 4472 13399 4545 4473 13400 4546 4471 13401 4544 4474 13402 4547 4475 13403 4548 4479 13404 4552 4477 13405 4550 4476 13406 4549 4476 13407 4549 4477 13408 4550 4478 13409 4551 4477 13410 4550 4479 13411 4552 4480 13412 4553 4481 13413 4554 4482 13414 4555 4483 13415 4556 4484 13416 4557 4485 13417 4558 4486 13418 4559 4489 13419 4562 4487 13420 4560 4488 13421 4561 4487 13422 4560 4489 13423 4562 4490 13424 4563 4495 13425 4568 4491 13426 4564 4492 13427 4565 4491 13428 4564 4493 13429 4566 4494 13430 4567 4491 13431 4564 4495 13432 4568 4493 13433 4566 4498 13434 4571 4496 13435 4569 4497 13436 4570 4496 13437 4569 4498 13438 4571 4499 13439 4572 4502 13440 4575 4500 13441 4573 4501 13442 4574 4500 13443 4573 4502 13444 4575 4503 13445 4576 4506 13446 4579 4504 13447 4577 4505 13448 4578 4504 13449 4577 4506 13450 4579 4507 13451 4580 4510 13452 4583 4508 13453 4581 4509 13454 4582 4508 13455 4581 4510 13456 4583 4511 13457 4584 4544 13458 4617 4513 13459 4586 4512 13460 4585 4515 13461 4588 4513 13462 4586 4514 13463 4587 4512 13464 4585 4513 13465 4586 4515 13466 4588 4518 13467 4591 4516 13468 4589 4517 13469 4590 4519 13470 4592 4516 13471 4589 4518 13472 4591 4521 13473 4594 4516 13474 4589 4519 13475 4592 4521 13476 4594 4520 13477 4593 4516 13478 4589 4523 13479 4596 4520 13480 4593 4521 13481 4594 4523 13482 4596 4522 13483 4595 4520 13484 4593 4525 13485 4598 4522 13486 4595 4523 13487 4596 4525 13488 4598 4524 13489 4597 4522 13490 4595 4527 13491 4600 4524 13492 4597 4525 13493 4598 4527 13494 4600 4526 13495 4599 4524 13496 4597 4529 13497 4602 4526 13498 4599 4527 13499 4600 4529 13500 4602 4528 13501 4601 4526 13502 4599 4531 13503 4604 4528 13504 4601 4529 13505 4602 4531 13506 4604 4530 13507 4603 4528 13508 4601 4534 13509 4607 4530 13510 4603 4531 13511 4604 4534 13512 4607 4532 13513 4605 4530 13514 4603 4534 13515 4607 4533 13516 4606 4532 13517 4605 4535 13518 4608 4533 13519 4606 4534 13520 4607 4538 13521 4611 4533 13522 4606 4535 13523 4608 4538 13524 4611 4536 13525 4609 4533 13526 4606 4538 13527 4611 4537 13528 4610 4536 13529 4609 4539 13530 4612 4537 13531 4610 4538 13532 4611 4541 13533 4614 4537 13534 4610 4539 13535 4612 4541 13536 4614 4540 13537 4613 4537 13538 4610 4543 13539 4616 4540 13540 4613 4541 13541 4614 4543 13542 4616 4542 13543 4615 4540 13544 4613 4545 13545 4618 4542 13546 4615 4543 13547 4616 4545 13548 4618 4544 13549 4617 4542 13550 4615 4513 13551 4586 4544 13552 4617 4545 13553 4618 4548 13554 4621 4546 13555 4623 4547 13556 4620 4546 13557 4619 4548 13558 4621 4549 13559 4622 4567 13560 4641 4550 13561 4624 4551 13562 4625 4554 13563 4628 4552 13564 4626 4553 13565 4627 4555 13566 4629 4552 13567 4626 4554 13568 4628 4558 13569 4632 4552 13570 4626 4555 13571 4629 4558 13572 4632 4556 13573 4630 4552 13574 4626 4558 13575 4632 4557 13576 4631 4556 13577 4630 4560 13578 4634 4557 13579 4631 4558 13580 4632 4560 13581 4634 4559 13582 4633 4557 13583 4631 4561 13584 4635 4559 13585 4633 4560 13586 4634 4563 13587 4637 4559 13588 4633 4561 13589 4635 4563 13590 4637 4562 13591 4636 4559 13592 4633 4566 13593 4640 4562 13594 4636 4563 13595 4637 4566 13596 4640 4564 13597 4638 4562 13598 4636 4566 13599 4640 4565 13600 4639 4564 13601 4638 4550 13602 4624 4565 13603 4639 4566 13604 4640 4550 13605 4624 4567 13606 4641 4565 13607 4639 4570 13608 4644 4568 13609 4642 4569 13610 4643 4568 13611 4642 4570 13612 4644 4571 13613 4645 4574 13614 4648 4572 13615 4646 4573 13616 4647 4572 13617 4646 4574 13618 4648 4575 13619 4649 4578 13620 4652 4576 13621 4650 4577 13622 4651 4576 13623 4650 4578 13624 4652 4579 13625 4653 4582 13626 4656 4580 13627 4654 4581 13628 4655 4580 13629 4654 4582 13630 4656 4583 13631 4657 4586 13632 4660 4584 13633 4658 4585 13634 4659 4584 13635 4658 4586 13636 4660 4587 13637 4661 4619 13638 4693 4588 13639 4662 4598 13640 4672 4619 13641 4693 4595 13642 4669 4589 13643 4663 4619 13644 4693 4590 13645 4664 4595 13646 4669 4619 13647 4693 4591 13648 4665 4590 13649 4664 4619 13650 4693 4592 13651 4666 4591 13652 4665 4619 13653 4693 4593 13654 4667 4592 13655 4666 4619 13656 4693 4594 13657 4668 4593 13658 4667 4596 13659 4670 4589 13660 4663 4595 13661 4669 4599 13662 4673 4589 13663 4663 4596 13664 4670 4619 13665 4693 4597 13666 4671 4594 13667 4668 4619 13668 4693 4598 13669 4672 4597 13670 4671 4600 13671 4674 4589 13672 4663 4599 13673 4673 4602 13674 4676 4589 13675 4663 4600 13676 4674 4602 13677 4676 4601 13678 4675 4589 13679 4663 4603 13680 4677 4601 13681 4675 4602 13682 4676 4604 13683 4678 4601 13684 4675 4603 13685 4677 4605 13686 4679 4601 13687 4675 4604 13688 4678 4606 13689 4680 4601 13690 4675 4605 13691 4679 4607 13692 4681 4601 13693 4675 4606 13694 4680 4609 13695 4683 4601 13696 4675 4607 13697 4681 4609 13698 4683 4608 13699 4682 4601 13700 4675 4610 13701 4684 4608 13702 4682 4609 13703 4683 4611 13704 4685 4608 13705 4682 4610 13706 4684 4612 13707 4686 4608 13708 4682 4611 13709 4685 4613 13710 4687 4608 13711 4682 4612 13712 4686 4614 13713 4688 4608 13714 4682 4613 13715 4687 4615 13716 4689 4608 13717 4682 4614 13718 4688 4616 13719 4690 4608 13720 4682 4615 13721 4689 4617 13722 4691 4608 13723 4682 4616 13724 4690 4618 13725 4692 4608 13726 4682 4617 13727 4691 4620 13728 4694 4608 13729 4682 4618 13730 4692 4620 13731 4694 4619 13732 4693 4608 13733 4682 4621 13734 4695 4619 13735 4693 4620 13736 4694 4622 13737 4696 4619 13738 4693 4621 13739 4695 4623 13740 4697 4619 13741 4693 4622 13742 4696 4588 13743 4662 4619 13744 4693 4623 13745 4697 4657 13746 4731 4624 13747 4698 4636 13748 4710 4627 13749 4701 4625 13750 4699 4626 13751 4700 4628 13752 4702 4625 13753 4699 4627 13754 4701 4630 13755 4704 4625 13756 4699 4628 13757 4702 4630 13758 4704 4629 13759 4703 4625 13760 4699 4633 13761 4707 4629 13762 4703 4630 13763 4704 4633 13764 4707 4631 13765 4705 4629 13766 4703 4633 13767 4707 4632 13768 4706 4631 13769 4705 4635 13770 4709 4632 13771 4706 4633 13772 4707 4635 13773 4709 4634 13774 4708 4632 13775 4706 4637 13776 4711 4634 13777 4708 4635 13778 4709 4637 13779 4711 4636 13780 4710 4634 13781 4708 4657 13782 4731 4636 13783 4710 4637 13784 4711 4641 13785 4715 4638 13786 4712 4639 13787 4713 4641 13788 4715 4640 13789 4714 4638 13790 4712 4643 13791 4717 4640 13792 4714 4641 13793 4715 4643 13794 4717 4642 13795 4716 4640 13796 4714 4645 13797 4719 4642 13798 4716 4643 13799 4717 4645 13800 4719 4644 13801 4718 4642 13802 4716 4647 13803 4721 4644 13804 4718 4645 13805 4719 4647 13806 4721 4646 13807 4720 4644 13808 4718 4650 13809 4724 4646 13810 4720 4647 13811 4721 4650 13812 4724 4648 13813 4722 4646 13814 4720 4650 13815 4724 4649 13816 4723 4648 13817 4722 4651 13818 4725 4649 13819 4723 4650 13820 4724 4653 13821 4727 4649 13822 4723 4651 13823 4725 4653 13824 4727 4652 13825 4726 4649 13826 4723 4656 13827 4730 4652 13828 4726 4653 13829 4727 4656 13830 4730 4654 13831 4728 4652 13832 4726 4656 13833 4730 4655 13834 4729 4654 13835 4728 4624 13836 4698 4655 13837 4729 4656 13838 4730 4624 13839 4698 4657 13840 4731 4655 13841 4729 4721 13842 4795 4658 13843 4732 4660 13844 4734 4660 13845 4734 4659 13846 4733 4721 13847 4795 4662 13848 4736 4659 13849 4733 4660 13850 4734 4662 13851 4736 4661 13852 4735 4659 13853 4733 4664 13854 4738 4661 13855 4735 4662 13856 4736 4664 13857 4738 4663 13858 4737 4661 13859 4735 4666 13860 4740 4663 13861 4737 4664 13862 4738 4666 13863 4740 4665 13864 4739 4663 13865 4737 4668 13866 4742 4665 13867 4739 4666 13868 4740 4668 13869 4742 4667 13870 4741 4665 13871 4739 4670 13872 4744 4667 13873 4741 4668 13874 4742 4670 13875 4744 4669 13876 4743 4667 13877 4741 4672 13878 4746 4669 13879 4743 4670 13880 4744 4672 13881 4746 4671 13882 4745 4669 13883 4743 4674 13884 4748 4671 13885 4745 4672 13886 4746 4674 13887 4748 4673 13888 4747 4671 13889 4745 4676 13890 4750 4673 13891 4747 4674 13892 4748 4676 13893 4750 4675 13894 4749 4673 13895 4747 4678 13896 4752 4675 13897 4749 4676 13898 4750 4678 13899 4752 4677 13900 4751 4675 13901 4749 4680 13902 4754 4677 13903 4751 4678 13904 4752 4680 13905 4754 4679 13906 4753 4677 13907 4751 4682 13908 4756 4679 13909 4753 4680 13910 4754 4682 13911 4756 4681 13912 4755 4679 13913 4753 4684 13914 4758 4681 13915 4755 4682 13916 4756 4684 13917 4758 4683 13918 4757 4681 13919 4755 4686 13920 4760 4683 13921 4757 4684 13922 4758 4686 13923 4760 4685 13924 4759 4683 13925 4757 4688 13926 4762 4685 13927 4759 4686 13928 4760 4688 13929 4762 4687 13930 4761 4685 13931 4759 4690 13932 4764 4687 13933 4761 4688 13934 4762 4690 13935 4764 4689 13936 4763 4687 13937 4761 4692 13938 4766 4689 13939 4763 4690 13940 4764 4692 13941 4766 4691 13942 4765 4689 13943 4763 4694 13944 4768 4691 13945 4765 4692 13946 4766 4694 13947 4768 4693 13948 4767 4691 13949 4765 4696 13950 4770 4693 13951 4767 4694 13952 4768 4696 13953 4770 4695 13954 4769 4693 13955 4767 4698 13956 4772 4695 13957 4769 4696 13958 4770 4698 13959 4772 4697 13960 4771 4695 13961 4769 4700 13962 4774 4697 13963 4771 4698 13964 4772 4700 13965 4774 4699 13966 4773 4697 13967 4771 4702 13968 4776 4699 13969 4773 4700 13970 4774 4702 13971 4776 4701 13972 4775 4699 13973 4773 4704 13974 4778 4701 13975 4775 4702 13976 4776 4704 13977 4778 4703 13978 4777 4701 13979 4775 4706 13980 4780 4703 13981 4777 4704 13982 4778 4706 13983 4780 4705 13984 4779 4703 13985 4777 4708 13986 4782 4705 13987 4779 4706 13988 4780 4708 13989 4782 4707 13990 4781 4705 13991 4779 4710 13992 4784 4707 13993 4781 4708 13994 4782 4710 13995 4784 4709 13996 4783 4707 13997 4781 4712 13998 4786 4709 13999 4783 4710 14000 4784 4712 14001 4786 4711 14002 4785 4709 14003 4783 4714 14004 4788 4711 14005 4785 4712 14006 4786 4714 14007 4788 4713 14008 4787 4711 14009 4785 4716 14010 4790 4713 14011 4787 4714 14012 4788 4716 14013 4790 4715 14014 4789 4713 14015 4787 4718 14016 4792 4715 14017 4789 4716 14018 4790 4718 14019 4792 4717 14020 4791 4715 14021 4789 4720 14022 4794 4717 14023 4791 4718 14024 4792 4720 14025 4794 4719 14026 4793 4717 14027 4791 4658 14028 4732 4719 14029 4793 4720 14030 4794 4658 14031 4732 4721 14032 4795 4719 14033 4793 4741 14034 4815 4722 14035 4796 4723 14036 4797 4732 14037 4806 4724 14038 4798 4725 14039 4799 4732 14040 4806 4726 14041 4800 4724 14042 4798 4732 14043 4806 4727 14044 4801 4726 14045 4800 4732 14046 4806 4728 14047 4802 4727 14048 4801 4732 14049 4806 4729 14050 4803 4728 14051 4802 4732 14052 4806 4730 14053 4804 4729 14054 4803 4732 14055 4806 4731 14056 4805 4730 14057 4804 4722 14058 4796 4731 14059 4805 4732 14060 4806 4722 14061 4796 4733 14062 4807 4731 14063 4805 4722 14064 4796 4734 14065 4808 4733 14066 4807 4722 14067 4796 4735 14068 4809 4734 14069 4808 4722 14070 4796 4736 14071 4810 4735 14072 4809 4722 14073 4796 4737 14074 4811 4736 14075 4810 4722 14076 4796 4738 14077 4812 4737 14078 4811 4722 14079 4796 4739 14080 4813 4738 14081 4812 4722 14082 4796 4740 14083 4814 4739 14084 4813 4722 14085 4796 4741 14086 4815 4740 14087 4814 4744 14088 4818 4742 14089 4816 4743 14090 4817 4742 14091 4816 4744 14092 4818 4745 14093 4819 4765 14094 4839 4746 14095 4820 4747 14096 4821 4756 14097 4830 4748 14098 4822 4749 14099 4823 4756 14100 4830 4750 14101 4824 4748 14102 4822 4756 14103 4830 4751 14104 4825 4750 14105 4824 4756 14106 4830 4752 14107 4826 4751 14108 4825 4756 14109 4830 4753 14110 4827 4752 14111 4826 4756 14112 4830 4754 14113 4828 4753 14114 4827 4756 14115 4830 4755 14116 4829 4754 14117 4828 4746 14118 4820 4755 14119 4829 4756 14120 4830 4746 14121 4820 4757 14122 4831 4755 14123 4829 4746 14124 4820 4758 14125 4832 4757 14126 4831 4746 14127 4820 4759 14128 4833 4758 14129 4832 4746 14130 4820 4760 14131 4834 4759 14132 4833 4746 14133 4820 4761 14134 4835 4760 14135 4834 4746 14136 4820 4762 14137 4836 4761 14138 4835 4746 14139 4820 4763 14140 4837 4762 14141 4836 4746 14142 4820 4764 14143 4838 4763 14144 4837 4746 14145 4820 4765 14146 4839 4764 14147 4838 4768 14148 4842 4766 14149 4840 4767 14150 4841 4766 14151 4840 4768 14152 4842 4769 14153 4843 4883 14154 4957 4844 14155 4918 4780 14156 4854 4785 14157 4859 4783 14158 4857 4770 14159 4844 4785 14160 4859 4771 14161 4845 4783 14162 4857 4786 14163 4860 4788 14164 4862 4772 14165 4846 4786 14166 4860 4773 14167 4847 4788 14168 4862 4838 14169 4912 4774 14170 4848 4775 14171 4849 4846 14172 4920 4776 14173 4850 4777 14174 4851 4881 14175 4955 4778 14176 4852 4779 14177 4853 4883 14178 4957 4780 14179 4854 4781 14180 4855 4785 14181 4859 4782 14182 4856 4771 14183 4845 4791 14184 4865 4770 14185 4844 4783 14186 4857 4791 14187 4865 4784 14188 4858 4770 14189 4844 4793 14190 4867 4782 14191 4856 4785 14192 4859 4796 14193 4870 4773 14194 4847 4786 14195 4860 4796 14196 4870 4787 14197 4861 4773 14198 4847 4794 14199 4868 4772 14200 4846 4788 14201 4862 4794 14202 4868 4789 14203 4863 4772 14204 4846 4793 14205 4867 4790 14206 4864 4782 14207 4856 4799 14208 4873 4784 14209 4858 4791 14210 4865 4799 14211 4873 4792 14212 4866 4784 14213 4858 4801 14214 4875 4790 14215 4864 4793 14216 4867 4804 14217 4878 4789 14218 4863 4794 14219 4868 4804 14220 4878 4795 14221 4869 4789 14222 4863 4802 14223 4876 4787 14224 4861 4796 14225 4870 4802 14226 4876 4797 14227 4871 4787 14228 4861 4801 14229 4875 4798 14230 4872 4790 14231 4864 4807 14232 4881 4792 14233 4866 4799 14234 4873 4807 14235 4881 4800 14236 4874 4792 14237 4866 4809 14238 4883 4798 14239 4872 4801 14240 4875 4812 14241 4886 4797 14242 4871 4802 14243 4876 4812 14244 4886 4803 14245 4877 4797 14246 4871 4810 14247 4884 4795 14248 4869 4804 14249 4878 4810 14250 4884 4805 14251 4879 4795 14252 4869 4809 14253 4883 4806 14254 4880 4798 14255 4872 4815 14256 4889 4800 14257 4874 4807 14258 4881 4815 14259 4889 4808 14260 4882 4800 14261 4874 4821 14262 4895 4806 14263 4880 4809 14264 4883 4818 14265 4892 4805 14266 4879 4810 14267 4884 4818 14268 4892 4811 14269 4885 4805 14270 4879 4816 14271 4890 4803 14272 4877 4812 14273 4886 4816 14274 4890 4813 14275 4887 4803 14276 4877 4821 14277 4895 4814 14278 4888 4806 14279 4880 4823 14280 4897 4808 14281 4882 4815 14282 4889 4826 14283 4900 4813 14284 4887 4816 14285 4890 4826 14286 4900 4817 14287 4891 4813 14288 4887 4824 14289 4898 4811 14290 4885 4818 14291 4892 4824 14292 4898 4819 14293 4893 4811 14294 4885 4823 14295 4897 4820 14296 4894 4808 14297 4882 4829 14298 4903 4814 14299 4888 4821 14300 4895 4829 14301 4903 4822 14302 4896 4814 14303 4888 4831 14304 4905 4820 14305 4894 4823 14306 4897 4834 14307 4908 4819 14308 4893 4824 14309 4898 4834 14310 4908 4825 14311 4899 4819 14312 4893 4832 14313 4906 4817 14314 4891 4826 14315 4900 4832 14316 4906 4827 14317 4901 4817 14318 4891 4831 14319 4905 4828 14320 4902 4820 14321 4894 4837 14322 4911 4822 14323 4896 4829 14324 4903 4837 14325 4911 4830 14326 4904 4822 14327 4896 4839 14328 4913 4828 14329 4902 4831 14330 4905 4842 14331 4916 4827 14332 4901 4832 14333 4906 4842 14334 4916 4833 14335 4907 4827 14336 4901 4840 14337 4914 4825 14338 4899 4834 14339 4908 4840 14340 4914 4835 14341 4909 4825 14342 4899 4839 14343 4913 4836 14344 4910 4828 14345 4902 4845 14346 4919 4830 14347 4904 4837 14348 4911 4845 14349 4919 4838 14350 4912 4830 14351 4904 4780 14352 4854 4836 14353 4910 4839 14354 4913 4848 14355 4922 4835 14356 4909 4840 14357 4914 4848 14358 4922 4841 14359 4915 4835 14360 4909 4885 14361 4959 4833 14362 4907 4842 14363 4916 4885 14364 4959 4843 14365 4917 4833 14366 4907 4780 14367 4854 4844 14368 4918 4836 14369 4910 4847 14370 4921 4838 14371 4912 4845 14372 4919 4847 14373 4921 4774 14374 4848 4838 14375 4912 4847 14376 4921 4846 14377 4920 4774 14378 4848 4841 14379 4915 4846 14380 4920 4847 14381 4921 4848 14382 4922 4846 14383 4920 4841 14384 4915 4849 14385 4923 4846 14386 4920 4848 14387 4922 4849 14388 4923 4776 14389 4850 4846 14390 4920 4851 14391 4925 4776 14392 4850 4849 14393 4923 4851 14394 4925 4850 14395 4924 4776 14396 4850 4853 14397 4927 4850 14398 4924 4851 14399 4925 4853 14400 4927 4852 14401 4926 4850 14402 4924 4855 14403 4929 4852 14404 4926 4853 14405 4927 4855 14406 4929 4854 14407 4928 4852 14408 4926 4857 14409 4931 4854 14410 4928 4855 14411 4929 4857 14412 4931 4856 14413 4930 4854 14414 4928 4859 14415 4933 4856 14416 4930 4857 14417 4931 4859 14418 4933 4858 14419 4932 4856 14420 4930 4861 14421 4935 4858 14422 4932 4859 14423 4933 4861 14424 4935 4860 14425 4934 4858 14426 4932 4863 14427 4937 4860 14428 4934 4861 14429 4935 4863 14430 4937 4862 14431 4936 4860 14432 4934 4865 14433 4939 4862 14434 4936 4863 14435 4937 4865 14436 4939 4864 14437 4938 4862 14438 4936 4868 14439 4942 4864 14440 4938 4865 14441 4939 4868 14442 4942 4866 14443 4940 4864 14444 4938 4868 14445 4942 4867 14446 4941 4866 14447 4940 4870 14448 4944 4867 14449 4941 4868 14450 4942 4870 14451 4944 4869 14452 4943 4867 14453 4941 4872 14454 4946 4869 14455 4943 4870 14456 4944 4872 14457 4946 4871 14458 4945 4869 14459 4943 4874 14460 4948 4871 14461 4945 4872 14462 4946 4874 14463 4948 4873 14464 4947 4871 14465 4945 4876 14466 4950 4873 14467 4947 4874 14468 4948 4876 14469 4950 4875 14470 4949 4873 14471 4947 4878 14472 4952 4875 14473 4949 4876 14474 4950 4878 14475 4952 4877 14476 4951 4875 14477 4949 4880 14478 4954 4877 14479 4951 4878 14480 4952 4880 14481 4954 4879 14482 4953 4877 14483 4951 4882 14484 4956 4879 14485 4953 4880 14486 4954 4882 14487 4956 4881 14488 4955 4879 14489 4953 4884 14490 4958 4881 14491 4955 4882 14492 4956 4884 14493 4958 4778 14494 4852 4881 14495 4955 4884 14496 4958 4883 14497 4957 4778 14498 4852 4843 14499 4917 4883 14500 4957 4884 14501 4958 4885 14502 4959 4883 14503 4957 4843 14504 4917 4844 14505 4918 4883 14506 4957 4885 14507 4959 4890 14508 4964 4886 14509 4960 4887 14510 4961 4891 14511 4965 4888 14512 4962 4889 14513 4963 4891 14514 4965 4890 14515 4964 4888 14516 4962 4886 14517 4960 4890 14518 4964 4891 14519 4965 4894 14520 4968 4892 14521 4966 4893 14522 4967 4892 14523 4966 4894 14524 4968 4895 14525 4969 4901 14526 4975 4896 14527 4970 4897 14528 4971 4900 14529 4974 4898 14530 4972 4899 14531 4973 4896 14532 4970 4898 14533 4972 4900 14534 4974 4896 14535 4970 4901 14536 4975 4898 14537 4972 4961 14538 5035 4902 14539 4976 4903 14540 4977 4909 14541 4983 4904 14542 4978 4905 14543 4979 4964 14544 5038 4906 14545 4980 4907 14546 4981 4964 14547 5038 4908 14548 4982 4906 14549 4980 4910 14550 4984 4904 14551 4978 4909 14552 4983 4913 14553 4987 4904 14554 4978 4910 14555 4984 4964 14556 5038 4911 14557 4985 4908 14558 4982 4964 14559 5038 4912 14560 4986 4911 14561 4985 4914 14562 4988 4904 14563 4978 4913 14564 4987 4922 14565 4996 4904 14566 4978 4914 14567 4988 4964 14568 5038 4915 14569 4989 4912 14570 4986 4927 14571 5001 4930 14572 5004 4916 14573 4990 4927 14574 5001 4917 14575 4991 4930 14576 5004 4927 14577 5001 4918 14578 4992 4917 14579 4991 4927 14580 5001 4919 14581 4993 4918 14582 4992 4927 14583 5001 4920 14584 4994 4919 14585 4993 4964 14586 5038 4921 14587 4995 4915 14588 4989 4924 14589 4998 4904 14590 4978 4922 14591 4996 4927 14592 5001 4923 14593 4997 4920 14594 4994 4928 14595 5002 4904 14596 4978 4924 14597 4998 4964 14598 5038 4925 14599 4999 4921 14600 4995 4927 14601 5001 4926 14602 5000 4923 14603 4997 4964 14604 5038 4927 14605 5001 4925 14606 4999 4916 14607 4990 4904 14608 4978 4928 14609 5002 4927 14610 5001 4929 14611 5003 4926 14612 5000 4931 14613 5005 4916 14614 4990 4930 14615 5004 4943 14616 5017 4916 14617 4990 4931 14618 5005 4927 14619 5001 4932 14620 5006 4929 14621 5003 4927 14622 5001 4933 14623 5007 4932 14624 5006 4964 14625 5038 4933 14626 5007 4927 14627 5001 4964 14628 5038 4934 14629 5008 4933 14630 5007 4964 14631 5038 4935 14632 5009 4934 14633 5008 4964 14634 5038 4936 14635 5010 4935 14636 5009 4964 14637 5038 4937 14638 5011 4936 14639 5010 4964 14640 5038 4938 14641 5012 4937 14642 5011 4964 14643 5038 4939 14644 5013 4938 14645 5012 4964 14646 5038 4940 14647 5014 4939 14648 5013 4964 14649 5038 4941 14650 5015 4940 14651 5014 4964 14652 5038 4942 14653 5016 4941 14654 5015 4944 14655 5018 4916 14656 4990 4943 14657 5017 4944 14658 5018 4904 14659 4978 4916 14660 4990 4945 14661 5019 4904 14662 4978 4944 14663 5018 4946 14664 5020 4904 14665 4978 4945 14666 5019 4947 14667 5021 4904 14668 4978 4946 14669 5020 4948 14670 5022 4904 14671 4978 4947 14672 5021 4949 14673 5023 4904 14674 4978 4948 14675 5022 4950 14676 5024 4904 14677 4978 4949 14678 5023 4951 14679 5025 4904 14680 4978 4950 14681 5024 4952 14682 5026 4904 14683 4978 4951 14684 5025 4962 14685 5036 4904 14686 4978 4952 14687 5026 4962 14688 5036 4953 14689 5027 4904 14690 4978 4962 14691 5036 4954 14692 5028 4953 14693 5027 4962 14694 5036 4955 14695 5029 4954 14696 5028 4962 14697 5036 4956 14698 5030 4955 14699 5029 4962 14700 5036 4957 14701 5031 4956 14702 5030 4962 14703 5036 4958 14704 5032 4957 14705 5031 4962 14706 5036 4959 14707 5033 4958 14708 5032 4962 14709 5036 4960 14710 5034 4959 14711 5033 4962 14712 5036 4961 14713 5035 4960 14714 5034 4963 14715 5037 4961 14716 5035 4962 14717 5036 4942 14718 5016 4961 14719 5035 4963 14720 5037 4964 14721 5038 4961 14722 5035 4942 14723 5016 4965 14724 5039 4961 14725 5035 4964 14726 5038 4966 14727 5040 4961 14728 5035 4965 14729 5039 4967 14730 5041 4961 14731 5035 4966 14732 5040 4968 14733 5042 4961 14734 5035 4967 14735 5041 4969 14736 5043 4961 14737 5035 4968 14738 5042 4902 14739 4976 4961 14740 5035 4969 14741 5043 4974 14742 5048 4970 14743 5044 4971 14744 5045 4975 14745 5049 4972 14746 5046 4973 14747 5047 4975 14748 5049 4974 14749 5048 4972 14750 5046 4970 14751 5044 4974 14752 5048 4975 14753 5049 4978 14754 5052 4976 14755 5050 4977 14756 5051 4976 14757 5050 4978 14758 5052 4979 14759 5053 4985 14760 5059 4980 14761 5054 4981 14762 5055 4984 14763 5058 4982 14764 5056 4983 14765 5057 4980 14766 5054 4982 14767 5056 4984 14768 5058 4980 14769 5054 4985 14770 5059 4982 14771 5056 4988 14772 5062 4986 14773 5060 4987 14774 5061 4993 14775 5067 4988 14776 5062 4989 14777 5063 5037 14778 5111 4990 14779 5064 4991 14780 5065 5037 14781 5111 4992 14782 5066 4990 14783 5064 4994 14784 5068 4988 14785 5062 4993 14786 5067 4997 14787 5071 4988 14788 5062 4994 14789 5068 5037 14790 5111 4995 14791 5069 4992 14792 5066 5037 14793 5111 4996 14794 5070 4995 14795 5069 4998 14796 5072 4988 14797 5062 4997 14798 5071 5006 14799 5080 4988 14800 5062 4998 14801 5072 5037 14802 5111 4999 14803 5073 4996 14804 5070 5001 14805 5075 5000 14806 5074 5011 14807 5085 5002 14808 5076 5000 14809 5074 5001 14810 5075 5003 14811 5077 5000 14812 5074 5002 14813 5076 5004 14814 5078 5000 14815 5074 5003 14816 5077 5007 14817 5081 5000 14818 5074 5004 14819 5078 5037 14820 5111 5005 14821 5079 4999 14822 5073 5008 14823 5082 4988 14824 5062 5006 14825 5080 5010 14826 5084 5000 14827 5074 5007 14828 5081 5012 14829 5086 4988 14830 5062 5008 14831 5082 5037 14832 5111 5009 14833 5083 5005 14834 5079 5013 14835 5087 5000 14836 5074 5010 14837 5084 5037 14838 5111 5011 14839 5085 5009 14840 5083 5000 14841 5074 4988 14842 5062 5012 14843 5086 5016 14844 5090 5000 14845 5074 5013 14846 5087 5011 14847 5085 5014 14848 5088 5001 14849 5075 5011 14850 5085 5015 14851 5089 5014 14852 5088 5017 14853 5091 5000 14854 5074 5016 14855 5090 5018 14856 5092 5000 14857 5074 5017 14858 5091 5018 14859 5092 4988 14860 5062 5000 14861 5074 5019 14862 5093 4988 14863 5062 5018 14864 5092 5020 14865 5094 4988 14866 5062 5019 14867 5093 5021 14868 5095 4988 14869 5062 5020 14870 5094 5022 14871 5096 4988 14872 5062 5021 14873 5095 5023 14874 5097 4988 14875 5062 5022 14876 5096 5024 14877 5098 4988 14878 5062 5023 14879 5097 5025 14880 5099 4988 14881 5062 5024 14882 5098 5026 14883 5100 4988 14884 5062 5025 14885 5099 5047 14886 5121 4988 14887 5062 5026 14888 5100 5011 14889 5085 5027 14890 5101 5015 14891 5089 5037 14892 5111 5027 14893 5101 5011 14894 5085 5037 14895 5111 5028 14896 5102 5027 14897 5101 5037 14898 5111 5029 14899 5103 5028 14900 5102 5037 14901 5111 5030 14902 5104 5029 14903 5103 5037 14904 5111 5031 14905 5105 5030 14906 5104 5037 14907 5111 5032 14908 5106 5031 14909 5105 5037 14910 5111 5033 14911 5107 5032 14912 5106 5037 14913 5111 5034 14914 5108 5033 14915 5107 5037 14916 5111 5035 14917 5109 5034 14918 5108 5037 14919 5111 5036 14920 5110 5035 14921 5109 5038 14922 5112 5036 14923 5110 5037 14924 5111 5039 14925 5113 5036 14926 5110 5038 14927 5112 5040 14928 5114 5036 14929 5110 5039 14930 5113 5041 14931 5115 5036 14932 5110 5040 14933 5114 5042 14934 5116 5036 14935 5110 5041 14936 5115 5043 14937 5117 5036 14938 5110 5042 14939 5116 5044 14940 5118 5036 14941 5110 5043 14942 5117 5045 14943 5119 5036 14944 5110 5044 14945 5118 5048 14946 5122 5036 14947 5110 5045 14948 5119 5048 14949 5122 5046 14950 5120 5036 14951 5110 5048 14952 5122 5047 14953 5121 5046 14954 5120 5048 14955 5122 4988 14956 5062 5047 14957 5121 5049 14958 5123 4988 14959 5062 5048 14960 5122 5050 14961 5124 4988 14962 5062 5049 14963 5123 5051 14964 5125 4988 14965 5062 5050 14966 5124 5052 14967 5126 4988 14968 5062 5051 14969 5125 5053 14970 5127 4988 14971 5062 5052 14972 5126 4986 14973 5060 4988 14974 5062 5053 14975 5127 5056 14976 5130 5054 14977 5128 5055 14978 5129 5054 14979 5128 5056 14980 5130 5057 14981 5131 5060 14982 5134 5058 14983 5132 5059 14984 5133 5058 14985 5132 5060 14986 5134 5061 14987 5135 5064 14988 5138 5062 14989 5136 5063 14990 5137 5062 14991 5136 5064 14992 5138 5065 14993 5139 5068 14994 5142 5066 14995 5140 5067 14996 5141 5066 14997 5140 5068 14998 5142 5069 14999 5143 5072 15000 5146 5070 15001 5144 5071 15002 5145 5070 15003 5144 5072 15004 5146 5073 15005 5147 5076 15006 5150 5074 15007 5148 5075 15008 5149 5074 15009 5148 5076 15010 5150 5077 15011 5151 5080 15012 5154 5078 15013 5152 5079 15014 5153 5078 15015 5152 5080 15016 5154 5081 15017 5155 5084 15018 5158 5082 15019 5156 5083 15020 5157 5082 15021 5156 5084 15022 5158 5085 15023 5159 5104 15024 5178 5086 15025 5160 5105 15026 5179 5106 15027 5180 5086 15028 5160 5087 15029 5161 5105 15030 5179 5086 15031 5160 5106 15032 5180 5090 15033 5164 5088 15034 5162 5089 15035 5163 5090 15036 5164 5107 15037 5181 5088 15038 5162 5091 15039 5165 5107 15040 5181 5090 15041 5164 5091 15042 5165 5108 15043 5182 5107 15044 5181 5092 15045 5166 5108 15046 5182 5091 15047 5165 5092 15048 5166 5109 15049 5183 5108 15050 5182 5093 15051 5167 5109 15052 5183 5092 15053 5166 5093 15054 5167 5110 15055 5184 5109 15056 5183 5094 15057 5168 5110 15058 5184 5093 15059 5167 5094 15060 5168 5111 15061 5185 5110 15062 5184 5095 15063 5169 5111 15064 5185 5094 15065 5168 5095 15066 5169 5112 15067 5186 5111 15068 5185 5096 15069 5170 5112 15070 5186 5095 15071 5169 5096 15072 5170 5113 15073 5187 5112 15074 5186 5096 15075 5170 5114 15076 5188 5113 15077 5187 5097 15078 5171 5114 15079 5188 5096 15080 5170 5098 15081 5172 5114 15082 5188 5097 15083 5171 5098 15084 5172 5115 15085 5189 5114 15086 5188 5098 15087 5172 5116 15088 5190 5115 15089 5189 5099 15090 5173 5116 15091 5190 5098 15092 5172 5100 15093 5174 5116 15094 5190 5099 15095 5173 5100 15096 5174 5117 15097 5191 5116 15098 5190 5100 15099 5174 5118 15100 5192 5117 15101 5191 5101 15102 5175 5118 15103 5192 5100 15104 5174 5102 15105 5176 5118 15106 5192 5101 15107 5175 5102 15108 5176 5119 15109 5193 5118 15110 5192 5103 15111 5177 5119 15112 5193 5102 15113 5176 5103 15114 5177 5104 15115 5178 5119 15116 5193 5086 15117 5160 5104 15118 5178 5103 15119 5177 5151 15120 5225 5132 15121 5206 5120 15122 5194 5123 15123 5197 5121 15124 5195 5122 15125 5196 5124 15126 5198 5121 15127 5195 5123 15128 5197 5126 15129 5200 5121 15130 5195 5124 15131 5198 5126 15132 5200 5125 15133 5199 5121 15134 5195 5128 15135 5202 5125 15136 5199 5126 15137 5200 5128 15138 5202 5127 15139 5201 5125 15140 5199 5130 15141 5204 5127 15142 5201 5128 15143 5202 5130 15144 5204 5129 15145 5203 5127 15146 5201 5133 15147 5207 5129 15148 5203 5130 15149 5204 5133 15150 5207 5131 15151 5205 5129 15152 5203 5133 15153 5207 5132 15154 5206 5131 15155 5205 5120 15156 5194 5132 15157 5206 5133 15158 5207 5138 15159 5212 5134 15160 5208 5135 15161 5209 5138 15162 5212 5136 15163 5210 5134 15164 5208 5138 15165 5212 5137 15166 5211 5136 15167 5210 5139 15168 5213 5137 15169 5211 5138 15170 5212 5141 15171 5215 5137 15172 5211 5139 15173 5213 5141 15174 5215 5140 15175 5214 5137 15176 5211 5143 15177 5217 5140 15178 5214 5141 15179 5215 5143 15180 5217 5142 15181 5216 5140 15182 5214 5145 15183 5219 5142 15184 5216 5143 15185 5217 5145 15186 5219 5144 15187 5218 5142 15188 5216 5147 15189 5221 5144 15190 5218 5145 15191 5219 5147 15192 5221 5146 15193 5220 5144 15194 5218 5149 15195 5223 5146 15196 5220 5147 15197 5221 5149 15198 5223 5148 15199 5222 5146 15200 5220 5152 15201 5226 5148 15202 5222 5149 15203 5223 5152 15204 5226 5150 15205 5224 5148 15206 5222 5152 15207 5226 5151 15208 5225 5150 15209 5224 5153 15210 5227 5151 15211 5225 5152 15212 5226 5132 15213 5206 5151 15214 5225 5153 15215 5227 5172 15216 5246 5156 15217 5230 5173 15218 5247 5174 15219 5248 5154 15220 5228 5175 15221 5249 5174 15222 5248 5155 15223 5229 5154 15224 5228 5173 15225 5247 5155 15226 5229 5174 15227 5248 5173 15228 5247 5156 15229 5230 5155 15230 5229 5159 15231 5233 5157 15232 5231 5158 15233 5232 5159 15234 5233 5176 15235 5250 5157 15236 5231 5160 15237 5234 5176 15238 5250 5159 15239 5233 5160 15240 5234 5177 15241 5251 5176 15242 5250 5161 15243 5235 5177 15244 5251 5160 15245 5234 5161 15246 5235 5178 15247 5252 5177 15248 5251 5162 15249 5236 5178 15250 5252 5161 15251 5235 5162 15252 5236 5179 15253 5253 5178 15254 5252 5163 15255 5237 5179 15256 5253 5162 15257 5236 5163 15258 5237 5180 15259 5254 5179 15260 5253 5164 15261 5238 5180 15262 5254 5163 15263 5237 5164 15264 5238 5181 15265 5255 5180 15266 5254 5165 15267 5239 5181 15268 5255 5164 15269 5238 5165 15270 5239 5182 15271 5256 5181 15272 5255 5165 15273 5239 5183 15274 5257 5182 15275 5256 5166 15276 5240 5183 15277 5257 5165 15278 5239 5167 15279 5241 5183 15280 5257 5166 15281 5240 5167 15282 5241 5184 15283 5258 5183 15284 5257 5168 15285 5242 5184 15286 5258 5167 15287 5241 5168 15288 5242 5185 15289 5259 5184 15290 5258 5169 15291 5243 5185 15292 5259 5168 15293 5242 5169 15294 5243 5186 15295 5260 5185 15296 5259 5170 15297 5244 5186 15298 5260 5169 15299 5243 5170 15300 5244 5187 15301 5261 5186 15302 5260 5170 15303 5244 5172 15304 5246 5187 15305 5261 5171 15306 5245 5172 15307 5246 5170 15308 5244 5156 15309 5230 5172 15310 5246 5171 15311 5245 5220 15312 5294 5196 15313 5270 5188 15314 5262 5192 15315 5266 5189 15316 5263 5190 15317 5264 5192 15318 5266 5191 15319 5265 5189 15320 5263 5194 15321 5268 5191 15322 5265 5192 15323 5266 5194 15324 5268 5193 15325 5267 5191 15326 5265 5197 15327 5271 5193 15328 5267 5194 15329 5268 5197 15330 5271 5195 15331 5269 5193 15332 5267 5197 15333 5271 5196 15334 5270 5195 15335 5269 5188 15336 5262 5196 15337 5270 5197 15338 5271 5201 15339 5275 5198 15340 5272 5199 15341 5273 5201 15342 5275 5200 15343 5274 5198 15344 5272 5203 15345 5277 5200 15346 5274 5201 15347 5275 5203 15348 5277 5202 15349 5276 5200 15350 5274 5205 15351 5279 5202 15352 5276 5203 15353 5277 5205 15354 5279 5204 15355 5278 5202 15356 5276 5207 15357 5281 5204 15358 5278 5205 15359 5279 5207 15360 5281 5206 15361 5280 5204 15362 5278 5209 15363 5283 5206 15364 5280 5207 15365 5281 5209 15366 5283 5208 15367 5282 5206 15368 5280 5211 15369 5285 5208 15370 5282 5209 15371 5283 5211 15372 5285 5210 15373 5284 5208 15374 5282 5213 15375 5287 5210 15376 5284 5211 15377 5285 5213 15378 5287 5212 15379 5286 5210 15380 5284 5215 15381 5289 5212 15382 5286 5213 15383 5287 5215 15384 5289 5214 15385 5288 5212 15386 5286 5217 15387 5291 5214 15388 5288 5215 15389 5289 5217 15390 5291 5216 15391 5290 5214 15392 5288 5219 15393 5293 5216 15394 5290 5217 15395 5291 5219 15396 5293 5218 15397 5292 5216 15398 5290 5221 15399 5295 5218 15400 5292 5219 15401 5293 5221 15402 5295 5220 15403 5294 5218 15404 5292 5196 15405 5270 5220 15406 5294 5221 15407 5295 5224 15408 5298 5222 15409 5296 5223 15410 5297 5222 15411 5296 5224 15412 5298 5225 15413 5299 5237 15414 5311 5226 15415 5300 5227 15416 5301 5232 15417 5306 5228 15418 5302 5229 15419 5303 5232 15420 5306 5230 15421 5304 5228 15422 5302 5232 15423 5306 5231 15424 5305 5230 15425 5304 5236 15426 5310 5231 15427 5305 5232 15428 5306 5236 15429 5310 5233 15430 5307 5231 15431 5305 5236 15432 5310 5234 15433 5308 5233 15434 5307 5236 15435 5310 5235 15436 5309 5234 15437 5308 5238 15438 5312 5235 15439 5309 5236 15440 5310 5238 15441 5312 5237 15442 5311 5235 15443 5309 5239 15444 5313 5237 15445 5311 5238 15446 5312 5240 15447 5314 5237 15448 5311 5239 15449 5313 5241 15450 5315 5237 15451 5311 5240 15452 5314 5242 15453 5316 5237 15454 5311 5241 15455 5315 5243 15456 5317 5237 15457 5311 5242 15458 5316 5244 15459 5318 5237 15460 5311 5243 15461 5317 5245 15462 5319 5237 15463 5311 5244 15464 5318 5246 15465 5320 5237 15466 5311 5245 15467 5319 5247 15468 5321 5237 15469 5311 5246 15470 5320 5248 15471 5322 5237 15472 5311 5247 15473 5321 5249 15474 5323 5237 15475 5311 5248 15476 5322 5250 15477 5324 5237 15478 5311 5249 15479 5323 5251 15480 5325 5237 15481 5311 5250 15482 5324 5252 15483 5326 5237 15484 5311 5251 15485 5325 5253 15486 5327 5237 15487 5311 5252 15488 5326 5254 15489 5328 5237 15490 5311 5253 15491 5327 5255 15492 5329 5237 15493 5311 5254 15494 5328 5256 15495 5330 5237 15496 5311 5255 15497 5329 5257 15498 5331 5237 15499 5311 5256 15500 5330 5258 15501 5332 5237 15502 5311 5257 15503 5331 5259 15504 5333 5237 15505 5311 5258 15506 5332 5260 15507 5334 5237 15508 5311 5259 15509 5333 5261 15510 5335 5237 15511 5311 5260 15512 5334 5226 15513 5300 5237 15514 5311 5261 15515 5335 5273 15516 5347 5262 15517 5336 5263 15518 5337 5268 15519 5342 5264 15520 5338 5265 15521 5339 5268 15522 5342 5266 15523 5340 5264 15524 5338 5268 15525 5342 5267 15526 5341 5266 15527 5340 5272 15528 5346 5267 15529 5341 5268 15530 5342 5272 15531 5346 5269 15532 5343 5267 15533 5341 5272 15534 5346 5270 15535 5344 5269 15536 5343 5272 15537 5346 5271 15538 5345 5270 15539 5344 5274 15540 5348 5271 15541 5345 5272 15542 5346 5274 15543 5348 5273 15544 5347 5271 15545 5345 5275 15546 5349 5273 15547 5347 5274 15548 5348 5276 15549 5350 5273 15550 5347 5275 15551 5349 5277 15552 5351 5273 15553 5347 5276 15554 5350 5278 15555 5352 5273 15556 5347 5277 15557 5351 5279 15558 5353 5273 15559 5347 5278 15560 5352 5280 15561 5354 5273 15562 5347 5279 15563 5353 5281 15564 5355 5273 15565 5347 5280 15566 5354 5282 15567 5356 5273 15568 5347 5281 15569 5355 5283 15570 5357 5273 15571 5347 5282 15572 5356 5284 15573 5358 5273 15574 5347 5283 15575 5357 5285 15576 5359 5273 15577 5347 5284 15578 5358 5286 15579 5360 5273 15580 5347 5285 15581 5359 5287 15582 5361 5273 15583 5347 5286 15584 5360 5288 15585 5362 5273 15586 5347 5287 15587 5361 5289 15588 5363 5273 15589 5347 5288 15590 5362 5290 15591 5364 5273 15592 5347 5289 15593 5363 5291 15594 5365 5273 15595 5347 5290 15596 5364 5292 15597 5366 5273 15598 5347 5291 15599 5365 5293 15600 5367 5273 15601 5347 5292 15602 5366 5294 15603 5368 5273 15604 5347 5293 15605 5367 5295 15606 5369 5273 15607 5347 5294 15608 5368 5296 15609 5370 5273 15610 5347 5295 15611 5369 5297 15612 5371 5273 15613 5347 5296 15614 5370 5262 15615 5336 5273 15616 5347 5297 15617 5371 5300 15618 5374 5298 15619 5372 5299 15620 5373 5298 15621 5372 5300 15622 5374 5301 15623 5375 5304 15624 5378 5302 15625 5376 5303 15626 5377 5302 15627 5376 5304 15628 5378 5305 15629 5379 5308 15630 5382 5306 15631 5380 5307 15632 5381 5306 15633 5380 5308 15634 5382 5309 15635 5383 5312 15636 5386 5310 15637 5384 5311 15638 5385 5310 15639 5384 5312 15640 5386 5313 15641 5387 5316 15642 5390 5314 15643 5388 5315 15644 5389 5314 15645 5388 5316 15646 5390 5317 15647 5391 5320 15648 5394 5318 15649 5392 5319 15650 5393 5318 15651 5392 5320 15652 5394 5321 15653 5395 5324 15654 5398 5322 15655 5396 5323 15656 5397 5322 15657 5396 5324 15658 5398 5325 15659 5399 5328 15660 5402 5326 15661 5400 5327 15662 5401 5326 15663 5400 5328 15664 5402 5329 15665 5403 5332 15666 5406 5330 15667 5404 5331 15668 5405 5330 15669 5404 5332 15670 5406 5333 15671 5407 5336 15672 5410 5334 15673 5408 5335 15674 5409 5334 15675 5408 5336 15676 5410 5337 15677 5411 5343 15678 5417 5338 15679 5412 5339 15680 5413 5338 15681 5412 5340 15682 5414 5341 15683 5415 5338 15684 5412 5342 15685 5416 5340 15686 5414 5338 15687 5412 5343 15688 5417 5342 15689 5416 5346 15690 5420 5344 15691 5418 5345 15692 5419 5348 15693 5422 5346 15694 5420 5347 15695 5421 5349 15696 5423 5346 15697 5420 5348 15698 5422 5344 15699 5418 5346 15700 5420 5349 15701 5423 5352 15702 5426 5350 15703 5424 5351 15704 5425 5350 15705 5424 5352 15706 5426 5353 15707 5427 5356 15708 5430 5354 15709 5428 5355 15710 5429 5354 15711 5428 5356 15712 5430 5357 15713 5431 5360 15714 5434 5358 15715 5432 5359 15716 5433 5358 15717 5432 5360 15718 5434 5361 15719 5435 5364 15720 5438 5362 15721 5436 5363 15722 5437 5362 15723 5436 5364 15724 5438 5365 15725 5439 5368 15726 5442 5366 15727 5440 5367 15728 5441 5366 15729 5440 5368 15730 5442 5369 15731 5443 5374 15732 5448 5370 15733 5444 5371 15734 5445 5375 15735 5449 5372 15736 5446 5373 15737 5447 5375 15738 5449 5374 15739 5448 5372 15740 5446 5370 15741 5444 5374 15742 5448 5375 15743 5449 5378 15744 5452 5376 15745 5450 5377 15746 5451 5380 15747 5454 5378 15748 5452 5379 15749 5453 5381 15750 5455 5378 15751 5452 5380 15752 5454 5376 15753 5450 5378 15754 5452 5381 15755 5455 5384 15756 5458 5382 15757 5456 5383 15758 5457 5382 15759 5456 5384 15760 5458 5385 15761 5459 5388 15762 5462 5386 15763 5460 5387 15764 5461 5386 15765 5460 5388 15766 5462 5389 15767 5463 5392 15768 5468 5390 15769 5464 5391 15770 5465 5390 15771 5464 5392 15772 5466 5393 15773 5467 5396 15774 5471 5394 15775 5469 5395 15776 5470 5394 15777 5469 5396 15778 5471 5397 15779 5472 5400 15780 5475 5398 15781 5473 5399 15782 5474 5398 15783 5473 5400 15784 5475 5401 15785 5476 5404 15786 5479 5402 15787 5477 5403 15788 5478 5402 15789 5477 5404 15790 5479 5405 15791 5480 5408 15792 5483 5406 15793 5481 5407 15794 5482 5406 15795 5481 5408 15796 5483 5409 15797 5484 5412 15798 5487 5410 15799 5485 5411 15800 5486 5410 15801 5485 5412 15802 5487 5413 15803 5488 5416 15804 5491 5414 15805 5489 5415 15806 5490 5414 15807 5489 5416 15808 5491 5417 15809 5492 5420 15810 5495 5418 15811 5493 5419 15812 5494 5418 15813 5493 5420 15814 5495 5421 15815 5496 5424 15816 5499 5422 15817 5497 5423 15818 5498 5422 15819 5497 5424 15820 5499 5425 15821 5500 5428 15822 5503 5426 15823 5501 5427 15824 5502 5430 15825 5505 5428 15826 5503 5429 15827 5504 5431 15828 5506 5428 15829 5503 5430 15830 5505 5426 15831 5501 5428 15832 5503 5431 15833 5506 5436 15834 5511 5432 15835 5507 5433 15836 5508 5437 15837 5512 5434 15838 5509 5435 15839 5510 5437 15840 5512 5436 15841 5511 5434 15842 5509 5432 15843 5507 5436 15844 5511 5437 15845 5512 5440 15846 5515 5438 15847 5513 5439 15848 5514 5438 15849 5513 5440 15850 5515 5441 15851 5516 5444 15852 5519 5442 15853 5517 5443 15854 5518 5442 15855 5517 5444 15856 5519 5445 15857 5520 5448 15858 5523 5446 15859 5521 5447 15860 5522 5446 15861 5521 5448 15862 5523 5449 15863 5524 5452 15864 5527 5450 15865 5525 5451 15866 5526 5450 15867 5525 5452 15868 5527 5453 15869 5528 5456 15870 5531 5454 15871 5529 5455 15872 5530 5454 15873 5529 5456 15874 5531 5457 15875 5532 5460 15876 5535 5458 15877 5533 5459 15878 5534 5462 15879 5537 5460 15880 5535 5461 15881 5536 5463 15882 5538 5460 15883 5535 5462 15884 5537 5458 15885 5533 5460 15886 5535 5463 15887 5538 5468 15888 5543 5464 15889 5539 5465 15890 5540 5469 15891 5544 5466 15892 5541 5467 15893 5542 5469 15894 5544 5468 15895 5543 5466 15896 5541 5464 15897 5539 5468 15898 5543 5469 15899 5544 5472 15900 5547 5470 15901 5545 5471 15902 5546 5470 15903 5545 5472 15904 5547 5473 15905 5548 5476 15906 5551 5474 15907 5549 5475 15908 5550 5474 15909 5549 5476 15910 5551 5477 15911 5552 5480 15912 5555 5478 15913 5553 5479 15914 5554 5478 15915 5553 5480 15916 5555 5481 15917 5556 5484 15918 5559 5482 15919 5557 5483 15920 5558 5482 15921 5557 5484 15922 5559 5485 15923 5560 5488 15924 5563 5486 15925 5561 5487 15926 5562 5486 15927 5561 5488 15928 5563 5489 15929 5564 5492 15930 5567 5490 15931 5565 5491 15932 5566 5494 15933 5569 5492 15934 5567 5493 15935 5568 5495 15936 5570 5492 15937 5567 5494 15938 5569 5490 15939 5565 5492 15940 5567 5495 15941 5570 5500 15942 5575 5499 15943 5574 5496 15944 5571 5496 15945 5571 5497 15946 5572 5498 15947 5573 5496 15948 5571 5499 15949 5574 5497 15950 5572 5499 15951 5574 5500 15952 5575 5501 15953 5576 5504 15954 5579 5502 15955 5577 5503 15956 5578 5502 15957 5577 5504 15958 5579 5505 15959 5580 5508 15960 5583 5506 15961 5581 5507 15962 5582 5506 15963 5581 5508 15964 5583 5509 15965 5584 5512 15966 5587 5510 15967 5585 5511 15968 5586 5510 15969 5585 5512 15970 5587 5513 15971 5588 5516 15972 5591 5514 15973 5589 5515 15974 5590 5514 15975 5589 5516 15976 5591 5517 15977 5592 5520 15978 5595 5518 15979 5593 5519 15980 5594 5518 15981 5593 5520 15982 5595 5521 15983 5596 5524 15984 5599 5522 15985 5597 5523 15986 5598 5526 15987 5601 5524 15988 5599 5525 15989 5600 5527 15990 5602 5524 15991 5599 5526 15992 5601 5522 15993 5597 5524 15994 5599 5527 15995 5602 5532 15996 5607 5528 15997 5603 5529 15998 5604 5533 15999 5608 5530 16000 5605 5531 16001 5606 5533 16002 5608 5532 16003 5607 5530 16004 5605 5528 16005 5603 5532 16006 5607 5533 16007 5608 5536 16008 5611 5534 16009 5609 5535 16010 5610 5534 16011 5609 5536 16012 5611 5537 16013 5612 5540 16014 5615 5538 16015 5613 5539 16016 5614 5538 16017 5613 5540 16018 5615 5541 16019 5616 5544 16020 5619 5542 16021 5617 5543 16022 5618 5542 16023 5617 5544 16024 5619 5545 16025 5620 5548 16026 5623 5546 16027 5621 5547 16028 5622 5546 16029 5621 5548 16030 5623 5549 16031 5624 5552 16032 5627 5550 16033 5625 5551 16034 5626 5550 16035 5625 5552 16036 5627 5553 16037 5628 5558 16038 5633 5554 16039 5629 5555 16040 5630 5559 16041 5634 5556 16042 5631 5557 16043 5632 5559 16044 5634 5558 16045 5633 5556 16046 5631 5554 16047 5629 5558 16048 5633 5559 16049 5634 5562 16050 5637 5560 16051 5635 5561 16052 5636 5564 16053 5639 5562 16054 5637 5563 16055 5638 5565 16056 5640 5562 16057 5637 5564 16058 5639 5560 16059 5635 5562 16060 5637 5565 16061 5640 5568 16062 5643 5566 16063 5641 5567 16064 5642 5566 16065 5641 5568 16066 5643 5569 16067 5644 5572 16068 5647 5570 16069 5645 5571 16070 5646 5570 16071 5645 5572 16072 5647 5573 16073 5648 5576 16074 5651 5574 16075 5649 5575 16076 5650 5574 16077 5649 5576 16078 5651 5577 16079 5652 5580 16080 5655 5578 16081 5653 5579 16082 5654 5578 16083 5653 5580 16084 5655 5581 16085 5656 5584 16086 5659 5582 16087 5657 5583 16088 5658 5582 16089 5657 5584 16090 5659 5585 16091 5660 5590 16092 5665 5586 16093 5661 5587 16094 5662 5591 16095 5666 5588 16096 5663 5589 16097 5664 5591 16098 5666 5590 16099 5665 5588 16100 5663 5586 16101 5661 5590 16102 5665 5591 16103 5666 5594 16104 5669 5592 16105 5667 5593 16106 5668 5596 16107 5671 5594 16108 5669 5595 16109 5670 5597 16110 5672 5594 16111 5669 5596 16112 5671 5592 16113 5667 5594 16114 5669 5597 16115 5672 5630 16116 5705 5603 16117 5678 5598 16118 5673 5602 16119 5677 5599 16120 5674 5600 16121 5675 5602 16122 5677 5601 16123 5676 5599 16124 5674 5598 16125 5673 5601 16126 5676 5602 16127 5677 5598 16128 5673 5603 16129 5678 5601 16130 5676 5608 16131 5683 5604 16132 5679 5605 16133 5680 5608 16134 5683 5606 16135 5681 5604 16136 5679 5608 16137 5683 5607 16138 5682 5606 16139 5681 5610 16140 5685 5607 16141 5682 5608 16142 5683 5610 16143 5685 5609 16144 5684 5607 16145 5682 5612 16146 5687 5609 16147 5684 5610 16148 5685 5612 16149 5687 5611 16150 5686 5609 16151 5684 5613 16152 5688 5611 16153 5686 5612 16154 5687 5616 16155 5691 5611 16156 5686 5613 16157 5688 5616 16158 5691 5614 16159 5689 5611 16160 5686 5616 16161 5691 5615 16162 5690 5614 16163 5689 5617 16164 5692 5615 16165 5690 5616 16166 5691 5619 16167 5694 5615 16168 5690 5617 16169 5692 5619 16170 5694 5618 16171 5693 5615 16172 5690 5621 16173 5696 5618 16174 5693 5619 16175 5694 5621 16176 5696 5620 16177 5695 5618 16178 5693 5623 16179 5698 5620 16180 5695 5621 16181 5696 5623 16182 5698 5622 16183 5697 5620 16184 5695 5625 16185 5700 5622 16186 5697 5623 16187 5698 5625 16188 5700 5624 16189 5699 5622 16190 5697 5628 16191 5703 5624 16192 5699 5625 16193 5700 5628 16194 5703 5626 16195 5701 5624 16196 5699 5628 16197 5703 5627 16198 5702 5626 16199 5701 5629 16200 5704 5627 16201 5702 5628 16202 5703 5631 16203 5706 5627 16204 5702 5629 16205 5704 5631 16206 5706 5630 16207 5705 5627 16208 5702 5603 16209 5678 5630 16210 5705 5631 16211 5706 5639 16212 5714 5632 16213 5707 5633 16214 5708 5638 16215 5713 5634 16216 5709 5635 16217 5710 5638 16218 5713 5636 16219 5711 5634 16220 5709 5638 16221 5713 5637 16222 5712 5636 16223 5711 5640 16224 5715 5637 16225 5712 5638 16226 5713 5640 16227 5715 5639 16228 5714 5637 16229 5712 5641 16230 5716 5639 16231 5714 5640 16232 5715 5642 16233 5717 5639 16234 5714 5641 16235 5716 5643 16236 5718 5639 16237 5714 5642 16238 5717 5644 16239 5719 5639 16240 5714 5643 16241 5718 5645 16242 5720 5639 16243 5714 5644 16244 5719 5646 16245 5721 5639 16246 5714 5645 16247 5720 5647 16248 5722 5639 16249 5714 5646 16250 5721 5648 16251 5723 5639 16252 5714 5647 16253 5722 5649 16254 5724 5639 16255 5714 5648 16256 5723 5650 16257 5725 5639 16258 5714 5649 16259 5724 5651 16260 5726 5639 16261 5714 5650 16262 5725 5652 16263 5727 5639 16264 5714 5651 16265 5726 5653 16266 5728 5639 16267 5714 5652 16268 5727 5654 16269 5729 5639 16270 5714 5653 16271 5728 5655 16272 5730 5639 16273 5714 5654 16274 5729 5656 16275 5731 5639 16276 5714 5655 16277 5730 5657 16278 5732 5639 16279 5714 5656 16280 5731 5658 16281 5733 5639 16282 5714 5657 16283 5732 5659 16284 5734 5639 16285 5714 5658 16286 5733 5660 16287 5735 5639 16288 5714 5659 16289 5734 5661 16290 5736 5639 16291 5714 5660 16292 5735 5662 16293 5737 5639 16294 5714 5661 16295 5736 5663 16296 5738 5639 16297 5714 5662 16298 5737 5632 16299 5707 5639 16300 5714 5663 16301 5738 5696 16302 5771 5680 16303 5755 5664 16304 5739 5667 16305 5742 5665 16306 5740 5666 16307 5741 5669 16308 5744 5665 16309 5740 5667 16310 5742 5669 16311 5744 5668 16312 5743 5665 16313 5740 5670 16314 5745 5668 16315 5743 5669 16316 5744 5673 16317 5748 5668 16318 5743 5670 16319 5745 5673 16320 5748 5671 16321 5746 5668 16322 5743 5673 16323 5748 5672 16324 5747 5671 16325 5746 5674 16326 5749 5672 16327 5747 5673 16328 5748 5677 16329 5752 5672 16330 5747 5674 16331 5749 5677 16332 5752 5675 16333 5750 5672 16334 5747 5677 16335 5752 5676 16336 5751 5675 16337 5750 5679 16338 5754 5676 16339 5751 5677 16340 5752 5679 16341 5754 5678 16342 5753 5676 16343 5751 5681 16344 5756 5678 16345 5753 5679 16346 5754 5681 16347 5756 5680 16348 5755 5678 16349 5753 5664 16350 5739 5680 16351 5755 5681 16352 5756 5684 16353 5759 5682 16354 5757 5683 16355 5758 5685 16356 5760 5682 16357 5757 5684 16358 5759 5687 16359 5762 5682 16360 5757 5685 16361 5760 5687 16362 5762 5686 16363 5761 5682 16364 5757 5690 16365 5765 5686 16366 5761 5687 16367 5762 5690 16368 5765 5688 16369 5763 5686 16370 5761 5690 16371 5765 5689 16372 5764 5688 16373 5763 5691 16374 5766 5689 16375 5764 5690 16376 5765 5693 16377 5768 5689 16378 5764 5691 16379 5766 5693 16380 5768 5692 16381 5767 5689 16382 5764 5695 16383 5770 5692 16384 5767 5693 16385 5768 5695 16386 5770 5694 16387 5769 5692 16388 5767 5697 16389 5772 5694 16390 5769 5695 16391 5770 5697 16392 5772 5696 16393 5771 5694 16394 5769 5680 16395 5755 5696 16396 5771 5697 16397 5772 5707 16398 5782 5698 16399 5773 5699 16400 5774 5704 16401 5779 5700 16402 5775 5701 16403 5776 5704 16404 5779 5702 16405 5777 5700 16406 5775 5704 16407 5779 5703 16408 5778 5702 16409 5777 5706 16410 5781 5703 16411 5778 5704 16412 5779 5706 16413 5781 5705 16414 5780 5703 16415 5778 5708 16416 5783 5705 16417 5780 5706 16418 5781 5708 16419 5783 5707 16420 5782 5705 16421 5780 5709 16422 5784 5707 16423 5782 5708 16424 5783 5710 16425 5785 5707 16426 5782 5709 16427 5784 5711 16428 5786 5707 16429 5782 5710 16430 5785 5712 16431 5787 5707 16432 5782 5711 16433 5786 5713 16434 5788 5707 16435 5782 5712 16436 5787 5714 16437 5789 5707 16438 5782 5713 16439 5788 5715 16440 5790 5707 16441 5782 5714 16442 5789 5716 16443 5791 5707 16444 5782 5715 16445 5790 5717 16446 5792 5707 16447 5782 5716 16448 5791 5718 16449 5793 5707 16450 5782 5717 16451 5792 5719 16452 5794 5707 16453 5782 5718 16454 5793 5720 16455 5795 5707 16456 5782 5719 16457 5794 5721 16458 5796 5707 16459 5782 5720 16460 5795 5722 16461 5797 5707 16462 5782 5721 16463 5796 5723 16464 5798 5707 16465 5782 5722 16466 5797 5724 16467 5799 5707 16468 5782 5723 16469 5798 5725 16470 5800 5707 16471 5782 5724 16472 5799 5726 16473 5801 5707 16474 5782 5725 16475 5800 5727 16476 5802 5707 16477 5782 5726 16478 5801 5728 16479 5803 5707 16480 5782 5727 16481 5802 5729 16482 5804 5707 16483 5782 5728 16484 5803 5698 16485 5773 5707 16486 5782 5729 16487 5804 5746 16488 5821 5730 16489 5805 5731 16490 5806 5735 16491 5810 5732 16492 5807 5733 16493 5808 5735 16494 5810 5734 16495 5809 5732 16496 5807 5737 16497 5812 5734 16498 5809 5735 16499 5810 5737 16500 5812 5736 16501 5811 5734 16502 5809 5739 16503 5814 5736 16504 5811 5737 16505 5812 5739 16506 5814 5738 16507 5813 5736 16508 5811 5741 16509 5816 5738 16510 5813 5739 16511 5814 5741 16512 5816 5740 16513 5815 5738 16514 5813 5743 16515 5818 5740 16516 5815 5741 16517 5816 5743 16518 5818 5742 16519 5817 5740 16520 5815 5745 16521 5820 5742 16522 5817 5743 16523 5818 5745 16524 5820 5744 16525 5819 5742 16526 5817 5747 16527 5822 5744 16528 5819 5745 16529 5820 5747 16530 5822 5746 16531 5821 5744 16532 5819 5730 16533 5805 5746 16534 5821 5747 16535 5822 5764 16536 5839 5748 16537 5823 5749 16538 5824 5753 16539 5828 5750 16540 5825 5751 16541 5826 5753 16542 5828 5752 16543 5827 5750 16544 5825 5755 16545 5830 5752 16546 5827 5753 16547 5828 5755 16548 5830 5754 16549 5829 5752 16550 5827 5757 16551 5832 5754 16552 5829 5755 16553 5830 5757 16554 5832 5756 16555 5831 5754 16556 5829 5759 16557 5834 5756 16558 5831 5757 16559 5832 5759 16560 5834 5758 16561 5833 5756 16562 5831 5761 16563 5836 5758 16564 5833 5759 16565 5834 5761 16566 5836 5760 16567 5835 5758 16568 5833 5763 16569 5838 5760 16570 5835 5761 16571 5836 5763 16572 5838 5762 16573 5837 5760 16574 5835 5765 16575 5840 5762 16576 5837 5763 16577 5838 5765 16578 5840 5764 16579 5839 5762 16580 5837 5748 16581 5823 5764 16582 5839 5765 16583 5840 5786 16584 5861 5766 16585 5841 5767 16586 5842 5770 16587 5845 5768 16588 5843 5769 16589 5844 5772 16590 5847 5768 16591 5843 5770 16592 5845 5772 16593 5847 5771 16594 5846 5768 16595 5843 5774 16596 5849 5771 16597 5846 5772 16598 5847 5774 16599 5849 5773 16600 5848 5771 16601 5846 5776 16602 5851 5773 16603 5848 5774 16604 5849 5776 16605 5851 5775 16606 5850 5773 16607 5848 5778 16608 5853 5775 16609 5850 5776 16610 5851 5778 16611 5853 5777 16612 5852 5775 16613 5850 5779 16614 5854 5777 16615 5852 5778 16616 5853 5781 16617 5856 5777 16618 5852 5779 16619 5854 5781 16620 5856 5780 16621 5855 5777 16622 5852 5783 16623 5858 5780 16624 5855 5781 16625 5856 5783 16626 5858 5782 16627 5857 5780 16628 5855 5785 16629 5860 5782 16630 5857 5783 16631 5858 5785 16632 5860 5784 16633 5859 5782 16634 5857 5787 16635 5862 5784 16636 5859 5785 16637 5860 5787 16638 5862 5786 16639 5861 5784 16640 5859 5766 16641 5841 5786 16642 5861 5787 16643 5862 5804 16644 5879 5788 16645 5863 5789 16646 5864 5793 16647 5868 5790 16648 5865 5791 16649 5866 5793 16650 5868 5792 16651 5867 5790 16652 5865 5795 16653 5870 5792 16654 5867 5793 16655 5868 5795 16656 5870 5794 16657 5869 5792 16658 5867 5797 16659 5872 5794 16660 5869 5795 16661 5870 5797 16662 5872 5796 16663 5871 5794 16664 5869 5799 16665 5874 5796 16666 5871 5797 16667 5872 5799 16668 5874 5798 16669 5873 5796 16670 5871 5801 16671 5876 5798 16672 5873 5799 16673 5874 5801 16674 5876 5800 16675 5875 5798 16676 5873 5803 16677 5878 5800 16678 5875 5801 16679 5876 5803 16680 5878 5802 16681 5877 5800 16682 5875 5805 16683 5880 5802 16684 5877 5803 16685 5878 5805 16686 5880 5804 16687 5879 5802 16688 5877 5788 16689 5863 5804 16690 5879 5805 16691 5880 5822 16692 5897 5806 16693 5881 5807 16694 5882 5811 16695 5886 5808 16696 5883 5809 16697 5884 5811 16698 5886 5810 16699 5885 5808 16700 5883 5813 16701 5888 5810 16702 5885 5811 16703 5886 5813 16704 5888 5812 16705 5887 5810 16706 5885 5815 16707 5890 5812 16708 5887 5813 16709 5888 5815 16710 5890 5814 16711 5889 5812 16712 5887 5817 16713 5892 5814 16714 5889 5815 16715 5890 5817 16716 5892 5816 16717 5891 5814 16718 5889 5819 16719 5894 5816 16720 5891 5817 16721 5892 5819 16722 5894 5818 16723 5893 5816 16724 5891 5821 16725 5896 5818 16726 5893 5819 16727 5894 5821 16728 5896 5820 16729 5895 5818 16730 5893 5823 16731 5898 5820 16732 5895 5821 16733 5896 5823 16734 5898 5822 16735 5897 5820 16736 5895 5806 16737 5881 5822 16738 5897 5823 16739 5898 5844 16740 5919 5824 16741 5899 5825 16742 5900 5829 16743 5904 5826 16744 5901 5827 16745 5902 5829 16746 5904 5828 16747 5903 5826 16748 5901 5831 16749 5906 5828 16750 5903 5829 16751 5904 5831 16752 5906 5830 16753 5905 5828 16754 5903 5833 16755 5908 5830 16756 5905 5831 16757 5906 5833 16758 5908 5832 16759 5907 5830 16760 5905 5835 16761 5910 5832 16762 5907 5833 16763 5908 5835 16764 5910 5834 16765 5909 5832 16766 5907 5837 16767 5912 5834 16768 5909 5835 16769 5910 5837 16770 5912 5836 16771 5911 5834 16772 5909 5839 16773 5914 5836 16774 5911 5837 16775 5912 5839 16776 5914 5838 16777 5913 5836 16778 5911 5841 16779 5916 5838 16780 5913 5839 16781 5914 5841 16782 5916 5840 16783 5915 5838 16784 5913 5843 16785 5918 5840 16786 5915 5841 16787 5916 5843 16788 5918 5842 16789 5917 5840 16790 5915 5845 16791 5920 5842 16792 5917 5843 16793 5918 5845 16794 5920 5844 16795 5919 5842 16796 5917 5824 16797 5899 5844 16798 5919 5845 16799 5920 5867 16800 5942 5846 16801 5921 5847 16802 5922 5850 16803 5925 5848 16804 5923 5849 16805 5924 5852 16806 5927 5848 16807 5923 5850 16808 5925 5852 16809 5927 5851 16810 5926 5848 16811 5923 5854 16812 5929 5851 16813 5926 5852 16814 5927 5854 16815 5929 5853 16816 5928 5851 16817 5926 5856 16818 5931 5853 16819 5928 5854 16820 5929 5856 16821 5931 5855 16822 5930 5853 16823 5928 5858 16824 5933 5855 16825 5930 5856 16826 5931 5858 16827 5933 5857 16828 5932 5855 16829 5930 5860 16830 5935 5857 16831 5932 5858 16832 5933 5860 16833 5935 5859 16834 5934 5857 16835 5932 5862 16836 5937 5859 16837 5934 5860 16838 5935 5862 16839 5937 5861 16840 5936 5859 16841 5934 5864 16842 5939 5861 16843 5936 5862 16844 5937 5864 16845 5939 5863 16846 5938 5861 16847 5936 5866 16848 5941 5863 16849 5938 5864 16850 5939 5866 16851 5941 5865 16852 5940 5863 16853 5938 5846 16854 5921 5865 16855 5940 5866 16856 5941 5846 16857 5921 5867 16858 5942 5865 16859 5940 5888 16860 5963 5868 16861 5943 5869 16862 5944 5872 16863 5947 5870 16864 5945 5871 16865 5946 5874 16866 5949 5870 16867 5945 5872 16868 5947 5874 16869 5949 5873 16870 5948 5870 16871 5945 5876 16872 5951 5873 16873 5948 5874 16874 5949 5876 16875 5951 5875 16876 5950 5873 16877 5948 5878 16878 5953 5875 16879 5950 5876 16880 5951 5878 16881 5953 5877 16882 5952 5875 16883 5950 5880 16884 5955 5877 16885 5952 5878 16886 5953 5880 16887 5955 5879 16888 5954 5877 16889 5952 5881 16890 5956 5879 16891 5954 5880 16892 5955 5883 16893 5958 5879 16894 5954 5881 16895 5956 5883 16896 5958 5882 16897 5957 5879 16898 5954 5885 16899 5960 5882 16900 5957 5883 16901 5958 5885 16902 5960 5884 16903 5959 5882 16904 5957 5887 16905 5962 5884 16906 5959 5885 16907 5960 5887 16908 5962 5886 16909 5961 5884 16910 5959 5889 16911 5964 5886 16912 5961 5887 16913 5962 5889 16914 5964 5888 16915 5963 5886 16916 5961 5868 16917 5943 5888 16918 5963 5889 16919 5964 5910 16920 5985 5890 16921 5965 5891 16922 5966 5894 16923 5969 5892 16924 5967 5893 16925 5968 5896 16926 5971 5892 16927 5967 5894 16928 5969 5896 16929 5971 5895 16930 5970 5892 16931 5967 5898 16932 5973 5895 16933 5970 5896 16934 5971 5898 16935 5973 5897 16936 5972 5895 16937 5970 5900 16938 5975 5897 16939 5972 5898 16940 5973 5900 16941 5975 5899 16942 5974 5897 16943 5972 5902 16944 5977 5899 16945 5974 5900 16946 5975 5902 16947 5977 5901 16948 5976 5899 16949 5974 5903 16950 5978 5901 16951 5976 5902 16952 5977 5905 16953 5980 5901 16954 5976 5903 16955 5978 5905 16956 5980 5904 16957 5979 5901 16958 5976 5907 16959 5982 5904 16960 5979 5905 16961 5980 5907 16962 5982 5906 16963 5981 5904 16964 5979 5909 16965 5984 5906 16966 5981 5907 16967 5982 5909 16968 5984 5908 16969 5983 5906 16970 5981 5911 16971 5986 5908 16972 5983 5909 16973 5984 5911 16974 5986 5910 16975 5985 5908 16976 5983 5890 16977 5965 5910 16978 5985 5911 16979 5986 5932 16980 6007 5912 16981 5987 5913 16982 5988 5916 16983 5991 5914 16984 5989 5915 16985 5990 5918 16986 5993 5914 16987 5989 5916 16988 5991 5918 16989 5993 5917 16990 5992 5914 16991 5989 5920 16992 5995 5917 16993 5992 5918 16994 5993 5920 16995 5995 5919 16996 5994 5917 16997 5992 5922 16998 5997 5919 16999 5994 5920 17000 5995 5922 17001 5997 5921 17002 5996 5919 17003 5994 5924 17004 5999 5921 17005 5996 5922 17006 5997 5924 17007 5999 5923 17008 5998 5921 17009 5996 5925 17010 6000 5923 17011 5998 5924 17012 5999 5927 17013 6002 5923 17014 5998 5925 17015 6000 5927 17016 6002 5926 17017 6001 5923 17018 5998 5929 17019 6004 5926 17020 6001 5927 17021 6002 5929 17022 6004 5928 17023 6003 5926 17024 6001 5931 17025 6006 5928 17026 6003 5929 17027 6004 5931 17028 6006 5930 17029 6005 5928 17030 6003 5933 17031 6008 5930 17032 6005 5931 17033 6006 5933 17034 6008 5932 17035 6007 5930 17036 6005 5912 17037 5987 5932 17038 6007 5933 17039 6008 5954 17040 6029 5934 17041 6009 5935 17042 6010 5938 17043 6013 5936 17044 6011 5937 17045 6012 5940 17046 6015 5936 17047 6011 5938 17048 6013 5940 17049 6015 5939 17050 6014 5936 17051 6011 5942 17052 6017 5939 17053 6014 5940 17054 6015 5942 17055 6017 5941 17056 6016 5939 17057 6014 5944 17058 6019 5941 17059 6016 5942 17060 6017 5944 17061 6019 5943 17062 6018 5941 17063 6016 5946 17064 6021 5943 17065 6018 5944 17066 6019 5946 17067 6021 5945 17068 6020 5943 17069 6018 5947 17070 6022 5945 17071 6020 5946 17072 6021 5949 17073 6024 5945 17074 6020 5947 17075 6022 5949 17076 6024 5948 17077 6023 5945 17078 6020 5951 17079 6026 5948 17080 6023 5949 17081 6024 5951 17082 6026 5950 17083 6025 5948 17084 6023 5953 17085 6028 5950 17086 6025 5951 17087 6026 5953 17088 6028 5952 17089 6027 5950 17090 6025 5955 17091 6030 5952 17092 6027 5953 17093 6028 5955 17094 6030 5954 17095 6029 5952 17096 6027 5934 17097 6009 5954 17098 6029 5955 17099 6030 5976 17100 6051 5956 17101 6031 5957 17102 6032 5960 17103 6035 5958 17104 6033 5959 17105 6034 5962 17106 6037 5958 17107 6033 5960 17108 6035 5962 17109 6037 5961 17110 6036 5958 17111 6033 5964 17112 6039 5961 17113 6036 5962 17114 6037 5964 17115 6039 5963 17116 6038 5961 17117 6036 5966 17118 6041 5963 17119 6038 5964 17120 6039 5966 17121 6041 5965 17122 6040 5963 17123 6038 5968 17124 6043 5965 17125 6040 5966 17126 6041 5968 17127 6043 5967 17128 6042 5965 17129 6040 5969 17130 6044 5967 17131 6042 5968 17132 6043 5971 17133 6046 5967 17134 6042 5969 17135 6044 5971 17136 6046 5970 17137 6045 5967 17138 6042 5973 17139 6048 5970 17140 6045 5971 17141 6046 5973 17142 6048 5972 17143 6047 5970 17144 6045 5975 17145 6050 5972 17146 6047 5973 17147 6048 5975 17148 6050 5974 17149 6049 5972 17150 6047 5977 17151 6052 5974 17152 6049 5975 17153 6050 5977 17154 6052 5976 17155 6051 5974 17156 6049 5956 17157 6031 5976 17158 6051 5977 17159 6052 5998 17160 6073 5978 17161 6053 5979 17162 6054 5982 17163 6057 5980 17164 6055 5981 17165 6056 5984 17166 6059 5980 17167 6055 5982 17168 6057 5984 17169 6059 5983 17170 6058 5980 17171 6055 5986 17172 6061 5983 17173 6058 5984 17174 6059 5986 17175 6061 5985 17176 6060 5983 17177 6058 5988 17178 6063 5985 17179 6060 5986 17180 6061 5988 17181 6063 5987 17182 6062 5985 17183 6060 5990 17184 6065 5987 17185 6062 5988 17186 6063 5990 17187 6065 5989 17188 6064 5987 17189 6062 5991 17190 6066 5989 17191 6064 5990 17192 6065 5993 17193 6068 5989 17194 6064 5991 17195 6066 5993 17196 6068 5992 17197 6067 5989 17198 6064 5995 17199 6070 5992 17200 6067 5993 17201 6068 5995 17202 6070 5994 17203 6069 5992 17204 6067 5997 17205 6072 5994 17206 6069 5995 17207 6070 5997 17208 6072 5996 17209 6071 5994 17210 6069 5999 17211 6074 5996 17212 6071 5997 17213 6072 5999 17214 6074 5998 17215 6073 5996 17216 6071 5978 17217 6053 5998 17218 6073 5999 17219 6074 6020 17220 6095 6000 17221 6075 6001 17222 6076 6004 17223 6079 6002 17224 6077 6003 17225 6078 6006 17226 6081 6002 17227 6077 6004 17228 6079 6006 17229 6081 6005 17230 6080 6002 17231 6077 6008 17232 6083 6005 17233 6080 6006 17234 6081 6008 17235 6083 6007 17236 6082 6005 17237 6080 6010 17238 6085 6007 17239 6082 6008 17240 6083 6010 17241 6085 6009 17242 6084 6007 17243 6082 6012 17244 6087 6009 17245 6084 6010 17246 6085 6012 17247 6087 6011 17248 6086 6009 17249 6084 6013 17250 6088 6011 17251 6086 6012 17252 6087 6015 17253 6090 6011 17254 6086 6013 17255 6088 6015 17256 6090 6014 17257 6089 6011 17258 6086 6017 17259 6092 6014 17260 6089 6015 17261 6090 6017 17262 6092 6016 17263 6091 6014 17264 6089 6019 17265 6094 6016 17266 6091 6017 17267 6092 6019 17268 6094 6018 17269 6093 6016 17270 6091 6021 17271 6096 6018 17272 6093 6019 17273 6094 6021 17274 6096 6020 17275 6095 6018 17276 6093 6000 17277 6075 6020 17278 6095 6021 17279 6096 6042 17280 6117 6022 17281 6097 6023 17282 6098 6026 17283 6101 6024 17284 6099 6025 17285 6100 6028 17286 6103 6024 17287 6099 6026 17288 6101 6028 17289 6103 6027 17290 6102 6024 17291 6099 6030 17292 6105 6027 17293 6102 6028 17294 6103 6030 17295 6105 6029 17296 6104 6027 17297 6102 6032 17298 6107 6029 17299 6104 6030 17300 6105 6032 17301 6107 6031 17302 6106 6029 17303 6104 6034 17304 6109 6031 17305 6106 6032 17306 6107 6034 17307 6109 6033 17308 6108 6031 17309 6106 6035 17310 6110 6033 17311 6108 6034 17312 6109 6037 17313 6112 6033 17314 6108 6035 17315 6110 6037 17316 6112 6036 17317 6111 6033 17318 6108 6039 17319 6114 6036 17320 6111 6037 17321 6112 6039 17322 6114 6038 17323 6113 6036 17324 6111 6041 17325 6116 6038 17326 6113 6039 17327 6114 6041 17328 6116 6040 17329 6115 6038 17330 6113 6043 17331 6118 6040 17332 6115 6041 17333 6116 6043 17334 6118 6042 17335 6117 6040 17336 6115 6022 17337 6097 6042 17338 6117 6043 17339 6118 6064 17340 6139 6044 17341 6119 6045 17342 6120 6048 17343 6123 6046 17344 6121 6047 17345 6122 6050 17346 6125 6046 17347 6121 6048 17348 6123 6050 17349 6125 6049 17350 6124 6046 17351 6121 6052 17352 6127 6049 17353 6124 6050 17354 6125 6052 17355 6127 6051 17356 6126 6049 17357 6124 6054 17358 6129 6051 17359 6126 6052 17360 6127 6054 17361 6129 6053 17362 6128 6051 17363 6126 6056 17364 6131 6053 17365 6128 6054 17366 6129 6056 17367 6131 6055 17368 6130 6053 17369 6128 6057 17370 6132 6055 17371 6130 6056 17372 6131 6059 17373 6134 6055 17374 6130 6057 17375 6132 6059 17376 6134 6058 17377 6133 6055 17378 6130 6061 17379 6136 6058 17380 6133 6059 17381 6134 6061 17382 6136 6060 17383 6135 6058 17384 6133 6063 17385 6138 6060 17386 6135 6061 17387 6136 6063 17388 6138 6062 17389 6137 6060 17390 6135 6065 17391 6140 6062 17392 6137 6063 17393 6138 6065 17394 6140 6064 17395 6139 6062 17396 6137 6044 17397 6119 6064 17398 6139 6065 17399 6140 6086 17400 6161 6066 17401 6141 6067 17402 6142 6070 17403 6145 6068 17404 6143 6069 17405 6144 6072 17406 6147 6068 17407 6143 6070 17408 6145 6072 17409 6147 6071 17410 6146 6068 17411 6143 6074 17412 6149 6071 17413 6146 6072 17414 6147 6074 17415 6149 6073 17416 6148 6071 17417 6146 6076 17418 6151 6073 17419 6148 6074 17420 6149 6076 17421 6151 6075 17422 6150 6073 17423 6148 6078 17424 6153 6075 17425 6150 6076 17426 6151 6078 17427 6153 6077 17428 6152 6075 17429 6150 6079 17430 6154 6077 17431 6152 6078 17432 6153 6081 17433 6156 6077 17434 6152 6079 17435 6154 6081 17436 6156 6080 17437 6155 6077 17438 6152 6083 17439 6158 6080 17440 6155 6081 17441 6156 6083 17442 6158 6082 17443 6157 6080 17444 6155 6085 17445 6160 6082 17446 6157 6083 17447 6158 6085 17448 6160 6084 17449 6159 6082 17450 6157 6087 17451 6162 6084 17452 6159 6085 17453 6160 6087 17454 6162 6086 17455 6161 6084 17456 6159 6066 17457 6141 6086 17458 6161 6087 17459 6162 6108 17460 6183 6088 17461 6163 6089 17462 6164 6092 17463 6167 6090 17464 6165 6091 17465 6166 6094 17466 6169 6090 17467 6165 6092 17468 6167 6094 17469 6169 6093 17470 6168 6090 17471 6165 6096 17472 6171 6093 17473 6168 6094 17474 6169 6096 17475 6171 6095 17476 6170 6093 17477 6168 6098 17478 6173 6095 17479 6170 6096 17480 6171 6098 17481 6173 6097 17482 6172 6095 17483 6170 6100 17484 6175 6097 17485 6172 6098 17486 6173 6100 17487 6175 6099 17488 6174 6097 17489 6172 6101 17490 6176 6099 17491 6174 6100 17492 6175 6103 17493 6178 6099 17494 6174 6101 17495 6176 6103 17496 6178 6102 17497 6177 6099 17498 6174 6105 17499 6180 6102 17500 6177 6103 17501 6178 6105 17502 6180 6104 17503 6179 6102 17504 6177 6107 17505 6182 6104 17506 6179 6105 17507 6180 6107 17508 6182 6106 17509 6181 6104 17510 6179 6109 17511 6184 6106 17512 6181 6107 17513 6182 6109 17514 6184 6108 17515 6183 6106 17516 6181 6088 17517 6163 6108 17518 6183 6109 17519 6184 6130 17520 6205 6110 17521 6185 6111 17522 6186 6114 17523 6189 6112 17524 6187 6113 17525 6188 6116 17526 6191 6112 17527 6187 6114 17528 6189 6116 17529 6191 6115 17530 6190 6112 17531 6187 6118 17532 6193 6115 17533 6190 6116 17534 6191 6118 17535 6193 6117 17536 6192 6115 17537 6190 6120 17538 6195 6117 17539 6192 6118 17540 6193 6120 17541 6195 6119 17542 6194 6117 17543 6192 6122 17544 6197 6119 17545 6194 6120 17546 6195 6122 17547 6197 6121 17548 6196 6119 17549 6194 6123 17550 6198 6121 17551 6196 6122 17552 6197 6125 17553 6200 6121 17554 6196 6123 17555 6198 6125 17556 6200 6124 17557 6199 6121 17558 6196 6127 17559 6202 6124 17560 6199 6125 17561 6200 6127 17562 6202 6126 17563 6201 6124 17564 6199 6129 17565 6204 6126 17566 6201 6127 17567 6202 6129 17568 6204 6128 17569 6203 6126 17570 6201 6131 17571 6206 6128 17572 6203 6129 17573 6204 6131 17574 6206 6130 17575 6205 6128 17576 6203 6110 17577 6185 6130 17578 6205 6131 17579 6206 6152 17580 6227 6132 17581 6207 6133 17582 6208 6136 17583 6211 6134 17584 6209 6135 17585 6210 6138 17586 6213 6134 17587 6209 6136 17588 6211 6138 17589 6213 6137 17590 6212 6134 17591 6209 6140 17592 6215 6137 17593 6212 6138 17594 6213 6140 17595 6215 6139 17596 6214 6137 17597 6212 6142 17598 6217 6139 17599 6214 6140 17600 6215 6142 17601 6217 6141 17602 6216 6139 17603 6214 6144 17604 6219 6141 17605 6216 6142 17606 6217 6144 17607 6219 6143 17608 6218 6141 17609 6216 6145 17610 6220 6143 17611 6218 6144 17612 6219 6147 17613 6222 6143 17614 6218 6145 17615 6220 6147 17616 6222 6146 17617 6221 6143 17618 6218 6149 17619 6224 6146 17620 6221 6147 17621 6222 6149 17622 6224 6148 17623 6223 6146 17624 6221 6151 17625 6226 6148 17626 6223 6149 17627 6224 6151 17628 6226 6150 17629 6225 6148 17630 6223 6153 17631 6228 6150 17632 6225 6151 17633 6226 6153 17634 6228 6152 17635 6227 6150 17636 6225 6132 17637 6207 6152 17638 6227 6153 17639 6228 6156 17640 6233 6154 17641 6229 6155 17642 6230 6154 17643 6229 6156 17644 6231 6157 17645 6232 6174 17646 6250 6158 17647 6234 6159 17648 6235 6162 17649 6238 6160 17650 6236 6161 17651 6237 6164 17652 6240 6160 17653 6236 6162 17654 6238 6164 17655 6240 6163 17656 6239 6160 17657 6236 6166 17658 6242 6163 17659 6239 6164 17660 6240 6166 17661 6242 6165 17662 6241 6163 17663 6239 6168 17664 6244 6165 17665 6241 6166 17666 6242 6168 17667 6244 6167 17668 6243 6165 17669 6241 6169 17670 6245 6167 17671 6243 6168 17672 6244 6171 17673 6247 6167 17674 6243 6169 17675 6245 6171 17676 6247 6170 17677 6246 6167 17678 6243 6173 17679 6249 6170 17680 6246 6171 17681 6247 6173 17682 6249 6172 17683 6248 6170 17684 6246 6175 17685 6251 6172 17686 6248 6173 17687 6249 6175 17688 6251 6174 17689 6250 6172 17690 6248 6158 17691 6234 6174 17692 6250 6175 17693 6251 6209 17694 6285 6176 17695 6252 6177 17696 6253 6179 17697 6255 6177 17698 6253 6178 17699 6254 6209 17700 6285 6177 17701 6253 6179 17702 6255 6184 17703 6260 6180 17704 6256 6181 17705 6257 6184 17706 6260 6182 17707 6258 6180 17708 6256 6184 17709 6260 6183 17710 6259 6182 17711 6258 6186 17712 6262 6183 17713 6259 6184 17714 6260 6186 17715 6262 6185 17716 6261 6183 17717 6259 6187 17718 6263 6185 17719 6261 6186 17720 6262 6189 17721 6265 6185 17722 6261 6187 17723 6263 6189 17724 6265 6188 17725 6264 6185 17726 6261 6192 17727 6268 6188 17728 6264 6189 17729 6265 6192 17730 6268 6190 17731 6266 6188 17732 6264 6192 17733 6268 6191 17734 6267 6190 17735 6266 6194 17736 6270 6191 17737 6267 6192 17738 6268 6194 17739 6270 6193 17740 6269 6191 17741 6267 6196 17742 6272 6193 17743 6269 6194 17744 6270 6196 17745 6272 6195 17746 6271 6193 17747 6269 6197 17748 6273 6195 17749 6271 6196 17750 6272 6200 17751 6276 6195 17752 6271 6197 17753 6273 6200 17754 6276 6198 17755 6274 6195 17756 6271 6200 17757 6276 6199 17758 6275 6198 17759 6274 6201 17760 6277 6199 17761 6275 6200 17762 6276 6204 17763 6280 6199 17764 6275 6201 17765 6277 6204 17766 6280 6202 17767 6278 6199 17768 6275 6204 17769 6280 6203 17770 6279 6202 17771 6278 6205 17772 6281 6203 17773 6279 6204 17774 6280 6207 17775 6283 6203 17776 6279 6205 17777 6281 6207 17778 6283 6206 17779 6282 6203 17780 6279 6176 17781 6252 6206 17782 6282 6207 17783 6283 6176 17784 6252 6208 17785 6284 6206 17786 6282 6176 17787 6252 6209 17788 6285 6208 17789 6284 6212 17790 6288 6210 17791 6286 6211 17792 6287 6210 17793 6286 6212 17794 6288 6213 17795 6289 6230 17796 6306 6214 17797 6290 6215 17798 6291 6219 17799 6295 6216 17800 6292 6217 17801 6293 6219 17802 6295 6218 17803 6294 6216 17804 6292 6221 17805 6297 6218 17806 6294 6219 17807 6295 6221 17808 6297 6220 17809 6296 6218 17810 6294 6223 17811 6299 6220 17812 6296 6221 17813 6297 6223 17814 6299 6222 17815 6298 6220 17816 6296 6225 17817 6301 6222 17818 6298 6223 17819 6299 6225 17820 6301 6224 17821 6300 6222 17822 6298 6227 17823 6303 6224 17824 6300 6225 17825 6301 6227 17826 6303 6226 17827 6302 6224 17828 6300 6229 17829 6305 6226 17830 6302 6227 17831 6303 6229 17832 6305 6228 17833 6304 6226 17834 6302 6231 17835 6307 6228 17836 6304 6229 17837 6305 6231 17838 6307 6230 17839 6306 6228 17840 6304 6214 17841 6290 6230 17842 6306 6231 17843 6307 6248 17844 6324 6232 17845 6308 6233 17846 6309 6237 17847 6313 6234 17848 6310 6235 17849 6311 6237 17850 6313 6236 17851 6312 6234 17852 6310 6239 17853 6315 6236 17854 6312 6237 17855 6313 6239 17856 6315 6238 17857 6314 6236 17858 6312 6241 17859 6317 6238 17860 6314 6239 17861 6315 6241 17862 6317 6240 17863 6316 6238 17864 6314 6243 17865 6319 6240 17866 6316 6241 17867 6317 6243 17868 6319 6242 17869 6318 6240 17870 6316 6245 17871 6321 6242 17872 6318 6243 17873 6319 6245 17874 6321 6244 17875 6320 6242 17876 6318 6247 17877 6323 6244 17878 6320 6245 17879 6321 6247 17880 6323 6246 17881 6322 6244 17882 6320 6249 17883 6325 6246 17884 6322 6247 17885 6323 6249 17886 6325 6248 17887 6324 6246 17888 6322 6232 17889 6308 6248 17890 6324 6249 17891 6325 6266 17892 6342 6250 17893 6326 6251 17894 6327 6255 17895 6331 6252 17896 6328 6253 17897 6329 6255 17898 6331 6254 17899 6330 6252 17900 6328 6257 17901 6333 6254 17902 6330 6255 17903 6331 6257 17904 6333 6256 17905 6332 6254 17906 6330 6259 17907 6335 6256 17908 6332 6257 17909 6333 6259 17910 6335 6258 17911 6334 6256 17912 6332 6261 17913 6337 6258 17914 6334 6259 17915 6335 6261 17916 6337 6260 17917 6336 6258 17918 6334 6263 17919 6339 6260 17920 6336 6261 17921 6337 6263 17922 6339 6262 17923 6338 6260 17924 6336 6265 17925 6341 6262 17926 6338 6263 17927 6339 6265 17928 6341 6264 17929 6340 6262 17930 6338 6267 17931 6343 6264 17932 6340 6265 17933 6341 6267 17934 6343 6266 17935 6342 6264 17936 6340 6250 17937 6326 6266 17938 6342 6267 17939 6343 6284 17940 6360 6268 17941 6344 6269 17942 6345 6273 17943 6349 6270 17944 6346 6271 17945 6347 6273 17946 6349 6272 17947 6348 6270 17948 6346 6275 17949 6351 6272 17950 6348 6273 17951 6349 6275 17952 6351 6274 17953 6350 6272 17954 6348 6277 17955 6353 6274 17956 6350 6275 17957 6351 6277 17958 6353 6276 17959 6352 6274 17960 6350 6279 17961 6355 6276 17962 6352 6277 17963 6353 6279 17964 6355 6278 17965 6354 6276 17966 6352 6281 17967 6357 6278 17968 6354 6279 17969 6355 6281 17970 6357 6280 17971 6356 6278 17972 6354 6283 17973 6359 6280 17974 6356 6281 17975 6357 6283 17976 6359 6282 17977 6358 6280 17978 6356 6285 17979 6361 6282 17980 6358 6283 17981 6359 6285 17982 6361 6284 17983 6360 6282 17984 6358 6268 17985 6344 6284 17986 6360 6285 17987 6361 6302 17988 6378 6286 17989 6362 6287 17990 6363 6291 17991 6367 6288 17992 6364 6289 17993 6365 6291 17994 6367 6290 17995 6366 6288 17996 6364 6293 17997 6369 6290 17998 6366 6291 17999 6367 6293 18000 6369 6292 18001 6368 6290 18002 6366 6295 18003 6371 6292 18004 6368 6293 18005 6369 6295 18006 6371 6294 18007 6370 6292 18008 6368 6297 18009 6373 6294 18010 6370 6295 18011 6371 6297 18012 6373 6296 18013 6372 6294 18014 6370 6299 18015 6375 6296 18016 6372 6297 18017 6373 6299 18018 6375 6298 18019 6374 6296 18020 6372 6301 18021 6377 6298 18022 6374 6299 18023 6375 6301 18024 6377 6300 18025 6376 6298 18026 6374 6303 18027 6379 6300 18028 6376 6301 18029 6377 6303 18030 6379 6302 18031 6378 6300 18032 6376 6286 18033 6362 6302 18034 6378 6303 18035 6379 6320 18036 6396 6304 18037 6380 6305 18038 6381 6309 18039 6385 6306 18040 6382 6307 18041 6383 6309 18042 6385 6308 18043 6384 6306 18044 6382 6311 18045 6387 6308 18046 6384 6309 18047 6385 6311 18048 6387 6310 18049 6386 6308 18050 6384 6313 18051 6389 6310 18052 6386 6311 18053 6387 6313 18054 6389 6312 18055 6388 6310 18056 6386 6315 18057 6391 6312 18058 6388 6313 18059 6389 6315 18060 6391 6314 18061 6390 6312 18062 6388 6317 18063 6393 6314 18064 6390 6315 18065 6391 6317 18066 6393 6316 18067 6392 6314 18068 6390 6319 18069 6395 6316 18070 6392 6317 18071 6393 6319 18072 6395 6318 18073 6394 6316 18074 6392 6321 18075 6397 6318 18076 6394 6319 18077 6395 6321 18078 6397 6320 18079 6396 6318 18080 6394 6304 18081 6380 6320 18082 6396 6321 18083 6397 6338 18084 6414 6322 18085 6398 6323 18086 6399 6327 18087 6403 6324 18088 6400 6325 18089 6401 6327 18090 6403 6326 18091 6402 6324 18092 6400 6329 18093 6405 6326 18094 6402 6327 18095 6403 6329 18096 6405 6328 18097 6404 6326 18098 6402 6331 18099 6407 6328 18100 6404 6329 18101 6405 6331 18102 6407 6330 18103 6406 6328 18104 6404 6333 18105 6409 6330 18106 6406 6331 18107 6407 6333 18108 6409 6332 18109 6408 6330 18110 6406 6335 18111 6411 6332 18112 6408 6333 18113 6409 6335 18114 6411 6334 18115 6410 6332 18116 6408 6337 18117 6413 6334 18118 6410 6335 18119 6411 6337 18120 6413 6336 18121 6412 6334 18122 6410 6339 18123 6415 6336 18124 6412 6337 18125 6413 6339 18126 6415 6338 18127 6414 6336 18128 6412 6322 18129 6398 6338 18130 6414 6339 18131 6415 6356 18132 6432 6340 18133 6416 6341 18134 6417 6345 18135 6421 6342 18136 6418 6343 18137 6419 6345 18138 6421 6344 18139 6420 6342 18140 6418 6347 18141 6423 6344 18142 6420 6345 18143 6421 6347 18144 6423 6346 18145 6422 6344 18146 6420 6349 18147 6425 6346 18148 6422 6347 18149 6423 6349 18150 6425 6348 18151 6424 6346 18152 6422 6351 18153 6427 6348 18154 6424 6349 18155 6425 6351 18156 6427 6350 18157 6426 6348 18158 6424 6353 18159 6429 6350 18160 6426 6351 18161 6427 6353 18162 6429 6352 18163 6428 6350 18164 6426 6355 18165 6431 6352 18166 6428 6353 18167 6429 6355 18168 6431 6354 18169 6430 6352 18170 6428 6357 18171 6433 6354 18172 6430 6355 18173 6431 6357 18174 6433 6356 18175 6432 6354 18176 6430 6340 18177 6416 6356 18178 6432 6357 18179 6433 6374 18180 6450 6358 18181 6434 6359 18182 6435 6363 18183 6439 6360 18184 6436 6361 18185 6437 6363 18186 6439 6362 18187 6438 6360 18188 6436 6365 18189 6441 6362 18190 6438 6363 18191 6439 6365 18192 6441 6364 18193 6440 6362 18194 6438 6367 18195 6443 6364 18196 6440 6365 18197 6441 6367 18198 6443 6366 18199 6442 6364 18200 6440 6369 18201 6445 6366 18202 6442 6367 18203 6443 6369 18204 6445 6368 18205 6444 6366 18206 6442 6371 18207 6447 6368 18208 6444 6369 18209 6445 6371 18210 6447 6370 18211 6446 6368 18212 6444 6373 18213 6449 6370 18214 6446 6371 18215 6447 6373 18216 6449 6372 18217 6448 6370 18218 6446 6375 18219 6451 6372 18220 6448 6373 18221 6449 6375 18222 6451 6374 18223 6450 6372 18224 6448 6358 18225 6434 6374 18226 6450 6375 18227 6451 6392 18228 6470 6376 18229 6452 6377 18230 6453 6381 18231 6457 6378 18232 6471 6379 18233 6455 6381 18234 6457 6380 18235 6472 6378 18236 6454 6383 18237 6459 6380 18238 6473 6381 18239 6457 6383 18240 6459 6382 18241 6474 6380 18242 6456 6385 18243 6461 6382 18244 6475 6383 18245 6459 6385 18246 6461 6384 18247 6476 6382 18248 6458 6387 18249 6463 6384 18250 6477 6385 18251 6461 6387 18252 6463 6386 18253 6478 6384 18254 6460 6389 18255 6465 6386 18256 6479 6387 18257 6463 6389 18258 6465 6388 18259 6480 6386 18260 6462 6391 18261 6467 6388 18262 6481 6389 18263 6465 6391 18264 6467 6390 18265 6482 6388 18266 6464 6393 18267 6469 6390 18268 6483 6391 18269 6467 6393 18270 6469 6392 18271 6484 6390 18272 6466 6376 18273 6452 6392 18274 6468 6393 18275 6469 6410 18276 6501 6394 18277 6485 6395 18278 6486 6399 18279 6490 6396 18280 6487 6397 18281 6488 6399 18282 6490 6398 18283 6489 6396 18284 6487 6401 18285 6492 6398 18286 6489 6399 18287 6490 6401 18288 6492 6400 18289 6491 6398 18290 6489 6403 18291 6494 6400 18292 6491 6401 18293 6492 6403 18294 6494 6402 18295 6493 6400 18296 6491 6405 18297 6496 6402 18298 6493 6403 18299 6494 6405 18300 6496 6404 18301 6495 6402 18302 6493 6407 18303 6498 6404 18304 6495 6405 18305 6496 6407 18306 6498 6406 18307 6497 6404 18308 6495 6409 18309 6500 6406 18310 6497 6407 18311 6498 6409 18312 6500 6408 18313 6499 6406 18314 6497 6411 18315 6502 6408 18316 6499 6409 18317 6500 6411 18318 6502 6410 18319 6501 6408 18320 6499 6394 18321 6485 6410 18322 6501 6411 18323 6502 6428 18324 6519 6412 18325 6503 6413 18326 6504 6417 18327 6508 6414 18328 6505 6415 18329 6506 6417 18330 6508 6416 18331 6507 6414 18332 6505 6419 18333 6510 6416 18334 6507 6417 18335 6508 6419 18336 6510 6418 18337 6509 6416 18338 6507 6421 18339 6512 6418 18340 6509 6419 18341 6510 6421 18342 6512 6420 18343 6511 6418 18344 6509 6423 18345 6514 6420 18346 6511 6421 18347 6512 6423 18348 6514 6422 18349 6513 6420 18350 6511 6425 18351 6516 6422 18352 6513 6423 18353 6514 6425 18354 6516 6424 18355 6515 6422 18356 6513 6427 18357 6518 6424 18358 6515 6425 18359 6516 6427 18360 6518 6426 18361 6517 6424 18362 6515 6429 18363 6520 6426 18364 6517 6427 18365 6518 6429 18366 6520 6428 18367 6519 6426 18368 6517 6412 18369 6503 6428 18370 6519 6429 18371 6520 6446 18372 6537 6430 18373 6521 6431 18374 6522 6435 18375 6526 6432 18376 6523 6433 18377 6524 6435 18378 6526 6434 18379 6525 6432 18380 6523 6437 18381 6528 6434 18382 6525 6435 18383 6526 6437 18384 6528 6436 18385 6527 6434 18386 6525 6439 18387 6530 6436 18388 6527 6437 18389 6528 6439 18390 6530 6438 18391 6529 6436 18392 6527 6441 18393 6532 6438 18394 6529 6439 18395 6530 6441 18396 6532 6440 18397 6531 6438 18398 6529 6443 18399 6534 6440 18400 6531 6441 18401 6532 6443 18402 6534 6442 18403 6533 6440 18404 6531 6445 18405 6536 6442 18406 6533 6443 18407 6534 6445 18408 6536 6444 18409 6535 6442 18410 6533 6447 18411 6538 6444 18412 6535 6445 18413 6536 6447 18414 6538 6446 18415 6537 6444 18416 6535 6430 18417 6521 6446 18418 6537 6447 18419 6538 6464 18420 6555 6448 18421 6539 6449 18422 6540 6453 18423 6544 6450 18424 6541 6451 18425 6542 6453 18426 6544 6452 18427 6543 6450 18428 6541 6455 18429 6546 6452 18430 6543 6453 18431 6544 6455 18432 6546 6454 18433 6545 6452 18434 6543 6457 18435 6548 6454 18436 6545 6455 18437 6546 6457 18438 6548 6456 18439 6547 6454 18440 6545 6459 18441 6550 6456 18442 6547 6457 18443 6548 6459 18444 6550 6458 18445 6549 6456 18446 6547 6461 18447 6552 6458 18448 6549 6459 18449 6550 6461 18450 6552 6460 18451 6551 6458 18452 6549 6463 18453 6554 6460 18454 6551 6461 18455 6552 6463 18456 6554 6462 18457 6553 6460 18458 6551 6465 18459 6556 6462 18460 6553 6463 18461 6554 6465 18462 6556 6464 18463 6555 6462 18464 6553 6448 18465 6539 6464 18466 6555 6465 18467 6556 6482 18468 6573 6466 18469 6557 6467 18470 6558 6471 18471 6562 6468 18472 6559 6469 18473 6560 6471 18474 6562 6470 18475 6561 6468 18476 6559 6473 18477 6564 6470 18478 6561 6471 18479 6562 6473 18480 6564 6472 18481 6563 6470 18482 6561 6475 18483 6566 6472 18484 6563 6473 18485 6564 6475 18486 6566 6474 18487 6565 6472 18488 6563 6477 18489 6568 6474 18490 6565 6475 18491 6566 6477 18492 6568 6476 18493 6567 6474 18494 6565 6479 18495 6570 6476 18496 6567 6477 18497 6568 6479 18498 6570 6478 18499 6569 6476 18500 6567 6481 18501 6572 6478 18502 6569 6479 18503 6570 6481 18504 6572 6480 18505 6571 6478 18506 6569 6483 18507 6574 6480 18508 6571 6481 18509 6572 6483 18510 6574 6482 18511 6573 6480 18512 6571 6466 18513 6557 6482 18514 6573 6483 18515 6574 6500 18516 6591 6484 18517 6575 6485 18518 6576 6489 18519 6580 6486 18520 6577 6487 18521 6578 6489 18522 6580 6488 18523 6579 6486 18524 6577 6491 18525 6582 6488 18526 6579 6489 18527 6580 6491 18528 6582 6490 18529 6581 6488 18530 6579 6493 18531 6584 6490 18532 6581 6491 18533 6582 6493 18534 6584 6492 18535 6583 6490 18536 6581 6495 18537 6586 6492 18538 6583 6493 18539 6584 6495 18540 6586 6494 18541 6585 6492 18542 6583 6497 18543 6588 6494 18544 6585 6495 18545 6586 6497 18546 6588 6496 18547 6587 6494 18548 6585 6499 18549 6590 6496 18550 6587 6497 18551 6588 6499 18552 6590 6498 18553 6589 6496 18554 6587 6501 18555 6592 6498 18556 6589 6499 18557 6590 6501 18558 6592 6500 18559 6591 6498 18560 6589 6484 18561 6575 6500 18562 6591 6501 18563 6592 6518 18564 6609 6502 18565 6593 6503 18566 6594 6507 18567 6598 6504 18568 6595 6505 18569 6596 6507 18570 6598 6506 18571 6597 6504 18572 6595 6509 18573 6600 6506 18574 6597 6507 18575 6598 6509 18576 6600 6508 18577 6599 6506 18578 6597 6511 18579 6602 6508 18580 6599 6509 18581 6600 6511 18582 6602 6510 18583 6601 6508 18584 6599 6513 18585 6604 6510 18586 6601 6511 18587 6602 6513 18588 6604 6512 18589 6603 6510 18590 6601 6515 18591 6606 6512 18592 6603 6513 18593 6604 6515 18594 6606 6514 18595 6605 6512 18596 6603 6517 18597 6608 6514 18598 6605 6515 18599 6606 6517 18600 6608 6516 18601 6607 6514 18602 6605 6519 18603 6610 6516 18604 6607 6517 18605 6608 6519 18606 6610 6518 18607 6609 6516 18608 6607 6502 18609 6593 6518 18610 6609 6519 18611 6610 6536 18612 6627 6520 18613 6611 6521 18614 6612 6525 18615 6616 6522 18616 6613 6523 18617 6614 6525 18618 6616 6524 18619 6615 6522 18620 6613 6527 18621 6618 6524 18622 6615 6525 18623 6616 6527 18624 6618 6526 18625 6617 6524 18626 6615 6529 18627 6620 6526 18628 6617 6527 18629 6618 6529 18630 6620 6528 18631 6619 6526 18632 6617 6531 18633 6622 6528 18634 6619 6529 18635 6620 6531 18636 6622 6530 18637 6621 6528 18638 6619 6533 18639 6624 6530 18640 6621 6531 18641 6622 6533 18642 6624 6532 18643 6623 6530 18644 6621 6535 18645 6626 6532 18646 6623 6533 18647 6624 6535 18648 6626 6534 18649 6625 6532 18650 6623 6537 18651 6628 6534 18652 6625 6535 18653 6626 6537 18654 6628 6536 18655 6627 6534 18656 6625 6520 18657 6611 6536 18658 6627 6537 18659 6628 6554 18660 6645 6538 18661 6629 6539 18662 6630 6543 18663 6634 6540 18664 6631 6541 18665 6632 6543 18666 6634 6542 18667 6633 6540 18668 6631 6545 18669 6636 6542 18670 6633 6543 18671 6634 6545 18672 6636 6544 18673 6635 6542 18674 6633 6547 18675 6638 6544 18676 6635 6545 18677 6636 6547 18678 6638 6546 18679 6637 6544 18680 6635 6549 18681 6640 6546 18682 6637 6547 18683 6638 6549 18684 6640 6548 18685 6639 6546 18686 6637 6551 18687 6642 6548 18688 6639 6549 18689 6640 6551 18690 6642 6550 18691 6641 6548 18692 6639 6553 18693 6644 6550 18694 6641 6551 18695 6642 6553 18696 6644 6552 18697 6643 6550 18698 6641 6555 18699 6646 6552 18700 6643 6553 18701 6644 6555 18702 6646 6554 18703 6645 6552 18704 6643 6538 18705 6629 6554 18706 6645 6555 18707 6646 6572 18708 6663 6556 18709 6647 6557 18710 6648 6561 18711 6652 6558 18712 6649 6559 18713 6650 6561 18714 6652 6560 18715 6651 6558 18716 6649 6563 18717 6654 6560 18718 6651 6561 18719 6652 6563 18720 6654 6562 18721 6653 6560 18722 6651 6565 18723 6656 6562 18724 6653 6563 18725 6654 6565 18726 6656 6564 18727 6655 6562 18728 6653 6567 18729 6658 6564 18730 6655 6565 18731 6656 6567 18732 6658 6566 18733 6657 6564 18734 6655 6569 18735 6660 6566 18736 6657 6567 18737 6658 6569 18738 6660 6568 18739 6659 6566 18740 6657 6571 18741 6662 6568 18742 6659 6569 18743 6660 6571 18744 6662 6570 18745 6661 6568 18746 6659 6573 18747 6664 6570 18748 6661 6571 18749 6662 6573 18750 6664 6572 18751 6663 6570 18752 6661 6556 18753 6647 6572 18754 6663 6573 18755 6664 6576 18756 6667 6574 18757 6665 6575 18758 6666 6574 18759 6665 6576 18760 6667 6577 18761 6668 6580 18762 6671 6578 18763 6669 6579 18764 6670 6582 18765 6673 6580 18766 6671 6581 18767 6672 6583 18768 6674 6580 18769 6671 6582 18770 6673 6578 18771 6669 6580 18772 6671 6583 18773 6674 6586 18774 6677 6584 18775 6675 6585 18776 6676 6584 18777 6675 6586 18778 6677 6587 18779 6678 6590 18780 6681 6588 18781 6679 6589 18782 6680 6588 18783 6679 6590 18784 6681 6591 18785 6682 6594 18786 6685 6592 18787 6683 6593 18788 6684 6592 18789 6683 6594 18790 6685 6595 18791 6686 6598 18792 6689 6596 18793 6687 6597 18794 6688 6596 18795 6687 6598 18796 6689 6599 18797 6690 6602 18798 6693 6600 18799 6691 6601 18800 6692 6600 18801 6691 6602 18802 6693 6603 18803 6694 6606 18804 6697 6604 18805 6695 6605 18806 6696 6604 18807 6695 6606 18808 6697 6607 18809 6698 6610 18810 6701 6608 18811 6699 6609 18812 6700 6608 18813 6699 6610 18814 6701 6611 18815 6702 6614 18816 6705 6612 18817 6703 6613 18818 6704 6612 18819 6703 6614 18820 6705 6615 18821 6706 6618 18822 6709 6616 18823 6707 6617 18824 6708 6616 18825 6707 6618 18826 6709 6619 18827 6710 6622 18828 6713 6620 18829 6711 6621 18830 6712 6620 18831 6711 6622 18832 6713 6623 18833 6714 6626 18834 6717 6624 18835 6715 6625 18836 6716 6628 18837 6719 6626 18838 6717 6627 18839 6718 6629 18840 6720 6626 18841 6717 6628 18842 6719 6631 18843 6722 6629 18844 6720 6630 18845 6721 6631 18846 6722 6626 18847 6717 6629 18848 6720 6624 18849 6715 6626 18850 6717 6631 18851 6722 6634 18852 6725 6632 18853 6723 6633 18854 6724 6632 18855 6723 6634 18856 6725 6635 18857 6726 6638 18858 6729 6636 18859 6727 6637 18860 6728 6636 18861 6727 6638 18862 6729 6639 18863 6730 6642 18864 6733 6640 18865 6731 6641 18866 6732 6640 18867 6731 6642 18868 6733 6643 18869 6734 6646 18870 6737 6644 18871 6739 6645 18872 6736 6644 18873 6735 6646 18874 6737 6647 18875 6738 6650 18876 6742 6648 18877 6740 6649 18878 6741 6648 18879 6740 6650 18880 6742 6651 18881 6743 6654 18882 6746 6652 18883 6744 6653 18884 6745 6652 18885 6744 6654 18886 6746 6655 18887 6747 6658 18888 6750 6656 18889 6748 6657 18890 6749 6656 18891 6748 6658 18892 6750 6659 18893 6751

+
+
+ + + + +37.200001 1.450000 0.120000 +37.200001 1.450000 0.000000 +36.500000 1.450000 0.000000 +36.500000 1.450000 0.120000 +36.505844 1.386313 0.000000 +36.505844 1.386313 0.120000 +36.524574 1.321167 0.000000 +36.524574 1.321167 0.120000 +36.557053 1.258477 0.000000 +36.557053 1.258477 0.120000 +36.602512 1.202513 0.000000 +36.602512 1.202513 0.120000 +36.658478 1.157052 0.000000 +36.658478 1.157052 0.120000 +36.721169 1.124574 0.000000 +36.721169 1.124574 0.120000 +36.786312 1.105843 0.000000 +36.786312 1.105843 0.120000 +36.849998 1.100000 0.000000 +36.849998 1.100000 0.120000 +36.913689 1.105843 0.000000 +36.913689 1.105843 0.120000 +36.978832 1.124574 0.000000 +36.978832 1.124574 0.120000 +37.041523 1.157052 0.000000 +37.041523 1.157052 0.120000 +37.097488 1.202513 0.000000 +37.097488 1.202513 0.120000 +37.142948 1.258477 0.000000 +37.142948 1.258477 0.120000 +37.175426 1.321167 0.000000 +37.175426 1.321167 0.120000 +37.194157 1.386313 0.000000 +37.194157 1.386313 0.120000 +35.200001 1.450000 0.120000 +35.200001 1.450000 0.000000 +34.500000 1.450000 0.000000 +34.500000 1.450000 0.120000 +34.505844 1.386313 0.000000 +34.524574 1.321167 0.000000 +34.505844 1.386313 0.120000 +34.524574 1.321167 0.120000 +34.557053 1.258477 0.000000 +34.557053 1.258477 0.120000 +34.602512 1.202513 0.000000 +34.602512 1.202513 0.120000 +34.658478 1.157052 0.000000 +34.658478 1.157052 0.120000 +34.721169 1.124574 0.000000 +34.786312 1.105843 0.000000 +34.721169 1.124574 0.120000 +34.786312 1.105843 0.120000 +34.849998 1.100000 0.000000 +34.849998 1.100000 0.120000 +34.913689 1.105843 0.000000 +34.913689 1.105843 0.120000 +34.978832 1.124574 0.000000 +34.978832 1.124574 0.120000 +35.041523 1.157052 0.000000 +35.041523 1.157052 0.120000 +35.097488 1.202513 0.000000 +35.097488 1.202513 0.120000 +35.142948 1.258477 0.000000 +35.142948 1.258477 0.120000 +35.175426 1.321167 0.000000 +35.175426 1.321167 0.120000 +35.194157 1.386313 0.000000 +35.194157 1.386313 0.120000 +32.500000 1.450000 0.000000 +32.500000 1.450000 0.120000 +33.200001 1.450000 0.120000 +33.200001 1.450000 0.000000 +33.194157 1.386313 0.120000 +33.194157 1.386313 0.000000 +33.175426 1.321167 0.120000 +33.175426 1.321167 0.000000 +33.142948 1.258477 0.120000 +33.097488 1.202513 0.120000 +33.142948 1.258477 0.000000 +33.041523 1.157052 0.120000 +33.097488 1.202513 0.000000 +32.978832 1.124574 0.120000 +33.041523 1.157052 0.000000 +32.978832 1.124574 0.000000 +32.913689 1.105843 0.120000 +32.913689 1.105843 0.000000 +32.849998 1.100000 0.120000 +32.849998 1.100000 0.000000 +32.786312 1.105843 0.120000 +32.786312 1.105843 0.000000 +32.721169 1.124574 0.120000 +32.721169 1.124574 0.000000 +32.658478 1.157052 0.120000 +32.658478 1.157052 0.000000 +32.602512 1.202513 0.120000 +32.602512 1.202513 0.000000 +32.557053 1.258477 0.120000 +32.524574 1.321167 0.120000 +32.557053 1.258477 0.000000 +32.524574 1.321167 0.000000 +32.505844 1.386313 0.120000 +32.505844 1.386313 0.000000 +31.200001 1.450000 0.120000 +31.200001 1.450000 0.000000 +30.500000 1.450000 0.000000 +30.500000 1.450000 0.120000 +30.505842 1.386313 0.000000 +30.505842 1.386313 0.120000 +30.524574 1.321167 0.000000 +30.524574 1.321167 0.120000 +30.557051 1.258477 0.000000 +30.557051 1.258477 0.120000 +30.602512 1.202513 0.000000 +30.602512 1.202513 0.120000 +30.658476 1.157052 0.000000 +30.658476 1.157052 0.120000 +30.721167 1.124574 0.000000 +30.721167 1.124574 0.120000 +30.786312 1.105843 0.000000 +30.786312 1.105843 0.120000 +30.850000 1.100000 0.000000 +30.850000 1.100000 0.120000 +30.913687 1.105843 0.000000 +30.913687 1.105843 0.120000 +30.978832 1.124574 0.000000 +30.978832 1.124574 0.120000 +31.041523 1.157052 0.000000 +31.041523 1.157052 0.120000 +31.097486 1.202513 0.000000 +31.097486 1.202513 0.120000 +31.142948 1.258477 0.000000 +31.142948 1.258477 0.120000 +31.175426 1.321167 0.000000 +31.175426 1.321167 0.120000 +31.194157 1.386313 0.000000 +31.194157 1.386313 0.120000 +29.200001 1.450000 0.120000 +29.200001 1.450000 0.000000 +28.500000 1.450000 0.000000 +28.500000 1.450000 0.120000 +28.505842 1.386313 0.000000 +28.505842 1.386313 0.120000 +28.524574 1.321167 0.000000 +28.524574 1.321167 0.120000 +28.557051 1.258477 0.000000 +28.557051 1.258477 0.120000 +28.602512 1.202513 0.000000 +28.602512 1.202513 0.120000 +28.658476 1.157052 0.000000 +28.658476 1.157052 0.120000 +28.721167 1.124574 0.000000 +28.721167 1.124574 0.120000 +28.786312 1.105843 0.000000 +28.786312 1.105843 0.120000 +28.850000 1.100000 0.000000 +28.850000 1.100000 0.120000 +28.913687 1.105843 0.000000 +28.913687 1.105843 0.120000 +28.978832 1.124574 0.000000 +28.978832 1.124574 0.120000 +29.041523 1.157052 0.000000 +29.041523 1.157052 0.120000 +29.097486 1.202513 0.000000 +29.097486 1.202513 0.120000 +29.142948 1.258477 0.000000 +29.142948 1.258477 0.120000 +29.175426 1.321167 0.000000 +29.175426 1.321167 0.120000 +29.194157 1.386313 0.000000 +29.194157 1.386313 0.120000 +27.200001 1.450000 0.120000 +27.200001 1.450000 0.000000 +26.500000 1.450000 0.000000 +26.500000 1.450000 0.120000 +26.505842 1.386313 0.000000 +26.505842 1.386313 0.120000 +26.524574 1.321167 0.000000 +26.524574 1.321167 0.120000 +26.557051 1.258477 0.000000 +26.557051 1.258477 0.120000 +26.602512 1.202513 0.000000 +26.602512 1.202513 0.120000 +26.658476 1.157052 0.000000 +26.658476 1.157052 0.120000 +26.721167 1.124574 0.000000 +26.721167 1.124574 0.120000 +26.786312 1.105843 0.000000 +26.786312 1.105843 0.120000 +26.850000 1.100000 0.000000 +26.850000 1.100000 0.120000 +26.913687 1.105843 0.000000 +26.913687 1.105843 0.120000 +26.978832 1.124574 0.000000 +26.978832 1.124574 0.120000 +27.041523 1.157052 0.000000 +27.041523 1.157052 0.120000 +27.097486 1.202513 0.000000 +27.142948 1.258477 0.000000 +27.097486 1.202513 0.120000 +27.175426 1.321167 0.000000 +27.142948 1.258477 0.120000 +27.175426 1.321167 0.120000 +27.194157 1.386313 0.000000 +27.194157 1.386313 0.120000 +25.200001 1.450000 0.120000 +25.200001 1.450000 0.000000 +24.500000 1.450000 0.000000 +24.500000 1.450000 0.120000 +24.505842 1.386313 0.000000 +24.505842 1.386313 0.120000 +24.524574 1.321167 0.000000 +24.524574 1.321167 0.120000 +24.557051 1.258477 0.000000 +24.557051 1.258477 0.120000 +24.602512 1.202513 0.000000 +24.602512 1.202513 0.120000 +24.658476 1.157052 0.000000 +24.658476 1.157052 0.120000 +24.721167 1.124574 0.000000 +24.721167 1.124574 0.120000 +24.786312 1.105843 0.000000 +24.786312 1.105843 0.120000 +24.850000 1.100000 0.000000 +24.850000 1.100000 0.120000 +24.913687 1.105843 0.000000 +24.913687 1.105843 0.120000 +24.978832 1.124574 0.000000 +24.978832 1.124574 0.120000 +25.041523 1.157052 0.000000 +25.041523 1.157052 0.120000 +25.097486 1.202513 0.000000 +25.097486 1.202513 0.120000 +25.142948 1.258477 0.000000 +25.142948 1.258477 0.120000 +25.175426 1.321167 0.000000 +25.175426 1.321167 0.120000 +25.194157 1.386313 0.000000 +25.194157 1.386313 0.120000 +23.200001 1.450000 0.120000 +23.200001 1.450000 0.000000 +22.500000 1.450000 0.000000 +22.500000 1.450000 0.120000 +22.505842 1.386313 0.000000 +22.505842 1.386313 0.120000 +22.524574 1.321167 0.000000 +22.524574 1.321167 0.120000 +22.557051 1.258477 0.000000 +22.557051 1.258477 0.120000 +22.602512 1.202513 0.000000 +22.602512 1.202513 0.120000 +22.658476 1.157052 0.000000 +22.658476 1.157052 0.120000 +22.721167 1.124574 0.000000 +22.721167 1.124574 0.120000 +22.786312 1.105843 0.000000 +22.786312 1.105843 0.120000 +22.850000 1.100000 0.000000 +22.850000 1.100000 0.120000 +22.913687 1.105843 0.000000 +22.913687 1.105843 0.120000 +22.978832 1.124574 0.000000 +22.978832 1.124574 0.120000 +23.041523 1.157052 0.000000 +23.041523 1.157052 0.120000 +23.097486 1.202513 0.000000 +23.097486 1.202513 0.120000 +23.142948 1.258477 0.000000 +23.142948 1.258477 0.120000 +23.175426 1.321167 0.000000 +23.175426 1.321167 0.120000 +23.194157 1.386313 0.000000 +23.194157 1.386313 0.120000 +21.200001 1.450000 0.120000 +21.200001 1.450000 0.000000 +20.500000 1.450000 0.000000 +20.500000 1.450000 0.120000 +20.505842 1.386313 0.000000 +20.505842 1.386313 0.120000 +20.524574 1.321167 0.000000 +20.524574 1.321167 0.120000 +20.557051 1.258477 0.000000 +20.557051 1.258477 0.120000 +20.602512 1.202513 0.000000 +20.602512 1.202513 0.120000 +20.658476 1.157052 0.000000 +20.658476 1.157052 0.120000 +20.721167 1.124574 0.000000 +20.721167 1.124574 0.120000 +20.786312 1.105843 0.000000 +20.786312 1.105843 0.120000 +20.850000 1.100000 0.000000 +20.850000 1.100000 0.120000 +20.913687 1.105843 0.000000 +20.913687 1.105843 0.120000 +20.978832 1.124574 0.000000 +20.978832 1.124574 0.120000 +21.041523 1.157052 0.000000 +21.041523 1.157052 0.120000 +21.097486 1.202513 0.000000 +21.097486 1.202513 0.120000 +21.142948 1.258477 0.000000 +21.142948 1.258477 0.120000 +21.175426 1.321167 0.000000 +21.175426 1.321167 0.120000 +21.194157 1.386313 0.000000 +21.194157 1.386313 0.120000 +19.200001 1.450000 0.120000 +19.200001 1.450000 0.000000 +18.500000 1.450000 0.000000 +18.500000 1.450000 0.120000 +18.505842 1.386313 0.000000 +18.505842 1.386313 0.120000 +18.524574 1.321167 0.000000 +18.524574 1.321167 0.120000 +18.557051 1.258477 0.000000 +18.602512 1.202513 0.000000 +18.557051 1.258477 0.120000 +18.602512 1.202513 0.120000 +18.658476 1.157052 0.000000 +18.658476 1.157052 0.120000 +18.721167 1.124574 0.000000 +18.721167 1.124574 0.120000 +18.786312 1.105843 0.000000 +18.786312 1.105843 0.120000 +18.850000 1.100000 0.000000 +18.850000 1.100000 0.120000 +18.913687 1.105843 0.000000 +18.913687 1.105843 0.120000 +18.978832 1.124574 0.000000 +18.978832 1.124574 0.120000 +19.041523 1.157052 0.000000 +19.041523 1.157052 0.120000 +19.097486 1.202513 0.000000 +19.097486 1.202513 0.120000 +19.142948 1.258477 0.000000 +19.142948 1.258477 0.120000 +19.175426 1.321167 0.000000 +19.194157 1.386313 0.000000 +19.175426 1.321167 0.120000 +19.194157 1.386313 0.120000 +17.200001 1.450000 0.120000 +17.200001 1.450000 0.000000 +16.505842 1.386313 0.000000 +16.500000 1.450000 0.000000 +16.500000 1.450000 0.120000 +16.505842 1.386313 0.120000 +16.524574 1.321167 0.000000 +16.557051 1.258477 0.000000 +16.524574 1.321167 0.120000 +16.557051 1.258477 0.120000 +16.602512 1.202513 0.000000 +16.602512 1.202513 0.120000 +16.658476 1.157052 0.000000 +16.658476 1.157052 0.120000 +16.721167 1.124574 0.000000 +16.721167 1.124574 0.120000 +16.786312 1.105843 0.000000 +16.786312 1.105843 0.120000 +16.850000 1.100000 0.000000 +16.850000 1.100000 0.120000 +16.913687 1.105843 0.000000 +16.913687 1.105843 0.120000 +16.978832 1.124574 0.000000 +16.978832 1.124574 0.120000 +17.041523 1.157052 0.000000 +17.041523 1.157052 0.120000 +17.097486 1.202513 0.000000 +17.097486 1.202513 0.120000 +17.142948 1.258477 0.000000 +17.175426 1.321167 0.000000 +17.142948 1.258477 0.120000 +17.175426 1.321167 0.120000 +17.194157 1.386313 0.000000 +17.194157 1.386313 0.120000 +15.200000 1.450000 0.120000 +15.200000 1.450000 0.000000 +14.500000 1.450000 0.000000 +14.500000 1.450000 0.120000 +14.505843 1.386313 0.000000 +14.505843 1.386313 0.120000 +14.524574 1.321167 0.000000 +14.524574 1.321167 0.120000 +14.557052 1.258477 0.000000 +14.557052 1.258477 0.120000 +14.602512 1.202513 0.000000 +14.602512 1.202513 0.120000 +14.658477 1.157052 0.000000 +14.658477 1.157052 0.120000 +14.721167 1.124574 0.000000 +14.786313 1.105843 0.000000 +14.721167 1.124574 0.120000 +14.786313 1.105843 0.120000 +14.850000 1.100000 0.000000 +14.850000 1.100000 0.120000 +14.913687 1.105843 0.000000 +14.913687 1.105843 0.120000 +14.978833 1.124574 0.000000 +14.978833 1.124574 0.120000 +15.041523 1.157052 0.000000 +15.041523 1.157052 0.120000 +15.097487 1.202513 0.000000 +15.097487 1.202513 0.120000 +15.142948 1.258477 0.000000 +15.142948 1.258477 0.120000 +15.175426 1.321167 0.000000 +15.175426 1.321167 0.120000 +15.194157 1.386313 0.000000 +15.194157 1.386313 0.120000 +13.200000 1.450000 0.120000 +13.200000 1.450000 0.000000 +12.500000 1.450000 0.000000 +12.500000 1.450000 0.120000 +12.505843 1.386313 0.000000 +12.505843 1.386313 0.120000 +12.524574 1.321167 0.000000 +12.524574 1.321167 0.120000 +12.557052 1.258477 0.000000 +12.557052 1.258477 0.120000 +12.602512 1.202513 0.000000 +12.602512 1.202513 0.120000 +12.658477 1.157052 0.000000 +12.658477 1.157052 0.120000 +12.721167 1.124574 0.000000 +12.721167 1.124574 0.120000 +12.786313 1.105843 0.000000 +12.786313 1.105843 0.120000 +12.850000 1.100000 0.000000 +12.913687 1.105843 0.000000 +12.850000 1.100000 0.120000 +12.913687 1.105843 0.120000 +12.978833 1.124574 0.000000 +12.978833 1.124574 0.120000 +13.041523 1.157052 0.000000 +13.041523 1.157052 0.120000 +13.097487 1.202513 0.000000 +13.097487 1.202513 0.120000 +13.142948 1.258477 0.000000 +13.142948 1.258477 0.120000 +13.175426 1.321167 0.000000 +13.194157 1.386313 0.000000 +13.175426 1.321167 0.120000 +13.194157 1.386313 0.120000 +11.200000 1.450000 0.120000 +11.200000 1.450000 0.000000 +10.500000 1.450000 0.000000 +10.500000 1.450000 0.120000 +10.505843 1.386313 0.000000 +10.505843 1.386313 0.120000 +10.524574 1.321167 0.000000 +10.524574 1.321167 0.120000 +10.557052 1.258477 0.000000 +10.557052 1.258477 0.120000 +10.602512 1.202513 0.000000 +10.602512 1.202513 0.120000 +10.658477 1.157052 0.000000 +10.658477 1.157052 0.120000 +10.721167 1.124574 0.000000 +10.721167 1.124574 0.120000 +10.786313 1.105843 0.000000 +10.786313 1.105843 0.120000 +10.850000 1.100000 0.000000 +10.850000 1.100000 0.120000 +10.913687 1.105843 0.000000 +10.913687 1.105843 0.120000 +10.978833 1.124574 0.000000 +10.978833 1.124574 0.120000 +11.041523 1.157052 0.000000 +11.041523 1.157052 0.120000 +11.097487 1.202513 0.000000 +11.097487 1.202513 0.120000 +11.142948 1.258477 0.000000 +11.142948 1.258477 0.120000 +11.175426 1.321167 0.000000 +11.175426 1.321167 0.120000 +11.194157 1.386313 0.000000 +11.194157 1.386313 0.120000 +9.200000 1.450000 0.120000 +9.200000 1.450000 0.000000 +8.500000 1.450000 0.000000 +8.500000 1.450000 0.120000 +8.505843 1.386313 0.000000 +8.505843 1.386313 0.120000 +8.524574 1.321167 0.000000 +8.524574 1.321167 0.120000 +8.557052 1.258477 0.000000 +8.557052 1.258477 0.120000 +8.602512 1.202513 0.000000 +8.602512 1.202513 0.120000 +8.658477 1.157052 0.000000 +8.658477 1.157052 0.120000 +8.721167 1.124574 0.000000 +8.721167 1.124574 0.120000 +8.786313 1.105843 0.000000 +8.786313 1.105843 0.120000 +8.850000 1.100000 0.000000 +8.850000 1.100000 0.120000 +8.913687 1.105843 0.000000 +8.913687 1.105843 0.120000 +8.978833 1.124574 0.000000 +8.978833 1.124574 0.120000 +9.041523 1.157052 0.000000 +9.041523 1.157052 0.120000 +9.097487 1.202513 0.000000 +9.097487 1.202513 0.120000 +9.142948 1.258477 0.000000 +9.142948 1.258477 0.120000 +9.175426 1.321167 0.000000 +9.194157 1.386313 0.000000 +9.175426 1.321167 0.120000 +9.194157 1.386313 0.120000 +7.200000 1.450000 0.120000 +7.200000 1.450000 0.000000 +6.500000 1.450000 0.000000 +6.500000 1.450000 0.120000 +6.505843 1.386313 0.000000 +6.505843 1.386313 0.120000 +6.524574 1.321167 0.000000 +6.557052 1.258477 0.000000 +6.524574 1.321167 0.120000 +6.557052 1.258477 0.120000 +6.602513 1.202513 0.000000 +6.602513 1.202513 0.120000 +6.658476 1.157052 0.000000 +6.658476 1.157052 0.120000 +6.721167 1.124574 0.000000 +6.721167 1.124574 0.120000 +6.786313 1.105843 0.000000 +6.786313 1.105843 0.120000 +6.850000 1.100000 0.000000 +6.850000 1.100000 0.120000 +6.913687 1.105843 0.000000 +6.913687 1.105843 0.120000 +6.978833 1.124574 0.000000 +6.978833 1.124574 0.120000 +7.041523 1.157052 0.000000 +7.097487 1.202513 0.000000 +7.041523 1.157052 0.120000 +7.097487 1.202513 0.120000 +7.142949 1.258477 0.000000 +7.142949 1.258477 0.120000 +7.175426 1.321167 0.000000 +7.175426 1.321167 0.120000 +7.194157 1.386313 0.000000 +7.194157 1.386313 0.120000 +5.200000 1.450000 0.120000 +5.200000 1.450000 0.000000 +4.500000 1.450000 0.000000 +4.500000 1.450000 0.120000 +4.505843 1.386313 0.000000 +4.505843 1.386313 0.120000 +4.524574 1.321167 0.000000 +4.557052 1.258477 0.000000 +4.524574 1.321167 0.120000 +4.557052 1.258477 0.120000 +4.602513 1.202513 0.000000 +4.602513 1.202513 0.120000 +4.658476 1.157052 0.000000 +4.658476 1.157052 0.120000 +4.721167 1.124574 0.000000 +4.721167 1.124574 0.120000 +4.786313 1.105843 0.000000 +4.786313 1.105843 0.120000 +4.850000 1.100000 0.000000 +4.850000 1.100000 0.120000 +4.913687 1.105843 0.000000 +4.913687 1.105843 0.120000 +4.978833 1.124574 0.000000 +4.978833 1.124574 0.120000 +5.041523 1.157052 0.000000 +5.041523 1.157052 0.120000 +5.097487 1.202513 0.000000 +5.097487 1.202513 0.120000 +5.142949 1.258477 0.000000 +5.142949 1.258477 0.120000 +5.175426 1.321167 0.000000 +5.175426 1.321167 0.120000 +5.194157 1.386313 0.000000 +5.194157 1.386313 0.120000 +3.200000 1.450000 0.120000 +3.200000 1.450000 0.000000 +2.500000 1.450000 0.000000 +2.500000 1.450000 0.120000 +2.505843 1.386313 0.000000 +2.505843 1.386313 0.120000 +2.524574 1.321167 0.000000 +2.524574 1.321167 0.120000 +2.557052 1.258477 0.000000 +2.557052 1.258477 0.120000 +2.602513 1.202513 0.000000 +2.602513 1.202513 0.120000 +2.658477 1.157052 0.000000 +2.658477 1.157052 0.120000 +2.721167 1.124574 0.000000 +2.721167 1.124574 0.120000 +2.786313 1.105843 0.000000 +2.786313 1.105843 0.120000 +2.850000 1.100000 0.000000 +2.850000 1.100000 0.120000 +2.913687 1.105843 0.000000 +2.913687 1.105843 0.120000 +2.978833 1.124574 0.000000 +2.978833 1.124574 0.120000 +3.041523 1.157052 0.000000 +3.041523 1.157052 0.120000 +3.097487 1.202513 0.000000 +3.097487 1.202513 0.120000 +3.142948 1.258477 0.000000 +3.142948 1.258477 0.120000 +3.175426 1.321167 0.000000 +3.175426 1.321167 0.120000 +3.194157 1.386313 0.000000 +3.194157 1.386313 0.120000 +38.194157 0.636313 0.120000 +38.200001 0.700000 0.120000 +37.500000 0.700000 0.000000 +37.500000 0.700000 0.120000 +37.505844 0.636313 0.000000 +37.505844 0.636313 0.120000 +37.524574 0.571167 0.000000 +37.524574 0.571167 0.120000 +37.557053 0.508477 0.000000 +37.602512 0.452513 0.000000 +37.557053 0.508477 0.120000 +37.602512 0.452513 0.120000 +37.658478 0.407052 0.000000 +37.658478 0.407052 0.120000 +37.721169 0.374574 0.000000 +37.721169 0.374574 0.120000 +37.786312 0.355843 0.000000 +37.786312 0.355843 0.120000 +37.849998 0.350000 0.000000 +37.849998 0.350000 0.120000 +37.913689 0.355843 0.000000 +37.913689 0.355843 0.120000 +37.978832 0.374574 0.000000 +38.041523 0.407052 0.000000 +37.978832 0.374574 0.120000 +38.041523 0.407052 0.120000 +38.097488 0.452513 0.000000 +38.142948 0.508477 0.000000 +38.097488 0.452513 0.120000 +38.142948 0.508477 0.120000 +38.175426 0.571167 0.000000 +38.175426 0.571167 0.120000 +38.194157 0.636313 0.000000 +38.200001 0.700000 0.000000 +37.505844 2.136313 0.120000 +37.500000 2.200000 0.000000 +37.500000 2.200000 0.120000 +37.505844 2.136313 0.000000 +38.194157 2.136313 0.120000 +38.200001 2.200000 0.120000 +38.200001 2.200000 0.000000 +38.194157 2.136313 0.000000 +38.175426 2.071167 0.120000 +38.142948 2.008476 0.120000 +38.175426 2.071167 0.000000 +38.142948 2.008476 0.000000 +38.097488 1.952513 0.120000 +38.097488 1.952513 0.000000 +38.041523 1.907052 0.120000 +38.041523 1.907052 0.000000 +37.978832 1.874574 0.120000 +37.978832 1.874574 0.000000 +37.913689 1.855843 0.120000 +37.913689 1.855843 0.000000 +37.849998 1.850000 0.120000 +37.849998 1.850000 0.000000 +37.786312 1.855843 0.120000 +37.786312 1.855843 0.000000 +37.721169 1.874574 0.120000 +37.721169 1.874574 0.000000 +37.658478 1.907052 0.120000 +37.658478 1.907052 0.000000 +37.602512 1.952513 0.120000 +37.557053 2.008476 0.120000 +37.602512 1.952513 0.000000 +37.557053 2.008476 0.000000 +37.524574 2.071167 0.120000 +37.524574 2.071167 0.000000 +36.194157 0.636313 0.120000 +36.200001 0.700000 0.120000 +35.500000 0.700000 0.000000 +35.500000 0.700000 0.120000 +35.505844 0.636313 0.000000 +35.505844 0.636313 0.120000 +35.524574 0.571167 0.000000 +35.557053 0.508477 0.000000 +35.524574 0.571167 0.120000 +35.557053 0.508477 0.120000 +35.602512 0.452513 0.000000 +35.602512 0.452513 0.120000 +35.658478 0.407052 0.000000 +35.658478 0.407052 0.120000 +35.721169 0.374574 0.000000 +35.721169 0.374574 0.120000 +35.786312 0.355843 0.000000 +35.786312 0.355843 0.120000 +35.849998 0.350000 0.000000 +35.849998 0.350000 0.120000 +35.913689 0.355843 0.000000 +35.913689 0.355843 0.120000 +35.978832 0.374574 0.000000 +35.978832 0.374574 0.120000 +36.041523 0.407052 0.000000 +36.041523 0.407052 0.120000 +36.097488 0.452513 0.000000 +36.142948 0.508477 0.000000 +36.097488 0.452513 0.120000 +36.142948 0.508477 0.120000 +36.175426 0.571167 0.000000 +36.175426 0.571167 0.120000 +36.194157 0.636313 0.000000 +36.200001 0.700000 0.000000 +35.500000 2.200000 0.000000 +35.500000 2.200000 0.120000 +36.194157 2.136313 0.120000 +36.200001 2.200000 0.120000 +36.200001 2.200000 0.000000 +36.175426 2.071167 0.120000 +36.194157 2.136313 0.000000 +36.175426 2.071167 0.000000 +36.142948 2.008476 0.120000 +36.097488 1.952513 0.120000 +36.142948 2.008476 0.000000 +36.097488 1.952513 0.000000 +36.041523 1.907052 0.120000 +36.041523 1.907052 0.000000 +35.978832 1.874574 0.120000 +35.978832 1.874574 0.000000 +35.913689 1.855843 0.120000 +35.913689 1.855843 0.000000 +35.849998 1.850000 0.120000 +35.786312 1.855843 0.120000 +35.849998 1.850000 0.000000 +35.786312 1.855843 0.000000 +35.721169 1.874574 0.120000 +35.721169 1.874574 0.000000 +35.658478 1.907052 0.120000 +35.658478 1.907052 0.000000 +35.602512 1.952513 0.120000 +35.602512 1.952513 0.000000 +35.557053 2.008476 0.120000 +35.557053 2.008476 0.000000 +35.524574 2.071167 0.120000 +35.524574 2.071167 0.000000 +35.505844 2.136313 0.120000 +35.505844 2.136313 0.000000 +34.194157 0.636313 0.120000 +34.200001 0.700000 0.120000 +33.500000 0.700000 0.000000 +33.500000 0.700000 0.120000 +33.505844 0.636313 0.000000 +33.505844 0.636313 0.120000 +33.524574 0.571167 0.000000 +33.524574 0.571167 0.120000 +33.557053 0.508477 0.000000 +33.602512 0.452513 0.000000 +33.557053 0.508477 0.120000 +33.602512 0.452513 0.120000 +33.658478 0.407052 0.000000 +33.658478 0.407052 0.120000 +33.721169 0.374574 0.000000 +33.721169 0.374574 0.120000 +33.786312 0.355843 0.000000 +33.786312 0.355843 0.120000 +33.849998 0.350000 0.000000 +33.849998 0.350000 0.120000 +33.913689 0.355843 0.000000 +33.913689 0.355843 0.120000 +33.978832 0.374574 0.000000 +34.041523 0.407052 0.000000 +33.978832 0.374574 0.120000 +34.041523 0.407052 0.120000 +34.097488 0.452513 0.000000 +34.142948 0.508477 0.000000 +34.097488 0.452513 0.120000 +34.142948 0.508477 0.120000 +34.175426 0.571167 0.000000 +34.175426 0.571167 0.120000 +34.194157 0.636313 0.000000 +34.200001 0.700000 0.000000 +33.500000 2.200000 0.000000 +33.500000 2.200000 0.120000 +34.194157 2.136313 0.120000 +34.200001 2.200000 0.120000 +34.200001 2.200000 0.000000 +34.175426 2.071167 0.120000 +34.194157 2.136313 0.000000 +34.175426 2.071167 0.000000 +34.142948 2.008476 0.120000 +34.142948 2.008476 0.000000 +34.097488 1.952513 0.120000 +34.097488 1.952513 0.000000 +34.041523 1.907052 0.120000 +34.041523 1.907052 0.000000 +33.978832 1.874574 0.120000 +33.978832 1.874574 0.000000 +33.913689 1.855843 0.120000 +33.913689 1.855843 0.000000 +33.849998 1.850000 0.120000 +33.849998 1.850000 0.000000 +33.786312 1.855843 0.120000 +33.786312 1.855843 0.000000 +33.721169 1.874574 0.120000 +33.721169 1.874574 0.000000 +33.658478 1.907052 0.120000 +33.658478 1.907052 0.000000 +33.602512 1.952513 0.120000 +33.602512 1.952513 0.000000 +33.557053 2.008476 0.120000 +33.557053 2.008476 0.000000 +33.524574 2.071167 0.120000 +33.524574 2.071167 0.000000 +33.505844 2.136313 0.120000 +33.505844 2.136313 0.000000 +31.500000 0.700000 0.000000 +31.500000 0.700000 0.120000 +32.200001 0.700000 0.120000 +32.200001 0.700000 0.000000 +32.194157 0.636313 0.120000 +32.194157 0.636313 0.000000 +32.175426 0.571167 0.120000 +32.175426 0.571167 0.000000 +32.142948 0.508477 0.120000 +32.142948 0.508477 0.000000 +32.097488 0.452513 0.120000 +32.097488 0.452513 0.000000 +32.041523 0.407052 0.120000 +32.041523 0.407052 0.000000 +31.978832 0.374574 0.120000 +31.978832 0.374574 0.000000 +31.913687 0.355843 0.120000 +31.913687 0.355843 0.000000 +31.850000 0.350000 0.120000 +31.850000 0.350000 0.000000 +31.786312 0.355843 0.120000 +31.786312 0.355843 0.000000 +31.721167 0.374574 0.120000 +31.721167 0.374574 0.000000 +31.658476 0.407052 0.120000 +31.658476 0.407052 0.000000 +31.602512 0.452513 0.120000 +31.602512 0.452513 0.000000 +31.557051 0.508477 0.120000 +31.557051 0.508477 0.000000 +31.524574 0.571167 0.120000 +31.505842 0.636313 0.120000 +31.524574 0.571167 0.000000 +31.505842 0.636313 0.000000 +31.524574 2.071167 0.000000 +31.505842 2.136313 0.000000 +31.500000 2.200000 0.000000 +31.500000 2.200000 0.120000 +32.194157 2.136313 0.120000 +32.200001 2.200000 0.120000 +32.200001 2.200000 0.000000 +32.194157 2.136313 0.000000 +32.175426 2.071167 0.120000 +32.175426 2.071167 0.000000 +32.142948 2.008476 0.120000 +32.142948 2.008476 0.000000 +32.097488 1.952513 0.120000 +32.041523 1.907052 0.120000 +32.097488 1.952513 0.000000 +32.041523 1.907052 0.000000 +31.978832 1.874574 0.120000 +31.978832 1.874574 0.000000 +31.913687 1.855843 0.120000 +31.850000 1.850000 0.120000 +31.913687 1.855843 0.000000 +31.786312 1.855843 0.120000 +31.850000 1.850000 0.000000 +31.786312 1.855843 0.000000 +31.721167 1.874574 0.120000 +31.721167 1.874574 0.000000 +31.658476 1.907052 0.120000 +31.658476 1.907052 0.000000 +31.602512 1.952513 0.120000 +31.602512 1.952513 0.000000 +31.557051 2.008476 0.120000 +31.524574 2.071167 0.120000 +31.557051 2.008476 0.000000 +31.505842 2.136313 0.120000 +30.200001 0.700000 0.120000 +30.200001 0.700000 0.000000 +29.500000 0.700000 0.000000 +29.500000 0.700000 0.120000 +29.505842 0.636313 0.000000 +29.505842 0.636313 0.120000 +29.524574 0.571167 0.000000 +29.524574 0.571167 0.120000 +29.557051 0.508477 0.000000 +29.557051 0.508477 0.120000 +29.602512 0.452513 0.000000 +29.602512 0.452513 0.120000 +29.658476 0.407052 0.000000 +29.721167 0.374574 0.000000 +29.658476 0.407052 0.120000 +29.721167 0.374574 0.120000 +29.786312 0.355843 0.000000 +29.786312 0.355843 0.120000 +29.850000 0.350000 0.000000 +29.850000 0.350000 0.120000 +29.913687 0.355843 0.000000 +29.913687 0.355843 0.120000 +29.978832 0.374574 0.000000 +29.978832 0.374574 0.120000 +30.041523 0.407052 0.000000 +30.041523 0.407052 0.120000 +30.097486 0.452513 0.000000 +30.097486 0.452513 0.120000 +30.142948 0.508477 0.000000 +30.142948 0.508477 0.120000 +30.175426 0.571167 0.000000 +30.175426 0.571167 0.120000 +30.194157 0.636313 0.000000 +30.194157 0.636313 0.120000 +29.602512 1.952513 0.120000 +29.505842 2.136313 0.000000 +29.500000 2.200000 0.000000 +29.500000 2.200000 0.120000 +29.505842 2.136313 0.120000 +29.524574 2.071167 0.000000 +29.524574 2.071167 0.120000 +29.557051 2.008476 0.000000 +29.602512 1.952513 0.000000 +29.557051 2.008476 0.120000 +30.200001 2.200000 0.120000 +30.200001 2.200000 0.000000 +30.194157 2.136313 0.120000 +30.194157 2.136313 0.000000 +30.175426 2.071167 0.120000 +30.142948 2.008476 0.120000 +30.175426 2.071167 0.000000 +30.142948 2.008476 0.000000 +30.097486 1.952513 0.120000 +30.097486 1.952513 0.000000 +30.041523 1.907052 0.120000 +30.041523 1.907052 0.000000 +29.978832 1.874574 0.120000 +29.978832 1.874574 0.000000 +29.913687 1.855843 0.120000 +29.913687 1.855843 0.000000 +29.850000 1.850000 0.120000 +29.850000 1.850000 0.000000 +29.786312 1.855843 0.120000 +29.786312 1.855843 0.000000 +29.721167 1.874574 0.120000 +29.658476 1.907052 0.120000 +29.721167 1.874574 0.000000 +29.658476 1.907052 0.000000 +27.500000 0.700000 0.000000 +27.500000 0.700000 0.120000 +28.200001 0.700000 0.120000 +28.200001 0.700000 0.000000 +28.194157 0.636313 0.120000 +28.194157 0.636313 0.000000 +28.175426 0.571167 0.120000 +28.175426 0.571167 0.000000 +28.142948 0.508477 0.120000 +28.142948 0.508477 0.000000 +28.097486 0.452513 0.120000 +28.097486 0.452513 0.000000 +28.041523 0.407052 0.120000 +28.041523 0.407052 0.000000 +27.978832 0.374574 0.120000 +27.978832 0.374574 0.000000 +27.913687 0.355843 0.120000 +27.913687 0.355843 0.000000 +27.850000 0.350000 0.120000 +27.850000 0.350000 0.000000 +27.786312 0.355843 0.120000 +27.786312 0.355843 0.000000 +27.721167 0.374574 0.120000 +27.658476 0.407052 0.120000 +27.721167 0.374574 0.000000 +27.658476 0.407052 0.000000 +27.602512 0.452513 0.120000 +27.602512 0.452513 0.000000 +27.557051 0.508477 0.120000 +27.557051 0.508477 0.000000 +27.524574 0.571167 0.120000 +27.505842 0.636313 0.120000 +27.524574 0.571167 0.000000 +27.505842 0.636313 0.000000 +28.200001 2.200000 0.120000 +28.200001 2.200000 0.000000 +27.505842 2.136313 0.000000 +27.500000 2.200000 0.000000 +27.500000 2.200000 0.120000 +27.505842 2.136313 0.120000 +27.524574 2.071167 0.000000 +27.557051 2.008476 0.000000 +27.524574 2.071167 0.120000 +27.602512 1.952513 0.000000 +27.557051 2.008476 0.120000 +27.658476 1.907052 0.000000 +27.602512 1.952513 0.120000 +27.658476 1.907052 0.120000 +27.721167 1.874574 0.000000 +27.786312 1.855843 0.000000 +27.721167 1.874574 0.120000 +27.786312 1.855843 0.120000 +27.850000 1.850000 0.000000 +27.850000 1.850000 0.120000 +27.913687 1.855843 0.000000 +27.913687 1.855843 0.120000 +27.978832 1.874574 0.000000 +27.978832 1.874574 0.120000 +28.041523 1.907052 0.000000 +28.041523 1.907052 0.120000 +28.097486 1.952513 0.000000 +28.097486 1.952513 0.120000 +28.142948 2.008476 0.000000 +28.142948 2.008476 0.120000 +28.175426 2.071167 0.000000 +28.175426 2.071167 0.120000 +28.194157 2.136313 0.000000 +28.194157 2.136313 0.120000 +26.200001 0.700000 0.120000 +26.200001 0.700000 0.000000 +25.500000 0.700000 0.000000 +25.500000 0.700000 0.120000 +25.505842 0.636313 0.000000 +25.505842 0.636313 0.120000 +25.524574 0.571167 0.000000 +25.557051 0.508477 0.000000 +25.524574 0.571167 0.120000 +25.557051 0.508477 0.120000 +25.602512 0.452513 0.000000 +25.602512 0.452513 0.120000 +25.658476 0.407052 0.000000 +25.658476 0.407052 0.120000 +25.721167 0.374574 0.000000 +25.721167 0.374574 0.120000 +25.786312 0.355843 0.000000 +25.786312 0.355843 0.120000 +25.850000 0.350000 0.000000 +25.850000 0.350000 0.120000 +25.913687 0.355843 0.000000 +25.913687 0.355843 0.120000 +25.978832 0.374574 0.000000 +25.978832 0.374574 0.120000 +26.041523 0.407052 0.000000 +26.097486 0.452513 0.000000 +26.041523 0.407052 0.120000 +26.097486 0.452513 0.120000 +26.142948 0.508477 0.000000 +26.142948 0.508477 0.120000 +26.175426 0.571167 0.000000 +26.175426 0.571167 0.120000 +26.194157 0.636313 0.000000 +26.194157 0.636313 0.120000 +25.557051 2.008476 0.000000 +25.500000 2.200000 0.000000 +25.500000 2.200000 0.120000 +25.505842 2.136313 0.000000 +25.505842 2.136313 0.120000 +25.524574 2.071167 0.000000 +26.200001 2.200000 0.120000 +26.200001 2.200000 0.000000 +26.194157 2.136313 0.120000 +26.194157 2.136313 0.000000 +26.175426 2.071167 0.120000 +26.142948 2.008476 0.120000 +26.175426 2.071167 0.000000 +26.142948 2.008476 0.000000 +26.097486 1.952513 0.120000 +26.097486 1.952513 0.000000 +26.041523 1.907052 0.120000 +26.041523 1.907052 0.000000 +25.978832 1.874574 0.120000 +25.978832 1.874574 0.000000 +25.913687 1.855843 0.120000 +25.850000 1.850000 0.120000 +25.913687 1.855843 0.000000 +25.850000 1.850000 0.000000 +25.786312 1.855843 0.120000 +25.786312 1.855843 0.000000 +25.721167 1.874574 0.120000 +25.721167 1.874574 0.000000 +25.658476 1.907052 0.120000 +25.658476 1.907052 0.000000 +25.602512 1.952513 0.120000 +25.602512 1.952513 0.000000 +25.557051 2.008476 0.120000 +25.524574 2.071167 0.120000 +23.500000 0.700000 0.000000 +23.500000 0.700000 0.120000 +24.200001 0.700000 0.120000 +24.200001 0.700000 0.000000 +24.194157 0.636313 0.120000 +24.194157 0.636313 0.000000 +24.175426 0.571167 0.120000 +24.142948 0.508477 0.120000 +24.175426 0.571167 0.000000 +24.142948 0.508477 0.000000 +24.097486 0.452513 0.120000 +24.097486 0.452513 0.000000 +24.041523 0.407052 0.120000 +24.041523 0.407052 0.000000 +23.978832 0.374574 0.120000 +23.978832 0.374574 0.000000 +23.913687 0.355843 0.120000 +23.850000 0.350000 0.120000 +23.913687 0.355843 0.000000 +23.850000 0.350000 0.000000 +23.786312 0.355843 0.120000 +23.786312 0.355843 0.000000 +23.721167 0.374574 0.120000 +23.721167 0.374574 0.000000 +23.658476 0.407052 0.120000 +23.658476 0.407052 0.000000 +23.602512 0.452513 0.120000 +23.602512 0.452513 0.000000 +23.557051 0.508477 0.120000 +23.557051 0.508477 0.000000 +23.524574 0.571167 0.120000 +23.524574 0.571167 0.000000 +23.505842 0.636313 0.120000 +23.505842 0.636313 0.000000 +23.524574 2.071167 0.000000 +23.500000 2.200000 0.000000 +23.500000 2.200000 0.120000 +23.505842 2.136313 0.000000 +24.200001 2.200000 0.120000 +24.200001 2.200000 0.000000 +24.194157 2.136313 0.120000 +24.194157 2.136313 0.000000 +24.175426 2.071167 0.120000 +24.142948 2.008476 0.120000 +24.175426 2.071167 0.000000 +24.142948 2.008476 0.000000 +24.097486 1.952513 0.120000 +24.097486 1.952513 0.000000 +24.041523 1.907052 0.120000 +24.041523 1.907052 0.000000 +23.978832 1.874574 0.120000 +23.913687 1.855843 0.120000 +23.978832 1.874574 0.000000 +23.913687 1.855843 0.000000 +23.850000 1.850000 0.120000 +23.850000 1.850000 0.000000 +23.786312 1.855843 0.120000 +23.786312 1.855843 0.000000 +23.721167 1.874574 0.120000 +23.721167 1.874574 0.000000 +23.658476 1.907052 0.120000 +23.658476 1.907052 0.000000 +23.602512 1.952513 0.120000 +23.602512 1.952513 0.000000 +23.557051 2.008476 0.120000 +23.557051 2.008476 0.000000 +23.524574 2.071167 0.120000 +23.505842 2.136313 0.120000 +22.200001 0.700000 0.120000 +22.200001 0.700000 0.000000 +21.500000 0.700000 0.000000 +21.500000 0.700000 0.120000 +21.505842 0.636313 0.000000 +21.524574 0.571167 0.000000 +21.505842 0.636313 0.120000 +21.524574 0.571167 0.120000 +21.557051 0.508477 0.000000 +21.557051 0.508477 0.120000 +21.602512 0.452513 0.000000 +21.602512 0.452513 0.120000 +21.658476 0.407052 0.000000 +21.658476 0.407052 0.120000 +21.721167 0.374574 0.000000 +21.721167 0.374574 0.120000 +21.786312 0.355843 0.000000 +21.786312 0.355843 0.120000 +21.850000 0.350000 0.000000 +21.850000 0.350000 0.120000 +21.913687 0.355843 0.000000 +21.913687 0.355843 0.120000 +21.978832 0.374574 0.000000 +21.978832 0.374574 0.120000 +22.041523 0.407052 0.000000 +22.097486 0.452513 0.000000 +22.041523 0.407052 0.120000 +22.097486 0.452513 0.120000 +22.142948 0.508477 0.000000 +22.142948 0.508477 0.120000 +22.175426 0.571167 0.000000 +22.194157 0.636313 0.000000 +22.175426 0.571167 0.120000 +22.194157 0.636313 0.120000 +22.200001 2.200000 0.120000 +22.200001 2.200000 0.000000 +21.505842 2.136313 0.000000 +21.500000 2.200000 0.000000 +21.500000 2.200000 0.120000 +21.505842 2.136313 0.120000 +21.524574 2.071167 0.000000 +21.524574 2.071167 0.120000 +21.557051 2.008476 0.000000 +21.557051 2.008476 0.120000 +21.602512 1.952513 0.000000 +21.602512 1.952513 0.120000 +21.658476 1.907052 0.000000 +21.658476 1.907052 0.120000 +21.721167 1.874574 0.000000 +21.721167 1.874574 0.120000 +21.786312 1.855843 0.000000 +21.786312 1.855843 0.120000 +21.850000 1.850000 0.000000 +21.850000 1.850000 0.120000 +21.913687 1.855843 0.000000 +21.913687 1.855843 0.120000 +21.978832 1.874574 0.000000 +21.978832 1.874574 0.120000 +22.041523 1.907052 0.000000 +22.097486 1.952513 0.000000 +22.041523 1.907052 0.120000 +22.097486 1.952513 0.120000 +22.142948 2.008476 0.000000 +22.142948 2.008476 0.120000 +22.175426 2.071167 0.000000 +22.194157 2.136313 0.000000 +22.175426 2.071167 0.120000 +22.194157 2.136313 0.120000 +1.500000 0.700000 0.000000 +1.500000 0.700000 0.120000 +2.200000 0.700000 0.120000 +2.200000 0.700000 0.000000 +2.194157 0.636313 0.120000 +2.194157 0.636313 0.000000 +2.175426 0.571167 0.120000 +2.175426 0.571167 0.000000 +2.142948 0.508477 0.120000 +2.142948 0.508477 0.000000 +2.097487 0.452513 0.120000 +2.097487 0.452513 0.000000 +2.041523 0.407052 0.120000 +2.041523 0.407052 0.000000 +1.978833 0.374574 0.120000 +1.978833 0.374574 0.000000 +1.913687 0.355843 0.120000 +1.913687 0.355843 0.000000 +1.850000 0.350000 0.120000 +1.850000 0.350000 0.000000 +1.786313 0.355843 0.120000 +1.786313 0.355843 0.000000 +1.721167 0.374574 0.120000 +1.721167 0.374574 0.000000 +1.658477 0.407052 0.120000 +1.658477 0.407052 0.000000 +1.602513 0.452513 0.120000 +1.602513 0.452513 0.000000 +1.557052 0.508477 0.120000 +1.557052 0.508477 0.000000 +1.524574 0.571167 0.120000 +1.524574 0.571167 0.000000 +1.505843 0.636313 0.120000 +1.505843 0.636313 0.000000 +2.200000 2.200000 0.120000 +2.200000 2.200000 0.000000 +1.500000 2.200000 0.000000 +1.500000 2.200000 0.120000 +1.505843 2.136313 0.000000 +1.505843 2.136313 0.120000 +1.524574 2.071167 0.000000 +1.524574 2.071167 0.120000 +1.557052 2.008476 0.000000 +1.557052 2.008476 0.120000 +1.602513 1.952513 0.000000 +1.602513 1.952513 0.120000 +1.658477 1.907052 0.000000 +1.658477 1.907052 0.120000 +1.721167 1.874574 0.000000 +1.721167 1.874574 0.120000 +1.786313 1.855843 0.000000 +1.786313 1.855843 0.120000 +1.850000 1.850000 0.000000 +1.850000 1.850000 0.120000 +1.913687 1.855843 0.000000 +1.913687 1.855843 0.120000 +1.978833 1.874574 0.000000 +1.978833 1.874574 0.120000 +2.041523 1.907052 0.000000 +2.041523 1.907052 0.120000 +2.097487 1.952513 0.000000 +2.142948 2.008476 0.000000 +2.097487 1.952513 0.120000 +2.142948 2.008476 0.120000 +2.175426 2.071167 0.000000 +2.175426 2.071167 0.120000 +2.194157 2.136313 0.000000 +2.194157 2.136313 0.120000 +4.200000 0.700000 0.120000 +4.200000 0.700000 0.000000 +3.500000 0.700000 0.000000 +3.500000 0.700000 0.120000 +3.505843 0.636313 0.000000 +3.505843 0.636313 0.120000 +3.524574 0.571167 0.000000 +3.524574 0.571167 0.120000 +3.557052 0.508477 0.000000 +3.557052 0.508477 0.120000 +3.602513 0.452513 0.000000 +3.602513 0.452513 0.120000 +3.658477 0.407052 0.000000 +3.658477 0.407052 0.120000 +3.721167 0.374574 0.000000 +3.721167 0.374574 0.120000 +3.786313 0.355843 0.000000 +3.786313 0.355843 0.120000 +3.850000 0.350000 0.000000 +3.850000 0.350000 0.120000 +3.913687 0.355843 0.000000 +3.913687 0.355843 0.120000 +3.978833 0.374574 0.000000 +3.978833 0.374574 0.120000 +4.041523 0.407052 0.000000 +4.041523 0.407052 0.120000 +4.097487 0.452513 0.000000 +4.097487 0.452513 0.120000 +4.142949 0.508477 0.000000 +4.142949 0.508477 0.120000 +4.175426 0.571167 0.000000 +4.175426 0.571167 0.120000 +4.194157 0.636313 0.000000 +4.194157 0.636313 0.120000 +4.200000 2.200000 0.120000 +4.200000 2.200000 0.000000 +3.500000 2.200000 0.000000 +3.500000 2.200000 0.120000 +3.505843 2.136313 0.000000 +3.505843 2.136313 0.120000 +3.524574 2.071167 0.000000 +3.524574 2.071167 0.120000 +3.557052 2.008476 0.000000 +3.602513 1.952513 0.000000 +3.557052 2.008476 0.120000 +3.602513 1.952513 0.120000 +3.658477 1.907052 0.000000 +3.658477 1.907052 0.120000 +3.721167 1.874574 0.000000 +3.721167 1.874574 0.120000 +3.786313 1.855843 0.000000 +3.786313 1.855843 0.120000 +3.850000 1.850000 0.000000 +3.850000 1.850000 0.120000 +3.913687 1.855843 0.000000 +3.913687 1.855843 0.120000 +3.978833 1.874574 0.000000 +4.041523 1.907052 0.000000 +3.978833 1.874574 0.120000 +4.041523 1.907052 0.120000 +4.097487 1.952513 0.000000 +4.142949 2.008476 0.000000 +4.097487 1.952513 0.120000 +4.175426 2.071167 0.000000 +4.142949 2.008476 0.120000 +4.194157 2.136313 0.000000 +4.175426 2.071167 0.120000 +4.194157 2.136313 0.120000 +5.505843 0.636313 0.000000 +5.500000 0.700000 0.000000 +6.200000 0.700000 0.120000 +6.200000 0.700000 0.000000 +6.194157 0.636313 0.120000 +6.194157 0.636313 0.000000 +6.175426 0.571167 0.120000 +6.175426 0.571167 0.000000 +6.142949 0.508477 0.120000 +6.142949 0.508477 0.000000 +6.097487 0.452513 0.120000 +6.097487 0.452513 0.000000 +6.041523 0.407052 0.120000 +6.041523 0.407052 0.000000 +5.978833 0.374574 0.120000 +5.978833 0.374574 0.000000 +5.913687 0.355843 0.120000 +5.913687 0.355843 0.000000 +5.850000 0.350000 0.120000 +5.850000 0.350000 0.000000 +5.786313 0.355843 0.120000 +5.786313 0.355843 0.000000 +5.721167 0.374574 0.120000 +5.721167 0.374574 0.000000 +5.658476 0.407052 0.120000 +5.658476 0.407052 0.000000 +5.602513 0.452513 0.120000 +5.602513 0.452513 0.000000 +5.557052 0.508477 0.120000 +5.557052 0.508477 0.000000 +5.524574 0.571167 0.120000 +5.524574 0.571167 0.000000 +5.505843 0.636313 0.120000 +5.500000 0.700000 0.120000 +6.200000 2.200000 0.120000 +6.200000 2.200000 0.000000 +5.500000 2.200000 0.000000 +5.500000 2.200000 0.120000 +5.505843 2.136313 0.000000 +5.505843 2.136313 0.120000 +5.524574 2.071167 0.000000 +5.524574 2.071167 0.120000 +5.557052 2.008476 0.000000 +5.557052 2.008476 0.120000 +5.602513 1.952513 0.000000 +5.602513 1.952513 0.120000 +5.658476 1.907052 0.000000 +5.658476 1.907052 0.120000 +5.721167 1.874574 0.000000 +5.721167 1.874574 0.120000 +5.786313 1.855843 0.000000 +5.786313 1.855843 0.120000 +5.850000 1.850000 0.000000 +5.850000 1.850000 0.120000 +5.913687 1.855843 0.000000 +5.913687 1.855843 0.120000 +5.978833 1.874574 0.000000 +5.978833 1.874574 0.120000 +6.041523 1.907052 0.000000 +6.041523 1.907052 0.120000 +6.097487 1.952513 0.000000 +6.142949 2.008476 0.000000 +6.097487 1.952513 0.120000 +6.175426 2.071167 0.000000 +6.142949 2.008476 0.120000 +6.194157 2.136313 0.000000 +6.175426 2.071167 0.120000 +6.194157 2.136313 0.120000 +7.500000 0.700000 0.000000 +7.500000 0.700000 0.120000 +8.200000 0.700000 0.120000 +8.200000 0.700000 0.000000 +8.194157 0.636313 0.120000 +8.194157 0.636313 0.000000 +8.175426 0.571167 0.120000 +8.175426 0.571167 0.000000 +8.142948 0.508477 0.120000 +8.142948 0.508477 0.000000 +8.097487 0.452513 0.120000 +8.041523 0.407052 0.120000 +8.097487 0.452513 0.000000 +8.041523 0.407052 0.000000 +7.978833 0.374574 0.120000 +7.978833 0.374574 0.000000 +7.913687 0.355843 0.120000 +7.913687 0.355843 0.000000 +7.850000 0.350000 0.120000 +7.850000 0.350000 0.000000 +7.786313 0.355843 0.120000 +7.786313 0.355843 0.000000 +7.721167 0.374574 0.120000 +7.658476 0.407052 0.120000 +7.721167 0.374574 0.000000 +7.658476 0.407052 0.000000 +7.602513 0.452513 0.120000 +7.602513 0.452513 0.000000 +7.557052 0.508477 0.120000 +7.557052 0.508477 0.000000 +7.524574 0.571167 0.120000 +7.505843 0.636313 0.120000 +7.524574 0.571167 0.000000 +7.505843 0.636313 0.000000 +7.500000 2.200000 0.000000 +7.500000 2.200000 0.120000 +8.200000 2.200000 0.120000 +8.200000 2.200000 0.000000 +8.194157 2.136313 0.120000 +8.194157 2.136313 0.000000 +8.175426 2.071167 0.120000 +8.175426 2.071167 0.000000 +8.142948 2.008476 0.120000 +8.142948 2.008476 0.000000 +8.097487 1.952513 0.120000 +8.097487 1.952513 0.000000 +8.041523 1.907052 0.120000 +8.041523 1.907052 0.000000 +7.978833 1.874574 0.120000 +7.978833 1.874574 0.000000 +7.913687 1.855843 0.120000 +7.913687 1.855843 0.000000 +7.850000 1.850000 0.120000 +7.786313 1.855843 0.120000 +7.850000 1.850000 0.000000 +7.786313 1.855843 0.000000 +7.721167 1.874574 0.120000 +7.658476 1.907052 0.120000 +7.721167 1.874574 0.000000 +7.658476 1.907052 0.000000 +7.602513 1.952513 0.120000 +7.602513 1.952513 0.000000 +7.557052 2.008476 0.120000 +7.557052 2.008476 0.000000 +7.524574 2.071167 0.120000 +7.524574 2.071167 0.000000 +7.505843 2.136313 0.120000 +7.505843 2.136313 0.000000 +9.505843 0.636313 0.120000 +9.500000 0.700000 0.000000 +9.500000 0.700000 0.120000 +9.505843 0.636313 0.000000 +10.200000 0.700000 0.120000 +10.200000 0.700000 0.000000 +10.194157 0.636313 0.120000 +10.194157 0.636313 0.000000 +10.175426 0.571167 0.120000 +10.175426 0.571167 0.000000 +10.142948 0.508477 0.120000 +10.097487 0.452513 0.120000 +10.142948 0.508477 0.000000 +10.097487 0.452513 0.000000 +10.041523 0.407052 0.120000 +10.041523 0.407052 0.000000 +9.978833 0.374574 0.120000 +9.978833 0.374574 0.000000 +9.913687 0.355843 0.120000 +9.913687 0.355843 0.000000 +9.850000 0.350000 0.120000 +9.850000 0.350000 0.000000 +9.786313 0.355843 0.120000 +9.786313 0.355843 0.000000 +9.721167 0.374574 0.120000 +9.721167 0.374574 0.000000 +9.658477 0.407052 0.120000 +9.658477 0.407052 0.000000 +9.602512 0.452513 0.120000 +9.602512 0.452513 0.000000 +9.557052 0.508477 0.120000 +9.557052 0.508477 0.000000 +9.524574 0.571167 0.120000 +9.524574 0.571167 0.000000 +9.500000 2.200000 0.000000 +9.500000 2.200000 0.120000 +10.200000 2.200000 0.120000 +10.200000 2.200000 0.000000 +10.194157 2.136313 0.120000 +10.194157 2.136313 0.000000 +10.175426 2.071167 0.120000 +10.175426 2.071167 0.000000 +10.142948 2.008476 0.120000 +10.142948 2.008476 0.000000 +10.097487 1.952513 0.120000 +10.041523 1.907052 0.120000 +10.097487 1.952513 0.000000 +10.041523 1.907052 0.000000 +9.978833 1.874574 0.120000 +9.978833 1.874574 0.000000 +9.913687 1.855843 0.120000 +9.913687 1.855843 0.000000 +9.850000 1.850000 0.120000 +9.850000 1.850000 0.000000 +9.786313 1.855843 0.120000 +9.721167 1.874574 0.120000 +9.786313 1.855843 0.000000 +9.658477 1.907052 0.120000 +9.721167 1.874574 0.000000 +9.658477 1.907052 0.000000 +9.602512 1.952513 0.120000 +9.602512 1.952513 0.000000 +9.557052 2.008476 0.120000 +9.557052 2.008476 0.000000 +9.524574 2.071167 0.120000 +9.505843 2.136313 0.120000 +9.524574 2.071167 0.000000 +9.505843 2.136313 0.000000 +12.200000 0.700000 0.120000 +12.200000 0.700000 0.000000 +11.500000 0.700000 0.000000 +11.500000 0.700000 0.120000 +11.505843 0.636313 0.000000 +11.505843 0.636313 0.120000 +11.524574 0.571167 0.000000 +11.524574 0.571167 0.120000 +11.557052 0.508477 0.000000 +11.557052 0.508477 0.120000 +11.602512 0.452513 0.000000 +11.602512 0.452513 0.120000 +11.658477 0.407052 0.000000 +11.658477 0.407052 0.120000 +11.721167 0.374574 0.000000 +11.721167 0.374574 0.120000 +11.786313 0.355843 0.000000 +11.786313 0.355843 0.120000 +11.850000 0.350000 0.000000 +11.850000 0.350000 0.120000 +11.913687 0.355843 0.000000 +11.913687 0.355843 0.120000 +11.978833 0.374574 0.000000 +11.978833 0.374574 0.120000 +12.041523 0.407052 0.000000 +12.041523 0.407052 0.120000 +12.097487 0.452513 0.000000 +12.097487 0.452513 0.120000 +12.142948 0.508477 0.000000 +12.175426 0.571167 0.000000 +12.142948 0.508477 0.120000 +12.175426 0.571167 0.120000 +12.194157 0.636313 0.000000 +12.194157 0.636313 0.120000 +12.200000 2.200000 0.120000 +12.200000 2.200000 0.000000 +11.500000 2.200000 0.000000 +11.500000 2.200000 0.120000 +11.505843 2.136313 0.000000 +11.505843 2.136313 0.120000 +11.524574 2.071167 0.000000 +11.524574 2.071167 0.120000 +11.557052 2.008476 0.000000 +11.602512 1.952513 0.000000 +11.557052 2.008476 0.120000 +11.602512 1.952513 0.120000 +11.658477 1.907052 0.000000 +11.658477 1.907052 0.120000 +11.721167 1.874574 0.000000 +11.786313 1.855843 0.000000 +11.721167 1.874574 0.120000 +11.786313 1.855843 0.120000 +11.850000 1.850000 0.000000 +11.913687 1.855843 0.000000 +11.850000 1.850000 0.120000 +11.913687 1.855843 0.120000 +11.978833 1.874574 0.000000 +11.978833 1.874574 0.120000 +12.041523 1.907052 0.000000 +12.041523 1.907052 0.120000 +12.097487 1.952513 0.000000 +12.142948 2.008476 0.000000 +12.097487 1.952513 0.120000 +12.142948 2.008476 0.120000 +12.175426 2.071167 0.000000 +12.175426 2.071167 0.120000 +12.194157 2.136313 0.000000 +12.194157 2.136313 0.120000 +13.505843 0.636313 0.120000 +13.500000 0.700000 0.000000 +13.500000 0.700000 0.120000 +13.505843 0.636313 0.000000 +14.200000 0.700000 0.120000 +14.200000 0.700000 0.000000 +14.194157 0.636313 0.120000 +14.194157 0.636313 0.000000 +14.175426 0.571167 0.120000 +14.175426 0.571167 0.000000 +14.142948 0.508477 0.120000 +14.097487 0.452513 0.120000 +14.142948 0.508477 0.000000 +14.097487 0.452513 0.000000 +14.041523 0.407052 0.120000 +14.041523 0.407052 0.000000 +13.978833 0.374574 0.120000 +13.978833 0.374574 0.000000 +13.913687 0.355843 0.120000 +13.913687 0.355843 0.000000 +13.850000 0.350000 0.120000 +13.850000 0.350000 0.000000 +13.786313 0.355843 0.120000 +13.786313 0.355843 0.000000 +13.721167 0.374574 0.120000 +13.721167 0.374574 0.000000 +13.658477 0.407052 0.120000 +13.658477 0.407052 0.000000 +13.602512 0.452513 0.120000 +13.602512 0.452513 0.000000 +13.557052 0.508477 0.120000 +13.557052 0.508477 0.000000 +13.524574 0.571167 0.120000 +13.524574 0.571167 0.000000 +13.505843 2.136313 0.120000 +13.505843 2.136313 0.000000 +13.500000 2.200000 0.000000 +13.500000 2.200000 0.120000 +14.200000 2.200000 0.120000 +14.200000 2.200000 0.000000 +14.194157 2.136313 0.120000 +14.194157 2.136313 0.000000 +14.175426 2.071167 0.120000 +14.175426 2.071167 0.000000 +14.142948 2.008476 0.120000 +14.142948 2.008476 0.000000 +14.097487 1.952513 0.120000 +14.097487 1.952513 0.000000 +14.041523 1.907052 0.120000 +14.041523 1.907052 0.000000 +13.978833 1.874574 0.120000 +13.978833 1.874574 0.000000 +13.913687 1.855843 0.120000 +13.850000 1.850000 0.120000 +13.913687 1.855843 0.000000 +13.786313 1.855843 0.120000 +13.850000 1.850000 0.000000 +13.786313 1.855843 0.000000 +13.721167 1.874574 0.120000 +13.721167 1.874574 0.000000 +13.658477 1.907052 0.120000 +13.658477 1.907052 0.000000 +13.602512 1.952513 0.120000 +13.602512 1.952513 0.000000 +13.557052 2.008476 0.120000 +13.557052 2.008476 0.000000 +13.524574 2.071167 0.120000 +13.524574 2.071167 0.000000 +15.524574 0.571167 0.120000 +15.500000 0.700000 0.000000 +15.500000 0.700000 0.120000 +15.505843 0.636313 0.000000 +15.505843 0.636313 0.120000 +15.524574 0.571167 0.000000 +16.200001 0.700000 0.120000 +16.200001 0.700000 0.000000 +16.194157 0.636313 0.120000 +16.194157 0.636313 0.000000 +16.175426 0.571167 0.120000 +16.175426 0.571167 0.000000 +16.142948 0.508477 0.120000 +16.097486 0.452513 0.120000 +16.142948 0.508477 0.000000 +16.097486 0.452513 0.000000 +16.041523 0.407052 0.120000 +16.041523 0.407052 0.000000 +15.978833 0.374574 0.120000 +15.978833 0.374574 0.000000 +15.913687 0.355843 0.120000 +15.913687 0.355843 0.000000 +15.850000 0.350000 0.120000 +15.850000 0.350000 0.000000 +15.786313 0.355843 0.120000 +15.786313 0.355843 0.000000 +15.721167 0.374574 0.120000 +15.721167 0.374574 0.000000 +15.658477 0.407052 0.120000 +15.658477 0.407052 0.000000 +15.602512 0.452513 0.120000 +15.557052 0.508477 0.120000 +15.602512 0.452513 0.000000 +15.557052 0.508477 0.000000 +15.524574 2.071167 0.120000 +15.500000 2.200000 0.000000 +15.500000 2.200000 0.120000 +15.505843 2.136313 0.000000 +15.505843 2.136313 0.120000 +15.524574 2.071167 0.000000 +16.194157 2.136313 0.120000 +16.200001 2.200000 0.120000 +16.200001 2.200000 0.000000 +16.194157 2.136313 0.000000 +16.175426 2.071167 0.120000 +16.175426 2.071167 0.000000 +16.142948 2.008476 0.120000 +16.142948 2.008476 0.000000 +16.097486 1.952513 0.120000 +16.097486 1.952513 0.000000 +16.041523 1.907052 0.120000 +16.041523 1.907052 0.000000 +15.978833 1.874574 0.120000 +15.978833 1.874574 0.000000 +15.913687 1.855843 0.120000 +15.913687 1.855843 0.000000 +15.850000 1.850000 0.120000 +15.850000 1.850000 0.000000 +15.786313 1.855843 0.120000 +15.786313 1.855843 0.000000 +15.721167 1.874574 0.120000 +15.658477 1.907052 0.120000 +15.721167 1.874574 0.000000 +15.658477 1.907052 0.000000 +15.602512 1.952513 0.120000 +15.557052 2.008476 0.120000 +15.602512 1.952513 0.000000 +15.557052 2.008476 0.000000 +17.500000 0.700000 0.000000 +17.500000 0.700000 0.120000 +18.200001 0.700000 0.120000 +18.200001 0.700000 0.000000 +18.194157 0.636313 0.120000 +18.194157 0.636313 0.000000 +18.175426 0.571167 0.120000 +18.175426 0.571167 0.000000 +18.142948 0.508477 0.120000 +18.142948 0.508477 0.000000 +18.097486 0.452513 0.120000 +18.097486 0.452513 0.000000 +18.041523 0.407052 0.120000 +18.041523 0.407052 0.000000 +17.978832 0.374574 0.120000 +17.978832 0.374574 0.000000 +17.913687 0.355843 0.120000 +17.850000 0.350000 0.120000 +17.913687 0.355843 0.000000 +17.850000 0.350000 0.000000 +17.786312 0.355843 0.120000 +17.786312 0.355843 0.000000 +17.721167 0.374574 0.120000 +17.721167 0.374574 0.000000 +17.658476 0.407052 0.120000 +17.658476 0.407052 0.000000 +17.602512 0.452513 0.120000 +17.602512 0.452513 0.000000 +17.557051 0.508477 0.120000 +17.524574 0.571167 0.120000 +17.557051 0.508477 0.000000 +17.524574 0.571167 0.000000 +17.505842 0.636313 0.120000 +17.505842 0.636313 0.000000 +18.200001 2.200000 0.120000 +18.200001 2.200000 0.000000 +17.500000 2.200000 0.000000 +17.500000 2.200000 0.120000 +17.505842 2.136313 0.000000 +17.505842 2.136313 0.120000 +17.524574 2.071167 0.000000 +17.557051 2.008476 0.000000 +17.524574 2.071167 0.120000 +17.557051 2.008476 0.120000 +17.602512 1.952513 0.000000 +17.602512 1.952513 0.120000 +17.658476 1.907052 0.000000 +17.658476 1.907052 0.120000 +17.721167 1.874574 0.000000 +17.721167 1.874574 0.120000 +17.786312 1.855843 0.000000 +17.786312 1.855843 0.120000 +17.850000 1.850000 0.000000 +17.850000 1.850000 0.120000 +17.913687 1.855843 0.000000 +17.913687 1.855843 0.120000 +17.978832 1.874574 0.000000 +17.978832 1.874574 0.120000 +18.041523 1.907052 0.000000 +18.041523 1.907052 0.120000 +18.097486 1.952513 0.000000 +18.097486 1.952513 0.120000 +18.142948 2.008476 0.000000 +18.142948 2.008476 0.120000 +18.175426 2.071167 0.000000 +18.175426 2.071167 0.120000 +18.194157 2.136313 0.000000 +18.194157 2.136313 0.120000 +19.500000 0.700000 0.000000 +19.500000 0.700000 0.120000 +20.200001 0.700000 0.120000 +20.200001 0.700000 0.000000 +20.194157 0.636313 0.120000 +20.194157 0.636313 0.000000 +20.175426 0.571167 0.120000 +20.142948 0.508477 0.120000 +20.175426 0.571167 0.000000 +20.142948 0.508477 0.000000 +20.097486 0.452513 0.120000 +20.097486 0.452513 0.000000 +20.041523 0.407052 0.120000 +20.041523 0.407052 0.000000 +19.978832 0.374574 0.120000 +19.978832 0.374574 0.000000 +19.913687 0.355843 0.120000 +19.850000 0.350000 0.120000 +19.913687 0.355843 0.000000 +19.850000 0.350000 0.000000 +19.786312 0.355843 0.120000 +19.786312 0.355843 0.000000 +19.721167 0.374574 0.120000 +19.721167 0.374574 0.000000 +19.658476 0.407052 0.120000 +19.658476 0.407052 0.000000 +19.602512 0.452513 0.120000 +19.602512 0.452513 0.000000 +19.557051 0.508477 0.120000 +19.557051 0.508477 0.000000 +19.524574 0.571167 0.120000 +19.524574 0.571167 0.000000 +19.505842 0.636313 0.120000 +19.505842 0.636313 0.000000 +19.500000 2.200000 0.000000 +19.500000 2.200000 0.120000 +20.200001 2.200000 0.120000 +20.200001 2.200000 0.000000 +20.194157 2.136313 0.120000 +20.194157 2.136313 0.000000 +20.175426 2.071167 0.120000 +20.142948 2.008476 0.120000 +20.175426 2.071167 0.000000 +20.142948 2.008476 0.000000 +20.097486 1.952513 0.120000 +20.097486 1.952513 0.000000 +20.041523 1.907052 0.120000 +20.041523 1.907052 0.000000 +19.978832 1.874574 0.120000 +19.978832 1.874574 0.000000 +19.913687 1.855843 0.120000 +19.913687 1.855843 0.000000 +19.850000 1.850000 0.120000 +19.850000 1.850000 0.000000 +19.786312 1.855843 0.120000 +19.786312 1.855843 0.000000 +19.721167 1.874574 0.120000 +19.658476 1.907052 0.120000 +19.721167 1.874574 0.000000 +19.658476 1.907052 0.000000 +19.602512 1.952513 0.120000 +19.602512 1.952513 0.000000 +19.557051 2.008476 0.120000 +19.557051 2.008476 0.000000 +19.524574 2.071167 0.120000 +19.524574 2.071167 0.000000 +19.505842 2.136313 0.120000 +19.505842 2.136313 0.000000 +0.000000 0.000000 0.120000 +0.000000 2.900000 0.120000 +0.000000 2.900000 0.000000 +0.000000 0.000000 0.000000 +39.700001 0.000000 0.120000 +0.000000 0.000000 0.120000 +0.000000 0.000000 0.000000 +39.700001 0.000000 0.000000 +39.700001 2.900000 0.120000 +39.700001 0.000000 0.120000 +39.700001 0.000000 0.000000 +39.700001 2.900000 0.000000 +0.000000 2.900000 0.120000 +39.700001 2.900000 0.120000 +39.700001 2.900000 0.000000 +0.000000 2.900000 0.000000 +0.000000 2.900000 0.120000 +1.524574 0.571167 0.120000 +1.505843 0.636313 0.120000 +1.500000 0.700000 0.120000 +1.505843 0.763687 0.120000 +1.524574 0.828833 0.120000 +1.557052 0.891523 0.120000 +2.602513 1.202513 0.120000 +3.142948 1.258477 0.120000 +4.602513 1.202513 0.120000 +5.142949 1.258477 0.120000 +6.602513 1.202513 0.120000 +7.142949 1.258477 0.120000 +8.602512 1.202513 0.120000 +9.142948 1.258477 0.120000 +10.602512 1.202513 0.120000 +11.602512 1.952513 0.120000 +12.142948 2.008476 0.120000 +12.097487 0.947487 0.120000 +12.602512 1.202513 0.120000 +13.142948 1.258477 0.120000 +14.602512 1.202513 0.120000 +15.142948 1.258477 0.120000 +15.557052 0.891523 0.120000 +15.602512 1.952513 0.120000 +16.142948 2.008476 0.120000 +17.142948 1.258477 0.120000 +18.602512 1.202513 0.120000 +19.142948 1.258477 0.120000 +20.602512 1.202513 0.120000 +21.142948 1.258477 0.120000 +22.602512 1.202513 0.120000 +23.142948 1.258477 0.120000 +24.602512 1.202513 0.120000 +25.142948 1.258477 0.120000 +26.602512 1.202513 0.120000 +27.142948 1.258477 0.120000 +27.557051 0.891523 0.120000 +27.602512 1.952513 0.120000 +28.142948 2.008476 0.120000 +29.142948 1.258477 0.120000 +30.602512 1.202513 0.120000 +31.602512 1.952513 0.120000 +32.142948 2.008476 0.120000 +32.097488 0.947487 0.120000 +32.602512 1.202513 0.120000 +33.142948 1.258477 0.120000 +34.602512 1.202513 0.120000 +35.602512 1.952513 0.120000 +36.142948 2.008476 0.120000 +36.097488 0.947487 0.120000 +36.602512 1.202513 0.120000 +37.142948 1.258477 0.120000 +37.557053 0.891523 0.120000 +37.602512 1.952513 0.120000 +37.097488 1.697487 0.120000 +36.557053 1.641523 0.120000 +35.097488 1.697487 0.120000 +34.557053 1.641523 0.120000 +34.142948 2.008476 0.120000 +34.097488 0.947487 0.120000 +33.557053 0.891523 0.120000 +32.557053 1.641523 0.120000 +31.097486 1.697487 0.120000 +30.097486 0.947487 0.120000 +29.557051 0.891523 0.120000 +29.602512 1.952513 0.120000 +29.097486 1.697487 0.120000 +28.557051 1.641523 0.120000 +27.097486 1.697487 0.120000 +26.557051 1.641523 0.120000 +26.142948 2.008476 0.120000 +26.097486 0.947487 0.120000 +25.557051 0.891523 0.120000 +24.097486 0.947487 0.120000 +23.557051 0.891523 0.120000 +23.602512 1.952513 0.120000 +23.097486 1.697487 0.120000 +22.557051 1.641523 0.120000 +22.142948 2.008476 0.120000 +22.097486 0.947487 0.120000 +21.557051 0.891523 0.120000 +20.097486 0.947487 0.120000 +19.557051 0.891523 0.120000 +19.602512 1.952513 0.120000 +19.097486 1.697487 0.120000 +18.557051 1.641523 0.120000 +18.142948 2.008476 0.120000 +18.097486 0.947487 0.120000 +17.557051 0.891523 0.120000 +16.557051 1.641523 0.120000 +15.097487 1.697487 0.120000 +14.557052 1.641523 0.120000 +14.142948 2.008476 0.120000 +14.097487 0.947487 0.120000 +13.557052 0.891523 0.120000 +12.557052 1.641523 0.120000 +11.097487 1.697487 0.120000 +10.557052 1.641523 0.120000 +10.142948 2.008476 0.120000 +10.097487 0.947487 0.120000 +9.557052 0.891523 0.120000 +8.557052 1.641523 0.120000 +8.142948 2.008476 0.120000 +8.097487 0.947487 0.120000 +7.557052 0.891523 0.120000 +6.557052 1.641523 0.120000 +6.142949 2.008476 0.120000 +6.097487 0.947487 0.120000 +5.557052 0.891523 0.120000 +4.097487 0.947487 0.120000 +3.557052 0.891523 0.120000 +3.602513 1.952513 0.120000 +3.097487 1.697487 0.120000 +2.557052 1.641523 0.120000 +2.142948 2.008476 0.120000 +2.097487 0.947487 0.120000 +1.602513 0.947487 0.120000 +2.142948 0.891523 0.120000 +3.524574 0.828833 0.120000 +4.142949 0.891523 0.120000 +5.524574 0.828833 0.120000 +6.142949 0.891523 0.120000 +7.524574 0.828833 0.120000 +8.142948 0.891523 0.120000 +9.524574 0.828833 0.120000 +10.142948 0.891523 0.120000 +11.142948 1.641523 0.120000 +12.524574 1.578833 0.120000 +12.557052 1.258477 0.120000 +12.142948 0.891523 0.120000 +13.524574 0.828833 0.120000 +14.142948 0.891523 0.120000 +15.524574 0.828833 0.120000 +15.175426 1.321167 0.120000 +15.142948 1.641523 0.120000 +16.524574 1.578833 0.120000 +17.524574 0.828833 0.120000 +18.142948 0.891523 0.120000 +19.524574 0.828833 0.120000 +20.142948 0.891523 0.120000 +21.524574 0.828833 0.120000 +22.142948 0.891523 0.120000 +23.524574 0.828833 0.120000 +24.142948 0.891523 0.120000 +25.524574 0.828833 0.120000 +26.142948 0.891523 0.120000 +27.524574 0.828833 0.120000 +27.175426 1.321167 0.120000 +27.142948 1.641523 0.120000 +28.524574 1.578833 0.120000 +29.524574 0.828833 0.120000 +30.142948 0.891523 0.120000 +31.142948 1.641523 0.120000 +32.524574 1.578833 0.120000 +32.557053 1.258477 0.120000 +32.142948 0.891523 0.120000 +33.524574 0.828833 0.120000 +34.142948 0.891523 0.120000 +35.142948 1.641523 0.120000 +36.524574 1.578833 0.120000 +36.557053 1.258477 0.120000 +36.142948 0.891523 0.120000 +37.524574 0.828833 0.120000 +37.175426 1.321167 0.120000 +37.142948 1.641523 0.120000 +37.557053 2.008476 0.120000 +36.175426 2.071167 0.120000 +35.557053 2.008476 0.120000 +34.175426 2.071167 0.120000 +34.524574 1.578833 0.120000 +34.557053 1.258477 0.120000 +33.175426 1.321167 0.120000 +32.175426 2.071167 0.120000 +31.557051 2.008476 0.120000 +30.557051 1.258477 0.120000 +29.175426 1.321167 0.120000 +29.142948 1.641523 0.120000 +29.557051 2.008476 0.120000 +28.175426 2.071167 0.120000 +27.557051 2.008476 0.120000 +26.175426 2.071167 0.120000 +26.524574 1.578833 0.120000 +26.557051 1.258477 0.120000 +25.175426 1.321167 0.120000 +24.557051 1.258477 0.120000 +23.175426 1.321167 0.120000 +23.142948 1.641523 0.120000 +23.557051 2.008476 0.120000 +22.175426 2.071167 0.120000 +22.524574 1.578833 0.120000 +22.557051 1.258477 0.120000 +21.175426 1.321167 0.120000 +20.557051 1.258477 0.120000 +19.175426 1.321167 0.120000 +19.142948 1.641523 0.120000 +19.557051 2.008476 0.120000 +18.175426 2.071167 0.120000 +18.524574 1.578833 0.120000 +18.557051 1.258477 0.120000 +17.175426 1.321167 0.120000 +16.175426 2.071167 0.120000 +15.557052 2.008476 0.120000 +14.175426 2.071167 0.120000 +14.524574 1.578833 0.120000 +14.557052 1.258477 0.120000 +13.175426 1.321167 0.120000 +12.175426 2.071167 0.120000 +11.557052 2.008476 0.120000 +10.175426 2.071167 0.120000 +10.524574 1.578833 0.120000 +10.557052 1.258477 0.120000 +9.175426 1.321167 0.120000 +8.175426 2.071167 0.120000 +8.524574 1.578833 0.120000 +8.557052 1.258477 0.120000 +7.175426 1.321167 0.120000 +6.175426 2.071167 0.120000 +6.524574 1.578833 0.120000 +6.557052 1.258477 0.120000 +5.175426 1.321167 0.120000 +4.557052 1.258477 0.120000 +3.175426 1.321167 0.120000 +3.142948 1.641523 0.120000 +3.557052 2.008476 0.120000 +2.175426 2.071167 0.120000 +2.524574 1.578833 0.120000 +2.557052 1.258477 0.120000 +1.557052 0.508477 0.120000 +2.658477 1.157052 0.120000 +3.097487 1.202513 0.120000 +4.658476 1.157052 0.120000 +5.097487 1.202513 0.120000 +6.658476 1.157052 0.120000 +7.097487 1.202513 0.120000 +8.658477 1.157052 0.120000 +9.097487 1.202513 0.120000 +10.658477 1.157052 0.120000 +11.658477 1.907052 0.120000 +12.097487 1.952513 0.120000 +12.041523 0.992948 0.120000 +12.658477 1.157052 0.120000 +13.097487 1.202513 0.120000 +14.658477 1.157052 0.120000 +15.097487 1.202513 0.120000 +15.602512 0.947487 0.120000 +15.658477 1.907052 0.120000 +16.097486 1.952513 0.120000 +17.097486 1.202513 0.120000 +18.658476 1.157052 0.120000 +19.097486 1.202513 0.120000 +20.658476 1.157052 0.120000 +21.097486 1.202513 0.120000 +22.658476 1.157052 0.120000 +23.097486 1.202513 0.120000 +24.658476 1.157052 0.120000 +25.097486 1.202513 0.120000 +26.658476 1.157052 0.120000 +27.097486 1.202513 0.120000 +27.602512 0.947487 0.120000 +27.658476 1.907052 0.120000 +28.097486 1.952513 0.120000 +29.097486 1.202513 0.120000 +30.658476 1.157052 0.120000 +31.658476 1.907052 0.120000 +32.097488 1.952513 0.120000 +32.041523 0.992948 0.120000 +32.658478 1.157052 0.120000 +33.097488 1.202513 0.120000 +34.658478 1.157052 0.120000 +35.658478 1.907052 0.120000 +36.097488 1.952513 0.120000 +36.041523 0.992948 0.120000 +36.658478 1.157052 0.120000 +37.097488 1.202513 0.120000 +37.602512 0.947487 0.120000 +37.658478 1.907052 0.120000 +37.041523 1.742948 0.120000 +36.602512 1.697487 0.120000 +35.041523 1.742948 0.120000 +34.602512 1.697487 0.120000 +34.097488 1.952513 0.120000 +34.041523 0.992948 0.120000 +33.602512 0.947487 0.120000 +32.602512 1.697487 0.120000 +31.041523 1.742948 0.120000 +30.041523 0.992948 0.120000 +29.602512 0.947487 0.120000 +29.658476 1.907052 0.120000 +29.041523 1.742948 0.120000 +28.602512 1.697487 0.120000 +27.041523 1.742948 0.120000 +26.602512 1.697487 0.120000 +26.097486 1.952513 0.120000 +26.041523 0.992948 0.120000 +25.602512 0.947487 0.120000 +24.041523 0.992948 0.120000 +23.602512 0.947487 0.120000 +23.658476 1.907052 0.120000 +23.041523 1.742948 0.120000 +22.602512 1.697487 0.120000 +22.097486 1.952513 0.120000 +22.041523 0.992948 0.120000 +21.602512 0.947487 0.120000 +20.041523 0.992948 0.120000 +19.602512 0.947487 0.120000 +19.658476 1.907052 0.120000 +19.041523 1.742948 0.120000 +18.602512 1.697487 0.120000 +18.097486 1.952513 0.120000 +18.041523 0.992948 0.120000 +17.602512 0.947487 0.120000 +16.602512 1.697487 0.120000 +15.041523 1.742948 0.120000 +14.602512 1.697487 0.120000 +14.097487 1.952513 0.120000 +14.041523 0.992948 0.120000 +13.602512 0.947487 0.120000 +12.602512 1.697487 0.120000 +11.041523 1.742948 0.120000 +10.602512 1.697487 0.120000 +10.097487 1.952513 0.120000 +10.041523 0.992948 0.120000 +9.602512 0.947487 0.120000 +8.602512 1.697487 0.120000 +8.097487 1.952513 0.120000 +8.041523 0.992948 0.120000 +7.602513 0.947487 0.120000 +6.602513 1.697487 0.120000 +6.097487 1.952513 0.120000 +6.041523 0.992948 0.120000 +5.602513 0.947487 0.120000 +4.041523 0.992948 0.120000 +3.602513 0.947487 0.120000 +3.658477 1.907052 0.120000 +3.041523 1.742948 0.120000 +2.602513 1.697487 0.120000 +2.097487 1.952513 0.120000 +2.041523 0.992948 0.120000 +1.658477 0.992948 0.120000 +2.175426 0.828833 0.120000 +3.505843 0.763687 0.120000 +4.175426 0.828833 0.120000 +5.505843 0.763687 0.120000 +6.175426 0.828833 0.120000 +7.505843 0.763687 0.120000 +8.175426 0.828833 0.120000 +9.505843 0.763687 0.120000 +10.175426 0.828833 0.120000 +11.175426 1.578833 0.120000 +12.505843 1.513687 0.120000 +12.524574 1.321167 0.120000 +12.175426 0.828833 0.120000 +13.505843 0.763687 0.120000 +14.175426 0.828833 0.120000 +15.505843 0.763687 0.120000 +15.194157 1.386313 0.120000 +15.175426 1.578833 0.120000 +16.505842 1.513687 0.120000 +17.505842 0.763687 0.120000 +18.175426 0.828833 0.120000 +19.505842 0.763687 0.120000 +20.175426 0.828833 0.120000 +21.505842 0.763687 0.120000 +22.175426 0.828833 0.120000 +23.505842 0.763687 0.120000 +24.175426 0.828833 0.120000 +25.505842 0.763687 0.120000 +26.175426 0.828833 0.120000 +27.505842 0.763687 0.120000 +27.194157 1.386313 0.120000 +27.175426 1.578833 0.120000 +28.505842 1.513687 0.120000 +29.505842 0.763687 0.120000 +30.175426 0.828833 0.120000 +31.175426 1.578833 0.120000 +32.505844 1.513687 0.120000 +32.524574 1.321167 0.120000 +32.175426 0.828833 0.120000 +33.505844 0.763687 0.120000 +34.175426 0.828833 0.120000 +35.175426 1.578833 0.120000 +36.505844 1.513687 0.120000 +36.524574 1.321167 0.120000 +36.175426 0.828833 0.120000 +37.505844 0.763687 0.120000 +37.194157 1.386313 0.120000 +37.175426 1.578833 0.120000 +37.524574 2.071167 0.120000 +36.194157 2.136313 0.120000 +35.524574 2.071167 0.120000 +34.194157 2.136313 0.120000 +34.505844 1.513687 0.120000 +34.524574 1.321167 0.120000 +33.194157 1.386313 0.120000 +32.194157 2.136313 0.120000 +31.524574 2.071167 0.120000 +30.524574 1.321167 0.120000 +29.194157 1.386313 0.120000 +29.175426 1.578833 0.120000 +29.524574 2.071167 0.120000 +28.194157 2.136313 0.120000 +27.524574 2.071167 0.120000 +26.194157 2.136313 0.120000 +26.505842 1.513687 0.120000 +26.524574 1.321167 0.120000 +25.194157 1.386313 0.120000 +24.524574 1.321167 0.120000 +23.194157 1.386313 0.120000 +23.175426 1.578833 0.120000 +23.524574 2.071167 0.120000 +22.194157 2.136313 0.120000 +22.505842 1.513687 0.120000 +22.524574 1.321167 0.120000 +21.194157 1.386313 0.120000 +20.524574 1.321167 0.120000 +19.194157 1.386313 0.120000 +19.175426 1.578833 0.120000 +19.524574 2.071167 0.120000 +18.194157 2.136313 0.120000 +18.505842 1.513687 0.120000 +18.524574 1.321167 0.120000 +17.194157 1.386313 0.120000 +16.194157 2.136313 0.120000 +15.524574 2.071167 0.120000 +14.194157 2.136313 0.120000 +14.505843 1.513687 0.120000 +14.524574 1.321167 0.120000 +13.194157 1.386313 0.120000 +12.194157 2.136313 0.120000 +11.524574 2.071167 0.120000 +10.194157 2.136313 0.120000 +10.505843 1.513687 0.120000 +10.524574 1.321167 0.120000 +9.194157 1.386313 0.120000 +8.194157 2.136313 0.120000 +8.505843 1.513687 0.120000 +8.524574 1.321167 0.120000 +7.194157 1.386313 0.120000 +6.194157 2.136313 0.120000 +6.505843 1.513687 0.120000 +6.524574 1.321167 0.120000 +5.194157 1.386313 0.120000 +4.524574 1.321167 0.120000 +3.194157 1.386313 0.120000 +3.175426 1.578833 0.120000 +3.524574 2.071167 0.120000 +2.194157 2.136313 0.120000 +2.505843 1.513687 0.120000 +2.524574 1.321167 0.120000 +1.602513 0.452513 0.120000 +2.721167 1.124574 0.120000 +3.041523 1.157052 0.120000 +4.721167 1.124574 0.120000 +5.041523 1.157052 0.120000 +6.721167 1.124574 0.120000 +7.041523 1.157052 0.120000 +8.721167 1.124574 0.120000 +9.041523 1.157052 0.120000 +10.721167 1.124574 0.120000 +11.721167 1.874574 0.120000 +12.041523 1.907052 0.120000 +11.978833 1.025426 0.120000 +12.721167 1.124574 0.120000 +13.041523 1.157052 0.120000 +14.721167 1.124574 0.120000 +15.041523 1.157052 0.120000 +15.658477 0.992948 0.120000 +15.721167 1.874574 0.120000 +16.041523 1.907052 0.120000 +17.041523 1.157052 0.120000 +18.721167 1.124574 0.120000 +19.041523 1.157052 0.120000 +20.721167 1.124574 0.120000 +21.041523 1.157052 0.120000 +22.721167 1.124574 0.120000 +23.041523 1.157052 0.120000 +24.721167 1.124574 0.120000 +25.041523 1.157052 0.120000 +26.721167 1.124574 0.120000 +27.041523 1.157052 0.120000 +27.658476 0.992948 0.120000 +27.721167 1.874574 0.120000 +28.041523 1.907052 0.120000 +29.041523 1.157052 0.120000 +30.721167 1.124574 0.120000 +31.721167 1.874574 0.120000 +32.041523 1.907052 0.120000 +31.978832 1.025426 0.120000 +32.721169 1.124574 0.120000 +33.041523 1.157052 0.120000 +34.721169 1.124574 0.120000 +35.721169 1.874574 0.120000 +36.041523 1.907052 0.120000 +35.978832 1.025426 0.120000 +36.721169 1.124574 0.120000 +37.041523 1.157052 0.120000 +37.658478 0.992948 0.120000 +37.721169 1.874574 0.120000 +36.978832 1.775426 0.120000 +36.658478 1.742948 0.120000 +34.978832 1.775426 0.120000 +34.658478 1.742948 0.120000 +34.041523 1.907052 0.120000 +33.978832 1.025426 0.120000 +33.658478 0.992948 0.120000 +32.658478 1.742948 0.120000 +30.978832 1.775426 0.120000 +29.978832 1.025426 0.120000 +29.658476 0.992948 0.120000 +29.721167 1.874574 0.120000 +28.978832 1.775426 0.120000 +28.658476 1.742948 0.120000 +26.978832 1.775426 0.120000 +26.658476 1.742948 0.120000 +26.041523 1.907052 0.120000 +25.978832 1.025426 0.120000 +25.658476 0.992948 0.120000 +23.978832 1.025426 0.120000 +23.658476 0.992948 0.120000 +23.721167 1.874574 0.120000 +22.978832 1.775426 0.120000 +22.658476 1.742948 0.120000 +22.041523 1.907052 0.120000 +21.978832 1.025426 0.120000 +21.658476 0.992948 0.120000 +19.978832 1.025426 0.120000 +19.658476 0.992948 0.120000 +19.721167 1.874574 0.120000 +18.978832 1.775426 0.120000 +18.658476 1.742948 0.120000 +18.041523 1.907052 0.120000 +17.978832 1.025426 0.120000 +17.658476 0.992948 0.120000 +16.658476 1.742948 0.120000 +14.978833 1.775426 0.120000 +14.658477 1.742948 0.120000 +14.041523 1.907052 0.120000 +13.978833 1.025426 0.120000 +13.658477 0.992948 0.120000 +12.658477 1.742948 0.120000 +10.978833 1.775426 0.120000 +10.658477 1.742948 0.120000 +10.041523 1.907052 0.120000 +9.978833 1.025426 0.120000 +9.658477 0.992948 0.120000 +8.658477 1.742948 0.120000 +8.041523 1.907052 0.120000 +7.978833 1.025426 0.120000 +7.658476 0.992948 0.120000 +6.658476 1.742948 0.120000 +6.041523 1.907052 0.120000 +5.978833 1.025426 0.120000 +5.658476 0.992948 0.120000 +3.978833 1.025426 0.120000 +3.658477 0.992948 0.120000 +3.721167 1.874574 0.120000 +2.978833 1.775426 0.120000 +2.658477 1.742948 0.120000 +2.041523 1.907052 0.120000 +1.978833 1.025426 0.120000 +1.721167 1.025426 0.120000 +2.194157 0.763687 0.120000 +3.500000 0.700000 0.120000 +4.194157 0.763687 0.120000 +5.500000 0.700000 0.120000 +6.194157 0.763687 0.120000 +7.500000 0.700000 0.120000 +8.194157 0.763687 0.120000 +9.500000 0.700000 0.120000 +10.194157 0.763687 0.120000 +11.194157 1.513687 0.120000 +12.500000 1.450000 0.120000 +12.505843 1.386313 0.120000 +11.978833 1.874574 0.120000 +11.913687 1.044157 0.120000 +11.913687 1.855843 0.120000 +11.850000 1.050000 0.120000 +11.850000 1.850000 0.120000 +11.786313 1.044157 0.120000 +11.786313 1.855843 0.120000 +11.721167 1.025426 0.120000 +11.200000 1.450000 0.120000 +11.658477 0.992948 0.120000 +11.194157 1.386313 0.120000 +11.602512 0.947487 0.120000 +11.175426 1.321167 0.120000 +11.557052 0.891523 0.120000 +11.142948 1.258477 0.120000 +11.524574 0.828833 0.120000 +11.097487 1.202513 0.120000 +11.505843 0.763687 0.120000 +11.041523 1.157052 0.120000 +12.194157 0.763687 0.120000 +13.500000 0.700000 0.120000 +14.194157 0.763687 0.120000 +15.500000 0.700000 0.120000 +15.200000 1.450000 0.120000 +15.194157 1.513687 0.120000 +15.721167 1.025426 0.120000 +15.786313 1.855843 0.120000 +15.786313 1.044157 0.120000 +15.850000 1.850000 0.120000 +15.850000 1.050000 0.120000 +15.913687 1.855843 0.120000 +15.913687 1.044157 0.120000 +15.978833 1.874574 0.120000 +16.500000 1.450000 0.120000 +16.505842 1.386313 0.120000 +15.978833 1.025426 0.120000 +16.524574 1.321167 0.120000 +16.041523 0.992948 0.120000 +16.557051 1.258477 0.120000 +16.097486 0.947487 0.120000 +16.602512 1.202513 0.120000 +16.142948 0.891523 0.120000 +16.658476 1.157052 0.120000 +16.175426 0.828833 0.120000 +16.721167 1.124574 0.120000 +17.500000 0.700000 0.120000 +11.500000 0.700000 0.120000 +16.194157 0.763687 0.120000 +18.194157 0.763687 0.120000 +19.500000 0.700000 0.120000 +20.194157 0.763687 0.120000 +21.500000 0.700000 0.120000 +22.194157 0.763687 0.120000 +23.500000 0.700000 0.120000 +24.194157 0.763687 0.120000 +25.500000 0.700000 0.120000 +26.194157 0.763687 0.120000 +27.500000 0.700000 0.120000 +27.200001 1.450000 0.120000 +27.194157 1.513687 0.120000 +27.721167 1.025426 0.120000 +27.786312 1.855843 0.120000 +27.786312 1.044157 0.120000 +27.850000 1.850000 0.120000 +27.850000 1.050000 0.120000 +27.913687 1.855843 0.120000 +27.913687 1.044157 0.120000 +27.978832 1.874574 0.120000 +28.500000 1.450000 0.120000 +28.505842 1.386313 0.120000 +27.978832 1.025426 0.120000 +28.524574 1.321167 0.120000 +28.041523 0.992948 0.120000 +28.557051 1.258477 0.120000 +28.097486 0.947487 0.120000 +28.602512 1.202513 0.120000 +28.142948 0.891523 0.120000 +28.658476 1.157052 0.120000 +28.175426 0.828833 0.120000 +28.721167 1.124574 0.120000 +29.500000 0.700000 0.120000 +30.194157 0.763687 0.120000 +31.194157 1.513687 0.120000 +32.500000 1.450000 0.120000 +32.505844 1.386313 0.120000 +31.978832 1.874574 0.120000 +31.913687 1.044157 0.120000 +31.913687 1.855843 0.120000 +31.850000 1.050000 0.120000 +31.850000 1.850000 0.120000 +31.786312 1.044157 0.120000 +31.786312 1.855843 0.120000 +31.721167 1.025426 0.120000 +31.200001 1.450000 0.120000 +31.658476 0.992948 0.120000 +31.194157 1.386313 0.120000 +31.602512 0.947487 0.120000 +31.175426 1.321167 0.120000 +31.557051 0.891523 0.120000 +31.142948 1.258477 0.120000 +31.524574 0.828833 0.120000 +31.097486 1.202513 0.120000 +31.505842 0.763687 0.120000 +31.041523 1.157052 0.120000 +28.194157 0.763687 0.120000 +31.500000 0.700000 0.120000 +32.194157 0.763687 0.120000 +33.500000 0.700000 0.120000 +34.194157 0.763687 0.120000 +35.194157 1.513687 0.120000 +36.500000 1.450000 0.120000 +36.505844 1.386313 0.120000 +35.978832 1.874574 0.120000 +35.913689 1.044157 0.120000 +35.913689 1.855843 0.120000 +35.849998 1.050000 0.120000 +35.849998 1.850000 0.120000 +35.786312 1.044157 0.120000 +35.786312 1.855843 0.120000 +35.721169 1.025426 0.120000 +35.200001 1.450000 0.120000 +35.658478 0.992948 0.120000 +35.194157 1.386313 0.120000 +35.602512 0.947487 0.120000 +35.175426 1.321167 0.120000 +35.557053 0.891523 0.120000 +35.142948 1.258477 0.120000 +35.524574 0.828833 0.120000 +35.097488 1.202513 0.120000 +35.505844 0.763687 0.120000 +35.041523 1.157052 0.120000 +36.194157 0.763687 0.120000 +37.500000 0.700000 0.120000 +35.500000 0.700000 0.120000 +37.200001 1.450000 0.120000 +37.194157 1.513687 0.120000 +37.721169 1.025426 0.120000 +37.786312 1.855843 0.120000 +37.786312 1.044157 0.120000 +37.849998 1.850000 0.120000 +37.849998 1.050000 0.120000 +37.913689 1.855843 0.120000 +37.913689 1.044157 0.120000 +37.978832 1.874574 0.120000 +37.978832 1.025426 0.120000 +38.041523 1.907052 0.120000 +37.505844 2.136313 0.120000 +36.200001 2.200000 0.120000 +35.505844 2.136313 0.120000 +34.200001 2.200000 0.120000 +34.500000 1.450000 0.120000 +34.505844 1.386313 0.120000 +33.978832 1.874574 0.120000 +33.913689 1.044157 0.120000 +33.913689 1.855843 0.120000 +33.849998 1.050000 0.120000 +33.849998 1.850000 0.120000 +33.786312 1.044157 0.120000 +33.786312 1.855843 0.120000 +33.721169 1.025426 0.120000 +33.200001 1.450000 0.120000 +33.194157 1.513687 0.120000 +33.721169 1.874574 0.120000 +33.175426 1.578833 0.120000 +33.658478 1.907052 0.120000 +33.142948 1.641523 0.120000 +33.602512 1.952513 0.120000 +33.097488 1.697487 0.120000 +33.557053 2.008476 0.120000 +33.041523 1.742948 0.120000 +33.524574 2.071167 0.120000 +32.978832 1.775426 0.120000 +33.505844 2.136313 0.120000 +32.200001 2.200000 0.120000 +31.505842 2.136313 0.120000 +30.505842 1.386313 0.120000 +29.200001 1.450000 0.120000 +29.194157 1.513687 0.120000 +29.721167 1.025426 0.120000 +29.786312 1.855843 0.120000 +29.786312 1.044157 0.120000 +29.850000 1.850000 0.120000 +29.850000 1.050000 0.120000 +29.913687 1.855843 0.120000 +29.913687 1.044157 0.120000 +29.978832 1.874574 0.120000 +30.500000 1.450000 0.120000 +30.041523 1.907052 0.120000 +30.505842 1.513687 0.120000 +30.097486 1.952513 0.120000 +30.524574 1.578833 0.120000 +30.142948 2.008476 0.120000 +30.557051 1.641523 0.120000 +30.175426 2.071167 0.120000 +30.602512 1.697487 0.120000 +30.194157 2.136313 0.120000 +30.658476 1.742948 0.120000 +29.505842 2.136313 0.120000 +28.200001 2.200000 0.120000 +27.505842 2.136313 0.120000 +26.200001 2.200000 0.120000 +30.200001 2.200000 0.120000 +26.500000 1.450000 0.120000 +26.505842 1.386313 0.120000 +25.978832 1.874574 0.120000 +25.913687 1.044157 0.120000 +25.913687 1.855843 0.120000 +25.850000 1.050000 0.120000 +25.850000 1.850000 0.120000 +25.786312 1.044157 0.120000 +25.786312 1.855843 0.120000 +25.721167 1.025426 0.120000 +25.200001 1.450000 0.120000 +25.194157 1.513687 0.120000 +25.721167 1.874574 0.120000 +25.175426 1.578833 0.120000 +25.658476 1.907052 0.120000 +25.142948 1.641523 0.120000 +25.602512 1.952513 0.120000 +25.097486 1.697487 0.120000 +25.557051 2.008476 0.120000 +25.041523 1.742948 0.120000 +25.524574 2.071167 0.120000 +24.978832 1.775426 0.120000 +24.505842 1.386313 0.120000 +23.200001 1.450000 0.120000 +23.194157 1.513687 0.120000 +23.721167 1.025426 0.120000 +23.786312 1.855843 0.120000 +23.786312 1.044157 0.120000 +23.850000 1.850000 0.120000 +23.850000 1.050000 0.120000 +23.913687 1.855843 0.120000 +23.913687 1.044157 0.120000 +23.978832 1.874574 0.120000 +24.500000 1.450000 0.120000 +24.041523 1.907052 0.120000 +24.505842 1.513687 0.120000 +24.097486 1.952513 0.120000 +24.524574 1.578833 0.120000 +24.142948 2.008476 0.120000 +24.557051 1.641523 0.120000 +24.175426 2.071167 0.120000 +24.602512 1.697487 0.120000 +24.194157 2.136313 0.120000 +24.658476 1.742948 0.120000 +23.505842 2.136313 0.120000 +22.200001 2.200000 0.120000 +22.500000 1.450000 0.120000 +25.505842 2.136313 0.120000 +24.200001 2.200000 0.120000 +22.505842 1.386313 0.120000 +21.978832 1.874574 0.120000 +21.913687 1.044157 0.120000 +21.913687 1.855843 0.120000 +21.850000 1.050000 0.120000 +21.850000 1.850000 0.120000 +21.786312 1.044157 0.120000 +21.786312 1.855843 0.120000 +21.721167 1.025426 0.120000 +21.200001 1.450000 0.120000 +21.194157 1.513687 0.120000 +21.721167 1.874574 0.120000 +21.175426 1.578833 0.120000 +21.658476 1.907052 0.120000 +21.142948 1.641523 0.120000 +21.602512 1.952513 0.120000 +21.097486 1.697487 0.120000 +21.557051 2.008476 0.120000 +21.041523 1.742948 0.120000 +21.524574 2.071167 0.120000 +20.978832 1.775426 0.120000 +20.505842 1.386313 0.120000 +19.200001 1.450000 0.120000 +19.194157 1.513687 0.120000 +19.721167 1.025426 0.120000 +19.786312 1.855843 0.120000 +19.786312 1.044157 0.120000 +19.850000 1.850000 0.120000 +19.850000 1.050000 0.120000 +19.913687 1.855843 0.120000 +19.913687 1.044157 0.120000 +19.978832 1.874574 0.120000 +20.500000 1.450000 0.120000 +20.041523 1.907052 0.120000 +20.505842 1.513687 0.120000 +20.097486 1.952513 0.120000 +20.524574 1.578833 0.120000 +20.142948 2.008476 0.120000 +20.557051 1.641523 0.120000 +20.175426 2.071167 0.120000 +20.602512 1.697487 0.120000 +20.194157 2.136313 0.120000 +20.658476 1.742948 0.120000 +19.505842 2.136313 0.120000 +18.200001 2.200000 0.120000 +18.500000 1.450000 0.120000 +21.505842 2.136313 0.120000 +20.200001 2.200000 0.120000 +18.505842 1.386313 0.120000 +17.978832 1.874574 0.120000 +17.913687 1.044157 0.120000 +17.913687 1.855843 0.120000 +17.850000 1.050000 0.120000 +17.850000 1.850000 0.120000 +17.786312 1.044157 0.120000 +17.786312 1.855843 0.120000 +17.721167 1.025426 0.120000 +17.200001 1.450000 0.120000 +17.194157 1.513687 0.120000 +17.721167 1.874574 0.120000 +17.175426 1.578833 0.120000 +17.658476 1.907052 0.120000 +17.142948 1.641523 0.120000 +17.602512 1.952513 0.120000 +17.097486 1.697487 0.120000 +17.557051 2.008476 0.120000 +17.041523 1.742948 0.120000 +17.524574 2.071167 0.120000 +16.978832 1.775426 0.120000 +16.200001 2.200000 0.120000 +15.505843 2.136313 0.120000 +14.200000 2.200000 0.120000 +14.500000 1.450000 0.120000 +14.505843 1.386313 0.120000 +13.978833 1.874574 0.120000 +13.913687 1.044157 0.120000 +13.913687 1.855843 0.120000 +13.850000 1.050000 0.120000 +13.850000 1.850000 0.120000 +13.786313 1.044157 0.120000 +13.786313 1.855843 0.120000 +13.721167 1.025426 0.120000 +13.200000 1.450000 0.120000 +13.194157 1.513687 0.120000 +13.721167 1.874574 0.120000 +13.175426 1.578833 0.120000 +13.658477 1.907052 0.120000 +13.142948 1.641523 0.120000 +13.602512 1.952513 0.120000 +13.097487 1.697487 0.120000 +13.557052 2.008476 0.120000 +13.041523 1.742948 0.120000 +13.524574 2.071167 0.120000 +12.978833 1.775426 0.120000 +17.505842 2.136313 0.120000 +13.505843 2.136313 0.120000 +12.200000 2.200000 0.120000 +11.505843 2.136313 0.120000 +10.200000 2.200000 0.120000 +10.500000 1.450000 0.120000 +10.505843 1.386313 0.120000 +9.978833 1.874574 0.120000 +9.913687 1.044157 0.120000 +9.913687 1.855843 0.120000 +9.850000 1.050000 0.120000 +9.850000 1.850000 0.120000 +9.786313 1.044157 0.120000 +9.786313 1.855843 0.120000 +9.721167 1.025426 0.120000 +9.200000 1.450000 0.120000 +9.194157 1.513687 0.120000 +9.721167 1.874574 0.120000 +9.175426 1.578833 0.120000 +9.658477 1.907052 0.120000 +9.142948 1.641523 0.120000 +9.602512 1.952513 0.120000 +9.097487 1.697487 0.120000 +9.557052 2.008476 0.120000 +9.041523 1.742948 0.120000 +9.524574 2.071167 0.120000 +8.978833 1.775426 0.120000 +8.200000 2.200000 0.120000 +8.500000 1.450000 0.120000 +9.505843 2.136313 0.120000 +8.505843 1.386313 0.120000 +7.978833 1.874574 0.120000 +7.913687 1.044157 0.120000 +7.913687 1.855843 0.120000 +7.850000 1.050000 0.120000 +7.850000 1.850000 0.120000 +7.786313 1.044157 0.120000 +7.786313 1.855843 0.120000 +7.721167 1.025426 0.120000 +7.200000 1.450000 0.120000 +7.194157 1.513687 0.120000 +7.721167 1.874574 0.120000 +7.175426 1.578833 0.120000 +7.658476 1.907052 0.120000 +7.142949 1.641523 0.120000 +7.602513 1.952513 0.120000 +7.097487 1.697487 0.120000 +7.557052 2.008476 0.120000 +7.041523 1.742948 0.120000 +7.524574 2.071167 0.120000 +6.978833 1.775426 0.120000 +6.200000 2.200000 0.120000 +6.500000 1.450000 0.120000 +6.505843 1.386313 0.120000 +5.978833 1.874574 0.120000 +5.913687 1.044157 0.120000 +5.913687 1.855843 0.120000 +5.850000 1.050000 0.120000 +5.850000 1.850000 0.120000 +5.786313 1.044157 0.120000 +5.786313 1.855843 0.120000 +5.721167 1.025426 0.120000 +5.200000 1.450000 0.120000 +5.194157 1.513687 0.120000 +5.721167 1.874574 0.120000 +5.175426 1.578833 0.120000 +5.658476 1.907052 0.120000 +5.142949 1.641523 0.120000 +5.602513 1.952513 0.120000 +5.097487 1.697487 0.120000 +5.557052 2.008476 0.120000 +5.041523 1.742948 0.120000 +5.524574 2.071167 0.120000 +4.978833 1.775426 0.120000 +4.505843 1.386313 0.120000 +3.200000 1.450000 0.120000 +3.194157 1.513687 0.120000 +3.721167 1.025426 0.120000 +3.786313 1.855843 0.120000 +3.786313 1.044157 0.120000 +3.850000 1.850000 0.120000 +3.850000 1.050000 0.120000 +3.913687 1.855843 0.120000 +3.913687 1.044157 0.120000 +3.978833 1.874574 0.120000 +4.500000 1.450000 0.120000 +4.041523 1.907052 0.120000 +4.505843 1.513687 0.120000 +4.097487 1.952513 0.120000 +4.524574 1.578833 0.120000 +4.142949 2.008476 0.120000 +4.557052 1.641523 0.120000 +4.175426 2.071167 0.120000 +4.602513 1.697487 0.120000 +4.194157 2.136313 0.120000 +4.658476 1.742948 0.120000 +7.505843 2.136313 0.120000 +5.505843 2.136313 0.120000 +4.200000 2.200000 0.120000 +3.505843 2.136313 0.120000 +2.200000 2.200000 0.120000 +2.500000 1.450000 0.120000 +2.505843 1.386313 0.120000 +1.978833 1.874574 0.120000 +1.913687 1.044157 0.120000 +1.913687 1.855843 0.120000 +1.850000 1.050000 0.120000 +1.850000 1.850000 0.120000 +1.786313 1.044157 0.120000 +1.786313 1.855843 0.120000 +1.721167 1.874574 0.120000 +1.658477 1.907052 0.120000 +1.602513 1.952513 0.120000 +1.557052 2.008476 0.120000 +1.524574 2.071167 0.120000 +1.505843 2.136313 0.120000 +1.500000 2.200000 0.120000 +1.505843 2.263687 0.120000 +1.524574 2.328833 0.120000 +1.557052 2.391523 0.120000 +2.786313 1.105843 0.120000 +2.978833 1.124574 0.120000 +4.786313 1.105843 0.120000 +4.978833 1.124574 0.120000 +6.786313 1.105843 0.120000 +6.978833 1.124574 0.120000 +8.786313 1.105843 0.120000 +8.978833 1.124574 0.120000 +10.786313 1.105843 0.120000 +10.978833 1.124574 0.120000 +12.786313 1.105843 0.120000 +12.978833 1.124574 0.120000 +14.786313 1.105843 0.120000 +14.978833 1.124574 0.120000 +16.786312 1.105843 0.120000 +16.978832 1.124574 0.120000 +18.786312 1.105843 0.120000 +18.978832 1.124574 0.120000 +20.786312 1.105843 0.120000 +20.978832 1.124574 0.120000 +22.786312 1.105843 0.120000 +22.978832 1.124574 0.120000 +24.786312 1.105843 0.120000 +24.978832 1.124574 0.120000 +26.786312 1.105843 0.120000 +26.978832 1.124574 0.120000 +28.786312 1.105843 0.120000 +28.978832 1.124574 0.120000 +30.786312 1.105843 0.120000 +30.978832 1.124574 0.120000 +32.786312 1.105843 0.120000 +32.978832 1.124574 0.120000 +34.786312 1.105843 0.120000 +34.978832 1.124574 0.120000 +36.786312 1.105843 0.120000 +36.978832 1.124574 0.120000 +36.913689 1.794157 0.120000 +36.721169 1.775426 0.120000 +34.913689 1.794157 0.120000 +34.721169 1.775426 0.120000 +32.913689 1.794157 0.120000 +32.721169 1.775426 0.120000 +30.913687 1.794157 0.120000 +30.721167 1.775426 0.120000 +28.913687 1.794157 0.120000 +28.721167 1.775426 0.120000 +26.913687 1.794157 0.120000 +26.721167 1.775426 0.120000 +24.913687 1.794157 0.120000 +24.721167 1.775426 0.120000 +22.913687 1.794157 0.120000 +22.721167 1.775426 0.120000 +20.913687 1.794157 0.120000 +20.721167 1.775426 0.120000 +18.913687 1.794157 0.120000 +18.721167 1.775426 0.120000 +16.913687 1.794157 0.120000 +16.721167 1.775426 0.120000 +14.913687 1.794157 0.120000 +14.721167 1.775426 0.120000 +12.913687 1.794157 0.120000 +12.721167 1.775426 0.120000 +10.913687 1.794157 0.120000 +10.721167 1.775426 0.120000 +8.913687 1.794157 0.120000 +8.721167 1.775426 0.120000 +6.913687 1.794157 0.120000 +6.721167 1.775426 0.120000 +4.913687 1.794157 0.120000 +4.721167 1.775426 0.120000 +2.913687 1.794157 0.120000 +2.721167 1.775426 0.120000 +1.602513 2.447487 0.120000 +1.658477 0.407052 0.120000 +2.200000 0.700000 0.120000 +3.505843 0.636313 0.120000 +4.200000 0.700000 0.120000 +5.505843 0.636313 0.120000 +6.200000 0.700000 0.120000 +7.505843 0.636313 0.120000 +8.200000 0.700000 0.120000 +9.505843 0.636313 0.120000 +10.200000 0.700000 0.120000 +11.505843 0.636313 0.120000 +12.200000 0.700000 0.120000 +13.505843 0.636313 0.120000 +14.200000 0.700000 0.120000 +15.505843 0.636313 0.120000 +16.200001 0.700000 0.120000 +17.505842 0.636313 0.120000 +18.200001 0.700000 0.120000 +19.505842 0.636313 0.120000 +20.200001 0.700000 0.120000 +21.505842 0.636313 0.120000 +22.200001 0.700000 0.120000 +23.505842 0.636313 0.120000 +24.200001 0.700000 0.120000 +25.505842 0.636313 0.120000 +26.200001 0.700000 0.120000 +27.505842 0.636313 0.120000 +28.200001 0.700000 0.120000 +29.505842 0.636313 0.120000 +30.200001 0.700000 0.120000 +31.505842 0.636313 0.120000 +32.200001 0.700000 0.120000 +33.505844 0.636313 0.120000 +34.200001 0.700000 0.120000 +35.505844 0.636313 0.120000 +36.200001 0.700000 0.120000 +37.505844 0.636313 0.120000 +38.041523 0.992948 0.120000 +38.097488 1.952513 0.120000 +37.500000 2.200000 0.120000 +36.194157 2.263687 0.120000 +35.500000 2.200000 0.120000 +34.194157 2.263687 0.120000 +33.500000 2.200000 0.120000 +32.194157 2.263687 0.120000 +31.500000 2.200000 0.120000 +30.194157 2.263687 0.120000 +29.500000 2.200000 0.120000 +28.194157 2.263687 0.120000 +27.500000 2.200000 0.120000 +26.194157 2.263687 0.120000 +25.500000 2.200000 0.120000 +24.194157 2.263687 0.120000 +23.500000 2.200000 0.120000 +22.194157 2.263687 0.120000 +21.500000 2.200000 0.120000 +20.194157 2.263687 0.120000 +19.500000 2.200000 0.120000 +18.194157 2.263687 0.120000 +17.500000 2.200000 0.120000 +16.194157 2.263687 0.120000 +15.500000 2.200000 0.120000 +14.194157 2.263687 0.120000 +13.500000 2.200000 0.120000 +12.194157 2.263687 0.120000 +11.500000 2.200000 0.120000 +10.194157 2.263687 0.120000 +9.500000 2.200000 0.120000 +8.194157 2.263687 0.120000 +7.500000 2.200000 0.120000 +6.194157 2.263687 0.120000 +5.500000 2.200000 0.120000 +4.194157 2.263687 0.120000 +3.500000 2.200000 0.120000 +2.194157 2.263687 0.120000 +2.850000 1.100000 0.120000 +2.913687 1.105843 0.120000 +2.194157 0.636313 0.120000 +3.524574 0.571167 0.120000 +2.175426 0.571167 0.120000 +3.557052 0.508477 0.120000 +2.142948 0.508477 0.120000 +3.602513 0.452513 0.120000 +4.850000 1.100000 0.120000 +4.913687 1.105843 0.120000 +4.194157 0.636313 0.120000 +5.524574 0.571167 0.120000 +4.175426 0.571167 0.120000 +5.557052 0.508477 0.120000 +4.142949 0.508477 0.120000 +5.602513 0.452513 0.120000 +6.850000 1.100000 0.120000 +6.913687 1.105843 0.120000 +6.194157 0.636313 0.120000 +7.524574 0.571167 0.120000 +6.175426 0.571167 0.120000 +7.557052 0.508477 0.120000 +6.142949 0.508477 0.120000 +7.602513 0.452513 0.120000 +8.850000 1.100000 0.120000 +8.913687 1.105843 0.120000 +8.194157 0.636313 0.120000 +9.524574 0.571167 0.120000 +8.175426 0.571167 0.120000 +9.557052 0.508477 0.120000 +8.142948 0.508477 0.120000 +9.602512 0.452513 0.120000 +10.850000 1.100000 0.120000 +10.913687 1.105843 0.120000 +10.194157 0.636313 0.120000 +11.524574 0.571167 0.120000 +10.175426 0.571167 0.120000 +11.557052 0.508477 0.120000 +10.142948 0.508477 0.120000 +11.602512 0.452513 0.120000 +12.850000 1.100000 0.120000 +12.913687 1.105843 0.120000 +12.194157 0.636313 0.120000 +13.524574 0.571167 0.120000 +12.175426 0.571167 0.120000 +13.557052 0.508477 0.120000 +12.142948 0.508477 0.120000 +13.602512 0.452513 0.120000 +14.850000 1.100000 0.120000 +14.913687 1.105843 0.120000 +14.194157 0.636313 0.120000 +15.524574 0.571167 0.120000 +14.175426 0.571167 0.120000 +15.557052 0.508477 0.120000 +14.142948 0.508477 0.120000 +15.602512 0.452513 0.120000 +16.850000 1.100000 0.120000 +16.913687 1.105843 0.120000 +16.194157 0.636313 0.120000 +17.524574 0.571167 0.120000 +16.175426 0.571167 0.120000 +17.557051 0.508477 0.120000 +16.142948 0.508477 0.120000 +17.602512 0.452513 0.120000 +18.850000 1.100000 0.120000 +18.913687 1.105843 0.120000 +18.194157 0.636313 0.120000 +19.524574 0.571167 0.120000 +18.175426 0.571167 0.120000 +19.557051 0.508477 0.120000 +18.142948 0.508477 0.120000 +19.602512 0.452513 0.120000 +20.850000 1.100000 0.120000 +20.913687 1.105843 0.120000 +20.194157 0.636313 0.120000 +21.524574 0.571167 0.120000 +20.175426 0.571167 0.120000 +21.557051 0.508477 0.120000 +20.142948 0.508477 0.120000 +21.602512 0.452513 0.120000 +22.850000 1.100000 0.120000 +22.913687 1.105843 0.120000 +22.194157 0.636313 0.120000 +23.524574 0.571167 0.120000 +22.175426 0.571167 0.120000 +23.557051 0.508477 0.120000 +22.142948 0.508477 0.120000 +23.602512 0.452513 0.120000 +24.850000 1.100000 0.120000 +24.913687 1.105843 0.120000 +24.194157 0.636313 0.120000 +25.524574 0.571167 0.120000 +24.175426 0.571167 0.120000 +25.557051 0.508477 0.120000 +24.142948 0.508477 0.120000 +25.602512 0.452513 0.120000 +26.850000 1.100000 0.120000 +26.913687 1.105843 0.120000 +26.194157 0.636313 0.120000 +27.524574 0.571167 0.120000 +26.175426 0.571167 0.120000 +27.557051 0.508477 0.120000 +26.142948 0.508477 0.120000 +27.602512 0.452513 0.120000 +28.850000 1.100000 0.120000 +28.913687 1.105843 0.120000 +28.194157 0.636313 0.120000 +29.524574 0.571167 0.120000 +28.175426 0.571167 0.120000 +29.557051 0.508477 0.120000 +28.142948 0.508477 0.120000 +29.602512 0.452513 0.120000 +30.850000 1.100000 0.120000 +30.913687 1.105843 0.120000 +30.194157 0.636313 0.120000 +31.524574 0.571167 0.120000 +30.175426 0.571167 0.120000 +31.557051 0.508477 0.120000 +30.142948 0.508477 0.120000 +31.602512 0.452513 0.120000 +32.849998 1.100000 0.120000 +32.913689 1.105843 0.120000 +32.194157 0.636313 0.120000 +33.524574 0.571167 0.120000 +32.175426 0.571167 0.120000 +33.557053 0.508477 0.120000 +32.142948 0.508477 0.120000 +33.602512 0.452513 0.120000 +34.849998 1.100000 0.120000 +34.913689 1.105843 0.120000 +34.194157 0.636313 0.120000 +35.524574 0.571167 0.120000 +34.175426 0.571167 0.120000 +35.557053 0.508477 0.120000 +34.142948 0.508477 0.120000 +35.602512 0.452513 0.120000 +36.849998 1.100000 0.120000 +36.913689 1.105843 0.120000 +36.194157 0.636313 0.120000 +37.524574 0.571167 0.120000 +36.175426 0.571167 0.120000 +37.557053 0.508477 0.120000 +36.142948 0.508477 0.120000 +37.602512 0.452513 0.120000 +36.849998 1.800000 0.120000 +36.786312 1.794157 0.120000 +37.505844 2.263687 0.120000 +36.175426 2.328833 0.120000 +37.524574 2.328833 0.120000 +36.142948 2.391523 0.120000 +37.557053 2.391523 0.120000 +36.097488 2.447487 0.120000 +34.849998 1.800000 0.120000 +34.786312 1.794157 0.120000 +35.505844 2.263687 0.120000 +34.175426 2.328833 0.120000 +35.524574 2.328833 0.120000 +34.142948 2.391523 0.120000 +35.557053 2.391523 0.120000 +34.097488 2.447487 0.120000 +32.849998 1.800000 0.120000 +32.786312 1.794157 0.120000 +33.505844 2.263687 0.120000 +32.175426 2.328833 0.120000 +33.524574 2.328833 0.120000 +32.142948 2.391523 0.120000 +33.557053 2.391523 0.120000 +32.097488 2.447487 0.120000 +30.850000 1.800000 0.120000 +30.786312 1.794157 0.120000 +31.505842 2.263687 0.120000 +30.175426 2.328833 0.120000 +31.524574 2.328833 0.120000 +30.142948 2.391523 0.120000 +31.557051 2.391523 0.120000 +30.097486 2.447487 0.120000 +28.850000 1.800000 0.120000 +28.786312 1.794157 0.120000 +29.505842 2.263687 0.120000 +28.175426 2.328833 0.120000 +29.524574 2.328833 0.120000 +28.142948 2.391523 0.120000 +29.557051 2.391523 0.120000 +28.097486 2.447487 0.120000 +26.850000 1.800000 0.120000 +26.786312 1.794157 0.120000 +27.505842 2.263687 0.120000 +26.175426 2.328833 0.120000 +27.524574 2.328833 0.120000 +26.142948 2.391523 0.120000 +27.557051 2.391523 0.120000 +26.097486 2.447487 0.120000 +24.850000 1.800000 0.120000 +24.786312 1.794157 0.120000 +25.505842 2.263687 0.120000 +24.175426 2.328833 0.120000 +25.524574 2.328833 0.120000 +24.142948 2.391523 0.120000 +25.557051 2.391523 0.120000 +24.097486 2.447487 0.120000 +22.850000 1.800000 0.120000 +22.786312 1.794157 0.120000 +23.505842 2.263687 0.120000 +22.175426 2.328833 0.120000 +23.524574 2.328833 0.120000 +22.142948 2.391523 0.120000 +23.557051 2.391523 0.120000 +22.097486 2.447487 0.120000 +20.850000 1.800000 0.120000 +20.786312 1.794157 0.120000 +21.505842 2.263687 0.120000 +20.175426 2.328833 0.120000 +21.524574 2.328833 0.120000 +20.142948 2.391523 0.120000 +21.557051 2.391523 0.120000 +20.097486 2.447487 0.120000 +18.850000 1.800000 0.120000 +18.786312 1.794157 0.120000 +19.505842 2.263687 0.120000 +18.175426 2.328833 0.120000 +19.524574 2.328833 0.120000 +18.142948 2.391523 0.120000 +19.557051 2.391523 0.120000 +18.097486 2.447487 0.120000 +16.850000 1.800000 0.120000 +16.786312 1.794157 0.120000 +17.505842 2.263687 0.120000 +16.175426 2.328833 0.120000 +17.524574 2.328833 0.120000 +16.142948 2.391523 0.120000 +17.557051 2.391523 0.120000 +16.097486 2.447487 0.120000 +14.850000 1.800000 0.120000 +14.786313 1.794157 0.120000 +15.505843 2.263687 0.120000 +14.175426 2.328833 0.120000 +15.524574 2.328833 0.120000 +14.142948 2.391523 0.120000 +15.557052 2.391523 0.120000 +14.097487 2.447487 0.120000 +12.850000 1.800000 0.120000 +12.786313 1.794157 0.120000 +13.505843 2.263687 0.120000 +12.175426 2.328833 0.120000 +13.524574 2.328833 0.120000 +12.142948 2.391523 0.120000 +13.557052 2.391523 0.120000 +12.097487 2.447487 0.120000 +10.850000 1.800000 0.120000 +10.786313 1.794157 0.120000 +11.505843 2.263687 0.120000 +10.175426 2.328833 0.120000 +11.524574 2.328833 0.120000 +10.142948 2.391523 0.120000 +11.557052 2.391523 0.120000 +10.097487 2.447487 0.120000 +8.850000 1.800000 0.120000 +8.786313 1.794157 0.120000 +9.505843 2.263687 0.120000 +8.175426 2.328833 0.120000 +9.524574 2.328833 0.120000 +8.142948 2.391523 0.120000 +9.557052 2.391523 0.120000 +8.097487 2.447487 0.120000 +6.850000 1.800000 0.120000 +6.786313 1.794157 0.120000 +7.505843 2.263687 0.120000 +6.175426 2.328833 0.120000 +7.524574 2.328833 0.120000 +6.142949 2.391523 0.120000 +7.557052 2.391523 0.120000 +6.097487 2.447487 0.120000 +4.850000 1.800000 0.120000 +4.786313 1.794157 0.120000 +5.505843 2.263687 0.120000 +4.175426 2.328833 0.120000 +5.524574 2.328833 0.120000 +4.142949 2.391523 0.120000 +5.557052 2.391523 0.120000 +4.097487 2.447487 0.120000 +2.850000 1.800000 0.120000 +2.786313 1.794157 0.120000 +3.505843 2.263687 0.120000 +2.175426 2.328833 0.120000 +3.524574 2.328833 0.120000 +2.142948 2.391523 0.120000 +3.557052 2.391523 0.120000 +2.097487 2.447487 0.120000 +1.658477 2.492949 0.120000 +1.721167 0.374574 0.120000 +2.097487 0.452513 0.120000 +3.658477 0.407052 0.120000 +4.097487 0.452513 0.120000 +5.658476 0.407052 0.120000 +6.097487 0.452513 0.120000 +7.658476 0.407052 0.120000 +8.097487 0.452513 0.120000 +9.658477 0.407052 0.120000 +10.097487 0.452513 0.120000 +11.658477 0.407052 0.120000 +12.097487 0.452513 0.120000 +13.658477 0.407052 0.120000 +14.097487 0.452513 0.120000 +15.658477 0.407052 0.120000 +16.097486 0.452513 0.120000 +17.658476 0.407052 0.120000 +18.097486 0.452513 0.120000 +19.658476 0.407052 0.120000 +20.097486 0.452513 0.120000 +21.658476 0.407052 0.120000 +22.097486 0.452513 0.120000 +23.658476 0.407052 0.120000 +24.097486 0.452513 0.120000 +25.658476 0.407052 0.120000 +26.097486 0.452513 0.120000 +27.658476 0.407052 0.120000 +28.097486 0.452513 0.120000 +29.658476 0.407052 0.120000 +30.097486 0.452513 0.120000 +31.658476 0.407052 0.120000 +32.097488 0.452513 0.120000 +33.658478 0.407052 0.120000 +34.097488 0.452513 0.120000 +35.658478 0.407052 0.120000 +36.097488 0.452513 0.120000 +37.658478 0.407052 0.120000 +38.097488 0.947487 0.120000 +38.142948 2.008476 0.120000 +37.602512 2.447487 0.120000 +36.041523 2.492949 0.120000 +35.602512 2.447487 0.120000 +34.041523 2.492949 0.120000 +33.602512 2.447487 0.120000 +32.041523 2.492949 0.120000 +31.602512 2.447487 0.120000 +30.041523 2.492949 0.120000 +29.602512 2.447487 0.120000 +28.041523 2.492949 0.120000 +27.602512 2.447487 0.120000 +26.041523 2.492949 0.120000 +25.602512 2.447487 0.120000 +24.041523 2.492949 0.120000 +23.602512 2.447487 0.120000 +22.041523 2.492949 0.120000 +21.602512 2.447487 0.120000 +20.041523 2.492949 0.120000 +19.602512 2.447487 0.120000 +18.041523 2.492949 0.120000 +17.602512 2.447487 0.120000 +16.041523 2.492949 0.120000 +15.602512 2.447487 0.120000 +14.041523 2.492949 0.120000 +13.602512 2.447487 0.120000 +12.041523 2.492949 0.120000 +11.602512 2.447487 0.120000 +10.041523 2.492949 0.120000 +9.602512 2.447487 0.120000 +8.041523 2.492949 0.120000 +7.602513 2.447487 0.120000 +6.041523 2.492949 0.120000 +5.602513 2.447487 0.120000 +4.041523 2.492949 0.120000 +3.602513 2.447487 0.120000 +2.041523 2.492949 0.120000 +1.721167 2.525426 0.120000 +1.786313 0.355843 0.120000 +2.041523 0.407052 0.120000 +3.721167 0.374574 0.120000 +4.041523 0.407052 0.120000 +5.721167 0.374574 0.120000 +6.041523 0.407052 0.120000 +7.721167 0.374574 0.120000 +8.041523 0.407052 0.120000 +9.721167 0.374574 0.120000 +10.041523 0.407052 0.120000 +11.721167 0.374574 0.120000 +12.041523 0.407052 0.120000 +13.721167 0.374574 0.120000 +14.041523 0.407052 0.120000 +15.721167 0.374574 0.120000 +16.041523 0.407052 0.120000 +17.721167 0.374574 0.120000 +18.041523 0.407052 0.120000 +19.721167 0.374574 0.120000 +20.041523 0.407052 0.120000 +21.721167 0.374574 0.120000 +22.041523 0.407052 0.120000 +23.721167 0.374574 0.120000 +24.041523 0.407052 0.120000 +25.721167 0.374574 0.120000 +26.041523 0.407052 0.120000 +27.721167 0.374574 0.120000 +28.041523 0.407052 0.120000 +29.721167 0.374574 0.120000 +30.041523 0.407052 0.120000 +31.721167 0.374574 0.120000 +32.041523 0.407052 0.120000 +33.721169 0.374574 0.120000 +34.041523 0.407052 0.120000 +35.721169 0.374574 0.120000 +36.041523 0.407052 0.120000 +37.721169 0.374574 0.120000 +38.142948 0.891523 0.120000 +38.175426 2.071167 0.120000 +37.658478 2.492949 0.120000 +35.978832 2.525426 0.120000 +35.658478 2.492949 0.120000 +33.978832 2.525426 0.120000 +33.658478 2.492949 0.120000 +31.978832 2.525426 0.120000 +31.658476 2.492949 0.120000 +29.978832 2.525426 0.120000 +29.658476 2.492949 0.120000 +27.978832 2.525426 0.120000 +27.658476 2.492949 0.120000 +25.978832 2.525426 0.120000 +25.658476 2.492949 0.120000 +23.978832 2.525426 0.120000 +23.658476 2.492949 0.120000 +21.978832 2.525426 0.120000 +21.658476 2.492949 0.120000 +19.978832 2.525426 0.120000 +19.658476 2.492949 0.120000 +17.978832 2.525426 0.120000 +17.658476 2.492949 0.120000 +15.978833 2.525426 0.120000 +15.658477 2.492949 0.120000 +13.978833 2.525426 0.120000 +13.658477 2.492949 0.120000 +11.978833 2.525426 0.120000 +11.658477 2.492949 0.120000 +9.978833 2.525426 0.120000 +9.658477 2.492949 0.120000 +7.978833 2.525426 0.120000 +7.658476 2.492949 0.120000 +5.978833 2.525426 0.120000 +5.658476 2.492949 0.120000 +3.978833 2.525426 0.120000 +3.658477 2.492949 0.120000 +1.978833 2.525426 0.120000 +1.978833 0.374574 0.120000 +3.978833 0.374574 0.120000 +5.978833 0.374574 0.120000 +7.978833 0.374574 0.120000 +9.978833 0.374574 0.120000 +3.786313 0.355843 0.120000 +5.786313 0.355843 0.120000 +7.786313 0.355843 0.120000 +9.786313 0.355843 0.120000 +11.786313 0.355843 0.120000 +11.978833 0.374574 0.120000 +13.978833 0.374574 0.120000 +15.978833 0.374574 0.120000 +13.786313 0.355843 0.120000 +15.786313 0.355843 0.120000 +17.786312 0.355843 0.120000 +17.978832 0.374574 0.120000 +19.978832 0.374574 0.120000 +21.978832 0.374574 0.120000 +23.978832 0.374574 0.120000 +19.786312 0.355843 0.120000 +21.786312 0.355843 0.120000 +23.786312 0.355843 0.120000 +25.786312 0.355843 0.120000 +25.978832 0.374574 0.120000 +27.978832 0.374574 0.120000 +29.978832 0.374574 0.120000 +27.786312 0.355843 0.120000 +29.786312 0.355843 0.120000 +31.786312 0.355843 0.120000 +31.978832 0.374574 0.120000 +33.978832 0.374574 0.120000 +35.978832 0.374574 0.120000 +38.175426 0.828833 0.120000 +33.786312 0.355843 0.120000 +35.786312 0.355843 0.120000 +37.786312 0.355843 0.120000 +38.194157 2.136313 0.120000 +37.721169 2.525426 0.120000 +35.721169 2.525426 0.120000 +33.721169 2.525426 0.120000 +35.913689 2.544157 0.120000 +33.913689 2.544157 0.120000 +31.913687 2.544157 0.120000 +31.721167 2.525426 0.120000 +29.721167 2.525426 0.120000 +27.721167 2.525426 0.120000 +25.721167 2.525426 0.120000 +29.913687 2.544157 0.120000 +27.913687 2.544157 0.120000 +25.913687 2.544157 0.120000 +23.913687 2.544157 0.120000 +23.721167 2.525426 0.120000 +21.721167 2.525426 0.120000 +19.721167 2.525426 0.120000 +21.913687 2.544157 0.120000 +19.913687 2.544157 0.120000 +17.913687 2.544157 0.120000 +17.721167 2.525426 0.120000 +15.721167 2.525426 0.120000 +13.721167 2.525426 0.120000 +11.721167 2.525426 0.120000 +15.913687 2.544157 0.120000 +13.913687 2.544157 0.120000 +11.913687 2.544157 0.120000 +9.913687 2.544157 0.120000 +9.721167 2.525426 0.120000 +7.721167 2.525426 0.120000 +5.721167 2.525426 0.120000 +7.913687 2.544157 0.120000 +5.913687 2.544157 0.120000 +3.913687 2.544157 0.120000 +3.721167 2.525426 0.120000 +1.913687 2.544157 0.120000 +1.786313 2.544157 0.120000 +39.700001 2.900000 0.120000 +1.850000 2.550000 0.120000 +1.850000 0.350000 0.120000 +0.000000 0.000000 0.120000 +1.913687 0.355843 0.120000 +3.850000 0.350000 0.120000 +3.913687 0.355843 0.120000 +5.850000 0.350000 0.120000 +5.913687 0.355843 0.120000 +7.850000 0.350000 0.120000 +7.913687 0.355843 0.120000 +9.850000 0.350000 0.120000 +9.913687 0.355843 0.120000 +11.850000 0.350000 0.120000 +11.913687 0.355843 0.120000 +13.850000 0.350000 0.120000 +13.913687 0.355843 0.120000 +15.850000 0.350000 0.120000 +15.913687 0.355843 0.120000 +17.850000 0.350000 0.120000 +17.913687 0.355843 0.120000 +19.850000 0.350000 0.120000 +19.913687 0.355843 0.120000 +21.850000 0.350000 0.120000 +21.913687 0.355843 0.120000 +23.850000 0.350000 0.120000 +23.913687 0.355843 0.120000 +25.850000 0.350000 0.120000 +25.913687 0.355843 0.120000 +27.850000 0.350000 0.120000 +27.913687 0.355843 0.120000 +29.850000 0.350000 0.120000 +29.913687 0.355843 0.120000 +31.850000 0.350000 0.120000 +31.913687 0.355843 0.120000 +33.849998 0.350000 0.120000 +33.913689 0.355843 0.120000 +35.849998 0.350000 0.120000 +35.913689 0.355843 0.120000 +37.849998 0.350000 0.120000 +37.913689 0.355843 0.120000 +37.978832 0.374574 0.120000 +38.041523 0.407052 0.120000 +38.097488 0.452513 0.120000 +38.142948 0.508477 0.120000 +39.700001 0.000000 0.120000 +38.175426 0.571167 0.120000 +38.194157 0.636313 0.120000 +38.200001 0.700000 0.120000 +38.194157 0.763687 0.120000 +38.200001 2.200000 0.120000 +38.194157 2.263687 0.120000 +38.175426 2.328833 0.120000 +38.142948 2.391523 0.120000 +38.097488 2.447487 0.120000 +38.041523 2.492949 0.120000 +37.978832 2.525426 0.120000 +37.913689 2.544157 0.120000 +37.849998 2.550000 0.120000 +37.786312 2.544157 0.120000 +35.849998 2.550000 0.120000 +35.786312 2.544157 0.120000 +33.849998 2.550000 0.120000 +33.786312 2.544157 0.120000 +31.786312 2.544157 0.120000 +29.786312 2.544157 0.120000 +27.786312 2.544157 0.120000 +25.786312 2.544157 0.120000 +31.850000 2.550000 0.120000 +29.850000 2.550000 0.120000 +27.850000 2.550000 0.120000 +25.850000 2.550000 0.120000 +23.850000 2.550000 0.120000 +23.786312 2.544157 0.120000 +21.786312 2.544157 0.120000 +19.786312 2.544157 0.120000 +21.850000 2.550000 0.120000 +19.850000 2.550000 0.120000 +17.850000 2.550000 0.120000 +17.786312 2.544157 0.120000 +15.786313 2.544157 0.120000 +13.786313 2.544157 0.120000 +11.786313 2.544157 0.120000 +15.850000 2.550000 0.120000 +13.850000 2.550000 0.120000 +11.850000 2.550000 0.120000 +9.850000 2.550000 0.120000 +9.786313 2.544157 0.120000 +7.786313 2.544157 0.120000 +5.786313 2.544157 0.120000 +7.850000 2.550000 0.120000 +5.850000 2.550000 0.120000 +3.850000 2.550000 0.120000 +3.786313 2.544157 0.120000 +0.000000 0.000000 0.000000 +1.505843 0.636313 0.000000 +1.500000 0.700000 0.000000 +1.505843 0.763687 0.000000 +1.524574 0.828833 0.000000 +1.557052 0.891523 0.000000 +1.602513 0.947487 0.000000 +2.142948 0.891523 0.000000 +2.097487 1.952513 0.000000 +2.602513 1.697487 0.000000 +3.142948 1.641523 0.000000 +3.557052 2.008476 0.000000 +3.602513 0.947487 0.000000 +4.142949 0.891523 0.000000 +5.602513 0.947487 0.000000 +6.142949 0.891523 0.000000 +6.097487 1.952513 0.000000 +6.602513 1.697487 0.000000 +7.602513 0.947487 0.000000 +8.142948 0.891523 0.000000 +8.097487 1.952513 0.000000 +8.602512 1.697487 0.000000 +9.602512 0.947487 0.000000 +10.142948 0.891523 0.000000 +10.097487 1.952513 0.000000 +10.602512 1.697487 0.000000 +11.602512 0.947487 0.000000 +12.142948 0.891523 0.000000 +12.097487 1.952513 0.000000 +12.602512 1.697487 0.000000 +13.602512 0.947487 0.000000 +14.142948 0.891523 0.000000 +14.097487 1.952513 0.000000 +14.602512 1.697487 0.000000 +15.142948 1.641523 0.000000 +15.557052 2.008476 0.000000 +15.602512 0.947487 0.000000 +16.142948 0.891523 0.000000 +17.142948 1.641523 0.000000 +18.602512 1.697487 0.000000 +19.142948 1.641523 0.000000 +20.602512 1.697487 0.000000 +21.142948 1.641523 0.000000 +21.557051 2.008476 0.000000 +21.602512 0.947487 0.000000 +22.142948 0.891523 0.000000 +23.142948 1.641523 0.000000 +24.602512 1.697487 0.000000 +25.142948 1.641523 0.000000 +26.602512 1.697487 0.000000 +27.602512 0.947487 0.000000 +28.142948 0.891523 0.000000 +28.097486 1.952513 0.000000 +28.602512 1.697487 0.000000 +29.142948 1.641523 0.000000 +29.557051 2.008476 0.000000 +29.602512 0.947487 0.000000 +30.142948 0.891523 0.000000 +31.602512 0.947487 0.000000 +32.142948 0.891523 0.000000 +32.097488 1.952513 0.000000 +32.602512 1.697487 0.000000 +33.602512 0.947487 0.000000 +34.142948 0.891523 0.000000 +34.097488 1.952513 0.000000 +34.602512 1.697487 0.000000 +35.602512 0.947487 0.000000 +36.142948 0.891523 0.000000 +36.097488 1.952513 0.000000 +36.602512 1.697487 0.000000 +37.142948 1.641523 0.000000 +37.557053 2.008476 0.000000 +37.602512 0.947487 0.000000 +37.097488 1.202513 0.000000 +36.557053 1.258477 0.000000 +35.097488 1.202513 0.000000 +34.557053 1.258477 0.000000 +33.097488 1.202513 0.000000 +32.557053 1.258477 0.000000 +31.097486 1.202513 0.000000 +30.557051 1.258477 0.000000 +29.097486 1.202513 0.000000 +28.557051 1.258477 0.000000 +27.097486 1.202513 0.000000 +26.557051 1.258477 0.000000 +26.142948 0.891523 0.000000 +26.097486 1.952513 0.000000 +25.557051 2.008476 0.000000 +24.097486 1.952513 0.000000 +23.557051 2.008476 0.000000 +23.602512 0.947487 0.000000 +23.097486 1.202513 0.000000 +22.557051 1.258477 0.000000 +21.097486 1.202513 0.000000 +20.097486 1.952513 0.000000 +19.557051 2.008476 0.000000 +19.602512 0.947487 0.000000 +19.097486 1.202513 0.000000 +18.557051 1.258477 0.000000 +18.142948 0.891523 0.000000 +18.097486 1.952513 0.000000 +17.557051 2.008476 0.000000 +16.557051 1.258477 0.000000 +15.097487 1.202513 0.000000 +14.557052 1.258477 0.000000 +13.097487 1.202513 0.000000 +12.557052 1.258477 0.000000 +11.097487 1.202513 0.000000 +10.557052 1.258477 0.000000 +9.097487 1.202513 0.000000 +8.557052 1.258477 0.000000 +7.097487 1.202513 0.000000 +6.557052 1.258477 0.000000 +5.097487 1.202513 0.000000 +4.557052 1.258477 0.000000 +3.097487 1.202513 0.000000 +2.557052 1.258477 0.000000 +1.658477 0.992948 0.000000 +2.524574 1.321167 0.000000 +2.557052 1.641523 0.000000 +2.142948 2.008476 0.000000 +3.524574 2.071167 0.000000 +3.175426 1.578833 0.000000 +3.142948 1.258477 0.000000 +4.524574 1.321167 0.000000 +5.142949 1.258477 0.000000 +6.524574 1.321167 0.000000 +6.557052 1.641523 0.000000 +6.142949 2.008476 0.000000 +7.142949 1.258477 0.000000 +8.524574 1.321167 0.000000 +8.557052 1.641523 0.000000 +8.142948 2.008476 0.000000 +9.142948 1.258477 0.000000 +10.524574 1.321167 0.000000 +10.557052 1.641523 0.000000 +10.142948 2.008476 0.000000 +11.142948 1.258477 0.000000 +12.524574 1.321167 0.000000 +12.557052 1.641523 0.000000 +12.142948 2.008476 0.000000 +13.142948 1.258477 0.000000 +14.524574 1.321167 0.000000 +14.557052 1.641523 0.000000 +14.142948 2.008476 0.000000 +15.524574 2.071167 0.000000 +15.175426 1.578833 0.000000 +15.142948 1.258477 0.000000 +16.524574 1.321167 0.000000 +17.524574 2.071167 0.000000 +18.142948 2.008476 0.000000 +19.524574 2.071167 0.000000 +20.142948 2.008476 0.000000 +21.524574 2.071167 0.000000 +21.175426 1.578833 0.000000 +21.142948 1.258477 0.000000 +22.524574 1.321167 0.000000 +23.524574 2.071167 0.000000 +24.142948 2.008476 0.000000 +25.524574 2.071167 0.000000 +26.142948 2.008476 0.000000 +27.142948 1.258477 0.000000 +28.524574 1.321167 0.000000 +28.557051 1.641523 0.000000 +28.142948 2.008476 0.000000 +29.524574 2.071167 0.000000 +29.175426 1.578833 0.000000 +29.142948 1.258477 0.000000 +30.524574 1.321167 0.000000 +31.142948 1.258477 0.000000 +32.524574 1.321167 0.000000 +32.557053 1.641523 0.000000 +32.142948 2.008476 0.000000 +33.142948 1.258477 0.000000 +34.524574 1.321167 0.000000 +34.557053 1.641523 0.000000 +34.142948 2.008476 0.000000 +35.142948 1.258477 0.000000 +36.524574 1.321167 0.000000 +36.557053 1.641523 0.000000 +36.142948 2.008476 0.000000 +37.524574 2.071167 0.000000 +37.175426 1.578833 0.000000 +37.142948 1.258477 0.000000 +37.557053 0.891523 0.000000 +36.175426 0.828833 0.000000 +35.557053 0.891523 0.000000 +34.175426 0.828833 0.000000 +33.557053 0.891523 0.000000 +32.175426 0.828833 0.000000 +31.557051 0.891523 0.000000 +30.175426 0.828833 0.000000 +29.557051 0.891523 0.000000 +28.175426 0.828833 0.000000 +27.557051 0.891523 0.000000 +26.175426 0.828833 0.000000 +26.524574 1.321167 0.000000 +26.557051 1.641523 0.000000 +25.175426 1.578833 0.000000 +24.557051 1.641523 0.000000 +23.175426 1.578833 0.000000 +23.142948 1.258477 0.000000 +23.557051 0.891523 0.000000 +22.175426 0.828833 0.000000 +21.557051 0.891523 0.000000 +20.557051 1.641523 0.000000 +19.175426 1.578833 0.000000 +19.142948 1.258477 0.000000 +19.557051 0.891523 0.000000 +18.175426 0.828833 0.000000 +18.524574 1.321167 0.000000 +18.557051 1.641523 0.000000 +17.175426 1.578833 0.000000 +16.175426 0.828833 0.000000 +15.557052 0.891523 0.000000 +14.175426 0.828833 0.000000 +13.557052 0.891523 0.000000 +12.175426 0.828833 0.000000 +11.557052 0.891523 0.000000 +10.175426 0.828833 0.000000 +9.557052 0.891523 0.000000 +8.175426 0.828833 0.000000 +7.557052 0.891523 0.000000 +6.175426 0.828833 0.000000 +5.557052 0.891523 0.000000 +4.175426 0.828833 0.000000 +3.557052 0.891523 0.000000 +2.175426 0.828833 0.000000 +1.524574 0.571167 0.000000 +2.097487 0.947487 0.000000 +2.041523 1.907052 0.000000 +2.658477 1.742948 0.000000 +3.097487 1.697487 0.000000 +3.602513 1.952513 0.000000 +3.658477 0.992948 0.000000 +4.097487 0.947487 0.000000 +5.658476 0.992948 0.000000 +6.097487 0.947487 0.000000 +6.041523 1.907052 0.000000 +6.658476 1.742948 0.000000 +7.658476 0.992948 0.000000 +8.097487 0.947487 0.000000 +8.041523 1.907052 0.000000 +8.658477 1.742948 0.000000 +9.658477 0.992948 0.000000 +10.097487 0.947487 0.000000 +10.041523 1.907052 0.000000 +10.658477 1.742948 0.000000 +11.658477 0.992948 0.000000 +12.097487 0.947487 0.000000 +12.041523 1.907052 0.000000 +12.658477 1.742948 0.000000 +13.658477 0.992948 0.000000 +14.097487 0.947487 0.000000 +14.041523 1.907052 0.000000 +14.658477 1.742948 0.000000 +15.097487 1.697487 0.000000 +15.602512 1.952513 0.000000 +15.658477 0.992948 0.000000 +16.097486 0.947487 0.000000 +17.097486 1.697487 0.000000 +18.658476 1.742948 0.000000 +19.097486 1.697487 0.000000 +20.658476 1.742948 0.000000 +21.097486 1.697487 0.000000 +21.602512 1.952513 0.000000 +21.658476 0.992948 0.000000 +22.097486 0.947487 0.000000 +23.097486 1.697487 0.000000 +24.658476 1.742948 0.000000 +25.097486 1.697487 0.000000 +26.658476 1.742948 0.000000 +27.658476 0.992948 0.000000 +28.097486 0.947487 0.000000 +28.041523 1.907052 0.000000 +28.658476 1.742948 0.000000 +29.097486 1.697487 0.000000 +29.602512 1.952513 0.000000 +29.658476 0.992948 0.000000 +30.097486 0.947487 0.000000 +31.658476 0.992948 0.000000 +32.097488 0.947487 0.000000 +32.041523 1.907052 0.000000 +32.658478 1.742948 0.000000 +33.658478 0.992948 0.000000 +34.097488 0.947487 0.000000 +34.041523 1.907052 0.000000 +34.658478 1.742948 0.000000 +35.658478 0.992948 0.000000 +36.097488 0.947487 0.000000 +36.041523 1.907052 0.000000 +36.658478 1.742948 0.000000 +37.097488 1.697487 0.000000 +37.602512 1.952513 0.000000 +37.658478 0.992948 0.000000 +37.041523 1.157052 0.000000 +36.602512 1.202513 0.000000 +35.041523 1.157052 0.000000 +34.602512 1.202513 0.000000 +33.041523 1.157052 0.000000 +32.602512 1.202513 0.000000 +31.041523 1.157052 0.000000 +30.602512 1.202513 0.000000 +29.041523 1.157052 0.000000 +28.602512 1.202513 0.000000 +27.041523 1.157052 0.000000 +26.602512 1.202513 0.000000 +26.097486 0.947487 0.000000 +26.041523 1.907052 0.000000 +25.602512 1.952513 0.000000 +24.041523 1.907052 0.000000 +23.602512 1.952513 0.000000 +23.658476 0.992948 0.000000 +23.041523 1.157052 0.000000 +22.602512 1.202513 0.000000 +21.041523 1.157052 0.000000 +20.041523 1.907052 0.000000 +19.602512 1.952513 0.000000 +19.658476 0.992948 0.000000 +19.041523 1.157052 0.000000 +18.602512 1.202513 0.000000 +18.097486 0.947487 0.000000 +18.041523 1.907052 0.000000 +17.602512 1.952513 0.000000 +16.602512 1.202513 0.000000 +15.041523 1.157052 0.000000 +14.602512 1.202513 0.000000 +13.041523 1.157052 0.000000 +12.602512 1.202513 0.000000 +11.041523 1.157052 0.000000 +10.602512 1.202513 0.000000 +9.041523 1.157052 0.000000 +8.602512 1.202513 0.000000 +7.041523 1.157052 0.000000 +6.602513 1.202513 0.000000 +5.041523 1.157052 0.000000 +4.602513 1.202513 0.000000 +3.041523 1.157052 0.000000 +2.602513 1.202513 0.000000 +1.721167 1.025426 0.000000 +2.505843 1.386313 0.000000 +2.524574 1.578833 0.000000 +2.175426 2.071167 0.000000 +3.505843 2.136313 0.000000 +3.194157 1.513687 0.000000 +3.175426 1.321167 0.000000 +4.505843 1.386313 0.000000 +5.175426 1.321167 0.000000 +6.505843 1.386313 0.000000 +6.524574 1.578833 0.000000 +6.175426 2.071167 0.000000 +7.175426 1.321167 0.000000 +8.505843 1.386313 0.000000 +8.524574 1.578833 0.000000 +8.175426 2.071167 0.000000 +9.175426 1.321167 0.000000 +10.505843 1.386313 0.000000 +10.524574 1.578833 0.000000 +10.175426 2.071167 0.000000 +11.175426 1.321167 0.000000 +12.505843 1.386313 0.000000 +12.524574 1.578833 0.000000 +12.175426 2.071167 0.000000 +13.175426 1.321167 0.000000 +14.505843 1.386313 0.000000 +14.524574 1.578833 0.000000 +14.175426 2.071167 0.000000 +15.505843 2.136313 0.000000 +15.194157 1.513687 0.000000 +15.175426 1.321167 0.000000 +16.505842 1.386313 0.000000 +17.505842 2.136313 0.000000 +18.175426 2.071167 0.000000 +19.505842 2.136313 0.000000 +20.175426 2.071167 0.000000 +21.505842 2.136313 0.000000 +21.194157 1.513687 0.000000 +21.175426 1.321167 0.000000 +22.505842 1.386313 0.000000 +23.505842 2.136313 0.000000 +24.175426 2.071167 0.000000 +25.505842 2.136313 0.000000 +26.175426 2.071167 0.000000 +27.175426 1.321167 0.000000 +28.505842 1.386313 0.000000 +28.524574 1.578833 0.000000 +28.175426 2.071167 0.000000 +29.505842 2.136313 0.000000 +29.194157 1.513687 0.000000 +29.175426 1.321167 0.000000 +30.505842 1.386313 0.000000 +31.175426 1.321167 0.000000 +32.505844 1.386313 0.000000 +32.524574 1.578833 0.000000 +32.175426 2.071167 0.000000 +33.175426 1.321167 0.000000 +34.505844 1.386313 0.000000 +34.524574 1.578833 0.000000 +34.175426 2.071167 0.000000 +35.175426 1.321167 0.000000 +36.505844 1.386313 0.000000 +36.524574 1.578833 0.000000 +36.175426 2.071167 0.000000 +37.505844 2.136313 0.000000 +37.194157 1.513687 0.000000 +37.175426 1.321167 0.000000 +37.524574 0.828833 0.000000 +36.194157 0.763687 0.000000 +35.524574 0.828833 0.000000 +34.194157 0.763687 0.000000 +33.524574 0.828833 0.000000 +32.194157 0.763687 0.000000 +31.524574 0.828833 0.000000 +30.194157 0.763687 0.000000 +29.524574 0.828833 0.000000 +28.194157 0.763687 0.000000 +27.524574 0.828833 0.000000 +26.194157 0.763687 0.000000 +26.505842 1.386313 0.000000 +26.524574 1.578833 0.000000 +25.194157 1.513687 0.000000 +24.524574 1.578833 0.000000 +23.194157 1.513687 0.000000 +23.175426 1.321167 0.000000 +23.524574 0.828833 0.000000 +22.194157 0.763687 0.000000 +21.524574 0.828833 0.000000 +20.524574 1.578833 0.000000 +19.194157 1.513687 0.000000 +19.175426 1.321167 0.000000 +19.524574 0.828833 0.000000 +18.194157 0.763687 0.000000 +18.505842 1.386313 0.000000 +18.524574 1.578833 0.000000 +17.194157 1.513687 0.000000 +16.194157 0.763687 0.000000 +15.524574 0.828833 0.000000 +14.194157 0.763687 0.000000 +13.524574 0.828833 0.000000 +12.194157 0.763687 0.000000 +11.524574 0.828833 0.000000 +10.194157 0.763687 0.000000 +9.524574 0.828833 0.000000 +8.194157 0.763687 0.000000 +7.524574 0.828833 0.000000 +6.194157 0.763687 0.000000 +5.524574 0.828833 0.000000 +4.194157 0.763687 0.000000 +3.524574 0.828833 0.000000 +2.194157 0.763687 0.000000 +1.557052 0.508477 0.000000 +2.041523 0.992948 0.000000 +1.978833 1.874574 0.000000 +2.721167 1.775426 0.000000 +3.041523 1.742948 0.000000 +3.658477 1.907052 0.000000 +3.721167 1.025426 0.000000 +4.041523 0.992948 0.000000 +5.721167 1.025426 0.000000 +6.041523 0.992948 0.000000 +5.978833 1.874574 0.000000 +6.721167 1.775426 0.000000 +7.721167 1.025426 0.000000 +8.041523 0.992948 0.000000 +7.978833 1.874574 0.000000 +8.721167 1.775426 0.000000 +9.721167 1.025426 0.000000 +10.041523 0.992948 0.000000 +9.978833 1.874574 0.000000 +10.721167 1.775426 0.000000 +11.721167 1.025426 0.000000 +12.041523 0.992948 0.000000 +11.978833 1.874574 0.000000 +12.721167 1.775426 0.000000 +13.721167 1.025426 0.000000 +14.041523 0.992948 0.000000 +13.978833 1.874574 0.000000 +14.721167 1.775426 0.000000 +15.041523 1.742948 0.000000 +15.658477 1.907052 0.000000 +15.721167 1.025426 0.000000 +16.041523 0.992948 0.000000 +17.041523 1.742948 0.000000 +18.721167 1.775426 0.000000 +19.041523 1.742948 0.000000 +20.721167 1.775426 0.000000 +21.041523 1.742948 0.000000 +21.658476 1.907052 0.000000 +21.721167 1.025426 0.000000 +22.041523 0.992948 0.000000 +23.041523 1.742948 0.000000 +24.721167 1.775426 0.000000 +25.041523 1.742948 0.000000 +26.721167 1.775426 0.000000 +27.721167 1.025426 0.000000 +28.041523 0.992948 0.000000 +27.978832 1.874574 0.000000 +28.721167 1.775426 0.000000 +29.041523 1.742948 0.000000 +29.658476 1.907052 0.000000 +29.721167 1.025426 0.000000 +30.041523 0.992948 0.000000 +31.721167 1.025426 0.000000 +32.041523 0.992948 0.000000 +31.978832 1.874574 0.000000 +32.721169 1.775426 0.000000 +33.721169 1.025426 0.000000 +34.041523 0.992948 0.000000 +33.978832 1.874574 0.000000 +34.721169 1.775426 0.000000 +35.721169 1.025426 0.000000 +36.041523 0.992948 0.000000 +35.978832 1.874574 0.000000 +36.721169 1.775426 0.000000 +37.041523 1.742948 0.000000 +37.658478 1.907052 0.000000 +37.721169 1.025426 0.000000 +36.978832 1.124574 0.000000 +36.658478 1.157052 0.000000 +34.978832 1.124574 0.000000 +34.658478 1.157052 0.000000 +32.978832 1.124574 0.000000 +32.658478 1.157052 0.000000 +30.978832 1.124574 0.000000 +30.658476 1.157052 0.000000 +28.978832 1.124574 0.000000 +28.658476 1.157052 0.000000 +26.978832 1.124574 0.000000 +26.658476 1.157052 0.000000 +26.041523 0.992948 0.000000 +25.978832 1.874574 0.000000 +25.658476 1.907052 0.000000 +23.978832 1.874574 0.000000 +23.658476 1.907052 0.000000 +23.721167 1.025426 0.000000 +22.978832 1.124574 0.000000 +22.658476 1.157052 0.000000 +20.978832 1.124574 0.000000 +19.978832 1.874574 0.000000 +19.658476 1.907052 0.000000 +19.721167 1.025426 0.000000 +18.978832 1.124574 0.000000 +18.658476 1.157052 0.000000 +18.041523 0.992948 0.000000 +17.978832 1.874574 0.000000 +17.658476 1.907052 0.000000 +16.658476 1.157052 0.000000 +14.978833 1.124574 0.000000 +14.658477 1.157052 0.000000 +12.978833 1.124574 0.000000 +12.658477 1.157052 0.000000 +10.978833 1.124574 0.000000 +10.658477 1.157052 0.000000 +8.978833 1.124574 0.000000 +8.658477 1.157052 0.000000 +6.978833 1.124574 0.000000 +6.658476 1.157052 0.000000 +4.978833 1.124574 0.000000 +4.658476 1.157052 0.000000 +2.978833 1.124574 0.000000 +2.658477 1.157052 0.000000 +1.786313 1.044157 0.000000 +2.500000 1.450000 0.000000 +2.505843 1.513687 0.000000 +1.978833 1.025426 0.000000 +1.913687 1.855843 0.000000 +1.913687 1.044157 0.000000 +1.850000 1.850000 0.000000 +1.850000 1.050000 0.000000 +1.786313 1.855843 0.000000 +1.721167 1.874574 0.000000 +2.194157 2.136313 0.000000 +3.500000 2.200000 0.000000 +3.200000 1.450000 0.000000 +3.194157 1.386313 0.000000 +3.721167 1.874574 0.000000 +3.786313 1.044157 0.000000 +3.786313 1.855843 0.000000 +3.850000 1.050000 0.000000 +3.850000 1.850000 0.000000 +3.913687 1.044157 0.000000 +3.913687 1.855843 0.000000 +3.978833 1.025426 0.000000 +4.500000 1.450000 0.000000 +4.505843 1.513687 0.000000 +3.978833 1.874574 0.000000 +4.524574 1.578833 0.000000 +4.041523 1.907052 0.000000 +4.557052 1.641523 0.000000 +4.097487 1.952513 0.000000 +4.602513 1.697487 0.000000 +4.142949 2.008476 0.000000 +4.658476 1.742948 0.000000 +4.175426 2.071167 0.000000 +4.721167 1.775426 0.000000 +5.194157 1.386313 0.000000 +6.500000 1.450000 0.000000 +6.505843 1.513687 0.000000 +5.978833 1.025426 0.000000 +5.913687 1.855843 0.000000 +5.913687 1.044157 0.000000 +5.850000 1.850000 0.000000 +5.850000 1.050000 0.000000 +5.786313 1.855843 0.000000 +5.786313 1.044157 0.000000 +5.721167 1.874574 0.000000 +5.200000 1.450000 0.000000 +5.658476 1.907052 0.000000 +5.194157 1.513687 0.000000 +5.602513 1.952513 0.000000 +5.175426 1.578833 0.000000 +5.557052 2.008476 0.000000 +5.142949 1.641523 0.000000 +5.524574 2.071167 0.000000 +5.097487 1.697487 0.000000 +5.505843 2.136313 0.000000 +5.041523 1.742948 0.000000 +4.194157 2.136313 0.000000 +5.500000 2.200000 0.000000 +6.194157 2.136313 0.000000 +7.194157 1.386313 0.000000 +8.500000 1.450000 0.000000 +8.505843 1.513687 0.000000 +7.978833 1.025426 0.000000 +7.913687 1.855843 0.000000 +7.913687 1.044157 0.000000 +7.850000 1.850000 0.000000 +7.850000 1.050000 0.000000 +7.786313 1.855843 0.000000 +7.786313 1.044157 0.000000 +7.721167 1.874574 0.000000 +7.200000 1.450000 0.000000 +7.658476 1.907052 0.000000 +7.194157 1.513687 0.000000 +7.602513 1.952513 0.000000 +7.175426 1.578833 0.000000 +7.557052 2.008476 0.000000 +7.142949 1.641523 0.000000 +7.524574 2.071167 0.000000 +7.097487 1.697487 0.000000 +7.505843 2.136313 0.000000 +7.041523 1.742948 0.000000 +8.194157 2.136313 0.000000 +9.194157 1.386313 0.000000 +10.500000 1.450000 0.000000 +10.505843 1.513687 0.000000 +9.978833 1.025426 0.000000 +9.913687 1.855843 0.000000 +9.913687 1.044157 0.000000 +9.850000 1.850000 0.000000 +9.850000 1.050000 0.000000 +9.786313 1.855843 0.000000 +9.786313 1.044157 0.000000 +9.721167 1.874574 0.000000 +9.200000 1.450000 0.000000 +9.658477 1.907052 0.000000 +9.194157 1.513687 0.000000 +9.602512 1.952513 0.000000 +9.175426 1.578833 0.000000 +9.557052 2.008476 0.000000 +9.142948 1.641523 0.000000 +9.524574 2.071167 0.000000 +9.097487 1.697487 0.000000 +9.505843 2.136313 0.000000 +9.041523 1.742948 0.000000 +7.500000 2.200000 0.000000 +9.500000 2.200000 0.000000 +10.194157 2.136313 0.000000 +11.194157 1.386313 0.000000 +12.500000 1.450000 0.000000 +12.505843 1.513687 0.000000 +11.978833 1.025426 0.000000 +11.913687 1.855843 0.000000 +11.913687 1.044157 0.000000 +11.850000 1.850000 0.000000 +11.850000 1.050000 0.000000 +11.786313 1.855843 0.000000 +11.786313 1.044157 0.000000 +11.721167 1.874574 0.000000 +11.200000 1.450000 0.000000 +11.658477 1.907052 0.000000 +11.194157 1.513687 0.000000 +11.602512 1.952513 0.000000 +11.175426 1.578833 0.000000 +11.557052 2.008476 0.000000 +11.142948 1.641523 0.000000 +11.524574 2.071167 0.000000 +11.097487 1.697487 0.000000 +11.505843 2.136313 0.000000 +11.041523 1.742948 0.000000 +12.194157 2.136313 0.000000 +13.194157 1.386313 0.000000 +14.500000 1.450000 0.000000 +14.505843 1.513687 0.000000 +13.978833 1.025426 0.000000 +13.913687 1.855843 0.000000 +13.913687 1.044157 0.000000 +13.850000 1.850000 0.000000 +13.850000 1.050000 0.000000 +13.786313 1.855843 0.000000 +13.786313 1.044157 0.000000 +13.721167 1.874574 0.000000 +13.200000 1.450000 0.000000 +13.658477 1.907052 0.000000 +13.194157 1.513687 0.000000 +13.602512 1.952513 0.000000 +13.175426 1.578833 0.000000 +13.557052 2.008476 0.000000 +13.142948 1.641523 0.000000 +13.524574 2.071167 0.000000 +13.097487 1.697487 0.000000 +13.505843 2.136313 0.000000 +13.041523 1.742948 0.000000 +11.500000 2.200000 0.000000 +13.500000 2.200000 0.000000 +14.194157 2.136313 0.000000 +15.500000 2.200000 0.000000 +15.200000 1.450000 0.000000 +15.194157 1.386313 0.000000 +15.721167 1.874574 0.000000 +15.786313 1.044157 0.000000 +15.786313 1.855843 0.000000 +15.850000 1.050000 0.000000 +15.850000 1.850000 0.000000 +15.913687 1.044157 0.000000 +15.913687 1.855843 0.000000 +15.978833 1.025426 0.000000 +16.500000 1.450000 0.000000 +16.505842 1.513687 0.000000 +15.978833 1.874574 0.000000 +16.524574 1.578833 0.000000 +16.041523 1.907052 0.000000 +16.557051 1.641523 0.000000 +16.097486 1.952513 0.000000 +16.602512 1.697487 0.000000 +16.142948 2.008476 0.000000 +16.658476 1.742948 0.000000 +16.175426 2.071167 0.000000 +16.721167 1.775426 0.000000 +17.500000 2.200000 0.000000 +18.194157 2.136313 0.000000 +19.500000 2.200000 0.000000 +16.194157 2.136313 0.000000 +20.194157 2.136313 0.000000 +21.500000 2.200000 0.000000 +21.200001 1.450000 0.000000 +21.194157 1.386313 0.000000 +21.721167 1.874574 0.000000 +21.786312 1.044157 0.000000 +21.786312 1.855843 0.000000 +21.850000 1.050000 0.000000 +21.850000 1.850000 0.000000 +21.913687 1.044157 0.000000 +21.913687 1.855843 0.000000 +21.978832 1.025426 0.000000 +22.500000 1.450000 0.000000 +22.505842 1.513687 0.000000 +21.978832 1.874574 0.000000 +22.524574 1.578833 0.000000 +22.041523 1.907052 0.000000 +22.557051 1.641523 0.000000 +22.097486 1.952513 0.000000 +22.602512 1.697487 0.000000 +22.142948 2.008476 0.000000 +22.658476 1.742948 0.000000 +22.175426 2.071167 0.000000 +22.721167 1.775426 0.000000 +23.500000 2.200000 0.000000 +24.194157 2.136313 0.000000 +25.500000 2.200000 0.000000 +26.194157 2.136313 0.000000 +22.194157 2.136313 0.000000 +27.194157 1.386313 0.000000 +28.500000 1.450000 0.000000 +28.505842 1.513687 0.000000 +27.978832 1.025426 0.000000 +27.913687 1.855843 0.000000 +27.913687 1.044157 0.000000 +27.850000 1.850000 0.000000 +27.850000 1.050000 0.000000 +27.786312 1.855843 0.000000 +27.786312 1.044157 0.000000 +27.721167 1.874574 0.000000 +27.200001 1.450000 0.000000 +27.658476 1.907052 0.000000 +27.194157 1.513687 0.000000 +27.602512 1.952513 0.000000 +27.175426 1.578833 0.000000 +27.557051 2.008476 0.000000 +27.142948 1.641523 0.000000 +27.524574 2.071167 0.000000 +27.097486 1.697487 0.000000 +27.505842 2.136313 0.000000 +27.041523 1.742948 0.000000 +28.194157 2.136313 0.000000 +29.500000 2.200000 0.000000 +29.200001 1.450000 0.000000 +29.194157 1.386313 0.000000 +29.721167 1.874574 0.000000 +29.786312 1.044157 0.000000 +29.786312 1.855843 0.000000 +29.850000 1.050000 0.000000 +29.850000 1.850000 0.000000 +29.913687 1.044157 0.000000 +29.913687 1.855843 0.000000 +29.978832 1.025426 0.000000 +30.500000 1.450000 0.000000 +30.505842 1.513687 0.000000 +29.978832 1.874574 0.000000 +30.524574 1.578833 0.000000 +30.041523 1.907052 0.000000 +30.557051 1.641523 0.000000 +30.097486 1.952513 0.000000 +30.602512 1.697487 0.000000 +30.142948 2.008476 0.000000 +30.658476 1.742948 0.000000 +30.175426 2.071167 0.000000 +30.721167 1.775426 0.000000 +31.194157 1.386313 0.000000 +27.500000 2.200000 0.000000 +30.194157 2.136313 0.000000 +32.500000 1.450000 0.000000 +32.505844 1.513687 0.000000 +31.978832 1.025426 0.000000 +31.913687 1.855843 0.000000 +31.913687 1.044157 0.000000 +31.850000 1.850000 0.000000 +31.850000 1.050000 0.000000 +31.786312 1.855843 0.000000 +31.786312 1.044157 0.000000 +31.721167 1.874574 0.000000 +31.200001 1.450000 0.000000 +31.658476 1.907052 0.000000 +31.194157 1.513687 0.000000 +31.602512 1.952513 0.000000 +31.175426 1.578833 0.000000 +31.557051 2.008476 0.000000 +31.142948 1.641523 0.000000 +31.524574 2.071167 0.000000 +31.097486 1.697487 0.000000 +31.505842 2.136313 0.000000 +31.041523 1.742948 0.000000 +32.194157 2.136313 0.000000 +33.194157 1.386313 0.000000 +34.500000 1.450000 0.000000 +34.505844 1.513687 0.000000 +33.978832 1.025426 0.000000 +33.913689 1.855843 0.000000 +33.913689 1.044157 0.000000 +33.849998 1.850000 0.000000 +33.849998 1.050000 0.000000 +33.786312 1.855843 0.000000 +33.786312 1.044157 0.000000 +33.721169 1.874574 0.000000 +33.200001 1.450000 0.000000 +33.658478 1.907052 0.000000 +33.194157 1.513687 0.000000 +33.602512 1.952513 0.000000 +33.175426 1.578833 0.000000 +33.557053 2.008476 0.000000 +33.142948 1.641523 0.000000 +33.524574 2.071167 0.000000 +33.097488 1.697487 0.000000 +33.505844 2.136313 0.000000 +33.041523 1.742948 0.000000 +34.194157 2.136313 0.000000 +35.194157 1.386313 0.000000 +31.500000 2.200000 0.000000 +33.500000 2.200000 0.000000 +36.500000 1.450000 0.000000 +36.505844 1.513687 0.000000 +35.978832 1.025426 0.000000 +35.913689 1.855843 0.000000 +35.913689 1.044157 0.000000 +35.849998 1.850000 0.000000 +35.849998 1.050000 0.000000 +35.786312 1.855843 0.000000 +35.786312 1.044157 0.000000 +35.721169 1.874574 0.000000 +35.200001 1.450000 0.000000 +35.658478 1.907052 0.000000 +35.194157 1.513687 0.000000 +35.602512 1.952513 0.000000 +35.175426 1.578833 0.000000 +35.557053 2.008476 0.000000 +35.142948 1.641523 0.000000 +35.524574 2.071167 0.000000 +35.097488 1.697487 0.000000 +35.505844 2.136313 0.000000 +35.041523 1.742948 0.000000 +36.194157 2.136313 0.000000 +37.500000 2.200000 0.000000 +37.200001 1.450000 0.000000 +37.194157 1.386313 0.000000 +37.721169 1.874574 0.000000 +37.786312 1.044157 0.000000 +37.786312 1.855843 0.000000 +37.849998 1.050000 0.000000 +37.849998 1.850000 0.000000 +37.913689 1.044157 0.000000 +37.913689 1.855843 0.000000 +37.978832 1.025426 0.000000 +37.978832 1.874574 0.000000 +38.041523 0.992948 0.000000 +37.505844 0.763687 0.000000 +36.200001 0.700000 0.000000 +35.500000 2.200000 0.000000 +35.505844 0.763687 0.000000 +34.200001 0.700000 0.000000 +33.505844 0.763687 0.000000 +32.200001 0.700000 0.000000 +31.505842 0.763687 0.000000 +30.200001 0.700000 0.000000 +29.505842 0.763687 0.000000 +28.200001 0.700000 0.000000 +27.505842 0.763687 0.000000 +26.200001 0.700000 0.000000 +26.500000 1.450000 0.000000 +26.505842 1.513687 0.000000 +25.978832 1.025426 0.000000 +25.913687 1.855843 0.000000 +25.913687 1.044157 0.000000 +25.850000 1.850000 0.000000 +25.850000 1.050000 0.000000 +25.786312 1.855843 0.000000 +25.786312 1.044157 0.000000 +25.721167 1.874574 0.000000 +25.200001 1.450000 0.000000 +25.194157 1.386313 0.000000 +25.721167 1.025426 0.000000 +25.175426 1.321167 0.000000 +25.658476 0.992948 0.000000 +25.142948 1.258477 0.000000 +25.602512 0.947487 0.000000 +25.097486 1.202513 0.000000 +25.557051 0.891523 0.000000 +25.041523 1.157052 0.000000 +25.524574 0.828833 0.000000 +24.978832 1.124574 0.000000 +24.505842 1.513687 0.000000 +23.200001 1.450000 0.000000 +23.194157 1.386313 0.000000 +23.721167 1.874574 0.000000 +23.786312 1.044157 0.000000 +23.786312 1.855843 0.000000 +23.850000 1.050000 0.000000 +23.850000 1.850000 0.000000 +23.913687 1.044157 0.000000 +23.913687 1.855843 0.000000 +23.978832 1.025426 0.000000 +24.500000 1.450000 0.000000 +24.041523 0.992948 0.000000 +24.505842 1.386313 0.000000 +24.097486 0.947487 0.000000 +24.524574 1.321167 0.000000 +24.142948 0.891523 0.000000 +24.557051 1.258477 0.000000 +24.175426 0.828833 0.000000 +24.602512 1.202513 0.000000 +24.194157 0.763687 0.000000 +24.658476 1.157052 0.000000 +23.505842 0.763687 0.000000 +22.200001 0.700000 0.000000 +21.505842 0.763687 0.000000 +25.505842 0.763687 0.000000 +24.200001 0.700000 0.000000 +20.505842 1.513687 0.000000 +19.200001 1.450000 0.000000 +19.194157 1.386313 0.000000 +19.721167 1.874574 0.000000 +19.786312 1.044157 0.000000 +19.786312 1.855843 0.000000 +19.850000 1.050000 0.000000 +19.850000 1.850000 0.000000 +19.913687 1.044157 0.000000 +19.913687 1.855843 0.000000 +19.978832 1.025426 0.000000 +20.500000 1.450000 0.000000 +20.041523 0.992948 0.000000 +20.505842 1.386313 0.000000 +20.097486 0.947487 0.000000 +20.524574 1.321167 0.000000 +20.142948 0.891523 0.000000 +20.557051 1.258477 0.000000 +20.175426 0.828833 0.000000 +20.602512 1.202513 0.000000 +20.194157 0.763687 0.000000 +20.658476 1.157052 0.000000 +19.505842 0.763687 0.000000 +18.200001 0.700000 0.000000 +18.500000 1.450000 0.000000 +18.505842 1.513687 0.000000 +17.978832 1.025426 0.000000 +17.913687 1.855843 0.000000 +17.913687 1.044157 0.000000 +17.850000 1.850000 0.000000 +17.850000 1.050000 0.000000 +17.786312 1.855843 0.000000 +17.786312 1.044157 0.000000 +17.721167 1.874574 0.000000 +17.200001 1.450000 0.000000 +17.194157 1.386313 0.000000 +17.721167 1.025426 0.000000 +17.175426 1.321167 0.000000 +17.658476 0.992948 0.000000 +17.142948 1.258477 0.000000 +17.602512 0.947487 0.000000 +17.097486 1.202513 0.000000 +17.557051 0.891523 0.000000 +17.041523 1.157052 0.000000 +17.524574 0.828833 0.000000 +16.978832 1.124574 0.000000 +20.200001 0.700000 0.000000 +17.505842 0.763687 0.000000 +16.200001 0.700000 0.000000 +15.505843 0.763687 0.000000 +14.200000 0.700000 0.000000 +13.505843 0.763687 0.000000 +12.200000 0.700000 0.000000 +11.505843 0.763687 0.000000 +10.200000 0.700000 0.000000 +9.505843 0.763687 0.000000 +8.200000 0.700000 0.000000 +7.505843 0.763687 0.000000 +6.200000 0.700000 0.000000 +5.505843 0.763687 0.000000 +4.200000 0.700000 0.000000 +3.505843 0.763687 0.000000 +2.200000 0.700000 0.000000 +1.658477 1.907052 0.000000 +1.602513 1.952513 0.000000 +1.557052 2.008476 0.000000 +1.524574 2.071167 0.000000 +1.505843 2.136313 0.000000 +1.500000 2.200000 0.000000 +1.505843 2.263687 0.000000 +1.524574 2.328833 0.000000 +1.557052 2.391523 0.000000 +1.602513 2.447487 0.000000 +2.786313 1.794157 0.000000 +2.978833 1.775426 0.000000 +4.786313 1.794157 0.000000 +4.978833 1.775426 0.000000 +6.786313 1.794157 0.000000 +6.978833 1.775426 0.000000 +8.786313 1.794157 0.000000 +8.978833 1.775426 0.000000 +10.786313 1.794157 0.000000 +10.978833 1.775426 0.000000 +12.786313 1.794157 0.000000 +12.978833 1.775426 0.000000 +14.786313 1.794157 0.000000 +14.978833 1.775426 0.000000 +16.786312 1.794157 0.000000 +16.978832 1.775426 0.000000 +18.786312 1.794157 0.000000 +18.978832 1.775426 0.000000 +20.786312 1.794157 0.000000 +20.978832 1.775426 0.000000 +22.786312 1.794157 0.000000 +22.978832 1.775426 0.000000 +24.786312 1.794157 0.000000 +24.978832 1.775426 0.000000 +26.786312 1.794157 0.000000 +26.978832 1.775426 0.000000 +28.786312 1.794157 0.000000 +28.978832 1.775426 0.000000 +30.786312 1.794157 0.000000 +30.978832 1.775426 0.000000 +32.786312 1.794157 0.000000 +32.978832 1.775426 0.000000 +34.786312 1.794157 0.000000 +34.978832 1.775426 0.000000 +36.786312 1.794157 0.000000 +36.978832 1.775426 0.000000 +36.913689 1.105843 0.000000 +36.721169 1.124574 0.000000 +34.913689 1.105843 0.000000 +34.721169 1.124574 0.000000 +32.913689 1.105843 0.000000 +32.721169 1.124574 0.000000 +30.913687 1.105843 0.000000 +30.721167 1.124574 0.000000 +28.913687 1.105843 0.000000 +28.721167 1.124574 0.000000 +26.913687 1.105843 0.000000 +26.721167 1.124574 0.000000 +24.913687 1.105843 0.000000 +24.721167 1.124574 0.000000 +22.913687 1.105843 0.000000 +22.721167 1.124574 0.000000 +20.913687 1.105843 0.000000 +20.721167 1.124574 0.000000 +18.913687 1.105843 0.000000 +18.721167 1.124574 0.000000 +16.913687 1.105843 0.000000 +16.721167 1.124574 0.000000 +14.913687 1.105843 0.000000 +14.721167 1.124574 0.000000 +12.913687 1.105843 0.000000 +12.721167 1.124574 0.000000 +10.913687 1.105843 0.000000 +10.721167 1.124574 0.000000 +8.913687 1.105843 0.000000 +8.721167 1.124574 0.000000 +6.913687 1.105843 0.000000 +6.721167 1.124574 0.000000 +4.913687 1.105843 0.000000 +4.721167 1.124574 0.000000 +2.913687 1.105843 0.000000 +2.721167 1.124574 0.000000 +1.602513 0.452513 0.000000 +1.658477 2.492949 0.000000 +2.200000 2.200000 0.000000 +3.505843 2.263687 0.000000 +4.200000 2.200000 0.000000 +5.505843 2.263687 0.000000 +6.200000 2.200000 0.000000 +7.505843 2.263687 0.000000 +8.200000 2.200000 0.000000 +9.505843 2.263687 0.000000 +10.200000 2.200000 0.000000 +11.505843 2.263687 0.000000 +12.200000 2.200000 0.000000 +13.505843 2.263687 0.000000 +14.200000 2.200000 0.000000 +15.505843 2.263687 0.000000 +16.200001 2.200000 0.000000 +17.505842 2.263687 0.000000 +18.200001 2.200000 0.000000 +19.505842 2.263687 0.000000 +20.200001 2.200000 0.000000 +21.505842 2.263687 0.000000 +22.200001 2.200000 0.000000 +23.505842 2.263687 0.000000 +24.200001 2.200000 0.000000 +25.505842 2.263687 0.000000 +26.200001 2.200000 0.000000 +27.505842 2.263687 0.000000 +28.200001 2.200000 0.000000 +29.505842 2.263687 0.000000 +30.200001 2.200000 0.000000 +31.505842 2.263687 0.000000 +32.200001 2.200000 0.000000 +33.505844 2.263687 0.000000 +34.200001 2.200000 0.000000 +35.505844 2.263687 0.000000 +36.200001 2.200000 0.000000 +37.505844 2.263687 0.000000 +38.041523 1.907052 0.000000 +38.097488 0.947487 0.000000 +37.500000 0.700000 0.000000 +36.194157 0.636313 0.000000 +35.500000 0.700000 0.000000 +34.194157 0.636313 0.000000 +33.500000 0.700000 0.000000 +32.194157 0.636313 0.000000 +31.500000 0.700000 0.000000 +30.194157 0.636313 0.000000 +29.500000 0.700000 0.000000 +28.194157 0.636313 0.000000 +27.500000 0.700000 0.000000 +26.194157 0.636313 0.000000 +25.500000 0.700000 0.000000 +24.194157 0.636313 0.000000 +23.500000 0.700000 0.000000 +22.194157 0.636313 0.000000 +21.500000 0.700000 0.000000 +20.194157 0.636313 0.000000 +19.500000 0.700000 0.000000 +18.194157 0.636313 0.000000 +17.500000 0.700000 0.000000 +16.194157 0.636313 0.000000 +15.500000 0.700000 0.000000 +14.194157 0.636313 0.000000 +13.500000 0.700000 0.000000 +12.194157 0.636313 0.000000 +11.500000 0.700000 0.000000 +10.194157 0.636313 0.000000 +9.500000 0.700000 0.000000 +8.194157 0.636313 0.000000 +7.500000 0.700000 0.000000 +6.194157 0.636313 0.000000 +5.500000 0.700000 0.000000 +4.194157 0.636313 0.000000 +3.500000 0.700000 0.000000 +2.194157 0.636313 0.000000 +2.850000 1.800000 0.000000 +2.913687 1.794157 0.000000 +2.194157 2.263687 0.000000 +3.524574 2.328833 0.000000 +2.175426 2.328833 0.000000 +3.557052 2.391523 0.000000 +2.142948 2.391523 0.000000 +3.602513 2.447487 0.000000 +4.850000 1.800000 0.000000 +4.913687 1.794157 0.000000 +4.194157 2.263687 0.000000 +5.524574 2.328833 0.000000 +4.175426 2.328833 0.000000 +5.557052 2.391523 0.000000 +4.142949 2.391523 0.000000 +5.602513 2.447487 0.000000 +6.850000 1.800000 0.000000 +6.913687 1.794157 0.000000 +6.194157 2.263687 0.000000 +7.524574 2.328833 0.000000 +6.175426 2.328833 0.000000 +7.557052 2.391523 0.000000 +6.142949 2.391523 0.000000 +7.602513 2.447487 0.000000 +8.850000 1.800000 0.000000 +8.913687 1.794157 0.000000 +8.194157 2.263687 0.000000 +9.524574 2.328833 0.000000 +8.175426 2.328833 0.000000 +9.557052 2.391523 0.000000 +8.142948 2.391523 0.000000 +9.602512 2.447487 0.000000 +10.850000 1.800000 0.000000 +10.913687 1.794157 0.000000 +10.194157 2.263687 0.000000 +11.524574 2.328833 0.000000 +10.175426 2.328833 0.000000 +11.557052 2.391523 0.000000 +10.142948 2.391523 0.000000 +11.602512 2.447487 0.000000 +12.850000 1.800000 0.000000 +12.913687 1.794157 0.000000 +12.194157 2.263687 0.000000 +13.524574 2.328833 0.000000 +12.175426 2.328833 0.000000 +13.557052 2.391523 0.000000 +12.142948 2.391523 0.000000 +13.602512 2.447487 0.000000 +14.850000 1.800000 0.000000 +14.913687 1.794157 0.000000 +14.194157 2.263687 0.000000 +15.524574 2.328833 0.000000 +14.175426 2.328833 0.000000 +15.557052 2.391523 0.000000 +14.142948 2.391523 0.000000 +15.602512 2.447487 0.000000 +16.850000 1.800000 0.000000 +16.913687 1.794157 0.000000 +16.194157 2.263687 0.000000 +17.524574 2.328833 0.000000 +16.175426 2.328833 0.000000 +17.557051 2.391523 0.000000 +16.142948 2.391523 0.000000 +17.602512 2.447487 0.000000 +18.850000 1.800000 0.000000 +18.913687 1.794157 0.000000 +18.194157 2.263687 0.000000 +19.524574 2.328833 0.000000 +18.175426 2.328833 0.000000 +19.557051 2.391523 0.000000 +18.142948 2.391523 0.000000 +19.602512 2.447487 0.000000 +20.850000 1.800000 0.000000 +20.913687 1.794157 0.000000 +20.194157 2.263687 0.000000 +21.524574 2.328833 0.000000 +20.175426 2.328833 0.000000 +21.557051 2.391523 0.000000 +20.142948 2.391523 0.000000 +21.602512 2.447487 0.000000 +22.850000 1.800000 0.000000 +22.913687 1.794157 0.000000 +22.194157 2.263687 0.000000 +23.524574 2.328833 0.000000 +22.175426 2.328833 0.000000 +23.557051 2.391523 0.000000 +22.142948 2.391523 0.000000 +23.602512 2.447487 0.000000 +24.850000 1.800000 0.000000 +24.913687 1.794157 0.000000 +24.194157 2.263687 0.000000 +25.524574 2.328833 0.000000 +24.175426 2.328833 0.000000 +25.557051 2.391523 0.000000 +24.142948 2.391523 0.000000 +25.602512 2.447487 0.000000 +26.850000 1.800000 0.000000 +26.913687 1.794157 0.000000 +26.194157 2.263687 0.000000 +27.524574 2.328833 0.000000 +26.175426 2.328833 0.000000 +27.557051 2.391523 0.000000 +26.142948 2.391523 0.000000 +27.602512 2.447487 0.000000 +28.850000 1.800000 0.000000 +28.913687 1.794157 0.000000 +28.194157 2.263687 0.000000 +29.524574 2.328833 0.000000 +28.175426 2.328833 0.000000 +29.557051 2.391523 0.000000 +28.142948 2.391523 0.000000 +29.602512 2.447487 0.000000 +30.850000 1.800000 0.000000 +30.913687 1.794157 0.000000 +30.194157 2.263687 0.000000 +31.524574 2.328833 0.000000 +30.175426 2.328833 0.000000 +31.557051 2.391523 0.000000 +30.142948 2.391523 0.000000 +31.602512 2.447487 0.000000 +32.849998 1.800000 0.000000 +32.913689 1.794157 0.000000 +32.194157 2.263687 0.000000 +33.524574 2.328833 0.000000 +32.175426 2.328833 0.000000 +33.557053 2.391523 0.000000 +32.142948 2.391523 0.000000 +33.602512 2.447487 0.000000 +34.849998 1.800000 0.000000 +34.913689 1.794157 0.000000 +34.194157 2.263687 0.000000 +35.524574 2.328833 0.000000 +34.175426 2.328833 0.000000 +35.557053 2.391523 0.000000 +34.142948 2.391523 0.000000 +35.602512 2.447487 0.000000 +36.849998 1.800000 0.000000 +36.913689 1.794157 0.000000 +36.194157 2.263687 0.000000 +37.524574 2.328833 0.000000 +36.175426 2.328833 0.000000 +37.557053 2.391523 0.000000 +36.142948 2.391523 0.000000 +37.602512 2.447487 0.000000 +36.849998 1.100000 0.000000 +36.786312 1.105843 0.000000 +37.505844 0.636313 0.000000 +36.175426 0.571167 0.000000 +37.524574 0.571167 0.000000 +36.142948 0.508477 0.000000 +37.557053 0.508477 0.000000 +36.097488 0.452513 0.000000 +34.849998 1.100000 0.000000 +34.786312 1.105843 0.000000 +35.505844 0.636313 0.000000 +34.175426 0.571167 0.000000 +35.524574 0.571167 0.000000 +34.142948 0.508477 0.000000 +35.557053 0.508477 0.000000 +34.097488 0.452513 0.000000 +32.849998 1.100000 0.000000 +32.786312 1.105843 0.000000 +33.505844 0.636313 0.000000 +32.175426 0.571167 0.000000 +33.524574 0.571167 0.000000 +32.142948 0.508477 0.000000 +33.557053 0.508477 0.000000 +32.097488 0.452513 0.000000 +30.850000 1.100000 0.000000 +30.786312 1.105843 0.000000 +31.505842 0.636313 0.000000 +30.175426 0.571167 0.000000 +31.524574 0.571167 0.000000 +30.142948 0.508477 0.000000 +31.557051 0.508477 0.000000 +30.097486 0.452513 0.000000 +28.850000 1.100000 0.000000 +28.786312 1.105843 0.000000 +29.505842 0.636313 0.000000 +28.175426 0.571167 0.000000 +29.524574 0.571167 0.000000 +28.142948 0.508477 0.000000 +29.557051 0.508477 0.000000 +28.097486 0.452513 0.000000 +26.850000 1.100000 0.000000 +26.786312 1.105843 0.000000 +27.505842 0.636313 0.000000 +26.175426 0.571167 0.000000 +27.524574 0.571167 0.000000 +26.142948 0.508477 0.000000 +27.557051 0.508477 0.000000 +26.097486 0.452513 0.000000 +24.850000 1.100000 0.000000 +24.786312 1.105843 0.000000 +25.505842 0.636313 0.000000 +24.175426 0.571167 0.000000 +25.524574 0.571167 0.000000 +24.142948 0.508477 0.000000 +25.557051 0.508477 0.000000 +24.097486 0.452513 0.000000 +22.850000 1.100000 0.000000 +22.786312 1.105843 0.000000 +23.505842 0.636313 0.000000 +22.175426 0.571167 0.000000 +23.524574 0.571167 0.000000 +22.142948 0.508477 0.000000 +23.557051 0.508477 0.000000 +22.097486 0.452513 0.000000 +20.850000 1.100000 0.000000 +20.786312 1.105843 0.000000 +21.505842 0.636313 0.000000 +20.175426 0.571167 0.000000 +21.524574 0.571167 0.000000 +20.142948 0.508477 0.000000 +21.557051 0.508477 0.000000 +20.097486 0.452513 0.000000 +18.850000 1.100000 0.000000 +18.786312 1.105843 0.000000 +19.505842 0.636313 0.000000 +18.175426 0.571167 0.000000 +19.524574 0.571167 0.000000 +18.142948 0.508477 0.000000 +19.557051 0.508477 0.000000 +18.097486 0.452513 0.000000 +16.850000 1.100000 0.000000 +16.786312 1.105843 0.000000 +17.505842 0.636313 0.000000 +16.175426 0.571167 0.000000 +17.524574 0.571167 0.000000 +16.142948 0.508477 0.000000 +17.557051 0.508477 0.000000 +16.097486 0.452513 0.000000 +14.850000 1.100000 0.000000 +14.786313 1.105843 0.000000 +15.505843 0.636313 0.000000 +14.175426 0.571167 0.000000 +15.524574 0.571167 0.000000 +14.142948 0.508477 0.000000 +15.557052 0.508477 0.000000 +14.097487 0.452513 0.000000 +12.850000 1.100000 0.000000 +12.786313 1.105843 0.000000 +13.505843 0.636313 0.000000 +12.175426 0.571167 0.000000 +13.524574 0.571167 0.000000 +12.142948 0.508477 0.000000 +13.557052 0.508477 0.000000 +12.097487 0.452513 0.000000 +10.850000 1.100000 0.000000 +10.786313 1.105843 0.000000 +11.505843 0.636313 0.000000 +10.175426 0.571167 0.000000 +11.524574 0.571167 0.000000 +10.142948 0.508477 0.000000 +11.557052 0.508477 0.000000 +10.097487 0.452513 0.000000 +8.850000 1.100000 0.000000 +8.786313 1.105843 0.000000 +9.505843 0.636313 0.000000 +8.175426 0.571167 0.000000 +9.524574 0.571167 0.000000 +8.142948 0.508477 0.000000 +9.557052 0.508477 0.000000 +8.097487 0.452513 0.000000 +6.850000 1.100000 0.000000 +6.786313 1.105843 0.000000 +7.505843 0.636313 0.000000 +6.175426 0.571167 0.000000 +7.524574 0.571167 0.000000 +6.142949 0.508477 0.000000 +7.557052 0.508477 0.000000 +6.097487 0.452513 0.000000 +4.850000 1.100000 0.000000 +4.786313 1.105843 0.000000 +5.505843 0.636313 0.000000 +4.175426 0.571167 0.000000 +5.524574 0.571167 0.000000 +4.142949 0.508477 0.000000 +5.557052 0.508477 0.000000 +4.097487 0.452513 0.000000 +2.850000 1.100000 0.000000 +2.786313 1.105843 0.000000 +3.505843 0.636313 0.000000 +2.175426 0.571167 0.000000 +3.524574 0.571167 0.000000 +2.142948 0.508477 0.000000 +3.557052 0.508477 0.000000 +2.097487 0.452513 0.000000 +1.658477 0.407052 0.000000 +1.721167 2.525426 0.000000 +2.097487 2.447487 0.000000 +3.658477 2.492949 0.000000 +4.097487 2.447487 0.000000 +5.658476 2.492949 0.000000 +6.097487 2.447487 0.000000 +7.658476 2.492949 0.000000 +8.097487 2.447487 0.000000 +9.658477 2.492949 0.000000 +10.097487 2.447487 0.000000 +11.658477 2.492949 0.000000 +12.097487 2.447487 0.000000 +13.658477 2.492949 0.000000 +14.097487 2.447487 0.000000 +15.658477 2.492949 0.000000 +16.097486 2.447487 0.000000 +17.658476 2.492949 0.000000 +18.097486 2.447487 0.000000 +19.658476 2.492949 0.000000 +20.097486 2.447487 0.000000 +21.658476 2.492949 0.000000 +22.097486 2.447487 0.000000 +23.658476 2.492949 0.000000 +24.097486 2.447487 0.000000 +25.658476 2.492949 0.000000 +26.097486 2.447487 0.000000 +27.658476 2.492949 0.000000 +28.097486 2.447487 0.000000 +29.658476 2.492949 0.000000 +30.097486 2.447487 0.000000 +31.658476 2.492949 0.000000 +32.097488 2.447487 0.000000 +33.658478 2.492949 0.000000 +34.097488 2.447487 0.000000 +35.658478 2.492949 0.000000 +36.097488 2.447487 0.000000 +37.658478 2.492949 0.000000 +38.097488 1.952513 0.000000 +38.142948 0.891523 0.000000 +37.602512 0.452513 0.000000 +36.041523 0.407052 0.000000 +35.602512 0.452513 0.000000 +34.041523 0.407052 0.000000 +33.602512 0.452513 0.000000 +32.041523 0.407052 0.000000 +31.602512 0.452513 0.000000 +30.041523 0.407052 0.000000 +29.602512 0.452513 0.000000 +28.041523 0.407052 0.000000 +27.602512 0.452513 0.000000 +26.041523 0.407052 0.000000 +25.602512 0.452513 0.000000 +24.041523 0.407052 0.000000 +23.602512 0.452513 0.000000 +22.041523 0.407052 0.000000 +21.602512 0.452513 0.000000 +20.041523 0.407052 0.000000 +19.602512 0.452513 0.000000 +18.041523 0.407052 0.000000 +17.602512 0.452513 0.000000 +16.041523 0.407052 0.000000 +15.602512 0.452513 0.000000 +14.041523 0.407052 0.000000 +13.602512 0.452513 0.000000 +12.041523 0.407052 0.000000 +11.602512 0.452513 0.000000 +10.041523 0.407052 0.000000 +9.602512 0.452513 0.000000 +8.041523 0.407052 0.000000 +7.602513 0.452513 0.000000 +6.041523 0.407052 0.000000 +5.602513 0.452513 0.000000 +4.041523 0.407052 0.000000 +3.602513 0.452513 0.000000 +2.041523 0.407052 0.000000 +1.721167 0.374574 0.000000 +1.786313 2.544157 0.000000 +2.041523 2.492949 0.000000 +3.721167 2.525426 0.000000 +4.041523 2.492949 0.000000 +5.721167 2.525426 0.000000 +6.041523 2.492949 0.000000 +7.721167 2.525426 0.000000 +8.041523 2.492949 0.000000 +9.721167 2.525426 0.000000 +10.041523 2.492949 0.000000 +11.721167 2.525426 0.000000 +12.041523 2.492949 0.000000 +13.721167 2.525426 0.000000 +14.041523 2.492949 0.000000 +15.721167 2.525426 0.000000 +16.041523 2.492949 0.000000 +17.721167 2.525426 0.000000 +18.041523 2.492949 0.000000 +19.721167 2.525426 0.000000 +20.041523 2.492949 0.000000 +21.721167 2.525426 0.000000 +22.041523 2.492949 0.000000 +23.721167 2.525426 0.000000 +24.041523 2.492949 0.000000 +25.721167 2.525426 0.000000 +26.041523 2.492949 0.000000 +27.721167 2.525426 0.000000 +28.041523 2.492949 0.000000 +29.721167 2.525426 0.000000 +30.041523 2.492949 0.000000 +31.721167 2.525426 0.000000 +32.041523 2.492949 0.000000 +33.721169 2.525426 0.000000 +34.041523 2.492949 0.000000 +35.721169 2.525426 0.000000 +36.041523 2.492949 0.000000 +37.721169 2.525426 0.000000 +38.142948 2.008476 0.000000 +38.175426 0.828833 0.000000 +37.658478 0.407052 0.000000 +35.978832 0.374574 0.000000 +35.658478 0.407052 0.000000 +33.978832 0.374574 0.000000 +33.658478 0.407052 0.000000 +31.978832 0.374574 0.000000 +31.658476 0.407052 0.000000 +29.978832 0.374574 0.000000 +29.658476 0.407052 0.000000 +27.978832 0.374574 0.000000 +27.658476 0.407052 0.000000 +25.978832 0.374574 0.000000 +25.658476 0.407052 0.000000 +23.978832 0.374574 0.000000 +23.658476 0.407052 0.000000 +21.978832 0.374574 0.000000 +21.658476 0.407052 0.000000 +19.978832 0.374574 0.000000 +19.658476 0.407052 0.000000 +17.978832 0.374574 0.000000 +17.658476 0.407052 0.000000 +15.978833 0.374574 0.000000 +15.658477 0.407052 0.000000 +13.978833 0.374574 0.000000 +13.658477 0.407052 0.000000 +11.978833 0.374574 0.000000 +11.658477 0.407052 0.000000 +9.978833 0.374574 0.000000 +9.658477 0.407052 0.000000 +7.978833 0.374574 0.000000 +7.658476 0.407052 0.000000 +5.978833 0.374574 0.000000 +5.658476 0.407052 0.000000 +3.978833 0.374574 0.000000 +3.658477 0.407052 0.000000 +1.978833 0.374574 0.000000 +1.978833 2.525426 0.000000 +3.978833 2.525426 0.000000 +5.978833 2.525426 0.000000 +7.978833 2.525426 0.000000 +9.978833 2.525426 0.000000 +3.786313 2.544157 0.000000 +5.786313 2.544157 0.000000 +7.786313 2.544157 0.000000 +9.786313 2.544157 0.000000 +11.786313 2.544157 0.000000 +11.978833 2.525426 0.000000 +13.978833 2.525426 0.000000 +15.978833 2.525426 0.000000 +13.786313 2.544157 0.000000 +15.786313 2.544157 0.000000 +17.786312 2.544157 0.000000 +17.978832 2.525426 0.000000 +19.978832 2.525426 0.000000 +21.978832 2.525426 0.000000 +23.978832 2.525426 0.000000 +19.786312 2.544157 0.000000 +21.786312 2.544157 0.000000 +23.786312 2.544157 0.000000 +25.786312 2.544157 0.000000 +25.978832 2.525426 0.000000 +27.978832 2.525426 0.000000 +29.978832 2.525426 0.000000 +27.786312 2.544157 0.000000 +29.786312 2.544157 0.000000 +31.786312 2.544157 0.000000 +31.978832 2.525426 0.000000 +33.978832 2.525426 0.000000 +35.978832 2.525426 0.000000 +38.175426 2.071167 0.000000 +33.786312 2.544157 0.000000 +35.786312 2.544157 0.000000 +37.786312 2.544157 0.000000 +38.194157 0.763687 0.000000 +37.721169 0.374574 0.000000 +35.721169 0.374574 0.000000 +33.721169 0.374574 0.000000 +35.913689 0.355843 0.000000 +33.913689 0.355843 0.000000 +31.913687 0.355843 0.000000 +31.721167 0.374574 0.000000 +29.721167 0.374574 0.000000 +27.721167 0.374574 0.000000 +25.721167 0.374574 0.000000 +29.913687 0.355843 0.000000 +27.913687 0.355843 0.000000 +25.913687 0.355843 0.000000 +23.913687 0.355843 0.000000 +23.721167 0.374574 0.000000 +21.721167 0.374574 0.000000 +19.721167 0.374574 0.000000 +21.913687 0.355843 0.000000 +19.913687 0.355843 0.000000 +17.913687 0.355843 0.000000 +17.721167 0.374574 0.000000 +15.721167 0.374574 0.000000 +13.721167 0.374574 0.000000 +11.721167 0.374574 0.000000 +15.913687 0.355843 0.000000 +13.913687 0.355843 0.000000 +11.913687 0.355843 0.000000 +9.913687 0.355843 0.000000 +9.721167 0.374574 0.000000 +7.721167 0.374574 0.000000 +5.721167 0.374574 0.000000 +7.913687 0.355843 0.000000 +5.913687 0.355843 0.000000 +3.913687 0.355843 0.000000 +3.721167 0.374574 0.000000 +1.913687 0.355843 0.000000 +1.786313 0.355843 0.000000 +39.700001 0.000000 0.000000 +1.850000 0.350000 0.000000 +1.850000 2.550000 0.000000 +0.000000 2.900000 0.000000 +1.913687 2.544157 0.000000 +3.850000 2.550000 0.000000 +3.913687 2.544157 0.000000 +5.850000 2.550000 0.000000 +5.913687 2.544157 0.000000 +7.850000 2.550000 0.000000 +7.913687 2.544157 0.000000 +9.850000 2.550000 0.000000 +9.913687 2.544157 0.000000 +11.850000 2.550000 0.000000 +11.913687 2.544157 0.000000 +13.850000 2.550000 0.000000 +13.913687 2.544157 0.000000 +15.850000 2.550000 0.000000 +15.913687 2.544157 0.000000 +17.850000 2.550000 0.000000 +17.913687 2.544157 0.000000 +19.850000 2.550000 0.000000 +19.913687 2.544157 0.000000 +21.850000 2.550000 0.000000 +21.913687 2.544157 0.000000 +23.850000 2.550000 0.000000 +23.913687 2.544157 0.000000 +25.850000 2.550000 0.000000 +25.913687 2.544157 0.000000 +27.850000 2.550000 0.000000 +27.913687 2.544157 0.000000 +29.850000 2.550000 0.000000 +29.913687 2.544157 0.000000 +31.850000 2.550000 0.000000 +31.913687 2.544157 0.000000 +33.849998 2.550000 0.000000 +33.913689 2.544157 0.000000 +35.849998 2.550000 0.000000 +35.913689 2.544157 0.000000 +37.849998 2.550000 0.000000 +37.913689 2.544157 0.000000 +37.978832 2.525426 0.000000 +38.041523 2.492949 0.000000 +38.097488 2.447487 0.000000 +38.142948 2.391523 0.000000 +39.700001 2.900000 0.000000 +38.175426 2.328833 0.000000 +38.194157 2.263687 0.000000 +38.200001 2.200000 0.000000 +38.194157 2.136313 0.000000 +38.200001 0.700000 0.000000 +38.194157 0.636313 0.000000 +38.175426 0.571167 0.000000 +38.142948 0.508477 0.000000 +38.097488 0.452513 0.000000 +38.041523 0.407052 0.000000 +37.978832 0.374574 0.000000 +37.913689 0.355843 0.000000 +37.849998 0.350000 0.000000 +37.786312 0.355843 0.000000 +35.849998 0.350000 0.000000 +35.786312 0.355843 0.000000 +33.849998 0.350000 0.000000 +33.786312 0.355843 0.000000 +31.786312 0.355843 0.000000 +29.786312 0.355843 0.000000 +27.786312 0.355843 0.000000 +25.786312 0.355843 0.000000 +31.850000 0.350000 0.000000 +29.850000 0.350000 0.000000 +27.850000 0.350000 0.000000 +25.850000 0.350000 0.000000 +23.850000 0.350000 0.000000 +23.786312 0.355843 0.000000 +21.786312 0.355843 0.000000 +19.786312 0.355843 0.000000 +21.850000 0.350000 0.000000 +19.850000 0.350000 0.000000 +17.850000 0.350000 0.000000 +17.786312 0.355843 0.000000 +15.786313 0.355843 0.000000 +13.786313 0.355843 0.000000 +11.786313 0.355843 0.000000 +15.850000 0.350000 0.000000 +13.850000 0.350000 0.000000 +11.850000 0.350000 0.000000 +9.850000 0.350000 0.000000 +9.786313 0.355843 0.000000 +7.786313 0.355843 0.000000 +5.786313 0.355843 0.000000 +7.850000 0.350000 0.000000 +5.850000 0.350000 0.000000 +3.850000 0.350000 0.000000 +3.786313 0.355843 0.000000 +19.505842 2.263687 0.000000 +19.500000 2.200000 0.120000 +19.500000 2.200000 0.000000 +19.505842 2.263687 0.120000 +20.200001 2.200000 0.000000 +20.200001 2.200000 0.120000 +20.194157 2.263687 0.000000 +20.175426 2.328833 0.000000 +20.194157 2.263687 0.120000 +20.142948 2.391523 0.000000 +20.175426 2.328833 0.120000 +20.097486 2.447487 0.000000 +20.142948 2.391523 0.120000 +20.041523 2.492949 0.000000 +20.097486 2.447487 0.120000 +20.041523 2.492949 0.120000 +19.978832 2.525426 0.000000 +19.913687 2.544157 0.000000 +19.978832 2.525426 0.120000 +19.850000 2.550000 0.000000 +19.913687 2.544157 0.120000 +19.850000 2.550000 0.120000 +19.786312 2.544157 0.000000 +19.786312 2.544157 0.120000 +19.721167 2.525426 0.000000 +19.721167 2.525426 0.120000 +19.658476 2.492949 0.000000 +19.658476 2.492949 0.120000 +19.602512 2.447487 0.000000 +19.602512 2.447487 0.120000 +19.557051 2.391523 0.000000 +19.524574 2.328833 0.000000 +19.557051 2.391523 0.120000 +19.524574 2.328833 0.120000 +19.505842 0.763687 0.000000 +19.505842 0.763687 0.120000 +19.500000 0.700000 0.120000 +19.500000 0.700000 0.000000 +20.200001 0.700000 0.000000 +20.200001 0.700000 0.120000 +20.194157 0.763687 0.000000 +20.175426 0.828833 0.000000 +20.194157 0.763687 0.120000 +20.142948 0.891523 0.000000 +20.175426 0.828833 0.120000 +20.097486 0.947487 0.000000 +20.142948 0.891523 0.120000 +20.041523 0.992948 0.000000 +20.097486 0.947487 0.120000 +19.978832 1.025426 0.000000 +20.041523 0.992948 0.120000 +19.978832 1.025426 0.120000 +19.913687 1.044157 0.000000 +19.913687 1.044157 0.120000 +19.850000 1.050000 0.000000 +19.850000 1.050000 0.120000 +19.786312 1.044157 0.000000 +19.786312 1.044157 0.120000 +19.721167 1.025426 0.000000 +19.721167 1.025426 0.120000 +19.658476 0.992948 0.000000 +19.658476 0.992948 0.120000 +19.602512 0.947487 0.000000 +19.602512 0.947487 0.120000 +19.557051 0.891523 0.000000 +19.524574 0.828833 0.000000 +19.557051 0.891523 0.120000 +19.524574 0.828833 0.120000 +17.505842 2.263687 0.000000 +17.505842 2.263687 0.120000 +17.500000 2.200000 0.120000 +17.500000 2.200000 0.000000 +18.200001 2.200000 0.000000 +18.200001 2.200000 0.120000 +18.194157 2.263687 0.000000 +18.194157 2.263687 0.120000 +18.175426 2.328833 0.000000 +18.142948 2.391523 0.000000 +18.175426 2.328833 0.120000 +18.142948 2.391523 0.120000 +18.097486 2.447487 0.000000 +18.097486 2.447487 0.120000 +18.041523 2.492949 0.000000 +17.978832 2.525426 0.000000 +18.041523 2.492949 0.120000 +17.978832 2.525426 0.120000 +17.913687 2.544157 0.000000 +17.913687 2.544157 0.120000 +17.850000 2.550000 0.000000 +17.850000 2.550000 0.120000 +17.786312 2.544157 0.000000 +17.786312 2.544157 0.120000 +17.721167 2.525426 0.000000 +17.721167 2.525426 0.120000 +17.658476 2.492949 0.000000 +17.658476 2.492949 0.120000 +17.602512 2.447487 0.000000 +17.602512 2.447487 0.120000 +17.557051 2.391523 0.000000 +17.557051 2.391523 0.120000 +17.524574 2.328833 0.000000 +17.524574 2.328833 0.120000 +17.505842 0.763687 0.000000 +17.505842 0.763687 0.120000 +17.500000 0.700000 0.120000 +17.500000 0.700000 0.000000 +18.200001 0.700000 0.000000 +18.200001 0.700000 0.120000 +18.194157 0.763687 0.000000 +18.175426 0.828833 0.000000 +18.194157 0.763687 0.120000 +18.175426 0.828833 0.120000 +18.142948 0.891523 0.000000 +18.097486 0.947487 0.000000 +18.142948 0.891523 0.120000 +18.097486 0.947487 0.120000 +18.041523 0.992948 0.000000 +18.041523 0.992948 0.120000 +17.978832 1.025426 0.000000 +17.913687 1.044157 0.000000 +17.978832 1.025426 0.120000 +17.850000 1.050000 0.000000 +17.913687 1.044157 0.120000 +17.786312 1.044157 0.000000 +17.850000 1.050000 0.120000 +17.786312 1.044157 0.120000 +17.721167 1.025426 0.000000 +17.721167 1.025426 0.120000 +17.658476 0.992948 0.000000 +17.602512 0.947487 0.000000 +17.658476 0.992948 0.120000 +17.602512 0.947487 0.120000 +17.557051 0.891523 0.000000 +17.557051 0.891523 0.120000 +17.524574 0.828833 0.000000 +17.524574 0.828833 0.120000 +15.602512 2.447487 0.000000 +15.505843 2.263687 0.120000 +15.500000 2.200000 0.120000 +15.500000 2.200000 0.000000 +15.524574 2.328833 0.120000 +15.505843 2.263687 0.000000 +15.524574 2.328833 0.000000 +15.557052 2.391523 0.120000 +15.557052 2.391523 0.000000 +15.602512 2.447487 0.120000 +16.200001 2.200000 0.000000 +16.200001 2.200000 0.120000 +16.194157 2.263687 0.000000 +16.175426 2.328833 0.000000 +16.194157 2.263687 0.120000 +16.175426 2.328833 0.120000 +16.142948 2.391523 0.000000 +16.142948 2.391523 0.120000 +16.097486 2.447487 0.000000 +16.041523 2.492949 0.000000 +16.097486 2.447487 0.120000 +16.041523 2.492949 0.120000 +15.978833 2.525426 0.000000 +15.913687 2.544157 0.000000 +15.978833 2.525426 0.120000 +15.913687 2.544157 0.120000 +15.850000 2.550000 0.000000 +15.850000 2.550000 0.120000 +15.786313 2.544157 0.000000 +15.786313 2.544157 0.120000 +15.721167 2.525426 0.000000 +15.721167 2.525426 0.120000 +15.658477 2.492949 0.000000 +15.658477 2.492949 0.120000 +16.175426 0.828833 0.120000 +16.194157 0.763687 0.000000 +16.200001 0.700000 0.000000 +16.200001 0.700000 0.120000 +16.175426 0.828833 0.000000 +16.194157 0.763687 0.120000 +15.500000 0.700000 0.120000 +15.500000 0.700000 0.000000 +15.505843 0.763687 0.120000 +15.524574 0.828833 0.120000 +15.505843 0.763687 0.000000 +15.557052 0.891523 0.120000 +15.524574 0.828833 0.000000 +15.557052 0.891523 0.000000 +15.602512 0.947487 0.120000 +15.602512 0.947487 0.000000 +15.658477 0.992948 0.120000 +15.658477 0.992948 0.000000 +15.721167 1.025426 0.120000 +15.721167 1.025426 0.000000 +15.786313 1.044157 0.120000 +15.786313 1.044157 0.000000 +15.850000 1.050000 0.120000 +15.850000 1.050000 0.000000 +15.913687 1.044157 0.120000 +15.913687 1.044157 0.000000 +15.978833 1.025426 0.120000 +15.978833 1.025426 0.000000 +16.041523 0.992948 0.120000 +16.041523 0.992948 0.000000 +16.097486 0.947487 0.120000 +16.097486 0.947487 0.000000 +16.142948 0.891523 0.120000 +16.142948 0.891523 0.000000 +14.175426 2.328833 0.120000 +14.194157 2.263687 0.000000 +14.200000 2.200000 0.000000 +14.200000 2.200000 0.120000 +14.175426 2.328833 0.000000 +14.194157 2.263687 0.120000 +13.505843 2.263687 0.120000 +13.500000 2.200000 0.120000 +13.500000 2.200000 0.000000 +13.524574 2.328833 0.120000 +13.505843 2.263687 0.000000 +13.524574 2.328833 0.000000 +13.557052 2.391523 0.120000 +13.557052 2.391523 0.000000 +13.602512 2.447487 0.120000 +13.602512 2.447487 0.000000 +13.658477 2.492949 0.120000 +13.658477 2.492949 0.000000 +13.721167 2.525426 0.120000 +13.786313 2.544157 0.120000 +13.721167 2.525426 0.000000 +13.786313 2.544157 0.000000 +13.850000 2.550000 0.120000 +13.850000 2.550000 0.000000 +13.913687 2.544157 0.120000 +13.913687 2.544157 0.000000 +13.978833 2.525426 0.120000 +13.978833 2.525426 0.000000 +14.041523 2.492949 0.120000 +14.041523 2.492949 0.000000 +14.097487 2.447487 0.120000 +14.097487 2.447487 0.000000 +14.142948 2.391523 0.120000 +14.142948 2.391523 0.000000 +13.500000 0.700000 0.120000 +13.500000 0.700000 0.000000 +14.194157 0.763687 0.000000 +14.200000 0.700000 0.000000 +14.200000 0.700000 0.120000 +14.194157 0.763687 0.120000 +14.175426 0.828833 0.000000 +14.175426 0.828833 0.120000 +14.142948 0.891523 0.000000 +14.097487 0.947487 0.000000 +14.142948 0.891523 0.120000 +14.041523 0.992948 0.000000 +14.097487 0.947487 0.120000 +13.978833 1.025426 0.000000 +14.041523 0.992948 0.120000 +13.913687 1.044157 0.000000 +13.978833 1.025426 0.120000 +13.850000 1.050000 0.000000 +13.913687 1.044157 0.120000 +13.786313 1.044157 0.000000 +13.850000 1.050000 0.120000 +13.786313 1.044157 0.120000 +13.721167 1.025426 0.000000 +13.658477 0.992948 0.000000 +13.721167 1.025426 0.120000 +13.602512 0.947487 0.000000 +13.658477 0.992948 0.120000 +13.557052 0.891523 0.000000 +13.602512 0.947487 0.120000 +13.557052 0.891523 0.120000 +13.524574 0.828833 0.000000 +13.524574 0.828833 0.120000 +13.505843 0.763687 0.000000 +13.505843 0.763687 0.120000 +11.786313 2.544157 0.000000 +12.194157 2.263687 0.000000 +12.200000 2.200000 0.000000 +12.200000 2.200000 0.120000 +12.194157 2.263687 0.120000 +12.175426 2.328833 0.000000 +12.142948 2.391523 0.000000 +12.175426 2.328833 0.120000 +12.142948 2.391523 0.120000 +12.097487 2.447487 0.000000 +12.041523 2.492949 0.000000 +12.097487 2.447487 0.120000 +11.978833 2.525426 0.000000 +12.041523 2.492949 0.120000 +11.913687 2.544157 0.000000 +11.978833 2.525426 0.120000 +11.850000 2.550000 0.000000 +11.913687 2.544157 0.120000 +11.505843 2.263687 0.120000 +11.500000 2.200000 0.120000 +11.500000 2.200000 0.000000 +11.524574 2.328833 0.120000 +11.505843 2.263687 0.000000 +11.557052 2.391523 0.120000 +11.524574 2.328833 0.000000 +11.557052 2.391523 0.000000 +11.602512 2.447487 0.120000 +11.602512 2.447487 0.000000 +11.658477 2.492949 0.120000 +11.721167 2.525426 0.120000 +11.658477 2.492949 0.000000 +11.721167 2.525426 0.000000 +11.786313 2.544157 0.120000 +11.850000 2.550000 0.120000 +11.500000 0.700000 0.120000 +11.500000 0.700000 0.000000 +12.200000 0.700000 0.000000 +12.200000 0.700000 0.120000 +12.194157 0.763687 0.000000 +12.194157 0.763687 0.120000 +12.175426 0.828833 0.000000 +12.175426 0.828833 0.120000 +12.142948 0.891523 0.000000 +12.097487 0.947487 0.000000 +12.142948 0.891523 0.120000 +12.041523 0.992948 0.000000 +12.097487 0.947487 0.120000 +11.978833 1.025426 0.000000 +12.041523 0.992948 0.120000 +11.913687 1.044157 0.000000 +11.978833 1.025426 0.120000 +11.913687 1.044157 0.120000 +11.850000 1.050000 0.000000 +11.786313 1.044157 0.000000 +11.850000 1.050000 0.120000 +11.721167 1.025426 0.000000 +11.786313 1.044157 0.120000 +11.658477 0.992948 0.000000 +11.721167 1.025426 0.120000 +11.602512 0.947487 0.000000 +11.658477 0.992948 0.120000 +11.602512 0.947487 0.120000 +11.557052 0.891523 0.000000 +11.557052 0.891523 0.120000 +11.524574 0.828833 0.000000 +11.524574 0.828833 0.120000 +11.505843 0.763687 0.000000 +11.505843 0.763687 0.120000 +9.505843 2.263687 0.000000 +9.500000 2.200000 0.120000 +9.500000 2.200000 0.000000 +9.505843 2.263687 0.120000 +10.200000 2.200000 0.000000 +10.200000 2.200000 0.120000 +10.194157 2.263687 0.000000 +10.194157 2.263687 0.120000 +10.175426 2.328833 0.000000 +10.175426 2.328833 0.120000 +10.142948 2.391523 0.000000 +10.097487 2.447487 0.000000 +10.142948 2.391523 0.120000 +10.041523 2.492949 0.000000 +10.097487 2.447487 0.120000 +9.978833 2.525426 0.000000 +10.041523 2.492949 0.120000 +9.978833 2.525426 0.120000 +9.913687 2.544157 0.000000 +9.913687 2.544157 0.120000 +9.850000 2.550000 0.000000 +9.786313 2.544157 0.000000 +9.850000 2.550000 0.120000 +9.721167 2.525426 0.000000 +9.786313 2.544157 0.120000 +9.658477 2.492949 0.000000 +9.721167 2.525426 0.120000 +9.658477 2.492949 0.120000 +9.602512 2.447487 0.000000 +9.557052 2.391523 0.000000 +9.602512 2.447487 0.120000 +9.557052 2.391523 0.120000 +9.524574 2.328833 0.000000 +9.524574 2.328833 0.120000 +9.500000 0.700000 0.120000 +9.500000 0.700000 0.000000 +10.200000 0.700000 0.000000 +10.200000 0.700000 0.120000 +10.194157 0.763687 0.000000 +10.194157 0.763687 0.120000 +10.175426 0.828833 0.000000 +10.175426 0.828833 0.120000 +10.142948 0.891523 0.000000 +10.097487 0.947487 0.000000 +10.142948 0.891523 0.120000 +10.041523 0.992948 0.000000 +10.097487 0.947487 0.120000 +9.978833 1.025426 0.000000 +10.041523 0.992948 0.120000 +9.913687 1.044157 0.000000 +9.978833 1.025426 0.120000 +9.850000 1.050000 0.000000 +9.913687 1.044157 0.120000 +9.786313 1.044157 0.000000 +9.850000 1.050000 0.120000 +9.786313 1.044157 0.120000 +9.721167 1.025426 0.000000 +9.658477 0.992948 0.000000 +9.721167 1.025426 0.120000 +9.658477 0.992948 0.120000 +9.602512 0.947487 0.000000 +9.602512 0.947487 0.120000 +9.557052 0.891523 0.000000 +9.557052 0.891523 0.120000 +9.524574 0.828833 0.000000 +9.524574 0.828833 0.120000 +9.505843 0.763687 0.000000 +9.505843 0.763687 0.120000 +7.500000 2.200000 0.120000 +7.500000 2.200000 0.000000 +8.194157 2.263687 0.000000 +8.200000 2.200000 0.000000 +8.200000 2.200000 0.120000 +8.194157 2.263687 0.120000 +8.175426 2.328833 0.000000 +8.175426 2.328833 0.120000 +8.142948 2.391523 0.000000 +8.097487 2.447487 0.000000 +8.142948 2.391523 0.120000 +8.041523 2.492949 0.000000 +8.097487 2.447487 0.120000 +7.978833 2.525426 0.000000 +8.041523 2.492949 0.120000 +7.913687 2.544157 0.000000 +7.978833 2.525426 0.120000 +7.913687 2.544157 0.120000 +7.850000 2.550000 0.000000 +7.786313 2.544157 0.000000 +7.850000 2.550000 0.120000 +7.786313 2.544157 0.120000 +7.721167 2.525426 0.000000 +7.658476 2.492949 0.000000 +7.721167 2.525426 0.120000 +7.658476 2.492949 0.120000 +7.602513 2.447487 0.000000 +7.602513 2.447487 0.120000 +7.557052 2.391523 0.000000 +7.557052 2.391523 0.120000 +7.524574 2.328833 0.000000 +7.524574 2.328833 0.120000 +7.505843 2.263687 0.000000 +7.505843 2.263687 0.120000 +7.500000 0.700000 0.120000 +7.500000 0.700000 0.000000 +8.194157 0.763687 0.000000 +8.200000 0.700000 0.000000 +8.200000 0.700000 0.120000 +8.175426 0.828833 0.000000 +8.194157 0.763687 0.120000 +8.142948 0.891523 0.000000 +8.175426 0.828833 0.120000 +8.097487 0.947487 0.000000 +8.142948 0.891523 0.120000 +8.041523 0.992948 0.000000 +8.097487 0.947487 0.120000 +8.041523 0.992948 0.120000 +7.978833 1.025426 0.000000 +7.978833 1.025426 0.120000 +7.913687 1.044157 0.000000 +7.913687 1.044157 0.120000 +7.850000 1.050000 0.000000 +7.850000 1.050000 0.120000 +7.786313 1.044157 0.000000 +7.786313 1.044157 0.120000 +7.721167 1.025426 0.000000 +7.721167 1.025426 0.120000 +7.658476 0.992948 0.000000 +7.602513 0.947487 0.000000 +7.658476 0.992948 0.120000 +7.602513 0.947487 0.120000 +7.557052 0.891523 0.000000 +7.557052 0.891523 0.120000 +7.524574 0.828833 0.000000 +7.524574 0.828833 0.120000 +7.505843 0.763687 0.000000 +7.505843 0.763687 0.120000 +5.524574 2.328833 0.120000 +5.505843 2.263687 0.120000 +5.500000 2.200000 0.120000 +5.500000 2.200000 0.000000 +6.200000 2.200000 0.000000 +6.200000 2.200000 0.120000 +6.194157 2.263687 0.000000 +6.175426 2.328833 0.000000 +6.194157 2.263687 0.120000 +6.142949 2.391523 0.000000 +6.175426 2.328833 0.120000 +6.097487 2.447487 0.000000 +6.142949 2.391523 0.120000 +6.097487 2.447487 0.120000 +6.041523 2.492949 0.000000 +6.041523 2.492949 0.120000 +5.978833 2.525426 0.000000 +5.978833 2.525426 0.120000 +5.913687 2.544157 0.000000 +5.913687 2.544157 0.120000 +5.850000 2.550000 0.000000 +5.786313 2.544157 0.000000 +5.850000 2.550000 0.120000 +5.721167 2.525426 0.000000 +5.786313 2.544157 0.120000 +5.658476 2.492949 0.000000 +5.721167 2.525426 0.120000 +5.602513 2.447487 0.000000 +5.658476 2.492949 0.120000 +5.602513 2.447487 0.120000 +5.557052 2.391523 0.000000 +5.524574 2.328833 0.000000 +5.557052 2.391523 0.120000 +5.505843 2.263687 0.000000 +5.505843 0.763687 0.000000 +5.500000 0.700000 0.120000 +5.500000 0.700000 0.000000 +5.505843 0.763687 0.120000 +6.200000 0.700000 0.000000 +6.200000 0.700000 0.120000 +6.194157 0.763687 0.000000 +6.194157 0.763687 0.120000 +6.175426 0.828833 0.000000 +6.175426 0.828833 0.120000 +6.142949 0.891523 0.000000 +6.097487 0.947487 0.000000 +6.142949 0.891523 0.120000 +6.097487 0.947487 0.120000 +6.041523 0.992948 0.000000 +5.978833 1.025426 0.000000 +6.041523 0.992948 0.120000 +5.913687 1.044157 0.000000 +5.978833 1.025426 0.120000 +5.850000 1.050000 0.000000 +5.913687 1.044157 0.120000 +5.850000 1.050000 0.120000 +5.786313 1.044157 0.000000 +5.721167 1.025426 0.000000 +5.786313 1.044157 0.120000 +5.721167 1.025426 0.120000 +5.658476 0.992948 0.000000 +5.658476 0.992948 0.120000 +5.602513 0.947487 0.000000 +5.602513 0.947487 0.120000 +5.557052 0.891523 0.000000 +5.557052 0.891523 0.120000 +5.524574 0.828833 0.000000 +5.524574 0.828833 0.120000 +3.505843 2.263687 0.000000 +3.500000 2.200000 0.120000 +3.500000 2.200000 0.000000 +3.505843 2.263687 0.120000 +4.200000 2.200000 0.000000 +4.200000 2.200000 0.120000 +4.194157 2.263687 0.000000 +4.175426 2.328833 0.000000 +4.194157 2.263687 0.120000 +4.142949 2.391523 0.000000 +4.175426 2.328833 0.120000 +4.142949 2.391523 0.120000 +4.097487 2.447487 0.000000 +4.097487 2.447487 0.120000 +4.041523 2.492949 0.000000 +4.041523 2.492949 0.120000 +3.978833 2.525426 0.000000 +3.978833 2.525426 0.120000 +3.913687 2.544157 0.000000 +3.913687 2.544157 0.120000 +3.850000 2.550000 0.000000 +3.850000 2.550000 0.120000 +3.786313 2.544157 0.000000 +3.786313 2.544157 0.120000 +3.721167 2.525426 0.000000 +3.721167 2.525426 0.120000 +3.658477 2.492949 0.000000 +3.658477 2.492949 0.120000 +3.602513 2.447487 0.000000 +3.557052 2.391523 0.000000 +3.602513 2.447487 0.120000 +3.557052 2.391523 0.120000 +3.524574 2.328833 0.000000 +3.524574 2.328833 0.120000 +3.500000 0.700000 0.120000 +3.500000 0.700000 0.000000 +4.194157 0.763687 0.000000 +4.200000 0.700000 0.000000 +4.200000 0.700000 0.120000 +4.194157 0.763687 0.120000 +4.175426 0.828833 0.000000 +4.175426 0.828833 0.120000 +4.142949 0.891523 0.000000 +4.142949 0.891523 0.120000 +4.097487 0.947487 0.000000 +4.097487 0.947487 0.120000 +4.041523 0.992948 0.000000 +4.041523 0.992948 0.120000 +3.978833 1.025426 0.000000 +3.978833 1.025426 0.120000 +3.913687 1.044157 0.000000 +3.913687 1.044157 0.120000 +3.850000 1.050000 0.000000 +3.850000 1.050000 0.120000 +3.786313 1.044157 0.000000 +3.786313 1.044157 0.120000 +3.721167 1.025426 0.000000 +3.721167 1.025426 0.120000 +3.658477 0.992948 0.000000 +3.658477 0.992948 0.120000 +3.602513 0.947487 0.000000 +3.602513 0.947487 0.120000 +3.557052 0.891523 0.000000 +3.557052 0.891523 0.120000 +3.524574 0.828833 0.000000 +3.524574 0.828833 0.120000 +3.505843 0.763687 0.000000 +3.505843 0.763687 0.120000 +1.500000 2.200000 0.120000 +1.500000 2.200000 0.000000 +2.200000 2.200000 0.000000 +2.200000 2.200000 0.120000 +2.194157 2.263687 0.000000 +2.175426 2.328833 0.000000 +2.194157 2.263687 0.120000 +2.142948 2.391523 0.000000 +2.175426 2.328833 0.120000 +2.097487 2.447487 0.000000 +2.142948 2.391523 0.120000 +2.041523 2.492949 0.000000 +2.097487 2.447487 0.120000 +2.041523 2.492949 0.120000 +1.978833 2.525426 0.000000 +1.978833 2.525426 0.120000 +1.913687 2.544157 0.000000 +1.913687 2.544157 0.120000 +1.850000 2.550000 0.000000 +1.786313 2.544157 0.000000 +1.850000 2.550000 0.120000 +1.786313 2.544157 0.120000 +1.721167 2.525426 0.000000 +1.658477 2.492949 0.000000 +1.721167 2.525426 0.120000 +1.602513 2.447487 0.000000 +1.658477 2.492949 0.120000 +1.557052 2.391523 0.000000 +1.602513 2.447487 0.120000 +1.524574 2.328833 0.000000 +1.557052 2.391523 0.120000 +1.524574 2.328833 0.120000 +1.505843 2.263687 0.000000 +1.505843 2.263687 0.120000 +2.194157 0.763687 0.000000 +2.200000 0.700000 0.000000 +1.505843 0.763687 0.120000 +1.500000 0.700000 0.120000 +1.500000 0.700000 0.000000 +1.505843 0.763687 0.000000 +1.524574 0.828833 0.120000 +1.524574 0.828833 0.000000 +1.557052 0.891523 0.120000 +1.557052 0.891523 0.000000 +1.602513 0.947487 0.120000 +1.602513 0.947487 0.000000 +1.658477 0.992948 0.120000 +1.658477 0.992948 0.000000 +1.721167 1.025426 0.120000 +1.786313 1.044157 0.120000 +1.721167 1.025426 0.000000 +1.786313 1.044157 0.000000 +1.850000 1.050000 0.120000 +1.850000 1.050000 0.000000 +1.913687 1.044157 0.120000 +1.913687 1.044157 0.000000 +1.978833 1.025426 0.120000 +1.978833 1.025426 0.000000 +2.041523 0.992948 0.120000 +2.097487 0.947487 0.120000 +2.041523 0.992948 0.000000 +2.142948 0.891523 0.120000 +2.097487 0.947487 0.000000 +2.175426 0.828833 0.120000 +2.142948 0.891523 0.000000 +2.194157 0.763687 0.120000 +2.175426 0.828833 0.000000 +2.200000 0.700000 0.120000 +21.505842 2.263687 0.000000 +21.500000 2.200000 0.120000 +21.500000 2.200000 0.000000 +21.505842 2.263687 0.120000 +22.200001 2.200000 0.000000 +22.200001 2.200000 0.120000 +22.194157 2.263687 0.000000 +22.194157 2.263687 0.120000 +22.175426 2.328833 0.000000 +22.175426 2.328833 0.120000 +22.142948 2.391523 0.000000 +22.097486 2.447487 0.000000 +22.142948 2.391523 0.120000 +22.097486 2.447487 0.120000 +22.041523 2.492949 0.000000 +22.041523 2.492949 0.120000 +21.978832 2.525426 0.000000 +21.978832 2.525426 0.120000 +21.913687 2.544157 0.000000 +21.913687 2.544157 0.120000 +21.850000 2.550000 0.000000 +21.850000 2.550000 0.120000 +21.786312 2.544157 0.000000 +21.786312 2.544157 0.120000 +21.721167 2.525426 0.000000 +21.721167 2.525426 0.120000 +21.658476 2.492949 0.000000 +21.658476 2.492949 0.120000 +21.602512 2.447487 0.000000 +21.602512 2.447487 0.120000 +21.557051 2.391523 0.000000 +21.557051 2.391523 0.120000 +21.524574 2.328833 0.000000 +21.524574 2.328833 0.120000 +21.557051 0.891523 0.000000 +21.505842 0.763687 0.120000 +21.500000 0.700000 0.120000 +21.500000 0.700000 0.000000 +21.505842 0.763687 0.000000 +21.524574 0.828833 0.120000 +21.557051 0.891523 0.120000 +21.524574 0.828833 0.000000 +22.200001 0.700000 0.000000 +22.200001 0.700000 0.120000 +22.194157 0.763687 0.000000 +22.175426 0.828833 0.000000 +22.194157 0.763687 0.120000 +22.175426 0.828833 0.120000 +22.142948 0.891523 0.000000 +22.097486 0.947487 0.000000 +22.142948 0.891523 0.120000 +22.041523 0.992948 0.000000 +22.097486 0.947487 0.120000 +22.041523 0.992948 0.120000 +21.978832 1.025426 0.000000 +21.978832 1.025426 0.120000 +21.913687 1.044157 0.000000 +21.913687 1.044157 0.120000 +21.850000 1.050000 0.000000 +21.850000 1.050000 0.120000 +21.786312 1.044157 0.000000 +21.786312 1.044157 0.120000 +21.721167 1.025426 0.000000 +21.721167 1.025426 0.120000 +21.658476 0.992948 0.000000 +21.658476 0.992948 0.120000 +21.602512 0.947487 0.000000 +21.602512 0.947487 0.120000 +23.524574 2.328833 0.000000 +23.500000 2.200000 0.120000 +23.500000 2.200000 0.000000 +23.505842 2.263687 0.120000 +23.505842 2.263687 0.000000 +23.524574 2.328833 0.120000 +24.200001 2.200000 0.000000 +24.200001 2.200000 0.120000 +24.194157 2.263687 0.000000 +24.194157 2.263687 0.120000 +24.175426 2.328833 0.000000 +24.175426 2.328833 0.120000 +24.142948 2.391523 0.000000 +24.097486 2.447487 0.000000 +24.142948 2.391523 0.120000 +24.097486 2.447487 0.120000 +24.041523 2.492949 0.000000 +24.041523 2.492949 0.120000 +23.978832 2.525426 0.000000 +23.978832 2.525426 0.120000 +23.913687 2.544157 0.000000 +23.850000 2.550000 0.000000 +23.913687 2.544157 0.120000 +23.786312 2.544157 0.000000 +23.850000 2.550000 0.120000 +23.721167 2.525426 0.000000 +23.786312 2.544157 0.120000 +23.658476 2.492949 0.000000 +23.721167 2.525426 0.120000 +23.658476 2.492949 0.120000 +23.602512 2.447487 0.000000 +23.602512 2.447487 0.120000 +23.557051 2.391523 0.000000 +23.557051 2.391523 0.120000 +23.505842 0.763687 0.000000 +23.505842 0.763687 0.120000 +23.500000 0.700000 0.120000 +23.500000 0.700000 0.000000 +24.200001 0.700000 0.000000 +24.200001 0.700000 0.120000 +24.194157 0.763687 0.000000 +24.175426 0.828833 0.000000 +24.194157 0.763687 0.120000 +24.142948 0.891523 0.000000 +24.175426 0.828833 0.120000 +24.097486 0.947487 0.000000 +24.142948 0.891523 0.120000 +24.041523 0.992948 0.000000 +24.097486 0.947487 0.120000 +23.978832 1.025426 0.000000 +24.041523 0.992948 0.120000 +23.978832 1.025426 0.120000 +23.913687 1.044157 0.000000 +23.913687 1.044157 0.120000 +23.850000 1.050000 0.000000 +23.850000 1.050000 0.120000 +23.786312 1.044157 0.000000 +23.786312 1.044157 0.120000 +23.721167 1.025426 0.000000 +23.721167 1.025426 0.120000 +23.658476 0.992948 0.000000 +23.658476 0.992948 0.120000 +23.602512 0.947487 0.000000 +23.602512 0.947487 0.120000 +23.557051 0.891523 0.000000 +23.524574 0.828833 0.000000 +23.557051 0.891523 0.120000 +23.524574 0.828833 0.120000 +25.505842 2.263687 0.000000 +25.500000 2.200000 0.120000 +25.500000 2.200000 0.000000 +25.505842 2.263687 0.120000 +26.200001 2.200000 0.000000 +26.200001 2.200000 0.120000 +26.194157 2.263687 0.000000 +26.175426 2.328833 0.000000 +26.194157 2.263687 0.120000 +26.175426 2.328833 0.120000 +26.142948 2.391523 0.000000 +26.142948 2.391523 0.120000 +26.097486 2.447487 0.000000 +26.097486 2.447487 0.120000 +26.041523 2.492949 0.000000 +26.041523 2.492949 0.120000 +25.978832 2.525426 0.000000 +25.913687 2.544157 0.000000 +25.978832 2.525426 0.120000 +25.913687 2.544157 0.120000 +25.850000 2.550000 0.000000 +25.850000 2.550000 0.120000 +25.786312 2.544157 0.000000 +25.721167 2.525426 0.000000 +25.786312 2.544157 0.120000 +25.721167 2.525426 0.120000 +25.658476 2.492949 0.000000 +25.658476 2.492949 0.120000 +25.602512 2.447487 0.000000 +25.602512 2.447487 0.120000 +25.557051 2.391523 0.000000 +25.524574 2.328833 0.000000 +25.557051 2.391523 0.120000 +25.524574 2.328833 0.120000 +25.505842 0.763687 0.000000 +25.505842 0.763687 0.120000 +25.500000 0.700000 0.120000 +25.500000 0.700000 0.000000 +26.200001 0.700000 0.000000 +26.200001 0.700000 0.120000 +26.194157 0.763687 0.000000 +26.175426 0.828833 0.000000 +26.194157 0.763687 0.120000 +26.175426 0.828833 0.120000 +26.142948 0.891523 0.000000 +26.097486 0.947487 0.000000 +26.142948 0.891523 0.120000 +26.097486 0.947487 0.120000 +26.041523 0.992948 0.000000 +26.041523 0.992948 0.120000 +25.978832 1.025426 0.000000 +25.913687 1.044157 0.000000 +25.978832 1.025426 0.120000 +25.913687 1.044157 0.120000 +25.850000 1.050000 0.000000 +25.850000 1.050000 0.120000 +25.786312 1.044157 0.000000 +25.786312 1.044157 0.120000 +25.721167 1.025426 0.000000 +25.721167 1.025426 0.120000 +25.658476 0.992948 0.000000 +25.658476 0.992948 0.120000 +25.602512 0.947487 0.000000 +25.557051 0.891523 0.000000 +25.602512 0.947487 0.120000 +25.557051 0.891523 0.120000 +25.524574 0.828833 0.000000 +25.524574 0.828833 0.120000 +28.097486 2.447487 0.120000 +28.194157 2.263687 0.000000 +28.200001 2.200000 0.000000 +28.200001 2.200000 0.120000 +28.175426 2.328833 0.000000 +28.194157 2.263687 0.120000 +28.175426 2.328833 0.120000 +28.142948 2.391523 0.000000 +28.142948 2.391523 0.120000 +28.097486 2.447487 0.000000 +27.500000 2.200000 0.120000 +27.500000 2.200000 0.000000 +27.505842 2.263687 0.120000 +27.505842 2.263687 0.000000 +27.524574 2.328833 0.120000 +27.524574 2.328833 0.000000 +27.557051 2.391523 0.120000 +27.557051 2.391523 0.000000 +27.602512 2.447487 0.120000 +27.658476 2.492949 0.120000 +27.602512 2.447487 0.000000 +27.658476 2.492949 0.000000 +27.721167 2.525426 0.120000 +27.721167 2.525426 0.000000 +27.786312 2.544157 0.120000 +27.786312 2.544157 0.000000 +27.850000 2.550000 0.120000 +27.850000 2.550000 0.000000 +27.913687 2.544157 0.120000 +27.913687 2.544157 0.000000 +27.978832 2.525426 0.120000 +27.978832 2.525426 0.000000 +28.041523 2.492949 0.120000 +28.041523 2.492949 0.000000 +27.505842 0.763687 0.000000 +27.505842 0.763687 0.120000 +27.500000 0.700000 0.120000 +27.500000 0.700000 0.000000 +28.200001 0.700000 0.000000 +28.200001 0.700000 0.120000 +28.194157 0.763687 0.000000 +28.175426 0.828833 0.000000 +28.194157 0.763687 0.120000 +28.142948 0.891523 0.000000 +28.175426 0.828833 0.120000 +28.097486 0.947487 0.000000 +28.142948 0.891523 0.120000 +28.041523 0.992948 0.000000 +28.097486 0.947487 0.120000 +27.978832 1.025426 0.000000 +28.041523 0.992948 0.120000 +27.978832 1.025426 0.120000 +27.913687 1.044157 0.000000 +27.913687 1.044157 0.120000 +27.850000 1.050000 0.000000 +27.850000 1.050000 0.120000 +27.786312 1.044157 0.000000 +27.721167 1.025426 0.000000 +27.786312 1.044157 0.120000 +27.721167 1.025426 0.120000 +27.658476 0.992948 0.000000 +27.658476 0.992948 0.120000 +27.602512 0.947487 0.000000 +27.602512 0.947487 0.120000 +27.557051 0.891523 0.000000 +27.524574 0.828833 0.000000 +27.557051 0.891523 0.120000 +27.524574 0.828833 0.120000 +30.142948 2.391523 0.000000 +30.194157 2.263687 0.000000 +30.200001 2.200000 0.000000 +30.200001 2.200000 0.120000 +30.194157 2.263687 0.120000 +30.175426 2.328833 0.000000 +29.505842 2.263687 0.120000 +29.500000 2.200000 0.120000 +29.500000 2.200000 0.000000 +29.524574 2.328833 0.120000 +29.505842 2.263687 0.000000 +29.524574 2.328833 0.000000 +29.557051 2.391523 0.120000 +29.602512 2.447487 0.120000 +29.557051 2.391523 0.000000 +29.602512 2.447487 0.000000 +29.658476 2.492949 0.120000 +29.658476 2.492949 0.000000 +29.721167 2.525426 0.120000 +29.721167 2.525426 0.000000 +29.786312 2.544157 0.120000 +29.786312 2.544157 0.000000 +29.850000 2.550000 0.120000 +29.850000 2.550000 0.000000 +29.913687 2.544157 0.120000 +29.913687 2.544157 0.000000 +29.978832 2.525426 0.120000 +29.978832 2.525426 0.000000 +30.041523 2.492949 0.120000 +30.041523 2.492949 0.000000 +30.097486 2.447487 0.120000 +30.142948 2.391523 0.120000 +30.097486 2.447487 0.000000 +30.175426 2.328833 0.120000 +29.557051 0.891523 0.120000 +29.505842 0.763687 0.120000 +29.500000 0.700000 0.120000 +29.500000 0.700000 0.000000 +29.505842 0.763687 0.000000 +29.524574 0.828833 0.120000 +30.200001 0.700000 0.000000 +30.200001 0.700000 0.120000 +30.194157 0.763687 0.000000 +30.175426 0.828833 0.000000 +30.194157 0.763687 0.120000 +30.142948 0.891523 0.000000 +30.175426 0.828833 0.120000 +30.097486 0.947487 0.000000 +30.142948 0.891523 0.120000 +30.041523 0.992948 0.000000 +30.097486 0.947487 0.120000 +30.041523 0.992948 0.120000 +29.978832 1.025426 0.000000 +29.978832 1.025426 0.120000 +29.913687 1.044157 0.000000 +29.850000 1.050000 0.000000 +29.913687 1.044157 0.120000 +29.786312 1.044157 0.000000 +29.850000 1.050000 0.120000 +29.721167 1.025426 0.000000 +29.786312 1.044157 0.120000 +29.658476 0.992948 0.000000 +29.721167 1.025426 0.120000 +29.658476 0.992948 0.120000 +29.602512 0.947487 0.000000 +29.602512 0.947487 0.120000 +29.557051 0.891523 0.000000 +29.524574 0.828833 0.000000 +31.913687 2.544157 0.120000 +32.194157 2.263687 0.000000 +32.200001 2.200000 0.000000 +32.200001 2.200000 0.120000 +32.194157 2.263687 0.120000 +32.175426 2.328833 0.000000 +32.142948 2.391523 0.000000 +32.175426 2.328833 0.120000 +32.142948 2.391523 0.120000 +32.097488 2.447487 0.000000 +32.097488 2.447487 0.120000 +32.041523 2.492949 0.000000 +31.978832 2.525426 0.000000 +32.041523 2.492949 0.120000 +31.913687 2.544157 0.000000 +31.978832 2.525426 0.120000 +31.500000 2.200000 0.120000 +31.500000 2.200000 0.000000 +31.505842 2.263687 0.120000 +31.505842 2.263687 0.000000 +31.524574 2.328833 0.120000 +31.524574 2.328833 0.000000 +31.557051 2.391523 0.120000 +31.557051 2.391523 0.000000 +31.602512 2.447487 0.120000 +31.658476 2.492949 0.120000 +31.602512 2.447487 0.000000 +31.658476 2.492949 0.000000 +31.721167 2.525426 0.120000 +31.721167 2.525426 0.000000 +31.786312 2.544157 0.120000 +31.786312 2.544157 0.000000 +31.850000 2.550000 0.120000 +31.850000 2.550000 0.000000 +31.524574 0.828833 0.000000 +31.505842 0.763687 0.120000 +31.500000 0.700000 0.120000 +31.500000 0.700000 0.000000 +31.524574 0.828833 0.120000 +31.505842 0.763687 0.000000 +32.200001 0.700000 0.000000 +32.200001 0.700000 0.120000 +32.194157 0.763687 0.000000 +32.194157 0.763687 0.120000 +32.175426 0.828833 0.000000 +32.175426 0.828833 0.120000 +32.142948 0.891523 0.000000 +32.142948 0.891523 0.120000 +32.097488 0.947487 0.000000 +32.041523 0.992948 0.000000 +32.097488 0.947487 0.120000 +32.041523 0.992948 0.120000 +31.978832 1.025426 0.000000 +31.978832 1.025426 0.120000 +31.913687 1.044157 0.000000 +31.913687 1.044157 0.120000 +31.850000 1.050000 0.000000 +31.850000 1.050000 0.120000 +31.786312 1.044157 0.000000 +31.721167 1.025426 0.000000 +31.786312 1.044157 0.120000 +31.721167 1.025426 0.120000 +31.658476 0.992948 0.000000 +31.602512 0.947487 0.000000 +31.658476 0.992948 0.120000 +31.602512 0.947487 0.120000 +31.557051 0.891523 0.000000 +31.557051 0.891523 0.120000 +33.500000 2.200000 0.120000 +33.500000 2.200000 0.000000 +34.194157 2.263687 0.000000 +34.200001 2.200000 0.000000 +34.200001 2.200000 0.120000 +34.175426 2.328833 0.000000 +34.194157 2.263687 0.120000 +34.142948 2.391523 0.000000 +34.175426 2.328833 0.120000 +34.097488 2.447487 0.000000 +34.142948 2.391523 0.120000 +34.097488 2.447487 0.120000 +34.041523 2.492949 0.000000 +34.041523 2.492949 0.120000 +33.978832 2.525426 0.000000 +33.978832 2.525426 0.120000 +33.913689 2.544157 0.000000 +33.913689 2.544157 0.120000 +33.849998 2.550000 0.000000 +33.849998 2.550000 0.120000 +33.786312 2.544157 0.000000 +33.786312 2.544157 0.120000 +33.721169 2.525426 0.000000 +33.721169 2.525426 0.120000 +33.658478 2.492949 0.000000 +33.658478 2.492949 0.120000 +33.602512 2.447487 0.000000 +33.557053 2.391523 0.000000 +33.602512 2.447487 0.120000 +33.557053 2.391523 0.120000 +33.524574 2.328833 0.000000 +33.505844 2.263687 0.000000 +33.524574 2.328833 0.120000 +33.505844 2.263687 0.120000 +33.505844 0.763687 0.120000 +33.500000 0.700000 0.120000 +34.200001 0.700000 0.000000 +34.200001 0.700000 0.120000 +34.194157 0.763687 0.000000 +34.194157 0.763687 0.120000 +34.175426 0.828833 0.000000 +34.175426 0.828833 0.120000 +34.142948 0.891523 0.000000 +34.142948 0.891523 0.120000 +34.097488 0.947487 0.000000 +34.041523 0.992948 0.000000 +34.097488 0.947487 0.120000 +34.041523 0.992948 0.120000 +33.978832 1.025426 0.000000 +33.978832 1.025426 0.120000 +33.913689 1.044157 0.000000 +33.913689 1.044157 0.120000 +33.849998 1.050000 0.000000 +33.786312 1.044157 0.000000 +33.849998 1.050000 0.120000 +33.721169 1.025426 0.000000 +33.786312 1.044157 0.120000 +33.658478 0.992948 0.000000 +33.721169 1.025426 0.120000 +33.602512 0.947487 0.000000 +33.658478 0.992948 0.120000 +33.602512 0.947487 0.120000 +33.557053 0.891523 0.000000 +33.557053 0.891523 0.120000 +33.524574 0.828833 0.000000 +33.524574 0.828833 0.120000 +33.505844 0.763687 0.000000 +33.500000 0.700000 0.000000 +35.500000 2.200000 0.120000 +35.500000 2.200000 0.000000 +36.194157 2.263687 0.000000 +36.200001 2.200000 0.000000 +36.200001 2.200000 0.120000 +36.194157 2.263687 0.120000 +36.175426 2.328833 0.000000 +36.142948 2.391523 0.000000 +36.175426 2.328833 0.120000 +36.097488 2.447487 0.000000 +36.142948 2.391523 0.120000 +36.097488 2.447487 0.120000 +36.041523 2.492949 0.000000 +35.978832 2.525426 0.000000 +36.041523 2.492949 0.120000 +35.978832 2.525426 0.120000 +35.913689 2.544157 0.000000 +35.913689 2.544157 0.120000 +35.849998 2.550000 0.000000 +35.786312 2.544157 0.000000 +35.849998 2.550000 0.120000 +35.786312 2.544157 0.120000 +35.721169 2.525426 0.000000 +35.658478 2.492949 0.000000 +35.721169 2.525426 0.120000 +35.658478 2.492949 0.120000 +35.602512 2.447487 0.000000 +35.602512 2.447487 0.120000 +35.557053 2.391523 0.000000 +35.557053 2.391523 0.120000 +35.524574 2.328833 0.000000 +35.505844 2.263687 0.000000 +35.524574 2.328833 0.120000 +35.505844 2.263687 0.120000 +35.500000 0.700000 0.120000 +35.500000 0.700000 0.000000 +36.200001 0.700000 0.000000 +36.200001 0.700000 0.120000 +36.194157 0.763687 0.000000 +36.194157 0.763687 0.120000 +36.175426 0.828833 0.000000 +36.175426 0.828833 0.120000 +36.142948 0.891523 0.000000 +36.097488 0.947487 0.000000 +36.142948 0.891523 0.120000 +36.097488 0.947487 0.120000 +36.041523 0.992948 0.000000 +36.041523 0.992948 0.120000 +35.978832 1.025426 0.000000 +35.913689 1.044157 0.000000 +35.978832 1.025426 0.120000 +35.849998 1.050000 0.000000 +35.913689 1.044157 0.120000 +35.786312 1.044157 0.000000 +35.849998 1.050000 0.120000 +35.721169 1.025426 0.000000 +35.786312 1.044157 0.120000 +35.721169 1.025426 0.120000 +35.658478 0.992948 0.000000 +35.602512 0.947487 0.000000 +35.658478 0.992948 0.120000 +35.602512 0.947487 0.120000 +35.557053 0.891523 0.000000 +35.557053 0.891523 0.120000 +35.524574 0.828833 0.000000 +35.524574 0.828833 0.120000 +35.505844 0.763687 0.000000 +35.505844 0.763687 0.120000 +37.500000 2.200000 0.120000 +37.500000 2.200000 0.000000 +38.194157 2.263687 0.000000 +38.200001 2.200000 0.000000 +38.200001 2.200000 0.120000 +38.194157 2.263687 0.120000 +38.175426 2.328833 0.000000 +38.142948 2.391523 0.000000 +38.175426 2.328833 0.120000 +38.097488 2.447487 0.000000 +38.142948 2.391523 0.120000 +38.097488 2.447487 0.120000 +38.041523 2.492949 0.000000 +37.978832 2.525426 0.000000 +38.041523 2.492949 0.120000 +37.978832 2.525426 0.120000 +37.913689 2.544157 0.000000 +37.913689 2.544157 0.120000 +37.849998 2.550000 0.000000 +37.849998 2.550000 0.120000 +37.786312 2.544157 0.000000 +37.786312 2.544157 0.120000 +37.721169 2.525426 0.000000 +37.721169 2.525426 0.120000 +37.658478 2.492949 0.000000 +37.658478 2.492949 0.120000 +37.602512 2.447487 0.000000 +37.602512 2.447487 0.120000 +37.557053 2.391523 0.000000 +37.557053 2.391523 0.120000 +37.524574 2.328833 0.000000 +37.505844 2.263687 0.000000 +37.524574 2.328833 0.120000 +37.505844 2.263687 0.120000 +37.500000 0.700000 0.120000 +37.500000 0.700000 0.000000 +38.200001 0.700000 0.000000 +38.200001 0.700000 0.120000 +38.194157 0.763687 0.000000 +38.175426 0.828833 0.000000 +38.194157 0.763687 0.120000 +38.175426 0.828833 0.120000 +38.142948 0.891523 0.000000 +38.097488 0.947487 0.000000 +38.142948 0.891523 0.120000 +38.097488 0.947487 0.120000 +38.041523 0.992948 0.000000 +38.041523 0.992948 0.120000 +37.978832 1.025426 0.000000 +37.913689 1.044157 0.000000 +37.978832 1.025426 0.120000 +37.913689 1.044157 0.120000 +37.849998 1.050000 0.000000 +37.849998 1.050000 0.120000 +37.786312 1.044157 0.000000 +37.721169 1.025426 0.000000 +37.786312 1.044157 0.120000 +37.721169 1.025426 0.120000 +37.658478 0.992948 0.000000 +37.602512 0.947487 0.000000 +37.658478 0.992948 0.120000 +37.602512 0.947487 0.120000 +37.557053 0.891523 0.000000 +37.557053 0.891523 0.120000 +37.524574 0.828833 0.000000 +37.524574 0.828833 0.120000 +37.505844 0.763687 0.000000 +37.505844 0.763687 0.120000 +2.500000 1.450000 0.120000 +2.500000 1.450000 0.000000 +3.200000 1.450000 0.000000 +3.200000 1.450000 0.120000 +3.194157 1.513687 0.000000 +3.175426 1.578833 0.000000 +3.194157 1.513687 0.120000 +3.142948 1.641523 0.000000 +3.175426 1.578833 0.120000 +3.142948 1.641523 0.120000 +3.097487 1.697487 0.000000 +3.097487 1.697487 0.120000 +3.041523 1.742948 0.000000 +3.041523 1.742948 0.120000 +2.978833 1.775426 0.000000 +2.978833 1.775426 0.120000 +2.913687 1.794157 0.000000 +2.913687 1.794157 0.120000 +2.850000 1.800000 0.000000 +2.850000 1.800000 0.120000 +2.786313 1.794157 0.000000 +2.786313 1.794157 0.120000 +2.721167 1.775426 0.000000 +2.721167 1.775426 0.120000 +2.658477 1.742948 0.000000 +2.602513 1.697487 0.000000 +2.658477 1.742948 0.120000 +2.602513 1.697487 0.120000 +2.557052 1.641523 0.000000 +2.557052 1.641523 0.120000 +2.524574 1.578833 0.000000 +2.524574 1.578833 0.120000 +2.505843 1.513687 0.000000 +2.505843 1.513687 0.120000 +4.500000 1.450000 0.120000 +4.500000 1.450000 0.000000 +5.200000 1.450000 0.000000 +5.200000 1.450000 0.120000 +5.194157 1.513687 0.000000 +5.175426 1.578833 0.000000 +5.194157 1.513687 0.120000 +5.175426 1.578833 0.120000 +5.142949 1.641523 0.000000 +5.142949 1.641523 0.120000 +5.097487 1.697487 0.000000 +5.097487 1.697487 0.120000 +5.041523 1.742948 0.000000 +5.041523 1.742948 0.120000 +4.978833 1.775426 0.000000 +4.978833 1.775426 0.120000 +4.913687 1.794157 0.000000 +4.913687 1.794157 0.120000 +4.850000 1.800000 0.000000 +4.850000 1.800000 0.120000 +4.786313 1.794157 0.000000 +4.786313 1.794157 0.120000 +4.721167 1.775426 0.000000 +4.721167 1.775426 0.120000 +4.658476 1.742948 0.000000 +4.658476 1.742948 0.120000 +4.602513 1.697487 0.000000 +4.602513 1.697487 0.120000 +4.557052 1.641523 0.000000 +4.524574 1.578833 0.000000 +4.557052 1.641523 0.120000 +4.505843 1.513687 0.000000 +4.524574 1.578833 0.120000 +4.505843 1.513687 0.120000 +6.500000 1.450000 0.120000 +6.500000 1.450000 0.000000 +7.194157 1.513687 0.000000 +7.200000 1.450000 0.000000 +7.200000 1.450000 0.120000 +7.194157 1.513687 0.120000 +7.175426 1.578833 0.000000 +7.175426 1.578833 0.120000 +7.142949 1.641523 0.000000 +7.142949 1.641523 0.120000 +7.097487 1.697487 0.000000 +7.097487 1.697487 0.120000 +7.041523 1.742948 0.000000 +7.041523 1.742948 0.120000 +6.978833 1.775426 0.000000 +6.978833 1.775426 0.120000 +6.913687 1.794157 0.000000 +6.913687 1.794157 0.120000 +6.850000 1.800000 0.000000 +6.850000 1.800000 0.120000 +6.786313 1.794157 0.000000 +6.786313 1.794157 0.120000 +6.721167 1.775426 0.000000 +6.721167 1.775426 0.120000 +6.658476 1.742948 0.000000 +6.602513 1.697487 0.000000 +6.658476 1.742948 0.120000 +6.602513 1.697487 0.120000 +6.557052 1.641523 0.000000 +6.557052 1.641523 0.120000 +6.524574 1.578833 0.000000 +6.524574 1.578833 0.120000 +6.505843 1.513687 0.000000 +6.505843 1.513687 0.120000 +8.978833 1.775426 0.120000 +9.194157 1.513687 0.000000 +9.200000 1.450000 0.000000 +9.200000 1.450000 0.120000 +9.175426 1.578833 0.000000 +9.194157 1.513687 0.120000 +9.142948 1.641523 0.000000 +9.175426 1.578833 0.120000 +9.097487 1.697487 0.000000 +9.142948 1.641523 0.120000 +9.097487 1.697487 0.120000 +9.041523 1.742948 0.000000 +9.041523 1.742948 0.120000 +8.978833 1.775426 0.000000 +8.505843 1.513687 0.120000 +8.500000 1.450000 0.120000 +8.500000 1.450000 0.000000 +8.505843 1.513687 0.000000 +8.524574 1.578833 0.120000 +8.557052 1.641523 0.120000 +8.524574 1.578833 0.000000 +8.557052 1.641523 0.000000 +8.602512 1.697487 0.120000 +8.658477 1.742948 0.120000 +8.602512 1.697487 0.000000 +8.658477 1.742948 0.000000 +8.721167 1.775426 0.120000 +8.721167 1.775426 0.000000 +8.786313 1.794157 0.120000 +8.786313 1.794157 0.000000 +8.850000 1.800000 0.120000 +8.850000 1.800000 0.000000 +8.913687 1.794157 0.120000 +8.913687 1.794157 0.000000 +10.500000 1.450000 0.120000 +10.500000 1.450000 0.000000 +11.200000 1.450000 0.000000 +11.200000 1.450000 0.120000 +11.194157 1.513687 0.000000 +11.175426 1.578833 0.000000 +11.194157 1.513687 0.120000 +11.175426 1.578833 0.120000 +11.142948 1.641523 0.000000 +11.097487 1.697487 0.000000 +11.142948 1.641523 0.120000 +11.041523 1.742948 0.000000 +11.097487 1.697487 0.120000 +11.041523 1.742948 0.120000 +10.978833 1.775426 0.000000 +10.978833 1.775426 0.120000 +10.913687 1.794157 0.000000 +10.850000 1.800000 0.000000 +10.913687 1.794157 0.120000 +10.786313 1.794157 0.000000 +10.850000 1.800000 0.120000 +10.786313 1.794157 0.120000 +10.721167 1.775426 0.000000 +10.658477 1.742948 0.000000 +10.721167 1.775426 0.120000 +10.602512 1.697487 0.000000 +10.658477 1.742948 0.120000 +10.602512 1.697487 0.120000 +10.557052 1.641523 0.000000 +10.557052 1.641523 0.120000 +10.524574 1.578833 0.000000 +10.524574 1.578833 0.120000 +10.505843 1.513687 0.000000 +10.505843 1.513687 0.120000 +12.500000 1.450000 0.120000 +12.500000 1.450000 0.000000 +13.194157 1.513687 0.000000 +13.200000 1.450000 0.000000 +13.200000 1.450000 0.120000 +13.175426 1.578833 0.000000 +13.194157 1.513687 0.120000 +13.142948 1.641523 0.000000 +13.175426 1.578833 0.120000 +13.142948 1.641523 0.120000 +13.097487 1.697487 0.000000 +13.041523 1.742948 0.000000 +13.097487 1.697487 0.120000 +12.978833 1.775426 0.000000 +13.041523 1.742948 0.120000 +12.913687 1.794157 0.000000 +12.978833 1.775426 0.120000 +12.913687 1.794157 0.120000 +12.850000 1.800000 0.000000 +12.850000 1.800000 0.120000 +12.786313 1.794157 0.000000 +12.721167 1.775426 0.000000 +12.786313 1.794157 0.120000 +12.721167 1.775426 0.120000 +12.658477 1.742948 0.000000 +12.658477 1.742948 0.120000 +12.602512 1.697487 0.000000 +12.602512 1.697487 0.120000 +12.557052 1.641523 0.000000 +12.524574 1.578833 0.000000 +12.557052 1.641523 0.120000 +12.524574 1.578833 0.120000 +12.505843 1.513687 0.000000 +12.505843 1.513687 0.120000 +14.500000 1.450000 0.120000 +14.500000 1.450000 0.000000 +15.194157 1.513687 0.000000 +15.200000 1.450000 0.000000 +15.200000 1.450000 0.120000 +15.175426 1.578833 0.000000 +15.194157 1.513687 0.120000 +15.175426 1.578833 0.120000 +15.142948 1.641523 0.000000 +15.097487 1.697487 0.000000 +15.142948 1.641523 0.120000 +15.041523 1.742948 0.000000 +15.097487 1.697487 0.120000 +15.041523 1.742948 0.120000 +14.978833 1.775426 0.000000 +14.978833 1.775426 0.120000 +14.913687 1.794157 0.000000 +14.913687 1.794157 0.120000 +14.850000 1.800000 0.000000 +14.850000 1.800000 0.120000 +14.786313 1.794157 0.000000 +14.786313 1.794157 0.120000 +14.721167 1.775426 0.000000 +14.721167 1.775426 0.120000 +14.658477 1.742948 0.000000 +14.658477 1.742948 0.120000 +14.602512 1.697487 0.000000 +14.602512 1.697487 0.120000 +14.557052 1.641523 0.000000 +14.557052 1.641523 0.120000 +14.524574 1.578833 0.000000 +14.524574 1.578833 0.120000 +14.505843 1.513687 0.000000 +14.505843 1.513687 0.120000 +16.500000 1.450000 0.120000 +16.500000 1.450000 0.000000 +17.194157 1.513687 0.000000 +17.200001 1.450000 0.000000 +17.200001 1.450000 0.120000 +17.175426 1.578833 0.000000 +17.194157 1.513687 0.120000 +17.175426 1.578833 0.120000 +17.142948 1.641523 0.000000 +17.097486 1.697487 0.000000 +17.142948 1.641523 0.120000 +17.097486 1.697487 0.120000 +17.041523 1.742948 0.000000 +17.041523 1.742948 0.120000 +16.978832 1.775426 0.000000 +16.978832 1.775426 0.120000 +16.913687 1.794157 0.000000 +16.913687 1.794157 0.120000 +16.850000 1.800000 0.000000 +16.850000 1.800000 0.120000 +16.786312 1.794157 0.000000 +16.786312 1.794157 0.120000 +16.721167 1.775426 0.000000 +16.721167 1.775426 0.120000 +16.658476 1.742948 0.000000 +16.658476 1.742948 0.120000 +16.602512 1.697487 0.000000 +16.602512 1.697487 0.120000 +16.557051 1.641523 0.000000 +16.557051 1.641523 0.120000 +16.524574 1.578833 0.000000 +16.524574 1.578833 0.120000 +16.505842 1.513687 0.000000 +16.505842 1.513687 0.120000 +18.500000 1.450000 0.120000 +18.500000 1.450000 0.000000 +19.194157 1.513687 0.000000 +19.200001 1.450000 0.000000 +19.200001 1.450000 0.120000 +19.175426 1.578833 0.000000 +19.194157 1.513687 0.120000 +19.142948 1.641523 0.000000 +19.175426 1.578833 0.120000 +19.142948 1.641523 0.120000 +19.097486 1.697487 0.000000 +19.097486 1.697487 0.120000 +19.041523 1.742948 0.000000 +18.978832 1.775426 0.000000 +19.041523 1.742948 0.120000 +18.913687 1.794157 0.000000 +18.978832 1.775426 0.120000 +18.913687 1.794157 0.120000 +18.850000 1.800000 0.000000 +18.786312 1.794157 0.000000 +18.850000 1.800000 0.120000 +18.721167 1.775426 0.000000 +18.786312 1.794157 0.120000 +18.721167 1.775426 0.120000 +18.658476 1.742948 0.000000 +18.602512 1.697487 0.000000 +18.658476 1.742948 0.120000 +18.602512 1.697487 0.120000 +18.557051 1.641523 0.000000 +18.557051 1.641523 0.120000 +18.524574 1.578833 0.000000 +18.524574 1.578833 0.120000 +18.505842 1.513687 0.000000 +18.505842 1.513687 0.120000 +20.500000 1.450000 0.120000 +20.500000 1.450000 0.000000 +21.200001 1.450000 0.000000 +21.200001 1.450000 0.120000 +21.194157 1.513687 0.000000 +21.175426 1.578833 0.000000 +21.194157 1.513687 0.120000 +21.175426 1.578833 0.120000 +21.142948 1.641523 0.000000 +21.142948 1.641523 0.120000 +21.097486 1.697487 0.000000 +21.097486 1.697487 0.120000 +21.041523 1.742948 0.000000 +21.041523 1.742948 0.120000 +20.978832 1.775426 0.000000 +20.978832 1.775426 0.120000 +20.913687 1.794157 0.000000 +20.913687 1.794157 0.120000 +20.850000 1.800000 0.000000 +20.850000 1.800000 0.120000 +20.786312 1.794157 0.000000 +20.721167 1.775426 0.000000 +20.786312 1.794157 0.120000 +20.721167 1.775426 0.120000 +20.658476 1.742948 0.000000 +20.658476 1.742948 0.120000 +20.602512 1.697487 0.000000 +20.602512 1.697487 0.120000 +20.557051 1.641523 0.000000 +20.557051 1.641523 0.120000 +20.524574 1.578833 0.000000 +20.524574 1.578833 0.120000 +20.505842 1.513687 0.000000 +20.505842 1.513687 0.120000 +22.500000 1.450000 0.120000 +22.500000 1.450000 0.000000 +23.200001 1.450000 0.000000 +23.200001 1.450000 0.120000 +23.194157 1.513687 0.000000 +23.175426 1.578833 0.000000 +23.194157 1.513687 0.120000 +23.175426 1.578833 0.120000 +23.142948 1.641523 0.000000 +23.142948 1.641523 0.120000 +23.097486 1.697487 0.000000 +23.097486 1.697487 0.120000 +23.041523 1.742948 0.000000 +23.041523 1.742948 0.120000 +22.978832 1.775426 0.000000 +22.978832 1.775426 0.120000 +22.913687 1.794157 0.000000 +22.913687 1.794157 0.120000 +22.850000 1.800000 0.000000 +22.850000 1.800000 0.120000 +22.786312 1.794157 0.000000 +22.721167 1.775426 0.000000 +22.786312 1.794157 0.120000 +22.721167 1.775426 0.120000 +22.658476 1.742948 0.000000 +22.658476 1.742948 0.120000 +22.602512 1.697487 0.000000 +22.602512 1.697487 0.120000 +22.557051 1.641523 0.000000 +22.557051 1.641523 0.120000 +22.524574 1.578833 0.000000 +22.524574 1.578833 0.120000 +22.505842 1.513687 0.000000 +22.505842 1.513687 0.120000 +24.978832 1.775426 0.120000 +25.194157 1.513687 0.000000 +25.200001 1.450000 0.000000 +25.200001 1.450000 0.120000 +25.175426 1.578833 0.000000 +25.194157 1.513687 0.120000 +25.142948 1.641523 0.000000 +25.175426 1.578833 0.120000 +25.142948 1.641523 0.120000 +25.097486 1.697487 0.000000 +25.041523 1.742948 0.000000 +25.097486 1.697487 0.120000 +24.978832 1.775426 0.000000 +25.041523 1.742948 0.120000 +24.505842 1.513687 0.120000 +24.500000 1.450000 0.120000 +24.500000 1.450000 0.000000 +24.505842 1.513687 0.000000 +24.524574 1.578833 0.120000 +24.557051 1.641523 0.120000 +24.524574 1.578833 0.000000 +24.557051 1.641523 0.000000 +24.602512 1.697487 0.120000 +24.658476 1.742948 0.120000 +24.602512 1.697487 0.000000 +24.658476 1.742948 0.000000 +24.721167 1.775426 0.120000 +24.721167 1.775426 0.000000 +24.786312 1.794157 0.120000 +24.786312 1.794157 0.000000 +24.850000 1.800000 0.120000 +24.850000 1.800000 0.000000 +24.913687 1.794157 0.120000 +24.913687 1.794157 0.000000 +26.500000 1.450000 0.120000 +26.500000 1.450000 0.000000 +27.194157 1.513687 0.000000 +27.200001 1.450000 0.000000 +27.200001 1.450000 0.120000 +27.175426 1.578833 0.000000 +27.194157 1.513687 0.120000 +27.142948 1.641523 0.000000 +27.175426 1.578833 0.120000 +27.142948 1.641523 0.120000 +27.097486 1.697487 0.000000 +27.041523 1.742948 0.000000 +27.097486 1.697487 0.120000 +26.978832 1.775426 0.000000 +27.041523 1.742948 0.120000 +26.978832 1.775426 0.120000 +26.913687 1.794157 0.000000 +26.913687 1.794157 0.120000 +26.850000 1.800000 0.000000 +26.850000 1.800000 0.120000 +26.786312 1.794157 0.000000 +26.786312 1.794157 0.120000 +26.721167 1.775426 0.000000 +26.721167 1.775426 0.120000 +26.658476 1.742948 0.000000 +26.658476 1.742948 0.120000 +26.602512 1.697487 0.000000 +26.557051 1.641523 0.000000 +26.602512 1.697487 0.120000 +26.557051 1.641523 0.120000 +26.524574 1.578833 0.000000 +26.524574 1.578833 0.120000 +26.505842 1.513687 0.000000 +26.505842 1.513687 0.120000 +28.500000 1.450000 0.120000 +28.500000 1.450000 0.000000 +29.194157 1.513687 0.000000 +29.200001 1.450000 0.000000 +29.200001 1.450000 0.120000 +29.175426 1.578833 0.000000 +29.194157 1.513687 0.120000 +29.142948 1.641523 0.000000 +29.175426 1.578833 0.120000 +29.097486 1.697487 0.000000 +29.142948 1.641523 0.120000 +29.097486 1.697487 0.120000 +29.041523 1.742948 0.000000 +29.041523 1.742948 0.120000 +28.978832 1.775426 0.000000 +28.913687 1.794157 0.000000 +28.978832 1.775426 0.120000 +28.850000 1.800000 0.000000 +28.913687 1.794157 0.120000 +28.786312 1.794157 0.000000 +28.850000 1.800000 0.120000 +28.786312 1.794157 0.120000 +28.721167 1.775426 0.000000 +28.658476 1.742948 0.000000 +28.721167 1.775426 0.120000 +28.602512 1.697487 0.000000 +28.658476 1.742948 0.120000 +28.602512 1.697487 0.120000 +28.557051 1.641523 0.000000 +28.557051 1.641523 0.120000 +28.524574 1.578833 0.000000 +28.524574 1.578833 0.120000 +28.505842 1.513687 0.000000 +28.505842 1.513687 0.120000 +30.505842 1.513687 0.000000 +30.500000 1.450000 0.120000 +30.500000 1.450000 0.000000 +30.505842 1.513687 0.120000 +31.200001 1.450000 0.000000 +31.200001 1.450000 0.120000 +31.194157 1.513687 0.000000 +31.175426 1.578833 0.000000 +31.194157 1.513687 0.120000 +31.175426 1.578833 0.120000 +31.142948 1.641523 0.000000 +31.142948 1.641523 0.120000 +31.097486 1.697487 0.000000 +31.097486 1.697487 0.120000 +31.041523 1.742948 0.000000 +30.978832 1.775426 0.000000 +31.041523 1.742948 0.120000 +30.978832 1.775426 0.120000 +30.913687 1.794157 0.000000 +30.913687 1.794157 0.120000 +30.850000 1.800000 0.000000 +30.786312 1.794157 0.000000 +30.850000 1.800000 0.120000 +30.721167 1.775426 0.000000 +30.786312 1.794157 0.120000 +30.658476 1.742948 0.000000 +30.721167 1.775426 0.120000 +30.658476 1.742948 0.120000 +30.602512 1.697487 0.000000 +30.602512 1.697487 0.120000 +30.557051 1.641523 0.000000 +30.557051 1.641523 0.120000 +30.524574 1.578833 0.000000 +30.524574 1.578833 0.120000 +32.505844 1.513687 0.000000 +32.500000 1.450000 0.120000 +32.500000 1.450000 0.000000 +32.505844 1.513687 0.120000 +33.200001 1.450000 0.000000 +33.200001 1.450000 0.120000 +33.194157 1.513687 0.000000 +33.175426 1.578833 0.000000 +33.194157 1.513687 0.120000 +33.175426 1.578833 0.120000 +33.142948 1.641523 0.000000 +33.097488 1.697487 0.000000 +33.142948 1.641523 0.120000 +33.097488 1.697487 0.120000 +33.041523 1.742948 0.000000 +33.041523 1.742948 0.120000 +32.978832 1.775426 0.000000 +32.978832 1.775426 0.120000 +32.913689 1.794157 0.000000 +32.913689 1.794157 0.120000 +32.849998 1.800000 0.000000 +32.786312 1.794157 0.000000 +32.849998 1.800000 0.120000 +32.721169 1.775426 0.000000 +32.786312 1.794157 0.120000 +32.658478 1.742948 0.000000 +32.721169 1.775426 0.120000 +32.658478 1.742948 0.120000 +32.602512 1.697487 0.000000 +32.602512 1.697487 0.120000 +32.557053 1.641523 0.000000 +32.557053 1.641523 0.120000 +32.524574 1.578833 0.000000 +32.524574 1.578833 0.120000 +34.500000 1.450000 0.120000 +34.500000 1.450000 0.000000 +35.200001 1.450000 0.000000 +35.200001 1.450000 0.120000 +35.194157 1.513687 0.000000 +35.175426 1.578833 0.000000 +35.194157 1.513687 0.120000 +35.175426 1.578833 0.120000 +35.142948 1.641523 0.000000 +35.097488 1.697487 0.000000 +35.142948 1.641523 0.120000 +35.097488 1.697487 0.120000 +35.041523 1.742948 0.000000 +35.041523 1.742948 0.120000 +34.978832 1.775426 0.000000 +34.978832 1.775426 0.120000 +34.913689 1.794157 0.000000 +34.849998 1.800000 0.000000 +34.913689 1.794157 0.120000 +34.786312 1.794157 0.000000 +34.849998 1.800000 0.120000 +34.721169 1.775426 0.000000 +34.786312 1.794157 0.120000 +34.658478 1.742948 0.000000 +34.721169 1.775426 0.120000 +34.602512 1.697487 0.000000 +34.658478 1.742948 0.120000 +34.602512 1.697487 0.120000 +34.557053 1.641523 0.000000 +34.557053 1.641523 0.120000 +34.524574 1.578833 0.000000 +34.524574 1.578833 0.120000 +34.505844 1.513687 0.000000 +34.505844 1.513687 0.120000 +36.500000 1.450000 0.120000 +36.500000 1.450000 0.000000 +37.194157 1.513687 0.000000 +37.200001 1.450000 0.000000 +37.200001 1.450000 0.120000 +37.175426 1.578833 0.000000 +37.194157 1.513687 0.120000 +37.142948 1.641523 0.000000 +37.175426 1.578833 0.120000 +37.142948 1.641523 0.120000 +37.097488 1.697487 0.000000 +37.041523 1.742948 0.000000 +37.097488 1.697487 0.120000 +36.978832 1.775426 0.000000 +37.041523 1.742948 0.120000 +36.978832 1.775426 0.120000 +36.913689 1.794157 0.000000 +36.913689 1.794157 0.120000 +36.849998 1.800000 0.000000 +36.786312 1.794157 0.000000 +36.849998 1.800000 0.120000 +36.786312 1.794157 0.120000 +36.721169 1.775426 0.000000 +36.721169 1.775426 0.120000 +36.658478 1.742948 0.000000 +36.658478 1.742948 0.120000 +36.602512 1.697487 0.000000 +36.602512 1.697487 0.120000 +36.557053 1.641523 0.000000 +36.557053 1.641523 0.120000 +36.524574 1.578833 0.000000 +36.524574 1.578833 0.120000 +36.505844 1.513687 0.000000 +36.505844 1.513687 0.120000 + + + + + + + + + + + +0.982801 -0.184667 0.000000 +0.995816 -0.091379 0.000000 +0.995816 -0.091379 0.000000 +-0.982801 -0.184667 0.000000 +-0.995816 -0.091379 0.000000 +-0.995816 -0.091379 0.000000 +-0.982801 -0.184667 0.000000 +-0.995816 -0.091379 0.000000 +-0.982801 -0.184667 0.000000 +-0.929042 -0.369974 0.000000 +-0.982801 -0.184667 0.000000 +-0.982801 -0.184667 0.000000 +-0.929042 -0.369974 0.000000 +-0.982801 -0.184667 0.000000 +-0.929042 -0.369974 0.000000 +-0.836407 -0.548108 0.000000 +-0.929042 -0.369974 0.000000 +-0.929042 -0.369974 0.000000 +-0.836407 -0.548108 0.000000 +-0.929042 -0.369974 0.000000 +-0.836407 -0.548108 0.000000 +-0.707107 -0.707106 0.000000 +-0.836407 -0.548108 0.000000 +-0.836407 -0.548108 0.000000 +-0.707107 -0.707106 0.000000 +-0.836407 -0.548108 0.000000 +-0.707107 -0.707106 0.000000 +-0.548103 -0.836411 0.000000 +-0.707107 -0.707106 0.000000 +-0.707107 -0.707106 0.000000 +-0.548103 -0.836411 0.000000 +-0.707107 -0.707106 0.000000 +-0.548103 -0.836411 0.000000 +-0.369978 -0.929040 0.000000 +-0.548103 -0.836411 0.000000 +-0.548103 -0.836411 0.000000 +-0.369978 -0.929040 0.000000 +-0.548103 -0.836411 0.000000 +-0.369978 -0.929040 0.000000 +-0.184670 -0.982801 0.000000 +-0.369978 -0.929040 0.000000 +-0.369978 -0.929040 0.000000 +-0.184670 -0.982801 0.000000 +-0.369978 -0.929040 0.000000 +-0.184670 -0.982801 0.000000 +-0.000003 -1.000000 0.000000 +-0.184670 -0.982801 0.000000 +-0.184670 -0.982801 0.000000 +-0.000003 -1.000000 0.000000 +-0.184670 -0.982801 0.000000 +-0.000003 -1.000000 0.000000 +0.184667 -0.982801 0.000000 +-0.000003 -1.000000 0.000000 +-0.000003 -1.000000 0.000000 +0.184667 -0.982801 0.000000 +-0.000003 -1.000000 0.000000 +0.184667 -0.982801 0.000000 +0.369978 -0.929040 0.000000 +0.184667 -0.982801 0.000000 +0.184667 -0.982801 0.000000 +0.369978 -0.929040 0.000000 +0.184667 -0.982801 0.000000 +0.369978 -0.929040 0.000000 +0.548103 -0.836411 0.000000 +0.369978 -0.929040 0.000000 +0.369978 -0.929040 0.000000 +0.548103 -0.836411 0.000000 +0.369978 -0.929040 0.000000 +0.548103 -0.836411 0.000000 +0.707107 -0.707106 0.000000 +0.548103 -0.836411 0.000000 +0.548103 -0.836411 0.000000 +0.707107 -0.707106 0.000000 +0.548103 -0.836411 0.000000 +0.707107 -0.707106 0.000000 +0.836407 -0.548108 0.000000 +0.707107 -0.707106 0.000000 +0.707107 -0.707106 0.000000 +0.836407 -0.548108 0.000000 +0.707107 -0.707106 0.000000 +0.836407 -0.548108 0.000000 +0.929042 -0.369974 0.000000 +0.836407 -0.548108 0.000000 +0.836407 -0.548108 0.000000 +0.929042 -0.369974 0.000000 +0.836407 -0.548108 0.000000 +0.929042 -0.369974 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369974 0.000000 +0.929042 -0.369974 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369974 0.000000 +0.982801 -0.184667 0.000000 +0.995816 -0.091379 0.000000 +0.982801 -0.184667 0.000000 +0.982801 -0.184667 0.000000 +0.982801 -0.184667 0.000000 +0.995816 -0.091379 0.000000 +0.995816 -0.091379 0.000000 +-0.982801 -0.184667 0.000000 +-0.995816 -0.091379 0.000000 +-0.995816 -0.091379 0.000000 +-0.982801 -0.184667 0.000000 +-0.995816 -0.091379 0.000000 +-0.982801 -0.184667 0.000000 +-0.982801 -0.184667 0.000000 +-0.982801 -0.184667 0.000000 +-0.929042 -0.369974 0.000000 +-0.929042 -0.369974 0.000000 +-0.982801 -0.184667 0.000000 +-0.929042 -0.369974 0.000000 +-0.836407 -0.548108 0.000000 +-0.929042 -0.369974 0.000000 +-0.929042 -0.369974 0.000000 +-0.836407 -0.548108 0.000000 +-0.929042 -0.369974 0.000000 +-0.836407 -0.548108 0.000000 +-0.707107 -0.707106 0.000000 +-0.836407 -0.548108 0.000000 +-0.836407 -0.548108 0.000000 +-0.707107 -0.707106 0.000000 +-0.836407 -0.548108 0.000000 +-0.707107 -0.707106 0.000000 +-0.548103 -0.836411 0.000000 +-0.707107 -0.707106 0.000000 +-0.707107 -0.707106 0.000000 +-0.548103 -0.836411 0.000000 +-0.707107 -0.707106 0.000000 +-0.548103 -0.836411 0.000000 +-0.369978 -0.929040 0.000000 +-0.548103 -0.836411 0.000000 +-0.548103 -0.836411 0.000000 +-0.369978 -0.929040 0.000000 +-0.548103 -0.836411 0.000000 +-0.369978 -0.929040 0.000000 +-0.369978 -0.929040 0.000000 +-0.369978 -0.929040 0.000000 +-0.184670 -0.982801 0.000000 +-0.184670 -0.982800 0.000000 +-0.369978 -0.929040 0.000000 +-0.184670 -0.982801 0.000000 +-0.000003 -1.000000 0.000000 +-0.184670 -0.982800 0.000000 +-0.184670 -0.982801 0.000000 +-0.000003 -1.000000 0.000000 +-0.184670 -0.982801 0.000000 +-0.000003 -1.000000 0.000000 +0.184667 -0.982801 0.000000 +-0.000003 -1.000000 0.000000 +-0.000003 -1.000000 0.000000 +0.184667 -0.982801 0.000000 +-0.000003 -1.000000 0.000000 +0.184667 -0.982801 0.000000 +0.369978 -0.929040 0.000000 +0.184667 -0.982801 0.000000 +0.184667 -0.982801 0.000000 +0.369978 -0.929040 0.000000 +0.184667 -0.982801 0.000000 +0.369978 -0.929040 0.000000 +0.548103 -0.836411 0.000000 +0.369978 -0.929040 0.000000 +0.369978 -0.929040 0.000000 +0.548103 -0.836411 0.000000 +0.369978 -0.929040 0.000000 +0.548103 -0.836411 0.000000 +0.707107 -0.707106 0.000000 +0.548103 -0.836411 0.000000 +0.548103 -0.836411 0.000000 +0.707107 -0.707106 0.000000 +0.548103 -0.836411 0.000000 +0.707107 -0.707106 0.000000 +0.836407 -0.548108 0.000000 +0.707107 -0.707106 0.000000 +0.707107 -0.707106 0.000000 +0.836407 -0.548108 0.000000 +0.707107 -0.707106 0.000000 +0.836407 -0.548108 0.000000 +0.929042 -0.369974 0.000000 +0.836407 -0.548108 0.000000 +0.836407 -0.548108 0.000000 +0.929042 -0.369974 0.000000 +0.836407 -0.548108 0.000000 +0.929042 -0.369974 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369974 0.000000 +0.929042 -0.369974 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369974 0.000000 +0.982801 -0.184667 0.000000 +0.995816 -0.091379 0.000000 +0.982801 -0.184667 0.000000 +0.982801 -0.184667 0.000000 +-0.982801 -0.184667 0.000000 +-0.995816 -0.091379 0.000000 +-0.995816 -0.091379 0.000000 +0.982801 -0.184667 0.000000 +0.995816 -0.091379 0.000000 +0.995816 -0.091379 0.000000 +0.982801 -0.184667 0.000000 +0.995816 -0.091379 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369974 0.000000 +0.982801 -0.184667 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369974 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369974 0.000000 +0.836407 -0.548108 0.000000 +0.929042 -0.369974 0.000000 +0.929042 -0.369974 0.000000 +0.836407 -0.548108 0.000000 +0.929042 -0.369974 0.000000 +0.836407 -0.548108 0.000000 +0.836407 -0.548108 0.000000 +0.836407 -0.548108 0.000000 +0.707107 -0.707106 0.000000 +0.707107 -0.707106 0.000000 +0.836407 -0.548108 0.000000 +0.707107 -0.707106 0.000000 +0.707107 -0.707106 0.000000 +0.707107 -0.707106 0.000000 +0.548103 -0.836411 0.000000 +0.548103 -0.836411 0.000000 +0.707107 -0.707106 0.000000 +0.548103 -0.836411 0.000000 +0.548103 -0.836411 0.000000 +0.548103 -0.836411 0.000000 +0.369978 -0.929040 0.000000 +0.369978 -0.929040 0.000000 +0.548103 -0.836411 0.000000 +0.369978 -0.929040 0.000000 +0.184667 -0.982801 0.000000 +0.369978 -0.929040 0.000000 +0.369978 -0.929040 0.000000 +0.184667 -0.982801 0.000000 +0.369978 -0.929040 0.000000 +0.184667 -0.982801 0.000000 +-0.000003 -1.000000 0.000000 +0.184667 -0.982801 0.000000 +0.184667 -0.982801 0.000000 +-0.000003 -1.000000 0.000000 +0.184667 -0.982801 0.000000 +-0.000003 -1.000000 0.000000 +-0.184670 -0.982801 0.000000 +-0.000003 -1.000000 0.000000 +-0.000003 -1.000000 0.000000 +-0.184670 -0.982801 0.000000 +-0.000003 -1.000000 0.000000 +-0.184670 -0.982801 0.000000 +-0.369978 -0.929040 0.000000 +-0.184670 -0.982801 0.000000 +-0.184670 -0.982801 0.000000 +-0.369978 -0.929040 0.000000 +-0.184670 -0.982801 0.000000 +-0.369978 -0.929040 0.000000 +-0.548103 -0.836411 0.000000 +-0.369978 -0.929040 0.000000 +-0.369978 -0.929040 0.000000 +-0.548103 -0.836411 0.000000 +-0.369978 -0.929040 0.000000 +-0.548103 -0.836411 0.000000 +-0.707107 -0.707106 0.000000 +-0.548103 -0.836411 0.000000 +-0.548103 -0.836411 0.000000 +-0.707107 -0.707106 0.000000 +-0.548103 -0.836411 0.000000 +-0.707107 -0.707106 0.000000 +-0.836407 -0.548108 0.000000 +-0.707107 -0.707106 0.000000 +-0.707107 -0.707106 0.000000 +-0.836407 -0.548108 0.000000 +-0.707107 -0.707106 0.000000 +-0.836407 -0.548108 0.000000 +-0.836407 -0.548108 0.000000 +-0.836407 -0.548108 0.000000 +-0.929042 -0.369974 0.000000 +-0.929042 -0.369974 0.000000 +-0.836407 -0.548108 0.000000 +-0.929042 -0.369974 0.000000 +-0.982801 -0.184667 0.000000 +-0.929042 -0.369974 0.000000 +-0.929042 -0.369974 0.000000 +-0.982801 -0.184667 0.000000 +-0.929042 -0.369974 0.000000 +-0.982801 -0.184667 0.000000 +-0.995816 -0.091379 0.000000 +-0.982801 -0.184667 0.000000 +-0.982801 -0.184667 0.000000 +0.982801 -0.184667 0.000000 +0.995816 -0.091379 0.000000 +0.995816 -0.091379 0.000000 +-0.982801 -0.184666 0.000000 +-0.995819 -0.091349 0.000000 +-0.995819 -0.091349 0.000000 +-0.982801 -0.184666 0.000000 +-0.995819 -0.091349 0.000000 +-0.982801 -0.184666 0.000000 +-0.929041 -0.369976 0.000000 +-0.982801 -0.184666 0.000000 +-0.982801 -0.184666 0.000000 +-0.929041 -0.369976 0.000000 +-0.982801 -0.184666 0.000000 +-0.929041 -0.369976 0.000000 +-0.836408 -0.548107 0.000000 +-0.929041 -0.369976 0.000000 +-0.929041 -0.369976 0.000000 +-0.836408 -0.548107 0.000000 +-0.929041 -0.369976 0.000000 +-0.836408 -0.548107 0.000000 +-0.707106 -0.707108 0.000000 +-0.836408 -0.548107 0.000000 +-0.836408 -0.548107 0.000000 +-0.707106 -0.707108 0.000000 +-0.836408 -0.548107 0.000000 +-0.707106 -0.707108 0.000000 +-0.548110 -0.836406 0.000000 +-0.707106 -0.707108 0.000000 +-0.707106 -0.707108 0.000000 +-0.548110 -0.836406 0.000000 +-0.707106 -0.707108 0.000000 +-0.548110 -0.836406 0.000000 +-0.369975 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.548110 -0.836406 0.000000 +-0.369975 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.369975 -0.929042 0.000000 +-0.184665 -0.982802 0.000000 +-0.369975 -0.929042 0.000000 +-0.369975 -0.929042 0.000000 +-0.184665 -0.982802 0.000000 +-0.369975 -0.929042 0.000000 +-0.184665 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +-0.184665 -0.982802 0.000000 +-0.184665 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +-0.184665 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +0.184666 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +0.000001 -1.000000 0.000000 +0.184666 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +0.184666 -0.982801 0.000000 +0.369975 -0.929042 0.000000 +0.184666 -0.982801 0.000000 +0.184666 -0.982801 0.000000 +0.369975 -0.929042 0.000000 +0.184666 -0.982801 0.000000 +0.369975 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.369975 -0.929042 0.000000 +0.369975 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.369975 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707108 0.000000 +0.548110 -0.836406 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707108 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707108 0.000000 +0.836402 -0.548117 0.000000 +0.707106 -0.707108 0.000000 +0.707106 -0.707108 0.000000 +0.836402 -0.548117 0.000000 +0.707106 -0.707108 0.000000 +0.836402 -0.548117 0.000000 +0.929042 -0.369974 0.000000 +0.836402 -0.548117 0.000000 +0.836402 -0.548117 0.000000 +0.929042 -0.369974 0.000000 +0.836402 -0.548117 0.000000 +0.929042 -0.369974 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369974 0.000000 +0.929042 -0.369974 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369974 0.000000 +0.982801 -0.184667 0.000000 +0.995816 -0.091379 0.000000 +0.982801 -0.184667 0.000000 +0.982801 -0.184667 0.000000 +0.982801 -0.184667 0.000000 +0.995816 -0.091379 0.000000 +0.995816 -0.091379 0.000000 +-0.982801 -0.184666 0.000000 +-0.995819 -0.091349 0.000000 +-0.995819 -0.091349 0.000000 +-0.982801 -0.184666 0.000000 +-0.995819 -0.091349 0.000000 +-0.982801 -0.184666 0.000000 +-0.929041 -0.369976 0.000000 +-0.982801 -0.184666 0.000000 +-0.982801 -0.184666 0.000000 +-0.929041 -0.369976 0.000000 +-0.982801 -0.184666 0.000000 +-0.929041 -0.369976 0.000000 +-0.836408 -0.548107 0.000000 +-0.929041 -0.369976 0.000000 +-0.929041 -0.369976 0.000000 +-0.836408 -0.548107 0.000000 +-0.929041 -0.369976 0.000000 +-0.836408 -0.548107 0.000000 +-0.707106 -0.707108 0.000000 +-0.836408 -0.548107 0.000000 +-0.836408 -0.548107 0.000000 +-0.707106 -0.707108 0.000000 +-0.836408 -0.548107 0.000000 +-0.707106 -0.707108 0.000000 +-0.548110 -0.836406 0.000000 +-0.707106 -0.707108 0.000000 +-0.707106 -0.707108 0.000000 +-0.548110 -0.836406 0.000000 +-0.707106 -0.707108 0.000000 +-0.548110 -0.836406 0.000000 +-0.369975 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.548110 -0.836406 0.000000 +-0.369975 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.369975 -0.929042 0.000000 +-0.184665 -0.982802 0.000000 +-0.369975 -0.929042 0.000000 +-0.369975 -0.929042 0.000000 +-0.184665 -0.982802 0.000000 +-0.369975 -0.929042 0.000000 +-0.184665 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +-0.184665 -0.982802 0.000000 +-0.184665 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +-0.184665 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +0.184666 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +0.000001 -1.000000 0.000000 +0.184666 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +0.184666 -0.982801 0.000000 +0.369975 -0.929042 0.000000 +0.184666 -0.982801 0.000000 +0.184666 -0.982801 0.000000 +0.369975 -0.929042 0.000000 +0.184666 -0.982801 0.000000 +0.369975 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.369975 -0.929042 0.000000 +0.369975 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.369975 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707108 0.000000 +0.548110 -0.836406 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707108 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707108 0.000000 +0.836402 -0.548117 0.000000 +0.707106 -0.707108 0.000000 +0.707106 -0.707108 0.000000 +0.836402 -0.548117 0.000000 +0.707106 -0.707108 0.000000 +0.836402 -0.548117 0.000000 +0.929042 -0.369974 0.000000 +0.836402 -0.548117 0.000000 +0.836402 -0.548117 0.000000 +0.929042 -0.369974 0.000000 +0.836402 -0.548117 0.000000 +0.929042 -0.369974 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369974 0.000000 +0.929042 -0.369974 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369974 0.000000 +0.982801 -0.184667 0.000000 +0.995816 -0.091379 0.000000 +0.982801 -0.184667 0.000000 +0.982801 -0.184667 0.000000 +0.982801 -0.184667 0.000000 +0.995816 -0.091379 0.000000 +0.995816 -0.091379 0.000000 +-0.982801 -0.184666 0.000000 +-0.995819 -0.091349 0.000000 +-0.995819 -0.091349 0.000000 +-0.982801 -0.184666 0.000000 +-0.995819 -0.091349 0.000000 +-0.982801 -0.184666 0.000000 +-0.929041 -0.369976 0.000000 +-0.982801 -0.184666 0.000000 +-0.982801 -0.184666 0.000000 +-0.929041 -0.369976 0.000000 +-0.982801 -0.184666 0.000000 +-0.929041 -0.369976 0.000000 +-0.836408 -0.548107 0.000000 +-0.929041 -0.369976 0.000000 +-0.929041 -0.369976 0.000000 +-0.836408 -0.548107 0.000000 +-0.929041 -0.369976 0.000000 +-0.836408 -0.548107 0.000000 +-0.707106 -0.707108 0.000000 +-0.836408 -0.548107 0.000000 +-0.836408 -0.548107 0.000000 +-0.707106 -0.707108 0.000000 +-0.836408 -0.548107 0.000000 +-0.707106 -0.707108 0.000000 +-0.548110 -0.836406 0.000000 +-0.707106 -0.707108 0.000000 +-0.707106 -0.707108 0.000000 +-0.548110 -0.836406 0.000000 +-0.707106 -0.707108 0.000000 +-0.548110 -0.836406 0.000000 +-0.369975 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.548110 -0.836406 0.000000 +-0.369975 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.369975 -0.929042 0.000000 +-0.184665 -0.982802 0.000000 +-0.369975 -0.929042 0.000000 +-0.369975 -0.929042 0.000000 +-0.184665 -0.982802 0.000000 +-0.369975 -0.929042 0.000000 +-0.184665 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +-0.184665 -0.982802 0.000000 +-0.184665 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +-0.184665 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +0.184666 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +0.000001 -1.000000 0.000000 +0.184666 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +0.184666 -0.982801 0.000000 +0.369975 -0.929042 0.000000 +0.184666 -0.982801 0.000000 +0.184666 -0.982801 0.000000 +0.369975 -0.929042 0.000000 +0.184666 -0.982801 0.000000 +0.369975 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.369975 -0.929042 0.000000 +0.369975 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.369975 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707108 0.000000 +0.548110 -0.836406 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707108 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707108 0.000000 +0.707106 -0.707108 0.000000 +0.707106 -0.707108 0.000000 +0.836402 -0.548117 0.000000 +0.836402 -0.548117 0.000000 +0.707106 -0.707108 0.000000 +0.836402 -0.548117 0.000000 +0.836402 -0.548117 0.000000 +0.836402 -0.548117 0.000000 +0.929042 -0.369974 0.000000 +0.929042 -0.369974 0.000000 +0.836402 -0.548117 0.000000 +0.929042 -0.369974 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369974 0.000000 +0.929042 -0.369974 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369974 0.000000 +0.982801 -0.184667 0.000000 +0.995816 -0.091379 0.000000 +0.982801 -0.184667 0.000000 +0.982801 -0.184667 0.000000 +0.982801 -0.184667 0.000000 +0.995816 -0.091379 0.000000 +0.995816 -0.091379 0.000000 +-0.982801 -0.184666 0.000000 +-0.995819 -0.091349 0.000000 +-0.995819 -0.091349 0.000000 +-0.982801 -0.184666 0.000000 +-0.995819 -0.091349 0.000000 +-0.982801 -0.184666 0.000000 +-0.929041 -0.369976 0.000000 +-0.982801 -0.184666 0.000000 +-0.982801 -0.184666 0.000000 +-0.929041 -0.369976 0.000000 +-0.982801 -0.184666 0.000000 +-0.929041 -0.369976 0.000000 +-0.836408 -0.548107 0.000000 +-0.929041 -0.369976 0.000000 +-0.929041 -0.369976 0.000000 +-0.836408 -0.548107 0.000000 +-0.929041 -0.369976 0.000000 +-0.836408 -0.548107 0.000000 +-0.707106 -0.707108 0.000000 +-0.836408 -0.548107 0.000000 +-0.836408 -0.548107 0.000000 +-0.707106 -0.707108 0.000000 +-0.836408 -0.548107 0.000000 +-0.707106 -0.707108 0.000000 +-0.548110 -0.836406 0.000000 +-0.707106 -0.707108 0.000000 +-0.707106 -0.707108 0.000000 +-0.548110 -0.836406 0.000000 +-0.707106 -0.707108 0.000000 +-0.548110 -0.836406 0.000000 +-0.369975 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.548110 -0.836406 0.000000 +-0.369975 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.369975 -0.929042 0.000000 +-0.184665 -0.982802 0.000000 +-0.369975 -0.929042 0.000000 +-0.369975 -0.929042 0.000000 +-0.184665 -0.982802 0.000000 +-0.369975 -0.929042 0.000000 +-0.184665 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +-0.184665 -0.982802 0.000000 +-0.184665 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +-0.184665 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +0.184666 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +0.000001 -1.000000 0.000000 +0.184666 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +0.184666 -0.982801 0.000000 +0.369975 -0.929042 0.000000 +0.184666 -0.982801 0.000000 +0.184666 -0.982801 0.000000 +0.369975 -0.929042 0.000000 +0.184666 -0.982801 0.000000 +0.369975 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.369975 -0.929042 0.000000 +0.369975 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.369975 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707108 0.000000 +0.548110 -0.836406 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707108 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707108 0.000000 +0.836402 -0.548117 0.000000 +0.707106 -0.707108 0.000000 +0.707106 -0.707108 0.000000 +0.836402 -0.548117 0.000000 +0.707106 -0.707108 0.000000 +0.836402 -0.548117 0.000000 +0.929042 -0.369974 0.000000 +0.836402 -0.548117 0.000000 +0.836402 -0.548117 0.000000 +0.929042 -0.369974 0.000000 +0.836402 -0.548117 0.000000 +0.929042 -0.369974 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369974 0.000000 +0.929042 -0.369974 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369974 0.000000 +0.982801 -0.184667 0.000000 +0.995816 -0.091379 0.000000 +0.982801 -0.184667 0.000000 +0.982801 -0.184667 0.000000 +0.982801 -0.184667 0.000000 +0.995816 -0.091379 0.000000 +0.995816 -0.091379 0.000000 +-0.982801 -0.184666 0.000000 +-0.995819 -0.091349 0.000000 +-0.995819 -0.091349 0.000000 +-0.982801 -0.184666 0.000000 +-0.995819 -0.091349 0.000000 +-0.982801 -0.184666 0.000000 +-0.929041 -0.369976 0.000000 +-0.982801 -0.184666 0.000000 +-0.982801 -0.184666 0.000000 +-0.929041 -0.369976 0.000000 +-0.982801 -0.184666 0.000000 +-0.929041 -0.369976 0.000000 +-0.836408 -0.548107 0.000000 +-0.929041 -0.369976 0.000000 +-0.929041 -0.369976 0.000000 +-0.836408 -0.548107 0.000000 +-0.929041 -0.369976 0.000000 +-0.836408 -0.548107 0.000000 +-0.707106 -0.707108 0.000000 +-0.836408 -0.548107 0.000000 +-0.836408 -0.548107 0.000000 +-0.707106 -0.707108 0.000000 +-0.836408 -0.548107 0.000000 +-0.707106 -0.707108 0.000000 +-0.548110 -0.836406 0.000000 +-0.707106 -0.707108 0.000000 +-0.707106 -0.707108 0.000000 +-0.548110 -0.836406 0.000000 +-0.707106 -0.707108 0.000000 +-0.548110 -0.836406 0.000000 +-0.369975 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.548110 -0.836406 0.000000 +-0.369975 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.369975 -0.929042 0.000000 +-0.184665 -0.982802 0.000000 +-0.369975 -0.929042 0.000000 +-0.369975 -0.929042 0.000000 +-0.184665 -0.982802 0.000000 +-0.369975 -0.929042 0.000000 +-0.184665 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +-0.184665 -0.982802 0.000000 +-0.184665 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +-0.184665 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +0.184666 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +0.000001 -1.000000 0.000000 +0.184666 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +0.184666 -0.982801 0.000000 +0.369975 -0.929042 0.000000 +0.184666 -0.982801 0.000000 +0.184666 -0.982801 0.000000 +0.369975 -0.929042 0.000000 +0.184666 -0.982801 0.000000 +0.369975 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.369975 -0.929042 0.000000 +0.369975 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.369975 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707108 0.000000 +0.548110 -0.836406 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707108 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707108 0.000000 +0.836402 -0.548117 0.000000 +0.707106 -0.707108 0.000000 +0.707106 -0.707108 0.000000 +0.836402 -0.548117 0.000000 +0.707106 -0.707108 0.000000 +0.836402 -0.548117 0.000000 +0.929042 -0.369974 0.000000 +0.836402 -0.548117 0.000000 +0.836402 -0.548117 0.000000 +0.929042 -0.369974 0.000000 +0.836402 -0.548117 0.000000 +0.929042 -0.369974 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369974 0.000000 +0.929042 -0.369974 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369974 0.000000 +0.982801 -0.184667 0.000000 +0.995816 -0.091379 0.000000 +0.982801 -0.184667 0.000000 +0.982801 -0.184667 0.000000 +0.982801 -0.184667 0.000000 +0.995816 -0.091379 0.000000 +0.995816 -0.091379 0.000000 +-0.982801 -0.184666 0.000000 +-0.995819 -0.091349 0.000000 +-0.995819 -0.091349 0.000000 +-0.982801 -0.184666 0.000000 +-0.995819 -0.091349 0.000000 +-0.982801 -0.184666 0.000000 +-0.929041 -0.369976 0.000000 +-0.982801 -0.184666 0.000000 +-0.982801 -0.184666 0.000000 +-0.929041 -0.369976 0.000000 +-0.982801 -0.184666 0.000000 +-0.929041 -0.369976 0.000000 +-0.836408 -0.548107 0.000000 +-0.929041 -0.369976 0.000000 +-0.929041 -0.369976 0.000000 +-0.836408 -0.548107 0.000000 +-0.929041 -0.369976 0.000000 +-0.836408 -0.548107 0.000000 +-0.707106 -0.707108 0.000000 +-0.836408 -0.548107 0.000000 +-0.836408 -0.548107 0.000000 +-0.707106 -0.707108 0.000000 +-0.836408 -0.548107 0.000000 +-0.707106 -0.707108 0.000000 +-0.548110 -0.836406 0.000000 +-0.707106 -0.707108 0.000000 +-0.707106 -0.707108 0.000000 +-0.548110 -0.836406 0.000000 +-0.707106 -0.707108 0.000000 +-0.548110 -0.836406 0.000000 +-0.369975 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.548110 -0.836406 0.000000 +-0.369975 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.369975 -0.929042 0.000000 +-0.184665 -0.982802 0.000000 +-0.369975 -0.929042 0.000000 +-0.369975 -0.929042 0.000000 +-0.184665 -0.982802 0.000000 +-0.369975 -0.929042 0.000000 +-0.184665 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +-0.184665 -0.982802 0.000000 +-0.184665 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +-0.184665 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +0.184666 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +0.000001 -1.000000 0.000000 +0.184666 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +0.184666 -0.982801 0.000000 +0.369975 -0.929042 0.000000 +0.184666 -0.982801 0.000000 +0.184666 -0.982801 0.000000 +0.369975 -0.929042 0.000000 +0.184666 -0.982801 0.000000 +0.369975 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.369975 -0.929042 0.000000 +0.369975 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.369975 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707108 0.000000 +0.548110 -0.836406 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707108 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707108 0.000000 +0.836402 -0.548117 0.000000 +0.707106 -0.707108 0.000000 +0.707106 -0.707108 0.000000 +0.836402 -0.548117 0.000000 +0.707106 -0.707108 0.000000 +0.836402 -0.548117 0.000000 +0.929042 -0.369974 0.000000 +0.836402 -0.548117 0.000000 +0.836402 -0.548117 0.000000 +0.929042 -0.369974 0.000000 +0.836402 -0.548117 0.000000 +0.929042 -0.369974 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369974 0.000000 +0.929042 -0.369974 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369974 0.000000 +0.982801 -0.184667 0.000000 +0.995816 -0.091379 0.000000 +0.982801 -0.184667 0.000000 +0.982801 -0.184667 0.000000 +0.982801 -0.184667 0.000000 +0.995816 -0.091379 0.000000 +0.995816 -0.091379 0.000000 +-0.982801 -0.184666 0.000000 +-0.995819 -0.091349 0.000000 +-0.995819 -0.091349 0.000000 +-0.982801 -0.184666 0.000000 +-0.995819 -0.091349 0.000000 +-0.982801 -0.184666 0.000000 +-0.929041 -0.369976 0.000000 +-0.982801 -0.184666 0.000000 +-0.982801 -0.184666 0.000000 +-0.929041 -0.369976 0.000000 +-0.982801 -0.184666 0.000000 +-0.929041 -0.369976 0.000000 +-0.836408 -0.548107 0.000000 +-0.929041 -0.369976 0.000000 +-0.929041 -0.369976 0.000000 +-0.836408 -0.548107 0.000000 +-0.929041 -0.369976 0.000000 +-0.836408 -0.548107 0.000000 +-0.836408 -0.548107 0.000000 +-0.836408 -0.548107 0.000000 +-0.707106 -0.707108 0.000000 +-0.707106 -0.707108 0.000000 +-0.836408 -0.548107 0.000000 +-0.707106 -0.707108 0.000000 +-0.548110 -0.836406 0.000000 +-0.707106 -0.707108 0.000000 +-0.707106 -0.707108 0.000000 +-0.548110 -0.836406 0.000000 +-0.707106 -0.707108 0.000000 +-0.548110 -0.836406 0.000000 +-0.369975 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.548110 -0.836406 0.000000 +-0.369975 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.369975 -0.929042 0.000000 +-0.184665 -0.982802 0.000000 +-0.369975 -0.929042 0.000000 +-0.369975 -0.929042 0.000000 +-0.184665 -0.982802 0.000000 +-0.369975 -0.929042 0.000000 +-0.184665 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +-0.184665 -0.982802 0.000000 +-0.184665 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +-0.184665 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +0.184666 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +0.000001 -1.000000 0.000000 +0.184666 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +0.184666 -0.982801 0.000000 +0.369975 -0.929042 0.000000 +0.184666 -0.982801 0.000000 +0.184666 -0.982801 0.000000 +0.369975 -0.929042 0.000000 +0.184666 -0.982801 0.000000 +0.369975 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.369975 -0.929042 0.000000 +0.369975 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.369975 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707108 0.000000 +0.548110 -0.836406 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707108 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707108 0.000000 +0.836402 -0.548117 0.000000 +0.707106 -0.707108 0.000000 +0.707106 -0.707108 0.000000 +0.836402 -0.548117 0.000000 +0.707106 -0.707108 0.000000 +0.836402 -0.548117 0.000000 +0.929042 -0.369974 0.000000 +0.836402 -0.548117 0.000000 +0.836402 -0.548117 0.000000 +0.929042 -0.369974 0.000000 +0.836402 -0.548117 0.000000 +0.929042 -0.369974 0.000000 +0.929042 -0.369974 0.000000 +0.929042 -0.369974 0.000000 +0.982801 -0.184667 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369974 0.000000 +0.982801 -0.184667 0.000000 +0.995816 -0.091379 0.000000 +0.982801 -0.184667 0.000000 +0.982801 -0.184667 0.000000 +0.982801 -0.184667 0.000000 +0.995816 -0.091379 0.000000 +0.995816 -0.091379 0.000000 +-0.995819 -0.091349 0.000000 +-0.995819 -0.091349 0.000000 +-0.982801 -0.184666 0.000000 +-0.982801 -0.184666 0.000000 +-0.995819 -0.091349 0.000000 +-0.982801 -0.184666 0.000000 +-0.929041 -0.369976 0.000000 +-0.982801 -0.184666 0.000000 +-0.982801 -0.184666 0.000000 +-0.929041 -0.369976 0.000000 +-0.982801 -0.184666 0.000000 +-0.929041 -0.369976 0.000000 +-0.929041 -0.369976 0.000000 +-0.929041 -0.369976 0.000000 +-0.836408 -0.548107 0.000000 +-0.836408 -0.548107 0.000000 +-0.929041 -0.369976 0.000000 +-0.836408 -0.548107 0.000000 +-0.707106 -0.707108 0.000000 +-0.836408 -0.548107 0.000000 +-0.836408 -0.548107 0.000000 +-0.707106 -0.707108 0.000000 +-0.836408 -0.548107 0.000000 +-0.707106 -0.707108 0.000000 +-0.548110 -0.836406 0.000000 +-0.707106 -0.707108 0.000000 +-0.707106 -0.707108 0.000000 +-0.548110 -0.836406 0.000000 +-0.707106 -0.707108 0.000000 +-0.548110 -0.836406 0.000000 +-0.369975 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.548110 -0.836406 0.000000 +-0.369975 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.369975 -0.929042 0.000000 +-0.184665 -0.982802 0.000000 +-0.369975 -0.929042 0.000000 +-0.369975 -0.929042 0.000000 +-0.184665 -0.982802 0.000000 +-0.369975 -0.929042 0.000000 +-0.184665 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +-0.184665 -0.982802 0.000000 +-0.184665 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +-0.184665 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +0.184666 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +0.000001 -1.000000 0.000000 +0.184666 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +0.184666 -0.982801 0.000000 +0.369975 -0.929042 0.000000 +0.184666 -0.982801 0.000000 +0.184666 -0.982801 0.000000 +0.369975 -0.929042 0.000000 +0.184666 -0.982801 0.000000 +0.369975 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.369975 -0.929042 0.000000 +0.369975 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.369975 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707108 0.000000 +0.548110 -0.836406 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707108 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707108 0.000000 +0.836402 -0.548117 0.000000 +0.707106 -0.707108 0.000000 +0.707106 -0.707108 0.000000 +0.836402 -0.548117 0.000000 +0.707106 -0.707108 0.000000 +0.836402 -0.548117 0.000000 +0.836402 -0.548117 0.000000 +0.836402 -0.548117 0.000000 +0.929042 -0.369974 0.000000 +0.929042 -0.369974 0.000000 +0.836402 -0.548117 0.000000 +0.929042 -0.369974 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369974 0.000000 +0.929042 -0.369974 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369974 0.000000 +0.982801 -0.184667 0.000000 +0.995816 -0.091379 0.000000 +0.982801 -0.184667 0.000000 +0.982801 -0.184667 0.000000 +0.982801 -0.184666 0.000000 +0.995817 -0.091364 0.000000 +0.995817 -0.091364 0.000000 +-0.982801 -0.184666 0.000000 +-0.995817 -0.091364 0.000000 +-0.995817 -0.091364 0.000000 +-0.982801 -0.184666 0.000000 +-0.995817 -0.091364 0.000000 +-0.982801 -0.184666 0.000000 +-0.929042 -0.369975 0.000000 +-0.982801 -0.184666 0.000000 +-0.982801 -0.184666 0.000000 +-0.929042 -0.369975 0.000000 +-0.982801 -0.184666 0.000000 +-0.929042 -0.369975 0.000000 +-0.836408 -0.548108 0.000000 +-0.929042 -0.369975 0.000000 +-0.929042 -0.369975 0.000000 +-0.836408 -0.548108 0.000000 +-0.929042 -0.369975 0.000000 +-0.836408 -0.548108 0.000000 +-0.707107 -0.707107 0.000000 +-0.836408 -0.548108 0.000000 +-0.836408 -0.548108 0.000000 +-0.707107 -0.707107 0.000000 +-0.836408 -0.548108 0.000000 +-0.707107 -0.707107 0.000000 +-0.548109 -0.836407 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.548109 -0.836407 0.000000 +-0.707107 -0.707107 0.000000 +-0.548109 -0.836407 0.000000 +-0.369976 -0.929041 0.000000 +-0.548109 -0.836407 0.000000 +-0.548109 -0.836407 0.000000 +-0.369976 -0.929041 0.000000 +-0.548109 -0.836407 0.000000 +-0.369976 -0.929041 0.000000 +-0.369976 -0.929041 0.000000 +-0.369976 -0.929041 0.000000 +-0.184664 -0.982802 0.000000 +-0.184664 -0.982802 0.000000 +-0.369976 -0.929041 0.000000 +-0.184664 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +-0.184664 -0.982802 0.000000 +-0.184664 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +-0.184664 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +0.184664 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +0.000001 -1.000000 0.000000 +0.184664 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +0.184664 -0.982802 0.000000 +0.369976 -0.929041 0.000000 +0.184664 -0.982802 0.000000 +0.184664 -0.982802 0.000000 +0.369976 -0.929041 0.000000 +0.184664 -0.982802 0.000000 +0.369976 -0.929041 0.000000 +0.548109 -0.836407 0.000000 +0.369976 -0.929041 0.000000 +0.369976 -0.929041 0.000000 +0.548109 -0.836407 0.000000 +0.369976 -0.929041 0.000000 +0.548109 -0.836407 0.000000 +0.707107 -0.707107 0.000000 +0.548109 -0.836407 0.000000 +0.548109 -0.836407 0.000000 +0.707107 -0.707107 0.000000 +0.548109 -0.836407 0.000000 +0.707107 -0.707107 0.000000 +0.836408 -0.548108 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836408 -0.548108 0.000000 +0.707107 -0.707107 0.000000 +0.836408 -0.548108 0.000000 +0.929042 -0.369975 0.000000 +0.836408 -0.548108 0.000000 +0.836408 -0.548108 0.000000 +0.929042 -0.369975 0.000000 +0.836408 -0.548108 0.000000 +0.929042 -0.369975 0.000000 +0.982801 -0.184666 0.000000 +0.929042 -0.369975 0.000000 +0.929042 -0.369975 0.000000 +0.982801 -0.184666 0.000000 +0.929042 -0.369975 0.000000 +0.982801 -0.184666 0.000000 +0.995817 -0.091364 0.000000 +0.982801 -0.184666 0.000000 +0.982801 -0.184666 0.000000 +0.982801 -0.184666 0.000000 +0.995817 -0.091364 0.000000 +0.995817 -0.091364 0.000000 +-0.982801 -0.184666 0.000000 +-0.995817 -0.091364 0.000000 +-0.995817 -0.091364 0.000000 +-0.982801 -0.184666 0.000000 +-0.995817 -0.091364 0.000000 +-0.982801 -0.184666 0.000000 +-0.929042 -0.369975 0.000000 +-0.982801 -0.184666 0.000000 +-0.982801 -0.184666 0.000000 +-0.929042 -0.369975 0.000000 +-0.982801 -0.184666 0.000000 +-0.929042 -0.369975 0.000000 +-0.836408 -0.548108 0.000000 +-0.929042 -0.369975 0.000000 +-0.929042 -0.369975 0.000000 +-0.836408 -0.548108 0.000000 +-0.929042 -0.369975 0.000000 +-0.836408 -0.548108 0.000000 +-0.707107 -0.707107 0.000000 +-0.836408 -0.548108 0.000000 +-0.836408 -0.548108 0.000000 +-0.707107 -0.707107 0.000000 +-0.836408 -0.548108 0.000000 +-0.707107 -0.707107 0.000000 +-0.548109 -0.836407 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.548109 -0.836407 0.000000 +-0.707107 -0.707107 0.000000 +-0.548109 -0.836407 0.000000 +-0.369976 -0.929041 0.000000 +-0.548109 -0.836407 0.000000 +-0.548109 -0.836407 0.000000 +-0.369976 -0.929041 0.000000 +-0.548109 -0.836407 0.000000 +-0.369976 -0.929041 0.000000 +-0.184664 -0.982802 0.000000 +-0.369976 -0.929041 0.000000 +-0.369976 -0.929041 0.000000 +-0.184664 -0.982802 0.000000 +-0.369976 -0.929041 0.000000 +-0.184664 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +-0.184664 -0.982802 0.000000 +-0.184664 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +-0.184664 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +0.000001 -1.000000 0.000000 +0.000001 -1.000000 0.000000 +0.184664 -0.982802 0.000000 +0.184664 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +0.184664 -0.982802 0.000000 +0.369976 -0.929041 0.000000 +0.184664 -0.982802 0.000000 +0.184664 -0.982802 0.000000 +0.369976 -0.929041 0.000000 +0.184664 -0.982802 0.000000 +0.369976 -0.929041 0.000000 +0.548109 -0.836407 0.000000 +0.369976 -0.929041 0.000000 +0.369976 -0.929041 0.000000 +0.548109 -0.836407 0.000000 +0.369976 -0.929041 0.000000 +0.548109 -0.836407 0.000000 +0.707107 -0.707107 0.000000 +0.548109 -0.836407 0.000000 +0.548109 -0.836407 0.000000 +0.707107 -0.707107 0.000000 +0.548109 -0.836407 0.000000 +0.707107 -0.707107 0.000000 +0.836408 -0.548108 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836408 -0.548108 0.000000 +0.707107 -0.707107 0.000000 +0.836408 -0.548108 0.000000 +0.929042 -0.369975 0.000000 +0.836408 -0.548108 0.000000 +0.836408 -0.548108 0.000000 +0.929042 -0.369975 0.000000 +0.836408 -0.548108 0.000000 +0.929042 -0.369975 0.000000 +0.929042 -0.369975 0.000000 +0.929042 -0.369975 0.000000 +0.982801 -0.184666 0.000000 +0.982801 -0.184666 0.000000 +0.929042 -0.369975 0.000000 +0.982801 -0.184666 0.000000 +0.995817 -0.091364 0.000000 +0.982801 -0.184666 0.000000 +0.982801 -0.184666 0.000000 +0.982801 -0.184666 0.000000 +0.995817 -0.091364 0.000000 +0.995817 -0.091364 0.000000 +-0.982801 -0.184666 0.000000 +-0.995817 -0.091364 0.000000 +-0.995817 -0.091364 0.000000 +-0.982801 -0.184666 0.000000 +-0.995817 -0.091364 0.000000 +-0.982801 -0.184666 0.000000 +-0.929042 -0.369975 0.000000 +-0.982801 -0.184666 0.000000 +-0.982801 -0.184666 0.000000 +-0.929042 -0.369975 0.000000 +-0.982801 -0.184666 0.000000 +-0.929042 -0.369975 0.000000 +-0.836408 -0.548108 0.000000 +-0.929042 -0.369975 0.000000 +-0.929042 -0.369975 0.000000 +-0.836408 -0.548108 0.000000 +-0.929042 -0.369975 0.000000 +-0.836408 -0.548108 0.000000 +-0.707107 -0.707107 0.000000 +-0.836408 -0.548108 0.000000 +-0.836408 -0.548108 0.000000 +-0.707107 -0.707107 0.000000 +-0.836408 -0.548108 0.000000 +-0.707107 -0.707107 0.000000 +-0.548109 -0.836407 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.548109 -0.836407 0.000000 +-0.707107 -0.707107 0.000000 +-0.548109 -0.836407 0.000000 +-0.369976 -0.929041 0.000000 +-0.548109 -0.836407 0.000000 +-0.548109 -0.836407 0.000000 +-0.369976 -0.929041 0.000000 +-0.548109 -0.836407 0.000000 +-0.369976 -0.929041 0.000000 +-0.184664 -0.982802 0.000000 +-0.369976 -0.929041 0.000000 +-0.369976 -0.929041 0.000000 +-0.184664 -0.982802 0.000000 +-0.369976 -0.929041 0.000000 +-0.184664 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +-0.184664 -0.982802 0.000000 +-0.184664 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +-0.184664 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +0.184664 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +0.000001 -1.000000 0.000000 +0.184664 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +0.184664 -0.982802 0.000000 +0.369976 -0.929041 0.000000 +0.184664 -0.982802 0.000000 +0.184664 -0.982802 0.000000 +0.369976 -0.929041 0.000000 +0.184664 -0.982802 0.000000 +0.369976 -0.929041 0.000000 +0.548109 -0.836407 0.000000 +0.369976 -0.929041 0.000000 +0.369976 -0.929041 0.000000 +0.548109 -0.836407 0.000000 +0.369976 -0.929041 0.000000 +0.548109 -0.836407 0.000000 +0.707107 -0.707107 0.000000 +0.548109 -0.836407 0.000000 +0.548109 -0.836407 0.000000 +0.707107 -0.707107 0.000000 +0.548109 -0.836407 0.000000 +0.707107 -0.707107 0.000000 +0.836408 -0.548108 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836408 -0.548108 0.000000 +0.707107 -0.707107 0.000000 +0.836408 -0.548108 0.000000 +0.929042 -0.369975 0.000000 +0.836408 -0.548108 0.000000 +0.836408 -0.548108 0.000000 +0.929042 -0.369975 0.000000 +0.836408 -0.548108 0.000000 +0.929042 -0.369975 0.000000 +0.982801 -0.184666 0.000000 +0.929042 -0.369975 0.000000 +0.929042 -0.369975 0.000000 +0.982801 -0.184666 0.000000 +0.929042 -0.369975 0.000000 +0.982801 -0.184666 0.000000 +0.995817 -0.091364 0.000000 +0.982801 -0.184666 0.000000 +0.982801 -0.184666 0.000000 +0.982801 -0.184666 0.000000 +0.995817 -0.091364 0.000000 +0.995817 -0.091364 0.000000 +-0.982801 -0.184666 0.000000 +-0.995817 -0.091364 0.000000 +-0.995817 -0.091364 0.000000 +-0.982801 -0.184666 0.000000 +-0.995817 -0.091364 0.000000 +-0.982801 -0.184666 0.000000 +-0.929042 -0.369975 0.000000 +-0.982801 -0.184666 0.000000 +-0.982801 -0.184666 0.000000 +-0.929042 -0.369975 0.000000 +-0.982801 -0.184666 0.000000 +-0.929042 -0.369975 0.000000 +-0.836408 -0.548108 0.000000 +-0.929042 -0.369975 0.000000 +-0.929042 -0.369975 0.000000 +-0.836408 -0.548108 0.000000 +-0.929042 -0.369975 0.000000 +-0.836408 -0.548108 0.000000 +-0.707107 -0.707107 0.000000 +-0.836408 -0.548108 0.000000 +-0.836408 -0.548108 0.000000 +-0.707107 -0.707107 0.000000 +-0.836408 -0.548108 0.000000 +-0.707107 -0.707107 0.000000 +-0.548109 -0.836407 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.548109 -0.836407 0.000000 +-0.707107 -0.707107 0.000000 +-0.548109 -0.836407 0.000000 +-0.369976 -0.929041 0.000000 +-0.548109 -0.836407 0.000000 +-0.548109 -0.836407 0.000000 +-0.369976 -0.929041 0.000000 +-0.548109 -0.836407 0.000000 +-0.369976 -0.929041 0.000000 +-0.184664 -0.982802 0.000000 +-0.369976 -0.929041 0.000000 +-0.369976 -0.929041 0.000000 +-0.184664 -0.982802 0.000000 +-0.369976 -0.929041 0.000000 +-0.184664 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +-0.184664 -0.982802 0.000000 +-0.184664 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +-0.184664 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +0.184664 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +0.000001 -1.000000 0.000000 +0.184664 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +0.184664 -0.982802 0.000000 +0.369976 -0.929041 0.000000 +0.184664 -0.982802 0.000000 +0.184664 -0.982802 0.000000 +0.369976 -0.929041 0.000000 +0.184664 -0.982802 0.000000 +0.369976 -0.929041 0.000000 +0.548109 -0.836407 0.000000 +0.369976 -0.929041 0.000000 +0.369976 -0.929041 0.000000 +0.548109 -0.836407 0.000000 +0.369976 -0.929041 0.000000 +0.548109 -0.836407 0.000000 +0.707107 -0.707107 0.000000 +0.548109 -0.836407 0.000000 +0.548109 -0.836407 0.000000 +0.707107 -0.707107 0.000000 +0.548109 -0.836407 0.000000 +0.707107 -0.707107 0.000000 +0.836408 -0.548108 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836408 -0.548108 0.000000 +0.707107 -0.707107 0.000000 +0.836408 -0.548108 0.000000 +0.929042 -0.369975 0.000000 +0.836408 -0.548108 0.000000 +0.836408 -0.548108 0.000000 +0.929042 -0.369975 0.000000 +0.836408 -0.548108 0.000000 +0.929042 -0.369975 0.000000 +0.929042 -0.369975 0.000000 +0.929042 -0.369975 0.000000 +0.982801 -0.184666 0.000000 +0.982801 -0.184666 0.000000 +0.929042 -0.369975 0.000000 +0.982801 -0.184666 0.000000 +0.995817 -0.091364 0.000000 +0.982801 -0.184666 0.000000 +0.982801 -0.184666 0.000000 +0.982802 -0.184663 0.000000 +0.995817 -0.091364 0.000000 +0.995817 -0.091364 0.000000 +-0.982801 -0.184666 0.000000 +-0.995817 -0.091364 0.000000 +-0.995817 -0.091364 0.000000 +-0.982801 -0.184666 0.000000 +-0.995817 -0.091364 0.000000 +-0.982801 -0.184666 0.000000 +-0.929042 -0.369975 0.000000 +-0.982801 -0.184666 0.000000 +-0.982801 -0.184666 0.000000 +-0.929042 -0.369975 0.000000 +-0.982801 -0.184666 0.000000 +-0.929042 -0.369975 0.000000 +-0.929042 -0.369975 0.000000 +-0.929042 -0.369975 0.000000 +-0.836406 -0.548110 0.000000 +-0.836406 -0.548110 0.000000 +-0.929042 -0.369975 0.000000 +-0.836406 -0.548110 0.000000 +-0.707108 -0.707106 0.000000 +-0.836406 -0.548110 0.000000 +-0.836406 -0.548110 0.000000 +-0.707108 -0.707106 0.000000 +-0.836406 -0.548110 0.000000 +-0.707108 -0.707106 0.000000 +-0.548110 -0.836406 0.000000 +-0.707108 -0.707106 0.000000 +-0.707108 -0.707106 0.000000 +-0.548110 -0.836406 0.000000 +-0.707108 -0.707106 0.000000 +-0.548110 -0.836406 0.000000 +-0.369974 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.548110 -0.836406 0.000000 +-0.369974 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.369974 -0.929042 0.000000 +-0.184665 -0.982801 0.000000 +-0.369974 -0.929042 0.000000 +-0.369974 -0.929042 0.000000 +-0.184665 -0.982801 0.000000 +-0.369974 -0.929042 0.000000 +-0.184665 -0.982801 0.000000 +0.000000 -1.000000 0.000000 +-0.184665 -0.982801 0.000000 +-0.184665 -0.982801 0.000000 +0.000000 -1.000000 0.000000 +-0.184665 -0.982801 0.000000 +0.000000 -1.000000 0.000000 +0.184665 -0.982802 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.184665 -0.982802 0.000000 +0.000000 -1.000000 0.000000 +0.184665 -0.982801 0.000000 +0.369975 -0.929042 0.000000 +0.184665 -0.982802 0.000000 +0.184665 -0.982801 0.000000 +0.369975 -0.929042 0.000000 +0.184665 -0.982801 0.000000 +0.369975 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.369975 -0.929042 0.000000 +0.369975 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.369975 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.548110 -0.836406 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707107 0.000000 +0.707106 -0.707107 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707107 0.000000 +0.836406 -0.548110 0.000000 +0.707106 -0.707107 0.000000 +0.707106 -0.707107 0.000000 +0.836406 -0.548110 0.000000 +0.707106 -0.707107 0.000000 +0.836406 -0.548110 0.000000 +0.929043 -0.369972 0.000000 +0.836406 -0.548110 0.000000 +0.836406 -0.548110 0.000000 +0.929043 -0.369972 0.000000 +0.836406 -0.548110 0.000000 +0.929043 -0.369972 0.000000 +0.982802 -0.184663 0.000000 +0.929043 -0.369972 0.000000 +0.929043 -0.369972 0.000000 +0.982802 -0.184663 0.000000 +0.929043 -0.369972 0.000000 +0.982802 -0.184663 0.000000 +0.995817 -0.091364 0.000000 +0.982802 -0.184663 0.000000 +0.982802 -0.184663 0.000000 +0.982802 -0.184663 0.000000 +0.995817 -0.091364 0.000000 +0.995817 -0.091364 0.000000 +-0.982801 -0.184666 0.000000 +-0.995817 -0.091364 0.000000 +-0.995817 -0.091364 0.000000 +-0.982801 -0.184666 0.000000 +-0.995817 -0.091364 0.000000 +-0.982801 -0.184666 0.000000 +-0.929042 -0.369975 0.000000 +-0.982801 -0.184666 0.000000 +-0.982801 -0.184666 0.000000 +-0.929042 -0.369975 0.000000 +-0.982801 -0.184666 0.000000 +-0.929042 -0.369975 0.000000 +-0.929042 -0.369975 0.000000 +-0.929042 -0.369975 0.000000 +-0.836406 -0.548110 0.000000 +-0.836406 -0.548110 0.000000 +-0.929042 -0.369975 0.000000 +-0.836406 -0.548110 0.000000 +-0.707108 -0.707106 0.000000 +-0.836406 -0.548110 0.000000 +-0.836406 -0.548110 0.000000 +-0.707108 -0.707106 0.000000 +-0.836406 -0.548110 0.000000 +-0.707108 -0.707106 0.000000 +-0.548110 -0.836406 0.000000 +-0.707108 -0.707106 0.000000 +-0.707108 -0.707106 0.000000 +-0.548110 -0.836406 0.000000 +-0.707108 -0.707106 0.000000 +-0.548110 -0.836406 0.000000 +-0.369974 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.548110 -0.836406 0.000000 +-0.369974 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.369974 -0.929042 0.000000 +-0.184665 -0.982801 0.000000 +-0.369974 -0.929042 0.000000 +-0.369974 -0.929042 0.000000 +-0.184665 -0.982801 0.000000 +-0.369974 -0.929042 0.000000 +-0.184665 -0.982801 0.000000 +0.000000 -1.000000 0.000000 +-0.184665 -0.982801 0.000000 +-0.184665 -0.982801 0.000000 +0.000000 -1.000000 0.000000 +-0.184665 -0.982801 0.000000 +0.000000 -1.000000 0.000000 +0.184665 -0.982802 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.184665 -0.982802 0.000000 +0.000000 -1.000000 0.000000 +0.184665 -0.982801 0.000000 +0.369975 -0.929042 0.000000 +0.184665 -0.982802 0.000000 +0.184665 -0.982801 0.000000 +0.369975 -0.929042 0.000000 +0.184665 -0.982801 0.000000 +0.369975 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.369975 -0.929042 0.000000 +0.369975 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.369975 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707107 0.000000 +0.548110 -0.836406 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707107 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707107 0.000000 +0.836406 -0.548110 0.000000 +0.707106 -0.707107 0.000000 +0.707106 -0.707107 0.000000 +0.836406 -0.548110 0.000000 +0.707106 -0.707107 0.000000 +0.836406 -0.548110 0.000000 +0.929043 -0.369972 0.000000 +0.836406 -0.548110 0.000000 +0.836406 -0.548110 0.000000 +0.929043 -0.369972 0.000000 +0.836406 -0.548110 0.000000 +0.929043 -0.369972 0.000000 +0.982802 -0.184663 0.000000 +0.929043 -0.369972 0.000000 +0.929043 -0.369972 0.000000 +0.982802 -0.184663 0.000000 +0.929043 -0.369972 0.000000 +0.982802 -0.184663 0.000000 +0.995817 -0.091364 0.000000 +0.982802 -0.184663 0.000000 +0.982802 -0.184663 0.000000 +0.982802 -0.184665 0.000000 +0.995817 -0.091364 0.000000 +0.995817 -0.091364 0.000000 +-0.982802 -0.184665 0.000000 +-0.995817 -0.091364 0.000000 +-0.995817 -0.091364 0.000000 +-0.982802 -0.184665 0.000000 +-0.995817 -0.091364 0.000000 +-0.982802 -0.184665 0.000000 +-0.929042 -0.369975 0.000000 +-0.982802 -0.184665 0.000000 +-0.982802 -0.184665 0.000000 +-0.929042 -0.369975 0.000000 +-0.982802 -0.184665 0.000000 +-0.929042 -0.369975 0.000000 +-0.836406 -0.548110 0.000000 +-0.929042 -0.369975 0.000000 +-0.929042 -0.369975 0.000000 +-0.836406 -0.548110 0.000000 +-0.929042 -0.369975 0.000000 +-0.836406 -0.548110 0.000000 +-0.707107 -0.707106 0.000000 +-0.836406 -0.548110 0.000000 +-0.836406 -0.548110 0.000000 +-0.707107 -0.707106 0.000000 +-0.836406 -0.548110 0.000000 +-0.707107 -0.707106 0.000000 +-0.548110 -0.836406 0.000000 +-0.707107 -0.707106 0.000000 +-0.707107 -0.707106 0.000000 +-0.548110 -0.836406 0.000000 +-0.707107 -0.707106 0.000000 +-0.548110 -0.836406 0.000000 +-0.369975 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.548110 -0.836406 0.000000 +-0.369975 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.369975 -0.929042 0.000000 +-0.184665 -0.982801 0.000000 +-0.369975 -0.929042 0.000000 +-0.369975 -0.929042 0.000000 +-0.184665 -0.982801 0.000000 +-0.369975 -0.929042 0.000000 +-0.184665 -0.982801 0.000000 +0.000000 -1.000000 0.000000 +-0.184665 -0.982801 0.000000 +-0.184665 -0.982801 0.000000 +0.000000 -1.000000 0.000000 +-0.184665 -0.982801 0.000000 +0.000000 -1.000000 0.000000 +0.184664 -0.982802 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.184664 -0.982802 0.000000 +0.000000 -1.000000 0.000000 +0.184664 -0.982802 0.000000 +0.369975 -0.929042 0.000000 +0.184664 -0.982802 0.000000 +0.184664 -0.982802 0.000000 +0.369975 -0.929042 0.000000 +0.184664 -0.982802 0.000000 +0.369975 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.369975 -0.929042 0.000000 +0.369975 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.369975 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.707107 -0.707106 0.000000 +0.548110 -0.836406 0.000000 +0.548110 -0.836406 0.000000 +0.707107 -0.707106 0.000000 +0.548110 -0.836406 0.000000 +0.707107 -0.707106 0.000000 +0.836406 -0.548110 0.000000 +0.707107 -0.707106 0.000000 +0.707107 -0.707106 0.000000 +0.836406 -0.548110 0.000000 +0.707107 -0.707106 0.000000 +0.836406 -0.548110 0.000000 +0.929042 -0.369975 0.000000 +0.836406 -0.548110 0.000000 +0.836406 -0.548110 0.000000 +0.929042 -0.369975 0.000000 +0.836406 -0.548110 0.000000 +0.929042 -0.369975 0.000000 +0.982802 -0.184665 0.000000 +0.929042 -0.369975 0.000000 +0.929042 -0.369975 0.000000 +0.982802 -0.184665 0.000000 +0.929042 -0.369975 0.000000 +0.982802 -0.184665 0.000000 +0.995817 -0.091364 0.000000 +0.982802 -0.184665 0.000000 +0.982802 -0.184665 0.000000 +0.995816 -0.091379 0.000000 +0.995816 -0.091379 0.000000 +0.982801 -0.184667 0.000000 +-0.982801 -0.184667 0.000000 +-0.995816 -0.091379 0.000000 +-0.995816 -0.091379 0.000000 +-0.982801 -0.184667 0.000000 +-0.995816 -0.091379 0.000000 +-0.982801 -0.184667 0.000000 +-0.929042 -0.369975 0.000000 +-0.982801 -0.184667 0.000000 +-0.982801 -0.184667 0.000000 +-0.929042 -0.369975 0.000000 +-0.982801 -0.184667 0.000000 +-0.929042 -0.369975 0.000000 +-0.836407 -0.548108 0.000000 +-0.929042 -0.369975 0.000000 +-0.929042 -0.369975 0.000000 +-0.836407 -0.548108 0.000000 +-0.929042 -0.369975 0.000000 +-0.836407 -0.548108 0.000000 +-0.836407 -0.548108 0.000000 +-0.836407 -0.548108 0.000000 +-0.707107 -0.707106 0.000000 +-0.707107 -0.707106 0.000000 +-0.836407 -0.548108 0.000000 +-0.707107 -0.707106 0.000000 +-0.548103 -0.836411 0.000000 +-0.707107 -0.707106 0.000000 +-0.707107 -0.707106 0.000000 +-0.548103 -0.836411 0.000000 +-0.707107 -0.707106 0.000000 +-0.548103 -0.836411 0.000000 +-0.369978 -0.929040 0.000000 +-0.548103 -0.836411 0.000000 +-0.548103 -0.836411 0.000000 +-0.369978 -0.929040 0.000000 +-0.548103 -0.836411 0.000000 +-0.369978 -0.929040 0.000000 +-0.184671 -0.982800 0.000000 +-0.369978 -0.929040 0.000000 +-0.369978 -0.929040 0.000000 +-0.184671 -0.982800 0.000000 +-0.369978 -0.929040 0.000000 +-0.184671 -0.982800 0.000000 +-0.000003 -1.000000 0.000000 +-0.184671 -0.982800 0.000000 +-0.184671 -0.982800 0.000000 +-0.000003 -1.000000 0.000000 +-0.184671 -0.982800 0.000000 +-0.000003 -1.000000 0.000000 +0.184668 -0.982801 0.000000 +-0.000003 -1.000000 0.000000 +-0.000003 -1.000000 0.000000 +0.184668 -0.982801 0.000000 +-0.000003 -1.000000 0.000000 +0.184668 -0.982801 0.000000 +0.369978 -0.929041 0.000000 +0.184668 -0.982801 0.000000 +0.184668 -0.982801 0.000000 +0.369978 -0.929041 0.000000 +0.184668 -0.982801 0.000000 +0.369978 -0.929040 0.000000 +0.369978 -0.929041 0.000000 +0.369978 -0.929040 0.000000 +0.548103 -0.836411 0.000000 +0.548103 -0.836411 0.000000 +0.369978 -0.929041 0.000000 +0.548103 -0.836411 0.000000 +0.707107 -0.707106 0.000000 +0.548103 -0.836411 0.000000 +0.548103 -0.836411 0.000000 +0.707107 -0.707106 0.000000 +0.548103 -0.836411 0.000000 +0.707107 -0.707106 0.000000 +0.707107 -0.707106 0.000000 +0.707107 -0.707106 0.000000 +0.836407 -0.548108 0.000000 +0.836407 -0.548108 0.000000 +0.707107 -0.707106 0.000000 +0.836407 -0.548108 0.000000 +0.929042 -0.369975 0.000000 +0.836407 -0.548108 0.000000 +0.836407 -0.548108 0.000000 +0.929042 -0.369975 0.000000 +0.836407 -0.548108 0.000000 +0.929042 -0.369975 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369975 0.000000 +0.929042 -0.369975 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369975 0.000000 +0.982801 -0.184667 0.000000 +0.982801 -0.184667 0.000000 +0.982801 -0.184667 0.000000 +0.995816 -0.091379 0.000000 +-0.929042 -0.369974 0.000000 +-0.982801 -0.184667 0.000000 +-0.982801 -0.184667 0.000000 +-0.982801 -0.184667 0.000000 +-0.995816 -0.091379 0.000000 +-0.995816 -0.091379 0.000000 +-0.982801 -0.184667 0.000000 +-0.995816 -0.091379 0.000000 +-0.982801 -0.184667 0.000000 +0.995816 -0.091379 0.000000 +0.995816 -0.091379 0.000000 +0.982801 -0.184667 0.000000 +0.982801 -0.184667 0.000000 +0.995816 -0.091379 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369974 0.000000 +0.982801 -0.184667 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369974 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369974 0.000000 +0.929042 -0.369974 0.000000 +0.929042 -0.369974 0.000000 +0.836407 -0.548109 0.000000 +0.836407 -0.548109 0.000000 +0.929042 -0.369974 0.000000 +0.836407 -0.548109 0.000000 +0.707107 -0.707107 0.000000 +0.836407 -0.548109 0.000000 +0.836407 -0.548109 0.000000 +0.707107 -0.707107 0.000000 +0.836407 -0.548109 0.000000 +0.707107 -0.707107 0.000000 +0.548103 -0.836411 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.548103 -0.836411 0.000000 +0.707107 -0.707107 0.000000 +0.548103 -0.836411 0.000000 +0.369978 -0.929040 0.000000 +0.548103 -0.836411 0.000000 +0.548103 -0.836411 0.000000 +0.369978 -0.929040 0.000000 +0.548103 -0.836411 0.000000 +0.369978 -0.929040 0.000000 +0.184667 -0.982801 0.000000 +0.369978 -0.929040 0.000000 +0.369978 -0.929040 0.000000 +0.184667 -0.982801 0.000000 +0.369978 -0.929040 0.000000 +0.184667 -0.982801 0.000000 +-0.000003 -1.000000 0.000000 +0.184667 -0.982801 0.000000 +0.184667 -0.982801 0.000000 +-0.000003 -1.000000 0.000000 +0.184667 -0.982801 0.000000 +-0.000003 -1.000000 0.000000 +-0.184670 -0.982801 0.000000 +-0.000003 -1.000000 0.000000 +-0.000003 -1.000000 0.000000 +-0.184670 -0.982801 0.000000 +-0.000003 -1.000000 0.000000 +-0.184670 -0.982801 0.000000 +-0.369978 -0.929040 0.000000 +-0.184670 -0.982801 0.000000 +-0.184670 -0.982801 0.000000 +-0.369978 -0.929040 0.000000 +-0.184670 -0.982801 0.000000 +-0.369978 -0.929040 0.000000 +-0.548103 -0.836411 0.000000 +-0.369978 -0.929040 0.000000 +-0.369978 -0.929040 0.000000 +-0.548103 -0.836411 0.000000 +-0.369978 -0.929040 0.000000 +-0.548103 -0.836411 0.000000 +-0.707107 -0.707107 0.000000 +-0.548103 -0.836411 0.000000 +-0.548103 -0.836411 0.000000 +-0.707107 -0.707107 0.000000 +-0.548103 -0.836411 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836407 -0.548109 0.000000 +-0.836407 -0.548109 0.000000 +-0.707107 -0.707107 0.000000 +-0.836407 -0.548109 0.000000 +-0.929042 -0.369974 0.000000 +-0.836407 -0.548109 0.000000 +-0.836407 -0.548109 0.000000 +-0.929042 -0.369974 0.000000 +-0.836407 -0.548109 0.000000 +-0.929042 -0.369974 0.000000 +-0.982801 -0.184667 0.000000 +-0.929042 -0.369974 0.000000 +-0.929042 -0.369974 0.000000 +0.995816 -0.091379 0.000000 +0.995816 -0.091379 0.000000 +0.982801 -0.184667 0.000000 +-0.982801 -0.184667 0.000000 +-0.995816 -0.091379 0.000000 +-0.995816 -0.091379 0.000000 +-0.982801 -0.184667 0.000000 +-0.995816 -0.091379 0.000000 +-0.982801 -0.184667 0.000000 +-0.929042 -0.369975 0.000000 +-0.982801 -0.184667 0.000000 +-0.982801 -0.184667 0.000000 +-0.929042 -0.369975 0.000000 +-0.982801 -0.184667 0.000000 +-0.929042 -0.369975 0.000000 +-0.929042 -0.369975 0.000000 +-0.929042 -0.369975 0.000000 +-0.836407 -0.548108 0.000000 +-0.836407 -0.548108 0.000000 +-0.929042 -0.369975 0.000000 +-0.836407 -0.548108 0.000000 +-0.707107 -0.707106 0.000000 +-0.836407 -0.548108 0.000000 +-0.836407 -0.548108 0.000000 +-0.707107 -0.707106 0.000000 +-0.836407 -0.548108 0.000000 +-0.707107 -0.707106 0.000000 +-0.548103 -0.836411 0.000000 +-0.707107 -0.707106 0.000000 +-0.707107 -0.707106 0.000000 +-0.548103 -0.836411 0.000000 +-0.707107 -0.707106 0.000000 +-0.548103 -0.836411 0.000000 +-0.369978 -0.929040 0.000000 +-0.548103 -0.836411 0.000000 +-0.548103 -0.836411 0.000000 +-0.369978 -0.929040 0.000000 +-0.548103 -0.836411 0.000000 +-0.369978 -0.929040 0.000000 +-0.184671 -0.982800 0.000000 +-0.369978 -0.929040 0.000000 +-0.369978 -0.929040 0.000000 +-0.184671 -0.982800 0.000000 +-0.369978 -0.929040 0.000000 +-0.184671 -0.982800 0.000000 +-0.000003 -1.000000 0.000000 +-0.184671 -0.982800 0.000000 +-0.184671 -0.982800 0.000000 +-0.000003 -1.000000 0.000000 +-0.184671 -0.982800 0.000000 +-0.000003 -1.000000 0.000000 +0.184668 -0.982801 0.000000 +-0.000003 -1.000000 0.000000 +-0.000003 -1.000000 0.000000 +0.184668 -0.982801 0.000000 +-0.000003 -1.000000 0.000000 +0.184668 -0.982801 0.000000 +0.369978 -0.929040 0.000000 +0.184668 -0.982801 0.000000 +0.184668 -0.982801 0.000000 +0.369978 -0.929040 0.000000 +0.184668 -0.982801 0.000000 +0.369978 -0.929040 0.000000 +0.548103 -0.836411 0.000000 +0.369978 -0.929040 0.000000 +0.369978 -0.929040 0.000000 +0.548103 -0.836411 0.000000 +0.369978 -0.929040 0.000000 +0.548103 -0.836411 0.000000 +0.707107 -0.707106 0.000000 +0.548103 -0.836411 0.000000 +0.548103 -0.836411 0.000000 +0.707107 -0.707106 0.000000 +0.548103 -0.836411 0.000000 +0.707107 -0.707106 0.000000 +0.707107 -0.707106 0.000000 +0.707107 -0.707106 0.000000 +0.836407 -0.548108 0.000000 +0.836407 -0.548108 0.000000 +0.707107 -0.707106 0.000000 +0.836407 -0.548108 0.000000 +0.929042 -0.369975 0.000000 +0.836407 -0.548108 0.000000 +0.836407 -0.548108 0.000000 +0.929042 -0.369975 0.000000 +0.836407 -0.548108 0.000000 +0.929042 -0.369975 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369975 0.000000 +0.929042 -0.369975 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369975 0.000000 +0.982801 -0.184667 0.000000 +0.982801 -0.184667 0.000000 +0.982801 -0.184667 0.000000 +0.995816 -0.091379 0.000000 +-0.982801 -0.184667 0.000000 +-0.995816 -0.091379 0.000000 +-0.995816 -0.091379 0.000000 +0.995816 -0.091379 0.000000 +0.995816 -0.091379 0.000000 +0.982801 -0.184667 0.000000 +0.982801 -0.184667 0.000000 +0.995816 -0.091379 0.000000 +0.982801 -0.184667 0.000000 +0.982801 -0.184667 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369974 0.000000 +0.929042 -0.369974 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369974 0.000000 +0.836407 -0.548109 0.000000 +0.929042 -0.369974 0.000000 +0.929042 -0.369974 0.000000 +0.836407 -0.548109 0.000000 +0.929042 -0.369974 0.000000 +0.836407 -0.548109 0.000000 +0.836407 -0.548109 0.000000 +0.836407 -0.548109 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836407 -0.548109 0.000000 +0.707107 -0.707107 0.000000 +0.548103 -0.836411 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.548103 -0.836411 0.000000 +0.707107 -0.707107 0.000000 +0.548103 -0.836411 0.000000 +0.369978 -0.929040 0.000000 +0.548103 -0.836411 0.000000 +0.548103 -0.836411 0.000000 +0.369978 -0.929040 0.000000 +0.548103 -0.836411 0.000000 +0.369978 -0.929040 0.000000 +0.184667 -0.982801 0.000000 +0.369978 -0.929040 0.000000 +0.369978 -0.929040 0.000000 +0.184667 -0.982801 0.000000 +0.369978 -0.929040 0.000000 +0.184667 -0.982801 0.000000 +-0.000003 -1.000000 0.000000 +0.184667 -0.982801 0.000000 +0.184667 -0.982801 0.000000 +-0.000003 -1.000000 0.000000 +0.184667 -0.982801 0.000000 +-0.000003 -1.000000 0.000000 +-0.000003 -1.000000 0.000000 +-0.000003 -1.000000 0.000000 +-0.184670 -0.982801 0.000000 +-0.184670 -0.982800 0.000000 +-0.000003 -1.000000 0.000000 +-0.184670 -0.982801 0.000000 +-0.369978 -0.929040 0.000000 +-0.184670 -0.982800 0.000000 +-0.184670 -0.982801 0.000000 +-0.369978 -0.929040 0.000000 +-0.184670 -0.982801 0.000000 +-0.369978 -0.929040 0.000000 +-0.548103 -0.836411 0.000000 +-0.369978 -0.929040 0.000000 +-0.369978 -0.929040 0.000000 +-0.548103 -0.836411 0.000000 +-0.369978 -0.929040 0.000000 +-0.548103 -0.836411 0.000000 +-0.707107 -0.707107 0.000000 +-0.548103 -0.836411 0.000000 +-0.548103 -0.836411 0.000000 +-0.707107 -0.707107 0.000000 +-0.548103 -0.836411 0.000000 +-0.707107 -0.707107 0.000000 +-0.836407 -0.548109 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836407 -0.548109 0.000000 +-0.707107 -0.707107 0.000000 +-0.836407 -0.548109 0.000000 +-0.929042 -0.369974 0.000000 +-0.836407 -0.548109 0.000000 +-0.836407 -0.548109 0.000000 +-0.929042 -0.369974 0.000000 +-0.836407 -0.548109 0.000000 +-0.929042 -0.369974 0.000000 +-0.982801 -0.184667 0.000000 +-0.929042 -0.369974 0.000000 +-0.929042 -0.369974 0.000000 +-0.982801 -0.184667 0.000000 +-0.929042 -0.369974 0.000000 +-0.982801 -0.184667 0.000000 +-0.995816 -0.091379 0.000000 +-0.982801 -0.184667 0.000000 +-0.982801 -0.184667 0.000000 +0.995816 -0.091379 0.000000 +0.995816 -0.091379 0.000000 +0.982801 -0.184667 0.000000 +-0.982801 -0.184667 0.000000 +-0.995816 -0.091379 0.000000 +-0.995816 -0.091379 0.000000 +-0.982801 -0.184667 0.000000 +-0.995816 -0.091379 0.000000 +-0.982801 -0.184667 0.000000 +-0.929042 -0.369975 0.000000 +-0.982801 -0.184667 0.000000 +-0.982801 -0.184667 0.000000 +-0.929042 -0.369975 0.000000 +-0.982801 -0.184667 0.000000 +-0.929042 -0.369975 0.000000 +-0.836407 -0.548108 0.000000 +-0.929042 -0.369975 0.000000 +-0.929042 -0.369975 0.000000 +-0.836407 -0.548108 0.000000 +-0.929042 -0.369975 0.000000 +-0.836407 -0.548108 0.000000 +-0.836407 -0.548108 0.000000 +-0.836407 -0.548108 0.000000 +-0.707107 -0.707106 0.000000 +-0.707107 -0.707106 0.000000 +-0.836407 -0.548108 0.000000 +-0.707107 -0.707106 0.000000 +-0.548103 -0.836411 0.000000 +-0.707107 -0.707106 0.000000 +-0.707107 -0.707106 0.000000 +-0.548103 -0.836411 0.000000 +-0.707107 -0.707106 0.000000 +-0.548103 -0.836411 0.000000 +-0.369978 -0.929040 0.000000 +-0.548103 -0.836411 0.000000 +-0.548103 -0.836411 0.000000 +-0.369978 -0.929040 0.000000 +-0.548103 -0.836411 0.000000 +-0.369978 -0.929040 0.000000 +-0.184671 -0.982800 0.000000 +-0.369978 -0.929040 0.000000 +-0.369978 -0.929040 0.000000 +-0.184671 -0.982800 0.000000 +-0.369978 -0.929040 0.000000 +-0.184671 -0.982800 0.000000 +-0.000003 -1.000000 0.000000 +-0.184671 -0.982800 0.000000 +-0.184671 -0.982800 0.000000 +-0.000003 -1.000000 0.000000 +-0.184671 -0.982800 0.000000 +-0.000003 -1.000000 0.000000 +0.184668 -0.982801 0.000000 +-0.000003 -1.000000 0.000000 +-0.000003 -1.000000 0.000000 +0.184668 -0.982801 0.000000 +-0.000003 -1.000000 0.000000 +0.184668 -0.982801 0.000000 +0.369978 -0.929041 0.000000 +0.184668 -0.982801 0.000000 +0.184668 -0.982801 0.000000 +0.369978 -0.929041 0.000000 +0.184668 -0.982801 0.000000 +0.369978 -0.929040 0.000000 +0.369978 -0.929041 0.000000 +0.369978 -0.929040 0.000000 +0.548103 -0.836411 0.000000 +0.548103 -0.836411 0.000000 +0.369978 -0.929041 0.000000 +0.548103 -0.836411 0.000000 +0.707107 -0.707106 0.000000 +0.548103 -0.836411 0.000000 +0.548103 -0.836411 0.000000 +0.707107 -0.707106 0.000000 +0.548103 -0.836411 0.000000 +0.707107 -0.707106 0.000000 +0.707107 -0.707106 0.000000 +0.707107 -0.707106 0.000000 +0.836407 -0.548108 0.000000 +0.836407 -0.548108 0.000000 +0.707107 -0.707106 0.000000 +0.836407 -0.548108 0.000000 +0.929042 -0.369975 0.000000 +0.836407 -0.548108 0.000000 +0.836407 -0.548108 0.000000 +0.929042 -0.369975 0.000000 +0.836407 -0.548108 0.000000 +0.929042 -0.369975 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369975 0.000000 +0.929042 -0.369975 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369975 0.000000 +0.982801 -0.184667 0.000000 +0.982801 -0.184667 0.000000 +0.982801 -0.184667 0.000000 +0.995816 -0.091379 0.000000 +-0.982801 -0.184667 0.000000 +-0.995816 -0.091379 0.000000 +-0.995816 -0.091379 0.000000 +0.995816 -0.091379 0.000000 +0.995816 -0.091379 0.000000 +0.982801 -0.184667 0.000000 +0.982801 -0.184667 0.000000 +0.995816 -0.091379 0.000000 +0.982801 -0.184667 0.000000 +0.982801 -0.184667 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369974 0.000000 +0.929042 -0.369974 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369974 0.000000 +0.836407 -0.548109 0.000000 +0.929042 -0.369974 0.000000 +0.929042 -0.369974 0.000000 +0.836407 -0.548109 0.000000 +0.929042 -0.369974 0.000000 +0.836407 -0.548109 0.000000 +0.707107 -0.707107 0.000000 +0.836407 -0.548109 0.000000 +0.836407 -0.548109 0.000000 +0.707107 -0.707107 0.000000 +0.836407 -0.548109 0.000000 +0.707107 -0.707107 0.000000 +0.548103 -0.836411 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.548103 -0.836411 0.000000 +0.707107 -0.707107 0.000000 +0.548103 -0.836411 0.000000 +0.369978 -0.929040 0.000000 +0.548103 -0.836411 0.000000 +0.548103 -0.836411 0.000000 +0.369978 -0.929040 0.000000 +0.548103 -0.836411 0.000000 +0.369978 -0.929040 0.000000 +0.184667 -0.982801 0.000000 +0.369978 -0.929040 0.000000 +0.369978 -0.929040 0.000000 +0.184667 -0.982801 0.000000 +0.369978 -0.929040 0.000000 +0.184667 -0.982801 0.000000 +-0.000003 -1.000000 0.000000 +0.184667 -0.982801 0.000000 +0.184667 -0.982801 0.000000 +-0.000003 -1.000000 0.000000 +0.184667 -0.982801 0.000000 +-0.000003 -1.000000 0.000000 +-0.184670 -0.982801 0.000000 +-0.000003 -1.000000 0.000000 +-0.000003 -1.000000 0.000000 +-0.184670 -0.982801 0.000000 +-0.000003 -1.000000 0.000000 +-0.184670 -0.982801 0.000000 +-0.369978 -0.929040 0.000000 +-0.184670 -0.982801 0.000000 +-0.184670 -0.982801 0.000000 +-0.369978 -0.929040 0.000000 +-0.184670 -0.982801 0.000000 +-0.369978 -0.929040 0.000000 +-0.548103 -0.836411 0.000000 +-0.369978 -0.929040 0.000000 +-0.369978 -0.929040 0.000000 +-0.548103 -0.836411 0.000000 +-0.369978 -0.929040 0.000000 +-0.548103 -0.836411 0.000000 +-0.707107 -0.707107 0.000000 +-0.548103 -0.836411 0.000000 +-0.548103 -0.836411 0.000000 +-0.707107 -0.707107 0.000000 +-0.548103 -0.836411 0.000000 +-0.707107 -0.707107 0.000000 +-0.836407 -0.548109 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836407 -0.548109 0.000000 +-0.707107 -0.707107 0.000000 +-0.836407 -0.548109 0.000000 +-0.929042 -0.369974 0.000000 +-0.836407 -0.548109 0.000000 +-0.836407 -0.548109 0.000000 +-0.929042 -0.369974 0.000000 +-0.836407 -0.548109 0.000000 +-0.929042 -0.369974 0.000000 +-0.982801 -0.184667 0.000000 +-0.929042 -0.369974 0.000000 +-0.929042 -0.369974 0.000000 +-0.982801 -0.184667 0.000000 +-0.929042 -0.369974 0.000000 +-0.982801 -0.184667 0.000000 +-0.995816 -0.091379 0.000000 +-0.982801 -0.184667 0.000000 +-0.982801 -0.184667 0.000000 +-0.982801 -0.184666 0.000000 +-0.995819 -0.091349 0.000000 +-0.995819 -0.091349 0.000000 +0.982801 -0.184667 0.000000 +0.995816 -0.091379 0.000000 +0.995816 -0.091379 0.000000 +0.982801 -0.184667 0.000000 +0.995816 -0.091379 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369975 0.000000 +0.982801 -0.184667 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369975 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369975 0.000000 +0.836407 -0.548108 0.000000 +0.929042 -0.369975 0.000000 +0.929042 -0.369975 0.000000 +0.836407 -0.548108 0.000000 +0.929042 -0.369975 0.000000 +0.836407 -0.548108 0.000000 +0.707107 -0.707106 0.000000 +0.836407 -0.548108 0.000000 +0.836407 -0.548108 0.000000 +0.707107 -0.707106 0.000000 +0.836407 -0.548108 0.000000 +0.707107 -0.707106 0.000000 +0.548103 -0.836411 0.000000 +0.707107 -0.707106 0.000000 +0.707107 -0.707106 0.000000 +0.548103 -0.836411 0.000000 +0.707107 -0.707106 0.000000 +0.548103 -0.836411 0.000000 +0.369974 -0.929042 0.000000 +0.548103 -0.836411 0.000000 +0.548103 -0.836411 0.000000 +0.369974 -0.929042 0.000000 +0.548103 -0.836411 0.000000 +0.369974 -0.929042 0.000000 +0.184667 -0.982801 0.000000 +0.369974 -0.929042 0.000000 +0.369974 -0.929042 0.000000 +0.184667 -0.982801 0.000000 +0.369974 -0.929042 0.000000 +0.184667 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +0.184667 -0.982801 0.000000 +0.184667 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +0.184667 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +-0.184665 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +0.000001 -1.000000 0.000000 +-0.184665 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +-0.184665 -0.982801 0.000000 +-0.369974 -0.929042 0.000000 +-0.184665 -0.982801 0.000000 +-0.184665 -0.982801 0.000000 +-0.369974 -0.929042 0.000000 +-0.184665 -0.982801 0.000000 +-0.369974 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.369974 -0.929042 0.000000 +-0.369974 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.369974 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.707106 -0.707108 0.000000 +-0.548110 -0.836406 0.000000 +-0.548110 -0.836406 0.000000 +-0.707106 -0.707108 0.000000 +-0.548110 -0.836406 0.000000 +-0.707106 -0.707108 0.000000 +-0.836408 -0.548107 0.000000 +-0.707106 -0.707108 0.000000 +-0.707106 -0.707108 0.000000 +-0.836408 -0.548107 0.000000 +-0.707106 -0.707108 0.000000 +-0.836408 -0.548107 0.000000 +-0.929041 -0.369976 0.000000 +-0.836408 -0.548107 0.000000 +-0.836408 -0.548107 0.000000 +-0.929041 -0.369976 0.000000 +-0.836408 -0.548107 0.000000 +-0.929041 -0.369976 0.000000 +-0.929041 -0.369976 0.000000 +-0.929041 -0.369976 0.000000 +-0.982801 -0.184666 0.000000 +-0.982801 -0.184666 0.000000 +-0.929041 -0.369976 0.000000 +-0.982801 -0.184666 0.000000 +-0.995819 -0.091349 0.000000 +-0.982801 -0.184666 0.000000 +-0.982801 -0.184666 0.000000 +-0.982801 -0.184665 0.000000 +-0.982801 -0.184665 0.000000 +-0.929041 -0.369976 0.000000 +-0.995819 -0.091349 0.000000 +-0.995819 -0.091349 0.000000 +-0.982801 -0.184665 0.000000 +-0.982801 -0.184665 0.000000 +-0.995819 -0.091349 0.000000 +-0.982801 -0.184665 0.000000 +0.995816 -0.091379 0.000000 +0.995816 -0.091379 0.000000 +0.982801 -0.184667 0.000000 +0.982801 -0.184667 0.000000 +0.995816 -0.091379 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369974 0.000000 +0.982801 -0.184667 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369974 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369974 0.000000 +0.836407 -0.548109 0.000000 +0.929042 -0.369974 0.000000 +0.929042 -0.369974 0.000000 +0.836407 -0.548109 0.000000 +0.929042 -0.369974 0.000000 +0.836407 -0.548109 0.000000 +0.707107 -0.707107 0.000000 +0.836407 -0.548109 0.000000 +0.836407 -0.548109 0.000000 +0.707107 -0.707107 0.000000 +0.836407 -0.548109 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.548103 -0.836411 0.000000 +0.548103 -0.836411 0.000000 +0.707107 -0.707107 0.000000 +0.548103 -0.836411 0.000000 +0.369975 -0.929042 0.000000 +0.548103 -0.836411 0.000000 +0.548103 -0.836411 0.000000 +0.369975 -0.929042 0.000000 +0.548103 -0.836411 0.000000 +0.369975 -0.929042 0.000000 +0.184666 -0.982801 0.000000 +0.369975 -0.929042 0.000000 +0.369975 -0.929042 0.000000 +0.184666 -0.982801 0.000000 +0.369975 -0.929042 0.000000 +0.184666 -0.982801 0.000000 +0.184666 -0.982801 0.000000 +0.184666 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +0.000001 -1.000000 0.000000 +0.184666 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +0.000001 -1.000000 0.000000 +0.000001 -1.000000 0.000000 +-0.184665 -0.982802 0.000000 +-0.184665 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +-0.184665 -0.982802 0.000000 +-0.369975 -0.929042 0.000000 +-0.184665 -0.982802 0.000000 +-0.184665 -0.982802 0.000000 +-0.369975 -0.929042 0.000000 +-0.184665 -0.982802 0.000000 +-0.369975 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.369975 -0.929042 0.000000 +-0.369975 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.369975 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.707106 -0.707108 0.000000 +-0.548110 -0.836406 0.000000 +-0.548110 -0.836406 0.000000 +-0.707106 -0.707108 0.000000 +-0.548110 -0.836406 0.000000 +-0.707106 -0.707108 0.000000 +-0.836408 -0.548107 0.000000 +-0.707106 -0.707108 0.000000 +-0.707106 -0.707108 0.000000 +-0.836408 -0.548107 0.000000 +-0.707106 -0.707108 0.000000 +-0.836408 -0.548107 0.000000 +-0.836408 -0.548107 0.000000 +-0.836408 -0.548107 0.000000 +-0.929041 -0.369976 0.000000 +-0.929041 -0.369976 0.000000 +-0.836408 -0.548107 0.000000 +-0.929041 -0.369976 0.000000 +-0.929041 -0.369976 0.000000 +-0.929041 -0.369976 0.000000 +-0.982801 -0.184665 0.000000 +0.982801 -0.184667 0.000000 +0.995816 -0.091379 0.000000 +0.995816 -0.091379 0.000000 +-0.982801 -0.184666 0.000000 +-0.995819 -0.091349 0.000000 +-0.995819 -0.091349 0.000000 +-0.982801 -0.184666 0.000000 +-0.995819 -0.091349 0.000000 +-0.982801 -0.184666 0.000000 +-0.929041 -0.369976 0.000000 +-0.982801 -0.184666 0.000000 +-0.982801 -0.184666 0.000000 +-0.929041 -0.369976 0.000000 +-0.982801 -0.184666 0.000000 +-0.929041 -0.369976 0.000000 +-0.836408 -0.548107 0.000000 +-0.929041 -0.369976 0.000000 +-0.929041 -0.369976 0.000000 +-0.836408 -0.548107 0.000000 +-0.929041 -0.369976 0.000000 +-0.836408 -0.548107 0.000000 +-0.707106 -0.707108 0.000000 +-0.836408 -0.548107 0.000000 +-0.836408 -0.548107 0.000000 +-0.707106 -0.707108 0.000000 +-0.836408 -0.548107 0.000000 +-0.707106 -0.707108 0.000000 +-0.548110 -0.836406 0.000000 +-0.707106 -0.707108 0.000000 +-0.707106 -0.707108 0.000000 +-0.548110 -0.836406 0.000000 +-0.707106 -0.707108 0.000000 +-0.548110 -0.836406 0.000000 +-0.548110 -0.836406 0.000000 +-0.548110 -0.836406 0.000000 +-0.369974 -0.929042 0.000000 +-0.369974 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.369974 -0.929042 0.000000 +-0.184665 -0.982801 0.000000 +-0.369974 -0.929042 0.000000 +-0.369974 -0.929042 0.000000 +-0.184665 -0.982801 0.000000 +-0.369974 -0.929042 0.000000 +-0.184665 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +-0.184665 -0.982801 0.000000 +-0.184665 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +-0.184665 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +0.184667 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +0.000001 -1.000000 0.000000 +0.184667 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +0.184667 -0.982801 0.000000 +0.369974 -0.929042 0.000000 +0.184667 -0.982801 0.000000 +0.184667 -0.982801 0.000000 +0.369974 -0.929042 0.000000 +0.184667 -0.982801 0.000000 +0.369974 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.369974 -0.929042 0.000000 +0.369974 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.369974 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707108 0.000000 +0.548110 -0.836406 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707108 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707108 0.000000 +0.836402 -0.548117 0.000000 +0.707106 -0.707108 0.000000 +0.707106 -0.707108 0.000000 +0.836402 -0.548117 0.000000 +0.707106 -0.707108 0.000000 +0.836402 -0.548117 0.000000 +0.929042 -0.369975 0.000000 +0.836402 -0.548117 0.000000 +0.836402 -0.548117 0.000000 +0.929042 -0.369975 0.000000 +0.836402 -0.548117 0.000000 +0.929042 -0.369975 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369975 0.000000 +0.929042 -0.369975 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369975 0.000000 +0.982801 -0.184667 0.000000 +0.995816 -0.091379 0.000000 +0.982801 -0.184667 0.000000 +0.982801 -0.184667 0.000000 +-0.548110 -0.836406 0.000000 +-0.707106 -0.707108 0.000000 +-0.707106 -0.707108 0.000000 +-0.995819 -0.091349 0.000000 +-0.995819 -0.091349 0.000000 +-0.982801 -0.184665 0.000000 +-0.982801 -0.184665 0.000000 +-0.995819 -0.091349 0.000000 +-0.982801 -0.184665 0.000000 +-0.929041 -0.369976 0.000000 +-0.982801 -0.184665 0.000000 +-0.982801 -0.184665 0.000000 +-0.929041 -0.369976 0.000000 +-0.982801 -0.184665 0.000000 +-0.929041 -0.369976 0.000000 +-0.836408 -0.548107 0.000000 +-0.929041 -0.369976 0.000000 +-0.929041 -0.369976 0.000000 +-0.836408 -0.548107 0.000000 +-0.929041 -0.369976 0.000000 +-0.836408 -0.548107 0.000000 +-0.836408 -0.548107 0.000000 +-0.836408 -0.548107 0.000000 +-0.707106 -0.707108 0.000000 +-0.707106 -0.707108 0.000000 +-0.836408 -0.548107 0.000000 +-0.707106 -0.707108 0.000000 +0.982801 -0.184667 0.000000 +0.995816 -0.091379 0.000000 +0.995816 -0.091379 0.000000 +0.982801 -0.184667 0.000000 +0.995816 -0.091379 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369974 0.000000 +0.982801 -0.184667 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369974 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369974 0.000000 +0.929042 -0.369974 0.000000 +0.929042 -0.369974 0.000000 +0.836401 -0.548117 0.000000 +0.836401 -0.548117 0.000000 +0.929042 -0.369974 0.000000 +0.836401 -0.548117 0.000000 +0.707106 -0.707108 0.000000 +0.836401 -0.548117 0.000000 +0.836401 -0.548117 0.000000 +0.707106 -0.707108 0.000000 +0.836401 -0.548117 0.000000 +0.707106 -0.707108 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707108 0.000000 +0.707106 -0.707108 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707108 0.000000 +0.548110 -0.836406 0.000000 +0.369975 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.548110 -0.836406 0.000000 +0.369975 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.369975 -0.929042 0.000000 +0.184666 -0.982801 0.000000 +0.369975 -0.929042 0.000000 +0.369975 -0.929042 0.000000 +0.184666 -0.982801 0.000000 +0.369975 -0.929042 0.000000 +0.184666 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +0.184666 -0.982801 0.000000 +0.184666 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +0.184666 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +-0.184665 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +0.000001 -1.000000 0.000000 +-0.184665 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +-0.184665 -0.982802 0.000000 +-0.369975 -0.929042 0.000000 +-0.184665 -0.982802 0.000000 +-0.184665 -0.982802 0.000000 +-0.369975 -0.929042 0.000000 +-0.184665 -0.982802 0.000000 +-0.369975 -0.929042 0.000000 +-0.369975 -0.929042 0.000000 +-0.369975 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.548110 -0.836406 0.000000 +-0.369975 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.707106 -0.707108 0.000000 +-0.548110 -0.836406 0.000000 +-0.548110 -0.836406 0.000000 +-0.982801 -0.184666 0.000000 +-0.995819 -0.091349 0.000000 +-0.995819 -0.091349 0.000000 +0.982801 -0.184667 0.000000 +0.995816 -0.091379 0.000000 +0.995816 -0.091379 0.000000 +0.982801 -0.184667 0.000000 +0.995816 -0.091379 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369975 0.000000 +0.982801 -0.184667 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369975 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369975 0.000000 +0.836402 -0.548117 0.000000 +0.929042 -0.369975 0.000000 +0.929042 -0.369975 0.000000 +0.836402 -0.548117 0.000000 +0.929042 -0.369975 0.000000 +0.836402 -0.548117 0.000000 +0.707106 -0.707108 0.000000 +0.836402 -0.548117 0.000000 +0.836402 -0.548117 0.000000 +0.707106 -0.707108 0.000000 +0.836402 -0.548117 0.000000 +0.707106 -0.707108 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707108 0.000000 +0.707106 -0.707108 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707108 0.000000 +0.548110 -0.836406 0.000000 +0.369974 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.548110 -0.836406 0.000000 +0.369974 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.369974 -0.929042 0.000000 +0.184667 -0.982801 0.000000 +0.369974 -0.929042 0.000000 +0.369974 -0.929042 0.000000 +0.184667 -0.982801 0.000000 +0.369974 -0.929042 0.000000 +0.184667 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +0.184667 -0.982801 0.000000 +0.184667 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +0.184667 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +-0.184665 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +0.000001 -1.000000 0.000000 +-0.184665 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +-0.184665 -0.982801 0.000000 +-0.369974 -0.929042 0.000000 +-0.184665 -0.982801 0.000000 +-0.184665 -0.982801 0.000000 +-0.369974 -0.929042 0.000000 +-0.184665 -0.982801 0.000000 +-0.369974 -0.929042 0.000000 +-0.369974 -0.929042 0.000000 +-0.369974 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.548110 -0.836406 0.000000 +-0.369974 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.707106 -0.707108 0.000000 +-0.548110 -0.836406 0.000000 +-0.548110 -0.836406 0.000000 +-0.707106 -0.707108 0.000000 +-0.548110 -0.836406 0.000000 +-0.707106 -0.707108 0.000000 +-0.836408 -0.548107 0.000000 +-0.707106 -0.707108 0.000000 +-0.707106 -0.707108 0.000000 +-0.836408 -0.548107 0.000000 +-0.707106 -0.707108 0.000000 +-0.836408 -0.548107 0.000000 +-0.929041 -0.369976 0.000000 +-0.836408 -0.548107 0.000000 +-0.836408 -0.548107 0.000000 +-0.929041 -0.369976 0.000000 +-0.836408 -0.548107 0.000000 +-0.929041 -0.369976 0.000000 +-0.929041 -0.369976 0.000000 +-0.929041 -0.369976 0.000000 +-0.982801 -0.184666 0.000000 +-0.982801 -0.184666 0.000000 +-0.929041 -0.369976 0.000000 +-0.982801 -0.184666 0.000000 +-0.995819 -0.091349 0.000000 +-0.982801 -0.184666 0.000000 +-0.982801 -0.184666 0.000000 +0.982801 -0.184667 0.000000 +0.995816 -0.091379 0.000000 +0.995816 -0.091379 0.000000 +-0.995819 -0.091349 0.000000 +-0.995819 -0.091349 0.000000 +-0.982801 -0.184665 0.000000 +-0.982801 -0.184665 0.000000 +-0.995819 -0.091349 0.000000 +-0.982801 -0.184665 0.000000 +-0.929041 -0.369976 0.000000 +-0.982801 -0.184665 0.000000 +-0.982801 -0.184665 0.000000 +-0.929041 -0.369976 0.000000 +-0.982801 -0.184665 0.000000 +-0.929041 -0.369976 0.000000 +-0.929041 -0.369976 0.000000 +-0.929041 -0.369976 0.000000 +-0.836408 -0.548107 0.000000 +-0.836408 -0.548107 0.000000 +-0.929041 -0.369976 0.000000 +-0.836408 -0.548107 0.000000 +-0.836408 -0.548107 0.000000 +-0.836408 -0.548107 0.000000 +-0.707106 -0.707108 0.000000 +-0.707106 -0.707108 0.000000 +-0.836408 -0.548107 0.000000 +-0.707106 -0.707108 0.000000 +-0.707106 -0.707108 0.000000 +-0.707106 -0.707108 0.000000 +-0.548110 -0.836406 0.000000 +-0.548110 -0.836406 0.000000 +-0.707106 -0.707108 0.000000 +-0.548110 -0.836406 0.000000 +-0.369975 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.548110 -0.836406 0.000000 +-0.369975 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.369975 -0.929042 0.000000 +-0.369975 -0.929042 0.000000 +-0.369975 -0.929042 0.000000 +-0.184665 -0.982802 0.000000 +-0.184665 -0.982802 0.000000 +-0.369975 -0.929042 0.000000 +-0.184665 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +-0.184665 -0.982802 0.000000 +-0.184665 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +-0.184665 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +0.184666 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +0.000001 -1.000000 0.000000 +0.184666 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +0.184666 -0.982801 0.000000 +0.369975 -0.929042 0.000000 +0.184666 -0.982801 0.000000 +0.184666 -0.982801 0.000000 +0.369975 -0.929042 0.000000 +0.184666 -0.982801 0.000000 +0.369975 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.369975 -0.929042 0.000000 +0.369975 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.369975 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707108 0.000000 +0.548110 -0.836406 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707108 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707108 0.000000 +0.836401 -0.548117 0.000000 +0.707106 -0.707108 0.000000 +0.707106 -0.707108 0.000000 +0.836401 -0.548117 0.000000 +0.707106 -0.707108 0.000000 +0.836401 -0.548117 0.000000 +0.929042 -0.369974 0.000000 +0.836401 -0.548117 0.000000 +0.836401 -0.548117 0.000000 +0.929042 -0.369974 0.000000 +0.836401 -0.548117 0.000000 +0.929042 -0.369974 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369974 0.000000 +0.929042 -0.369974 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369974 0.000000 +0.982801 -0.184667 0.000000 +0.995816 -0.091379 0.000000 +0.982801 -0.184667 0.000000 +0.982801 -0.184667 0.000000 +0.982801 -0.184667 0.000000 +0.995816 -0.091379 0.000000 +0.995816 -0.091379 0.000000 +-0.982801 -0.184666 0.000000 +-0.995819 -0.091349 0.000000 +-0.995819 -0.091349 0.000000 +-0.982801 -0.184666 0.000000 +-0.995819 -0.091349 0.000000 +-0.982801 -0.184666 0.000000 +-0.929041 -0.369976 0.000000 +-0.982801 -0.184666 0.000000 +-0.982801 -0.184666 0.000000 +-0.929041 -0.369976 0.000000 +-0.982801 -0.184666 0.000000 +-0.929041 -0.369976 0.000000 +-0.929041 -0.369976 0.000000 +-0.929041 -0.369976 0.000000 +-0.836408 -0.548107 0.000000 +-0.836408 -0.548107 0.000000 +-0.929041 -0.369976 0.000000 +-0.836408 -0.548107 0.000000 +-0.707106 -0.707108 0.000000 +-0.836408 -0.548107 0.000000 +-0.836408 -0.548107 0.000000 +-0.707106 -0.707108 0.000000 +-0.836408 -0.548107 0.000000 +-0.707106 -0.707108 0.000000 +-0.548110 -0.836406 0.000000 +-0.707106 -0.707108 0.000000 +-0.707106 -0.707108 0.000000 +-0.548110 -0.836406 0.000000 +-0.707106 -0.707108 0.000000 +-0.548110 -0.836406 0.000000 +-0.369974 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.548110 -0.836406 0.000000 +-0.369974 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.369974 -0.929042 0.000000 +-0.184665 -0.982801 0.000000 +-0.369974 -0.929042 0.000000 +-0.369974 -0.929042 0.000000 +-0.184665 -0.982801 0.000000 +-0.369974 -0.929042 0.000000 +-0.184665 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +-0.184665 -0.982801 0.000000 +-0.184665 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +-0.184665 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +0.184667 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +0.000001 -1.000000 0.000000 +0.184667 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +0.184667 -0.982801 0.000000 +0.369974 -0.929042 0.000000 +0.184667 -0.982801 0.000000 +0.184667 -0.982801 0.000000 +0.369974 -0.929042 0.000000 +0.184667 -0.982801 0.000000 +0.369974 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.369974 -0.929042 0.000000 +0.369974 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.369974 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.548110 -0.836406 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707108 0.000000 +0.707106 -0.707108 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707108 0.000000 +0.836402 -0.548117 0.000000 +0.707106 -0.707108 0.000000 +0.707106 -0.707108 0.000000 +0.836402 -0.548117 0.000000 +0.707106 -0.707108 0.000000 +0.836402 -0.548117 0.000000 +0.929042 -0.369975 0.000000 +0.836402 -0.548117 0.000000 +0.836402 -0.548117 0.000000 +0.929042 -0.369975 0.000000 +0.836402 -0.548117 0.000000 +0.929042 -0.369975 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369975 0.000000 +0.929042 -0.369975 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369975 0.000000 +0.982801 -0.184667 0.000000 +0.995816 -0.091379 0.000000 +0.982801 -0.184667 0.000000 +0.982801 -0.184667 0.000000 +-0.929041 -0.369976 0.000000 +-0.929041 -0.369976 0.000000 +-0.836408 -0.548107 0.000000 +-0.982801 -0.184665 0.000000 +-0.995819 -0.091349 0.000000 +-0.995819 -0.091349 0.000000 +-0.982801 -0.184665 0.000000 +-0.995819 -0.091349 0.000000 +-0.982801 -0.184665 0.000000 +-0.929041 -0.369976 0.000000 +-0.982801 -0.184665 0.000000 +-0.982801 -0.184665 0.000000 +-0.929041 -0.369976 0.000000 +-0.982801 -0.184665 0.000000 +-0.929041 -0.369976 0.000000 +0.982801 -0.184667 0.000000 +0.995816 -0.091379 0.000000 +0.995816 -0.091379 0.000000 +0.982801 -0.184667 0.000000 +0.995816 -0.091379 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369974 0.000000 +0.982801 -0.184667 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369974 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369974 0.000000 +0.929042 -0.369974 0.000000 +0.929042 -0.369974 0.000000 +0.836401 -0.548117 0.000000 +0.836401 -0.548117 0.000000 +0.929042 -0.369974 0.000000 +0.836401 -0.548117 0.000000 +0.707106 -0.707108 0.000000 +0.836401 -0.548117 0.000000 +0.836401 -0.548117 0.000000 +0.707106 -0.707108 0.000000 +0.836401 -0.548117 0.000000 +0.707106 -0.707108 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707108 0.000000 +0.707106 -0.707108 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707108 0.000000 +0.548110 -0.836406 0.000000 +0.369975 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.548110 -0.836406 0.000000 +0.369975 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.369975 -0.929042 0.000000 +0.184666 -0.982801 0.000000 +0.369975 -0.929042 0.000000 +0.369975 -0.929042 0.000000 +0.184666 -0.982801 0.000000 +0.369975 -0.929042 0.000000 +0.184666 -0.982801 0.000000 +0.184666 -0.982801 0.000000 +0.184666 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +0.000001 -1.000000 0.000000 +0.184666 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +-0.184665 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +0.000001 -1.000000 0.000000 +-0.184665 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +-0.184665 -0.982802 0.000000 +-0.369975 -0.929042 0.000000 +-0.184665 -0.982802 0.000000 +-0.184665 -0.982802 0.000000 +-0.369975 -0.929042 0.000000 +-0.184665 -0.982802 0.000000 +-0.369975 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.369975 -0.929042 0.000000 +-0.369975 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.369975 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.707106 -0.707108 0.000000 +-0.548110 -0.836406 0.000000 +-0.548110 -0.836406 0.000000 +-0.707106 -0.707108 0.000000 +-0.548110 -0.836406 0.000000 +-0.707106 -0.707108 0.000000 +-0.836408 -0.548107 0.000000 +-0.707106 -0.707108 0.000000 +-0.707106 -0.707108 0.000000 +-0.836408 -0.548107 0.000000 +-0.707106 -0.707108 0.000000 +-0.836408 -0.548107 0.000000 +-0.836408 -0.548107 0.000000 +-0.836408 -0.548107 0.000000 +-0.929041 -0.369976 0.000000 +-0.982801 -0.184666 0.000000 +-0.995819 -0.091349 0.000000 +-0.995819 -0.091349 0.000000 +0.982801 -0.184667 0.000000 +0.995816 -0.091379 0.000000 +0.995816 -0.091379 0.000000 +0.982801 -0.184667 0.000000 +0.995816 -0.091379 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369975 0.000000 +0.982801 -0.184667 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369975 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369975 0.000000 +0.929042 -0.369975 0.000000 +0.929042 -0.369975 0.000000 +0.836402 -0.548117 0.000000 +0.836402 -0.548117 0.000000 +0.929042 -0.369975 0.000000 +0.836402 -0.548117 0.000000 +0.707106 -0.707108 0.000000 +0.836402 -0.548117 0.000000 +0.836402 -0.548117 0.000000 +0.707106 -0.707108 0.000000 +0.836402 -0.548117 0.000000 +0.707106 -0.707108 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707108 0.000000 +0.707106 -0.707108 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707108 0.000000 +0.548110 -0.836406 0.000000 +0.369974 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.548110 -0.836406 0.000000 +0.369974 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.369974 -0.929042 0.000000 +0.184667 -0.982801 0.000000 +0.369974 -0.929042 0.000000 +0.369974 -0.929042 0.000000 +0.184667 -0.982801 0.000000 +0.369974 -0.929042 0.000000 +0.184667 -0.982801 0.000000 +0.184667 -0.982801 0.000000 +0.184667 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +0.000001 -1.000000 0.000000 +0.184667 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +-0.184665 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +0.000001 -1.000000 0.000000 +-0.184665 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +-0.184665 -0.982801 0.000000 +-0.369974 -0.929042 0.000000 +-0.184665 -0.982801 0.000000 +-0.184665 -0.982801 0.000000 +-0.369974 -0.929042 0.000000 +-0.184665 -0.982801 0.000000 +-0.369974 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.369974 -0.929042 0.000000 +-0.369974 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.369974 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.707106 -0.707108 0.000000 +-0.548110 -0.836406 0.000000 +-0.548110 -0.836406 0.000000 +-0.707106 -0.707108 0.000000 +-0.548110 -0.836406 0.000000 +-0.707106 -0.707108 0.000000 +-0.836408 -0.548107 0.000000 +-0.707106 -0.707108 0.000000 +-0.707106 -0.707108 0.000000 +-0.836408 -0.548107 0.000000 +-0.707106 -0.707108 0.000000 +-0.836408 -0.548107 0.000000 +-0.929041 -0.369976 0.000000 +-0.836408 -0.548107 0.000000 +-0.836408 -0.548107 0.000000 +-0.929041 -0.369976 0.000000 +-0.836408 -0.548107 0.000000 +-0.929041 -0.369976 0.000000 +-0.982801 -0.184666 0.000000 +-0.929041 -0.369976 0.000000 +-0.929041 -0.369976 0.000000 +-0.982801 -0.184666 0.000000 +-0.929041 -0.369976 0.000000 +-0.982801 -0.184666 0.000000 +-0.995819 -0.091349 0.000000 +-0.982801 -0.184666 0.000000 +-0.982801 -0.184666 0.000000 +-0.982801 -0.184665 0.000000 +-0.982801 -0.184665 0.000000 +-0.929041 -0.369976 0.000000 +-0.982801 -0.184665 0.000000 +-0.995819 -0.091349 0.000000 +-0.995819 -0.091349 0.000000 +-0.982801 -0.184665 0.000000 +-0.995819 -0.091349 0.000000 +-0.982801 -0.184665 0.000000 +0.982801 -0.184667 0.000000 +0.995816 -0.091379 0.000000 +0.995816 -0.091379 0.000000 +0.982801 -0.184667 0.000000 +0.995816 -0.091379 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369974 0.000000 +0.982801 -0.184667 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369974 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369974 0.000000 +0.929042 -0.369974 0.000000 +0.929042 -0.369974 0.000000 +0.836401 -0.548117 0.000000 +0.836401 -0.548117 0.000000 +0.929042 -0.369974 0.000000 +0.836401 -0.548117 0.000000 +0.707106 -0.707108 0.000000 +0.836401 -0.548117 0.000000 +0.836401 -0.548117 0.000000 +0.707106 -0.707108 0.000000 +0.836401 -0.548117 0.000000 +0.707106 -0.707108 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707108 0.000000 +0.707106 -0.707108 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707108 0.000000 +0.548110 -0.836406 0.000000 +0.369975 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.548110 -0.836406 0.000000 +0.369975 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.369975 -0.929042 0.000000 +0.369975 -0.929042 0.000000 +0.369975 -0.929042 0.000000 +0.184666 -0.982801 0.000000 +0.184666 -0.982801 0.000000 +0.369975 -0.929042 0.000000 +0.184666 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +0.184666 -0.982801 0.000000 +0.184666 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +0.184666 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +-0.184665 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +0.000001 -1.000000 0.000000 +-0.184665 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +-0.184665 -0.982802 0.000000 +-0.369975 -0.929042 0.000000 +-0.184665 -0.982802 0.000000 +-0.184665 -0.982802 0.000000 +-0.369975 -0.929042 0.000000 +-0.184665 -0.982802 0.000000 +-0.369975 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.369975 -0.929042 0.000000 +-0.369975 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.369975 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.707106 -0.707108 0.000000 +-0.548110 -0.836406 0.000000 +-0.548110 -0.836406 0.000000 +-0.707106 -0.707108 0.000000 +-0.548110 -0.836406 0.000000 +-0.707106 -0.707108 0.000000 +-0.836408 -0.548107 0.000000 +-0.707106 -0.707108 0.000000 +-0.707106 -0.707108 0.000000 +-0.836408 -0.548107 0.000000 +-0.707106 -0.707108 0.000000 +-0.836408 -0.548107 0.000000 +-0.929041 -0.369976 0.000000 +-0.836408 -0.548107 0.000000 +-0.836408 -0.548107 0.000000 +-0.929041 -0.369976 0.000000 +-0.836408 -0.548107 0.000000 +-0.929041 -0.369976 0.000000 +-0.929041 -0.369976 0.000000 +-0.929041 -0.369976 0.000000 +-0.982801 -0.184665 0.000000 +0.982801 -0.184667 0.000000 +0.995816 -0.091379 0.000000 +0.995816 -0.091379 0.000000 +-0.982801 -0.184666 0.000000 +-0.995819 -0.091349 0.000000 +-0.995819 -0.091349 0.000000 +-0.982801 -0.184666 0.000000 +-0.995819 -0.091349 0.000000 +-0.982801 -0.184666 0.000000 +-0.982801 -0.184666 0.000000 +-0.982801 -0.184666 0.000000 +-0.929041 -0.369976 0.000000 +-0.929041 -0.369976 0.000000 +-0.982801 -0.184666 0.000000 +-0.929041 -0.369976 0.000000 +-0.836408 -0.548107 0.000000 +-0.929041 -0.369976 0.000000 +-0.929041 -0.369976 0.000000 +-0.836408 -0.548107 0.000000 +-0.929041 -0.369976 0.000000 +-0.836408 -0.548107 0.000000 +-0.707106 -0.707108 0.000000 +-0.836408 -0.548107 0.000000 +-0.836408 -0.548107 0.000000 +-0.707106 -0.707108 0.000000 +-0.836408 -0.548107 0.000000 +-0.707106 -0.707108 0.000000 +-0.548110 -0.836406 0.000000 +-0.707106 -0.707108 0.000000 +-0.707106 -0.707108 0.000000 +-0.548110 -0.836406 0.000000 +-0.707106 -0.707108 0.000000 +-0.548110 -0.836406 0.000000 +-0.369974 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.548110 -0.836406 0.000000 +-0.369974 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.369974 -0.929042 0.000000 +-0.184665 -0.982801 0.000000 +-0.369974 -0.929042 0.000000 +-0.369974 -0.929042 0.000000 +-0.184665 -0.982801 0.000000 +-0.369974 -0.929042 0.000000 +-0.184665 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +-0.184665 -0.982801 0.000000 +-0.184665 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +-0.184665 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +0.184667 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +0.000001 -1.000000 0.000000 +0.184667 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +0.184667 -0.982801 0.000000 +0.369974 -0.929042 0.000000 +0.184667 -0.982801 0.000000 +0.184667 -0.982801 0.000000 +0.369974 -0.929042 0.000000 +0.184667 -0.982801 0.000000 +0.369974 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.369974 -0.929042 0.000000 +0.369974 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.369974 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.548110 -0.836406 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707108 0.000000 +0.707106 -0.707108 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707108 0.000000 +0.836402 -0.548117 0.000000 +0.707106 -0.707108 0.000000 +0.707106 -0.707108 0.000000 +0.836402 -0.548117 0.000000 +0.707106 -0.707108 0.000000 +0.836402 -0.548117 0.000000 +0.929042 -0.369975 0.000000 +0.836402 -0.548117 0.000000 +0.836402 -0.548117 0.000000 +0.929042 -0.369975 0.000000 +0.836402 -0.548117 0.000000 +0.929042 -0.369975 0.000000 +0.929042 -0.369975 0.000000 +0.929042 -0.369975 0.000000 +0.982801 -0.184667 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369975 0.000000 +0.982801 -0.184667 0.000000 +0.995816 -0.091379 0.000000 +0.982801 -0.184667 0.000000 +0.982801 -0.184667 0.000000 +0.982801 -0.184667 0.000000 +0.995816 -0.091379 0.000000 +0.995816 -0.091379 0.000000 +-0.995819 -0.091349 0.000000 +-0.995819 -0.091349 0.000000 +-0.982801 -0.184665 0.000000 +-0.982801 -0.184665 0.000000 +-0.995819 -0.091349 0.000000 +-0.982801 -0.184665 0.000000 +-0.929041 -0.369976 0.000000 +-0.982801 -0.184665 0.000000 +-0.982801 -0.184665 0.000000 +-0.929041 -0.369976 0.000000 +-0.982801 -0.184665 0.000000 +-0.929041 -0.369976 0.000000 +-0.836408 -0.548107 0.000000 +-0.929041 -0.369976 0.000000 +-0.929041 -0.369976 0.000000 +-0.836408 -0.548107 0.000000 +-0.929041 -0.369976 0.000000 +-0.836408 -0.548107 0.000000 +-0.707106 -0.707108 0.000000 +-0.836408 -0.548107 0.000000 +-0.836408 -0.548107 0.000000 +-0.707106 -0.707108 0.000000 +-0.836408 -0.548107 0.000000 +-0.707106 -0.707108 0.000000 +-0.548110 -0.836406 0.000000 +-0.707106 -0.707108 0.000000 +-0.707106 -0.707108 0.000000 +-0.548110 -0.836406 0.000000 +-0.707106 -0.707108 0.000000 +-0.548110 -0.836406 0.000000 +-0.369975 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.548110 -0.836406 0.000000 +-0.369975 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.369975 -0.929042 0.000000 +-0.184665 -0.982802 0.000000 +-0.369975 -0.929042 0.000000 +-0.369975 -0.929042 0.000000 +-0.184665 -0.982802 0.000000 +-0.369975 -0.929042 0.000000 +-0.184665 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +-0.184665 -0.982802 0.000000 +-0.184665 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +-0.184665 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +0.184666 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +0.000001 -1.000000 0.000000 +0.184666 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +0.184666 -0.982801 0.000000 +0.369975 -0.929042 0.000000 +0.184666 -0.982801 0.000000 +0.184666 -0.982801 0.000000 +0.369975 -0.929042 0.000000 +0.184666 -0.982801 0.000000 +0.369975 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.369975 -0.929042 0.000000 +0.369975 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.369975 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.548110 -0.836406 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707108 0.000000 +0.707106 -0.707108 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707108 0.000000 +0.836401 -0.548117 0.000000 +0.707106 -0.707108 0.000000 +0.707106 -0.707108 0.000000 +0.836401 -0.548117 0.000000 +0.707106 -0.707108 0.000000 +0.836401 -0.548117 0.000000 +0.929042 -0.369974 0.000000 +0.836401 -0.548117 0.000000 +0.836401 -0.548117 0.000000 +0.929042 -0.369974 0.000000 +0.836401 -0.548117 0.000000 +0.929042 -0.369974 0.000000 +0.929042 -0.369974 0.000000 +0.929042 -0.369974 0.000000 +0.982801 -0.184667 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369974 0.000000 +0.982801 -0.184667 0.000000 +0.995816 -0.091379 0.000000 +0.982801 -0.184667 0.000000 +0.982801 -0.184667 0.000000 +-0.982802 -0.184665 0.000000 +-0.995817 -0.091364 0.000000 +-0.995817 -0.091364 0.000000 +0.982802 -0.184665 0.000000 +0.995817 -0.091364 0.000000 +0.995817 -0.091364 0.000000 +0.982802 -0.184665 0.000000 +0.995817 -0.091364 0.000000 +0.982802 -0.184665 0.000000 +0.929042 -0.369975 0.000000 +0.982802 -0.184665 0.000000 +0.982802 -0.184665 0.000000 +0.929042 -0.369975 0.000000 +0.982802 -0.184665 0.000000 +0.929042 -0.369975 0.000000 +0.836406 -0.548110 0.000000 +0.929042 -0.369975 0.000000 +0.929042 -0.369975 0.000000 +0.836406 -0.548110 0.000000 +0.929042 -0.369975 0.000000 +0.836406 -0.548110 0.000000 +0.707107 -0.707106 0.000000 +0.836406 -0.548110 0.000000 +0.836406 -0.548110 0.000000 +0.707107 -0.707106 0.000000 +0.836406 -0.548110 0.000000 +0.707107 -0.707106 0.000000 +0.548110 -0.836406 0.000000 +0.707107 -0.707106 0.000000 +0.707107 -0.707106 0.000000 +0.548110 -0.836406 0.000000 +0.707107 -0.707106 0.000000 +0.548110 -0.836406 0.000000 +0.369975 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.548110 -0.836406 0.000000 +0.369975 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.369975 -0.929042 0.000000 +0.184665 -0.982802 0.000000 +0.369975 -0.929042 0.000000 +0.369975 -0.929042 0.000000 +0.184665 -0.982802 0.000000 +0.369975 -0.929042 0.000000 +0.184665 -0.982802 0.000000 +0.000000 -1.000000 0.000000 +0.184665 -0.982802 0.000000 +0.184665 -0.982802 0.000000 +0.000000 -1.000000 0.000000 +0.184665 -0.982802 0.000000 +0.000000 -1.000000 0.000000 +-0.184665 -0.982802 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.184665 -0.982802 0.000000 +0.000000 -1.000000 0.000000 +-0.184665 -0.982802 0.000000 +-0.369975 -0.929042 0.000000 +-0.184665 -0.982802 0.000000 +-0.184665 -0.982802 0.000000 +-0.369975 -0.929042 0.000000 +-0.184665 -0.982802 0.000000 +-0.369975 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.369975 -0.929042 0.000000 +-0.369975 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.369975 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.707107 -0.707107 0.000000 +-0.548110 -0.836406 0.000000 +-0.548110 -0.836406 0.000000 +-0.707107 -0.707107 0.000000 +-0.548110 -0.836406 0.000000 +-0.707107 -0.707107 0.000000 +-0.836406 -0.548110 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836406 -0.548110 0.000000 +-0.707107 -0.707107 0.000000 +-0.836406 -0.548110 0.000000 +-0.929042 -0.369974 0.000000 +-0.836406 -0.548110 0.000000 +-0.836406 -0.548110 0.000000 +-0.929042 -0.369974 0.000000 +-0.836406 -0.548110 0.000000 +-0.929042 -0.369974 0.000000 +-0.982802 -0.184665 0.000000 +-0.929042 -0.369974 0.000000 +-0.929042 -0.369974 0.000000 +-0.982802 -0.184665 0.000000 +-0.929042 -0.369974 0.000000 +-0.982802 -0.184665 0.000000 +-0.995817 -0.091364 0.000000 +-0.982802 -0.184665 0.000000 +-0.982802 -0.184665 0.000000 +0.982802 -0.184664 0.000000 +0.995817 -0.091364 0.000000 +0.995817 -0.091364 0.000000 +-0.982802 -0.184664 0.000000 +-0.995817 -0.091364 0.000000 +-0.995817 -0.091364 0.000000 +-0.982802 -0.184664 0.000000 +-0.995817 -0.091364 0.000000 +-0.982802 -0.184664 0.000000 +-0.929042 -0.369974 0.000000 +-0.982802 -0.184664 0.000000 +-0.982802 -0.184664 0.000000 +-0.929042 -0.369974 0.000000 +-0.982802 -0.184664 0.000000 +-0.929042 -0.369974 0.000000 +-0.836406 -0.548110 0.000000 +-0.929042 -0.369974 0.000000 +-0.929042 -0.369974 0.000000 +-0.836406 -0.548110 0.000000 +-0.929042 -0.369974 0.000000 +-0.836406 -0.548110 0.000000 +-0.707106 -0.707107 0.000000 +-0.836406 -0.548110 0.000000 +-0.836406 -0.548110 0.000000 +-0.707106 -0.707107 0.000000 +-0.836406 -0.548110 0.000000 +-0.707106 -0.707107 0.000000 +-0.548110 -0.836406 0.000000 +-0.707106 -0.707107 0.000000 +-0.707106 -0.707107 0.000000 +-0.548110 -0.836406 0.000000 +-0.707106 -0.707107 0.000000 +-0.548110 -0.836406 0.000000 +-0.369975 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.548110 -0.836406 0.000000 +-0.369975 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.369975 -0.929042 0.000000 +-0.184665 -0.982802 0.000000 +-0.369975 -0.929042 0.000000 +-0.369975 -0.929042 0.000000 +-0.184665 -0.982802 0.000000 +-0.369975 -0.929042 0.000000 +-0.184665 -0.982802 0.000000 +0.000000 -1.000000 0.000000 +-0.184665 -0.982802 0.000000 +-0.184665 -0.982802 0.000000 +0.000000 -1.000000 0.000000 +-0.184665 -0.982802 0.000000 +0.000000 -1.000000 0.000000 +0.184665 -0.982802 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.184665 -0.982802 0.000000 +0.000000 -1.000000 0.000000 +0.184665 -0.982802 0.000000 +0.369975 -0.929042 0.000000 +0.184665 -0.982802 0.000000 +0.184665 -0.982802 0.000000 +0.369975 -0.929042 0.000000 +0.184665 -0.982802 0.000000 +0.369975 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.369975 -0.929042 0.000000 +0.369975 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.369975 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.707107 -0.707107 0.000000 +0.548110 -0.836406 0.000000 +0.548110 -0.836406 0.000000 +0.707107 -0.707107 0.000000 +0.548110 -0.836406 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836406 -0.548110 0.000000 +0.836406 -0.548110 0.000000 +0.707107 -0.707107 0.000000 +0.836406 -0.548110 0.000000 +0.929042 -0.369975 0.000000 +0.836406 -0.548110 0.000000 +0.836406 -0.548110 0.000000 +0.929042 -0.369975 0.000000 +0.836406 -0.548110 0.000000 +0.929042 -0.369975 0.000000 +0.982802 -0.184664 0.000000 +0.929042 -0.369975 0.000000 +0.929042 -0.369975 0.000000 +0.982802 -0.184664 0.000000 +0.929042 -0.369975 0.000000 +0.982802 -0.184664 0.000000 +0.995817 -0.091364 0.000000 +0.982802 -0.184664 0.000000 +0.982802 -0.184664 0.000000 +0.982802 -0.184663 0.000000 +0.995817 -0.091364 0.000000 +0.995817 -0.091364 0.000000 +-0.982802 -0.184665 0.000000 +-0.995817 -0.091364 0.000000 +-0.995817 -0.091364 0.000000 +-0.982802 -0.184665 0.000000 +-0.995817 -0.091364 0.000000 +-0.982802 -0.184665 0.000000 +-0.929042 -0.369975 0.000000 +-0.982802 -0.184665 0.000000 +-0.982802 -0.184665 0.000000 +-0.929042 -0.369975 0.000000 +-0.982802 -0.184665 0.000000 +-0.929042 -0.369975 0.000000 +-0.836406 -0.548110 0.000000 +-0.929042 -0.369975 0.000000 +-0.929042 -0.369975 0.000000 +-0.836406 -0.548110 0.000000 +-0.929042 -0.369975 0.000000 +-0.836406 -0.548110 0.000000 +-0.707107 -0.707106 0.000000 +-0.836406 -0.548110 0.000000 +-0.836406 -0.548110 0.000000 +-0.707107 -0.707106 0.000000 +-0.836406 -0.548110 0.000000 +-0.707107 -0.707106 0.000000 +-0.548110 -0.836406 0.000000 +-0.707107 -0.707106 0.000000 +-0.707107 -0.707106 0.000000 +-0.548110 -0.836406 0.000000 +-0.707107 -0.707106 0.000000 +-0.548110 -0.836406 0.000000 +-0.369975 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.548110 -0.836406 0.000000 +-0.369975 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.369975 -0.929042 0.000000 +-0.184665 -0.982801 0.000000 +-0.369975 -0.929042 0.000000 +-0.369975 -0.929042 0.000000 +-0.184665 -0.982801 0.000000 +-0.369975 -0.929042 0.000000 +-0.184665 -0.982801 0.000000 +0.000000 -1.000000 0.000000 +-0.184665 -0.982801 0.000000 +-0.184665 -0.982801 0.000000 +0.000000 -1.000000 0.000000 +-0.184665 -0.982801 0.000000 +0.000000 -1.000000 0.000000 +0.184665 -0.982802 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.184665 -0.982802 0.000000 +0.000000 -1.000000 0.000000 +0.184665 -0.982802 0.000000 +0.369974 -0.929042 0.000000 +0.184665 -0.982802 0.000000 +0.184665 -0.982802 0.000000 +0.369974 -0.929042 0.000000 +0.184665 -0.982802 0.000000 +0.369974 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.369974 -0.929042 0.000000 +0.369974 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.369974 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707107 0.000000 +0.548110 -0.836406 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707107 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707107 0.000000 +0.836406 -0.548110 0.000000 +0.707106 -0.707107 0.000000 +0.707106 -0.707107 0.000000 +0.836406 -0.548110 0.000000 +0.707106 -0.707107 0.000000 +0.836406 -0.548110 0.000000 +0.929043 -0.369972 0.000000 +0.836406 -0.548110 0.000000 +0.836406 -0.548110 0.000000 +0.929043 -0.369972 0.000000 +0.836406 -0.548110 0.000000 +0.929043 -0.369972 0.000000 +0.982802 -0.184663 0.000000 +0.929043 -0.369972 0.000000 +0.929043 -0.369972 0.000000 +0.982802 -0.184663 0.000000 +0.929043 -0.369972 0.000000 +0.982802 -0.184663 0.000000 +0.995817 -0.091364 0.000000 +0.982802 -0.184663 0.000000 +0.982802 -0.184663 0.000000 +0.982802 -0.184663 0.000000 +0.995817 -0.091364 0.000000 +0.995817 -0.091364 0.000000 +-0.982802 -0.184664 0.000000 +-0.995817 -0.091364 0.000000 +-0.995817 -0.091364 0.000000 +-0.982802 -0.184664 0.000000 +-0.995817 -0.091364 0.000000 +-0.982802 -0.184664 0.000000 +-0.929042 -0.369975 0.000000 +-0.982802 -0.184664 0.000000 +-0.982802 -0.184664 0.000000 +-0.929042 -0.369975 0.000000 +-0.982802 -0.184664 0.000000 +-0.929042 -0.369975 0.000000 +-0.836406 -0.548110 0.000000 +-0.929042 -0.369975 0.000000 +-0.929042 -0.369975 0.000000 +-0.836406 -0.548110 0.000000 +-0.929042 -0.369975 0.000000 +-0.836406 -0.548110 0.000000 +-0.836406 -0.548110 0.000000 +-0.836406 -0.548110 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836406 -0.548110 0.000000 +-0.707107 -0.707107 0.000000 +-0.548110 -0.836406 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.548110 -0.836406 0.000000 +-0.707107 -0.707107 0.000000 +-0.548110 -0.836406 0.000000 +-0.369975 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.548110 -0.836406 0.000000 +-0.369975 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.369975 -0.929042 0.000000 +-0.184665 -0.982801 0.000000 +-0.369975 -0.929042 0.000000 +-0.369975 -0.929042 0.000000 +-0.184665 -0.982801 0.000000 +-0.369975 -0.929042 0.000000 +-0.184665 -0.982801 0.000000 +0.000000 -1.000000 0.000000 +-0.184665 -0.982801 0.000000 +-0.184665 -0.982801 0.000000 +0.000000 -1.000000 0.000000 +-0.184665 -0.982801 0.000000 +0.000000 -1.000000 0.000000 +0.184664 -0.982802 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.184664 -0.982802 0.000000 +0.000000 -1.000000 0.000000 +0.184664 -0.982802 0.000000 +0.369975 -0.929042 0.000000 +0.184664 -0.982802 0.000000 +0.184664 -0.982802 0.000000 +0.369975 -0.929042 0.000000 +0.184664 -0.982802 0.000000 +0.369975 -0.929042 0.000000 +0.369975 -0.929042 0.000000 +0.369975 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.548110 -0.836406 0.000000 +0.369975 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707108 0.000000 +0.548110 -0.836406 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707108 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707108 0.000000 +0.707106 -0.707108 0.000000 +0.707106 -0.707108 0.000000 +0.836406 -0.548110 0.000000 +0.836406 -0.548110 0.000000 +0.707106 -0.707108 0.000000 +0.836406 -0.548110 0.000000 +0.836406 -0.548110 0.000000 +0.836406 -0.548110 0.000000 +0.929043 -0.369972 0.000000 +0.929043 -0.369972 0.000000 +0.836406 -0.548110 0.000000 +0.929043 -0.369972 0.000000 +0.929043 -0.369972 0.000000 +0.929043 -0.369972 0.000000 +0.982802 -0.184663 0.000000 +0.982802 -0.184663 0.000000 +0.929043 -0.369972 0.000000 +0.982802 -0.184663 0.000000 +0.995817 -0.091364 0.000000 +0.982802 -0.184663 0.000000 +0.982802 -0.184663 0.000000 +-0.995817 -0.091364 0.000000 +-0.995817 -0.091364 0.000000 +-0.982801 -0.184666 0.000000 +0.982802 -0.184663 0.000000 +0.995817 -0.091364 0.000000 +0.995817 -0.091364 0.000000 +0.982802 -0.184663 0.000000 +0.995817 -0.091364 0.000000 +0.982802 -0.184663 0.000000 +0.929043 -0.369972 0.000000 +0.982802 -0.184663 0.000000 +0.982802 -0.184663 0.000000 +0.929043 -0.369972 0.000000 +0.982802 -0.184663 0.000000 +0.929043 -0.369972 0.000000 +0.836406 -0.548110 0.000000 +0.929043 -0.369972 0.000000 +0.929043 -0.369972 0.000000 +0.836406 -0.548110 0.000000 +0.929043 -0.369972 0.000000 +0.836406 -0.548110 0.000000 +0.707106 -0.707107 0.000000 +0.836406 -0.548110 0.000000 +0.836406 -0.548110 0.000000 +0.707106 -0.707107 0.000000 +0.836406 -0.548110 0.000000 +0.707106 -0.707107 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707107 0.000000 +0.707106 -0.707107 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707107 0.000000 +0.548110 -0.836406 0.000000 +0.369975 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.548110 -0.836406 0.000000 +0.369975 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.369975 -0.929042 0.000000 +0.184665 -0.982801 0.000000 +0.369975 -0.929042 0.000000 +0.369975 -0.929042 0.000000 +0.184665 -0.982801 0.000000 +0.369975 -0.929042 0.000000 +0.184665 -0.982801 0.000000 +0.000000 -1.000000 0.000000 +0.184665 -0.982801 0.000000 +0.184665 -0.982801 0.000000 +0.000000 -1.000000 0.000000 +0.184665 -0.982801 0.000000 +0.000000 -1.000000 0.000000 +-0.184665 -0.982801 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.184665 -0.982801 0.000000 +0.000000 -1.000000 0.000000 +-0.184665 -0.982801 0.000000 +-0.369973 -0.929042 0.000000 +-0.184665 -0.982801 0.000000 +-0.184665 -0.982801 0.000000 +-0.369973 -0.929042 0.000000 +-0.184665 -0.982801 0.000000 +-0.369973 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.369973 -0.929042 0.000000 +-0.369973 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.369973 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.707108 -0.707106 0.000000 +-0.548110 -0.836406 0.000000 +-0.548110 -0.836406 0.000000 +-0.707108 -0.707106 0.000000 +-0.548110 -0.836406 0.000000 +-0.707108 -0.707106 0.000000 +-0.836406 -0.548110 0.000000 +-0.707108 -0.707106 0.000000 +-0.707108 -0.707106 0.000000 +-0.836406 -0.548110 0.000000 +-0.707108 -0.707106 0.000000 +-0.836406 -0.548110 0.000000 +-0.929042 -0.369975 0.000000 +-0.836406 -0.548110 0.000000 +-0.836406 -0.548110 0.000000 +-0.929042 -0.369975 0.000000 +-0.836406 -0.548110 0.000000 +-0.929042 -0.369975 0.000000 +-0.982801 -0.184666 0.000000 +-0.929042 -0.369975 0.000000 +-0.929042 -0.369975 0.000000 +-0.982801 -0.184666 0.000000 +-0.929042 -0.369975 0.000000 +-0.982801 -0.184666 0.000000 +-0.982801 -0.184666 0.000000 +-0.982801 -0.184666 0.000000 +-0.995817 -0.091364 0.000000 +0.982802 -0.184663 0.000000 +0.995817 -0.091364 0.000000 +0.995817 -0.091364 0.000000 +-0.982801 -0.184666 0.000000 +-0.995817 -0.091364 0.000000 +-0.995817 -0.091364 0.000000 +-0.982801 -0.184666 0.000000 +-0.995817 -0.091364 0.000000 +-0.982801 -0.184666 0.000000 +-0.929042 -0.369975 0.000000 +-0.982801 -0.184666 0.000000 +-0.982801 -0.184666 0.000000 +-0.929042 -0.369975 0.000000 +-0.982801 -0.184666 0.000000 +-0.929042 -0.369975 0.000000 +-0.836406 -0.548110 0.000000 +-0.929042 -0.369975 0.000000 +-0.929042 -0.369975 0.000000 +-0.836406 -0.548110 0.000000 +-0.929042 -0.369975 0.000000 +-0.836406 -0.548110 0.000000 +-0.707107 -0.707106 0.000000 +-0.836406 -0.548110 0.000000 +-0.836406 -0.548110 0.000000 +-0.707107 -0.707106 0.000000 +-0.836406 -0.548110 0.000000 +-0.707107 -0.707106 0.000000 +-0.548110 -0.836406 0.000000 +-0.707107 -0.707106 0.000000 +-0.707107 -0.707106 0.000000 +-0.548110 -0.836406 0.000000 +-0.707107 -0.707106 0.000000 +-0.548110 -0.836406 0.000000 +-0.369974 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.548110 -0.836406 0.000000 +-0.369974 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.369974 -0.929042 0.000000 +-0.184665 -0.982801 0.000000 +-0.369974 -0.929042 0.000000 +-0.369974 -0.929042 0.000000 +-0.184665 -0.982801 0.000000 +-0.369974 -0.929042 0.000000 +-0.184665 -0.982801 0.000000 +0.000000 -1.000000 0.000000 +-0.184665 -0.982801 0.000000 +-0.184665 -0.982801 0.000000 +0.000000 -1.000000 0.000000 +-0.184665 -0.982801 0.000000 +0.000000 -1.000000 0.000000 +0.184665 -0.982802 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.184665 -0.982802 0.000000 +0.000000 -1.000000 0.000000 +0.184665 -0.982801 0.000000 +0.369975 -0.929042 0.000000 +0.184665 -0.982802 0.000000 +0.184665 -0.982801 0.000000 +0.369975 -0.929042 0.000000 +0.184665 -0.982801 0.000000 +0.369975 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.369975 -0.929042 0.000000 +0.369975 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.369975 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707108 0.000000 +0.548110 -0.836406 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707108 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707108 0.000000 +0.707106 -0.707108 0.000000 +0.707106 -0.707108 0.000000 +0.836406 -0.548110 0.000000 +0.836406 -0.548110 0.000000 +0.707106 -0.707108 0.000000 +0.836406 -0.548110 0.000000 +0.836406 -0.548110 0.000000 +0.836406 -0.548110 0.000000 +0.929043 -0.369972 0.000000 +0.929043 -0.369972 0.000000 +0.836406 -0.548110 0.000000 +0.929043 -0.369972 0.000000 +0.929043 -0.369972 0.000000 +0.929043 -0.369972 0.000000 +0.982802 -0.184663 0.000000 +0.982802 -0.184663 0.000000 +0.929043 -0.369972 0.000000 +0.982802 -0.184663 0.000000 +0.995817 -0.091364 0.000000 +0.982802 -0.184663 0.000000 +0.982802 -0.184663 0.000000 +-0.982801 -0.184666 0.000000 +-0.995817 -0.091364 0.000000 +-0.995817 -0.091364 0.000000 +0.982801 -0.184666 0.000000 +0.995817 -0.091364 0.000000 +0.995817 -0.091364 0.000000 +0.982801 -0.184666 0.000000 +0.995817 -0.091364 0.000000 +0.982801 -0.184666 0.000000 +0.929042 -0.369975 0.000000 +0.982801 -0.184666 0.000000 +0.982801 -0.184666 0.000000 +0.929042 -0.369975 0.000000 +0.982801 -0.184666 0.000000 +0.929042 -0.369975 0.000000 +0.836408 -0.548108 0.000000 +0.929042 -0.369975 0.000000 +0.929042 -0.369975 0.000000 +0.836408 -0.548108 0.000000 +0.929042 -0.369975 0.000000 +0.836408 -0.548108 0.000000 +0.707107 -0.707107 0.000000 +0.836408 -0.548108 0.000000 +0.836408 -0.548108 0.000000 +0.707107 -0.707107 0.000000 +0.836408 -0.548108 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.548109 -0.836407 0.000000 +0.548109 -0.836407 0.000000 +0.707107 -0.707107 0.000000 +0.548109 -0.836407 0.000000 +0.369976 -0.929041 0.000000 +0.548109 -0.836407 0.000000 +0.548109 -0.836407 0.000000 +0.369976 -0.929041 0.000000 +0.548109 -0.836407 0.000000 +0.369976 -0.929041 0.000000 +0.184665 -0.982801 0.000000 +0.369976 -0.929041 0.000000 +0.369976 -0.929041 0.000000 +0.184665 -0.982801 0.000000 +0.369976 -0.929041 0.000000 +0.184665 -0.982801 0.000000 +0.000000 -1.000000 0.000000 +0.184665 -0.982801 0.000000 +0.184665 -0.982801 0.000000 +0.000000 -1.000000 0.000000 +0.184665 -0.982801 0.000000 +0.000000 -1.000000 0.000000 +-0.184665 -0.982801 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.184665 -0.982801 0.000000 +0.000000 -1.000000 0.000000 +-0.184665 -0.982801 0.000000 +-0.369973 -0.929042 0.000000 +-0.184665 -0.982801 0.000000 +-0.184665 -0.982801 0.000000 +-0.369973 -0.929042 0.000000 +-0.184665 -0.982801 0.000000 +-0.369974 -0.929042 0.000000 +-0.369973 -0.929042 0.000000 +-0.369974 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.548110 -0.836406 0.000000 +-0.369973 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.707108 -0.707106 0.000000 +-0.548110 -0.836406 0.000000 +-0.548110 -0.836406 0.000000 +-0.707108 -0.707106 0.000000 +-0.548110 -0.836406 0.000000 +-0.707108 -0.707106 0.000000 +-0.836406 -0.548110 0.000000 +-0.707108 -0.707106 0.000000 +-0.707108 -0.707106 0.000000 +-0.836406 -0.548110 0.000000 +-0.707108 -0.707106 0.000000 +-0.836406 -0.548110 0.000000 +-0.929042 -0.369975 0.000000 +-0.836406 -0.548110 0.000000 +-0.836406 -0.548110 0.000000 +-0.929042 -0.369975 0.000000 +-0.836406 -0.548110 0.000000 +-0.929042 -0.369975 0.000000 +-0.929042 -0.369975 0.000000 +-0.929042 -0.369975 0.000000 +-0.982801 -0.184666 0.000000 +-0.982801 -0.184666 0.000000 +-0.929042 -0.369975 0.000000 +-0.982801 -0.184666 0.000000 +-0.995817 -0.091364 0.000000 +-0.982801 -0.184666 0.000000 +-0.982801 -0.184666 0.000000 +-0.982801 -0.184666 0.000000 +-0.995817 -0.091364 0.000000 +-0.995817 -0.091364 0.000000 +0.982801 -0.184666 0.000000 +0.995817 -0.091364 0.000000 +0.995817 -0.091364 0.000000 +0.982801 -0.184666 0.000000 +0.995817 -0.091364 0.000000 +0.982801 -0.184666 0.000000 +0.929042 -0.369975 0.000000 +0.982801 -0.184666 0.000000 +0.982801 -0.184666 0.000000 +0.929042 -0.369975 0.000000 +0.982801 -0.184666 0.000000 +0.929042 -0.369975 0.000000 +0.836407 -0.548108 0.000000 +0.929042 -0.369975 0.000000 +0.929042 -0.369975 0.000000 +0.836407 -0.548108 0.000000 +0.929042 -0.369975 0.000000 +0.836407 -0.548108 0.000000 +0.707106 -0.707107 0.000000 +0.836407 -0.548108 0.000000 +0.836407 -0.548108 0.000000 +0.707106 -0.707107 0.000000 +0.836407 -0.548108 0.000000 +0.707106 -0.707107 0.000000 +0.548109 -0.836407 0.000000 +0.707106 -0.707107 0.000000 +0.707106 -0.707107 0.000000 +0.548109 -0.836407 0.000000 +0.707106 -0.707107 0.000000 +0.548109 -0.836407 0.000000 +0.369977 -0.929041 0.000000 +0.548109 -0.836407 0.000000 +0.548109 -0.836407 0.000000 +0.369977 -0.929041 0.000000 +0.548109 -0.836407 0.000000 +0.369977 -0.929041 0.000000 +0.184665 -0.982801 0.000000 +0.369977 -0.929041 0.000000 +0.369977 -0.929041 0.000000 +0.184665 -0.982801 0.000000 +0.369977 -0.929041 0.000000 +0.184665 -0.982802 0.000000 +0.000000 -1.000000 0.000000 +0.184665 -0.982801 0.000000 +0.184665 -0.982802 0.000000 +0.000000 -1.000000 0.000000 +0.184665 -0.982802 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.184665 -0.982801 0.000000 +-0.184665 -0.982801 0.000000 +0.000000 -1.000000 0.000000 +-0.184665 -0.982801 0.000000 +-0.369974 -0.929042 0.000000 +-0.184665 -0.982801 0.000000 +-0.184665 -0.982801 0.000000 +-0.369974 -0.929042 0.000000 +-0.184665 -0.982801 0.000000 +-0.369974 -0.929042 0.000000 +-0.369974 -0.929042 0.000000 +-0.369974 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.548110 -0.836406 0.000000 +-0.369974 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.707107 -0.707106 0.000000 +-0.548110 -0.836406 0.000000 +-0.548110 -0.836406 0.000000 +-0.707107 -0.707106 0.000000 +-0.548110 -0.836406 0.000000 +-0.707107 -0.707106 0.000000 +-0.836406 -0.548110 0.000000 +-0.707107 -0.707106 0.000000 +-0.707107 -0.707106 0.000000 +-0.836406 -0.548110 0.000000 +-0.707107 -0.707106 0.000000 +-0.836406 -0.548110 0.000000 +-0.929042 -0.369975 0.000000 +-0.836406 -0.548110 0.000000 +-0.836406 -0.548110 0.000000 +-0.929042 -0.369975 0.000000 +-0.836406 -0.548110 0.000000 +-0.929042 -0.369975 0.000000 +-0.982801 -0.184666 0.000000 +-0.929042 -0.369975 0.000000 +-0.929042 -0.369975 0.000000 +-0.982801 -0.184666 0.000000 +-0.929042 -0.369975 0.000000 +-0.982801 -0.184666 0.000000 +-0.995817 -0.091364 0.000000 +-0.982801 -0.184666 0.000000 +-0.982801 -0.184666 0.000000 +-0.929042 -0.369975 0.000000 +-0.982801 -0.184666 0.000000 +-0.982801 -0.184666 0.000000 +-0.982801 -0.184666 0.000000 +-0.995817 -0.091364 0.000000 +-0.995817 -0.091364 0.000000 +-0.982801 -0.184666 0.000000 +-0.995817 -0.091364 0.000000 +-0.982801 -0.184666 0.000000 +0.982801 -0.184666 0.000000 +0.995817 -0.091364 0.000000 +0.995817 -0.091364 0.000000 +0.982801 -0.184666 0.000000 +0.995817 -0.091364 0.000000 +0.982801 -0.184666 0.000000 +0.929042 -0.369975 0.000000 +0.982801 -0.184666 0.000000 +0.982801 -0.184666 0.000000 +0.929042 -0.369975 0.000000 +0.982801 -0.184666 0.000000 +0.929042 -0.369975 0.000000 +0.836408 -0.548108 0.000000 +0.929042 -0.369975 0.000000 +0.929042 -0.369975 0.000000 +0.836408 -0.548108 0.000000 +0.929042 -0.369975 0.000000 +0.836408 -0.548108 0.000000 +0.836408 -0.548108 0.000000 +0.836408 -0.548108 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836408 -0.548108 0.000000 +0.707107 -0.707107 0.000000 +0.548109 -0.836407 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.548109 -0.836407 0.000000 +0.707107 -0.707107 0.000000 +0.548109 -0.836407 0.000000 +0.369975 -0.929042 0.000000 +0.548109 -0.836407 0.000000 +0.548109 -0.836407 0.000000 +0.369975 -0.929042 0.000000 +0.548109 -0.836407 0.000000 +0.369975 -0.929042 0.000000 +0.184665 -0.982802 0.000000 +0.369975 -0.929042 0.000000 +0.369975 -0.929042 0.000000 +0.184665 -0.982802 0.000000 +0.369975 -0.929042 0.000000 +0.184665 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +0.184665 -0.982802 0.000000 +0.184665 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +0.184665 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +-0.184664 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +0.000001 -1.000000 0.000000 +-0.184664 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +-0.184664 -0.982802 0.000000 +-0.369975 -0.929042 0.000000 +-0.184664 -0.982802 0.000000 +-0.184664 -0.982802 0.000000 +-0.369975 -0.929042 0.000000 +-0.184664 -0.982802 0.000000 +-0.369975 -0.929042 0.000000 +-0.548109 -0.836407 0.000000 +-0.369975 -0.929042 0.000000 +-0.369975 -0.929042 0.000000 +-0.548109 -0.836407 0.000000 +-0.369975 -0.929042 0.000000 +-0.548109 -0.836407 0.000000 +-0.707107 -0.707107 0.000000 +-0.548109 -0.836407 0.000000 +-0.548109 -0.836407 0.000000 +-0.707107 -0.707107 0.000000 +-0.548109 -0.836407 0.000000 +-0.707107 -0.707107 0.000000 +-0.836408 -0.548108 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836408 -0.548108 0.000000 +-0.707107 -0.707107 0.000000 +-0.836408 -0.548108 0.000000 +-0.929042 -0.369975 0.000000 +-0.836408 -0.548108 0.000000 +-0.836408 -0.548108 0.000000 +-0.929042 -0.369975 0.000000 +-0.836408 -0.548108 0.000000 +-0.929042 -0.369975 0.000000 +-0.982801 -0.184666 0.000000 +-0.929042 -0.369975 0.000000 +-0.929042 -0.369975 0.000000 +-0.982801 -0.184666 0.000000 +-0.995817 -0.091364 0.000000 +-0.995817 -0.091364 0.000000 +0.982801 -0.184666 0.000000 +0.995817 -0.091364 0.000000 +0.995817 -0.091364 0.000000 +0.982801 -0.184666 0.000000 +0.995817 -0.091364 0.000000 +0.982801 -0.184666 0.000000 +0.929042 -0.369975 0.000000 +0.982801 -0.184666 0.000000 +0.982801 -0.184666 0.000000 +0.929042 -0.369975 0.000000 +0.982801 -0.184666 0.000000 +0.929042 -0.369975 0.000000 +0.836407 -0.548108 0.000000 +0.929042 -0.369975 0.000000 +0.929042 -0.369975 0.000000 +0.836407 -0.548108 0.000000 +0.929042 -0.369975 0.000000 +0.836407 -0.548108 0.000000 +0.707106 -0.707107 0.000000 +0.836407 -0.548108 0.000000 +0.836407 -0.548108 0.000000 +0.707106 -0.707107 0.000000 +0.836407 -0.548108 0.000000 +0.707106 -0.707107 0.000000 +0.707106 -0.707107 0.000000 +0.707106 -0.707107 0.000000 +0.548109 -0.836407 0.000000 +0.548109 -0.836407 0.000000 +0.707106 -0.707107 0.000000 +0.548109 -0.836407 0.000000 +0.369976 -0.929041 0.000000 +0.548109 -0.836407 0.000000 +0.548109 -0.836407 0.000000 +0.369976 -0.929041 0.000000 +0.548109 -0.836407 0.000000 +0.369976 -0.929041 0.000000 +0.184664 -0.982802 0.000000 +0.369976 -0.929041 0.000000 +0.369976 -0.929041 0.000000 +0.184664 -0.982802 0.000000 +0.369976 -0.929041 0.000000 +0.184664 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +0.184664 -0.982802 0.000000 +0.184664 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +0.184664 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +-0.184664 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +0.000001 -1.000000 0.000000 +-0.184664 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +-0.184664 -0.982802 0.000000 +-0.184664 -0.982802 0.000000 +-0.184664 -0.982802 0.000000 +-0.369976 -0.929041 0.000000 +-0.369976 -0.929041 0.000000 +-0.184664 -0.982802 0.000000 +-0.369976 -0.929041 0.000000 +-0.369976 -0.929041 0.000000 +-0.369976 -0.929041 0.000000 +-0.548109 -0.836407 0.000000 +-0.548109 -0.836407 0.000000 +-0.369976 -0.929041 0.000000 +-0.548109 -0.836407 0.000000 +-0.707106 -0.707107 0.000000 +-0.548109 -0.836407 0.000000 +-0.548109 -0.836407 0.000000 +-0.707106 -0.707107 0.000000 +-0.548109 -0.836407 0.000000 +-0.707106 -0.707107 0.000000 +-0.836407 -0.548108 0.000000 +-0.707106 -0.707107 0.000000 +-0.707106 -0.707107 0.000000 +-0.836407 -0.548108 0.000000 +-0.707106 -0.707107 0.000000 +-0.836407 -0.548108 0.000000 +-0.929042 -0.369975 0.000000 +-0.836407 -0.548108 0.000000 +-0.836407 -0.548108 0.000000 +-0.929042 -0.369975 0.000000 +-0.836407 -0.548108 0.000000 +-0.929042 -0.369975 0.000000 +-0.929042 -0.369975 0.000000 +-0.929042 -0.369975 0.000000 +-0.982801 -0.184666 0.000000 +-0.982801 -0.184666 0.000000 +-0.929042 -0.369975 0.000000 +-0.982801 -0.184666 0.000000 +-0.995817 -0.091364 0.000000 +-0.982801 -0.184666 0.000000 +-0.982801 -0.184666 0.000000 +0.982801 -0.184666 0.000000 +0.995817 -0.091364 0.000000 +0.995817 -0.091364 0.000000 +-0.982801 -0.184666 0.000000 +-0.995817 -0.091364 0.000000 +-0.995817 -0.091364 0.000000 +-0.982801 -0.184666 0.000000 +-0.995817 -0.091364 0.000000 +-0.982801 -0.184666 0.000000 +-0.929042 -0.369975 0.000000 +-0.982801 -0.184666 0.000000 +-0.982801 -0.184666 0.000000 +-0.929042 -0.369975 0.000000 +-0.982801 -0.184666 0.000000 +-0.929042 -0.369975 0.000000 +-0.836408 -0.548108 0.000000 +-0.929042 -0.369975 0.000000 +-0.929042 -0.369975 0.000000 +-0.836408 -0.548108 0.000000 +-0.929042 -0.369975 0.000000 +-0.836408 -0.548108 0.000000 +-0.707107 -0.707107 0.000000 +-0.836408 -0.548108 0.000000 +-0.836408 -0.548108 0.000000 +-0.707107 -0.707107 0.000000 +-0.836408 -0.548108 0.000000 +-0.707107 -0.707107 0.000000 +-0.548109 -0.836407 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.548109 -0.836407 0.000000 +-0.707107 -0.707107 0.000000 +-0.548109 -0.836407 0.000000 +-0.369975 -0.929042 0.000000 +-0.548109 -0.836407 0.000000 +-0.548109 -0.836407 0.000000 +-0.369975 -0.929042 0.000000 +-0.548109 -0.836407 0.000000 +-0.369975 -0.929042 0.000000 +-0.184664 -0.982802 0.000000 +-0.369975 -0.929042 0.000000 +-0.369975 -0.929042 0.000000 +-0.184664 -0.982802 0.000000 +-0.369975 -0.929042 0.000000 +-0.184664 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +-0.184664 -0.982802 0.000000 +-0.184664 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +-0.184664 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +0.184665 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +0.000001 -1.000000 0.000000 +0.184665 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +0.184665 -0.982802 0.000000 +0.369975 -0.929042 0.000000 +0.184665 -0.982802 0.000000 +0.184665 -0.982802 0.000000 +0.369975 -0.929042 0.000000 +0.184665 -0.982802 0.000000 +0.369975 -0.929042 0.000000 +0.548109 -0.836407 0.000000 +0.369975 -0.929042 0.000000 +0.369975 -0.929042 0.000000 +0.548109 -0.836407 0.000000 +0.369975 -0.929042 0.000000 +0.548109 -0.836407 0.000000 +0.707107 -0.707107 0.000000 +0.548109 -0.836407 0.000000 +0.548109 -0.836407 0.000000 +0.707107 -0.707107 0.000000 +0.548109 -0.836407 0.000000 +0.707107 -0.707107 0.000000 +0.836408 -0.548108 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836408 -0.548108 0.000000 +0.707107 -0.707107 0.000000 +0.836408 -0.548108 0.000000 +0.836408 -0.548108 0.000000 +0.836408 -0.548108 0.000000 +0.929042 -0.369975 0.000000 +0.929042 -0.369975 0.000000 +0.836408 -0.548108 0.000000 +0.929042 -0.369975 0.000000 +0.982801 -0.184666 0.000000 +0.929042 -0.369975 0.000000 +0.929042 -0.369975 0.000000 +0.982801 -0.184666 0.000000 +0.929042 -0.369975 0.000000 +0.982801 -0.184666 0.000000 +0.995817 -0.091364 0.000000 +0.982801 -0.184666 0.000000 +0.982801 -0.184666 0.000000 +0.982801 -0.184666 0.000000 +0.995817 -0.091364 0.000000 +0.995817 -0.091364 0.000000 +-0.982801 -0.184666 0.000000 +-0.995817 -0.091364 0.000000 +-0.995817 -0.091364 0.000000 +-0.982801 -0.184666 0.000000 +-0.995817 -0.091364 0.000000 +-0.982801 -0.184666 0.000000 +-0.929042 -0.369975 0.000000 +-0.982801 -0.184666 0.000000 +-0.982801 -0.184666 0.000000 +-0.929042 -0.369975 0.000000 +-0.982801 -0.184666 0.000000 +-0.929042 -0.369975 0.000000 +-0.836407 -0.548108 0.000000 +-0.929042 -0.369975 0.000000 +-0.929042 -0.369975 0.000000 +-0.836407 -0.548108 0.000000 +-0.929042 -0.369975 0.000000 +-0.836407 -0.548108 0.000000 +-0.836407 -0.548108 0.000000 +-0.836407 -0.548108 0.000000 +-0.707106 -0.707107 0.000000 +-0.707106 -0.707107 0.000000 +-0.836407 -0.548108 0.000000 +-0.707106 -0.707107 0.000000 +-0.548109 -0.836407 0.000000 +-0.707106 -0.707107 0.000000 +-0.707106 -0.707107 0.000000 +-0.548109 -0.836407 0.000000 +-0.707106 -0.707107 0.000000 +-0.548109 -0.836407 0.000000 +-0.369976 -0.929041 0.000000 +-0.548109 -0.836407 0.000000 +-0.548109 -0.836407 0.000000 +-0.369976 -0.929041 0.000000 +-0.548109 -0.836407 0.000000 +-0.369976 -0.929041 0.000000 +-0.369976 -0.929041 0.000000 +-0.369976 -0.929041 0.000000 +-0.184664 -0.982802 0.000000 +-0.184664 -0.982802 0.000000 +-0.369976 -0.929041 0.000000 +-0.184664 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +-0.184664 -0.982802 0.000000 +-0.184664 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +-0.184664 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +0.000001 -1.000000 0.000000 +0.000001 -1.000000 0.000000 +0.184664 -0.982802 0.000000 +0.184664 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +0.184664 -0.982802 0.000000 +0.369976 -0.929041 0.000000 +0.184664 -0.982802 0.000000 +0.184664 -0.982802 0.000000 +0.369976 -0.929041 0.000000 +0.184664 -0.982802 0.000000 +0.369976 -0.929041 0.000000 +0.548109 -0.836407 0.000000 +0.369976 -0.929041 0.000000 +0.369976 -0.929041 0.000000 +0.548109 -0.836407 0.000000 +0.369976 -0.929041 0.000000 +0.548109 -0.836407 0.000000 +0.707106 -0.707107 0.000000 +0.548109 -0.836407 0.000000 +0.548109 -0.836407 0.000000 +0.707106 -0.707107 0.000000 +0.548109 -0.836407 0.000000 +0.707106 -0.707107 0.000000 +0.707106 -0.707107 0.000000 +0.707106 -0.707107 0.000000 +0.836407 -0.548108 0.000000 +0.836407 -0.548108 0.000000 +0.707106 -0.707107 0.000000 +0.836407 -0.548108 0.000000 +0.929042 -0.369975 0.000000 +0.836407 -0.548108 0.000000 +0.836407 -0.548108 0.000000 +0.929042 -0.369975 0.000000 +0.836407 -0.548108 0.000000 +0.929042 -0.369975 0.000000 +0.982801 -0.184666 0.000000 +0.929042 -0.369975 0.000000 +0.929042 -0.369975 0.000000 +0.982801 -0.184666 0.000000 +0.929042 -0.369975 0.000000 +0.982801 -0.184666 0.000000 +0.995817 -0.091364 0.000000 +0.982801 -0.184666 0.000000 +0.982801 -0.184666 0.000000 +-0.929042 -0.369975 0.000000 +-0.982801 -0.184666 0.000000 +-0.982801 -0.184666 0.000000 +-0.982801 -0.184666 0.000000 +-0.995817 -0.091364 0.000000 +-0.995817 -0.091364 0.000000 +-0.982801 -0.184666 0.000000 +-0.995817 -0.091364 0.000000 +-0.982801 -0.184666 0.000000 +0.982801 -0.184666 0.000000 +0.995817 -0.091364 0.000000 +0.995817 -0.091364 0.000000 +0.982801 -0.184666 0.000000 +0.995817 -0.091364 0.000000 +0.982801 -0.184666 0.000000 +0.929042 -0.369975 0.000000 +0.982801 -0.184666 0.000000 +0.982801 -0.184666 0.000000 +0.929042 -0.369975 0.000000 +0.982801 -0.184666 0.000000 +0.929042 -0.369975 0.000000 +0.836408 -0.548108 0.000000 +0.929042 -0.369975 0.000000 +0.929042 -0.369975 0.000000 +0.836408 -0.548108 0.000000 +0.929042 -0.369975 0.000000 +0.836408 -0.548108 0.000000 +0.836408 -0.548108 0.000000 +0.836408 -0.548108 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.836408 -0.548108 0.000000 +0.707107 -0.707107 0.000000 +0.548109 -0.836407 0.000000 +0.707107 -0.707107 0.000000 +0.707107 -0.707107 0.000000 +0.548109 -0.836407 0.000000 +0.707107 -0.707107 0.000000 +0.548109 -0.836407 0.000000 +0.369975 -0.929042 0.000000 +0.548109 -0.836407 0.000000 +0.548109 -0.836407 0.000000 +0.369975 -0.929042 0.000000 +0.548109 -0.836407 0.000000 +0.369975 -0.929042 0.000000 +0.184665 -0.982802 0.000000 +0.369975 -0.929042 0.000000 +0.369975 -0.929042 0.000000 +0.184665 -0.982802 0.000000 +0.369975 -0.929042 0.000000 +0.184665 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +0.184665 -0.982802 0.000000 +0.184665 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +0.184665 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +-0.184664 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +0.000001 -1.000000 0.000000 +-0.184664 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +-0.184664 -0.982802 0.000000 +-0.369975 -0.929042 0.000000 +-0.184664 -0.982802 0.000000 +-0.184664 -0.982802 0.000000 +-0.369975 -0.929042 0.000000 +-0.184664 -0.982802 0.000000 +-0.369975 -0.929042 0.000000 +-0.548109 -0.836407 0.000000 +-0.369975 -0.929042 0.000000 +-0.369975 -0.929042 0.000000 +-0.548109 -0.836407 0.000000 +-0.369975 -0.929042 0.000000 +-0.548109 -0.836407 0.000000 +-0.707107 -0.707107 0.000000 +-0.548109 -0.836407 0.000000 +-0.548109 -0.836407 0.000000 +-0.707107 -0.707107 0.000000 +-0.548109 -0.836407 0.000000 +-0.707107 -0.707107 0.000000 +-0.836408 -0.548108 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836408 -0.548108 0.000000 +-0.707107 -0.707107 0.000000 +-0.836408 -0.548108 0.000000 +-0.929042 -0.369975 0.000000 +-0.836408 -0.548108 0.000000 +-0.836408 -0.548108 0.000000 +-0.929042 -0.369975 0.000000 +-0.836408 -0.548108 0.000000 +-0.929042 -0.369975 0.000000 +-0.982801 -0.184666 0.000000 +-0.929042 -0.369975 0.000000 +-0.929042 -0.369975 0.000000 +-0.929042 -0.369975 0.000000 +-0.982801 -0.184666 0.000000 +-0.982801 -0.184666 0.000000 +-0.995817 -0.091364 0.000000 +-0.995817 -0.091364 0.000000 +-0.982801 -0.184666 0.000000 +-0.982801 -0.184666 0.000000 +-0.995817 -0.091364 0.000000 +-0.982801 -0.184666 0.000000 +0.982801 -0.184666 0.000000 +0.995817 -0.091364 0.000000 +0.995817 -0.091364 0.000000 +0.982801 -0.184666 0.000000 +0.995817 -0.091364 0.000000 +0.982801 -0.184666 0.000000 +0.929042 -0.369975 0.000000 +0.982801 -0.184666 0.000000 +0.982801 -0.184666 0.000000 +0.929042 -0.369975 0.000000 +0.982801 -0.184666 0.000000 +0.929042 -0.369975 0.000000 +0.836407 -0.548108 0.000000 +0.929042 -0.369975 0.000000 +0.929042 -0.369975 0.000000 +0.836407 -0.548108 0.000000 +0.929042 -0.369975 0.000000 +0.836407 -0.548108 0.000000 +0.707106 -0.707107 0.000000 +0.836407 -0.548108 0.000000 +0.836407 -0.548108 0.000000 +0.707106 -0.707107 0.000000 +0.836407 -0.548108 0.000000 +0.707106 -0.707107 0.000000 +0.548109 -0.836407 0.000000 +0.707106 -0.707107 0.000000 +0.707106 -0.707107 0.000000 +0.548109 -0.836407 0.000000 +0.707106 -0.707107 0.000000 +0.548109 -0.836407 0.000000 +0.369976 -0.929041 0.000000 +0.548109 -0.836407 0.000000 +0.548109 -0.836407 0.000000 +0.369976 -0.929041 0.000000 +0.548109 -0.836407 0.000000 +0.369976 -0.929041 0.000000 +0.184664 -0.982802 0.000000 +0.369976 -0.929041 0.000000 +0.369976 -0.929041 0.000000 +0.184664 -0.982802 0.000000 +0.369976 -0.929041 0.000000 +0.184664 -0.982802 0.000000 +0.184664 -0.982802 0.000000 +0.184664 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +0.000001 -1.000000 0.000000 +0.184664 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +0.000001 -1.000000 0.000000 +0.000001 -1.000000 0.000000 +-0.184664 -0.982802 0.000000 +-0.184664 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +-0.184664 -0.982802 0.000000 +-0.369976 -0.929041 0.000000 +-0.184664 -0.982802 0.000000 +-0.184664 -0.982802 0.000000 +-0.369976 -0.929041 0.000000 +-0.184664 -0.982802 0.000000 +-0.369976 -0.929041 0.000000 +-0.548109 -0.836407 0.000000 +-0.369976 -0.929041 0.000000 +-0.369976 -0.929041 0.000000 +-0.548109 -0.836407 0.000000 +-0.369976 -0.929041 0.000000 +-0.548109 -0.836407 0.000000 +-0.707106 -0.707107 0.000000 +-0.548109 -0.836407 0.000000 +-0.548109 -0.836407 0.000000 +-0.707106 -0.707107 0.000000 +-0.548109 -0.836407 0.000000 +-0.707106 -0.707107 0.000000 +-0.836407 -0.548108 0.000000 +-0.707106 -0.707107 0.000000 +-0.707106 -0.707107 0.000000 +-0.836407 -0.548108 0.000000 +-0.707106 -0.707107 0.000000 +-0.836407 -0.548108 0.000000 +-0.929042 -0.369975 0.000000 +-0.836407 -0.548108 0.000000 +-0.836407 -0.548108 0.000000 +-0.929042 -0.369975 0.000000 +-0.836407 -0.548108 0.000000 +-0.929042 -0.369975 0.000000 +-0.982801 -0.184666 0.000000 +-0.929042 -0.369975 0.000000 +-0.929042 -0.369975 0.000000 +-0.836408 -0.548108 0.000000 +-0.929042 -0.369975 0.000000 +-0.929042 -0.369975 0.000000 +-0.982801 -0.184666 0.000000 +-0.995817 -0.091364 0.000000 +-0.995817 -0.091364 0.000000 +-0.982801 -0.184666 0.000000 +-0.995817 -0.091364 0.000000 +-0.982801 -0.184666 0.000000 +-0.929042 -0.369975 0.000000 +-0.982801 -0.184666 0.000000 +-0.982801 -0.184666 0.000000 +-0.929042 -0.369975 0.000000 +-0.982801 -0.184666 0.000000 +-0.929042 -0.369975 0.000000 +0.982801 -0.184667 0.000000 +0.995816 -0.091379 0.000000 +0.995816 -0.091379 0.000000 +0.982801 -0.184667 0.000000 +0.995816 -0.091379 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369975 0.000000 +0.982801 -0.184667 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369975 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369975 0.000000 +0.836402 -0.548117 0.000000 +0.929042 -0.369975 0.000000 +0.929042 -0.369975 0.000000 +0.836402 -0.548117 0.000000 +0.929042 -0.369975 0.000000 +0.836402 -0.548117 0.000000 +0.836402 -0.548117 0.000000 +0.836402 -0.548117 0.000000 +0.707106 -0.707108 0.000000 +0.707106 -0.707108 0.000000 +0.836402 -0.548117 0.000000 +0.707106 -0.707108 0.000000 +0.548113 -0.836404 0.000000 +0.707106 -0.707108 0.000000 +0.707106 -0.707108 0.000000 +0.548113 -0.836404 0.000000 +0.707106 -0.707108 0.000000 +0.548113 -0.836404 0.000000 +0.369975 -0.929042 0.000000 +0.548113 -0.836404 0.000000 +0.548113 -0.836404 0.000000 +0.369975 -0.929042 0.000000 +0.548113 -0.836404 0.000000 +0.369975 -0.929042 0.000000 +0.184665 -0.982802 0.000000 +0.369975 -0.929042 0.000000 +0.369975 -0.929042 0.000000 +0.184665 -0.982802 0.000000 +0.369975 -0.929042 0.000000 +0.184665 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +0.184665 -0.982802 0.000000 +0.184665 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +0.184665 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +-0.184664 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +0.000001 -1.000000 0.000000 +-0.184664 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +-0.184664 -0.982802 0.000000 +-0.369975 -0.929042 0.000000 +-0.184664 -0.982802 0.000000 +-0.184664 -0.982802 0.000000 +-0.369975 -0.929042 0.000000 +-0.184664 -0.982802 0.000000 +-0.369975 -0.929042 0.000000 +-0.548109 -0.836407 0.000000 +-0.369975 -0.929042 0.000000 +-0.369975 -0.929042 0.000000 +-0.548109 -0.836407 0.000000 +-0.369975 -0.929042 0.000000 +-0.548109 -0.836407 0.000000 +-0.707107 -0.707107 0.000000 +-0.548109 -0.836407 0.000000 +-0.548109 -0.836407 0.000000 +-0.707107 -0.707107 0.000000 +-0.548109 -0.836407 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.707107 -0.707107 0.000000 +-0.836408 -0.548108 0.000000 +-0.836408 -0.548108 0.000000 +-0.707107 -0.707107 0.000000 +-0.836408 -0.548108 0.000000 +-0.929042 -0.369975 0.000000 +-0.836408 -0.548108 0.000000 +-0.836408 -0.548108 0.000000 +-0.836407 -0.548108 0.000000 +-0.929042 -0.369975 0.000000 +-0.929042 -0.369975 0.000000 +-0.982801 -0.184666 0.000000 +-0.995817 -0.091364 0.000000 +-0.995817 -0.091364 0.000000 +-0.982801 -0.184666 0.000000 +-0.995817 -0.091364 0.000000 +-0.982801 -0.184666 0.000000 +-0.929042 -0.369975 0.000000 +-0.982801 -0.184666 0.000000 +-0.982801 -0.184666 0.000000 +-0.929042 -0.369975 0.000000 +-0.982801 -0.184666 0.000000 +-0.929042 -0.369975 0.000000 +0.995816 -0.091379 0.000000 +0.995816 -0.091379 0.000000 +0.982801 -0.184667 0.000000 +0.982801 -0.184667 0.000000 +0.995816 -0.091379 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369974 0.000000 +0.982801 -0.184667 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369974 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369974 0.000000 +0.836401 -0.548117 0.000000 +0.929042 -0.369974 0.000000 +0.929042 -0.369974 0.000000 +0.836401 -0.548117 0.000000 +0.929042 -0.369974 0.000000 +0.836401 -0.548117 0.000000 +0.707106 -0.707108 0.000000 +0.836401 -0.548117 0.000000 +0.836401 -0.548117 0.000000 +0.707106 -0.707108 0.000000 +0.836401 -0.548117 0.000000 +0.707106 -0.707108 0.000000 +0.548113 -0.836404 0.000000 +0.707106 -0.707108 0.000000 +0.707106 -0.707108 0.000000 +0.548113 -0.836404 0.000000 +0.707106 -0.707108 0.000000 +0.548113 -0.836404 0.000000 +0.369976 -0.929041 0.000000 +0.548113 -0.836404 0.000000 +0.548113 -0.836404 0.000000 +0.369976 -0.929041 0.000000 +0.548113 -0.836404 0.000000 +0.369976 -0.929041 0.000000 +0.184664 -0.982802 0.000000 +0.369976 -0.929041 0.000000 +0.369976 -0.929041 0.000000 +0.184664 -0.982802 0.000000 +0.369976 -0.929041 0.000000 +0.184664 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +0.184664 -0.982802 0.000000 +0.184664 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +0.184664 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +-0.184664 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +0.000001 -1.000000 0.000000 +-0.184664 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +-0.184664 -0.982802 0.000000 +-0.369976 -0.929041 0.000000 +-0.184664 -0.982802 0.000000 +-0.184664 -0.982802 0.000000 +-0.369976 -0.929041 0.000000 +-0.184664 -0.982802 0.000000 +-0.369976 -0.929041 0.000000 +-0.369976 -0.929041 0.000000 +-0.369976 -0.929041 0.000000 +-0.548109 -0.836407 0.000000 +-0.548109 -0.836407 0.000000 +-0.369976 -0.929041 0.000000 +-0.548109 -0.836407 0.000000 +-0.707106 -0.707107 0.000000 +-0.548109 -0.836407 0.000000 +-0.548109 -0.836407 0.000000 +-0.707106 -0.707107 0.000000 +-0.548109 -0.836407 0.000000 +-0.707106 -0.707107 0.000000 +-0.707106 -0.707107 0.000000 +-0.707106 -0.707107 0.000000 +-0.836407 -0.548108 0.000000 +-0.836407 -0.548108 0.000000 +-0.707106 -0.707107 0.000000 +-0.836407 -0.548108 0.000000 +-0.929042 -0.369975 0.000000 +-0.836407 -0.548108 0.000000 +-0.836407 -0.548108 0.000000 +-0.982801 -0.184666 0.000000 +-0.995819 -0.091349 0.000000 +-0.995819 -0.091349 0.000000 +0.982801 -0.184667 0.000000 +0.995816 -0.091379 0.000000 +0.995816 -0.091379 0.000000 +0.982801 -0.184667 0.000000 +0.995816 -0.091379 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369975 0.000000 +0.982801 -0.184667 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369975 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369975 0.000000 +0.836402 -0.548117 0.000000 +0.929042 -0.369975 0.000000 +0.929042 -0.369975 0.000000 +0.836402 -0.548117 0.000000 +0.929042 -0.369975 0.000000 +0.836402 -0.548117 0.000000 +0.707106 -0.707108 0.000000 +0.836402 -0.548117 0.000000 +0.836402 -0.548117 0.000000 +0.707106 -0.707108 0.000000 +0.836402 -0.548117 0.000000 +0.707106 -0.707108 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707108 0.000000 +0.707106 -0.707108 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707108 0.000000 +0.548110 -0.836406 0.000000 +0.369974 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.548110 -0.836406 0.000000 +0.369974 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.369974 -0.929042 0.000000 +0.184667 -0.982801 0.000000 +0.369974 -0.929042 0.000000 +0.369974 -0.929042 0.000000 +0.184667 -0.982801 0.000000 +0.369974 -0.929042 0.000000 +0.184667 -0.982801 0.000000 +0.184667 -0.982801 0.000000 +0.184667 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +0.000001 -1.000000 0.000000 +0.184667 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +-0.184665 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +0.000001 -1.000000 0.000000 +-0.184665 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +-0.184665 -0.982801 0.000000 +-0.369974 -0.929042 0.000000 +-0.184665 -0.982801 0.000000 +-0.184665 -0.982801 0.000000 +-0.369974 -0.929042 0.000000 +-0.184665 -0.982801 0.000000 +-0.369974 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.369974 -0.929042 0.000000 +-0.369974 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.369974 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.707106 -0.707108 0.000000 +-0.548110 -0.836406 0.000000 +-0.548110 -0.836406 0.000000 +-0.707106 -0.707108 0.000000 +-0.548110 -0.836406 0.000000 +-0.707106 -0.707108 0.000000 +-0.836408 -0.548107 0.000000 +-0.707106 -0.707108 0.000000 +-0.707106 -0.707108 0.000000 +-0.836408 -0.548107 0.000000 +-0.707106 -0.707108 0.000000 +-0.836408 -0.548107 0.000000 +-0.836408 -0.548107 0.000000 +-0.836408 -0.548107 0.000000 +-0.929041 -0.369976 0.000000 +-0.929041 -0.369976 0.000000 +-0.836408 -0.548107 0.000000 +-0.929041 -0.369976 0.000000 +-0.982801 -0.184666 0.000000 +-0.929041 -0.369976 0.000000 +-0.929041 -0.369976 0.000000 +-0.982801 -0.184666 0.000000 +-0.929041 -0.369976 0.000000 +-0.982801 -0.184666 0.000000 +-0.995819 -0.091349 0.000000 +-0.982801 -0.184666 0.000000 +-0.982801 -0.184666 0.000000 +0.982801 -0.184667 0.000000 +0.995816 -0.091379 0.000000 +0.995816 -0.091379 0.000000 +-0.982801 -0.184665 0.000000 +-0.995819 -0.091349 0.000000 +-0.995819 -0.091349 0.000000 +-0.982801 -0.184665 0.000000 +-0.995819 -0.091349 0.000000 +-0.982801 -0.184665 0.000000 +-0.929041 -0.369976 0.000000 +-0.982801 -0.184665 0.000000 +-0.982801 -0.184665 0.000000 +-0.929041 -0.369976 0.000000 +-0.982801 -0.184665 0.000000 +-0.929041 -0.369976 0.000000 +-0.929041 -0.369976 0.000000 +-0.929041 -0.369976 0.000000 +-0.836408 -0.548107 0.000000 +-0.836408 -0.548107 0.000000 +-0.929041 -0.369976 0.000000 +-0.836408 -0.548107 0.000000 +-0.707106 -0.707108 0.000000 +-0.836408 -0.548107 0.000000 +-0.836408 -0.548107 0.000000 +-0.707106 -0.707108 0.000000 +-0.836408 -0.548107 0.000000 +-0.707106 -0.707108 0.000000 +-0.548110 -0.836406 0.000000 +-0.707106 -0.707108 0.000000 +-0.707106 -0.707108 0.000000 +-0.548110 -0.836406 0.000000 +-0.707106 -0.707108 0.000000 +-0.548110 -0.836406 0.000000 +-0.369975 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.548110 -0.836406 0.000000 +-0.369975 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.369975 -0.929042 0.000000 +-0.184665 -0.982802 0.000000 +-0.369975 -0.929042 0.000000 +-0.369975 -0.929042 0.000000 +-0.184665 -0.982802 0.000000 +-0.369975 -0.929042 0.000000 +-0.184665 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +-0.184665 -0.982802 0.000000 +-0.184665 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +-0.184665 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +0.184666 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +0.000001 -1.000000 0.000000 +0.184666 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +0.184666 -0.982801 0.000000 +0.369975 -0.929042 0.000000 +0.184666 -0.982801 0.000000 +0.184666 -0.982801 0.000000 +0.369975 -0.929042 0.000000 +0.184666 -0.982801 0.000000 +0.369975 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.369975 -0.929042 0.000000 +0.369975 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.369975 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707108 0.000000 +0.548110 -0.836406 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707108 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707108 0.000000 +0.836401 -0.548117 0.000000 +0.707106 -0.707108 0.000000 +0.707106 -0.707108 0.000000 +0.836401 -0.548117 0.000000 +0.707106 -0.707108 0.000000 +0.836401 -0.548117 0.000000 +0.929042 -0.369974 0.000000 +0.836401 -0.548117 0.000000 +0.836401 -0.548117 0.000000 +0.929042 -0.369974 0.000000 +0.836401 -0.548117 0.000000 +0.929042 -0.369974 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369974 0.000000 +0.929042 -0.369974 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369974 0.000000 +0.982801 -0.184667 0.000000 +0.995816 -0.091379 0.000000 +0.982801 -0.184667 0.000000 +0.982801 -0.184667 0.000000 +-0.982801 -0.184666 0.000000 +-0.995819 -0.091349 0.000000 +-0.995819 -0.091349 0.000000 +0.982801 -0.184667 0.000000 +0.995816 -0.091379 0.000000 +0.995816 -0.091379 0.000000 +0.982801 -0.184667 0.000000 +0.995816 -0.091379 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369975 0.000000 +0.982801 -0.184667 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369975 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369975 0.000000 +0.929042 -0.369975 0.000000 +0.929042 -0.369975 0.000000 +0.836402 -0.548117 0.000000 +0.836402 -0.548117 0.000000 +0.929042 -0.369975 0.000000 +0.836402 -0.548117 0.000000 +0.707106 -0.707108 0.000000 +0.836402 -0.548117 0.000000 +0.836402 -0.548117 0.000000 +0.707106 -0.707108 0.000000 +0.836402 -0.548117 0.000000 +0.707106 -0.707108 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707108 0.000000 +0.707106 -0.707108 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707108 0.000000 +0.548110 -0.836406 0.000000 +0.369974 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.548110 -0.836406 0.000000 +0.369974 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.369974 -0.929042 0.000000 +0.184667 -0.982801 0.000000 +0.369974 -0.929042 0.000000 +0.369974 -0.929042 0.000000 +0.184667 -0.982801 0.000000 +0.369974 -0.929042 0.000000 +0.184667 -0.982801 0.000000 +0.184667 -0.982801 0.000000 +0.184667 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +0.000001 -1.000000 0.000000 +0.184667 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +-0.184665 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +0.000001 -1.000000 0.000000 +-0.184665 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +-0.184665 -0.982801 0.000000 +-0.369974 -0.929042 0.000000 +-0.184665 -0.982801 0.000000 +-0.184665 -0.982801 0.000000 +-0.369974 -0.929042 0.000000 +-0.184665 -0.982801 0.000000 +-0.369974 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.369974 -0.929042 0.000000 +-0.369974 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.369974 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.707106 -0.707108 0.000000 +-0.548110 -0.836406 0.000000 +-0.548110 -0.836406 0.000000 +-0.707106 -0.707108 0.000000 +-0.548110 -0.836406 0.000000 +-0.707106 -0.707108 0.000000 +-0.836408 -0.548107 0.000000 +-0.707106 -0.707108 0.000000 +-0.707106 -0.707108 0.000000 +-0.836408 -0.548107 0.000000 +-0.707106 -0.707108 0.000000 +-0.836408 -0.548107 0.000000 +-0.929041 -0.369976 0.000000 +-0.836408 -0.548107 0.000000 +-0.836408 -0.548107 0.000000 +-0.929041 -0.369976 0.000000 +-0.836408 -0.548107 0.000000 +-0.929041 -0.369976 0.000000 +-0.982801 -0.184666 0.000000 +-0.929041 -0.369976 0.000000 +-0.929041 -0.369976 0.000000 +-0.982801 -0.184666 0.000000 +-0.929041 -0.369976 0.000000 +-0.982801 -0.184666 0.000000 +-0.995819 -0.091349 0.000000 +-0.982801 -0.184666 0.000000 +-0.982801 -0.184666 0.000000 +-0.982801 -0.184665 0.000000 +-0.995819 -0.091349 0.000000 +-0.995819 -0.091349 0.000000 +0.982801 -0.184667 0.000000 +0.995816 -0.091379 0.000000 +0.995816 -0.091379 0.000000 +0.982801 -0.184667 0.000000 +0.995816 -0.091379 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369974 0.000000 +0.982801 -0.184667 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369974 0.000000 +0.982801 -0.184667 0.000000 +0.929042 -0.369974 0.000000 +0.929042 -0.369974 0.000000 +0.929042 -0.369974 0.000000 +0.836401 -0.548117 0.000000 +0.836401 -0.548117 0.000000 +0.929042 -0.369974 0.000000 +0.836401 -0.548117 0.000000 +0.707106 -0.707108 0.000000 +0.836401 -0.548117 0.000000 +0.836401 -0.548117 0.000000 +0.707106 -0.707108 0.000000 +0.836401 -0.548117 0.000000 +0.707106 -0.707108 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707108 0.000000 +0.707106 -0.707108 0.000000 +0.548110 -0.836406 0.000000 +0.707106 -0.707108 0.000000 +0.548110 -0.836406 0.000000 +0.369975 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.548110 -0.836406 0.000000 +0.369975 -0.929042 0.000000 +0.548110 -0.836406 0.000000 +0.369975 -0.929042 0.000000 +0.184666 -0.982801 0.000000 +0.369975 -0.929042 0.000000 +0.369975 -0.929042 0.000000 +0.184666 -0.982801 0.000000 +0.369975 -0.929042 0.000000 +0.184666 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +0.184666 -0.982801 0.000000 +0.184666 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +0.184666 -0.982801 0.000000 +0.000001 -1.000000 0.000000 +-0.184665 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +0.000001 -1.000000 0.000000 +-0.184665 -0.982802 0.000000 +0.000001 -1.000000 0.000000 +-0.184665 -0.982802 0.000000 +-0.369975 -0.929042 0.000000 +-0.184665 -0.982802 0.000000 +-0.184665 -0.982802 0.000000 +-0.369975 -0.929042 0.000000 +-0.184665 -0.982802 0.000000 +-0.369975 -0.929042 0.000000 +-0.369975 -0.929042 0.000000 +-0.369975 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.548110 -0.836406 0.000000 +-0.369975 -0.929042 0.000000 +-0.548110 -0.836406 0.000000 +-0.707106 -0.707108 0.000000 +-0.548110 -0.836406 0.000000 +-0.548110 -0.836406 0.000000 +-0.707106 -0.707108 0.000000 +-0.548110 -0.836406 0.000000 +-0.707106 -0.707108 0.000000 +-0.836408 -0.548107 0.000000 +-0.707106 -0.707108 0.000000 +-0.707106 -0.707108 0.000000 +-0.836408 -0.548107 0.000000 +-0.707106 -0.707108 0.000000 +-0.836408 -0.548107 0.000000 +-0.929041 -0.369976 0.000000 +-0.836408 -0.548107 0.000000 +-0.836408 -0.548107 0.000000 +-0.929041 -0.369976 0.000000 +-0.836408 -0.548107 0.000000 +-0.929041 -0.369976 0.000000 +-0.982801 -0.184665 0.000000 +-0.929041 -0.369976 0.000000 +-0.929041 -0.369976 0.000000 +-0.982801 -0.184665 0.000000 +-0.929041 -0.369976 0.000000 +-0.982801 -0.184665 0.000000 +-0.995819 -0.091349 0.000000 +-0.982801 -0.184665 0.000000 +-0.982801 -0.184665 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.929041 0.369976 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184666 0.000000 +-0.995819 0.091349 0.000000 +-0.995819 0.091349 0.000000 +-0.982801 0.184666 0.000000 +-0.995819 0.091349 0.000000 +-0.982801 0.184666 0.000000 +0.982801 0.184667 0.000000 +0.995816 0.091379 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369975 0.000000 +0.929042 0.369975 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369975 0.000000 +0.929042 0.369975 0.000000 +0.929042 0.369975 0.000000 +0.836402 0.548117 0.000000 +0.836402 0.548117 0.000000 +0.929042 0.369975 0.000000 +0.836402 0.548117 0.000000 +0.836402 0.548117 0.000000 +0.836402 0.548117 0.000000 +0.707106 0.707107 0.000000 +0.707106 0.707107 0.000000 +0.836402 0.548117 0.000000 +0.707106 0.707107 0.000000 +0.707106 0.707107 0.000000 +0.707106 0.707107 0.000000 +0.548110 0.836406 0.000000 +0.548110 0.836406 0.000000 +0.707106 0.707107 0.000000 +0.548110 0.836406 0.000000 +0.369973 0.929042 0.000000 +0.548110 0.836406 0.000000 +0.548110 0.836406 0.000000 +0.369973 0.929042 0.000000 +0.548110 0.836406 0.000000 +0.369973 0.929042 0.000000 +0.369973 0.929042 0.000000 +0.369973 0.929042 0.000000 +0.184666 0.982801 0.000000 +0.184666 0.982801 0.000000 +0.369973 0.929042 0.000000 +0.184666 0.982801 0.000000 +0.184666 0.982801 0.000000 +0.184666 0.982801 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.184666 0.982801 0.000000 +0.000001 1.000000 0.000000 +-0.184665 0.982802 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +-0.184665 0.982802 0.000000 +0.000001 1.000000 0.000000 +-0.184665 0.982801 0.000000 +-0.369973 0.929042 0.000000 +-0.184665 0.982802 0.000000 +-0.184665 0.982801 0.000000 +-0.369973 0.929042 0.000000 +-0.184665 0.982801 0.000000 +-0.369973 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.369973 0.929042 0.000000 +-0.369973 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.369973 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.707106 0.707107 0.000000 +-0.548110 0.836406 0.000000 +-0.548110 0.836406 0.000000 +-0.707106 0.707107 0.000000 +-0.548110 0.836406 0.000000 +-0.707106 0.707107 0.000000 +-0.836408 0.548107 0.000000 +-0.707106 0.707107 0.000000 +-0.707106 0.707107 0.000000 +-0.836408 0.548107 0.000000 +-0.707106 0.707107 0.000000 +-0.836408 0.548107 0.000000 +-0.836408 0.548107 0.000000 +-0.836408 0.548107 0.000000 +-0.929041 0.369976 0.000000 +-0.929041 0.369976 0.000000 +-0.836408 0.548107 0.000000 +-0.929041 0.369976 0.000000 +-0.982801 0.184666 0.000000 +-0.929041 0.369976 0.000000 +-0.929041 0.369976 0.000000 +-0.929041 0.369976 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184666 0.000000 +-0.995819 0.091349 0.000000 +-0.995819 0.091349 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184666 0.000000 +-0.995819 0.091349 0.000000 +-0.982801 0.184666 0.000000 +0.982801 0.184667 0.000000 +0.995816 0.091379 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369974 0.000000 +0.929042 0.369974 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369974 0.000000 +0.929042 0.369974 0.000000 +0.929042 0.369974 0.000000 +0.836402 0.548117 0.000000 +0.836402 0.548117 0.000000 +0.929042 0.369974 0.000000 +0.836402 0.548117 0.000000 +0.836402 0.548117 0.000000 +0.836402 0.548117 0.000000 +0.707106 0.707108 0.000000 +0.707106 0.707108 0.000000 +0.836402 0.548117 0.000000 +0.707106 0.707108 0.000000 +0.707106 0.707108 0.000000 +0.707106 0.707108 0.000000 +0.548110 0.836406 0.000000 +0.548110 0.836406 0.000000 +0.707106 0.707108 0.000000 +0.548110 0.836406 0.000000 +0.548110 0.836406 0.000000 +0.548110 0.836406 0.000000 +0.369975 0.929042 0.000000 +0.369975 0.929042 0.000000 +0.548110 0.836406 0.000000 +0.369975 0.929042 0.000000 +0.184666 0.982801 0.000000 +0.369975 0.929042 0.000000 +0.369975 0.929042 0.000000 +0.184666 0.982801 0.000000 +0.369975 0.929042 0.000000 +0.184666 0.982801 0.000000 +0.000001 1.000000 0.000000 +0.184666 0.982801 0.000000 +0.184666 0.982801 0.000000 +0.000001 1.000000 0.000000 +0.184666 0.982801 0.000000 +0.000001 1.000000 0.000000 +-0.184665 0.982802 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +-0.184665 0.982802 0.000000 +0.000001 1.000000 0.000000 +-0.184665 0.982802 0.000000 +-0.369975 0.929042 0.000000 +-0.184665 0.982802 0.000000 +-0.184665 0.982802 0.000000 +-0.369975 0.929042 0.000000 +-0.184665 0.982802 0.000000 +-0.369975 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.369975 0.929042 0.000000 +-0.369975 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.369975 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.707106 0.707108 0.000000 +-0.548110 0.836406 0.000000 +-0.548110 0.836406 0.000000 +-0.707106 0.707108 0.000000 +-0.548110 0.836406 0.000000 +-0.707106 0.707108 0.000000 +-0.836408 0.548107 0.000000 +-0.707106 0.707108 0.000000 +-0.707106 0.707108 0.000000 +-0.836408 0.548107 0.000000 +-0.707106 0.707108 0.000000 +-0.836408 0.548107 0.000000 +-0.836408 0.548107 0.000000 +-0.836408 0.548107 0.000000 +-0.929041 0.369976 0.000000 +-0.929041 0.369976 0.000000 +-0.836408 0.548107 0.000000 +-0.929041 0.369976 0.000000 +-0.982801 0.184666 0.000000 +-0.929041 0.369976 0.000000 +-0.929041 0.369976 0.000000 +-0.929041 0.369976 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184666 0.000000 +-0.995819 0.091349 0.000000 +-0.995819 0.091349 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184666 0.000000 +-0.995819 0.091349 0.000000 +-0.982801 0.184666 0.000000 +0.982801 0.184667 0.000000 +0.995816 0.091379 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369975 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369975 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369975 0.000000 +0.929042 0.369975 0.000000 +0.929042 0.369975 0.000000 +0.836402 0.548117 0.000000 +0.836402 0.548117 0.000000 +0.929042 0.369975 0.000000 +0.836402 0.548117 0.000000 +0.707106 0.707107 0.000000 +0.836402 0.548117 0.000000 +0.836402 0.548117 0.000000 +0.707106 0.707107 0.000000 +0.836402 0.548117 0.000000 +0.707106 0.707107 0.000000 +0.548110 0.836406 0.000000 +0.707106 0.707107 0.000000 +0.707106 0.707107 0.000000 +0.548110 0.836406 0.000000 +0.707106 0.707107 0.000000 +0.548110 0.836406 0.000000 +0.548110 0.836406 0.000000 +0.548110 0.836406 0.000000 +0.369973 0.929042 0.000000 +0.369973 0.929042 0.000000 +0.548110 0.836406 0.000000 +0.369973 0.929042 0.000000 +0.184666 0.982801 0.000000 +0.369973 0.929042 0.000000 +0.369973 0.929042 0.000000 +0.184666 0.982801 0.000000 +0.369973 0.929042 0.000000 +0.184666 0.982801 0.000000 +0.000001 1.000000 0.000000 +0.184666 0.982801 0.000000 +0.184666 0.982801 0.000000 +0.000001 1.000000 0.000000 +0.184666 0.982801 0.000000 +0.000001 1.000000 0.000000 +-0.184665 0.982802 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +-0.184665 0.982802 0.000000 +0.000001 1.000000 0.000000 +-0.184665 0.982801 0.000000 +-0.369973 0.929042 0.000000 +-0.184665 0.982802 0.000000 +-0.184665 0.982801 0.000000 +-0.369973 0.929042 0.000000 +-0.184665 0.982801 0.000000 +-0.369973 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.369973 0.929042 0.000000 +-0.369973 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.369973 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.707106 0.707107 0.000000 +-0.548110 0.836406 0.000000 +-0.548110 0.836406 0.000000 +-0.707106 0.707107 0.000000 +-0.548110 0.836406 0.000000 +-0.707106 0.707107 0.000000 +-0.836408 0.548107 0.000000 +-0.707106 0.707107 0.000000 +-0.707106 0.707107 0.000000 +-0.836408 0.548107 0.000000 +-0.707106 0.707107 0.000000 +-0.836408 0.548107 0.000000 +-0.929041 0.369976 0.000000 +-0.836408 0.548107 0.000000 +-0.836408 0.548107 0.000000 +-0.929041 0.369976 0.000000 +-0.836408 0.548107 0.000000 +-0.929041 0.369976 0.000000 +-0.982801 0.184666 0.000000 +-0.929041 0.369976 0.000000 +-0.929041 0.369976 0.000000 +-0.929041 0.369976 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184666 0.000000 +-0.995819 0.091349 0.000000 +-0.995819 0.091349 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184666 0.000000 +-0.995819 0.091349 0.000000 +-0.982801 0.184666 0.000000 +0.982801 0.184667 0.000000 +0.995816 0.091379 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369974 0.000000 +0.929042 0.369974 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369974 0.000000 +0.836402 0.548117 0.000000 +0.929042 0.369974 0.000000 +0.929042 0.369974 0.000000 +0.836402 0.548117 0.000000 +0.929042 0.369974 0.000000 +0.836402 0.548117 0.000000 +0.836402 0.548117 0.000000 +0.836402 0.548117 0.000000 +0.707106 0.707108 0.000000 +0.707106 0.707108 0.000000 +0.836402 0.548117 0.000000 +0.707106 0.707108 0.000000 +0.548110 0.836406 0.000000 +0.707106 0.707108 0.000000 +0.707106 0.707108 0.000000 +0.548110 0.836406 0.000000 +0.707106 0.707108 0.000000 +0.548110 0.836406 0.000000 +0.369975 0.929042 0.000000 +0.548110 0.836406 0.000000 +0.548110 0.836406 0.000000 +0.369975 0.929042 0.000000 +0.548110 0.836406 0.000000 +0.369975 0.929042 0.000000 +0.369975 0.929042 0.000000 +0.369975 0.929042 0.000000 +0.184666 0.982801 0.000000 +0.184666 0.982801 0.000000 +0.369975 0.929042 0.000000 +0.184666 0.982801 0.000000 +0.184666 0.982801 0.000000 +0.184666 0.982801 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.184666 0.982801 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +-0.184665 0.982802 0.000000 +-0.184665 0.982802 0.000000 +0.000001 1.000000 0.000000 +-0.184665 0.982802 0.000000 +-0.369975 0.929042 0.000000 +-0.184665 0.982802 0.000000 +-0.184665 0.982802 0.000000 +-0.369975 0.929042 0.000000 +-0.184665 0.982802 0.000000 +-0.369975 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.369975 0.929042 0.000000 +-0.369975 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.369975 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.548110 0.836406 0.000000 +-0.548110 0.836406 0.000000 +-0.707106 0.707108 0.000000 +-0.707106 0.707108 0.000000 +-0.548110 0.836406 0.000000 +-0.707106 0.707108 0.000000 +-0.836408 0.548107 0.000000 +-0.707106 0.707108 0.000000 +-0.707106 0.707108 0.000000 +-0.836408 0.548107 0.000000 +-0.707106 0.707108 0.000000 +-0.836408 0.548107 0.000000 +-0.929041 0.369976 0.000000 +-0.836408 0.548107 0.000000 +-0.836408 0.548107 0.000000 +-0.929041 0.369976 0.000000 +-0.836408 0.548107 0.000000 +-0.929041 0.369976 0.000000 +-0.982801 0.184666 0.000000 +-0.929041 0.369976 0.000000 +-0.929041 0.369976 0.000000 +-0.548109 0.836407 0.000000 +-0.707107 0.707106 0.000000 +-0.707107 0.707106 0.000000 +-0.995817 0.091364 0.000000 +-0.995817 0.091364 0.000000 +-0.982801 0.184667 0.000000 +-0.982801 0.184666 0.000000 +-0.995817 0.091364 0.000000 +-0.982801 0.184667 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184667 0.000000 +-0.929042 0.369975 0.000000 +-0.929042 0.369975 0.000000 +-0.982801 0.184666 0.000000 +-0.929042 0.369975 0.000000 +-0.836408 0.548108 0.000000 +-0.929042 0.369975 0.000000 +-0.929042 0.369975 0.000000 +-0.836408 0.548108 0.000000 +-0.929042 0.369975 0.000000 +-0.836408 0.548108 0.000000 +-0.707107 0.707106 0.000000 +-0.836408 0.548108 0.000000 +-0.836408 0.548108 0.000000 +-0.707107 0.707106 0.000000 +-0.836408 0.548108 0.000000 +-0.707107 0.707106 0.000000 +0.982801 0.184667 0.000000 +0.995816 0.091379 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369975 0.000000 +0.929042 0.369975 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369975 0.000000 +0.836402 0.548117 0.000000 +0.929042 0.369975 0.000000 +0.929042 0.369975 0.000000 +0.836402 0.548117 0.000000 +0.929042 0.369975 0.000000 +0.836402 0.548117 0.000000 +0.707106 0.707107 0.000000 +0.836402 0.548117 0.000000 +0.836402 0.548117 0.000000 +0.707106 0.707107 0.000000 +0.836402 0.548117 0.000000 +0.707106 0.707107 0.000000 +0.707106 0.707107 0.000000 +0.707106 0.707107 0.000000 +0.548113 0.836404 0.000000 +0.548113 0.836404 0.000000 +0.707106 0.707107 0.000000 +0.548113 0.836404 0.000000 +0.369974 0.929042 0.000000 +0.548113 0.836404 0.000000 +0.548113 0.836404 0.000000 +0.369974 0.929042 0.000000 +0.548113 0.836404 0.000000 +0.369974 0.929042 0.000000 +0.369974 0.929042 0.000000 +0.369974 0.929042 0.000000 +0.184664 0.982802 0.000000 +0.184664 0.982802 0.000000 +0.369974 0.929042 0.000000 +0.184664 0.982802 0.000000 +0.000001 1.000000 0.000000 +0.184664 0.982802 0.000000 +0.184664 0.982802 0.000000 +0.000001 1.000000 0.000000 +0.184664 0.982802 0.000000 +0.000001 1.000000 0.000000 +-0.184664 0.982802 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +-0.184664 0.982802 0.000000 +0.000001 1.000000 0.000000 +-0.184664 0.982802 0.000000 +-0.369974 0.929042 0.000000 +-0.184664 0.982802 0.000000 +-0.184664 0.982802 0.000000 +-0.369974 0.929042 0.000000 +-0.184664 0.982802 0.000000 +-0.369974 0.929042 0.000000 +-0.548109 0.836407 0.000000 +-0.369974 0.929042 0.000000 +-0.369974 0.929042 0.000000 +-0.548109 0.836407 0.000000 +-0.369974 0.929042 0.000000 +-0.548109 0.836407 0.000000 +-0.707107 0.707106 0.000000 +-0.548109 0.836407 0.000000 +-0.548109 0.836407 0.000000 +0.836402 0.548117 0.000000 +0.929042 0.369974 0.000000 +0.929042 0.369974 0.000000 +0.995816 0.091379 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369974 0.000000 +0.929042 0.369974 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369974 0.000000 +-0.982801 0.184666 0.000000 +-0.995817 0.091364 0.000000 +-0.995817 0.091364 0.000000 +-0.982801 0.184666 0.000000 +-0.995817 0.091364 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184666 0.000000 +-0.929042 0.369975 0.000000 +-0.929042 0.369975 0.000000 +-0.982801 0.184666 0.000000 +-0.929042 0.369975 0.000000 +-0.929042 0.369975 0.000000 +-0.929042 0.369975 0.000000 +-0.836408 0.548108 0.000000 +-0.836408 0.548108 0.000000 +-0.929042 0.369975 0.000000 +-0.836408 0.548108 0.000000 +-0.707106 0.707107 0.000000 +-0.836408 0.548108 0.000000 +-0.836408 0.548108 0.000000 +-0.707106 0.707107 0.000000 +-0.836408 0.548108 0.000000 +-0.707106 0.707107 0.000000 +-0.548109 0.836407 0.000000 +-0.707106 0.707107 0.000000 +-0.707106 0.707107 0.000000 +-0.548109 0.836407 0.000000 +-0.707106 0.707107 0.000000 +-0.548109 0.836407 0.000000 +-0.369976 0.929041 0.000000 +-0.548109 0.836407 0.000000 +-0.548109 0.836407 0.000000 +-0.369976 0.929041 0.000000 +-0.548109 0.836407 0.000000 +-0.369976 0.929041 0.000000 +-0.184664 0.982802 0.000000 +-0.369976 0.929041 0.000000 +-0.369976 0.929041 0.000000 +-0.184664 0.982802 0.000000 +-0.369976 0.929041 0.000000 +-0.184664 0.982802 0.000000 +0.000001 1.000000 0.000000 +-0.184664 0.982802 0.000000 +-0.184664 0.982802 0.000000 +0.000001 1.000000 0.000000 +-0.184664 0.982802 0.000000 +0.000001 1.000000 0.000000 +0.184664 0.982802 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.184664 0.982802 0.000000 +0.000001 1.000000 0.000000 +0.184664 0.982802 0.000000 +0.369976 0.929041 0.000000 +0.184664 0.982802 0.000000 +0.184664 0.982802 0.000000 +0.369976 0.929041 0.000000 +0.184664 0.982802 0.000000 +0.369976 0.929041 0.000000 +0.548113 0.836404 0.000000 +0.369976 0.929041 0.000000 +0.369976 0.929041 0.000000 +0.548113 0.836404 0.000000 +0.369976 0.929041 0.000000 +0.548113 0.836404 0.000000 +0.707106 0.707108 0.000000 +0.548113 0.836404 0.000000 +0.548113 0.836404 0.000000 +0.707106 0.707108 0.000000 +0.548113 0.836404 0.000000 +0.707106 0.707108 0.000000 +0.836402 0.548117 0.000000 +0.707106 0.707108 0.000000 +0.707106 0.707108 0.000000 +0.836402 0.548117 0.000000 +0.707106 0.707108 0.000000 +0.836402 0.548117 0.000000 +0.929042 0.369974 0.000000 +0.836402 0.548117 0.000000 +0.836402 0.548117 0.000000 +0.836408 0.548108 0.000000 +0.929042 0.369975 0.000000 +0.929042 0.369975 0.000000 +0.995817 0.091364 0.000000 +0.995817 0.091364 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184666 0.000000 +0.995817 0.091364 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184666 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369975 0.000000 +0.929042 0.369975 0.000000 +0.982801 0.184666 0.000000 +0.929042 0.369975 0.000000 +-0.995817 0.091364 0.000000 +-0.995817 0.091364 0.000000 +-0.982801 0.184667 0.000000 +-0.982801 0.184666 0.000000 +-0.995817 0.091364 0.000000 +-0.982801 0.184667 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184667 0.000000 +-0.929042 0.369975 0.000000 +-0.929042 0.369975 0.000000 +-0.982801 0.184666 0.000000 +-0.929042 0.369975 0.000000 +-0.836408 0.548108 0.000000 +-0.929042 0.369975 0.000000 +-0.929042 0.369975 0.000000 +-0.836408 0.548108 0.000000 +-0.929042 0.369975 0.000000 +-0.836408 0.548108 0.000000 +-0.707107 0.707106 0.000000 +-0.836408 0.548108 0.000000 +-0.836408 0.548108 0.000000 +-0.707107 0.707106 0.000000 +-0.836408 0.548108 0.000000 +-0.707107 0.707106 0.000000 +-0.548109 0.836407 0.000000 +-0.707107 0.707106 0.000000 +-0.707107 0.707106 0.000000 +-0.548109 0.836407 0.000000 +-0.707107 0.707106 0.000000 +-0.548109 0.836407 0.000000 +-0.369974 0.929042 0.000000 +-0.548109 0.836407 0.000000 +-0.548109 0.836407 0.000000 +-0.369974 0.929042 0.000000 +-0.548109 0.836407 0.000000 +-0.369974 0.929042 0.000000 +-0.369974 0.929042 0.000000 +-0.369974 0.929042 0.000000 +-0.184664 0.982802 0.000000 +-0.184664 0.982802 0.000000 +-0.369974 0.929042 0.000000 +-0.184664 0.982802 0.000000 +0.000001 1.000000 0.000000 +-0.184664 0.982802 0.000000 +-0.184664 0.982802 0.000000 +0.000001 1.000000 0.000000 +-0.184664 0.982802 0.000000 +0.000001 1.000000 0.000000 +0.184664 0.982802 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.184664 0.982802 0.000000 +0.000001 1.000000 0.000000 +0.184664 0.982802 0.000000 +0.369974 0.929042 0.000000 +0.184664 0.982802 0.000000 +0.184664 0.982802 0.000000 +0.369974 0.929042 0.000000 +0.184664 0.982802 0.000000 +0.369974 0.929042 0.000000 +0.548109 0.836407 0.000000 +0.369974 0.929042 0.000000 +0.369974 0.929042 0.000000 +0.548109 0.836407 0.000000 +0.369974 0.929042 0.000000 +0.548109 0.836407 0.000000 +0.707107 0.707106 0.000000 +0.548109 0.836407 0.000000 +0.548109 0.836407 0.000000 +0.707107 0.707106 0.000000 +0.548109 0.836407 0.000000 +0.707107 0.707106 0.000000 +0.836408 0.548108 0.000000 +0.707107 0.707106 0.000000 +0.707107 0.707106 0.000000 +0.836408 0.548108 0.000000 +0.707107 0.707106 0.000000 +0.836408 0.548108 0.000000 +0.929042 0.369975 0.000000 +0.836408 0.548108 0.000000 +0.836408 0.548108 0.000000 +-0.982801 0.184666 0.000000 +-0.995817 0.091364 0.000000 +-0.995817 0.091364 0.000000 +0.995817 0.091364 0.000000 +0.995817 0.091364 0.000000 +0.982801 0.184666 0.000000 +0.982801 0.184666 0.000000 +0.995817 0.091364 0.000000 +0.982801 0.184666 0.000000 +0.929042 0.369975 0.000000 +0.982801 0.184666 0.000000 +0.982801 0.184666 0.000000 +0.929042 0.369975 0.000000 +0.982801 0.184666 0.000000 +0.929042 0.369975 0.000000 +0.836408 0.548108 0.000000 +0.929042 0.369975 0.000000 +0.929042 0.369975 0.000000 +0.836408 0.548108 0.000000 +0.929042 0.369975 0.000000 +0.836408 0.548108 0.000000 +0.836408 0.548108 0.000000 +0.836408 0.548108 0.000000 +0.707106 0.707107 0.000000 +0.707106 0.707107 0.000000 +0.836408 0.548108 0.000000 +0.707106 0.707107 0.000000 +0.707106 0.707107 0.000000 +0.707106 0.707107 0.000000 +0.548109 0.836407 0.000000 +0.548109 0.836407 0.000000 +0.707106 0.707107 0.000000 +0.548109 0.836407 0.000000 +0.548109 0.836407 0.000000 +0.548109 0.836407 0.000000 +0.369976 0.929041 0.000000 +0.369976 0.929041 0.000000 +0.548109 0.836407 0.000000 +0.369976 0.929041 0.000000 +0.369976 0.929041 0.000000 +0.369976 0.929041 0.000000 +0.184664 0.982802 0.000000 +0.184664 0.982802 0.000000 +0.369976 0.929041 0.000000 +0.184664 0.982802 0.000000 +0.184664 0.982802 0.000000 +0.184664 0.982802 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.184664 0.982802 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +-0.184664 0.982802 0.000000 +-0.184664 0.982802 0.000000 +0.000001 1.000000 0.000000 +-0.184664 0.982802 0.000000 +-0.369976 0.929041 0.000000 +-0.184664 0.982802 0.000000 +-0.184664 0.982802 0.000000 +-0.369976 0.929041 0.000000 +-0.184664 0.982802 0.000000 +-0.369976 0.929041 0.000000 +-0.369976 0.929041 0.000000 +-0.369976 0.929041 0.000000 +-0.548109 0.836407 0.000000 +-0.548109 0.836407 0.000000 +-0.369976 0.929041 0.000000 +-0.548109 0.836407 0.000000 +-0.548109 0.836407 0.000000 +-0.548109 0.836407 0.000000 +-0.707106 0.707107 0.000000 +-0.707106 0.707107 0.000000 +-0.548109 0.836407 0.000000 +-0.707106 0.707107 0.000000 +-0.707106 0.707107 0.000000 +-0.707106 0.707107 0.000000 +-0.836408 0.548108 0.000000 +-0.836408 0.548108 0.000000 +-0.707106 0.707107 0.000000 +-0.836408 0.548108 0.000000 +-0.929042 0.369975 0.000000 +-0.836408 0.548108 0.000000 +-0.836408 0.548108 0.000000 +-0.929042 0.369975 0.000000 +-0.836408 0.548108 0.000000 +-0.929042 0.369975 0.000000 +-0.982801 0.184666 0.000000 +-0.929042 0.369975 0.000000 +-0.929042 0.369975 0.000000 +-0.982801 0.184666 0.000000 +-0.929042 0.369975 0.000000 +-0.982801 0.184666 0.000000 +-0.995817 0.091364 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184666 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +-0.184664 0.982802 0.000000 +0.995817 0.091364 0.000000 +0.995817 0.091364 0.000000 +0.982801 0.184666 0.000000 +0.982801 0.184667 0.000000 +0.995817 0.091364 0.000000 +0.982801 0.184666 0.000000 +0.929042 0.369975 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184666 0.000000 +0.929042 0.369975 0.000000 +0.982801 0.184666 0.000000 +0.929042 0.369975 0.000000 +0.929042 0.369975 0.000000 +0.929042 0.369975 0.000000 +0.836408 0.548108 0.000000 +0.836408 0.548108 0.000000 +0.929042 0.369975 0.000000 +0.836408 0.548108 0.000000 +0.707107 0.707106 0.000000 +0.836408 0.548108 0.000000 +0.836408 0.548108 0.000000 +0.707107 0.707106 0.000000 +0.836408 0.548108 0.000000 +0.707107 0.707106 0.000000 +0.707107 0.707106 0.000000 +0.707107 0.707106 0.000000 +0.548109 0.836407 0.000000 +0.548109 0.836407 0.000000 +0.707107 0.707106 0.000000 +0.548109 0.836407 0.000000 +0.548109 0.836407 0.000000 +0.548109 0.836407 0.000000 +0.369974 0.929042 0.000000 +0.369974 0.929042 0.000000 +0.548109 0.836407 0.000000 +0.369974 0.929042 0.000000 +0.369974 0.929042 0.000000 +0.369974 0.929042 0.000000 +0.184664 0.982802 0.000000 +0.184664 0.982802 0.000000 +0.369974 0.929042 0.000000 +0.184664 0.982802 0.000000 +0.184664 0.982802 0.000000 +0.184664 0.982802 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.184664 0.982802 0.000000 +0.000001 1.000000 0.000000 +-0.995817 0.091364 0.000000 +-0.995817 0.091364 0.000000 +-0.982801 0.184667 0.000000 +-0.982801 0.184666 0.000000 +-0.995817 0.091364 0.000000 +-0.982801 0.184667 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184667 0.000000 +-0.929042 0.369975 0.000000 +-0.929042 0.369975 0.000000 +-0.982801 0.184666 0.000000 +-0.929042 0.369975 0.000000 +-0.929042 0.369975 0.000000 +-0.929042 0.369975 0.000000 +-0.836408 0.548108 0.000000 +-0.836408 0.548108 0.000000 +-0.929042 0.369975 0.000000 +-0.836408 0.548108 0.000000 +-0.707107 0.707106 0.000000 +-0.836408 0.548108 0.000000 +-0.836408 0.548108 0.000000 +-0.707107 0.707106 0.000000 +-0.836408 0.548108 0.000000 +-0.707107 0.707106 0.000000 +-0.548109 0.836407 0.000000 +-0.707107 0.707106 0.000000 +-0.707107 0.707106 0.000000 +-0.548109 0.836407 0.000000 +-0.707107 0.707106 0.000000 +-0.548109 0.836407 0.000000 +-0.548109 0.836407 0.000000 +-0.548109 0.836407 0.000000 +-0.369974 0.929042 0.000000 +-0.369974 0.929042 0.000000 +-0.548109 0.836407 0.000000 +-0.369974 0.929042 0.000000 +-0.184664 0.982802 0.000000 +-0.369974 0.929042 0.000000 +-0.369974 0.929042 0.000000 +-0.184664 0.982802 0.000000 +-0.369974 0.929042 0.000000 +-0.184664 0.982802 0.000000 +-0.184664 0.982802 0.000000 +-0.184664 0.982802 0.000000 +0.000001 1.000000 0.000000 +-0.982801 0.184666 0.000000 +-0.995817 0.091364 0.000000 +-0.995817 0.091364 0.000000 +0.982801 0.184666 0.000000 +0.995817 0.091364 0.000000 +0.995817 0.091364 0.000000 +0.982801 0.184666 0.000000 +0.995817 0.091364 0.000000 +0.982801 0.184666 0.000000 +0.929042 0.369975 0.000000 +0.982801 0.184666 0.000000 +0.982801 0.184666 0.000000 +0.929042 0.369975 0.000000 +0.982801 0.184666 0.000000 +0.929042 0.369975 0.000000 +0.836408 0.548108 0.000000 +0.929042 0.369975 0.000000 +0.929042 0.369975 0.000000 +0.836408 0.548108 0.000000 +0.929042 0.369975 0.000000 +0.836408 0.548108 0.000000 +0.836408 0.548108 0.000000 +0.836408 0.548108 0.000000 +0.707106 0.707107 0.000000 +0.707106 0.707107 0.000000 +0.836408 0.548108 0.000000 +0.707106 0.707107 0.000000 +0.707106 0.707107 0.000000 +0.707106 0.707107 0.000000 +0.548109 0.836407 0.000000 +0.548109 0.836407 0.000000 +0.707106 0.707107 0.000000 +0.548109 0.836407 0.000000 +0.548109 0.836407 0.000000 +0.548109 0.836407 0.000000 +0.369976 0.929041 0.000000 +0.369976 0.929041 0.000000 +0.548109 0.836407 0.000000 +0.369976 0.929041 0.000000 +0.369976 0.929041 0.000000 +0.369976 0.929041 0.000000 +0.184664 0.982802 0.000000 +0.184664 0.982802 0.000000 +0.369976 0.929041 0.000000 +0.184664 0.982802 0.000000 +0.000001 1.000000 0.000000 +0.184664 0.982802 0.000000 +0.184664 0.982802 0.000000 +0.000001 1.000000 0.000000 +0.184664 0.982802 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +-0.184664 0.982802 0.000000 +-0.184664 0.982802 0.000000 +0.000001 1.000000 0.000000 +-0.184664 0.982802 0.000000 +-0.184664 0.982802 0.000000 +-0.184664 0.982802 0.000000 +-0.369976 0.929041 0.000000 +-0.369976 0.929041 0.000000 +-0.184664 0.982802 0.000000 +-0.369976 0.929041 0.000000 +-0.369976 0.929041 0.000000 +-0.369976 0.929041 0.000000 +-0.548109 0.836407 0.000000 +-0.548109 0.836407 0.000000 +-0.369976 0.929041 0.000000 +-0.548109 0.836407 0.000000 +-0.548109 0.836407 0.000000 +-0.548109 0.836407 0.000000 +-0.707106 0.707107 0.000000 +-0.707106 0.707107 0.000000 +-0.548109 0.836407 0.000000 +-0.707106 0.707107 0.000000 +-0.836408 0.548108 0.000000 +-0.707106 0.707107 0.000000 +-0.707106 0.707107 0.000000 +-0.836408 0.548108 0.000000 +-0.707106 0.707107 0.000000 +-0.836408 0.548108 0.000000 +-0.929042 0.369975 0.000000 +-0.836408 0.548108 0.000000 +-0.836408 0.548108 0.000000 +-0.929042 0.369975 0.000000 +-0.836408 0.548108 0.000000 +-0.929042 0.369975 0.000000 +-0.982801 0.184666 0.000000 +-0.929042 0.369975 0.000000 +-0.929042 0.369975 0.000000 +-0.982801 0.184666 0.000000 +-0.929042 0.369975 0.000000 +-0.982801 0.184666 0.000000 +-0.995817 0.091364 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184666 0.000000 +-0.929042 0.369975 0.000000 +-0.982801 0.184667 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184667 0.000000 +-0.995817 0.091364 0.000000 +-0.995817 0.091364 0.000000 +-0.982801 0.184667 0.000000 +-0.995817 0.091364 0.000000 +-0.982801 0.184666 0.000000 +0.982801 0.184667 0.000000 +0.995817 0.091364 0.000000 +0.995817 0.091364 0.000000 +0.982801 0.184667 0.000000 +0.995817 0.091364 0.000000 +0.982801 0.184666 0.000000 +0.929042 0.369975 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184666 0.000000 +0.929042 0.369975 0.000000 +0.982801 0.184666 0.000000 +0.929042 0.369975 0.000000 +0.836408 0.548108 0.000000 +0.929042 0.369975 0.000000 +0.929042 0.369975 0.000000 +0.836408 0.548108 0.000000 +0.929042 0.369975 0.000000 +0.836408 0.548108 0.000000 +0.836408 0.548108 0.000000 +0.836408 0.548108 0.000000 +0.707107 0.707106 0.000000 +0.707107 0.707106 0.000000 +0.836408 0.548108 0.000000 +0.707107 0.707106 0.000000 +0.707107 0.707106 0.000000 +0.707107 0.707106 0.000000 +0.548109 0.836407 0.000000 +0.548109 0.836407 0.000000 +0.707107 0.707106 0.000000 +0.548109 0.836407 0.000000 +0.548109 0.836407 0.000000 +0.548109 0.836407 0.000000 +0.369974 0.929042 0.000000 +0.369974 0.929042 0.000000 +0.548109 0.836407 0.000000 +0.369974 0.929042 0.000000 +0.184664 0.982802 0.000000 +0.369974 0.929042 0.000000 +0.369974 0.929042 0.000000 +0.184664 0.982802 0.000000 +0.369974 0.929042 0.000000 +0.184664 0.982802 0.000000 +0.000001 1.000000 0.000000 +0.184664 0.982802 0.000000 +0.184664 0.982802 0.000000 +0.000001 1.000000 0.000000 +0.184664 0.982802 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +-0.184664 0.982802 0.000000 +-0.184664 0.982802 0.000000 +0.000001 1.000000 0.000000 +-0.184664 0.982802 0.000000 +-0.184664 0.982802 0.000000 +-0.184664 0.982802 0.000000 +-0.369974 0.929042 0.000000 +-0.369974 0.929042 0.000000 +-0.184664 0.982802 0.000000 +-0.369974 0.929042 0.000000 +-0.369974 0.929042 0.000000 +-0.369974 0.929042 0.000000 +-0.548109 0.836407 0.000000 +-0.548109 0.836407 0.000000 +-0.369974 0.929042 0.000000 +-0.548109 0.836407 0.000000 +-0.707107 0.707106 0.000000 +-0.548109 0.836407 0.000000 +-0.548109 0.836407 0.000000 +-0.707107 0.707106 0.000000 +-0.548109 0.836407 0.000000 +-0.707107 0.707106 0.000000 +-0.707107 0.707106 0.000000 +-0.707107 0.707106 0.000000 +-0.836408 0.548108 0.000000 +-0.836408 0.548108 0.000000 +-0.707107 0.707106 0.000000 +-0.836408 0.548108 0.000000 +-0.929042 0.369975 0.000000 +-0.836408 0.548108 0.000000 +-0.836408 0.548108 0.000000 +-0.929042 0.369975 0.000000 +-0.836408 0.548108 0.000000 +-0.929042 0.369975 0.000000 +-0.982801 0.184666 0.000000 +-0.929042 0.369975 0.000000 +-0.929042 0.369975 0.000000 +-0.982801 0.184666 0.000000 +-0.995817 0.091364 0.000000 +-0.995817 0.091364 0.000000 +0.982801 0.184666 0.000000 +0.995817 0.091364 0.000000 +0.995817 0.091364 0.000000 +0.982801 0.184666 0.000000 +0.995817 0.091364 0.000000 +0.982801 0.184666 0.000000 +0.929042 0.369975 0.000000 +0.982801 0.184666 0.000000 +0.982801 0.184666 0.000000 +0.929042 0.369975 0.000000 +0.982801 0.184666 0.000000 +0.929042 0.369975 0.000000 +0.836408 0.548108 0.000000 +0.929042 0.369975 0.000000 +0.929042 0.369975 0.000000 +0.836408 0.548108 0.000000 +0.929042 0.369975 0.000000 +0.836408 0.548108 0.000000 +0.836408 0.548108 0.000000 +0.836408 0.548108 0.000000 +0.707106 0.707107 0.000000 +0.707106 0.707107 0.000000 +0.836408 0.548108 0.000000 +0.707106 0.707107 0.000000 +0.707106 0.707107 0.000000 +0.707106 0.707107 0.000000 +0.548109 0.836407 0.000000 +0.548109 0.836407 0.000000 +0.707106 0.707107 0.000000 +0.548109 0.836407 0.000000 +0.548109 0.836407 0.000000 +0.548109 0.836407 0.000000 +0.369976 0.929041 0.000000 +0.369976 0.929041 0.000000 +0.548109 0.836407 0.000000 +0.369976 0.929041 0.000000 +0.369976 0.929041 0.000000 +0.369976 0.929041 0.000000 +0.184664 0.982802 0.000000 +0.184664 0.982802 0.000000 +0.369976 0.929041 0.000000 +0.184664 0.982802 0.000000 +0.184664 0.982802 0.000000 +0.184664 0.982802 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.184664 0.982802 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +-0.184664 0.982802 0.000000 +-0.184664 0.982802 0.000000 +0.000001 1.000000 0.000000 +-0.184664 0.982802 0.000000 +-0.369976 0.929041 0.000000 +-0.184664 0.982802 0.000000 +-0.184664 0.982802 0.000000 +-0.369976 0.929041 0.000000 +-0.184664 0.982802 0.000000 +-0.369976 0.929041 0.000000 +-0.369976 0.929041 0.000000 +-0.369976 0.929041 0.000000 +-0.548109 0.836407 0.000000 +-0.548109 0.836407 0.000000 +-0.369976 0.929041 0.000000 +-0.548109 0.836407 0.000000 +-0.707106 0.707107 0.000000 +-0.548109 0.836407 0.000000 +-0.548109 0.836407 0.000000 +-0.707106 0.707107 0.000000 +-0.548109 0.836407 0.000000 +-0.707106 0.707107 0.000000 +-0.836408 0.548108 0.000000 +-0.707106 0.707107 0.000000 +-0.707106 0.707107 0.000000 +-0.836408 0.548108 0.000000 +-0.707106 0.707107 0.000000 +-0.836408 0.548108 0.000000 +-0.929042 0.369975 0.000000 +-0.836408 0.548108 0.000000 +-0.836408 0.548108 0.000000 +-0.929042 0.369975 0.000000 +-0.836408 0.548108 0.000000 +-0.929042 0.369975 0.000000 +-0.982801 0.184666 0.000000 +-0.929042 0.369975 0.000000 +-0.929042 0.369975 0.000000 +-0.982801 0.184666 0.000000 +-0.929042 0.369975 0.000000 +-0.982801 0.184666 0.000000 +-0.995817 0.091364 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184667 0.000000 +-0.995817 0.091364 0.000000 +-0.995817 0.091364 0.000000 +0.995817 0.091364 0.000000 +0.995817 0.091364 0.000000 +0.982801 0.184666 0.000000 +0.982801 0.184667 0.000000 +0.995817 0.091364 0.000000 +0.982801 0.184666 0.000000 +0.929042 0.369975 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184666 0.000000 +0.929042 0.369975 0.000000 +0.982801 0.184666 0.000000 +0.929042 0.369975 0.000000 +0.836408 0.548108 0.000000 +0.929042 0.369975 0.000000 +0.929042 0.369975 0.000000 +0.836408 0.548108 0.000000 +0.929042 0.369975 0.000000 +0.836408 0.548108 0.000000 +0.836408 0.548108 0.000000 +0.836408 0.548108 0.000000 +0.707107 0.707106 0.000000 +0.707107 0.707106 0.000000 +0.836408 0.548108 0.000000 +0.707107 0.707106 0.000000 +0.707107 0.707106 0.000000 +0.707107 0.707106 0.000000 +0.548109 0.836407 0.000000 +0.548109 0.836407 0.000000 +0.707107 0.707106 0.000000 +0.548109 0.836407 0.000000 +0.548109 0.836407 0.000000 +0.548109 0.836407 0.000000 +0.369975 0.929042 0.000000 +0.369975 0.929042 0.000000 +0.548109 0.836407 0.000000 +0.369975 0.929042 0.000000 +0.369975 0.929042 0.000000 +0.369975 0.929042 0.000000 +0.184665 0.982802 0.000000 +0.184665 0.982802 0.000000 +0.369975 0.929042 0.000000 +0.184665 0.982802 0.000000 +0.000000 1.000000 0.000000 +0.184665 0.982802 0.000000 +0.184665 0.982802 0.000000 +0.000000 1.000000 0.000000 +0.184665 0.982802 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.184665 0.982802 0.000000 +-0.184665 0.982802 0.000000 +0.000000 1.000000 0.000000 +-0.184665 0.982802 0.000000 +-0.369972 0.929043 0.000000 +-0.184665 0.982802 0.000000 +-0.184665 0.982802 0.000000 +-0.369972 0.929043 0.000000 +-0.184665 0.982802 0.000000 +-0.369972 0.929043 0.000000 +-0.369972 0.929043 0.000000 +-0.369972 0.929043 0.000000 +-0.548110 0.836406 0.000000 +-0.548110 0.836406 0.000000 +-0.369972 0.929043 0.000000 +-0.548110 0.836406 0.000000 +-0.707108 0.707105 0.000000 +-0.548110 0.836406 0.000000 +-0.548110 0.836406 0.000000 +-0.707108 0.707105 0.000000 +-0.548110 0.836406 0.000000 +-0.707108 0.707105 0.000000 +-0.836406 0.548110 0.000000 +-0.707108 0.707105 0.000000 +-0.707108 0.707105 0.000000 +-0.836406 0.548110 0.000000 +-0.707108 0.707105 0.000000 +-0.836406 0.548110 0.000000 +-0.929042 0.369975 0.000000 +-0.836406 0.548110 0.000000 +-0.836406 0.548110 0.000000 +-0.929042 0.369975 0.000000 +-0.836406 0.548110 0.000000 +-0.929042 0.369975 0.000000 +-0.982801 0.184666 0.000000 +-0.929042 0.369975 0.000000 +-0.929042 0.369975 0.000000 +-0.982801 0.184666 0.000000 +-0.929042 0.369975 0.000000 +-0.982801 0.184667 0.000000 +-0.995817 0.091364 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184667 0.000000 +-0.982801 0.184666 0.000000 +-0.995817 0.091364 0.000000 +-0.995817 0.091364 0.000000 +0.995817 0.091364 0.000000 +0.995817 0.091364 0.000000 +0.982801 0.184666 0.000000 +0.982801 0.184666 0.000000 +0.995817 0.091364 0.000000 +0.982801 0.184666 0.000000 +0.982801 0.184666 0.000000 +0.982801 0.184666 0.000000 +0.929042 0.369975 0.000000 +0.929042 0.369975 0.000000 +0.982801 0.184666 0.000000 +0.929042 0.369975 0.000000 +0.929042 0.369975 0.000000 +0.929042 0.369975 0.000000 +0.836408 0.548108 0.000000 +0.836408 0.548108 0.000000 +0.929042 0.369975 0.000000 +0.836408 0.548108 0.000000 +0.836408 0.548108 0.000000 +0.836408 0.548108 0.000000 +0.707106 0.707107 0.000000 +0.707106 0.707107 0.000000 +0.836408 0.548108 0.000000 +0.707106 0.707107 0.000000 +0.707106 0.707107 0.000000 +0.707106 0.707107 0.000000 +0.548109 0.836407 0.000000 +0.548109 0.836407 0.000000 +0.707106 0.707107 0.000000 +0.548109 0.836407 0.000000 +0.369977 0.929041 0.000000 +0.548109 0.836407 0.000000 +0.548109 0.836407 0.000000 +0.369977 0.929041 0.000000 +0.548109 0.836407 0.000000 +0.369977 0.929041 0.000000 +0.184665 0.982801 0.000000 +0.369977 0.929041 0.000000 +0.369977 0.929041 0.000000 +0.184665 0.982801 0.000000 +0.369977 0.929041 0.000000 +0.184665 0.982802 0.000000 +0.000000 1.000000 0.000000 +0.184665 0.982801 0.000000 +0.184665 0.982802 0.000000 +0.000000 1.000000 0.000000 +0.184665 0.982802 0.000000 +0.000000 1.000000 0.000000 +-0.184665 0.982801 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.184665 0.982801 0.000000 +0.000000 1.000000 0.000000 +-0.184665 0.982801 0.000000 +-0.369974 0.929042 0.000000 +-0.184665 0.982801 0.000000 +-0.184665 0.982801 0.000000 +-0.369974 0.929042 0.000000 +-0.184665 0.982801 0.000000 +-0.369974 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.369974 0.929042 0.000000 +-0.369974 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.369974 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.548110 0.836406 0.000000 +-0.548110 0.836406 0.000000 +-0.707108 0.707106 0.000000 +-0.707108 0.707106 0.000000 +-0.548110 0.836406 0.000000 +-0.707108 0.707106 0.000000 +-0.836406 0.548110 0.000000 +-0.707108 0.707106 0.000000 +-0.707108 0.707106 0.000000 +-0.836406 0.548110 0.000000 +-0.707108 0.707106 0.000000 +-0.836406 0.548110 0.000000 +-0.929042 0.369975 0.000000 +-0.836406 0.548110 0.000000 +-0.836406 0.548110 0.000000 +-0.929042 0.369975 0.000000 +-0.836406 0.548110 0.000000 +-0.929042 0.369975 0.000000 +-0.982801 0.184666 0.000000 +-0.929042 0.369975 0.000000 +-0.929042 0.369975 0.000000 +-0.982801 0.184666 0.000000 +-0.929042 0.369975 0.000000 +-0.982801 0.184666 0.000000 +-0.995817 0.091364 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184667 0.000000 +-0.929042 0.369975 0.000000 +-0.995817 0.091364 0.000000 +-0.995817 0.091364 0.000000 +-0.982801 0.184667 0.000000 +-0.982801 0.184666 0.000000 +-0.995817 0.091364 0.000000 +-0.982801 0.184667 0.000000 +0.982802 0.184663 0.000000 +0.995817 0.091364 0.000000 +0.995817 0.091364 0.000000 +0.982802 0.184663 0.000000 +0.995817 0.091364 0.000000 +0.982802 0.184663 0.000000 +0.982802 0.184663 0.000000 +0.982802 0.184663 0.000000 +0.929043 0.369972 0.000000 +0.929043 0.369972 0.000000 +0.982802 0.184663 0.000000 +0.929043 0.369972 0.000000 +0.929043 0.369972 0.000000 +0.929043 0.369972 0.000000 +0.836406 0.548110 0.000000 +0.836406 0.548110 0.000000 +0.929043 0.369972 0.000000 +0.836406 0.548110 0.000000 +0.836406 0.548110 0.000000 +0.836406 0.548110 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836406 0.548110 0.000000 +0.707107 0.707107 0.000000 +0.548110 0.836406 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.548110 0.836406 0.000000 +0.707107 0.707107 0.000000 +0.548110 0.836406 0.000000 +0.369974 0.929042 0.000000 +0.548110 0.836406 0.000000 +0.548110 0.836406 0.000000 +0.369974 0.929042 0.000000 +0.548110 0.836406 0.000000 +0.369974 0.929042 0.000000 +0.184665 0.982802 0.000000 +0.369974 0.929042 0.000000 +0.369974 0.929042 0.000000 +0.184665 0.982802 0.000000 +0.369974 0.929042 0.000000 +0.184665 0.982802 0.000000 +0.000000 1.000000 0.000000 +0.184665 0.982802 0.000000 +0.184665 0.982802 0.000000 +0.000000 1.000000 0.000000 +0.184665 0.982802 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.184665 0.982802 0.000000 +-0.184665 0.982802 0.000000 +0.000000 1.000000 0.000000 +-0.184665 0.982802 0.000000 +-0.184665 0.982802 0.000000 +-0.184665 0.982802 0.000000 +-0.369972 0.929043 0.000000 +-0.369972 0.929043 0.000000 +-0.184665 0.982802 0.000000 +-0.369972 0.929043 0.000000 +-0.369972 0.929043 0.000000 +-0.369972 0.929043 0.000000 +-0.548110 0.836406 0.000000 +-0.548110 0.836406 0.000000 +-0.369972 0.929043 0.000000 +-0.548110 0.836406 0.000000 +-0.548110 0.836406 0.000000 +-0.548110 0.836406 0.000000 +-0.707108 0.707105 0.000000 +-0.707108 0.707105 0.000000 +-0.548110 0.836406 0.000000 +-0.707108 0.707105 0.000000 +-0.836406 0.548110 0.000000 +-0.707108 0.707105 0.000000 +-0.707108 0.707105 0.000000 +-0.836406 0.548110 0.000000 +-0.707108 0.707105 0.000000 +-0.836406 0.548110 0.000000 +-0.836406 0.548110 0.000000 +-0.836406 0.548110 0.000000 +-0.929042 0.369975 0.000000 +-0.929042 0.369975 0.000000 +-0.836406 0.548110 0.000000 +-0.929042 0.369975 0.000000 +-0.929042 0.369975 0.000000 +-0.929042 0.369975 0.000000 +-0.982801 0.184666 0.000000 +-0.929042 0.369975 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184666 0.000000 +-0.995817 0.091364 0.000000 +-0.995817 0.091364 0.000000 +-0.982801 0.184666 0.000000 +-0.995817 0.091364 0.000000 +-0.982801 0.184666 0.000000 +0.982802 0.184663 0.000000 +0.995817 0.091364 0.000000 +0.995817 0.091364 0.000000 +0.982802 0.184663 0.000000 +0.995817 0.091364 0.000000 +0.982802 0.184663 0.000000 +0.929043 0.369972 0.000000 +0.982802 0.184663 0.000000 +0.982802 0.184663 0.000000 +0.929043 0.369972 0.000000 +0.982802 0.184663 0.000000 +0.929043 0.369972 0.000000 +0.836406 0.548110 0.000000 +0.929043 0.369972 0.000000 +0.929043 0.369972 0.000000 +0.836406 0.548110 0.000000 +0.929043 0.369972 0.000000 +0.836406 0.548110 0.000000 +0.836406 0.548110 0.000000 +0.836406 0.548110 0.000000 +0.707106 0.707107 0.000000 +0.707106 0.707107 0.000000 +0.836406 0.548110 0.000000 +0.707106 0.707107 0.000000 +0.548110 0.836406 0.000000 +0.707106 0.707107 0.000000 +0.707106 0.707107 0.000000 +0.548110 0.836406 0.000000 +0.707106 0.707107 0.000000 +0.548110 0.836406 0.000000 +0.548110 0.836406 0.000000 +0.548110 0.836406 0.000000 +0.369975 0.929042 0.000000 +0.369975 0.929042 0.000000 +0.548110 0.836406 0.000000 +0.369975 0.929042 0.000000 +0.369975 0.929042 0.000000 +0.369975 0.929042 0.000000 +0.184665 0.982801 0.000000 +0.184665 0.982802 0.000000 +0.369975 0.929042 0.000000 +0.184665 0.982801 0.000000 +0.184665 0.982802 0.000000 +0.184665 0.982801 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.184665 0.982802 0.000000 +0.000000 1.000000 0.000000 +-0.184665 0.982801 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.184665 0.982801 0.000000 +0.000000 1.000000 0.000000 +-0.184665 0.982801 0.000000 +-0.184665 0.982801 0.000000 +-0.184665 0.982801 0.000000 +-0.369974 0.929042 0.000000 +-0.369974 0.929042 0.000000 +-0.184665 0.982801 0.000000 +-0.369974 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.369974 0.929042 0.000000 +-0.369974 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.369974 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.707108 0.707106 0.000000 +-0.548110 0.836406 0.000000 +-0.548110 0.836406 0.000000 +-0.707108 0.707106 0.000000 +-0.548110 0.836406 0.000000 +-0.707108 0.707106 0.000000 +-0.836406 0.548110 0.000000 +-0.707108 0.707106 0.000000 +-0.707108 0.707106 0.000000 +-0.836406 0.548110 0.000000 +-0.707108 0.707106 0.000000 +-0.836406 0.548110 0.000000 +-0.929042 0.369975 0.000000 +-0.836406 0.548110 0.000000 +-0.836406 0.548110 0.000000 +-0.929042 0.369975 0.000000 +-0.836406 0.548110 0.000000 +-0.929042 0.369975 0.000000 +-0.982801 0.184666 0.000000 +-0.929042 0.369975 0.000000 +-0.929042 0.369975 0.000000 +-0.929042 0.369975 0.000000 +-0.982802 0.184665 0.000000 +-0.982802 0.184665 0.000000 +-0.982802 0.184665 0.000000 +-0.995817 0.091364 0.000000 +-0.995817 0.091364 0.000000 +-0.982802 0.184665 0.000000 +-0.995817 0.091364 0.000000 +-0.982802 0.184665 0.000000 +0.982802 0.184663 0.000000 +0.995817 0.091364 0.000000 +0.995817 0.091364 0.000000 +0.982802 0.184663 0.000000 +0.995817 0.091364 0.000000 +0.982802 0.184663 0.000000 +0.982802 0.184663 0.000000 +0.982802 0.184663 0.000000 +0.929043 0.369972 0.000000 +0.929043 0.369972 0.000000 +0.982802 0.184663 0.000000 +0.929043 0.369972 0.000000 +0.929043 0.369972 0.000000 +0.929043 0.369972 0.000000 +0.836406 0.548110 0.000000 +0.836406 0.548110 0.000000 +0.929043 0.369972 0.000000 +0.836406 0.548110 0.000000 +0.707107 0.707107 0.000000 +0.836406 0.548110 0.000000 +0.836406 0.548110 0.000000 +0.707107 0.707107 0.000000 +0.836406 0.548110 0.000000 +0.707107 0.707107 0.000000 +0.548110 0.836406 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.548110 0.836406 0.000000 +0.707107 0.707107 0.000000 +0.548110 0.836406 0.000000 +0.369973 0.929042 0.000000 +0.548110 0.836406 0.000000 +0.548110 0.836406 0.000000 +0.369973 0.929042 0.000000 +0.548110 0.836406 0.000000 +0.369973 0.929042 0.000000 +0.184664 0.982802 0.000000 +0.369973 0.929042 0.000000 +0.369973 0.929042 0.000000 +0.184664 0.982802 0.000000 +0.369973 0.929042 0.000000 +0.184664 0.982802 0.000000 +0.000000 1.000000 0.000000 +0.184664 0.982802 0.000000 +0.184664 0.982802 0.000000 +0.000000 1.000000 0.000000 +0.184664 0.982802 0.000000 +0.000000 1.000000 0.000000 +-0.184665 0.982802 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.184665 0.982802 0.000000 +0.000000 1.000000 0.000000 +-0.184665 0.982802 0.000000 +-0.369974 0.929042 0.000000 +-0.184665 0.982802 0.000000 +-0.184665 0.982802 0.000000 +-0.369974 0.929042 0.000000 +-0.184665 0.982802 0.000000 +-0.369974 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.369974 0.929042 0.000000 +-0.369974 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.369974 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.707108 0.707106 0.000000 +-0.548110 0.836406 0.000000 +-0.548110 0.836406 0.000000 +-0.707108 0.707106 0.000000 +-0.548110 0.836406 0.000000 +-0.707108 0.707106 0.000000 +-0.707108 0.707106 0.000000 +-0.707108 0.707106 0.000000 +-0.836406 0.548110 0.000000 +-0.836406 0.548110 0.000000 +-0.707108 0.707106 0.000000 +-0.836406 0.548110 0.000000 +-0.929042 0.369975 0.000000 +-0.836406 0.548110 0.000000 +-0.836406 0.548110 0.000000 +-0.929042 0.369975 0.000000 +-0.836406 0.548110 0.000000 +-0.929042 0.369975 0.000000 +-0.982802 0.184665 0.000000 +-0.929042 0.369975 0.000000 +-0.929042 0.369975 0.000000 +-0.982802 0.184665 0.000000 +-0.995817 0.091364 0.000000 +-0.995817 0.091364 0.000000 +0.995817 0.091364 0.000000 +0.995817 0.091364 0.000000 +0.982802 0.184663 0.000000 +0.982802 0.184663 0.000000 +0.995817 0.091364 0.000000 +0.982802 0.184663 0.000000 +0.929043 0.369972 0.000000 +0.982802 0.184663 0.000000 +0.982802 0.184663 0.000000 +0.929043 0.369972 0.000000 +0.982802 0.184663 0.000000 +0.929043 0.369972 0.000000 +0.836406 0.548110 0.000000 +0.929043 0.369972 0.000000 +0.929043 0.369972 0.000000 +0.836406 0.548110 0.000000 +0.929043 0.369972 0.000000 +0.836406 0.548110 0.000000 +0.707106 0.707107 0.000000 +0.836406 0.548110 0.000000 +0.836406 0.548110 0.000000 +0.707106 0.707107 0.000000 +0.836406 0.548110 0.000000 +0.707106 0.707107 0.000000 +0.548110 0.836406 0.000000 +0.707106 0.707107 0.000000 +0.707106 0.707107 0.000000 +0.548110 0.836406 0.000000 +0.707106 0.707107 0.000000 +0.548110 0.836406 0.000000 +0.369975 0.929042 0.000000 +0.548110 0.836406 0.000000 +0.548110 0.836406 0.000000 +0.369975 0.929042 0.000000 +0.548110 0.836406 0.000000 +0.369975 0.929042 0.000000 +0.184664 0.982802 0.000000 +0.369975 0.929042 0.000000 +0.369975 0.929042 0.000000 +0.184664 0.982802 0.000000 +0.369975 0.929042 0.000000 +0.184664 0.982802 0.000000 +0.000000 1.000000 0.000000 +0.184664 0.982802 0.000000 +0.184664 0.982802 0.000000 +0.000000 1.000000 0.000000 +0.184664 0.982802 0.000000 +0.000000 1.000000 0.000000 +-0.184665 0.982801 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.184665 0.982801 0.000000 +0.000000 1.000000 0.000000 +-0.184665 0.982801 0.000000 +-0.369975 0.929042 0.000000 +-0.184665 0.982801 0.000000 +-0.184665 0.982801 0.000000 +-0.369975 0.929042 0.000000 +-0.184665 0.982801 0.000000 +-0.369975 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.369975 0.929042 0.000000 +-0.369975 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.369975 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.707107 0.707107 0.000000 +-0.548110 0.836406 0.000000 +-0.548110 0.836406 0.000000 +-0.707107 0.707107 0.000000 +-0.548110 0.836406 0.000000 +-0.707107 0.707107 0.000000 +-0.836406 0.548110 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836406 0.548110 0.000000 +-0.707107 0.707107 0.000000 +-0.836406 0.548110 0.000000 +-0.929042 0.369975 0.000000 +-0.836406 0.548110 0.000000 +-0.836406 0.548110 0.000000 +-0.929042 0.369975 0.000000 +-0.836406 0.548110 0.000000 +-0.929042 0.369975 0.000000 +-0.982802 0.184665 0.000000 +-0.929042 0.369975 0.000000 +-0.929042 0.369975 0.000000 +-0.982802 0.184665 0.000000 +-0.929042 0.369975 0.000000 +-0.982802 0.184665 0.000000 +-0.995817 0.091364 0.000000 +-0.982802 0.184665 0.000000 +-0.982802 0.184665 0.000000 +-0.982802 0.184665 0.000000 +-0.995817 0.091364 0.000000 +-0.995817 0.091364 0.000000 +0.982802 0.184665 0.000000 +0.995817 0.091364 0.000000 +0.995817 0.091364 0.000000 +0.982802 0.184665 0.000000 +0.995817 0.091364 0.000000 +0.982802 0.184665 0.000000 +0.982802 0.184665 0.000000 +0.982802 0.184665 0.000000 +0.929042 0.369975 0.000000 +0.929042 0.369975 0.000000 +0.982802 0.184665 0.000000 +0.929042 0.369975 0.000000 +0.929042 0.369975 0.000000 +0.929042 0.369975 0.000000 +0.836406 0.548110 0.000000 +0.836406 0.548110 0.000000 +0.929042 0.369975 0.000000 +0.836406 0.548110 0.000000 +0.836406 0.548110 0.000000 +0.836406 0.548110 0.000000 +0.707108 0.707106 0.000000 +0.707108 0.707106 0.000000 +0.836406 0.548110 0.000000 +0.707108 0.707106 0.000000 +0.707108 0.707106 0.000000 +0.707108 0.707106 0.000000 +0.548110 0.836406 0.000000 +0.548110 0.836406 0.000000 +0.707108 0.707106 0.000000 +0.548110 0.836406 0.000000 +0.369974 0.929042 0.000000 +0.548110 0.836406 0.000000 +0.548110 0.836406 0.000000 +0.369974 0.929042 0.000000 +0.548110 0.836406 0.000000 +0.369974 0.929042 0.000000 +0.184665 0.982802 0.000000 +0.369974 0.929042 0.000000 +0.369974 0.929042 0.000000 +0.184665 0.982802 0.000000 +0.369974 0.929042 0.000000 +0.184665 0.982802 0.000000 +0.000000 1.000000 0.000000 +0.184665 0.982802 0.000000 +0.184665 0.982802 0.000000 +0.000000 1.000000 0.000000 +0.184665 0.982802 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.184665 0.982802 0.000000 +-0.184665 0.982802 0.000000 +0.000000 1.000000 0.000000 +-0.184665 0.982802 0.000000 +-0.369974 0.929042 0.000000 +-0.184665 0.982802 0.000000 +-0.184665 0.982802 0.000000 +-0.369974 0.929042 0.000000 +-0.184665 0.982802 0.000000 +-0.369974 0.929042 0.000000 +-0.369974 0.929042 0.000000 +-0.369974 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.548110 0.836406 0.000000 +-0.369974 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.548110 0.836406 0.000000 +-0.548110 0.836406 0.000000 +-0.707107 0.707106 0.000000 +-0.707107 0.707106 0.000000 +-0.548110 0.836406 0.000000 +-0.707107 0.707106 0.000000 +-0.707107 0.707106 0.000000 +-0.707107 0.707106 0.000000 +-0.836406 0.548110 0.000000 +-0.836406 0.548110 0.000000 +-0.707107 0.707106 0.000000 +-0.836406 0.548110 0.000000 +-0.836406 0.548110 0.000000 +-0.836406 0.548110 0.000000 +-0.929042 0.369974 0.000000 +-0.929042 0.369974 0.000000 +-0.836406 0.548110 0.000000 +-0.929042 0.369974 0.000000 +-0.982802 0.184665 0.000000 +-0.929042 0.369974 0.000000 +-0.929042 0.369974 0.000000 +-0.982802 0.184665 0.000000 +-0.929042 0.369974 0.000000 +-0.982802 0.184665 0.000000 +-0.995817 0.091364 0.000000 +-0.982802 0.184665 0.000000 +-0.982802 0.184665 0.000000 +0.995817 0.091364 0.000000 +0.995817 0.091364 0.000000 +0.982802 0.184665 0.000000 +-0.995817 0.091364 0.000000 +-0.995817 0.091364 0.000000 +-0.982802 0.184665 0.000000 +-0.982802 0.184665 0.000000 +-0.995817 0.091364 0.000000 +-0.982802 0.184665 0.000000 +-0.929042 0.369974 0.000000 +-0.982802 0.184665 0.000000 +-0.982802 0.184665 0.000000 +-0.929042 0.369974 0.000000 +-0.982802 0.184665 0.000000 +-0.929042 0.369974 0.000000 +-0.836406 0.548110 0.000000 +-0.929042 0.369974 0.000000 +-0.929042 0.369974 0.000000 +-0.836406 0.548110 0.000000 +-0.929042 0.369974 0.000000 +-0.836406 0.548110 0.000000 +-0.707107 0.707107 0.000000 +-0.836406 0.548110 0.000000 +-0.836406 0.548110 0.000000 +-0.707107 0.707107 0.000000 +-0.836406 0.548110 0.000000 +-0.707107 0.707107 0.000000 +-0.548110 0.836406 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.548110 0.836406 0.000000 +-0.707107 0.707107 0.000000 +-0.548110 0.836406 0.000000 +-0.369975 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.548110 0.836406 0.000000 +-0.369975 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.369975 0.929042 0.000000 +-0.369975 0.929042 0.000000 +-0.369975 0.929042 0.000000 +-0.184665 0.982802 0.000000 +-0.184665 0.982802 0.000000 +-0.369975 0.929042 0.000000 +-0.184665 0.982802 0.000000 +0.000000 1.000000 0.000000 +-0.184665 0.982802 0.000000 +-0.184665 0.982802 0.000000 +0.000000 1.000000 0.000000 +-0.184665 0.982802 0.000000 +0.000000 1.000000 0.000000 +0.184665 0.982802 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.184665 0.982802 0.000000 +0.000000 1.000000 0.000000 +0.184665 0.982802 0.000000 +0.369975 0.929042 0.000000 +0.184665 0.982802 0.000000 +0.184665 0.982802 0.000000 +0.369975 0.929042 0.000000 +0.184665 0.982802 0.000000 +0.369975 0.929042 0.000000 +0.548110 0.836406 0.000000 +0.369975 0.929042 0.000000 +0.369975 0.929042 0.000000 +0.548110 0.836406 0.000000 +0.369975 0.929042 0.000000 +0.548110 0.836406 0.000000 +0.548110 0.836406 0.000000 +0.548110 0.836406 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.548110 0.836406 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836406 0.548110 0.000000 +0.836406 0.548110 0.000000 +0.707107 0.707107 0.000000 +0.836406 0.548110 0.000000 +0.836406 0.548110 0.000000 +0.836406 0.548110 0.000000 +0.929042 0.369975 0.000000 +0.929042 0.369975 0.000000 +0.836406 0.548110 0.000000 +0.929042 0.369975 0.000000 +0.929042 0.369975 0.000000 +0.929042 0.369975 0.000000 +0.982802 0.184665 0.000000 +0.982802 0.184665 0.000000 +0.929042 0.369975 0.000000 +0.982802 0.184665 0.000000 +0.982802 0.184665 0.000000 +0.982802 0.184665 0.000000 +0.995817 0.091364 0.000000 +-0.929041 0.369976 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184666 0.000000 +-0.995819 0.091349 0.000000 +-0.995819 0.091349 0.000000 +-0.982801 0.184666 0.000000 +-0.995819 0.091349 0.000000 +-0.982801 0.184666 0.000000 +0.982801 0.184667 0.000000 +0.995816 0.091379 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369975 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369975 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369975 0.000000 +0.836402 0.548117 0.000000 +0.929042 0.369975 0.000000 +0.929042 0.369975 0.000000 +0.836402 0.548117 0.000000 +0.929042 0.369975 0.000000 +0.836402 0.548117 0.000000 +0.836402 0.548117 0.000000 +0.836402 0.548117 0.000000 +0.707106 0.707107 0.000000 +0.707106 0.707107 0.000000 +0.836402 0.548117 0.000000 +0.707106 0.707107 0.000000 +0.548110 0.836406 0.000000 +0.707106 0.707107 0.000000 +0.707106 0.707107 0.000000 +0.548110 0.836406 0.000000 +0.707106 0.707107 0.000000 +0.548110 0.836406 0.000000 +0.369973 0.929042 0.000000 +0.548110 0.836406 0.000000 +0.548110 0.836406 0.000000 +0.369973 0.929042 0.000000 +0.548110 0.836406 0.000000 +0.369973 0.929042 0.000000 +0.184666 0.982801 0.000000 +0.369973 0.929042 0.000000 +0.369973 0.929042 0.000000 +0.184666 0.982801 0.000000 +0.369973 0.929042 0.000000 +0.184666 0.982801 0.000000 +0.000001 1.000000 0.000000 +0.184666 0.982801 0.000000 +0.184666 0.982801 0.000000 +0.000001 1.000000 0.000000 +0.184666 0.982801 0.000000 +0.000001 1.000000 0.000000 +-0.184665 0.982802 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +-0.184665 0.982802 0.000000 +0.000001 1.000000 0.000000 +-0.184665 0.982801 0.000000 +-0.369973 0.929042 0.000000 +-0.184665 0.982802 0.000000 +-0.184665 0.982801 0.000000 +-0.369973 0.929042 0.000000 +-0.184665 0.982801 0.000000 +-0.369973 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.369973 0.929042 0.000000 +-0.369973 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.369973 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.707106 0.707107 0.000000 +-0.548110 0.836406 0.000000 +-0.548110 0.836406 0.000000 +-0.707106 0.707107 0.000000 +-0.548110 0.836406 0.000000 +-0.707106 0.707107 0.000000 +-0.836408 0.548107 0.000000 +-0.707106 0.707107 0.000000 +-0.707106 0.707107 0.000000 +-0.836408 0.548107 0.000000 +-0.707106 0.707107 0.000000 +-0.836408 0.548107 0.000000 +-0.929041 0.369976 0.000000 +-0.836408 0.548107 0.000000 +-0.836408 0.548107 0.000000 +-0.929041 0.369976 0.000000 +-0.836408 0.548107 0.000000 +-0.929041 0.369976 0.000000 +-0.982801 0.184666 0.000000 +-0.929041 0.369976 0.000000 +-0.929041 0.369976 0.000000 +-0.707106 0.707108 0.000000 +-0.836408 0.548107 0.000000 +-0.836408 0.548107 0.000000 +-0.995819 0.091349 0.000000 +-0.995819 0.091349 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184666 0.000000 +-0.995819 0.091349 0.000000 +-0.982801 0.184666 0.000000 +-0.929041 0.369976 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184666 0.000000 +-0.929041 0.369976 0.000000 +-0.982801 0.184666 0.000000 +-0.929041 0.369976 0.000000 +-0.929041 0.369976 0.000000 +-0.929041 0.369976 0.000000 +-0.836408 0.548107 0.000000 +-0.836408 0.548107 0.000000 +-0.929041 0.369976 0.000000 +-0.836408 0.548107 0.000000 +0.982801 0.184667 0.000000 +0.995816 0.091379 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369974 0.000000 +0.929042 0.369974 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369974 0.000000 +0.836402 0.548117 0.000000 +0.929042 0.369974 0.000000 +0.929042 0.369974 0.000000 +0.836402 0.548117 0.000000 +0.929042 0.369974 0.000000 +0.836402 0.548117 0.000000 +0.836402 0.548117 0.000000 +0.836402 0.548117 0.000000 +0.707106 0.707108 0.000000 +0.707106 0.707108 0.000000 +0.836402 0.548117 0.000000 +0.707106 0.707108 0.000000 +0.707106 0.707108 0.000000 +0.707106 0.707108 0.000000 +0.548110 0.836406 0.000000 +0.548110 0.836406 0.000000 +0.707106 0.707108 0.000000 +0.548110 0.836406 0.000000 +0.369975 0.929042 0.000000 +0.548110 0.836406 0.000000 +0.548110 0.836406 0.000000 +0.369975 0.929042 0.000000 +0.548110 0.836406 0.000000 +0.369975 0.929042 0.000000 +0.184666 0.982801 0.000000 +0.369975 0.929042 0.000000 +0.369975 0.929042 0.000000 +0.184666 0.982801 0.000000 +0.369975 0.929042 0.000000 +0.184666 0.982801 0.000000 +0.000001 1.000000 0.000000 +0.184666 0.982801 0.000000 +0.184666 0.982801 0.000000 +0.000001 1.000000 0.000000 +0.184666 0.982801 0.000000 +0.000001 1.000000 0.000000 +-0.184665 0.982802 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +-0.184665 0.982802 0.000000 +0.000001 1.000000 0.000000 +-0.184665 0.982802 0.000000 +-0.369975 0.929042 0.000000 +-0.184665 0.982802 0.000000 +-0.184665 0.982802 0.000000 +-0.369975 0.929042 0.000000 +-0.184665 0.982802 0.000000 +-0.369975 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.369975 0.929042 0.000000 +-0.369975 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.369975 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.707106 0.707108 0.000000 +-0.548110 0.836406 0.000000 +-0.548110 0.836406 0.000000 +-0.707106 0.707108 0.000000 +-0.548110 0.836406 0.000000 +-0.707106 0.707108 0.000000 +-0.836408 0.548107 0.000000 +-0.707106 0.707108 0.000000 +-0.707106 0.707108 0.000000 +-0.836408 0.548107 0.000000 +-0.929041 0.369976 0.000000 +-0.929041 0.369976 0.000000 +-0.982801 0.184666 0.000000 +-0.995819 0.091349 0.000000 +-0.995819 0.091349 0.000000 +-0.982801 0.184666 0.000000 +-0.995819 0.091349 0.000000 +-0.982801 0.184666 0.000000 +-0.929041 0.369976 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184666 0.000000 +-0.929041 0.369976 0.000000 +-0.982801 0.184666 0.000000 +-0.929041 0.369976 0.000000 +0.982801 0.184667 0.000000 +0.995816 0.091379 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369975 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369975 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369975 0.000000 +0.836402 0.548117 0.000000 +0.929042 0.369975 0.000000 +0.929042 0.369975 0.000000 +0.836402 0.548117 0.000000 +0.929042 0.369975 0.000000 +0.836402 0.548117 0.000000 +0.836402 0.548117 0.000000 +0.836402 0.548117 0.000000 +0.707106 0.707107 0.000000 +0.707106 0.707107 0.000000 +0.836402 0.548117 0.000000 +0.707106 0.707107 0.000000 +0.548110 0.836406 0.000000 +0.707106 0.707107 0.000000 +0.707106 0.707107 0.000000 +0.548110 0.836406 0.000000 +0.707106 0.707107 0.000000 +0.548110 0.836406 0.000000 +0.369973 0.929042 0.000000 +0.548110 0.836406 0.000000 +0.548110 0.836406 0.000000 +0.369973 0.929042 0.000000 +0.548110 0.836406 0.000000 +0.369973 0.929042 0.000000 +0.184666 0.982801 0.000000 +0.369973 0.929042 0.000000 +0.369973 0.929042 0.000000 +0.184666 0.982801 0.000000 +0.369973 0.929042 0.000000 +0.184666 0.982801 0.000000 +0.184666 0.982801 0.000000 +0.184666 0.982801 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.184666 0.982801 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +-0.184665 0.982802 0.000000 +-0.184665 0.982801 0.000000 +0.000001 1.000000 0.000000 +-0.184665 0.982802 0.000000 +-0.184665 0.982801 0.000000 +-0.184665 0.982802 0.000000 +-0.369973 0.929042 0.000000 +-0.369973 0.929042 0.000000 +-0.184665 0.982801 0.000000 +-0.369973 0.929042 0.000000 +-0.369973 0.929042 0.000000 +-0.369973 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.548110 0.836406 0.000000 +-0.369973 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.707106 0.707107 0.000000 +-0.548110 0.836406 0.000000 +-0.548110 0.836406 0.000000 +-0.707106 0.707107 0.000000 +-0.548110 0.836406 0.000000 +-0.707106 0.707107 0.000000 +-0.836408 0.548107 0.000000 +-0.707106 0.707107 0.000000 +-0.707106 0.707107 0.000000 +-0.836408 0.548107 0.000000 +-0.707106 0.707107 0.000000 +-0.836408 0.548107 0.000000 +-0.929041 0.369976 0.000000 +-0.836408 0.548107 0.000000 +-0.836408 0.548107 0.000000 +-0.929041 0.369976 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184666 0.000000 +-0.995819 0.091349 0.000000 +-0.995819 0.091349 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184666 0.000000 +-0.995819 0.091349 0.000000 +-0.982801 0.184666 0.000000 +0.982801 0.184667 0.000000 +0.995816 0.091379 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369974 0.000000 +0.929042 0.369974 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369974 0.000000 +0.929042 0.369974 0.000000 +0.929042 0.369974 0.000000 +0.836402 0.548117 0.000000 +0.836402 0.548117 0.000000 +0.929042 0.369974 0.000000 +0.836402 0.548117 0.000000 +0.836402 0.548117 0.000000 +0.836402 0.548117 0.000000 +0.707106 0.707108 0.000000 +0.707106 0.707108 0.000000 +0.836402 0.548117 0.000000 +0.707106 0.707108 0.000000 +0.707106 0.707108 0.000000 +0.707106 0.707108 0.000000 +0.548110 0.836406 0.000000 +0.548110 0.836406 0.000000 +0.707106 0.707108 0.000000 +0.548110 0.836406 0.000000 +0.548110 0.836406 0.000000 +0.548110 0.836406 0.000000 +0.369975 0.929042 0.000000 +0.369975 0.929042 0.000000 +0.548110 0.836406 0.000000 +0.369975 0.929042 0.000000 +0.184666 0.982801 0.000000 +0.369975 0.929042 0.000000 +0.369975 0.929042 0.000000 +0.184666 0.982801 0.000000 +0.369975 0.929042 0.000000 +0.184666 0.982801 0.000000 +0.000001 1.000000 0.000000 +0.184666 0.982801 0.000000 +0.184666 0.982801 0.000000 +0.000001 1.000000 0.000000 +0.184666 0.982801 0.000000 +0.000001 1.000000 0.000000 +-0.184665 0.982802 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +-0.184665 0.982802 0.000000 +0.000001 1.000000 0.000000 +-0.184665 0.982802 0.000000 +-0.369975 0.929042 0.000000 +-0.184665 0.982802 0.000000 +-0.184665 0.982802 0.000000 +-0.369975 0.929042 0.000000 +-0.184665 0.982802 0.000000 +-0.369975 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.369975 0.929042 0.000000 +-0.369975 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.369975 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.707106 0.707108 0.000000 +-0.548110 0.836406 0.000000 +-0.548110 0.836406 0.000000 +-0.707106 0.707108 0.000000 +-0.548110 0.836406 0.000000 +-0.707106 0.707108 0.000000 +-0.836408 0.548107 0.000000 +-0.707106 0.707108 0.000000 +-0.707106 0.707108 0.000000 +-0.836408 0.548107 0.000000 +-0.707106 0.707108 0.000000 +-0.836408 0.548107 0.000000 +-0.836408 0.548107 0.000000 +-0.836408 0.548107 0.000000 +-0.929041 0.369976 0.000000 +-0.929041 0.369976 0.000000 +-0.836408 0.548107 0.000000 +-0.929041 0.369976 0.000000 +-0.982801 0.184666 0.000000 +-0.929041 0.369976 0.000000 +-0.929041 0.369976 0.000000 +-0.929041 0.369976 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184666 0.000000 +-0.995819 0.091349 0.000000 +-0.995819 0.091349 0.000000 +-0.982801 0.184666 0.000000 +-0.995819 0.091349 0.000000 +-0.982801 0.184666 0.000000 +0.982801 0.184667 0.000000 +0.995816 0.091379 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369975 0.000000 +0.929042 0.369975 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369975 0.000000 +0.836402 0.548117 0.000000 +0.929042 0.369975 0.000000 +0.929042 0.369975 0.000000 +0.836402 0.548117 0.000000 +0.929042 0.369975 0.000000 +0.836402 0.548117 0.000000 +0.707106 0.707107 0.000000 +0.836402 0.548117 0.000000 +0.836402 0.548117 0.000000 +0.707106 0.707107 0.000000 +0.836402 0.548117 0.000000 +0.707106 0.707107 0.000000 +0.548110 0.836406 0.000000 +0.707106 0.707107 0.000000 +0.707106 0.707107 0.000000 +0.548110 0.836406 0.000000 +0.707106 0.707107 0.000000 +0.548110 0.836406 0.000000 +0.369973 0.929042 0.000000 +0.548110 0.836406 0.000000 +0.548110 0.836406 0.000000 +0.369973 0.929042 0.000000 +0.548110 0.836406 0.000000 +0.369973 0.929042 0.000000 +0.369973 0.929042 0.000000 +0.369973 0.929042 0.000000 +0.184666 0.982801 0.000000 +0.184666 0.982801 0.000000 +0.369973 0.929042 0.000000 +0.184666 0.982801 0.000000 +0.000001 1.000000 0.000000 +0.184666 0.982801 0.000000 +0.184666 0.982801 0.000000 +0.000001 1.000000 0.000000 +0.184666 0.982801 0.000000 +0.000001 1.000000 0.000000 +-0.184665 0.982801 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +-0.184665 0.982801 0.000000 +0.000001 1.000000 0.000000 +-0.184665 0.982801 0.000000 +-0.184665 0.982801 0.000000 +-0.184665 0.982801 0.000000 +-0.369973 0.929042 0.000000 +-0.369973 0.929042 0.000000 +-0.184665 0.982801 0.000000 +-0.369973 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.369973 0.929042 0.000000 +-0.369973 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.369973 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.707106 0.707107 0.000000 +-0.548110 0.836406 0.000000 +-0.548110 0.836406 0.000000 +-0.707106 0.707107 0.000000 +-0.548110 0.836406 0.000000 +-0.707106 0.707107 0.000000 +-0.836408 0.548107 0.000000 +-0.707106 0.707107 0.000000 +-0.707106 0.707107 0.000000 +-0.836408 0.548107 0.000000 +-0.707106 0.707107 0.000000 +-0.836408 0.548107 0.000000 +-0.836408 0.548107 0.000000 +-0.836408 0.548107 0.000000 +-0.929041 0.369976 0.000000 +-0.929041 0.369976 0.000000 +-0.836408 0.548107 0.000000 +-0.929041 0.369976 0.000000 +-0.982801 0.184666 0.000000 +-0.929041 0.369976 0.000000 +-0.929041 0.369976 0.000000 +-0.929041 0.369976 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184666 0.000000 +-0.995819 0.091349 0.000000 +-0.995819 0.091349 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184666 0.000000 +-0.995819 0.091349 0.000000 +-0.982801 0.184666 0.000000 +0.982801 0.184667 0.000000 +0.995816 0.091379 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369974 0.000000 +0.929042 0.369974 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369974 0.000000 +0.836402 0.548117 0.000000 +0.929042 0.369974 0.000000 +0.929042 0.369974 0.000000 +0.836402 0.548117 0.000000 +0.929042 0.369974 0.000000 +0.836402 0.548117 0.000000 +0.836402 0.548117 0.000000 +0.836402 0.548117 0.000000 +0.707106 0.707108 0.000000 +0.707106 0.707108 0.000000 +0.836402 0.548117 0.000000 +0.707106 0.707108 0.000000 +0.548110 0.836406 0.000000 +0.707106 0.707108 0.000000 +0.707106 0.707108 0.000000 +0.548110 0.836406 0.000000 +0.707106 0.707108 0.000000 +0.548110 0.836406 0.000000 +0.369975 0.929042 0.000000 +0.548110 0.836406 0.000000 +0.548110 0.836406 0.000000 +0.369975 0.929042 0.000000 +0.548110 0.836406 0.000000 +0.369975 0.929042 0.000000 +0.369975 0.929042 0.000000 +0.369975 0.929042 0.000000 +0.184666 0.982801 0.000000 +0.184666 0.982801 0.000000 +0.369975 0.929042 0.000000 +0.184666 0.982801 0.000000 +0.000001 1.000000 0.000000 +0.184666 0.982801 0.000000 +0.184666 0.982801 0.000000 +0.000001 1.000000 0.000000 +0.184666 0.982801 0.000000 +0.000001 1.000000 0.000000 +-0.184665 0.982802 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +-0.184665 0.982802 0.000000 +0.000001 1.000000 0.000000 +-0.184665 0.982802 0.000000 +-0.369975 0.929042 0.000000 +-0.184665 0.982802 0.000000 +-0.184665 0.982802 0.000000 +-0.369975 0.929042 0.000000 +-0.184665 0.982802 0.000000 +-0.369975 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.369975 0.929042 0.000000 +-0.369975 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.369975 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.707106 0.707108 0.000000 +-0.548110 0.836406 0.000000 +-0.548110 0.836406 0.000000 +-0.707106 0.707108 0.000000 +-0.548110 0.836406 0.000000 +-0.707106 0.707108 0.000000 +-0.707106 0.707108 0.000000 +-0.707106 0.707108 0.000000 +-0.836408 0.548107 0.000000 +-0.836408 0.548107 0.000000 +-0.707106 0.707108 0.000000 +-0.836408 0.548107 0.000000 +-0.929041 0.369976 0.000000 +-0.836408 0.548107 0.000000 +-0.836408 0.548107 0.000000 +-0.929041 0.369976 0.000000 +-0.836408 0.548107 0.000000 +-0.929041 0.369976 0.000000 +-0.982801 0.184666 0.000000 +-0.929041 0.369976 0.000000 +-0.929041 0.369976 0.000000 +0.548110 0.836406 0.000000 +0.707106 0.707107 0.000000 +0.707106 0.707107 0.000000 +0.995816 0.091379 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369975 0.000000 +0.929042 0.369975 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369975 0.000000 +0.836402 0.548117 0.000000 +0.929042 0.369975 0.000000 +0.929042 0.369975 0.000000 +0.836402 0.548117 0.000000 +0.929042 0.369975 0.000000 +0.836402 0.548117 0.000000 +0.707106 0.707107 0.000000 +0.836402 0.548117 0.000000 +0.836402 0.548117 0.000000 +0.707106 0.707107 0.000000 +0.836402 0.548117 0.000000 +0.707106 0.707107 0.000000 +-0.982801 0.184666 0.000000 +-0.995819 0.091349 0.000000 +-0.995819 0.091349 0.000000 +-0.982801 0.184666 0.000000 +-0.995819 0.091349 0.000000 +-0.982801 0.184666 0.000000 +-0.929041 0.369976 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184666 0.000000 +-0.929041 0.369976 0.000000 +-0.982801 0.184666 0.000000 +-0.929041 0.369976 0.000000 +-0.836408 0.548107 0.000000 +-0.929041 0.369976 0.000000 +-0.929041 0.369976 0.000000 +-0.836408 0.548107 0.000000 +-0.929041 0.369976 0.000000 +-0.836408 0.548107 0.000000 +-0.707106 0.707107 0.000000 +-0.836408 0.548107 0.000000 +-0.836408 0.548107 0.000000 +-0.707106 0.707107 0.000000 +-0.836408 0.548107 0.000000 +-0.707106 0.707107 0.000000 +-0.707106 0.707107 0.000000 +-0.707106 0.707107 0.000000 +-0.548110 0.836406 0.000000 +-0.548110 0.836406 0.000000 +-0.707106 0.707107 0.000000 +-0.548110 0.836406 0.000000 +-0.369973 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.548110 0.836406 0.000000 +-0.369973 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.369973 0.929042 0.000000 +-0.184665 0.982801 0.000000 +-0.369973 0.929042 0.000000 +-0.369973 0.929042 0.000000 +-0.184665 0.982801 0.000000 +-0.369973 0.929042 0.000000 +-0.184665 0.982802 0.000000 +0.000001 1.000000 0.000000 +-0.184665 0.982801 0.000000 +-0.184665 0.982802 0.000000 +0.000001 1.000000 0.000000 +-0.184665 0.982802 0.000000 +0.000001 1.000000 0.000000 +0.184666 0.982801 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.184666 0.982801 0.000000 +0.000001 1.000000 0.000000 +0.184666 0.982801 0.000000 +0.369973 0.929042 0.000000 +0.184666 0.982801 0.000000 +0.184666 0.982801 0.000000 +0.369973 0.929042 0.000000 +0.184666 0.982801 0.000000 +0.369973 0.929042 0.000000 +0.548110 0.836406 0.000000 +0.369973 0.929042 0.000000 +0.369973 0.929042 0.000000 +0.548110 0.836406 0.000000 +0.369973 0.929042 0.000000 +0.548110 0.836406 0.000000 +0.707106 0.707107 0.000000 +0.548110 0.836406 0.000000 +0.548110 0.836406 0.000000 +-0.929041 0.369976 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184666 0.000000 +-0.995819 0.091349 0.000000 +-0.995819 0.091349 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184666 0.000000 +-0.995819 0.091349 0.000000 +-0.982801 0.184666 0.000000 +0.982801 0.184667 0.000000 +0.995816 0.091379 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369974 0.000000 +0.929042 0.369974 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369974 0.000000 +0.929042 0.369974 0.000000 +0.929042 0.369974 0.000000 +0.836402 0.548117 0.000000 +0.836402 0.548117 0.000000 +0.929042 0.369974 0.000000 +0.836402 0.548117 0.000000 +0.836402 0.548117 0.000000 +0.836402 0.548117 0.000000 +0.707106 0.707108 0.000000 +0.707106 0.707108 0.000000 +0.836402 0.548117 0.000000 +0.707106 0.707108 0.000000 +0.707106 0.707108 0.000000 +0.707106 0.707108 0.000000 +0.548110 0.836406 0.000000 +0.548110 0.836406 0.000000 +0.707106 0.707108 0.000000 +0.548110 0.836406 0.000000 +0.548110 0.836406 0.000000 +0.548110 0.836406 0.000000 +0.369975 0.929042 0.000000 +0.369975 0.929042 0.000000 +0.548110 0.836406 0.000000 +0.369975 0.929042 0.000000 +0.184666 0.982801 0.000000 +0.369975 0.929042 0.000000 +0.369975 0.929042 0.000000 +0.184666 0.982801 0.000000 +0.369975 0.929042 0.000000 +0.184666 0.982801 0.000000 +0.000001 1.000000 0.000000 +0.184666 0.982801 0.000000 +0.184666 0.982801 0.000000 +0.000001 1.000000 0.000000 +0.184666 0.982801 0.000000 +0.000001 1.000000 0.000000 +-0.184665 0.982802 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +-0.184665 0.982802 0.000000 +0.000001 1.000000 0.000000 +-0.184665 0.982802 0.000000 +-0.184665 0.982802 0.000000 +-0.184665 0.982802 0.000000 +-0.369975 0.929042 0.000000 +-0.369975 0.929042 0.000000 +-0.184665 0.982802 0.000000 +-0.369975 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.369975 0.929042 0.000000 +-0.369975 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.369975 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.707106 0.707108 0.000000 +-0.548110 0.836406 0.000000 +-0.548110 0.836406 0.000000 +-0.707106 0.707108 0.000000 +-0.548110 0.836406 0.000000 +-0.707106 0.707108 0.000000 +-0.836408 0.548107 0.000000 +-0.707106 0.707108 0.000000 +-0.707106 0.707108 0.000000 +-0.836408 0.548107 0.000000 +-0.707106 0.707108 0.000000 +-0.836408 0.548107 0.000000 +-0.836408 0.548107 0.000000 +-0.836408 0.548107 0.000000 +-0.929041 0.369976 0.000000 +-0.929041 0.369976 0.000000 +-0.836408 0.548107 0.000000 +-0.929041 0.369976 0.000000 +-0.982801 0.184666 0.000000 +-0.929041 0.369976 0.000000 +-0.929041 0.369976 0.000000 +0.929042 0.369975 0.000000 +0.929042 0.369975 0.000000 +0.836402 0.548117 0.000000 +0.995816 0.091379 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369975 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369975 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369975 0.000000 +-0.995819 0.091349 0.000000 +-0.995819 0.091349 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184666 0.000000 +-0.995819 0.091349 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184666 0.000000 +-0.929041 0.369976 0.000000 +-0.929041 0.369976 0.000000 +-0.982801 0.184666 0.000000 +-0.929041 0.369976 0.000000 +-0.836408 0.548107 0.000000 +-0.929041 0.369976 0.000000 +-0.929041 0.369976 0.000000 +-0.836408 0.548107 0.000000 +-0.929041 0.369976 0.000000 +-0.836408 0.548107 0.000000 +-0.836408 0.548107 0.000000 +-0.836408 0.548107 0.000000 +-0.707106 0.707107 0.000000 +-0.707106 0.707107 0.000000 +-0.836408 0.548107 0.000000 +-0.707106 0.707107 0.000000 +-0.548110 0.836406 0.000000 +-0.707106 0.707107 0.000000 +-0.707106 0.707107 0.000000 +-0.548110 0.836406 0.000000 +-0.707106 0.707107 0.000000 +-0.548110 0.836406 0.000000 +-0.369973 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.548110 0.836406 0.000000 +-0.369973 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.369973 0.929042 0.000000 +-0.184665 0.982801 0.000000 +-0.369973 0.929042 0.000000 +-0.369973 0.929042 0.000000 +-0.184665 0.982801 0.000000 +-0.369973 0.929042 0.000000 +-0.184665 0.982802 0.000000 +0.000001 1.000000 0.000000 +-0.184665 0.982801 0.000000 +-0.184665 0.982802 0.000000 +0.000001 1.000000 0.000000 +-0.184665 0.982802 0.000000 +0.000001 1.000000 0.000000 +0.184666 0.982801 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.184666 0.982801 0.000000 +0.000001 1.000000 0.000000 +0.184666 0.982801 0.000000 +0.369973 0.929042 0.000000 +0.184666 0.982801 0.000000 +0.184666 0.982801 0.000000 +0.369973 0.929042 0.000000 +0.184666 0.982801 0.000000 +0.369973 0.929042 0.000000 +0.548110 0.836406 0.000000 +0.369973 0.929042 0.000000 +0.369973 0.929042 0.000000 +0.548110 0.836406 0.000000 +0.369973 0.929042 0.000000 +0.548110 0.836406 0.000000 +0.707106 0.707107 0.000000 +0.548110 0.836406 0.000000 +0.548110 0.836406 0.000000 +0.707106 0.707107 0.000000 +0.548110 0.836406 0.000000 +0.707106 0.707107 0.000000 +0.707106 0.707107 0.000000 +0.707106 0.707107 0.000000 +0.836402 0.548117 0.000000 +0.836402 0.548117 0.000000 +0.707106 0.707107 0.000000 +0.836402 0.548117 0.000000 +0.836402 0.548117 0.000000 +0.836402 0.548117 0.000000 +0.929042 0.369975 0.000000 +-0.929041 0.369976 0.000000 +-0.929041 0.369976 0.000000 +-0.836408 0.548107 0.000000 +-0.995819 0.091349 0.000000 +-0.995819 0.091349 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184666 0.000000 +-0.995819 0.091349 0.000000 +-0.982801 0.184666 0.000000 +-0.929041 0.369976 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184666 0.000000 +-0.929041 0.369976 0.000000 +-0.982801 0.184666 0.000000 +-0.929041 0.369976 0.000000 +0.982801 0.184667 0.000000 +0.995816 0.091379 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369974 0.000000 +0.929042 0.369974 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369974 0.000000 +0.929042 0.369974 0.000000 +0.929042 0.369974 0.000000 +0.836402 0.548117 0.000000 +0.836402 0.548117 0.000000 +0.929042 0.369974 0.000000 +0.836402 0.548117 0.000000 +0.836402 0.548117 0.000000 +0.836402 0.548117 0.000000 +0.707106 0.707108 0.000000 +0.707106 0.707108 0.000000 +0.836402 0.548117 0.000000 +0.707106 0.707108 0.000000 +0.707106 0.707108 0.000000 +0.707106 0.707108 0.000000 +0.548110 0.836406 0.000000 +0.548110 0.836406 0.000000 +0.707106 0.707108 0.000000 +0.548110 0.836406 0.000000 +0.369975 0.929042 0.000000 +0.548110 0.836406 0.000000 +0.548110 0.836406 0.000000 +0.369975 0.929042 0.000000 +0.548110 0.836406 0.000000 +0.369975 0.929042 0.000000 +0.184666 0.982801 0.000000 +0.369975 0.929042 0.000000 +0.369975 0.929042 0.000000 +0.184666 0.982801 0.000000 +0.369975 0.929042 0.000000 +0.184666 0.982801 0.000000 +0.184666 0.982801 0.000000 +0.184666 0.982801 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.184666 0.982801 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +-0.184665 0.982802 0.000000 +-0.184665 0.982802 0.000000 +0.000001 1.000000 0.000000 +-0.184665 0.982802 0.000000 +-0.184665 0.982802 0.000000 +-0.184665 0.982802 0.000000 +-0.369975 0.929042 0.000000 +-0.369975 0.929042 0.000000 +-0.184665 0.982802 0.000000 +-0.369975 0.929042 0.000000 +-0.369975 0.929042 0.000000 +-0.369975 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.548110 0.836406 0.000000 +-0.369975 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.707106 0.707108 0.000000 +-0.548110 0.836406 0.000000 +-0.548110 0.836406 0.000000 +-0.707106 0.707108 0.000000 +-0.548110 0.836406 0.000000 +-0.707106 0.707108 0.000000 +-0.836408 0.548107 0.000000 +-0.707106 0.707108 0.000000 +-0.707106 0.707108 0.000000 +-0.836408 0.548107 0.000000 +-0.707106 0.707108 0.000000 +-0.836408 0.548107 0.000000 +-0.836408 0.548107 0.000000 +-0.836408 0.548107 0.000000 +-0.929041 0.369976 0.000000 +0.000001 1.000000 0.000000 +0.184666 0.982801 0.000000 +0.184666 0.982801 0.000000 +0.995816 0.091379 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369975 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369975 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369975 0.000000 +0.929042 0.369975 0.000000 +0.929042 0.369975 0.000000 +0.836407 0.548108 0.000000 +0.836407 0.548108 0.000000 +0.929042 0.369975 0.000000 +0.836407 0.548108 0.000000 +0.707108 0.707106 0.000000 +0.836407 0.548108 0.000000 +0.836407 0.548108 0.000000 +0.707108 0.707106 0.000000 +0.836407 0.548108 0.000000 +0.707108 0.707106 0.000000 +0.548103 0.836411 0.000000 +0.707108 0.707106 0.000000 +0.707108 0.707106 0.000000 +0.548103 0.836411 0.000000 +0.707108 0.707106 0.000000 +0.548103 0.836411 0.000000 +0.548103 0.836411 0.000000 +0.548103 0.836411 0.000000 +0.369973 0.929042 0.000000 +0.369973 0.929042 0.000000 +0.548103 0.836411 0.000000 +0.369973 0.929042 0.000000 +0.369973 0.929042 0.000000 +0.369973 0.929042 0.000000 +0.184666 0.982801 0.000000 +0.184666 0.982801 0.000000 +0.369973 0.929042 0.000000 +0.184666 0.982801 0.000000 +-0.982801 0.184666 0.000000 +-0.995819 0.091349 0.000000 +-0.995819 0.091349 0.000000 +-0.982801 0.184666 0.000000 +-0.995819 0.091349 0.000000 +-0.982801 0.184666 0.000000 +-0.929041 0.369976 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184666 0.000000 +-0.929041 0.369976 0.000000 +-0.982801 0.184666 0.000000 +-0.929041 0.369976 0.000000 +-0.836408 0.548107 0.000000 +-0.929041 0.369976 0.000000 +-0.929041 0.369976 0.000000 +-0.836408 0.548107 0.000000 +-0.929041 0.369976 0.000000 +-0.836408 0.548107 0.000000 +-0.707106 0.707107 0.000000 +-0.836408 0.548107 0.000000 +-0.836408 0.548107 0.000000 +-0.707106 0.707107 0.000000 +-0.836408 0.548107 0.000000 +-0.707106 0.707107 0.000000 +-0.707106 0.707107 0.000000 +-0.707106 0.707107 0.000000 +-0.548110 0.836406 0.000000 +-0.548110 0.836406 0.000000 +-0.707106 0.707107 0.000000 +-0.548110 0.836406 0.000000 +-0.369973 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.548110 0.836406 0.000000 +-0.369973 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.369973 0.929042 0.000000 +-0.184665 0.982801 0.000000 +-0.369973 0.929042 0.000000 +-0.369973 0.929042 0.000000 +-0.184665 0.982801 0.000000 +-0.369973 0.929042 0.000000 +-0.184665 0.982802 0.000000 +0.000001 1.000000 0.000000 +-0.184665 0.982801 0.000000 +-0.184665 0.982802 0.000000 +0.000001 1.000000 0.000000 +-0.184665 0.982802 0.000000 +0.000001 1.000000 0.000000 +0.184666 0.982801 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +-0.836408 0.548107 0.000000 +-0.929041 0.369976 0.000000 +-0.929041 0.369976 0.000000 +-0.995819 0.091349 0.000000 +-0.995819 0.091349 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184666 0.000000 +-0.995819 0.091349 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184666 0.000000 +-0.929041 0.369976 0.000000 +-0.929041 0.369976 0.000000 +-0.982801 0.184666 0.000000 +-0.929041 0.369976 0.000000 +0.982801 0.184667 0.000000 +0.995816 0.091379 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369974 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369974 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369974 0.000000 +0.836407 0.548109 0.000000 +0.929042 0.369974 0.000000 +0.929042 0.369974 0.000000 +0.836407 0.548109 0.000000 +0.929042 0.369974 0.000000 +0.836407 0.548109 0.000000 +0.707107 0.707106 0.000000 +0.836407 0.548109 0.000000 +0.836407 0.548109 0.000000 +0.707107 0.707106 0.000000 +0.836407 0.548109 0.000000 +0.707107 0.707106 0.000000 +0.707107 0.707106 0.000000 +0.707107 0.707106 0.000000 +0.548103 0.836411 0.000000 +0.548103 0.836411 0.000000 +0.707107 0.707106 0.000000 +0.548103 0.836411 0.000000 +0.369975 0.929042 0.000000 +0.548103 0.836411 0.000000 +0.548103 0.836411 0.000000 +0.369975 0.929042 0.000000 +0.548103 0.836411 0.000000 +0.369975 0.929042 0.000000 +0.184666 0.982801 0.000000 +0.369975 0.929042 0.000000 +0.369975 0.929042 0.000000 +0.184666 0.982801 0.000000 +0.369975 0.929042 0.000000 +0.184666 0.982801 0.000000 +0.000001 1.000000 0.000000 +0.184666 0.982801 0.000000 +0.184666 0.982801 0.000000 +0.000001 1.000000 0.000000 +0.184666 0.982801 0.000000 +0.000001 1.000000 0.000000 +-0.184665 0.982802 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +-0.184665 0.982802 0.000000 +0.000001 1.000000 0.000000 +-0.184665 0.982802 0.000000 +-0.184665 0.982802 0.000000 +-0.184665 0.982802 0.000000 +-0.369975 0.929042 0.000000 +-0.369975 0.929042 0.000000 +-0.184665 0.982802 0.000000 +-0.369975 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.369975 0.929042 0.000000 +-0.369975 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.369975 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.548110 0.836406 0.000000 +-0.548110 0.836406 0.000000 +-0.707106 0.707108 0.000000 +-0.707106 0.707108 0.000000 +-0.548110 0.836406 0.000000 +-0.707106 0.707108 0.000000 +-0.836408 0.548107 0.000000 +-0.707106 0.707108 0.000000 +-0.707106 0.707108 0.000000 +-0.836408 0.548107 0.000000 +-0.707106 0.707108 0.000000 +-0.836408 0.548107 0.000000 +-0.929041 0.369976 0.000000 +-0.836408 0.548107 0.000000 +-0.836408 0.548107 0.000000 +-0.982801 0.184667 0.000000 +-0.995816 0.091379 0.000000 +-0.995816 0.091379 0.000000 +0.995816 0.091379 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369975 0.000000 +0.929042 0.369975 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369975 0.000000 +0.929042 0.369975 0.000000 +0.929042 0.369975 0.000000 +0.836407 0.548108 0.000000 +0.836407 0.548108 0.000000 +0.929042 0.369975 0.000000 +0.836407 0.548108 0.000000 +0.836407 0.548108 0.000000 +0.836407 0.548108 0.000000 +0.707108 0.707106 0.000000 +0.707108 0.707106 0.000000 +0.836407 0.548108 0.000000 +0.707108 0.707106 0.000000 +0.548103 0.836411 0.000000 +0.707108 0.707106 0.000000 +0.707108 0.707106 0.000000 +0.548103 0.836411 0.000000 +0.707108 0.707106 0.000000 +0.548103 0.836411 0.000000 +0.369977 0.929041 0.000000 +0.548103 0.836411 0.000000 +0.548103 0.836411 0.000000 +0.369977 0.929041 0.000000 +0.548103 0.836411 0.000000 +0.369977 0.929041 0.000000 +0.184667 0.982801 0.000000 +0.369977 0.929041 0.000000 +0.369977 0.929041 0.000000 +0.184667 0.982801 0.000000 +0.369977 0.929041 0.000000 +0.184667 0.982801 0.000000 +-0.000003 1.000000 0.000000 +0.184667 0.982801 0.000000 +0.184667 0.982801 0.000000 +-0.000003 1.000000 0.000000 +0.184667 0.982801 0.000000 +-0.000003 1.000000 0.000000 +-0.184670 0.982801 0.000000 +-0.000003 1.000000 0.000000 +-0.000003 1.000000 0.000000 +-0.184670 0.982801 0.000000 +-0.000003 1.000000 0.000000 +-0.184670 0.982801 0.000000 +-0.369977 0.929041 0.000000 +-0.184670 0.982801 0.000000 +-0.184670 0.982801 0.000000 +-0.369977 0.929041 0.000000 +-0.184670 0.982801 0.000000 +-0.369977 0.929041 0.000000 +-0.548103 0.836411 0.000000 +-0.369977 0.929041 0.000000 +-0.369977 0.929041 0.000000 +-0.548103 0.836411 0.000000 +-0.369977 0.929041 0.000000 +-0.548103 0.836411 0.000000 +-0.707108 0.707106 0.000000 +-0.548103 0.836411 0.000000 +-0.548103 0.836411 0.000000 +-0.707108 0.707106 0.000000 +-0.548103 0.836411 0.000000 +-0.707108 0.707106 0.000000 +-0.707108 0.707106 0.000000 +-0.707108 0.707106 0.000000 +-0.836407 0.548108 0.000000 +-0.836407 0.548108 0.000000 +-0.707108 0.707106 0.000000 +-0.836407 0.548108 0.000000 +-0.929042 0.369975 0.000000 +-0.836407 0.548108 0.000000 +-0.836407 0.548108 0.000000 +-0.929042 0.369975 0.000000 +-0.836407 0.548108 0.000000 +-0.929042 0.369975 0.000000 +-0.929042 0.369975 0.000000 +-0.929042 0.369975 0.000000 +-0.982801 0.184667 0.000000 +-0.982801 0.184667 0.000000 +-0.929042 0.369975 0.000000 +-0.982801 0.184667 0.000000 +-0.995816 0.091379 0.000000 +-0.982801 0.184667 0.000000 +-0.982801 0.184667 0.000000 +-0.995816 0.091379 0.000000 +-0.995816 0.091379 0.000000 +-0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.995816 0.091379 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369974 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369974 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369974 0.000000 +0.836407 0.548109 0.000000 +0.929042 0.369974 0.000000 +0.929042 0.369974 0.000000 +0.836407 0.548109 0.000000 +0.929042 0.369974 0.000000 +0.836407 0.548109 0.000000 +0.707107 0.707106 0.000000 +0.836407 0.548109 0.000000 +0.836407 0.548109 0.000000 +0.707107 0.707106 0.000000 +0.836407 0.548109 0.000000 +0.707107 0.707106 0.000000 +0.707107 0.707106 0.000000 +0.707107 0.707106 0.000000 +0.548103 0.836411 0.000000 +0.548103 0.836411 0.000000 +0.707107 0.707106 0.000000 +0.548103 0.836411 0.000000 +0.369978 0.929040 0.000000 +0.548103 0.836411 0.000000 +0.548103 0.836411 0.000000 +0.369978 0.929040 0.000000 +0.548103 0.836411 0.000000 +0.369978 0.929040 0.000000 +0.184667 0.982801 0.000000 +0.369978 0.929040 0.000000 +0.369978 0.929040 0.000000 +0.184667 0.982801 0.000000 +0.369978 0.929040 0.000000 +0.184667 0.982801 0.000000 +-0.000003 1.000000 0.000000 +0.184667 0.982801 0.000000 +0.184667 0.982801 0.000000 +-0.000003 1.000000 0.000000 +0.184667 0.982801 0.000000 +-0.000003 1.000000 0.000000 +-0.000003 1.000000 0.000000 +-0.000003 1.000000 0.000000 +-0.184670 0.982801 0.000000 +-0.184670 0.982801 0.000000 +-0.000003 1.000000 0.000000 +-0.184670 0.982801 0.000000 +-0.184670 0.982801 0.000000 +-0.184670 0.982801 0.000000 +-0.369978 0.929040 0.000000 +-0.369978 0.929040 0.000000 +-0.184670 0.982801 0.000000 +-0.369978 0.929040 0.000000 +-0.369978 0.929040 0.000000 +-0.369978 0.929040 0.000000 +-0.548103 0.836411 0.000000 +-0.548103 0.836411 0.000000 +-0.369978 0.929040 0.000000 +-0.548103 0.836411 0.000000 +-0.548103 0.836411 0.000000 +-0.548103 0.836411 0.000000 +-0.707107 0.707106 0.000000 +-0.707107 0.707106 0.000000 +-0.548103 0.836411 0.000000 +-0.707107 0.707106 0.000000 +-0.836407 0.548109 0.000000 +-0.707107 0.707106 0.000000 +-0.707107 0.707106 0.000000 +-0.836407 0.548109 0.000000 +-0.707107 0.707106 0.000000 +-0.836407 0.548109 0.000000 +-0.929042 0.369974 0.000000 +-0.836407 0.548109 0.000000 +-0.836407 0.548109 0.000000 +-0.929042 0.369974 0.000000 +-0.836407 0.548109 0.000000 +-0.929042 0.369974 0.000000 +-0.982801 0.184667 0.000000 +-0.929042 0.369974 0.000000 +-0.929042 0.369974 0.000000 +-0.982801 0.184667 0.000000 +-0.929042 0.369974 0.000000 +-0.982801 0.184667 0.000000 +-0.982801 0.184667 0.000000 +-0.982801 0.184667 0.000000 +-0.995816 0.091379 0.000000 +-0.982801 0.184667 0.000000 +-0.995816 0.091379 0.000000 +-0.995816 0.091379 0.000000 +0.995816 0.091379 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369975 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369975 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369975 0.000000 +0.929042 0.369975 0.000000 +0.929042 0.369975 0.000000 +0.836407 0.548108 0.000000 +0.836407 0.548108 0.000000 +0.929042 0.369975 0.000000 +0.836407 0.548108 0.000000 +0.836407 0.548108 0.000000 +0.836407 0.548108 0.000000 +0.707108 0.707106 0.000000 +0.707108 0.707106 0.000000 +0.836407 0.548108 0.000000 +0.707108 0.707106 0.000000 +0.548103 0.836411 0.000000 +0.707108 0.707106 0.000000 +0.707108 0.707106 0.000000 +0.548103 0.836411 0.000000 +0.707108 0.707106 0.000000 +0.548103 0.836411 0.000000 +0.548103 0.836411 0.000000 +0.548103 0.836411 0.000000 +0.369977 0.929041 0.000000 +0.369977 0.929041 0.000000 +0.548103 0.836411 0.000000 +0.369977 0.929041 0.000000 +0.184667 0.982801 0.000000 +0.369977 0.929041 0.000000 +0.369977 0.929041 0.000000 +0.184667 0.982801 0.000000 +0.369977 0.929041 0.000000 +0.184667 0.982801 0.000000 +-0.000003 1.000000 0.000000 +0.184667 0.982801 0.000000 +0.184667 0.982801 0.000000 +-0.000003 1.000000 0.000000 +0.184667 0.982801 0.000000 +-0.000003 1.000000 0.000000 +-0.000003 1.000000 0.000000 +-0.000003 1.000000 0.000000 +-0.184670 0.982801 0.000000 +-0.184670 0.982801 0.000000 +-0.000003 1.000000 0.000000 +-0.184670 0.982801 0.000000 +-0.369977 0.929041 0.000000 +-0.184670 0.982801 0.000000 +-0.184670 0.982801 0.000000 +-0.369977 0.929041 0.000000 +-0.184670 0.982801 0.000000 +-0.369977 0.929041 0.000000 +-0.369977 0.929041 0.000000 +-0.369977 0.929041 0.000000 +-0.548103 0.836411 0.000000 +-0.548103 0.836411 0.000000 +-0.369977 0.929041 0.000000 +-0.548103 0.836411 0.000000 +-0.707108 0.707106 0.000000 +-0.548103 0.836411 0.000000 +-0.548103 0.836411 0.000000 +-0.707108 0.707106 0.000000 +-0.548103 0.836411 0.000000 +-0.707108 0.707106 0.000000 +-0.836407 0.548108 0.000000 +-0.707108 0.707106 0.000000 +-0.707108 0.707106 0.000000 +-0.836407 0.548108 0.000000 +-0.707108 0.707106 0.000000 +-0.836407 0.548108 0.000000 +-0.929042 0.369975 0.000000 +-0.836407 0.548108 0.000000 +-0.836407 0.548108 0.000000 +-0.929042 0.369975 0.000000 +-0.836407 0.548108 0.000000 +-0.929042 0.369975 0.000000 +-0.929042 0.369975 0.000000 +-0.929042 0.369975 0.000000 +-0.982801 0.184667 0.000000 +-0.982801 0.184667 0.000000 +-0.929042 0.369975 0.000000 +-0.982801 0.184667 0.000000 +-0.995816 0.091379 0.000000 +-0.982801 0.184667 0.000000 +-0.982801 0.184667 0.000000 +-0.982801 0.184667 0.000000 +-0.995816 0.091379 0.000000 +-0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.995816 0.091379 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369974 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369974 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369974 0.000000 +0.836407 0.548109 0.000000 +0.929042 0.369974 0.000000 +0.929042 0.369974 0.000000 +0.836407 0.548109 0.000000 +0.929042 0.369974 0.000000 +0.836407 0.548109 0.000000 +0.836407 0.548109 0.000000 +0.836407 0.548109 0.000000 +0.707107 0.707106 0.000000 +0.707107 0.707106 0.000000 +0.836407 0.548109 0.000000 +0.707107 0.707106 0.000000 +0.548103 0.836411 0.000000 +0.707107 0.707106 0.000000 +0.707107 0.707106 0.000000 +0.548103 0.836411 0.000000 +0.707107 0.707106 0.000000 +0.548103 0.836411 0.000000 +0.369978 0.929040 0.000000 +0.548103 0.836411 0.000000 +0.548103 0.836411 0.000000 +0.369978 0.929040 0.000000 +0.548103 0.836411 0.000000 +0.369978 0.929040 0.000000 +0.369978 0.929040 0.000000 +0.369978 0.929040 0.000000 +0.184667 0.982801 0.000000 +0.184667 0.982801 0.000000 +0.369978 0.929040 0.000000 +0.184667 0.982801 0.000000 +0.184667 0.982801 0.000000 +0.184667 0.982801 0.000000 +-0.000003 1.000000 0.000000 +-0.000003 1.000000 0.000000 +0.184667 0.982801 0.000000 +-0.000003 1.000000 0.000000 +-0.000003 1.000000 0.000000 +-0.000003 1.000000 0.000000 +-0.184670 0.982801 0.000000 +-0.184670 0.982801 0.000000 +-0.000003 1.000000 0.000000 +-0.184670 0.982801 0.000000 +-0.184670 0.982801 0.000000 +-0.184670 0.982801 0.000000 +-0.369978 0.929040 0.000000 +-0.369978 0.929040 0.000000 +-0.184670 0.982801 0.000000 +-0.369978 0.929040 0.000000 +-0.548103 0.836411 0.000000 +-0.369978 0.929040 0.000000 +-0.369978 0.929040 0.000000 +-0.548103 0.836411 0.000000 +-0.369978 0.929040 0.000000 +-0.548103 0.836411 0.000000 +-0.548103 0.836411 0.000000 +-0.548103 0.836411 0.000000 +-0.707107 0.707106 0.000000 +-0.707107 0.707106 0.000000 +-0.548103 0.836411 0.000000 +-0.707107 0.707106 0.000000 +-0.836407 0.548109 0.000000 +-0.707107 0.707106 0.000000 +-0.707107 0.707106 0.000000 +-0.836407 0.548109 0.000000 +-0.707107 0.707106 0.000000 +-0.836407 0.548109 0.000000 +-0.929042 0.369974 0.000000 +-0.836407 0.548109 0.000000 +-0.836407 0.548109 0.000000 +-0.929042 0.369974 0.000000 +-0.836407 0.548109 0.000000 +-0.929042 0.369974 0.000000 +-0.982801 0.184667 0.000000 +-0.929042 0.369974 0.000000 +-0.929042 0.369974 0.000000 +-0.982801 0.184667 0.000000 +-0.929042 0.369974 0.000000 +-0.982801 0.184667 0.000000 +-0.995816 0.091379 0.000000 +-0.982801 0.184667 0.000000 +-0.982801 0.184667 0.000000 +-0.982801 0.184667 0.000000 +-0.995816 0.091379 0.000000 +-0.995816 0.091379 0.000000 +0.995816 0.091379 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369975 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369975 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369975 0.000000 +0.929042 0.369975 0.000000 +0.929042 0.369975 0.000000 +0.836407 0.548108 0.000000 +0.836407 0.548108 0.000000 +0.929042 0.369975 0.000000 +0.836407 0.548108 0.000000 +0.836407 0.548108 0.000000 +0.836407 0.548108 0.000000 +0.707108 0.707106 0.000000 +0.707108 0.707106 0.000000 +0.836407 0.548108 0.000000 +0.707108 0.707106 0.000000 +0.548103 0.836411 0.000000 +0.707108 0.707106 0.000000 +0.707108 0.707106 0.000000 +0.548103 0.836411 0.000000 +0.707108 0.707106 0.000000 +0.548103 0.836411 0.000000 +0.548103 0.836411 0.000000 +0.548103 0.836411 0.000000 +0.369977 0.929041 0.000000 +0.369977 0.929041 0.000000 +0.548103 0.836411 0.000000 +0.369977 0.929041 0.000000 +0.184667 0.982801 0.000000 +0.369977 0.929041 0.000000 +0.369977 0.929041 0.000000 +0.184667 0.982801 0.000000 +0.369977 0.929041 0.000000 +0.184667 0.982801 0.000000 +-0.000003 1.000000 0.000000 +0.184667 0.982801 0.000000 +0.184667 0.982801 0.000000 +-0.000003 1.000000 0.000000 +0.184667 0.982801 0.000000 +-0.000003 1.000000 0.000000 +-0.184670 0.982801 0.000000 +-0.000003 1.000000 0.000000 +-0.000003 1.000000 0.000000 +-0.184670 0.982801 0.000000 +-0.000003 1.000000 0.000000 +-0.184670 0.982801 0.000000 +-0.369977 0.929041 0.000000 +-0.184670 0.982801 0.000000 +-0.184670 0.982801 0.000000 +-0.369977 0.929041 0.000000 +-0.184670 0.982801 0.000000 +-0.369977 0.929041 0.000000 +-0.548103 0.836411 0.000000 +-0.369977 0.929041 0.000000 +-0.369977 0.929041 0.000000 +-0.548103 0.836411 0.000000 +-0.369977 0.929041 0.000000 +-0.548103 0.836411 0.000000 +-0.707108 0.707106 0.000000 +-0.548103 0.836411 0.000000 +-0.548103 0.836411 0.000000 +-0.707108 0.707106 0.000000 +-0.548103 0.836411 0.000000 +-0.707108 0.707106 0.000000 +-0.836407 0.548108 0.000000 +-0.707108 0.707106 0.000000 +-0.707108 0.707106 0.000000 +-0.836407 0.548108 0.000000 +-0.707108 0.707106 0.000000 +-0.836407 0.548108 0.000000 +-0.929042 0.369975 0.000000 +-0.836407 0.548108 0.000000 +-0.836407 0.548108 0.000000 +-0.929042 0.369975 0.000000 +-0.836407 0.548108 0.000000 +-0.929042 0.369975 0.000000 +-0.929042 0.369975 0.000000 +-0.929042 0.369975 0.000000 +-0.982801 0.184667 0.000000 +-0.982801 0.184667 0.000000 +-0.929042 0.369975 0.000000 +-0.982801 0.184667 0.000000 +-0.995816 0.091379 0.000000 +-0.982801 0.184667 0.000000 +-0.982801 0.184667 0.000000 +-0.982801 0.184667 0.000000 +-0.995816 0.091379 0.000000 +-0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.995816 0.091379 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369974 0.000000 +0.929042 0.369974 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369974 0.000000 +0.836407 0.548109 0.000000 +0.929042 0.369974 0.000000 +0.929042 0.369974 0.000000 +0.836407 0.548109 0.000000 +0.929042 0.369974 0.000000 +0.836407 0.548109 0.000000 +0.836407 0.548109 0.000000 +0.836407 0.548109 0.000000 +0.707107 0.707106 0.000000 +0.707107 0.707106 0.000000 +0.836407 0.548109 0.000000 +0.707107 0.707106 0.000000 +0.548103 0.836411 0.000000 +0.707107 0.707106 0.000000 +0.707107 0.707106 0.000000 +0.548103 0.836411 0.000000 +0.707107 0.707106 0.000000 +0.548103 0.836411 0.000000 +0.369978 0.929040 0.000000 +0.548103 0.836411 0.000000 +0.548103 0.836411 0.000000 +0.369978 0.929040 0.000000 +0.548103 0.836411 0.000000 +0.369978 0.929040 0.000000 +0.369978 0.929040 0.000000 +0.369978 0.929040 0.000000 +0.184667 0.982801 0.000000 +0.184667 0.982801 0.000000 +0.369978 0.929040 0.000000 +0.184667 0.982801 0.000000 +-0.000003 1.000000 0.000000 +0.184667 0.982801 0.000000 +0.184667 0.982801 0.000000 +-0.000003 1.000000 0.000000 +0.184667 0.982801 0.000000 +-0.000003 1.000000 0.000000 +-0.184670 0.982801 0.000000 +-0.000003 1.000000 0.000000 +-0.000003 1.000000 0.000000 +-0.184670 0.982801 0.000000 +-0.000003 1.000000 0.000000 +-0.184670 0.982800 0.000000 +-0.184670 0.982801 0.000000 +-0.184670 0.982800 0.000000 +-0.369978 0.929040 0.000000 +-0.369978 0.929040 0.000000 +-0.184670 0.982801 0.000000 +-0.369978 0.929040 0.000000 +-0.548103 0.836411 0.000000 +-0.369978 0.929040 0.000000 +-0.369978 0.929040 0.000000 +-0.548103 0.836411 0.000000 +-0.369978 0.929040 0.000000 +-0.548103 0.836411 0.000000 +-0.548103 0.836411 0.000000 +-0.548103 0.836411 0.000000 +-0.707107 0.707106 0.000000 +-0.707107 0.707106 0.000000 +-0.548103 0.836411 0.000000 +-0.707107 0.707106 0.000000 +-0.836407 0.548109 0.000000 +-0.707107 0.707106 0.000000 +-0.707107 0.707106 0.000000 +-0.836407 0.548109 0.000000 +-0.707107 0.707106 0.000000 +-0.836407 0.548109 0.000000 +-0.929042 0.369974 0.000000 +-0.836407 0.548109 0.000000 +-0.836407 0.548109 0.000000 +-0.929042 0.369974 0.000000 +-0.836407 0.548109 0.000000 +-0.929042 0.369974 0.000000 +-0.982801 0.184667 0.000000 +-0.929042 0.369974 0.000000 +-0.929042 0.369974 0.000000 +-0.982801 0.184667 0.000000 +-0.929042 0.369974 0.000000 +-0.982801 0.184667 0.000000 +-0.995816 0.091379 0.000000 +-0.982801 0.184667 0.000000 +-0.982801 0.184667 0.000000 +-0.982802 0.184665 0.000000 +-0.995817 0.091364 0.000000 +-0.995818 0.091364 0.000000 +0.982802 0.184665 0.000000 +0.995817 0.091364 0.000000 +0.995818 0.091364 0.000000 +0.982802 0.184665 0.000000 +0.995818 0.091364 0.000000 +0.982802 0.184665 0.000000 +0.982802 0.184665 0.000000 +0.982802 0.184665 0.000000 +0.929042 0.369975 0.000000 +0.929042 0.369975 0.000000 +0.982802 0.184665 0.000000 +0.929042 0.369975 0.000000 +0.929042 0.369975 0.000000 +0.929042 0.369975 0.000000 +0.836406 0.548110 0.000000 +0.836406 0.548110 0.000000 +0.929042 0.369975 0.000000 +0.836406 0.548110 0.000000 +0.707107 0.707106 0.000000 +0.836406 0.548110 0.000000 +0.836406 0.548110 0.000000 +0.707107 0.707106 0.000000 +0.836406 0.548110 0.000000 +0.707107 0.707106 0.000000 +0.548110 0.836406 0.000000 +0.707107 0.707106 0.000000 +0.707107 0.707106 0.000000 +0.548110 0.836406 0.000000 +0.707107 0.707106 0.000000 +0.548110 0.836406 0.000000 +0.369975 0.929042 0.000000 +0.548110 0.836406 0.000000 +0.548110 0.836406 0.000000 +0.369975 0.929042 0.000000 +0.548110 0.836406 0.000000 +0.369975 0.929042 0.000000 +0.184664 0.982802 0.000000 +0.369975 0.929042 0.000000 +0.369975 0.929042 0.000000 +0.184664 0.982802 0.000000 +0.369975 0.929042 0.000000 +0.184664 0.982802 0.000000 +0.000000 1.000000 0.000000 +0.184664 0.982802 0.000000 +0.184664 0.982802 0.000000 +0.000000 1.000000 0.000000 +0.184664 0.982802 0.000000 +0.000000 1.000000 0.000000 +-0.184665 0.982801 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.184665 0.982801 0.000000 +0.000000 1.000000 0.000000 +-0.184665 0.982801 0.000000 +-0.369975 0.929042 0.000000 +-0.184665 0.982801 0.000000 +-0.184665 0.982801 0.000000 +-0.369975 0.929042 0.000000 +-0.184665 0.982801 0.000000 +-0.369975 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.369975 0.929042 0.000000 +-0.369975 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.369975 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.548110 0.836406 0.000000 +-0.548110 0.836406 0.000000 +-0.707107 0.707106 0.000000 +-0.707107 0.707106 0.000000 +-0.548110 0.836406 0.000000 +-0.707107 0.707106 0.000000 +-0.836406 0.548110 0.000000 +-0.707107 0.707106 0.000000 +-0.707107 0.707106 0.000000 +-0.836406 0.548110 0.000000 +-0.707107 0.707106 0.000000 +-0.836406 0.548110 0.000000 +-0.929042 0.369975 0.000000 +-0.836406 0.548110 0.000000 +-0.836406 0.548110 0.000000 +-0.929042 0.369975 0.000000 +-0.836406 0.548110 0.000000 +-0.929042 0.369975 0.000000 +-0.982802 0.184665 0.000000 +-0.929042 0.369975 0.000000 +-0.929042 0.369975 0.000000 +-0.982802 0.184665 0.000000 +-0.929042 0.369975 0.000000 +-0.982802 0.184665 0.000000 +-0.995818 0.091364 0.000000 +-0.982802 0.184665 0.000000 +-0.982802 0.184665 0.000000 +-0.982801 0.184666 0.000000 +-0.995817 0.091364 0.000000 +-0.995818 0.091364 0.000000 +0.982802 0.184663 0.000000 +0.995817 0.091364 0.000000 +0.995818 0.091364 0.000000 +0.982802 0.184663 0.000000 +0.995818 0.091364 0.000000 +0.982802 0.184663 0.000000 +0.982802 0.184663 0.000000 +0.982802 0.184663 0.000000 +0.929043 0.369972 0.000000 +0.929043 0.369972 0.000000 +0.982802 0.184663 0.000000 +0.929043 0.369972 0.000000 +0.836406 0.548110 0.000000 +0.929043 0.369972 0.000000 +0.929043 0.369972 0.000000 +0.836406 0.548110 0.000000 +0.929043 0.369972 0.000000 +0.836406 0.548110 0.000000 +0.707106 0.707107 0.000000 +0.836406 0.548110 0.000000 +0.836406 0.548110 0.000000 +0.707106 0.707107 0.000000 +0.836406 0.548110 0.000000 +0.707106 0.707107 0.000000 +0.548110 0.836406 0.000000 +0.707106 0.707107 0.000000 +0.707106 0.707107 0.000000 +0.548110 0.836406 0.000000 +0.707106 0.707107 0.000000 +0.548110 0.836406 0.000000 +0.369975 0.929042 0.000000 +0.548110 0.836406 0.000000 +0.548110 0.836406 0.000000 +0.369975 0.929042 0.000000 +0.548110 0.836406 0.000000 +0.369975 0.929042 0.000000 +0.184665 0.982801 0.000000 +0.369975 0.929042 0.000000 +0.369975 0.929042 0.000000 +0.184665 0.982801 0.000000 +0.369975 0.929042 0.000000 +0.184665 0.982802 0.000000 +0.000000 1.000000 0.000000 +0.184665 0.982801 0.000000 +0.184665 0.982802 0.000000 +0.000000 1.000000 0.000000 +0.184665 0.982802 0.000000 +0.000000 1.000000 0.000000 +-0.184665 0.982801 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.184665 0.982801 0.000000 +0.000000 1.000000 0.000000 +-0.184665 0.982801 0.000000 +-0.369974 0.929042 0.000000 +-0.184665 0.982801 0.000000 +-0.184665 0.982801 0.000000 +-0.369974 0.929042 0.000000 +-0.184665 0.982801 0.000000 +-0.369974 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.369974 0.929042 0.000000 +-0.369974 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.369974 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.707108 0.707106 0.000000 +-0.548110 0.836406 0.000000 +-0.548110 0.836406 0.000000 +-0.707108 0.707106 0.000000 +-0.548110 0.836406 0.000000 +-0.707108 0.707106 0.000000 +-0.836406 0.548110 0.000000 +-0.707108 0.707106 0.000000 +-0.707108 0.707106 0.000000 +-0.836406 0.548110 0.000000 +-0.707108 0.707106 0.000000 +-0.836406 0.548110 0.000000 +-0.836406 0.548110 0.000000 +-0.836406 0.548110 0.000000 +-0.929042 0.369975 0.000000 +-0.929042 0.369975 0.000000 +-0.836406 0.548110 0.000000 +-0.929042 0.369975 0.000000 +-0.929042 0.369975 0.000000 +-0.929042 0.369975 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184666 0.000000 +-0.929042 0.369975 0.000000 +-0.982801 0.184666 0.000000 +-0.995818 0.091364 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184666 0.000000 +-0.995817 0.091364 0.000000 +-0.995818 0.091364 0.000000 +0.995818 0.091364 0.000000 +0.995817 0.091364 0.000000 +0.982802 0.184663 0.000000 +0.982802 0.184663 0.000000 +0.995818 0.091364 0.000000 +0.982802 0.184663 0.000000 +0.929043 0.369972 0.000000 +0.982802 0.184663 0.000000 +0.982802 0.184663 0.000000 +0.929043 0.369972 0.000000 +0.982802 0.184663 0.000000 +0.929043 0.369972 0.000000 +0.836406 0.548110 0.000000 +0.929043 0.369972 0.000000 +0.929043 0.369972 0.000000 +0.836406 0.548110 0.000000 +0.929043 0.369972 0.000000 +0.836406 0.548110 0.000000 +0.707106 0.707107 0.000000 +0.836406 0.548110 0.000000 +0.836406 0.548110 0.000000 +0.707106 0.707107 0.000000 +0.836406 0.548110 0.000000 +0.707106 0.707107 0.000000 +0.548110 0.836406 0.000000 +0.707106 0.707107 0.000000 +0.707106 0.707107 0.000000 +0.548110 0.836406 0.000000 +0.707106 0.707107 0.000000 +0.548110 0.836406 0.000000 +0.369975 0.929042 0.000000 +0.548110 0.836406 0.000000 +0.548110 0.836406 0.000000 +0.369975 0.929042 0.000000 +0.548110 0.836406 0.000000 +0.369975 0.929042 0.000000 +0.184665 0.982801 0.000000 +0.369975 0.929042 0.000000 +0.369975 0.929042 0.000000 +0.184665 0.982801 0.000000 +0.369975 0.929042 0.000000 +0.184665 0.982802 0.000000 +0.000000 1.000000 0.000000 +0.184665 0.982801 0.000000 +0.184665 0.982802 0.000000 +0.000000 1.000000 0.000000 +0.184665 0.982802 0.000000 +0.000000 1.000000 0.000000 +-0.184665 0.982801 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-0.184665 0.982801 0.000000 +0.000000 1.000000 0.000000 +-0.184665 0.982801 0.000000 +-0.369974 0.929042 0.000000 +-0.184665 0.982801 0.000000 +-0.184665 0.982801 0.000000 +-0.369974 0.929042 0.000000 +-0.184665 0.982801 0.000000 +-0.369974 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.369974 0.929042 0.000000 +-0.369974 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.369974 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.548110 0.836406 0.000000 +-0.548110 0.836406 0.000000 +-0.707108 0.707106 0.000000 +-0.707108 0.707106 0.000000 +-0.548110 0.836406 0.000000 +-0.707108 0.707106 0.000000 +-0.836406 0.548110 0.000000 +-0.707108 0.707106 0.000000 +-0.707108 0.707106 0.000000 +-0.836406 0.548110 0.000000 +-0.707108 0.707106 0.000000 +-0.836406 0.548110 0.000000 +-0.929042 0.369975 0.000000 +-0.836406 0.548110 0.000000 +-0.836406 0.548110 0.000000 +-0.929042 0.369975 0.000000 +-0.836406 0.548110 0.000000 +-0.929042 0.369975 0.000000 +-0.982801 0.184666 0.000000 +-0.929042 0.369975 0.000000 +-0.929042 0.369975 0.000000 +-0.982801 0.184666 0.000000 +-0.929042 0.369975 0.000000 +-0.982801 0.184666 0.000000 +-0.995818 0.091364 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184666 0.000000 +0.184664 0.982802 0.000000 +0.369976 0.929041 0.000000 +0.369976 0.929041 0.000000 +0.995818 0.091364 0.000000 +0.995817 0.091364 0.000000 +0.982801 0.184666 0.000000 +0.982801 0.184666 0.000000 +0.995818 0.091364 0.000000 +0.982801 0.184666 0.000000 +0.982801 0.184666 0.000000 +0.982801 0.184666 0.000000 +0.929042 0.369975 0.000000 +0.929042 0.369975 0.000000 +0.982801 0.184666 0.000000 +0.929042 0.369975 0.000000 +0.929042 0.369975 0.000000 +0.929042 0.369975 0.000000 +0.836408 0.548108 0.000000 +0.836408 0.548108 0.000000 +0.929042 0.369975 0.000000 +0.836408 0.548108 0.000000 +0.836408 0.548108 0.000000 +0.836408 0.548108 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836408 0.548108 0.000000 +0.707107 0.707107 0.000000 +0.548109 0.836407 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.548109 0.836407 0.000000 +0.707107 0.707107 0.000000 +0.548109 0.836407 0.000000 +0.369976 0.929041 0.000000 +0.548109 0.836407 0.000000 +0.548109 0.836407 0.000000 +0.369976 0.929041 0.000000 +0.548109 0.836407 0.000000 +0.369976 0.929041 0.000000 +-0.995818 0.091364 0.000000 +-0.995817 0.091364 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184666 0.000000 +-0.995818 0.091364 0.000000 +-0.982801 0.184666 0.000000 +-0.929042 0.369975 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184666 0.000000 +-0.929042 0.369975 0.000000 +-0.982801 0.184666 0.000000 +-0.929042 0.369975 0.000000 +-0.929042 0.369975 0.000000 +-0.929042 0.369975 0.000000 +-0.836408 0.548108 0.000000 +-0.836408 0.548108 0.000000 +-0.929042 0.369975 0.000000 +-0.836408 0.548108 0.000000 +-0.707107 0.707107 0.000000 +-0.836408 0.548108 0.000000 +-0.836408 0.548108 0.000000 +-0.707107 0.707107 0.000000 +-0.836408 0.548108 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.548109 0.836407 0.000000 +-0.548109 0.836407 0.000000 +-0.707107 0.707107 0.000000 +-0.548109 0.836407 0.000000 +-0.369976 0.929041 0.000000 +-0.548109 0.836407 0.000000 +-0.548109 0.836407 0.000000 +-0.369976 0.929041 0.000000 +-0.548109 0.836407 0.000000 +-0.369976 0.929041 0.000000 +-0.184664 0.982802 0.000000 +-0.369976 0.929041 0.000000 +-0.369976 0.929041 0.000000 +-0.184664 0.982802 0.000000 +-0.369976 0.929041 0.000000 +-0.184664 0.982802 0.000000 +0.000001 1.000000 0.000000 +-0.184664 0.982802 0.000000 +-0.184664 0.982802 0.000000 +0.000001 1.000000 0.000000 +-0.184664 0.982802 0.000000 +0.000001 1.000000 0.000000 +0.184664 0.982802 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.184664 0.982802 0.000000 +0.000001 1.000000 0.000000 +0.184664 0.982802 0.000000 +0.369976 0.929041 0.000000 +0.184664 0.982802 0.000000 +0.184664 0.982802 0.000000 +-0.982801 0.184666 0.000000 +-0.995817 0.091364 0.000000 +-0.995818 0.091364 0.000000 +0.982801 0.184666 0.000000 +0.995817 0.091364 0.000000 +0.995818 0.091364 0.000000 +0.982801 0.184666 0.000000 +0.995818 0.091364 0.000000 +0.982801 0.184666 0.000000 +0.982801 0.184666 0.000000 +0.982801 0.184666 0.000000 +0.929042 0.369975 0.000000 +0.929042 0.369975 0.000000 +0.982801 0.184666 0.000000 +0.929042 0.369975 0.000000 +0.836408 0.548108 0.000000 +0.929042 0.369975 0.000000 +0.929042 0.369975 0.000000 +0.836408 0.548108 0.000000 +0.929042 0.369975 0.000000 +0.836408 0.548108 0.000000 +0.836408 0.548108 0.000000 +0.836408 0.548108 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836408 0.548108 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.548109 0.836407 0.000000 +0.548109 0.836407 0.000000 +0.707107 0.707107 0.000000 +0.548109 0.836407 0.000000 +0.369976 0.929041 0.000000 +0.548109 0.836407 0.000000 +0.548109 0.836407 0.000000 +0.369976 0.929041 0.000000 +0.548109 0.836407 0.000000 +0.369976 0.929041 0.000000 +0.184664 0.982802 0.000000 +0.369976 0.929041 0.000000 +0.369976 0.929041 0.000000 +0.184664 0.982802 0.000000 +0.369976 0.929041 0.000000 +0.184664 0.982802 0.000000 +0.184664 0.982802 0.000000 +0.184664 0.982802 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.184664 0.982802 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +-0.184664 0.982802 0.000000 +-0.184664 0.982802 0.000000 +0.000001 1.000000 0.000000 +-0.184664 0.982802 0.000000 +-0.369976 0.929041 0.000000 +-0.184664 0.982802 0.000000 +-0.184664 0.982802 0.000000 +-0.369976 0.929041 0.000000 +-0.184664 0.982802 0.000000 +-0.369976 0.929041 0.000000 +-0.369976 0.929041 0.000000 +-0.369976 0.929041 0.000000 +-0.548109 0.836407 0.000000 +-0.548109 0.836407 0.000000 +-0.369976 0.929041 0.000000 +-0.548109 0.836407 0.000000 +-0.548109 0.836407 0.000000 +-0.548109 0.836407 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.548109 0.836407 0.000000 +-0.707107 0.707107 0.000000 +-0.836408 0.548108 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836408 0.548108 0.000000 +-0.707107 0.707107 0.000000 +-0.836408 0.548108 0.000000 +-0.929042 0.369975 0.000000 +-0.836408 0.548108 0.000000 +-0.836408 0.548108 0.000000 +-0.929042 0.369975 0.000000 +-0.836408 0.548108 0.000000 +-0.929042 0.369975 0.000000 +-0.982801 0.184666 0.000000 +-0.929042 0.369975 0.000000 +-0.929042 0.369975 0.000000 +-0.982801 0.184666 0.000000 +-0.929042 0.369975 0.000000 +-0.982801 0.184666 0.000000 +-0.995818 0.091364 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184666 0.000000 +-0.995817 0.091364 0.000000 +-0.995818 0.091364 0.000000 +0.995818 0.091364 0.000000 +0.995817 0.091364 0.000000 +0.982801 0.184666 0.000000 +0.982801 0.184666 0.000000 +0.995818 0.091364 0.000000 +0.982801 0.184666 0.000000 +0.982801 0.184666 0.000000 +0.982801 0.184666 0.000000 +0.929042 0.369975 0.000000 +0.929042 0.369975 0.000000 +0.982801 0.184666 0.000000 +0.929042 0.369975 0.000000 +0.929042 0.369975 0.000000 +0.929042 0.369975 0.000000 +0.836408 0.548108 0.000000 +0.836408 0.548108 0.000000 +0.929042 0.369975 0.000000 +0.836408 0.548108 0.000000 +0.707107 0.707107 0.000000 +0.836408 0.548108 0.000000 +0.836408 0.548108 0.000000 +0.707107 0.707107 0.000000 +0.836408 0.548108 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.548109 0.836407 0.000000 +0.548109 0.836407 0.000000 +0.707107 0.707107 0.000000 +0.548109 0.836407 0.000000 +0.548109 0.836407 0.000000 +0.548109 0.836407 0.000000 +0.369976 0.929041 0.000000 +0.369976 0.929041 0.000000 +0.548109 0.836407 0.000000 +0.369976 0.929041 0.000000 +0.369976 0.929041 0.000000 +0.369976 0.929041 0.000000 +0.184664 0.982802 0.000000 +0.184664 0.982802 0.000000 +0.369976 0.929041 0.000000 +0.184664 0.982802 0.000000 +0.000001 1.000000 0.000000 +0.184664 0.982802 0.000000 +0.184664 0.982802 0.000000 +0.000001 1.000000 0.000000 +0.184664 0.982802 0.000000 +0.000001 1.000000 0.000000 +-0.184664 0.982802 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +-0.184664 0.982802 0.000000 +0.000001 1.000000 0.000000 +-0.184664 0.982802 0.000000 +-0.184664 0.982802 0.000000 +-0.184664 0.982802 0.000000 +-0.369976 0.929041 0.000000 +-0.369976 0.929041 0.000000 +-0.184664 0.982802 0.000000 +-0.369976 0.929041 0.000000 +-0.548109 0.836407 0.000000 +-0.369976 0.929041 0.000000 +-0.369976 0.929041 0.000000 +-0.548109 0.836407 0.000000 +-0.369976 0.929041 0.000000 +-0.548109 0.836407 0.000000 +-0.707107 0.707107 0.000000 +-0.548109 0.836407 0.000000 +-0.548109 0.836407 0.000000 +-0.707107 0.707107 0.000000 +-0.548109 0.836407 0.000000 +-0.707107 0.707107 0.000000 +-0.836408 0.548108 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836408 0.548108 0.000000 +-0.707107 0.707107 0.000000 +-0.836408 0.548108 0.000000 +-0.836408 0.548108 0.000000 +-0.836408 0.548108 0.000000 +-0.929042 0.369975 0.000000 +-0.929042 0.369975 0.000000 +-0.836408 0.548108 0.000000 +-0.929042 0.369975 0.000000 +-0.982801 0.184666 0.000000 +-0.929042 0.369975 0.000000 +-0.929042 0.369975 0.000000 +-0.982801 0.184666 0.000000 +-0.929042 0.369975 0.000000 +-0.982801 0.184666 0.000000 +-0.995818 0.091364 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184666 0.000000 +-0.995817 0.091364 0.000000 +-0.995818 0.091364 0.000000 +0.995818 0.091364 0.000000 +0.995817 0.091364 0.000000 +0.982801 0.184666 0.000000 +0.982801 0.184666 0.000000 +0.995818 0.091364 0.000000 +0.982801 0.184666 0.000000 +0.982801 0.184666 0.000000 +0.982801 0.184666 0.000000 +0.929042 0.369975 0.000000 +0.929042 0.369975 0.000000 +0.982801 0.184666 0.000000 +0.929042 0.369975 0.000000 +0.836408 0.548108 0.000000 +0.929042 0.369975 0.000000 +0.929042 0.369975 0.000000 +0.836408 0.548108 0.000000 +0.929042 0.369975 0.000000 +0.836408 0.548108 0.000000 +0.836408 0.548108 0.000000 +0.836408 0.548108 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.836408 0.548108 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.707107 0.707107 0.000000 +0.548109 0.836407 0.000000 +0.548109 0.836407 0.000000 +0.707107 0.707107 0.000000 +0.548109 0.836407 0.000000 +0.369976 0.929041 0.000000 +0.548109 0.836407 0.000000 +0.548109 0.836407 0.000000 +0.369976 0.929041 0.000000 +0.548109 0.836407 0.000000 +0.369976 0.929041 0.000000 +0.184664 0.982802 0.000000 +0.369976 0.929041 0.000000 +0.369976 0.929041 0.000000 +0.184664 0.982802 0.000000 +0.369976 0.929041 0.000000 +0.184664 0.982802 0.000000 +0.000001 1.000000 0.000000 +0.184664 0.982802 0.000000 +0.184664 0.982802 0.000000 +0.000001 1.000000 0.000000 +0.184664 0.982802 0.000000 +0.000001 1.000000 0.000000 +-0.184664 0.982802 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +-0.184664 0.982802 0.000000 +0.000001 1.000000 0.000000 +-0.184664 0.982802 0.000000 +-0.369976 0.929041 0.000000 +-0.184664 0.982802 0.000000 +-0.184664 0.982802 0.000000 +-0.369976 0.929041 0.000000 +-0.184664 0.982802 0.000000 +-0.369976 0.929041 0.000000 +-0.548109 0.836407 0.000000 +-0.369976 0.929041 0.000000 +-0.369976 0.929041 0.000000 +-0.548109 0.836407 0.000000 +-0.369976 0.929041 0.000000 +-0.548109 0.836407 0.000000 +-0.707107 0.707107 0.000000 +-0.548109 0.836407 0.000000 +-0.548109 0.836407 0.000000 +-0.707107 0.707107 0.000000 +-0.548109 0.836407 0.000000 +-0.707107 0.707107 0.000000 +-0.836408 0.548108 0.000000 +-0.707107 0.707107 0.000000 +-0.707107 0.707107 0.000000 +-0.836408 0.548108 0.000000 +-0.707107 0.707107 0.000000 +-0.836408 0.548108 0.000000 +-0.929042 0.369975 0.000000 +-0.836408 0.548108 0.000000 +-0.836408 0.548108 0.000000 +-0.929042 0.369975 0.000000 +-0.836408 0.548108 0.000000 +-0.929042 0.369975 0.000000 +-0.982801 0.184666 0.000000 +-0.929042 0.369975 0.000000 +-0.929042 0.369975 0.000000 +-0.982801 0.184666 0.000000 +-0.929042 0.369975 0.000000 +-0.982801 0.184666 0.000000 +-0.995818 0.091364 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184666 0.000000 +-0.995819 0.091350 0.000000 +-0.995819 0.091350 0.000000 +0.995816 0.091379 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369974 0.000000 +0.929042 0.369974 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369974 0.000000 +0.836402 0.548117 0.000000 +0.929042 0.369974 0.000000 +0.929042 0.369974 0.000000 +0.836402 0.548117 0.000000 +0.929042 0.369974 0.000000 +0.836402 0.548117 0.000000 +0.836402 0.548117 0.000000 +0.836402 0.548117 0.000000 +0.707106 0.707108 0.000000 +0.707106 0.707108 0.000000 +0.836402 0.548117 0.000000 +0.707106 0.707108 0.000000 +0.548110 0.836406 0.000000 +0.707106 0.707108 0.000000 +0.707106 0.707108 0.000000 +0.548110 0.836406 0.000000 +0.707106 0.707108 0.000000 +0.548110 0.836406 0.000000 +0.369975 0.929042 0.000000 +0.548110 0.836406 0.000000 +0.548110 0.836406 0.000000 +0.369975 0.929042 0.000000 +0.548110 0.836406 0.000000 +0.369975 0.929042 0.000000 +0.184666 0.982801 0.000000 +0.369975 0.929042 0.000000 +0.369975 0.929042 0.000000 +0.184666 0.982801 0.000000 +0.369975 0.929042 0.000000 +0.184666 0.982801 0.000000 +0.000001 1.000000 0.000000 +0.184666 0.982801 0.000000 +0.184666 0.982801 0.000000 +0.000001 1.000000 0.000000 +0.184666 0.982801 0.000000 +0.000001 1.000000 0.000000 +-0.184665 0.982802 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +-0.184665 0.982802 0.000000 +0.000001 1.000000 0.000000 +-0.184665 0.982802 0.000000 +-0.369975 0.929042 0.000000 +-0.184665 0.982802 0.000000 +-0.184665 0.982802 0.000000 +-0.369975 0.929042 0.000000 +-0.184665 0.982802 0.000000 +-0.369975 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.369975 0.929042 0.000000 +-0.369975 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.369975 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.707106 0.707108 0.000000 +-0.548110 0.836406 0.000000 +-0.548110 0.836406 0.000000 +-0.707106 0.707108 0.000000 +-0.548110 0.836406 0.000000 +-0.707106 0.707108 0.000000 +-0.836408 0.548107 0.000000 +-0.707106 0.707108 0.000000 +-0.707106 0.707108 0.000000 +-0.836408 0.548107 0.000000 +-0.707106 0.707108 0.000000 +-0.836408 0.548107 0.000000 +-0.929041 0.369976 0.000000 +-0.836408 0.548107 0.000000 +-0.836408 0.548107 0.000000 +-0.929041 0.369976 0.000000 +-0.836408 0.548107 0.000000 +-0.929041 0.369976 0.000000 +-0.982801 0.184666 0.000000 +-0.929041 0.369976 0.000000 +-0.929041 0.369976 0.000000 +-0.982801 0.184666 0.000000 +-0.929041 0.369976 0.000000 +-0.982801 0.184666 0.000000 +-0.995819 0.091350 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184666 0.000000 +-0.995819 0.091350 0.000000 +-0.995819 0.091350 0.000000 +0.995816 0.091379 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369974 0.000000 +0.929042 0.369974 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369974 0.000000 +0.929042 0.369974 0.000000 +0.929042 0.369974 0.000000 +0.836402 0.548117 0.000000 +0.836402 0.548117 0.000000 +0.929042 0.369974 0.000000 +0.836402 0.548117 0.000000 +0.707106 0.707108 0.000000 +0.836402 0.548117 0.000000 +0.836402 0.548117 0.000000 +0.707106 0.707108 0.000000 +0.836402 0.548117 0.000000 +0.707106 0.707108 0.000000 +0.548110 0.836406 0.000000 +0.707106 0.707108 0.000000 +0.707106 0.707108 0.000000 +0.548110 0.836406 0.000000 +0.707106 0.707108 0.000000 +0.548110 0.836406 0.000000 +0.548110 0.836406 0.000000 +0.548110 0.836406 0.000000 +0.369975 0.929042 0.000000 +0.369975 0.929042 0.000000 +0.548110 0.836406 0.000000 +0.369975 0.929042 0.000000 +0.369975 0.929042 0.000000 +0.369975 0.929042 0.000000 +0.184666 0.982801 0.000000 +0.184666 0.982801 0.000000 +0.369975 0.929042 0.000000 +0.184666 0.982801 0.000000 +0.000001 1.000000 0.000000 +0.184666 0.982801 0.000000 +0.184666 0.982801 0.000000 +0.000001 1.000000 0.000000 +0.184666 0.982801 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +-0.184665 0.982802 0.000000 +-0.184665 0.982802 0.000000 +0.000001 1.000000 0.000000 +-0.184665 0.982802 0.000000 +-0.184665 0.982802 0.000000 +-0.184665 0.982802 0.000000 +-0.369975 0.929042 0.000000 +-0.369975 0.929042 0.000000 +-0.184665 0.982802 0.000000 +-0.369975 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.369975 0.929042 0.000000 +-0.369975 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.369975 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.548110 0.836406 0.000000 +-0.548110 0.836406 0.000000 +-0.707106 0.707108 0.000000 +-0.707106 0.707108 0.000000 +-0.548110 0.836406 0.000000 +-0.707106 0.707108 0.000000 +-0.836408 0.548107 0.000000 +-0.707106 0.707108 0.000000 +-0.707106 0.707108 0.000000 +-0.836408 0.548107 0.000000 +-0.707106 0.707108 0.000000 +-0.836408 0.548107 0.000000 +-0.929041 0.369976 0.000000 +-0.836408 0.548107 0.000000 +-0.836408 0.548107 0.000000 +-0.929041 0.369976 0.000000 +-0.836408 0.548107 0.000000 +-0.929041 0.369976 0.000000 +-0.982801 0.184666 0.000000 +-0.929041 0.369976 0.000000 +-0.929041 0.369976 0.000000 +-0.982801 0.184666 0.000000 +-0.929041 0.369976 0.000000 +-0.982801 0.184666 0.000000 +-0.995819 0.091350 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184666 0.000000 +-0.995819 0.091350 0.000000 +-0.995819 0.091350 0.000000 +0.982801 0.184667 0.000000 +0.995816 0.091379 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369974 0.000000 +0.929042 0.369974 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369974 0.000000 +0.836402 0.548117 0.000000 +0.929042 0.369974 0.000000 +0.929042 0.369974 0.000000 +0.836402 0.548117 0.000000 +0.929042 0.369974 0.000000 +0.836402 0.548117 0.000000 +0.707106 0.707108 0.000000 +0.836402 0.548117 0.000000 +0.836402 0.548117 0.000000 +0.707106 0.707108 0.000000 +0.836402 0.548117 0.000000 +0.707106 0.707108 0.000000 +0.548110 0.836406 0.000000 +0.707106 0.707108 0.000000 +0.707106 0.707108 0.000000 +0.548110 0.836406 0.000000 +0.707106 0.707108 0.000000 +0.548110 0.836406 0.000000 +0.369975 0.929042 0.000000 +0.548110 0.836406 0.000000 +0.548110 0.836406 0.000000 +0.369975 0.929042 0.000000 +0.548110 0.836406 0.000000 +0.369975 0.929042 0.000000 +0.184666 0.982801 0.000000 +0.369975 0.929042 0.000000 +0.369975 0.929042 0.000000 +0.184666 0.982801 0.000000 +0.369975 0.929042 0.000000 +0.184666 0.982801 0.000000 +0.000001 1.000000 0.000000 +0.184666 0.982801 0.000000 +0.184666 0.982801 0.000000 +0.000001 1.000000 0.000000 +0.184666 0.982801 0.000000 +0.000001 1.000000 0.000000 +-0.184665 0.982802 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +-0.184665 0.982802 0.000000 +0.000001 1.000000 0.000000 +-0.184665 0.982802 0.000000 +-0.184665 0.982802 0.000000 +-0.184665 0.982802 0.000000 +-0.369975 0.929042 0.000000 +-0.369975 0.929042 0.000000 +-0.184665 0.982802 0.000000 +-0.369975 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.369975 0.929042 0.000000 +-0.369975 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.369975 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.707106 0.707108 0.000000 +-0.548110 0.836406 0.000000 +-0.548110 0.836406 0.000000 +-0.707106 0.707108 0.000000 +-0.548110 0.836406 0.000000 +-0.707106 0.707108 0.000000 +-0.836408 0.548107 0.000000 +-0.707106 0.707108 0.000000 +-0.707106 0.707108 0.000000 +-0.836408 0.548107 0.000000 +-0.707106 0.707108 0.000000 +-0.836408 0.548107 0.000000 +-0.929041 0.369976 0.000000 +-0.836408 0.548107 0.000000 +-0.836408 0.548107 0.000000 +-0.929041 0.369976 0.000000 +-0.836408 0.548107 0.000000 +-0.929041 0.369976 0.000000 +-0.982801 0.184666 0.000000 +-0.929041 0.369976 0.000000 +-0.929041 0.369976 0.000000 +-0.982801 0.184666 0.000000 +-0.929041 0.369976 0.000000 +-0.982801 0.184666 0.000000 +-0.995819 0.091350 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184666 0.000000 +-0.995819 0.091350 0.000000 +-0.995819 0.091350 0.000000 +0.982801 0.184667 0.000000 +0.995816 0.091379 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369974 0.000000 +0.929042 0.369974 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369974 0.000000 +0.836402 0.548117 0.000000 +0.929042 0.369974 0.000000 +0.929042 0.369974 0.000000 +0.836402 0.548117 0.000000 +0.929042 0.369974 0.000000 +0.836402 0.548117 0.000000 +0.707106 0.707108 0.000000 +0.836402 0.548117 0.000000 +0.836402 0.548117 0.000000 +0.707106 0.707108 0.000000 +0.836402 0.548117 0.000000 +0.707106 0.707108 0.000000 +0.548110 0.836406 0.000000 +0.707106 0.707108 0.000000 +0.707106 0.707108 0.000000 +0.548110 0.836406 0.000000 +0.707106 0.707108 0.000000 +0.548110 0.836406 0.000000 +0.369975 0.929042 0.000000 +0.548110 0.836406 0.000000 +0.548110 0.836406 0.000000 +0.369975 0.929042 0.000000 +0.548110 0.836406 0.000000 +0.369975 0.929042 0.000000 +0.184666 0.982801 0.000000 +0.369975 0.929042 0.000000 +0.369975 0.929042 0.000000 +0.184666 0.982801 0.000000 +0.369975 0.929042 0.000000 +0.184666 0.982801 0.000000 +0.000001 1.000000 0.000000 +0.184666 0.982801 0.000000 +0.184666 0.982801 0.000000 +0.000001 1.000000 0.000000 +0.184666 0.982801 0.000000 +0.000001 1.000000 0.000000 +-0.184665 0.982802 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +-0.184665 0.982802 0.000000 +0.000001 1.000000 0.000000 +-0.184665 0.982802 0.000000 +-0.184665 0.982802 0.000000 +-0.184665 0.982802 0.000000 +-0.369975 0.929042 0.000000 +-0.369975 0.929042 0.000000 +-0.184665 0.982802 0.000000 +-0.369975 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.369975 0.929042 0.000000 +-0.369975 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.369975 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.707106 0.707108 0.000000 +-0.548110 0.836406 0.000000 +-0.548110 0.836406 0.000000 +-0.707106 0.707108 0.000000 +-0.548110 0.836406 0.000000 +-0.707106 0.707108 0.000000 +-0.836408 0.548107 0.000000 +-0.707106 0.707108 0.000000 +-0.707106 0.707108 0.000000 +-0.836408 0.548107 0.000000 +-0.707106 0.707108 0.000000 +-0.836408 0.548107 0.000000 +-0.929041 0.369976 0.000000 +-0.836408 0.548107 0.000000 +-0.836408 0.548107 0.000000 +-0.929041 0.369976 0.000000 +-0.836408 0.548107 0.000000 +-0.929041 0.369976 0.000000 +-0.982801 0.184666 0.000000 +-0.929041 0.369976 0.000000 +-0.929041 0.369976 0.000000 +-0.982801 0.184666 0.000000 +-0.929041 0.369976 0.000000 +-0.982801 0.184666 0.000000 +-0.995819 0.091350 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184666 0.000000 +0.184666 0.982801 0.000000 +0.369975 0.929042 0.000000 +0.369975 0.929042 0.000000 +0.995816 0.091379 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369974 0.000000 +0.929042 0.369974 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369974 0.000000 +0.929042 0.369974 0.000000 +0.929042 0.369974 0.000000 +0.836402 0.548117 0.000000 +0.836402 0.548117 0.000000 +0.929042 0.369974 0.000000 +0.836402 0.548117 0.000000 +0.707106 0.707108 0.000000 +0.836402 0.548117 0.000000 +0.836402 0.548117 0.000000 +0.707106 0.707108 0.000000 +0.836402 0.548117 0.000000 +0.707106 0.707108 0.000000 +0.707106 0.707108 0.000000 +0.707106 0.707108 0.000000 +0.548110 0.836406 0.000000 +0.548110 0.836406 0.000000 +0.707106 0.707108 0.000000 +0.548110 0.836406 0.000000 +0.548110 0.836406 0.000000 +0.548110 0.836406 0.000000 +0.369975 0.929042 0.000000 +0.369975 0.929042 0.000000 +0.548110 0.836406 0.000000 +0.369975 0.929042 0.000000 +-0.995819 0.091350 0.000000 +-0.995819 0.091350 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184666 0.000000 +-0.995819 0.091350 0.000000 +-0.982801 0.184666 0.000000 +-0.929041 0.369976 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184666 0.000000 +-0.929041 0.369976 0.000000 +-0.982801 0.184666 0.000000 +-0.929041 0.369976 0.000000 +-0.929041 0.369976 0.000000 +-0.929041 0.369976 0.000000 +-0.836408 0.548107 0.000000 +-0.836408 0.548107 0.000000 +-0.929041 0.369976 0.000000 +-0.836408 0.548107 0.000000 +-0.707106 0.707108 0.000000 +-0.836408 0.548107 0.000000 +-0.836408 0.548107 0.000000 +-0.707106 0.707108 0.000000 +-0.836408 0.548107 0.000000 +-0.707106 0.707108 0.000000 +-0.707106 0.707108 0.000000 +-0.707106 0.707108 0.000000 +-0.548110 0.836406 0.000000 +-0.548110 0.836406 0.000000 +-0.707106 0.707108 0.000000 +-0.548110 0.836406 0.000000 +-0.369975 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.548110 0.836406 0.000000 +-0.369975 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.369975 0.929042 0.000000 +-0.184665 0.982802 0.000000 +-0.369975 0.929042 0.000000 +-0.369975 0.929042 0.000000 +-0.184665 0.982802 0.000000 +-0.369975 0.929042 0.000000 +-0.184665 0.982802 0.000000 +0.000001 1.000000 0.000000 +-0.184665 0.982802 0.000000 +-0.184665 0.982802 0.000000 +0.000001 1.000000 0.000000 +-0.184665 0.982802 0.000000 +0.000001 1.000000 0.000000 +0.184666 0.982801 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.184666 0.982801 0.000000 +0.000001 1.000000 0.000000 +0.184666 0.982801 0.000000 +0.369975 0.929042 0.000000 +0.184666 0.982801 0.000000 +0.184666 0.982801 0.000000 +-0.982801 0.184666 0.000000 +-0.995819 0.091350 0.000000 +-0.995819 0.091350 0.000000 +0.995816 0.091379 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369974 0.000000 +0.929042 0.369974 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369974 0.000000 +0.929042 0.369974 0.000000 +0.929042 0.369974 0.000000 +0.836402 0.548117 0.000000 +0.836402 0.548117 0.000000 +0.929042 0.369974 0.000000 +0.836402 0.548117 0.000000 +0.707106 0.707108 0.000000 +0.836402 0.548117 0.000000 +0.836402 0.548117 0.000000 +0.707106 0.707108 0.000000 +0.836402 0.548117 0.000000 +0.707106 0.707108 0.000000 +0.707106 0.707108 0.000000 +0.707106 0.707108 0.000000 +0.548110 0.836406 0.000000 +0.548110 0.836406 0.000000 +0.707106 0.707108 0.000000 +0.548110 0.836406 0.000000 +0.548110 0.836406 0.000000 +0.548110 0.836406 0.000000 +0.369975 0.929042 0.000000 +0.369975 0.929042 0.000000 +0.548110 0.836406 0.000000 +0.369975 0.929042 0.000000 +0.184666 0.982801 0.000000 +0.369975 0.929042 0.000000 +0.369975 0.929042 0.000000 +0.184666 0.982801 0.000000 +0.369975 0.929042 0.000000 +0.184666 0.982801 0.000000 +0.000001 1.000000 0.000000 +0.184666 0.982801 0.000000 +0.184666 0.982801 0.000000 +0.000001 1.000000 0.000000 +0.184666 0.982801 0.000000 +0.000001 1.000000 0.000000 +-0.184665 0.982802 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +-0.184665 0.982802 0.000000 +0.000001 1.000000 0.000000 +-0.184665 0.982802 0.000000 +-0.369975 0.929042 0.000000 +-0.184665 0.982802 0.000000 +-0.184665 0.982802 0.000000 +-0.369975 0.929042 0.000000 +-0.184665 0.982802 0.000000 +-0.369975 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.369975 0.929042 0.000000 +-0.369975 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.369975 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.707106 0.707108 0.000000 +-0.548110 0.836406 0.000000 +-0.548110 0.836406 0.000000 +-0.707106 0.707108 0.000000 +-0.548110 0.836406 0.000000 +-0.707106 0.707108 0.000000 +-0.707106 0.707108 0.000000 +-0.707106 0.707108 0.000000 +-0.836408 0.548107 0.000000 +-0.836408 0.548107 0.000000 +-0.707106 0.707108 0.000000 +-0.836408 0.548107 0.000000 +-0.929041 0.369976 0.000000 +-0.836408 0.548107 0.000000 +-0.836408 0.548107 0.000000 +-0.929041 0.369976 0.000000 +-0.836408 0.548107 0.000000 +-0.929041 0.369976 0.000000 +-0.982801 0.184666 0.000000 +-0.929041 0.369976 0.000000 +-0.929041 0.369976 0.000000 +-0.982801 0.184666 0.000000 +-0.929041 0.369976 0.000000 +-0.982801 0.184666 0.000000 +-0.995819 0.091350 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184666 0.000000 +-0.995819 0.091350 0.000000 +-0.995819 0.091350 0.000000 +0.995816 0.091379 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369974 0.000000 +0.929042 0.369974 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369974 0.000000 +0.929042 0.369974 0.000000 +0.929042 0.369974 0.000000 +0.836402 0.548117 0.000000 +0.836402 0.548117 0.000000 +0.929042 0.369974 0.000000 +0.836402 0.548117 0.000000 +0.836402 0.548117 0.000000 +0.836402 0.548117 0.000000 +0.707106 0.707108 0.000000 +0.707106 0.707108 0.000000 +0.836402 0.548117 0.000000 +0.707106 0.707108 0.000000 +0.548110 0.836406 0.000000 +0.707106 0.707108 0.000000 +0.707106 0.707108 0.000000 +0.548110 0.836406 0.000000 +0.707106 0.707108 0.000000 +0.548110 0.836406 0.000000 +0.369975 0.929042 0.000000 +0.548110 0.836406 0.000000 +0.548110 0.836406 0.000000 +0.369975 0.929042 0.000000 +0.548110 0.836406 0.000000 +0.369975 0.929042 0.000000 +0.369975 0.929042 0.000000 +0.369975 0.929042 0.000000 +0.184666 0.982801 0.000000 +0.184666 0.982801 0.000000 +0.369975 0.929042 0.000000 +0.184666 0.982801 0.000000 +0.184666 0.982801 0.000000 +0.184666 0.982801 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.184666 0.982801 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +-0.184665 0.982802 0.000000 +-0.184665 0.982802 0.000000 +0.000001 1.000000 0.000000 +-0.184665 0.982802 0.000000 +-0.369975 0.929042 0.000000 +-0.184665 0.982802 0.000000 +-0.184665 0.982802 0.000000 +-0.369975 0.929042 0.000000 +-0.184665 0.982802 0.000000 +-0.369975 0.929042 0.000000 +-0.369975 0.929042 0.000000 +-0.369975 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.548110 0.836406 0.000000 +-0.369975 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.548110 0.836406 0.000000 +-0.548110 0.836406 0.000000 +-0.707106 0.707108 0.000000 +-0.707106 0.707108 0.000000 +-0.548110 0.836406 0.000000 +-0.707106 0.707108 0.000000 +-0.836408 0.548107 0.000000 +-0.707106 0.707108 0.000000 +-0.707106 0.707108 0.000000 +-0.836408 0.548107 0.000000 +-0.707106 0.707108 0.000000 +-0.836408 0.548107 0.000000 +-0.929041 0.369976 0.000000 +-0.836408 0.548107 0.000000 +-0.836408 0.548107 0.000000 +-0.929041 0.369976 0.000000 +-0.836408 0.548107 0.000000 +-0.929041 0.369976 0.000000 +-0.982801 0.184666 0.000000 +-0.929041 0.369976 0.000000 +-0.929041 0.369976 0.000000 +-0.982801 0.184666 0.000000 +-0.929041 0.369976 0.000000 +-0.982801 0.184666 0.000000 +-0.995819 0.091350 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184666 0.000000 +-0.929041 0.369976 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184666 0.000000 +-0.982801 0.184666 0.000000 +-0.995819 0.091350 0.000000 +-0.995819 0.091350 0.000000 +-0.982801 0.184666 0.000000 +-0.995819 0.091350 0.000000 +-0.982801 0.184666 0.000000 +0.982801 0.184667 0.000000 +0.995816 0.091379 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369974 0.000000 +0.929042 0.369974 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369974 0.000000 +0.836402 0.548117 0.000000 +0.929042 0.369974 0.000000 +0.929042 0.369974 0.000000 +0.836402 0.548117 0.000000 +0.929042 0.369974 0.000000 +0.836402 0.548117 0.000000 +0.707106 0.707108 0.000000 +0.836402 0.548117 0.000000 +0.836402 0.548117 0.000000 +0.707106 0.707108 0.000000 +0.836402 0.548117 0.000000 +0.707106 0.707108 0.000000 +0.548110 0.836406 0.000000 +0.707106 0.707108 0.000000 +0.707106 0.707108 0.000000 +0.548110 0.836406 0.000000 +0.707106 0.707108 0.000000 +0.548110 0.836406 0.000000 +0.548110 0.836406 0.000000 +0.548110 0.836406 0.000000 +0.369975 0.929042 0.000000 +0.369975 0.929042 0.000000 +0.548110 0.836406 0.000000 +0.369975 0.929042 0.000000 +0.184666 0.982801 0.000000 +0.369975 0.929042 0.000000 +0.369975 0.929042 0.000000 +0.184666 0.982801 0.000000 +0.369975 0.929042 0.000000 +0.184666 0.982801 0.000000 +0.000001 1.000000 0.000000 +0.184666 0.982801 0.000000 +0.184666 0.982801 0.000000 +0.000001 1.000000 0.000000 +0.184666 0.982801 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +0.000001 1.000000 0.000000 +-0.184665 0.982802 0.000000 +-0.184665 0.982802 0.000000 +0.000001 1.000000 0.000000 +-0.184665 0.982802 0.000000 +-0.184665 0.982802 0.000000 +-0.184665 0.982802 0.000000 +-0.369975 0.929042 0.000000 +-0.369975 0.929042 0.000000 +-0.184665 0.982802 0.000000 +-0.369975 0.929042 0.000000 +-0.369975 0.929042 0.000000 +-0.369975 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.548110 0.836406 0.000000 +-0.369975 0.929042 0.000000 +-0.548110 0.836406 0.000000 +-0.707106 0.707108 0.000000 +-0.548110 0.836406 0.000000 +-0.548110 0.836406 0.000000 +-0.707106 0.707108 0.000000 +-0.548110 0.836406 0.000000 +-0.707106 0.707108 0.000000 +-0.836408 0.548107 0.000000 +-0.707106 0.707108 0.000000 +-0.707106 0.707108 0.000000 +-0.836408 0.548107 0.000000 +-0.707106 0.707108 0.000000 +-0.836408 0.548107 0.000000 +-0.929041 0.369976 0.000000 +-0.836408 0.548107 0.000000 +-0.836408 0.548107 0.000000 +-0.929041 0.369976 0.000000 +-0.836408 0.548107 0.000000 +-0.929041 0.369976 0.000000 +-0.982801 0.184666 0.000000 +-0.929041 0.369976 0.000000 +-0.929041 0.369976 0.000000 +-0.929042 0.369974 0.000000 +-0.982801 0.184667 0.000000 +-0.982801 0.184667 0.000000 +-0.982801 0.184667 0.000000 +-0.995816 0.091379 0.000000 +-0.995816 0.091379 0.000000 +-0.982801 0.184667 0.000000 +-0.995816 0.091379 0.000000 +-0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.995816 0.091379 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369974 0.000000 +0.929042 0.369974 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369974 0.000000 +0.836407 0.548108 0.000000 +0.929042 0.369974 0.000000 +0.929042 0.369974 0.000000 +0.836407 0.548108 0.000000 +0.929042 0.369974 0.000000 +0.836407 0.548108 0.000000 +0.836407 0.548108 0.000000 +0.836407 0.548108 0.000000 +0.707107 0.707106 0.000000 +0.707107 0.707106 0.000000 +0.836407 0.548108 0.000000 +0.707107 0.707106 0.000000 +0.548103 0.836411 0.000000 +0.707107 0.707106 0.000000 +0.707107 0.707106 0.000000 +0.548103 0.836411 0.000000 +0.707107 0.707106 0.000000 +0.548103 0.836411 0.000000 +0.369978 0.929040 0.000000 +0.548103 0.836411 0.000000 +0.548103 0.836411 0.000000 +0.369978 0.929040 0.000000 +0.548103 0.836411 0.000000 +0.369978 0.929040 0.000000 +0.184667 0.982801 0.000000 +0.369978 0.929040 0.000000 +0.369978 0.929040 0.000000 +0.184667 0.982801 0.000000 +0.369978 0.929040 0.000000 +0.184667 0.982801 0.000000 +-0.000003 1.000000 0.000000 +0.184667 0.982801 0.000000 +0.184667 0.982801 0.000000 +-0.000003 1.000000 0.000000 +0.184667 0.982801 0.000000 +-0.000003 1.000000 0.000000 +-0.000003 1.000000 0.000000 +-0.000003 1.000000 0.000000 +-0.184670 0.982801 0.000000 +-0.184670 0.982801 0.000000 +-0.000003 1.000000 0.000000 +-0.184670 0.982801 0.000000 +-0.184670 0.982801 0.000000 +-0.184670 0.982801 0.000000 +-0.369978 0.929040 0.000000 +-0.369978 0.929040 0.000000 +-0.184670 0.982801 0.000000 +-0.369978 0.929040 0.000000 +-0.369978 0.929040 0.000000 +-0.369978 0.929040 0.000000 +-0.548103 0.836411 0.000000 +-0.548103 0.836411 0.000000 +-0.369978 0.929040 0.000000 +-0.548103 0.836411 0.000000 +-0.707107 0.707106 0.000000 +-0.548103 0.836411 0.000000 +-0.548103 0.836411 0.000000 +-0.707107 0.707106 0.000000 +-0.548103 0.836411 0.000000 +-0.707107 0.707106 0.000000 +-0.836407 0.548108 0.000000 +-0.707107 0.707106 0.000000 +-0.707107 0.707106 0.000000 +-0.836407 0.548108 0.000000 +-0.707107 0.707106 0.000000 +-0.836407 0.548108 0.000000 +-0.929042 0.369974 0.000000 +-0.836407 0.548108 0.000000 +-0.836407 0.548108 0.000000 +-0.929042 0.369974 0.000000 +-0.836407 0.548108 0.000000 +-0.929042 0.369974 0.000000 +-0.982801 0.184667 0.000000 +-0.929042 0.369974 0.000000 +-0.929042 0.369974 0.000000 +-0.982801 0.184667 0.000000 +-0.995816 0.091379 0.000000 +-0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.995816 0.091379 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369974 0.000000 +0.929042 0.369974 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369974 0.000000 +0.836407 0.548108 0.000000 +0.929042 0.369974 0.000000 +0.929042 0.369974 0.000000 +0.836407 0.548108 0.000000 +0.929042 0.369974 0.000000 +0.836407 0.548108 0.000000 +0.836407 0.548108 0.000000 +0.836407 0.548108 0.000000 +0.707107 0.707106 0.000000 +0.707107 0.707106 0.000000 +0.836407 0.548108 0.000000 +0.707107 0.707106 0.000000 +0.548103 0.836411 0.000000 +0.707107 0.707106 0.000000 +0.707107 0.707106 0.000000 +0.548103 0.836411 0.000000 +0.707107 0.707106 0.000000 +0.548103 0.836411 0.000000 +0.369978 0.929040 0.000000 +0.548103 0.836411 0.000000 +0.548103 0.836411 0.000000 +0.369978 0.929040 0.000000 +0.548103 0.836411 0.000000 +0.369978 0.929040 0.000000 +0.184667 0.982801 0.000000 +0.369978 0.929040 0.000000 +0.369978 0.929040 0.000000 +0.184667 0.982801 0.000000 +0.369978 0.929040 0.000000 +0.184667 0.982801 0.000000 +0.184667 0.982801 0.000000 +0.184667 0.982801 0.000000 +-0.000003 1.000000 0.000000 +-0.000003 1.000000 0.000000 +0.184667 0.982801 0.000000 +-0.000003 1.000000 0.000000 +-0.000003 1.000000 0.000000 +-0.000003 1.000000 0.000000 +-0.184670 0.982801 0.000000 +-0.184670 0.982801 0.000000 +-0.000003 1.000000 0.000000 +-0.184670 0.982801 0.000000 +-0.184670 0.982801 0.000000 +-0.184670 0.982801 0.000000 +-0.369978 0.929040 0.000000 +-0.369978 0.929040 0.000000 +-0.184670 0.982801 0.000000 +-0.369978 0.929040 0.000000 +-0.369978 0.929040 0.000000 +-0.369978 0.929040 0.000000 +-0.548103 0.836411 0.000000 +-0.548103 0.836411 0.000000 +-0.369978 0.929040 0.000000 +-0.548103 0.836411 0.000000 +-0.548103 0.836411 0.000000 +-0.548103 0.836411 0.000000 +-0.707107 0.707106 0.000000 +-0.707107 0.707106 0.000000 +-0.548103 0.836411 0.000000 +-0.707107 0.707106 0.000000 +-0.836407 0.548108 0.000000 +-0.707107 0.707106 0.000000 +-0.707107 0.707106 0.000000 +-0.836407 0.548108 0.000000 +-0.707107 0.707106 0.000000 +-0.836407 0.548108 0.000000 +-0.929042 0.369974 0.000000 +-0.836407 0.548108 0.000000 +-0.836407 0.548108 0.000000 +-0.929042 0.369974 0.000000 +-0.836407 0.548108 0.000000 +-0.929042 0.369974 0.000000 +-0.982801 0.184667 0.000000 +-0.929042 0.369974 0.000000 +-0.929042 0.369974 0.000000 +-0.982801 0.184667 0.000000 +-0.929042 0.369974 0.000000 +-0.982801 0.184667 0.000000 +-0.995816 0.091379 0.000000 +-0.982801 0.184667 0.000000 +-0.982801 0.184667 0.000000 +-0.982801 0.184667 0.000000 +-0.995816 0.091379 0.000000 +-0.995816 0.091379 0.000000 +0.995816 0.091379 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.995816 0.091379 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369974 0.000000 +0.929042 0.369974 0.000000 +0.982801 0.184667 0.000000 +0.929042 0.369974 0.000000 +0.929042 0.369974 0.000000 +0.929042 0.369974 0.000000 +0.836407 0.548108 0.000000 +0.836407 0.548108 0.000000 +0.929042 0.369974 0.000000 +0.836407 0.548108 0.000000 +0.707107 0.707106 0.000000 +0.836407 0.548108 0.000000 +0.836407 0.548108 0.000000 +0.707107 0.707106 0.000000 +0.836407 0.548108 0.000000 +0.707107 0.707106 0.000000 +0.707107 0.707106 0.000000 +0.707107 0.707106 0.000000 +0.548103 0.836411 0.000000 +0.548103 0.836411 0.000000 +0.707107 0.707106 0.000000 +0.548103 0.836411 0.000000 +0.548103 0.836411 0.000000 +0.548103 0.836411 0.000000 +0.369978 0.929040 0.000000 +0.369978 0.929040 0.000000 +0.548103 0.836411 0.000000 +0.369978 0.929040 0.000000 +0.184667 0.982801 0.000000 +0.369978 0.929040 0.000000 +0.369978 0.929040 0.000000 +0.184667 0.982801 0.000000 +0.369978 0.929040 0.000000 +0.184667 0.982801 0.000000 +-0.000003 1.000000 0.000000 +0.184667 0.982801 0.000000 +0.184667 0.982801 0.000000 +-0.000003 1.000000 0.000000 +0.184667 0.982801 0.000000 +-0.000003 1.000000 0.000000 +-0.000003 1.000000 0.000000 +-0.000003 1.000000 0.000000 +-0.184670 0.982801 0.000000 +-0.184670 0.982800 0.000000 +-0.000003 1.000000 0.000000 +-0.184670 0.982801 0.000000 +-0.369978 0.929040 0.000000 +-0.184670 0.982800 0.000000 +-0.184670 0.982801 0.000000 +-0.369978 0.929040 0.000000 +-0.184670 0.982801 0.000000 +-0.369978 0.929040 0.000000 +-0.548103 0.836411 0.000000 +-0.369978 0.929040 0.000000 +-0.369978 0.929040 0.000000 +-0.548103 0.836411 0.000000 +-0.369978 0.929040 0.000000 +-0.548103 0.836411 0.000000 +-0.707107 0.707106 0.000000 +-0.548103 0.836411 0.000000 +-0.548103 0.836411 0.000000 +-0.707107 0.707106 0.000000 +-0.548103 0.836411 0.000000 +-0.707107 0.707106 0.000000 +-0.836407 0.548108 0.000000 +-0.707107 0.707106 0.000000 +-0.707107 0.707106 0.000000 +-0.836407 0.548108 0.000000 +-0.707107 0.707106 0.000000 +-0.836407 0.548108 0.000000 +-0.929042 0.369974 0.000000 +-0.836407 0.548108 0.000000 +-0.836407 0.548108 0.000000 +-0.929042 0.369974 0.000000 +-0.836407 0.548108 0.000000 +-0.929042 0.369974 0.000000 +-0.982801 0.184667 0.000000 +-0.929042 0.369974 0.000000 +-0.929042 0.369974 0.000000 +-0.982801 0.184667 0.000000 +-0.929042 0.369974 0.000000 +-0.982801 0.184667 0.000000 +-0.995816 0.091379 0.000000 +-0.982801 0.184667 0.000000 +-0.982801 0.184667 0.000000 + + + + + + + + + + + +0.175327 0.644281 +0.175327 0.644281 +0.189160 0.644410 +0.189160 0.644410 +0.189085 0.642168 +0.189085 0.642168 +0.188757 0.639873 +0.188757 0.639873 +0.188156 0.637661 +0.188156 0.637661 +0.187293 0.635684 +0.187293 0.635684 +0.186217 0.634074 +0.186217 0.634074 +0.184999 0.632920 +0.184999 0.632920 +0.183723 0.632249 +0.183723 0.632249 +0.182469 0.632032 +0.182469 0.632032 +0.181206 0.632226 +0.181206 0.632226 +0.179907 0.632873 +0.179907 0.632873 +0.178647 0.634004 +0.178647 0.634004 +0.177512 0.635593 +0.177512 0.635593 +0.176578 0.637554 +0.176578 0.637554 +0.175896 0.639753 +0.175896 0.639753 +0.175484 0.642042 +0.175484 0.642042 +0.214849 0.644649 +0.214849 0.644649 +0.228682 0.644778 +0.228682 0.644778 +0.228607 0.642536 +0.228279 0.640241 +0.228607 0.642536 +0.228279 0.640241 +0.227678 0.638030 +0.227678 0.638030 +0.226815 0.636052 +0.226815 0.636052 +0.225739 0.634443 +0.225739 0.634443 +0.224521 0.633289 +0.223245 0.632618 +0.224521 0.633289 +0.223245 0.632618 +0.221991 0.632400 +0.221991 0.632400 +0.220728 0.632594 +0.220728 0.632594 +0.219429 0.633241 +0.219429 0.633241 +0.218169 0.634372 +0.218169 0.634372 +0.217034 0.635961 +0.217034 0.635961 +0.216100 0.637922 +0.216100 0.637922 +0.215418 0.640121 +0.215418 0.640121 +0.215006 0.642410 +0.215006 0.642410 +0.268204 0.645146 +0.268204 0.645146 +0.254371 0.645017 +0.254371 0.645017 +0.254528 0.642778 +0.254528 0.642778 +0.254940 0.640489 +0.254940 0.640489 +0.255622 0.638290 +0.256556 0.636329 +0.255622 0.638290 +0.257691 0.634740 +0.256556 0.636329 +0.258951 0.633609 +0.257691 0.634740 +0.258951 0.633609 +0.260250 0.632962 +0.260250 0.632962 +0.261513 0.632768 +0.261513 0.632768 +0.262767 0.632986 +0.262767 0.632986 +0.264042 0.633657 +0.264042 0.633657 +0.265260 0.634811 +0.265260 0.634811 +0.266337 0.636420 +0.266337 0.636420 +0.267200 0.638398 +0.267801 0.640609 +0.267200 0.638398 +0.267801 0.640609 +0.268129 0.642905 +0.268129 0.642905 +0.293893 0.645386 +0.293893 0.645386 +0.307726 0.645514 +0.307726 0.645514 +0.307651 0.643273 +0.307651 0.643273 +0.307323 0.640977 +0.307323 0.640977 +0.306722 0.638766 +0.306722 0.638766 +0.305859 0.636789 +0.305859 0.636789 +0.304782 0.635179 +0.304782 0.635179 +0.303564 0.634025 +0.303564 0.634025 +0.302289 0.633354 +0.302289 0.633354 +0.301034 0.633137 +0.301034 0.633137 +0.299772 0.633331 +0.299772 0.633331 +0.298473 0.633978 +0.298473 0.633978 +0.297213 0.635108 +0.297213 0.635108 +0.296078 0.636698 +0.296078 0.636698 +0.295144 0.638658 +0.295144 0.638658 +0.294462 0.640858 +0.294462 0.640858 +0.294049 0.643146 +0.294049 0.643146 +0.333415 0.645754 +0.333415 0.645754 +0.347248 0.645883 +0.347248 0.645883 +0.347173 0.643641 +0.347173 0.643641 +0.346845 0.641346 +0.346845 0.641346 +0.346243 0.639134 +0.346243 0.639134 +0.345381 0.637157 +0.345381 0.637157 +0.344304 0.635547 +0.344304 0.635547 +0.343086 0.634393 +0.343086 0.634393 +0.341811 0.633722 +0.341811 0.633722 +0.340556 0.633505 +0.340556 0.633505 +0.339294 0.633699 +0.339294 0.633699 +0.337995 0.634346 +0.337995 0.634346 +0.336735 0.635477 +0.336735 0.635477 +0.335600 0.637066 +0.335600 0.637066 +0.334666 0.639026 +0.334666 0.639026 +0.333983 0.641226 +0.333983 0.641226 +0.333571 0.643514 +0.333571 0.643514 +0.372937 0.646122 +0.372937 0.646122 +0.386770 0.646251 +0.386770 0.646251 +0.386695 0.644009 +0.386695 0.644009 +0.386367 0.641714 +0.386367 0.641714 +0.385765 0.639502 +0.385765 0.639502 +0.384903 0.637525 +0.384903 0.637525 +0.383826 0.635915 +0.383826 0.635915 +0.382608 0.634761 +0.382608 0.634761 +0.381333 0.634090 +0.381333 0.634090 +0.380078 0.633873 +0.380078 0.633873 +0.378816 0.634067 +0.378816 0.634067 +0.377517 0.634714 +0.377517 0.634714 +0.376257 0.635845 +0.376257 0.635845 +0.375122 0.637434 +0.374187 0.639394 +0.375122 0.637434 +0.373505 0.641594 +0.374187 0.639394 +0.373505 0.641594 +0.373093 0.643882 +0.373093 0.643882 +0.412459 0.646490 +0.412459 0.646490 +0.426292 0.646619 +0.426292 0.646619 +0.426217 0.644377 +0.426217 0.644377 +0.425889 0.642082 +0.425889 0.642082 +0.425287 0.639870 +0.425287 0.639870 +0.424425 0.637893 +0.424425 0.637893 +0.423348 0.636284 +0.423348 0.636284 +0.422130 0.635129 +0.422130 0.635129 +0.420855 0.634458 +0.420855 0.634458 +0.419600 0.634241 +0.419600 0.634241 +0.418338 0.634435 +0.418338 0.634435 +0.417039 0.635082 +0.417039 0.635082 +0.415779 0.636213 +0.415779 0.636213 +0.414644 0.637802 +0.414644 0.637802 +0.413709 0.639763 +0.413709 0.639763 +0.413027 0.641962 +0.413027 0.641962 +0.412615 0.644251 +0.412615 0.644251 +0.451981 0.646858 +0.451981 0.646858 +0.465813 0.646987 +0.465813 0.646987 +0.465739 0.644745 +0.465739 0.644745 +0.465411 0.642450 +0.465411 0.642450 +0.464809 0.640239 +0.464809 0.640239 +0.463947 0.638261 +0.463947 0.638261 +0.462870 0.636652 +0.462870 0.636652 +0.461652 0.635498 +0.461652 0.635498 +0.460377 0.634827 +0.460377 0.634827 +0.459122 0.634609 +0.459122 0.634609 +0.457860 0.634803 +0.457860 0.634803 +0.456560 0.635450 +0.456560 0.635450 +0.455301 0.636581 +0.455301 0.636581 +0.454166 0.638170 +0.454166 0.638170 +0.453231 0.640131 +0.453231 0.640131 +0.452549 0.642330 +0.452549 0.642330 +0.452137 0.644619 +0.452137 0.644619 +0.491503 0.647226 +0.491503 0.647226 +0.505335 0.647355 +0.505335 0.647355 +0.505261 0.645114 +0.505261 0.645114 +0.504933 0.642818 +0.504933 0.642818 +0.504331 0.640607 +0.504331 0.640607 +0.503469 0.638630 +0.503469 0.638630 +0.502392 0.637020 +0.502392 0.637020 +0.501174 0.635866 +0.501174 0.635866 +0.499899 0.635195 +0.499899 0.635195 +0.498644 0.634977 +0.498644 0.634977 +0.497382 0.635171 +0.497382 0.635171 +0.496082 0.635818 +0.496082 0.635818 +0.494823 0.636949 +0.494823 0.636949 +0.493688 0.638538 +0.493688 0.638538 +0.492753 0.640499 +0.492753 0.640499 +0.492071 0.642698 +0.492071 0.642698 +0.491659 0.644987 +0.491659 0.644987 +0.531025 0.647595 +0.531025 0.647595 +0.544857 0.647723 +0.544857 0.647723 +0.544783 0.645482 +0.544783 0.645482 +0.544454 0.643186 +0.544454 0.643186 +0.543853 0.640975 +0.542991 0.638998 +0.543853 0.640975 +0.542991 0.638998 +0.541914 0.637388 +0.541914 0.637388 +0.540696 0.636234 +0.540696 0.636234 +0.539421 0.635563 +0.539421 0.635563 +0.538166 0.635346 +0.538166 0.635346 +0.536904 0.635540 +0.536904 0.635540 +0.535604 0.636186 +0.535604 0.636186 +0.534345 0.637318 +0.534345 0.637318 +0.533209 0.638907 +0.533209 0.638907 +0.532275 0.640867 +0.532275 0.640867 +0.531593 0.643067 +0.531181 0.645355 +0.531593 0.643067 +0.531181 0.645355 +0.570547 0.647963 +0.570547 0.647963 +0.584305 0.645850 +0.584379 0.648092 +0.584379 0.648092 +0.584305 0.645850 +0.583976 0.643555 +0.583375 0.641343 +0.583976 0.643555 +0.583375 0.641343 +0.582512 0.639366 +0.582512 0.639366 +0.581436 0.637756 +0.581436 0.637756 +0.580218 0.636602 +0.580218 0.636602 +0.578943 0.635931 +0.578943 0.635931 +0.577688 0.635714 +0.577688 0.635714 +0.576425 0.635908 +0.576425 0.635908 +0.575126 0.636555 +0.575126 0.636555 +0.573866 0.637686 +0.573866 0.637686 +0.572731 0.639275 +0.572731 0.639275 +0.571797 0.641235 +0.571115 0.643435 +0.571797 0.641235 +0.571115 0.643435 +0.570703 0.645723 +0.570703 0.645723 +0.610068 0.648331 +0.610068 0.648331 +0.623901 0.648460 +0.623901 0.648460 +0.623827 0.646218 +0.623827 0.646218 +0.623498 0.643923 +0.623498 0.643923 +0.622897 0.641711 +0.622897 0.641711 +0.622034 0.639734 +0.622034 0.639734 +0.620958 0.638124 +0.620958 0.638124 +0.619740 0.636970 +0.618464 0.636299 +0.619740 0.636970 +0.618464 0.636299 +0.617210 0.636082 +0.617210 0.636082 +0.615947 0.636276 +0.615947 0.636276 +0.614648 0.636923 +0.614648 0.636923 +0.613388 0.638054 +0.613388 0.638054 +0.612253 0.639643 +0.612253 0.639643 +0.611319 0.641603 +0.611319 0.641603 +0.610637 0.643803 +0.610637 0.643803 +0.610225 0.646091 +0.610225 0.646091 +0.649590 0.648699 +0.649590 0.648699 +0.663423 0.648828 +0.663423 0.648828 +0.663348 0.646586 +0.663348 0.646586 +0.663020 0.644291 +0.663020 0.644291 +0.662419 0.642079 +0.662419 0.642079 +0.661556 0.640102 +0.661556 0.640102 +0.660480 0.638493 +0.660480 0.638493 +0.659262 0.637338 +0.659262 0.637338 +0.657986 0.636667 +0.657986 0.636667 +0.656732 0.636450 +0.655470 0.636644 +0.656732 0.636450 +0.655470 0.636644 +0.654170 0.637291 +0.654170 0.637291 +0.652910 0.638422 +0.652910 0.638422 +0.651775 0.640011 +0.651775 0.640011 +0.650841 0.641972 +0.650841 0.641972 +0.650159 0.644171 +0.649747 0.646460 +0.650159 0.644171 +0.649747 0.646460 +0.689112 0.649067 +0.689112 0.649067 +0.702945 0.649196 +0.702945 0.649196 +0.702870 0.646955 +0.702870 0.646955 +0.702542 0.644659 +0.702542 0.644659 +0.701941 0.642448 +0.701941 0.642448 +0.701078 0.640470 +0.701078 0.640470 +0.700002 0.638861 +0.700002 0.638861 +0.698784 0.637707 +0.698784 0.637707 +0.697508 0.637036 +0.697508 0.637036 +0.696254 0.636818 +0.696254 0.636818 +0.694991 0.637012 +0.694991 0.637012 +0.693692 0.637659 +0.693692 0.637659 +0.692432 0.638790 +0.692432 0.638790 +0.691297 0.640379 +0.691297 0.640379 +0.690363 0.642340 +0.690363 0.642340 +0.689681 0.644539 +0.689681 0.644539 +0.689269 0.646828 +0.689269 0.646828 +0.728634 0.649435 +0.728634 0.649435 +0.742467 0.649564 +0.742467 0.649564 +0.742392 0.647323 +0.742392 0.647323 +0.742064 0.645027 +0.742064 0.645027 +0.741463 0.642816 +0.741463 0.642816 +0.740600 0.640839 +0.740600 0.640839 +0.739523 0.639229 +0.739523 0.639229 +0.738306 0.638075 +0.738306 0.638075 +0.737030 0.637404 +0.737030 0.637404 +0.735776 0.637187 +0.735776 0.637187 +0.734513 0.637380 +0.734513 0.637380 +0.733214 0.638027 +0.733214 0.638027 +0.731954 0.639158 +0.731954 0.639158 +0.730819 0.640747 +0.730819 0.640747 +0.729885 0.642708 +0.729885 0.642708 +0.729203 0.644908 +0.728791 0.647196 +0.729203 0.644908 +0.728791 0.647196 +0.768156 0.649804 +0.768156 0.649804 +0.781989 0.649933 +0.781989 0.649933 +0.781914 0.647691 +0.781914 0.647691 +0.781586 0.645396 +0.780985 0.643184 +0.781586 0.645396 +0.780985 0.643184 +0.780122 0.641207 +0.780122 0.641207 +0.779045 0.639597 +0.779045 0.639597 +0.777828 0.638443 +0.777828 0.638443 +0.776552 0.637772 +0.776552 0.637772 +0.775298 0.637555 +0.775298 0.637555 +0.774035 0.637749 +0.774035 0.637749 +0.772736 0.638395 +0.772736 0.638395 +0.771476 0.639527 +0.770341 0.641116 +0.771476 0.639527 +0.770341 0.641116 +0.769407 0.643076 +0.769407 0.643076 +0.768725 0.645276 +0.768725 0.645276 +0.768313 0.647564 +0.768313 0.647564 +0.807678 0.650172 +0.807678 0.650172 +0.821511 0.650301 +0.821511 0.650301 +0.821436 0.648059 +0.821436 0.648059 +0.821108 0.645764 +0.820506 0.643552 +0.821108 0.645764 +0.820506 0.643552 +0.819644 0.641575 +0.819644 0.641575 +0.818567 0.639965 +0.818567 0.639965 +0.817349 0.638811 +0.817349 0.638811 +0.816074 0.638140 +0.816074 0.638140 +0.814819 0.637923 +0.814819 0.637923 +0.813557 0.638117 +0.813557 0.638117 +0.812258 0.638764 +0.812258 0.638764 +0.810998 0.639895 +0.810998 0.639895 +0.809863 0.641484 +0.809863 0.641484 +0.808928 0.643444 +0.808928 0.643444 +0.808246 0.645644 +0.808246 0.645644 +0.807834 0.647932 +0.807834 0.647932 +0.847200 0.650540 +0.847200 0.650540 +0.861033 0.650669 +0.861033 0.650669 +0.860958 0.648427 +0.860958 0.648427 +0.860630 0.646132 +0.860630 0.646132 +0.860028 0.643920 +0.860028 0.643920 +0.859166 0.641943 +0.859166 0.641943 +0.858089 0.640333 +0.858089 0.640333 +0.856871 0.639179 +0.856871 0.639179 +0.855596 0.638508 +0.855596 0.638508 +0.854341 0.638291 +0.854341 0.638291 +0.853079 0.638485 +0.853079 0.638485 +0.851780 0.639132 +0.851780 0.639132 +0.850520 0.640263 +0.850520 0.640263 +0.849385 0.641852 +0.849385 0.641852 +0.848451 0.643812 +0.848451 0.643812 +0.847768 0.646012 +0.847768 0.646012 +0.847356 0.648300 +0.847356 0.648300 +0.156205 0.615472 +0.156048 0.617711 +0.169881 0.617840 +0.169881 0.617840 +0.169807 0.615598 +0.169807 0.615598 +0.169478 0.613303 +0.169478 0.613303 +0.168877 0.611091 +0.168014 0.609114 +0.168877 0.611091 +0.168014 0.609114 +0.166938 0.607505 +0.166938 0.607505 +0.165720 0.606350 +0.165720 0.606350 +0.164445 0.605680 +0.164445 0.605680 +0.163190 0.605462 +0.163190 0.605462 +0.161927 0.605656 +0.161927 0.605656 +0.160628 0.606303 +0.159368 0.607434 +0.160628 0.606303 +0.159368 0.607434 +0.158233 0.609023 +0.157299 0.610984 +0.158233 0.609023 +0.157299 0.610984 +0.156617 0.613183 +0.156617 0.613183 +0.156205 0.615472 +0.156048 0.617711 +0.168842 0.668370 +0.168917 0.670612 +0.168917 0.670612 +0.168842 0.668370 +0.155241 0.668243 +0.155084 0.670483 +0.155084 0.670483 +0.155241 0.668243 +0.155653 0.665955 +0.156335 0.663755 +0.155653 0.665955 +0.156335 0.663755 +0.157269 0.661795 +0.157269 0.661795 +0.158404 0.660206 +0.158404 0.660206 +0.159664 0.659075 +0.159664 0.659075 +0.160963 0.658428 +0.160963 0.658428 +0.162225 0.658234 +0.162225 0.658234 +0.163480 0.658451 +0.163480 0.658451 +0.164756 0.659122 +0.164756 0.659122 +0.165973 0.660276 +0.165973 0.660276 +0.167050 0.661886 +0.167913 0.663863 +0.167050 0.661886 +0.167913 0.663863 +0.168514 0.666075 +0.168514 0.666075 +0.195727 0.615840 +0.195570 0.618079 +0.209403 0.618208 +0.209403 0.618208 +0.209329 0.615966 +0.209329 0.615966 +0.209000 0.613671 +0.208399 0.611460 +0.209000 0.613671 +0.208399 0.611460 +0.207536 0.609482 +0.207536 0.609482 +0.206460 0.607873 +0.206460 0.607873 +0.205242 0.606719 +0.205242 0.606719 +0.203966 0.606048 +0.203966 0.606048 +0.202712 0.605830 +0.202712 0.605830 +0.201449 0.606024 +0.201449 0.606024 +0.200150 0.606671 +0.200150 0.606671 +0.198890 0.607802 +0.198890 0.607802 +0.197755 0.609391 +0.196821 0.611352 +0.197755 0.609391 +0.196821 0.611352 +0.196139 0.613551 +0.196139 0.613551 +0.195727 0.615840 +0.195570 0.618079 +0.208439 0.670980 +0.208439 0.670980 +0.194762 0.668611 +0.194606 0.670851 +0.194606 0.670851 +0.195175 0.666323 +0.194762 0.668611 +0.195175 0.666323 +0.195857 0.664123 +0.196791 0.662163 +0.195857 0.664123 +0.196791 0.662163 +0.197926 0.660574 +0.197926 0.660574 +0.199186 0.659443 +0.199186 0.659443 +0.200485 0.658796 +0.200485 0.658796 +0.201747 0.658602 +0.203002 0.658819 +0.201747 0.658602 +0.203002 0.658819 +0.204277 0.659490 +0.204277 0.659490 +0.205495 0.660644 +0.205495 0.660644 +0.206572 0.662254 +0.206572 0.662254 +0.207434 0.664231 +0.207434 0.664231 +0.208036 0.666443 +0.208036 0.666443 +0.208364 0.668738 +0.208364 0.668738 +0.235249 0.616208 +0.235092 0.618447 +0.248925 0.618576 +0.248925 0.618576 +0.248850 0.616335 +0.248850 0.616335 +0.248522 0.614039 +0.248522 0.614039 +0.247921 0.611828 +0.247058 0.609851 +0.247921 0.611828 +0.247058 0.609851 +0.245982 0.608241 +0.245982 0.608241 +0.244764 0.607087 +0.244764 0.607087 +0.243488 0.606416 +0.243488 0.606416 +0.242234 0.606199 +0.242234 0.606199 +0.240971 0.606392 +0.240971 0.606392 +0.239672 0.607039 +0.238412 0.608171 +0.239672 0.607039 +0.238412 0.608171 +0.237277 0.609760 +0.236343 0.611720 +0.237277 0.609760 +0.236343 0.611720 +0.235661 0.613919 +0.235661 0.613919 +0.235249 0.616208 +0.235092 0.618447 +0.247961 0.671348 +0.247961 0.671348 +0.234284 0.668980 +0.234128 0.671219 +0.234128 0.671219 +0.234696 0.666691 +0.234284 0.668980 +0.234696 0.666691 +0.235379 0.664492 +0.235379 0.664492 +0.236313 0.662531 +0.236313 0.662531 +0.237448 0.660942 +0.237448 0.660942 +0.238708 0.659811 +0.238708 0.659811 +0.240007 0.659164 +0.240007 0.659164 +0.241269 0.658970 +0.241269 0.658970 +0.242524 0.659187 +0.242524 0.659187 +0.243799 0.659858 +0.243799 0.659858 +0.245017 0.661013 +0.245017 0.661013 +0.246094 0.662622 +0.246094 0.662622 +0.246956 0.664599 +0.246956 0.664599 +0.247558 0.666811 +0.247558 0.666811 +0.247886 0.669106 +0.247886 0.669106 +0.288447 0.618944 +0.288447 0.618944 +0.274614 0.618816 +0.274614 0.618816 +0.274771 0.616576 +0.274771 0.616576 +0.275183 0.614288 +0.275183 0.614288 +0.275865 0.612088 +0.275865 0.612088 +0.276799 0.610128 +0.276799 0.610128 +0.277934 0.608539 +0.277934 0.608539 +0.279194 0.607408 +0.279194 0.607408 +0.280493 0.606761 +0.280493 0.606761 +0.281756 0.606567 +0.281756 0.606567 +0.283010 0.606784 +0.283010 0.606784 +0.284286 0.607455 +0.284286 0.607455 +0.285504 0.608609 +0.285504 0.608609 +0.286580 0.610219 +0.286580 0.610219 +0.287443 0.612196 +0.287443 0.612196 +0.288044 0.614408 +0.288372 0.616703 +0.288044 0.614408 +0.288372 0.616703 +0.287080 0.667179 +0.287408 0.669474 +0.287483 0.671716 +0.287483 0.671716 +0.273806 0.669348 +0.273650 0.671587 +0.273650 0.671587 +0.273806 0.669348 +0.274218 0.667059 +0.274218 0.667059 +0.274900 0.664860 +0.274900 0.664860 +0.275835 0.662899 +0.276970 0.661310 +0.275835 0.662899 +0.276970 0.661310 +0.278230 0.660179 +0.278230 0.660179 +0.279529 0.659532 +0.280791 0.659338 +0.279529 0.659532 +0.282046 0.659556 +0.280791 0.659338 +0.282046 0.659556 +0.283321 0.660227 +0.283321 0.660227 +0.284539 0.661381 +0.284539 0.661381 +0.285616 0.662990 +0.285616 0.662990 +0.286478 0.664968 +0.287080 0.667179 +0.286478 0.664968 +0.287408 0.669474 +0.314136 0.619184 +0.314136 0.619184 +0.327969 0.619313 +0.327969 0.619313 +0.327894 0.617071 +0.327894 0.617071 +0.327566 0.614776 +0.327566 0.614776 +0.326964 0.612564 +0.326964 0.612564 +0.326102 0.610587 +0.326102 0.610587 +0.325025 0.608977 +0.323808 0.607823 +0.325025 0.608977 +0.323808 0.607823 +0.322532 0.607152 +0.322532 0.607152 +0.321277 0.606935 +0.321277 0.606935 +0.320015 0.607129 +0.320015 0.607129 +0.318716 0.607776 +0.318716 0.607776 +0.317456 0.608907 +0.317456 0.608907 +0.316321 0.610496 +0.316321 0.610496 +0.315387 0.612456 +0.315387 0.612456 +0.314705 0.614656 +0.314705 0.614656 +0.314293 0.616944 +0.314293 0.616944 +0.325138 0.663359 +0.326930 0.669843 +0.327005 0.672084 +0.327005 0.672084 +0.326930 0.669843 +0.326602 0.667547 +0.326602 0.667547 +0.326000 0.665336 +0.325138 0.663359 +0.326000 0.665336 +0.313172 0.671955 +0.313172 0.671955 +0.313328 0.669716 +0.313328 0.669716 +0.313740 0.667427 +0.314422 0.665228 +0.313740 0.667427 +0.314422 0.665228 +0.315357 0.663267 +0.315357 0.663267 +0.316492 0.661678 +0.316492 0.661678 +0.317752 0.660547 +0.317752 0.660547 +0.319051 0.659900 +0.319051 0.659900 +0.320313 0.659706 +0.320313 0.659706 +0.321568 0.659924 +0.321568 0.659924 +0.322843 0.660595 +0.324061 0.661749 +0.322843 0.660595 +0.324061 0.661749 +0.367491 0.619681 +0.367491 0.619681 +0.353658 0.619552 +0.353658 0.619552 +0.353814 0.617312 +0.353814 0.617312 +0.354226 0.615024 +0.354226 0.615024 +0.354909 0.612824 +0.354909 0.612824 +0.355843 0.610864 +0.355843 0.610864 +0.356978 0.609275 +0.356978 0.609275 +0.358238 0.608144 +0.358238 0.608144 +0.359537 0.607497 +0.359537 0.607497 +0.360799 0.607303 +0.360799 0.607303 +0.362054 0.607520 +0.362054 0.607520 +0.363329 0.608191 +0.364547 0.609345 +0.363329 0.608191 +0.364547 0.609345 +0.365624 0.610955 +0.365624 0.610955 +0.366486 0.612932 +0.366486 0.612932 +0.367088 0.615144 +0.367416 0.617439 +0.367088 0.615144 +0.367416 0.617439 +0.352694 0.672324 +0.352694 0.672324 +0.366452 0.670211 +0.366526 0.672453 +0.366526 0.672453 +0.366452 0.670211 +0.366124 0.667915 +0.365522 0.665704 +0.366124 0.667915 +0.364660 0.663727 +0.365522 0.665704 +0.363583 0.662117 +0.364660 0.663727 +0.363583 0.662117 +0.362365 0.660963 +0.361090 0.660292 +0.362365 0.660963 +0.361090 0.660292 +0.359835 0.660075 +0.359835 0.660075 +0.358573 0.660269 +0.358573 0.660269 +0.357273 0.660916 +0.357273 0.660916 +0.356014 0.662047 +0.356014 0.662047 +0.354879 0.663636 +0.354879 0.663636 +0.353944 0.665596 +0.353944 0.665596 +0.353262 0.667796 +0.353262 0.667796 +0.352850 0.670084 +0.352850 0.670084 +0.393180 0.619920 +0.393180 0.619920 +0.407013 0.620049 +0.407013 0.620049 +0.406938 0.617807 +0.406938 0.617807 +0.406610 0.615512 +0.406008 0.613301 +0.406610 0.615512 +0.406008 0.613301 +0.405146 0.611323 +0.405146 0.611323 +0.404069 0.609714 +0.404069 0.609714 +0.402851 0.608559 +0.402851 0.608559 +0.401576 0.607889 +0.401576 0.607889 +0.400321 0.607671 +0.400321 0.607671 +0.399059 0.607865 +0.399059 0.607865 +0.397760 0.608512 +0.397760 0.608512 +0.396500 0.609643 +0.395365 0.611232 +0.396500 0.609643 +0.395365 0.611232 +0.394431 0.613193 +0.394431 0.613193 +0.393748 0.615392 +0.393748 0.615392 +0.393336 0.617681 +0.393336 0.617681 +0.405044 0.666072 +0.406048 0.672821 +0.406048 0.672821 +0.405974 0.670579 +0.405974 0.670579 +0.405646 0.668284 +0.392216 0.672692 +0.392216 0.672692 +0.392372 0.670452 +0.392372 0.670452 +0.392784 0.668164 +0.393466 0.665964 +0.392784 0.668164 +0.393466 0.665964 +0.394401 0.664004 +0.394401 0.664004 +0.395536 0.662415 +0.395536 0.662415 +0.396795 0.661284 +0.396795 0.661284 +0.398095 0.660637 +0.399357 0.660443 +0.398095 0.660637 +0.399357 0.660443 +0.400612 0.660660 +0.400612 0.660660 +0.401887 0.661331 +0.401887 0.661331 +0.403105 0.662485 +0.403105 0.662485 +0.404182 0.664095 +0.404182 0.664095 +0.405044 0.666072 +0.405646 0.668284 +0.446535 0.620417 +0.446535 0.620417 +0.432702 0.620288 +0.432702 0.620288 +0.432858 0.618049 +0.432858 0.618049 +0.433270 0.615760 +0.433952 0.613561 +0.433270 0.615760 +0.433952 0.613561 +0.434887 0.611600 +0.434887 0.611600 +0.436022 0.610011 +0.436022 0.610011 +0.437282 0.608880 +0.437282 0.608880 +0.438581 0.608233 +0.439843 0.608039 +0.438581 0.608233 +0.439843 0.608039 +0.441098 0.608257 +0.441098 0.608257 +0.442373 0.608928 +0.442373 0.608928 +0.443591 0.610082 +0.443591 0.610082 +0.444668 0.611691 +0.444668 0.611691 +0.445530 0.613669 +0.445530 0.613669 +0.446132 0.615880 +0.446132 0.615880 +0.446460 0.618176 +0.446460 0.618176 +0.445168 0.668652 +0.445570 0.673189 +0.445570 0.673189 +0.445496 0.670947 +0.431738 0.673060 +0.431738 0.673060 +0.431894 0.670820 +0.431894 0.670820 +0.432306 0.668532 +0.432988 0.666332 +0.432306 0.668532 +0.432988 0.666332 +0.433922 0.664372 +0.433922 0.664372 +0.435058 0.662783 +0.435058 0.662783 +0.436317 0.661652 +0.437617 0.661005 +0.436317 0.661652 +0.437617 0.661005 +0.438879 0.660811 +0.438879 0.660811 +0.440134 0.661028 +0.440134 0.661028 +0.441409 0.661699 +0.441409 0.661699 +0.442627 0.662853 +0.442627 0.662853 +0.443704 0.664463 +0.443704 0.664463 +0.444566 0.666440 +0.444566 0.666440 +0.445168 0.668652 +0.445496 0.670947 +0.472224 0.620657 +0.472224 0.620657 +0.486057 0.620785 +0.486057 0.620785 +0.485982 0.618544 +0.485654 0.616248 +0.485982 0.618544 +0.485654 0.616248 +0.485052 0.614037 +0.485052 0.614037 +0.484190 0.612060 +0.484190 0.612060 +0.483113 0.610450 +0.483113 0.610450 +0.481895 0.609296 +0.481895 0.609296 +0.480620 0.608625 +0.480620 0.608625 +0.479365 0.608408 +0.479365 0.608408 +0.478103 0.608601 +0.478103 0.608601 +0.476803 0.609248 +0.476803 0.609248 +0.475544 0.610379 +0.474409 0.611969 +0.475544 0.610379 +0.474409 0.611969 +0.473474 0.613929 +0.473474 0.613929 +0.472792 0.616129 +0.472380 0.618417 +0.472792 0.616129 +0.472380 0.618417 +0.471260 0.673428 +0.471260 0.673428 +0.485018 0.671315 +0.485092 0.673557 +0.485092 0.673557 +0.485018 0.671315 +0.484689 0.669020 +0.484689 0.669020 +0.484088 0.666808 +0.484088 0.666808 +0.483226 0.664831 +0.483226 0.664831 +0.482149 0.663222 +0.482149 0.663222 +0.480931 0.662067 +0.480931 0.662067 +0.479656 0.661396 +0.479656 0.661396 +0.478401 0.661179 +0.478401 0.661179 +0.477139 0.661373 +0.477139 0.661373 +0.475839 0.662020 +0.475839 0.662020 +0.474580 0.663151 +0.473444 0.664740 +0.474580 0.663151 +0.473444 0.664740 +0.472510 0.666701 +0.472510 0.666701 +0.471828 0.668900 +0.471416 0.671189 +0.471828 0.668900 +0.471416 0.671189 +0.881276 0.624467 +0.881276 0.624467 +0.867443 0.624338 +0.867443 0.624338 +0.867600 0.622099 +0.867600 0.622099 +0.868011 0.619810 +0.868011 0.619810 +0.868693 0.617611 +0.868693 0.617611 +0.869628 0.615650 +0.869628 0.615650 +0.870763 0.614061 +0.870763 0.614061 +0.872023 0.612930 +0.872023 0.612930 +0.873322 0.612283 +0.873322 0.612283 +0.874584 0.612089 +0.874584 0.612089 +0.875839 0.612307 +0.875839 0.612307 +0.877115 0.612978 +0.877115 0.612978 +0.878332 0.614132 +0.878332 0.614132 +0.879409 0.615741 +0.879409 0.615741 +0.880272 0.617719 +0.880272 0.617719 +0.880873 0.619930 +0.880873 0.619930 +0.881201 0.622225 +0.881201 0.622225 +0.866479 0.677110 +0.866479 0.677110 +0.880311 0.677239 +0.880311 0.677239 +0.880237 0.674997 +0.880237 0.674997 +0.879909 0.672702 +0.879909 0.672702 +0.879307 0.670490 +0.879307 0.670490 +0.878445 0.668513 +0.878445 0.668513 +0.877368 0.666903 +0.877368 0.666903 +0.876150 0.665749 +0.876150 0.665749 +0.874875 0.665078 +0.874875 0.665078 +0.873620 0.664861 +0.873620 0.664861 +0.872358 0.665055 +0.872358 0.665055 +0.871058 0.665702 +0.871058 0.665702 +0.869799 0.666833 +0.869799 0.666833 +0.868664 0.668422 +0.867729 0.670382 +0.868664 0.668422 +0.867729 0.670382 +0.867047 0.672582 +0.867047 0.672582 +0.866635 0.674870 +0.866635 0.674870 +0.827921 0.623970 +0.827921 0.623970 +0.841754 0.624099 +0.841754 0.624099 +0.841679 0.621857 +0.841679 0.621857 +0.841351 0.619562 +0.841351 0.619562 +0.840750 0.617350 +0.840750 0.617350 +0.839887 0.615373 +0.839887 0.615373 +0.838810 0.613764 +0.838810 0.613764 +0.837592 0.612609 +0.837592 0.612609 +0.836317 0.611938 +0.836317 0.611938 +0.835062 0.611721 +0.835062 0.611721 +0.833800 0.611915 +0.833800 0.611915 +0.832501 0.612562 +0.832501 0.612562 +0.831241 0.613693 +0.831241 0.613693 +0.830106 0.615282 +0.830106 0.615282 +0.829172 0.617243 +0.829172 0.617243 +0.828490 0.619442 +0.828490 0.619442 +0.828078 0.621731 +0.828078 0.621731 +0.826957 0.676742 +0.826957 0.676742 +0.840790 0.676870 +0.840790 0.676870 +0.840715 0.674629 +0.840715 0.674629 +0.840387 0.672334 +0.840387 0.672334 +0.839785 0.670122 +0.838923 0.668145 +0.839785 0.670122 +0.838923 0.668145 +0.837846 0.666535 +0.837846 0.666535 +0.836628 0.665381 +0.836628 0.665381 +0.835353 0.664710 +0.835353 0.664710 +0.834098 0.664493 +0.834098 0.664493 +0.832836 0.664687 +0.832836 0.664687 +0.831536 0.665334 +0.830277 0.666465 +0.831536 0.665334 +0.830277 0.666465 +0.829142 0.668054 +0.828207 0.670014 +0.829142 0.668054 +0.827525 0.672214 +0.828207 0.670014 +0.827113 0.674502 +0.827525 0.672214 +0.827113 0.674502 +0.802157 0.621489 +0.802232 0.623731 +0.788399 0.623602 +0.788399 0.623602 +0.788556 0.621362 +0.788556 0.621362 +0.788968 0.619074 +0.788968 0.619074 +0.789650 0.616874 +0.789650 0.616874 +0.790584 0.614914 +0.790584 0.614914 +0.791719 0.613325 +0.791719 0.613325 +0.792979 0.612194 +0.792979 0.612194 +0.794278 0.611547 +0.794278 0.611547 +0.795541 0.611353 +0.795541 0.611353 +0.796795 0.611570 +0.796795 0.611570 +0.798071 0.612241 +0.798071 0.612241 +0.799289 0.613395 +0.799289 0.613395 +0.800365 0.615005 +0.800365 0.615005 +0.801228 0.616982 +0.801228 0.616982 +0.801829 0.619194 +0.801829 0.619194 +0.802157 0.621489 +0.802232 0.623731 +0.787435 0.676374 +0.787435 0.676374 +0.801268 0.676502 +0.801268 0.676502 +0.801193 0.674261 +0.801193 0.674261 +0.800865 0.671965 +0.800865 0.671965 +0.800263 0.669754 +0.800263 0.669754 +0.799401 0.667777 +0.799401 0.667777 +0.798324 0.666167 +0.798324 0.666167 +0.797106 0.665013 +0.797106 0.665013 +0.795831 0.664342 +0.795831 0.664342 +0.794576 0.664125 +0.794576 0.664125 +0.793314 0.664318 +0.793314 0.664318 +0.792015 0.664965 +0.792015 0.664965 +0.790755 0.666096 +0.790755 0.666096 +0.789620 0.667686 +0.788686 0.669646 +0.789620 0.667686 +0.788003 0.671845 +0.788686 0.669646 +0.787591 0.674134 +0.788003 0.671845 +0.787591 0.674134 +0.762710 0.623363 +0.762710 0.623363 +0.748877 0.623234 +0.748877 0.623234 +0.749034 0.620994 +0.749034 0.620994 +0.749446 0.618706 +0.749446 0.618706 +0.750128 0.616506 +0.750128 0.616506 +0.751062 0.614546 +0.752197 0.612957 +0.751062 0.614546 +0.752197 0.612957 +0.753457 0.611826 +0.753457 0.611826 +0.754756 0.611179 +0.754756 0.611179 +0.756019 0.610985 +0.756019 0.610985 +0.757273 0.611202 +0.757273 0.611202 +0.758549 0.611873 +0.759767 0.613027 +0.758549 0.611873 +0.759767 0.613027 +0.760843 0.614637 +0.760843 0.614637 +0.761706 0.616614 +0.761706 0.616614 +0.762307 0.618826 +0.762635 0.621121 +0.762307 0.618826 +0.762635 0.621121 +0.761746 0.676134 +0.761746 0.676134 +0.747913 0.676005 +0.747913 0.676005 +0.748069 0.673766 +0.748069 0.673766 +0.748482 0.671477 +0.748482 0.671477 +0.749164 0.669278 +0.749164 0.669278 +0.750098 0.667317 +0.750098 0.667317 +0.751233 0.665728 +0.751233 0.665728 +0.752493 0.664597 +0.752493 0.664597 +0.753792 0.663950 +0.753792 0.663950 +0.755054 0.663756 +0.756309 0.663974 +0.755054 0.663756 +0.756309 0.663974 +0.757584 0.664645 +0.758802 0.665799 +0.757584 0.664645 +0.758802 0.665799 +0.759879 0.667408 +0.759879 0.667408 +0.760741 0.669386 +0.760741 0.669386 +0.761343 0.671597 +0.761343 0.671597 +0.761671 0.673892 +0.761671 0.673892 +0.723114 0.620753 +0.723188 0.622994 +0.723188 0.622994 +0.723114 0.620753 +0.709355 0.622866 +0.709355 0.622866 +0.709512 0.620626 +0.709512 0.620626 +0.709924 0.618338 +0.709924 0.618338 +0.710606 0.616138 +0.711540 0.614178 +0.710606 0.616138 +0.711540 0.614178 +0.712675 0.612589 +0.712675 0.612589 +0.713935 0.611457 +0.713935 0.611457 +0.715235 0.610811 +0.715235 0.610811 +0.716497 0.610617 +0.716497 0.610617 +0.717752 0.610834 +0.717752 0.610834 +0.719027 0.611505 +0.719027 0.611505 +0.720245 0.612659 +0.720245 0.612659 +0.721321 0.614269 +0.721321 0.614269 +0.722184 0.616246 +0.722184 0.616246 +0.722785 0.618457 +0.722785 0.618457 +0.722224 0.675766 +0.722224 0.675766 +0.708391 0.675637 +0.708391 0.675637 +0.708548 0.673398 +0.708548 0.673398 +0.708959 0.671109 +0.708959 0.671109 +0.709642 0.668910 +0.709642 0.668910 +0.710576 0.666949 +0.711711 0.665360 +0.710576 0.666949 +0.711711 0.665360 +0.712971 0.664229 +0.712971 0.664229 +0.714270 0.663582 +0.714270 0.663582 +0.715532 0.663388 +0.715532 0.663388 +0.716787 0.663606 +0.718063 0.664276 +0.716787 0.663606 +0.719280 0.665431 +0.718063 0.664276 +0.719280 0.665431 +0.720357 0.667040 +0.720357 0.667040 +0.721219 0.669017 +0.721219 0.669017 +0.721821 0.671229 +0.722149 0.673524 +0.721821 0.671229 +0.722149 0.673524 +0.669833 0.622497 +0.669833 0.622497 +0.683666 0.622626 +0.683666 0.622626 +0.683592 0.620385 +0.683592 0.620385 +0.683263 0.618089 +0.683263 0.618089 +0.682662 0.615878 +0.682662 0.615878 +0.681800 0.613901 +0.681800 0.613901 +0.680723 0.612291 +0.680723 0.612291 +0.679505 0.611137 +0.679505 0.611137 +0.678229 0.610466 +0.678229 0.610466 +0.676975 0.610248 +0.676975 0.610248 +0.675712 0.610442 +0.675712 0.610442 +0.674413 0.611089 +0.674413 0.611089 +0.673153 0.612220 +0.673153 0.612220 +0.672018 0.613809 +0.672018 0.613809 +0.671084 0.615770 +0.670402 0.617969 +0.671084 0.615770 +0.670402 0.617969 +0.669990 0.620258 +0.669990 0.620258 +0.668869 0.675269 +0.668869 0.675269 +0.682702 0.675398 +0.682702 0.675398 +0.682627 0.673156 +0.682627 0.673156 +0.682299 0.670861 +0.682299 0.670861 +0.681697 0.668649 +0.680835 0.666672 +0.681697 0.668649 +0.680835 0.666672 +0.679759 0.665062 +0.679759 0.665062 +0.678541 0.663908 +0.677265 0.663237 +0.678541 0.663908 +0.677265 0.663237 +0.676011 0.663020 +0.674748 0.663214 +0.676011 0.663020 +0.674748 0.663214 +0.673449 0.663861 +0.673449 0.663861 +0.672189 0.664992 +0.672189 0.664992 +0.671054 0.666581 +0.670120 0.668541 +0.671054 0.666581 +0.670120 0.668541 +0.669438 0.670741 +0.669438 0.670741 +0.669026 0.673029 +0.669026 0.673029 +0.644070 0.620016 +0.644144 0.622258 +0.644144 0.622258 +0.644070 0.620016 +0.630311 0.622129 +0.630311 0.622129 +0.630468 0.619890 +0.630468 0.619890 +0.630880 0.617601 +0.630880 0.617601 +0.631562 0.615402 +0.632496 0.613441 +0.631562 0.615402 +0.632496 0.613441 +0.633631 0.611852 +0.633631 0.611852 +0.634891 0.610721 +0.634891 0.610721 +0.636191 0.610074 +0.636191 0.610074 +0.637453 0.609880 +0.637453 0.609880 +0.638708 0.610098 +0.638708 0.610098 +0.639983 0.610769 +0.639983 0.610769 +0.641201 0.611923 +0.641201 0.611923 +0.642277 0.613532 +0.642277 0.613532 +0.643140 0.615510 +0.643140 0.615510 +0.643741 0.617721 +0.643741 0.617721 +0.643105 0.672788 +0.643105 0.672788 +0.643180 0.675030 +0.643180 0.675030 +0.629347 0.674901 +0.629347 0.674901 +0.629504 0.672661 +0.629504 0.672661 +0.629916 0.670373 +0.629916 0.670373 +0.630598 0.668173 +0.630598 0.668173 +0.631532 0.666213 +0.631532 0.666213 +0.632667 0.664624 +0.632667 0.664624 +0.633927 0.663493 +0.633927 0.663493 +0.635226 0.662846 +0.636489 0.662652 +0.635226 0.662846 +0.637743 0.662869 +0.636489 0.662652 +0.637743 0.662869 +0.639019 0.663540 +0.639019 0.663540 +0.640237 0.664694 +0.640237 0.664694 +0.641313 0.666304 +0.641313 0.666304 +0.642176 0.668281 +0.642176 0.668281 +0.642777 0.670493 +0.642777 0.670493 +0.604219 0.617353 +0.604622 0.621890 +0.604622 0.621890 +0.604548 0.619648 +0.604548 0.619648 +0.604219 0.617353 +0.590790 0.621761 +0.590790 0.621761 +0.590946 0.619521 +0.590946 0.619521 +0.591358 0.617233 +0.591358 0.617233 +0.592040 0.615034 +0.592974 0.613073 +0.592040 0.615034 +0.592974 0.613073 +0.594110 0.611484 +0.594110 0.611484 +0.595369 0.610353 +0.595369 0.610353 +0.596669 0.609706 +0.596669 0.609706 +0.597931 0.609512 +0.597931 0.609512 +0.599186 0.609729 +0.599186 0.609729 +0.600461 0.610400 +0.600461 0.610400 +0.601679 0.611554 +0.601679 0.611554 +0.602756 0.613164 +0.603618 0.615141 +0.602756 0.613164 +0.603618 0.615141 +0.603255 0.670124 +0.603658 0.674662 +0.603658 0.674662 +0.603583 0.672420 +0.603583 0.672420 +0.603255 0.670124 +0.589982 0.672293 +0.589825 0.674533 +0.589825 0.674533 +0.589982 0.672293 +0.590394 0.670005 +0.590394 0.670005 +0.591076 0.667805 +0.591076 0.667805 +0.592010 0.665845 +0.592010 0.665845 +0.593145 0.664256 +0.593145 0.664256 +0.594405 0.663125 +0.594405 0.663125 +0.595704 0.662478 +0.595704 0.662478 +0.596967 0.662284 +0.596967 0.662284 +0.598221 0.662501 +0.598221 0.662501 +0.599497 0.663172 +0.600715 0.664326 +0.599497 0.663172 +0.600715 0.664326 +0.601791 0.665936 +0.602654 0.667913 +0.601791 0.665936 +0.602654 0.667913 +0.565100 0.621522 +0.565100 0.621522 +0.551268 0.621393 +0.551268 0.621393 +0.551424 0.619153 +0.551424 0.619153 +0.551836 0.616865 +0.551836 0.616865 +0.552518 0.614665 +0.552518 0.614665 +0.553452 0.612705 +0.553452 0.612705 +0.554588 0.611116 +0.554588 0.611116 +0.555847 0.609985 +0.555847 0.609985 +0.557147 0.609338 +0.558409 0.609144 +0.557147 0.609338 +0.558409 0.609144 +0.559664 0.609361 +0.559664 0.609361 +0.560939 0.610032 +0.560939 0.610032 +0.562157 0.611186 +0.562157 0.611186 +0.563234 0.612796 +0.563234 0.612796 +0.564096 0.614773 +0.564698 0.616985 +0.564096 0.614773 +0.564698 0.616985 +0.565026 0.619280 +0.565026 0.619280 +0.550303 0.674164 +0.550303 0.674164 +0.564136 0.674293 +0.564136 0.674293 +0.564062 0.672052 +0.564062 0.672052 +0.563733 0.669756 +0.563132 0.667545 +0.563733 0.669756 +0.563132 0.667545 +0.562269 0.665568 +0.562269 0.665568 +0.561193 0.663958 +0.561193 0.663958 +0.559975 0.662804 +0.559975 0.662804 +0.558699 0.662133 +0.558699 0.662133 +0.557445 0.661916 +0.557445 0.661916 +0.556183 0.662109 +0.556183 0.662109 +0.554883 0.662756 +0.554883 0.662756 +0.553623 0.663887 +0.553623 0.663887 +0.552488 0.665477 +0.552488 0.665477 +0.551554 0.667437 +0.551554 0.667437 +0.550872 0.669636 +0.550872 0.669636 +0.550460 0.671925 +0.550460 0.671925 +0.525578 0.621154 +0.525578 0.621154 +0.511746 0.621025 +0.511746 0.621025 +0.511902 0.618785 +0.511902 0.618785 +0.512314 0.616497 +0.512996 0.614297 +0.512314 0.616497 +0.512996 0.614297 +0.513931 0.612337 +0.513931 0.612337 +0.515066 0.610748 +0.515066 0.610748 +0.516325 0.609617 +0.516325 0.609617 +0.517625 0.608970 +0.518887 0.608776 +0.517625 0.608970 +0.518887 0.608776 +0.520142 0.608993 +0.520142 0.608993 +0.521417 0.609664 +0.521417 0.609664 +0.522635 0.610818 +0.522635 0.610818 +0.523712 0.612428 +0.523712 0.612428 +0.524574 0.614405 +0.524574 0.614405 +0.525176 0.616617 +0.525176 0.616617 +0.525504 0.618912 +0.525504 0.618912 +0.524614 0.673925 +0.524614 0.673925 +0.510782 0.673796 +0.510782 0.673796 +0.510938 0.671557 +0.510938 0.671557 +0.511350 0.669268 +0.512032 0.667069 +0.511350 0.669268 +0.512032 0.667069 +0.512966 0.665108 +0.512966 0.665108 +0.514102 0.663519 +0.514102 0.663519 +0.515361 0.662388 +0.515361 0.662388 +0.516661 0.661741 +0.516661 0.661741 +0.517923 0.661547 +0.517923 0.661547 +0.519177 0.661765 +0.519177 0.661765 +0.520453 0.662436 +0.521671 0.663590 +0.520453 0.662436 +0.521671 0.663590 +0.522748 0.665199 +0.522748 0.665199 +0.523610 0.667177 +0.523610 0.667177 +0.524211 0.669388 +0.524211 0.669388 +0.524540 0.671684 +0.524540 0.671684 +0.911367 0.600117 +0.909503 0.702142 +0.909503 0.702142 +0.911367 0.600117 +0.126857 0.592808 +0.911367 0.600117 +0.911367 0.600117 +0.126857 0.592808 +0.124993 0.694833 +0.126857 0.592808 +0.126857 0.592808 +0.124993 0.694833 +0.909503 0.702142 +0.124993 0.694833 +0.124993 0.694833 +0.909503 0.702142 +0.909503 0.702142 +0.880873 0.619930 +0.881201 0.622225 +0.881276 0.624467 +0.881119 0.626707 +0.880707 0.628995 +0.880025 0.631195 +0.859166 0.641943 +0.848451 0.643812 +0.819644 0.641575 +0.808928 0.643444 +0.780122 0.641207 +0.769407 0.643076 +0.740600 0.640839 +0.729885 0.642708 +0.701078 0.640470 +0.680835 0.666672 +0.670120 0.668541 +0.671700 0.631223 +0.661556 0.640102 +0.650841 0.641972 +0.622034 0.639734 +0.611319 0.641603 +0.603372 0.628617 +0.601791 0.665936 +0.591076 0.667805 +0.571797 0.641235 +0.542991 0.638998 +0.532275 0.640867 +0.503469 0.638630 +0.492753 0.640499 +0.463947 0.638261 +0.453231 0.640131 +0.424425 0.637893 +0.413709 0.639763 +0.384903 0.637525 +0.374187 0.639394 +0.366240 0.626408 +0.364660 0.663727 +0.353944 0.665596 +0.334666 0.639026 +0.305859 0.636789 +0.285616 0.662990 +0.274900 0.664860 +0.276481 0.627541 +0.266337 0.636420 +0.255622 0.638290 +0.226815 0.636052 +0.206572 0.662254 +0.195857 0.664123 +0.197437 0.626805 +0.187293 0.635684 +0.176578 0.637554 +0.168631 0.624568 +0.167050 0.661886 +0.177194 0.653007 +0.187909 0.651137 +0.216716 0.653375 +0.227431 0.651506 +0.235379 0.664492 +0.236959 0.627173 +0.247674 0.625304 +0.266953 0.651874 +0.295760 0.654111 +0.316003 0.627910 +0.326718 0.626040 +0.325138 0.663359 +0.335282 0.654480 +0.345997 0.652610 +0.374804 0.654848 +0.385519 0.652978 +0.393466 0.665964 +0.395047 0.628646 +0.405762 0.626777 +0.434569 0.629014 +0.445284 0.627145 +0.443704 0.664463 +0.453847 0.655584 +0.464563 0.653715 +0.472510 0.666701 +0.474091 0.629382 +0.484806 0.627513 +0.513612 0.629750 +0.524328 0.627881 +0.522748 0.665199 +0.532891 0.656320 +0.543607 0.654451 +0.551554 0.667437 +0.553134 0.630119 +0.563850 0.628249 +0.583129 0.654819 +0.611935 0.657057 +0.622651 0.655187 +0.630598 0.668173 +0.632178 0.630855 +0.642894 0.628986 +0.662173 0.655555 +0.690979 0.657793 +0.701694 0.655924 +0.709642 0.668910 +0.711222 0.631591 +0.721938 0.629722 +0.741216 0.656292 +0.749164 0.669278 +0.750744 0.631959 +0.761459 0.630090 +0.780738 0.656660 +0.788686 0.669646 +0.790266 0.632328 +0.800981 0.630458 +0.829788 0.632696 +0.840503 0.630826 +0.838923 0.668145 +0.849067 0.659266 +0.859782 0.657396 +0.867729 0.670382 +0.869310 0.633064 +0.879091 0.633155 +0.868447 0.631087 +0.841185 0.628627 +0.828925 0.630719 +0.801664 0.628259 +0.789404 0.630350 +0.762142 0.627891 +0.749882 0.629982 +0.722620 0.627522 +0.710360 0.629614 +0.690117 0.655816 +0.662855 0.653356 +0.662419 0.642079 +0.670838 0.629246 +0.643576 0.626786 +0.631316 0.628878 +0.604054 0.626418 +0.610637 0.643803 +0.611073 0.655079 +0.583811 0.652620 +0.564532 0.626050 +0.552272 0.628141 +0.525010 0.625682 +0.512750 0.627773 +0.485488 0.625313 +0.473228 0.627405 +0.445966 0.624945 +0.433706 0.627037 +0.406444 0.624577 +0.394184 0.626669 +0.366922 0.624209 +0.373505 0.641594 +0.373941 0.652870 +0.346679 0.650411 +0.327400 0.623841 +0.315140 0.625932 +0.294897 0.652134 +0.267635 0.649674 +0.267200 0.638398 +0.275619 0.625564 +0.248357 0.623104 +0.236097 0.625196 +0.215853 0.651398 +0.188591 0.648938 +0.188156 0.637661 +0.196575 0.624828 +0.169313 0.622368 +0.175896 0.639753 +0.176332 0.651030 +0.167913 0.663863 +0.195175 0.666323 +0.207434 0.664231 +0.234696 0.666691 +0.228113 0.649306 +0.227678 0.638030 +0.254940 0.640489 +0.274218 0.667059 +0.286478 0.664968 +0.306722 0.638766 +0.333983 0.641226 +0.334419 0.652502 +0.326000 0.665336 +0.353262 0.667796 +0.365522 0.665704 +0.392784 0.668164 +0.386201 0.650779 +0.385765 0.639502 +0.413027 0.641962 +0.425287 0.639870 +0.452549 0.642330 +0.452985 0.653607 +0.444566 0.666440 +0.471828 0.668900 +0.465245 0.651515 +0.464809 0.640239 +0.492071 0.642698 +0.504331 0.640607 +0.531593 0.643067 +0.532029 0.654343 +0.523610 0.667177 +0.550872 0.669636 +0.544289 0.652251 +0.543853 0.640975 +0.571115 0.643435 +0.590394 0.670005 +0.602654 0.667913 +0.629916 0.670373 +0.623333 0.652988 +0.622897 0.641711 +0.650159 0.644171 +0.669438 0.670741 +0.681697 0.668649 +0.708959 0.671109 +0.702376 0.653724 +0.701941 0.642448 +0.729203 0.644908 +0.748482 0.671477 +0.741898 0.654092 +0.741463 0.642816 +0.768725 0.645276 +0.788003 0.671845 +0.781420 0.654460 +0.780985 0.643184 +0.808246 0.645644 +0.820506 0.643552 +0.847768 0.646012 +0.848204 0.657288 +0.839785 0.670122 +0.867047 0.672582 +0.860464 0.655197 +0.860028 0.643920 +0.880272 0.617719 +0.858089 0.640333 +0.849385 0.641852 +0.818567 0.639965 +0.809863 0.641484 +0.779045 0.639597 +0.770341 0.641116 +0.739523 0.639229 +0.730819 0.640747 +0.700002 0.638861 +0.679759 0.665062 +0.671054 0.666581 +0.672777 0.632833 +0.660480 0.638493 +0.651775 0.640011 +0.620958 0.638124 +0.612253 0.639643 +0.602437 0.630578 +0.600715 0.664326 +0.592010 0.665845 +0.572731 0.639275 +0.541914 0.637388 +0.533209 0.638907 +0.502392 0.637020 +0.493688 0.638538 +0.462870 0.636652 +0.454166 0.638170 +0.423348 0.636284 +0.414644 0.637802 +0.383826 0.635915 +0.375122 0.637434 +0.365306 0.628369 +0.363583 0.662117 +0.354879 0.663636 +0.335600 0.637066 +0.304782 0.635179 +0.284539 0.661381 +0.275835 0.662899 +0.277557 0.629151 +0.265260 0.634811 +0.256556 0.636329 +0.225739 0.634443 +0.205495 0.660644 +0.196791 0.662163 +0.198514 0.628415 +0.186217 0.634074 +0.177512 0.635593 +0.167696 0.626528 +0.165973 0.660276 +0.178271 0.654616 +0.186975 0.653098 +0.217793 0.654985 +0.226497 0.653466 +0.236313 0.662531 +0.238036 0.628783 +0.246740 0.627264 +0.266019 0.653834 +0.296836 0.655721 +0.317079 0.629519 +0.325784 0.628001 +0.324061 0.661749 +0.336358 0.656089 +0.345063 0.654571 +0.375880 0.656457 +0.384585 0.654939 +0.394401 0.664004 +0.396123 0.630256 +0.404828 0.628737 +0.435645 0.630624 +0.444350 0.629105 +0.442627 0.662853 +0.454924 0.657194 +0.463629 0.655675 +0.473444 0.664740 +0.475167 0.630992 +0.483872 0.629473 +0.514689 0.631360 +0.523394 0.629842 +0.521671 0.663590 +0.533968 0.657930 +0.542672 0.656411 +0.552488 0.665477 +0.554211 0.631728 +0.562916 0.630210 +0.582194 0.656780 +0.613012 0.658666 +0.621716 0.657148 +0.631532 0.666213 +0.633255 0.632465 +0.641959 0.630946 +0.661238 0.657516 +0.692056 0.659403 +0.700760 0.657884 +0.710576 0.666949 +0.712299 0.633201 +0.721003 0.631682 +0.740282 0.658252 +0.750098 0.667317 +0.751821 0.633569 +0.760525 0.632051 +0.779804 0.658620 +0.789620 0.667686 +0.791342 0.633937 +0.800047 0.632419 +0.830864 0.634305 +0.839569 0.632787 +0.837846 0.666535 +0.850143 0.660875 +0.858848 0.659357 +0.868664 0.668422 +0.870386 0.634674 +0.877956 0.634744 +0.867846 0.628875 +0.841598 0.626338 +0.828324 0.628507 +0.802076 0.625970 +0.788802 0.628139 +0.762554 0.625602 +0.749280 0.627771 +0.723032 0.625234 +0.709758 0.627403 +0.689515 0.653604 +0.663267 0.651067 +0.663020 0.644291 +0.670236 0.627034 +0.643988 0.624498 +0.630714 0.626666 +0.604466 0.624129 +0.610225 0.646091 +0.610471 0.652868 +0.584223 0.650331 +0.564944 0.623761 +0.551670 0.625930 +0.525422 0.623393 +0.512148 0.625562 +0.485900 0.623025 +0.472627 0.625194 +0.446378 0.622657 +0.433105 0.624825 +0.406856 0.622289 +0.393583 0.624457 +0.367334 0.621920 +0.373093 0.643882 +0.373340 0.650659 +0.347091 0.648122 +0.327812 0.621552 +0.314539 0.623721 +0.294296 0.649923 +0.268047 0.647386 +0.267801 0.640609 +0.275017 0.623353 +0.248769 0.620816 +0.235495 0.622984 +0.215252 0.649186 +0.189003 0.646649 +0.188757 0.639873 +0.195973 0.622616 +0.169725 0.620080 +0.175484 0.642042 +0.175730 0.648818 +0.168514 0.666075 +0.194762 0.668611 +0.208036 0.666443 +0.234284 0.668980 +0.228525 0.647018 +0.228279 0.640241 +0.254528 0.642778 +0.273806 0.669348 +0.287080 0.667179 +0.307323 0.640977 +0.333571 0.643514 +0.333818 0.650291 +0.326602 0.667547 +0.352850 0.670084 +0.366124 0.667915 +0.392372 0.670452 +0.386613 0.648490 +0.386367 0.641714 +0.412615 0.644251 +0.425889 0.642082 +0.452137 0.644619 +0.452384 0.651395 +0.445168 0.668652 +0.471416 0.671189 +0.465657 0.649227 +0.465411 0.642450 +0.491659 0.644987 +0.504933 0.642818 +0.531181 0.645355 +0.531427 0.652132 +0.524211 0.669388 +0.550460 0.671925 +0.544701 0.649963 +0.544454 0.643186 +0.570703 0.645723 +0.589982 0.672293 +0.603255 0.670124 +0.629504 0.672661 +0.623745 0.650699 +0.623498 0.643923 +0.649747 0.646460 +0.669026 0.673029 +0.682299 0.670861 +0.708548 0.673398 +0.702789 0.651436 +0.702542 0.644659 +0.728791 0.647196 +0.748069 0.673766 +0.742311 0.651804 +0.742064 0.645027 +0.768313 0.647564 +0.787591 0.674134 +0.781832 0.652172 +0.781586 0.645396 +0.807834 0.647932 +0.821108 0.645764 +0.847356 0.648300 +0.847603 0.655077 +0.840387 0.672334 +0.866635 0.674870 +0.860876 0.652908 +0.860630 0.646132 +0.879409 0.615741 +0.856871 0.639179 +0.850520 0.640263 +0.817349 0.638811 +0.810998 0.639895 +0.777828 0.638443 +0.771476 0.639527 +0.738306 0.638075 +0.731954 0.639158 +0.698784 0.637707 +0.678541 0.663908 +0.672189 0.664992 +0.673995 0.633987 +0.659262 0.637338 +0.652910 0.638422 +0.619740 0.636970 +0.613388 0.638054 +0.601302 0.632167 +0.599497 0.663172 +0.593145 0.664256 +0.573866 0.637686 +0.540696 0.636234 +0.534345 0.637318 +0.501174 0.635866 +0.494823 0.636949 +0.461652 0.635498 +0.455301 0.636581 +0.422130 0.635129 +0.415779 0.636213 +0.382608 0.634761 +0.376257 0.635845 +0.364171 0.629958 +0.362365 0.660963 +0.356014 0.662047 +0.336735 0.635477 +0.303564 0.634025 +0.283321 0.660227 +0.276970 0.661310 +0.278776 0.630305 +0.264042 0.633657 +0.257691 0.634740 +0.224521 0.633289 +0.204277 0.659490 +0.197926 0.660574 +0.199732 0.629569 +0.184999 0.632920 +0.178647 0.634004 +0.166561 0.628117 +0.164756 0.659122 +0.179489 0.655770 +0.185840 0.654687 +0.219011 0.656139 +0.225362 0.655055 +0.237448 0.660942 +0.239254 0.629937 +0.245605 0.628853 +0.264884 0.655423 +0.298054 0.656875 +0.318297 0.630673 +0.324649 0.629590 +0.322843 0.660595 +0.337576 0.657243 +0.343928 0.656160 +0.377098 0.657611 +0.383450 0.656528 +0.395536 0.662415 +0.397341 0.631410 +0.403693 0.630326 +0.436863 0.631778 +0.443215 0.630694 +0.441409 0.661699 +0.456142 0.658348 +0.462493 0.657264 +0.474580 0.663151 +0.476385 0.632146 +0.482737 0.631062 +0.515907 0.632514 +0.522258 0.631431 +0.520453 0.662436 +0.535186 0.659084 +0.541537 0.658001 +0.553623 0.663887 +0.555429 0.632882 +0.561780 0.631799 +0.581059 0.658369 +0.614230 0.659820 +0.620581 0.658737 +0.632667 0.664624 +0.634473 0.633619 +0.640824 0.632535 +0.660103 0.659105 +0.693274 0.660557 +0.699625 0.659473 +0.711711 0.665360 +0.713517 0.634355 +0.719868 0.633272 +0.739147 0.659841 +0.751233 0.665728 +0.753039 0.634723 +0.759390 0.633640 +0.778669 0.660210 +0.790755 0.666096 +0.792560 0.635091 +0.798912 0.634008 +0.832082 0.635460 +0.838434 0.634376 +0.836628 0.665381 +0.851361 0.662030 +0.857713 0.660946 +0.869799 0.666833 +0.871604 0.635828 +0.876696 0.635875 +0.867518 0.626580 +0.841754 0.624099 +0.827996 0.626212 +0.802232 0.623731 +0.788474 0.625844 +0.762710 0.623363 +0.748952 0.625475 +0.723188 0.622994 +0.709430 0.625107 +0.689187 0.651309 +0.663423 0.648828 +0.663348 0.646586 +0.673449 0.663861 +0.675270 0.634658 +0.674748 0.663214 +0.676525 0.634875 +0.676011 0.663020 +0.677787 0.634681 +0.677265 0.663237 +0.679086 0.634034 +0.689112 0.649067 +0.680346 0.632903 +0.689269 0.646828 +0.681481 0.631314 +0.689681 0.644539 +0.682416 0.629354 +0.690363 0.642340 +0.683098 0.627154 +0.691297 0.640379 +0.683510 0.624866 +0.692432 0.638790 +0.669908 0.624739 +0.644144 0.622258 +0.630386 0.624371 +0.604622 0.621890 +0.610068 0.648331 +0.610143 0.650573 +0.600043 0.633298 +0.598221 0.662501 +0.598743 0.633945 +0.596967 0.662284 +0.597481 0.634139 +0.595704 0.662478 +0.596226 0.633922 +0.594405 0.663125 +0.584379 0.648092 +0.584305 0.645850 +0.594951 0.633251 +0.583976 0.643555 +0.593733 0.632096 +0.583375 0.641343 +0.592656 0.630487 +0.582512 0.639366 +0.591794 0.628510 +0.581436 0.637756 +0.591192 0.626298 +0.580218 0.636602 +0.565100 0.621522 +0.683666 0.622626 +0.590864 0.624003 +0.551342 0.623635 +0.525578 0.621154 +0.511820 0.623266 +0.486057 0.620785 +0.472298 0.622898 +0.446535 0.620417 +0.432776 0.622530 +0.407013 0.620049 +0.393255 0.622162 +0.367491 0.619681 +0.372937 0.646122 +0.373011 0.648364 +0.362911 0.631089 +0.361090 0.660292 +0.361612 0.631736 +0.359835 0.660075 +0.360349 0.631930 +0.358573 0.660269 +0.359095 0.631712 +0.357273 0.660916 +0.347248 0.645883 +0.347173 0.643641 +0.357819 0.631042 +0.346845 0.641346 +0.356601 0.629887 +0.346243 0.639134 +0.355525 0.628278 +0.345381 0.637157 +0.354662 0.626301 +0.344304 0.635547 +0.354061 0.624089 +0.343086 0.634393 +0.327969 0.619313 +0.314211 0.621426 +0.293968 0.647627 +0.268204 0.645146 +0.268129 0.642905 +0.278230 0.660179 +0.280051 0.630976 +0.279529 0.659532 +0.281306 0.631194 +0.280791 0.659338 +0.282568 0.631000 +0.282046 0.659556 +0.283867 0.630353 +0.293893 0.645386 +0.285127 0.629222 +0.294049 0.643146 +0.286262 0.627632 +0.294462 0.640858 +0.287196 0.625672 +0.295144 0.638658 +0.287879 0.623472 +0.296078 0.636698 +0.288291 0.621184 +0.297213 0.635108 +0.353733 0.621794 +0.288447 0.618944 +0.274689 0.621057 +0.248925 0.618576 +0.235167 0.620689 +0.214924 0.646891 +0.189160 0.644410 +0.189085 0.642168 +0.199186 0.659443 +0.201007 0.630240 +0.200485 0.658796 +0.202262 0.630457 +0.201747 0.658602 +0.203524 0.630263 +0.203002 0.658819 +0.204823 0.629616 +0.214849 0.644649 +0.206083 0.628485 +0.215006 0.642410 +0.207218 0.626896 +0.215418 0.640121 +0.208152 0.624936 +0.216100 0.637922 +0.208835 0.622736 +0.217034 0.635961 +0.209247 0.620448 +0.218169 0.634372 +0.195645 0.620321 +0.169881 0.617840 +0.209403 0.618208 +0.175327 0.644281 +0.175402 0.646523 +0.165301 0.629248 +0.163480 0.658451 +0.164002 0.629895 +0.162225 0.658234 +0.162740 0.630089 +0.160963 0.658428 +0.161485 0.629872 +0.159664 0.659075 +0.160210 0.629201 +0.158404 0.660206 +0.168842 0.668370 +0.194606 0.670851 +0.208364 0.668738 +0.234128 0.671219 +0.228682 0.644778 +0.228607 0.642536 +0.238708 0.659811 +0.240529 0.630608 +0.240007 0.659164 +0.241784 0.630825 +0.241269 0.658970 +0.243046 0.630631 +0.242524 0.659187 +0.244345 0.629984 +0.254371 0.645017 +0.254446 0.647259 +0.243799 0.659858 +0.254774 0.649554 +0.245017 0.661013 +0.255375 0.651766 +0.246094 0.662622 +0.256238 0.653743 +0.246956 0.664599 +0.257314 0.655353 +0.247558 0.666811 +0.258532 0.656507 +0.247886 0.669106 +0.273650 0.671587 +0.287408 0.669474 +0.307651 0.643273 +0.333415 0.645754 +0.333489 0.647995 +0.323389 0.630721 +0.321568 0.659924 +0.322090 0.631368 +0.320313 0.659706 +0.320828 0.631562 +0.319051 0.659900 +0.319573 0.631344 +0.317752 0.660547 +0.307726 0.645514 +0.316492 0.661678 +0.307569 0.647754 +0.315357 0.663267 +0.307157 0.650042 +0.314422 0.665228 +0.306475 0.652242 +0.313740 0.667427 +0.305541 0.654202 +0.313328 0.669716 +0.304406 0.655791 +0.326930 0.669843 +0.352694 0.672324 +0.366452 0.670211 +0.392216 0.672692 +0.313172 0.671955 +0.386770 0.646251 +0.386695 0.644009 +0.396795 0.661284 +0.398617 0.632081 +0.398095 0.660637 +0.399871 0.632298 +0.399357 0.660443 +0.401134 0.632104 +0.400612 0.660660 +0.402433 0.631457 +0.412459 0.646490 +0.412533 0.648732 +0.401887 0.661331 +0.412862 0.651027 +0.403105 0.662485 +0.413463 0.653239 +0.404182 0.664095 +0.414326 0.655216 +0.405044 0.666072 +0.415402 0.656825 +0.405646 0.668284 +0.416620 0.657980 +0.426217 0.644377 +0.451981 0.646858 +0.452055 0.649100 +0.441955 0.631825 +0.440134 0.661028 +0.440656 0.632472 +0.438879 0.660811 +0.439393 0.632666 +0.437617 0.661005 +0.438139 0.632449 +0.436317 0.661652 +0.426292 0.646619 +0.435058 0.662783 +0.426135 0.648858 +0.433922 0.664372 +0.425723 0.651147 +0.432988 0.666332 +0.425041 0.653346 +0.432306 0.668532 +0.424107 0.655307 +0.431894 0.670820 +0.422972 0.656896 +0.445496 0.670947 +0.471260 0.673428 +0.465813 0.646987 +0.405974 0.670579 +0.431738 0.673060 +0.465739 0.644745 +0.475839 0.662020 +0.477660 0.632817 +0.477139 0.661373 +0.478915 0.633034 +0.478401 0.661179 +0.480177 0.632841 +0.479656 0.661396 +0.481477 0.632194 +0.491503 0.647226 +0.491577 0.649468 +0.480931 0.662067 +0.491905 0.651763 +0.482149 0.663222 +0.492507 0.653975 +0.483226 0.664831 +0.493369 0.655952 +0.484088 0.666808 +0.494446 0.657562 +0.484689 0.669020 +0.495664 0.658716 +0.505261 0.645114 +0.531025 0.647595 +0.531099 0.649836 +0.520999 0.632562 +0.519177 0.661765 +0.519699 0.633209 +0.517923 0.661547 +0.518437 0.633403 +0.516661 0.661741 +0.517182 0.633185 +0.515361 0.662388 +0.505335 0.647355 +0.514102 0.663519 +0.505179 0.649595 +0.512966 0.665108 +0.504767 0.651883 +0.512032 0.667069 +0.504085 0.654083 +0.511350 0.669268 +0.503150 0.656043 +0.510938 0.671557 +0.502015 0.657632 +0.524540 0.671684 +0.550303 0.674164 +0.544857 0.647723 +0.485018 0.671315 +0.510782 0.673796 +0.544783 0.645482 +0.554883 0.662756 +0.556704 0.633553 +0.556183 0.662109 +0.557959 0.633771 +0.557445 0.661916 +0.559221 0.633577 +0.558699 0.662133 +0.560521 0.632930 +0.570547 0.647963 +0.570621 0.650204 +0.559975 0.662804 +0.570949 0.652500 +0.561193 0.663958 +0.571551 0.654711 +0.562269 0.665568 +0.572413 0.656689 +0.563132 0.667545 +0.573490 0.658298 +0.563733 0.669756 +0.574708 0.659452 +0.589825 0.674533 +0.603583 0.672420 +0.629347 0.674901 +0.623901 0.648460 +0.623827 0.646218 +0.633927 0.663493 +0.635748 0.634290 +0.635226 0.662846 +0.637003 0.634507 +0.636489 0.662652 +0.638265 0.634313 +0.637743 0.662869 +0.639565 0.633666 +0.649590 0.648699 +0.649665 0.650941 +0.639019 0.663540 +0.649993 0.653236 +0.640237 0.664694 +0.650595 0.655448 +0.641313 0.666304 +0.651457 0.657425 +0.642176 0.668281 +0.652534 0.659035 +0.642777 0.670493 +0.653752 0.660189 +0.564062 0.672052 +0.643105 0.672788 +0.668869 0.675269 +0.682627 0.673156 +0.708391 0.675637 +0.702945 0.649196 +0.702870 0.646955 +0.712971 0.664229 +0.714792 0.635026 +0.714270 0.663582 +0.716047 0.635243 +0.715532 0.663388 +0.717309 0.635050 +0.716787 0.663606 +0.718608 0.634403 +0.728634 0.649435 +0.728709 0.651677 +0.718063 0.664276 +0.729037 0.653972 +0.719280 0.665431 +0.729638 0.656184 +0.720357 0.667040 +0.730501 0.658161 +0.721219 0.669017 +0.731578 0.659771 +0.721821 0.671229 +0.732795 0.660925 +0.747913 0.676005 +0.742467 0.649564 +0.722149 0.673524 +0.742392 0.647323 +0.752493 0.664597 +0.754314 0.635394 +0.753792 0.663950 +0.755569 0.635612 +0.755054 0.663756 +0.756831 0.635418 +0.756309 0.663974 +0.758130 0.634771 +0.768156 0.649804 +0.768231 0.652045 +0.757584 0.664645 +0.768559 0.654341 +0.758802 0.665799 +0.769160 0.656552 +0.759879 0.667408 +0.770023 0.658529 +0.760741 0.669386 +0.771099 0.660139 +0.761343 0.671597 +0.772317 0.661293 +0.787435 0.676374 +0.781989 0.649933 +0.781914 0.647691 +0.792015 0.664965 +0.793836 0.635762 +0.793314 0.664318 +0.795090 0.635980 +0.794576 0.664125 +0.796353 0.635786 +0.795831 0.664342 +0.797652 0.635139 +0.807678 0.650172 +0.807753 0.652413 +0.797106 0.665013 +0.808081 0.654709 +0.798324 0.666167 +0.808682 0.656920 +0.799401 0.667777 +0.809545 0.658898 +0.800263 0.669754 +0.810621 0.660507 +0.800865 0.671965 +0.811839 0.661661 +0.821436 0.648059 +0.847200 0.650540 +0.847275 0.652782 +0.837174 0.635507 +0.835353 0.664710 +0.835875 0.636154 +0.834098 0.664493 +0.834612 0.636348 +0.832836 0.664687 +0.833358 0.636131 +0.831536 0.665334 +0.821511 0.650301 +0.830277 0.666465 +0.821354 0.652540 +0.829142 0.668054 +0.820942 0.654829 +0.828207 0.670014 +0.820260 0.657028 +0.827525 0.672214 +0.819326 0.658989 +0.827113 0.674502 +0.818191 0.660578 +0.761671 0.673892 +0.801193 0.674261 +0.826957 0.676742 +0.840715 0.674629 +0.866479 0.677110 +0.861033 0.650669 +0.860958 0.648427 +0.871058 0.665702 +0.872880 0.636499 +0.872358 0.665055 +0.874134 0.636716 +0.873620 0.664861 +0.875397 0.636522 +0.874875 0.665078 +0.876150 0.665749 +0.877368 0.666903 +0.878445 0.668513 +0.879307 0.670490 +0.879909 0.672702 +0.880237 0.674997 +0.880311 0.677239 +0.880155 0.679478 +0.879743 0.681767 +0.879061 0.683966 +0.855596 0.638508 +0.851780 0.639132 +0.816074 0.638140 +0.812258 0.638764 +0.776552 0.637772 +0.772736 0.638395 +0.737030 0.637404 +0.733214 0.638027 +0.697508 0.637036 +0.693692 0.637659 +0.657986 0.636667 +0.654170 0.637291 +0.618464 0.636299 +0.614648 0.636923 +0.578943 0.635931 +0.575126 0.636555 +0.539421 0.635563 +0.535604 0.636186 +0.499899 0.635195 +0.496082 0.635818 +0.460377 0.634827 +0.456560 0.635450 +0.420855 0.634458 +0.417039 0.635082 +0.381333 0.634090 +0.377517 0.634714 +0.341811 0.633722 +0.337995 0.634346 +0.302289 0.633354 +0.298473 0.633978 +0.262767 0.632986 +0.258951 0.633609 +0.223245 0.632618 +0.219429 0.633241 +0.183723 0.632249 +0.179907 0.632873 +0.180764 0.656442 +0.184580 0.655818 +0.220286 0.656810 +0.224102 0.656186 +0.259808 0.657178 +0.263624 0.656554 +0.299330 0.657546 +0.303146 0.656923 +0.338851 0.657914 +0.342668 0.657291 +0.378373 0.658282 +0.382190 0.657659 +0.417895 0.658651 +0.421712 0.658027 +0.457417 0.659019 +0.461234 0.658395 +0.496939 0.659387 +0.500756 0.658763 +0.536461 0.659755 +0.540278 0.659132 +0.575983 0.660123 +0.579800 0.659500 +0.615505 0.660491 +0.619321 0.659868 +0.655027 0.660860 +0.658843 0.660236 +0.694549 0.661228 +0.698365 0.660604 +0.734071 0.661596 +0.737887 0.660972 +0.773593 0.661964 +0.777409 0.661341 +0.813115 0.662332 +0.816931 0.661709 +0.852637 0.662700 +0.856453 0.662077 +0.878127 0.685927 +0.878332 0.614132 +0.867443 0.624338 +0.841679 0.621857 +0.827921 0.623970 +0.802157 0.621489 +0.788399 0.623602 +0.762635 0.621121 +0.748877 0.623234 +0.723114 0.620753 +0.709355 0.622866 +0.683592 0.620385 +0.669833 0.622497 +0.644070 0.620016 +0.630311 0.622129 +0.604548 0.619648 +0.590790 0.621761 +0.565026 0.619280 +0.551268 0.621393 +0.525504 0.618912 +0.511746 0.621025 +0.485982 0.618544 +0.472224 0.620657 +0.446460 0.618176 +0.432702 0.620288 +0.406938 0.617807 +0.393180 0.619920 +0.367416 0.617439 +0.353658 0.619552 +0.327894 0.617071 +0.314136 0.619184 +0.288372 0.616703 +0.274614 0.618816 +0.248850 0.616335 +0.235092 0.618447 +0.209329 0.615966 +0.195570 0.618079 +0.169807 0.615598 +0.158992 0.628047 +0.157269 0.661795 +0.168917 0.670612 +0.194681 0.673093 +0.208439 0.670980 +0.234203 0.673461 +0.247961 0.671348 +0.273724 0.673829 +0.287483 0.671716 +0.313246 0.674197 +0.327005 0.672084 +0.352768 0.674565 +0.366526 0.672453 +0.392290 0.674933 +0.406048 0.672821 +0.431812 0.675302 +0.445570 0.673189 +0.471334 0.675670 +0.485092 0.673557 +0.510856 0.676038 +0.524614 0.673925 +0.550378 0.676406 +0.564136 0.674293 +0.589900 0.676774 +0.603658 0.674662 +0.629422 0.677142 +0.643180 0.675030 +0.668944 0.677511 +0.682702 0.675398 +0.708466 0.677879 +0.722224 0.675766 +0.747988 0.678247 +0.761746 0.676134 +0.787509 0.678615 +0.801268 0.676502 +0.827031 0.678983 +0.840790 0.676870 +0.866553 0.679352 +0.854341 0.638291 +0.853079 0.638485 +0.867600 0.622099 +0.841351 0.619562 +0.868011 0.619810 +0.840750 0.617350 +0.868693 0.617611 +0.839887 0.615373 +0.814819 0.637923 +0.813557 0.638117 +0.828078 0.621731 +0.801829 0.619194 +0.828490 0.619442 +0.801228 0.616982 +0.829172 0.617243 +0.800365 0.615005 +0.775298 0.637555 +0.774035 0.637749 +0.788556 0.621362 +0.762307 0.618826 +0.788968 0.619074 +0.761706 0.616614 +0.789650 0.616874 +0.760843 0.614637 +0.735776 0.637187 +0.734513 0.637380 +0.749034 0.620994 +0.722785 0.618457 +0.749446 0.618706 +0.722184 0.616246 +0.750128 0.616506 +0.721321 0.614269 +0.696254 0.636818 +0.694991 0.637012 +0.709512 0.620626 +0.683263 0.618089 +0.709924 0.618338 +0.682662 0.615878 +0.710606 0.616138 +0.681800 0.613901 +0.656732 0.636450 +0.655470 0.636644 +0.669990 0.620258 +0.643741 0.617721 +0.670402 0.617969 +0.643140 0.615510 +0.671084 0.615770 +0.642277 0.613532 +0.617210 0.636082 +0.615947 0.636276 +0.630468 0.619890 +0.604219 0.617353 +0.630880 0.617601 +0.603618 0.615141 +0.631562 0.615402 +0.602756 0.613164 +0.577688 0.635714 +0.576425 0.635908 +0.590946 0.619521 +0.564698 0.616985 +0.591358 0.617233 +0.564096 0.614773 +0.592040 0.615034 +0.563234 0.612796 +0.538166 0.635346 +0.536904 0.635540 +0.551424 0.619153 +0.525176 0.616617 +0.551836 0.616865 +0.524574 0.614405 +0.552518 0.614665 +0.523712 0.612428 +0.498644 0.634977 +0.497382 0.635171 +0.511902 0.618785 +0.485654 0.616248 +0.512314 0.616497 +0.485052 0.614037 +0.512996 0.614297 +0.484190 0.612060 +0.459122 0.634609 +0.457860 0.634803 +0.472380 0.618417 +0.446132 0.615880 +0.472792 0.616129 +0.445530 0.613669 +0.473474 0.613929 +0.444668 0.611691 +0.419600 0.634241 +0.418338 0.634435 +0.432858 0.618049 +0.406610 0.615512 +0.433270 0.615760 +0.406008 0.613301 +0.433952 0.613561 +0.405146 0.611323 +0.380078 0.633873 +0.378816 0.634067 +0.393336 0.617681 +0.367088 0.615144 +0.393748 0.615392 +0.366486 0.612932 +0.394431 0.613193 +0.365624 0.610955 +0.340556 0.633505 +0.339294 0.633699 +0.353814 0.617312 +0.327566 0.614776 +0.354226 0.615024 +0.326964 0.612564 +0.354909 0.612824 +0.326102 0.610587 +0.301034 0.633137 +0.299772 0.633331 +0.314293 0.616944 +0.288044 0.614408 +0.314705 0.614656 +0.287443 0.612196 +0.315387 0.612456 +0.286580 0.610219 +0.261513 0.632768 +0.260250 0.632962 +0.274771 0.616576 +0.248522 0.614039 +0.275183 0.614288 +0.247921 0.611828 +0.275865 0.612088 +0.247058 0.609851 +0.221991 0.632400 +0.220728 0.632594 +0.235249 0.616208 +0.209000 0.613671 +0.235661 0.613919 +0.208399 0.611460 +0.236343 0.611720 +0.207536 0.609482 +0.182469 0.632032 +0.181206 0.632226 +0.195727 0.615840 +0.169478 0.613303 +0.196139 0.613551 +0.168877 0.611091 +0.196821 0.611352 +0.168014 0.609114 +0.182019 0.656659 +0.183281 0.656465 +0.168760 0.672851 +0.195009 0.675388 +0.168348 0.675140 +0.195610 0.677599 +0.167666 0.677339 +0.196473 0.679577 +0.221541 0.657027 +0.222803 0.656833 +0.208282 0.673219 +0.234531 0.675756 +0.207870 0.675508 +0.235132 0.677968 +0.207188 0.677707 +0.235995 0.679945 +0.261063 0.657395 +0.262325 0.657201 +0.247804 0.673588 +0.274053 0.676124 +0.247392 0.675876 +0.274654 0.678336 +0.246710 0.678075 +0.275517 0.680313 +0.300584 0.657763 +0.301847 0.657570 +0.287326 0.673956 +0.313575 0.676493 +0.286914 0.676244 +0.314176 0.678704 +0.286232 0.678444 +0.315039 0.680681 +0.340106 0.658132 +0.341369 0.657938 +0.326848 0.674324 +0.353097 0.676861 +0.326436 0.676612 +0.353698 0.679072 +0.325754 0.678812 +0.354560 0.681049 +0.379628 0.658500 +0.380891 0.658306 +0.366370 0.674692 +0.392619 0.677229 +0.365958 0.676980 +0.393220 0.679440 +0.365276 0.679180 +0.394082 0.681418 +0.419150 0.658868 +0.420412 0.658674 +0.405892 0.675060 +0.432140 0.677597 +0.405480 0.677349 +0.432742 0.679808 +0.404798 0.679548 +0.433604 0.681786 +0.458672 0.659236 +0.459934 0.659042 +0.445414 0.675428 +0.471662 0.677965 +0.445002 0.677717 +0.472264 0.680177 +0.444320 0.679916 +0.473126 0.682154 +0.498194 0.659604 +0.499456 0.659410 +0.484936 0.675797 +0.511184 0.678333 +0.484524 0.678085 +0.511786 0.680545 +0.483842 0.680284 +0.512648 0.682522 +0.537716 0.659972 +0.538978 0.659779 +0.524458 0.676165 +0.550706 0.678702 +0.524046 0.678453 +0.551308 0.680913 +0.523364 0.680653 +0.552170 0.682890 +0.577238 0.660340 +0.578500 0.660147 +0.563980 0.676533 +0.590228 0.679070 +0.563568 0.678821 +0.590830 0.681281 +0.562886 0.681021 +0.591692 0.683258 +0.616760 0.660709 +0.618022 0.660515 +0.603502 0.676901 +0.629750 0.679438 +0.603090 0.679189 +0.630352 0.681649 +0.602408 0.681389 +0.631214 0.683627 +0.656282 0.661077 +0.657544 0.660883 +0.643023 0.677269 +0.669272 0.679806 +0.642612 0.679558 +0.669873 0.682018 +0.641930 0.681757 +0.670736 0.683995 +0.695804 0.661445 +0.697066 0.661251 +0.682545 0.677637 +0.708794 0.680174 +0.682134 0.679926 +0.709395 0.682386 +0.681451 0.682125 +0.710258 0.684363 +0.735325 0.661813 +0.736588 0.661619 +0.722067 0.678005 +0.748316 0.680542 +0.721655 0.680294 +0.748917 0.682754 +0.720973 0.682494 +0.749780 0.684731 +0.774848 0.662181 +0.776110 0.661988 +0.761589 0.678374 +0.787838 0.680911 +0.761177 0.680662 +0.788439 0.683122 +0.760495 0.682862 +0.789302 0.685099 +0.814369 0.662550 +0.815632 0.662356 +0.801111 0.678742 +0.827360 0.681279 +0.800699 0.681030 +0.827961 0.683490 +0.800017 0.683230 +0.828824 0.685467 +0.853891 0.662918 +0.855154 0.662724 +0.840633 0.679110 +0.866882 0.681647 +0.840221 0.681399 +0.867483 0.683858 +0.839539 0.683598 +0.868345 0.685836 +0.876992 0.687516 +0.877115 0.612978 +0.869628 0.615650 +0.838810 0.613764 +0.830106 0.615282 +0.799289 0.613395 +0.790584 0.614914 +0.759767 0.613027 +0.751062 0.614546 +0.720245 0.612659 +0.711540 0.614178 +0.680723 0.612291 +0.672018 0.613809 +0.641201 0.611923 +0.632496 0.613441 +0.601679 0.611554 +0.592974 0.613073 +0.562157 0.611186 +0.553452 0.612705 +0.522635 0.610818 +0.513931 0.612337 +0.483113 0.610450 +0.474409 0.611969 +0.443591 0.610082 +0.434887 0.611600 +0.404069 0.609714 +0.395365 0.611232 +0.364547 0.609345 +0.355843 0.610864 +0.325025 0.608977 +0.316321 0.610496 +0.285504 0.608609 +0.276799 0.610128 +0.245982 0.608241 +0.237277 0.609760 +0.206460 0.607873 +0.197755 0.609391 +0.166938 0.607505 +0.157915 0.626437 +0.156335 0.663755 +0.166732 0.679300 +0.197549 0.681186 +0.206254 0.679668 +0.237071 0.681554 +0.245776 0.680036 +0.276593 0.681923 +0.285298 0.680404 +0.316115 0.682291 +0.324820 0.680772 +0.355637 0.682659 +0.364342 0.681140 +0.395159 0.683027 +0.403864 0.681509 +0.434681 0.683395 +0.443386 0.681877 +0.474203 0.683764 +0.482907 0.682245 +0.513725 0.684132 +0.522429 0.682613 +0.553247 0.684500 +0.561951 0.682981 +0.592769 0.684868 +0.601473 0.683350 +0.632290 0.685236 +0.640995 0.683718 +0.671813 0.685604 +0.680517 0.684086 +0.711334 0.685973 +0.720039 0.684454 +0.750856 0.686341 +0.759561 0.684822 +0.790378 0.686709 +0.799083 0.685190 +0.829900 0.687077 +0.838605 0.685559 +0.869422 0.687445 +0.875732 0.688647 +0.875839 0.612307 +0.870763 0.614061 +0.837592 0.612609 +0.831241 0.613693 +0.798071 0.612241 +0.791719 0.613325 +0.758549 0.611873 +0.752197 0.612957 +0.719027 0.611505 +0.712675 0.612589 +0.679505 0.611137 +0.673153 0.612220 +0.639983 0.610769 +0.633631 0.611852 +0.600461 0.610400 +0.594110 0.611484 +0.560939 0.610032 +0.554588 0.611116 +0.521417 0.609664 +0.515066 0.610748 +0.481895 0.609296 +0.475544 0.610379 +0.442373 0.608928 +0.436022 0.610011 +0.402851 0.608559 +0.396500 0.609643 +0.363329 0.608191 +0.356978 0.609275 +0.323808 0.607823 +0.317456 0.608907 +0.284286 0.607455 +0.277934 0.608539 +0.244764 0.607087 +0.238412 0.608171 +0.205242 0.606719 +0.198890 0.607802 +0.165720 0.606350 +0.157053 0.624460 +0.155653 0.665955 +0.165597 0.680889 +0.198767 0.682340 +0.205119 0.681257 +0.238289 0.682709 +0.244641 0.681625 +0.277811 0.683077 +0.284163 0.681993 +0.317333 0.683445 +0.323685 0.682361 +0.356855 0.683813 +0.363207 0.682730 +0.396377 0.684181 +0.402728 0.683098 +0.435899 0.684550 +0.442250 0.683466 +0.475421 0.684918 +0.481772 0.683834 +0.514943 0.685286 +0.521294 0.684202 +0.554465 0.685654 +0.560816 0.684570 +0.593987 0.686022 +0.600338 0.684938 +0.633508 0.686390 +0.639860 0.685307 +0.673030 0.686759 +0.679382 0.685675 +0.712552 0.687127 +0.718904 0.686043 +0.752074 0.687495 +0.758426 0.686411 +0.791596 0.687863 +0.797948 0.686779 +0.831118 0.688231 +0.837470 0.687148 +0.870640 0.688599 +0.872023 0.612930 +0.832501 0.612562 +0.792979 0.612194 +0.753457 0.611826 +0.713935 0.611457 +0.836317 0.611938 +0.796795 0.611570 +0.757273 0.611202 +0.717752 0.610834 +0.678229 0.610466 +0.674413 0.611089 +0.634891 0.610721 +0.595369 0.610353 +0.638708 0.610098 +0.599186 0.609729 +0.559664 0.609361 +0.555847 0.609985 +0.516325 0.609617 +0.476803 0.609248 +0.437282 0.608880 +0.520142 0.608993 +0.480620 0.608625 +0.441098 0.608257 +0.401576 0.607889 +0.397760 0.608512 +0.358238 0.608144 +0.318716 0.607776 +0.362054 0.607520 +0.322532 0.607152 +0.283010 0.606784 +0.279194 0.607408 +0.239672 0.607039 +0.200150 0.606671 +0.156451 0.622248 +0.243488 0.606416 +0.203966 0.606048 +0.164445 0.605680 +0.155241 0.668243 +0.164337 0.682020 +0.203859 0.682388 +0.243381 0.682756 +0.200043 0.683011 +0.239565 0.683380 +0.279087 0.683748 +0.282903 0.683124 +0.322425 0.683492 +0.361947 0.683861 +0.401469 0.684229 +0.318608 0.684116 +0.358130 0.684484 +0.397652 0.684852 +0.437174 0.685220 +0.440991 0.684597 +0.480513 0.684965 +0.520034 0.685333 +0.476696 0.685589 +0.516218 0.685957 +0.555740 0.686325 +0.559556 0.685701 +0.599078 0.686070 +0.638600 0.686438 +0.678122 0.686806 +0.595262 0.686693 +0.634784 0.687061 +0.674306 0.687429 +0.713828 0.687798 +0.717644 0.687174 +0.757166 0.687542 +0.796688 0.687910 +0.753350 0.688166 +0.792872 0.688534 +0.832393 0.688902 +0.836210 0.688279 +0.871915 0.689270 +0.874432 0.689294 +0.124993 0.694833 +0.873170 0.689488 +0.874584 0.612089 +0.911367 0.600117 +0.873322 0.612283 +0.835062 0.611721 +0.833800 0.611915 +0.795541 0.611353 +0.794278 0.611547 +0.756019 0.610985 +0.754756 0.611179 +0.716497 0.610617 +0.715235 0.610811 +0.676975 0.610248 +0.675712 0.610442 +0.637453 0.609880 +0.636191 0.610074 +0.597931 0.609512 +0.596669 0.609706 +0.558409 0.609144 +0.557147 0.609338 +0.518887 0.608776 +0.517625 0.608970 +0.479365 0.608408 +0.478103 0.608601 +0.439843 0.608039 +0.438581 0.608233 +0.400321 0.607671 +0.399059 0.607865 +0.360799 0.607303 +0.359537 0.607497 +0.321277 0.606935 +0.320015 0.607129 +0.281756 0.606567 +0.280493 0.606761 +0.242234 0.606199 +0.240971 0.606392 +0.202712 0.605830 +0.201449 0.606024 +0.163190 0.605462 +0.161927 0.605656 +0.160628 0.606303 +0.159368 0.607434 +0.158233 0.609023 +0.157299 0.610984 +0.126857 0.592808 +0.156617 0.613183 +0.156205 0.615472 +0.156048 0.617711 +0.156123 0.619953 +0.155084 0.670483 +0.155159 0.672724 +0.155487 0.675020 +0.156088 0.677231 +0.156951 0.679208 +0.158027 0.680818 +0.159245 0.681972 +0.160521 0.682643 +0.161776 0.682861 +0.163038 0.682667 +0.201297 0.683229 +0.202560 0.683035 +0.240819 0.683597 +0.242082 0.683403 +0.281604 0.683771 +0.321126 0.684139 +0.360647 0.684507 +0.400169 0.684876 +0.280341 0.683965 +0.319863 0.684333 +0.359385 0.684701 +0.398907 0.685069 +0.438429 0.685438 +0.439691 0.685244 +0.479213 0.685612 +0.518735 0.685980 +0.477951 0.685806 +0.517473 0.686174 +0.556995 0.686542 +0.558257 0.686348 +0.597779 0.686717 +0.637301 0.687085 +0.676823 0.687453 +0.596517 0.686910 +0.636039 0.687279 +0.675560 0.687647 +0.715082 0.688015 +0.716345 0.687821 +0.755867 0.688189 +0.795389 0.688558 +0.754604 0.688383 +0.794126 0.688751 +0.833648 0.689119 +0.834911 0.688926 +0.911367 0.600117 +0.881201 0.622225 +0.881276 0.624467 +0.881119 0.626707 +0.880707 0.628995 +0.880025 0.631195 +0.879091 0.633155 +0.868447 0.631087 +0.868664 0.668422 +0.858848 0.659357 +0.848204 0.657288 +0.839785 0.670122 +0.839569 0.632787 +0.828925 0.630719 +0.800047 0.632419 +0.789404 0.630350 +0.789620 0.667686 +0.779804 0.658620 +0.760525 0.632051 +0.749882 0.629982 +0.750098 0.667317 +0.740282 0.658252 +0.721003 0.631682 +0.710360 0.629614 +0.710576 0.666949 +0.700760 0.657884 +0.681481 0.631314 +0.670838 0.629246 +0.671054 0.666581 +0.661238 0.657516 +0.641959 0.630946 +0.631316 0.628878 +0.631532 0.666213 +0.621716 0.657148 +0.611073 0.655079 +0.602654 0.667913 +0.602437 0.630578 +0.591794 0.628510 +0.571551 0.654711 +0.542672 0.656411 +0.532029 0.654343 +0.503150 0.656043 +0.492507 0.653975 +0.484088 0.666808 +0.483872 0.629473 +0.473228 0.627405 +0.452985 0.653607 +0.424107 0.655307 +0.413463 0.653239 +0.384585 0.654939 +0.365306 0.628369 +0.354662 0.626301 +0.354879 0.663636 +0.345063 0.654571 +0.334419 0.652502 +0.326000 0.665336 +0.325784 0.628001 +0.315140 0.625932 +0.286262 0.627632 +0.275619 0.625564 +0.275835 0.662899 +0.266019 0.653834 +0.246740 0.627264 +0.236097 0.625196 +0.236313 0.662531 +0.226497 0.653466 +0.207218 0.626896 +0.196575 0.624828 +0.196791 0.662163 +0.186975 0.653098 +0.176332 0.651030 +0.167913 0.663863 +0.167696 0.626528 +0.177512 0.635593 +0.188156 0.637661 +0.217034 0.635961 +0.227678 0.638030 +0.256556 0.636329 +0.267200 0.638398 +0.296078 0.636698 +0.306722 0.638766 +0.335600 0.637066 +0.346243 0.639134 +0.375122 0.637434 +0.385765 0.639502 +0.394184 0.626669 +0.394401 0.664004 +0.405044 0.666072 +0.433922 0.664372 +0.444566 0.666440 +0.444350 0.629105 +0.454166 0.638170 +0.464809 0.640239 +0.493688 0.638538 +0.512966 0.665108 +0.523610 0.667177 +0.523394 0.629842 +0.533209 0.638907 +0.543853 0.640975 +0.552272 0.628141 +0.552488 0.665477 +0.563132 0.667545 +0.583375 0.641343 +0.612253 0.639643 +0.622897 0.641711 +0.651775 0.640011 +0.662419 0.642079 +0.691297 0.640379 +0.701941 0.642448 +0.730819 0.640747 +0.741463 0.642816 +0.770341 0.641116 +0.780985 0.643184 +0.809863 0.641484 +0.820506 0.643552 +0.849385 0.641852 +0.860028 0.643920 +0.877956 0.634744 +0.860630 0.646132 +0.859782 0.657396 +0.867729 0.670382 +0.840387 0.672334 +0.847603 0.655077 +0.848451 0.643812 +0.821108 0.645764 +0.808928 0.643444 +0.781586 0.645396 +0.780738 0.656660 +0.788686 0.669646 +0.769407 0.643076 +0.742064 0.645027 +0.741216 0.656292 +0.749164 0.669278 +0.729885 0.642708 +0.702542 0.644659 +0.701694 0.655924 +0.709642 0.668910 +0.690363 0.642340 +0.663020 0.644291 +0.662173 0.655555 +0.670120 0.668541 +0.650841 0.641972 +0.623498 0.643923 +0.622651 0.655187 +0.630598 0.668173 +0.603255 0.670124 +0.610471 0.652868 +0.611319 0.641603 +0.583976 0.643555 +0.563733 0.669756 +0.551554 0.667437 +0.524211 0.669388 +0.512032 0.667069 +0.484689 0.669020 +0.491905 0.651763 +0.492753 0.640499 +0.465411 0.642450 +0.445168 0.668652 +0.432988 0.666332 +0.405646 0.668284 +0.393466 0.665964 +0.374187 0.639394 +0.346845 0.641346 +0.345997 0.652610 +0.353944 0.665596 +0.326602 0.667547 +0.333818 0.650291 +0.334666 0.639026 +0.307323 0.640977 +0.295144 0.638658 +0.267801 0.640609 +0.266953 0.651874 +0.274900 0.664860 +0.255622 0.638290 +0.228279 0.640241 +0.227431 0.651506 +0.235379 0.664492 +0.216100 0.637922 +0.188757 0.639873 +0.187909 0.651137 +0.195857 0.664123 +0.168514 0.666075 +0.175730 0.648818 +0.176578 0.637554 +0.168631 0.624568 +0.195973 0.622616 +0.208152 0.624936 +0.235495 0.622984 +0.247674 0.625304 +0.275017 0.623353 +0.287196 0.625672 +0.314539 0.623721 +0.326718 0.626040 +0.354061 0.624089 +0.366240 0.626408 +0.393583 0.624457 +0.386367 0.641714 +0.385519 0.652978 +0.412862 0.651027 +0.425041 0.653346 +0.452384 0.651395 +0.453231 0.640131 +0.445284 0.627145 +0.472627 0.625194 +0.484806 0.627513 +0.504085 0.654083 +0.531427 0.652132 +0.532275 0.640867 +0.524328 0.627881 +0.551670 0.625930 +0.544454 0.643186 +0.543607 0.654451 +0.570949 0.652500 +0.591192 0.626298 +0.603372 0.628617 +0.630714 0.626666 +0.642894 0.628986 +0.670236 0.627034 +0.682416 0.629354 +0.709758 0.627403 +0.721938 0.629722 +0.749280 0.627771 +0.761459 0.630090 +0.788802 0.628139 +0.800981 0.630458 +0.828324 0.628507 +0.840503 0.630826 +0.867846 0.628875 +0.880873 0.619930 +0.869310 0.633064 +0.869799 0.666833 +0.857713 0.660946 +0.849067 0.659266 +0.838923 0.668145 +0.838434 0.634376 +0.829788 0.632696 +0.798912 0.634008 +0.790266 0.632328 +0.790755 0.666096 +0.778669 0.660210 +0.759390 0.633640 +0.750744 0.631959 +0.751233 0.665728 +0.739147 0.659841 +0.719868 0.633272 +0.711222 0.631591 +0.711711 0.665360 +0.699625 0.659473 +0.680346 0.632903 +0.671700 0.631223 +0.672189 0.664992 +0.660103 0.659105 +0.640824 0.632535 +0.632178 0.630855 +0.632667 0.664624 +0.620581 0.658737 +0.611935 0.657057 +0.601791 0.665936 +0.601302 0.632167 +0.592656 0.630487 +0.572413 0.656689 +0.541537 0.658001 +0.532891 0.656320 +0.502015 0.657632 +0.493369 0.655952 +0.483226 0.664831 +0.482737 0.631062 +0.474091 0.629382 +0.453847 0.655584 +0.422972 0.656896 +0.414326 0.655216 +0.383450 0.656528 +0.364171 0.629958 +0.355525 0.628278 +0.356014 0.662047 +0.343928 0.656160 +0.335282 0.654480 +0.325138 0.663359 +0.324649 0.629590 +0.316003 0.627910 +0.285127 0.629222 +0.276481 0.627541 +0.276970 0.661310 +0.264884 0.655423 +0.245605 0.628853 +0.236959 0.627173 +0.237448 0.660942 +0.225362 0.655055 +0.206083 0.628485 +0.197437 0.626805 +0.197926 0.660574 +0.185840 0.654687 +0.177194 0.653007 +0.167050 0.661886 +0.166561 0.628117 +0.178647 0.634004 +0.187293 0.635684 +0.218169 0.634372 +0.226815 0.636052 +0.257691 0.634740 +0.266337 0.636420 +0.297213 0.635108 +0.305859 0.636789 +0.336735 0.635477 +0.345381 0.637157 +0.376257 0.635845 +0.384903 0.637525 +0.395047 0.628646 +0.395536 0.662415 +0.404182 0.664095 +0.435058 0.662783 +0.443704 0.664463 +0.443215 0.630694 +0.455301 0.636581 +0.463947 0.638261 +0.494823 0.636949 +0.514102 0.663519 +0.522748 0.665199 +0.522258 0.631431 +0.534345 0.637318 +0.542991 0.638998 +0.553134 0.630119 +0.553623 0.663887 +0.562269 0.665568 +0.582512 0.639366 +0.613388 0.638054 +0.622034 0.639734 +0.652910 0.638422 +0.661556 0.640102 +0.692432 0.638790 +0.701078 0.640470 +0.731954 0.639158 +0.740600 0.640839 +0.771476 0.639527 +0.780122 0.641207 +0.810998 0.639895 +0.819644 0.641575 +0.850520 0.640263 +0.859166 0.641943 +0.876696 0.635875 +0.860958 0.648427 +0.860464 0.655197 +0.867047 0.672582 +0.840715 0.674629 +0.847275 0.652782 +0.847768 0.646012 +0.821436 0.648059 +0.808246 0.645644 +0.781914 0.647691 +0.781420 0.654460 +0.788003 0.671845 +0.768725 0.645276 +0.742392 0.647323 +0.741898 0.654092 +0.748482 0.671477 +0.729203 0.644908 +0.702870 0.646955 +0.702376 0.653724 +0.708959 0.671109 +0.689681 0.644539 +0.663348 0.646586 +0.662855 0.653356 +0.669438 0.670741 +0.650159 0.644171 +0.623827 0.646218 +0.623333 0.652988 +0.629916 0.670373 +0.603583 0.672420 +0.610143 0.650573 +0.610637 0.643803 +0.584305 0.645850 +0.564062 0.672052 +0.550872 0.669636 +0.524540 0.671684 +0.511350 0.669268 +0.485018 0.671315 +0.491577 0.649468 +0.492071 0.642698 +0.465739 0.644745 +0.445496 0.670947 +0.432306 0.668532 +0.405974 0.670579 +0.392784 0.668164 +0.373505 0.641594 +0.347173 0.643641 +0.346679 0.650411 +0.353262 0.667796 +0.326930 0.669843 +0.333489 0.647995 +0.333983 0.641226 +0.307651 0.643273 +0.294462 0.640858 +0.268129 0.642905 +0.267635 0.649674 +0.274218 0.667059 +0.254940 0.640489 +0.228607 0.642536 +0.228113 0.649306 +0.234696 0.666691 +0.215418 0.640121 +0.189085 0.642168 +0.188591 0.648938 +0.195175 0.666323 +0.168842 0.668370 +0.175402 0.646523 +0.175896 0.639753 +0.169313 0.622368 +0.195645 0.620321 +0.208835 0.622736 +0.235167 0.620689 +0.248357 0.623104 +0.274689 0.621057 +0.287879 0.623472 +0.314211 0.621426 +0.327400 0.623841 +0.353733 0.621794 +0.366922 0.624209 +0.393255 0.622162 +0.386695 0.644009 +0.386201 0.650779 +0.412533 0.648732 +0.425723 0.651147 +0.452055 0.649100 +0.452549 0.642330 +0.445966 0.624945 +0.472298 0.622898 +0.485488 0.625313 +0.504767 0.651883 +0.531099 0.649836 +0.531593 0.643067 +0.525010 0.625682 +0.551342 0.623635 +0.544783 0.645482 +0.544289 0.652251 +0.570621 0.650204 +0.590864 0.624003 +0.604054 0.626418 +0.630386 0.624371 +0.643576 0.626786 +0.669908 0.624739 +0.683098 0.627154 +0.709430 0.625107 +0.722620 0.627522 +0.748952 0.625475 +0.762142 0.627891 +0.788474 0.625844 +0.801664 0.628259 +0.827996 0.626212 +0.841185 0.628627 +0.867518 0.626580 +0.880272 0.617719 +0.870386 0.634674 +0.871058 0.665702 +0.856453 0.662077 +0.850143 0.660875 +0.837846 0.666535 +0.837174 0.635507 +0.830864 0.634305 +0.797652 0.635139 +0.791342 0.633937 +0.792015 0.664965 +0.777409 0.661341 +0.758130 0.634771 +0.751821 0.633569 +0.752493 0.664597 +0.737887 0.660972 +0.718608 0.634403 +0.712299 0.633201 +0.712971 0.664229 +0.698365 0.660604 +0.679086 0.634034 +0.672777 0.632833 +0.673449 0.663861 +0.658843 0.660236 +0.639565 0.633666 +0.633255 0.632465 +0.633927 0.663493 +0.619321 0.659868 +0.613012 0.658666 +0.600715 0.664326 +0.600043 0.633298 +0.593733 0.632096 +0.573490 0.658298 +0.540278 0.659132 +0.533968 0.657930 +0.500756 0.658763 +0.494446 0.657562 +0.482149 0.663222 +0.481477 0.632194 +0.475167 0.630992 +0.454924 0.657194 +0.421712 0.658027 +0.415402 0.656825 +0.382190 0.657659 +0.362911 0.631089 +0.356601 0.629887 +0.357273 0.660916 +0.342668 0.657291 +0.336358 0.656089 +0.324061 0.661749 +0.323389 0.630721 +0.317079 0.629519 +0.283867 0.630353 +0.277557 0.629151 +0.278230 0.660179 +0.263624 0.656554 +0.244345 0.629984 +0.238036 0.628783 +0.238708 0.659811 +0.224102 0.656186 +0.204823 0.629616 +0.198514 0.628415 +0.199186 0.659443 +0.184580 0.655818 +0.178271 0.654616 +0.165973 0.660276 +0.165301 0.629248 +0.179907 0.632873 +0.186217 0.634074 +0.219429 0.633241 +0.225739 0.634443 +0.258951 0.633609 +0.265260 0.634811 +0.298473 0.633978 +0.304782 0.635179 +0.337995 0.634346 +0.344304 0.635547 +0.377517 0.634714 +0.383826 0.635915 +0.396123 0.630256 +0.396795 0.661284 +0.403105 0.662485 +0.436317 0.661652 +0.442627 0.662853 +0.441955 0.631825 +0.456560 0.635450 +0.462870 0.636652 +0.496082 0.635818 +0.515361 0.662388 +0.521671 0.663590 +0.520999 0.632562 +0.535604 0.636186 +0.541914 0.637388 +0.554211 0.631728 +0.554883 0.662756 +0.561193 0.663958 +0.581436 0.637756 +0.614648 0.636923 +0.620958 0.638124 +0.654170 0.637291 +0.660480 0.638493 +0.693692 0.637659 +0.700002 0.638861 +0.733214 0.638027 +0.739523 0.639229 +0.772736 0.638395 +0.779045 0.639597 +0.812258 0.638764 +0.818567 0.639965 +0.851780 0.639132 +0.858089 0.640333 +0.875397 0.636522 +0.861033 0.650669 +0.860876 0.652908 +0.871604 0.635828 +0.872358 0.665055 +0.872880 0.636499 +0.873620 0.664861 +0.874134 0.636716 +0.874875 0.665078 +0.876150 0.665749 +0.866635 0.674870 +0.840790 0.676870 +0.847200 0.650540 +0.847356 0.648300 +0.836628 0.665381 +0.835875 0.636154 +0.835353 0.664710 +0.834612 0.636348 +0.834098 0.664493 +0.833358 0.636131 +0.832836 0.664687 +0.832082 0.635460 +0.821511 0.650301 +0.821354 0.652540 +0.831536 0.665334 +0.820942 0.654829 +0.830277 0.666465 +0.820260 0.657028 +0.829142 0.668054 +0.819326 0.658989 +0.828207 0.670014 +0.818191 0.660578 +0.827525 0.672214 +0.816931 0.661709 +0.807834 0.647932 +0.781989 0.649933 +0.781832 0.652172 +0.792560 0.635091 +0.793314 0.664318 +0.793836 0.635762 +0.794576 0.664125 +0.795090 0.635980 +0.795831 0.664342 +0.796353 0.635786 +0.797106 0.665013 +0.807678 0.650172 +0.798324 0.666167 +0.807753 0.652413 +0.799401 0.667777 +0.808081 0.654709 +0.800263 0.669754 +0.808682 0.656920 +0.800865 0.671965 +0.809545 0.658898 +0.801193 0.674261 +0.810621 0.660507 +0.827113 0.674502 +0.801268 0.676502 +0.787591 0.674134 +0.768313 0.647564 +0.742467 0.649564 +0.742311 0.651804 +0.753039 0.634723 +0.753792 0.663950 +0.754314 0.635394 +0.755054 0.663756 +0.755569 0.635612 +0.756309 0.663974 +0.756831 0.635418 +0.757584 0.664645 +0.768156 0.649804 +0.758802 0.665799 +0.768231 0.652045 +0.759879 0.667408 +0.768559 0.654341 +0.760741 0.669386 +0.769160 0.656552 +0.761343 0.671597 +0.770023 0.658529 +0.761671 0.673892 +0.771099 0.660139 +0.748069 0.673766 +0.728791 0.647196 +0.702945 0.649196 +0.702789 0.651436 +0.713517 0.634355 +0.714270 0.663582 +0.714792 0.635026 +0.715532 0.663388 +0.716047 0.635243 +0.716787 0.663606 +0.717309 0.635050 +0.718063 0.664276 +0.728634 0.649435 +0.719280 0.665431 +0.728709 0.651677 +0.720357 0.667040 +0.729037 0.653972 +0.721219 0.669017 +0.729638 0.656184 +0.721821 0.671229 +0.730501 0.658161 +0.722149 0.673524 +0.731578 0.659771 +0.761746 0.676134 +0.722224 0.675766 +0.708548 0.673398 +0.689269 0.646828 +0.663423 0.648828 +0.663267 0.651067 +0.673995 0.633987 +0.674748 0.663214 +0.675270 0.634658 +0.676011 0.663020 +0.676525 0.634875 +0.677265 0.663237 +0.677787 0.634681 +0.678541 0.663908 +0.689112 0.649067 +0.679759 0.665062 +0.689187 0.651309 +0.680835 0.666672 +0.689515 0.653604 +0.681697 0.668649 +0.690117 0.655816 +0.682299 0.670861 +0.690979 0.657793 +0.682627 0.673156 +0.692056 0.659403 +0.669026 0.673029 +0.649747 0.646460 +0.623901 0.648460 +0.623745 0.650699 +0.634473 0.633619 +0.635226 0.662846 +0.635748 0.634290 +0.636489 0.662652 +0.637003 0.634507 +0.637743 0.662869 +0.638265 0.634313 +0.639019 0.663540 +0.649590 0.648699 +0.640237 0.664694 +0.649665 0.650941 +0.641313 0.666304 +0.649993 0.653236 +0.642176 0.668281 +0.650595 0.655448 +0.642777 0.670493 +0.651457 0.657425 +0.643105 0.672788 +0.652534 0.659035 +0.682702 0.675398 +0.643180 0.675030 +0.629504 0.672661 +0.603658 0.674662 +0.610068 0.648331 +0.610225 0.646091 +0.599497 0.663172 +0.598743 0.633945 +0.598221 0.662501 +0.597481 0.634139 +0.596967 0.662284 +0.596226 0.633922 +0.595704 0.662478 +0.594951 0.633251 +0.584379 0.648092 +0.584223 0.650331 +0.594405 0.663125 +0.583811 0.652620 +0.593145 0.664256 +0.583129 0.654819 +0.592010 0.665845 +0.582194 0.656780 +0.591076 0.667805 +0.581059 0.658369 +0.590394 0.670005 +0.579800 0.659500 +0.564136 0.674293 +0.550460 0.671925 +0.524614 0.673925 +0.589982 0.672293 +0.510938 0.671557 +0.485092 0.673557 +0.491503 0.647226 +0.491659 0.644987 +0.480931 0.662067 +0.480177 0.632841 +0.479656 0.661396 +0.478915 0.633034 +0.478401 0.661179 +0.477660 0.632817 +0.477139 0.661373 +0.476385 0.632146 +0.465813 0.646987 +0.465657 0.649227 +0.475839 0.662020 +0.465245 0.651515 +0.474580 0.663151 +0.464563 0.653715 +0.473444 0.664740 +0.463629 0.655675 +0.472510 0.666701 +0.462493 0.657264 +0.471828 0.668900 +0.461234 0.658395 +0.445570 0.673189 +0.431894 0.670820 +0.406048 0.672821 +0.392372 0.670452 +0.471416 0.671189 +0.373093 0.643882 +0.347248 0.645883 +0.347091 0.648122 +0.357819 0.631042 +0.358573 0.660269 +0.359095 0.631712 +0.359835 0.660075 +0.360349 0.631930 +0.361090 0.660292 +0.361612 0.631736 +0.362365 0.660963 +0.372937 0.646122 +0.363583 0.662117 +0.373011 0.648364 +0.364660 0.663727 +0.373340 0.650659 +0.365522 0.665704 +0.373941 0.652870 +0.366124 0.667915 +0.374804 0.654848 +0.366452 0.670211 +0.375880 0.656457 +0.352850 0.670084 +0.327005 0.672084 +0.333415 0.645754 +0.333571 0.643514 +0.322843 0.660595 +0.322090 0.631368 +0.321568 0.659924 +0.320828 0.631562 +0.320313 0.659706 +0.319573 0.631344 +0.319051 0.659900 +0.318297 0.630673 +0.307726 0.645514 +0.307569 0.647754 +0.317752 0.660547 +0.307157 0.650042 +0.316492 0.661678 +0.306475 0.652242 +0.315357 0.663267 +0.305541 0.654202 +0.314422 0.665228 +0.304406 0.655791 +0.313740 0.667427 +0.303146 0.656923 +0.294049 0.643146 +0.366526 0.672453 +0.313328 0.669716 +0.268204 0.645146 +0.268047 0.647386 +0.278776 0.630305 +0.279529 0.659532 +0.280051 0.630976 +0.280791 0.659338 +0.281306 0.631194 +0.282046 0.659556 +0.282568 0.631000 +0.283321 0.660227 +0.293893 0.645386 +0.284539 0.661381 +0.293968 0.647627 +0.285616 0.662990 +0.294296 0.649923 +0.286478 0.664968 +0.294897 0.652134 +0.287080 0.667179 +0.295760 0.654111 +0.287408 0.669474 +0.296836 0.655721 +0.273806 0.669348 +0.254528 0.642778 +0.228682 0.644778 +0.228525 0.647018 +0.239254 0.629937 +0.240007 0.659164 +0.240529 0.630608 +0.241269 0.658970 +0.241784 0.630825 +0.242524 0.659187 +0.243046 0.630631 +0.243799 0.659858 +0.254371 0.645017 +0.245017 0.661013 +0.254446 0.647259 +0.246094 0.662622 +0.254774 0.649554 +0.246956 0.664599 +0.255375 0.651766 +0.247558 0.666811 +0.256238 0.653743 +0.247886 0.669106 +0.257314 0.655353 +0.234284 0.668980 +0.215006 0.642410 +0.287483 0.671716 +0.247961 0.671348 +0.189160 0.644410 +0.189003 0.646649 +0.199732 0.629569 +0.200485 0.658796 +0.201007 0.630240 +0.201747 0.658602 +0.202262 0.630457 +0.203002 0.658819 +0.203524 0.630263 +0.204277 0.659490 +0.214849 0.644649 +0.205495 0.660644 +0.214924 0.646891 +0.206572 0.662254 +0.215252 0.649186 +0.207434 0.664231 +0.215853 0.651398 +0.208036 0.666443 +0.216716 0.653375 +0.208364 0.668738 +0.217793 0.654985 +0.194762 0.668611 +0.168917 0.670612 +0.175327 0.644281 +0.175484 0.642042 +0.164756 0.659122 +0.164002 0.629895 +0.163480 0.658451 +0.162740 0.630089 +0.162225 0.658234 +0.161485 0.629872 +0.160963 0.658428 +0.160210 0.629201 +0.159664 0.659075 +0.158992 0.628047 +0.169725 0.620080 +0.195570 0.618079 +0.208439 0.670980 +0.209247 0.620448 +0.235092 0.618447 +0.248769 0.620816 +0.274614 0.618816 +0.288291 0.621184 +0.314136 0.619184 +0.327812 0.621552 +0.353658 0.619552 +0.367334 0.621920 +0.393180 0.619920 +0.386770 0.646251 +0.386613 0.648490 +0.397341 0.631410 +0.398095 0.660637 +0.398617 0.632081 +0.399357 0.660443 +0.399871 0.632298 +0.400612 0.660660 +0.401134 0.632104 +0.401887 0.661331 +0.412459 0.646490 +0.412615 0.644251 +0.402433 0.631457 +0.413027 0.641962 +0.403693 0.630326 +0.413709 0.639763 +0.404828 0.628737 +0.414644 0.637802 +0.405762 0.626777 +0.415779 0.636213 +0.406444 0.624577 +0.417039 0.635082 +0.426135 0.648858 +0.451981 0.646858 +0.452137 0.644619 +0.441409 0.661699 +0.440656 0.632472 +0.440134 0.661028 +0.439393 0.632666 +0.438879 0.660811 +0.438139 0.632449 +0.437617 0.661005 +0.436863 0.631778 +0.426292 0.646619 +0.435645 0.630624 +0.426217 0.644377 +0.434569 0.629014 +0.425889 0.642082 +0.433706 0.627037 +0.425287 0.639870 +0.433105 0.624825 +0.424425 0.637893 +0.432776 0.622530 +0.423348 0.636284 +0.446378 0.622657 +0.472224 0.620657 +0.485900 0.623025 +0.406856 0.622289 +0.432702 0.620288 +0.505179 0.649595 +0.531025 0.647595 +0.531181 0.645355 +0.520453 0.662436 +0.519699 0.633209 +0.519177 0.661765 +0.518437 0.633403 +0.517923 0.661547 +0.517182 0.633185 +0.516661 0.661741 +0.515907 0.632514 +0.505335 0.647355 +0.514689 0.631360 +0.505261 0.645114 +0.513612 0.629750 +0.504933 0.642818 +0.512750 0.627773 +0.504331 0.640607 +0.512148 0.625562 +0.503469 0.638630 +0.511820 0.623266 +0.502392 0.637020 +0.525422 0.623393 +0.551268 0.621393 +0.544857 0.647723 +0.544701 0.649963 +0.555429 0.632882 +0.556183 0.662109 +0.556704 0.633553 +0.557445 0.661916 +0.557959 0.633771 +0.558699 0.662133 +0.559221 0.633577 +0.559975 0.662804 +0.570547 0.647963 +0.570703 0.645723 +0.560521 0.632930 +0.571115 0.643435 +0.561780 0.631799 +0.571797 0.641235 +0.562916 0.630210 +0.572731 0.639275 +0.563850 0.628249 +0.573866 0.637686 +0.564532 0.626050 +0.575126 0.636555 +0.511746 0.621025 +0.564944 0.623761 +0.590790 0.621761 +0.604466 0.624129 +0.630311 0.622129 +0.643988 0.624498 +0.669833 0.622497 +0.683510 0.624866 +0.709355 0.622866 +0.723032 0.625234 +0.748877 0.623234 +0.762554 0.625602 +0.788399 0.623602 +0.802076 0.625970 +0.827921 0.623970 +0.841598 0.626338 +0.867443 0.624338 +0.877368 0.666903 +0.878445 0.668513 +0.879307 0.670490 +0.879909 0.672702 +0.880237 0.674997 +0.880311 0.677239 +0.880155 0.679478 +0.879743 0.681767 +0.879061 0.683966 +0.878127 0.685927 +0.855154 0.662724 +0.851361 0.662030 +0.815632 0.662356 +0.811839 0.661661 +0.776110 0.661988 +0.772317 0.661293 +0.736588 0.661619 +0.732795 0.660925 +0.697066 0.661251 +0.693274 0.660557 +0.657544 0.660883 +0.653752 0.660189 +0.618022 0.660515 +0.614230 0.659820 +0.578500 0.660147 +0.574708 0.659452 +0.538978 0.659779 +0.535186 0.659084 +0.499456 0.659410 +0.495664 0.658716 +0.459934 0.659042 +0.456142 0.658348 +0.420412 0.658674 +0.416620 0.657980 +0.380891 0.658306 +0.377098 0.657611 +0.341369 0.657938 +0.337576 0.657243 +0.301847 0.657570 +0.298054 0.656875 +0.262325 0.657201 +0.258532 0.656507 +0.222803 0.656833 +0.219011 0.656139 +0.183281 0.656465 +0.179489 0.655770 +0.181206 0.632226 +0.184999 0.632920 +0.220728 0.632594 +0.224521 0.633289 +0.260250 0.632962 +0.264042 0.633657 +0.299772 0.633331 +0.303564 0.634025 +0.339294 0.633699 +0.343086 0.634393 +0.378816 0.634067 +0.382608 0.634761 +0.418338 0.634435 +0.422130 0.635129 +0.457860 0.634803 +0.461652 0.635498 +0.497382 0.635171 +0.501174 0.635866 +0.536904 0.635540 +0.540696 0.636234 +0.576425 0.635908 +0.580218 0.636602 +0.615947 0.636276 +0.619740 0.636970 +0.655470 0.636644 +0.659262 0.637338 +0.694991 0.637012 +0.698784 0.637707 +0.734513 0.637380 +0.738306 0.638075 +0.774035 0.637749 +0.777828 0.638443 +0.813557 0.638117 +0.817349 0.638811 +0.853079 0.638485 +0.856871 0.639179 +0.879409 0.615741 +0.876992 0.687516 +0.866479 0.677110 +0.840633 0.679110 +0.826957 0.676742 +0.801111 0.678742 +0.787435 0.676374 +0.761589 0.678374 +0.747913 0.676005 +0.722067 0.678005 +0.708391 0.675637 +0.682545 0.677637 +0.668869 0.675269 +0.643023 0.677269 +0.629347 0.674901 +0.603502 0.676901 +0.589825 0.674533 +0.563980 0.676533 +0.550303 0.674164 +0.524458 0.676165 +0.510782 0.673796 +0.484936 0.675797 +0.471260 0.673428 +0.445414 0.675428 +0.431738 0.673060 +0.405892 0.675060 +0.392216 0.672692 +0.366370 0.674692 +0.352694 0.672324 +0.326848 0.674324 +0.313172 0.671955 +0.287326 0.673956 +0.273650 0.671587 +0.247804 0.673588 +0.234128 0.671219 +0.208282 0.673219 +0.194606 0.670851 +0.168760 0.672851 +0.158404 0.660206 +0.157915 0.626437 +0.169881 0.617840 +0.195727 0.615840 +0.209403 0.618208 +0.235249 0.616208 +0.248925 0.618576 +0.274771 0.616576 +0.288447 0.618944 +0.314293 0.616944 +0.327969 0.619313 +0.353814 0.617312 +0.367491 0.619681 +0.393336 0.617681 +0.407013 0.620049 +0.432858 0.618049 +0.446535 0.620417 +0.472380 0.618417 +0.486057 0.620785 +0.511902 0.618785 +0.525578 0.621154 +0.551424 0.619153 +0.565100 0.621522 +0.590946 0.619521 +0.604622 0.621890 +0.630468 0.619890 +0.644144 0.622258 +0.669990 0.620258 +0.683666 0.622626 +0.709512 0.620626 +0.723188 0.622994 +0.749034 0.620994 +0.762710 0.623363 +0.788556 0.621362 +0.802232 0.623731 +0.828078 0.621731 +0.841754 0.624099 +0.867600 0.622099 +0.853891 0.662918 +0.852637 0.662700 +0.866553 0.679352 +0.840221 0.681399 +0.866882 0.681647 +0.839539 0.683598 +0.867483 0.683858 +0.838605 0.685559 +0.814369 0.662550 +0.813115 0.662332 +0.827031 0.678983 +0.800699 0.681030 +0.827360 0.681279 +0.800017 0.683230 +0.827961 0.683490 +0.799083 0.685190 +0.774848 0.662181 +0.773593 0.661964 +0.787509 0.678615 +0.761177 0.680662 +0.787838 0.680911 +0.760495 0.682862 +0.788439 0.683122 +0.759561 0.684822 +0.735325 0.661813 +0.734071 0.661596 +0.747988 0.678247 +0.721655 0.680294 +0.748316 0.680542 +0.720973 0.682494 +0.748917 0.682754 +0.720039 0.684454 +0.695804 0.661445 +0.694549 0.661228 +0.708466 0.677879 +0.682134 0.679926 +0.708794 0.680174 +0.681451 0.682125 +0.709395 0.682386 +0.680517 0.684086 +0.656282 0.661077 +0.655027 0.660860 +0.668944 0.677511 +0.642612 0.679558 +0.669272 0.679806 +0.641930 0.681757 +0.669873 0.682018 +0.640995 0.683718 +0.616760 0.660709 +0.615505 0.660491 +0.629422 0.677142 +0.603090 0.679189 +0.629750 0.679438 +0.602408 0.681389 +0.630352 0.681649 +0.601473 0.683350 +0.577238 0.660340 +0.575983 0.660123 +0.589900 0.676774 +0.563568 0.678821 +0.590228 0.679070 +0.562886 0.681021 +0.590830 0.681281 +0.561951 0.682981 +0.537716 0.659972 +0.536461 0.659755 +0.550378 0.676406 +0.524046 0.678453 +0.550706 0.678702 +0.523364 0.680653 +0.551308 0.680913 +0.522429 0.682613 +0.498194 0.659604 +0.496939 0.659387 +0.510856 0.676038 +0.484524 0.678085 +0.511184 0.678333 +0.483842 0.680284 +0.511786 0.680545 +0.482907 0.682245 +0.458672 0.659236 +0.457417 0.659019 +0.471334 0.675670 +0.445002 0.677717 +0.471662 0.677965 +0.444320 0.679916 +0.472264 0.680177 +0.443386 0.681877 +0.419150 0.658868 +0.417895 0.658651 +0.431812 0.675302 +0.405480 0.677349 +0.432140 0.677597 +0.404798 0.679548 +0.432742 0.679808 +0.403864 0.681509 +0.379628 0.658500 +0.378373 0.658282 +0.392290 0.674933 +0.365958 0.676980 +0.392619 0.677229 +0.365276 0.679180 +0.393220 0.679440 +0.364342 0.681140 +0.340106 0.658132 +0.338851 0.657914 +0.352768 0.674565 +0.326436 0.676612 +0.353097 0.676861 +0.325754 0.678812 +0.353698 0.679072 +0.324820 0.680772 +0.300584 0.657763 +0.299330 0.657546 +0.313246 0.674197 +0.286914 0.676244 +0.313575 0.676493 +0.286232 0.678444 +0.314176 0.678704 +0.285298 0.680404 +0.261063 0.657395 +0.259808 0.657178 +0.273724 0.673829 +0.247392 0.675876 +0.274053 0.676124 +0.246710 0.678075 +0.274654 0.678336 +0.245776 0.680036 +0.221541 0.657027 +0.220286 0.656810 +0.234203 0.673461 +0.207870 0.675508 +0.234531 0.675756 +0.207188 0.677707 +0.235132 0.677968 +0.206254 0.679668 +0.182019 0.656659 +0.180764 0.656442 +0.194681 0.673093 +0.168348 0.675140 +0.195009 0.675388 +0.167666 0.677339 +0.195610 0.677599 +0.166732 0.679300 +0.182469 0.632032 +0.183723 0.632249 +0.169807 0.615598 +0.196139 0.613551 +0.169478 0.613303 +0.196821 0.611352 +0.168877 0.611091 +0.197755 0.609391 +0.221991 0.632400 +0.223245 0.632618 +0.209329 0.615966 +0.235661 0.613919 +0.209000 0.613671 +0.236343 0.611720 +0.208399 0.611460 +0.237277 0.609760 +0.261513 0.632768 +0.262767 0.632986 +0.248850 0.616335 +0.275183 0.614288 +0.248522 0.614039 +0.275865 0.612088 +0.247921 0.611828 +0.276799 0.610128 +0.301034 0.633137 +0.302289 0.633354 +0.288372 0.616703 +0.314705 0.614656 +0.288044 0.614408 +0.315387 0.612456 +0.287443 0.612196 +0.316321 0.610496 +0.340556 0.633505 +0.341811 0.633722 +0.327894 0.617071 +0.354226 0.615024 +0.327566 0.614776 +0.354909 0.612824 +0.326964 0.612564 +0.355843 0.610864 +0.380078 0.633873 +0.381333 0.634090 +0.367416 0.617439 +0.393748 0.615392 +0.367088 0.615144 +0.394431 0.613193 +0.366486 0.612932 +0.395365 0.611232 +0.419600 0.634241 +0.420855 0.634458 +0.406938 0.617807 +0.433270 0.615760 +0.406610 0.615512 +0.433952 0.613561 +0.406008 0.613301 +0.434887 0.611600 +0.459122 0.634609 +0.460377 0.634827 +0.446460 0.618176 +0.472792 0.616129 +0.446132 0.615880 +0.473474 0.613929 +0.445530 0.613669 +0.474409 0.611969 +0.498644 0.634977 +0.499899 0.635195 +0.485982 0.618544 +0.512314 0.616497 +0.485654 0.616248 +0.512996 0.614297 +0.485052 0.614037 +0.513931 0.612337 +0.538166 0.635346 +0.539421 0.635563 +0.525504 0.618912 +0.551836 0.616865 +0.525176 0.616617 +0.552518 0.614665 +0.524574 0.614405 +0.553452 0.612705 +0.577688 0.635714 +0.578943 0.635931 +0.565026 0.619280 +0.591358 0.617233 +0.564698 0.616985 +0.592040 0.615034 +0.564096 0.614773 +0.592974 0.613073 +0.617210 0.636082 +0.618464 0.636299 +0.604548 0.619648 +0.630880 0.617601 +0.604219 0.617353 +0.631562 0.615402 +0.603618 0.615141 +0.632496 0.613441 +0.656732 0.636450 +0.657986 0.636667 +0.644070 0.620016 +0.670402 0.617969 +0.643741 0.617721 +0.671084 0.615770 +0.643140 0.615510 +0.672018 0.613809 +0.696254 0.636818 +0.697508 0.637036 +0.683592 0.620385 +0.709924 0.618338 +0.683263 0.618089 +0.710606 0.616138 +0.682662 0.615878 +0.711540 0.614178 +0.735776 0.637187 +0.737030 0.637404 +0.723114 0.620753 +0.749446 0.618706 +0.722785 0.618457 +0.750128 0.616506 +0.722184 0.616246 +0.751062 0.614546 +0.775298 0.637555 +0.776552 0.637772 +0.762635 0.621121 +0.788968 0.619074 +0.762307 0.618826 +0.789650 0.616874 +0.761706 0.616614 +0.790584 0.614914 +0.814819 0.637923 +0.816074 0.638140 +0.802157 0.621489 +0.828490 0.619442 +0.801829 0.619194 +0.829172 0.617243 +0.801228 0.616982 +0.830106 0.615282 +0.854341 0.638291 +0.855596 0.638508 +0.841679 0.621857 +0.868011 0.619810 +0.841351 0.619562 +0.868693 0.617611 +0.840750 0.617350 +0.869628 0.615650 +0.878332 0.614132 +0.875732 0.688647 +0.868345 0.685836 +0.837470 0.687148 +0.828824 0.685467 +0.797948 0.686779 +0.789302 0.685099 +0.758426 0.686411 +0.749780 0.684731 +0.718904 0.686043 +0.710258 0.684363 +0.679382 0.685675 +0.670736 0.683995 +0.639860 0.685307 +0.631214 0.683627 +0.600338 0.684938 +0.591692 0.683258 +0.560816 0.684570 +0.552170 0.682890 +0.521294 0.684202 +0.512648 0.682522 +0.481772 0.683834 +0.473126 0.682154 +0.442250 0.683466 +0.433604 0.681786 +0.402728 0.683098 +0.394082 0.681418 +0.363207 0.682730 +0.354560 0.681049 +0.323685 0.682361 +0.315039 0.680681 +0.284163 0.681993 +0.275517 0.680313 +0.244641 0.681625 +0.235995 0.679945 +0.205119 0.681257 +0.196473 0.679577 +0.165597 0.680889 +0.157269 0.661795 +0.157053 0.624460 +0.168014 0.609114 +0.198890 0.607802 +0.207536 0.609482 +0.238412 0.608171 +0.247058 0.609851 +0.277934 0.608539 +0.286580 0.610219 +0.317456 0.608907 +0.326102 0.610587 +0.356978 0.609275 +0.365624 0.610955 +0.396500 0.609643 +0.405146 0.611323 +0.436022 0.610011 +0.444668 0.611691 +0.475544 0.610379 +0.484190 0.612060 +0.515066 0.610748 +0.523712 0.612428 +0.554588 0.611116 +0.563234 0.612796 +0.594110 0.611484 +0.602756 0.613164 +0.633631 0.611852 +0.642277 0.613532 +0.673153 0.612220 +0.681800 0.613901 +0.712675 0.612589 +0.721321 0.614269 +0.752197 0.612957 +0.760843 0.614637 +0.791719 0.613325 +0.800365 0.615005 +0.831241 0.613693 +0.839887 0.615373 +0.870763 0.614061 +0.877115 0.612978 +0.874432 0.689294 +0.869422 0.687445 +0.836210 0.688279 +0.829900 0.687077 +0.796688 0.687910 +0.790378 0.686709 +0.757166 0.687542 +0.750856 0.686341 +0.717644 0.687174 +0.711334 0.685973 +0.678122 0.686806 +0.671813 0.685604 +0.638600 0.686438 +0.632290 0.685236 +0.599078 0.686070 +0.592769 0.684868 +0.559556 0.685701 +0.553247 0.684500 +0.520034 0.685333 +0.513725 0.684132 +0.480513 0.684965 +0.474203 0.683764 +0.440991 0.684597 +0.434681 0.683395 +0.401469 0.684229 +0.395159 0.683027 +0.361947 0.683861 +0.355637 0.682659 +0.322425 0.683492 +0.316115 0.682291 +0.282903 0.683124 +0.276593 0.681923 +0.243381 0.682756 +0.237071 0.681554 +0.203859 0.682388 +0.197549 0.681186 +0.164337 0.682020 +0.156335 0.663755 +0.156451 0.622248 +0.166938 0.607505 +0.200150 0.606671 +0.206460 0.607873 +0.239672 0.607039 +0.245982 0.608241 +0.279194 0.607408 +0.285504 0.608609 +0.318716 0.607776 +0.325025 0.608977 +0.358238 0.608144 +0.364547 0.609345 +0.397760 0.608512 +0.404069 0.609714 +0.437282 0.608880 +0.443591 0.610082 +0.476803 0.609248 +0.483113 0.610450 +0.516325 0.609617 +0.522635 0.610818 +0.555847 0.609985 +0.562157 0.611186 +0.595369 0.610353 +0.601679 0.611554 +0.634891 0.610721 +0.641201 0.611923 +0.674413 0.611089 +0.680723 0.612291 +0.713935 0.611457 +0.720245 0.612659 +0.753457 0.611826 +0.759767 0.613027 +0.792979 0.612194 +0.799289 0.613395 +0.832501 0.612562 +0.838810 0.613764 +0.872023 0.612930 +0.870640 0.688599 +0.831118 0.688231 +0.791596 0.687863 +0.752074 0.687495 +0.712552 0.687127 +0.834911 0.688926 +0.795389 0.688558 +0.755867 0.688189 +0.716345 0.687821 +0.676823 0.687453 +0.673030 0.686759 +0.633508 0.686390 +0.593987 0.686022 +0.637301 0.687085 +0.597779 0.686717 +0.558257 0.686348 +0.554465 0.685654 +0.514943 0.685286 +0.475421 0.684918 +0.435899 0.684550 +0.518735 0.685980 +0.479213 0.685612 +0.439691 0.685244 +0.400169 0.684876 +0.396377 0.684181 +0.356855 0.683813 +0.317333 0.683445 +0.360647 0.684507 +0.321126 0.684139 +0.281604 0.683771 +0.277811 0.683077 +0.238289 0.682709 +0.198767 0.682340 +0.155653 0.665955 +0.242082 0.683403 +0.202560 0.683035 +0.163038 0.682667 +0.156123 0.619953 +0.165720 0.606350 +0.205242 0.606719 +0.244764 0.607087 +0.201449 0.606024 +0.240971 0.606392 +0.280493 0.606761 +0.284286 0.607455 +0.323808 0.607823 +0.363329 0.608191 +0.402851 0.608559 +0.320015 0.607129 +0.359537 0.607497 +0.399059 0.607865 +0.438581 0.608233 +0.442373 0.608928 +0.481895 0.609296 +0.521417 0.609664 +0.478103 0.608601 +0.517625 0.608970 +0.557147 0.609338 +0.560939 0.610032 +0.600461 0.610400 +0.639983 0.610769 +0.679505 0.611137 +0.596669 0.609706 +0.636191 0.610074 +0.675712 0.610442 +0.715235 0.610811 +0.719027 0.611505 +0.758549 0.611873 +0.798071 0.612241 +0.754756 0.611179 +0.794278 0.611547 +0.833800 0.611915 +0.837592 0.612609 +0.873322 0.612283 +0.875839 0.612307 +0.126857 0.592808 +0.874584 0.612089 +0.873170 0.689488 +0.909503 0.702142 +0.871915 0.689270 +0.833648 0.689119 +0.832393 0.688902 +0.794126 0.688751 +0.792872 0.688534 +0.754604 0.688383 +0.753350 0.688166 +0.715082 0.688015 +0.713828 0.687798 +0.675560 0.687647 +0.674306 0.687429 +0.636039 0.687279 +0.634784 0.687061 +0.596517 0.686910 +0.595262 0.686693 +0.556995 0.686542 +0.555740 0.686325 +0.517473 0.686174 +0.516218 0.685957 +0.477951 0.685806 +0.476696 0.685589 +0.438429 0.685438 +0.437174 0.685220 +0.398907 0.685069 +0.397652 0.684852 +0.359385 0.684701 +0.358130 0.684484 +0.319863 0.684333 +0.318608 0.684116 +0.280341 0.683965 +0.279087 0.683748 +0.240819 0.683597 +0.239565 0.683380 +0.201297 0.683229 +0.200043 0.683011 +0.161776 0.682861 +0.160521 0.682643 +0.159245 0.681972 +0.158027 0.680818 +0.156951 0.679208 +0.156088 0.677231 +0.124993 0.694833 +0.155487 0.675020 +0.155159 0.672724 +0.155084 0.670483 +0.155241 0.668243 +0.156048 0.617711 +0.156205 0.615472 +0.156617 0.613183 +0.157299 0.610984 +0.158233 0.609023 +0.159368 0.607434 +0.160628 0.606303 +0.161927 0.605656 +0.163190 0.605462 +0.164445 0.605680 +0.202712 0.605830 +0.203966 0.606048 +0.242234 0.606199 +0.243488 0.606416 +0.283010 0.606784 +0.322532 0.607152 +0.362054 0.607520 +0.401576 0.607889 +0.281756 0.606567 +0.321277 0.606935 +0.360799 0.607303 +0.400321 0.607671 +0.439843 0.608039 +0.441098 0.608257 +0.480620 0.608625 +0.520142 0.608993 +0.479365 0.608408 +0.518887 0.608776 +0.558409 0.609144 +0.559664 0.609361 +0.599186 0.609729 +0.638708 0.610098 +0.678229 0.610466 +0.597931 0.609512 +0.637453 0.609880 +0.676975 0.610248 +0.716497 0.610617 +0.717752 0.610834 +0.757273 0.611202 +0.796795 0.611570 +0.756019 0.610985 +0.795541 0.611353 +0.835062 0.611721 +0.836317 0.611938 +0.524458 0.676165 +0.524614 0.673925 +0.524614 0.673925 +0.524458 0.676165 +0.510782 0.673796 +0.510782 0.673796 +0.510856 0.676038 +0.511184 0.678333 +0.510856 0.676038 +0.511786 0.680545 +0.511184 0.678333 +0.512648 0.682522 +0.511786 0.680545 +0.513725 0.684132 +0.512648 0.682522 +0.513725 0.684132 +0.514943 0.685286 +0.516218 0.685957 +0.514943 0.685286 +0.517473 0.686174 +0.516218 0.685957 +0.517473 0.686174 +0.518735 0.685980 +0.518735 0.685980 +0.520034 0.685333 +0.520034 0.685333 +0.521294 0.684202 +0.521294 0.684202 +0.522429 0.682613 +0.522429 0.682613 +0.523364 0.680653 +0.524046 0.678453 +0.523364 0.680653 +0.524046 0.678453 +0.525422 0.623393 +0.525422 0.623393 +0.525578 0.621154 +0.525578 0.621154 +0.511746 0.621025 +0.511746 0.621025 +0.511820 0.623266 +0.512148 0.625562 +0.511820 0.623266 +0.512750 0.627773 +0.512148 0.625562 +0.513612 0.629750 +0.512750 0.627773 +0.514689 0.631360 +0.513612 0.629750 +0.515907 0.632514 +0.514689 0.631360 +0.515907 0.632514 +0.517182 0.633185 +0.517182 0.633185 +0.518437 0.633403 +0.518437 0.633403 +0.519699 0.633209 +0.519699 0.633209 +0.520999 0.632562 +0.520999 0.632562 +0.522258 0.631431 +0.522258 0.631431 +0.523394 0.629842 +0.523394 0.629842 +0.524328 0.627881 +0.525010 0.625682 +0.524328 0.627881 +0.525010 0.625682 +0.563980 0.676533 +0.563980 0.676533 +0.564136 0.674293 +0.564136 0.674293 +0.550303 0.674164 +0.550303 0.674164 +0.550378 0.676406 +0.550378 0.676406 +0.550706 0.678702 +0.551308 0.680913 +0.550706 0.678702 +0.551308 0.680913 +0.552170 0.682890 +0.552170 0.682890 +0.553247 0.684500 +0.554465 0.685654 +0.553247 0.684500 +0.554465 0.685654 +0.555740 0.686325 +0.555740 0.686325 +0.556995 0.686542 +0.556995 0.686542 +0.558257 0.686348 +0.558257 0.686348 +0.559556 0.685701 +0.559556 0.685701 +0.560816 0.684570 +0.560816 0.684570 +0.561951 0.682981 +0.561951 0.682981 +0.562886 0.681021 +0.562886 0.681021 +0.563568 0.678821 +0.563568 0.678821 +0.564944 0.623761 +0.564944 0.623761 +0.565100 0.621522 +0.565100 0.621522 +0.551268 0.621393 +0.551268 0.621393 +0.551342 0.623635 +0.551670 0.625930 +0.551342 0.623635 +0.551670 0.625930 +0.552272 0.628141 +0.553134 0.630119 +0.552272 0.628141 +0.553134 0.630119 +0.554211 0.631728 +0.554211 0.631728 +0.555429 0.632882 +0.556704 0.633553 +0.555429 0.632882 +0.557959 0.633771 +0.556704 0.633553 +0.559221 0.633577 +0.557959 0.633771 +0.559221 0.633577 +0.560521 0.632930 +0.560521 0.632930 +0.561780 0.631799 +0.562916 0.630210 +0.561780 0.631799 +0.562916 0.630210 +0.563850 0.628249 +0.563850 0.628249 +0.564532 0.626050 +0.564532 0.626050 +0.601473 0.683350 +0.603502 0.676901 +0.603658 0.674662 +0.603658 0.674662 +0.603090 0.679189 +0.603502 0.676901 +0.603090 0.679189 +0.602408 0.681389 +0.602408 0.681389 +0.601473 0.683350 +0.589825 0.674533 +0.589825 0.674533 +0.589900 0.676774 +0.590228 0.679070 +0.589900 0.676774 +0.590228 0.679070 +0.590830 0.681281 +0.590830 0.681281 +0.591692 0.683258 +0.592769 0.684868 +0.591692 0.683258 +0.592769 0.684868 +0.593987 0.686022 +0.595262 0.686693 +0.593987 0.686022 +0.595262 0.686693 +0.596517 0.686910 +0.596517 0.686910 +0.597779 0.686717 +0.597779 0.686717 +0.599078 0.686070 +0.599078 0.686070 +0.600338 0.684938 +0.600338 0.684938 +0.591192 0.626298 +0.590864 0.624003 +0.590790 0.621761 +0.590790 0.621761 +0.591192 0.626298 +0.590864 0.624003 +0.604622 0.621890 +0.604622 0.621890 +0.604466 0.624129 +0.604054 0.626418 +0.604466 0.624129 +0.603372 0.628617 +0.604054 0.626418 +0.603372 0.628617 +0.602437 0.630578 +0.602437 0.630578 +0.601302 0.632167 +0.601302 0.632167 +0.600043 0.633298 +0.600043 0.633298 +0.598743 0.633945 +0.598743 0.633945 +0.597481 0.634139 +0.597481 0.634139 +0.596226 0.633922 +0.596226 0.633922 +0.594951 0.633251 +0.594951 0.633251 +0.593733 0.632096 +0.593733 0.632096 +0.592656 0.630487 +0.592656 0.630487 +0.591794 0.628510 +0.591794 0.628510 +0.629750 0.679438 +0.629422 0.677142 +0.629347 0.674901 +0.629347 0.674901 +0.629750 0.679438 +0.629422 0.677142 +0.643023 0.677269 +0.643180 0.675030 +0.643180 0.675030 +0.642612 0.679558 +0.643023 0.677269 +0.642612 0.679558 +0.641930 0.681757 +0.641930 0.681757 +0.640995 0.683718 +0.640995 0.683718 +0.639860 0.685307 +0.639860 0.685307 +0.638600 0.686438 +0.637301 0.687085 +0.638600 0.686438 +0.637301 0.687085 +0.636039 0.687279 +0.636039 0.687279 +0.634784 0.687061 +0.634784 0.687061 +0.633508 0.686390 +0.633508 0.686390 +0.632290 0.685236 +0.632290 0.685236 +0.631214 0.683627 +0.631214 0.683627 +0.630352 0.681649 +0.630352 0.681649 +0.644144 0.622258 +0.644144 0.622258 +0.630386 0.624371 +0.630311 0.622129 +0.630311 0.622129 +0.630386 0.624371 +0.630714 0.626666 +0.630714 0.626666 +0.631316 0.628878 +0.632178 0.630855 +0.631316 0.628878 +0.633255 0.632465 +0.632178 0.630855 +0.634473 0.633619 +0.633255 0.632465 +0.635748 0.634290 +0.634473 0.633619 +0.637003 0.634507 +0.635748 0.634290 +0.638265 0.634313 +0.637003 0.634507 +0.638265 0.634313 +0.639565 0.633666 +0.640824 0.632535 +0.639565 0.633666 +0.641959 0.630946 +0.640824 0.632535 +0.642894 0.628986 +0.641959 0.630946 +0.642894 0.628986 +0.643576 0.626786 +0.643576 0.626786 +0.643988 0.624498 +0.643988 0.624498 +0.676823 0.687453 +0.668944 0.677511 +0.668869 0.675269 +0.668869 0.675269 +0.668944 0.677511 +0.669272 0.679806 +0.669873 0.682018 +0.669272 0.679806 +0.669873 0.682018 +0.670736 0.683995 +0.671813 0.685604 +0.670736 0.683995 +0.673030 0.686759 +0.671813 0.685604 +0.674306 0.687429 +0.673030 0.686759 +0.675560 0.687647 +0.674306 0.687429 +0.682545 0.677637 +0.682702 0.675398 +0.682702 0.675398 +0.682134 0.679926 +0.682545 0.677637 +0.681451 0.682125 +0.682134 0.679926 +0.681451 0.682125 +0.680517 0.684086 +0.680517 0.684086 +0.679382 0.685675 +0.678122 0.686806 +0.679382 0.685675 +0.678122 0.686806 +0.676823 0.687453 +0.675560 0.687647 +0.683666 0.622626 +0.683666 0.622626 +0.669833 0.622497 +0.669833 0.622497 +0.669908 0.624739 +0.669908 0.624739 +0.670236 0.627034 +0.670236 0.627034 +0.670838 0.629246 +0.671700 0.631223 +0.670838 0.629246 +0.672777 0.632833 +0.671700 0.631223 +0.673995 0.633987 +0.672777 0.632833 +0.675270 0.634658 +0.673995 0.633987 +0.675270 0.634658 +0.676525 0.634875 +0.677787 0.634681 +0.676525 0.634875 +0.679086 0.634034 +0.677787 0.634681 +0.680346 0.632903 +0.679086 0.634034 +0.681481 0.631314 +0.680346 0.632903 +0.681481 0.631314 +0.682416 0.629354 +0.682416 0.629354 +0.683098 0.627154 +0.683098 0.627154 +0.683510 0.624866 +0.683510 0.624866 +0.722067 0.678005 +0.722224 0.675766 +0.722224 0.675766 +0.722067 0.678005 +0.708391 0.675637 +0.708391 0.675637 +0.708466 0.677879 +0.708466 0.677879 +0.708794 0.680174 +0.708794 0.680174 +0.709395 0.682386 +0.710258 0.684363 +0.709395 0.682386 +0.711334 0.685973 +0.710258 0.684363 +0.712552 0.687127 +0.711334 0.685973 +0.712552 0.687127 +0.713828 0.687798 +0.713828 0.687798 +0.715082 0.688015 +0.716345 0.687821 +0.715082 0.688015 +0.717644 0.687174 +0.716345 0.687821 +0.718904 0.686043 +0.717644 0.687174 +0.718904 0.686043 +0.720039 0.684454 +0.720973 0.682494 +0.720039 0.684454 +0.720973 0.682494 +0.721655 0.680294 +0.721655 0.680294 +0.723188 0.622994 +0.723188 0.622994 +0.709355 0.622866 +0.709355 0.622866 +0.709430 0.625107 +0.709430 0.625107 +0.709758 0.627403 +0.709758 0.627403 +0.710360 0.629614 +0.711222 0.631591 +0.710360 0.629614 +0.712299 0.633201 +0.711222 0.631591 +0.713517 0.634355 +0.712299 0.633201 +0.714792 0.635026 +0.713517 0.634355 +0.716047 0.635243 +0.714792 0.635026 +0.717309 0.635050 +0.716047 0.635243 +0.717309 0.635050 +0.718608 0.634403 +0.719868 0.633272 +0.718608 0.634403 +0.719868 0.633272 +0.721003 0.631682 +0.721003 0.631682 +0.721938 0.629722 +0.721938 0.629722 +0.722620 0.627522 +0.722620 0.627522 +0.723032 0.625234 +0.723032 0.625234 +0.761746 0.676134 +0.761746 0.676134 +0.747988 0.678247 +0.747913 0.676005 +0.747913 0.676005 +0.747988 0.678247 +0.748316 0.680542 +0.748316 0.680542 +0.748917 0.682754 +0.749780 0.684731 +0.748917 0.682754 +0.750856 0.686341 +0.749780 0.684731 +0.752074 0.687495 +0.750856 0.686341 +0.753350 0.688166 +0.752074 0.687495 +0.753350 0.688166 +0.754604 0.688383 +0.755867 0.688189 +0.754604 0.688383 +0.755867 0.688189 +0.757166 0.687542 +0.758426 0.686411 +0.757166 0.687542 +0.758426 0.686411 +0.759561 0.684822 +0.759561 0.684822 +0.760495 0.682862 +0.760495 0.682862 +0.761177 0.680662 +0.761177 0.680662 +0.761589 0.678374 +0.761589 0.678374 +0.762710 0.623363 +0.762710 0.623363 +0.748952 0.625475 +0.748877 0.623234 +0.748877 0.623234 +0.749280 0.627771 +0.748952 0.625475 +0.749882 0.629982 +0.749280 0.627771 +0.750744 0.631959 +0.749882 0.629982 +0.751821 0.633569 +0.750744 0.631959 +0.751821 0.633569 +0.753039 0.634723 +0.753039 0.634723 +0.754314 0.635394 +0.754314 0.635394 +0.755569 0.635612 +0.755569 0.635612 +0.756831 0.635418 +0.756831 0.635418 +0.758130 0.634771 +0.758130 0.634771 +0.759390 0.633640 +0.760525 0.632051 +0.759390 0.633640 +0.760525 0.632051 +0.761459 0.630090 +0.761459 0.630090 +0.762142 0.627891 +0.762142 0.627891 +0.762554 0.625602 +0.762554 0.625602 +0.800699 0.681030 +0.801111 0.678742 +0.801268 0.676502 +0.801268 0.676502 +0.787435 0.676374 +0.787435 0.676374 +0.787509 0.678615 +0.787838 0.680911 +0.787509 0.678615 +0.788439 0.683122 +0.787838 0.680911 +0.789302 0.685099 +0.788439 0.683122 +0.789302 0.685099 +0.790378 0.686709 +0.790378 0.686709 +0.791596 0.687863 +0.791596 0.687863 +0.792872 0.688534 +0.792872 0.688534 +0.794126 0.688751 +0.795389 0.688558 +0.794126 0.688751 +0.796688 0.687910 +0.795389 0.688558 +0.797948 0.686779 +0.796688 0.687910 +0.799083 0.685190 +0.797948 0.686779 +0.799083 0.685190 +0.800017 0.683230 +0.800699 0.681030 +0.800017 0.683230 +0.801111 0.678742 +0.802076 0.625970 +0.802232 0.623731 +0.802232 0.623731 +0.802076 0.625970 +0.788399 0.623602 +0.788399 0.623602 +0.788474 0.625844 +0.788474 0.625844 +0.788802 0.628139 +0.788802 0.628139 +0.789404 0.630350 +0.790266 0.632328 +0.789404 0.630350 +0.790266 0.632328 +0.791342 0.633937 +0.792560 0.635091 +0.791342 0.633937 +0.793836 0.635762 +0.792560 0.635091 +0.795090 0.635980 +0.793836 0.635762 +0.795090 0.635980 +0.796353 0.635786 +0.797652 0.635139 +0.796353 0.635786 +0.797652 0.635139 +0.798912 0.634008 +0.798912 0.634008 +0.800047 0.632419 +0.800047 0.632419 +0.800981 0.630458 +0.800981 0.630458 +0.801664 0.628259 +0.801664 0.628259 +0.840633 0.679110 +0.840790 0.676870 +0.840790 0.676870 +0.840633 0.679110 +0.826957 0.676742 +0.826957 0.676742 +0.827031 0.678983 +0.827360 0.681279 +0.827031 0.678983 +0.827961 0.683490 +0.827360 0.681279 +0.827961 0.683490 +0.828824 0.685467 +0.828824 0.685467 +0.829900 0.687077 +0.829900 0.687077 +0.831118 0.688231 +0.831118 0.688231 +0.832393 0.688902 +0.832393 0.688902 +0.833648 0.689119 +0.833648 0.689119 +0.834911 0.688926 +0.834911 0.688926 +0.836210 0.688279 +0.836210 0.688279 +0.837470 0.687148 +0.837470 0.687148 +0.838605 0.685559 +0.839539 0.683598 +0.838605 0.685559 +0.839539 0.683598 +0.840221 0.681399 +0.840221 0.681399 +0.841754 0.624099 +0.841754 0.624099 +0.827996 0.626212 +0.827921 0.623970 +0.827921 0.623970 +0.827996 0.626212 +0.828324 0.628507 +0.828324 0.628507 +0.828925 0.630719 +0.828925 0.630719 +0.829788 0.632696 +0.829788 0.632696 +0.830864 0.634305 +0.830864 0.634305 +0.832082 0.635460 +0.832082 0.635460 +0.833358 0.636131 +0.833358 0.636131 +0.834612 0.636348 +0.834612 0.636348 +0.835875 0.636154 +0.835875 0.636154 +0.837174 0.635507 +0.837174 0.635507 +0.838434 0.634376 +0.838434 0.634376 +0.839569 0.632787 +0.839569 0.632787 +0.840503 0.630826 +0.840503 0.630826 +0.841185 0.628627 +0.841185 0.628627 +0.841598 0.626338 +0.841598 0.626338 +0.880311 0.677239 +0.880311 0.677239 +0.866479 0.677110 +0.866479 0.677110 +0.866553 0.679352 +0.866882 0.681647 +0.866553 0.679352 +0.867483 0.683858 +0.866882 0.681647 +0.868345 0.685836 +0.867483 0.683858 +0.869422 0.687445 +0.868345 0.685836 +0.869422 0.687445 +0.870640 0.688599 +0.870640 0.688599 +0.871915 0.689270 +0.871915 0.689270 +0.873170 0.689488 +0.874432 0.689294 +0.873170 0.689488 +0.874432 0.689294 +0.875732 0.688647 +0.876992 0.687516 +0.875732 0.688647 +0.878127 0.685927 +0.876992 0.687516 +0.879061 0.683966 +0.878127 0.685927 +0.879743 0.681767 +0.879061 0.683966 +0.879743 0.681767 +0.880155 0.679478 +0.880155 0.679478 +0.867518 0.626580 +0.867443 0.624338 +0.881119 0.626707 +0.881276 0.624467 +0.881276 0.624467 +0.881119 0.626707 +0.880707 0.628995 +0.880707 0.628995 +0.880025 0.631195 +0.880025 0.631195 +0.879091 0.633155 +0.879091 0.633155 +0.877956 0.634744 +0.877956 0.634744 +0.876696 0.635875 +0.875397 0.636522 +0.876696 0.635875 +0.875397 0.636522 +0.874134 0.636716 +0.874134 0.636716 +0.872880 0.636499 +0.872880 0.636499 +0.871604 0.635828 +0.871604 0.635828 +0.870386 0.634674 +0.869310 0.633064 +0.870386 0.634674 +0.868447 0.631087 +0.869310 0.633064 +0.867846 0.628875 +0.868447 0.631087 +0.867518 0.626580 +0.867846 0.628875 +0.867443 0.624338 +0.484936 0.675797 +0.485092 0.673557 +0.485092 0.673557 +0.484936 0.675797 +0.471260 0.673428 +0.471260 0.673428 +0.471334 0.675670 +0.471334 0.675670 +0.471662 0.677965 +0.471662 0.677965 +0.472264 0.680177 +0.473126 0.682154 +0.472264 0.680177 +0.473126 0.682154 +0.474203 0.683764 +0.474203 0.683764 +0.475421 0.684918 +0.475421 0.684918 +0.476696 0.685589 +0.476696 0.685589 +0.477951 0.685806 +0.477951 0.685806 +0.479213 0.685612 +0.479213 0.685612 +0.480513 0.684965 +0.480513 0.684965 +0.481772 0.683834 +0.481772 0.683834 +0.482907 0.682245 +0.482907 0.682245 +0.483842 0.680284 +0.483842 0.680284 +0.484524 0.678085 +0.484524 0.678085 +0.484806 0.627513 +0.485900 0.623025 +0.486057 0.620785 +0.486057 0.620785 +0.485900 0.623025 +0.485488 0.625313 +0.484806 0.627513 +0.485488 0.625313 +0.472224 0.620657 +0.472224 0.620657 +0.472298 0.622898 +0.472627 0.625194 +0.472298 0.622898 +0.472627 0.625194 +0.473228 0.627405 +0.474091 0.629382 +0.473228 0.627405 +0.475167 0.630992 +0.474091 0.629382 +0.475167 0.630992 +0.476385 0.632146 +0.476385 0.632146 +0.477660 0.632817 +0.477660 0.632817 +0.478915 0.633034 +0.478915 0.633034 +0.480177 0.632841 +0.480177 0.632841 +0.481477 0.632194 +0.481477 0.632194 +0.482737 0.631062 +0.482737 0.631062 +0.483872 0.629473 +0.483872 0.629473 +0.445002 0.677717 +0.445570 0.673189 +0.445570 0.673189 +0.445414 0.675428 +0.445414 0.675428 +0.445002 0.677717 +0.431738 0.673060 +0.431738 0.673060 +0.431812 0.675302 +0.431812 0.675302 +0.432140 0.677597 +0.432140 0.677597 +0.432742 0.679808 +0.433604 0.681786 +0.432742 0.679808 +0.433604 0.681786 +0.434681 0.683395 +0.434681 0.683395 +0.435899 0.684550 +0.435899 0.684550 +0.437174 0.685220 +0.438429 0.685438 +0.437174 0.685220 +0.439691 0.685244 +0.438429 0.685438 +0.440991 0.684597 +0.439691 0.685244 +0.442250 0.683466 +0.440991 0.684597 +0.442250 0.683466 +0.443386 0.681877 +0.443386 0.681877 +0.444320 0.679916 +0.444320 0.679916 +0.446378 0.622657 +0.446378 0.622657 +0.446535 0.620417 +0.446535 0.620417 +0.432702 0.620288 +0.432702 0.620288 +0.432776 0.622530 +0.433105 0.624825 +0.432776 0.622530 +0.433706 0.627037 +0.433105 0.624825 +0.434569 0.629014 +0.433706 0.627037 +0.435645 0.630624 +0.434569 0.629014 +0.436863 0.631778 +0.435645 0.630624 +0.436863 0.631778 +0.438139 0.632449 +0.438139 0.632449 +0.439393 0.632666 +0.439393 0.632666 +0.440656 0.632472 +0.440656 0.632472 +0.441955 0.631825 +0.441955 0.631825 +0.443215 0.630694 +0.443215 0.630694 +0.444350 0.629105 +0.444350 0.629105 +0.445284 0.627145 +0.445966 0.624945 +0.445284 0.627145 +0.445966 0.624945 +0.405892 0.675060 +0.406048 0.672821 +0.406048 0.672821 +0.405892 0.675060 +0.392216 0.672692 +0.392216 0.672692 +0.392290 0.674933 +0.392619 0.677229 +0.392290 0.674933 +0.392619 0.677229 +0.393220 0.679440 +0.393220 0.679440 +0.394082 0.681418 +0.394082 0.681418 +0.395159 0.683027 +0.395159 0.683027 +0.396377 0.684181 +0.397652 0.684852 +0.396377 0.684181 +0.397652 0.684852 +0.398907 0.685069 +0.398907 0.685069 +0.400169 0.684876 +0.401469 0.684229 +0.400169 0.684876 +0.401469 0.684229 +0.402728 0.683098 +0.402728 0.683098 +0.403864 0.681509 +0.403864 0.681509 +0.404798 0.679548 +0.405480 0.677349 +0.404798 0.679548 +0.405480 0.677349 +0.406856 0.622289 +0.406856 0.622289 +0.407013 0.620049 +0.407013 0.620049 +0.393180 0.619920 +0.393180 0.619920 +0.393255 0.622162 +0.393583 0.624457 +0.393255 0.622162 +0.393583 0.624457 +0.394184 0.626669 +0.395047 0.628646 +0.394184 0.626669 +0.395047 0.628646 +0.396123 0.630256 +0.396123 0.630256 +0.397341 0.631410 +0.398617 0.632081 +0.397341 0.631410 +0.398617 0.632081 +0.399871 0.632298 +0.399871 0.632298 +0.401134 0.632104 +0.401134 0.632104 +0.402433 0.631457 +0.402433 0.631457 +0.403693 0.630326 +0.403693 0.630326 +0.404828 0.628737 +0.405762 0.626777 +0.404828 0.628737 +0.405762 0.626777 +0.406444 0.624577 +0.406444 0.624577 +0.354560 0.681049 +0.352768 0.674565 +0.352694 0.672324 +0.352694 0.672324 +0.353097 0.676861 +0.352768 0.674565 +0.353097 0.676861 +0.353698 0.679072 +0.353698 0.679072 +0.354560 0.681049 +0.366526 0.672453 +0.366526 0.672453 +0.366370 0.674692 +0.366370 0.674692 +0.365958 0.676980 +0.365958 0.676980 +0.365276 0.679180 +0.365276 0.679180 +0.364342 0.681140 +0.363207 0.682730 +0.364342 0.681140 +0.363207 0.682730 +0.361947 0.683861 +0.361947 0.683861 +0.360647 0.684507 +0.360647 0.684507 +0.359385 0.684701 +0.359385 0.684701 +0.358130 0.684484 +0.358130 0.684484 +0.356855 0.683813 +0.356855 0.683813 +0.355637 0.682659 +0.355637 0.682659 +0.367334 0.621920 +0.367334 0.621920 +0.367491 0.619681 +0.367491 0.619681 +0.353658 0.619552 +0.353658 0.619552 +0.353733 0.621794 +0.354061 0.624089 +0.353733 0.621794 +0.354662 0.626301 +0.354061 0.624089 +0.355525 0.628278 +0.354662 0.626301 +0.356601 0.629887 +0.355525 0.628278 +0.357819 0.631042 +0.356601 0.629887 +0.357819 0.631042 +0.359095 0.631712 +0.359095 0.631712 +0.360349 0.631930 +0.360349 0.631930 +0.361612 0.631736 +0.362911 0.631089 +0.361612 0.631736 +0.362911 0.631089 +0.364171 0.629958 +0.364171 0.629958 +0.365306 0.628369 +0.365306 0.628369 +0.366240 0.626408 +0.366922 0.624209 +0.366240 0.626408 +0.366922 0.624209 +0.314176 0.678704 +0.313246 0.674197 +0.313172 0.671955 +0.313172 0.671955 +0.313246 0.674197 +0.313575 0.676493 +0.326848 0.674324 +0.327005 0.672084 +0.327005 0.672084 +0.326436 0.676612 +0.326848 0.674324 +0.326436 0.676612 +0.325754 0.678812 +0.324820 0.680772 +0.325754 0.678812 +0.324820 0.680772 +0.323685 0.682361 +0.323685 0.682361 +0.322425 0.683492 +0.322425 0.683492 +0.321126 0.684139 +0.321126 0.684139 +0.319863 0.684333 +0.319863 0.684333 +0.318608 0.684116 +0.318608 0.684116 +0.317333 0.683445 +0.317333 0.683445 +0.316115 0.682291 +0.316115 0.682291 +0.315039 0.680681 +0.314176 0.678704 +0.315039 0.680681 +0.313575 0.676493 +0.326718 0.626040 +0.327812 0.621552 +0.327969 0.619313 +0.327969 0.619313 +0.327812 0.621552 +0.327400 0.623841 +0.314136 0.619184 +0.314136 0.619184 +0.314211 0.621426 +0.314539 0.623721 +0.314211 0.621426 +0.315140 0.625932 +0.314539 0.623721 +0.316003 0.627910 +0.315140 0.625932 +0.317079 0.629519 +0.316003 0.627910 +0.317079 0.629519 +0.318297 0.630673 +0.318297 0.630673 +0.319573 0.631344 +0.320828 0.631562 +0.319573 0.631344 +0.322090 0.631368 +0.320828 0.631562 +0.323389 0.630721 +0.322090 0.631368 +0.324649 0.629590 +0.323389 0.630721 +0.324649 0.629590 +0.325784 0.628001 +0.325784 0.628001 +0.326718 0.626040 +0.327400 0.623841 +0.279087 0.683748 +0.273724 0.673829 +0.273650 0.671587 +0.273650 0.671587 +0.273724 0.673829 +0.274053 0.676124 +0.274654 0.678336 +0.274053 0.676124 +0.274654 0.678336 +0.275517 0.680313 +0.275517 0.680313 +0.276593 0.681923 +0.277811 0.683077 +0.276593 0.681923 +0.279087 0.683748 +0.277811 0.683077 +0.287483 0.671716 +0.287483 0.671716 +0.287326 0.673956 +0.287326 0.673956 +0.286914 0.676244 +0.286914 0.676244 +0.286232 0.678444 +0.286232 0.678444 +0.285298 0.680404 +0.284163 0.681993 +0.285298 0.680404 +0.284163 0.681993 +0.282903 0.683124 +0.282903 0.683124 +0.281604 0.683771 +0.281604 0.683771 +0.280341 0.683965 +0.280341 0.683965 +0.287879 0.623472 +0.288291 0.621184 +0.288447 0.618944 +0.288447 0.618944 +0.287879 0.623472 +0.288291 0.621184 +0.274614 0.618816 +0.274614 0.618816 +0.274689 0.621057 +0.274689 0.621057 +0.275017 0.623353 +0.275017 0.623353 +0.275619 0.625564 +0.275619 0.625564 +0.276481 0.627541 +0.277557 0.629151 +0.276481 0.627541 +0.277557 0.629151 +0.278776 0.630305 +0.278776 0.630305 +0.280051 0.630976 +0.280051 0.630976 +0.281306 0.631194 +0.281306 0.631194 +0.282568 0.631000 +0.283867 0.630353 +0.282568 0.631000 +0.283867 0.630353 +0.285127 0.629222 +0.286262 0.627632 +0.285127 0.629222 +0.286262 0.627632 +0.287196 0.625672 +0.287196 0.625672 +0.247961 0.671348 +0.247961 0.671348 +0.234203 0.673461 +0.234128 0.671219 +0.234128 0.671219 +0.234531 0.675756 +0.234203 0.673461 +0.235132 0.677968 +0.234531 0.675756 +0.235995 0.679945 +0.235132 0.677968 +0.235995 0.679945 +0.237071 0.681554 +0.237071 0.681554 +0.238289 0.682709 +0.238289 0.682709 +0.239565 0.683380 +0.239565 0.683380 +0.240819 0.683597 +0.240819 0.683597 +0.242082 0.683403 +0.242082 0.683403 +0.243381 0.682756 +0.243381 0.682756 +0.244641 0.681625 +0.244641 0.681625 +0.245776 0.680036 +0.246710 0.678075 +0.245776 0.680036 +0.246710 0.678075 +0.247392 0.675876 +0.247804 0.673588 +0.247392 0.675876 +0.247804 0.673588 +0.248769 0.620816 +0.248925 0.618576 +0.235092 0.618447 +0.235092 0.618447 +0.235167 0.620689 +0.235167 0.620689 +0.235495 0.622984 +0.235495 0.622984 +0.236097 0.625196 +0.236097 0.625196 +0.236959 0.627173 +0.238036 0.628783 +0.236959 0.627173 +0.238036 0.628783 +0.239254 0.629937 +0.239254 0.629937 +0.240529 0.630608 +0.240529 0.630608 +0.241784 0.630825 +0.243046 0.630631 +0.241784 0.630825 +0.244345 0.629984 +0.243046 0.630631 +0.245605 0.628853 +0.244345 0.629984 +0.246740 0.627264 +0.245605 0.628853 +0.246740 0.627264 +0.247674 0.625304 +0.247674 0.625304 +0.248357 0.623104 +0.248357 0.623104 +0.248769 0.620816 +0.248925 0.618576 +0.208439 0.670980 +0.208439 0.670980 +0.194681 0.673093 +0.194606 0.670851 +0.194606 0.670851 +0.194681 0.673093 +0.195009 0.675388 +0.195610 0.677599 +0.195009 0.675388 +0.196473 0.679577 +0.195610 0.677599 +0.196473 0.679577 +0.197549 0.681186 +0.198767 0.682340 +0.197549 0.681186 +0.198767 0.682340 +0.200043 0.683011 +0.200043 0.683011 +0.201297 0.683229 +0.202560 0.683035 +0.201297 0.683229 +0.202560 0.683035 +0.203859 0.682388 +0.205119 0.681257 +0.203859 0.682388 +0.205119 0.681257 +0.206254 0.679668 +0.206254 0.679668 +0.207188 0.677707 +0.207188 0.677707 +0.207870 0.675508 +0.208282 0.673219 +0.207870 0.675508 +0.208282 0.673219 +0.209403 0.618208 +0.209403 0.618208 +0.195570 0.618079 +0.195570 0.618079 +0.195645 0.620321 +0.195645 0.620321 +0.195973 0.622616 +0.195973 0.622616 +0.196575 0.624828 +0.197437 0.626805 +0.196575 0.624828 +0.197437 0.626805 +0.198514 0.628415 +0.198514 0.628415 +0.199732 0.629569 +0.201007 0.630240 +0.199732 0.629569 +0.202262 0.630457 +0.201007 0.630240 +0.203524 0.630263 +0.202262 0.630457 +0.204823 0.629616 +0.203524 0.630263 +0.204823 0.629616 +0.206083 0.628485 +0.207218 0.626896 +0.206083 0.628485 +0.207218 0.626896 +0.208152 0.624936 +0.208152 0.624936 +0.208835 0.622736 +0.208835 0.622736 +0.209247 0.620448 +0.209247 0.620448 +0.168917 0.670612 +0.168917 0.670612 +0.155159 0.672724 +0.155084 0.670483 +0.155084 0.670483 +0.155159 0.672724 +0.155487 0.675020 +0.156088 0.677231 +0.155487 0.675020 +0.156951 0.679208 +0.156088 0.677231 +0.156951 0.679208 +0.158027 0.680818 +0.159245 0.681972 +0.158027 0.680818 +0.159245 0.681972 +0.160521 0.682643 +0.160521 0.682643 +0.161776 0.682861 +0.161776 0.682861 +0.163038 0.682667 +0.163038 0.682667 +0.164337 0.682020 +0.164337 0.682020 +0.165597 0.680889 +0.165597 0.680889 +0.166732 0.679300 +0.166732 0.679300 +0.167666 0.677339 +0.167666 0.677339 +0.168348 0.675140 +0.168760 0.672851 +0.168348 0.675140 +0.168760 0.672851 +0.169881 0.617840 +0.169881 0.617840 +0.156048 0.617711 +0.156048 0.617711 +0.156123 0.619953 +0.156451 0.622248 +0.156123 0.619953 +0.156451 0.622248 +0.157053 0.624460 +0.157915 0.626437 +0.157053 0.624460 +0.157915 0.626437 +0.158992 0.628047 +0.158992 0.628047 +0.160210 0.629201 +0.161485 0.629872 +0.160210 0.629201 +0.161485 0.629872 +0.162740 0.630089 +0.162740 0.630089 +0.164002 0.629895 +0.165301 0.629248 +0.164002 0.629895 +0.165301 0.629248 +0.166561 0.628117 +0.167696 0.626528 +0.166561 0.628117 +0.167696 0.626528 +0.168631 0.624568 +0.168631 0.624568 +0.169313 0.622368 +0.169313 0.622368 +0.169725 0.620080 +0.169725 0.620080 +0.861033 0.650669 +0.861033 0.650669 +0.847200 0.650540 +0.847200 0.650540 +0.847275 0.652782 +0.847603 0.655077 +0.847275 0.652782 +0.848204 0.657288 +0.847603 0.655077 +0.848204 0.657288 +0.849067 0.659266 +0.849067 0.659266 +0.850143 0.660875 +0.850143 0.660875 +0.851361 0.662030 +0.851361 0.662030 +0.852637 0.662700 +0.852637 0.662700 +0.853891 0.662918 +0.853891 0.662918 +0.855154 0.662724 +0.855154 0.662724 +0.856453 0.662077 +0.856453 0.662077 +0.857713 0.660946 +0.858848 0.659357 +0.857713 0.660946 +0.858848 0.659357 +0.859782 0.657396 +0.859782 0.657396 +0.860464 0.655197 +0.860464 0.655197 +0.860876 0.652908 +0.860876 0.652908 +0.821511 0.650301 +0.821511 0.650301 +0.807678 0.650172 +0.807678 0.650172 +0.807753 0.652413 +0.808081 0.654709 +0.807753 0.652413 +0.808081 0.654709 +0.808682 0.656920 +0.808682 0.656920 +0.809545 0.658898 +0.809545 0.658898 +0.810621 0.660507 +0.810621 0.660507 +0.811839 0.661661 +0.811839 0.661661 +0.813115 0.662332 +0.813115 0.662332 +0.814369 0.662550 +0.814369 0.662550 +0.815632 0.662356 +0.815632 0.662356 +0.816931 0.661709 +0.816931 0.661709 +0.818191 0.660578 +0.818191 0.660578 +0.819326 0.658989 +0.819326 0.658989 +0.820260 0.657028 +0.820942 0.654829 +0.820260 0.657028 +0.821354 0.652540 +0.820942 0.654829 +0.821354 0.652540 +0.781989 0.649933 +0.781989 0.649933 +0.768231 0.652045 +0.768156 0.649804 +0.768156 0.649804 +0.768231 0.652045 +0.768559 0.654341 +0.768559 0.654341 +0.769160 0.656552 +0.769160 0.656552 +0.770023 0.658529 +0.770023 0.658529 +0.771099 0.660139 +0.771099 0.660139 +0.772317 0.661293 +0.772317 0.661293 +0.773593 0.661964 +0.773593 0.661964 +0.774848 0.662181 +0.774848 0.662181 +0.776110 0.661988 +0.776110 0.661988 +0.777409 0.661341 +0.777409 0.661341 +0.778669 0.660210 +0.779804 0.658620 +0.778669 0.660210 +0.779804 0.658620 +0.780738 0.656660 +0.780738 0.656660 +0.781420 0.654460 +0.781420 0.654460 +0.781832 0.652172 +0.781832 0.652172 +0.732795 0.660925 +0.728709 0.651677 +0.728634 0.649435 +0.728634 0.649435 +0.729037 0.653972 +0.728709 0.651677 +0.729638 0.656184 +0.729037 0.653972 +0.730501 0.658161 +0.729638 0.656184 +0.730501 0.658161 +0.731578 0.659771 +0.731578 0.659771 +0.732795 0.660925 +0.742311 0.651804 +0.742467 0.649564 +0.742467 0.649564 +0.742311 0.651804 +0.741898 0.654092 +0.741216 0.656292 +0.741898 0.654092 +0.741216 0.656292 +0.740282 0.658252 +0.739147 0.659841 +0.740282 0.658252 +0.739147 0.659841 +0.737887 0.660972 +0.737887 0.660972 +0.736588 0.661619 +0.736588 0.661619 +0.735325 0.661813 +0.735325 0.661813 +0.734071 0.661596 +0.734071 0.661596 +0.702945 0.649196 +0.702945 0.649196 +0.689112 0.649067 +0.689112 0.649067 +0.689187 0.651309 +0.689515 0.653604 +0.689187 0.651309 +0.689515 0.653604 +0.690117 0.655816 +0.690979 0.657793 +0.690117 0.655816 +0.692056 0.659403 +0.690979 0.657793 +0.692056 0.659403 +0.693274 0.660557 +0.693274 0.660557 +0.694549 0.661228 +0.695804 0.661445 +0.694549 0.661228 +0.697066 0.661251 +0.695804 0.661445 +0.697066 0.661251 +0.698365 0.660604 +0.699625 0.659473 +0.698365 0.660604 +0.700760 0.657884 +0.699625 0.659473 +0.700760 0.657884 +0.701694 0.655924 +0.701694 0.655924 +0.702376 0.653724 +0.702376 0.653724 +0.702789 0.651436 +0.702789 0.651436 +0.663423 0.648828 +0.663423 0.648828 +0.649665 0.650941 +0.649590 0.648699 +0.649590 0.648699 +0.649993 0.653236 +0.649665 0.650941 +0.650595 0.655448 +0.649993 0.653236 +0.650595 0.655448 +0.651457 0.657425 +0.652534 0.659035 +0.651457 0.657425 +0.653752 0.660189 +0.652534 0.659035 +0.655027 0.660860 +0.653752 0.660189 +0.655027 0.660860 +0.656282 0.661077 +0.656282 0.661077 +0.657544 0.660883 +0.658843 0.660236 +0.657544 0.660883 +0.658843 0.660236 +0.660103 0.659105 +0.660103 0.659105 +0.661238 0.657516 +0.661238 0.657516 +0.662173 0.655555 +0.662855 0.653356 +0.662173 0.655555 +0.662855 0.653356 +0.663267 0.651067 +0.663267 0.651067 +0.623901 0.648460 +0.623901 0.648460 +0.610143 0.650573 +0.610068 0.648331 +0.610068 0.648331 +0.610471 0.652868 +0.610143 0.650573 +0.610471 0.652868 +0.611073 0.655079 +0.611935 0.657057 +0.611073 0.655079 +0.613012 0.658666 +0.611935 0.657057 +0.613012 0.658666 +0.614230 0.659820 +0.614230 0.659820 +0.615505 0.660491 +0.615505 0.660491 +0.616760 0.660709 +0.616760 0.660709 +0.618022 0.660515 +0.618022 0.660515 +0.619321 0.659868 +0.619321 0.659868 +0.620581 0.658737 +0.620581 0.658737 +0.621716 0.657148 +0.621716 0.657148 +0.622651 0.655187 +0.622651 0.655187 +0.623333 0.652988 +0.623333 0.652988 +0.623745 0.650699 +0.623745 0.650699 +0.584379 0.648092 +0.584379 0.648092 +0.570621 0.650204 +0.570547 0.647963 +0.570547 0.647963 +0.570949 0.652500 +0.570621 0.650204 +0.570949 0.652500 +0.571551 0.654711 +0.572413 0.656689 +0.571551 0.654711 +0.572413 0.656689 +0.573490 0.658298 +0.573490 0.658298 +0.574708 0.659452 +0.574708 0.659452 +0.575983 0.660123 +0.575983 0.660123 +0.577238 0.660340 +0.577238 0.660340 +0.578500 0.660147 +0.578500 0.660147 +0.579800 0.659500 +0.579800 0.659500 +0.581059 0.658369 +0.581059 0.658369 +0.582194 0.656780 +0.582194 0.656780 +0.583129 0.654819 +0.583129 0.654819 +0.583811 0.652620 +0.583811 0.652620 +0.584223 0.650331 +0.584223 0.650331 +0.544857 0.647723 +0.544857 0.647723 +0.531099 0.649836 +0.531025 0.647595 +0.531025 0.647595 +0.531427 0.652132 +0.531099 0.649836 +0.532029 0.654343 +0.531427 0.652132 +0.532029 0.654343 +0.532891 0.656320 +0.532891 0.656320 +0.533968 0.657930 +0.535186 0.659084 +0.533968 0.657930 +0.536461 0.659755 +0.535186 0.659084 +0.536461 0.659755 +0.537716 0.659972 +0.538978 0.659779 +0.537716 0.659972 +0.540278 0.659132 +0.538978 0.659779 +0.540278 0.659132 +0.541537 0.658001 +0.542672 0.656411 +0.541537 0.658001 +0.542672 0.656411 +0.543607 0.654451 +0.543607 0.654451 +0.544289 0.652251 +0.544289 0.652251 +0.544701 0.649963 +0.544701 0.649963 +0.505335 0.647355 +0.505335 0.647355 +0.491503 0.647226 +0.491503 0.647226 +0.491577 0.649468 +0.491905 0.651763 +0.491577 0.649468 +0.491905 0.651763 +0.492507 0.653975 +0.492507 0.653975 +0.493369 0.655952 +0.493369 0.655952 +0.494446 0.657562 +0.494446 0.657562 +0.495664 0.658716 +0.495664 0.658716 +0.496939 0.659387 +0.496939 0.659387 +0.498194 0.659604 +0.498194 0.659604 +0.499456 0.659410 +0.500756 0.658763 +0.499456 0.659410 +0.500756 0.658763 +0.502015 0.657632 +0.502015 0.657632 +0.503150 0.656043 +0.503150 0.656043 +0.504085 0.654083 +0.504085 0.654083 +0.504767 0.651883 +0.504767 0.651883 +0.505179 0.649595 +0.505179 0.649595 +0.465813 0.646987 +0.465813 0.646987 +0.451981 0.646858 +0.451981 0.646858 +0.452055 0.649100 +0.452384 0.651395 +0.452055 0.649100 +0.452384 0.651395 +0.452985 0.653607 +0.452985 0.653607 +0.453847 0.655584 +0.453847 0.655584 +0.454924 0.657194 +0.454924 0.657194 +0.456142 0.658348 +0.456142 0.658348 +0.457417 0.659019 +0.457417 0.659019 +0.458672 0.659236 +0.458672 0.659236 +0.459934 0.659042 +0.461234 0.658395 +0.459934 0.659042 +0.461234 0.658395 +0.462493 0.657264 +0.462493 0.657264 +0.463629 0.655675 +0.463629 0.655675 +0.464563 0.653715 +0.464563 0.653715 +0.465245 0.651515 +0.465245 0.651515 +0.465657 0.649227 +0.465657 0.649227 +0.416620 0.657980 +0.412533 0.648732 +0.412459 0.646490 +0.412459 0.646490 +0.412862 0.651027 +0.412533 0.648732 +0.413463 0.653239 +0.412862 0.651027 +0.413463 0.653239 +0.414326 0.655216 +0.415402 0.656825 +0.414326 0.655216 +0.416620 0.657980 +0.415402 0.656825 +0.426135 0.648858 +0.426292 0.646619 +0.426292 0.646619 +0.426135 0.648858 +0.425723 0.651147 +0.425041 0.653346 +0.425723 0.651147 +0.425041 0.653346 +0.424107 0.655307 +0.422972 0.656896 +0.424107 0.655307 +0.422972 0.656896 +0.421712 0.658027 +0.421712 0.658027 +0.420412 0.658674 +0.420412 0.658674 +0.419150 0.658868 +0.419150 0.658868 +0.417895 0.658651 +0.417895 0.658651 +0.386770 0.646251 +0.386770 0.646251 +0.373011 0.648364 +0.372937 0.646122 +0.372937 0.646122 +0.373340 0.650659 +0.373011 0.648364 +0.373941 0.652870 +0.373340 0.650659 +0.373941 0.652870 +0.374804 0.654848 +0.375880 0.656457 +0.374804 0.654848 +0.377098 0.657611 +0.375880 0.656457 +0.377098 0.657611 +0.378373 0.658282 +0.378373 0.658282 +0.379628 0.658500 +0.379628 0.658500 +0.380891 0.658306 +0.380891 0.658306 +0.382190 0.657659 +0.382190 0.657659 +0.383450 0.656528 +0.383450 0.656528 +0.384585 0.654939 +0.385519 0.652978 +0.384585 0.654939 +0.385519 0.652978 +0.386201 0.650779 +0.386201 0.650779 +0.386613 0.648490 +0.386613 0.648490 +0.347248 0.645883 +0.347248 0.645883 +0.333489 0.647995 +0.333415 0.645754 +0.333415 0.645754 +0.333818 0.650291 +0.333489 0.647995 +0.334419 0.652502 +0.333818 0.650291 +0.335282 0.654480 +0.334419 0.652502 +0.335282 0.654480 +0.336358 0.656089 +0.336358 0.656089 +0.337576 0.657243 +0.338851 0.657914 +0.337576 0.657243 +0.340106 0.658132 +0.338851 0.657914 +0.341369 0.657938 +0.340106 0.658132 +0.341369 0.657938 +0.342668 0.657291 +0.343928 0.656160 +0.342668 0.657291 +0.345063 0.654571 +0.343928 0.656160 +0.345063 0.654571 +0.345997 0.652610 +0.345997 0.652610 +0.346679 0.650411 +0.346679 0.650411 +0.347091 0.648122 +0.347091 0.648122 +0.307569 0.647754 +0.307726 0.645514 +0.307726 0.645514 +0.307569 0.647754 +0.293893 0.645386 +0.293893 0.645386 +0.293968 0.647627 +0.294296 0.649923 +0.293968 0.647627 +0.294296 0.649923 +0.294897 0.652134 +0.294897 0.652134 +0.295760 0.654111 +0.295760 0.654111 +0.296836 0.655721 +0.298054 0.656875 +0.296836 0.655721 +0.298054 0.656875 +0.299330 0.657546 +0.299330 0.657546 +0.300584 0.657763 +0.301847 0.657570 +0.300584 0.657763 +0.303146 0.656923 +0.301847 0.657570 +0.304406 0.655791 +0.303146 0.656923 +0.304406 0.655791 +0.305541 0.654202 +0.305541 0.654202 +0.306475 0.652242 +0.306475 0.652242 +0.307157 0.650042 +0.307157 0.650042 +0.268047 0.647386 +0.268204 0.645146 +0.268204 0.645146 +0.268047 0.647386 +0.254371 0.645017 +0.254371 0.645017 +0.254446 0.647259 +0.254774 0.649554 +0.254446 0.647259 +0.254774 0.649554 +0.255375 0.651766 +0.256238 0.653743 +0.255375 0.651766 +0.256238 0.653743 +0.257314 0.655353 +0.257314 0.655353 +0.258532 0.656507 +0.258532 0.656507 +0.259808 0.657178 +0.259808 0.657178 +0.261063 0.657395 +0.262325 0.657201 +0.261063 0.657395 +0.263624 0.656554 +0.262325 0.657201 +0.264884 0.655423 +0.263624 0.656554 +0.264884 0.655423 +0.266019 0.653834 +0.266019 0.653834 +0.266953 0.651874 +0.266953 0.651874 +0.267635 0.649674 +0.267635 0.649674 +0.228682 0.644778 +0.228682 0.644778 +0.214849 0.644649 +0.214849 0.644649 +0.214924 0.646891 +0.215252 0.649186 +0.214924 0.646891 +0.215252 0.649186 +0.215853 0.651398 +0.216716 0.653375 +0.215853 0.651398 +0.216716 0.653375 +0.217793 0.654985 +0.217793 0.654985 +0.219011 0.656139 +0.219011 0.656139 +0.220286 0.656810 +0.221541 0.657027 +0.220286 0.656810 +0.222803 0.656833 +0.221541 0.657027 +0.224102 0.656186 +0.222803 0.656833 +0.225362 0.655055 +0.224102 0.656186 +0.226497 0.653466 +0.225362 0.655055 +0.226497 0.653466 +0.227431 0.651506 +0.227431 0.651506 +0.228113 0.649306 +0.228113 0.649306 +0.228525 0.647018 +0.228525 0.647018 +0.189160 0.644410 +0.189160 0.644410 +0.175402 0.646523 +0.175327 0.644281 +0.175327 0.644281 +0.175730 0.648818 +0.175402 0.646523 +0.176332 0.651030 +0.175730 0.648818 +0.176332 0.651030 +0.177194 0.653007 +0.178271 0.654616 +0.177194 0.653007 +0.179489 0.655770 +0.178271 0.654616 +0.179489 0.655770 +0.180764 0.656442 +0.180764 0.656442 +0.182019 0.656659 +0.183281 0.656465 +0.182019 0.656659 +0.183281 0.656465 +0.184580 0.655818 +0.184580 0.655818 +0.185840 0.654687 +0.185840 0.654687 +0.186975 0.653098 +0.186975 0.653098 +0.187909 0.651137 +0.187909 0.651137 +0.188591 0.648938 +0.188591 0.648938 +0.189003 0.646649 +0.189003 0.646649 + + + + + + + + + + + +

32 0 32 1 1 1 0 2 0 5 3 5 3 4 3 2 5 2 5 6 5 2 7 2 4 8 4 7 9 7 5 10 5 4 11 4 7 12 7 4 13 4 6 14 6 9 15 9 7 16 7 6 17 6 9 18 9 6 19 6 8 20 8 11 21 11 9 22 9 8 23 8 11 24 11 8 25 8 10 26 10 13 27 13 11 28 11 10 29 10 13 30 13 10 31 10 12 32 12 15 33 15 13 34 13 12 35 12 15 36 15 12 37 12 14 38 14 17 39 17 15 40 15 14 41 14 17 42 17 14 43 14 16 44 16 19 45 19 17 46 17 16 47 16 19 48 19 16 49 16 18 50 18 21 51 21 19 52 19 18 53 18 21 54 21 18 55 18 20 56 20 23 57 23 21 58 21 20 59 20 23 60 23 20 61 20 22 62 22 25 63 25 23 64 23 22 65 22 25 66 25 22 67 22 24 68 24 27 69 27 25 70 25 24 71 24 27 72 27 24 73 24 26 74 26 29 75 29 27 76 27 26 77 26 29 78 29 26 79 26 28 80 28 31 81 31 29 82 29 28 83 28 31 84 31 28 85 28 30 86 30 33 87 33 31 88 31 30 89 30 33 90 33 30 91 30 32 92 32 0 93 0 33 94 33 32 95 32 66 96 66 35 97 35 34 98 34 40 99 40 37 100 37 36 101 36 40 102 40 36 103 36 38 104 38 40 105 40 38 106 38 39 107 39 41 108 41 40 109 40 39 110 39 43 111 43 41 112 41 39 113 39 43 114 43 39 115 39 42 116 42 45 117 45 43 118 43 42 119 42 45 120 45 42 121 42 44 122 44 47 123 47 45 124 45 44 125 44 47 126 47 44 127 44 46 128 46 50 129 50 47 130 47 46 131 46 50 132 50 46 133 46 48 134 48 50 135 50 48 136 48 49 137 49 51 138 51 50 139 50 49 140 49 53 141 53 51 142 51 49 143 49 53 144 53 49 145 49 52 146 52 55 147 55 53 148 53 52 149 52 55 150 55 52 151 52 54 152 54 57 153 57 55 154 55 54 155 54 57 156 57 54 157 54 56 158 56 59 159 59 57 160 57 56 161 56 59 162 59 56 163 56 58 164 58 61 165 61 59 166 59 58 167 58 61 168 61 58 169 58 60 170 60 63 171 63 61 172 61 60 173 60 63 174 63 60 175 60 62 176 62 65 177 65 63 178 63 62 179 62 65 180 65 62 181 62 64 182 64 67 183 67 65 184 65 64 185 64 67 186 67 64 187 64 66 188 66 34 189 34 67 190 67 66 191 66 100 192 100 69 193 69 68 194 68 73 195 73 71 196 71 70 197 70 73 198 73 70 199 70 72 200 72 75 201 75 73 202 73 72 203 72 75 204 75 72 205 72 74 206 74 78 207 78 75 208 75 74 209 74 78 210 78 74 211 74 76 212 76 78 213 78 76 214 76 77 215 77 80 216 80 78 217 78 77 218 77 80 219 80 77 220 77 79 221 79 82 222 82 80 223 80 79 224 79 82 225 82 79 226 79 81 227 81 83 228 83 82 229 82 81 230 81 85 231 85 83 232 83 81 233 81 85 234 85 81 235 81 84 236 84 87 237 87 85 238 85 84 239 84 87 240 87 84 241 84 86 242 86 89 243 89 87 244 87 86 245 86 89 246 89 86 247 86 88 248 88 91 249 91 89 250 89 88 251 88 91 252 91 88 253 88 90 254 90 93 255 93 91 256 91 90 257 90 93 258 93 90 259 90 92 260 92 95 261 95 93 262 93 92 263 92 95 264 95 92 265 92 94 266 94 98 267 98 95 268 95 94 269 94 98 270 98 94 271 94 96 272 96 98 273 98 96 274 96 97 275 97 99 276 99 98 277 98 97 278 97 101 279 101 99 280 99 97 281 97 101 282 101 97 283 97 100 284 100 68 285 68 101 286 101 100 287 100 134 288 134 103 289 103 102 290 102 107 291 107 105 292 105 104 293 104 107 294 107 104 295 104 106 296 106 109 297 109 107 298 107 106 299 106 109 300 109 106 301 106 108 302 108 111 303 111 109 304 109 108 305 108 111 306 111 108 307 108 110 308 110 113 309 113 111 310 111 110 311 110 113 312 113 110 313 110 112 314 112 115 315 115 113 316 113 112 317 112 115 318 115 112 319 112 114 320 114 117 321 117 115 322 115 114 323 114 117 324 117 114 325 114 116 326 116 119 327 119 117 328 117 116 329 116 119 330 119 116 331 116 118 332 118 121 333 121 119 334 119 118 335 118 121 336 121 118 337 118 120 338 120 123 339 123 121 340 121 120 341 120 123 342 123 120 343 120 122 344 122 125 345 125 123 346 123 122 347 122 125 348 125 122 349 122 124 350 124 127 351 127 125 352 125 124 353 124 127 354 127 124 355 124 126 356 126 129 357 129 127 358 127 126 359 126 129 360 129 126 361 126 128 362 128 131 363 131 129 364 129 128 365 128 131 366 131 128 367 128 130 368 130 133 369 133 131 370 131 130 371 130 133 372 133 130 373 130 132 374 132 135 375 135 133 376 133 132 377 132 135 378 135 132 379 132 134 380 134 102 381 102 135 382 135 134 383 134 168 384 168 137 385 137 136 386 136 141 387 141 139 388 139 138 389 138 141 390 141 138 391 138 140 392 140 143 393 143 141 394 141 140 395 140 143 396 143 140 397 140 142 398 142 145 399 145 143 400 143 142 401 142 145 402 145 142 403 142 144 404 144 147 405 147 145 406 145 144 407 144 147 408 147 144 409 144 146 410 146 149 411 149 147 412 147 146 413 146 149 414 149 146 415 146 148 416 148 151 417 151 149 418 149 148 419 148 151 420 151 148 421 148 150 422 150 153 423 153 151 424 151 150 425 150 153 426 153 150 427 150 152 428 152 155 429 155 153 430 153 152 431 152 155 432 155 152 433 152 154 434 154 157 435 157 155 436 155 154 437 154 157 438 157 154 439 154 156 440 156 159 441 159 157 442 157 156 443 156 159 444 159 156 445 156 158 446 158 161 447 161 159 448 159 158 449 158 161 450 161 158 451 158 160 452 160 163 453 163 161 454 161 160 455 160 163 456 163 160 457 160 162 458 162 165 459 165 163 460 163 162 461 162 165 462 165 162 463 162 164 464 164 167 465 167 165 466 165 164 467 164 167 468 167 164 469 164 166 470 166 169 471 169 167 472 167 166 473 166 169 474 169 166 475 166 168 476 168 136 477 136 169 478 169 168 479 168 202 480 202 171 481 171 170 482 170 175 483 175 173 484 173 172 485 172 175 486 175 172 487 172 174 488 174 177 489 177 175 490 175 174 491 174 177 492 177 174 493 174 176 494 176 179 495 179 177 496 177 176 497 176 179 498 179 176 499 176 178 500 178 181 501 181 179 502 179 178 503 178 181 504 181 178 505 178 180 506 180 183 507 183 181 508 181 180 509 180 183 510 183 180 511 180 182 512 182 185 513 185 183 514 183 182 515 182 185 516 185 182 517 182 184 518 184 187 519 187 185 520 185 184 521 184 187 522 187 184 523 184 186 524 186 189 525 189 187 526 187 186 527 186 189 528 189 186 529 186 188 530 188 191 531 191 189 532 189 188 533 188 191 534 191 188 535 188 190 536 190 193 537 193 191 538 191 190 539 190 193 540 193 190 541 190 192 542 192 195 543 195 193 544 193 192 545 192 195 546 195 192 547 192 194 548 194 198 549 198 195 550 195 194 551 194 198 552 198 194 553 194 196 554 196 198 555 198 196 556 196 197 557 197 200 558 200 198 559 198 197 560 197 200 561 200 197 562 197 199 563 199 201 564 201 200 565 200 199 566 199 203 567 203 201 568 201 199 569 199 203 570 203 199 571 199 202 572 202 170 573 170 203 574 203 202 575 202 236 576 236 205 577 205 204 578 204 209 579 209 207 580 207 206 581 206 209 582 209 206 583 206 208 584 208 211 585 211 209 586 209 208 587 208 211 588 211 208 589 208 210 590 210 213 591 213 211 592 211 210 593 210 213 594 213 210 595 210 212 596 212 215 597 215 213 598 213 212 599 212 215 600 215 212 601 212 214 602 214 217 603 217 215 604 215 214 605 214 217 606 217 214 607 214 216 608 216 219 609 219 217 610 217 216 611 216 219 612 219 216 613 216 218 614 218 221 615 221 219 616 219 218 617 218 221 618 221 218 619 218 220 620 220 223 621 223 221 622 221 220 623 220 223 624 223 220 625 220 222 626 222 225 627 225 223 628 223 222 629 222 225 630 225 222 631 222 224 632 224 227 633 227 225 634 225 224 635 224 227 636 227 224 637 224 226 638 226 229 639 229 227 640 227 226 641 226 229 642 229 226 643 226 228 644 228 231 645 231 229 646 229 228 647 228 231 648 231 228 649 228 230 650 230 233 651 233 231 652 231 230 653 230 233 654 233 230 655 230 232 656 232 235 657 235 233 658 233 232 659 232 235 660 235 232 661 232 234 662 234 237 663 237 235 664 235 234 665 234 237 666 237 234 667 234 236 668 236 204 669 204 237 670 237 236 671 236 270 672 270 239 673 239 238 674 238 243 675 243 241 676 241 240 677 240 243 678 243 240 679 240 242 680 242 245 681 245 243 682 243 242 683 242 245 684 245 242 685 242 244 686 244 247 687 247 245 688 245 244 689 244 247 690 247 244 691 244 246 692 246 249 693 249 247 694 247 246 695 246 249 696 249 246 697 246 248 698 248 251 699 251 249 700 249 248 701 248 251 702 251 248 703 248 250 704 250 253 705 253 251 706 251 250 707 250 253 708 253 250 709 250 252 710 252 255 711 255 253 712 253 252 713 252 255 714 255 252 715 252 254 716 254 257 717 257 255 718 255 254 719 254 257 720 257 254 721 254 256 722 256 259 723 259 257 724 257 256 725 256 259 726 259 256 727 256 258 728 258 261 729 261 259 730 259 258 731 258 261 732 261 258 733 258 260 734 260 263 735 263 261 736 261 260 737 260 263 738 263 260 739 260 262 740 262 265 741 265 263 742 263 262 743 262 265 744 265 262 745 262 264 746 264 267 747 267 265 748 265 264 749 264 267 750 267 264 751 264 266 752 266 269 753 269 267 754 267 266 755 266 269 756 269 266 757 266 268 758 268 271 759 271 269 760 269 268 761 268 271 762 271 268 763 268 270 764 270 238 765 238 271 766 271 270 767 270 304 768 304 273 769 273 272 770 272 277 771 277 275 772 275 274 773 274 277 774 277 274 775 274 276 776 276 279 777 279 277 778 277 276 779 276 279 780 279 276 781 276 278 782 278 281 783 281 279 784 279 278 785 278 281 786 281 278 787 278 280 788 280 283 789 283 281 790 281 280 791 280 283 792 283 280 793 280 282 794 282 285 795 285 283 796 283 282 797 282 285 798 285 282 799 282 284 800 284 287 801 287 285 802 285 284 803 284 287 804 287 284 805 284 286 806 286 289 807 289 287 808 287 286 809 286 289 810 289 286 811 286 288 812 288 291 813 291 289 814 289 288 815 288 291 816 291 288 817 288 290 818 290 293 819 293 291 820 291 290 821 290 293 822 293 290 823 290 292 824 292 295 825 295 293 826 293 292 827 292 295 828 295 292 829 292 294 830 294 297 831 297 295 832 295 294 833 294 297 834 297 294 835 294 296 836 296 299 837 299 297 838 297 296 839 296 299 840 299 296 841 296 298 842 298 301 843 301 299 844 299 298 845 298 301 846 301 298 847 298 300 848 300 303 849 303 301 850 301 300 851 300 303 852 303 300 853 300 302 854 302 305 855 305 303 856 303 302 857 302 305 858 305 302 859 302 304 860 304 272 861 272 305 862 305 304 863 304 337 864 337 307 865 307 306 866 306 311 867 311 309 868 309 308 869 308 311 870 311 308 871 308 310 872 310 313 873 313 311 874 311 310 875 310 313 876 313 310 877 310 312 878 312 316 879 316 313 880 313 312 881 312 316 882 316 312 883 312 314 884 314 316 885 316 314 886 314 315 887 315 317 888 317 316 889 316 315 890 315 319 891 319 317 892 317 315 893 315 319 894 319 315 895 315 318 896 318 321 897 321 319 898 319 318 899 318 321 900 321 318 901 318 320 902 320 323 903 323 321 904 321 320 905 320 323 906 323 320 907 320 322 908 322 325 909 325 323 910 323 322 911 322 325 912 325 322 913 322 324 914 324 327 915 327 325 916 325 324 917 324 327 918 327 324 919 324 326 920 326 329 921 329 327 922 327 326 923 326 329 924 329 326 925 326 328 926 328 331 927 331 329 928 329 328 929 328 331 930 331 328 931 328 330 932 330 333 933 333 331 934 331 330 935 330 333 936 333 330 937 330 332 938 332 335 939 335 333 940 333 332 941 332 335 942 335 332 943 332 334 944 334 338 945 338 335 946 335 334 947 334 338 948 338 334 949 334 336 950 336 338 951 338 336 952 336 337 953 337 339 954 339 338 955 338 337 956 337 306 957 306 339 958 339 337 959 337 372 960 372 341 961 341 340 962 340 344 963 344 343 964 343 342 965 342 345 966 345 344 967 344 342 968 342 348 969 348 345 970 345 342 971 342 348 972 348 342 973 342 346 974 346 348 975 348 346 976 346 347 977 347 349 978 349 348 979 348 347 980 347 351 981 351 349 982 349 347 983 347 351 984 351 347 985 347 350 986 350 353 987 353 351 988 351 350 989 350 353 990 353 350 991 350 352 992 352 355 993 355 353 994 353 352 995 352 355 996 355 352 997 352 354 998 354 357 999 357 355 1000 355 354 1001 354 357 1002 357 354 1003 354 356 1004 356 359 1005 359 357 1006 357 356 1007 356 359 1008 359 356 1009 356 358 1010 358 361 1011 361 359 1012 359 358 1013 358 361 1014 361 358 1015 358 360 1016 360 363 1017 363 361 1018 361 360 1019 360 363 1020 363 360 1021 360 362 1022 362 365 1023 365 363 1024 363 362 1025 362 365 1026 365 362 1027 362 364 1028 364 367 1029 367 365 1030 365 364 1031 364 367 1032 367 364 1033 364 366 1034 366 370 1035 370 367 1036 367 366 1037 366 370 1038 370 366 1039 366 368 1040 368 370 1041 370 368 1042 368 369 1043 369 371 1044 371 370 1045 370 369 1046 369 373 1047 373 371 1048 371 369 1049 369 373 1050 373 369 1051 369 372 1052 372 340 1053 340 373 1054 373 372 1055 372 406 1056 406 375 1057 375 374 1058 374 379 1059 379 377 1060 377 376 1061 376 379 1062 379 376 1063 376 378 1064 378 381 1065 381 379 1066 379 378 1067 378 381 1068 381 378 1069 378 380 1070 380 383 1071 383 381 1072 381 380 1073 380 383 1074 383 380 1075 380 382 1076 382 385 1077 385 383 1078 383 382 1079 382 385 1080 385 382 1081 382 384 1082 384 387 1083 387 385 1084 385 384 1085 384 387 1086 387 384 1087 384 386 1088 386 390 1089 390 387 1090 387 386 1091 386 390 1092 390 386 1093 386 388 1094 388 390 1095 390 388 1096 388 389 1097 389 391 1098 391 390 1099 390 389 1100 389 393 1101 393 391 1102 391 389 1103 389 393 1104 393 389 1105 389 392 1106 392 395 1107 395 393 1108 393 392 1109 392 395 1110 395 392 1111 392 394 1112 394 397 1113 397 395 1114 395 394 1115 394 397 1116 397 394 1117 394 396 1118 396 399 1119 399 397 1120 397 396 1121 396 399 1122 399 396 1123 396 398 1124 398 401 1125 401 399 1126 399 398 1127 398 401 1128 401 398 1129 398 400 1130 400 403 1131 403 401 1132 401 400 1133 400 403 1134 403 400 1135 400 402 1136 402 405 1137 405 403 1138 403 402 1139 402 405 1140 405 402 1141 402 404 1142 404 407 1143 407 405 1144 405 404 1145 404 407 1146 407 404 1147 404 406 1148 406 374 1149 374 407 1150 407 406 1151 406 439 1152 439 409 1153 409 408 1154 408 413 1155 413 411 1156 411 410 1157 410 413 1158 413 410 1159 410 412 1160 412 415 1161 415 413 1162 413 412 1163 412 415 1164 415 412 1165 412 414 1166 414 417 1167 417 415 1168 415 414 1169 414 417 1170 417 414 1171 414 416 1172 416 419 1173 419 417 1174 417 416 1175 416 419 1176 419 416 1177 416 418 1178 418 421 1179 421 419 1180 419 418 1181 418 421 1182 421 418 1183 418 420 1184 420 423 1185 423 421 1186 421 420 1187 420 423 1188 423 420 1189 420 422 1190 422 425 1191 425 423 1192 423 422 1193 422 425 1194 425 422 1195 422 424 1196 424 428 1197 428 425 1198 425 424 1199 424 428 1200 428 424 1201 424 426 1202 426 428 1203 428 426 1204 426 427 1205 427 429 1206 429 428 1207 428 427 1208 427 431 1209 431 429 1210 429 427 1211 427 431 1212 431 427 1213 427 430 1214 430 433 1215 433 431 1216 431 430 1217 430 433 1218 433 430 1219 430 432 1220 432 435 1221 435 433 1222 433 432 1223 432 435 1224 435 432 1225 432 434 1226 434 437 1227 437 435 1228 435 434 1229 434 437 1230 437 434 1231 434 436 1232 436 440 1233 440 437 1234 437 436 1235 436 440 1236 440 436 1237 436 438 1238 438 440 1239 440 438 1240 438 439 1241 439 441 1242 441 440 1243 440 439 1244 439 408 1245 408 441 1246 441 439 1247 439 474 1248 474 443 1249 443 442 1250 442 447 1251 447 445 1252 445 444 1253 444 447 1254 447 444 1255 444 446 1256 446 449 1257 449 447 1258 447 446 1259 446 449 1260 449 446 1261 446 448 1262 448 451 1263 451 449 1264 449 448 1265 448 451 1266 451 448 1267 448 450 1268 450 453 1269 453 451 1270 451 450 1271 450 453 1272 453 450 1273 450 452 1274 452 455 1275 455 453 1276 453 452 1277 452 455 1278 455 452 1279 452 454 1280 454 457 1281 457 455 1282 455 454 1283 454 457 1284 457 454 1285 454 456 1286 456 459 1287 459 457 1288 457 456 1289 456 459 1290 459 456 1291 456 458 1292 458 461 1293 461 459 1294 459 458 1295 458 461 1296 461 458 1297 458 460 1298 460 463 1299 463 461 1300 461 460 1301 460 463 1302 463 460 1303 460 462 1304 462 465 1305 465 463 1306 463 462 1307 462 465 1308 465 462 1309 462 464 1310 464 467 1311 467 465 1312 465 464 1313 464 467 1314 467 464 1315 464 466 1316 466 469 1317 469 467 1318 467 466 1319 466 469 1320 469 466 1321 466 468 1322 468 471 1323 471 469 1324 469 468 1325 468 471 1326 471 468 1327 468 470 1328 470 473 1329 473 471 1330 471 470 1331 470 473 1332 473 470 1333 470 472 1334 472 475 1335 475 473 1336 473 472 1337 472 475 1338 475 472 1339 472 474 1340 474 442 1341 442 475 1342 475 474 1343 474 507 1344 507 477 1345 477 476 1346 476 481 1347 481 479 1348 479 478 1349 478 481 1350 481 478 1351 478 480 1352 480 483 1353 483 481 1354 481 480 1355 480 483 1356 483 480 1357 480 482 1358 482 485 1359 485 483 1360 483 482 1361 482 485 1362 485 482 1363 482 484 1364 484 487 1365 487 485 1366 485 484 1367 484 487 1368 487 484 1369 484 486 1370 486 489 1371 489 487 1372 487 486 1373 486 489 1374 489 486 1375 486 488 1376 488 491 1377 491 489 1378 489 488 1379 488 491 1380 491 488 1381 488 490 1382 490 493 1383 493 491 1384 491 490 1385 490 493 1386 493 490 1387 490 492 1388 492 495 1389 495 493 1390 493 492 1391 492 495 1392 495 492 1393 492 494 1394 494 497 1395 497 495 1396 495 494 1397 494 497 1398 497 494 1399 494 496 1400 496 499 1401 499 497 1402 497 496 1403 496 499 1404 499 496 1405 496 498 1406 498 501 1407 501 499 1408 499 498 1409 498 501 1410 501 498 1411 498 500 1412 500 503 1413 503 501 1414 501 500 1415 500 503 1416 503 500 1417 500 502 1418 502 505 1419 505 503 1420 503 502 1421 502 505 1422 505 502 1423 502 504 1424 504 508 1425 508 505 1426 505 504 1427 504 508 1428 508 504 1429 504 506 1430 506 508 1431 508 506 1432 506 507 1433 507 509 1434 509 508 1435 508 507 1436 507 476 1437 476 509 1438 509 507 1439 507 542 1440 542 511 1441 511 510 1442 510 515 1443 515 513 1444 513 512 1445 512 515 1446 515 512 1447 512 514 1448 514 518 1449 518 515 1450 515 514 1451 514 518 1452 518 514 1453 514 516 1454 516 518 1455 518 516 1456 516 517 1457 517 519 1458 519 518 1459 518 517 1460 517 521 1461 521 519 1462 519 517 1463 517 521 1464 521 517 1465 517 520 1466 520 523 1467 523 521 1468 521 520 1469 520 523 1470 523 520 1471 520 522 1472 522 525 1473 525 523 1474 523 522 1475 522 525 1476 525 522 1477 522 524 1478 524 527 1479 527 525 1480 525 524 1481 524 527 1482 527 524 1483 524 526 1484 526 529 1485 529 527 1486 527 526 1487 526 529 1488 529 526 1489 526 528 1490 528 531 1491 531 529 1492 529 528 1493 528 531 1494 531 528 1495 528 530 1496 530 533 1497 533 531 1498 531 530 1499 530 533 1500 533 530 1501 530 532 1502 532 536 1503 536 533 1504 533 532 1505 532 536 1506 536 532 1507 532 534 1508 534 536 1509 536 534 1510 534 535 1511 535 537 1512 537 536 1513 536 535 1514 535 539 1515 539 537 1516 537 535 1517 535 539 1518 539 535 1519 535 538 1520 538 541 1521 541 539 1522 539 538 1523 538 541 1524 541 538 1525 538 540 1526 540 543 1527 543 541 1528 541 540 1529 540 543 1530 543 540 1531 540 542 1532 542 510 1533 510 543 1534 543 542 1535 542 576 1536 576 545 1537 545 544 1538 544 549 1539 549 547 1540 547 546 1541 546 549 1542 549 546 1543 546 548 1544 548 552 1545 552 549 1546 549 548 1547 548 552 1548 552 548 1549 548 550 1550 550 552 1551 552 550 1552 550 551 1553 551 553 1554 553 552 1555 552 551 1556 551 555 1557 555 553 1558 553 551 1559 551 555 1560 555 551 1561 551 554 1562 554 557 1563 557 555 1564 555 554 1565 554 557 1566 557 554 1567 554 556 1568 556 559 1569 559 557 1570 557 556 1571 556 559 1572 559 556 1573 556 558 1574 558 561 1575 561 559 1576 559 558 1577 558 561 1578 561 558 1579 558 560 1580 560 563 1581 563 561 1582 561 560 1583 560 563 1584 563 560 1585 560 562 1586 562 565 1587 565 563 1588 563 562 1589 562 565 1590 565 562 1591 562 564 1592 564 567 1593 567 565 1594 565 564 1595 564 567 1596 567 564 1597 564 566 1598 566 569 1599 569 567 1600 567 566 1601 566 569 1602 569 566 1603 566 568 1604 568 571 1605 571 569 1606 569 568 1607 568 571 1608 571 568 1609 568 570 1610 570 573 1611 573 571 1612 571 570 1613 570 573 1614 573 570 1615 570 572 1616 572 575 1617 575 573 1618 573 572 1619 572 575 1620 575 572 1621 572 574 1622 574 577 1623 577 575 1624 575 574 1625 574 577 1626 577 574 1627 574 576 1628 576 544 1629 544 577 1630 577 576 1631 576 610 1632 610 579 1633 579 578 1634 578 583 1635 583 581 1636 581 580 1637 580 583 1638 583 580 1639 580 582 1640 582 585 1641 585 583 1642 583 582 1643 582 585 1644 585 582 1645 582 584 1646 584 587 1647 587 585 1648 585 584 1649 584 587 1650 587 584 1651 584 586 1652 586 589 1653 589 587 1654 587 586 1655 586 589 1656 589 586 1657 586 588 1658 588 591 1659 591 589 1660 589 588 1661 588 591 1662 591 588 1663 588 590 1664 590 593 1665 593 591 1666 591 590 1667 590 593 1668 593 590 1669 590 592 1670 592 595 1671 595 593 1672 593 592 1673 592 595 1674 595 592 1675 592 594 1676 594 597 1677 597 595 1678 595 594 1679 594 597 1680 597 594 1681 594 596 1682 596 599 1683 599 597 1684 597 596 1685 596 599 1686 599 596 1687 596 598 1688 598 601 1689 601 599 1690 599 598 1691 598 601 1692 601 598 1693 598 600 1694 600 603 1695 603 601 1696 601 600 1697 600 603 1698 603 600 1699 600 602 1700 602 605 1701 605 603 1702 603 602 1703 602 605 1704 605 602 1705 602 604 1706 604 607 1707 607 605 1708 605 604 1709 604 607 1710 607 604 1711 604 606 1712 606 609 1713 609 607 1714 607 606 1715 606 609 1716 609 606 1717 606 608 1718 608 611 1719 611 609 1720 609 608 1721 608 611 1722 611 608 1723 608 610 1724 610 578 1725 578 611 1726 611 610 1727 610 645 1728 645 613 1729 613 612 1730 612 617 1731 617 615 1732 615 614 1733 614 617 1734 617 614 1735 614 616 1736 616 619 1737 619 617 1738 617 616 1739 616 619 1740 619 616 1741 616 618 1742 618 622 1743 622 619 1744 619 618 1745 618 622 1746 622 618 1747 618 620 1748 620 622 1749 622 620 1750 620 621 1751 621 623 1752 623 622 1753 622 621 1754 621 625 1755 625 623 1756 623 621 1757 621 625 1758 625 621 1759 621 624 1760 624 627 1761 627 625 1762 625 624 1763 624 627 1764 627 624 1765 624 626 1766 626 629 1767 629 627 1768 627 626 1769 626 629 1770 629 626 1771 626 628 1772 628 631 1773 631 629 1774 629 628 1775 628 631 1776 631 628 1777 628 630 1778 630 633 1779 633 631 1780 631 630 1781 630 633 1782 633 630 1783 630 632 1784 632 636 1785 636 633 1786 633 632 1787 632 636 1788 636 632 1789 632 634 1790 634 636 1791 636 634 1792 634 635 1793 635 637 1794 637 636 1795 636 635 1796 635 640 1797 640 637 1798 637 635 1799 635 640 1800 640 635 1801 635 638 1802 638 640 1803 640 638 1804 638 639 1805 639 641 1806 641 640 1807 640 639 1808 639 643 1809 643 641 1810 641 639 1811 639 643 1812 643 639 1813 639 642 1814 642 612 1815 612 643 1816 643 642 1817 642 612 1818 612 642 1819 642 644 1820 644 612 1821 612 644 1822 644 645 1823 645 678 1824 678 646 1825 646 649 1826 649 646 1827 646 648 1828 648 647 1829 647 646 1830 646 647 1831 647 649 1832 649 652 1833 652 651 1834 651 650 1835 650 653 1836 653 652 1837 652 650 1838 650 656 1839 656 653 1840 653 650 1841 650 656 1842 656 650 1843 650 654 1844 654 656 1845 656 654 1846 654 655 1847 655 657 1848 657 656 1849 656 655 1850 655 659 1851 659 657 1852 657 655 1853 655 659 1854 659 655 1855 655 658 1856 658 661 1857 661 659 1858 659 658 1859 658 661 1860 661 658 1861 658 660 1862 660 663 1863 663 661 1864 661 660 1865 660 663 1866 663 660 1867 660 662 1868 662 665 1869 665 663 1870 663 662 1871 662 665 1872 665 662 1873 662 664 1874 664 667 1875 667 665 1876 665 664 1877 664 667 1878 667 664 1879 664 666 1880 666 669 1881 669 667 1882 667 666 1883 666 669 1884 669 666 1885 666 668 1886 668 671 1887 671 669 1888 669 668 1889 668 671 1890 671 668 1891 668 670 1892 670 673 1893 673 671 1894 671 670 1895 670 673 1896 673 670 1897 670 672 1898 672 676 1899 676 673 1900 673 672 1901 672 676 1902 676 672 1903 672 674 1904 674 676 1905 676 674 1906 674 675 1907 675 677 1908 677 676 1909 676 675 1910 675 679 1911 679 677 1912 677 675 1913 675 679 1914 679 675 1915 675 678 1916 678 649 1917 649 679 1918 679 678 1919 678 713 1920 713 681 1921 681 680 1922 680 685 1923 685 683 1924 683 682 1925 682 685 1926 685 682 1927 682 684 1928 684 688 1929 688 685 1930 685 684 1931 684 688 1932 688 684 1933 684 686 1934 686 688 1935 688 686 1936 686 687 1937 687 689 1938 689 688 1939 688 687 1940 687 691 1941 691 689 1942 689 687 1943 687 691 1944 691 687 1945 687 690 1946 690 693 1947 693 691 1948 691 690 1949 690 693 1950 693 690 1951 690 692 1952 692 695 1953 695 693 1954 693 692 1955 692 695 1956 695 692 1957 692 694 1958 694 697 1959 697 695 1960 695 694 1961 694 697 1962 697 694 1963 694 696 1964 696 699 1965 699 697 1966 697 696 1967 696 699 1968 699 696 1969 696 698 1970 698 701 1971 701 699 1972 699 698 1973 698 701 1974 701 698 1975 698 700 1976 700 703 1977 703 701 1978 701 700 1979 700 703 1980 703 700 1981 700 702 1982 702 705 1983 705 703 1984 703 702 1985 702 705 1986 705 702 1987 702 704 1988 704 708 1989 708 705 1990 705 704 1991 704 708 1992 708 704 1993 704 706 1994 706 708 1995 708 706 1996 706 707 1997 707 709 1998 709 708 1999 708 707 2000 707 711 2001 711 709 2002 709 707 2003 707 711 2004 711 707 2005 707 710 2006 710 680 2007 680 711 2008 711 710 2009 710 680 2010 680 710 2011 710 712 2012 712 680 2013 680 712 2014 712 713 2015 713 746 2016 746 715 2017 715 714 2018 714 718 2019 718 717 2020 717 716 2021 716 720 2022 720 718 2023 718 716 2024 716 720 2025 720 716 2026 716 719 2027 719 721 2028 721 720 2029 720 719 2030 719 724 2031 724 721 2032 721 719 2033 719 724 2034 724 719 2035 719 722 2036 722 724 2037 724 722 2038 722 723 2039 723 725 2040 725 724 2041 724 723 2042 723 727 2043 727 725 2044 725 723 2045 723 727 2046 727 723 2047 723 726 2048 726 729 2049 729 727 2050 727 726 2051 726 729 2052 729 726 2053 726 728 2054 728 731 2055 731 729 2056 729 728 2057 728 731 2058 731 728 2059 728 730 2060 730 734 2061 734 731 2062 731 730 2063 730 734 2064 734 730 2065 730 732 2066 732 734 2067 734 732 2068 732 733 2069 733 735 2070 735 734 2071 734 733 2072 733 737 2073 737 735 2074 735 733 2075 733 737 2076 737 733 2077 733 736 2078 736 739 2079 739 737 2080 737 736 2081 736 739 2082 739 736 2083 736 738 2084 738 741 2085 741 739 2086 739 738 2087 738 741 2088 741 738 2089 738 740 2090 740 743 2091 743 741 2092 741 740 2093 740 743 2094 743 740 2095 740 742 2096 742 745 2097 745 743 2098 743 742 2099 742 745 2100 745 742 2101 742 744 2102 744 747 2103 747 745 2104 745 744 2105 744 747 2106 747 744 2107 744 746 2108 746 714 2109 714 747 2110 747 746 2111 746 781 2112 781 749 2113 749 748 2114 748 753 2115 753 751 2116 751 750 2117 750 753 2118 753 750 2119 750 752 2120 752 755 2121 755 753 2122 753 752 2123 752 755 2124 755 752 2125 752 754 2126 754 758 2127 758 755 2128 755 754 2129 754 758 2130 758 754 2131 754 756 2132 756 758 2133 758 756 2134 756 757 2135 757 759 2136 759 758 2137 758 757 2138 757 761 2139 761 759 2140 759 757 2141 757 761 2142 761 757 2143 757 760 2144 760 763 2145 763 761 2146 761 760 2147 760 763 2148 763 760 2149 760 762 2150 762 765 2151 765 763 2152 763 762 2153 762 765 2154 765 762 2155 762 764 2156 764 767 2157 767 765 2158 765 764 2159 764 767 2160 767 764 2161 764 766 2162 766 769 2163 769 767 2164 767 766 2165 766 769 2166 769 766 2167 766 768 2168 768 772 2169 772 769 2170 769 768 2171 768 772 2172 772 768 2173 768 770 2174 770 772 2175 772 770 2176 770 771 2177 771 773 2178 773 772 2179 772 771 2180 771 776 2181 776 773 2182 773 771 2183 771 776 2184 776 771 2185 771 774 2186 774 776 2187 776 774 2188 774 775 2189 775 777 2190 777 776 2191 776 775 2192 775 779 2193 779 777 2194 777 775 2195 775 779 2196 779 775 2197 775 778 2198 778 748 2199 748 779 2200 779 778 2201 778 748 2202 748 778 2203 778 780 2204 780 748 2205 748 780 2206 780 781 2207 781 814 2208 814 783 2209 783 782 2210 782 786 2211 786 785 2212 785 784 2213 784 788 2214 788 786 2215 786 784 2216 784 788 2217 788 784 2218 784 787 2219 787 789 2220 789 788 2221 788 787 2222 787 791 2223 791 789 2224 789 787 2225 787 791 2226 791 787 2227 787 790 2228 790 793 2229 793 791 2230 791 790 2231 790 793 2232 793 790 2233 790 792 2234 792 795 2235 795 793 2236 793 792 2237 792 795 2238 795 792 2239 792 794 2240 794 797 2241 797 795 2242 795 794 2243 794 797 2244 797 794 2245 794 796 2246 796 799 2247 799 797 2248 797 796 2249 796 799 2250 799 796 2251 796 798 2252 798 801 2253 801 799 2254 799 798 2255 798 801 2256 801 798 2257 798 800 2258 800 803 2259 803 801 2260 801 800 2261 800 803 2262 803 800 2263 800 802 2264 802 805 2265 805 803 2266 803 802 2267 802 805 2268 805 802 2269 802 804 2270 804 807 2271 807 805 2272 805 804 2273 804 807 2274 807 804 2275 804 806 2276 806 809 2277 809 807 2278 807 806 2279 806 809 2280 809 806 2281 806 808 2282 808 811 2283 811 809 2284 809 808 2285 808 811 2286 811 808 2287 808 810 2288 810 813 2289 813 811 2290 811 810 2291 810 813 2292 813 810 2293 810 812 2294 812 815 2295 815 813 2296 813 812 2297 812 815 2298 815 812 2299 812 814 2300 814 782 2301 782 815 2302 815 814 2303 814 847 2304 847 817 2305 817 816 2306 816 821 2307 821 819 2308 819 818 2309 818 821 2310 821 818 2311 818 820 2312 820 823 2313 823 821 2314 821 820 2315 820 823 2316 823 820 2317 820 822 2318 822 825 2319 825 823 2320 823 822 2321 822 825 2322 825 822 2323 822 824 2324 824 827 2325 827 825 2326 825 824 2327 824 827 2328 827 824 2329 824 826 2330 826 829 2331 829 827 2332 827 826 2333 826 829 2334 829 826 2335 826 828 2336 828 831 2337 831 829 2338 829 828 2339 828 831 2340 831 828 2341 828 830 2342 830 833 2343 833 831 2344 831 830 2345 830 833 2346 833 830 2347 830 832 2348 832 835 2349 835 833 2350 833 832 2351 832 835 2352 835 832 2353 832 834 2354 834 837 2355 837 835 2356 835 834 2357 834 837 2358 837 834 2359 834 836 2360 836 839 2361 839 837 2362 837 836 2363 836 839 2364 839 836 2365 836 838 2366 838 841 2367 841 839 2368 839 838 2369 838 841 2370 841 838 2371 838 840 2372 840 843 2373 843 841 2374 841 840 2375 840 843 2376 843 840 2377 840 842 2378 842 845 2379 845 843 2380 843 842 2381 842 845 2382 845 842 2383 842 844 2384 844 848 2385 848 845 2386 845 844 2387 844 848 2388 848 844 2389 844 846 2390 846 848 2391 848 846 2392 846 847 2393 847 849 2394 849 848 2395 848 847 2396 847 816 2397 816 849 2398 849 847 2399 847 883 2400 883 851 2401 851 850 2402 850 853 2403 853 852 2404 852 851 2405 851 883 2406 883 853 2407 853 851 2408 851 856 2409 856 855 2410 855 854 2411 854 857 2412 857 856 2413 856 854 2414 854 859 2415 859 857 2416 857 854 2417 854 859 2418 859 854 2419 854 858 2420 858 861 2421 861 859 2422 859 858 2423 858 861 2424 861 858 2425 858 860 2426 860 864 2427 864 861 2428 861 860 2429 860 864 2430 864 860 2431 860 862 2432 862 864 2433 864 862 2434 862 863 2435 863 865 2436 865 864 2437 864 863 2438 863 867 2439 867 865 2440 865 863 2441 863 867 2442 867 863 2443 863 866 2444 866 870 2445 870 867 2446 867 866 2447 866 870 2448 870 866 2449 866 868 2450 868 870 2451 870 868 2452 868 869 2453 869 872 2454 872 870 2455 870 869 2456 869 872 2457 872 869 2458 869 871 2459 871 873 2460 873 872 2461 872 871 2462 871 875 2463 875 873 2464 873 871 2465 871 875 2466 875 871 2467 871 874 2468 874 877 2469 877 875 2470 875 874 2471 874 877 2472 877 874 2473 874 876 2474 876 879 2475 879 877 2476 877 876 2477 876 879 2478 879 876 2479 876 878 2480 878 882 2481 882 879 2482 879 878 2483 878 882 2484 882 878 2485 878 880 2486 880 882 2487 882 880 2488 880 881 2489 881 850 2490 850 882 2491 882 881 2492 881 850 2493 850 881 2494 881 883 2495 883 916 2496 916 885 2497 885 884 2498 884 889 2499 889 887 2500 887 886 2501 886 889 2502 889 886 2503 886 888 2504 888 891 2505 891 889 2506 889 888 2507 888 891 2508 891 888 2509 888 890 2510 890 893 2511 893 891 2512 891 890 2513 890 893 2514 893 890 2515 890 892 2516 892 895 2517 895 893 2518 893 892 2519 892 895 2520 895 892 2521 892 894 2522 894 898 2523 898 895 2524 895 894 2525 894 898 2526 898 894 2527 894 896 2528 896 898 2529 898 896 2530 896 897 2531 897 899 2532 899 898 2533 898 897 2534 897 901 2535 901 899 2536 899 897 2537 897 901 2538 901 897 2539 897 900 2540 900 903 2541 903 901 2542 901 900 2543 900 903 2544 903 900 2545 900 902 2546 902 905 2547 905 903 2548 903 902 2549 902 905 2550 905 902 2551 902 904 2552 904 907 2553 907 905 2554 905 904 2555 904 907 2556 907 904 2557 904 906 2558 906 909 2559 909 907 2560 907 906 2561 906 909 2562 909 906 2563 906 908 2564 908 911 2565 911 909 2566 909 908 2567 908 911 2568 911 908 2569 908 910 2570 910 913 2571 913 911 2572 911 910 2573 910 913 2574 913 910 2575 910 912 2576 912 915 2577 915 913 2578 913 912 2579 912 915 2580 915 912 2581 912 914 2582 914 917 2583 917 915 2584 915 914 2585 914 917 2586 917 914 2587 914 916 2588 916 884 2589 884 917 2590 917 916 2591 916 949 2592 949 918 2593 918 926 2594 926 921 2595 921 920 2596 920 919 2597 919 922 2598 922 921 2599 921 919 2600 919 924 2601 924 922 2602 922 919 2603 919 924 2604 924 919 2605 919 923 2606 923 927 2607 927 924 2608 924 923 2609 923 927 2610 927 923 2611 923 925 2612 925 927 2613 927 925 2614 925 926 2615 926 918 2616 918 927 2617 927 926 2618 926 931 2619 931 929 2620 929 928 2621 928 931 2622 931 928 2623 928 930 2624 930 934 2625 934 931 2626 931 930 2627 930 934 2628 934 930 2629 930 932 2630 932 934 2631 934 932 2632 932 933 2633 933 935 2634 935 934 2635 934 933 2636 933 937 2637 937 935 2638 935 933 2639 933 937 2640 937 933 2641 933 936 2642 936 939 2643 939 937 2644 937 936 2645 936 939 2646 939 936 2647 936 938 2648 938 941 2649 941 939 2650 939 938 2651 938 941 2652 941 938 2653 938 940 2654 940 943 2655 943 941 2656 941 940 2657 940 943 2658 943 940 2659 940 942 2660 942 945 2661 945 943 2662 943 942 2663 942 945 2664 945 942 2665 942 944 2666 944 947 2667 947 945 2668 945 944 2669 944 947 2670 947 944 2671 944 946 2672 946 950 2673 950 947 2674 947 946 2675 946 950 2676 950 946 2677 946 948 2678 948 950 2679 950 948 2680 948 949 2681 949 951 2682 951 950 2683 950 949 2684 949 926 2685 926 951 2686 951 949 2687 949 983 2688 983 953 2689 953 952 2690 952 957 2691 957 955 2692 955 954 2693 954 957 2694 957 954 2695 954 956 2696 956 959 2697 959 957 2698 957 956 2699 956 959 2700 959 956 2701 956 958 2702 958 961 2703 961 959 2704 959 958 2705 958 961 2706 961 958 2707 958 960 2708 960 963 2709 963 961 2710 961 960 2711 960 963 2712 963 960 2713 960 962 2714 962 965 2715 965 963 2716 963 962 2717 962 965 2718 965 962 2719 962 964 2720 964 967 2721 967 965 2722 965 964 2723 964 967 2724 967 964 2725 964 966 2726 966 969 2727 969 967 2728 967 966 2729 966 969 2730 969 966 2731 966 968 2732 968 971 2733 971 969 2734 969 968 2735 968 971 2736 971 968 2737 968 970 2738 970 973 2739 973 971 2740 971 970 2741 970 973 2742 973 970 2743 970 972 2744 972 976 2745 976 973 2746 973 972 2747 972 976 2748 976 972 2749 972 974 2750 974 976 2751 976 974 2752 974 975 2753 975 977 2754 977 976 2755 976 975 2756 975 979 2757 979 977 2758 977 975 2759 975 979 2760 979 975 2761 975 978 2762 978 981 2763 981 979 2764 979 978 2765 978 981 2766 981 978 2767 978 980 2768 980 984 2769 984 981 2770 981 980 2771 980 984 2772 984 980 2773 980 982 2774 982 984 2775 984 982 2776 982 983 2777 983 985 2778 985 984 2779 984 983 2780 983 952 2781 952 985 2782 985 983 2783 983 1018 2784 1018 987 2785 987 986 2786 986 990 2787 990 989 2788 989 988 2789 988 991 2790 991 990 2791 990 988 2792 988 994 2793 994 991 2794 991 988 2795 988 994 2796 994 988 2797 988 992 2798 992 994 2799 994 992 2800 992 993 2801 993 996 2802 996 994 2803 994 993 2804 993 996 2805 996 993 2806 993 995 2807 995 998 2808 998 996 2809 996 995 2810 995 998 2811 998 995 2812 995 997 2813 997 999 2814 999 998 2815 998 997 2816 997 1002 2817 1002 999 2818 999 997 2819 997 1002 2820 1002 997 2821 997 1000 2822 1000 1002 2823 1002 1000 2824 1000 1001 2825 1001 1003 2826 1003 1002 2827 1002 1001 2828 1001 1005 2829 1005 1003 2830 1003 1001 2831 1001 1005 2832 1005 1001 2833 1001 1004 2834 1004 1007 2835 1007 1005 2836 1005 1004 2837 1004 1007 2838 1007 1004 2839 1004 1006 2840 1006 1009 2841 1009 1007 2842 1007 1006 2843 1006 1009 2844 1009 1006 2845 1006 1008 2846 1008 1011 2847 1011 1009 2848 1009 1008 2849 1008 1011 2850 1011 1008 2851 1008 1010 2852 1010 1013 2853 1013 1011 2854 1011 1010 2855 1010 1013 2856 1013 1010 2857 1010 1012 2858 1012 1015 2859 1015 1013 2860 1013 1012 2861 1012 1015 2862 1015 1012 2863 1012 1014 2864 1014 1017 2865 1017 1015 2866 1015 1014 2867 1014 1017 2868 1017 1014 2869 1014 1016 2870 1016 1019 2871 1019 1017 2872 1017 1016 2873 1016 1019 2874 1019 1016 2875 1016 1018 2876 1018 986 2877 986 1019 2878 1019 1018 2879 1018 1052 2880 1052 1021 2881 1021 1020 2882 1020 1025 2883 1025 1023 2884 1023 1022 2885 1022 1025 2886 1025 1022 2887 1022 1024 2888 1024 1028 2889 1028 1025 2890 1025 1024 2891 1024 1028 2892 1028 1024 2893 1024 1026 2894 1026 1028 2895 1028 1026 2896 1026 1027 2897 1027 1029 2898 1029 1028 2899 1028 1027 2900 1027 1031 2901 1031 1029 2902 1029 1027 2903 1027 1031 2904 1031 1027 2905 1027 1030 2906 1030 1033 2907 1033 1031 2908 1031 1030 2909 1030 1033 2910 1033 1030 2911 1030 1032 2912 1032 1035 2913 1035 1033 2914 1033 1032 2915 1032 1035 2916 1035 1032 2917 1032 1034 2918 1034 1037 2919 1037 1035 2920 1035 1034 2921 1034 1037 2922 1037 1034 2923 1034 1036 2924 1036 1039 2925 1039 1037 2926 1037 1036 2927 1036 1039 2928 1039 1036 2929 1036 1038 2930 1038 1041 2931 1041 1039 2932 1039 1038 2933 1038 1041 2934 1041 1038 2935 1038 1040 2936 1040 1043 2937 1043 1041 2938 1041 1040 2939 1040 1043 2940 1043 1040 2941 1040 1042 2942 1042 1046 2943 1046 1043 2944 1043 1042 2945 1042 1046 2946 1046 1042 2947 1042 1044 2948 1044 1046 2949 1046 1044 2950 1044 1045 2951 1045 1047 2952 1047 1046 2953 1046 1045 2954 1045 1049 2955 1049 1047 2956 1047 1045 2957 1045 1049 2958 1049 1045 2959 1045 1048 2960 1048 1051 2961 1051 1049 2962 1049 1048 2963 1048 1051 2964 1051 1048 2965 1048 1050 2966 1050 1053 2967 1053 1051 2968 1051 1050 2969 1050 1053 2970 1053 1050 2971 1050 1052 2972 1052 1020 2973 1020 1053 2974 1053 1052 2975 1052 1087 2976 1087 1059 2977 1059 1054 2978 1054 1058 2979 1058 1056 2980 1056 1055 2981 1055 1058 2982 1058 1055 2983 1055 1057 2984 1057 1087 2985 1087 1058 2986 1058 1057 2987 1057 1087 2988 1087 1057 2989 1057 1059 2990 1059 1063 2991 1063 1061 2992 1061 1060 2993 1060 1063 2994 1063 1060 2995 1060 1062 2996 1062 1066 2997 1066 1063 2998 1063 1062 2999 1062 1066 3000 1066 1062 3001 1062 1064 3002 1064 1066 3003 1066 1064 3004 1064 1065 3005 1065 1067 3006 1067 1066 3007 1066 1065 3008 1065 1069 3009 1069 1067 3010 1067 1065 3011 1065 1069 3012 1069 1065 3013 1065 1068 3014 1068 1071 3015 1071 1069 3016 1069 1068 3017 1068 1071 3018 1071 1068 3019 1068 1070 3020 1070 1073 3021 1073 1071 3022 1071 1070 3023 1070 1073 3024 1073 1070 3025 1070 1072 3026 1072 1076 3027 1076 1073 3028 1073 1072 3029 1072 1076 3030 1076 1072 3031 1072 1074 3032 1074 1076 3033 1076 1074 3034 1074 1075 3035 1075 1077 3036 1077 1076 3037 1076 1075 3038 1075 1079 3039 1079 1077 3040 1077 1075 3041 1075 1079 3042 1079 1075 3043 1075 1078 3044 1078 1081 3045 1081 1079 3046 1079 1078 3047 1078 1081 3048 1081 1078 3049 1078 1080 3050 1080 1083 3051 1083 1081 3052 1081 1080 3053 1080 1083 3054 1083 1080 3055 1080 1082 3056 1082 1085 3057 1085 1083 3058 1083 1082 3059 1082 1085 3060 1085 1082 3061 1082 1084 3062 1084 1054 3063 1054 1085 3064 1085 1084 3065 1084 1054 3066 1054 1084 3067 1084 1086 3068 1086 1054 3069 1054 1086 3070 1086 1087 3071 1087 1120 3072 1120 1089 3073 1089 1088 3074 1088 1093 3075 1093 1091 3076 1091 1090 3077 1090 1093 3078 1093 1090 3079 1090 1092 3080 1092 1096 3081 1096 1093 3082 1093 1092 3083 1092 1096 3084 1096 1092 3085 1092 1094 3086 1094 1096 3087 1096 1094 3088 1094 1095 3089 1095 1097 3090 1097 1096 3091 1096 1095 3092 1095 1099 3093 1099 1097 3094 1097 1095 3095 1095 1099 3096 1099 1095 3097 1095 1098 3098 1098 1101 3099 1101 1099 3100 1099 1098 3101 1098 1101 3102 1101 1098 3103 1098 1100 3104 1100 1103 3105 1103 1101 3106 1101 1100 3107 1100 1103 3108 1103 1100 3109 1100 1102 3110 1102 1106 3111 1106 1103 3112 1103 1102 3113 1102 1106 3114 1106 1102 3115 1102 1104 3116 1104 1106 3117 1106 1104 3118 1104 1105 3119 1105 1107 3120 1107 1106 3121 1106 1105 3122 1105 1109 3123 1109 1107 3124 1107 1105 3125 1105 1109 3126 1109 1105 3127 1105 1108 3128 1108 1111 3129 1111 1109 3130 1109 1108 3131 1108 1111 3132 1111 1108 3133 1108 1110 3134 1110 1113 3135 1113 1111 3136 1111 1110 3137 1110 1113 3138 1113 1110 3139 1110 1112 3140 1112 1115 3141 1115 1113 3142 1113 1112 3143 1112 1115 3144 1115 1112 3145 1112 1114 3146 1114 1117 3147 1117 1115 3148 1115 1114 3149 1114 1117 3150 1117 1114 3151 1114 1116 3152 1116 1119 3153 1119 1117 3154 1117 1116 3155 1116 1119 3156 1119 1116 3157 1116 1118 3158 1118 1121 3159 1121 1119 3160 1119 1118 3161 1118 1121 3162 1121 1118 3163 1118 1120 3164 1120 1088 3165 1088 1121 3166 1121 1120 3167 1120 1155 3168 1155 1125 3169 1125 1122 3170 1122 1155 3171 1155 1124 3172 1124 1123 3173 1123 1155 3174 1155 1123 3175 1123 1125 3176 1125 1129 3177 1129 1127 3178 1127 1126 3179 1126 1129 3180 1129 1126 3181 1126 1128 3182 1128 1132 3183 1132 1129 3184 1129 1128 3185 1128 1132 3186 1132 1128 3187 1128 1130 3188 1130 1132 3189 1132 1130 3190 1130 1131 3191 1131 1133 3192 1133 1132 3193 1132 1131 3194 1131 1135 3195 1135 1133 3196 1133 1131 3197 1131 1135 3198 1135 1131 3199 1131 1134 3200 1134 1137 3201 1137 1135 3202 1135 1134 3203 1134 1137 3204 1137 1134 3205 1134 1136 3206 1136 1140 3207 1140 1137 3208 1137 1136 3209 1136 1140 3210 1140 1136 3211 1136 1138 3212 1138 1140 3213 1140 1138 3214 1138 1139 3215 1139 1141 3216 1141 1140 3217 1140 1139 3218 1139 1143 3219 1143 1141 3220 1141 1139 3221 1139 1143 3222 1143 1139 3223 1139 1142 3224 1142 1145 3225 1145 1143 3226 1143 1142 3227 1142 1145 3228 1145 1142 3229 1142 1144 3230 1144 1147 3231 1147 1145 3232 1145 1144 3233 1144 1147 3234 1147 1144 3235 1144 1146 3236 1146 1149 3237 1149 1147 3238 1147 1146 3239 1146 1149 3240 1149 1146 3241 1146 1148 3242 1148 1151 3243 1151 1149 3244 1149 1148 3245 1148 1151 3246 1151 1148 3247 1148 1150 3248 1150 1153 3249 1153 1151 3250 1151 1150 3251 1150 1153 3252 1153 1150 3253 1150 1152 3254 1152 1122 3255 1122 1153 3256 1153 1152 3257 1152 1122 3258 1122 1152 3259 1152 1154 3260 1154 1122 3261 1122 1154 3262 1154 1155 3263 1155 1187 3264 1187 1157 3265 1157 1156 3266 1156 1162 3267 1162 1159 3268 1159 1158 3269 1158 1162 3270 1162 1158 3271 1158 1160 3272 1160 1162 3273 1162 1160 3274 1160 1161 3275 1161 1163 3276 1163 1162 3277 1162 1161 3278 1161 1165 3279 1165 1163 3280 1163 1161 3281 1161 1165 3282 1165 1161 3283 1161 1164 3284 1164 1167 3285 1167 1165 3286 1165 1164 3287 1164 1167 3288 1167 1164 3289 1164 1166 3290 1166 1169 3291 1169 1167 3292 1167 1166 3293 1166 1169 3294 1169 1166 3295 1166 1168 3296 1168 1171 3297 1171 1169 3298 1169 1168 3299 1168 1171 3300 1171 1168 3301 1168 1170 3302 1170 1173 3303 1173 1171 3304 1171 1170 3305 1170 1173 3306 1173 1170 3307 1170 1172 3308 1172 1175 3309 1175 1173 3310 1173 1172 3311 1172 1175 3312 1175 1172 3313 1172 1174 3314 1174 1177 3315 1177 1175 3316 1175 1174 3317 1174 1177 3318 1177 1174 3319 1174 1176 3320 1176 1179 3321 1179 1177 3322 1177 1176 3323 1176 1179 3324 1179 1176 3325 1176 1178 3326 1178 1182 3327 1182 1179 3328 1179 1178 3329 1178 1182 3330 1182 1178 3331 1178 1180 3332 1180 1182 3333 1182 1180 3334 1180 1181 3335 1181 1183 3336 1183 1182 3337 1182 1181 3338 1181 1185 3339 1185 1183 3340 1183 1181 3341 1181 1185 3342 1185 1181 3343 1181 1184 3344 1184 1188 3345 1188 1185 3346 1185 1184 3347 1184 1188 3348 1188 1184 3349 1184 1186 3350 1186 1188 3351 1188 1186 3352 1186 1187 3353 1187 1189 3354 1189 1188 3355 1188 1187 3356 1187 1156 3357 1156 1189 3358 1189 1187 3359 1187 1221 3360 1221 1191 3361 1191 1190 3362 1190 1194 3363 1194 1193 3364 1193 1192 3365 1192 1195 3366 1195 1194 3367 1194 1192 3368 1192 1197 3369 1197 1195 3370 1195 1192 3371 1192 1197 3372 1197 1192 3373 1192 1196 3374 1196 1199 3375 1199 1197 3376 1197 1196 3377 1196 1199 3378 1199 1196 3379 1196 1198 3380 1198 1201 3381 1201 1199 3382 1199 1198 3383 1198 1201 3384 1201 1198 3385 1198 1200 3386 1200 1203 3387 1203 1201 3388 1201 1200 3389 1200 1203 3390 1203 1200 3391 1200 1202 3392 1202 1205 3393 1205 1203 3394 1203 1202 3395 1202 1205 3396 1205 1202 3397 1202 1204 3398 1204 1207 3399 1207 1205 3400 1205 1204 3401 1204 1207 3402 1207 1204 3403 1204 1206 3404 1206 1209 3405 1209 1207 3406 1207 1206 3407 1206 1209 3408 1209 1206 3409 1206 1208 3410 1208 1211 3411 1211 1209 3412 1209 1208 3413 1208 1211 3414 1211 1208 3415 1208 1210 3416 1210 1213 3417 1213 1211 3418 1211 1210 3419 1210 1213 3420 1213 1210 3421 1210 1212 3422 1212 1216 3423 1216 1213 3424 1213 1212 3425 1212 1216 3426 1216 1212 3427 1212 1214 3428 1214 1216 3429 1216 1214 3430 1214 1215 3431 1215 1217 3432 1217 1216 3433 1216 1215 3434 1215 1219 3435 1219 1217 3436 1217 1215 3437 1215 1219 3438 1219 1215 3439 1215 1218 3440 1218 1222 3441 1222 1219 3442 1219 1218 3443 1218 1222 3444 1222 1218 3445 1218 1220 3446 1220 1222 3447 1222 1220 3448 1220 1221 3449 1221 1223 3450 1223 1222 3451 1222 1221 3452 1221 1190 3453 1190 1223 3454 1223 1221 3455 1221 1256 3456 1256 1225 3457 1225 1224 3458 1224 1229 3459 1229 1227 3460 1227 1226 3461 1226 1229 3462 1229 1226 3463 1226 1228 3464 1228 1231 3465 1231 1229 3466 1229 1228 3467 1228 1231 3468 1231 1228 3469 1228 1230 3470 1230 1233 3471 1233 1231 3472 1231 1230 3473 1230 1233 3474 1233 1230 3475 1230 1232 3476 1232 1235 3477 1235 1233 3478 1233 1232 3479 1232 1235 3480 1235 1232 3481 1232 1234 3482 1234 1237 3483 1237 1235 3484 1235 1234 3485 1234 1237 3486 1237 1234 3487 1234 1236 3488 1236 1239 3489 1239 1237 3490 1237 1236 3491 1236 1239 3492 1239 1236 3493 1236 1238 3494 1238 1241 3495 1241 1239 3496 1239 1238 3497 1238 1241 3498 1241 1238 3499 1238 1240 3500 1240 1243 3501 1243 1241 3502 1241 1240 3503 1240 1243 3504 1243 1240 3505 1240 1242 3506 1242 1245 3507 1245 1243 3508 1243 1242 3509 1242 1245 3510 1245 1242 3511 1242 1244 3512 1244 1247 3513 1247 1245 3514 1245 1244 3515 1244 1247 3516 1247 1244 3517 1244 1246 3518 1246 1249 3519 1249 1247 3520 1247 1246 3521 1246 1249 3522 1249 1246 3523 1246 1248 3524 1248 1251 3525 1251 1249 3526 1249 1248 3527 1248 1251 3528 1251 1248 3529 1248 1250 3530 1250 1253 3531 1253 1251 3532 1251 1250 3533 1250 1253 3534 1253 1250 3535 1250 1252 3536 1252 1255 3537 1255 1253 3538 1253 1252 3539 1252 1255 3540 1255 1252 3541 1252 1254 3542 1254 1257 3543 1257 1255 3544 1255 1254 3545 1254 1257 3546 1257 1254 3547 1254 1256 3548 1256 1224 3549 1224 1257 3550 1257 1256 3551 1256 1290 3552 1290 1259 3553 1259 1258 3554 1258 1263 3555 1263 1261 3556 1261 1260 3557 1260 1263 3558 1263 1260 3559 1260 1262 3560 1262 1265 3561 1265 1263 3562 1263 1262 3563 1262 1265 3564 1265 1262 3565 1262 1264 3566 1264 1267 3567 1267 1265 3568 1265 1264 3569 1264 1267 3570 1267 1264 3571 1264 1266 3572 1266 1269 3573 1269 1267 3574 1267 1266 3575 1266 1269 3576 1269 1266 3577 1266 1268 3578 1268 1271 3579 1271 1269 3580 1269 1268 3581 1268 1271 3582 1271 1268 3583 1268 1270 3584 1270 1273 3585 1273 1271 3586 1271 1270 3587 1270 1273 3588 1273 1270 3589 1270 1272 3590 1272 1275 3591 1275 1273 3592 1273 1272 3593 1272 1275 3594 1275 1272 3595 1272 1274 3596 1274 1277 3597 1277 1275 3598 1275 1274 3599 1274 1277 3600 1277 1274 3601 1274 1276 3602 1276 1279 3603 1279 1277 3604 1277 1276 3605 1276 1279 3606 1279 1276 3607 1276 1278 3608 1278 1281 3609 1281 1279 3610 1279 1278 3611 1278 1281 3612 1281 1278 3613 1278 1280 3614 1280 1283 3615 1283 1281 3616 1281 1280 3617 1280 1283 3618 1283 1280 3619 1280 1282 3620 1282 1286 3621 1286 1283 3622 1283 1282 3623 1282 1286 3624 1286 1282 3625 1282 1284 3626 1284 1286 3627 1286 1284 3628 1284 1285 3629 1285 1287 3630 1287 1286 3631 1286 1285 3632 1285 1289 3633 1289 1287 3634 1287 1285 3635 1285 1289 3636 1289 1285 3637 1285 1288 3638 1288 1291 3639 1291 1289 3640 1289 1288 3641 1288 1291 3642 1291 1288 3643 1288 1290 3644 1290 1258 3645 1258 1291 3646 1291 1290 3647 1290 1324 3648 1324 1293 3649 1293 1292 3650 1292 1297 3651 1297 1295 3652 1295 1294 3653 1294 1297 3654 1297 1294 3655 1294 1296 3656 1296 1299 3657 1299 1297 3658 1297 1296 3659 1296 1299 3660 1299 1296 3661 1296 1298 3662 1298 1301 3663 1301 1299 3664 1299 1298 3665 1298 1301 3666 1301 1298 3667 1298 1300 3668 1300 1303 3669 1303 1301 3670 1301 1300 3671 1300 1303 3672 1303 1300 3673 1300 1302 3674 1302 1305 3675 1305 1303 3676 1303 1302 3677 1302 1305 3678 1305 1302 3679 1302 1304 3680 1304 1307 3681 1307 1305 3682 1305 1304 3683 1304 1307 3684 1307 1304 3685 1304 1306 3686 1306 1309 3687 1309 1307 3688 1307 1306 3689 1306 1309 3690 1309 1306 3691 1306 1308 3692 1308 1311 3693 1311 1309 3694 1309 1308 3695 1308 1311 3696 1311 1308 3697 1308 1310 3698 1310 1313 3699 1313 1311 3700 1311 1310 3701 1310 1313 3702 1313 1310 3703 1310 1312 3704 1312 1315 3705 1315 1313 3706 1313 1312 3707 1312 1315 3708 1315 1312 3709 1312 1314 3710 1314 1317 3711 1317 1315 3712 1315 1314 3713 1314 1317 3714 1317 1314 3715 1314 1316 3716 1316 1319 3717 1319 1317 3718 1317 1316 3719 1316 1319 3720 1319 1316 3721 1316 1318 3722 1318 1321 3723 1321 1319 3724 1319 1318 3725 1318 1321 3726 1321 1318 3727 1318 1320 3728 1320 1323 3729 1323 1321 3730 1321 1320 3731 1320 1323 3732 1323 1320 3733 1320 1322 3734 1322 1325 3735 1325 1323 3736 1323 1322 3737 1322 1325 3738 1325 1322 3739 1322 1324 3740 1324 1292 3741 1292 1325 3742 1325 1324 3743 1324 1357 3744 1357 1327 3745 1327 1326 3746 1326 1331 3747 1331 1329 3748 1329 1328 3749 1328 1331 3750 1331 1328 3751 1328 1330 3752 1330 1333 3753 1333 1331 3754 1331 1330 3755 1330 1333 3756 1333 1330 3757 1330 1332 3758 1332 1336 3759 1336 1333 3760 1333 1332 3761 1332 1336 3762 1336 1332 3763 1332 1334 3764 1334 1336 3765 1336 1334 3766 1334 1335 3767 1335 1337 3768 1337 1336 3769 1336 1335 3770 1335 1339 3771 1339 1337 3772 1337 1335 3773 1335 1339 3774 1339 1335 3775 1335 1338 3776 1338 1341 3777 1341 1339 3778 1339 1338 3779 1338 1341 3780 1341 1338 3781 1338 1340 3782 1340 1343 3783 1343 1341 3784 1341 1340 3785 1340 1343 3786 1343 1340 3787 1340 1342 3788 1342 1345 3789 1345 1343 3790 1343 1342 3791 1342 1345 3792 1345 1342 3793 1342 1344 3794 1344 1347 3795 1347 1345 3796 1345 1344 3797 1344 1347 3798 1347 1344 3799 1344 1346 3800 1346 1350 3801 1350 1347 3802 1347 1346 3803 1346 1350 3804 1350 1346 3805 1346 1348 3806 1348 1350 3807 1350 1348 3808 1348 1349 3809 1349 1351 3810 1351 1350 3811 1350 1349 3812 1349 1354 3813 1354 1351 3814 1351 1349 3815 1349 1354 3816 1354 1349 3817 1349 1352 3818 1352 1354 3819 1354 1352 3820 1352 1353 3821 1353 1356 3822 1356 1354 3823 1354 1353 3824 1353 1356 3825 1356 1353 3826 1353 1355 3827 1355 1358 3828 1358 1356 3829 1356 1355 3830 1355 1358 3831 1358 1355 3832 1355 1357 3833 1357 1359 3834 1359 1358 3835 1358 1357 3836 1357 1326 3837 1326 1359 3838 1359 1357 3839 1357 1393 3840 1393 1361 3841 1361 1360 3842 1360 1365 3843 1365 1363 3844 1363 1362 3845 1362 1365 3846 1365 1362 3847 1362 1364 3848 1364 1367 3849 1367 1365 3850 1365 1364 3851 1364 1367 3852 1367 1364 3853 1364 1366 3854 1366 1369 3855 1369 1367 3856 1367 1366 3857 1366 1369 3858 1369 1366 3859 1366 1368 3860 1368 1371 3861 1371 1369 3862 1369 1368 3863 1368 1371 3864 1371 1368 3865 1368 1370 3866 1370 1373 3867 1373 1371 3868 1371 1370 3869 1370 1373 3870 1373 1370 3871 1370 1372 3872 1372 1375 3873 1375 1373 3874 1373 1372 3875 1372 1375 3876 1375 1372 3877 1372 1374 3878 1374 1377 3879 1377 1375 3880 1375 1374 3881 1374 1377 3882 1377 1374 3883 1374 1376 3884 1376 1379 3885 1379 1377 3886 1377 1376 3887 1376 1379 3888 1379 1376 3889 1376 1378 3890 1378 1381 3891 1381 1379 3892 1379 1378 3893 1378 1381 3894 1381 1378 3895 1378 1380 3896 1380 1383 3897 1383 1381 3898 1381 1380 3899 1380 1383 3900 1383 1380 3901 1380 1382 3902 1382 1385 3903 1385 1383 3904 1383 1382 3905 1382 1385 3906 1385 1382 3907 1382 1384 3908 1384 1387 3909 1387 1385 3910 1385 1384 3911 1384 1387 3912 1387 1384 3913 1384 1386 3914 1386 1389 3915 1389 1387 3916 1387 1386 3917 1386 1389 3918 1389 1386 3919 1386 1388 3920 1388 1391 3921 1391 1389 3922 1389 1388 3923 1388 1391 3924 1391 1388 3925 1388 1390 3926 1390 1360 3927 1360 1391 3928 1391 1390 3929 1390 1360 3930 1360 1390 3931 1390 1392 3932 1392 1360 3933 1360 1392 3934 1392 1393 3935 1393 1425 3936 1425 1395 3937 1395 1394 3938 1394 1399 3939 1399 1397 3940 1397 1396 3941 1396 1399 3942 1399 1396 3943 1396 1398 3944 1398 1401 3945 1401 1399 3946 1399 1398 3947 1398 1401 3948 1401 1398 3949 1398 1400 3950 1400 1403 3951 1403 1401 3952 1401 1400 3953 1400 1403 3954 1403 1400 3955 1400 1402 3956 1402 1405 3957 1405 1403 3958 1403 1402 3959 1402 1405 3960 1405 1402 3961 1402 1404 3962 1404 1407 3963 1407 1405 3964 1405 1404 3965 1404 1407 3966 1407 1404 3967 1404 1406 3968 1406 1409 3969 1409 1407 3970 1407 1406 3971 1406 1409 3972 1409 1406 3973 1406 1408 3974 1408 1411 3975 1411 1409 3976 1409 1408 3977 1408 1411 3978 1411 1408 3979 1408 1410 3980 1410 1413 3981 1413 1411 3982 1411 1410 3983 1410 1413 3984 1413 1410 3985 1410 1412 3986 1412 1415 3987 1415 1413 3988 1413 1412 3989 1412 1415 3990 1415 1412 3991 1412 1414 3992 1414 1417 3993 1417 1415 3994 1415 1414 3995 1414 1417 3996 1417 1414 3997 1414 1416 3998 1416 1419 3999 1419 1417 4000 1417 1416 4001 1416 1419 4002 1419 1416 4003 1416 1418 4004 1418 1422 4005 1422 1419 4006 1419 1418 4007 1418 1422 4008 1422 1418 4009 1418 1420 4010 1420 1422 4011 1422 1420 4012 1420 1421 4013 1421 1424 4014 1424 1422 4015 1422 1421 4016 1421 1424 4017 1424 1421 4018 1421 1423 4019 1423 1426 4020 1426 1424 4021 1424 1423 4022 1423 1426 4023 1426 1423 4024 1423 1425 4025 1425 1427 4026 1427 1426 4027 1426 1425 4028 1425 1394 4029 1394 1427 4030 1427 1425 4031 1425 1459 4032 1459 1429 4033 1429 1428 4034 1428 1433 4035 1433 1431 4036 1431 1430 4037 1430 1433 4038 1433 1430 4039 1430 1432 4040 1432 1435 4041 1435 1433 4042 1433 1432 4043 1432 1435 4044 1435 1432 4045 1432 1434 4046 1434 1437 4047 1437 1435 4048 1435 1434 4049 1434 1437 4050 1437 1434 4051 1434 1436 4052 1436 1440 4053 1440 1437 4054 1437 1436 4055 1436 1440 4056 1440 1436 4057 1436 1438 4058 1438 1440 4059 1440 1438 4060 1438 1439 4061 1439 1441 4062 1441 1440 4063 1440 1439 4064 1439 1443 4065 1443 1441 4066 1441 1439 4067 1439 1443 4068 1443 1439 4069 1439 1442 4070 1442 1445 4071 1445 1443 4072 1443 1442 4073 1442 1445 4074 1445 1442 4075 1442 1444 4076 1444 1447 4077 1447 1445 4078 1445 1444 4079 1444 1447 4080 1447 1444 4081 1444 1446 4082 1446 1449 4083 1449 1447 4084 1447 1446 4085 1446 1449 4086 1449 1446 4087 1446 1448 4088 1448 1452 4089 1452 1449 4090 1449 1448 4091 1448 1452 4092 1452 1448 4093 1448 1450 4094 1450 1452 4095 1452 1450 4096 1450 1451 4097 1451 1453 4098 1453 1452 4099 1452 1451 4100 1451 1455 4101 1455 1453 4102 1453 1451 4103 1451 1455 4104 1455 1451 4105 1451 1454 4106 1454 1457 4107 1457 1455 4108 1455 1454 4109 1454 1457 4110 1457 1454 4111 1454 1456 4112 1456 1460 4113 1460 1457 4114 1457 1456 4115 1456 1460 4116 1460 1456 4117 1456 1458 4118 1458 1460 4119 1460 1458 4120 1458 1459 4121 1459 1461 4122 1461 1460 4123 1460 1459 4124 1459 1428 4125 1428 1461 4126 1461 1459 4127 1459 1494 4128 1494 1463 4129 1463 1462 4130 1462 1467 4131 1467 1465 4132 1465 1464 4133 1464 1467 4134 1467 1464 4135 1464 1466 4136 1466 1469 4137 1469 1467 4138 1467 1466 4139 1466 1469 4140 1469 1466 4141 1466 1468 4142 1468 1471 4143 1471 1469 4144 1469 1468 4145 1468 1471 4146 1471 1468 4147 1468 1470 4148 1470 1473 4149 1473 1471 4150 1471 1470 4151 1470 1473 4152 1473 1470 4153 1470 1472 4154 1472 1475 4155 1475 1473 4156 1473 1472 4157 1472 1475 4158 1475 1472 4159 1472 1474 4160 1474 1477 4161 1477 1475 4162 1475 1474 4163 1474 1477 4164 1477 1474 4165 1474 1476 4166 1476 1479 4167 1479 1477 4168 1477 1476 4169 1476 1479 4170 1479 1476 4171 1476 1478 4172 1478 1482 4173 1482 1479 4174 1479 1478 4175 1478 1482 4176 1482 1478 4177 1478 1480 4178 1480 1482 4179 1482 1480 4180 1480 1481 4181 1481 1483 4182 1483 1482 4183 1482 1481 4184 1481 1486 4185 1486 1483 4186 1483 1481 4187 1481 1486 4188 1486 1481 4189 1481 1484 4190 1484 1486 4191 1486 1484 4192 1484 1485 4193 1485 1487 4194 1487 1486 4195 1486 1485 4196 1485 1489 4197 1489 1487 4198 1487 1485 4199 1485 1489 4200 1489 1485 4201 1485 1488 4202 1488 1491 4203 1491 1489 4204 1489 1488 4205 1488 1491 4206 1491 1488 4207 1488 1490 4208 1490 1493 4209 1493 1491 4210 1491 1490 4211 1490 1493 4212 1493 1490 4213 1490 1492 4214 1492 1495 4215 1495 1493 4216 1493 1492 4217 1492 1495 4218 1495 1492 4219 1492 1494 4220 1494 1462 4221 1462 1495 4222 1495 1494 4223 1494 1528 4224 1528 1496 4225 1496 1499 4226 1499 1496 4227 1496 1498 4228 1498 1497 4229 1497 1496 4230 1496 1497 4231 1497 1499 4232 1499 1503 4233 1503 1501 4234 1501 1500 4235 1500 1503 4236 1503 1500 4237 1500 1502 4238 1502 1505 4239 1505 1503 4240 1503 1502 4241 1502 1505 4242 1505 1502 4243 1502 1504 4244 1504 1508 4245 1508 1505 4246 1505 1504 4247 1504 1508 4248 1508 1504 4249 1504 1506 4250 1506 1508 4251 1508 1506 4252 1506 1507 4253 1507 1509 4254 1509 1508 4255 1508 1507 4256 1507 1511 4257 1511 1509 4258 1509 1507 4259 1507 1511 4260 1511 1507 4261 1507 1510 4262 1510 1513 4263 1513 1511 4264 1511 1510 4265 1510 1513 4266 1513 1510 4267 1510 1512 4268 1512 1515 4269 1515 1513 4270 1513 1512 4271 1512 1515 4272 1515 1512 4273 1512 1514 4274 1514 1517 4275 1517 1515 4276 1515 1514 4277 1514 1517 4278 1517 1514 4279 1514 1516 4280 1516 1519 4281 1519 1517 4282 1517 1516 4283 1516 1519 4284 1519 1516 4285 1516 1518 4286 1518 1521 4287 1521 1519 4288 1519 1518 4289 1518 1521 4290 1521 1518 4291 1518 1520 4292 1520 1523 4293 1523 1521 4294 1521 1520 4295 1520 1523 4296 1523 1520 4297 1520 1522 4298 1522 1525 4299 1525 1523 4300 1523 1522 4301 1522 1525 4302 1525 1522 4303 1522 1524 4304 1524 1527 4305 1527 1525 4306 1525 1524 4307 1524 1527 4308 1527 1524 4309 1524 1526 4310 1526 1529 4311 1529 1527 4312 1527 1526 4313 1526 1529 4314 1529 1526 4315 1526 1528 4316 1528 1499 4317 1499 1529 4318 1529 1528 4319 1528 1561 4320 1561 1531 4321 1531 1530 4322 1530 1535 4323 1535 1533 4324 1533 1532 4325 1532 1535 4326 1535 1532 4327 1532 1534 4328 1534 1537 4329 1537 1535 4330 1535 1534 4331 1534 1537 4332 1537 1534 4333 1534 1536 4334 1536 1539 4335 1539 1537 4336 1537 1536 4337 1536 1539 4338 1539 1536 4339 1536 1538 4340 1538 1542 4341 1542 1539 4342 1539 1538 4343 1538 1542 4344 1542 1538 4345 1538 1540 4346 1540 1542 4347 1542 1540 4348 1540 1541 4349 1541 1543 4350 1543 1542 4351 1542 1541 4352 1541 1545 4353 1545 1543 4354 1543 1541 4355 1541 1545 4356 1545 1541 4357 1541 1544 4358 1544 1547 4359 1547 1545 4360 1545 1544 4361 1544 1547 4362 1547 1544 4363 1544 1546 4364 1546 1549 4365 1549 1547 4366 1547 1546 4367 1546 1549 4368 1549 1546 4369 1546 1548 4370 1548 1552 4371 1552 1549 4372 1549 1548 4373 1548 1552 4374 1552 1548 4375 1548 1550 4376 1550 1552 4377 1552 1550 4378 1550 1551 4379 1551 1554 4380 1554 1552 4381 1552 1551 4382 1551 1554 4383 1554 1551 4384 1551 1553 4385 1553 1555 4386 1555 1554 4387 1554 1553 4388 1553 1557 4389 1557 1555 4390 1555 1553 4391 1553 1557 4392 1557 1553 4393 1553 1556 4394 1556 1559 4395 1559 1557 4396 1557 1556 4397 1556 1559 4398 1559 1556 4399 1556 1558 4400 1558 1562 4401 1562 1559 4402 1559 1558 4403 1558 1562 4404 1562 1558 4405 1558 1560 4406 1560 1562 4407 1562 1560 4408 1560 1561 4409 1561 1563 4410 1563 1562 4411 1562 1561 4412 1561 1530 4413 1530 1563 4414 1563 1561 4415 1561 1596 4416 1596 1565 4417 1565 1564 4418 1564 1569 4419 1569 1567 4420 1567 1566 4421 1566 1569 4422 1569 1566 4423 1566 1568 4424 1568 1571 4425 1571 1569 4426 1569 1568 4427 1568 1571 4428 1571 1568 4429 1568 1570 4430 1570 1573 4431 1573 1571 4432 1571 1570 4433 1570 1573 4434 1573 1570 4435 1570 1572 4436 1572 1575 4437 1575 1573 4438 1573 1572 4439 1572 1575 4440 1575 1572 4441 1572 1574 4442 1574 1577 4443 1577 1575 4444 1575 1574 4445 1574 1577 4446 1577 1574 4447 1574 1576 4448 1576 1579 4449 1579 1577 4450 1577 1576 4451 1576 1579 4452 1579 1576 4453 1576 1578 4454 1578 1581 4455 1581 1579 4456 1579 1578 4457 1578 1581 4458 1581 1578 4459 1578 1580 4460 1580 1583 4461 1583 1581 4462 1581 1580 4463 1580 1583 4464 1583 1580 4465 1580 1582 4466 1582 1585 4467 1585 1583 4468 1583 1582 4469 1582 1585 4470 1585 1582 4471 1582 1584 4472 1584 1587 4473 1587 1585 4474 1585 1584 4475 1584 1587 4476 1587 1584 4477 1584 1586 4478 1586 1589 4479 1589 1587 4480 1587 1586 4481 1586 1589 4482 1589 1586 4483 1586 1588 4484 1588 1591 4485 1591 1589 4486 1589 1588 4487 1588 1591 4488 1591 1588 4489 1588 1590 4490 1590 1594 4491 1594 1591 4492 1591 1590 4493 1590 1594 4494 1594 1590 4495 1590 1592 4496 1592 1594 4497 1594 1592 4498 1592 1593 4499 1593 1595 4500 1595 1594 4501 1594 1593 4502 1593 1597 4503 1597 1595 4504 1595 1593 4505 1593 1597 4506 1597 1593 4507 1593 1596 4508 1596 1564 4509 1564 1597 4510 1597 1596 4511 1596 1630 4512 1630 1599 4513 1599 1598 4514 1598 1603 4515 1603 1601 4516 1601 1600 4517 1600 1603 4518 1603 1600 4519 1600 1602 4520 1602 1605 4521 1605 1603 4522 1603 1602 4523 1602 1605 4524 1605 1602 4525 1602 1604 4526 1604 1608 4527 1608 1605 4528 1605 1604 4529 1604 1608 4530 1608 1604 4531 1604 1606 4532 1606 1608 4533 1608 1606 4534 1606 1607 4535 1607 1609 4536 1609 1608 4537 1608 1607 4538 1607 1611 4539 1611 1609 4540 1609 1607 4541 1607 1611 4542 1611 1607 4543 1607 1610 4544 1610 1614 4545 1614 1611 4546 1611 1610 4547 1610 1614 4548 1614 1610 4549 1610 1612 4550 1612 1614 4551 1614 1612 4552 1612 1613 4553 1613 1615 4554 1615 1614 4555 1614 1613 4556 1613 1618 4557 1618 1615 4558 1615 1613 4559 1613 1618 4560 1618 1613 4561 1613 1616 4562 1616 1618 4563 1618 1616 4564 1616 1617 4565 1617 1619 4566 1619 1618 4567 1618 1617 4568 1617 1621 4569 1621 1619 4570 1619 1617 4571 1617 1621 4572 1621 1617 4573 1617 1620 4574 1620 1623 4575 1623 1621 4576 1621 1620 4577 1620 1623 4578 1623 1620 4579 1620 1622 4580 1622 1626 4581 1626 1623 4582 1623 1622 4583 1622 1626 4584 1626 1622 4585 1622 1624 4586 1624 1626 4587 1626 1624 4588 1624 1625 4589 1625 1627 4590 1627 1626 4591 1626 1625 4592 1625 1629 4593 1629 1627 4594 1627 1625 4595 1625 1629 4596 1629 1625 4597 1625 1628 4598 1628 1631 4599 1631 1629 4600 1629 1628 4601 1628 1631 4602 1631 1628 4603 1628 1630 4604 1630 1598 4605 1598 1631 4606 1631 1630 4607 1630 1664 4608 1664 1632 4609 1632 1635 4610 1635 1632 4611 1632 1634 4612 1634 1633 4613 1633 1632 4614 1632 1633 4615 1633 1635 4616 1635 1639 4617 1639 1637 4618 1637 1636 4619 1636 1639 4620 1639 1636 4621 1636 1638 4622 1638 1641 4623 1641 1639 4624 1639 1638 4625 1638 1641 4626 1641 1638 4627 1638 1640 4628 1640 1644 4629 1644 1641 4630 1641 1640 4631 1640 1644 4632 1644 1640 4633 1640 1642 4634 1642 1644 4635 1644 1642 4636 1642 1643 4637 1643 1645 4638 1645 1644 4639 1644 1643 4640 1643 1647 4641 1647 1645 4642 1645 1643 4643 1643 1647 4644 1647 1643 4645 1643 1646 4646 1646 1649 4647 1649 1647 4648 1647 1646 4649 1646 1649 4650 1649 1646 4651 1646 1648 4652 1648 1651 4653 1651 1649 4654 1649 1648 4655 1648 1651 4656 1651 1648 4657 1648 1650 4658 1650 1653 4659 1653 1651 4660 1651 1650 4661 1650 1653 4662 1653 1650 4663 1650 1652 4664 1652 1655 4665 1655 1653 4666 1653 1652 4667 1652 1655 4668 1655 1652 4669 1652 1654 4670 1654 1657 4671 1657 1655 4672 1655 1654 4673 1654 1657 4674 1657 1654 4675 1654 1656 4676 1656 1659 4677 1659 1657 4678 1657 1656 4679 1656 1659 4680 1659 1656 4681 1656 1658 4682 1658 1661 4683 1661 1659 4684 1659 1658 4685 1658 1661 4686 1661 1658 4687 1658 1660 4688 1660 1663 4689 1663 1661 4690 1661 1660 4691 1660 1663 4692 1663 1660 4693 1660 1662 4694 1662 1665 4695 1665 1663 4696 1663 1662 4697 1662 1665 4698 1665 1662 4699 1662 1664 4700 1664 1635 4701 1635 1665 4702 1665 1664 4703 1664 1698 4704 1698 1666 4705 1666 1667 4706 1667 1669 4707 1669 1668 4708 1668 1667 4709 1667 1666 4710 1666 1669 4711 1669 1667 4712 1667 1673 4713 1673 1671 4714 1671 1670 4715 1670 1673 4716 1673 1670 4717 1670 1672 4718 1672 1675 4719 1675 1673 4720 1673 1672 4721 1672 1675 4722 1675 1672 4723 1672 1674 4724 1674 1677 4725 1677 1675 4726 1675 1674 4727 1674 1677 4728 1677 1674 4729 1674 1676 4730 1676 1679 4731 1679 1677 4732 1677 1676 4733 1676 1679 4734 1679 1676 4735 1676 1678 4736 1678 1681 4737 1681 1679 4738 1679 1678 4739 1678 1681 4740 1681 1678 4741 1678 1680 4742 1680 1683 4743 1683 1681 4744 1681 1680 4745 1680 1683 4746 1683 1680 4747 1680 1682 4748 1682 1686 4749 1686 1683 4750 1683 1682 4751 1682 1686 4752 1686 1682 4753 1682 1684 4754 1684 1686 4755 1686 1684 4756 1684 1685 4757 1685 1688 4758 1688 1686 4759 1686 1685 4760 1685 1688 4761 1688 1685 4762 1685 1687 4763 1687 1689 4764 1689 1688 4765 1688 1687 4766 1687 1691 4767 1691 1689 4768 1689 1687 4769 1687 1691 4770 1691 1687 4771 1687 1690 4772 1690 1693 4773 1693 1691 4774 1691 1690 4775 1690 1693 4776 1693 1690 4777 1690 1692 4778 1692 1695 4779 1695 1693 4780 1693 1692 4781 1692 1695 4782 1695 1692 4783 1692 1694 4784 1694 1697 4785 1697 1695 4786 1695 1694 4787 1694 1697 4788 1697 1694 4789 1694 1696 4790 1696 1699 4791 1699 1697 4792 1697 1696 4793 1696 1699 4794 1699 1696 4795 1696 1698 4796 1698 1667 4797 1667 1699 4798 1699 1698 4799 1698 1731 4800 1731 1700 4801 1700 1705 4802 1705 1704 4803 1704 1702 4804 1702 1701 4805 1701 1704 4806 1704 1701 4807 1701 1703 4808 1703 1700 4809 1700 1704 4810 1704 1703 4811 1703 1700 4812 1700 1703 4813 1703 1705 4814 1705 1709 4815 1709 1707 4816 1707 1706 4817 1706 1709 4818 1709 1706 4819 1706 1708 4820 1708 1711 4821 1711 1709 4822 1709 1708 4823 1708 1711 4824 1711 1708 4825 1708 1710 4826 1710 1714 4827 1714 1711 4828 1711 1710 4829 1710 1714 4830 1714 1710 4831 1710 1712 4832 1712 1714 4833 1714 1712 4834 1712 1713 4835 1713 1715 4836 1715 1714 4837 1714 1713 4838 1713 1717 4839 1717 1715 4840 1715 1713 4841 1713 1717 4842 1717 1713 4843 1713 1716 4844 1716 1719 4845 1719 1717 4846 1717 1716 4847 1716 1719 4848 1719 1716 4849 1716 1718 4850 1718 1721 4851 1721 1719 4852 1719 1718 4853 1718 1721 4854 1721 1718 4855 1718 1720 4856 1720 1723 4857 1723 1721 4858 1721 1720 4859 1720 1723 4860 1723 1720 4861 1720 1722 4862 1722 1725 4863 1725 1723 4864 1723 1722 4865 1722 1725 4866 1725 1722 4867 1722 1724 4868 1724 1727 4869 1727 1725 4870 1725 1724 4871 1724 1727 4872 1727 1724 4873 1724 1726 4874 1726 1729 4875 1729 1727 4876 1727 1726 4877 1726 1729 4878 1729 1726 4879 1726 1728 4880 1728 1732 4881 1732 1729 4882 1729 1728 4883 1728 1732 4884 1732 1728 4885 1728 1730 4886 1730 1732 4887 1732 1730 4888 1730 1731 4889 1731 1733 4890 1733 1732 4891 1732 1731 4892 1731 1705 4893 1705 1733 4894 1733 1731 4895 1731 1765 4896 1765 1734 4897 1734 1739 4898 1739 1738 4899 1738 1736 4900 1736 1735 4901 1735 1738 4902 1738 1735 4903 1735 1737 4904 1737 1734 4905 1734 1738 4906 1738 1737 4907 1737 1734 4908 1734 1737 4909 1737 1739 4910 1739 1742 4911 1742 1741 4912 1741 1740 4913 1740 1743 4914 1743 1742 4915 1742 1740 4916 1740 1745 4917 1745 1743 4918 1743 1740 4919 1740 1745 4920 1745 1740 4921 1740 1744 4922 1744 1747 4923 1747 1745 4924 1745 1744 4925 1744 1747 4926 1747 1744 4927 1744 1746 4928 1746 1749 4929 1749 1747 4930 1747 1746 4931 1746 1749 4932 1749 1746 4933 1746 1748 4934 1748 1751 4935 1751 1749 4936 1749 1748 4937 1748 1751 4938 1751 1748 4939 1748 1750 4940 1750 1753 4941 1753 1751 4942 1751 1750 4943 1750 1753 4944 1753 1750 4945 1750 1752 4946 1752 1755 4947 1755 1753 4948 1753 1752 4949 1752 1755 4950 1755 1752 4951 1752 1754 4952 1754 1757 4953 1757 1755 4954 1755 1754 4955 1754 1757 4956 1757 1754 4957 1754 1756 4958 1756 1759 4959 1759 1757 4960 1757 1756 4961 1756 1759 4962 1759 1756 4963 1756 1758 4964 1758 1762 4965 1762 1759 4966 1759 1758 4967 1758 1762 4968 1762 1758 4969 1758 1760 4970 1760 1762 4971 1762 1760 4972 1760 1761 4973 1761 1763 4974 1763 1762 4975 1762 1761 4976 1761 1766 4977 1766 1763 4978 1763 1761 4979 1761 1766 4980 1766 1761 4981 1761 1764 4982 1764 1766 4983 1766 1764 4984 1764 1765 4985 1765 1767 4986 1767 1766 4987 1766 1765 4988 1765 1739 4989 1739 1767 4990 1767 1765 4991 1765 1800 4992 1800 1769 4993 1769 1768 4994 1768 1773 4995 1773 1771 4996 1771 1770 4997 1770 1773 4998 1773 1770 4999 1770 1772 5000 1772 1775 5001 1775 1773 5002 1773 1772 5003 1772 1775 5004 1775 1772 5005 1772 1774 5006 1774 1777 5007 1777 1775 5008 1775 1774 5009 1774 1777 5010 1777 1774 5011 1774 1776 5012 1776 1779 5013 1779 1777 5014 1777 1776 5015 1776 1779 5016 1779 1776 5017 1776 1778 5018 1778 1781 5019 1781 1779 5020 1779 1778 5021 1778 1781 5022 1781 1778 5023 1778 1780 5024 1780 1783 5025 1783 1781 5026 1781 1780 5027 1780 1783 5028 1783 1780 5029 1780 1782 5030 1782 1786 5031 1786 1783 5032 1783 1782 5033 1782 1786 5034 1786 1782 5035 1782 1784 5036 1784 1786 5037 1786 1784 5038 1784 1785 5039 1785 1787 5040 1787 1786 5041 1786 1785 5042 1785 1789 5043 1789 1787 5044 1787 1785 5045 1785 1789 5046 1789 1785 5047 1785 1788 5048 1788 1791 5049 1791 1789 5050 1789 1788 5051 1788 1791 5052 1791 1788 5053 1788 1790 5054 1790 1793 5055 1793 1791 5056 1791 1790 5057 1790 1793 5058 1793 1790 5059 1790 1792 5060 1792 1795 5061 1795 1793 5062 1793 1792 5063 1792 1795 5064 1795 1792 5065 1792 1794 5066 1794 1798 5067 1798 1795 5068 1795 1794 5069 1794 1798 5070 1798 1794 5071 1794 1796 5072 1796 1798 5073 1798 1796 5074 1796 1797 5075 1797 1799 5076 1799 1798 5077 1798 1797 5078 1797 1801 5079 1801 1799 5080 1799 1797 5081 1797 1801 5082 1801 1797 5083 1797 1800 5084 1800 1768 5085 1768 1801 5086 1801 1800 5087 1800 1834 5088 1834 1803 5089 1803 1802 5090 1802 1807 5091 1807 1805 5092 1805 1804 5093 1804 1807 5094 1807 1804 5095 1804 1806 5096 1806 1810 5097 1810 1807 5098 1807 1806 5099 1806 1810 5100 1810 1806 5101 1806 1808 5102 1808 1810 5103 1810 1808 5104 1808 1809 5105 1809 1811 5106 1811 1810 5107 1810 1809 5108 1809 1813 5109 1813 1811 5110 1811 1809 5111 1809 1813 5112 1813 1809 5113 1809 1812 5114 1812 1815 5115 1815 1813 5116 1813 1812 5117 1812 1815 5118 1815 1812 5119 1812 1814 5120 1814 1817 5121 1817 1815 5122 1815 1814 5123 1814 1817 5124 1817 1814 5125 1814 1816 5126 1816 1819 5127 1819 1817 5128 1817 1816 5129 1816 1819 5130 1819 1816 5131 1816 1818 5132 1818 1821 5133 1821 1819 5134 1819 1818 5135 1818 1821 5136 1821 1818 5137 1818 1820 5138 1820 1823 5139 1823 1821 5140 1821 1820 5141 1820 1823 5142 1823 1820 5143 1820 1822 5144 1822 1825 5145 1825 1823 5146 1823 1822 5147 1822 1825 5148 1825 1822 5149 1822 1824 5150 1824 1827 5151 1827 1825 5152 1825 1824 5153 1824 1827 5154 1827 1824 5155 1824 1826 5156 1826 1829 5157 1829 1827 5158 1827 1826 5159 1826 1829 5160 1829 1826 5161 1826 1828 5162 1828 1831 5163 1831 1829 5164 1829 1828 5165 1828 1831 5166 1831 1828 5167 1828 1830 5168 1830 1833 5169 1833 1831 5170 1831 1830 5171 1830 1833 5172 1833 1830 5173 1830 1832 5174 1832 1835 5175 1835 1833 5176 1833 1832 5177 1832 1835 5178 1835 1832 5179 1832 1834 5180 1834 1802 5181 1802 1835 5182 1835 1834 5183 1834 1868 5184 1868 1837 5185 1837 1836 5186 1836 1841 5187 1841 1839 5188 1839 1838 5189 1838 1841 5190 1841 1838 5191 1838 1840 5192 1840 1844 5193 1844 1841 5194 1841 1840 5195 1840 1844 5196 1844 1840 5197 1840 1842 5198 1842 1844 5199 1844 1842 5200 1842 1843 5201 1843 1845 5202 1845 1844 5203 1844 1843 5204 1843 1847 5205 1847 1845 5206 1845 1843 5207 1843 1847 5208 1847 1843 5209 1843 1846 5210 1846 1849 5211 1849 1847 5212 1847 1846 5213 1846 1849 5214 1849 1846 5215 1846 1848 5216 1848 1851 5217 1851 1849 5218 1849 1848 5219 1848 1851 5220 1851 1848 5221 1848 1850 5222 1850 1854 5223 1854 1851 5224 1851 1850 5225 1850 1854 5226 1854 1850 5227 1850 1852 5228 1852 1854 5229 1854 1852 5230 1852 1853 5231 1853 1855 5232 1855 1854 5233 1854 1853 5234 1853 1857 5235 1857 1855 5236 1855 1853 5237 1853 1857 5238 1857 1853 5239 1853 1856 5240 1856 1859 5241 1859 1857 5242 1857 1856 5243 1856 1859 5244 1859 1856 5245 1856 1858 5246 1858 1861 5247 1861 1859 5248 1859 1858 5249 1858 1861 5250 1861 1858 5251 1858 1860 5252 1860 1863 5253 1863 1861 5254 1861 1860 5255 1860 1863 5256 1863 1860 5257 1860 1862 5258 1862 1865 5259 1865 1863 5260 1863 1862 5261 1862 1865 5262 1865 1862 5263 1862 1864 5264 1864 1867 5265 1867 1865 5266 1865 1864 5267 1864 1867 5268 1867 1864 5269 1864 1866 5270 1866 1869 5271 1869 1867 5272 1867 1866 5273 1866 1869 5274 1869 1866 5275 1866 1868 5276 1868 1836 5277 1836 1869 5278 1869 1868 5279 1868 1902 5280 1902 1871 5281 1871 1870 5282 1870 1875 5283 1875 1873 5284 1873 1872 5285 1872 1875 5286 1875 1872 5287 1872 1874 5288 1874 1878 5289 1878 1875 5290 1875 1874 5291 1874 1878 5292 1878 1874 5293 1874 1876 5294 1876 1878 5295 1878 1876 5296 1876 1877 5297 1877 1879 5298 1879 1878 5299 1878 1877 5300 1877 1881 5301 1881 1879 5302 1879 1877 5303 1877 1881 5304 1881 1877 5305 1877 1880 5306 1880 1883 5307 1883 1881 5308 1881 1880 5309 1880 1883 5310 1883 1880 5311 1880 1882 5312 1882 1885 5313 1885 1883 5314 1883 1882 5315 1882 1885 5316 1885 1882 5317 1882 1884 5318 1884 1887 5319 1887 1885 5320 1885 1884 5321 1884 1887 5322 1887 1884 5323 1884 1886 5324 1886 1889 5325 1889 1887 5326 1887 1886 5327 1886 1889 5328 1889 1886 5329 1886 1888 5330 1888 1891 5331 1891 1889 5332 1889 1888 5333 1888 1891 5334 1891 1888 5335 1888 1890 5336 1890 1894 5337 1894 1891 5338 1891 1890 5339 1890 1894 5340 1894 1890 5341 1890 1892 5342 1892 1894 5343 1894 1892 5344 1892 1893 5345 1893 1895 5346 1895 1894 5347 1894 1893 5348 1893 1897 5349 1897 1895 5350 1895 1893 5351 1893 1897 5352 1897 1893 5353 1893 1896 5354 1896 1899 5355 1899 1897 5356 1897 1896 5357 1896 1899 5358 1899 1896 5359 1896 1898 5360 1898 1901 5361 1901 1899 5362 1899 1898 5363 1898 1901 5364 1901 1898 5365 1898 1900 5366 1900 1903 5367 1903 1901 5368 1901 1900 5369 1900 1903 5370 1903 1900 5371 1900 1902 5372 1902 1870 5373 1870 1903 5374 1903 1902 5375 1902 1906 5376 1906 1905 5377 1905 1904 5378 1904 1904 5379 1904 1907 5380 1907 1906 5381 1906 1910 5382 1910 1909 5383 1909 1908 5384 1908 1908 5385 1908 1911 5386 1911 1910 5387 1910 1914 5388 1914 1913 5389 1913 1912 5390 1912 1912 5391 1912 1915 5392 1915 1914 5393 1914 1918 5394 1918 1917 5395 1917 1916 5396 1916 1916 5397 1916 1919 5398 1919 1918 5399 1918 3622 5400 3622 3682 5401 3682 3684 5402 3684 1921 5403 1921 3625 5404 3625 1920 5405 1920 1922 5406 1922 1921 5407 1921 1920 5408 1920 1923 5409 1923 1922 5410 1922 1920 5411 1920 1924 5412 1924 1923 5413 1923 1920 5414 1920 1925 5415 1925 1924 5416 1924 1920 5417 1920 1926 5418 1926 1925 5419 1925 1920 5420 1920 2037 5421 2037 1926 5422 1926 1920 5423 1920 2038 5424 2038 2147 5425 2147 1927 5426 1927 2150 5427 2150 1928 5428 1928 2031 5429 2031 2040 5430 2040 2141 5431 2141 1929 5432 1929 2152 5433 2152 1930 5434 1930 2029 5435 2029 2042 5436 2042 2139 5437 2139 1931 5438 1931 2154 5439 2154 1932 5440 1932 2025 5441 2025 2044 5442 2044 2135 5443 2135 1933 5444 1933 2156 5445 2156 1934 5446 1934 2021 5447 2021 2046 5448 2046 2131 5449 2131 1935 5450 1935 2047 5451 2047 2128 5452 2128 1936 5453 1936 2159 5454 2159 1937 5455 1937 2016 5456 2016 2049 5457 2049 2050 5458 2050 1938 5459 1938 2050 5460 2050 2049 5461 2049 1939 5462 1939 2162 5463 2162 1940 5464 1940 2015 5465 2015 2052 5466 2052 2125 5467 2125 1941 5468 1941 2164 5469 2164 1942 5470 1942 1943 5471 1943 2165 5472 2165 1943 5473 1943 1942 5474 1942 2055 5475 2055 2122 5476 2122 1944 5477 1944 2167 5478 2167 1945 5479 1945 2010 5480 2010 2168 5481 2168 1946 5482 1946 2009 5483 2009 2058 5484 2058 2119 5485 2119 1947 5486 1947 2170 5487 2170 1948 5488 1948 2003 5489 2003 2060 5490 2060 2113 5491 2113 1949 5492 1949 2172 5493 2172 1950 5494 1950 2001 5495 2001 2062 5496 2062 2111 5497 2111 1951 5498 1951 2174 5499 2174 1952 5500 1952 1995 5501 1995 2064 5502 2064 2105 5503 2105 1953 5504 1953 2176 5505 2176 1954 5506 1954 1993 5507 1993 2066 5508 2066 2103 5509 2103 1955 5510 1955 2178 5511 2178 1956 5512 1956 1957 5513 1957 2179 5514 2179 1957 5515 1957 1956 5516 1956 2069 5517 2069 2100 5518 2100 1958 5519 1958 2181 5520 2181 1959 5521 1959 1988 5522 1988 2182 5523 2182 1960 5524 1960 1985 5525 1985 2072 5526 2072 2095 5527 2095 1961 5528 1961 2073 5529 2073 2094 5530 2094 1962 5531 1962 2185 5532 2185 1963 5533 1963 1982 5534 1982 2075 5535 2075 2076 5536 2076 1964 5537 1964 2076 5538 2076 2075 5539 2075 1965 5540 1965 2188 5541 2188 1966 5542 1966 1981 5543 1981 2078 5544 2078 2091 5545 2091 1967 5546 1967 2079 5547 2079 2088 5548 2088 1968 5549 1968 2191 5550 2191 1969 5551 1969 1976 5552 1976 2081 5553 2081 2082 5554 2082 1970 5555 1970 2082 5556 2082 2081 5557 2081 1971 5558 1971 2194 5559 2194 1972 5560 1972 1973 5561 1973 2195 5562 2195 1973 5563 1973 1972 5564 1972 2085 5565 2085 2086 5566 2086 1974 5567 1974 2086 5568 2086 2085 5569 2085 1975 5570 1975 2198 5571 2198 1976 5572 1976 1969 5573 1969 2088 5574 2088 2079 5575 2079 1977 5576 1977 2200 5577 2200 1978 5578 1978 1979 5579 1979 2201 5580 2201 1979 5581 1979 1978 5582 1978 2091 5583 2091 2078 5584 2078 1980 5585 1980 2203 5586 2203 1981 5587 1981 1966 5588 1966 2204 5589 2204 1982 5590 1982 1963 5591 1963 2094 5592 2094 2073 5593 2073 1983 5594 1983 2095 5595 2095 2072 5596 2072 1984 5597 1984 2207 5598 2207 1985 5599 1985 1960 5600 1960 2097 5601 2097 2098 5602 2098 1986 5603 1986 2098 5604 2098 2097 5605 2097 1987 5606 1987 2210 5607 2210 1988 5608 1988 1959 5609 1959 2100 5610 2100 2069 5611 2069 1989 5612 1989 2212 5613 2212 1990 5614 1990 1991 5615 1991 2213 5616 2213 1991 5617 1991 1990 5618 1990 2103 5619 2103 2066 5620 2066 1992 5621 1992 2215 5622 2215 1993 5623 1993 1954 5624 1954 2105 5625 2105 2064 5626 2064 1994 5627 1994 2217 5628 2217 1995 5629 1995 1952 5630 1952 2107 5631 2107 2108 5632 2108 1996 5633 1996 2108 5634 2108 2107 5635 2107 1997 5636 1997 2220 5637 2220 1998 5638 1998 1999 5639 1999 2221 5640 2221 1999 5641 1999 1998 5642 1998 2111 5643 2111 2062 5644 2062 2000 5645 2000 2223 5646 2223 2001 5647 2001 1950 5648 1950 2113 5649 2113 2060 5650 2060 2002 5651 2002 2225 5652 2225 2003 5653 2003 1948 5654 1948 2115 5655 2115 2116 5656 2116 2004 5657 2004 2116 5658 2116 2115 5659 2115 2005 5660 2005 2228 5661 2228 2006 5662 2006 2007 5663 2007 2229 5664 2229 2007 5665 2007 2006 5666 2006 2119 5667 2119 2058 5668 2058 2008 5669 2008 2231 5670 2231 2009 5671 2009 1946 5672 1946 2232 5673 2232 2010 5674 2010 1945 5675 1945 2122 5676 2122 2055 5677 2055 2011 5678 2011 2234 5679 2234 2012 5680 2012 2013 5681 2013 2235 5682 2235 2013 5683 2013 2012 5684 2012 2125 5685 2125 2052 5686 2052 2014 5687 2014 2237 5688 2237 2015 5689 2015 1940 5690 1940 2238 5691 2238 2016 5692 2016 1937 5693 1937 2128 5694 2128 2047 5695 2047 2017 5696 2017 2240 5697 2240 2018 5698 2018 2019 5699 2019 2241 5700 2241 2019 5701 2019 2018 5702 2018 2131 5703 2131 2046 5704 2046 2020 5705 2020 2243 5706 2243 2021 5707 2021 1934 5708 1934 2244 5709 2244 2022 5710 2022 2023 5711 2023 2245 5712 2245 2023 5713 2023 2022 5714 2022 2135 5715 2135 2044 5716 2044 2024 5717 2024 2247 5718 2247 2025 5719 2025 1932 5720 1932 2248 5721 2248 2026 5722 2026 2027 5723 2027 2249 5724 2249 2027 5725 2027 2026 5726 2026 2139 5727 2139 2042 5728 2042 2028 5729 2028 2251 5730 2251 2029 5731 2029 1930 5732 1930 2141 5733 2141 2040 5734 2040 2030 5735 2030 2253 5736 2253 2031 5737 2031 1928 5738 1928 2143 5739 2143 2144 5740 2144 2032 5741 2032 2144 5742 2144 2143 5743 2143 2033 5744 2033 2256 5745 2256 2034 5746 2034 2035 5747 2035 2257 5748 2257 2035 5749 2035 2034 5750 2034 2147 5751 2147 2038 5752 2038 2036 5753 2036 2259 5754 2259 2037 5755 2037 1920 5756 1920 2260 5757 2260 2038 5758 2038 1927 5759 1927 2150 5760 2150 2031 5761 2031 2039 5762 2039 2262 5763 2262 2040 5764 2040 1929 5765 1929 2152 5766 2152 2029 5767 2029 2041 5768 2041 2264 5769 2264 2042 5770 2042 1931 5771 1931 2154 5772 2154 2025 5773 2025 2043 5774 2043 2266 5775 2266 2044 5776 2044 1933 5777 1933 2156 5778 2156 2021 5779 2021 2045 5780 2045 2268 5781 2268 2046 5782 2046 1935 5783 1935 2269 5784 2269 2047 5785 2047 1936 5786 1936 2159 5787 2159 2016 5788 2016 2048 5789 2048 2271 5790 2271 2049 5791 2049 1938 5792 1938 2272 5793 2272 2050 5794 2050 1939 5795 1939 2162 5796 2162 2015 5797 2015 2051 5798 2051 2274 5799 2274 2052 5800 2052 1941 5801 1941 2164 5802 2164 1943 5803 1943 2053 5804 2053 2165 5805 2165 1942 5806 1942 2054 5807 2054 2277 5808 2277 2055 5809 2055 1944 5810 1944 2167 5811 2167 2010 5812 2010 2056 5813 2056 2168 5814 2168 2009 5815 2009 2057 5816 2057 2280 5817 2280 2058 5818 2058 1947 5819 1947 2170 5820 2170 2003 5821 2003 2059 5822 2059 2282 5823 2282 2060 5824 2060 1949 5825 1949 2172 5826 2172 2001 5827 2001 2061 5828 2061 2284 5829 2284 2062 5830 2062 1951 5831 1951 2174 5832 2174 1995 5833 1995 2063 5834 2063 2286 5835 2286 2064 5836 2064 1953 5837 1953 2176 5838 2176 1993 5839 1993 2065 5840 2065 2288 5841 2288 2066 5842 2066 1955 5843 1955 2178 5844 2178 1957 5845 1957 2067 5846 2067 2179 5847 2179 1956 5848 1956 2068 5849 2068 2291 5850 2291 2069 5851 2069 1958 5852 1958 2181 5853 2181 1988 5854 1988 2070 5855 2070 2182 5856 2182 1985 5857 1985 2071 5858 2071 2294 5859 2294 2072 5860 2072 1961 5861 1961 2295 5862 2295 2073 5863 2073 1962 5864 1962 2185 5865 2185 1982 5866 1982 2074 5867 2074 2297 5868 2297 2075 5869 2075 1964 5870 1964 2298 5871 2298 2076 5872 2076 1965 5873 1965 2188 5874 2188 1981 5875 1981 2077 5876 2077 2300 5877 2300 2078 5878 2078 1967 5879 1967 2301 5880 2301 2079 5881 2079 1968 5882 1968 2191 5883 2191 1976 5884 1976 2080 5885 2080 2303 5886 2303 2081 5887 2081 1970 5888 1970 2304 5889 2304 2082 5890 2082 1971 5891 1971 2194 5892 2194 1973 5893 1973 2083 5894 2083 2195 5895 2195 1972 5896 1972 2084 5897 2084 2307 5898 2307 2085 5899 2085 1974 5900 1974 2308 5901 2308 2086 5902 2086 1975 5903 1975 2198 5904 2198 1969 5905 1969 2087 5906 2087 2310 5907 2310 2088 5908 2088 1977 5909 1977 2200 5910 2200 1979 5911 1979 2089 5912 2089 2201 5913 2201 1978 5914 1978 2090 5915 2090 2313 5916 2313 2091 5917 2091 1980 5918 1980 2203 5919 2203 1966 5920 1966 2092 5921 2092 2204 5922 2204 1963 5923 1963 2093 5924 2093 2316 5925 2316 2094 5926 2094 1983 5927 1983 2317 5928 2317 2095 5929 2095 1984 5930 1984 2207 5931 2207 1960 5932 1960 2096 5933 2096 2319 5934 2319 2097 5935 2097 1986 5936 1986 2320 5937 2320 2098 5938 2098 1987 5939 1987 2210 5940 2210 1959 5941 1959 2099 5942 2099 2322 5943 2322 2100 5944 2100 1989 5945 1989 2212 5946 2212 1991 5947 1991 2101 5948 2101 2213 5949 2213 1990 5950 1990 2102 5951 2102 2325 5952 2325 2103 5953 2103 1992 5954 1992 2215 5955 2215 1954 5956 1954 2104 5957 2104 2327 5958 2327 2105 5959 2105 1994 5960 1994 2217 5961 2217 1952 5962 1952 2106 5963 2106 2329 5964 2329 2107 5965 2107 1996 5966 1996 2330 5967 2330 2108 5968 2108 1997 5969 1997 2220 5970 2220 1999 5971 1999 2109 5972 2109 2221 5973 2221 1998 5974 1998 2110 5975 2110 2333 5976 2333 2111 5977 2111 2000 5978 2000 2223 5979 2223 1950 5980 1950 2112 5981 2112 2335 5982 2335 2113 5983 2113 2002 5984 2002 2225 5985 2225 1948 5986 1948 2114 5987 2114 2337 5988 2337 2115 5989 2115 2004 5990 2004 2338 5991 2338 2116 5992 2116 2005 5993 2005 2228 5994 2228 2007 5995 2007 2117 5996 2117 2229 5997 2229 2006 5998 2006 2118 5999 2118 2341 6000 2341 2119 6001 2119 2008 6002 2008 2231 6003 2231 1946 6004 1946 2120 6005 2120 2232 6006 2232 1945 6007 1945 2121 6008 2121 2344 6009 2344 2122 6010 2122 2011 6011 2011 2234 6012 2234 2013 6013 2013 2123 6014 2123 2235 6015 2235 2012 6016 2012 2124 6017 2124 2347 6018 2347 2125 6019 2125 2014 6020 2014 2237 6021 2237 1940 6022 1940 2126 6023 2126 2238 6024 2238 1937 6025 1937 2127 6026 2127 2350 6027 2350 2128 6028 2128 2017 6029 2017 2240 6030 2240 2019 6031 2019 2129 6032 2129 2241 6033 2241 2018 6034 2018 2130 6035 2130 2353 6036 2353 2131 6037 2131 2020 6038 2020 2243 6039 2243 1934 6040 1934 2132 6041 2132 2244 6042 2244 2023 6043 2023 2133 6044 2133 2245 6045 2245 2022 6046 2022 2134 6047 2134 2357 6048 2357 2135 6049 2135 2024 6050 2024 2247 6051 2247 1932 6052 1932 2136 6053 2136 2248 6054 2248 2027 6055 2027 2137 6056 2137 2249 6057 2249 2026 6058 2026 2138 6059 2138 2361 6060 2361 2139 6061 2139 2028 6062 2028 2251 6063 2251 1930 6064 1930 2140 6065 2140 2363 6066 2363 2141 6067 2141 2030 6068 2030 2253 6069 2253 1928 6070 1928 2142 6071 2142 2365 6072 2365 2143 6073 2143 2032 6074 2032 2366 6075 2366 2144 6076 2144 2033 6077 2033 2256 6078 2256 2035 6079 2035 2145 6080 2145 2257 6081 2257 2034 6082 2034 2146 6083 2146 2369 6084 2369 2147 6085 2147 2036 6086 2036 3625 6087 3625 1921 6088 1921 2148 6089 2148 2260 6090 2260 1927 6091 1927 2149 6092 2149 2372 6093 2372 2150 6094 2150 2039 6095 2039 2262 6096 2262 1929 6097 1929 2151 6098 2151 2374 6099 2374 2152 6100 2152 2041 6101 2041 2264 6102 2264 1931 6103 1931 2153 6104 2153 2376 6105 2376 2154 6106 2154 2043 6107 2043 2266 6108 2266 1933 6109 1933 2155 6110 2155 2378 6111 2378 2156 6112 2156 2045 6113 2045 2268 6114 2268 1935 6115 1935 2157 6116 2157 2269 6117 2269 1936 6118 1936 2158 6119 2158 2381 6120 2381 2159 6121 2159 2048 6122 2048 2271 6123 2271 1938 6124 1938 2160 6125 2160 2272 6126 2272 1939 6127 1939 2161 6128 2161 2384 6129 2384 2162 6130 2162 2051 6131 2051 2274 6132 2274 1941 6133 1941 2163 6134 2163 2386 6135 2386 2164 6136 2164 2053 6137 2053 2387 6138 2387 2165 6139 2165 2054 6140 2054 2277 6141 2277 1944 6142 1944 2166 6143 2166 2389 6144 2389 2167 6145 2167 2056 6146 2056 2390 6147 2390 2168 6148 2168 2057 6149 2057 2280 6150 2280 1947 6151 1947 2169 6152 2169 2392 6153 2392 2170 6154 2170 2059 6155 2059 2282 6156 2282 1949 6157 1949 2171 6158 2171 2394 6159 2394 2172 6160 2172 2061 6161 2061 2284 6162 2284 1951 6163 1951 2173 6164 2173 2396 6165 2396 2174 6166 2174 2063 6167 2063 2286 6168 2286 1953 6169 1953 2175 6170 2175 2398 6171 2398 2176 6172 2176 2065 6173 2065 2288 6174 2288 1955 6175 1955 2177 6176 2177 2400 6177 2400 2178 6178 2178 2067 6179 2067 2401 6180 2401 2179 6181 2179 2068 6182 2068 2291 6183 2291 1958 6184 1958 2180 6185 2180 2403 6186 2403 2181 6187 2181 2070 6188 2070 2404 6189 2404 2182 6190 2182 2071 6191 2071 2294 6192 2294 1961 6193 1961 2183 6194 2183 2295 6195 2295 1962 6196 1962 2184 6197 2184 2407 6198 2407 2185 6199 2185 2074 6200 2074 2297 6201 2297 1964 6202 1964 2186 6203 2186 2298 6204 2298 1965 6205 1965 2187 6206 2187 2410 6207 2410 2188 6208 2188 2077 6209 2077 2300 6210 2300 1967 6211 1967 2189 6212 2189 2301 6213 2301 1968 6214 1968 2190 6215 2190 2413 6216 2413 2191 6217 2191 2080 6218 2080 2303 6219 2303 1970 6220 1970 2192 6221 2192 2304 6222 2304 1971 6223 1971 2193 6224 2193 2416 6225 2416 2194 6226 2194 2083 6227 2083 2417 6228 2417 2195 6229 2195 2084 6230 2084 2307 6231 2307 1974 6232 1974 2196 6233 2196 2308 6234 2308 1975 6235 1975 2197 6236 2197 2420 6237 2420 2198 6238 2198 2087 6239 2087 2310 6240 2310 1977 6241 1977 2199 6242 2199 2422 6243 2422 2200 6244 2200 2089 6245 2089 2423 6246 2423 2201 6247 2201 2090 6248 2090 2313 6249 2313 1980 6250 1980 2202 6251 2202 2425 6252 2425 2203 6253 2203 2092 6254 2092 2426 6255 2426 2204 6256 2204 2093 6257 2093 2316 6258 2316 1983 6259 1983 2205 6260 2205 2317 6261 2317 1984 6262 1984 2206 6263 2206 2429 6264 2429 2207 6265 2207 2096 6266 2096 2319 6267 2319 1986 6268 1986 2208 6269 2208 2320 6270 2320 1987 6271 1987 2209 6272 2209 2432 6273 2432 2210 6274 2210 2099 6275 2099 2322 6276 2322 1989 6277 1989 2211 6278 2211 2434 6279 2434 2212 6280 2212 2101 6281 2101 2435 6282 2435 2213 6283 2213 2102 6284 2102 2325 6285 2325 1992 6286 1992 2214 6287 2214 2437 6288 2437 2215 6289 2215 2104 6290 2104 2327 6291 2327 1994 6292 1994 2216 6293 2216 2439 6294 2439 2217 6295 2217 2106 6296 2106 2329 6297 2329 1996 6298 1996 2218 6299 2218 2330 6300 2330 1997 6301 1997 2219 6302 2219 2442 6303 2442 2220 6304 2220 2109 6305 2109 2443 6306 2443 2221 6307 2221 2110 6308 2110 2333 6309 2333 2000 6310 2000 2222 6311 2222 2445 6312 2445 2223 6313 2223 2112 6314 2112 2335 6315 2335 2002 6316 2002 2224 6317 2224 2447 6318 2447 2225 6319 2225 2114 6320 2114 2337 6321 2337 2004 6322 2004 2226 6323 2226 2338 6324 2338 2005 6325 2005 2227 6326 2227 2450 6327 2450 2228 6328 2228 2117 6329 2117 2451 6330 2451 2229 6331 2229 2118 6332 2118 2341 6333 2341 2008 6334 2008 2230 6335 2230 2453 6336 2453 2231 6337 2231 2120 6338 2120 2454 6339 2454 2232 6340 2232 2121 6341 2121 2344 6342 2344 2011 6343 2011 2233 6344 2233 2456 6345 2456 2234 6346 2234 2123 6347 2123 2457 6348 2457 2235 6349 2235 2124 6350 2124 2347 6351 2347 2014 6352 2014 2236 6353 2236 2459 6354 2459 2237 6355 2237 2126 6356 2126 2460 6357 2460 2238 6358 2238 2127 6359 2127 2350 6360 2350 2017 6361 2017 2239 6362 2239 2462 6363 2462 2240 6364 2240 2129 6365 2129 2463 6366 2463 2241 6367 2241 2130 6368 2130 2353 6369 2353 2020 6370 2020 2242 6371 2242 2465 6372 2465 2243 6373 2243 2132 6374 2132 2466 6375 2466 2244 6376 2244 2133 6377 2133 2467 6378 2467 2245 6379 2245 2134 6380 2134 2357 6381 2357 2024 6382 2024 2246 6383 2246 2469 6384 2469 2247 6385 2247 2136 6386 2136 2470 6387 2470 2248 6388 2248 2137 6389 2137 2471 6390 2471 2249 6391 2249 2138 6392 2138 2361 6393 2361 2028 6394 2028 2250 6395 2250 2473 6396 2473 2251 6397 2251 2140 6398 2140 2363 6399 2363 2030 6400 2030 2252 6401 2252 2475 6402 2475 2253 6403 2253 2142 6404 2142 2365 6405 2365 2032 6406 2032 2254 6407 2254 2366 6408 2366 2033 6409 2033 2255 6410 2255 2478 6411 2478 2256 6412 2256 2145 6413 2145 2479 6414 2479 2257 6415 2257 2146 6416 2146 2369 6417 2369 2036 6418 2036 2258 6419 2258 2481 6420 2481 2259 6421 2259 1920 6422 1920 2482 6423 2482 2260 6424 2260 2149 6425 2149 2372 6426 2372 2039 6427 2039 2261 6428 2261 2484 6429 2484 2262 6430 2262 2151 6431 2151 2374 6432 2374 2041 6433 2041 2263 6434 2263 2486 6435 2486 2264 6436 2264 2153 6437 2153 2376 6438 2376 2043 6439 2043 2265 6440 2265 2488 6441 2488 2266 6442 2266 2155 6443 2155 2378 6444 2378 2045 6445 2045 2267 6446 2267 2490 6447 2490 2268 6448 2268 2157 6449 2157 2491 6450 2491 2269 6451 2269 2158 6452 2158 2381 6453 2381 2048 6454 2048 2270 6455 2270 2493 6456 2493 2271 6457 2271 2160 6458 2160 2513 6459 2513 2272 6460 2272 2161 6461 2161 2384 6462 2384 2051 6463 2051 2273 6464 2273 2515 6465 2515 2274 6466 2274 2163 6467 2163 2386 6468 2386 2053 6469 2053 2275 6470 2275 2387 6471 2387 2054 6472 2054 2276 6473 2276 2518 6474 2518 2277 6475 2277 2166 6476 2166 2389 6477 2389 2056 6478 2056 2278 6479 2278 2390 6480 2390 2057 6481 2057 2279 6482 2279 2542 6483 2542 2280 6484 2280 2169 6485 2169 2392 6486 2392 2059 6487 2059 2281 6488 2281 2544 6489 2544 2282 6490 2282 2171 6491 2171 2394 6492 2394 2061 6493 2061 2283 6494 2283 2546 6495 2546 2284 6496 2284 2173 6497 2173 2396 6498 2396 2063 6499 2063 2285 6500 2285 2548 6501 2548 2286 6502 2286 2175 6503 2175 2398 6504 2398 2065 6505 2065 2287 6506 2287 2550 6507 2550 2288 6508 2288 2177 6509 2177 2400 6510 2400 2067 6511 2067 2289 6512 2289 2401 6513 2401 2068 6514 2068 2290 6515 2290 2553 6516 2553 2291 6517 2291 2180 6518 2180 2403 6519 2403 2070 6520 2070 2292 6521 2292 2404 6522 2404 2071 6523 2071 2293 6524 2293 2575 6525 2575 2294 6526 2294 2183 6527 2183 2576 6528 2576 2295 6529 2295 2184 6530 2184 2407 6531 2407 2074 6532 2074 2296 6533 2296 2578 6534 2578 2297 6535 2297 2186 6536 2186 2600 6537 2600 2298 6538 2298 2187 6539 2187 2410 6540 2410 2077 6541 2077 2299 6542 2299 2602 6543 2602 2300 6544 2300 2189 6545 2189 2603 6546 2603 2301 6547 2301 2190 6548 2190 2413 6549 2413 2080 6550 2080 2302 6551 2302 2605 6552 2605 2303 6553 2303 2192 6554 2192 2625 6555 2625 2304 6556 2304 2193 6557 2193 2416 6558 2416 2083 6559 2083 2305 6560 2305 2417 6561 2417 2084 6562 2084 2306 6563 2306 2629 6564 2629 2307 6565 2307 2196 6566 2196 2640 6567 2640 2308 6568 2308 2197 6569 2197 2420 6570 2420 2087 6571 2087 2309 6572 2309 2642 6573 2642 2310 6574 2310 2199 6575 2199 2422 6576 2422 2089 6577 2089 2311 6578 2311 2423 6579 2423 2090 6580 2090 2312 6581 2312 2645 6582 2645 2313 6583 2313 2202 6584 2202 2425 6585 2425 2092 6586 2092 2314 6587 2314 2426 6588 2426 2093 6589 2093 2315 6590 2315 2668 6591 2668 2316 6592 2316 2205 6593 2205 2669 6594 2669 2317 6595 2317 2206 6596 2206 2429 6597 2429 2096 6598 2096 2318 6599 2318 2671 6600 2671 2319 6601 2319 2208 6602 2208 2691 6603 2691 2320 6604 2320 2209 6605 2209 2432 6606 2432 2099 6607 2099 2321 6608 2321 2693 6609 2693 2322 6610 2322 2211 6611 2211 2434 6612 2434 2101 6613 2101 2323 6614 2323 2435 6615 2435 2102 6616 2102 2324 6617 2324 2697 6618 2697 2325 6619 2325 2214 6620 2214 2437 6621 2437 2104 6622 2104 2326 6623 2326 2718 6624 2718 2327 6625 2327 2216 6626 2216 2439 6627 2439 2106 6628 2106 2328 6629 2328 2720 6630 2720 2329 6631 2329 2218 6632 2218 2740 6633 2740 2330 6634 2330 2219 6635 2219 2442 6636 2442 2109 6637 2109 2331 6638 2331 2443 6639 2443 2110 6640 2110 2332 6641 2332 2745 6642 2745 2333 6643 2333 2222 6644 2222 2445 6645 2445 2112 6646 2112 2334 6647 2334 2766 6648 2766 2335 6649 2335 2224 6650 2224 2447 6651 2447 2114 6652 2114 2336 6653 2336 2768 6654 2768 2337 6655 2337 2226 6656 2226 2788 6657 2788 2338 6658 2338 2227 6659 2227 2450 6660 2450 2117 6661 2117 2339 6662 2339 2451 6663 2451 2118 6664 2118 2340 6665 2340 2793 6666 2793 2341 6667 2341 2230 6668 2230 2453 6669 2453 2120 6670 2120 2342 6671 2342 2454 6672 2454 2121 6673 2121 2343 6674 2343 2815 6675 2815 2344 6676 2344 2233 6677 2233 2456 6678 2456 2123 6679 2123 2345 6680 2345 2457 6681 2457 2124 6682 2124 2346 6683 2346 2818 6684 2818 2347 6685 2347 2236 6686 2236 2459 6687 2459 2126 6688 2126 2348 6689 2348 2460 6690 2460 2127 6691 2127 2349 6692 2349 2842 6693 2842 2350 6694 2350 2239 6695 2239 2462 6696 2462 2129 6697 2129 2351 6698 2351 2463 6699 2463 2130 6700 2130 2352 6701 2352 2845 6702 2845 2353 6703 2353 2242 6704 2242 2465 6705 2465 2132 6706 2132 2354 6707 2354 2466 6708 2466 2133 6709 2133 2355 6710 2355 2467 6711 2467 2134 6712 2134 2356 6713 2356 2869 6714 2869 2357 6715 2357 2246 6716 2246 2469 6717 2469 2136 6718 2136 2358 6719 2358 2470 6720 2470 2137 6721 2137 2359 6722 2359 2471 6723 2471 2138 6724 2138 2360 6725 2360 2892 6726 2892 2361 6727 2361 2250 6728 2250 2473 6729 2473 2140 6730 2140 2362 6731 2362 2913 6732 2913 2363 6733 2363 2252 6734 2252 2475 6735 2475 2142 6736 2142 2364 6737 2364 2915 6738 2915 2365 6739 2365 2254 6740 2254 2938 6741 2938 2366 6742 2366 2255 6743 2255 2478 6744 2478 2145 6745 2145 2367 6746 2367 2479 6747 2479 2146 6748 2146 2368 6749 2368 2941 6750 2941 2369 6751 2369 2258 6752 2258 3625 6753 3625 2148 6754 2148 2370 6755 2370 2482 6756 2482 2149 6757 2149 2371 6758 2371 2960 6759 2960 2372 6760 2372 2261 6761 2261 2484 6762 2484 2151 6763 2151 2373 6764 2373 2962 6765 2962 2374 6766 2374 2263 6767 2263 2486 6768 2486 2153 6769 2153 2375 6770 2375 2964 6771 2964 2376 6772 2376 2265 6773 2265 2488 6774 2488 2155 6775 2155 2377 6776 2377 2966 6777 2966 2378 6778 2378 2267 6779 2267 2490 6780 2490 2157 6781 2157 2379 6782 2379 2491 6783 2491 2158 6784 2158 2380 6785 2380 2494 6786 2494 2381 6787 2381 2270 6788 2270 2493 6789 2493 2160 6790 2160 2382 6791 2382 2513 6792 2513 2161 6793 2161 2383 6794 2383 2970 6795 2970 2384 6796 2384 2273 6797 2273 2515 6798 2515 2163 6799 2163 2385 6800 2385 2972 6801 2972 2386 6802 2386 2275 6803 2275 2519 6804 2519 2387 6805 2387 2276 6806 2276 2518 6807 2518 2166 6808 2166 2388 6809 2388 2526 6810 2526 2389 6811 2389 2278 6812 2278 2974 6813 2974 2390 6814 2390 2279 6815 2279 2542 6816 2542 2169 6817 2169 2391 6818 2391 2976 6819 2976 2392 6820 2392 2281 6821 2281 2544 6822 2544 2171 6823 2171 2393 6824 2393 2978 6825 2978 2394 6826 2394 2283 6827 2283 2546 6828 2546 2173 6829 2173 2395 6830 2395 2980 6831 2980 2396 6832 2396 2285 6833 2285 2548 6834 2548 2175 6835 2175 2397 6836 2397 2982 6837 2982 2398 6838 2398 2287 6839 2287 2550 6840 2550 2177 6841 2177 2399 6842 2399 2984 6843 2984 2400 6844 2400 2289 6845 2289 2554 6846 2554 2401 6847 2401 2290 6848 2290 2553 6849 2553 2180 6850 2180 2402 6851 2402 2561 6852 2561 2403 6853 2403 2292 6854 2292 2986 6855 2986 2404 6856 2404 2293 6857 2293 2575 6858 2575 2183 6859 2183 2405 6860 2405 2576 6861 2576 2184 6862 2184 2406 6863 2406 2579 6864 2579 2407 6865 2407 2296 6866 2296 2578 6867 2578 2186 6868 2186 2408 6869 2408 2600 6870 2600 2187 6871 2187 2409 6872 2409 2990 6873 2990 2410 6874 2410 2299 6875 2299 2602 6876 2602 2189 6877 2189 2411 6878 2411 2603 6879 2603 2190 6880 2190 2412 6881 2412 2606 6882 2606 2413 6883 2413 2302 6884 2302 2605 6885 2605 2192 6886 2192 2414 6887 2414 2625 6888 2625 2193 6889 2193 2415 6890 2415 2994 6891 2994 2416 6892 2416 2305 6893 2305 2630 6894 2630 2417 6895 2417 2306 6896 2306 2629 6897 2629 2196 6898 2196 2418 6899 2418 2640 6900 2640 2197 6901 2197 2419 6902 2419 2996 6903 2996 2420 6904 2420 2309 6905 2309 2642 6906 2642 2199 6907 2199 2421 6908 2421 2998 6909 2998 2422 6910 2422 2311 6911 2311 2646 6912 2646 2423 6913 2423 2312 6914 2312 2645 6915 2645 2202 6916 2202 2424 6917 2424 2653 6918 2653 2425 6919 2425 2314 6920 2314 3000 6921 3000 2426 6922 2426 2315 6923 2315 2668 6924 2668 2205 6925 2205 2427 6926 2427 2669 6927 2669 2206 6928 2206 2428 6929 2428 2672 6930 2672 2429 6931 2429 2318 6932 2318 2671 6933 2671 2208 6934 2208 2430 6935 2430 2691 6936 2691 2209 6937 2209 2431 6938 2431 3004 6939 3004 2432 6940 2432 2321 6941 2321 2693 6942 2693 2211 6943 2211 2433 6944 2433 3006 6945 3006 2434 6946 2434 2323 6947 2323 2698 6948 2698 2435 6949 2435 2324 6950 2324 2697 6951 2697 2214 6952 2214 2436 6953 2436 2705 6954 2705 2437 6955 2437 2326 6956 2326 2718 6957 2718 2216 6958 2216 2438 6959 2438 2721 6960 2721 2439 6961 2439 2328 6962 2328 2720 6963 2720 2218 6964 2218 2440 6965 2440 2740 6966 2740 2219 6967 2219 2441 6968 2441 3010 6969 3010 2442 6970 2442 2331 6971 2331 2746 6972 2746 2443 6973 2443 2332 6974 2332 2745 6975 2745 2222 6976 2222 2444 6977 2444 2753 6978 2753 2445 6979 2445 2334 6980 2334 2766 6981 2766 2224 6982 2224 2446 6983 2446 2769 6984 2769 2447 6985 2447 2336 6986 2336 2768 6987 2768 2226 6988 2226 2448 6989 2448 2788 6990 2788 2227 6991 2227 2449 6992 2449 3014 6993 3014 2450 6994 2450 2339 6995 2339 2794 6996 2794 2451 6997 2451 2340 6998 2340 2793 6999 2793 2230 7000 2230 2452 7001 2452 2801 7002 2801 2453 7003 2453 2342 7004 2342 3016 7005 3016 2454 7006 2454 2343 7007 2343 2815 7008 2815 2233 7009 2233 2455 7010 2455 3018 7011 3018 2456 7012 2456 2345 7013 2345 2819 7014 2819 2457 7015 2457 2346 7016 2346 2818 7017 2818 2236 7018 2236 2458 7019 2458 2826 7020 2826 2459 7021 2459 2348 7022 2348 3020 7023 3020 2460 7024 2460 2349 7025 2349 2842 7026 2842 2239 7027 2239 2461 7028 2461 3022 7029 3022 2462 7030 2462 2351 7031 2351 2846 7032 2846 2463 7033 2463 2352 7034 2352 2845 7035 2845 2242 7036 2242 2464 7037 2464 2853 7038 2853 2465 7039 2465 2354 7040 2354 3024 7041 3024 2466 7042 2466 2355 7043 2355 2870 7044 2870 2467 7045 2467 2356 7046 2356 2869 7047 2869 2246 7048 2246 2468 7049 2468 2877 7050 2877 2469 7051 2469 2358 7052 2358 3026 7053 3026 2470 7054 2470 2359 7055 2359 2893 7056 2893 2471 7057 2471 2360 7058 2360 2892 7059 2892 2250 7060 2250 2472 7061 2472 2900 7062 2900 2473 7063 2473 2362 7064 2362 2913 7065 2913 2252 7066 2252 2474 7067 2474 2916 7068 2916 2475 7069 2475 2364 7070 2364 2915 7071 2915 2254 7072 2254 2476 7073 2476 2938 7074 2938 2255 7075 2255 2477 7076 2477 3030 7077 3030 2478 7078 2478 2367 7079 2367 2942 7080 2942 2479 7081 2479 2368 7082 2368 2941 7083 2941 2258 7084 2258 2480 7085 2480 2947 7086 2947 2481 7087 2481 1920 7088 1920 3033 7089 3033 2482 7090 2482 2371 7091 2371 2960 7092 2960 2261 7093 2261 2483 7094 2483 3035 7095 3035 2484 7096 2484 2373 7097 2373 2962 7098 2962 2263 7099 2263 2485 7100 2485 3037 7101 3037 2486 7102 2486 2375 7103 2375 2964 7104 2964 2265 7105 2265 2487 7106 2487 3039 7107 3039 2488 7108 2488 2377 7109 2377 2966 7110 2966 2267 7111 2267 2489 7112 2489 3041 7113 3041 2490 7114 2490 2379 7115 2379 2502 7116 2502 2491 7117 2491 2380 7118 2380 2494 7119 2494 2270 7120 2270 2492 7121 2492 2492 7122 2492 2493 7123 2493 2382 7124 2382 2494 7125 2494 2492 7126 2492 2382 7127 2382 2496 7128 2496 2494 7129 2494 2382 7130 2382 2496 7131 2496 2382 7132 2382 2495 7133 2495 2498 7134 2498 2496 7135 2496 2495 7136 2495 2498 7137 2498 2495 7138 2495 2497 7139 2497 2500 7140 2500 2498 7141 2498 2497 7142 2497 2500 7143 2500 2497 7144 2497 2499 7145 2499 2380 7146 2380 2500 7147 2500 2499 7148 2499 2502 7149 2502 2380 7150 2380 2499 7151 2499 2502 7152 2502 2499 7153 2499 2501 7154 2501 2504 7155 2504 2502 7156 2502 2501 7157 2501 2504 7158 2504 2501 7159 2501 2503 7160 2503 2506 7161 2506 2504 7162 2504 2503 7163 2503 2506 7164 2506 2503 7165 2503 2505 7166 2505 2508 7167 2508 2506 7168 2506 2505 7169 2505 2508 7170 2508 2505 7171 2505 2507 7172 2507 2510 7173 2510 2508 7174 2508 2507 7175 2507 2510 7176 2510 2507 7177 2507 2509 7178 2509 2512 7179 2512 2510 7180 2510 2509 7181 2509 2512 7182 2512 2509 7183 2509 2511 7184 2511 2968 7185 2968 2512 7186 2512 2511 7187 2511 3043 7188 3043 2513 7189 2513 2383 7190 2383 2970 7191 2970 2273 7192 2273 2514 7193 2514 3045 7194 3045 2515 7195 2515 2385 7196 2385 2972 7197 2972 2275 7198 2275 2516 7199 2516 2519 7200 2519 2276 7201 2276 2517 7202 2517 2517 7203 2517 2518 7204 2518 2388 7205 2388 2519 7206 2519 2517 7207 2517 2388 7208 2388 2521 7209 2521 2519 7210 2519 2388 7211 2388 2521 7212 2521 2388 7213 2388 2520 7214 2520 2523 7215 2523 2521 7216 2521 2520 7217 2520 2523 7218 2523 2520 7219 2520 2522 7220 2522 2525 7221 2525 2523 7222 2523 2522 7223 2522 2525 7224 2525 2522 7225 2522 2524 7226 2524 2529 7227 2529 2525 7228 2525 2524 7229 2524 2529 7230 2529 2524 7231 2524 2526 7232 2526 2529 7233 2529 2526 7234 2526 2278 7235 2278 2529 7236 2529 2278 7237 2278 2527 7238 2527 2529 7239 2529 2527 7240 2527 2528 7241 2528 2531 7242 2531 2529 7243 2529 2528 7244 2528 2531 7245 2531 2528 7246 2528 2530 7247 2530 2533 7248 2533 2531 7249 2531 2530 7250 2530 2533 7251 2533 2530 7252 2530 2532 7253 2532 2535 7254 2535 2533 7255 2533 2532 7256 2532 2535 7257 2535 2532 7258 2532 2534 7259 2534 2537 7260 2537 2535 7261 2535 2534 7262 2534 2537 7263 2537 2534 7264 2534 2536 7265 2536 2541 7266 2541 2537 7267 2537 2536 7268 2536 2541 7269 2541 2536 7270 2536 2538 7271 2538 2974 7272 2974 2279 7273 2279 2539 7274 2539 2968 7275 2968 2511 7276 2511 2540 7277 2540 3047 7278 3047 2541 7279 2541 2538 7280 2538 3049 7281 3049 2542 7282 2542 2391 7283 2391 2976 7284 2976 2281 7285 2281 2543 7286 2543 3051 7287 3051 2544 7288 2544 2393 7289 2393 2978 7290 2978 2283 7291 2283 2545 7292 2545 3053 7293 3053 2546 7294 2546 2395 7295 2395 2980 7296 2980 2285 7297 2285 2547 7298 2547 3055 7299 3055 2548 7300 2548 2397 7301 2397 2982 7302 2982 2287 7303 2287 2549 7304 2549 3057 7305 3057 2550 7306 2550 2399 7307 2399 2984 7308 2984 2289 7309 2289 2551 7310 2551 2554 7311 2554 2290 7312 2290 2552 7313 2552 2552 7314 2552 2553 7315 2553 2402 7316 2402 2554 7317 2554 2552 7318 2552 2402 7319 2402 2556 7320 2556 2554 7321 2554 2402 7322 2402 2556 7323 2556 2402 7324 2402 2555 7325 2555 2558 7326 2558 2556 7327 2556 2555 7328 2555 2558 7329 2558 2555 7330 2555 2557 7331 2557 2560 7332 2560 2558 7333 2558 2557 7334 2557 2560 7335 2560 2557 7336 2557 2559 7337 2559 2564 7338 2564 2560 7339 2560 2559 7340 2559 2564 7341 2564 2559 7342 2559 2561 7343 2561 2564 7344 2564 2561 7345 2561 2292 7346 2292 2564 7347 2564 2292 7348 2292 2562 7349 2562 2564 7350 2564 2562 7351 2562 2563 7352 2563 2566 7353 2566 2564 7354 2564 2563 7355 2563 2566 7356 2566 2563 7357 2563 2565 7358 2565 2568 7359 2568 2566 7360 2566 2565 7361 2565 2568 7362 2568 2565 7363 2565 2567 7364 2567 2570 7365 2570 2568 7366 2568 2567 7367 2567 2570 7368 2570 2567 7369 2567 2569 7370 2569 2572 7371 2572 2570 7372 2570 2569 7373 2569 2572 7374 2572 2569 7375 2569 2571 7376 2571 2598 7377 2598 2572 7378 2572 2571 7379 2571 2598 7380 2598 2571 7381 2571 2573 7382 2573 2986 7383 2986 2293 7384 2293 2574 7385 2574 3061 7386 3061 2575 7387 2575 2405 7388 2405 2587 7389 2587 2576 7390 2576 2406 7391 2406 2579 7392 2579 2296 7393 2296 2577 7394 2577 2577 7395 2577 2578 7396 2578 2408 7397 2408 2579 7398 2579 2577 7399 2577 2408 7400 2408 2581 7401 2581 2579 7402 2579 2408 7403 2408 2581 7404 2581 2408 7405 2408 2580 7406 2580 2583 7407 2583 2581 7408 2581 2580 7409 2580 2583 7410 2583 2580 7411 2580 2582 7412 2582 2585 7413 2585 2583 7414 2583 2582 7415 2582 2585 7416 2585 2582 7417 2582 2584 7418 2584 2406 7419 2406 2585 7420 2585 2584 7421 2584 2587 7422 2587 2406 7423 2406 2584 7424 2584 2587 7425 2587 2584 7426 2584 2586 7427 2586 2589 7428 2589 2587 7429 2587 2586 7430 2586 2589 7431 2589 2586 7432 2586 2588 7433 2588 2591 7434 2591 2589 7435 2589 2588 7436 2588 2591 7437 2591 2588 7438 2588 2590 7439 2590 2593 7440 2593 2591 7441 2591 2590 7442 2590 2593 7443 2593 2590 7444 2590 2592 7445 2592 2595 7446 2595 2593 7447 2593 2592 7448 2592 2595 7449 2595 2592 7450 2592 2594 7451 2594 2597 7452 2597 2595 7453 2595 2594 7454 2594 2597 7455 2597 2594 7456 2594 2596 7457 2596 2988 7458 2988 2597 7459 2597 2596 7460 2596 3059 7461 3059 2598 7462 2598 2573 7463 2573 2988 7464 2988 2596 7465 2596 2599 7466 2599 3063 7467 3063 2600 7468 2600 2409 7469 2409 2990 7470 2990 2299 7471 2299 2601 7472 2601 3065 7473 3065 2602 7474 2602 2411 7475 2411 2614 7476 2614 2603 7477 2603 2412 7478 2412 2606 7479 2606 2302 7480 2302 2604 7481 2604 2604 7482 2604 2605 7483 2605 2414 7484 2414 2606 7485 2606 2604 7486 2604 2414 7487 2414 2608 7488 2608 2606 7489 2606 2414 7490 2414 2608 7491 2608 2414 7492 2414 2607 7493 2607 2610 7494 2610 2608 7495 2608 2607 7496 2607 2610 7497 2610 2607 7498 2607 2609 7499 2609 2612 7500 2612 2610 7501 2610 2609 7502 2609 2612 7503 2612 2609 7504 2609 2611 7505 2611 2412 7506 2412 2612 7507 2612 2611 7508 2611 2614 7509 2614 2412 7510 2412 2611 7511 2611 2614 7512 2614 2611 7513 2611 2613 7514 2613 2616 7515 2616 2614 7516 2614 2613 7517 2613 2616 7518 2616 2613 7519 2613 2615 7520 2615 2618 7521 2618 2616 7522 2616 2615 7523 2615 2618 7524 2618 2615 7525 2615 2617 7526 2617 2620 7527 2620 2618 7528 2618 2617 7529 2617 2620 7530 2620 2617 7531 2617 2619 7532 2619 2622 7533 2622 2620 7534 2620 2619 7535 2619 2622 7536 2622 2619 7537 2619 2621 7538 2621 2624 7539 2624 2622 7540 2622 2621 7541 2621 2624 7542 2624 2621 7543 2621 2623 7544 2623 2992 7545 2992 2624 7546 2624 2623 7547 2623 3067 7548 3067 2625 7549 2625 2415 7550 2415 2994 7551 2994 2305 7552 2305 2626 7553 2626 2992 7554 2992 2623 7555 2623 2627 7556 2627 2630 7557 2630 2306 7558 2306 2628 7559 2628 2628 7560 2628 2629 7561 2629 2418 7562 2418 2630 7563 2630 2628 7564 2628 2418 7565 2418 2632 7566 2632 2630 7567 2630 2418 7568 2418 2632 7569 2632 2418 7570 2418 2631 7571 2631 2634 7572 2634 2632 7573 2632 2631 7574 2631 2634 7575 2634 2631 7576 2631 2633 7577 2633 2636 7578 2636 2634 7579 2634 2633 7580 2633 2636 7581 2636 2633 7582 2633 2635 7583 2635 2638 7584 2638 2636 7585 2636 2635 7586 2635 2638 7587 2638 2635 7588 2635 2637 7589 2637 3069 7590 3069 2638 7591 2638 2637 7592 2637 3069 7593 3069 2637 7594 2637 2639 7595 2639 3071 7596 3071 2640 7597 2640 2419 7598 2419 2996 7599 2996 2309 7600 2309 2641 7601 2641 3073 7602 3073 2642 7603 2642 2421 7604 2421 2998 7605 2998 2311 7606 2311 2643 7607 2643 2646 7608 2646 2312 7609 2312 2644 7610 2644 2644 7611 2644 2645 7612 2645 2424 7613 2424 2646 7614 2646 2644 7615 2644 2424 7616 2424 2648 7617 2648 2646 7618 2646 2424 7619 2424 2648 7620 2648 2424 7621 2424 2647 7622 2647 2650 7623 2650 2648 7624 2648 2647 7625 2647 2650 7626 2650 2647 7627 2647 2649 7628 2649 2652 7629 2652 2650 7630 2650 2649 7631 2649 2652 7632 2652 2649 7633 2649 2651 7634 2651 2656 7635 2656 2652 7636 2652 2651 7637 2651 2656 7638 2656 2651 7639 2651 2653 7640 2653 2656 7641 2656 2653 7642 2653 2314 7643 2314 2656 7644 2656 2314 7645 2314 2654 7646 2654 2656 7647 2656 2654 7648 2654 2655 7649 2655 2658 7650 2658 2656 7651 2656 2655 7652 2655 2658 7653 2658 2655 7654 2655 2657 7655 2657 2660 7656 2660 2658 7657 2658 2657 7658 2657 2660 7659 2660 2657 7660 2657 2659 7661 2659 2662 7662 2662 2660 7663 2660 2659 7664 2659 2662 7665 2662 2659 7666 2659 2661 7667 2661 2664 7668 2664 2662 7669 2662 2661 7670 2661 2664 7671 2664 2661 7672 2661 2663 7673 2663 2666 7674 2666 2664 7675 2664 2663 7676 2663 2666 7677 2666 2663 7678 2663 2665 7679 2665 3075 7680 3075 2666 7681 2666 2665 7682 2665 3000 7683 3000 2315 7684 2315 2667 7685 2667 3077 7686 3077 2668 7687 2668 2427 7688 2427 2680 7689 2680 2669 7690 2669 2428 7691 2428 2672 7692 2672 2318 7693 2318 2670 7694 2670 2670 7695 2670 2671 7696 2671 2430 7697 2430 2672 7698 2672 2670 7699 2670 2430 7700 2430 2674 7701 2674 2672 7702 2672 2430 7703 2430 2674 7704 2674 2430 7705 2430 2673 7706 2673 2676 7707 2676 2674 7708 2674 2673 7709 2673 2676 7710 2676 2673 7711 2673 2675 7712 2675 2678 7713 2678 2676 7714 2676 2675 7715 2675 2678 7716 2678 2675 7717 2675 2677 7718 2677 2428 7719 2428 2678 7720 2678 2677 7721 2677 2680 7722 2680 2428 7723 2428 2677 7724 2677 2680 7725 2680 2677 7726 2677 2679 7727 2679 2682 7728 2682 2680 7729 2680 2679 7730 2679 2682 7731 2682 2679 7732 2679 2681 7733 2681 2684 7734 2684 2682 7735 2682 2681 7736 2681 2684 7737 2684 2681 7738 2681 2683 7739 2683 2686 7740 2686 2684 7741 2684 2683 7742 2683 2686 7743 2686 2683 7744 2683 2685 7745 2685 2688 7746 2688 2686 7747 2686 2685 7748 2685 2688 7749 2688 2685 7750 2685 2687 7751 2687 2690 7752 2690 2688 7753 2688 2687 7754 2687 2690 7755 2690 2687 7756 2687 2689 7757 2689 3002 7758 3002 2690 7759 2690 2689 7760 2689 3079 7761 3079 2691 7762 2691 2431 7763 2431 3004 7764 3004 2321 7765 2321 2692 7766 2692 3081 7767 3081 2693 7768 2693 2433 7769 2433 3006 7770 3006 2323 7771 2323 2694 7772 2694 3002 7773 3002 2689 7774 2689 2695 7775 2695 2698 7776 2698 2324 7777 2324 2696 7778 2696 2696 7779 2696 2697 7780 2697 2436 7781 2436 2698 7782 2698 2696 7783 2696 2436 7784 2436 2700 7785 2700 2698 7786 2698 2436 7787 2436 2700 7788 2700 2436 7789 2436 2699 7790 2699 2702 7791 2702 2700 7792 2700 2699 7793 2699 2702 7794 2702 2699 7795 2699 2701 7796 2701 2704 7797 2704 2702 7798 2702 2701 7799 2701 2704 7800 2704 2701 7801 2701 2703 7802 2703 2708 7803 2708 2704 7804 2704 2703 7805 2703 2708 7806 2708 2703 7807 2703 2705 7808 2705 2708 7809 2708 2705 7810 2705 2326 7811 2326 2708 7812 2708 2326 7813 2326 2706 7814 2706 2708 7815 2708 2706 7816 2706 2707 7817 2707 2710 7818 2710 2708 7819 2708 2707 7820 2707 2710 7821 2710 2707 7822 2707 2709 7823 2709 2712 7824 2712 2710 7825 2710 2709 7826 2709 2712 7827 2712 2709 7828 2709 2711 7829 2711 2714 7830 2714 2712 7831 2712 2711 7832 2711 2714 7833 2714 2711 7834 2711 2713 7835 2713 2716 7836 2716 2714 7837 2714 2713 7838 2713 2716 7839 2716 2713 7840 2713 2715 7841 2715 2743 7842 2743 2716 7843 2716 2715 7844 2715 2743 7845 2743 2715 7846 2715 2717 7847 2717 2729 7848 2729 2718 7849 2718 2438 7850 2438 2721 7851 2721 2328 7852 2328 2719 7853 2719 2719 7854 2719 2720 7855 2720 2440 7856 2440 2721 7857 2721 2719 7858 2719 2440 7859 2440 2723 7860 2723 2721 7861 2721 2440 7862 2440 2723 7863 2723 2440 7864 2440 2722 7865 2722 2725 7866 2725 2723 7867 2723 2722 7868 2722 2725 7869 2725 2722 7870 2722 2724 7871 2724 2727 7872 2727 2725 7873 2725 2724 7874 2724 2727 7875 2727 2724 7876 2724 2726 7877 2726 2438 7878 2438 2727 7879 2727 2726 7880 2726 2729 7881 2729 2438 7882 2438 2726 7883 2726 2729 7884 2729 2726 7885 2726 2728 7886 2728 2731 7887 2731 2729 7888 2729 2728 7889 2728 2731 7890 2731 2728 7891 2728 2730 7892 2730 2733 7893 2733 2731 7894 2731 2730 7895 2730 2733 7896 2733 2730 7897 2730 2732 7898 2732 2735 7899 2735 2733 7900 2733 2732 7901 2732 2735 7902 2735 2732 7903 2732 2734 7904 2734 2737 7905 2737 2735 7906 2735 2734 7907 2734 2737 7908 2737 2734 7909 2734 2736 7910 2736 2739 7911 2739 2737 7912 2737 2736 7913 2736 2739 7914 2739 2736 7915 2736 2738 7916 2738 3008 7917 3008 2739 7918 2739 2738 7919 2738 3085 7920 3085 2740 7921 2740 2441 7922 2441 3010 7923 3010 2331 7924 2331 2741 7925 2741 2746 7926 2746 2332 7927 2332 2742 7928 2742 3083 7929 3083 2743 7930 2743 2717 7931 2717 3008 7932 3008 2738 7933 2738 2744 7934 2744 2742 7935 2742 2745 7936 2745 2444 7937 2444 2746 7938 2746 2742 7939 2742 2444 7940 2444 2748 7941 2748 2746 7942 2746 2444 7943 2444 2748 7944 2748 2444 7945 2444 2747 7946 2747 2750 7947 2750 2748 7948 2748 2747 7949 2747 2750 7950 2750 2747 7951 2747 2749 7952 2749 2752 7953 2752 2750 7954 2750 2749 7955 2749 2752 7956 2752 2749 7957 2749 2751 7958 2751 2756 7959 2756 2752 7960 2752 2751 7961 2751 2756 7962 2756 2751 7963 2751 2753 7964 2753 2756 7965 2756 2753 7966 2753 2334 7967 2334 2756 7968 2756 2334 7969 2334 2754 7970 2754 2756 7971 2756 2754 7972 2754 2755 7973 2755 2758 7974 2758 2756 7975 2756 2755 7976 2755 2758 7977 2758 2755 7978 2755 2757 7979 2757 2760 7980 2760 2758 7981 2758 2757 7982 2757 2760 7983 2760 2757 7984 2757 2759 7985 2759 2762 7986 2762 2760 7987 2760 2759 7988 2759 2762 7989 2762 2759 7990 2759 2761 7991 2761 2764 7992 2764 2762 7993 2762 2761 7994 2761 2764 7995 2764 2761 7996 2761 2763 7997 2763 2791 7998 2791 2764 7999 2764 2763 8000 2763 2791 8001 2791 2763 8002 2763 2765 8003 2765 2777 8004 2777 2766 8005 2766 2446 8006 2446 2769 8007 2769 2336 8008 2336 2767 8009 2767 2767 8010 2767 2768 8011 2768 2448 8012 2448 2769 8013 2769 2767 8014 2767 2448 8015 2448 2771 8016 2771 2769 8017 2769 2448 8018 2448 2771 8019 2771 2448 8020 2448 2770 8021 2770 2773 8022 2773 2771 8023 2771 2770 8024 2770 2773 8025 2773 2770 8026 2770 2772 8027 2772 2775 8028 2775 2773 8029 2773 2772 8030 2772 2775 8031 2775 2772 8032 2772 2774 8033 2774 2446 8034 2446 2775 8035 2775 2774 8036 2774 2777 8037 2777 2446 8038 2446 2774 8039 2774 2777 8040 2777 2774 8041 2774 2776 8042 2776 2779 8043 2779 2777 8044 2777 2776 8045 2776 2779 8046 2779 2776 8047 2776 2778 8048 2778 2781 8049 2781 2779 8050 2779 2778 8051 2778 2781 8052 2781 2778 8053 2778 2780 8054 2780 2783 8055 2783 2781 8056 2781 2780 8057 2780 2783 8058 2783 2780 8059 2780 2782 8060 2782 2785 8061 2785 2783 8062 2783 2782 8063 2782 2785 8064 2785 2782 8065 2782 2784 8066 2784 2787 8067 2787 2785 8068 2785 2784 8069 2784 2787 8070 2787 2784 8071 2784 2786 8072 2786 3012 8073 3012 2787 8074 2787 2786 8075 2786 3089 8076 3089 2788 8077 2788 2449 8078 2449 3014 8079 3014 2339 8080 2339 2789 8081 2789 2794 8082 2794 2340 8083 2340 2790 8084 2790 3087 8085 3087 2791 8086 2791 2765 8087 2765 3012 8088 3012 2786 8089 2786 2792 8090 2792 2790 8091 2790 2793 8092 2793 2452 8093 2452 2794 8094 2794 2790 8095 2790 2452 8096 2452 2796 8097 2796 2794 8098 2794 2452 8099 2452 2796 8100 2796 2452 8101 2452 2795 8102 2795 2798 8103 2798 2796 8104 2796 2795 8105 2795 2798 8106 2798 2795 8107 2795 2797 8108 2797 2800 8109 2800 2798 8110 2798 2797 8111 2797 2800 8112 2800 2797 8113 2797 2799 8114 2799 2804 8115 2804 2800 8116 2800 2799 8117 2799 2804 8118 2804 2799 8119 2799 2801 8120 2801 2804 8121 2804 2801 8122 2801 2342 8123 2342 2804 8124 2804 2342 8125 2342 2802 8126 2802 2804 8127 2804 2802 8128 2802 2803 8129 2803 2806 8130 2806 2804 8131 2804 2803 8132 2803 2806 8133 2806 2803 8134 2803 2805 8135 2805 2808 8136 2808 2806 8137 2806 2805 8138 2805 2808 8139 2808 2805 8140 2805 2807 8141 2807 2810 8142 2810 2808 8143 2808 2807 8144 2807 2810 8145 2810 2807 8146 2807 2809 8147 2809 2812 8148 2812 2810 8149 2810 2809 8150 2809 2812 8151 2812 2809 8152 2809 2811 8153 2811 2839 8154 2839 2812 8155 2812 2811 8156 2811 2839 8157 2839 2811 8158 2811 2813 8159 2813 3016 8160 3016 2343 8161 2343 2814 8162 2814 3093 8163 3093 2815 8164 2815 2455 8165 2455 3018 8166 3018 2345 8167 2345 2816 8168 2816 2819 8169 2819 2346 8170 2346 2817 8171 2817 2817 8172 2817 2818 8173 2818 2458 8174 2458 2819 8175 2819 2817 8176 2817 2458 8177 2458 2821 8178 2821 2819 8179 2819 2458 8180 2458 2821 8181 2821 2458 8182 2458 2820 8183 2820 2823 8184 2823 2821 8185 2821 2820 8186 2820 2823 8187 2823 2820 8188 2820 2822 8189 2822 2825 8190 2825 2823 8191 2823 2822 8192 2822 2825 8193 2825 2822 8194 2822 2824 8195 2824 2829 8196 2829 2825 8197 2825 2824 8198 2824 2829 8199 2829 2824 8200 2824 2826 8201 2826 2829 8202 2829 2826 8203 2826 2348 8204 2348 2829 8205 2829 2348 8206 2348 2827 8207 2827 2829 8208 2829 2827 8209 2827 2828 8210 2828 2831 8211 2831 2829 8212 2829 2828 8213 2828 2831 8214 2831 2828 8215 2828 2830 8216 2830 2833 8217 2833 2831 8218 2831 2830 8219 2830 2833 8220 2833 2830 8221 2830 2832 8222 2832 2835 8223 2835 2833 8224 2833 2832 8225 2832 2835 8226 2835 2832 8227 2832 2834 8228 2834 2837 8229 2837 2835 8230 2835 2834 8231 2834 2837 8232 2837 2834 8233 2834 2836 8234 2836 2840 8235 2840 2837 8236 2837 2836 8237 2836 2840 8238 2840 2836 8239 2836 2838 8240 2838 3091 8241 3091 2839 8242 2839 2813 8243 2813 3095 8244 3095 2840 8245 2840 2838 8246 2838 3020 8247 3020 2349 8248 2349 2841 8249 2841 3097 8250 3097 2842 8251 2842 2461 8252 2461 3022 8253 3022 2351 8254 2351 2843 8255 2843 2846 8256 2846 2352 8257 2352 2844 8258 2844 2844 8259 2844 2845 8260 2845 2464 8261 2464 2846 8262 2846 2844 8263 2844 2464 8264 2464 2848 8265 2848 2846 8266 2846 2464 8267 2464 2848 8268 2848 2464 8269 2464 2847 8270 2847 2850 8271 2850 2848 8272 2848 2847 8273 2847 2850 8274 2850 2847 8275 2847 2849 8276 2849 2852 8277 2852 2850 8278 2850 2849 8279 2849 2852 8280 2852 2849 8281 2849 2851 8282 2851 2856 8283 2856 2852 8284 2852 2851 8285 2851 2856 8286 2856 2851 8287 2851 2853 8288 2853 2856 8289 2856 2853 8290 2853 2354 8291 2354 2856 8292 2856 2354 8293 2354 2854 8294 2854 2856 8295 2856 2854 8296 2854 2855 8297 2855 2858 8298 2858 2856 8299 2856 2855 8300 2855 2858 8301 2858 2855 8302 2855 2857 8303 2857 2860 8304 2860 2858 8305 2858 2857 8306 2857 2860 8307 2860 2857 8308 2857 2859 8309 2859 2862 8310 2862 2860 8311 2860 2859 8312 2859 2862 8313 2862 2859 8314 2859 2861 8315 2861 2864 8316 2864 2862 8317 2862 2861 8318 2861 2864 8319 2864 2861 8320 2861 2863 8321 2863 2868 8322 2868 2864 8323 2864 2863 8324 2863 2868 8325 2868 2863 8326 2863 2865 8327 2865 3024 8328 3024 2355 8329 2355 2866 8330 2866 2870 8331 2870 2356 8332 2356 2867 8333 2867 3099 8334 3099 2868 8335 2868 2865 8336 2865 2867 8337 2867 2869 8338 2869 2468 8339 2468 2870 8340 2870 2867 8341 2867 2468 8342 2468 2872 8343 2872 2870 8344 2870 2468 8345 2468 2872 8346 2872 2468 8347 2468 2871 8348 2871 2874 8349 2874 2872 8350 2872 2871 8351 2871 2874 8352 2874 2871 8353 2871 2873 8354 2873 2876 8355 2876 2874 8356 2874 2873 8357 2873 2876 8358 2876 2873 8359 2873 2875 8360 2875 2880 8361 2880 2876 8362 2876 2875 8363 2875 2880 8364 2880 2875 8365 2875 2877 8366 2877 2880 8367 2880 2877 8368 2877 2358 8369 2358 2880 8370 2880 2358 8371 2358 2878 8372 2878 2880 8373 2880 2878 8374 2878 2879 8375 2879 2882 8376 2882 2880 8377 2880 2879 8378 2879 2882 8379 2882 2879 8380 2879 2881 8381 2881 2884 8382 2884 2882 8383 2882 2881 8384 2881 2884 8385 2884 2881 8386 2881 2883 8387 2883 2886 8388 2886 2884 8389 2884 2883 8390 2883 2886 8391 2886 2883 8392 2883 2885 8393 2885 2888 8394 2888 2886 8395 2886 2885 8396 2885 2888 8397 2888 2885 8398 2885 2887 8399 2887 2935 8400 2935 2888 8401 2888 2887 8402 2887 2935 8403 2935 2887 8404 2887 2889 8405 2889 3026 8406 3026 2359 8407 2359 2890 8408 2890 2893 8409 2893 2360 8410 2360 2891 8411 2891 2891 8412 2891 2892 8413 2892 2472 8414 2472 2893 8415 2893 2891 8416 2891 2472 8417 2472 2895 8418 2895 2893 8419 2893 2472 8420 2472 2895 8421 2895 2472 8422 2472 2894 8423 2894 2897 8424 2897 2895 8425 2895 2894 8426 2894 2897 8427 2897 2894 8428 2894 2896 8429 2896 2899 8430 2899 2897 8431 2897 2896 8432 2896 2899 8433 2899 2896 8434 2896 2898 8435 2898 2903 8436 2903 2899 8437 2899 2898 8438 2898 2903 8439 2903 2898 8440 2898 2900 8441 2900 2903 8442 2903 2900 8443 2900 2362 8444 2362 2903 8445 2903 2362 8446 2362 2901 8447 2901 2903 8448 2903 2901 8449 2901 2902 8450 2902 2905 8451 2905 2903 8452 2903 2902 8453 2902 2905 8454 2905 2902 8455 2902 2904 8456 2904 2907 8457 2907 2905 8458 2905 2904 8459 2904 2907 8460 2907 2904 8461 2904 2906 8462 2906 2909 8463 2909 2907 8464 2907 2906 8465 2906 2909 8466 2909 2906 8467 2906 2908 8468 2908 2911 8469 2911 2909 8470 2909 2908 8471 2908 2911 8472 2911 2908 8473 2908 2910 8474 2910 2936 8475 2936 2911 8476 2911 2910 8477 2910 2936 8478 2936 2910 8479 2910 2912 8480 2912 2924 8481 2924 2913 8482 2913 2474 8483 2474 2916 8484 2916 2364 8485 2364 2914 8486 2914 2914 8487 2914 2915 8488 2915 2476 8489 2476 2916 8490 2916 2914 8491 2914 2476 8492 2476 2918 8493 2918 2916 8494 2916 2476 8495 2476 2918 8496 2918 2476 8497 2476 2917 8498 2917 2920 8499 2920 2918 8500 2918 2917 8501 2917 2920 8502 2920 2917 8503 2917 2919 8504 2919 2922 8505 2922 2920 8506 2920 2919 8507 2919 2922 8508 2922 2919 8509 2919 2921 8510 2921 2474 8511 2474 2922 8512 2922 2921 8513 2921 2924 8514 2924 2474 8515 2474 2921 8516 2921 2924 8517 2924 2921 8518 2921 2923 8519 2923 2926 8520 2926 2924 8521 2924 2923 8522 2923 2926 8523 2926 2923 8524 2923 2925 8525 2925 2928 8526 2928 2926 8527 2926 2925 8528 2925 2928 8529 2928 2925 8530 2925 2927 8531 2927 2930 8532 2930 2928 8533 2928 2927 8534 2927 2930 8535 2930 2927 8536 2927 2929 8537 2929 2932 8538 2932 2930 8539 2930 2929 8540 2929 2932 8541 2932 2929 8542 2929 2931 8543 2931 2934 8544 2934 2932 8545 2932 2931 8546 2931 2934 8547 2934 2931 8548 2931 2933 8549 2933 3028 8550 3028 2934 8551 2934 2933 8552 2933 3101 8553 3101 2935 8554 2935 2889 8555 2889 3103 8556 3103 2936 8557 2936 2912 8558 2912 3028 8559 3028 2933 8560 2933 2937 8561 2937 3105 8562 3105 2938 8563 2938 2477 8564 2477 3030 8565 3030 2367 8566 2367 2939 8567 2939 2942 8568 2942 2368 8569 2368 2940 8570 2940 2940 8571 2940 2941 8572 2941 2480 8573 2480 2942 8574 2942 2940 8575 2940 2480 8576 2480 2944 8577 2944 2942 8578 2942 2480 8579 2480 2944 8580 2944 2480 8581 2480 2943 8582 2943 2946 8583 2946 2944 8584 2944 2943 8585 2943 2946 8586 2946 2943 8587 2943 2945 8588 2945 2948 8589 2948 2946 8590 2946 2945 8591 2945 2948 8592 2948 2945 8593 2945 2947 8594 2947 2949 8595 2949 2948 8596 2948 2947 8597 2947 2950 8598 2950 2949 8599 2949 2947 8600 2947 2950 8601 2950 2947 8602 2947 1920 8603 1920 2951 8604 2951 2950 8605 2950 1920 8606 1920 2952 8607 2952 2951 8608 2951 1920 8609 1920 2953 8610 2953 2952 8611 2952 1920 8612 1920 2954 8613 2954 2953 8614 2953 1920 8615 1920 2955 8616 2955 2954 8617 2954 1920 8618 1920 2956 8619 2956 2955 8620 2955 1920 8621 1920 2957 8622 2957 2956 8623 2956 1920 8624 1920 2958 8625 2958 2957 8626 2957 1920 8627 1920 3031 8628 3031 2958 8629 2958 1920 8630 1920 3033 8631 3033 2371 8632 2371 2959 8633 2959 3108 8634 3108 2960 8635 2960 2483 8636 2483 3035 8637 3035 2373 8638 2373 2961 8639 2961 3116 8640 3116 2962 8641 2962 2485 8642 2485 3037 8643 3037 2375 8644 2375 2963 8645 2963 3124 8646 3124 2964 8647 2964 2487 8648 2487 3039 8649 3039 2377 8650 2377 2965 8651 2965 3132 8652 3132 2966 8653 2966 2489 8654 2489 3041 8655 3041 2379 8656 2379 2967 8657 2967 3140 8658 3140 2968 8659 2968 2540 8660 2540 3043 8661 3043 2383 8662 2383 2969 8663 2969 3148 8664 3148 2970 8665 2970 2514 8666 2514 3045 8667 3045 2385 8668 2385 2971 8669 2971 3156 8670 3156 2972 8671 2972 2516 8672 2516 3047 8673 3047 2538 8674 2538 2973 8675 2973 3164 8676 3164 2974 8677 2974 2539 8678 2539 3049 8679 3049 2391 8680 2391 2975 8681 2975 3172 8682 3172 2976 8683 2976 2543 8684 2543 3051 8685 3051 2393 8686 2393 2977 8687 2977 3180 8688 3180 2978 8689 2978 2545 8690 2545 3053 8691 3053 2395 8692 2395 2979 8693 2979 3188 8694 3188 2980 8695 2980 2547 8696 2547 3055 8697 3055 2397 8698 2397 2981 8699 2981 3196 8700 3196 2982 8701 2982 2549 8702 2549 3057 8703 3057 2399 8704 2399 2983 8705 2983 3204 8706 3204 2984 8707 2984 2551 8708 2551 3059 8709 3059 2573 8710 2573 2985 8711 2985 3212 8712 3212 2986 8713 2986 2574 8714 2574 3061 8715 3061 2405 8716 2405 2987 8717 2987 3220 8718 3220 2988 8719 2988 2599 8720 2599 3063 8721 3063 2409 8722 2409 2989 8723 2989 3228 8724 3228 2990 8725 2990 2601 8726 2601 3065 8727 3065 2411 8728 2411 2991 8729 2991 3236 8730 3236 2992 8731 2992 2627 8732 2627 3067 8733 3067 2415 8734 2415 2993 8735 2993 3244 8736 3244 2994 8737 2994 2626 8738 2626 3071 8739 3071 2419 8740 2419 2995 8741 2995 3252 8742 3252 2996 8743 2996 2641 8744 2641 3073 8745 3073 2421 8746 2421 2997 8747 2997 3260 8748 3260 2998 8749 2998 2643 8750 2643 3075 8751 3075 2665 8752 2665 2999 8753 2999 3268 8754 3268 3000 8755 3000 2667 8756 2667 3077 8757 3077 2427 8758 2427 3001 8759 3001 3276 8760 3276 3002 8761 3002 2695 8762 2695 3079 8763 3079 2431 8764 2431 3003 8765 3003 3284 8766 3284 3004 8767 3004 2692 8768 2692 3081 8769 3081 2433 8770 2433 3005 8771 3005 3292 8772 3292 3006 8773 3006 2694 8774 2694 3083 8775 3083 2717 8776 2717 3007 8777 3007 3300 8778 3300 3008 8779 3008 2744 8780 2744 3085 8781 3085 2441 8782 2441 3009 8783 3009 3308 8784 3308 3010 8785 3010 2741 8786 2741 3087 8787 3087 2765 8788 2765 3011 8789 3011 3316 8790 3316 3012 8791 3012 2792 8792 2792 3089 8793 3089 2449 8794 2449 3013 8795 3013 3324 8796 3324 3014 8797 3014 2789 8798 2789 3091 8799 3091 2813 8800 2813 3015 8801 3015 3332 8802 3332 3016 8803 3016 2814 8804 2814 3093 8805 3093 2455 8806 2455 3017 8807 3017 3340 8808 3340 3018 8809 3018 2816 8810 2816 3095 8811 3095 2838 8812 2838 3019 8813 3019 3348 8814 3348 3020 8815 3020 2841 8816 2841 3097 8817 3097 2461 8818 2461 3021 8819 3021 3356 8820 3356 3022 8821 3022 2843 8822 2843 3099 8823 3099 2865 8824 2865 3023 8825 3023 3364 8826 3364 3024 8827 3024 2866 8828 2866 3101 8829 3101 2889 8830 2889 3025 8831 3025 3372 8832 3372 3026 8833 3026 2890 8834 2890 3103 8835 3103 2912 8836 2912 3027 8837 3027 3380 8838 3380 3028 8839 3028 2937 8840 2937 3105 8841 3105 2477 8842 2477 3029 8843 3029 3388 8844 3388 3030 8845 3030 2939 8846 2939 3395 8847 3395 3031 8848 3031 1920 8849 1920 3625 8850 3625 2370 8851 2370 3032 8852 3032 3109 8853 3109 3033 8854 3033 2959 8855 2959 3108 8856 3108 2483 8857 2483 3034 8858 3034 3117 8859 3117 3035 8860 3035 2961 8861 2961 3116 8862 3116 2485 8863 2485 3036 8864 3036 3125 8865 3125 3037 8866 3037 2963 8867 2963 3124 8868 3124 2487 8869 2487 3038 8870 3038 3133 8871 3133 3039 8872 3039 2965 8873 2965 3132 8874 3132 2489 8875 2489 3040 8876 3040 3141 8877 3141 3041 8878 3041 2967 8879 2967 3140 8880 3140 2540 8881 2540 3042 8882 3042 3149 8883 3149 3043 8884 3043 2969 8885 2969 3148 8886 3148 2514 8887 2514 3044 8888 3044 3157 8889 3157 3045 8890 3045 2971 8891 2971 3156 8892 3156 2516 8893 2516 3046 8894 3046 3165 8895 3165 3047 8896 3047 2973 8897 2973 3164 8898 3164 2539 8899 2539 3048 8900 3048 3173 8901 3173 3049 8902 3049 2975 8903 2975 3172 8904 3172 2543 8905 2543 3050 8906 3050 3181 8907 3181 3051 8908 3051 2977 8909 2977 3180 8910 3180 2545 8911 2545 3052 8912 3052 3189 8913 3189 3053 8914 3053 2979 8915 2979 3188 8916 3188 2547 8917 2547 3054 8918 3054 3197 8919 3197 3055 8920 3055 2981 8921 2981 3196 8922 3196 2549 8923 2549 3056 8924 3056 3205 8925 3205 3057 8926 3057 2983 8927 2983 3204 8928 3204 2551 8929 2551 3058 8930 3058 3213 8931 3213 3059 8932 3059 2985 8933 2985 3212 8934 3212 2574 8935 2574 3060 8936 3060 3221 8937 3221 3061 8938 3061 2987 8939 2987 3220 8940 3220 2599 8941 2599 3062 8942 3062 3229 8943 3229 3063 8944 3063 2989 8945 2989 3228 8946 3228 2601 8947 2601 3064 8948 3064 3237 8949 3237 3065 8950 3065 2991 8951 2991 3236 8952 3236 2627 8953 2627 3066 8954 3066 3245 8955 3245 3067 8956 3067 2993 8957 2993 3244 8958 3244 2626 8959 2626 3068 8960 3068 3433 8961 3433 3069 8962 3069 2639 8963 2639 3433 8964 3433 2639 8965 2639 3070 8966 3070 3253 8967 3253 3071 8968 3071 2995 8969 2995 3252 8970 3252 2641 8971 2641 3072 8972 3072 3261 8973 3261 3073 8974 3073 2997 8975 2997 3260 8976 3260 2643 8977 2643 3074 8978 3074 3269 8979 3269 3075 8980 3075 2999 8981 2999 3268 8982 3268 2667 8983 2667 3076 8984 3076 3277 8985 3277 3077 8986 3077 3001 8987 3001 3276 8988 3276 2695 8989 2695 3078 8990 3078 3285 8991 3285 3079 8992 3079 3003 8993 3003 3284 8994 3284 2692 8995 2692 3080 8996 3080 3293 8997 3293 3081 8998 3081 3005 8999 3005 3292 9000 3292 2694 9001 2694 3082 9002 3082 3301 9003 3301 3083 9004 3083 3007 9005 3007 3300 9006 3300 2744 9007 2744 3084 9008 3084 3309 9009 3309 3085 9010 3085 3009 9011 3009 3308 9012 3308 2741 9013 2741 3086 9014 3086 3317 9015 3317 3087 9016 3087 3011 9017 3011 3316 9018 3316 2792 9019 2792 3088 9020 3088 3325 9021 3325 3089 9022 3089 3013 9023 3013 3324 9024 3324 2789 9025 2789 3090 9026 3090 3333 9027 3333 3091 9028 3091 3015 9029 3015 3332 9030 3332 2814 9031 2814 3092 9032 3092 3341 9033 3341 3093 9034 3093 3017 9035 3017 3340 9036 3340 2816 9037 2816 3094 9038 3094 3349 9039 3349 3095 9040 3095 3019 9041 3019 3348 9042 3348 2841 9043 2841 3096 9044 3096 3357 9045 3357 3097 9046 3097 3021 9047 3021 3356 9048 3356 2843 9049 2843 3098 9050 3098 3365 9051 3365 3099 9052 3099 3023 9053 3023 3364 9054 3364 2866 9055 2866 3100 9056 3100 3373 9057 3373 3101 9058 3101 3025 9059 3025 3372 9060 3372 2890 9061 2890 3102 9062 3102 3381 9063 3381 3103 9064 3103 3027 9065 3027 3380 9066 3380 2937 9067 2937 3104 9068 3104 3389 9069 3389 3105 9070 3105 3029 9071 3029 3388 9072 3388 2939 9073 2939 3106 9074 3106 3109 9075 3109 2959 9076 2959 3107 9077 3107 3107 9078 3107 3108 9079 3108 3034 9080 3034 3109 9081 3109 3107 9082 3107 3034 9083 3034 3111 9084 3111 3109 9085 3109 3034 9086 3034 3111 9087 3111 3034 9088 3034 3110 9089 3110 3113 9090 3113 3111 9091 3111 3110 9092 3110 3113 9093 3113 3110 9094 3110 3112 9095 3112 3397 9096 3397 3113 9097 3113 3112 9098 3112 3397 9099 3397 3112 9100 3112 3114 9101 3114 3117 9102 3117 2961 9103 2961 3115 9104 3115 3115 9105 3115 3116 9106 3116 3036 9107 3036 3117 9108 3117 3115 9109 3115 3036 9110 3036 3119 9111 3119 3117 9112 3117 3036 9113 3036 3119 9114 3119 3036 9115 3036 3118 9116 3118 3121 9117 3121 3119 9118 3119 3118 9119 3118 3121 9120 3121 3118 9121 3118 3120 9122 3120 3399 9123 3399 3121 9124 3121 3120 9125 3120 3399 9126 3399 3120 9127 3120 3122 9128 3122 3125 9129 3125 2963 9130 2963 3123 9131 3123 3123 9132 3123 3124 9133 3124 3038 9134 3038 3125 9135 3125 3123 9136 3123 3038 9137 3038 3127 9138 3127 3125 9139 3125 3038 9140 3038 3127 9141 3127 3038 9142 3038 3126 9143 3126 3129 9144 3129 3127 9145 3127 3126 9146 3126 3129 9147 3129 3126 9148 3126 3128 9149 3128 3401 9150 3401 3129 9151 3129 3128 9152 3128 3401 9153 3401 3128 9154 3128 3130 9155 3130 3133 9156 3133 2965 9157 2965 3131 9158 3131 3131 9159 3131 3132 9160 3132 3040 9161 3040 3133 9162 3133 3131 9163 3131 3040 9164 3040 3135 9165 3135 3133 9166 3133 3040 9167 3040 3135 9168 3135 3040 9169 3040 3134 9170 3134 3137 9171 3137 3135 9172 3135 3134 9173 3134 3137 9174 3137 3134 9175 3134 3136 9176 3136 3403 9177 3403 3137 9178 3137 3136 9179 3136 3403 9180 3403 3136 9181 3136 3138 9182 3138 3141 9183 3141 2967 9184 2967 3139 9185 3139 3139 9186 3139 3140 9187 3140 3042 9188 3042 3141 9189 3141 3139 9190 3139 3042 9191 3042 3143 9192 3143 3141 9193 3141 3042 9194 3042 3143 9195 3143 3042 9196 3042 3142 9197 3142 3145 9198 3145 3143 9199 3143 3142 9200 3142 3145 9201 3145 3142 9202 3142 3144 9203 3144 3405 9204 3405 3145 9205 3145 3144 9206 3144 3405 9207 3405 3144 9208 3144 3146 9209 3146 3149 9210 3149 2969 9211 2969 3147 9212 3147 3147 9213 3147 3148 9214 3148 3044 9215 3044 3149 9216 3149 3147 9217 3147 3044 9218 3044 3151 9219 3151 3149 9220 3149 3044 9221 3044 3151 9222 3151 3044 9223 3044 3150 9224 3150 3153 9225 3153 3151 9226 3151 3150 9227 3150 3153 9228 3153 3150 9229 3150 3152 9230 3152 3407 9231 3407 3153 9232 3153 3152 9233 3152 3407 9234 3407 3152 9235 3152 3154 9236 3154 3157 9237 3157 2971 9238 2971 3155 9239 3155 3155 9240 3155 3156 9241 3156 3046 9242 3046 3157 9243 3157 3155 9244 3155 3046 9245 3046 3159 9246 3159 3157 9247 3157 3046 9248 3046 3159 9249 3159 3046 9250 3046 3158 9251 3158 3161 9252 3161 3159 9253 3159 3158 9254 3158 3161 9255 3161 3158 9256 3158 3160 9257 3160 3409 9258 3409 3161 9259 3161 3160 9260 3160 3409 9261 3409 3160 9262 3160 3162 9263 3162 3165 9264 3165 2973 9265 2973 3163 9266 3163 3163 9267 3163 3164 9268 3164 3048 9269 3048 3165 9270 3165 3163 9271 3163 3048 9272 3048 3167 9273 3167 3165 9274 3165 3048 9275 3048 3167 9276 3167 3048 9277 3048 3166 9278 3166 3169 9279 3169 3167 9280 3167 3166 9281 3166 3169 9282 3169 3166 9283 3166 3168 9284 3168 3411 9285 3411 3169 9286 3169 3168 9287 3168 3411 9288 3411 3168 9289 3168 3170 9290 3170 3173 9291 3173 2975 9292 2975 3171 9293 3171 3171 9294 3171 3172 9295 3172 3050 9296 3050 3173 9297 3173 3171 9298 3171 3050 9299 3050 3175 9300 3175 3173 9301 3173 3050 9302 3050 3175 9303 3175 3050 9304 3050 3174 9305 3174 3177 9306 3177 3175 9307 3175 3174 9308 3174 3177 9309 3177 3174 9310 3174 3176 9311 3176 3413 9312 3413 3177 9313 3177 3176 9314 3176 3413 9315 3413 3176 9316 3176 3178 9317 3178 3181 9318 3181 2977 9319 2977 3179 9320 3179 3179 9321 3179 3180 9322 3180 3052 9323 3052 3181 9324 3181 3179 9325 3179 3052 9326 3052 3183 9327 3183 3181 9328 3181 3052 9329 3052 3183 9330 3183 3052 9331 3052 3182 9332 3182 3185 9333 3185 3183 9334 3183 3182 9335 3182 3185 9336 3185 3182 9337 3182 3184 9338 3184 3415 9339 3415 3185 9340 3185 3184 9341 3184 3415 9342 3415 3184 9343 3184 3186 9344 3186 3189 9345 3189 2979 9346 2979 3187 9347 3187 3187 9348 3187 3188 9349 3188 3054 9350 3054 3189 9351 3189 3187 9352 3187 3054 9353 3054 3191 9354 3191 3189 9355 3189 3054 9356 3054 3191 9357 3191 3054 9358 3054 3190 9359 3190 3193 9360 3193 3191 9361 3191 3190 9362 3190 3193 9363 3193 3190 9364 3190 3192 9365 3192 3417 9366 3417 3193 9367 3193 3192 9368 3192 3417 9369 3417 3192 9370 3192 3194 9371 3194 3197 9372 3197 2981 9373 2981 3195 9374 3195 3195 9375 3195 3196 9376 3196 3056 9377 3056 3197 9378 3197 3195 9379 3195 3056 9380 3056 3199 9381 3199 3197 9382 3197 3056 9383 3056 3199 9384 3199 3056 9385 3056 3198 9386 3198 3201 9387 3201 3199 9388 3199 3198 9389 3198 3201 9390 3201 3198 9391 3198 3200 9392 3200 3419 9393 3419 3201 9394 3201 3200 9395 3200 3419 9396 3419 3200 9397 3200 3202 9398 3202 3205 9399 3205 2983 9400 2983 3203 9401 3203 3203 9402 3203 3204 9403 3204 3058 9404 3058 3205 9405 3205 3203 9406 3203 3058 9407 3058 3207 9408 3207 3205 9409 3205 3058 9410 3058 3207 9411 3207 3058 9412 3058 3206 9413 3206 3209 9414 3209 3207 9415 3207 3206 9416 3206 3209 9417 3209 3206 9418 3206 3208 9419 3208 3421 9420 3421 3209 9421 3209 3208 9422 3208 3421 9423 3421 3208 9424 3208 3210 9425 3210 3213 9426 3213 2985 9427 2985 3211 9428 3211 3211 9429 3211 3212 9430 3212 3060 9431 3060 3213 9432 3213 3211 9433 3211 3060 9434 3060 3215 9435 3215 3213 9436 3213 3060 9437 3060 3215 9438 3215 3060 9439 3060 3214 9440 3214 3217 9441 3217 3215 9442 3215 3214 9443 3214 3217 9444 3217 3214 9445 3214 3216 9446 3216 3423 9447 3423 3217 9448 3217 3216 9449 3216 3423 9450 3423 3216 9451 3216 3218 9452 3218 3221 9453 3221 2987 9454 2987 3219 9455 3219 3219 9456 3219 3220 9457 3220 3062 9458 3062 3221 9459 3221 3219 9460 3219 3062 9461 3062 3223 9462 3223 3221 9463 3221 3062 9464 3062 3223 9465 3223 3062 9466 3062 3222 9467 3222 3225 9468 3225 3223 9469 3223 3222 9470 3222 3225 9471 3225 3222 9472 3222 3224 9473 3224 3425 9474 3425 3225 9475 3225 3224 9476 3224 3425 9477 3425 3224 9478 3224 3226 9479 3226 3229 9480 3229 2989 9481 2989 3227 9482 3227 3227 9483 3227 3228 9484 3228 3064 9485 3064 3229 9486 3229 3227 9487 3227 3064 9488 3064 3231 9489 3231 3229 9490 3229 3064 9491 3064 3231 9492 3231 3064 9493 3064 3230 9494 3230 3233 9495 3233 3231 9496 3231 3230 9497 3230 3233 9498 3233 3230 9499 3230 3232 9500 3232 3427 9501 3427 3233 9502 3233 3232 9503 3232 3427 9504 3427 3232 9505 3232 3234 9506 3234 3237 9507 3237 2991 9508 2991 3235 9509 3235 3235 9510 3235 3236 9511 3236 3066 9512 3066 3237 9513 3237 3235 9514 3235 3066 9515 3066 3239 9516 3239 3237 9517 3237 3066 9518 3066 3239 9519 3239 3066 9520 3066 3238 9521 3238 3241 9522 3241 3239 9523 3239 3238 9524 3238 3241 9525 3241 3238 9526 3238 3240 9527 3240 3429 9528 3429 3241 9529 3241 3240 9530 3240 3429 9531 3429 3240 9532 3240 3242 9533 3242 3245 9534 3245 2993 9535 2993 3243 9536 3243 3243 9537 3243 3244 9538 3244 3068 9539 3068 3245 9540 3245 3243 9541 3243 3068 9542 3068 3247 9543 3247 3245 9544 3245 3068 9545 3068 3247 9546 3247 3068 9547 3068 3246 9548 3246 3249 9549 3249 3247 9550 3247 3246 9551 3246 3249 9552 3249 3246 9553 3246 3248 9554 3248 3431 9555 3431 3249 9556 3249 3248 9557 3248 3431 9558 3431 3248 9559 3248 3250 9560 3250 3253 9561 3253 2995 9562 2995 3251 9563 3251 3251 9564 3251 3252 9565 3252 3072 9566 3072 3253 9567 3253 3251 9568 3251 3072 9569 3072 3255 9570 3255 3253 9571 3253 3072 9572 3072 3255 9573 3255 3072 9574 3072 3254 9575 3254 3257 9576 3257 3255 9577 3255 3254 9578 3254 3257 9579 3257 3254 9580 3254 3256 9581 3256 3435 9582 3435 3257 9583 3257 3256 9584 3256 3435 9585 3435 3256 9586 3256 3258 9587 3258 3261 9588 3261 2997 9589 2997 3259 9590 3259 3259 9591 3259 3260 9592 3260 3074 9593 3074 3261 9594 3261 3259 9595 3259 3074 9596 3074 3263 9597 3263 3261 9598 3261 3074 9599 3074 3263 9600 3263 3074 9601 3074 3262 9602 3262 3265 9603 3265 3263 9604 3263 3262 9605 3262 3265 9606 3265 3262 9607 3262 3264 9608 3264 3437 9609 3437 3265 9610 3265 3264 9611 3264 3437 9612 3437 3264 9613 3264 3266 9614 3266 3269 9615 3269 2999 9616 2999 3267 9617 3267 3267 9618 3267 3268 9619 3268 3076 9620 3076 3269 9621 3269 3267 9622 3267 3076 9623 3076 3271 9624 3271 3269 9625 3269 3076 9626 3076 3271 9627 3271 3076 9628 3076 3270 9629 3270 3273 9630 3273 3271 9631 3271 3270 9632 3270 3273 9633 3273 3270 9634 3270 3272 9635 3272 3439 9636 3439 3273 9637 3273 3272 9638 3272 3439 9639 3439 3272 9640 3272 3274 9641 3274 3277 9642 3277 3001 9643 3001 3275 9644 3275 3275 9645 3275 3276 9646 3276 3078 9647 3078 3277 9648 3277 3275 9649 3275 3078 9650 3078 3279 9651 3279 3277 9652 3277 3078 9653 3078 3279 9654 3279 3078 9655 3078 3278 9656 3278 3281 9657 3281 3279 9658 3279 3278 9659 3278 3281 9660 3281 3278 9661 3278 3280 9662 3280 3441 9663 3441 3281 9664 3281 3280 9665 3280 3441 9666 3441 3280 9667 3280 3282 9668 3282 3285 9669 3285 3003 9670 3003 3283 9671 3283 3283 9672 3283 3284 9673 3284 3080 9674 3080 3285 9675 3285 3283 9676 3283 3080 9677 3080 3287 9678 3287 3285 9679 3285 3080 9680 3080 3287 9681 3287 3080 9682 3080 3286 9683 3286 3289 9684 3289 3287 9685 3287 3286 9686 3286 3289 9687 3289 3286 9688 3286 3288 9689 3288 3443 9690 3443 3289 9691 3289 3288 9692 3288 3443 9693 3443 3288 9694 3288 3290 9695 3290 3293 9696 3293 3005 9697 3005 3291 9698 3291 3291 9699 3291 3292 9700 3292 3082 9701 3082 3293 9702 3293 3291 9703 3291 3082 9704 3082 3295 9705 3295 3293 9706 3293 3082 9707 3082 3295 9708 3295 3082 9709 3082 3294 9710 3294 3297 9711 3297 3295 9712 3295 3294 9713 3294 3297 9714 3297 3294 9715 3294 3296 9716 3296 3445 9717 3445 3297 9718 3297 3296 9719 3296 3445 9720 3445 3296 9721 3296 3298 9722 3298 3301 9723 3301 3007 9724 3007 3299 9725 3299 3299 9726 3299 3300 9727 3300 3084 9728 3084 3301 9729 3301 3299 9730 3299 3084 9731 3084 3303 9732 3303 3301 9733 3301 3084 9734 3084 3303 9735 3303 3084 9736 3084 3302 9737 3302 3305 9738 3305 3303 9739 3303 3302 9740 3302 3305 9741 3305 3302 9742 3302 3304 9743 3304 3447 9744 3447 3305 9745 3305 3304 9746 3304 3447 9747 3447 3304 9748 3304 3306 9749 3306 3309 9750 3309 3009 9751 3009 3307 9752 3307 3307 9753 3307 3308 9754 3308 3086 9755 3086 3309 9756 3309 3307 9757 3307 3086 9758 3086 3311 9759 3311 3309 9760 3309 3086 9761 3086 3311 9762 3311 3086 9763 3086 3310 9764 3310 3313 9765 3313 3311 9766 3311 3310 9767 3310 3313 9768 3313 3310 9769 3310 3312 9770 3312 3449 9771 3449 3313 9772 3313 3312 9773 3312 3449 9774 3449 3312 9775 3312 3314 9776 3314 3317 9777 3317 3011 9778 3011 3315 9779 3315 3315 9780 3315 3316 9781 3316 3088 9782 3088 3317 9783 3317 3315 9784 3315 3088 9785 3088 3319 9786 3319 3317 9787 3317 3088 9788 3088 3319 9789 3319 3088 9790 3088 3318 9791 3318 3321 9792 3321 3319 9793 3319 3318 9794 3318 3321 9795 3321 3318 9796 3318 3320 9797 3320 3451 9798 3451 3321 9799 3321 3320 9800 3320 3451 9801 3451 3320 9802 3320 3322 9803 3322 3325 9804 3325 3013 9805 3013 3323 9806 3323 3323 9807 3323 3324 9808 3324 3090 9809 3090 3325 9810 3325 3323 9811 3323 3090 9812 3090 3327 9813 3327 3325 9814 3325 3090 9815 3090 3327 9816 3327 3090 9817 3090 3326 9818 3326 3329 9819 3329 3327 9820 3327 3326 9821 3326 3329 9822 3329 3326 9823 3326 3328 9824 3328 3453 9825 3453 3329 9826 3329 3328 9827 3328 3453 9828 3453 3328 9829 3328 3330 9830 3330 3333 9831 3333 3015 9832 3015 3331 9833 3331 3331 9834 3331 3332 9835 3332 3092 9836 3092 3333 9837 3333 3331 9838 3331 3092 9839 3092 3335 9840 3335 3333 9841 3333 3092 9842 3092 3335 9843 3335 3092 9844 3092 3334 9845 3334 3337 9846 3337 3335 9847 3335 3334 9848 3334 3337 9849 3337 3334 9850 3334 3336 9851 3336 3455 9852 3455 3337 9853 3337 3336 9854 3336 3455 9855 3455 3336 9856 3336 3338 9857 3338 3341 9858 3341 3017 9859 3017 3339 9860 3339 3339 9861 3339 3340 9862 3340 3094 9863 3094 3341 9864 3341 3339 9865 3339 3094 9866 3094 3343 9867 3343 3341 9868 3341 3094 9869 3094 3343 9870 3343 3094 9871 3094 3342 9872 3342 3345 9873 3345 3343 9874 3343 3342 9875 3342 3345 9876 3345 3342 9877 3342 3344 9878 3344 3457 9879 3457 3345 9880 3345 3344 9881 3344 3457 9882 3457 3344 9883 3344 3346 9884 3346 3349 9885 3349 3019 9886 3019 3347 9887 3347 3347 9888 3347 3348 9889 3348 3096 9890 3096 3349 9891 3349 3347 9892 3347 3096 9893 3096 3351 9894 3351 3349 9895 3349 3096 9896 3096 3351 9897 3351 3096 9898 3096 3350 9899 3350 3353 9900 3353 3351 9901 3351 3350 9902 3350 3353 9903 3353 3350 9904 3350 3352 9905 3352 3459 9906 3459 3353 9907 3353 3352 9908 3352 3459 9909 3459 3352 9910 3352 3354 9911 3354 3357 9912 3357 3021 9913 3021 3355 9914 3355 3355 9915 3355 3356 9916 3356 3098 9917 3098 3357 9918 3357 3355 9919 3355 3098 9920 3098 3359 9921 3359 3357 9922 3357 3098 9923 3098 3359 9924 3359 3098 9925 3098 3358 9926 3358 3361 9927 3361 3359 9928 3359 3358 9929 3358 3361 9930 3361 3358 9931 3358 3360 9932 3360 3461 9933 3461 3361 9934 3361 3360 9935 3360 3461 9936 3461 3360 9937 3360 3362 9938 3362 3365 9939 3365 3023 9940 3023 3363 9941 3363 3363 9942 3363 3364 9943 3364 3100 9944 3100 3365 9945 3365 3363 9946 3363 3100 9947 3100 3367 9948 3367 3365 9949 3365 3100 9950 3100 3367 9951 3367 3100 9952 3100 3366 9953 3366 3369 9954 3369 3367 9955 3367 3366 9956 3366 3369 9957 3369 3366 9958 3366 3368 9959 3368 3463 9960 3463 3369 9961 3369 3368 9962 3368 3463 9963 3463 3368 9964 3368 3370 9965 3370 3373 9966 3373 3025 9967 3025 3371 9968 3371 3371 9969 3371 3372 9970 3372 3102 9971 3102 3373 9972 3373 3371 9973 3371 3102 9974 3102 3375 9975 3375 3373 9976 3373 3102 9977 3102 3375 9978 3375 3102 9979 3102 3374 9980 3374 3377 9981 3377 3375 9982 3375 3374 9983 3374 3377 9984 3377 3374 9985 3374 3376 9986 3376 3465 9987 3465 3377 9988 3377 3376 9989 3376 3465 9990 3465 3376 9991 3376 3378 9992 3378 3381 9993 3381 3027 9994 3027 3379 9995 3379 3379 9996 3379 3380 9997 3380 3104 9998 3104 3381 9999 3381 3379 10000 3379 3104 10001 3104 3383 10002 3383 3381 10003 3381 3104 10004 3104 3383 10005 3383 3104 10006 3104 3382 10007 3382 3385 10008 3385 3383 10009 3383 3382 10010 3382 3385 10011 3385 3382 10012 3382 3384 10013 3384 3467 10014 3467 3385 10015 3385 3384 10016 3384 3467 10017 3467 3384 10018 3384 3386 10019 3386 3389 10020 3389 3029 10021 3029 3387 10022 3387 3387 10023 3387 3388 10024 3388 3106 10025 3106 3389 10026 3389 3387 10027 3387 3106 10028 3106 3391 10029 3391 3389 10030 3389 3106 10031 3106 3391 10032 3391 3106 10033 3106 3390 10034 3390 3393 10035 3393 3391 10036 3391 3390 10037 3390 3393 10038 3393 3390 10039 3390 3392 10040 3392 3469 10041 3469 3393 10042 3393 3392 10043 3392 3469 10044 3469 3392 10045 3392 3394 10046 3394 3471 10047 3471 3395 10048 3395 1920 10049 1920 3625 10050 3625 3032 10051 3032 3396 10052 3396 3473 10053 3473 3397 10054 3397 3114 10055 3114 3473 10056 3473 3114 10057 3114 3398 10058 3398 3475 10059 3475 3399 10060 3399 3122 10061 3122 3475 10062 3475 3122 10063 3122 3400 10064 3400 3477 10065 3477 3401 10066 3401 3130 10067 3130 3477 10068 3477 3130 10069 3130 3402 10070 3402 3479 10071 3479 3403 10072 3403 3138 10073 3138 3479 10074 3479 3138 10075 3138 3404 10076 3404 3481 10077 3481 3405 10078 3405 3146 10079 3146 3481 10080 3481 3146 10081 3146 3406 10082 3406 3483 10083 3483 3407 10084 3407 3154 10085 3154 3483 10086 3483 3154 10087 3154 3408 10088 3408 3485 10089 3485 3409 10090 3409 3162 10091 3162 3485 10092 3485 3162 10093 3162 3410 10094 3410 3487 10095 3487 3411 10096 3411 3170 10097 3170 3487 10098 3487 3170 10099 3170 3412 10100 3412 3489 10101 3489 3413 10102 3413 3178 10103 3178 3489 10104 3489 3178 10105 3178 3414 10106 3414 3491 10107 3491 3415 10108 3415 3186 10109 3186 3491 10110 3491 3186 10111 3186 3416 10112 3416 3493 10113 3493 3417 10114 3417 3194 10115 3194 3493 10116 3493 3194 10117 3194 3418 10118 3418 3495 10119 3495 3419 10120 3419 3202 10121 3202 3495 10122 3495 3202 10123 3202 3420 10124 3420 3497 10125 3497 3421 10126 3421 3210 10127 3210 3497 10128 3497 3210 10129 3210 3422 10130 3422 3499 10131 3499 3423 10132 3423 3218 10133 3218 3499 10134 3499 3218 10135 3218 3424 10136 3424 3501 10137 3501 3425 10138 3425 3226 10139 3226 3501 10140 3501 3226 10141 3226 3426 10142 3426 3503 10143 3503 3427 10144 3427 3234 10145 3234 3503 10146 3503 3234 10147 3234 3428 10148 3428 3505 10149 3505 3429 10150 3429 3242 10151 3242 3505 10152 3505 3242 10153 3242 3430 10154 3430 3507 10155 3507 3431 10156 3431 3250 10157 3250 3507 10158 3507 3250 10159 3250 3432 10160 3432 3509 10161 3509 3433 10162 3433 3070 10163 3070 3509 10164 3509 3070 10165 3070 3434 10166 3434 3511 10167 3511 3435 10168 3435 3258 10169 3258 3511 10170 3511 3258 10171 3258 3436 10172 3436 3513 10173 3513 3437 10174 3437 3266 10175 3266 3513 10176 3513 3266 10177 3266 3438 10178 3438 3515 10179 3515 3439 10180 3439 3274 10181 3274 3515 10182 3515 3274 10183 3274 3440 10184 3440 3517 10185 3517 3441 10186 3441 3282 10187 3282 3517 10188 3517 3282 10189 3282 3442 10190 3442 3519 10191 3519 3443 10192 3443 3290 10193 3290 3519 10194 3519 3290 10195 3290 3444 10196 3444 3521 10197 3521 3445 10198 3445 3298 10199 3298 3521 10200 3521 3298 10201 3298 3446 10202 3446 3523 10203 3523 3447 10204 3447 3306 10205 3306 3523 10206 3523 3306 10207 3306 3448 10208 3448 3525 10209 3525 3449 10210 3449 3314 10211 3314 3525 10212 3525 3314 10213 3314 3450 10214 3450 3527 10215 3527 3451 10216 3451 3322 10217 3322 3527 10218 3527 3322 10219 3322 3452 10220 3452 3529 10221 3529 3453 10222 3453 3330 10223 3330 3529 10224 3529 3330 10225 3330 3454 10226 3454 3531 10227 3531 3455 10228 3455 3338 10229 3338 3531 10230 3531 3338 10231 3338 3456 10232 3456 3533 10233 3533 3457 10234 3457 3346 10235 3346 3533 10236 3533 3346 10237 3346 3458 10238 3458 3535 10239 3535 3459 10240 3459 3354 10241 3354 3535 10242 3535 3354 10243 3354 3460 10244 3460 3537 10245 3537 3461 10246 3461 3362 10247 3362 3537 10248 3537 3362 10249 3362 3462 10250 3462 3539 10251 3539 3463 10252 3463 3370 10253 3370 3539 10254 3539 3370 10255 3370 3464 10256 3464 3541 10257 3541 3465 10258 3465 3378 10259 3378 3541 10260 3541 3378 10261 3378 3466 10262 3466 3543 10263 3543 3467 10264 3467 3386 10265 3386 3543 10266 3543 3386 10267 3386 3468 10268 3468 3545 10269 3545 3469 10270 3469 3394 10271 3394 3545 10272 3545 3394 10273 3394 3470 10274 3470 3621 10275 3621 3471 10276 3471 1920 10277 1920 3625 10278 3625 3396 10279 3396 3472 10280 3472 3547 10281 3547 3473 10282 3473 3398 10283 3398 3547 10284 3547 3398 10285 3398 3474 10286 3474 3548 10287 3548 3475 10288 3475 3400 10289 3400 3548 10290 3548 3400 10291 3400 3476 10292 3476 3549 10293 3549 3477 10294 3477 3402 10295 3402 3549 10296 3549 3402 10297 3402 3478 10298 3478 3550 10299 3550 3479 10300 3479 3404 10301 3404 3550 10302 3550 3404 10303 3404 3480 10304 3480 3551 10305 3551 3481 10306 3481 3406 10307 3406 3551 10308 3551 3406 10309 3406 3482 10310 3482 3557 10311 3557 3483 10312 3483 3408 10313 3408 3557 10314 3557 3408 10315 3408 3484 10316 3484 3558 10317 3558 3485 10318 3485 3410 10319 3410 3558 10320 3558 3410 10321 3410 3486 10322 3486 3559 10323 3559 3487 10324 3487 3412 10325 3412 3559 10326 3559 3412 10327 3412 3488 10328 3488 3563 10329 3563 3489 10330 3489 3414 10331 3414 3563 10332 3563 3414 10333 3414 3490 10334 3490 3564 10335 3564 3491 10336 3491 3416 10337 3416 3564 10338 3564 3416 10339 3416 3492 10340 3492 3565 10341 3565 3493 10342 3493 3418 10343 3418 3565 10344 3565 3418 10345 3418 3494 10346 3494 3566 10347 3566 3495 10348 3495 3420 10349 3420 3566 10350 3566 3420 10351 3420 3496 10352 3496 3571 10353 3571 3497 10354 3497 3422 10355 3422 3571 10356 3571 3422 10357 3422 3498 10358 3498 3572 10359 3572 3499 10360 3499 3424 10361 3424 3572 10362 3572 3424 10363 3424 3500 10364 3500 3573 10365 3573 3501 10366 3501 3426 10367 3426 3573 10368 3573 3426 10369 3426 3502 10370 3502 3577 10371 3577 3503 10372 3503 3428 10373 3428 3577 10374 3577 3428 10375 3428 3504 10376 3504 3578 10377 3578 3505 10378 3505 3430 10379 3430 3578 10380 3578 3430 10381 3430 3506 10382 3506 3579 10383 3579 3507 10384 3507 3432 10385 3432 3579 10386 3579 3432 10387 3432 3508 10388 3508 3580 10389 3580 3509 10390 3509 3434 10391 3434 3580 10392 3580 3434 10393 3434 3510 10394 3510 3585 10395 3585 3511 10396 3511 3436 10397 3436 3585 10398 3585 3436 10399 3436 3512 10400 3512 3586 10401 3586 3513 10402 3513 3438 10403 3438 3586 10404 3586 3438 10405 3438 3514 10406 3514 3587 10407 3587 3515 10408 3515 3440 10409 3440 3587 10410 3587 3440 10411 3440 3516 10412 3516 3591 10413 3591 3517 10414 3517 3442 10415 3442 3591 10416 3591 3442 10417 3442 3518 10418 3518 3592 10419 3592 3519 10420 3519 3444 10421 3444 3592 10422 3592 3444 10423 3444 3520 10424 3520 3593 10425 3593 3521 10426 3521 3446 10427 3446 3593 10428 3593 3446 10429 3446 3522 10430 3522 3594 10431 3594 3523 10432 3523 3448 10433 3448 3594 10434 3594 3448 10435 3448 3524 10436 3524 3599 10437 3599 3525 10438 3525 3450 10439 3450 3599 10440 3599 3450 10441 3450 3526 10442 3526 3600 10443 3600 3527 10444 3527 3452 10445 3452 3600 10446 3600 3452 10447 3452 3528 10448 3528 3601 10449 3601 3529 10450 3529 3454 10451 3454 3601 10452 3601 3454 10453 3454 3530 10454 3530 3605 10455 3605 3531 10456 3531 3456 10457 3456 3605 10458 3605 3456 10459 3456 3532 10460 3532 3606 10461 3606 3533 10462 3533 3458 10463 3458 3606 10464 3606 3458 10465 3458 3534 10466 3534 3607 10467 3607 3535 10468 3535 3460 10469 3460 3607 10470 3607 3460 10471 3460 3536 10472 3536 3608 10473 3608 3537 10474 3537 3462 10475 3462 3608 10476 3608 3462 10477 3462 3538 10478 3538 3613 10479 3613 3539 10480 3539 3464 10481 3464 3613 10482 3613 3464 10483 3464 3540 10484 3540 3614 10485 3614 3541 10486 3541 3466 10487 3466 3614 10488 3614 3466 10489 3466 3542 10490 3542 3615 10491 3615 3543 10492 3543 3468 10493 3468 3615 10494 3615 3468 10495 3468 3544 10496 3544 3619 10497 3619 3545 10498 3545 3470 10499 3470 3619 10500 3619 3470 10501 3470 3546 10502 3546 3626 10503 3626 3547 10504 3547 3474 10505 3474 3628 10506 3628 3548 10507 3548 3476 10508 3476 3630 10509 3630 3549 10510 3549 3478 10511 3478 3632 10512 3632 3550 10513 3550 3480 10514 3480 3634 10515 3634 3551 10516 3551 3482 10517 3482 3626 10518 3626 3474 10519 3474 3552 10520 3552 3628 10521 3628 3476 10522 3476 3553 10523 3553 3630 10524 3630 3478 10525 3478 3554 10526 3554 3632 10527 3632 3480 10528 3480 3555 10529 3555 3634 10530 3634 3482 10531 3482 3556 10532 3556 3636 10533 3636 3557 10534 3557 3484 10535 3484 3638 10536 3638 3558 10537 3558 3486 10538 3486 3640 10539 3640 3559 10540 3559 3488 10541 3488 3636 10542 3636 3484 10543 3484 3560 10544 3560 3638 10545 3638 3486 10546 3486 3561 10547 3561 3640 10548 3640 3488 10549 3488 3562 10550 3562 3642 10551 3642 3563 10552 3563 3490 10553 3490 3644 10554 3644 3564 10555 3564 3492 10556 3492 3646 10557 3646 3565 10558 3565 3494 10559 3494 3648 10560 3648 3566 10561 3566 3496 10562 3496 3642 10563 3642 3490 10564 3490 3567 10565 3567 3644 10566 3644 3492 10567 3492 3568 10568 3568 3646 10569 3646 3494 10570 3494 3569 10571 3569 3648 10572 3648 3496 10573 3496 3570 10574 3570 3650 10575 3650 3571 10576 3571 3498 10577 3498 3652 10578 3652 3572 10579 3572 3500 10580 3500 3654 10581 3654 3573 10582 3573 3502 10583 3502 3650 10584 3650 3498 10585 3498 3574 10586 3574 3652 10587 3652 3500 10588 3500 3575 10589 3575 3654 10590 3654 3502 10591 3502 3576 10592 3576 3656 10593 3656 3577 10594 3577 3504 10595 3504 3658 10596 3658 3578 10597 3578 3506 10598 3506 3660 10599 3660 3579 10600 3579 3508 10601 3508 3671 10602 3671 3580 10603 3580 3510 10604 3510 3656 10605 3656 3504 10606 3504 3581 10607 3581 3658 10608 3658 3506 10609 3506 3582 10610 3582 3660 10611 3660 3508 10612 3508 3583 10613 3583 3671 10614 3671 3510 10615 3510 3584 10616 3584 3681 10617 3681 3585 10618 3585 3512 10619 3512 3683 10620 3683 3586 10621 3586 3514 10622 3514 3685 10623 3685 3587 10624 3587 3516 10625 3516 3681 10626 3681 3512 10627 3512 3588 10628 3588 3683 10629 3683 3514 10630 3514 3589 10631 3589 3685 10632 3685 3516 10633 3516 3590 10634 3590 3686 10635 3686 3591 10636 3591 3518 10637 3518 3687 10638 3687 3592 10639 3592 3520 10640 3520 3688 10641 3688 3593 10642 3593 3522 10643 3522 3689 10644 3689 3594 10645 3594 3524 10646 3524 3686 10647 3686 3518 10648 3518 3595 10649 3595 3687 10650 3687 3520 10651 3520 3596 10652 3596 3688 10653 3688 3522 10654 3522 3597 10655 3597 3689 10656 3689 3524 10657 3524 3598 10658 3598 3695 10659 3695 3599 10660 3599 3526 10661 3526 3696 10662 3696 3600 10663 3600 3528 10664 3528 3697 10665 3697 3601 10666 3601 3530 10667 3530 3695 10668 3695 3526 10669 3526 3602 10670 3602 3696 10671 3696 3528 10672 3528 3603 10673 3603 3697 10674 3697 3530 10675 3530 3604 10676 3604 3701 10677 3701 3605 10678 3605 3532 10679 3532 3702 10680 3702 3606 10681 3606 3534 10682 3534 3703 10683 3703 3607 10684 3607 3536 10685 3536 3704 10686 3704 3608 10687 3608 3538 10688 3538 3701 10689 3701 3532 10690 3532 3609 10691 3609 3702 10692 3702 3534 10693 3534 3610 10694 3610 3703 10695 3703 3536 10696 3536 3611 10697 3611 3704 10698 3704 3538 10699 3538 3612 10700 3612 3709 10701 3709 3613 10702 3613 3540 10703 3540 3710 10704 3710 3614 10705 3614 3542 10706 3542 3711 10707 3711 3615 10708 3615 3544 10709 3544 3709 10710 3709 3540 10711 3540 3616 10712 3616 3710 10713 3710 3542 10714 3542 3617 10715 3617 3711 10716 3711 3544 10717 3544 3618 10718 3618 3715 10719 3715 3619 10720 3619 3546 10721 3546 3715 10722 3715 3546 10723 3546 3620 10724 3620 3623 10725 3623 3621 10726 3621 1920 10727 1920 3623 10728 3623 1920 10729 1920 3622 10730 3622 3620 10731 3620 3623 10732 3623 3622 10733 3622 3625 10734 3625 3472 10735 3472 3624 10736 3624 3667 10737 3667 3625 10738 3625 3624 10739 3624 3667 10740 3667 3624 10741 3624 3626 10742 3626 3626 10743 3626 3552 10744 3552 3627 10745 3627 3667 10746 3667 3626 10747 3626 3627 10748 3627 3667 10749 3667 3627 10750 3627 3628 10751 3628 3628 10752 3628 3553 10753 3553 3629 10754 3629 3667 10755 3667 3628 10756 3628 3629 10757 3629 3667 10758 3667 3629 10759 3629 3630 10760 3630 3630 10761 3630 3554 10762 3554 3631 10763 3631 3667 10764 3667 3630 10765 3630 3631 10766 3631 3667 10767 3667 3631 10768 3631 3632 10769 3632 3632 10770 3632 3555 10771 3555 3633 10772 3633 3667 10773 3667 3632 10774 3632 3633 10775 3633 3667 10776 3667 3633 10777 3633 3634 10778 3634 3634 10779 3634 3556 10780 3556 3635 10781 3635 3667 10782 3667 3634 10783 3634 3635 10784 3635 3667 10785 3667 3635 10786 3635 3636 10787 3636 3636 10788 3636 3560 10789 3560 3637 10790 3637 3667 10791 3667 3636 10792 3636 3637 10793 3637 3667 10794 3667 3637 10795 3637 3638 10796 3638 3638 10797 3638 3561 10798 3561 3639 10799 3639 3667 10800 3667 3638 10801 3638 3639 10802 3639 3667 10803 3667 3639 10804 3639 3640 10805 3640 3640 10806 3640 3562 10807 3562 3641 10808 3641 3667 10809 3667 3640 10810 3640 3641 10811 3641 3667 10812 3667 3641 10813 3641 3642 10814 3642 3642 10815 3642 3567 10816 3567 3643 10817 3643 3667 10818 3667 3642 10819 3642 3643 10820 3643 3667 10821 3667 3643 10822 3643 3644 10823 3644 3644 10824 3644 3568 10825 3568 3645 10826 3645 3667 10827 3667 3644 10828 3644 3645 10829 3645 3667 10830 3667 3645 10831 3645 3646 10832 3646 3646 10833 3646 3569 10834 3569 3647 10835 3647 3667 10836 3667 3646 10837 3646 3647 10838 3647 3667 10839 3667 3647 10840 3647 3648 10841 3648 3648 10842 3648 3570 10843 3570 3649 10844 3649 3667 10845 3667 3648 10846 3648 3649 10847 3649 3667 10848 3667 3649 10849 3649 3650 10850 3650 3650 10851 3650 3574 10852 3574 3651 10853 3651 3667 10854 3667 3650 10855 3650 3651 10856 3651 3667 10857 3667 3651 10858 3651 3652 10859 3652 3652 10860 3652 3575 10861 3575 3653 10862 3653 3667 10863 3667 3652 10864 3652 3653 10865 3653 3667 10866 3667 3653 10867 3653 3654 10868 3654 3654 10869 3654 3576 10870 3576 3655 10871 3655 3667 10872 3667 3654 10873 3654 3655 10874 3655 3667 10875 3667 3655 10876 3655 3656 10877 3656 3656 10878 3656 3581 10879 3581 3657 10880 3657 3667 10881 3667 3656 10882 3656 3657 10883 3657 3667 10884 3667 3657 10885 3657 3658 10886 3658 3658 10887 3658 3582 10888 3582 3659 10889 3659 3667 10890 3667 3658 10891 3658 3659 10892 3659 3667 10893 3667 3659 10894 3659 3660 10895 3660 3667 10896 3667 3660 10897 3660 3583 10898 3583 3667 10899 3667 3583 10900 3583 3661 10901 3661 3667 10902 3667 3661 10903 3661 3662 10904 3662 3667 10905 3667 3662 10906 3662 3663 10907 3663 3667 10908 3667 3663 10909 3663 3664 10910 3664 3667 10911 3667 3664 10912 3664 3665 10913 3665 3667 10914 3667 3665 10915 3665 3666 10916 3666 3622 10917 3622 3667 10918 3667 3666 10919 3666 3622 10920 3622 3666 10921 3666 3668 10922 3668 3622 10923 3622 3668 10924 3668 3669 10925 3669 3622 10926 3622 3669 10927 3669 3670 10928 3670 3622 10929 3622 3670 10930 3670 3671 10931 3671 3622 10932 3622 3671 10933 3671 3584 10934 3584 3622 10935 3622 3584 10936 3584 3672 10937 3672 3622 10938 3622 3672 10939 3672 3673 10940 3673 3622 10941 3622 3673 10942 3673 3674 10943 3674 3622 10944 3622 3674 10945 3674 3675 10946 3675 3622 10947 3622 3675 10948 3675 3676 10949 3676 3622 10950 3622 3676 10951 3676 3677 10952 3677 3622 10953 3622 3677 10954 3677 3678 10955 3678 3622 10956 3622 3678 10957 3678 3679 10958 3679 3622 10959 3622 3679 10960 3679 3680 10961 3680 3680 10962 3680 3681 10963 3681 3588 10964 3588 3622 10965 3622 3680 10966 3680 3588 10967 3588 3622 10968 3622 3588 10969 3588 3682 10970 3682 3682 10971 3682 3683 10972 3683 3589 10973 3589 3682 10974 3682 3589 10975 3589 3684 10976 3684 3684 10977 3684 3685 10978 3685 3590 10979 3590 3690 10980 3690 3686 10981 3686 3595 10982 3595 3691 10983 3691 3687 10984 3687 3596 10985 3596 3692 10986 3692 3688 10987 3688 3597 10988 3597 3693 10989 3693 3689 10990 3689 3598 10991 3598 3684 10992 3684 3590 10993 3590 3690 10994 3690 3690 10995 3690 3595 10996 3595 3691 10997 3691 3691 10998 3691 3596 10999 3596 3692 11000 3692 3692 11001 3692 3597 11002 3597 3693 11003 3693 3693 11004 3693 3598 11005 3598 3694 11006 3694 3694 11007 3694 3695 11008 3695 3602 11009 3602 3698 11010 3698 3696 11011 3696 3603 11012 3603 3699 11013 3699 3697 11014 3697 3604 11015 3604 3694 11016 3694 3602 11017 3602 3698 11018 3698 3698 11019 3698 3603 11020 3603 3699 11021 3699 3699 11022 3699 3604 11023 3604 3700 11024 3700 3700 11025 3700 3701 11026 3701 3609 11027 3609 3705 11028 3705 3702 11029 3702 3610 11030 3610 3706 11031 3706 3703 11032 3703 3611 11033 3611 3707 11034 3707 3704 11035 3704 3612 11036 3612 3700 11037 3700 3609 11038 3609 3705 11039 3705 3705 11040 3705 3610 11041 3610 3706 11042 3706 3706 11043 3706 3611 11044 3611 3707 11045 3707 3707 11046 3707 3612 11047 3612 3708 11048 3708 3708 11049 3708 3709 11050 3709 3616 11051 3616 3712 11052 3712 3710 11053 3710 3617 11054 3617 3713 11055 3713 3711 11056 3711 3618 11057 3618 3708 11058 3708 3616 11059 3616 3712 11060 3712 3712 11061 3712 3617 11062 3617 3713 11063 3713 3713 11064 3713 3618 11065 3618 3714 11066 3714 3714 11067 3714 3715 11068 3715 3620 11069 3620 3714 11070 3714 3620 11071 3620 3622 11072 3622 3713 11073 3713 3714 11074 3714 3622 11075 3622 3712 11076 3712 3713 11077 3713 3622 11078 3622 3708 11079 3708 3712 11080 3712 3622 11081 3622 3707 11082 3707 3708 11083 3708 3622 11084 3622 3706 11085 3706 3707 11086 3707 3622 11087 3622 3705 11088 3705 3706 11089 3706 3622 11090 3622 3700 11091 3700 3705 11092 3705 3622 11093 3622 3699 11094 3699 3700 11095 3700 3622 11096 3622 3698 11097 3698 3699 11098 3699 3622 11099 3622 3694 11100 3694 3698 11101 3698 3622 11102 3622 3693 11103 3693 3694 11104 3694 3622 11105 3622 3692 11106 3692 3693 11107 3693 3622 11108 3622 3691 11109 3691 3692 11110 3692 3622 11111 3622 3690 11112 3690 3691 11113 3691 3622 11114 3622 3684 11115 3684 3690 11116 3690 3622 11117 3622 5418 11118 5418 5480 11119 5480 5478 11120 5478 5421 11121 5421 3944 11122 3944 3716 11123 3716 5421 11124 5421 3717 11125 3717 3944 11126 3944 5421 11127 5421 3718 11128 3718 3717 11129 3717 5421 11130 5421 3719 11131 3719 3718 11132 3718 5421 11133 5421 3720 11134 3720 3719 11135 3719 5421 11136 5421 3721 11137 3721 3720 11138 3720 5421 11139 5421 3722 11140 3722 3721 11141 3721 3945 11142 3945 3832 11143 3832 3723 11144 3723 3835 11145 3835 3724 11146 3724 3836 11147 3836 3836 11148 3836 3725 11149 3725 3835 11150 3835 3948 11151 3948 3727 11152 3727 3726 11153 3726 3949 11154 3949 3726 11155 3726 3727 11156 3727 3839 11157 3839 3728 11158 3728 3942 11159 3942 3951 11160 3951 3830 11161 3830 3729 11162 3729 3841 11163 3841 3730 11164 3730 3940 11165 3940 3953 11166 3953 3828 11167 3828 3731 11168 3731 3843 11169 3843 3732 11170 3732 3844 11171 3844 3844 11172 3844 3733 11173 3733 3843 11174 3843 3845 11175 3845 3734 11176 3734 3938 11177 3938 3957 11178 3957 3826 11179 3826 3735 11180 3735 3847 11181 3847 3736 11182 3736 3848 11183 3848 3848 11184 3848 3737 11185 3737 3847 11186 3847 3849 11187 3849 3738 11188 3738 3936 11189 3936 3961 11190 3961 3824 11191 3824 3739 11192 3739 3851 11193 3851 3740 11194 3740 3852 11195 3852 3852 11196 3852 3741 11197 3741 3851 11198 3851 3853 11199 3853 3742 11200 3742 3934 11201 3934 3965 11202 3965 3822 11203 3822 3743 11204 3743 3855 11205 3855 3744 11206 3744 3856 11207 3856 3856 11208 3856 3745 11209 3745 3855 11210 3855 3857 11211 3857 3746 11212 3746 3932 11213 3932 3969 11214 3969 3820 11215 3820 3747 11216 3747 3859 11217 3859 3748 11218 3748 3860 11219 3860 3860 11220 3860 3749 11221 3749 3859 11222 3859 3972 11223 3972 3751 11224 3751 3750 11225 3750 3973 11226 3973 3750 11227 3750 3751 11228 3751 3863 11229 3863 3752 11230 3752 3930 11231 3930 3975 11232 3975 3818 11233 3818 3753 11234 3753 3976 11235 3976 3817 11236 3817 3754 11237 3754 3866 11238 3866 3755 11239 3755 3927 11240 3927 3978 11241 3978 3811 11242 3811 3756 11243 3756 3868 11244 3868 3757 11245 3757 3921 11246 3921 3980 11247 3980 3759 11248 3759 3758 11249 3758 3981 11250 3981 3758 11251 3758 3759 11252 3759 3871 11253 3871 3760 11254 3760 3920 11255 3920 3983 11256 3983 3808 11257 3808 3761 11258 3761 3984 11259 3984 3805 11260 3805 3762 11261 3762 3874 11262 3874 3763 11263 3763 3915 11264 3915 3986 11265 3986 3803 11266 3803 3764 11267 3764 3876 11268 3876 3765 11269 3765 3913 11270 3913 3877 11271 3877 3766 11272 3766 3910 11273 3910 3989 11274 3989 3798 11275 3798 3767 11276 3767 3879 11277 3879 3768 11278 3768 3880 11279 3880 3880 11280 3880 3769 11281 3769 3879 11282 3879 3992 11283 3992 3771 11284 3771 3770 11285 3770 3993 11286 3993 3770 11287 3770 3771 11288 3771 3883 11289 3883 3772 11290 3772 3908 11291 3908 3995 11292 3995 3796 11293 3796 3773 11294 3773 3885 11295 3885 3774 11296 3774 3906 11297 3906 3997 11298 3997 3794 11299 3794 3775 11300 3775 3887 11301 3887 3776 11302 3776 3888 11303 3888 3888 11304 3888 3777 11305 3777 3887 11306 3887 3889 11307 3889 3778 11308 3778 3904 11309 3904 4001 11310 4001 3792 11311 3792 3779 11312 3779 3891 11313 3891 3780 11314 3780 3892 11315 3892 3892 11316 3892 3781 11317 3781 3891 11318 3891 3893 11319 3893 3782 11320 3782 3902 11321 3902 4005 11322 4005 3790 11323 3790 3783 11324 3783 3895 11325 3895 3784 11326 3784 3896 11327 3896 3896 11328 3896 3785 11329 3785 3895 11330 3895 4008 11331 4008 3787 11332 3787 3786 11333 3786 4009 11334 4009 3786 11335 3786 3787 11336 3787 3899 11337 3899 3788 11338 3788 3900 11339 3900 3900 11340 3900 3789 11341 3789 3899 11342 3899 4012 11343 4012 3783 11344 3783 3790 11345 3790 3902 11346 3902 3791 11347 3791 3893 11348 3893 4014 11349 4014 3779 11350 3779 3792 11351 3792 3904 11352 3904 3793 11353 3793 3889 11354 3889 4016 11355 4016 3775 11356 3775 3794 11357 3794 3906 11358 3906 3795 11359 3795 3885 11360 3885 4018 11361 4018 3773 11362 3773 3796 11363 3796 3908 11364 3908 3797 11365 3797 3883 11366 3883 4020 11367 4020 3767 11368 3767 3798 11369 3798 3910 11370 3910 3799 11371 3799 3877 11372 3877 4022 11373 4022 3801 11374 3801 3800 11375 3800 4023 11376 4023 3800 11377 3800 3801 11378 3801 3913 11379 3913 3802 11380 3802 3876 11381 3876 4025 11382 4025 3764 11383 3764 3803 11384 3803 3915 11385 3915 3804 11386 3804 3874 11387 3874 4027 11388 4027 3762 11389 3762 3805 11390 3805 3917 11391 3917 3806 11392 3806 3918 11393 3918 3918 11394 3918 3807 11395 3807 3917 11396 3917 4030 11397 4030 3761 11398 3761 3808 11399 3808 3920 11400 3920 3809 11401 3809 3871 11402 3871 3921 11403 3921 3810 11404 3810 3868 11405 3868 4033 11406 4033 3756 11407 3756 3811 11408 3811 3923 11409 3923 3812 11410 3812 3924 11411 3924 3924 11412 3924 3813 11413 3813 3923 11414 3923 4036 11415 4036 3815 11416 3815 3814 11417 3814 4037 11418 4037 3814 11419 3814 3815 11420 3815 3927 11421 3927 3816 11422 3816 3866 11423 3866 4039 11424 4039 3754 11425 3754 3817 11426 3817 4040 11427 4040 3753 11428 3753 3818 11429 3818 3930 11430 3930 3819 11431 3819 3863 11432 3863 4042 11433 4042 3747 11434 3747 3820 11435 3820 3932 11436 3932 3821 11437 3821 3857 11438 3857 4044 11439 4044 3743 11440 3743 3822 11441 3822 3934 11442 3934 3823 11443 3823 3853 11444 3853 4046 11445 4046 3739 11446 3739 3824 11447 3824 3936 11448 3936 3825 11449 3825 3849 11450 3849 4048 11451 4048 3735 11452 3735 3826 11453 3826 3938 11454 3938 3827 11455 3827 3845 11456 3845 4050 11457 4050 3731 11458 3731 3828 11459 3828 3940 11460 3940 3829 11461 3829 3841 11462 3841 4052 11463 4052 3729 11464 3729 3830 11465 3830 3942 11466 3942 3831 11467 3831 3839 11468 3839 4054 11469 4054 3723 11470 3723 3832 11471 3832 5421 11472 5421 3833 11473 3833 3722 11474 3722 3945 11475 3945 3834 11476 3834 3832 11477 3832 4057 11478 4057 3724 11479 3724 3835 11480 3835 4058 11481 4058 3725 11482 3725 3836 11483 3836 3948 11484 3948 3837 11485 3837 3727 11486 3727 3949 11487 3949 3838 11488 3838 3726 11489 3726 4061 11490 4061 3728 11491 3728 3839 11492 3839 3951 11493 3951 3840 11494 3840 3830 11495 3830 4063 11496 4063 3730 11497 3730 3841 11498 3841 3953 11499 3953 3842 11500 3842 3828 11501 3828 4065 11502 4065 3732 11503 3732 3843 11504 3843 4066 11505 4066 3733 11506 3733 3844 11507 3844 4067 11508 4067 3734 11509 3734 3845 11510 3845 3957 11511 3957 3846 11512 3846 3826 11513 3826 4069 11514 4069 3736 11515 3736 3847 11516 3847 4070 11517 4070 3737 11518 3737 3848 11519 3848 4071 11520 4071 3738 11521 3738 3849 11522 3849 3961 11523 3961 3850 11524 3850 3824 11525 3824 4073 11526 4073 3740 11527 3740 3851 11528 3851 4074 11529 4074 3741 11530 3741 3852 11531 3852 4075 11532 4075 3742 11533 3742 3853 11534 3853 3965 11535 3965 3854 11536 3854 3822 11537 3822 4077 11538 4077 3744 11539 3744 3855 11540 3855 4078 11541 4078 3745 11542 3745 3856 11543 3856 4079 11544 4079 3746 11545 3746 3857 11546 3857 3969 11547 3969 3858 11548 3858 3820 11549 3820 4081 11550 4081 3748 11551 3748 3859 11552 3859 4082 11553 4082 3749 11554 3749 3860 11555 3860 3972 11556 3972 3861 11557 3861 3751 11558 3751 3973 11559 3973 3862 11560 3862 3750 11561 3750 4085 11562 4085 3752 11563 3752 3863 11564 3863 3975 11565 3975 3864 11566 3864 3818 11567 3818 3976 11568 3976 3865 11569 3865 3817 11570 3817 4088 11571 4088 3755 11572 3755 3866 11573 3866 3978 11574 3978 3867 11575 3867 3811 11576 3811 4090 11577 4090 3757 11578 3757 3868 11579 3868 3980 11580 3980 3869 11581 3869 3759 11582 3759 3981 11583 3981 3870 11584 3870 3758 11585 3758 4093 11586 4093 3760 11587 3760 3871 11588 3871 3983 11589 3983 3872 11590 3872 3808 11591 3808 3984 11592 3984 3873 11593 3873 3805 11594 3805 4096 11595 4096 3763 11596 3763 3874 11597 3874 3986 11598 3986 3875 11599 3875 3803 11600 3803 4098 11601 4098 3765 11602 3765 3876 11603 3876 4099 11604 4099 3766 11605 3766 3877 11606 3877 3989 11607 3989 3878 11608 3878 3798 11609 3798 4101 11610 4101 3768 11611 3768 3879 11612 3879 4102 11613 4102 3769 11614 3769 3880 11615 3880 3992 11616 3992 3881 11617 3881 3771 11618 3771 3993 11619 3993 3882 11620 3882 3770 11621 3770 4105 11622 4105 3772 11623 3772 3883 11624 3883 3995 11625 3995 3884 11626 3884 3796 11627 3796 4107 11628 4107 3774 11629 3774 3885 11630 3885 3997 11631 3997 3886 11632 3886 3794 11633 3794 4109 11634 4109 3776 11635 3776 3887 11636 3887 4110 11637 4110 3777 11638 3777 3888 11639 3888 4111 11640 4111 3778 11641 3778 3889 11642 3889 4001 11643 4001 3890 11644 3890 3792 11645 3792 4113 11646 4113 3780 11647 3780 3891 11648 3891 4114 11649 4114 3781 11650 3781 3892 11651 3892 4115 11652 4115 3782 11653 3782 3893 11654 3893 4005 11655 4005 3894 11656 3894 3790 11657 3790 4117 11658 4117 3784 11659 3784 3895 11660 3895 4118 11661 4118 3785 11662 3785 3896 11663 3896 4008 11664 4008 3897 11665 3897 3787 11666 3787 4009 11667 4009 3898 11668 3898 3786 11669 3786 4121 11670 4121 3788 11671 3788 3899 11672 3899 4122 11673 4122 3789 11674 3789 3900 11675 3900 4012 11676 4012 3901 11677 3901 3783 11678 3783 4124 11679 4124 3791 11680 3791 3902 11681 3902 4014 11682 4014 3903 11683 3903 3779 11684 3779 4126 11685 4126 3793 11686 3793 3904 11687 3904 4016 11688 4016 3905 11689 3905 3775 11690 3775 4128 11691 4128 3795 11692 3795 3906 11693 3906 4018 11694 4018 3907 11695 3907 3773 11696 3773 4130 11697 4130 3797 11698 3797 3908 11699 3908 4020 11700 4020 3909 11701 3909 3767 11702 3767 4132 11703 4132 3799 11704 3799 3910 11705 3910 4022 11706 4022 3911 11707 3911 3801 11708 3801 4023 11709 4023 3912 11710 3912 3800 11711 3800 4135 11712 4135 3802 11713 3802 3913 11714 3913 4025 11715 4025 3914 11716 3914 3764 11717 3764 4137 11718 4137 3804 11719 3804 3915 11720 3915 4027 11721 4027 3916 11722 3916 3762 11723 3762 4139 11724 4139 3806 11725 3806 3917 11726 3917 4140 11727 4140 3807 11728 3807 3918 11729 3918 4030 11730 4030 3919 11731 3919 3761 11732 3761 4142 11733 4142 3809 11734 3809 3920 11735 3920 4143 11736 4143 3810 11737 3810 3921 11738 3921 4033 11739 4033 3922 11740 3922 3756 11741 3756 4145 11742 4145 3812 11743 3812 3923 11744 3923 4146 11745 4146 3813 11746 3813 3924 11747 3924 4036 11748 4036 3925 11749 3925 3815 11750 3815 4037 11751 4037 3926 11752 3926 3814 11753 3814 4149 11754 4149 3816 11755 3816 3927 11756 3927 4039 11757 4039 3928 11758 3928 3754 11759 3754 4040 11760 4040 3929 11761 3929 3753 11762 3753 4152 11763 4152 3819 11764 3819 3930 11765 3930 4042 11766 4042 3931 11767 3931 3747 11768 3747 4154 11769 4154 3821 11770 3821 3932 11771 3932 4044 11772 4044 3933 11773 3933 3743 11774 3743 4156 11775 4156 3823 11776 3823 3934 11777 3934 4046 11778 4046 3935 11779 3935 3739 11780 3739 4158 11781 4158 3825 11782 3825 3936 11783 3936 4048 11784 4048 3937 11785 3937 3735 11786 3735 4160 11787 4160 3827 11788 3827 3938 11789 3938 4050 11790 4050 3939 11791 3939 3731 11792 3731 4162 11793 4162 3829 11794 3829 3940 11795 3940 4052 11796 4052 3941 11797 3941 3729 11798 3729 4164 11799 4164 3831 11800 3831 3942 11801 3942 4054 11802 4054 3943 11803 3943 3723 11804 3723 4166 11805 4166 3716 11806 3716 3944 11807 3944 4167 11808 4167 3834 11809 3834 3945 11810 3945 4057 11811 4057 3946 11812 3946 3724 11813 3724 4058 11814 4058 3947 11815 3947 3725 11816 3725 4170 11817 4170 3837 11818 3837 3948 11819 3948 4171 11820 4171 3838 11821 3838 3949 11822 3949 4061 11823 4061 3950 11824 3950 3728 11825 3728 4173 11826 4173 3840 11827 3840 3951 11828 3951 4063 11829 4063 3952 11830 3952 3730 11831 3730 4175 11832 4175 3842 11833 3842 3953 11834 3953 4065 11835 4065 3954 11836 3954 3732 11837 3732 4066 11838 4066 3955 11839 3955 3733 11840 3733 4067 11841 4067 3956 11842 3956 3734 11843 3734 4179 11844 4179 3846 11845 3846 3957 11846 3957 4069 11847 4069 3958 11848 3958 3736 11849 3736 4070 11850 4070 3959 11851 3959 3737 11852 3737 4071 11853 4071 3960 11854 3960 3738 11855 3738 4183 11856 4183 3850 11857 3850 3961 11858 3961 4073 11859 4073 3962 11860 3962 3740 11861 3740 4074 11862 4074 3963 11863 3963 3741 11864 3741 4075 11865 4075 3964 11866 3964 3742 11867 3742 4187 11868 4187 3854 11869 3854 3965 11870 3965 4077 11871 4077 3966 11872 3966 3744 11873 3744 4078 11874 4078 3967 11875 3967 3745 11876 3745 4079 11877 4079 3968 11878 3968 3746 11879 3746 4191 11880 4191 3858 11881 3858 3969 11882 3969 4081 11883 4081 3970 11884 3970 3748 11885 3748 4082 11886 4082 3971 11887 3971 3749 11888 3749 4194 11889 4194 3861 11890 3861 3972 11891 3972 4195 11892 4195 3862 11893 3862 3973 11894 3973 4085 11895 4085 3974 11896 3974 3752 11897 3752 4197 11898 4197 3864 11899 3864 3975 11900 3975 4198 11901 4198 3865 11902 3865 3976 11903 3976 4088 11904 4088 3977 11905 3977 3755 11906 3755 4200 11907 4200 3867 11908 3867 3978 11909 3978 4090 11910 4090 3979 11911 3979 3757 11912 3757 4202 11913 4202 3869 11914 3869 3980 11915 3980 4203 11916 4203 3870 11917 3870 3981 11918 3981 4093 11919 4093 3982 11920 3982 3760 11921 3760 4205 11922 4205 3872 11923 3872 3983 11924 3983 4206 11925 4206 3873 11926 3873 3984 11927 3984 4096 11928 4096 3985 11929 3985 3763 11930 3763 4208 11931 4208 3875 11932 3875 3986 11933 3986 4098 11934 4098 3987 11935 3987 3765 11936 3765 4099 11937 4099 3988 11938 3988 3766 11939 3766 4211 11940 4211 3878 11941 3878 3989 11942 3989 4101 11943 4101 3990 11944 3990 3768 11945 3768 4102 11946 4102 3991 11947 3991 3769 11948 3769 4214 11949 4214 3881 11950 3881 3992 11951 3992 4215 11952 4215 3882 11953 3882 3993 11954 3993 4105 11955 4105 3994 11956 3994 3772 11957 3772 4217 11958 4217 3884 11959 3884 3995 11960 3995 4107 11961 4107 3996 11962 3996 3774 11963 3774 4219 11964 4219 3886 11965 3886 3997 11966 3997 4109 11967 4109 3998 11968 3998 3776 11969 3776 4110 11970 4110 3999 11971 3999 3777 11972 3777 4111 11973 4111 4000 11974 4000 3778 11975 3778 4223 11976 4223 3890 11977 3890 4001 11978 4001 4113 11979 4113 4002 11980 4002 3780 11981 3780 4114 11982 4114 4003 11983 4003 3781 11984 3781 4115 11985 4115 4004 11986 4004 3782 11987 3782 4227 11988 4227 3894 11989 3894 4005 11990 4005 4117 11991 4117 4006 11992 4006 3784 11993 3784 4118 11994 4118 4007 11995 4007 3785 11996 3785 4230 11997 4230 3897 11998 3897 4008 11999 4008 4231 12000 4231 3898 12001 3898 4009 12002 4009 4121 12003 4121 4010 12004 4010 3788 12005 3788 4122 12006 4122 4011 12007 4011 3789 12008 3789 4234 12009 4234 3901 12010 3901 4012 12011 4012 4124 12012 4124 4013 12013 4013 3791 12014 3791 4236 12015 4236 3903 12016 3903 4014 12017 4014 4126 12018 4126 4015 12019 4015 3793 12020 3793 4238 12021 4238 3905 12022 3905 4016 12023 4016 4128 12024 4128 4017 12025 4017 3795 12026 3795 4240 12027 4240 3907 12028 3907 4018 12029 4018 4130 12030 4130 4019 12031 4019 3797 12032 3797 4242 12033 4242 3909 12034 3909 4020 12035 4020 4132 12036 4132 4021 12037 4021 3799 12038 3799 4244 12039 4244 3911 12040 3911 4022 12041 4022 4245 12042 4245 3912 12043 3912 4023 12044 4023 4135 12045 4135 4024 12046 4024 3802 12047 3802 4247 12048 4247 3914 12049 3914 4025 12050 4025 4137 12051 4137 4026 12052 4026 3804 12053 3804 4249 12054 4249 3916 12055 3916 4027 12056 4027 4139 12057 4139 4028 12058 4028 3806 12059 3806 4140 12060 4140 4029 12061 4029 3807 12062 3807 4252 12063 4252 3919 12064 3919 4030 12065 4030 4142 12066 4142 4031 12067 4031 3809 12068 3809 4143 12069 4143 4032 12070 4032 3810 12071 3810 4255 12072 4255 3922 12073 3922 4033 12074 4033 4145 12075 4145 4034 12076 4034 3812 12077 3812 4146 12078 4146 4035 12079 4035 3813 12080 3813 4258 12081 4258 3925 12082 3925 4036 12083 4036 4259 12084 4259 3926 12085 3926 4037 12086 4037 4149 12087 4149 4038 12088 4038 3816 12089 3816 4261 12090 4261 3928 12091 3928 4039 12092 4039 4262 12093 4262 3929 12094 3929 4040 12095 4040 4152 12096 4152 4041 12097 4041 3819 12098 3819 4264 12099 4264 3931 12100 3931 4042 12101 4042 4154 12102 4154 4043 12103 4043 3821 12104 3821 4266 12105 4266 3933 12106 3933 4044 12107 4044 4156 12108 4156 4045 12109 4045 3823 12110 3823 4268 12111 4268 3935 12112 3935 4046 12113 4046 4158 12114 4158 4047 12115 4047 3825 12116 3825 4270 12117 4270 3937 12118 3937 4048 12119 4048 4160 12120 4160 4049 12121 4049 3827 12122 3827 4272 12123 4272 3939 12124 3939 4050 12125 4050 4162 12126 4162 4051 12127 4051 3829 12128 3829 4274 12129 4274 3941 12130 3941 4052 12131 4052 4164 12132 4164 4053 12133 4053 3831 12134 3831 4276 12135 4276 3943 12136 3943 4054 12137 4054 5421 12138 5421 4055 12139 4055 3833 12140 3833 4167 12141 4167 4056 12142 4056 3834 12143 3834 4279 12144 4279 3946 12145 3946 4057 12146 4057 4287 12147 4287 3947 12148 3947 4058 12149 4058 4170 12150 4170 4059 12151 4059 3837 12152 3837 4171 12153 4171 4060 12154 4060 3838 12155 3838 4290 12156 4290 3950 12157 3950 4061 12158 4061 4173 12159 4173 4062 12160 4062 3840 12161 3840 4311 12162 4311 3952 12163 3952 4063 12164 4063 4175 12165 4175 4064 12166 4064 3842 12167 3842 4313 12168 4313 3954 12169 3954 4065 12170 4065 4335 12171 4335 3955 12172 3955 4066 12173 4066 4336 12174 4336 3956 12175 3956 4067 12176 4067 4179 12177 4179 4068 12178 4068 3846 12179 3846 4338 12180 4338 3958 12181 3958 4069 12182 4069 4358 12183 4358 3959 12184 3959 4070 12185 4070 4359 12186 4359 3960 12187 3960 4071 12188 4071 4183 12189 4183 4072 12190 4072 3850 12191 3850 4361 12192 4361 3962 12193 3962 4073 12194 4073 4383 12195 4383 3963 12196 3963 4074 12197 4074 4384 12198 4384 3964 12199 3964 4075 12200 4075 4187 12201 4187 4076 12202 4076 3854 12203 3854 4386 12204 4386 3966 12205 3966 4077 12206 4077 4406 12207 4406 3967 12208 3967 4078 12209 4078 4407 12210 4407 3968 12211 3968 4079 12212 4079 4191 12213 4191 4080 12214 4080 3858 12215 3858 4409 12216 4409 3970 12217 3970 4081 12218 4081 4431 12219 4431 3971 12220 3971 4082 12221 4082 4194 12222 4194 4083 12223 4083 3861 12224 3861 4195 12225 4195 4084 12226 4084 3862 12227 3862 4434 12228 4434 3974 12229 3974 4085 12230 4085 4197 12231 4197 4086 12232 4086 3864 12233 3864 4198 12234 4198 4087 12235 4087 3865 12236 3865 4456 12237 4456 3977 12238 3977 4088 12239 4088 4200 12240 4200 4089 12241 4089 3867 12242 3867 4459 12243 4459 3979 12244 3979 4090 12245 4090 4202 12246 4202 4091 12247 4091 3869 12248 3869 4203 12249 4203 4092 12250 4092 3870 12251 3870 4462 12252 4462 3982 12253 3982 4093 12254 4093 4205 12255 4205 4094 12256 4094 3872 12257 3872 4206 12258 4206 4095 12259 4095 3873 12260 3873 4484 12261 4484 3985 12262 3985 4096 12263 4096 4208 12264 4208 4097 12265 4097 3875 12266 3875 4486 12267 4486 3987 12268 3987 4098 12269 4098 4488 12270 4488 3988 12271 3988 4099 12272 4099 4211 12273 4211 4100 12274 4100 3878 12275 3878 4490 12276 4490 3990 12277 3990 4101 12278 4101 4510 12279 4510 3991 12280 3991 4102 12281 4102 4214 12282 4214 4103 12283 4103 3881 12284 3881 4215 12285 4215 4104 12286 4104 3882 12287 3882 4513 12288 4513 3994 12289 3994 4105 12290 4105 4217 12291 4217 4106 12292 4106 3884 12293 3884 4534 12294 4534 3996 12295 3996 4107 12296 4107 4219 12297 4219 4108 12298 4108 3886 12299 3886 4538 12300 4538 3998 12301 3998 4109 12302 4109 4558 12303 4558 3999 12304 3999 4110 12305 4110 4559 12306 4559 4000 12307 4000 4111 12308 4111 4223 12309 4223 4112 12310 4112 3890 12311 3890 4561 12312 4561 4002 12313 4002 4113 12314 4113 4581 12315 4581 4003 12316 4003 4114 12317 4114 4582 12318 4582 4004 12319 4004 4115 12320 4115 4227 12321 4227 4116 12322 4116 3894 12323 3894 4586 12324 4586 4006 12325 4006 4117 12326 4117 4606 12327 4606 4007 12328 4007 4118 12329 4118 4230 12330 4230 4119 12331 4119 3897 12332 3897 4231 12333 4231 4120 12334 4120 3898 12335 3898 4609 12336 4609 4010 12337 4010 4121 12338 4121 4620 12339 4620 4011 12340 4011 4122 12341 4122 4234 12342 4234 4123 12343 4123 3901 12344 3901 4623 12345 4623 4013 12346 4013 4124 12347 4124 4236 12348 4236 4125 12349 4125 3903 12350 3903 4625 12351 4625 4015 12352 4015 4126 12353 4126 4238 12354 4238 4127 12355 4127 3905 12356 3905 4627 12357 4627 4017 12358 4017 4128 12359 4128 4240 12360 4240 4129 12361 4129 3907 12362 3907 4629 12363 4629 4019 12364 4019 4130 12365 4130 4242 12366 4242 4131 12367 4131 3909 12368 3909 4631 12369 4631 4021 12370 4021 4132 12371 4132 4244 12372 4244 4133 12373 4133 3911 12374 3911 4245 12375 4245 4134 12376 4134 3912 12377 3912 4634 12378 4634 4024 12379 4024 4135 12380 4135 4247 12381 4247 4136 12382 4136 3914 12383 3914 4655 12384 4655 4026 12385 4026 4137 12386 4137 4249 12387 4249 4138 12388 4138 3916 12389 3916 4657 12390 4657 4028 12391 4028 4139 12392 4139 4677 12393 4677 4029 12394 4029 4140 12395 4140 4252 12396 4252 4141 12397 4141 3919 12398 3919 4679 12399 4679 4031 12400 4031 4142 12401 4142 4682 12402 4682 4032 12403 4032 4143 12404 4143 4255 12405 4255 4144 12406 4144 3922 12407 3922 4684 12408 4684 4034 12409 4034 4145 12410 4145 4704 12411 4704 4035 12412 4035 4146 12413 4146 4258 12414 4258 4147 12415 4147 3925 12416 3925 4259 12417 4259 4148 12418 4148 3926 12419 3926 4707 12420 4707 4038 12421 4038 4149 12422 4149 4261 12423 4261 4150 12424 4150 3928 12425 3928 4262 12426 4262 4151 12427 4151 3929 12428 3929 4731 12429 4731 4041 12430 4041 4152 12431 4152 4264 12432 4264 4153 12433 4153 3931 12434 3931 4733 12435 4733 4043 12436 4043 4154 12437 4154 4266 12438 4266 4155 12439 4155 3933 12440 3933 4735 12441 4735 4045 12442 4045 4156 12443 4156 4268 12444 4268 4157 12445 4157 3935 12446 3935 4737 12447 4737 4047 12448 4047 4158 12449 4158 4270 12450 4270 4159 12451 4159 3937 12452 3937 4739 12453 4739 4049 12454 4049 4160 12455 4160 4272 12456 4272 4161 12457 4161 3939 12458 3939 4741 12459 4741 4051 12460 4051 4162 12461 4162 4274 12462 4274 4163 12463 4163 3941 12464 3941 4743 12465 4743 4053 12466 4053 4164 12467 4164 4276 12468 4276 4165 12469 4165 3943 12470 3943 4827 12471 4827 3716 12472 3716 4166 12473 4166 4280 12474 4280 4056 12475 4056 4167 12476 4167 4279 12477 4279 4168 12478 4168 3946 12479 3946 4287 12480 4287 4169 12481 4169 3947 12482 3947 4756 12483 4756 4059 12484 4059 4170 12485 4170 4291 12486 4291 4060 12487 4060 4171 12488 4171 4290 12489 4290 4172 12490 4172 3950 12491 3950 4298 12492 4298 4062 12493 4062 4173 12494 4173 4311 12495 4311 4174 12496 4174 3952 12497 3952 4314 12498 4314 4064 12499 4064 4175 12500 4175 4313 12501 4313 4176 12502 4176 3954 12503 3954 4335 12504 4335 4177 12505 4177 3955 12506 3955 4336 12507 4336 4178 12508 4178 3956 12509 3956 4339 12510 4339 4068 12511 4068 4179 12512 4179 4338 12513 4338 4180 12514 4180 3958 12515 3958 4358 12516 4358 4181 12517 4181 3959 12518 3959 4359 12519 4359 4182 12520 4182 3960 12521 3960 4362 12522 4362 4072 12523 4072 4183 12524 4183 4361 12525 4361 4184 12526 4184 3962 12527 3962 4383 12528 4383 4185 12529 4185 3963 12530 3963 4384 12531 4384 4186 12532 4186 3964 12533 3964 4387 12534 4387 4076 12535 4076 4187 12536 4187 4386 12537 4386 4188 12538 4188 3966 12539 3966 4406 12540 4406 4189 12541 4189 3967 12542 3967 4407 12543 4407 4190 12544 4190 3968 12545 3968 4410 12546 4410 4080 12547 4080 4191 12548 4191 4409 12549 4409 4192 12550 4192 3970 12551 3970 4431 12552 4431 4193 12553 4193 3971 12554 3971 4768 12555 4768 4083 12556 4083 4194 12557 4194 4435 12558 4435 4084 12559 4084 4195 12560 4195 4434 12561 4434 4196 12562 4196 3974 12563 3974 4442 12564 4442 4086 12565 4086 4197 12566 4197 4770 12567 4770 4087 12568 4087 4198 12569 4198 4456 12570 4456 4199 12571 4199 3977 12572 3977 4772 12573 4772 4089 12574 4089 4200 12575 4200 4459 12576 4459 4201 12577 4201 3979 12578 3979 4774 12579 4774 4091 12580 4091 4202 12581 4202 4463 12582 4463 4092 12583 4092 4203 12584 4203 4462 12585 4462 4204 12586 4204 3982 12587 3982 4470 12588 4470 4094 12589 4094 4205 12590 4205 4776 12591 4776 4095 12592 4095 4206 12593 4206 4484 12594 4484 4207 12595 4207 3985 12596 3985 4778 12597 4778 4097 12598 4097 4208 12599 4208 4486 12600 4486 4209 12601 4209 3987 12602 3987 4488 12603 4488 4210 12604 4210 3988 12605 3988 4491 12606 4491 4100 12607 4100 4211 12608 4211 4490 12609 4490 4212 12610 4212 3990 12611 3990 4510 12612 4510 4213 12613 4213 3991 12614 3991 4782 12615 4782 4103 12616 4103 4214 12617 4214 4514 12618 4514 4104 12619 4104 4215 12620 4215 4513 12621 4513 4216 12622 4216 3994 12623 3994 4521 12624 4521 4106 12625 4106 4217 12626 4217 4534 12627 4534 4218 12628 4218 3996 12629 3996 4539 12630 4539 4108 12631 4108 4219 12632 4219 4538 12633 4538 4220 12634 4220 3998 12635 3998 4558 12636 4558 4221 12637 4221 3999 12638 3999 4559 12639 4559 4222 12640 4222 4000 12641 4000 4562 12642 4562 4112 12643 4112 4223 12644 4223 4561 12645 4561 4224 12646 4224 4002 12647 4002 4581 12648 4581 4225 12649 4225 4003 12650 4003 4582 12651 4582 4226 12652 4226 4004 12653 4004 4587 12654 4587 4116 12655 4116 4227 12656 4227 4586 12657 4586 4228 12658 4228 4006 12659 4006 4606 12660 4606 4229 12661 4229 4007 12662 4007 4790 12663 4790 4119 12664 4119 4230 12665 4230 4610 12666 4610 4120 12667 4120 4231 12668 4231 4609 12669 4609 4232 12670 4232 4010 12671 4010 4620 12672 4620 4233 12673 4233 4011 12674 4011 4792 12675 4792 4123 12676 4123 4234 12677 4234 4623 12678 4623 4235 12679 4235 4013 12680 4013 4794 12681 4794 4125 12682 4125 4236 12683 4236 4625 12684 4625 4237 12685 4237 4015 12686 4015 4796 12687 4796 4127 12688 4127 4238 12689 4238 4627 12690 4627 4239 12691 4239 4017 12692 4017 4798 12693 4798 4129 12694 4129 4240 12695 4240 4629 12696 4629 4241 12697 4241 4019 12698 4019 4800 12699 4800 4131 12700 4131 4242 12701 4242 4631 12702 4631 4243 12703 4243 4021 12704 4021 4802 12705 4802 4133 12706 4133 4244 12707 4244 4635 12708 4635 4134 12709 4134 4245 12710 4245 4634 12711 4634 4246 12712 4246 4024 12713 4024 4642 12714 4642 4136 12715 4136 4247 12716 4247 4655 12717 4655 4248 12718 4248 4026 12719 4026 4658 12720 4658 4138 12721 4138 4249 12722 4249 4657 12723 4657 4250 12724 4250 4028 12725 4028 4677 12726 4677 4251 12727 4251 4029 12728 4029 4806 12729 4806 4141 12730 4141 4252 12731 4252 4679 12732 4679 4253 12733 4253 4031 12734 4031 4682 12735 4682 4254 12736 4254 4032 12737 4032 4685 12738 4685 4144 12739 4144 4255 12740 4255 4684 12741 4684 4256 12742 4256 4034 12743 4034 4704 12744 4704 4257 12745 4257 4035 12746 4035 4810 12747 4810 4147 12748 4147 4258 12749 4258 4708 12750 4708 4148 12751 4148 4259 12752 4259 4707 12753 4707 4260 12754 4260 4038 12755 4038 4715 12756 4715 4150 12757 4150 4261 12758 4261 4812 12759 4812 4151 12760 4151 4262 12761 4262 4731 12762 4731 4263 12763 4263 4041 12764 4041 4814 12765 4814 4153 12766 4153 4264 12767 4264 4733 12768 4733 4265 12769 4265 4043 12770 4043 4816 12771 4816 4155 12772 4155 4266 12773 4266 4735 12774 4735 4267 12775 4267 4045 12776 4045 4818 12777 4818 4157 12778 4157 4268 12779 4268 4737 12780 4737 4269 12781 4269 4047 12782 4047 4820 12783 4820 4159 12784 4159 4270 12785 4270 4739 12786 4739 4271 12787 4271 4049 12788 4049 4822 12789 4822 4161 12790 4161 4272 12791 4272 4741 12792 4741 4273 12793 4273 4051 12794 4051 4824 12795 4824 4163 12796 4163 4274 12797 4274 4743 12798 4743 4275 12799 4275 4053 12800 4053 4826 12801 4826 4165 12802 4165 4276 12803 4276 5421 12804 5421 4277 12805 4277 4055 12806 4055 4280 12807 4280 4278 12808 4278 4056 12809 4056 4278 12810 4278 4168 12811 4168 4279 12812 4279 4280 12813 4280 4168 12814 4168 4278 12815 4278 4282 12816 4282 4168 12817 4168 4280 12818 4280 4282 12819 4282 4281 12820 4281 4168 12821 4168 4284 12822 4284 4281 12823 4281 4282 12824 4282 4284 12825 4284 4283 12826 4283 4281 12827 4281 4277 12828 4277 4283 12829 4283 4284 12830 4284 4277 12831 4277 4285 12832 4285 4283 12833 4283 4277 12834 4277 4286 12835 4286 4285 12836 4285 4829 12837 4829 4169 12838 4169 4287 12839 4287 4756 12840 4756 4288 12841 4288 4059 12842 4059 4291 12843 4291 4289 12844 4289 4060 12845 4060 4289 12846 4289 4172 12847 4172 4290 12848 4290 4291 12849 4291 4172 12850 4172 4289 12851 4289 4293 12852 4293 4172 12853 4172 4291 12854 4291 4293 12855 4293 4292 12856 4292 4172 12857 4172 4295 12858 4295 4292 12859 4292 4293 12860 4293 4295 12861 4295 4294 12862 4294 4292 12863 4292 4297 12864 4297 4294 12865 4294 4295 12866 4295 4297 12867 4297 4296 12868 4296 4294 12869 4294 4301 12870 4301 4296 12871 4296 4297 12872 4297 4301 12873 4301 4298 12874 4298 4296 12875 4296 4301 12876 4301 4062 12877 4062 4298 12878 4298 4301 12879 4301 4299 12880 4299 4062 12881 4062 4301 12882 4301 4300 12883 4300 4299 12884 4299 4303 12885 4303 4300 12886 4300 4301 12887 4301 4303 12888 4303 4302 12889 4302 4300 12890 4300 4305 12891 4305 4302 12892 4302 4303 12893 4303 4305 12894 4305 4304 12895 4304 4302 12896 4302 4307 12897 4307 4304 12898 4304 4305 12899 4305 4307 12900 4307 4306 12901 4306 4304 12902 4304 4309 12903 4309 4306 12904 4306 4307 12905 4307 4309 12906 4309 4308 12907 4308 4306 12908 4306 4333 12909 4333 4308 12910 4308 4309 12911 4309 4333 12912 4333 4310 12913 4310 4308 12914 4308 4322 12915 4322 4174 12916 4174 4311 12917 4311 4314 12918 4314 4312 12919 4312 4064 12920 4064 4312 12921 4312 4176 12922 4176 4313 12923 4313 4314 12924 4314 4176 12925 4176 4312 12926 4312 4316 12927 4316 4176 12928 4176 4314 12929 4314 4316 12930 4316 4315 12931 4315 4176 12932 4176 4318 12933 4318 4315 12934 4315 4316 12935 4316 4318 12936 4318 4317 12937 4317 4315 12938 4315 4320 12939 4320 4317 12940 4317 4318 12941 4318 4320 12942 4320 4319 12943 4319 4317 12944 4317 4174 12945 4174 4319 12946 4319 4320 12947 4320 4322 12948 4322 4319 12949 4319 4174 12950 4174 4322 12951 4322 4321 12952 4321 4319 12953 4319 4324 12954 4324 4321 12955 4321 4322 12956 4322 4324 12957 4324 4323 12958 4323 4321 12959 4321 4326 12960 4326 4323 12961 4323 4324 12962 4324 4326 12963 4326 4325 12964 4325 4323 12965 4323 4328 12966 4328 4325 12967 4325 4326 12968 4326 4328 12969 4328 4327 12970 4327 4325 12971 4325 4330 12972 4330 4327 12973 4327 4328 12974 4328 4330 12975 4330 4329 12976 4329 4327 12977 4327 4332 12978 4332 4329 12979 4329 4330 12980 4330 4332 12981 4332 4331 12982 4331 4329 12983 4329 4758 12984 4758 4331 12985 4331 4332 12986 4332 4831 12987 4831 4310 12988 4310 4333 12989 4333 4758 12990 4758 4334 12991 4334 4331 12992 4331 4833 12993 4833 4177 12994 4177 4335 12995 4335 4347 12996 4347 4178 12997 4178 4336 12998 4336 4339 12999 4339 4337 13000 4337 4068 13001 4068 4337 13002 4337 4180 13003 4180 4338 13004 4338 4339 13005 4339 4180 13006 4180 4337 13007 4337 4341 13008 4341 4180 13009 4180 4339 13010 4339 4341 13011 4341 4340 13012 4340 4180 13013 4180 4343 13014 4343 4340 13015 4340 4341 13016 4341 4343 13017 4343 4342 13018 4342 4340 13019 4340 4345 13020 4345 4342 13021 4342 4343 13022 4343 4345 13023 4345 4344 13024 4344 4342 13025 4342 4178 13026 4178 4344 13027 4344 4345 13028 4345 4347 13029 4347 4344 13030 4344 4178 13031 4178 4347 13032 4347 4346 13033 4346 4344 13034 4344 4349 13035 4349 4346 13036 4346 4347 13037 4347 4349 13038 4349 4348 13039 4348 4346 13040 4346 4351 13041 4351 4348 13042 4348 4349 13043 4349 4351 13044 4351 4350 13045 4350 4348 13046 4348 4353 13047 4353 4350 13048 4350 4351 13049 4351 4353 13050 4353 4352 13051 4352 4350 13052 4350 4355 13053 4355 4352 13054 4352 4353 13055 4353 4355 13056 4355 4354 13057 4354 4352 13058 4352 4357 13059 4357 4354 13060 4354 4355 13061 4355 4357 13062 4357 4356 13063 4356 4354 13064 4354 4760 13065 4760 4356 13066 4356 4357 13067 4357 4835 13068 4835 4181 13069 4181 4358 13070 4358 4370 13071 4370 4182 13072 4182 4359 13073 4359 4362 13074 4362 4360 13075 4360 4072 13076 4072 4360 13077 4360 4184 13078 4184 4361 13079 4361 4362 13080 4362 4184 13081 4184 4360 13082 4360 4364 13083 4364 4184 13084 4184 4362 13085 4362 4364 13086 4364 4363 13087 4363 4184 13088 4184 4366 13089 4366 4363 13090 4363 4364 13091 4364 4366 13092 4366 4365 13093 4365 4363 13094 4363 4368 13095 4368 4365 13096 4365 4366 13097 4366 4368 13098 4368 4367 13099 4367 4365 13100 4365 4182 13101 4182 4367 13102 4367 4368 13103 4368 4370 13104 4370 4367 13105 4367 4182 13106 4182 4370 13107 4370 4369 13108 4369 4367 13109 4367 4372 13110 4372 4369 13111 4369 4370 13112 4370 4372 13113 4372 4371 13114 4371 4369 13115 4369 4374 13116 4374 4371 13117 4371 4372 13118 4372 4374 13119 4374 4373 13120 4373 4371 13121 4371 4376 13122 4376 4373 13123 4373 4374 13124 4374 4376 13125 4376 4375 13126 4375 4373 13127 4373 4378 13128 4378 4375 13129 4375 4376 13130 4376 4378 13131 4378 4377 13132 4377 4375 13133 4375 4380 13134 4380 4377 13135 4377 4378 13136 4378 4380 13137 4380 4379 13138 4379 4377 13139 4377 4762 13140 4762 4379 13141 4379 4380 13142 4380 4760 13143 4760 4381 13144 4381 4356 13145 4356 4762 13146 4762 4382 13147 4382 4379 13148 4379 4837 13149 4837 4185 13150 4185 4383 13151 4383 4395 13152 4395 4186 13153 4186 4384 13154 4384 4387 13155 4387 4385 13156 4385 4076 13157 4076 4385 13158 4385 4188 13159 4188 4386 13160 4386 4387 13161 4387 4188 13162 4188 4385 13163 4385 4389 13164 4389 4188 13165 4188 4387 13166 4387 4389 13167 4389 4388 13168 4388 4188 13169 4188 4391 13170 4391 4388 13171 4388 4389 13172 4389 4391 13173 4391 4390 13174 4390 4388 13175 4388 4393 13176 4393 4390 13177 4390 4391 13178 4391 4393 13179 4393 4392 13180 4392 4390 13181 4390 4186 13182 4186 4392 13183 4392 4393 13184 4393 4395 13185 4395 4392 13186 4392 4186 13187 4186 4395 13188 4395 4394 13189 4394 4392 13190 4392 4397 13191 4397 4394 13192 4394 4395 13193 4395 4397 13194 4397 4396 13195 4396 4394 13196 4394 4399 13197 4399 4396 13198 4396 4397 13199 4397 4399 13200 4399 4398 13201 4398 4396 13202 4396 4401 13203 4401 4398 13204 4398 4399 13205 4399 4401 13206 4401 4400 13207 4400 4398 13208 4398 4403 13209 4403 4400 13210 4400 4401 13211 4401 4403 13212 4403 4402 13213 4402 4400 13214 4400 4405 13215 4405 4402 13216 4402 4403 13217 4403 4405 13218 4405 4404 13219 4404 4402 13220 4402 4764 13221 4764 4404 13222 4404 4405 13223 4405 4839 13224 4839 4189 13225 4189 4406 13226 4406 4418 13227 4418 4190 13228 4190 4407 13229 4407 4410 13230 4410 4408 13231 4408 4080 13232 4080 4408 13233 4408 4192 13234 4192 4409 13235 4409 4410 13236 4410 4192 13237 4192 4408 13238 4408 4412 13239 4412 4192 13240 4192 4410 13241 4410 4412 13242 4412 4411 13243 4411 4192 13244 4192 4414 13245 4414 4411 13246 4411 4412 13247 4412 4414 13248 4414 4413 13249 4413 4411 13250 4411 4416 13251 4416 4413 13252 4413 4414 13253 4414 4416 13254 4416 4415 13255 4415 4413 13256 4413 4190 13257 4190 4415 13258 4415 4416 13259 4416 4418 13260 4418 4415 13261 4415 4190 13262 4190 4418 13263 4418 4417 13264 4417 4415 13265 4415 4420 13266 4420 4417 13267 4417 4418 13268 4418 4420 13269 4420 4419 13270 4419 4417 13271 4417 4422 13272 4422 4419 13273 4419 4420 13274 4420 4422 13275 4422 4421 13276 4421 4419 13277 4419 4424 13278 4424 4421 13279 4421 4422 13280 4422 4424 13281 4424 4423 13282 4423 4421 13283 4421 4426 13284 4426 4423 13285 4423 4424 13286 4424 4426 13287 4426 4425 13288 4425 4423 13289 4423 4428 13290 4428 4425 13291 4425 4426 13292 4426 4428 13293 4428 4427 13294 4427 4425 13295 4425 4766 13296 4766 4427 13297 4427 4428 13298 4428 4764 13299 4764 4429 13300 4429 4404 13301 4404 4766 13302 4766 4430 13303 4430 4427 13304 4427 4841 13305 4841 4193 13306 4193 4431 13307 4431 4768 13308 4768 4432 13309 4432 4083 13310 4083 4435 13311 4435 4433 13312 4433 4084 13313 4084 4433 13314 4433 4196 13315 4196 4434 13316 4434 4435 13317 4435 4196 13318 4196 4433 13319 4433 4437 13320 4437 4196 13321 4196 4435 13322 4435 4437 13323 4437 4436 13324 4436 4196 13325 4196 4439 13326 4439 4436 13327 4436 4437 13328 4437 4439 13329 4439 4438 13330 4438 4436 13331 4436 4441 13332 4441 4438 13333 4438 4439 13334 4439 4441 13335 4441 4440 13336 4440 4438 13337 4438 4445 13338 4445 4440 13339 4440 4441 13340 4441 4445 13341 4445 4442 13342 4442 4440 13343 4440 4445 13344 4445 4086 13345 4086 4442 13346 4442 4445 13347 4445 4443 13348 4443 4086 13349 4086 4445 13350 4445 4444 13351 4444 4443 13352 4443 4447 13353 4447 4444 13354 4444 4445 13355 4445 4447 13356 4447 4446 13357 4446 4444 13358 4444 4449 13359 4449 4446 13360 4446 4447 13361 4447 4449 13362 4449 4448 13363 4448 4446 13364 4446 4451 13365 4451 4448 13366 4448 4449 13367 4449 4451 13368 4451 4450 13369 4450 4448 13370 4448 4453 13371 4453 4450 13372 4450 4451 13373 4451 4453 13374 4453 4452 13375 4452 4450 13376 4450 4458 13377 4458 4452 13378 4452 4453 13379 4453 4458 13380 4458 4454 13381 4454 4452 13382 4452 4770 13383 4770 4455 13384 4455 4087 13385 4087 4845 13386 4845 4199 13387 4199 4456 13388 4456 4772 13389 4772 4457 13390 4457 4089 13391 4089 4843 13392 4843 4454 13393 4454 4458 13394 4458 4847 13395 4847 4201 13396 4201 4459 13397 4459 4774 13398 4774 4460 13399 4460 4091 13400 4091 4463 13401 4463 4461 13402 4461 4092 13403 4092 4461 13404 4461 4204 13405 4204 4462 13406 4462 4463 13407 4463 4204 13408 4204 4461 13409 4461 4465 13410 4465 4204 13411 4204 4463 13412 4463 4465 13413 4465 4464 13414 4464 4204 13415 4204 4467 13416 4467 4464 13417 4464 4465 13418 4465 4467 13419 4467 4466 13420 4466 4464 13421 4464 4469 13422 4469 4466 13423 4466 4467 13424 4467 4469 13425 4469 4468 13426 4468 4466 13427 4466 4473 13428 4473 4468 13429 4468 4469 13430 4469 4473 13431 4473 4470 13432 4470 4468 13433 4468 4473 13434 4473 4094 13435 4094 4470 13436 4470 4473 13437 4473 4471 13438 4471 4094 13439 4094 4473 13440 4473 4472 13441 4472 4471 13442 4471 4475 13443 4475 4472 13444 4472 4473 13445 4473 4475 13446 4475 4474 13447 4474 4472 13448 4472 4477 13449 4477 4474 13450 4474 4475 13451 4475 4477 13452 4477 4476 13453 4476 4474 13454 4474 4479 13455 4479 4476 13456 4476 4477 13457 4477 4479 13458 4479 4478 13459 4478 4476 13460 4476 4481 13461 4481 4478 13462 4478 4479 13463 4479 4481 13464 4481 4480 13465 4480 4478 13466 4478 4487 13467 4487 4480 13468 4480 4481 13469 4481 4487 13470 4487 4482 13471 4482 4480 13472 4480 4776 13473 4776 4483 13474 4483 4095 13475 4095 4851 13476 4851 4207 13477 4207 4484 13478 4484 4778 13479 4778 4485 13480 4485 4097 13481 4097 4853 13482 4853 4209 13483 4209 4486 13484 4486 4849 13485 4849 4482 13486 4482 4487 13487 4487 4499 13488 4499 4210 13489 4210 4488 13490 4488 4491 13491 4491 4489 13492 4489 4100 13493 4100 4489 13494 4489 4212 13495 4212 4490 13496 4490 4491 13497 4491 4212 13498 4212 4489 13499 4489 4493 13500 4493 4212 13501 4212 4491 13502 4491 4493 13503 4493 4492 13504 4492 4212 13505 4212 4495 13506 4495 4492 13507 4492 4493 13508 4493 4495 13509 4495 4494 13510 4494 4492 13511 4492 4497 13512 4497 4494 13513 4494 4495 13514 4495 4497 13515 4497 4496 13516 4496 4494 13517 4494 4210 13518 4210 4496 13519 4496 4497 13520 4497 4499 13521 4499 4496 13522 4496 4210 13523 4210 4499 13524 4499 4498 13525 4498 4496 13526 4496 4501 13527 4501 4498 13528 4498 4499 13529 4499 4501 13530 4501 4500 13531 4500 4498 13532 4498 4503 13533 4503 4500 13534 4500 4501 13535 4501 4503 13536 4503 4502 13537 4502 4500 13538 4500 4505 13539 4505 4502 13540 4502 4503 13541 4503 4505 13542 4505 4504 13543 4504 4502 13544 4502 4507 13545 4507 4504 13546 4504 4505 13547 4505 4507 13548 4507 4506 13549 4506 4504 13550 4504 4509 13551 4509 4506 13552 4506 4507 13553 4507 4509 13554 4509 4508 13555 4508 4506 13556 4506 4780 13557 4780 4508 13558 4508 4509 13559 4509 4855 13560 4855 4213 13561 4213 4510 13562 4510 4782 13563 4782 4511 13564 4511 4103 13565 4103 4514 13566 4514 4512 13567 4512 4104 13568 4104 4512 13569 4512 4216 13570 4216 4513 13571 4513 4514 13572 4514 4216 13573 4216 4512 13574 4512 4516 13575 4516 4216 13576 4216 4514 13577 4514 4516 13578 4516 4515 13579 4515 4216 13580 4216 4518 13581 4518 4515 13582 4515 4516 13583 4516 4518 13584 4518 4517 13585 4517 4515 13586 4515 4520 13587 4520 4517 13588 4517 4518 13589 4518 4520 13590 4520 4519 13591 4519 4517 13592 4517 4524 13593 4524 4519 13594 4519 4520 13595 4520 4524 13596 4524 4521 13597 4521 4519 13598 4519 4524 13599 4524 4106 13600 4106 4521 13601 4521 4524 13602 4524 4522 13603 4522 4106 13604 4106 4524 13605 4524 4523 13606 4523 4522 13607 4522 4526 13608 4526 4523 13609 4523 4524 13610 4524 4526 13611 4526 4525 13612 4525 4523 13613 4523 4528 13614 4528 4525 13615 4525 4526 13616 4526 4528 13617 4528 4527 13618 4527 4525 13619 4525 4530 13620 4530 4527 13621 4527 4528 13622 4528 4530 13623 4530 4529 13624 4529 4527 13625 4527 4532 13626 4532 4529 13627 4529 4530 13628 4530 4532 13629 4532 4531 13630 4531 4529 13631 4529 4536 13632 4536 4531 13633 4531 4532 13634 4532 4536 13635 4536 4533 13636 4533 4531 13637 4531 4547 13638 4547 4218 13639 4218 4534 13640 4534 4780 13641 4780 4535 13642 4535 4508 13643 4508 4857 13644 4857 4533 13645 4533 4536 13646 4536 4539 13647 4539 4537 13648 4537 4108 13649 4108 4537 13650 4537 4220 13651 4220 4538 13652 4538 4539 13653 4539 4220 13654 4220 4537 13655 4537 4541 13656 4541 4220 13657 4220 4539 13658 4539 4541 13659 4541 4540 13660 4540 4220 13661 4220 4543 13662 4543 4540 13663 4540 4541 13664 4541 4543 13665 4543 4542 13666 4542 4540 13667 4540 4545 13668 4545 4542 13669 4542 4543 13670 4543 4545 13671 4545 4544 13672 4544 4542 13673 4542 4218 13674 4218 4544 13675 4544 4545 13676 4545 4547 13677 4547 4544 13678 4544 4218 13679 4218 4547 13680 4547 4546 13681 4546 4544 13682 4544 4549 13683 4549 4546 13684 4546 4547 13685 4547 4549 13686 4549 4548 13687 4548 4546 13688 4546 4551 13689 4551 4548 13690 4548 4549 13691 4549 4551 13692 4551 4550 13693 4550 4548 13694 4548 4553 13695 4553 4550 13696 4550 4551 13697 4551 4553 13698 4553 4552 13699 4552 4550 13700 4550 4555 13701 4555 4552 13702 4552 4553 13703 4553 4555 13704 4555 4554 13705 4554 4552 13706 4552 4557 13707 4557 4554 13708 4554 4555 13709 4555 4557 13710 4557 4556 13711 4556 4554 13712 4554 4784 13713 4784 4556 13714 4556 4557 13715 4557 4859 13716 4859 4221 13717 4221 4558 13718 4558 4570 13719 4570 4222 13720 4222 4559 13721 4559 4562 13722 4562 4560 13723 4560 4112 13724 4112 4560 13725 4560 4224 13726 4224 4561 13727 4561 4562 13728 4562 4224 13729 4224 4560 13730 4560 4564 13731 4564 4224 13732 4224 4562 13733 4562 4564 13734 4564 4563 13735 4563 4224 13736 4224 4566 13737 4566 4563 13738 4563 4564 13739 4564 4566 13740 4566 4565 13741 4565 4563 13742 4563 4568 13743 4568 4565 13744 4565 4566 13745 4566 4568 13746 4568 4567 13747 4567 4565 13748 4565 4222 13749 4222 4567 13750 4567 4568 13751 4568 4570 13752 4570 4567 13753 4567 4222 13754 4222 4570 13755 4570 4569 13756 4569 4567 13757 4567 4572 13758 4572 4569 13759 4569 4570 13760 4570 4572 13761 4572 4571 13762 4571 4569 13763 4569 4574 13764 4574 4571 13765 4571 4572 13766 4572 4574 13767 4574 4573 13768 4573 4571 13769 4571 4576 13770 4576 4573 13771 4573 4574 13772 4574 4576 13773 4576 4575 13774 4575 4573 13775 4573 4578 13776 4578 4575 13777 4575 4576 13778 4576 4578 13779 4578 4577 13780 4577 4575 13781 4575 4580 13782 4580 4577 13783 4577 4578 13784 4578 4580 13785 4580 4579 13786 4579 4577 13787 4577 4786 13788 4786 4579 13789 4579 4580 13790 4580 4861 13791 4861 4225 13792 4225 4581 13793 4581 4595 13794 4595 4226 13795 4226 4582 13796 4582 4784 13797 4784 4583 13798 4583 4556 13799 4556 4786 13800 4786 4584 13801 4584 4579 13802 4579 4587 13803 4587 4585 13804 4585 4116 13805 4116 4585 13806 4585 4228 13807 4228 4586 13808 4586 4587 13809 4587 4228 13810 4228 4585 13811 4585 4589 13812 4589 4228 13813 4228 4587 13814 4587 4589 13815 4589 4588 13816 4588 4228 13817 4228 4591 13818 4591 4588 13819 4588 4589 13820 4589 4591 13821 4591 4590 13822 4590 4588 13823 4588 4593 13824 4593 4590 13825 4590 4591 13826 4591 4593 13827 4593 4592 13828 4592 4590 13829 4590 4226 13830 4226 4592 13831 4592 4593 13832 4593 4595 13833 4595 4592 13834 4592 4226 13835 4226 4595 13836 4595 4594 13837 4594 4592 13838 4592 4597 13839 4597 4594 13840 4594 4595 13841 4595 4597 13842 4597 4596 13843 4596 4594 13844 4594 4599 13845 4599 4596 13846 4596 4597 13847 4597 4599 13848 4599 4598 13849 4598 4596 13850 4596 4601 13851 4601 4598 13852 4598 4599 13853 4599 4601 13854 4601 4600 13855 4600 4598 13856 4598 4603 13857 4603 4600 13858 4600 4601 13859 4601 4603 13860 4603 4602 13861 4602 4600 13862 4600 4605 13863 4605 4602 13864 4602 4603 13865 4603 4605 13866 4605 4604 13867 4604 4602 13868 4602 4788 13869 4788 4604 13870 4604 4605 13871 4605 4863 13872 4863 4229 13873 4229 4606 13874 4606 4790 13875 4790 4607 13876 4607 4119 13877 4119 4610 13878 4610 4608 13879 4608 4120 13880 4120 4608 13881 4608 4232 13882 4232 4609 13883 4609 4610 13884 4610 4232 13885 4232 4608 13886 4608 4612 13887 4612 4232 13888 4232 4610 13889 4610 4612 13890 4612 4611 13891 4611 4232 13892 4232 4614 13893 4614 4611 13894 4611 4612 13895 4612 4614 13896 4614 4613 13897 4613 4611 13898 4611 4616 13899 4616 4613 13900 4613 4614 13901 4614 4616 13902 4616 4615 13903 4615 4613 13904 4613 4618 13905 4618 4615 13906 4615 4616 13907 4616 4618 13908 4618 4617 13909 4617 4615 13910 4615 4865 13911 4865 4617 13912 4617 4618 13913 4618 4865 13914 4865 4619 13915 4619 4617 13916 4617 4867 13917 4867 4233 13918 4233 4620 13919 4620 4792 13920 4792 4621 13921 4621 4123 13922 4123 4788 13923 4788 4622 13924 4622 4604 13925 4604 4869 13926 4869 4235 13927 4235 4623 13928 4623 4794 13929 4794 4624 13930 4624 4125 13931 4125 4871 13932 4871 4237 13933 4237 4625 13934 4625 4796 13935 4796 4626 13936 4626 4127 13937 4127 4873 13938 4873 4239 13939 4239 4627 13940 4627 4798 13941 4798 4628 13942 4628 4129 13943 4129 4875 13944 4875 4241 13945 4241 4629 13946 4629 4800 13947 4800 4630 13948 4630 4131 13949 4131 4877 13950 4877 4243 13951 4243 4631 13952 4631 4802 13953 4802 4632 13954 4632 4133 13955 4133 4635 13956 4635 4633 13957 4633 4134 13958 4134 4633 13959 4633 4246 13960 4246 4634 13961 4634 4635 13962 4635 4246 13963 4246 4633 13964 4633 4637 13965 4637 4246 13966 4246 4635 13967 4635 4637 13968 4637 4636 13969 4636 4246 13970 4246 4639 13971 4639 4636 13972 4636 4637 13973 4637 4639 13974 4639 4638 13975 4638 4636 13976 4636 4641 13977 4641 4638 13978 4638 4639 13979 4639 4641 13980 4641 4640 13981 4640 4638 13982 4638 4645 13983 4645 4640 13984 4640 4641 13985 4641 4645 13986 4645 4642 13987 4642 4640 13988 4640 4645 13989 4645 4136 13990 4136 4642 13991 4642 4645 13992 4645 4643 13993 4643 4136 13994 4136 4645 13995 4645 4644 13996 4644 4643 13997 4643 4647 13998 4647 4644 13999 4644 4645 14000 4645 4647 14001 4647 4646 14002 4646 4644 14003 4644 4649 14004 4649 4646 14005 4646 4647 14006 4647 4649 14007 4649 4648 14008 4648 4646 14009 4646 4651 14010 4651 4648 14011 4648 4649 14012 4649 4651 14013 4651 4650 14014 4650 4648 14015 4648 4653 14016 4653 4650 14017 4650 4651 14018 4651 4653 14019 4653 4652 14020 4652 4650 14021 4650 4680 14022 4680 4652 14023 4652 4653 14024 4653 4680 14025 4680 4654 14026 4654 4652 14027 4652 4666 14028 4666 4248 14029 4248 4655 14030 4655 4658 14031 4658 4656 14032 4656 4138 14033 4138 4656 14034 4656 4250 14035 4250 4657 14036 4657 4658 14037 4658 4250 14038 4250 4656 14039 4656 4660 14040 4660 4250 14041 4250 4658 14042 4658 4660 14043 4660 4659 14044 4659 4250 14045 4250 4662 14046 4662 4659 14047 4659 4660 14048 4660 4662 14049 4662 4661 14050 4661 4659 14051 4659 4664 14052 4664 4661 14053 4661 4662 14054 4662 4664 14055 4664 4663 14056 4663 4661 14057 4661 4248 14058 4248 4663 14059 4663 4664 14060 4664 4666 14061 4666 4663 14062 4663 4248 14063 4248 4666 14064 4666 4665 14065 4665 4663 14066 4663 4668 14067 4668 4665 14068 4665 4666 14069 4666 4668 14070 4668 4667 14071 4667 4665 14072 4665 4670 14073 4670 4667 14074 4667 4668 14075 4668 4670 14076 4670 4669 14077 4669 4667 14078 4667 4672 14079 4672 4669 14080 4669 4670 14081 4670 4672 14082 4672 4671 14083 4671 4669 14084 4669 4674 14085 4674 4671 14086 4671 4672 14087 4672 4674 14088 4674 4673 14089 4673 4671 14090 4671 4676 14091 4676 4673 14092 4673 4674 14093 4674 4676 14094 4676 4675 14095 4675 4673 14096 4673 4804 14097 4804 4675 14098 4675 4676 14099 4676 4881 14100 4881 4251 14101 4251 4677 14102 4677 4806 14103 4806 4678 14104 4678 4141 14105 4141 4883 14106 4883 4253 14107 4253 4679 14108 4679 4879 14109 4879 4654 14110 4654 4680 14111 4680 4804 14112 4804 4681 14113 4681 4675 14114 4675 4693 14115 4693 4254 14116 4254 4682 14117 4682 4685 14118 4685 4683 14119 4683 4144 14120 4144 4683 14121 4683 4256 14122 4256 4684 14123 4684 4685 14124 4685 4256 14125 4256 4683 14126 4683 4687 14127 4687 4256 14128 4256 4685 14129 4685 4687 14130 4687 4686 14131 4686 4256 14132 4256 4689 14133 4689 4686 14134 4686 4687 14135 4687 4689 14136 4689 4688 14137 4688 4686 14138 4686 4691 14139 4691 4688 14140 4688 4689 14141 4689 4691 14142 4691 4690 14143 4690 4688 14144 4688 4254 14145 4254 4690 14146 4690 4691 14147 4691 4693 14148 4693 4690 14149 4690 4254 14150 4254 4693 14151 4693 4692 14152 4692 4690 14153 4690 4695 14154 4695 4692 14155 4692 4693 14156 4693 4695 14157 4695 4694 14158 4694 4692 14159 4692 4697 14160 4697 4694 14161 4694 4695 14162 4695 4697 14163 4697 4696 14164 4696 4694 14165 4694 4699 14166 4699 4696 14167 4696 4697 14168 4697 4699 14169 4699 4698 14170 4698 4696 14171 4696 4701 14172 4701 4698 14173 4698 4699 14174 4699 4701 14175 4701 4700 14176 4700 4698 14177 4698 4703 14178 4703 4700 14179 4700 4701 14180 4701 4703 14181 4703 4702 14182 4702 4700 14183 4700 4808 14184 4808 4702 14185 4702 4703 14186 4703 4885 14187 4885 4257 14188 4257 4704 14189 4704 4810 14190 4810 4705 14191 4705 4147 14192 4147 4708 14193 4708 4706 14194 4706 4148 14195 4148 4706 14196 4706 4260 14197 4260 4707 14198 4707 4708 14199 4708 4260 14200 4260 4706 14201 4706 4710 14202 4710 4260 14203 4260 4708 14204 4708 4710 14205 4710 4709 14206 4709 4260 14207 4260 4712 14208 4712 4709 14209 4709 4710 14210 4710 4712 14211 4712 4711 14212 4711 4709 14213 4709 4714 14214 4714 4711 14215 4711 4712 14216 4712 4714 14217 4714 4713 14218 4713 4711 14219 4711 4718 14220 4718 4713 14221 4713 4714 14222 4714 4718 14223 4718 4715 14224 4715 4713 14225 4713 4718 14226 4718 4150 14227 4150 4715 14228 4715 4718 14229 4718 4716 14230 4716 4150 14231 4150 4718 14232 4718 4717 14233 4717 4716 14234 4716 4720 14235 4720 4717 14236 4717 4718 14237 4718 4720 14238 4720 4719 14239 4719 4717 14240 4717 4722 14241 4722 4719 14242 4719 4720 14243 4720 4722 14244 4722 4721 14245 4721 4719 14246 4719 4724 14247 4724 4721 14248 4721 4722 14249 4722 4724 14250 4724 4723 14251 4723 4721 14252 4721 4726 14253 4726 4723 14254 4723 4724 14255 4724 4726 14256 4726 4725 14257 4725 4723 14258 4723 4729 14259 4729 4725 14260 4725 4726 14261 4726 4729 14262 4729 4727 14263 4727 4725 14264 4725 4808 14265 4808 4728 14266 4728 4702 14267 4702 4887 14268 4887 4727 14269 4727 4729 14270 4729 4812 14271 4812 4730 14272 4730 4151 14273 4151 4889 14274 4889 4263 14275 4263 4731 14276 4731 4814 14277 4814 4732 14278 4732 4153 14279 4153 4891 14280 4891 4265 14281 4265 4733 14282 4733 4816 14283 4816 4734 14284 4734 4155 14285 4155 4893 14286 4893 4267 14287 4267 4735 14288 4735 4818 14289 4818 4736 14290 4736 4157 14291 4157 4895 14292 4895 4269 14293 4269 4737 14294 4737 4820 14295 4820 4738 14296 4738 4159 14297 4159 4897 14298 4897 4271 14299 4271 4739 14300 4739 4822 14301 4822 4740 14302 4740 4161 14303 4161 4899 14304 4899 4273 14305 4273 4741 14306 4741 4824 14307 4824 4742 14308 4742 4163 14309 4163 4901 14310 4901 4275 14311 4275 4743 14312 4743 4826 14313 4826 4744 14314 4744 4165 14315 4165 4277 14316 4277 4745 14317 4745 4286 14318 4286 5421 14319 5421 4745 14320 4745 4277 14321 4277 5421 14322 5421 4746 14323 4746 4745 14324 4745 5421 14325 5421 4747 14326 4747 4746 14327 4746 5421 14328 5421 4748 14329 4748 4747 14330 4747 5421 14331 5421 4749 14332 4749 4748 14333 4748 5421 14334 5421 4750 14335 4750 4749 14336 4749 5421 14337 5421 4751 14338 4751 4750 14339 4750 5421 14340 5421 4752 14341 4752 4751 14342 4751 5421 14343 5421 4753 14344 4753 4752 14345 4752 5421 14346 5421 4754 14347 4754 4753 14348 4753 4829 14349 4829 4755 14350 4755 4169 14351 4169 4904 14352 4904 4288 14353 4288 4756 14354 4756 4831 14355 4831 4757 14356 4757 4310 14357 4310 4912 14358 4912 4334 14359 4334 4758 14360 4758 4833 14361 4833 4759 14362 4759 4177 14363 4177 4920 14364 4920 4381 14365 4381 4760 14366 4760 4835 14367 4835 4761 14368 4761 4181 14369 4181 4928 14370 4928 4382 14371 4382 4762 14372 4762 4837 14373 4837 4763 14374 4763 4185 14375 4185 4936 14376 4936 4429 14377 4429 4764 14378 4764 4839 14379 4839 4765 14380 4765 4189 14381 4189 4944 14382 4944 4430 14383 4430 4766 14384 4766 4841 14385 4841 4767 14386 4767 4193 14387 4193 4952 14388 4952 4432 14389 4432 4768 14390 4768 4843 14391 4843 4769 14392 4769 4454 14393 4454 4960 14394 4960 4455 14395 4455 4770 14396 4770 4845 14397 4845 4771 14398 4771 4199 14399 4199 4968 14400 4968 4457 14401 4457 4772 14402 4772 4847 14403 4847 4773 14404 4773 4201 14405 4201 4976 14406 4976 4460 14407 4460 4774 14408 4774 4849 14409 4849 4775 14410 4775 4482 14411 4482 4984 14412 4984 4483 14413 4483 4776 14414 4776 4851 14415 4851 4777 14416 4777 4207 14417 4207 4992 14418 4992 4485 14419 4485 4778 14420 4778 4853 14421 4853 4779 14422 4779 4209 14423 4209 5000 14424 5000 4535 14425 4535 4780 14426 4780 4855 14427 4855 4781 14428 4781 4213 14429 4213 5008 14430 5008 4511 14431 4511 4782 14432 4782 4857 14433 4857 4783 14434 4783 4533 14435 4533 5016 14436 5016 4583 14437 4583 4784 14438 4784 4859 14439 4859 4785 14440 4785 4221 14441 4221 5024 14442 5024 4584 14443 4584 4786 14444 4786 4861 14445 4861 4787 14446 4787 4225 14447 4225 5032 14448 5032 4622 14449 4622 4788 14450 4788 4863 14451 4863 4789 14452 4789 4229 14453 4229 5040 14454 5040 4607 14455 4607 4790 14456 4790 4867 14457 4867 4791 14458 4791 4233 14459 4233 5048 14460 5048 4621 14461 4621 4792 14462 4792 4869 14463 4869 4793 14464 4793 4235 14465 4235 5056 14466 5056 4624 14467 4624 4794 14468 4794 4871 14469 4871 4795 14470 4795 4237 14471 4237 5064 14472 5064 4626 14473 4626 4796 14474 4796 4873 14475 4873 4797 14476 4797 4239 14477 4239 5072 14478 5072 4628 14479 4628 4798 14480 4798 4875 14481 4875 4799 14482 4799 4241 14483 4241 5080 14484 5080 4630 14485 4630 4800 14486 4800 4877 14487 4877 4801 14488 4801 4243 14489 4243 5088 14490 5088 4632 14491 4632 4802 14492 4802 4879 14493 4879 4803 14494 4803 4654 14495 4654 5096 14496 5096 4681 14497 4681 4804 14498 4804 4881 14499 4881 4805 14500 4805 4251 14501 4251 5104 14502 5104 4678 14503 4678 4806 14504 4806 4883 14505 4883 4807 14506 4807 4253 14507 4253 5112 14508 5112 4728 14509 4728 4808 14510 4808 4885 14511 4885 4809 14512 4809 4257 14513 4257 5120 14514 5120 4705 14515 4705 4810 14516 4810 4887 14517 4887 4811 14518 4811 4727 14519 4727 5128 14520 5128 4730 14521 4730 4812 14522 4812 4889 14523 4889 4813 14524 4813 4263 14525 4263 5136 14526 5136 4732 14527 4732 4814 14528 4814 4891 14529 4891 4815 14530 4815 4265 14531 4265 5144 14532 5144 4734 14533 4734 4816 14534 4816 4893 14535 4893 4817 14536 4817 4267 14537 4267 5152 14538 5152 4736 14539 4736 4818 14540 4818 4895 14541 4895 4819 14542 4819 4269 14543 4269 5160 14544 5160 4738 14545 4738 4820 14546 4820 4897 14547 4897 4821 14548 4821 4271 14549 4271 5168 14550 5168 4740 14551 4740 4822 14552 4822 4899 14553 4899 4823 14554 4823 4273 14555 4273 5176 14556 5176 4742 14557 4742 4824 14558 4824 4901 14559 4901 4825 14560 4825 4275 14561 4275 5184 14562 5184 4744 14563 4744 4826 14564 4826 5191 14565 5191 3716 14566 3716 4827 14567 4827 5421 14568 5421 4828 14569 4828 4754 14570 4754 4905 14571 4905 4755 14572 4755 4829 14573 4829 4904 14574 4904 4830 14575 4830 4288 14576 4288 4913 14577 4913 4757 14578 4757 4831 14579 4831 4912 14580 4912 4832 14581 4832 4334 14582 4334 4921 14583 4921 4759 14584 4759 4833 14585 4833 4920 14586 4920 4834 14587 4834 4381 14588 4381 4929 14589 4929 4761 14590 4761 4835 14591 4835 4928 14592 4928 4836 14593 4836 4382 14594 4382 4937 14595 4937 4763 14596 4763 4837 14597 4837 4936 14598 4936 4838 14599 4838 4429 14600 4429 4945 14601 4945 4765 14602 4765 4839 14603 4839 4944 14604 4944 4840 14605 4840 4430 14606 4430 4953 14607 4953 4767 14608 4767 4841 14609 4841 4952 14610 4952 4842 14611 4842 4432 14612 4432 4961 14613 4961 4769 14614 4769 4843 14615 4843 4960 14616 4960 4844 14617 4844 4455 14618 4455 4969 14619 4969 4771 14620 4771 4845 14621 4845 4968 14622 4968 4846 14623 4846 4457 14624 4457 4977 14625 4977 4773 14626 4773 4847 14627 4847 4976 14628 4976 4848 14629 4848 4460 14630 4460 4985 14631 4985 4775 14632 4775 4849 14633 4849 4984 14634 4984 4850 14635 4850 4483 14636 4483 4993 14637 4993 4777 14638 4777 4851 14639 4851 4992 14640 4992 4852 14641 4852 4485 14642 4485 5001 14643 5001 4779 14644 4779 4853 14645 4853 5000 14646 5000 4854 14647 4854 4535 14648 4535 5009 14649 5009 4781 14650 4781 4855 14651 4855 5008 14652 5008 4856 14653 4856 4511 14654 4511 5017 14655 5017 4783 14656 4783 4857 14657 4857 5016 14658 5016 4858 14659 4858 4583 14660 4583 5025 14661 5025 4785 14662 4785 4859 14663 4859 5024 14664 5024 4860 14665 4860 4584 14666 4584 5033 14667 5033 4787 14668 4787 4861 14669 4861 5032 14670 5032 4862 14671 4862 4622 14672 4622 5041 14673 5041 4789 14674 4789 4863 14675 4863 5040 14676 5040 4864 14677 4864 4607 14678 4607 5229 14679 5229 4619 14680 4619 4865 14681 4865 5229 14682 5229 4866 14683 4866 4619 14684 4619 5049 14685 5049 4791 14686 4791 4867 14687 4867 5048 14688 5048 4868 14689 4868 4621 14690 4621 5057 14691 5057 4793 14692 4793 4869 14693 4869 5056 14694 5056 4870 14695 4870 4624 14696 4624 5065 14697 5065 4795 14698 4795 4871 14699 4871 5064 14700 5064 4872 14701 4872 4626 14702 4626 5073 14703 5073 4797 14704 4797 4873 14705 4873 5072 14706 5072 4874 14707 4874 4628 14708 4628 5081 14709 5081 4799 14710 4799 4875 14711 4875 5080 14712 5080 4876 14713 4876 4630 14714 4630 5089 14715 5089 4801 14716 4801 4877 14717 4877 5088 14718 5088 4878 14719 4878 4632 14720 4632 5097 14721 5097 4803 14722 4803 4879 14723 4879 5096 14724 5096 4880 14725 4880 4681 14726 4681 5105 14727 5105 4805 14728 4805 4881 14729 4881 5104 14730 5104 4882 14731 4882 4678 14732 4678 5113 14733 5113 4807 14734 4807 4883 14735 4883 5112 14736 5112 4884 14737 4884 4728 14738 4728 5121 14739 5121 4809 14740 4809 4885 14741 4885 5120 14742 5120 4886 14743 4886 4705 14744 4705 5129 14745 5129 4811 14746 4811 4887 14747 4887 5128 14748 5128 4888 14749 4888 4730 14750 4730 5137 14751 5137 4813 14752 4813 4889 14753 4889 5136 14754 5136 4890 14755 4890 4732 14756 4732 5145 14757 5145 4815 14758 4815 4891 14759 4891 5144 14760 5144 4892 14761 4892 4734 14762 4734 5153 14763 5153 4817 14764 4817 4893 14765 4893 5152 14766 5152 4894 14767 4894 4736 14768 4736 5161 14769 5161 4819 14770 4819 4895 14771 4895 5160 14772 5160 4896 14773 4896 4738 14774 4738 5169 14775 5169 4821 14776 4821 4897 14777 4897 5168 14778 5168 4898 14779 4898 4740 14780 4740 5177 14781 5177 4823 14782 4823 4899 14783 4899 5176 14784 5176 4900 14785 4900 4742 14786 4742 5185 14787 5185 4825 14788 4825 4901 14789 4901 5184 14790 5184 4902 14791 4902 4744 14792 4744 4905 14793 4905 4903 14794 4903 4755 14795 4755 4903 14796 4903 4830 14797 4830 4904 14798 4904 4905 14799 4905 4830 14800 4830 4903 14801 4903 4907 14802 4907 4830 14803 4830 4905 14804 4905 4907 14805 4907 4906 14806 4906 4830 14807 4830 4909 14808 4909 4906 14809 4906 4907 14810 4907 4909 14811 4909 4908 14812 4908 4906 14813 4906 5193 14814 5193 4908 14815 4908 4909 14816 4909 5193 14817 5193 4910 14818 4910 4908 14819 4908 4913 14820 4913 4911 14821 4911 4757 14822 4757 4911 14823 4911 4832 14824 4832 4912 14825 4912 4913 14826 4913 4832 14827 4832 4911 14828 4911 4915 14829 4915 4832 14830 4832 4913 14831 4913 4915 14832 4915 4914 14833 4914 4832 14834 4832 4917 14835 4917 4914 14836 4914 4915 14837 4915 4917 14838 4917 4916 14839 4916 4914 14840 4914 5195 14841 5195 4916 14842 4916 4917 14843 4917 5195 14844 5195 4918 14845 4918 4916 14846 4916 4921 14847 4921 4919 14848 4919 4759 14849 4759 4919 14850 4919 4834 14851 4834 4920 14852 4920 4921 14853 4921 4834 14854 4834 4919 14855 4919 4923 14856 4923 4834 14857 4834 4921 14858 4921 4923 14859 4923 4922 14860 4922 4834 14861 4834 4925 14862 4925 4922 14863 4922 4923 14864 4923 4925 14865 4925 4924 14866 4924 4922 14867 4922 5197 14868 5197 4924 14869 4924 4925 14870 4925 5197 14871 5197 4926 14872 4926 4924 14873 4924 4929 14874 4929 4927 14875 4927 4761 14876 4761 4927 14877 4927 4836 14878 4836 4928 14879 4928 4929 14880 4929 4836 14881 4836 4927 14882 4927 4931 14883 4931 4836 14884 4836 4929 14885 4929 4931 14886 4931 4930 14887 4930 4836 14888 4836 4933 14889 4933 4930 14890 4930 4931 14891 4931 4933 14892 4933 4932 14893 4932 4930 14894 4930 5199 14895 5199 4932 14896 4932 4933 14897 4933 5199 14898 5199 4934 14899 4934 4932 14900 4932 4937 14901 4937 4935 14902 4935 4763 14903 4763 4935 14904 4935 4838 14905 4838 4936 14906 4936 4937 14907 4937 4838 14908 4838 4935 14909 4935 4939 14910 4939 4838 14911 4838 4937 14912 4937 4939 14913 4939 4938 14914 4938 4838 14915 4838 4941 14916 4941 4938 14917 4938 4939 14918 4939 4941 14919 4941 4940 14920 4940 4938 14921 4938 5201 14922 5201 4940 14923 4940 4941 14924 4941 5201 14925 5201 4942 14926 4942 4940 14927 4940 4945 14928 4945 4943 14929 4943 4765 14930 4765 4943 14931 4943 4840 14932 4840 4944 14933 4944 4945 14934 4945 4840 14935 4840 4943 14936 4943 4947 14937 4947 4840 14938 4840 4945 14939 4945 4947 14940 4947 4946 14941 4946 4840 14942 4840 4949 14943 4949 4946 14944 4946 4947 14945 4947 4949 14946 4949 4948 14947 4948 4946 14948 4946 5203 14949 5203 4948 14950 4948 4949 14951 4949 5203 14952 5203 4950 14953 4950 4948 14954 4948 4953 14955 4953 4951 14956 4951 4767 14957 4767 4951 14958 4951 4842 14959 4842 4952 14960 4952 4953 14961 4953 4842 14962 4842 4951 14963 4951 4955 14964 4955 4842 14965 4842 4953 14966 4953 4955 14967 4955 4954 14968 4954 4842 14969 4842 4957 14970 4957 4954 14971 4954 4955 14972 4955 4957 14973 4957 4956 14974 4956 4954 14975 4954 5205 14976 5205 4956 14977 4956 4957 14978 4957 5205 14979 5205 4958 14980 4958 4956 14981 4956 4961 14982 4961 4959 14983 4959 4769 14984 4769 4959 14985 4959 4844 14986 4844 4960 14987 4960 4961 14988 4961 4844 14989 4844 4959 14990 4959 4963 14991 4963 4844 14992 4844 4961 14993 4961 4963 14994 4963 4962 14995 4962 4844 14996 4844 4965 14997 4965 4962 14998 4962 4963 14999 4963 4965 15000 4965 4964 15001 4964 4962 15002 4962 5207 15003 5207 4964 15004 4964 4965 15005 4965 5207 15006 5207 4966 15007 4966 4964 15008 4964 4969 15009 4969 4967 15010 4967 4771 15011 4771 4967 15012 4967 4846 15013 4846 4968 15014 4968 4969 15015 4969 4846 15016 4846 4967 15017 4967 4971 15018 4971 4846 15019 4846 4969 15020 4969 4971 15021 4971 4970 15022 4970 4846 15023 4846 4973 15024 4973 4970 15025 4970 4971 15026 4971 4973 15027 4973 4972 15028 4972 4970 15029 4970 5209 15030 5209 4972 15031 4972 4973 15032 4973 5209 15033 5209 4974 15034 4974 4972 15035 4972 4977 15036 4977 4975 15037 4975 4773 15038 4773 4975 15039 4975 4848 15040 4848 4976 15041 4976 4977 15042 4977 4848 15043 4848 4975 15044 4975 4979 15045 4979 4848 15046 4848 4977 15047 4977 4979 15048 4979 4978 15049 4978 4848 15050 4848 4981 15051 4981 4978 15052 4978 4979 15053 4979 4981 15054 4981 4980 15055 4980 4978 15056 4978 5211 15057 5211 4980 15058 4980 4981 15059 4981 5211 15060 5211 4982 15061 4982 4980 15062 4980 4985 15063 4985 4983 15064 4983 4775 15065 4775 4983 15066 4983 4850 15067 4850 4984 15068 4984 4985 15069 4985 4850 15070 4850 4983 15071 4983 4987 15072 4987 4850 15073 4850 4985 15074 4985 4987 15075 4987 4986 15076 4986 4850 15077 4850 4989 15078 4989 4986 15079 4986 4987 15080 4987 4989 15081 4989 4988 15082 4988 4986 15083 4986 5213 15084 5213 4988 15085 4988 4989 15086 4989 5213 15087 5213 4990 15088 4990 4988 15089 4988 4993 15090 4993 4991 15091 4991 4777 15092 4777 4991 15093 4991 4852 15094 4852 4992 15095 4992 4993 15096 4993 4852 15097 4852 4991 15098 4991 4995 15099 4995 4852 15100 4852 4993 15101 4993 4995 15102 4995 4994 15103 4994 4852 15104 4852 4997 15105 4997 4994 15106 4994 4995 15107 4995 4997 15108 4997 4996 15109 4996 4994 15110 4994 5215 15111 5215 4996 15112 4996 4997 15113 4997 5215 15114 5215 4998 15115 4998 4996 15116 4996 5001 15117 5001 4999 15118 4999 4779 15119 4779 4999 15120 4999 4854 15121 4854 5000 15122 5000 5001 15123 5001 4854 15124 4854 4999 15125 4999 5003 15126 5003 4854 15127 4854 5001 15128 5001 5003 15129 5003 5002 15130 5002 4854 15131 4854 5005 15132 5005 5002 15133 5002 5003 15134 5003 5005 15135 5005 5004 15136 5004 5002 15137 5002 5217 15138 5217 5004 15139 5004 5005 15140 5005 5217 15141 5217 5006 15142 5006 5004 15143 5004 5009 15144 5009 5007 15145 5007 4781 15146 4781 5007 15147 5007 4856 15148 4856 5008 15149 5008 5009 15150 5009 4856 15151 4856 5007 15152 5007 5011 15153 5011 4856 15154 4856 5009 15155 5009 5011 15156 5011 5010 15157 5010 4856 15158 4856 5013 15159 5013 5010 15160 5010 5011 15161 5011 5013 15162 5013 5012 15163 5012 5010 15164 5010 5219 15165 5219 5012 15166 5012 5013 15167 5013 5219 15168 5219 5014 15169 5014 5012 15170 5012 5017 15171 5017 5015 15172 5015 4783 15173 4783 5015 15174 5015 4858 15175 4858 5016 15176 5016 5017 15177 5017 4858 15178 4858 5015 15179 5015 5019 15180 5019 4858 15181 4858 5017 15182 5017 5019 15183 5019 5018 15184 5018 4858 15185 4858 5021 15186 5021 5018 15187 5018 5019 15188 5019 5021 15189 5021 5020 15190 5020 5018 15191 5018 5221 15192 5221 5020 15193 5020 5021 15194 5021 5221 15195 5221 5022 15196 5022 5020 15197 5020 5025 15198 5025 5023 15199 5023 4785 15200 4785 5023 15201 5023 4860 15202 4860 5024 15203 5024 5025 15204 5025 4860 15205 4860 5023 15206 5023 5027 15207 5027 4860 15208 4860 5025 15209 5025 5027 15210 5027 5026 15211 5026 4860 15212 4860 5029 15213 5029 5026 15214 5026 5027 15215 5027 5029 15216 5029 5028 15217 5028 5026 15218 5026 5223 15219 5223 5028 15220 5028 5029 15221 5029 5223 15222 5223 5030 15223 5030 5028 15224 5028 5033 15225 5033 5031 15226 5031 4787 15227 4787 5031 15228 5031 4862 15229 4862 5032 15230 5032 5033 15231 5033 4862 15232 4862 5031 15233 5031 5035 15234 5035 4862 15235 4862 5033 15236 5033 5035 15237 5035 5034 15238 5034 4862 15239 4862 5037 15240 5037 5034 15241 5034 5035 15242 5035 5037 15243 5037 5036 15244 5036 5034 15245 5034 5225 15246 5225 5036 15247 5036 5037 15248 5037 5225 15249 5225 5038 15250 5038 5036 15251 5036 5041 15252 5041 5039 15253 5039 4789 15254 4789 5039 15255 5039 4864 15256 4864 5040 15257 5040 5041 15258 5041 4864 15259 4864 5039 15260 5039 5043 15261 5043 4864 15262 4864 5041 15263 5041 5043 15264 5043 5042 15265 5042 4864 15266 4864 5045 15267 5045 5042 15268 5042 5043 15269 5043 5045 15270 5045 5044 15271 5044 5042 15272 5042 5227 15273 5227 5044 15274 5044 5045 15275 5045 5227 15276 5227 5046 15277 5046 5044 15278 5044 5049 15279 5049 5047 15280 5047 4791 15281 4791 5047 15282 5047 4868 15283 4868 5048 15284 5048 5049 15285 5049 4868 15286 4868 5047 15287 5047 5051 15288 5051 4868 15289 4868 5049 15290 5049 5051 15291 5051 5050 15292 5050 4868 15293 4868 5053 15294 5053 5050 15295 5050 5051 15296 5051 5053 15297 5053 5052 15298 5052 5050 15299 5050 5231 15300 5231 5052 15301 5052 5053 15302 5053 5231 15303 5231 5054 15304 5054 5052 15305 5052 5057 15306 5057 5055 15307 5055 4793 15308 4793 5055 15309 5055 4870 15310 4870 5056 15311 5056 5057 15312 5057 4870 15313 4870 5055 15314 5055 5059 15315 5059 4870 15316 4870 5057 15317 5057 5059 15318 5059 5058 15319 5058 4870 15320 4870 5061 15321 5061 5058 15322 5058 5059 15323 5059 5061 15324 5061 5060 15325 5060 5058 15326 5058 5233 15327 5233 5060 15328 5060 5061 15329 5061 5233 15330 5233 5062 15331 5062 5060 15332 5060 5065 15333 5065 5063 15334 5063 4795 15335 4795 5063 15336 5063 4872 15337 4872 5064 15338 5064 5065 15339 5065 4872 15340 4872 5063 15341 5063 5067 15342 5067 4872 15343 4872 5065 15344 5065 5067 15345 5067 5066 15346 5066 4872 15347 4872 5069 15348 5069 5066 15349 5066 5067 15350 5067 5069 15351 5069 5068 15352 5068 5066 15353 5066 5235 15354 5235 5068 15355 5068 5069 15356 5069 5235 15357 5235 5070 15358 5070 5068 15359 5068 5073 15360 5073 5071 15361 5071 4797 15362 4797 5071 15363 5071 4874 15364 4874 5072 15365 5072 5073 15366 5073 4874 15367 4874 5071 15368 5071 5075 15369 5075 4874 15370 4874 5073 15371 5073 5075 15372 5075 5074 15373 5074 4874 15374 4874 5077 15375 5077 5074 15376 5074 5075 15377 5075 5077 15378 5077 5076 15379 5076 5074 15380 5074 5237 15381 5237 5076 15382 5076 5077 15383 5077 5237 15384 5237 5078 15385 5078 5076 15386 5076 5081 15387 5081 5079 15388 5079 4799 15389 4799 5079 15390 5079 4876 15391 4876 5080 15392 5080 5081 15393 5081 4876 15394 4876 5079 15395 5079 5083 15396 5083 4876 15397 4876 5081 15398 5081 5083 15399 5083 5082 15400 5082 4876 15401 4876 5085 15402 5085 5082 15403 5082 5083 15404 5083 5085 15405 5085 5084 15406 5084 5082 15407 5082 5239 15408 5239 5084 15409 5084 5085 15410 5085 5239 15411 5239 5086 15412 5086 5084 15413 5084 5089 15414 5089 5087 15415 5087 4801 15416 4801 5087 15417 5087 4878 15418 4878 5088 15419 5088 5089 15420 5089 4878 15421 4878 5087 15422 5087 5091 15423 5091 4878 15424 4878 5089 15425 5089 5091 15426 5091 5090 15427 5090 4878 15428 4878 5093 15429 5093 5090 15430 5090 5091 15431 5091 5093 15432 5093 5092 15433 5092 5090 15434 5090 5241 15435 5241 5092 15436 5092 5093 15437 5093 5241 15438 5241 5094 15439 5094 5092 15440 5092 5097 15441 5097 5095 15442 5095 4803 15443 4803 5095 15444 5095 4880 15445 4880 5096 15446 5096 5097 15447 5097 4880 15448 4880 5095 15449 5095 5099 15450 5099 4880 15451 4880 5097 15452 5097 5099 15453 5099 5098 15454 5098 4880 15455 4880 5101 15456 5101 5098 15457 5098 5099 15458 5099 5101 15459 5101 5100 15460 5100 5098 15461 5098 5243 15462 5243 5100 15463 5100 5101 15464 5101 5243 15465 5243 5102 15466 5102 5100 15467 5100 5105 15468 5105 5103 15469 5103 4805 15470 4805 5103 15471 5103 4882 15472 4882 5104 15473 5104 5105 15474 5105 4882 15475 4882 5103 15476 5103 5107 15477 5107 4882 15478 4882 5105 15479 5105 5107 15480 5107 5106 15481 5106 4882 15482 4882 5109 15483 5109 5106 15484 5106 5107 15485 5107 5109 15486 5109 5108 15487 5108 5106 15488 5106 5245 15489 5245 5108 15490 5108 5109 15491 5109 5245 15492 5245 5110 15493 5110 5108 15494 5108 5113 15495 5113 5111 15496 5111 4807 15497 4807 5111 15498 5111 4884 15499 4884 5112 15500 5112 5113 15501 5113 4884 15502 4884 5111 15503 5111 5115 15504 5115 4884 15505 4884 5113 15506 5113 5115 15507 5115 5114 15508 5114 4884 15509 4884 5117 15510 5117 5114 15511 5114 5115 15512 5115 5117 15513 5117 5116 15514 5116 5114 15515 5114 5247 15516 5247 5116 15517 5116 5117 15518 5117 5247 15519 5247 5118 15520 5118 5116 15521 5116 5121 15522 5121 5119 15523 5119 4809 15524 4809 5119 15525 5119 4886 15526 4886 5120 15527 5120 5121 15528 5121 4886 15529 4886 5119 15530 5119 5123 15531 5123 4886 15532 4886 5121 15533 5121 5123 15534 5123 5122 15535 5122 4886 15536 4886 5125 15537 5125 5122 15538 5122 5123 15539 5123 5125 15540 5125 5124 15541 5124 5122 15542 5122 5249 15543 5249 5124 15544 5124 5125 15545 5125 5249 15546 5249 5126 15547 5126 5124 15548 5124 5129 15549 5129 5127 15550 5127 4811 15551 4811 5127 15552 5127 4888 15553 4888 5128 15554 5128 5129 15555 5129 4888 15556 4888 5127 15557 5127 5131 15558 5131 4888 15559 4888 5129 15560 5129 5131 15561 5131 5130 15562 5130 4888 15563 4888 5133 15564 5133 5130 15565 5130 5131 15566 5131 5133 15567 5133 5132 15568 5132 5130 15569 5130 5251 15570 5251 5132 15571 5132 5133 15572 5133 5251 15573 5251 5134 15574 5134 5132 15575 5132 5137 15576 5137 5135 15577 5135 4813 15578 4813 5135 15579 5135 4890 15580 4890 5136 15581 5136 5137 15582 5137 4890 15583 4890 5135 15584 5135 5139 15585 5139 4890 15586 4890 5137 15587 5137 5139 15588 5139 5138 15589 5138 4890 15590 4890 5141 15591 5141 5138 15592 5138 5139 15593 5139 5141 15594 5141 5140 15595 5140 5138 15596 5138 5253 15597 5253 5140 15598 5140 5141 15599 5141 5253 15600 5253 5142 15601 5142 5140 15602 5140 5145 15603 5145 5143 15604 5143 4815 15605 4815 5143 15606 5143 4892 15607 4892 5144 15608 5144 5145 15609 5145 4892 15610 4892 5143 15611 5143 5147 15612 5147 4892 15613 4892 5145 15614 5145 5147 15615 5147 5146 15616 5146 4892 15617 4892 5149 15618 5149 5146 15619 5146 5147 15620 5147 5149 15621 5149 5148 15622 5148 5146 15623 5146 5255 15624 5255 5148 15625 5148 5149 15626 5149 5255 15627 5255 5150 15628 5150 5148 15629 5148 5153 15630 5153 5151 15631 5151 4817 15632 4817 5151 15633 5151 4894 15634 4894 5152 15635 5152 5153 15636 5153 4894 15637 4894 5151 15638 5151 5155 15639 5155 4894 15640 4894 5153 15641 5153 5155 15642 5155 5154 15643 5154 4894 15644 4894 5157 15645 5157 5154 15646 5154 5155 15647 5155 5157 15648 5157 5156 15649 5156 5154 15650 5154 5257 15651 5257 5156 15652 5156 5157 15653 5157 5257 15654 5257 5158 15655 5158 5156 15656 5156 5161 15657 5161 5159 15658 5159 4819 15659 4819 5159 15660 5159 4896 15661 4896 5160 15662 5160 5161 15663 5161 4896 15664 4896 5159 15665 5159 5163 15666 5163 4896 15667 4896 5161 15668 5161 5163 15669 5163 5162 15670 5162 4896 15671 4896 5165 15672 5165 5162 15673 5162 5163 15674 5163 5165 15675 5165 5164 15676 5164 5162 15677 5162 5259 15678 5259 5164 15679 5164 5165 15680 5165 5259 15681 5259 5166 15682 5166 5164 15683 5164 5169 15684 5169 5167 15685 5167 4821 15686 4821 5167 15687 5167 4898 15688 4898 5168 15689 5168 5169 15690 5169 4898 15691 4898 5167 15692 5167 5171 15693 5171 4898 15694 4898 5169 15695 5169 5171 15696 5171 5170 15697 5170 4898 15698 4898 5173 15699 5173 5170 15700 5170 5171 15701 5171 5173 15702 5173 5172 15703 5172 5170 15704 5170 5261 15705 5261 5172 15706 5172 5173 15707 5173 5261 15708 5261 5174 15709 5174 5172 15710 5172 5177 15711 5177 5175 15712 5175 4823 15713 4823 5175 15714 5175 4900 15715 4900 5176 15716 5176 5177 15717 5177 4900 15718 4900 5175 15719 5175 5179 15720 5179 4900 15721 4900 5177 15722 5177 5179 15723 5179 5178 15724 5178 4900 15725 4900 5181 15726 5181 5178 15727 5178 5179 15728 5179 5181 15729 5181 5180 15730 5180 5178 15731 5178 5263 15732 5263 5180 15733 5180 5181 15734 5181 5263 15735 5263 5182 15736 5182 5180 15737 5180 5185 15738 5185 5183 15739 5183 4825 15740 4825 5183 15741 5183 4902 15742 4902 5184 15743 5184 5185 15744 5185 4902 15745 4902 5183 15746 5183 5187 15747 5187 4902 15748 4902 5185 15749 5185 5187 15750 5187 5186 15751 5186 4902 15752 4902 5189 15753 5189 5186 15754 5186 5187 15755 5187 5189 15756 5189 5188 15757 5188 5186 15758 5186 5265 15759 5265 5188 15760 5188 5189 15761 5189 5265 15762 5265 5190 15763 5190 5188 15764 5188 5267 15765 5267 3716 15766 3716 5191 15767 5191 5421 15768 5421 5192 15769 5192 4828 15770 4828 5269 15771 5269 4910 15772 4910 5193 15773 5193 5269 15774 5269 5194 15775 5194 4910 15776 4910 5271 15777 5271 4918 15778 4918 5195 15779 5195 5271 15780 5271 5196 15781 5196 4918 15782 4918 5273 15783 5273 4926 15784 4926 5197 15785 5197 5273 15786 5273 5198 15787 5198 4926 15788 4926 5275 15789 5275 4934 15790 4934 5199 15791 5199 5275 15792 5275 5200 15793 5200 4934 15794 4934 5277 15795 5277 4942 15796 4942 5201 15797 5201 5277 15798 5277 5202 15799 5202 4942 15800 4942 5279 15801 5279 4950 15802 4950 5203 15803 5203 5279 15804 5279 5204 15805 5204 4950 15806 4950 5281 15807 5281 4958 15808 4958 5205 15809 5205 5281 15810 5281 5206 15811 5206 4958 15812 4958 5283 15813 5283 4966 15814 4966 5207 15815 5207 5283 15816 5283 5208 15817 5208 4966 15818 4966 5285 15819 5285 4974 15820 4974 5209 15821 5209 5285 15822 5285 5210 15823 5210 4974 15824 4974 5287 15825 5287 4982 15826 4982 5211 15827 5211 5287 15828 5287 5212 15829 5212 4982 15830 4982 5289 15831 5289 4990 15832 4990 5213 15833 5213 5289 15834 5289 5214 15835 5214 4990 15836 4990 5291 15837 5291 4998 15838 4998 5215 15839 5215 5291 15840 5291 5216 15841 5216 4998 15842 4998 5293 15843 5293 5006 15844 5006 5217 15845 5217 5293 15846 5293 5218 15847 5218 5006 15848 5006 5295 15849 5295 5014 15850 5014 5219 15851 5219 5295 15852 5295 5220 15853 5220 5014 15854 5014 5297 15855 5297 5022 15856 5022 5221 15857 5221 5297 15858 5297 5222 15859 5222 5022 15860 5022 5299 15861 5299 5030 15862 5030 5223 15863 5223 5299 15864 5299 5224 15865 5224 5030 15866 5030 5301 15867 5301 5038 15868 5038 5225 15869 5225 5301 15870 5301 5226 15871 5226 5038 15872 5038 5303 15873 5303 5046 15874 5046 5227 15875 5227 5303 15876 5303 5228 15877 5228 5046 15878 5046 5305 15879 5305 4866 15880 4866 5229 15881 5229 5305 15882 5305 5230 15883 5230 4866 15884 4866 5307 15885 5307 5054 15886 5054 5231 15887 5231 5307 15888 5307 5232 15889 5232 5054 15890 5054 5309 15891 5309 5062 15892 5062 5233 15893 5233 5309 15894 5309 5234 15895 5234 5062 15896 5062 5311 15897 5311 5070 15898 5070 5235 15899 5235 5311 15900 5311 5236 15901 5236 5070 15902 5070 5313 15903 5313 5078 15904 5078 5237 15905 5237 5313 15906 5313 5238 15907 5238 5078 15908 5078 5315 15909 5315 5086 15910 5086 5239 15911 5239 5315 15912 5315 5240 15913 5240 5086 15914 5086 5317 15915 5317 5094 15916 5094 5241 15917 5241 5317 15918 5317 5242 15919 5242 5094 15920 5094 5319 15921 5319 5102 15922 5102 5243 15923 5243 5319 15924 5319 5244 15925 5244 5102 15926 5102 5321 15927 5321 5110 15928 5110 5245 15929 5245 5321 15930 5321 5246 15931 5246 5110 15932 5110 5323 15933 5323 5118 15934 5118 5247 15935 5247 5323 15936 5323 5248 15937 5248 5118 15938 5118 5325 15939 5325 5126 15940 5126 5249 15941 5249 5325 15942 5325 5250 15943 5250 5126 15944 5126 5327 15945 5327 5134 15946 5134 5251 15947 5251 5327 15948 5327 5252 15949 5252 5134 15950 5134 5329 15951 5329 5142 15952 5142 5253 15953 5253 5329 15954 5329 5254 15955 5254 5142 15956 5142 5331 15957 5331 5150 15958 5150 5255 15959 5255 5331 15960 5331 5256 15961 5256 5150 15962 5150 5333 15963 5333 5158 15964 5158 5257 15965 5257 5333 15966 5333 5258 15967 5258 5158 15968 5158 5335 15969 5335 5166 15970 5166 5259 15971 5259 5335 15972 5335 5260 15973 5260 5166 15974 5166 5337 15975 5337 5174 15976 5174 5261 15977 5261 5337 15978 5337 5262 15979 5262 5174 15980 5174 5339 15981 5339 5182 15982 5182 5263 15983 5263 5339 15984 5339 5264 15985 5264 5182 15986 5182 5341 15987 5341 5190 15988 5190 5265 15989 5265 5341 15990 5341 5266 15991 5266 5190 15992 5190 5417 15993 5417 3716 15994 3716 5267 15995 5267 5421 15996 5421 5268 15997 5268 5192 15998 5192 5343 15999 5343 5194 16000 5194 5269 16001 5269 5343 16002 5343 5270 16003 5270 5194 16004 5194 5344 16005 5344 5196 16006 5196 5271 16007 5271 5344 16008 5344 5272 16009 5272 5196 16010 5196 5345 16011 5345 5198 16012 5198 5273 16013 5273 5345 16014 5345 5274 16015 5274 5198 16016 5198 5346 16017 5346 5200 16018 5200 5275 16019 5275 5346 16020 5346 5276 16021 5276 5200 16022 5200 5347 16023 5347 5202 16024 5202 5277 16025 5277 5347 16026 5347 5278 16027 5278 5202 16028 5202 5353 16029 5353 5204 16030 5204 5279 16031 5279 5353 16032 5353 5280 16033 5280 5204 16034 5204 5354 16035 5354 5206 16036 5206 5281 16037 5281 5354 16038 5354 5282 16039 5282 5206 16040 5206 5355 16041 5355 5208 16042 5208 5283 16043 5283 5355 16044 5355 5284 16045 5284 5208 16046 5208 5359 16047 5359 5210 16048 5210 5285 16049 5285 5359 16050 5359 5286 16051 5286 5210 16052 5210 5360 16053 5360 5212 16054 5212 5287 16055 5287 5360 16056 5360 5288 16057 5288 5212 16058 5212 5361 16059 5361 5214 16060 5214 5289 16061 5289 5361 16062 5361 5290 16063 5290 5214 16064 5214 5362 16065 5362 5216 16066 5216 5291 16067 5291 5362 16068 5362 5292 16069 5292 5216 16070 5216 5367 16071 5367 5218 16072 5218 5293 16073 5293 5367 16074 5367 5294 16075 5294 5218 16076 5218 5368 16077 5368 5220 16078 5220 5295 16079 5295 5368 16080 5368 5296 16081 5296 5220 16082 5220 5369 16083 5369 5222 16084 5222 5297 16085 5297 5369 16086 5369 5298 16087 5298 5222 16088 5222 5373 16089 5373 5224 16090 5224 5299 16091 5299 5373 16092 5373 5300 16093 5300 5224 16094 5224 5374 16095 5374 5226 16096 5226 5301 16097 5301 5374 16098 5374 5302 16099 5302 5226 16100 5226 5375 16101 5375 5228 16102 5228 5303 16103 5303 5375 16104 5375 5304 16105 5304 5228 16106 5228 5376 16107 5376 5230 16108 5230 5305 16109 5305 5376 16110 5376 5306 16111 5306 5230 16112 5230 5381 16113 5381 5232 16114 5232 5307 16115 5307 5381 16116 5381 5308 16117 5308 5232 16118 5232 5382 16119 5382 5234 16120 5234 5309 16121 5309 5382 16122 5382 5310 16123 5310 5234 16124 5234 5383 16125 5383 5236 16126 5236 5311 16127 5311 5383 16128 5383 5312 16129 5312 5236 16130 5236 5387 16131 5387 5238 16132 5238 5313 16133 5313 5387 16134 5387 5314 16135 5314 5238 16136 5238 5388 16137 5388 5240 16138 5240 5315 16139 5315 5388 16140 5388 5316 16141 5316 5240 16142 5240 5389 16143 5389 5242 16144 5242 5317 16145 5317 5389 16146 5389 5318 16147 5318 5242 16148 5242 5390 16149 5390 5244 16150 5244 5319 16151 5319 5390 16152 5390 5320 16153 5320 5244 16154 5244 5395 16155 5395 5246 16156 5246 5321 16157 5321 5395 16158 5395 5322 16159 5322 5246 16160 5246 5396 16161 5396 5248 16162 5248 5323 16163 5323 5396 16164 5396 5324 16165 5324 5248 16166 5248 5397 16167 5397 5250 16168 5250 5325 16169 5325 5397 16170 5397 5326 16171 5326 5250 16172 5250 5401 16173 5401 5252 16174 5252 5327 16175 5327 5401 16176 5401 5328 16177 5328 5252 16178 5252 5402 16179 5402 5254 16180 5254 5329 16181 5329 5402 16182 5402 5330 16183 5330 5254 16184 5254 5403 16185 5403 5256 16186 5256 5331 16187 5331 5403 16188 5403 5332 16189 5332 5256 16190 5256 5404 16191 5404 5258 16192 5258 5333 16193 5333 5404 16194 5404 5334 16195 5334 5258 16196 5258 5409 16197 5409 5260 16198 5260 5335 16199 5335 5409 16200 5409 5336 16201 5336 5260 16202 5260 5410 16203 5410 5262 16204 5262 5337 16205 5337 5410 16206 5410 5338 16207 5338 5262 16208 5262 5411 16209 5411 5264 16210 5264 5339 16211 5339 5411 16212 5411 5340 16213 5340 5264 16214 5264 5415 16215 5415 5266 16216 5266 5341 16217 5341 5415 16218 5415 5342 16219 5342 5266 16220 5266 5422 16221 5422 5270 16222 5270 5343 16223 5343 5424 16224 5424 5272 16225 5272 5344 16226 5344 5426 16227 5426 5274 16228 5274 5345 16229 5345 5428 16230 5428 5276 16231 5276 5346 16232 5346 5430 16233 5430 5278 16234 5278 5347 16235 5347 5422 16236 5422 5348 16237 5348 5270 16238 5270 5424 16239 5424 5349 16240 5349 5272 16241 5272 5426 16242 5426 5350 16243 5350 5274 16244 5274 5428 16245 5428 5351 16246 5351 5276 16247 5276 5430 16248 5430 5352 16249 5352 5278 16250 5278 5432 16251 5432 5280 16252 5280 5353 16253 5353 5434 16254 5434 5282 16255 5282 5354 16256 5354 5436 16257 5436 5284 16258 5284 5355 16259 5355 5432 16260 5432 5356 16261 5356 5280 16262 5280 5434 16263 5434 5357 16264 5357 5282 16265 5282 5436 16266 5436 5358 16267 5358 5284 16268 5284 5438 16269 5438 5286 16270 5286 5359 16271 5359 5440 16272 5440 5288 16273 5288 5360 16274 5360 5442 16275 5442 5290 16276 5290 5361 16277 5361 5444 16278 5444 5292 16279 5292 5362 16280 5362 5438 16281 5438 5363 16282 5363 5286 16283 5286 5440 16284 5440 5364 16285 5364 5288 16286 5288 5442 16287 5442 5365 16288 5365 5290 16289 5290 5444 16290 5444 5366 16291 5366 5292 16292 5292 5446 16293 5446 5294 16294 5294 5367 16295 5367 5448 16296 5448 5296 16297 5296 5368 16298 5368 5450 16299 5450 5298 16300 5298 5369 16301 5369 5446 16302 5446 5370 16303 5370 5294 16304 5294 5448 16305 5448 5371 16306 5371 5296 16307 5296 5450 16308 5450 5372 16309 5372 5298 16310 5298 5452 16311 5452 5300 16312 5300 5373 16313 5373 5454 16314 5454 5302 16315 5302 5374 16316 5374 5456 16317 5456 5304 16318 5304 5375 16319 5375 5467 16320 5467 5306 16321 5306 5376 16322 5376 5452 16323 5452 5377 16324 5377 5300 16325 5300 5454 16326 5454 5378 16327 5378 5302 16328 5302 5456 16329 5456 5379 16330 5379 5304 16331 5304 5467 16332 5467 5380 16333 5380 5306 16334 5306 5477 16335 5477 5308 16336 5308 5381 16337 5381 5479 16338 5479 5310 16339 5310 5382 16340 5382 5481 16341 5481 5312 16342 5312 5383 16343 5383 5477 16344 5477 5384 16345 5384 5308 16346 5308 5479 16347 5479 5385 16348 5385 5310 16349 5310 5481 16350 5481 5386 16351 5386 5312 16352 5312 5482 16353 5482 5314 16354 5314 5387 16355 5387 5483 16356 5483 5316 16357 5316 5388 16358 5388 5484 16359 5484 5318 16360 5318 5389 16361 5389 5485 16362 5485 5320 16363 5320 5390 16364 5390 5482 16365 5482 5391 16366 5391 5314 16367 5314 5483 16368 5483 5392 16369 5392 5316 16370 5316 5484 16371 5484 5393 16372 5393 5318 16373 5318 5485 16374 5485 5394 16375 5394 5320 16376 5320 5491 16377 5491 5322 16378 5322 5395 16379 5395 5492 16380 5492 5324 16381 5324 5396 16382 5396 5493 16383 5493 5326 16384 5326 5397 16385 5397 5491 16386 5491 5398 16387 5398 5322 16388 5322 5492 16389 5492 5399 16390 5399 5324 16391 5324 5493 16392 5493 5400 16393 5400 5326 16394 5326 5497 16395 5497 5328 16396 5328 5401 16397 5401 5498 16398 5498 5330 16399 5330 5402 16400 5402 5499 16401 5499 5332 16402 5332 5403 16403 5403 5500 16404 5500 5334 16405 5334 5404 16406 5404 5497 16407 5497 5405 16408 5405 5328 16409 5328 5498 16410 5498 5406 16411 5406 5330 16412 5330 5499 16413 5499 5407 16414 5407 5332 16415 5332 5500 16416 5500 5408 16417 5408 5334 16418 5334 5505 16419 5505 5336 16420 5336 5409 16421 5409 5506 16422 5506 5338 16423 5338 5410 16424 5410 5507 16425 5507 5340 16426 5340 5411 16427 5411 5505 16428 5505 5412 16429 5412 5336 16430 5336 5506 16431 5506 5413 16432 5413 5338 16433 5338 5507 16434 5507 5414 16435 5414 5340 16436 5340 5511 16437 5511 5342 16438 5342 5415 16439 5415 5511 16440 5511 5416 16441 5416 5342 16442 5342 5419 16443 5419 3716 16444 3716 5417 16445 5417 5419 16446 5419 5418 16447 5418 3716 16448 3716 5416 16449 5416 5418 16450 5418 5419 16451 5419 5421 16452 5421 5420 16453 5420 5268 16454 5268 5463 16455 5463 5420 16456 5420 5421 16457 5421 5463 16458 5463 5422 16459 5422 5420 16460 5420 5422 16461 5422 5423 16462 5423 5348 16463 5348 5463 16464 5463 5423 16465 5423 5422 16466 5422 5463 16467 5463 5424 16468 5424 5423 16469 5423 5424 16470 5424 5425 16471 5425 5349 16472 5349 5463 16473 5463 5425 16474 5425 5424 16475 5424 5463 16476 5463 5426 16477 5426 5425 16478 5425 5426 16479 5426 5427 16480 5427 5350 16481 5350 5463 16482 5463 5427 16483 5427 5426 16484 5426 5463 16485 5463 5428 16486 5428 5427 16487 5427 5428 16488 5428 5429 16489 5429 5351 16490 5351 5463 16491 5463 5429 16492 5429 5428 16493 5428 5463 16494 5463 5430 16495 5430 5429 16496 5429 5430 16497 5430 5431 16498 5431 5352 16499 5352 5463 16500 5463 5431 16501 5431 5430 16502 5430 5463 16503 5463 5432 16504 5432 5431 16505 5431 5432 16506 5432 5433 16507 5433 5356 16508 5356 5463 16509 5463 5433 16510 5433 5432 16511 5432 5463 16512 5463 5434 16513 5434 5433 16514 5433 5434 16515 5434 5435 16516 5435 5357 16517 5357 5463 16518 5463 5435 16519 5435 5434 16520 5434 5463 16521 5463 5436 16522 5436 5435 16523 5435 5436 16524 5436 5437 16525 5437 5358 16526 5358 5463 16527 5463 5437 16528 5437 5436 16529 5436 5463 16530 5463 5438 16531 5438 5437 16532 5437 5438 16533 5438 5439 16534 5439 5363 16535 5363 5463 16536 5463 5439 16537 5439 5438 16538 5438 5463 16539 5463 5440 16540 5440 5439 16541 5439 5440 16542 5440 5441 16543 5441 5364 16544 5364 5463 16545 5463 5441 16546 5441 5440 16547 5440 5463 16548 5463 5442 16549 5442 5441 16550 5441 5442 16551 5442 5443 16552 5443 5365 16553 5365 5463 16554 5463 5443 16555 5443 5442 16556 5442 5463 16557 5463 5444 16558 5444 5443 16559 5443 5444 16560 5444 5445 16561 5445 5366 16562 5366 5463 16563 5463 5445 16564 5445 5444 16565 5444 5463 16566 5463 5446 16567 5446 5445 16568 5445 5446 16569 5446 5447 16570 5447 5370 16571 5370 5463 16572 5463 5447 16573 5447 5446 16574 5446 5463 16575 5463 5448 16576 5448 5447 16577 5447 5448 16578 5448 5449 16579 5449 5371 16580 5371 5463 16581 5463 5449 16582 5449 5448 16583 5448 5463 16584 5463 5450 16585 5450 5449 16586 5449 5450 16587 5450 5451 16588 5451 5372 16589 5372 5463 16590 5463 5451 16591 5451 5450 16592 5450 5463 16593 5463 5452 16594 5452 5451 16595 5451 5452 16596 5452 5453 16597 5453 5377 16598 5377 5463 16599 5463 5453 16600 5453 5452 16601 5452 5463 16602 5463 5454 16603 5454 5453 16604 5453 5454 16605 5454 5455 16606 5455 5378 16607 5378 5463 16608 5463 5455 16609 5455 5454 16610 5454 5463 16611 5463 5456 16612 5456 5455 16613 5455 5463 16614 5463 5379 16615 5379 5456 16616 5456 5463 16617 5463 5457 16618 5457 5379 16619 5379 5463 16620 5463 5458 16621 5458 5457 16622 5457 5463 16623 5463 5459 16624 5459 5458 16625 5458 5463 16626 5463 5460 16627 5460 5459 16628 5459 5463 16629 5463 5461 16630 5461 5460 16631 5460 5463 16632 5463 5462 16633 5462 5461 16634 5461 5418 16635 5418 5462 16636 5462 5463 16637 5463 5418 16638 5418 5464 16639 5464 5462 16640 5462 5418 16641 5418 5465 16642 5465 5464 16643 5464 5418 16644 5418 5466 16645 5466 5465 16646 5465 5418 16647 5418 5467 16648 5467 5466 16649 5466 5418 16650 5418 5380 16651 5380 5467 16652 5467 5418 16653 5418 5468 16654 5468 5380 16655 5380 5418 16656 5418 5469 16657 5469 5468 16658 5468 5418 16659 5418 5470 16660 5470 5469 16661 5469 5418 16662 5418 5471 16663 5471 5470 16664 5470 5418 16665 5418 5472 16666 5472 5471 16667 5471 5418 16668 5418 5473 16669 5473 5472 16670 5472 5418 16671 5418 5474 16672 5474 5473 16673 5473 5418 16674 5418 5475 16675 5475 5474 16676 5474 5418 16677 5418 5476 16678 5476 5475 16679 5475 5476 16680 5476 5384 16681 5384 5477 16682 5477 5418 16683 5418 5384 16684 5384 5476 16685 5476 5418 16686 5418 5478 16687 5478 5384 16688 5384 5478 16689 5478 5385 16690 5385 5479 16691 5479 5478 16692 5478 5480 16693 5480 5385 16694 5385 5480 16695 5480 5386 16696 5386 5481 16697 5481 5486 16698 5486 5391 16699 5391 5482 16700 5482 5487 16701 5487 5392 16702 5392 5483 16703 5483 5488 16704 5488 5393 16705 5393 5484 16706 5484 5489 16707 5489 5394 16708 5394 5485 16709 5485 5480 16710 5480 5486 16711 5486 5386 16712 5386 5486 16713 5486 5487 16714 5487 5391 16715 5391 5487 16716 5487 5488 16717 5488 5392 16718 5392 5488 16719 5488 5489 16720 5489 5393 16721 5393 5489 16722 5489 5490 16723 5490 5394 16724 5394 5490 16725 5490 5398 16726 5398 5491 16727 5491 5494 16728 5494 5399 16729 5399 5492 16730 5492 5495 16731 5495 5400 16732 5400 5493 16733 5493 5490 16734 5490 5494 16735 5494 5398 16736 5398 5494 16737 5494 5495 16738 5495 5399 16739 5399 5495 16740 5495 5496 16741 5496 5400 16742 5400 5496 16743 5496 5405 16744 5405 5497 16745 5497 5501 16746 5501 5406 16747 5406 5498 16748 5498 5502 16749 5502 5407 16750 5407 5499 16751 5499 5503 16752 5503 5408 16753 5408 5500 16754 5500 5496 16755 5496 5501 16756 5501 5405 16757 5405 5501 16758 5501 5502 16759 5502 5406 16760 5406 5502 16761 5502 5503 16762 5503 5407 16763 5407 5503 16764 5503 5504 16765 5504 5408 16766 5408 5504 16767 5504 5412 16768 5412 5505 16769 5505 5508 16770 5508 5413 16771 5413 5506 16772 5506 5509 16773 5509 5414 16774 5414 5507 16775 5507 5504 16776 5504 5508 16777 5508 5412 16778 5412 5508 16779 5508 5509 16780 5509 5413 16781 5413 5509 16782 5509 5510 16783 5510 5414 16784 5414 5510 16785 5510 5416 16786 5416 5511 16787 5511 5510 16788 5510 5418 16789 5418 5416 16790 5416 5509 16791 5509 5418 16792 5418 5510 16793 5510 5508 16794 5508 5418 16795 5418 5509 16796 5509 5504 16797 5504 5418 16798 5418 5508 16799 5508 5503 16800 5503 5418 16801 5418 5504 16802 5504 5502 16803 5502 5418 16804 5418 5503 16805 5503 5501 16806 5501 5418 16807 5418 5502 16808 5502 5496 16809 5496 5418 16810 5418 5501 16811 5501 5495 16812 5495 5418 16813 5418 5496 16814 5496 5494 16815 5494 5418 16816 5418 5495 16817 5495 5490 16818 5490 5418 16819 5418 5494 16820 5494 5489 16821 5489 5418 16822 5418 5490 16823 5490 5488 16824 5488 5418 16825 5418 5489 16826 5489 5487 16827 5487 5418 16828 5418 5488 16829 5488 5486 16830 5486 5418 16831 5418 5487 16832 5487 5480 16833 5480 5418 16834 5418 5486 16835 5486 5543 16836 5543 5512 16837 5512 5515 16838 5515 5512 16839 5512 5514 16840 5514 5513 16841 5513 5512 16842 5512 5513 16843 5513 5515 16844 5515 5520 16845 5520 5517 16846 5517 5516 16847 5516 5520 16848 5520 5516 16849 5516 5518 16850 5518 5520 16851 5520 5518 16852 5518 5519 16853 5519 5522 16854 5522 5520 16855 5520 5519 16856 5519 5522 16857 5522 5519 16858 5519 5521 16859 5521 5524 16860 5524 5522 16861 5522 5521 16862 5521 5524 16863 5524 5521 16864 5521 5523 16865 5523 5526 16866 5526 5524 16867 5524 5523 16868 5523 5526 16869 5526 5523 16870 5523 5525 16871 5525 5527 16872 5527 5526 16873 5526 5525 16874 5525 5530 16875 5530 5527 16876 5527 5525 16877 5525 5530 16878 5530 5525 16879 5525 5528 16880 5528 5530 16881 5530 5528 16882 5528 5529 16883 5529 5532 16884 5532 5530 16885 5530 5529 16886 5529 5532 16887 5532 5529 16888 5529 5531 16889 5531 5533 16890 5533 5532 16891 5532 5531 16892 5531 5535 16893 5535 5533 16894 5533 5531 16895 5531 5535 16896 5535 5531 16897 5531 5534 16898 5534 5537 16899 5537 5535 16900 5535 5534 16901 5534 5537 16902 5537 5534 16903 5534 5536 16904 5536 5539 16905 5539 5537 16906 5537 5536 16907 5536 5539 16908 5539 5536 16909 5536 5538 16910 5538 5541 16911 5541 5539 16912 5539 5538 16913 5538 5541 16914 5541 5538 16915 5538 5540 16916 5540 5544 16917 5544 5541 16918 5541 5540 16919 5540 5544 16920 5544 5540 16921 5540 5542 16922 5542 5544 16923 5544 5542 16924 5542 5543 16925 5543 5545 16926 5545 5544 16927 5544 5543 16928 5543 5515 16929 5515 5545 16930 5545 5543 16931 5543 5577 16932 5577 5546 16933 5546 5547 16934 5547 5549 16935 5549 5548 16936 5548 5547 16937 5547 5546 16938 5546 5549 16939 5549 5547 16940 5547 5554 16941 5554 5551 16942 5551 5550 16943 5550 5554 16944 5554 5550 16945 5550 5552 16946 5552 5554 16947 5554 5552 16948 5552 5553 16949 5553 5556 16950 5556 5554 16951 5554 5553 16952 5553 5556 16953 5556 5553 16954 5553 5555 16955 5555 5558 16956 5558 5556 16957 5556 5555 16958 5555 5558 16959 5558 5555 16960 5555 5557 16961 5557 5560 16962 5560 5558 16963 5558 5557 16964 5557 5560 16965 5560 5557 16966 5557 5559 16967 5559 5562 16968 5562 5560 16969 5560 5559 16970 5559 5562 16971 5562 5559 16972 5559 5561 16973 5561 5563 16974 5563 5562 16975 5562 5561 16976 5561 5565 16977 5565 5563 16978 5563 5561 16979 5561 5565 16980 5565 5561 16981 5561 5564 16982 5564 5567 16983 5567 5565 16984 5565 5564 16985 5564 5567 16986 5567 5564 16987 5564 5566 16988 5566 5569 16989 5569 5567 16990 5567 5566 16991 5566 5569 16992 5569 5566 16993 5566 5568 16994 5568 5571 16995 5571 5569 16996 5569 5568 16997 5568 5571 16998 5571 5568 16999 5568 5570 17000 5570 5573 17001 5573 5571 17002 5571 5570 17003 5570 5573 17004 5573 5570 17005 5570 5572 17006 5572 5575 17007 5575 5573 17008 5573 5572 17009 5572 5575 17010 5575 5572 17011 5572 5574 17012 5574 5578 17013 5578 5575 17014 5575 5574 17015 5574 5578 17016 5578 5574 17017 5574 5576 17018 5576 5578 17019 5578 5576 17020 5576 5577 17021 5577 5579 17022 5579 5578 17023 5578 5577 17024 5577 5547 17025 5547 5579 17026 5579 5577 17027 5577 5612 17028 5612 5580 17029 5580 5581 17030 5581 5583 17031 5583 5582 17032 5582 5581 17033 5581 5580 17034 5580 5583 17035 5583 5581 17036 5581 5587 17037 5587 5585 17038 5585 5584 17039 5584 5587 17040 5587 5584 17041 5584 5586 17042 5586 5590 17043 5590 5587 17044 5587 5586 17045 5586 5590 17046 5590 5586 17047 5586 5588 17048 5588 5590 17049 5590 5588 17050 5588 5589 17051 5589 5591 17052 5591 5590 17053 5590 5589 17054 5589 5593 17055 5593 5591 17056 5591 5589 17057 5589 5593 17058 5593 5589 17059 5589 5592 17060 5592 5596 17061 5596 5593 17062 5593 5592 17063 5592 5596 17064 5596 5592 17065 5592 5594 17066 5594 5596 17067 5596 5594 17068 5594 5595 17069 5595 5597 17070 5597 5596 17071 5596 5595 17072 5595 5599 17073 5599 5597 17074 5597 5595 17075 5595 5599 17076 5599 5595 17077 5595 5598 17078 5598 5601 17079 5601 5599 17080 5599 5598 17081 5598 5601 17082 5601 5598 17083 5598 5600 17084 5600 5603 17085 5603 5601 17086 5601 5600 17087 5600 5603 17088 5603 5600 17089 5600 5602 17090 5602 5605 17091 5605 5603 17092 5603 5602 17093 5602 5605 17094 5605 5602 17095 5602 5604 17096 5604 5607 17097 5607 5605 17098 5605 5604 17099 5604 5607 17100 5607 5604 17101 5604 5606 17102 5606 5609 17103 5609 5607 17104 5607 5606 17105 5606 5609 17106 5609 5606 17107 5606 5608 17108 5608 5611 17109 5611 5609 17110 5609 5608 17111 5608 5611 17112 5611 5608 17113 5608 5610 17114 5610 5613 17115 5613 5611 17116 5611 5610 17117 5610 5613 17118 5613 5610 17119 5610 5612 17120 5612 5581 17121 5581 5613 17122 5613 5612 17123 5612 5646 17124 5646 5614 17125 5614 5615 17126 5615 5617 17127 5617 5616 17128 5616 5615 17129 5615 5614 17130 5614 5617 17131 5617 5615 17132 5615 5622 17133 5622 5619 17134 5619 5618 17135 5618 5622 17136 5622 5618 17137 5618 5620 17138 5620 5622 17139 5622 5620 17140 5620 5621 17141 5621 5623 17142 5623 5622 17143 5622 5621 17144 5621 5626 17145 5626 5623 17146 5623 5621 17147 5621 5626 17148 5626 5621 17149 5621 5624 17150 5624 5626 17151 5626 5624 17152 5624 5625 17153 5625 5627 17154 5627 5626 17155 5626 5625 17156 5625 5629 17157 5629 5627 17158 5627 5625 17159 5625 5629 17160 5629 5625 17161 5625 5628 17162 5628 5632 17163 5632 5629 17164 5629 5628 17165 5628 5632 17166 5632 5628 17167 5628 5630 17168 5630 5632 17169 5632 5630 17170 5630 5631 17171 5631 5634 17172 5634 5632 17173 5632 5631 17174 5631 5634 17175 5634 5631 17176 5631 5633 17177 5633 5636 17178 5636 5634 17179 5634 5633 17180 5633 5636 17181 5636 5633 17182 5633 5635 17183 5635 5637 17184 5637 5636 17185 5636 5635 17186 5635 5639 17187 5639 5637 17188 5637 5635 17189 5635 5639 17190 5639 5635 17191 5635 5638 17192 5638 5642 17193 5642 5639 17194 5639 5638 17195 5638 5642 17196 5642 5638 17197 5638 5640 17198 5640 5642 17199 5642 5640 17200 5640 5641 17201 5641 5643 17202 5643 5642 17203 5642 5641 17204 5641 5645 17205 5645 5643 17206 5643 5641 17207 5641 5645 17208 5645 5641 17209 5641 5644 17210 5644 5647 17211 5647 5645 17212 5645 5644 17213 5644 5647 17214 5647 5644 17215 5644 5646 17216 5646 5615 17217 5615 5647 17218 5647 5646 17219 5646 5680 17220 5680 5648 17221 5648 5657 17222 5657 5651 17223 5651 5650 17224 5650 5649 17225 5649 5653 17226 5653 5651 17227 5651 5649 17228 5649 5653 17229 5653 5649 17230 5649 5652 17231 5652 5654 17232 5654 5653 17233 5653 5652 17234 5652 5656 17235 5656 5654 17236 5654 5652 17237 5652 5656 17238 5656 5652 17239 5652 5655 17240 5655 5648 17241 5648 5656 17242 5656 5655 17243 5655 5648 17244 5648 5655 17245 5655 5657 17246 5657 5662 17247 5662 5659 17248 5659 5658 17249 5658 5662 17250 5662 5658 17251 5658 5660 17252 5660 5662 17253 5662 5660 17254 5660 5661 17255 5661 5663 17256 5663 5662 17257 5662 5661 17258 5661 5665 17259 5665 5663 17260 5663 5661 17261 5661 5665 17262 5665 5661 17263 5661 5664 17264 5664 5668 17265 5668 5665 17266 5665 5664 17267 5664 5668 17268 5668 5664 17269 5664 5666 17270 5666 5668 17271 5668 5666 17272 5666 5667 17273 5667 5669 17274 5669 5668 17275 5668 5667 17276 5667 5672 17277 5672 5669 17278 5669 5667 17279 5667 5672 17280 5672 5667 17281 5667 5670 17282 5670 5672 17283 5672 5670 17284 5670 5671 17285 5671 5673 17286 5673 5672 17287 5672 5671 17288 5671 5675 17289 5675 5673 17290 5673 5671 17291 5671 5675 17292 5675 5671 17293 5671 5674 17294 5674 5677 17295 5677 5675 17296 5675 5674 17297 5674 5677 17298 5677 5674 17299 5674 5676 17300 5676 5679 17301 5679 5677 17302 5677 5676 17303 5676 5679 17304 5679 5676 17305 5676 5678 17306 5678 5681 17307 5681 5679 17308 5679 5678 17309 5678 5681 17310 5681 5678 17311 5678 5680 17312 5680 5657 17313 5657 5681 17314 5681 5680 17315 5680 5714 17316 5714 5682 17317 5682 5686 17318 5686 5685 17319 5685 5684 17320 5684 5683 17321 5683 5687 17322 5687 5685 17323 5685 5683 17324 5683 5687 17325 5687 5683 17326 5683 5686 17327 5686 5682 17328 5682 5687 17329 5687 5686 17330 5686 5692 17331 5692 5689 17332 5689 5688 17333 5688 5692 17334 5692 5688 17335 5688 5690 17336 5690 5692 17337 5692 5690 17338 5690 5691 17339 5691 5694 17340 5694 5692 17341 5692 5691 17342 5691 5694 17343 5694 5691 17344 5691 5693 17345 5693 5695 17346 5695 5694 17347 5694 5693 17348 5693 5697 17349 5697 5695 17350 5695 5693 17351 5693 5697 17352 5697 5693 17353 5693 5696 17354 5696 5699 17355 5699 5697 17356 5697 5696 17357 5696 5699 17358 5699 5696 17359 5696 5698 17360 5698 5701 17361 5701 5699 17362 5699 5698 17363 5698 5701 17364 5701 5698 17365 5698 5700 17366 5700 5703 17367 5703 5701 17368 5701 5700 17369 5700 5703 17370 5703 5700 17371 5700 5702 17372 5702 5705 17373 5705 5703 17374 5703 5702 17375 5702 5705 17376 5705 5702 17377 5702 5704 17378 5704 5707 17379 5707 5705 17380 5705 5704 17381 5704 5707 17382 5707 5704 17383 5704 5706 17384 5706 5709 17385 5709 5707 17386 5707 5706 17387 5706 5709 17388 5709 5706 17389 5706 5708 17390 5708 5711 17391 5711 5709 17392 5709 5708 17393 5708 5711 17394 5711 5708 17395 5708 5710 17396 5710 5713 17397 5713 5711 17398 5711 5710 17399 5710 5713 17400 5713 5710 17401 5710 5712 17402 5712 5715 17403 5715 5713 17404 5713 5712 17405 5712 5715 17406 5715 5712 17407 5712 5714 17408 5714 5686 17409 5686 5715 17410 5715 5714 17411 5714 5748 17412 5748 5716 17413 5716 5720 17414 5720 5719 17415 5719 5718 17416 5718 5717 17417 5717 5721 17418 5721 5719 17419 5719 5717 17420 5717 5721 17421 5721 5717 17422 5717 5720 17423 5720 5716 17424 5716 5721 17425 5721 5720 17426 5720 5724 17427 5724 5723 17428 5723 5722 17429 5722 5726 17430 5726 5724 17431 5724 5722 17432 5722 5726 17433 5726 5722 17434 5722 5725 17435 5725 5727 17436 5727 5726 17437 5726 5725 17438 5725 5729 17439 5729 5727 17440 5727 5725 17441 5725 5729 17442 5729 5725 17443 5725 5728 17444 5728 5731 17445 5731 5729 17446 5729 5728 17447 5728 5731 17448 5731 5728 17449 5728 5730 17450 5730 5733 17451 5733 5731 17452 5731 5730 17453 5730 5733 17454 5733 5730 17455 5730 5732 17456 5732 5736 17457 5736 5733 17458 5733 5732 17459 5732 5736 17460 5736 5732 17461 5732 5734 17462 5734 5736 17463 5736 5734 17464 5734 5735 17465 5735 5737 17466 5737 5736 17467 5736 5735 17468 5735 5739 17469 5739 5737 17470 5737 5735 17471 5735 5739 17472 5739 5735 17473 5735 5738 17474 5738 5741 17475 5741 5739 17476 5739 5738 17477 5738 5741 17478 5741 5738 17479 5738 5740 17480 5740 5743 17481 5743 5741 17482 5741 5740 17483 5740 5743 17484 5743 5740 17485 5740 5742 17486 5742 5745 17487 5745 5743 17488 5743 5742 17489 5742 5745 17490 5745 5742 17491 5742 5744 17492 5744 5747 17493 5747 5745 17494 5745 5744 17495 5744 5747 17496 5747 5744 17497 5744 5746 17498 5746 5749 17499 5749 5747 17500 5747 5746 17501 5746 5749 17502 5749 5746 17503 5746 5748 17504 5748 5720 17505 5720 5749 17506 5749 5748 17507 5748 5782 17508 5782 5751 17509 5751 5750 17510 5750 5754 17511 5754 5753 17512 5753 5752 17513 5752 5755 17514 5755 5754 17515 5754 5752 17516 5752 5757 17517 5757 5755 17518 5755 5752 17519 5752 5757 17520 5757 5752 17521 5752 5756 17522 5756 5760 17523 5760 5757 17524 5757 5756 17525 5756 5760 17526 5760 5756 17527 5756 5758 17528 5758 5760 17529 5760 5758 17530 5758 5759 17531 5759 5762 17532 5762 5760 17533 5760 5759 17534 5759 5762 17535 5762 5759 17536 5759 5761 17537 5761 5764 17538 5764 5762 17539 5762 5761 17540 5761 5764 17541 5764 5761 17542 5761 5763 17543 5763 5766 17544 5766 5764 17545 5764 5763 17546 5763 5766 17547 5766 5763 17548 5763 5765 17549 5765 5768 17550 5768 5766 17551 5766 5765 17552 5765 5768 17553 5768 5765 17554 5765 5767 17555 5767 5770 17556 5770 5768 17557 5768 5767 17558 5767 5770 17559 5770 5767 17560 5767 5769 17561 5769 5771 17562 5771 5770 17563 5770 5769 17564 5769 5774 17565 5774 5771 17566 5771 5769 17567 5769 5774 17568 5774 5769 17569 5769 5772 17570 5772 5774 17571 5774 5772 17572 5772 5773 17573 5773 5776 17574 5776 5774 17575 5774 5773 17576 5773 5776 17577 5776 5773 17578 5773 5775 17579 5775 5778 17580 5778 5776 17581 5776 5775 17582 5775 5778 17583 5778 5775 17584 5775 5777 17585 5777 5779 17586 5779 5778 17587 5778 5777 17588 5777 5781 17589 5781 5779 17590 5779 5777 17591 5777 5781 17592 5781 5777 17593 5777 5780 17594 5780 5783 17595 5783 5781 17596 5781 5780 17597 5780 5783 17598 5783 5780 17599 5780 5782 17600 5782 5750 17601 5750 5783 17602 5783 5782 17603 5782 5817 17604 5817 5800 17605 5800 5784 17606 5784 5787 17607 5787 5786 17608 5786 5785 17609 5785 5788 17610 5788 5787 17611 5787 5785 17612 5785 5791 17613 5791 5788 17614 5788 5785 17615 5785 5791 17616 5791 5785 17617 5785 5789 17618 5789 5791 17619 5791 5789 17620 5789 5790 17621 5790 5792 17622 5792 5791 17623 5791 5790 17624 5790 5795 17625 5795 5792 17626 5792 5790 17627 5790 5795 17628 5795 5790 17629 5790 5793 17630 5793 5795 17631 5795 5793 17632 5793 5794 17633 5794 5797 17634 5797 5795 17635 5795 5794 17636 5794 5797 17637 5797 5794 17638 5794 5796 17639 5796 5799 17640 5799 5797 17641 5797 5796 17642 5796 5799 17643 5799 5796 17644 5796 5798 17645 5798 5801 17646 5801 5799 17647 5799 5798 17648 5798 5801 17649 5801 5798 17650 5798 5800 17651 5800 5817 17652 5817 5801 17653 5801 5800 17654 5800 5804 17655 5804 5803 17656 5803 5802 17657 5802 5806 17658 5806 5804 17659 5804 5802 17660 5802 5806 17661 5806 5802 17662 5802 5805 17663 5805 5808 17664 5808 5806 17665 5806 5805 17666 5805 5808 17667 5808 5805 17668 5805 5807 17669 5807 5809 17670 5809 5808 17671 5808 5807 17672 5807 5811 17673 5811 5809 17674 5809 5807 17675 5807 5811 17676 5811 5807 17677 5807 5810 17678 5810 5814 17679 5814 5811 17680 5811 5810 17681 5810 5814 17682 5814 5810 17683 5810 5812 17684 5812 5814 17685 5814 5812 17686 5812 5813 17687 5813 5815 17688 5815 5814 17689 5814 5813 17690 5813 5784 17691 5784 5815 17692 5815 5813 17693 5813 5784 17694 5784 5813 17695 5813 5816 17696 5816 5784 17697 5784 5816 17698 5816 5817 17699 5817 5850 17700 5850 5819 17701 5819 5818 17702 5818 5823 17703 5823 5821 17704 5821 5820 17705 5820 5823 17706 5823 5820 17707 5820 5822 17708 5822 5825 17709 5825 5823 17710 5823 5822 17711 5822 5825 17712 5825 5822 17713 5822 5824 17714 5824 5828 17715 5828 5825 17716 5825 5824 17717 5824 5828 17718 5828 5824 17719 5824 5826 17720 5826 5828 17721 5828 5826 17722 5826 5827 17723 5827 5830 17724 5830 5828 17725 5828 5827 17726 5827 5830 17727 5830 5827 17728 5827 5829 17729 5829 5832 17730 5832 5830 17731 5830 5829 17732 5829 5832 17733 5832 5829 17734 5829 5831 17735 5831 5834 17736 5834 5832 17737 5832 5831 17738 5831 5834 17739 5834 5831 17740 5831 5833 17741 5833 5835 17742 5835 5834 17743 5834 5833 17744 5833 5838 17745 5838 5835 17746 5835 5833 17747 5833 5838 17748 5838 5833 17749 5833 5836 17750 5836 5838 17751 5838 5836 17752 5836 5837 17753 5837 5840 17754 5840 5838 17755 5838 5837 17756 5837 5840 17757 5840 5837 17758 5837 5839 17759 5839 5842 17760 5842 5840 17761 5840 5839 17762 5839 5842 17763 5842 5839 17764 5839 5841 17765 5841 5844 17766 5844 5842 17767 5842 5841 17768 5841 5844 17769 5844 5841 17770 5841 5843 17771 5843 5845 17772 5845 5844 17773 5844 5843 17774 5843 5847 17775 5847 5845 17776 5845 5843 17777 5843 5847 17778 5847 5843 17779 5843 5846 17780 5846 5849 17781 5849 5847 17782 5847 5846 17783 5846 5849 17784 5849 5846 17785 5846 5848 17786 5848 5851 17787 5851 5849 17788 5849 5848 17789 5848 5851 17790 5851 5848 17791 5848 5850 17792 5850 5818 17793 5818 5851 17794 5851 5850 17795 5850 5884 17796 5884 5852 17797 5852 5855 17798 5855 5852 17799 5852 5854 17800 5854 5853 17801 5853 5852 17802 5852 5853 17803 5853 5855 17804 5855 5859 17805 5859 5857 17806 5857 5856 17807 5856 5859 17808 5859 5856 17809 5856 5858 17810 5858 5861 17811 5861 5859 17812 5859 5858 17813 5858 5861 17814 5861 5858 17815 5858 5860 17816 5860 5864 17817 5864 5861 17818 5861 5860 17819 5860 5864 17820 5864 5860 17821 5860 5862 17822 5862 5864 17823 5864 5862 17824 5862 5863 17825 5863 5866 17826 5866 5864 17827 5864 5863 17828 5863 5866 17829 5866 5863 17830 5863 5865 17831 5865 5868 17832 5868 5866 17833 5866 5865 17834 5865 5868 17835 5868 5865 17836 5865 5867 17837 5867 5869 17838 5869 5868 17839 5868 5867 17840 5867 5871 17841 5871 5869 17842 5869 5867 17843 5867 5871 17844 5871 5867 17845 5867 5870 17846 5870 5874 17847 5874 5871 17848 5871 5870 17849 5870 5874 17850 5874 5870 17851 5870 5872 17852 5872 5874 17853 5874 5872 17854 5872 5873 17855 5873 5876 17856 5876 5874 17857 5874 5873 17858 5873 5876 17859 5876 5873 17860 5873 5875 17861 5875 5878 17862 5878 5876 17863 5876 5875 17864 5875 5878 17865 5878 5875 17866 5875 5877 17867 5877 5879 17868 5879 5878 17869 5878 5877 17870 5877 5882 17871 5882 5879 17872 5879 5877 17873 5877 5882 17874 5882 5877 17875 5877 5880 17876 5880 5882 17877 5882 5880 17878 5880 5881 17879 5881 5883 17880 5883 5882 17881 5882 5881 17882 5881 5885 17883 5885 5883 17884 5883 5881 17885 5881 5885 17886 5885 5881 17887 5881 5884 17888 5884 5855 17889 5855 5885 17890 5885 5884 17891 5884 5918 17892 5918 5887 17893 5887 5886 17894 5886 5891 17895 5891 5889 17896 5889 5888 17897 5888 5891 17898 5891 5888 17899 5888 5890 17900 5890 5893 17901 5893 5891 17902 5891 5890 17903 5890 5893 17904 5893 5890 17905 5890 5892 17906 5892 5896 17907 5896 5893 17908 5893 5892 17909 5892 5896 17910 5896 5892 17911 5892 5894 17912 5894 5896 17913 5896 5894 17914 5894 5895 17915 5895 5898 17916 5898 5896 17917 5896 5895 17918 5895 5898 17919 5898 5895 17920 5895 5897 17921 5897 5900 17922 5900 5898 17923 5898 5897 17924 5897 5900 17925 5900 5897 17926 5897 5899 17927 5899 5902 17928 5902 5900 17929 5900 5899 17930 5899 5902 17931 5902 5899 17932 5899 5901 17933 5901 5904 17934 5904 5902 17935 5902 5901 17936 5901 5904 17937 5904 5901 17938 5901 5903 17939 5903 5906 17940 5906 5904 17941 5904 5903 17942 5903 5906 17943 5906 5903 17944 5903 5905 17945 5905 5907 17946 5907 5906 17947 5906 5905 17948 5905 5910 17949 5910 5907 17950 5907 5905 17951 5905 5910 17952 5910 5905 17953 5905 5908 17954 5908 5910 17955 5910 5908 17956 5908 5909 17957 5909 5911 17958 5911 5910 17959 5910 5909 17960 5909 5913 17961 5913 5911 17962 5911 5909 17963 5909 5913 17964 5913 5909 17965 5909 5912 17966 5912 5915 17967 5915 5913 17968 5913 5912 17969 5912 5915 17970 5915 5912 17971 5912 5914 17972 5914 5917 17973 5917 5915 17974 5915 5914 17975 5914 5917 17976 5917 5914 17977 5914 5916 17978 5916 5919 17979 5919 5917 17980 5917 5916 17981 5916 5919 17982 5919 5916 17983 5916 5918 17984 5918 5886 17985 5886 5919 17986 5919 5918 17987 5918 5952 17988 5952 5921 17989 5921 5920 17990 5920 5924 17991 5924 5923 17992 5923 5922 17993 5922 5925 17994 5925 5924 17995 5924 5922 17996 5922 5927 17997 5927 5925 17998 5925 5922 17999 5922 5927 18000 5927 5922 18001 5922 5926 18002 5926 5930 18003 5930 5927 18004 5927 5926 18005 5926 5930 18006 5930 5926 18007 5926 5928 18008 5928 5930 18009 5930 5928 18010 5928 5929 18011 5929 5932 18012 5932 5930 18013 5930 5929 18014 5929 5932 18015 5932 5929 18016 5929 5931 18017 5931 5934 18018 5934 5932 18019 5932 5931 18020 5931 5934 18021 5934 5931 18022 5931 5933 18023 5933 5936 18024 5936 5934 18025 5934 5933 18026 5933 5936 18027 5936 5933 18028 5933 5935 18029 5935 5937 18030 5937 5936 18031 5936 5935 18032 5935 5940 18033 5940 5937 18034 5937 5935 18035 5935 5940 18036 5940 5935 18037 5935 5938 18038 5938 5940 18039 5940 5938 18040 5938 5939 18041 5939 5941 18042 5941 5940 18043 5940 5939 18044 5939 5944 18045 5944 5941 18046 5941 5939 18047 5939 5944 18048 5944 5939 18049 5939 5942 18050 5942 5944 18051 5944 5942 18052 5942 5943 18053 5943 5945 18054 5945 5944 18055 5944 5943 18056 5943 5947 18057 5947 5945 18058 5945 5943 18059 5943 5947 18060 5947 5943 18061 5943 5946 18062 5946 5949 18063 5949 5947 18064 5947 5946 18065 5946 5949 18066 5949 5946 18067 5946 5948 18068 5948 5951 18069 5951 5949 18070 5949 5948 18071 5948 5951 18072 5951 5948 18073 5948 5950 18074 5950 5953 18075 5953 5951 18076 5951 5950 18077 5950 5953 18078 5953 5950 18079 5950 5952 18080 5952 5920 18081 5920 5953 18082 5953 5952 18083 5952 5986 18084 5986 5955 18085 5955 5954 18086 5954 5958 18087 5958 5957 18088 5957 5956 18089 5956 5960 18090 5960 5958 18091 5958 5956 18092 5956 5960 18093 5960 5956 18094 5956 5959 18095 5959 5962 18096 5962 5960 18097 5960 5959 18098 5959 5962 18099 5962 5959 18100 5959 5961 18101 5961 5964 18102 5964 5962 18103 5962 5961 18104 5961 5964 18105 5964 5961 18106 5961 5963 18107 5963 5966 18108 5966 5964 18109 5964 5963 18110 5963 5966 18111 5966 5963 18112 5963 5965 18113 5965 5967 18114 5967 5966 18115 5966 5965 18116 5965 5969 18117 5969 5967 18118 5967 5965 18119 5965 5969 18120 5969 5965 18121 5965 5968 18122 5968 5971 18123 5971 5969 18124 5969 5968 18125 5968 5971 18126 5971 5968 18127 5968 5970 18128 5970 5973 18129 5973 5971 18130 5971 5970 18131 5970 5973 18132 5973 5970 18133 5970 5972 18134 5972 5975 18135 5975 5973 18136 5973 5972 18137 5972 5975 18138 5975 5972 18139 5972 5974 18140 5974 5977 18141 5977 5975 18142 5975 5974 18143 5974 5977 18144 5977 5974 18145 5974 5976 18146 5976 5980 18147 5980 5977 18148 5977 5976 18149 5976 5980 18150 5980 5976 18151 5976 5978 18152 5978 5980 18153 5980 5978 18154 5978 5979 18155 5979 5981 18156 5981 5980 18157 5980 5979 18158 5979 5983 18159 5983 5981 18160 5981 5979 18161 5979 5983 18162 5983 5979 18163 5979 5982 18164 5982 5985 18165 5985 5983 18166 5983 5982 18167 5982 5985 18168 5985 5982 18169 5982 5984 18170 5984 5987 18171 5987 5985 18172 5985 5984 18173 5984 5987 18174 5987 5984 18175 5984 5986 18176 5986 5954 18177 5954 5987 18178 5987 5986 18179 5986 6021 18180 6021 5989 18181 5989 5988 18182 5988 5991 18183 5991 5990 18184 5990 5989 18185 5989 6021 18186 6021 5991 18187 5991 5989 18188 5989 5996 18189 5996 5993 18190 5993 5992 18191 5992 5996 18192 5996 5992 18193 5992 5994 18194 5994 5996 18195 5996 5994 18196 5994 5995 18197 5995 5998 18198 5998 5996 18199 5996 5995 18200 5995 5998 18201 5998 5995 18202 5995 5997 18203 5997 6000 18204 6000 5998 18205 5998 5997 18206 5997 6000 18207 6000 5997 18208 5997 5999 18209 5999 6001 18210 6001 6000 18211 6000 5999 18212 5999 6003 18213 6003 6001 18214 6001 5999 18215 5999 6003 18216 6003 5999 18217 5999 6002 18218 6002 6005 18219 6005 6003 18220 6003 6002 18221 6002 6005 18222 6005 6002 18223 6002 6004 18224 6004 6007 18225 6007 6005 18226 6005 6004 18227 6004 6007 18228 6007 6004 18229 6004 6006 18230 6006 6010 18231 6010 6007 18232 6007 6006 18233 6006 6010 18234 6010 6006 18235 6006 6008 18236 6008 6010 18237 6010 6008 18238 6008 6009 18239 6009 6012 18240 6012 6010 18241 6010 6009 18242 6009 6012 18243 6012 6009 18244 6009 6011 18245 6011 6014 18246 6014 6012 18247 6012 6011 18248 6011 6014 18249 6014 6011 18250 6011 6013 18251 6013 6016 18252 6016 6014 18253 6014 6013 18254 6013 6016 18255 6016 6013 18256 6013 6015 18257 6015 6017 18258 6017 6016 18259 6016 6015 18260 6015 6020 18261 6020 6017 18262 6017 6015 18263 6015 6020 18264 6020 6015 18265 6015 6018 18266 6018 6020 18267 6020 6018 18268 6018 6019 18269 6019 5988 18270 5988 6020 18271 6020 6019 18272 6019 5988 18273 5988 6019 18274 6019 6021 18275 6021 6054 18276 6054 6022 18277 6022 6025 18278 6025 6022 18279 6022 6024 18280 6024 6023 18281 6023 6022 18282 6022 6023 18283 6023 6025 18284 6025 6029 18285 6029 6027 18286 6027 6026 18287 6026 6029 18288 6029 6026 18289 6026 6028 18290 6028 6031 18291 6031 6029 18292 6029 6028 18293 6028 6031 18294 6031 6028 18295 6028 6030 18296 6030 6034 18297 6034 6031 18298 6031 6030 18299 6030 6034 18300 6034 6030 18301 6030 6032 18302 6032 6034 18303 6034 6032 18304 6032 6033 18305 6033 6035 18306 6035 6034 18307 6034 6033 18308 6033 6038 18309 6038 6035 18310 6035 6033 18311 6033 6038 18312 6038 6033 18313 6033 6036 18314 6036 6038 18315 6038 6036 18316 6036 6037 18317 6037 6040 18318 6040 6038 18319 6038 6037 18320 6037 6040 18321 6040 6037 18322 6037 6039 18323 6039 6042 18324 6042 6040 18325 6040 6039 18326 6039 6042 18327 6042 6039 18328 6039 6041 18329 6041 6043 18330 6043 6042 18331 6042 6041 18332 6041 6046 18333 6046 6043 18334 6043 6041 18335 6041 6046 18336 6046 6041 18337 6041 6044 18338 6044 6046 18339 6046 6044 18340 6044 6045 18341 6045 6047 18342 6047 6046 18343 6046 6045 18344 6045 6049 18345 6049 6047 18346 6047 6045 18347 6045 6049 18348 6049 6045 18349 6045 6048 18350 6048 6051 18351 6051 6049 18352 6049 6048 18353 6048 6051 18354 6051 6048 18355 6048 6050 18356 6050 6053 18357 6053 6051 18358 6051 6050 18359 6050 6053 18360 6053 6050 18361 6050 6052 18362 6052 6055 18363 6055 6053 18364 6053 6052 18365 6052 6055 18366 6055 6052 18367 6052 6054 18368 6054 6025 18369 6025 6055 18370 6055 6054 18371 6054 6088 18372 6088 6056 18373 6056 6059 18374 6059 6056 18375 6056 6058 18376 6058 6057 18377 6057 6056 18378 6056 6057 18379 6057 6059 18380 6059 6064 18381 6064 6061 18382 6061 6060 18383 6060 6064 18384 6064 6060 18385 6060 6062 18386 6062 6064 18387 6064 6062 18388 6062 6063 18389 6063 6066 18390 6066 6064 18391 6064 6063 18392 6063 6066 18393 6066 6063 18394 6063 6065 18395 6065 6067 18396 6067 6066 18397 6066 6065 18398 6065 6069 18399 6069 6067 18400 6067 6065 18401 6065 6069 18402 6069 6065 18403 6065 6068 18404 6068 6071 18405 6071 6069 18406 6069 6068 18407 6068 6071 18408 6071 6068 18409 6068 6070 18410 6070 6073 18411 6073 6071 18412 6071 6070 18413 6070 6073 18414 6073 6070 18415 6070 6072 18416 6072 6075 18417 6075 6073 18418 6073 6072 18419 6072 6075 18420 6075 6072 18421 6072 6074 18422 6074 6077 18423 6077 6075 18424 6075 6074 18425 6074 6077 18426 6077 6074 18427 6074 6076 18428 6076 6079 18429 6079 6077 18430 6077 6076 18431 6076 6079 18432 6079 6076 18433 6076 6078 18434 6078 6081 18435 6081 6079 18436 6079 6078 18437 6078 6081 18438 6081 6078 18439 6078 6080 18440 6080 6083 18441 6083 6081 18442 6081 6080 18443 6080 6083 18444 6083 6080 18445 6080 6082 18446 6082 6086 18447 6086 6083 18448 6083 6082 18449 6082 6086 18450 6086 6082 18451 6082 6084 18452 6084 6086 18453 6086 6084 18454 6084 6085 18455 6085 6087 18456 6087 6086 18457 6086 6085 18458 6085 6089 18459 6089 6087 18460 6087 6085 18461 6085 6089 18462 6089 6085 18463 6085 6088 18464 6088 6059 18465 6059 6089 18466 6089 6088 18467 6088 6122 18468 6122 6091 18469 6091 6090 18470 6090 6094 18471 6094 6093 18472 6093 6092 18473 6092 6095 18474 6095 6094 18475 6094 6092 18476 6092 6097 18477 6097 6095 18478 6095 6092 18479 6092 6097 18480 6097 6092 18481 6092 6096 18482 6096 6099 18483 6099 6097 18484 6097 6096 18485 6096 6099 18486 6099 6096 18487 6096 6098 18488 6098 6101 18489 6101 6099 18490 6099 6098 18491 6098 6101 18492 6101 6098 18493 6098 6100 18494 6100 6103 18495 6103 6101 18496 6101 6100 18497 6100 6103 18498 6103 6100 18499 6100 6102 18500 6102 6105 18501 6105 6103 18502 6103 6102 18503 6102 6105 18504 6105 6102 18505 6102 6104 18506 6104 6107 18507 6107 6105 18508 6105 6104 18509 6104 6107 18510 6107 6104 18511 6104 6106 18512 6106 6109 18513 6109 6107 18514 6107 6106 18515 6106 6109 18516 6109 6106 18517 6106 6108 18518 6108 6111 18519 6111 6109 18520 6109 6108 18521 6108 6111 18522 6111 6108 18523 6108 6110 18524 6110 6113 18525 6113 6111 18526 6111 6110 18527 6110 6113 18528 6113 6110 18529 6110 6112 18530 6112 6115 18531 6115 6113 18532 6113 6112 18533 6112 6115 18534 6115 6112 18535 6112 6114 18536 6114 6117 18537 6117 6115 18538 6115 6114 18539 6114 6117 18540 6117 6114 18541 6114 6116 18542 6116 6119 18543 6119 6117 18544 6117 6116 18545 6116 6119 18546 6119 6116 18547 6116 6118 18548 6118 6121 18549 6121 6119 18550 6119 6118 18551 6118 6121 18552 6121 6118 18553 6118 6120 18554 6120 6123 18555 6123 6121 18556 6121 6120 18557 6120 6123 18558 6123 6120 18559 6120 6122 18560 6122 6090 18561 6090 6123 18562 6123 6122 18563 6122 6156 18564 6156 6125 18565 6125 6124 18566 6124 6130 18567 6130 6127 18568 6127 6126 18569 6126 6130 18570 6130 6126 18571 6126 6128 18572 6128 6130 18573 6130 6128 18574 6128 6129 18575 6129 6132 18576 6132 6130 18577 6130 6129 18578 6129 6132 18579 6132 6129 18580 6129 6131 18581 6131 6134 18582 6134 6132 18583 6132 6131 18584 6131 6134 18585 6134 6131 18586 6131 6133 18587 6133 6136 18588 6136 6134 18589 6134 6133 18590 6133 6136 18591 6136 6133 18592 6133 6135 18593 6135 6137 18594 6137 6136 18595 6136 6135 18596 6135 6139 18597 6139 6137 18598 6137 6135 18599 6135 6139 18600 6139 6135 18601 6135 6138 18602 6138 6141 18603 6141 6139 18604 6139 6138 18605 6138 6141 18606 6141 6138 18607 6138 6140 18608 6140 6144 18609 6144 6141 18610 6141 6140 18611 6140 6144 18612 6144 6140 18613 6140 6142 18614 6142 6144 18615 6144 6142 18616 6142 6143 18617 6143 6145 18618 6145 6144 18619 6144 6143 18620 6143 6148 18621 6148 6145 18622 6145 6143 18623 6143 6148 18624 6148 6143 18625 6143 6146 18626 6146 6148 18627 6148 6146 18628 6146 6147 18629 6147 6150 18630 6150 6148 18631 6148 6147 18632 6147 6150 18633 6150 6147 18634 6147 6149 18635 6149 6152 18636 6152 6150 18637 6150 6149 18638 6149 6152 18639 6152 6149 18640 6149 6151 18641 6151 6154 18642 6154 6152 18643 6152 6151 18644 6151 6154 18645 6154 6151 18646 6151 6153 18647 6153 6155 18648 6155 6154 18649 6154 6153 18650 6153 6157 18651 6157 6155 18652 6155 6153 18653 6153 6157 18654 6157 6153 18655 6153 6156 18656 6156 6124 18657 6124 6157 18658 6157 6156 18659 6156 6191 18660 6191 6159 18661 6159 6158 18662 6158 6162 18663 6162 6161 18664 6161 6160 18665 6160 6163 18666 6163 6162 18667 6162 6160 18668 6160 6165 18669 6165 6163 18670 6163 6160 18671 6160 6165 18672 6165 6160 18673 6160 6164 18674 6164 6167 18675 6167 6165 18676 6165 6164 18677 6164 6167 18678 6167 6164 18679 6164 6166 18680 6166 6169 18681 6169 6167 18682 6167 6166 18683 6166 6169 18684 6169 6166 18685 6166 6168 18686 6168 6171 18687 6171 6169 18688 6169 6168 18689 6168 6171 18690 6171 6168 18691 6168 6170 18692 6170 6174 18693 6174 6171 18694 6171 6170 18695 6170 6174 18696 6174 6170 18697 6170 6172 18698 6172 6174 18699 6174 6172 18700 6172 6173 18701 6173 6175 18702 6175 6174 18703 6174 6173 18704 6173 6177 18705 6177 6175 18706 6175 6173 18707 6173 6177 18708 6177 6173 18709 6173 6176 18710 6176 6179 18711 6179 6177 18712 6177 6176 18713 6176 6179 18714 6179 6176 18715 6176 6178 18716 6178 6181 18717 6181 6179 18718 6179 6178 18719 6178 6181 18720 6181 6178 18721 6178 6180 18722 6180 6184 18723 6184 6181 18724 6181 6180 18725 6180 6184 18726 6184 6180 18727 6180 6182 18728 6182 6184 18729 6184 6182 18730 6182 6183 18731 6183 6186 18732 6186 6184 18733 6184 6183 18734 6183 6186 18735 6186 6183 18736 6183 6185 18737 6185 6188 18738 6188 6186 18739 6186 6185 18740 6185 6188 18741 6188 6185 18742 6185 6187 18743 6187 6190 18744 6190 6188 18745 6188 6187 18746 6187 6190 18747 6190 6187 18748 6187 6189 18749 6189 6158 18750 6158 6190 18751 6190 6189 18752 6189 6158 18753 6158 6189 18754 6189 6191 18755 6191 6224 18756 6224 6192 18757 6192 6195 18758 6195 6192 18759 6192 6194 18760 6194 6193 18761 6193 6192 18762 6192 6193 18763 6193 6195 18764 6195 6199 18765 6199 6197 18766 6197 6196 18767 6196 6199 18768 6199 6196 18769 6196 6198 18770 6198 6201 18771 6201 6199 18772 6199 6198 18773 6198 6201 18774 6201 6198 18775 6198 6200 18776 6200 6204 18777 6204 6201 18778 6201 6200 18779 6200 6204 18780 6204 6200 18781 6200 6202 18782 6202 6204 18783 6204 6202 18784 6202 6203 18785 6203 6205 18786 6205 6204 18787 6204 6203 18788 6203 6207 18789 6207 6205 18790 6205 6203 18791 6203 6207 18792 6207 6203 18793 6203 6206 18794 6206 6209 18795 6209 6207 18796 6207 6206 18797 6206 6209 18798 6209 6206 18799 6206 6208 18800 6208 6211 18801 6211 6209 18802 6209 6208 18803 6208 6211 18804 6211 6208 18805 6208 6210 18806 6210 6213 18807 6213 6211 18808 6211 6210 18809 6210 6213 18810 6213 6210 18811 6210 6212 18812 6212 6215 18813 6215 6213 18814 6213 6212 18815 6212 6215 18816 6215 6212 18817 6212 6214 18818 6214 6217 18819 6217 6215 18820 6215 6214 18821 6214 6217 18822 6217 6214 18823 6214 6216 18824 6216 6219 18825 6219 6217 18826 6217 6216 18827 6216 6219 18828 6219 6216 18829 6216 6218 18830 6218 6221 18831 6221 6219 18832 6219 6218 18833 6218 6221 18834 6221 6218 18835 6218 6220 18836 6220 6223 18837 6223 6221 18838 6221 6220 18839 6220 6223 18840 6223 6220 18841 6220 6222 18842 6222 6225 18843 6225 6223 18844 6223 6222 18845 6222 6225 18846 6225 6222 18847 6222 6224 18848 6224 6195 18849 6195 6225 18850 6225 6224 18851 6224 6258 18852 6258 6226 18853 6226 6232 18854 6232 6229 18855 6229 6228 18856 6228 6227 18857 6227 6230 18858 6230 6229 18859 6229 6227 18860 6227 6233 18861 6233 6230 18862 6230 6227 18863 6227 6233 18864 6233 6227 18865 6227 6231 18866 6231 6233 18867 6233 6231 18868 6231 6232 18869 6232 6226 18870 6226 6233 18871 6233 6232 18872 6232 6238 18873 6238 6235 18874 6235 6234 18875 6234 6238 18876 6238 6234 18877 6234 6236 18878 6236 6238 18879 6238 6236 18880 6236 6237 18881 6237 6239 18882 6239 6238 18883 6238 6237 18884 6237 6242 18885 6242 6239 18886 6239 6237 18887 6237 6242 18888 6242 6237 18889 6237 6240 18890 6240 6242 18891 6242 6240 18892 6240 6241 18893 6241 6244 18894 6244 6242 18895 6242 6241 18896 6241 6244 18897 6244 6241 18898 6241 6243 18899 6243 6245 18900 6245 6244 18901 6244 6243 18902 6243 6247 18903 6247 6245 18904 6245 6243 18905 6243 6247 18906 6247 6243 18907 6243 6246 18908 6246 6249 18909 6249 6247 18910 6247 6246 18911 6246 6249 18912 6249 6246 18913 6246 6248 18914 6248 6251 18915 6251 6249 18916 6249 6248 18917 6248 6251 18918 6251 6248 18919 6248 6250 18920 6250 6253 18921 6253 6251 18922 6251 6250 18923 6250 6253 18924 6253 6250 18925 6250 6252 18926 6252 6255 18927 6255 6253 18928 6253 6252 18929 6252 6255 18930 6255 6252 18931 6252 6254 18932 6254 6257 18933 6257 6255 18934 6255 6254 18935 6254 6257 18936 6257 6254 18937 6254 6256 18938 6256 6259 18939 6259 6257 18940 6257 6256 18941 6256 6259 18942 6259 6256 18943 6256 6258 18944 6258 6232 18945 6232 6259 18946 6259 6258 18947 6258 6292 18948 6292 6260 18949 6260 6265 18950 6265 6264 18951 6264 6262 18952 6262 6261 18953 6261 6264 18954 6264 6261 18955 6261 6263 18956 6263 6260 18957 6260 6264 18958 6264 6263 18959 6263 6260 18960 6260 6263 18961 6263 6265 18962 6265 6269 18963 6269 6267 18964 6267 6266 18965 6266 6269 18966 6269 6266 18967 6266 6268 18968 6268 6271 18969 6271 6269 18970 6269 6268 18971 6268 6271 18972 6271 6268 18973 6268 6270 18974 6270 6274 18975 6274 6271 18976 6271 6270 18977 6270 6274 18978 6274 6270 18979 6270 6272 18980 6272 6274 18981 6274 6272 18982 6272 6273 18983 6273 6275 18984 6275 6274 18985 6274 6273 18986 6273 6277 18987 6277 6275 18988 6275 6273 18989 6273 6277 18990 6277 6273 18991 6273 6276 18992 6276 6279 18993 6279 6277 18994 6277 6276 18995 6276 6279 18996 6279 6276 18997 6276 6278 18998 6278 6282 18999 6282 6279 19000 6279 6278 19001 6278 6282 19002 6282 6278 19003 6278 6280 19004 6280 6282 19005 6282 6280 19006 6280 6281 19007 6281 6284 19008 6284 6282 19009 6282 6281 19010 6281 6284 19011 6284 6281 19012 6281 6283 19013 6283 6286 19014 6286 6284 19015 6284 6283 19016 6283 6286 19017 6286 6283 19018 6283 6285 19019 6285 6288 19020 6288 6286 19021 6286 6285 19022 6285 6288 19023 6288 6285 19024 6285 6287 19025 6287 6289 19026 6289 6288 19027 6288 6287 19028 6287 6291 19029 6291 6289 19030 6289 6287 19031 6287 6291 19032 6291 6287 19033 6287 6290 19034 6290 6293 19035 6293 6291 19036 6291 6290 19037 6290 6293 19038 6293 6290 19039 6290 6292 19040 6292 6265 19041 6265 6293 19042 6293 6292 19043 6292 6325 19044 6325 6294 19045 6294 6295 19046 6295 6297 19047 6297 6296 19048 6296 6295 19049 6295 6294 19050 6294 6297 19051 6297 6295 19052 6295 6302 19053 6302 6299 19054 6299 6298 19055 6298 6302 19056 6302 6298 19057 6298 6300 19058 6300 6302 19059 6302 6300 19060 6300 6301 19061 6301 6304 19062 6304 6302 19063 6302 6301 19064 6301 6304 19065 6304 6301 19066 6301 6303 19067 6303 6306 19068 6306 6304 19069 6304 6303 19070 6303 6306 19071 6306 6303 19072 6303 6305 19073 6305 6308 19074 6308 6306 19075 6306 6305 19076 6305 6308 19077 6308 6305 19078 6305 6307 19079 6307 6310 19080 6310 6308 19081 6308 6307 19082 6307 6310 19083 6310 6307 19084 6307 6309 19085 6309 6311 19086 6311 6310 19087 6310 6309 19088 6309 6313 19089 6313 6311 19090 6311 6309 19091 6309 6313 19092 6313 6309 19093 6309 6312 19094 6312 6315 19095 6315 6313 19096 6313 6312 19097 6312 6315 19098 6315 6312 19099 6312 6314 19100 6314 6317 19101 6317 6315 19102 6315 6314 19103 6314 6317 19104 6317 6314 19105 6314 6316 19106 6316 6319 19107 6319 6317 19108 6317 6316 19109 6316 6319 19110 6319 6316 19111 6316 6318 19112 6318 6321 19113 6321 6319 19114 6319 6318 19115 6318 6321 19116 6321 6318 19117 6318 6320 19118 6320 6323 19119 6323 6321 19120 6321 6320 19121 6320 6323 19122 6323 6320 19123 6320 6322 19124 6322 6326 19125 6326 6323 19126 6323 6322 19127 6322 6326 19128 6326 6322 19129 6322 6324 19130 6324 6326 19131 6326 6324 19132 6324 6325 19133 6325 6327 19134 6327 6326 19135 6326 6325 19136 6325 6295 19137 6295 6327 19138 6327 6325 19139 6325 6359 19140 6359 6328 19141 6328 6331 19142 6331 6328 19143 6328 6330 19144 6330 6329 19145 6329 6328 19146 6328 6329 19147 6329 6331 19148 6331 6336 19149 6336 6333 19150 6333 6332 19151 6332 6336 19152 6336 6332 19153 6332 6334 19154 6334 6336 19155 6336 6334 19156 6334 6335 19157 6335 6337 19158 6337 6336 19159 6336 6335 19160 6335 6339 19161 6339 6337 19162 6337 6335 19163 6335 6339 19164 6339 6335 19165 6335 6338 19166 6338 6341 19167 6341 6339 19168 6339 6338 19169 6338 6341 19170 6341 6338 19171 6338 6340 19172 6340 6343 19173 6343 6341 19174 6341 6340 19175 6340 6343 19176 6343 6340 19177 6340 6342 19178 6342 6346 19179 6346 6343 19180 6343 6342 19181 6342 6346 19182 6346 6342 19183 6342 6344 19184 6344 6346 19185 6346 6344 19186 6344 6345 19187 6345 6347 19188 6347 6346 19189 6346 6345 19190 6345 6349 19191 6349 6347 19192 6347 6345 19193 6345 6349 19194 6349 6345 19195 6345 6348 19196 6348 6352 19197 6352 6349 19198 6349 6348 19199 6348 6352 19200 6352 6348 19201 6348 6350 19202 6350 6352 19203 6352 6350 19204 6350 6351 19205 6351 6353 19206 6353 6352 19207 6352 6351 19208 6351 6355 19209 6355 6353 19210 6353 6351 19211 6351 6355 19212 6355 6351 19213 6351 6354 19214 6354 6357 19215 6357 6355 19216 6355 6354 19217 6354 6357 19218 6357 6354 19219 6354 6356 19220 6356 6360 19221 6360 6357 19222 6357 6356 19223 6356 6360 19224 6360 6356 19225 6356 6358 19226 6358 6360 19227 6360 6358 19228 6358 6359 19229 6359 6361 19230 6361 6360 19231 6360 6359 19232 6359 6331 19233 6331 6361 19234 6361 6359 19235 6359 6394 19236 6394 6362 19237 6362 6363 19238 6363 6365 19239 6365 6364 19240 6364 6363 19241 6363 6362 19242 6362 6365 19243 6365 6363 19244 6363 6370 19245 6370 6367 19246 6367 6366 19247 6366 6370 19248 6370 6366 19249 6366 6368 19250 6368 6370 19251 6370 6368 19252 6368 6369 19253 6369 6371 19254 6371 6370 19255 6370 6369 19256 6369 6374 19257 6374 6371 19258 6371 6369 19259 6369 6374 19260 6374 6369 19261 6369 6372 19262 6372 6374 19263 6374 6372 19264 6372 6373 19265 6373 6375 19266 6375 6374 19267 6374 6373 19268 6373 6377 19269 6377 6375 19270 6375 6373 19271 6373 6377 19272 6377 6373 19273 6373 6376 19274 6376 6380 19275 6380 6377 19276 6377 6376 19277 6376 6380 19278 6380 6376 19279 6376 6378 19280 6378 6380 19281 6380 6378 19282 6378 6379 19283 6379 6381 19284 6381 6380 19285 6380 6379 19286 6379 6383 19287 6383 6381 19288 6381 6379 19289 6379 6383 19290 6383 6379 19291 6379 6382 19292 6382 6385 19293 6385 6383 19294 6383 6382 19295 6382 6385 19296 6385 6382 19297 6382 6384 19298 6384 6387 19299 6387 6385 19300 6385 6384 19301 6384 6387 19302 6387 6384 19303 6384 6386 19304 6386 6389 19305 6389 6387 19306 6387 6386 19307 6386 6389 19308 6389 6386 19309 6386 6388 19310 6388 6392 19311 6392 6389 19312 6389 6388 19313 6388 6392 19314 6392 6388 19315 6388 6390 19316 6390 6392 19317 6392 6390 19318 6390 6391 19319 6391 6393 19320 6393 6392 19321 6392 6391 19322 6391 6395 19323 6395 6393 19324 6393 6391 19325 6391 6395 19326 6395 6391 19327 6391 6394 19328 6394 6363 19329 6363 6395 19330 6395 6394 19331 6394 6428 19332 6428 6396 19333 6396 6405 19334 6405 6399 19335 6399 6398 19336 6398 6397 19337 6397 6401 19338 6401 6399 19339 6399 6397 19340 6397 6401 19341 6401 6397 19342 6397 6400 19343 6400 6402 19344 6402 6401 19345 6401 6400 19346 6400 6404 19347 6404 6402 19348 6402 6400 19349 6400 6404 19350 6404 6400 19351 6400 6403 19352 6403 6396 19353 6396 6404 19354 6404 6403 19355 6403 6396 19356 6396 6403 19357 6403 6405 19358 6405 6409 19359 6409 6407 19360 6407 6406 19361 6406 6409 19362 6409 6406 19363 6406 6408 19364 6408 6411 19365 6411 6409 19366 6409 6408 19367 6408 6411 19368 6411 6408 19369 6408 6410 19370 6410 6413 19371 6413 6411 19372 6411 6410 19373 6410 6413 19374 6413 6410 19375 6410 6412 19376 6412 6416 19377 6416 6413 19378 6413 6412 19379 6412 6416 19380 6416 6412 19381 6412 6414 19382 6414 6416 19383 6416 6414 19384 6414 6415 19385 6415 6417 19386 6417 6416 19387 6416 6415 19388 6415 6419 19389 6419 6417 19390 6417 6415 19391 6415 6419 19392 6419 6415 19393 6415 6418 19394 6418 6421 19395 6421 6419 19396 6419 6418 19397 6418 6421 19398 6421 6418 19399 6418 6420 19400 6420 6423 19401 6423 6421 19402 6421 6420 19403 6420 6423 19404 6423 6420 19405 6420 6422 19406 6422 6425 19407 6425 6423 19408 6423 6422 19409 6422 6425 19410 6425 6422 19411 6422 6424 19412 6424 6427 19413 6427 6425 19414 6425 6424 19415 6424 6427 19416 6427 6424 19417 6424 6426 19418 6426 6429 19419 6429 6427 19420 6427 6426 19421 6426 6429 19422 6429 6426 19423 6426 6428 19424 6428 6405 19425 6405 6429 19426 6429 6428 19427 6428 6461 19428 6461 6430 19429 6430 6431 19430 6431 6433 19431 6433 6432 19432 6432 6431 19433 6431 6430 19434 6430 6433 19435 6433 6431 19436 6431 6438 19437 6438 6435 19438 6435 6434 19439 6434 6438 19440 6438 6434 19441 6434 6436 19442 6436 6438 19443 6438 6436 19444 6436 6437 19445 6437 6440 19446 6440 6438 19447 6438 6437 19448 6437 6440 19449 6440 6437 19450 6437 6439 19451 6439 6442 19452 6442 6440 19453 6440 6439 19454 6439 6442 19455 6442 6439 19456 6439 6441 19457 6441 6444 19458 6444 6442 19459 6442 6441 19460 6441 6444 19461 6444 6441 19462 6441 6443 19463 6443 6446 19464 6446 6444 19465 6444 6443 19466 6443 6446 19467 6446 6443 19468 6443 6445 19469 6445 6447 19470 6447 6446 19471 6446 6445 19472 6445 6449 19473 6449 6447 19474 6447 6445 19475 6445 6449 19476 6449 6445 19477 6445 6448 19478 6448 6451 19479 6451 6449 19480 6449 6448 19481 6448 6451 19482 6451 6448 19483 6448 6450 19484 6450 6454 19485 6454 6451 19486 6451 6450 19487 6450 6454 19488 6454 6450 19489 6450 6452 19490 6452 6454 19491 6454 6452 19492 6452 6453 19493 6453 6455 19494 6455 6454 19495 6454 6453 19496 6453 6457 19497 6457 6455 19498 6455 6453 19499 6453 6457 19500 6457 6453 19501 6453 6456 19502 6456 6459 19503 6459 6457 19504 6457 6456 19505 6456 6459 19506 6459 6456 19507 6456 6458 19508 6458 6462 19509 6462 6459 19510 6459 6458 19511 6458 6462 19512 6462 6458 19513 6458 6460 19514 6460 6462 19515 6462 6460 19516 6460 6461 19517 6461 6463 19518 6463 6462 19519 6462 6461 19520 6461 6431 19521 6431 6463 19522 6463 6461 19523 6461 6497 19524 6497 6469 19525 6469 6464 19526 6464 6467 19527 6467 6466 19528 6466 6465 19529 6465 6468 19530 6468 6467 19531 6467 6465 19532 6465 6497 19533 6497 6468 19534 6468 6465 19535 6465 6497 19536 6497 6465 19537 6465 6469 19538 6469 6472 19539 6472 6471 19540 6471 6470 19541 6470 6474 19542 6474 6472 19543 6472 6470 19544 6470 6474 19545 6474 6470 19546 6470 6473 19547 6473 6475 19548 6475 6474 19549 6474 6473 19550 6473 6478 19551 6478 6475 19552 6475 6473 19553 6473 6478 19554 6478 6473 19555 6473 6476 19556 6476 6478 19557 6478 6476 19558 6476 6477 19559 6477 6479 19560 6479 6478 19561 6478 6477 19562 6477 6481 19563 6481 6479 19564 6479 6477 19565 6477 6481 19566 6481 6477 19567 6477 6480 19568 6480 6483 19569 6483 6481 19570 6481 6480 19571 6480 6483 19572 6483 6480 19573 6480 6482 19574 6482 6485 19575 6485 6483 19576 6483 6482 19577 6482 6485 19578 6485 6482 19579 6482 6484 19580 6484 6487 19581 6487 6485 19582 6485 6484 19583 6484 6487 19584 6487 6484 19585 6484 6486 19586 6486 6489 19587 6489 6487 19588 6487 6486 19589 6486 6489 19590 6489 6486 19591 6486 6488 19592 6488 6491 19593 6491 6489 19594 6489 6488 19595 6488 6491 19596 6491 6488 19597 6488 6490 19598 6490 6493 19599 6493 6491 19600 6491 6490 19601 6490 6493 19602 6493 6490 19603 6490 6492 19604 6492 6496 19605 6496 6493 19606 6493 6492 19607 6492 6496 19608 6496 6492 19609 6492 6494 19610 6494 6496 19611 6496 6494 19612 6494 6495 19613 6495 6464 19614 6464 6496 19615 6496 6495 19616 6495 6464 19617 6464 6495 19618 6495 6497 19619 6497 6531 19620 6531 6503 19621 6503 6498 19622 6498 6501 19623 6501 6500 19624 6500 6499 19625 6499 6502 19626 6502 6501 19627 6501 6499 19628 6499 6531 19629 6531 6502 19630 6502 6499 19631 6499 6531 19632 6531 6499 19633 6499 6503 19634 6503 6508 19635 6508 6505 19636 6505 6504 19637 6504 6508 19638 6508 6504 19639 6504 6506 19640 6506 6508 19641 6508 6506 19642 6506 6507 19643 6507 6510 19644 6510 6508 19645 6508 6507 19646 6507 6510 19647 6510 6507 19648 6507 6509 19649 6509 6512 19650 6512 6510 19651 6510 6509 19652 6509 6512 19653 6512 6509 19654 6509 6511 19655 6511 6514 19656 6514 6512 19657 6512 6511 19658 6511 6514 19659 6514 6511 19660 6511 6513 19661 6513 6515 19662 6515 6514 19663 6514 6513 19664 6513 6517 19665 6517 6515 19666 6515 6513 19667 6513 6517 19668 6517 6513 19669 6513 6516 19670 6516 6520 19671 6520 6517 19672 6517 6516 19673 6516 6520 19674 6520 6516 19675 6516 6518 19676 6518 6520 19677 6520 6518 19678 6518 6519 19679 6519 6522 19680 6522 6520 19681 6520 6519 19682 6519 6522 19683 6522 6519 19684 6519 6521 19685 6521 6524 19686 6524 6522 19687 6522 6521 19688 6521 6524 19689 6524 6521 19690 6521 6523 19691 6523 6526 19692 6526 6524 19693 6524 6523 19694 6523 6526 19695 6526 6523 19696 6523 6525 19697 6525 6527 19698 6527 6526 19699 6526 6525 19700 6525 6529 19701 6529 6527 19702 6527 6525 19703 6525 6529 19704 6529 6525 19705 6525 6528 19706 6528 6498 19707 6498 6529 19708 6529 6528 19709 6528 6498 19710 6498 6528 19711 6528 6530 19712 6530 6498 19713 6498 6530 19714 6530 6531 19715 6531 6564 19716 6564 6532 19717 6532 6546 19718 6546 6535 19719 6535 6534 19720 6534 6533 19721 6533 6536 19722 6536 6535 19723 6535 6533 19724 6533 6539 19725 6539 6536 19726 6536 6533 19727 6533 6539 19728 6539 6533 19729 6533 6537 19730 6537 6539 19731 6539 6537 19732 6537 6538 19733 6538 6540 19734 6540 6539 19735 6539 6538 19736 6538 6542 19737 6542 6540 19738 6540 6538 19739 6538 6542 19740 6542 6538 19741 6538 6541 19742 6541 6545 19743 6545 6542 19744 6542 6541 19745 6541 6545 19746 6545 6541 19747 6541 6543 19748 6543 6545 19749 6545 6543 19750 6543 6544 19751 6544 6547 19752 6547 6545 19753 6545 6544 19754 6544 6547 19755 6547 6544 19756 6544 6546 19757 6546 6532 19758 6532 6547 19759 6547 6546 19760 6546 6551 19761 6551 6549 19762 6549 6548 19763 6548 6551 19764 6551 6548 19765 6548 6550 19766 6550 6553 19767 6553 6551 19768 6551 6550 19769 6550 6553 19770 6553 6550 19771 6550 6552 19772 6552 6555 19773 6555 6553 19774 6553 6552 19775 6552 6555 19776 6555 6552 19777 6552 6554 19778 6554 6558 19779 6558 6555 19780 6555 6554 19781 6554 6558 19782 6558 6554 19783 6554 6556 19784 6556 6558 19785 6558 6556 19786 6556 6557 19787 6557 6559 19788 6559 6558 19789 6558 6557 19790 6557 6561 19791 6561 6559 19792 6559 6557 19793 6557 6561 19794 6561 6557 19795 6557 6560 19796 6560 6563 19797 6563 6561 19798 6561 6560 19799 6560 6563 19800 6563 6560 19801 6560 6562 19802 6562 6565 19803 6565 6563 19804 6563 6562 19805 6562 6565 19806 6565 6562 19807 6562 6564 19808 6564 6546 19809 6546 6565 19810 6565 6564 19811 6564 6598 19812 6598 6566 19813 6566 6570 19814 6570 6569 19815 6569 6568 19816 6568 6567 19817 6567 6571 19818 6571 6569 19819 6569 6567 19820 6567 6571 19821 6571 6567 19822 6567 6570 19823 6570 6566 19824 6566 6571 19825 6571 6570 19826 6570 6575 19827 6575 6573 19828 6573 6572 19829 6572 6575 19830 6575 6572 19831 6572 6574 19832 6574 6577 19833 6577 6575 19834 6575 6574 19835 6574 6577 19836 6577 6574 19837 6574 6576 19838 6576 6579 19839 6579 6577 19840 6577 6576 19841 6576 6579 19842 6579 6576 19843 6576 6578 19844 6578 6582 19845 6582 6579 19846 6579 6578 19847 6578 6582 19848 6582 6578 19849 6578 6580 19850 6580 6582 19851 6582 6580 19852 6580 6581 19853 6581 6583 19854 6583 6582 19855 6582 6581 19856 6581 6585 19857 6585 6583 19858 6583 6581 19859 6581 6585 19860 6585 6581 19861 6581 6584 19862 6584 6587 19863 6587 6585 19864 6585 6584 19865 6584 6587 19866 6587 6584 19867 6584 6586 19868 6586 6589 19869 6589 6587 19870 6587 6586 19871 6586 6589 19872 6589 6586 19873 6586 6588 19874 6588 6592 19875 6592 6589 19876 6589 6588 19877 6588 6592 19878 6592 6588 19879 6588 6590 19880 6590 6592 19881 6592 6590 19882 6590 6591 19883 6591 6593 19884 6593 6592 19885 6592 6591 19886 6591 6596 19887 6596 6593 19888 6593 6591 19889 6591 6596 19890 6596 6591 19891 6591 6594 19892 6594 6596 19893 6596 6594 19894 6594 6595 19895 6595 6597 19896 6597 6596 19897 6596 6595 19898 6595 6599 19899 6599 6597 19900 6597 6595 19901 6595 6599 19902 6599 6595 19903 6595 6598 19904 6598 6570 19905 6570 6599 19906 6599 6598 19907 6598 6631 19908 6631 6601 19909 6601 6600 19910 6600 6604 19911 6604 6603 19912 6603 6602 19913 6602 6606 19914 6606 6604 19915 6604 6602 19916 6602 6606 19917 6606 6602 19918 6602 6605 19919 6605 6608 19920 6608 6606 19921 6606 6605 19922 6605 6608 19923 6608 6605 19924 6605 6607 19925 6607 6610 19926 6610 6608 19927 6608 6607 19928 6607 6610 19929 6610 6607 19930 6607 6609 19931 6609 6611 19932 6611 6610 19933 6610 6609 19934 6609 6613 19935 6613 6611 19936 6611 6609 19937 6609 6613 19938 6613 6609 19939 6609 6612 19940 6612 6615 19941 6615 6613 19942 6613 6612 19943 6612 6615 19944 6615 6612 19945 6612 6614 19946 6614 6617 19947 6617 6615 19948 6615 6614 19949 6614 6617 19950 6617 6614 19951 6614 6616 19952 6616 6619 19953 6619 6617 19954 6617 6616 19955 6616 6619 19956 6619 6616 19957 6616 6618 19958 6618 6621 19959 6621 6619 19960 6619 6618 19961 6618 6621 19962 6621 6618 19963 6618 6620 19964 6620 6623 19965 6623 6621 19966 6621 6620 19967 6620 6623 19968 6623 6620 19969 6620 6622 19970 6622 6625 19971 6625 6623 19972 6623 6622 19973 6622 6625 19974 6625 6622 19975 6622 6624 19976 6624 6628 19977 6628 6625 19978 6625 6624 19979 6624 6628 19980 6628 6624 19981 6624 6626 19982 6626 6628 19983 6628 6626 19984 6626 6627 19985 6627 6629 19986 6629 6628 19987 6628 6627 19988 6627 6632 19989 6632 6629 19990 6629 6627 19991 6627 6632 19992 6632 6627 19993 6627 6630 19994 6630 6632 19995 6632 6630 19996 6630 6631 19997 6631 6633 19998 6633 6632 19999 6632 6631 20000 6631 6600 20001 6600 6633 20002 6633 6631 20003 6631 6667 20004 6667 6635 20005 6635 6634 20006 6634 6639 20007 6639 6637 20008 6637 6636 20009 6636 6639 20010 6639 6636 20011 6636 6638 20012 6638 6641 20013 6641 6639 20014 6639 6638 20015 6638 6641 20016 6641 6638 20017 6638 6640 20018 6640 6643 20019 6643 6641 20020 6641 6640 20021 6640 6643 20022 6643 6640 20023 6640 6642 20024 6642 6646 20025 6646 6643 20026 6643 6642 20027 6642 6646 20028 6646 6642 20029 6642 6644 20030 6644 6646 20031 6646 6644 20032 6644 6645 20033 6645 6647 20034 6647 6646 20035 6646 6645 20036 6645 6649 20037 6649 6647 20038 6647 6645 20039 6645 6649 20040 6649 6645 20041 6645 6648 20042 6648 6651 20043 6651 6649 20044 6649 6648 20045 6648 6651 20046 6651 6648 20047 6648 6650 20048 6650 6654 20049 6654 6651 20050 6651 6650 20051 6650 6654 20052 6654 6650 20053 6650 6652 20054 6652 6654 20055 6654 6652 20056 6652 6653 20057 6653 6656 20058 6656 6654 20059 6654 6653 20060 6653 6656 20061 6656 6653 20062 6653 6655 20063 6655 6658 20064 6658 6656 20065 6656 6655 20066 6655 6658 20067 6658 6655 20068 6655 6657 20069 6657 6660 20070 6660 6658 20071 6658 6657 20072 6657 6660 20073 6660 6657 20074 6657 6659 20075 6659 6661 20076 6661 6660 20077 6660 6659 20078 6659 6663 20079 6663 6661 20080 6661 6659 20081 6659 6663 20082 6663 6659 20083 6659 6662 20084 6662 6665 20085 6665 6663 20086 6663 6662 20087 6662 6665 20088 6665 6662 20089 6662 6664 20090 6664 6634 20091 6634 6665 20092 6665 6664 20093 6664 6634 20094 6634 6664 20095 6664 6666 20096 6666 6634 20097 6634 6666 20098 6666 6667 20099 6667 6699 20100 6699 6669 20101 6669 6668 20102 6668 6672 20103 6672 6671 20104 6671 6670 20105 6670 6673 20106 6673 6672 20107 6672 6670 20108 6670 6676 20109 6676 6673 20110 6673 6670 20111 6670 6676 20112 6676 6670 20113 6670 6674 20114 6674 6676 20115 6676 6674 20116 6674 6675 20117 6675 6678 20118 6678 6676 20119 6676 6675 20120 6675 6678 20121 6678 6675 20122 6675 6677 20123 6677 6679 20124 6679 6678 20125 6678 6677 20126 6677 6682 20127 6682 6679 20128 6679 6677 20129 6677 6682 20130 6682 6677 20131 6677 6680 20132 6680 6682 20133 6682 6680 20134 6680 6681 20135 6681 6683 20136 6683 6682 20137 6682 6681 20138 6681 6685 20139 6685 6683 20140 6683 6681 20141 6681 6685 20142 6685 6681 20143 6681 6684 20144 6684 6688 20145 6688 6685 20146 6685 6684 20147 6684 6688 20148 6688 6684 20149 6684 6686 20150 6686 6688 20151 6688 6686 20152 6686 6687 20153 6687 6689 20154 6689 6688 20155 6688 6687 20156 6687 6692 20157 6692 6689 20158 6689 6687 20159 6687 6692 20160 6692 6687 20161 6687 6690 20162 6690 6692 20163 6692 6690 20164 6690 6691 20165 6691 6693 20166 6693 6692 20167 6692 6691 20168 6691 6695 20169 6695 6693 20170 6693 6691 20171 6691 6695 20172 6695 6691 20173 6691 6694 20174 6694 6697 20175 6697 6695 20176 6695 6694 20177 6694 6697 20178 6697 6694 20179 6694 6696 20180 6696 6700 20181 6700 6697 20182 6697 6696 20183 6696 6700 20184 6700 6696 20185 6696 6698 20186 6698 6700 20187 6700 6698 20188 6698 6699 20189 6699 6701 20190 6701 6700 20191 6700 6699 20192 6699 6668 20193 6668 6701 20194 6701 6699 20195 6699 6734 20196 6734 6703 20197 6703 6702 20198 6702 6707 20199 6707 6705 20200 6705 6704 20201 6704 6707 20202 6707 6704 20203 6704 6706 20204 6706 6709 20205 6709 6707 20206 6707 6706 20207 6706 6709 20208 6709 6706 20209 6706 6708 20210 6708 6712 20211 6712 6709 20212 6709 6708 20213 6708 6712 20214 6712 6708 20215 6708 6710 20216 6710 6712 20217 6712 6710 20218 6710 6711 20219 6711 6713 20220 6713 6712 20221 6712 6711 20222 6711 6715 20223 6715 6713 20224 6713 6711 20225 6711 6715 20226 6715 6711 20227 6711 6714 20228 6714 6718 20229 6718 6715 20230 6715 6714 20231 6714 6718 20232 6718 6714 20233 6714 6716 20234 6716 6718 20235 6718 6716 20236 6716 6717 20237 6717 6720 20238 6720 6718 20239 6718 6717 20240 6717 6720 20241 6720 6717 20242 6717 6719 20243 6719 6722 20244 6722 6720 20245 6720 6719 20246 6719 6722 20247 6722 6719 20248 6719 6721 20249 6721 6724 20250 6724 6722 20251 6722 6721 20252 6721 6724 20253 6724 6721 20254 6721 6723 20255 6723 6725 20256 6725 6724 20257 6724 6723 20258 6723 6728 20259 6728 6725 20260 6725 6723 20261 6723 6728 20262 6728 6723 20263 6723 6726 20264 6726 6728 20265 6728 6726 20266 6726 6727 20267 6727 6729 20268 6729 6728 20269 6728 6727 20270 6727 6731 20271 6731 6729 20272 6729 6727 20273 6727 6731 20274 6731 6727 20275 6727 6730 20276 6730 6733 20277 6733 6731 20278 6731 6730 20279 6730 6733 20280 6733 6730 20281 6730 6732 20282 6732 6735 20283 6735 6733 20284 6733 6732 20285 6732 6735 20286 6735 6732 20287 6732 6734 20288 6734 6702 20289 6702 6735 20290 6735 6734 20291 6734 6767 20292 6767 6737 20293 6737 6736 20294 6736 6740 20295 6740 6739 20296 6739 6738 20297 6738 6741 20298 6741 6740 20299 6740 6738 20300 6738 6744 20301 6744 6741 20302 6741 6738 20303 6738 6744 20304 6744 6738 20305 6738 6742 20306 6742 6744 20307 6744 6742 20308 6742 6743 20309 6743 6746 20310 6746 6744 20311 6744 6743 20312 6743 6746 20313 6746 6743 20314 6743 6745 20315 6745 6747 20316 6747 6746 20317 6746 6745 20318 6745 6750 20319 6750 6747 20320 6747 6745 20321 6745 6750 20322 6750 6745 20323 6745 6748 20324 6748 6750 20325 6750 6748 20326 6748 6749 20327 6749 6751 20328 6751 6750 20329 6750 6749 20330 6749 6753 20331 6753 6751 20332 6751 6749 20333 6749 6753 20334 6753 6749 20335 6749 6752 20336 6752 6755 20337 6755 6753 20338 6753 6752 20339 6752 6755 20340 6755 6752 20341 6752 6754 20342 6754 6757 20343 6757 6755 20344 6755 6754 20345 6754 6757 20346 6757 6754 20347 6754 6756 20348 6756 6759 20349 6759 6757 20350 6757 6756 20351 6756 6759 20352 6759 6756 20353 6756 6758 20354 6758 6761 20355 6761 6759 20356 6759 6758 20357 6758 6761 20358 6761 6758 20359 6758 6760 20360 6760 6763 20361 6763 6761 20362 6761 6760 20363 6760 6763 20364 6763 6760 20365 6760 6762 20366 6762 6765 20367 6765 6763 20368 6763 6762 20369 6762 6765 20370 6765 6762 20371 6762 6764 20372 6764 6768 20373 6768 6765 20374 6765 6764 20375 6764 6768 20376 6768 6764 20377 6764 6766 20378 6766 6768 20379 6768 6766 20380 6766 6767 20381 6767 6769 20382 6769 6768 20383 6768 6767 20384 6767 6736 20385 6736 6769 20386 6769 6767 20387 6767 6802 20388 6802 6771 20389 6771 6770 20390 6770 6776 20391 6776 6773 20392 6773 6772 20393 6772 6776 20394 6776 6772 20395 6772 6774 20396 6774 6776 20397 6776 6774 20398 6774 6775 20399 6775 6777 20400 6777 6776 20401 6776 6775 20402 6775 6780 20403 6780 6777 20404 6777 6775 20405 6775 6780 20406 6780 6775 20407 6775 6778 20408 6778 6780 20409 6780 6778 20410 6778 6779 20411 6779 6781 20412 6781 6780 20413 6780 6779 20414 6779 6783 20415 6783 6781 20416 6781 6779 20417 6779 6783 20418 6783 6779 20419 6779 6782 20420 6782 6786 20421 6786 6783 20422 6783 6782 20423 6782 6786 20424 6786 6782 20425 6782 6784 20426 6784 6786 20427 6786 6784 20428 6784 6785 20429 6785 6787 20430 6787 6786 20431 6786 6785 20432 6785 6789 20433 6789 6787 20434 6787 6785 20435 6785 6789 20436 6789 6785 20437 6785 6788 20438 6788 6792 20439 6792 6789 20440 6789 6788 20441 6788 6792 20442 6792 6788 20443 6788 6790 20444 6790 6792 20445 6792 6790 20446 6790 6791 20447 6791 6793 20448 6793 6792 20449 6792 6791 20450 6791 6796 20451 6796 6793 20452 6793 6791 20453 6791 6796 20454 6796 6791 20455 6791 6794 20456 6794 6796 20457 6796 6794 20458 6794 6795 20459 6795 6797 20460 6797 6796 20461 6796 6795 20462 6795 6799 20463 6799 6797 20464 6797 6795 20465 6795 6799 20466 6799 6795 20467 6795 6798 20468 6798 6801 20469 6801 6799 20470 6799 6798 20471 6798 6801 20472 6801 6798 20473 6798 6800 20474 6800 6803 20475 6803 6801 20476 6801 6800 20477 6800 6803 20478 6803 6800 20479 6800 6802 20480 6802 6770 20481 6770 6803 20482 6803 6802 20483 6802 6836 20484 6836 6805 20485 6805 6804 20486 6804 6810 20487 6810 6807 20488 6807 6806 20489 6806 6810 20490 6810 6806 20491 6806 6808 20492 6808 6810 20493 6810 6808 20494 6808 6809 20495 6809 6812 20496 6812 6810 20497 6810 6809 20498 6809 6812 20499 6812 6809 20500 6809 6811 20501 6811 6813 20502 6813 6812 20503 6812 6811 20504 6811 6815 20505 6815 6813 20506 6813 6811 20507 6811 6815 20508 6815 6811 20509 6811 6814 20510 6814 6817 20511 6817 6815 20512 6815 6814 20513 6814 6817 20514 6817 6814 20515 6814 6816 20516 6816 6819 20517 6819 6817 20518 6817 6816 20519 6816 6819 20520 6819 6816 20521 6816 6818 20522 6818 6821 20523 6821 6819 20524 6819 6818 20525 6818 6821 20526 6821 6818 20527 6818 6820 20528 6820 6823 20529 6823 6821 20530 6821 6820 20531 6820 6823 20532 6823 6820 20533 6820 6822 20534 6822 6825 20535 6825 6823 20536 6823 6822 20537 6822 6825 20538 6825 6822 20539 6822 6824 20540 6824 6827 20541 6827 6825 20542 6825 6824 20543 6824 6827 20544 6827 6824 20545 6824 6826 20546 6826 6830 20547 6830 6827 20548 6827 6826 20549 6826 6830 20550 6830 6826 20551 6826 6828 20552 6828 6830 20553 6830 6828 20554 6828 6829 20555 6829 6831 20556 6831 6830 20557 6830 6829 20558 6829 6833 20559 6833 6831 20560 6831 6829 20561 6829 6833 20562 6833 6829 20563 6829 6832 20564 6832 6835 20565 6835 6833 20566 6833 6832 20567 6832 6835 20568 6835 6832 20569 6832 6834 20570 6834 6837 20571 6837 6835 20572 6835 6834 20573 6834 6837 20574 6837 6834 20575 6834 6836 20576 6836 6804 20577 6804 6837 20578 6837 6836 20579 6836 6869 20580 6869 6839 20581 6839 6838 20582 6838 6844 20583 6844 6841 20584 6841 6840 20585 6840 6844 20586 6844 6840 20587 6840 6842 20588 6842 6844 20589 6844 6842 20590 6842 6843 20591 6843 6845 20592 6845 6844 20593 6844 6843 20594 6843 6847 20595 6847 6845 20596 6845 6843 20597 6843 6847 20598 6847 6843 20599 6843 6846 20600 6846 6849 20601 6849 6847 20602 6847 6846 20603 6846 6849 20604 6849 6846 20605 6846 6848 20606 6848 6851 20607 6851 6849 20608 6849 6848 20609 6848 6851 20610 6851 6848 20611 6848 6850 20612 6850 6853 20613 6853 6851 20614 6851 6850 20615 6850 6853 20616 6853 6850 20617 6850 6852 20618 6852 6855 20619 6855 6853 20620 6853 6852 20621 6852 6855 20622 6855 6852 20623 6852 6854 20624 6854 6857 20625 6857 6855 20626 6855 6854 20627 6854 6857 20628 6857 6854 20629 6854 6856 20630 6856 6859 20631 6859 6857 20632 6857 6856 20633 6856 6859 20634 6859 6856 20635 6856 6858 20636 6858 6861 20637 6861 6859 20638 6859 6858 20639 6858 6861 20640 6861 6858 20641 6858 6860 20642 6860 6863 20643 6863 6861 20644 6861 6860 20645 6860 6863 20646 6863 6860 20647 6860 6862 20648 6862 6865 20649 6865 6863 20650 6863 6862 20651 6862 6865 20652 6865 6862 20653 6862 6864 20654 6864 6868 20655 6868 6865 20656 6865 6864 20657 6864 6868 20658 6868 6864 20659 6864 6866 20660 6866 6868 20661 6868 6866 20662 6866 6867 20663 6867 6870 20664 6870 6868 20665 6868 6867 20666 6867 6870 20667 6870 6867 20668 6867 6869 20669 6869 6871 20670 6871 6870 20671 6870 6869 20672 6869 6838 20673 6838 6871 20674 6871 6869 20675 6869 6904 20676 6904 6873 20677 6873 6872 20678 6872 6876 20679 6876 6875 20680 6875 6874 20681 6874 6877 20682 6877 6876 20683 6876 6874 20684 6874 6879 20685 6879 6877 20686 6877 6874 20687 6874 6879 20688 6879 6874 20689 6874 6878 20690 6878 6881 20691 6881 6879 20692 6879 6878 20693 6878 6881 20694 6881 6878 20695 6878 6880 20696 6880 6883 20697 6883 6881 20698 6881 6880 20699 6880 6883 20700 6883 6880 20701 6880 6882 20702 6882 6885 20703 6885 6883 20704 6883 6882 20705 6882 6885 20706 6885 6882 20707 6882 6884 20708 6884 6887 20709 6887 6885 20710 6885 6884 20711 6884 6887 20712 6887 6884 20713 6884 6886 20714 6886 6889 20715 6889 6887 20716 6887 6886 20717 6886 6889 20718 6889 6886 20719 6886 6888 20720 6888 6891 20721 6891 6889 20722 6889 6888 20723 6888 6891 20724 6891 6888 20725 6888 6890 20726 6890 6893 20727 6893 6891 20728 6891 6890 20729 6890 6893 20730 6893 6890 20731 6890 6892 20732 6892 6895 20733 6895 6893 20734 6893 6892 20735 6892 6895 20736 6895 6892 20737 6892 6894 20738 6894 6898 20739 6898 6895 20740 6895 6894 20741 6894 6898 20742 6898 6894 20743 6894 6896 20744 6896 6898 20745 6898 6896 20746 6896 6897 20747 6897 6899 20748 6899 6898 20749 6898 6897 20750 6897 6901 20751 6901 6899 20752 6899 6897 20753 6897 6901 20754 6901 6897 20755 6897 6900 20756 6900 6903 20757 6903 6901 20758 6901 6900 20759 6900 6903 20760 6903 6900 20761 6900 6902 20762 6902 6905 20763 6905 6903 20764 6903 6902 20765 6902 6905 20766 6905 6902 20767 6902 6904 20768 6904 6872 20769 6872 6905 20770 6905 6904 20771 6904 6938 20772 6938 6906 20773 6906 6919 20774 6919 6909 20775 6909 6908 20776 6908 6907 20777 6907 6911 20778 6911 6909 20779 6909 6907 20780 6907 6911 20781 6911 6907 20782 6907 6910 20783 6910 6913 20784 6913 6911 20785 6911 6910 20786 6910 6913 20787 6913 6910 20788 6910 6912 20789 6912 6915 20790 6915 6913 20791 6913 6912 20792 6912 6915 20793 6915 6912 20794 6912 6914 20795 6914 6916 20796 6916 6915 20797 6915 6914 20798 6914 6918 20799 6918 6916 20800 6916 6914 20801 6914 6918 20802 6918 6914 20803 6914 6917 20804 6917 6906 20805 6906 6918 20806 6918 6917 20807 6917 6906 20808 6906 6917 20809 6917 6919 20810 6919 6922 20811 6922 6921 20812 6921 6920 20813 6920 6923 20814 6923 6922 20815 6922 6920 20816 6920 6926 20817 6926 6923 20818 6923 6920 20819 6920 6926 20820 6926 6920 20821 6920 6924 20822 6924 6926 20823 6926 6924 20824 6924 6925 20825 6925 6927 20826 6927 6926 20827 6926 6925 20828 6925 6930 20829 6930 6927 20830 6927 6925 20831 6925 6930 20832 6930 6925 20833 6925 6928 20834 6928 6930 20835 6930 6928 20836 6928 6929 20837 6929 6931 20838 6931 6930 20839 6930 6929 20840 6929 6933 20841 6933 6931 20842 6931 6929 20843 6929 6933 20844 6933 6929 20845 6929 6932 20846 6932 6935 20847 6935 6933 20848 6933 6932 20849 6932 6935 20850 6935 6932 20851 6932 6934 20852 6934 6937 20853 6937 6935 20854 6935 6934 20855 6934 6937 20856 6937 6934 20857 6934 6936 20858 6936 6939 20859 6939 6937 20860 6937 6936 20861 6936 6939 20862 6939 6936 20863 6936 6938 20864 6938 6919 20865 6919 6939 20866 6939 6938 20867 6938 6972 20868 6972 6941 20869 6941 6940 20870 6940 6946 20871 6946 6943 20872 6943 6942 20873 6942 6946 20874 6946 6942 20875 6942 6944 20876 6944 6946 20877 6946 6944 20878 6944 6945 20879 6945 6947 20880 6947 6946 20881 6946 6945 20882 6945 6950 20883 6950 6947 20884 6947 6945 20885 6945 6950 20886 6950 6945 20887 6945 6948 20888 6948 6950 20889 6950 6948 20890 6948 6949 20891 6949 6952 20892 6952 6950 20893 6950 6949 20894 6949 6952 20895 6952 6949 20896 6949 6951 20897 6951 6953 20898 6953 6952 20899 6952 6951 20900 6951 6955 20901 6955 6953 20902 6953 6951 20903 6951 6955 20904 6955 6951 20905 6951 6954 20906 6954 6958 20907 6958 6955 20908 6955 6954 20909 6954 6958 20910 6958 6954 20911 6954 6956 20912 6956 6958 20913 6958 6956 20914 6956 6957 20915 6957 6960 20916 6960 6958 20917 6958 6957 20918 6957 6960 20919 6960 6957 20920 6957 6959 20921 6959 6961 20922 6961 6960 20923 6960 6959 20924 6959 6964 20925 6964 6961 20926 6961 6959 20927 6959 6964 20928 6964 6959 20929 6959 6962 20930 6962 6964 20931 6964 6962 20932 6962 6963 20933 6963 6966 20934 6966 6964 20935 6964 6963 20936 6963 6966 20937 6966 6963 20938 6963 6965 20939 6965 6967 20940 6967 6966 20941 6966 6965 20942 6965 6969 20943 6969 6967 20944 6967 6965 20945 6965 6969 20946 6969 6965 20947 6965 6968 20948 6968 6971 20949 6971 6969 20950 6969 6968 20951 6968 6971 20952 6971 6968 20953 6968 6970 20954 6970 6973 20955 6973 6971 20956 6971 6970 20957 6970 6973 20958 6973 6970 20959 6970 6972 20960 6972 6940 20961 6940 6973 20962 6973 6972 20963 6972 7006 20964 7006 6975 20965 6975 6974 20966 6974 6978 20967 6978 6977 20968 6977 6976 20969 6976 6980 20970 6980 6978 20971 6978 6976 20972 6976 6980 20973 6980 6976 20974 6976 6979 20975 6979 6982 20976 6982 6980 20977 6980 6979 20978 6979 6982 20979 6982 6979 20980 6979 6981 20981 6981 6983 20982 6983 6982 20983 6982 6981 20984 6981 6986 20985 6986 6983 20986 6983 6981 20987 6981 6986 20988 6986 6981 20989 6981 6984 20990 6984 6986 20991 6986 6984 20992 6984 6985 20993 6985 6988 20994 6988 6986 20995 6986 6985 20996 6985 6988 20997 6988 6985 20998 6985 6987 20999 6987 6990 21000 6990 6988 21001 6988 6987 21002 6987 6990 21003 6990 6987 21004 6987 6989 21005 6989 6991 21006 6991 6990 21007 6990 6989 21008 6989 6993 21009 6993 6991 21010 6991 6989 21011 6989 6993 21012 6993 6989 21013 6989 6992 21014 6992 6996 21015 6996 6993 21016 6993 6992 21017 6992 6996 21018 6996 6992 21019 6992 6994 21020 6994 6996 21021 6996 6994 21022 6994 6995 21023 6995 6997 21024 6997 6996 21025 6996 6995 21026 6995 6999 21027 6999 6997 21028 6997 6995 21029 6995 6999 21030 6999 6995 21031 6995 6998 21032 6998 7001 21033 7001 6999 21034 6999 6998 21035 6998 7001 21036 7001 6998 21037 6998 7000 21038 7000 7004 21039 7004 7001 21040 7001 7000 21041 7000 7004 21042 7004 7000 21043 7000 7002 21044 7002 7004 21045 7004 7002 21046 7002 7003 21047 7003 7005 21048 7005 7004 21049 7004 7003 21050 7003 7007 21051 7007 7005 21052 7005 7003 21053 7003 7007 21054 7007 7003 21055 7003 7006 21056 7006 6974 21057 6974 7007 21058 7007 7006 21059 7006 7040 21060 7040 7009 21061 7009 7008 21062 7008 7012 21063 7012 7011 21064 7011 7010 21065 7010 7014 21066 7014 7012 21067 7012 7010 21068 7010 7014 21069 7014 7010 21070 7010 7013 21071 7013 7015 21072 7015 7014 21073 7014 7013 21074 7013 7018 21075 7018 7015 21076 7015 7013 21077 7013 7018 21078 7018 7013 21079 7013 7016 21080 7016 7018 21081 7018 7016 21082 7016 7017 21083 7017 7020 21084 7020 7018 21085 7018 7017 21086 7017 7020 21087 7020 7017 21088 7017 7019 21089 7019 7021 21090 7021 7020 21091 7020 7019 21092 7019 7023 21093 7023 7021 21094 7021 7019 21095 7019 7023 21096 7023 7019 21097 7019 7022 21098 7022 7025 21099 7025 7023 21100 7023 7022 21101 7022 7025 21102 7025 7022 21103 7022 7024 21104 7024 7027 21105 7027 7025 21106 7025 7024 21107 7024 7027 21108 7027 7024 21109 7024 7026 21110 7026 7029 21111 7029 7027 21112 7027 7026 21113 7026 7029 21114 7029 7026 21115 7026 7028 21116 7028 7031 21117 7031 7029 21118 7029 7028 21119 7028 7031 21120 7031 7028 21121 7028 7030 21122 7030 7033 21123 7033 7031 21124 7031 7030 21125 7030 7033 21126 7033 7030 21127 7030 7032 21128 7032 7035 21129 7035 7033 21130 7033 7032 21131 7032 7035 21132 7035 7032 21133 7032 7034 21134 7034 7037 21135 7037 7035 21136 7035 7034 21137 7034 7037 21138 7037 7034 21139 7034 7036 21140 7036 7039 21141 7039 7037 21142 7037 7036 21143 7036 7039 21144 7039 7036 21145 7036 7038 21146 7038 7041 21147 7041 7039 21148 7039 7038 21149 7038 7041 21150 7041 7038 21151 7038 7040 21152 7040 7008 21153 7008 7041 21154 7041 7040 21155 7040 7074 21156 7074 7043 21157 7043 7042 21158 7042 7046 21159 7046 7045 21160 7045 7044 21161 7044 7048 21162 7048 7046 21163 7046 7044 21164 7044 7048 21165 7048 7044 21166 7044 7047 21167 7047 7049 21168 7049 7048 21169 7048 7047 21170 7047 7052 21171 7052 7049 21172 7049 7047 21173 7047 7052 21174 7052 7047 21175 7047 7050 21176 7050 7052 21177 7052 7050 21178 7050 7051 21179 7051 7053 21180 7053 7052 21181 7052 7051 21182 7051 7055 21183 7055 7053 21184 7053 7051 21185 7051 7055 21186 7055 7051 21187 7051 7054 21188 7054 7057 21189 7057 7055 21190 7055 7054 21191 7054 7057 21192 7057 7054 21193 7054 7056 21194 7056 7059 21195 7059 7057 21196 7057 7056 21197 7056 7059 21198 7059 7056 21199 7056 7058 21200 7058 7061 21201 7061 7059 21202 7059 7058 21203 7058 7061 21204 7061 7058 21205 7058 7060 21206 7060 7063 21207 7063 7061 21208 7061 7060 21209 7060 7063 21210 7063 7060 21211 7060 7062 21212 7062 7065 21213 7065 7063 21214 7063 7062 21215 7062 7065 21216 7065 7062 21217 7062 7064 21218 7064 7067 21219 7067 7065 21220 7065 7064 21221 7064 7067 21222 7067 7064 21223 7064 7066 21224 7066 7069 21225 7069 7067 21226 7067 7066 21227 7066 7069 21228 7069 7066 21229 7066 7068 21230 7068 7071 21231 7071 7069 21232 7069 7068 21233 7068 7071 21234 7071 7068 21235 7068 7070 21236 7070 7073 21237 7073 7071 21238 7071 7070 21239 7070 7073 21240 7073 7070 21241 7070 7072 21242 7072 7075 21243 7075 7073 21244 7073 7072 21245 7072 7075 21246 7075 7072 21247 7072 7074 21248 7074 7042 21249 7042 7075 21250 7075 7074 21251 7074 7108 21252 7108 7077 21253 7077 7076 21254 7076 7080 21255 7080 7079 21256 7079 7078 21257 7078 7082 21258 7082 7080 21259 7080 7078 21260 7078 7082 21261 7082 7078 21262 7078 7081 21263 7081 7084 21264 7084 7082 21265 7082 7081 21266 7081 7084 21267 7084 7081 21268 7081 7083 21269 7083 7085 21270 7085 7084 21271 7084 7083 21272 7083 7087 21273 7087 7085 21274 7085 7083 21275 7083 7087 21276 7087 7083 21277 7083 7086 21278 7086 7090 21279 7090 7087 21280 7087 7086 21281 7086 7090 21282 7090 7086 21283 7086 7088 21284 7088 7090 21285 7090 7088 21286 7088 7089 21287 7089 7092 21288 7092 7090 21289 7090 7089 21290 7089 7092 21291 7092 7089 21292 7089 7091 21293 7091 7093 21294 7093 7092 21295 7092 7091 21296 7091 7096 21297 7096 7093 21298 7093 7091 21299 7091 7096 21300 7096 7091 21301 7091 7094 21302 7094 7096 21303 7096 7094 21304 7094 7095 21305 7095 7098 21306 7098 7096 21307 7096 7095 21308 7095 7098 21309 7098 7095 21310 7095 7097 21311 7097 7099 21312 7099 7098 21313 7098 7097 21314 7097 7102 21315 7102 7099 21316 7099 7097 21317 7097 7102 21318 7102 7097 21319 7097 7100 21320 7100 7102 21321 7102 7100 21322 7100 7101 21323 7101 7103 21324 7103 7102 21325 7102 7101 21326 7101 7105 21327 7105 7103 21328 7103 7101 21329 7101 7105 21330 7105 7101 21331 7101 7104 21332 7104 7107 21333 7107 7105 21334 7105 7104 21335 7104 7107 21336 7107 7104 21337 7104 7106 21338 7106 7109 21339 7109 7107 21340 7107 7106 21341 7106 7109 21342 7109 7106 21343 7106 7108 21344 7108 7076 21345 7076 7109 21346 7109 7108 21347 7108 7142 21348 7142 7111 21349 7111 7110 21350 7110 7116 21351 7116 7113 21352 7113 7112 21353 7112 7116 21354 7116 7112 21355 7112 7114 21356 7114 7116 21357 7116 7114 21358 7114 7115 21359 7115 7117 21360 7117 7116 21361 7116 7115 21362 7115 7119 21363 7119 7117 21364 7117 7115 21365 7115 7119 21366 7119 7115 21367 7115 7118 21368 7118 7121 21369 7121 7119 21370 7119 7118 21371 7118 7121 21372 7121 7118 21373 7118 7120 21374 7120 7123 21375 7123 7121 21376 7121 7120 21377 7120 7123 21378 7123 7120 21379 7120 7122 21380 7122 7125 21381 7125 7123 21382 7123 7122 21383 7122 7125 21384 7125 7122 21385 7122 7124 21386 7124 7127 21387 7127 7125 21388 7125 7124 21389 7124 7127 21390 7127 7124 21391 7124 7126 21392 7126 7129 21393 7129 7127 21394 7127 7126 21395 7126 7129 21396 7129 7126 21397 7126 7128 21398 7128 7132 21399 7132 7129 21400 7129 7128 21401 7128 7132 21402 7132 7128 21403 7128 7130 21404 7130 7132 21405 7132 7130 21406 7130 7131 21407 7131 7133 21408 7133 7132 21409 7132 7131 21410 7131 7135 21411 7135 7133 21412 7133 7131 21413 7131 7135 21414 7135 7131 21415 7131 7134 21416 7134 7137 21417 7137 7135 21418 7135 7134 21419 7134 7137 21420 7137 7134 21421 7134 7136 21422 7136 7139 21423 7139 7137 21424 7137 7136 21425 7136 7139 21426 7139 7136 21427 7136 7138 21428 7138 7141 21429 7141 7139 21430 7139 7138 21431 7138 7141 21432 7141 7138 21433 7138 7140 21434 7140 7143 21435 7143 7141 21436 7141 7140 21437 7140 7143 21438 7143 7140 21439 7140 7142 21440 7142 7110 21441 7110 7143 21442 7143 7142 21443 7142 7176 21444 7176 7145 21445 7145 7144 21446 7144 7150 21447 7150 7147 21448 7147 7146 21449 7146 7150 21450 7150 7146 21451 7146 7148 21452 7148 7150 21453 7150 7148 21454 7148 7149 21455 7149 7151 21456 7151 7150 21457 7150 7149 21458 7149 7153 21459 7153 7151 21460 7151 7149 21461 7149 7153 21462 7153 7149 21463 7149 7152 21464 7152 7155 21465 7155 7153 21466 7153 7152 21467 7152 7155 21468 7155 7152 21469 7152 7154 21470 7154 7157 21471 7157 7155 21472 7155 7154 21473 7154 7157 21474 7157 7154 21475 7154 7156 21476 7156 7159 21477 7159 7157 21478 7157 7156 21479 7156 7159 21480 7159 7156 21481 7156 7158 21482 7158 7161 21483 7161 7159 21484 7159 7158 21485 7158 7161 21486 7161 7158 21487 7158 7160 21488 7160 7163 21489 7163 7161 21490 7161 7160 21491 7160 7163 21492 7163 7160 21493 7160 7162 21494 7162 7166 21495 7166 7163 21496 7163 7162 21497 7162 7166 21498 7166 7162 21499 7162 7164 21500 7164 7166 21501 7166 7164 21502 7164 7165 21503 7165 7167 21504 7167 7166 21505 7166 7165 21506 7165 7169 21507 7169 7167 21508 7167 7165 21509 7165 7169 21510 7169 7165 21511 7165 7168 21512 7168 7171 21513 7171 7169 21514 7169 7168 21515 7168 7171 21516 7171 7168 21517 7168 7170 21518 7170 7173 21519 7173 7171 21520 7171 7170 21521 7170 7173 21522 7173 7170 21523 7170 7172 21524 7172 7175 21525 7175 7173 21526 7173 7172 21527 7172 7175 21528 7175 7172 21529 7172 7174 21530 7174 7177 21531 7177 7175 21532 7175 7174 21533 7174 7177 21534 7177 7174 21535 7174 7176 21536 7176 7144 21537 7144 7177 21538 7177 7176 21539 7176 7210 21540 7210 7178 21541 7178 7190 21542 7190 7181 21543 7181 7180 21544 7180 7179 21545 7179 7183 21546 7183 7181 21547 7181 7179 21548 7179 7183 21549 7183 7179 21550 7179 7182 21551 7182 7185 21552 7185 7183 21553 7183 7182 21554 7182 7185 21555 7185 7182 21556 7182 7184 21557 7184 7186 21558 7186 7185 21559 7185 7184 21560 7184 7189 21561 7189 7186 21562 7186 7184 21563 7184 7189 21564 7189 7184 21565 7184 7187 21566 7187 7189 21567 7189 7187 21568 7187 7188 21569 7188 7191 21570 7191 7189 21571 7189 7188 21572 7188 7191 21573 7191 7188 21574 7188 7190 21575 7190 7178 21576 7178 7191 21577 7191 7190 21578 7190 7194 21579 7194 7193 21580 7193 7192 21581 7192 7195 21582 7195 7194 21583 7194 7192 21584 7192 7198 21585 7198 7195 21586 7195 7192 21587 7192 7198 21588 7198 7192 21589 7192 7196 21590 7196 7198 21591 7198 7196 21592 7196 7197 21593 7197 7199 21594 7199 7198 21595 7198 7197 21596 7197 7202 21597 7202 7199 21598 7199 7197 21599 7197 7202 21600 7202 7197 21601 7197 7200 21602 7200 7202 21603 7202 7200 21604 7200 7201 21605 7201 7203 21606 7203 7202 21607 7202 7201 21608 7201 7205 21609 7205 7203 21610 7203 7201 21611 7201 7205 21612 7205 7201 21613 7201 7204 21614 7204 7207 21615 7207 7205 21616 7205 7204 21617 7204 7207 21618 7207 7204 21619 7204 7206 21620 7206 7209 21621 7209 7207 21622 7207 7206 21623 7206 7209 21624 7209 7206 21625 7206 7208 21626 7208 7211 21627 7211 7209 21628 7209 7208 21629 7208 7211 21630 7211 7208 21631 7208 7210 21632 7210 7190 21633 7190 7211 21634 7211 7210 21635 7210 7244 21636 7244 7213 21637 7213 7212 21638 7212 7216 21639 7216 7215 21640 7215 7214 21641 7214 7218 21642 7218 7216 21643 7216 7214 21644 7214 7218 21645 7218 7214 21646 7214 7217 21647 7217 7220 21648 7220 7218 21649 7218 7217 21650 7217 7220 21651 7220 7217 21652 7217 7219 21653 7219 7221 21654 7221 7220 21655 7220 7219 21656 7219 7224 21657 7224 7221 21658 7221 7219 21659 7219 7224 21660 7224 7219 21661 7219 7222 21662 7222 7224 21663 7224 7222 21664 7222 7223 21665 7223 7226 21666 7226 7224 21667 7224 7223 21668 7223 7226 21669 7226 7223 21670 7223 7225 21671 7225 7227 21672 7227 7226 21673 7226 7225 21674 7225 7229 21675 7229 7227 21676 7227 7225 21677 7225 7229 21678 7229 7225 21679 7225 7228 21680 7228 7231 21681 7231 7229 21682 7229 7228 21683 7228 7231 21684 7231 7228 21685 7228 7230 21686 7230 7233 21687 7233 7231 21688 7231 7230 21689 7230 7233 21690 7233 7230 21691 7230 7232 21692 7232 7235 21693 7235 7233 21694 7233 7232 21695 7232 7235 21696 7235 7232 21697 7232 7234 21698 7234 7237 21699 7237 7235 21700 7235 7234 21701 7234 7237 21702 7237 7234 21703 7234 7236 21704 7236 7240 21705 7240 7237 21706 7237 7236 21707 7236 7240 21708 7240 7236 21709 7236 7238 21710 7238 7240 21711 7240 7238 21712 7238 7239 21713 7239 7241 21714 7241 7240 21715 7240 7239 21716 7239 7243 21717 7243 7241 21718 7241 7239 21719 7239 7243 21720 7243 7239 21721 7239 7242 21722 7242 7245 21723 7245 7243 21724 7243 7242 21725 7242 7245 21726 7245 7242 21727 7242 7244 21728 7244 7212 21729 7212 7245 21730 7245 7244 21731 7244 7278 21732 7278 7247 21733 7247 7246 21734 7246 7250 21735 7250 7249 21736 7249 7248 21737 7248 7252 21738 7252 7250 21739 7250 7248 21740 7248 7252 21741 7252 7248 21742 7248 7251 21743 7251 7254 21744 7254 7252 21745 7252 7251 21746 7251 7254 21747 7254 7251 21748 7251 7253 21749 7253 7256 21750 7256 7254 21751 7254 7253 21752 7253 7256 21753 7256 7253 21754 7253 7255 21755 7255 7257 21756 7257 7256 21757 7256 7255 21758 7255 7259 21759 7259 7257 21760 7257 7255 21761 7255 7259 21762 7259 7255 21763 7255 7258 21764 7258 7262 21765 7262 7259 21766 7259 7258 21767 7258 7262 21768 7262 7258 21769 7258 7260 21770 7260 7262 21771 7262 7260 21772 7260 7261 21773 7261 7264 21774 7264 7262 21775 7262 7261 21776 7261 7264 21777 7264 7261 21778 7261 7263 21779 7263 7266 21780 7266 7264 21781 7264 7263 21782 7263 7266 21783 7266 7263 21784 7263 7265 21785 7265 7267 21786 7267 7266 21787 7266 7265 21788 7265 7270 21789 7270 7267 21790 7267 7265 21791 7265 7270 21792 7270 7265 21793 7265 7268 21794 7268 7270 21795 7270 7268 21796 7268 7269 21797 7269 7272 21798 7272 7270 21799 7270 7269 21800 7269 7272 21801 7272 7269 21802 7269 7271 21803 7271 7273 21804 7273 7272 21805 7272 7271 21806 7271 7275 21807 7275 7273 21808 7273 7271 21809 7271 7275 21810 7275 7271 21811 7271 7274 21812 7274 7277 21813 7277 7275 21814 7275 7274 21815 7274 7277 21816 7277 7274 21817 7274 7276 21818 7276 7279 21819 7279 7277 21820 7277 7276 21821 7276 7279 21822 7279 7276 21823 7276 7278 21824 7278 7246 21825 7246 7279 21826 7279 7278 21827 7278 7312 21828 7312 7280 21829 7280 7283 21830 7283 7280 21831 7280 7282 21832 7282 7281 21833 7281 7280 21834 7280 7281 21835 7281 7283 21836 7283 7288 21837 7288 7285 21838 7285 7284 21839 7284 7288 21840 7288 7284 21841 7284 7286 21842 7286 7288 21843 7288 7286 21844 7286 7287 21845 7287 7289 21846 7289 7288 21847 7288 7287 21848 7287 7291 21849 7291 7289 21850 7289 7287 21851 7287 7291 21852 7291 7287 21853 7287 7290 21854 7290 7293 21855 7293 7291 21856 7291 7290 21857 7290 7293 21858 7293 7290 21859 7290 7292 21860 7292 7296 21861 7296 7293 21862 7293 7292 21863 7292 7296 21864 7296 7292 21865 7292 7294 21866 7294 7296 21867 7296 7294 21868 7294 7295 21869 7295 7297 21870 7297 7296 21871 7296 7295 21872 7295 7299 21873 7299 7297 21874 7297 7295 21875 7295 7299 21876 7299 7295 21877 7295 7298 21878 7298 7302 21879 7302 7299 21880 7299 7298 21881 7298 7302 21882 7302 7298 21883 7298 7300 21884 7300 7302 21885 7302 7300 21886 7300 7301 21887 7301 7304 21888 7304 7302 21889 7302 7301 21890 7301 7304 21891 7304 7301 21892 7301 7303 21893 7303 7306 21894 7306 7304 21895 7304 7303 21896 7303 7306 21897 7306 7303 21898 7303 7305 21899 7305 7307 21900 7307 7306 21901 7306 7305 21902 7305 7309 21903 7309 7307 21904 7307 7305 21905 7305 7309 21906 7309 7305 21907 7305 7308 21908 7308 7311 21909 7311 7309 21910 7309 7308 21911 7308 7311 21912 7311 7308 21913 7308 7310 21914 7310 7313 21915 7313 7311 21916 7311 7310 21917 7310 7313 21918 7313 7310 21919 7310 7312 21920 7312 7283 21921 7283 7313 21922 7313 7312 21923 7312 7346 21924 7346 7314 21925 7314 7317 21926 7317 7314 21927 7314 7316 21928 7316 7315 21929 7315 7314 21930 7314 7315 21931 7315 7317 21932 7317 7322 21933 7322 7319 21934 7319 7318 21935 7318 7322 21936 7322 7318 21937 7318 7320 21938 7320 7322 21939 7322 7320 21940 7320 7321 21941 7321 7323 21942 7323 7322 21943 7322 7321 21944 7321 7326 21945 7326 7323 21946 7323 7321 21947 7321 7326 21948 7326 7321 21949 7321 7324 21950 7324 7326 21951 7326 7324 21952 7324 7325 21953 7325 7327 21954 7327 7326 21955 7326 7325 21956 7325 7329 21957 7329 7327 21958 7327 7325 21959 7325 7329 21960 7329 7325 21961 7325 7328 21962 7328 7331 21963 7331 7329 21964 7329 7328 21965 7328 7331 21966 7331 7328 21967 7328 7330 21968 7330 7333 21969 7333 7331 21970 7331 7330 21971 7330 7333 21972 7333 7330 21973 7330 7332 21974 7332 7336 21975 7336 7333 21976 7333 7332 21977 7332 7336 21978 7336 7332 21979 7332 7334 21980 7334 7336 21981 7336 7334 21982 7334 7335 21983 7335 7338 21984 7338 7336 21985 7336 7335 21986 7335 7338 21987 7338 7335 21988 7335 7337 21989 7337 7340 21990 7340 7338 21991 7338 7337 21992 7337 7340 21993 7340 7337 21994 7337 7339 21995 7339 7341 21996 7341 7340 21997 7340 7339 21998 7339 7343 21999 7343 7341 22000 7341 7339 22001 7339 7343 22002 7343 7339 22003 7339 7342 22004 7342 7345 22005 7345 7343 22006 7343 7342 22007 7342 7345 22008 7345 7342 22009 7342 7344 22010 7344 7347 22011 7347 7345 22012 7345 7344 22013 7344 7347 22014 7347 7344 22015 7344 7346 22016 7346 7317 22017 7317 7347 22018 7347 7346 22019 7346 7380 22020 7380 7349 22021 7349 7348 22022 7348 7354 22023 7354 7351 22024 7351 7350 22025 7350 7354 22026 7354 7350 22027 7350 7352 22028 7352 7354 22029 7354 7352 22030 7352 7353 22031 7353 7355 22032 7355 7354 22033 7354 7353 22034 7353 7358 22035 7358 7355 22036 7355 7353 22037 7353 7358 22038 7358 7353 22039 7353 7356 22040 7356 7358 22041 7358 7356 22042 7356 7357 22043 7357 7359 22044 7359 7358 22045 7358 7357 22046 7357 7361 22047 7361 7359 22048 7359 7357 22049 7357 7361 22050 7361 7357 22051 7357 7360 22052 7360 7363 22053 7363 7361 22054 7361 7360 22055 7360 7363 22056 7363 7360 22057 7360 7362 22058 7362 7366 22059 7366 7363 22060 7363 7362 22061 7362 7366 22062 7366 7362 22063 7362 7364 22064 7364 7366 22065 7366 7364 22066 7364 7365 22067 7365 7368 22068 7368 7366 22069 7366 7365 22070 7365 7368 22071 7368 7365 22072 7365 7367 22073 7367 7370 22074 7370 7368 22075 7368 7367 22076 7367 7370 22077 7370 7367 22078 7367 7369 22079 7369 7372 22080 7372 7370 22081 7370 7369 22082 7369 7372 22083 7372 7369 22084 7369 7371 22085 7371 7374 22086 7374 7372 22087 7372 7371 22088 7371 7374 22089 7374 7371 22090 7371 7373 22091 7373 7375 22092 7375 7374 22093 7374 7373 22094 7373 7377 22095 7377 7375 22096 7375 7373 22097 7373 7377 22098 7377 7373 22099 7373 7376 22100 7376 7379 22101 7379 7377 22102 7377 7376 22103 7376 7379 22104 7379 7376 22105 7376 7378 22106 7378 7381 22107 7381 7379 22108 7379 7378 22109 7378 7381 22110 7381 7378 22111 7378 7380 22112 7380 7348 22113 7348 7381 22114 7381 7380 22115 7380 7414 22116 7414 7383 22117 7383 7382 22118 7382 7386 22119 7386 7385 22120 7385 7384 22121 7384 7388 22122 7388 7386 22123 7386 7384 22124 7384 7388 22125 7388 7384 22126 7384 7387 22127 7387 7390 22128 7390 7388 22129 7388 7387 22130 7387 7390 22131 7390 7387 22132 7387 7389 22133 7389 7391 22134 7391 7390 22135 7390 7389 22136 7389 7394 22137 7394 7391 22138 7391 7389 22139 7389 7394 22140 7394 7389 22141 7389 7392 22142 7392 7394 22143 7394 7392 22144 7392 7393 22145 7393 7396 22146 7396 7394 22147 7394 7393 22148 7393 7396 22149 7396 7393 22150 7393 7395 22151 7395 7397 22152 7397 7396 22153 7396 7395 22154 7395 7399 22155 7399 7397 22156 7397 7395 22157 7395 7399 22158 7399 7395 22159 7395 7398 22160 7398 7402 22161 7402 7399 22162 7399 7398 22163 7398 7402 22164 7402 7398 22165 7398 7400 22166 7400 7402 22167 7402 7400 22168 7400 7401 22169 7401 7403 22170 7403 7402 22171 7402 7401 22172 7401 7405 22173 7405 7403 22174 7403 7401 22175 7401 7405 22176 7405 7401 22177 7401 7404 22178 7404 7407 22179 7407 7405 22180 7405 7404 22181 7404 7407 22182 7407 7404 22183 7404 7406 22184 7406 7409 22185 7409 7407 22186 7407 7406 22187 7406 7409 22188 7409 7406 22189 7406 7408 22190 7408 7411 22191 7411 7409 22192 7409 7408 22193 7408 7411 22194 7411 7408 22195 7408 7410 22196 7410 7413 22197 7413 7411 22198 7411 7410 22199 7410 7413 22200 7413 7410 22201 7410 7412 22202 7412 7415 22203 7415 7413 22204 7413 7412 22205 7412 7415 22206 7415 7412 22207 7412 7414 22208 7414 7382 22209 7382 7415 22210 7415 7414 22211 7414

+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + -0.000668 -0.000000 0.000000 0.000000 0.000000 -0.000000 0.000668 0.000000 -0.000000 0.000668 0.000000 0.000000 0.000000 0.000000 0.000000 1.0000001.00000094.386012 33.034558 0.000067 -1249.999146 -0.242587 0.693320 -99.997363 2731.445557 -33.033670 94.383459 0.734535 899.803650 0.000000 0.000000 0.000000 1.0000001.000000100.000015 -0.000000 0.000000 -6749.997559 0.000000 0.734533 -99.997279 3001.437500 -0.000000 99.997279 0.734533 897.820190 0.000000 0.000000 0.000000 1.0000001.00000094.386014 33.034578 0.000067 -3750.000000 -0.242587 0.693320 -99.997371 2731.445557 -33.033688 94.383468 0.734535 899.803650 0.000000 0.000000 0.000000 1.0000001.000000-0.000013 0.000000 -100.000015 -8200.000977 -99.997272 0.734561 0.000013 2990.411621 0.734561 99.997272 0.000000 757.897461 0.000000 0.000000 0.000000 1.0000001.000000-100.000015 0.000027 -0.000009 0.000977 -0.000027 -99.997386 0.734502 -17.904053 -0.000009 0.734502 99.997386 -2405.089844 0.000000 0.000000 0.000000 1.0000001.000000100.000015 0.000000 -0.000000 -2878.363037 0.000000 -99.997279 -0.734626 2730.966064 -0.000000 0.734626 -99.997279 -1445.255371 0.000000 0.000000 0.000000 1.0000001.000000-0.000053 0.000053 100.000000 1300.001221 99.997348 0.734493 0.000053 -2605.264893 -0.734493 99.997348 -0.000053 -2036.071289 0.000000 0.000000 0.000000 1.0000001.000000-100.000000 -0.000027 0.000000 2975.001465 0.000027 -99.997364 0.734466 2482.320801 0.000000 0.734466 99.997364 -2383.448730 0.000000 0.000000 0.000000 1.0000001.000000-100.000000 -0.000027 0.000000 2715.000977 0.000027 -99.997364 0.734466 2402.322754 0.000000 0.734466 99.997364 -2382.862305 0.000000 0.000000 0.000000 1.0000001.000000-100.000000 -0.000027 0.000000 2805.002197 0.000027 -99.997364 0.734466 2524.156250 0.000000 0.734466 99.997364 -2133.750000 0.000000 0.000000 0.000000 1.0000001.000000100.000015 0.000000 -0.000000 2420.001221 0.000000 0.734520 -99.997279 2727.918701 -0.000000 99.997279 0.734520 1351.310303 0.000000 0.000000 0.000000 1.0000001.000000100.000015 0.000000 -0.000000 2420.001221 0.000000 0.734520 -99.997279 2727.919189 -0.000000 99.997279 0.734520 419.816650 0.000000 0.000000 0.000000 1.0000001.000000-100.000015 0.000000 0.000027 0.000977 0.000027 0.734573 99.997279 -856.763062 -0.000000 99.997279 -0.734573 476.150116 0.000000 0.000000 0.000000 1.0000001.0000000.000013 0.000013 -100.000000 -1299.998535 99.997303 -0.734499 0.000013 -2605.265869 -0.734499 -99.997303 -0.000013 -2036.071289 0.000000 0.000000 0.000000 1.0000001.000000-0.000013 0.000000 -100.000015 2450.001221 -99.997341 0.734514 0.000013 -2605.264160 0.734514 99.997341 0.000000 -2036.074219 0.000000 0.000000 0.000000 1.0000001.000000-99.840921 -5.639527 0.000054 3750.001709 -0.041373 0.733408 99.997317 2581.449951 -5.639376 99.838219 -0.734574 900.905396 0.000000 0.000000 0.000000 1.0000001.000000-0.000027 0.000026 100.000015 -2449.999023 99.997341 0.734493 0.000026 -2605.263428 -0.734493 99.997341 -0.000027 -2036.074219 0.000000 0.000000 0.000000 1.0000001.0000000.000013 0.000013 -100.000015 -1299.998535 99.997325 -0.734499 0.000013 -2605.265869 -0.734499 -99.997325 -0.000013 -2036.071289 0.000000 0.000000 0.000000 1.0000001.000000-0.000040 0.000040 100.000000 -2449.999023 99.997341 0.734493 0.000040 -2605.263428 -0.734493 99.997341 -0.000040 -2036.074219 0.000000 0.000000 0.000000 1.0000001.000000-0.000013 0.000000 -100.000000 2450.001221 -99.997341 0.734514 0.000013 -2605.264160 0.734514 99.997341 0.000000 -2036.074219 0.000000 0.000000 0.000000 1.0000001.000000100.000015 0.000000 -0.000000 3750.001221 0.000000 0.734520 -99.997279 2421.453857 -0.000000 99.997279 0.734520 902.080688 0.000000 0.000000 0.000000 1.0000001.000000100.000015 -0.000000 0.000000 2219.959717 0.000000 99.997386 0.734514 -1949.642578 -0.000000 -0.734514 99.997386 -1510.875977 0.000000 0.000000 0.000000 1.0000001.000000-0.000013 0.000000 -100.000015 2450.001221 -99.997386 0.734514 0.000013 -2605.264160 0.734514 99.997386 0.000000 -2036.074219 0.000000 0.000000 0.000000 1.0000001.000000-0.000080 0.000079 100.000015 -2449.999023 99.997386 0.734494 0.000079 -2605.263428 -0.734494 99.997386 -0.000080 -2036.074219 0.000000 0.000000 0.000000 1.0000001.000000-99.840951 -5.639528 0.000054 3750.001709 -0.041373 0.733408 99.997340 2581.449951 -5.639378 99.838219 -0.734574 900.905396 0.000000 0.000000 0.000000 1.0000001.0000000.000013 0.000013 -100.000000 -1299.998535 99.997348 -0.734499 0.000013 -2605.265869 -0.734499 -99.997348 -0.000013 -2036.071289 0.000000 0.000000 0.000000 1.0000001.000000100.000000 0.000000 0.000000 -1989.998901 0.000000 -99.997348 -0.734494 2272.768311 -0.000000 0.734494 -99.997348 -2321.908691 0.000000 0.000000 0.000000 1.0000001.000000100.000015 0.000000 0.000000 -8250.000977 0.000000 0.734546 -99.997279 2995.420898 -0.000000 99.997279 0.734546 -602.175964 0.000000 0.000000 0.000000 1.0000001.000000-0.000013 0.000000 -100.000015 8212.001953 -99.997272 0.734561 0.000013 2990.411377 0.734561 99.997272 0.000000 757.897461 0.000000 0.000000 0.000000 1.0000001.000000 + 30.0000000.0000003.333333 + + + + + +
diff --git a/simulators/sim_env/meshes/turtlebot3/sensors/astra.jpg b/simulators/sim_env/meshes/turtlebot3/sensors/astra.jpg new file mode 100755 index 0000000..670c5b8 Binary files /dev/null and b/simulators/sim_env/meshes/turtlebot3/sensors/astra.jpg differ diff --git a/simulators/sim_env/meshes/turtlebot3/sensors/lds.stl b/simulators/sim_env/meshes/turtlebot3/sensors/lds.stl new file mode 100755 index 0000000..510903e Binary files /dev/null and b/simulators/sim_env/meshes/turtlebot3/sensors/lds.stl differ diff --git a/simulators/sim_env/meshes/turtlebot3/sensors/r200.dae b/simulators/sim_env/meshes/turtlebot3/sensors/r200.dae new file mode 100755 index 0000000..c1ebc6a --- /dev/null +++ b/simulators/sim_env/meshes/turtlebot3/sensors/r200.dae @@ -0,0 +1,890 @@ + + + + + Google SketchUp 8.0.4811 + + 2015-05-31T08:41:34Z + 2015-05-31T08:41:34Z + + Z_UP + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 0.1184986753859656 7.755517072645532 2.24409448818898 51.06260368681876 7.755517072645532 2.165354330708662 0.1184986753859656 7.755517072645532 2.165354330708662 51.06260368681876 7.755517072645532 2.24409448818898 0.1184986753859656 7.755517072645532 2.24409448818898 0.1184986753859656 2.804370064010866 2.165354330708662 0.1184986753859656 2.804370064010866 2.24409448818898 0.1184986753859656 7.755517072645532 2.165354330708662 51.06260368681876 7.755517072645532 2.165354330708662 51.06260368681876 0.1184986753859656 2.24409448818898 51.06260368681876 0.1184986753859656 2.165354330708662 51.06260368681876 7.755517072645532 2.24409448818898 25.61991398185795 2.804370064010866 2.24409448818898 0.1184986753859656 2.804370064010866 2.165354330708662 25.61991398185795 2.804370064010866 2.165354330708662 0.1184986753859656 2.804370064010866 2.24409448818898 51.06260368681876 0.1184986753859656 2.24409448818898 30.70679771243117 0.1184986753859656 2.165354330708662 51.06260368681876 0.1184986753859656 2.165354330708662 30.70679771243117 0.1184986753859656 2.24409448818898 30.70679771243117 0.1184986753859656 2.24409448818898 25.61991398185795 2.804370064010866 2.165354330708662 30.70679771243117 0.1184986753859656 2.165354330708662 25.61991398185795 2.804370064010866 2.24409448818898 + + + + + + + + + + 0 1 0 0 1 0 0 1 0 0 1 0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 -1.741429659934826e-017 -1 -0 -1.741429659934826e-017 -1 -0 -1.741429659934826e-017 -1 -0 -1.741429659934826e-017 -1 -0 -1.363521329027796e-018 -1 1.38790518535184e-045 -1.363521329027796e-018 -1 1.38790518535184e-045 -1.363521329027796e-018 -1 1.38790518535184e-045 -1.363521329027796e-018 -1 1.38790518535184e-045 -0.4669118737456303 -0.8843038517135072 -0 -0.4669118737456303 -0.8843038517135072 -0 -0.4669118737456303 -0.8843038517135072 -0 -0.4669118737456303 -0.8843038517135072 -0 + + + + + + + + + + + + + + +

0 1 2 1 0 3 4 5 6 5 4 7 8 9 10 9 8 11 12 13 14 13 12 15 16 17 18 17 16 19 20 21 22 21 20 23

+
+
+
+ + + + 0.1184986753859656 2.43930318405221 1.968503937007876 0.1184986753859656 0.2465682045726894 2.165354330708662 0.1184986753859656 0.2465682045726894 1.968503937007876 0.1184986753859656 2.43930318405221 2.165354330708662 0.1184986753859656 0.2465682045726894 1.968503937007876 0.119594327961949 0.2298517765885317 2.165354330708662 0.119594327961949 0.2298517765885317 1.968503937007876 0.1184986753859656 0.2465682045726894 2.165354330708662 0.2465682045726913 0.1184986753859656 1.968503937007876 0.3477764914940549 0.5226027736765067 1.968503937007876 0.3460392041832313 0.5491086559751139 1.968503937007876 0.352958627958972 0.4965504143728474 1.968503937007876 0.361496945786306 0.4713973411548998 1.968503937007876 0.3732453519907644 0.4475739300791728 1.968503937007876 0.3880028280849136 0.4254878063142707 1.968503937007876 0.4055168695612388 0.4055168695612393 1.968503937007876 0.4254878063142707 0.3880028280849154 1.968503937007876 0.4475739300791731 0.3732453519907652 1.968503937007876 0.4713973411549005 0.3614969457863064 1.968503937007876 0.4965504143728469 0.3529586279589738 1.968503937007876 0.5226027736765072 0.3477764914940557 1.968503937007876 0.5491086559751147 0.346039204183232 1.968503937007876 30.0860261920037 0.1184986753859688 1.968503937007876 28.98669970978262 0.3460392041831966 1.968503937007876 29.00270410638306 0.3478174866438403 1.968503937007876 29.01792778668387 0.3530655869813785 1.968503937007876 29.03162811879157 0.3615274957018001 1.968503937007876 29.04313678181573 0.3727904293538459 1.968503937007876 29.05189236747371 0.386304966668887 1.968503937007876 29.05746776635262 0.4014118500799385 1.968503937007876 29.05959100288907 0.4173741452051467 1.968503937007876 0.119594327961949 0.2298517765885317 1.968503937007876 0.1184986753859656 2.43930318405221 1.968503937007876 0.1184986753859656 0.2465682045726894 1.968503937007876 0.1195943279619488 2.456019612036368 1.968503937007876 0.1228625387705512 2.472450017303047 1.968503937007876 0.1228625387705518 0.2134213713218521 1.968503937007876 0.1282473878187184 2.488313271062767 1.968503937007876 0.1282473878187189 0.1975581175621329 1.968503937007876 0.1356567388462739 2.503337948645572 1.968503937007876 0.1356567388462747 0.1825334399793274 1.968503937007876 0.1449638158028762 2.517266973652394 1.968503937007876 0.1449638158028776 0.1686044149725052 1.968503937007876 0.1560093720213884 2.529862016603511 1.968503937007876 0.1560093720213896 0.1560093720213882 1.968503937007876 0.1686044149725052 2.540907572822023 1.968503937007876 0.1686044149725068 0.1449638158028763 1.968503937007876 0.1825334399793273 2.550214649778626 1.968503937007876 0.1825334399793289 0.1356567388462739 1.968503937007876 0.1975581175621327 2.557624000806182 1.968503937007876 0.197558117562134 0.1282473878187185 1.968503937007876 0.213421371321852 2.563008849854349 1.968503937007876 0.2134213713218537 0.1228625387705514 1.968503937007876 0.2298517765885315 2.566277060662952 1.968503937007876 0.2298517765885331 0.1195943279619491 1.968503937007876 0.2465682045726894 2.567372713238935 1.968503937007876 0.3460392041832319 2.136762732649793 1.968503937007876 0.3477764914940558 2.163268614948401 1.968503937007876 0.3529586279589722 2.189320974252061 1.968503937007876 0.3614969457863068 2.214474047470008 1.968503937007876 0.3732453519907648 2.238297458545735 1.968503937007876 0.3880028280849145 2.260383582310638 1.968503937007876 0.4055168695612396 2.280354519063669 1.968503937007876 0.4254878063142705 2.297868560539994 1.968503937007876 0.4475739300791732 2.312626036634144 1.968503937007876 0.4713973411548998 2.324374442838602 1.968503937007876 0.4965504143728471 2.332912760665936 1.968503937007876 0.5226027736765068 2.338094897130853 1.968503937007876 0.5491086559751146 2.339832184441677 1.968503937007876 25.56118838034679 2.567372713238936 1.968503937007876 25.50480608586854 2.339832184441669 1.968503937007876 29.0207414471994 0.4834205400204281 1.968503937007876 30.09912146437194 0.1713469183847506 1.968503937007876 29.03406389556177 0.4743753551861666 1.968503937007876 29.04507585432682 0.4626263227489491 1.968503937007876 29.05324014512329 0.4487465765392888 1.968503937007876 29.05815850270828 0.4334131895122746 1.968503937007876 30.09803909744245 0.1212016043046447 1.968503937007876 30.10330938016302 0.1244567554178949 1.968503937007876 30.10848249331568 0.1633477397435226 1.968503937007876 30.10773656538716 0.1287894127682915 1.968503937007876 30.11110468898 0.1339882234195986 1.968503937007876 30.11162315591949 0.1580084394959358 1.968503937007876 30.11324944927784 0.1397995822959414 1.968503937007876 30.11351516370367 0.1521099485644012 1.968503937007876 30.11406622194742 0.145940003383379 1.968503937007876 0.1195943279619488 2.456019612036368 1.968503937007876 0.1184986753859656 2.43930318405221 2.165354330708662 0.1184986753859656 2.43930318405221 1.968503937007876 0.1195943279619488 2.456019612036368 2.165354330708662 0.1228625387705518 0.2134213713218521 2.165354330708662 0.1228625387705518 0.2134213713218521 1.968503937007876 30.09912146437194 0.1713469183847506 2.165354330708662 25.56118838034679 2.567372713238936 1.968503937007876 30.09912146437194 0.1713469183847506 1.968503937007876 25.56118838034679 2.567372713238936 2.165354330708662 25.56118838034679 2.567372713238936 2.165354330708662 0.2465682045726894 2.567372713238935 1.968503937007876 25.56118838034679 2.567372713238936 1.968503937007876 0.2465682045726894 2.567372713238935 2.165354330708662 0.2465682045726894 2.567372713238935 2.165354330708662 0.2298517765885315 2.566277060662952 1.968503937007876 0.2465682045726894 2.567372713238935 1.968503937007876 0.2298517765885315 2.566277060662952 2.165354330708662 0.213421371321852 2.563008849854349 1.968503937007876 0.213421371321852 2.563008849854349 2.165354330708662 0.1975581175621327 2.557624000806182 1.968503937007876 0.1975581175621327 2.557624000806182 2.165354330708662 0.1825334399793273 2.550214649778626 1.968503937007876 0.1825334399793273 2.550214649778626 2.165354330708662 0.1686044149725052 2.540907572822023 1.968503937007876 0.1686044149725052 2.540907572822023 2.165354330708662 0.1560093720213884 2.529862016603511 1.968503937007876 0.1560093720213884 2.529862016603511 2.165354330708662 0.1449638158028762 2.517266973652394 2.165354330708662 0.1449638158028762 2.517266973652394 1.968503937007876 0.1356567388462739 2.503337948645572 2.165354330708662 0.1356567388462739 2.503337948645572 1.968503937007876 0.1282473878187184 2.488313271062767 2.165354330708662 0.1282473878187184 2.488313271062767 1.968503937007876 0.1228625387705512 2.472450017303047 2.165354330708662 0.1228625387705512 2.472450017303047 1.968503937007876 0.1282473878187189 0.1975581175621329 2.165354330708662 0.1282473878187189 0.1975581175621329 1.968503937007876 0.1356567388462747 0.1825334399793274 2.165354330708662 0.1356567388462747 0.1825334399793274 1.968503937007876 0.1449638158028776 0.1686044149725052 2.165354330708662 0.1449638158028776 0.1686044149725052 1.968503937007876 0.1560093720213896 0.1560093720213882 2.165354330708662 0.1560093720213896 0.1560093720213882 1.968503937007876 0.1686044149725068 0.1449638158028763 1.968503937007876 0.1686044149725068 0.1449638158028763 2.165354330708662 0.1825334399793289 0.1356567388462739 1.968503937007876 0.1825334399793289 0.1356567388462739 2.165354330708662 0.197558117562134 0.1282473878187185 1.968503937007876 0.197558117562134 0.1282473878187185 2.165354330708662 0.2134213713218537 0.1228625387705514 1.968503937007876 0.2134213713218537 0.1228625387705514 2.165354330708662 0.2298517765885331 0.1195943279619491 1.968503937007876 0.2298517765885331 0.1195943279619491 2.165354330708662 0.2465682045726913 0.1184986753859656 1.968503937007876 0.2465682045726913 0.1184986753859656 2.165354330708662 0.2465682045726913 0.1184986753859656 2.165354330708662 30.0860261920037 0.1184986753859688 1.968503937007876 0.2465682045726913 0.1184986753859656 1.968503937007876 30.0860261920037 0.1184986753859688 2.165354330708662 30.0860261920037 0.1184986753859688 2.165354330708662 30.09803909744245 0.1212016043046447 1.968503937007876 30.0860261920037 0.1184986753859688 1.968503937007876 30.09803909744245 0.1212016043046447 2.165354330708662 30.09803909744245 0.1212016043046447 2.165354330708662 30.10330938016302 0.1244567554178949 1.968503937007876 30.09803909744245 0.1212016043046447 1.968503937007876 30.10330938016302 0.1244567554178949 2.165354330708662 30.10330938016302 0.1244567554178949 2.165354330708662 30.10773656538716 0.1287894127682915 1.968503937007876 30.10330938016302 0.1244567554178949 1.968503937007876 30.10773656538716 0.1287894127682915 2.165354330708662 30.11110468898 0.1339882234195986 2.165354330708662 30.10773656538716 0.1287894127682915 1.968503937007876 30.10773656538716 0.1287894127682915 2.165354330708662 30.11110468898 0.1339882234195986 1.968503937007876 30.11324944927784 0.1397995822959414 2.165354330708662 30.11110468898 0.1339882234195986 1.968503937007876 30.11110468898 0.1339882234195986 2.165354330708662 30.11324944927784 0.1397995822959414 1.968503937007876 30.11406622194742 0.145940003383379 2.165354330708662 30.11324944927784 0.1397995822959414 1.968503937007876 30.11324944927784 0.1397995822959414 2.165354330708662 30.11406622194742 0.145940003383379 1.968503937007876 30.11351516370367 0.1521099485644012 2.165354330708662 30.11406622194742 0.145940003383379 1.968503937007876 30.11406622194742 0.145940003383379 2.165354330708662 30.11351516370367 0.1521099485644012 1.968503937007876 30.11162315591949 0.1580084394959358 2.165354330708662 30.11351516370367 0.1521099485644012 1.968503937007876 30.11351516370367 0.1521099485644012 2.165354330708662 30.11162315591949 0.1580084394959358 1.968503937007876 30.10848249331568 0.1633477397435226 2.165354330708662 30.11162315591949 0.1580084394959358 1.968503937007876 30.11162315591949 0.1580084394959358 2.165354330708662 30.10848249331568 0.1633477397435226 1.968503937007876 30.10848249331568 0.1633477397435226 2.165354330708662 30.09912146437194 0.1713469183847506 1.968503937007876 30.10848249331568 0.1633477397435226 1.968503937007876 30.09912146437194 0.1713469183847506 2.165354330708662 + + + + + + + + + + 1 0 0 1 0 0 1 0 0 1 0 0 0.9978589232386028 0.06540312923015378 0 0.9914448613738085 0.1305261922200654 0 0.9914448613738085 0.1305261922200654 0 0.9978589232386028 0.06540312923015378 0 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 0.9914448613738105 -0.1305261922200504 0 0.9978589232386037 -0.06540312923014092 -0 0.9978589232386037 -0.06540312923014092 -0 0.9914448613738105 -0.1305261922200504 0 0.9659258262890664 0.2588190451025282 0 0.9659258262890664 0.2588190451025282 0 -0.4669118737456304 -0.8843038517135073 0 -0.4669118737456304 -0.8843038517135073 0 -0.4669118737456304 -0.8843038517135073 0 -0.4669118737456304 -0.8843038517135073 0 3.508559139078474e-017 -1 -0 3.508559139078474e-017 -1 -0 3.508559139078474e-017 -1 -0 3.508559139078474e-017 -1 -0 0.06540312923014653 -0.9978589232386035 -0 0.1305261922200657 -0.9914448613738085 0 0.06540312923014653 -0.9978589232386035 -0 0.1305261922200657 -0.9914448613738085 0 0.2588190451025326 -0.9659258262890651 0 0.2588190451025326 -0.9659258262890651 0 0.3826834323650984 -0.9238795325112833 0 0.3826834323650984 -0.9238795325112833 0 0.5000000000000157 -0.8660254037844295 0 0.5000000000000157 -0.8660254037844295 0 0.6087614290087283 -0.7933533402912294 0 0.6087614290087283 -0.7933533402912294 0 0.7071067811865515 -0.7071067811865435 0 0.7071067811865515 -0.7071067811865435 0 0.7933533402912371 -0.6087614290087183 0 0.7933533402912371 -0.6087614290087183 0 0.8660254037844378 -0.5000000000000014 0 0.8660254037844378 -0.5000000000000014 0 0.9238795325112877 -0.3826834323650871 0 0.9238795325112877 -0.3826834323650871 0 0.965925826289069 -0.258819045102518 0 0.965925826289069 -0.258819045102518 0 0.9238795325112841 0.3826834323650963 0 0.9238795325112841 0.3826834323650963 0 0.8660254037844283 0.500000000000018 0 0.8660254037844283 0.500000000000018 0 0.7933533402912328 0.6087614290087237 0 0.7933533402912328 0.6087614290087237 0 0.7071067811865434 0.7071067811865516 0 0.7071067811865434 0.7071067811865516 0 0.6087614290087107 0.7933533402912428 0 0.6087614290087107 0.7933533402912428 0 0.5000000000000019 0.8660254037844377 0 0.5000000000000019 0.8660254037844377 0 0.3826834323650855 0.9238795325112886 0 0.3826834323650855 0.9238795325112886 0 0.2588190451025133 0.9659258262890702 0 0.2588190451025133 0.9659258262890702 0 0.1305261922200561 0.9914448613738098 0 0.1305261922200561 0.9914448613738098 0 0.06540312923015844 0.9978589232386027 0 0.06540312923015844 0.9978589232386027 0 -1.083146562226566e-016 1 -1.259049816913602e-017 -1.083146562226566e-016 1 -1.259049816913602e-017 -1.083146562226566e-016 1 -1.259049816913602e-017 -1.083146562226566e-016 1 -1.259049816913602e-017 -0.2195141426946766 0.9756093178916556 -0 -0.2195141426946766 0.9756093178916556 -0 -0.2195141426946766 0.9756093178916556 -0 -0.2195141426946766 0.9756093178916556 -0 -0.5254901336654482 0.8507996940645135 -0 -0.5254901336654482 0.8507996940645135 -0 -0.5254901336654482 0.8507996940645135 -0 -0.5254901336654482 0.8507996940645135 -0 -0.6994356363115606 0.7146955930026729 -0 -0.6994356363115606 0.7146955930026729 -0 -0.6994356363115606 0.7146955930026729 -0 -0.6994356363115606 0.7146955930026729 -0 -0.8392617144369261 0.5437276659140966 -0 -0.8392617144369261 0.5437276659140966 -0 -0.8392617144369261 0.5437276659140966 -0 -0.8392617144369261 0.5437276659140966 -0 -0.9381474611967006 0.3462359615207312 -0 -0.9381474611967006 0.3462359615207312 -0 -0.9381474611967006 0.3462359615207312 -0 -0.9381474611967006 0.3462359615207312 -0 -0.9912690949632644 0.1318543945824739 -0 -0.9912690949632644 0.1318543945824739 -0 -0.9912690949632644 0.1318543945824739 -0 -0.9912690949632644 0.1318543945824739 -0 -0.9960352699715455 -0.08895920960030257 -0 -0.9960352699715455 -0.08895920960030257 -0 -0.9960352699715455 -0.08895920960030257 -0 -0.9960352699715455 -0.08895920960030257 -0 -0.9522134857026214 -0.3054332621802407 -0 -0.9522134857026214 -0.3054332621802407 -0 -0.9522134857026214 -0.3054332621802407 -0 -0.9522134857026214 -0.3054332621802407 -0 -0.8619414285757618 -0.5070078635531948 -0 -0.8619414285757618 -0.5070078635531948 -0 -0.8619414285757618 -0.5070078635531948 -0 -0.8619414285757618 -0.5070078635531948 -0 -0.6496407765509248 -0.7602413178999887 -0 -0.6496407765509248 -0.7602413178999887 -0 -0.6496407765509248 -0.7602413178999887 -0 -0.6496407765509248 -0.7602413178999887 -0 + + + + + + + + + + + + + + +

0 1 2 1 0 3 4 5 6 5 4 7 8 9 10 9 8 11 11 8 12 12 8 13 13 8 14 14 8 15 15 8 16 16 8 17 17 8 18 18 8 19 19 8 20 20 8 21 21 8 22 21 22 23 23 22 24 24 22 25 25 22 26 26 22 27 27 22 28 28 22 29 29 22 30 31 32 33 32 31 34 34 31 35 35 31 36 35 36 37 37 36 38 37 38 39 39 38 40 39 40 41 41 40 42 41 42 43 43 42 44 43 44 45 45 44 46 45 46 47 47 46 48 47 48 49 49 48 50 49 50 51 51 50 52 51 52 53 53 52 54 53 54 55 55 54 8 55 8 56 55 56 57 55 57 58 55 58 59 55 59 60 55 60 61 55 61 62 55 62 63 55 63 64 55 64 65 55 65 66 55 66 67 55 67 68 55 68 69 56 8 10 69 68 70 69 70 71 69 71 72 72 71 73 72 73 74 72 74 75 72 75 76 72 76 30 72 30 22 72 22 77 72 77 78 72 78 79 79 78 80 79 80 81 79 81 82 82 81 83 82 83 84 84 83 85 86 87 88 87 86 89 6 90 91 90 6 5 92 93 94 93 92 95 96 97 98 97 96 99 100 101 102 101 100 103 103 104 101 104 103 105 105 106 104 106 105 107 107 108 106 108 107 109 109 110 108 110 109 111 111 112 110 112 111 113 112 114 115 114 112 113 115 116 117 116 115 114 117 118 119 118 117 116 119 120 121 120 119 118 121 89 86 89 121 120 91 122 123 122 91 90 123 124 125 124 123 122 125 126 127 126 125 124 127 128 129 128 127 126 128 130 129 130 128 131 131 132 130 132 131 133 133 134 132 134 133 135 135 136 134 136 135 137 137 138 136 138 137 139 139 140 138 140 139 141 142 143 144 143 142 145 146 147 148 147 146 149 150 151 152 151 150 153 154 155 156 155 154 157 158 159 160 159 158 161 162 163 164 163 162 165 166 167 168 167 166 169 170 171 172 171 170 173 174 175 176 175 174 177 178 179 180 179 178 181 182 183 184 183 182 185

+
+
+
+ + + + 29.00270410638306 0.3478174866438403 1.968503937007876 29.01792778668387 0.3530655869813785 1.062992125984253 29.00270410638306 0.3478174866438403 1.062992125984253 29.01792778668387 0.3530655869813785 1.968503937007876 28.98669970978262 0.3460392041831966 1.968503937007876 29.00270410638306 0.3478174866438403 1.110223024625157e-015 28.98669970978262 0.3460392041831966 1.110223024625157e-015 29.03162811879157 0.3615274957018001 1.062992125984253 29.03162811879157 0.3615274957018001 1.968503937007876 43.19998259988454 2.339832184441669 1.062992125984254 29.0207414471994 0.4834205400204281 1.062992125984253 25.50480608586854 2.339832184441669 1.062992125984253 29.03406389556177 0.4743753551861666 1.062992125984253 29.04507585432682 0.4626263227489491 1.062992125984253 29.05324014512329 0.4487465765392888 1.062992125984253 29.05815850270828 0.4334131895122746 1.062992125984253 29.05959100288907 0.4173741452051467 1.062992125984253 43.1999825998845 0.3478174866438403 1.062992125984253 43.22648848218315 0.3495547739546886 1.062992125984253 43.22648848218314 2.338094897130838 1.062992125984254 43.25254084148678 2.332912760665932 1.062992125984254 43.25254084148678 0.3547369104195798 1.062992125984253 43.27769391470476 2.324374442838592 1.062992125984254 43.27769391470472 0.3632752282469342 1.062992125984253 43.30151732578045 0.3750236344513948 1.062992125984253 43.30151732578047 2.312626036634134 1.062992125984254 43.32360344954538 0.3897811105455223 1.062992125984253 43.32360344954538 2.297868560539985 1.062992125984254 43.34357438629841 2.280354519063661 1.062992125984254 43.34357438629839 0.4072951520218343 1.062992125984253 43.36108842777473 0.4272660887748755 1.062992125984253 43.36108842777473 2.260383582310626 1.062992125984254 43.37584590386888 2.238297458545732 1.062992125984254 43.37584590386889 0.4493522125397943 1.062992125984253 43.38759431007334 2.214474047469995 1.062992125984254 43.38759431007329 0.4731756236155132 1.062992125984253 43.39613262790066 0.4983286968334623 1.062992125984253 43.39613262790067 2.189320974252053 1.062992125984254 43.40131476436558 0.5243810561371171 1.062992125984253 43.40131476436559 2.163268614948387 1.062992125984254 43.4030520516764 0.5508869384357514 1.062992125984253 43.4030520516764 2.136762732649783 1.062992125984254 29.01792778668387 0.3530655869813785 1.062992125984253 29.00270410638306 0.3478174866438403 1.062992125984253 29.03162811879157 0.3615274957018001 1.062992125984253 29.04313678181573 0.3727904293538459 1.062992125984253 29.05189236747371 0.386304966668887 1.062992125984253 29.05746776635262 0.4014118500799385 1.062992125984253 0.5491086559751147 0.346039204183232 1.968503937007876 28.98669970978262 0.3460392041831966 1.110223024625157e-015 0.5491086559751147 0.346039204183232 1.110223024625157e-015 28.98669970978262 0.3460392041831966 1.968503937007876 29.00270410638306 0.3478174866438403 1.110223024625157e-015 43.1999825998845 0.3478174866438403 0.157480314960631 50.14425631911605 0.3478174866438403 1.110223024625157e-015 29.00270410638306 0.3478174866438403 1.062992125984253 43.1999825998845 0.3478174866438403 1.062992125984253 50.14425631911605 0.3478174866438403 0.157480314960631 29.04313678181573 0.3727904293538459 1.062992125984253 29.04313678181573 0.3727904293538459 1.968503937007876 43.4030520516764 2.136762732649783 1.062992125984254 43.4030520516764 0.5508869384357514 0.157480314960631 43.4030520516764 0.5508869384357514 1.062992125984253 43.4030520516764 2.136762732649783 0.1574803149606311 43.4030520516764 0.5508869384357514 1.062992125984253 43.40131476436558 0.5243810561371171 0.157480314960631 43.40131476436558 0.5243810561371171 1.062992125984253 43.4030520516764 0.5508869384357514 0.157480314960631 43.39613262790066 0.4983286968334623 0.157480314960631 43.39613262790066 0.4983286968334623 1.062992125984253 43.38759431007329 0.4731756236155132 0.157480314960631 43.38759431007329 0.4731756236155132 1.062992125984253 43.37584590386889 0.4493522125397943 0.157480314960631 43.37584590386889 0.4493522125397943 1.062992125984253 43.36108842777473 0.4272660887748755 0.157480314960631 43.36108842777473 0.4272660887748755 1.062992125984253 43.34357438629839 0.4072951520218343 0.157480314960631 43.34357438629839 0.4072951520218343 1.062992125984253 43.32360344954538 0.3897811105455223 1.062992125984253 43.32360344954538 0.3897811105455223 0.157480314960631 43.30151732578045 0.3750236344513948 1.062992125984253 43.30151732578045 0.3750236344513948 0.157480314960631 43.27769391470472 0.3632752282469342 1.062992125984253 43.27769391470472 0.3632752282469342 0.157480314960631 43.25254084148678 0.3547369104195798 1.062992125984253 43.25254084148678 0.3547369104195798 0.157480314960631 43.22648848218315 0.3495547739546886 1.062992125984253 43.22648848218315 0.3495547739546886 0.157480314960631 43.1999825998845 0.3478174866438403 1.062992125984253 43.1999825998845 0.3478174866438403 0.157480314960631 29.05189236747371 0.386304966668887 1.968503937007876 29.05189236747371 0.386304966668887 1.062992125984253 29.05746776635262 0.4014118500799385 1.968503937007876 29.05746776635262 0.4014118500799385 1.062992125984253 29.05959100288907 0.4173741452051467 1.968503937007876 29.05959100288907 0.4173741452051467 1.062992125984253 29.05815850270828 0.4334131895122746 1.968503937007876 29.05815850270828 0.4334131895122746 1.062992125984253 29.05324014512329 0.4487465765392888 1.968503937007876 29.05324014512329 0.4487465765392888 1.062992125984253 29.04507585432682 0.4626263227489491 1.968503937007876 29.04507585432682 0.4626263227489491 1.062992125984253 29.03406389556177 0.4743753551861666 1.968503937007876 29.03406389556177 0.4743753551861666 1.062992125984253 29.0207414471994 0.4834205400204281 1.062992125984253 29.0207414471994 0.4834205400204281 1.968503937007876 29.0207414471994 0.4834205400204281 1.968503937007876 25.50480608586854 2.339832184441669 1.062992125984253 29.0207414471994 0.4834205400204281 1.062992125984253 25.50480608586854 2.339832184441669 1.968503937007876 50.14425631911605 2.339832184441669 0.157480314960631 25.50480608586854 2.339832184441669 1.110223024625157e-015 50.14425631911605 2.339832184441669 1.110223024625157e-015 43.19998259988454 2.339832184441669 0.1574803149606311 25.50480608586854 2.339832184441669 1.062992125984253 43.19998259988454 2.339832184441669 1.062992125984254 43.22648848218314 2.338094897130838 1.062992125984254 43.19998259988454 2.339832184441669 0.1574803149606311 43.22648848218314 2.338094897130838 0.1574803149606311 43.19998259988454 2.339832184441669 1.062992125984254 43.25254084148678 2.332912760665932 1.062992125984254 43.25254084148678 2.332912760665932 0.1574803149606311 43.27769391470476 2.324374442838592 1.062992125984254 43.27769391470476 2.324374442838592 0.1574803149606311 43.30151732578047 2.312626036634134 1.062992125984254 43.30151732578047 2.312626036634134 0.1574803149606311 43.32360344954538 2.297868560539985 1.062992125984254 43.32360344954538 2.297868560539985 0.1574803149606311 43.34357438629841 2.280354519063661 1.062992125984254 43.34357438629841 2.280354519063661 0.1574803149606311 43.36108842777473 2.260383582310626 0.1574803149606311 43.36108842777473 2.260383582310626 1.062992125984254 43.37584590386888 2.238297458545732 0.1574803149606311 43.37584590386888 2.238297458545732 1.062992125984254 43.38759431007334 2.214474047469995 0.1574803149606311 43.38759431007334 2.214474047469995 1.062992125984254 43.39613262790067 2.189320974252053 0.1574803149606311 43.39613262790067 2.189320974252053 1.062992125984254 43.40131476436559 2.163268614948387 0.1574803149606311 43.40131476436559 2.163268614948387 1.062992125984254 43.4030520516764 2.136762732649783 0.1574803149606311 43.4030520516764 2.136762732649783 1.062992125984254 0.5226027736765072 0.3477764914940557 1.968503937007876 0.5491086559751147 0.346039204183232 1.110223024625157e-015 0.5226027736765072 0.3477764914940557 1.110223024625157e-015 0.5491086559751147 0.346039204183232 1.968503937007876 50.14425631911605 2.339832184441669 0.157480314960631 43.22648848218314 2.338094897130838 0.1574803149606311 43.19998259988454 2.339832184441669 0.1574803149606311 43.25254084148678 2.332912760665932 0.1574803149606311 43.27769391470476 2.324374442838592 0.1574803149606311 43.30151732578047 2.312626036634134 0.1574803149606311 43.32360344954538 2.297868560539985 0.1574803149606311 43.34357438629841 2.280354519063661 0.1574803149606311 43.36108842777473 2.260383582310626 0.1574803149606311 43.37584590386888 2.238297458545732 0.1574803149606311 43.38759431007334 2.214474047469995 0.1574803149606311 43.39613262790067 2.189320974252053 0.1574803149606311 43.40131476436559 2.163268614948387 0.1574803149606311 43.4030520516764 2.136762732649783 0.1574803149606311 43.4030520516764 0.5508869384357514 0.157480314960631 43.22648848218315 0.3495547739546886 0.157480314960631 50.14425631911605 0.3478174866438403 0.157480314960631 43.1999825998845 0.3478174866438403 0.157480314960631 43.25254084148678 0.3547369104195798 0.157480314960631 43.27769391470472 0.3632752282469342 0.157480314960631 43.30151732578045 0.3750236344513948 0.157480314960631 43.32360344954538 0.3897811105455223 0.157480314960631 43.34357438629839 0.4072951520218343 0.157480314960631 43.36108842777473 0.4272660887748755 0.157480314960631 43.37584590386889 0.4493522125397943 0.157480314960631 43.38759431007329 0.4731756236155132 0.157480314960631 43.39613262790066 0.4983286968334623 0.157480314960631 43.40131476436558 0.5243810561371171 0.157480314960631 50.17076220141468 2.338094897130827 0.157480314960631 50.17076220141466 0.3495547739546495 0.157480314960631 50.19681456071831 0.35473691041958 0.157480314960631 50.19681456071832 2.332912760665919 0.157480314960631 50.22196763393623 0.3632752282469015 0.157480314960631 50.22196763393626 2.324374442838587 0.157480314960631 50.24579104501201 0.3750236344513794 0.157480314960631 50.24579104501199 2.312626036634129 0.157480314960631 50.26787716877689 2.297868560539985 0.157480314960631 50.26787716877686 0.3897811105455421 0.157480314960631 50.28784810552991 0.407295152021843 0.157480314960631 50.28784810552993 2.280354519063654 0.157480314960631 50.30536214700624 0.4272660887748815 0.157480314960631 50.30536214700626 2.260383582310614 0.157480314960631 50.32011962310041 0.4493522125397739 0.157480314960631 50.32011962310039 2.238297458545719 0.157480314960631 50.33186802930484 2.214474047469999 0.157480314960631 50.33186802930485 0.4731756236154915 0.157480314960631 50.34040634713219 2.189320974252057 0.157480314960631 50.3404063471322 0.498328696833425 0.157480314960631 50.34558848359709 2.163268614948385 0.157480314960631 50.34558848359711 0.5243810561371139 0.157480314960631 50.3473257709079 2.136762732649773 0.157480314960631 50.3473257709079 0.5508869384357039 0.157480314960631 50.14425631911605 0.3478174866438403 0.157480314960631 50.17076220141466 0.3495547739546495 1.110223024625157e-015 50.14425631911605 0.3478174866438403 1.110223024625157e-015 50.17076220141466 0.3495547739546495 0.157480314960631 25.50480608586854 2.339832184441669 1.062992125984253 0.5491086559751146 2.339832184441677 1.110223024625157e-015 25.50480608586854 2.339832184441669 1.110223024625157e-015 0.5491086559751146 2.339832184441677 1.968503937007876 25.50480608586854 2.339832184441669 1.968503937007876 50.17076220141468 2.338094897130827 0.157480314960631 50.14425631911605 2.339832184441669 1.110223024625157e-015 50.17076220141468 2.338094897130827 1.110223024625157e-015 50.14425631911605 2.339832184441669 0.157480314960631 0.4965504143728469 0.3529586279589738 1.968503937007876 0.4965504143728469 0.3529586279589738 1.110223024625157e-015 50.19681456071832 2.332912760665919 0.157480314960631 50.19681456071832 2.332912760665919 1.110223024625157e-015 50.22196763393626 2.324374442838587 0.157480314960631 50.22196763393626 2.324374442838587 1.110223024625157e-015 50.24579104501199 2.312626036634129 0.157480314960631 50.24579104501199 2.312626036634129 1.110223024625157e-015 50.26787716877689 2.297868560539985 0.157480314960631 50.26787716877689 2.297868560539985 1.110223024625157e-015 50.28784810552993 2.280354519063654 0.157480314960631 50.28784810552993 2.280354519063654 1.110223024625157e-015 50.30536214700626 2.260383582310614 1.110223024625157e-015 50.30536214700626 2.260383582310614 0.157480314960631 50.32011962310039 2.238297458545719 1.110223024625157e-015 50.32011962310039 2.238297458545719 0.157480314960631 50.33186802930484 2.214474047469999 1.110223024625157e-015 50.33186802930484 2.214474047469999 0.157480314960631 50.34040634713219 2.189320974252057 1.110223024625157e-015 50.34040634713219 2.189320974252057 0.157480314960631 50.34558848359709 2.163268614948385 1.110223024625157e-015 50.34558848359709 2.163268614948385 0.157480314960631 50.3473257709079 2.136762732649773 1.110223024625157e-015 50.3473257709079 2.136762732649773 0.157480314960631 50.3473257709079 2.136762732649773 0.157480314960631 50.3473257709079 0.5508869384357039 1.110223024625157e-015 50.3473257709079 0.5508869384357039 0.157480314960631 50.3473257709079 2.136762732649773 1.110223024625157e-015 50.3473257709079 0.5508869384357039 0.157480314960631 50.34558848359711 0.5243810561371139 1.110223024625157e-015 50.34558848359711 0.5243810561371139 0.157480314960631 50.3473257709079 0.5508869384357039 1.110223024625157e-015 50.3404063471322 0.498328696833425 1.110223024625157e-015 50.3404063471322 0.498328696833425 0.157480314960631 50.33186802930485 0.4731756236154915 1.110223024625157e-015 50.33186802930485 0.4731756236154915 0.157480314960631 50.32011962310041 0.4493522125397739 1.110223024625157e-015 50.32011962310041 0.4493522125397739 0.157480314960631 50.30536214700624 0.4272660887748815 1.110223024625157e-015 50.30536214700624 0.4272660887748815 0.157480314960631 50.28784810552991 0.407295152021843 1.110223024625157e-015 50.28784810552991 0.407295152021843 0.157480314960631 50.26787716877686 0.3897811105455421 0.157480314960631 50.26787716877686 0.3897811105455421 1.110223024625157e-015 50.24579104501201 0.3750236344513794 0.157480314960631 50.24579104501201 0.3750236344513794 1.110223024625157e-015 50.22196763393623 0.3632752282469015 0.157480314960631 50.22196763393623 0.3632752282469015 1.110223024625157e-015 50.19681456071831 0.35473691041958 0.157480314960631 50.19681456071831 0.35473691041958 1.110223024625157e-015 0.5491086559751146 2.339832184441677 1.968503937007876 0.5226027736765068 2.338094897130853 1.110223024625157e-015 0.5491086559751146 2.339832184441677 1.110223024625157e-015 0.5226027736765068 2.338094897130853 1.968503937007876 0.4713973411549005 0.3614969457863064 1.968503937007876 0.4713973411549005 0.3614969457863064 1.110223024625157e-015 0.4965504143728471 2.332912760665936 1.110223024625157e-015 0.4965504143728471 2.332912760665936 1.968503937007876 0.4475739300791731 0.3732453519907652 1.968503937007876 0.4475739300791731 0.3732453519907652 1.110223024625157e-015 0.4713973411548998 2.324374442838602 1.110223024625157e-015 0.4713973411548998 2.324374442838602 1.968503937007876 0.4254878063142707 0.3880028280849154 1.968503937007876 0.4254878063142707 0.3880028280849154 1.110223024625157e-015 0.4475739300791732 2.312626036634144 1.110223024625157e-015 0.4475739300791732 2.312626036634144 1.968503937007876 0.4055168695612388 0.4055168695612393 1.968503937007876 0.4055168695612388 0.4055168695612393 1.110223024625157e-015 0.4254878063142705 2.297868560539994 1.110223024625157e-015 0.4254878063142705 2.297868560539994 1.968503937007876 0.3880028280849136 0.4254878063142707 1.110223024625157e-015 0.3880028280849136 0.4254878063142707 1.968503937007876 0.4055168695612396 2.280354519063669 1.110223024625157e-015 0.4055168695612396 2.280354519063669 1.968503937007876 0.3732453519907644 0.4475739300791728 1.110223024625157e-015 0.3732453519907644 0.4475739300791728 1.968503937007876 0.3880028280849145 2.260383582310638 1.968503937007876 0.3880028280849145 2.260383582310638 1.110223024625157e-015 0.361496945786306 0.4713973411548998 1.110223024625157e-015 0.361496945786306 0.4713973411548998 1.968503937007876 0.3732453519907648 2.238297458545735 1.968503937007876 0.3732453519907648 2.238297458545735 1.110223024625157e-015 0.352958627958972 0.4965504143728474 1.110223024625157e-015 0.352958627958972 0.4965504143728474 1.968503937007876 0.3614969457863068 2.214474047470008 1.968503937007876 0.3614969457863068 2.214474047470008 1.110223024625157e-015 0.3477764914940549 0.5226027736765067 1.110223024625157e-015 0.3477764914940549 0.5226027736765067 1.968503937007876 0.3529586279589722 2.189320974252061 1.968503937007876 0.3529586279589722 2.189320974252061 1.110223024625157e-015 0.3460392041832313 0.5491086559751139 1.110223024625157e-015 0.3460392041832313 0.5491086559751139 1.968503937007876 0.3477764914940558 2.163268614948401 1.968503937007876 0.3477764914940558 2.163268614948401 1.110223024625157e-015 0.3460392041832319 2.136762732649793 1.110223024625157e-015 0.3460392041832313 0.5491086559751139 1.968503937007876 0.3460392041832313 0.5491086559751139 1.110223024625157e-015 0.3460392041832319 2.136762732649793 1.968503937007876 0.3460392041832319 2.136762732649793 1.968503937007876 0.3460392041832319 2.136762732649793 1.110223024625157e-015 + + + + + + + + + + -0.2195141426946883 0.9756093178916528 -2.251662460960872e-031 -0.4283200860438445 0.9036270823140448 -2.039446246926806e-031 -0.1832544872618059 0.983065507938516 -2.276641252136103e-031 -0.4283200860438445 0.9036270823140448 -2.039446246926806e-031 -0.1104325181011955 0.9938836244479679 -2.317022766077274e-031 -0.1104325181011955 0.9938836244479679 -2.317022766077274e-031 -0.1104325181011955 0.9938836244479679 -2.317022766077274e-031 -0.6162319912743373 0.7875646849180484 -1.727743062721139e-031 -0.6162319912743373 0.7875646849180484 -1.727743062721139e-031 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 1.247349874666141e-015 1 -2.354039508393784e-031 1.247349874666141e-015 1 -2.354039508393784e-031 1.247349874666141e-015 1 -2.354039508393784e-031 1.247349874666141e-015 1 -2.354039508393784e-031 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0.7740832592965722 0.6330838077828211 -1.331758214899901e-031 -0.7740832592965722 0.6330838077828211 -1.331758214899901e-031 -1 -5.063450264559819e-035 9.643711856883543e-019 -1 -5.063450264559819e-035 9.643711856883543e-019 -1 -5.063450264559819e-035 9.643711856883543e-019 -1 -5.063450264559819e-035 9.643711856883543e-019 -0.9978589232386242 0.06540312922982872 3.458633610382481e-018 -0.9914448613738267 0.1305261922199271 5.938085634997029e-018 -0.9914448613738267 0.1305261922199271 5.938085634997029e-018 -0.9978589232386242 0.06540312922982872 3.458633610382481e-018 -0.9659258262888851 0.2588190451032043 1.081019779277784e-017 -0.9659258262888851 0.2588190451032043 1.081019779277784e-017 -0.9238795325113519 0.3826834323649326 1.549734446910911e-017 -0.9238795325113519 0.3826834323649326 1.549734446910911e-017 -0.8660254037849143 0.4999999999991764 1.9919327284905e-017 -0.8660254037849143 0.4999999999991764 1.9919327284905e-017 -0.7933533402911954 0.6087614290087726 2.400048488823272e-017 -0.7933533402911954 0.6087614290087726 2.400048488823272e-017 -0.7071067811865249 0.7071067811865701 2.767098754089725e-017 -0.7071067811865249 0.7071067811865701 2.767098754089725e-017 -0.60876142900828 0.7933533402915732 3.086803192490265e-017 -0.60876142900828 0.7933533402915732 3.086803192490265e-017 -0.4999999999994493 0.8660254037847566 3.353691572442538e-017 -0.4999999999994493 0.8660254037847566 3.353691572442538e-017 -0.3826834323655326 0.9238795325111033 3.563197359769641e-017 -0.3826834323655326 0.9238795325111033 3.563197359769641e-017 -0.2588190451025693 0.9659258262890552 3.711735852368559e-017 -0.2588190451025693 0.9659258262890552 3.711735852368559e-017 -0.1305261922200869 0.9914448613738056 3.796765515445271e-017 -0.1305261922200869 0.9914448613738056 3.796765515445271e-017 -0.06540312923095472 0.9978589232385504 3.814966628060576e-017 -0.06540312923095472 0.9978589232385504 3.814966628060576e-017 -0.8941736899130333 0.4477202388404067 -8.708083845489539e-032 -0.8941736899130333 0.4477202388404067 -8.708083845489539e-032 -0.9706451080888319 0.2405162658599619 -3.673793332284476e-032 -0.9706451080888319 0.2405162658599619 -3.673793332284476e-032 -0.9997671337217909 0.02157958131462663 1.539709831518109e-032 -0.9997671337217909 0.02157958131462663 1.539709831518109e-032 -0.9801191546728204 -0.1984097846464127 6.67810384924031e-032 -0.9801191546728204 -0.1984097846464127 6.67810384924031e-032 -0.9126596261640011 -0.4087204506385578 1.149073085081814e-031 -0.9126596261640011 -0.4087204506385578 1.149073085081814e-031 -0.8006793160253677 -0.5990931754653439 1.574282432564735e-031 -0.8006793160253677 -0.5990931754653439 1.574282432564735e-031 -0.6496407765509797 -0.7602413178999415 1.9226961353246e-031 -0.6496407765509797 -0.7602413178999415 1.9226961353246e-031 -0.5617119664874528 -0.8273328633052111 2.062622892710896e-031 -0.5617119664874528 -0.8273328633052111 2.062622892710896e-031 -0.4669118737456301 -0.8843038517135073 2.177318097629222e-031 -0.4669118737456301 -0.8843038517135073 2.177318097629222e-031 -0.4669118737456301 -0.8843038517135073 2.177318097629222e-031 -0.4669118737456301 -0.8843038517135073 2.177318097629222e-031 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.1305261922200457 -0.9914448613738112 -3.771590375694363e-017 -0.06540312923042768 -0.9978589232385848 -3.802352049403922e-017 -0.1305261922200457 -0.9914448613738112 -3.771590375694363e-017 -0.06540312923042768 -0.9978589232385848 -3.802352049403922e-017 -0.2588190451023318 -0.9659258262891188 -3.661816326487966e-017 -0.2588190451023318 -0.9659258262891188 -3.661816326487966e-017 -0.3826834323651677 -0.9238795325112544 -3.489387584687525e-017 -0.3826834323651677 -0.9238795325112544 -3.489387584687525e-017 -0.5000000000000009 -0.8660254037844382 -3.25725445387254e-017 -0.5000000000000009 -0.8660254037844382 -3.25725445387254e-017 -0.6087614290086468 -0.7933533402912919 -2.969388796270346e-017 -0.6087614290086468 -0.7933533402912919 -2.969388796270346e-017 -0.707106781186616 -0.707106781186479 -2.630716073093143e-017 -0.707106781186616 -0.707106781186479 -2.630716073093143e-017 -0.7933533402912433 -0.6087614290087099 -2.247031068533741e-017 -0.7933533402912433 -0.6087614290087099 -2.247031068533741e-017 -0.8660254037844346 -0.5000000000000071 -1.824898739396858e-017 -0.8660254037844346 -0.5000000000000071 -1.824898739396858e-017 -0.9238795325113181 -0.3826834323650143 -1.371541886870991e-017 -0.9238795325113181 -0.3826834323650143 -1.371541886870991e-017 -0.9659258262890479 -0.2588190451025965 -8.947175723984055e-018 -0.9659258262890479 -0.2588190451025965 -8.947175723984055e-018 -0.991444861373845 -0.130526192219789 -4.025843921976333e-018 -0.991444861373845 -0.130526192219789 -4.025843921976333e-018 -0.9978589232386543 -0.06540312922937021 -1.534020824458279e-018 -0.9978589232386543 -0.06540312922937021 -1.534020824458279e-018 0.1305261922200759 0.9914448613738072 -2.360634470126157e-031 0.0654031292301361 0.997858923238604 -2.362395058420794e-031 0.1305261922200759 0.9914448613738072 -2.360634470126157e-031 0.0654031292301361 0.997858923238604 -2.362395058420794e-031 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -0.06540312922959453 0.9978589232386395 -0 -0.1305261922200789 0.9914448613738068 0 -0.06540312922959453 0.9978589232386395 -0 -0.1305261922200789 0.9914448613738068 0 -2.847216503390403e-016 -1 2.354039508393783e-031 -2.847216503390403e-016 -1 2.354039508393783e-031 -2.847216503390403e-016 -1 2.354039508393783e-031 -2.847216503390403e-016 -1 2.354039508393783e-031 -2.847216503390403e-016 -1 2.354039508393783e-031 -0.1305261922203011 -0.9914448613737775 0 -0.06540312923079149 -0.9978589232385611 -0 -0.1305261922203011 -0.9914448613737775 0 -0.06540312923079149 -0.9978589232385611 -0 0.2588190451025202 0.9659258262890684 -2.326838321583154e-031 0.2588190451025202 0.9659258262890684 -2.326838321583154e-031 -0.2588190451024253 -0.9659258262890939 0 -0.2588190451024253 -0.9659258262890939 0 -0.3826834323650169 -0.9238795325113171 0 -0.3826834323650169 -0.9238795325113171 0 -0.4999999999999031 -0.8660254037844946 0 -0.4999999999999031 -0.8660254037844946 0 -0.6087614290086439 -0.7933533402912941 0 -0.6087614290086439 -0.7933533402912941 0 -0.7071067811866093 -0.7071067811864858 0 -0.7071067811866093 -0.7071067811864858 0 -0.7933533402914218 -0.6087614290084773 0 -0.7933533402914218 -0.6087614290084773 0 -0.8660254037845377 -0.4999999999998284 0 -0.8660254037845377 -0.4999999999998284 0 -0.9238795325112122 -0.3826834323652698 0 -0.9238795325112122 -0.3826834323652698 0 -0.9659258262890901 -0.2588190451024401 0 -0.9659258262890901 -0.2588190451024401 0 -0.9914448613738833 -0.1305261922194982 0 -0.9914448613738833 -0.1305261922194982 0 -0.997858923238638 -0.06540312922961909 -0 -0.997858923238638 -0.06540312922961909 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -0.9978589232386694 0.06540312922913877 -0 -0.9914448613739054 0.1305261922193298 0 -0.9914448613739054 0.1305261922193298 0 -0.9978589232386694 0.06540312922913877 -0 -0.9659258262890584 0.2588190451025578 0 -0.9659258262890584 0.2588190451025578 0 -0.923879532511276 0.3826834323651157 0 -0.923879532511276 0.3826834323651157 0 -0.8660254037843593 0.5000000000001372 0 -0.8660254037843593 0.5000000000001372 0 -0.793353340290994 0.608761429009035 0 -0.793353340290994 0.608761429009035 0 -0.7071067811861586 0.7071067811869366 0 -0.7071067811861586 0.7071067811869366 0 -0.6087614290088786 0.793353340291114 0 -0.6087614290088786 0.793353340291114 0 -0.5000000000005405 0.8660254037841265 0 -0.5000000000005405 0.8660254037841265 0 -0.3826834323649039 0.9238795325113639 0 -0.3826834323649039 0.9238795325113639 0 -0.2588190451027368 0.9659258262890103 0 -0.2588190451027368 0.9659258262890103 0 0.0654031292301436 -0.9978589232386035 2.33560359979311e-031 0.1305261922200579 -0.9914448613738096 2.307166278009732e-031 0.0654031292301436 -0.9978589232386035 2.33560359979311e-031 0.1305261922200579 -0.9914448613738096 2.307166278009732e-031 0.382683432365069 0.9238795325112953 -2.253229324236416e-031 0.382683432365069 0.9238795325112953 -2.253229324236416e-031 0.2588190451025239 -0.9659258262890675 2.220816792941599e-031 0.2588190451025239 -0.9659258262890675 2.220816792941599e-031 0.5000000000000147 0.8660254037844301 -2.141066948438753e-031 0.5000000000000147 0.8660254037844301 -2.141066948438753e-031 0.3826834323650852 -0.9238795325112886 2.096468516819501e-031 0.3826834323650852 -0.9238795325112886 2.096468516819501e-031 0.6087614290087049 0.7933533402912473 -1.992270323537472e-031 0.6087614290087049 0.7933533402912473 -1.992270323537472e-031 0.4999999999999988 -0.8660254037844394 1.936249083123728e-031 0.4999999999999988 -0.8660254037844394 1.936249083123728e-031 0.7071067811865293 0.7071067811865658 -1.809385401038751e-031 0.7071067811865293 0.7071067811865658 -1.809385401038751e-031 0.6087614290087232 -0.7933533402912332 1.742899890786038e-031 0.6087614290087232 -0.7933533402912332 1.742899890786038e-031 0.7933533402912396 0.6087614290087149 -1.595541392671784e-031 0.7933533402912396 0.6087614290087149 -1.595541392671784e-031 0.7071067811865497 -0.7071067811865455 1.519729198093864e-031 0.7071067811865497 -0.7071067811865455 1.519729198093864e-031 0.8660254037844386 0.4999999999999999 -1.35439722870862e-031 0.8660254037844386 0.4999999999999999 -1.35439722870862e-031 0.7933533402912354 -0.6087614290087204 1.270555517473774e-031 0.7933533402912354 -0.6087614290087204 1.270555517473774e-031 0.9238795325112905 0.3826834323650806 -1.090078952652364e-031 0.9238795325112905 0.3826834323650806 -1.090078952652364e-031 0.8660254037844404 -0.4999999999999971 9.996422796851562e-032 0.8660254037844404 -0.4999999999999971 9.996422796851562e-032 0.9659258262890674 0.258819045102524 -8.071091234892916e-032 0.9659258262890674 0.258819045102524 -8.071091234892916e-032 0.9238795325112879 -0.3826834323650874 7.116248853379323e-032 0.9238795325112879 -0.3826834323650874 7.116248853379323e-032 0.9914448613738091 0.1305261922200617 -5.103294334503805e-032 0.9914448613738091 0.1305261922200617 -5.103294334503805e-032 0.965925826289068 -0.2588190451025222 4.114313919028921e-032 0.965925826289068 -0.2588190451025222 4.114313919028921e-032 0.9978589232386044 0.06540312923013249 -3.583408847236163e-032 0.9978589232386044 0.06540312923013249 -3.583408847236163e-032 0.9914448613738105 -0.1305261922200517 1.041981932820484e-032 0.9914448613738105 -0.1305261922200517 1.041981932820484e-032 1 -3.846068690370998e-016 -2.04817865315044e-032 1 -3.846068690370998e-016 -2.04817865315044e-032 1 -3.846068690370998e-016 -2.04817865315044e-032 1 -3.846068690370998e-016 -2.04817865315044e-032 0.9978589232386037 -0.0654031292301418 -5.041778436296195e-033 0.9978589232386037 -0.0654031292301418 -5.041778436296195e-033 + + + + + + + + + + + + + + +

0 1 2 1 0 3 4 5 6 5 4 2 2 4 0 3 7 1 7 3 8 9 10 11 10 9 12 12 9 13 13 9 14 14 9 15 15 9 16 16 9 17 17 9 18 18 9 19 18 19 20 18 20 21 21 20 22 21 22 23 23 22 24 24 22 25 24 25 26 26 25 27 26 27 28 26 28 29 29 28 30 30 28 31 30 31 32 30 32 33 33 32 34 33 34 35 35 34 36 36 34 37 36 37 38 38 37 39 38 39 40 40 39 41 42 17 43 17 42 44 17 44 45 17 45 46 17 46 47 17 47 16 48 49 50 49 48 51 52 53 54 53 52 55 53 55 56 57 54 53 8 58 7 58 8 59 60 61 62 61 60 63 64 65 66 65 64 67 66 68 69 68 66 65 69 70 71 70 69 68 71 72 73 72 71 70 73 74 75 74 73 72 75 76 77 76 75 74 78 76 79 76 78 77 80 79 81 79 80 78 82 81 83 81 82 80 84 83 85 83 84 82 86 85 87 85 86 84 88 87 89 87 88 86 90 58 59 58 90 91 92 91 90 91 92 93 94 93 92 93 94 95 96 95 94 95 96 97 98 97 96 97 98 99 100 99 98 99 100 101 102 101 100 101 102 103 102 104 103 104 102 105 106 107 108 107 106 109 110 111 112 111 110 113 111 113 114 114 113 115 116 117 118 117 116 119 120 118 121 118 120 116 122 121 123 121 122 120 124 123 125 123 124 122 126 125 127 125 126 124 128 127 129 127 128 126 128 130 131 130 128 129 131 132 133 132 131 130 133 134 135 134 133 132 135 136 137 136 135 134 137 138 139 138 137 136 139 140 141 140 139 138 142 143 144 143 142 145 146 147 148 147 146 149 149 146 150 150 146 151 151 146 152 152 146 153 153 146 154 154 146 155 155 146 156 156 146 157 157 146 158 158 146 159 159 146 160 161 162 163 162 161 164 162 164 165 162 165 166 162 166 167 162 167 168 162 168 169 162 169 170 162 170 171 162 171 172 162 172 173 162 173 160 162 160 146 162 146 174 162 174 175 175 174 176 176 174 177 176 177 178 178 177 179 178 179 180 180 179 181 180 181 182 180 182 183 183 182 184 184 182 185 184 185 186 186 185 187 186 187 188 188 187 189 188 189 190 188 190 191 191 190 192 191 192 193 193 192 194 193 194 195 195 194 196 195 196 197 198 199 200 199 198 201 202 203 204 203 202 205 205 202 206 207 208 209 208 207 210 211 144 212 144 211 142 213 209 214 209 213 207 215 214 216 214 215 213 217 216 218 216 217 215 219 218 220 218 219 217 221 220 222 220 221 219 221 223 224 223 221 222 224 225 226 225 224 223 226 227 228 227 226 225 228 229 230 229 228 227 230 231 232 231 230 229 232 233 234 233 232 231 235 236 237 236 235 238 239 240 241 240 239 242 241 243 244 243 241 240 244 245 246 245 244 243 246 247 248 247 246 245 248 249 250 249 248 247 250 251 252 251 250 249 253 251 254 251 253 252 255 254 256 254 255 253 257 256 258 256 257 255 259 258 260 258 259 257 201 260 199 260 201 259 261 262 263 262 261 264 265 212 266 212 265 211 264 267 262 267 264 268 269 266 270 266 269 265 268 271 267 271 268 272 273 270 274 270 273 269 272 275 271 275 272 276 277 274 278 274 277 273 276 279 275 279 276 280 281 277 278 277 281 282 280 283 279 283 280 284 285 282 281 282 285 286 283 287 288 287 283 284 289 286 285 286 289 290 288 291 292 291 288 287 293 290 289 290 293 294 292 295 296 295 292 291 297 294 293 294 297 298 296 299 300 299 296 295 301 298 297 298 301 302 300 303 304 303 300 299 305 306 307 306 305 308 304 309 310 309 304 303

+
+
+
+ + + + 43.38400397036494 7.421059675912715 0.07874015748031579 43.37882183390003 3.127233759244795 0.07874015748031607 43.37882183390003 7.395007316609055 0.07874015748031579 43.38055912121086 3.10072787694619 0.07874015748031607 43.38574125767577 3.074675517642528 0.07874015748031607 43.39254228819227 7.446212749130662 0.07874015748031579 43.39427957550313 3.04952244442458 0.07874015748031607 43.40429069439674 7.470036160206389 0.07874015748031579 43.4060279817076 3.025699033348864 0.07874015748031607 43.4132129304469 7.39162008924713 0.07874015748031579 43.41904817049088 7.492122283971291 0.07874015748031579 43.41729449628541 7.412139506376729 0.07874015748031579 43.42438369328506 7.43302360729623 0.07874015748031579 43.43656221196721 7.512093220724323 0.07874015748031579 43.4341381633926 7.452803715947015 0.07874015748031579 43.44639100492 7.47114138918596 0.07874015748031579 43.45653314872024 7.529607262200647 0.07874015748031579 43.46093256835167 7.487722864339863 0.07874015748031579 43.47861927248514 7.544364738294798 0.07874015748031579 43.47751404350557 7.502264427771523 0.07874015748031579 43.49585171674453 7.514517269298941 0.07874015748031579 43.50244268356087 7.556113144499255 0.07874015748031579 43.51563182539531 7.524271739406478 0.07874015748031579 43.52759575677882 7.56465146232659 0.07874015748031579 43.53651592631481 7.531360936406135 0.07874015748031579 43.55364811608248 7.569833598791506 0.07874015748031579 43.55703534344437 7.535442502244626 0.07874015748031579 50.144256319116 7.569833598791506 0.07874015748031607 50.14313047118674 7.535442502244621 0.07874015748031607 50.16626363075097 7.53392627486092 0.07874015748031607 50.1707622014146 7.568096311480678 0.07874015748031607 50.18789439118228 7.529623649095314 0.07874015748031607 50.19681456071828 7.562914175015767 0.07874015748031607 50.20877849210176 7.522534452095655 0.07874015748031607 50.22196763393622 7.554375857188427 0.07874015748031607 50.22855860075256 7.512779981988107 0.07874015748031607 50.24579104501194 7.542627450983966 0.07874015748031607 50.24689627399151 7.500527140460703 0.07874015748031607 50.26787716877683 7.527869974889834 0.07874015748031607 50.26347774914542 7.485985577029031 0.07874015748031607 50.27801931257708 7.469404101875151 0.07874015748031607 50.28784810552988 7.510355933413502 0.07874015748031607 50.29027215410449 7.451066428636207 0.07874015748031607 50.3053621470062 7.490384996660477 0.07874015748031607 50.30002662421204 7.431286319985366 0.07874015748031607 50.30711582121172 7.410402219065904 0.07874015748031607 50.32011962310036 7.468298872895575 0.07874015748031607 50.31141844697731 7.388771458634578 0.07874015748031607 50.31293467436102 7.365638299070358 0.07874015748031607 50.31293467436102 3.128359607174147 0.07874015748031607 50.32011962310035 3.025699033348873 0.07874015748031607 50.33186802930481 3.049522444424608 0.07874015748031607 50.3318680293048 7.44447546181984 0.07874015748031607 50.34040634713218 7.419322388601879 0.07874015748031607 50.34040634713214 3.074675517642548 0.07874015748031607 50.34558848359704 3.100727876946217 0.07874015748031607 50.34558848359706 7.393270029298235 0.07874015748031607 50.3473257709079 3.127233759244805 0.07874015748031607 50.3473257709079 7.366764146999632 0.07874015748031607 43.4132129304469 3.128359607174164 0.07874015748031607 43.42078545780171 3.003612909583954 0.07874015748031607 43.41472915783061 3.105226447609857 0.07874015748031607 43.41903178359623 3.083595687178518 0.07874015748031607 43.4261209805959 3.062711586259032 0.07874015748031607 43.43829949927805 2.98364197283092 0.07874015748031607 43.43587545070344 3.042931477608274 0.07874015748031607 43.44812829223088 3.024593804369232 0.07874015748031607 43.45827043603106 2.96612793135459 0.07874015748031607 43.46266985566252 3.008012329215369 0.07874015748031607 43.480356559796 2.951370455260453 0.07874015748031607 43.47925133081637 2.993470765783733 0.07874015748031607 43.49758900405537 2.981217924256313 0.07874015748031607 43.5041799708717 2.939622049055988 0.07874015748031607 43.51736911270614 2.971463454148768 0.07874015748031607 43.52933304408965 2.931083731228659 0.07874015748031607 43.53825321362565 2.964374257149114 0.07874015748031607 43.55538540339332 2.925901594763743 0.07874015748031607 43.55988397405696 2.960071631383501 0.07874015748031607 43.58189128569192 2.924164307452924 0.07874015748031607 43.58301713362136 2.958555403999797 0.07874015748031607 50.14425631911599 2.924164307452924 0.07874015748031607 50.14313047118665 2.958555403999804 0.07874015748031607 50.166263630751 2.960071631383512 0.07874015748031607 50.17076220141464 2.925901594763754 0.07874015748031607 50.1878943911823 2.96437425714911 0.07874015748031607 50.19681456071832 2.931083731228657 0.07874015748031607 50.20877849210176 2.971463454148789 0.07874015748031607 50.22196763393622 2.939622049056019 0.07874015748031607 50.22855860075259 2.981217924256331 0.07874015748031607 50.24579104501196 2.951370455260466 0.07874015748031607 50.24689627399157 2.993470765783735 0.07874015748031607 50.26787716877688 2.966127931354595 0.07874015748031607 50.26347774914544 3.008012329215407 0.07874015748031607 50.27801931257705 3.024593804369262 0.07874015748031607 50.28784810552991 2.98364197283095 0.07874015748031607 50.2902721541045 3.042931477608267 0.07874015748031607 50.3053621470062 3.003612909583975 0.07874015748031607 50.30002662421204 3.062711586259064 0.07874015748031607 50.30711582121167 3.083595687178512 0.07874015748031607 50.31141844697729 3.105226447609863 0.07874015748031607 50.144256319116 7.569833598791506 1.090510587941475e-015 43.55364811608248 7.569833598791506 0.07874015748031579 43.55364811608248 7.569833598791506 8.326672684688674e-016 50.144256319116 7.569833598791506 0.07874015748031607 50.1707622014146 7.568096311480678 0.07874015748031607 50.144256319116 7.569833598791506 1.090510587941475e-015 50.1707622014146 7.568096311480678 1.090510587941475e-015 50.144256319116 7.569833598791506 0.07874015748031607 50.19681456071828 7.562914175015767 0.07874015748031607 50.19681456071828 7.562914175015767 1.090510587941475e-015 50.22196763393622 7.554375857188427 0.07874015748031607 50.22196763393622 7.554375857188427 1.090510587941475e-015 50.24579104501194 7.542627450983966 0.07874015748031607 50.24579104501194 7.542627450983966 1.090510587941475e-015 50.26787716877683 7.527869974889834 0.07874015748031607 50.26787716877683 7.527869974889834 1.090510587941475e-015 50.28784810552988 7.510355933413502 0.07874015748031607 50.28784810552988 7.510355933413502 1.090510587941475e-015 50.3053621470062 7.490384996660477 1.090510587941475e-015 50.3053621470062 7.490384996660477 0.07874015748031607 50.32011962310036 7.468298872895575 1.118266163557104e-015 50.32011962310036 7.468298872895575 0.07874015748031607 50.3318680293048 7.44447546181984 1.118266163557104e-015 50.3318680293048 7.44447546181984 0.07874015748031607 50.34040634713218 7.419322388601879 1.118266163557104e-015 50.34040634713218 7.419322388601879 0.07874015748031607 50.34558848359706 7.393270029298235 1.118266163557104e-015 50.34558848359706 7.393270029298235 0.07874015748031607 50.3473257709079 7.366764146999632 1.118266163557104e-015 50.3473257709079 7.366764146999632 0.07874015748031607 50.3473257709079 7.366764146999632 0.07874015748031607 50.3473257709079 3.127233759244805 1.103017739216966e-015 50.3473257709079 3.127233759244805 0.07874015748031607 50.3473257709079 7.366764146999632 1.118266163557104e-015 50.3473257709079 3.127233759244805 0.07874015748031607 50.34558848359704 3.100727876946217 1.105899590885709e-015 50.34558848359704 3.100727876946217 0.07874015748031607 50.3473257709079 3.127233759244805 1.103017739216966e-015 50.34040634713214 3.074675517642548 1.108591182719098e-015 50.34040634713214 3.074675517642548 0.07874015748031607 50.33186802930481 3.049522444424608 1.111046460834616e-015 50.33186802930481 3.049522444424608 0.07874015748031607 50.32011962310035 3.025699033348873 1.113223414742969e-015 50.32011962310035 3.025699033348873 0.07874015748031607 50.3053621470062 3.003612909583975 1.115084796159225e-015 50.3053621470062 3.003612909583975 0.07874015748031607 50.28784810552991 2.98364197283095 1.116598756331273e-015 50.28784810552991 2.98364197283095 0.07874015748031607 50.26787716877688 2.966127931354595 1.11773939098083e-015 50.26787716877688 2.966127931354595 0.07874015748031607 50.24579104501196 2.951370455260466 1.11848718353279e-015 50.24579104501196 2.951370455260466 0.07874015748031607 50.22196763393622 2.939622049056019 1.118829339049262e-015 50.22196763393622 2.939622049056019 0.07874015748031607 50.19681456071832 2.931083731228657 0.07874015748031607 50.19681456071832 2.931083731228657 1.118760003154504e-015 50.17076220141464 2.925901594763754 0.07874015748031607 50.17076220141464 2.925901594763754 1.118280362204888e-015 50.14425631911599 2.924164307452924 0.07874015748031607 50.14425631911599 2.924164307452924 1.117398622990049e-015 43.58189128569192 2.924164307452924 0.07874015748031607 50.14425631911599 2.924164307452924 1.117398622990049e-015 43.58189128569192 2.924164307452924 1.109233975091996e-015 50.14425631911599 2.924164307452924 0.07874015748031607 43.55538540339332 2.925901594763743 1.109463768595622e-015 43.58189128569192 2.924164307452924 0.07874015748031607 43.58189128569192 2.924164307452924 1.109233975091996e-015 43.55538540339332 2.925901594763743 0.07874015748031607 43.52933304408965 2.931083731228659 0.07874015748031607 43.52933304408965 2.931083731228659 1.109462778393509e-015 43.5041799708717 2.939622049055988 0.07874015748031607 43.5041799708717 2.939622049055988 1.109231021428294e-015 43.480356559796 2.951370455260453 0.07874015748031607 43.480356559796 2.951370455260453 1.108772463125903e-015 43.45827043603106 2.96612793135459 0.07874015748031607 43.45827043603106 2.96612793135459 1.108094949546031e-015 43.43829949927805 2.98364197283092 0.07874015748031607 43.43829949927805 2.98364197283092 1.107210073133866e-015 43.42078545780171 3.003612909583954 1.106132974370159e-015 43.42078545780171 3.003612909583954 0.07874015748031607 43.4060279817076 3.025699033348864 1.104882082713383e-015 43.4060279817076 3.025699033348864 0.07874015748031607 43.39427957550313 3.04952244442458 1.1034788012666e-015 43.39427957550313 3.04952244442458 0.07874015748031607 43.38574125767577 3.074675517642528 1.101947140564425e-015 43.38574125767577 3.074675517642528 0.07874015748031607 43.38055912121086 3.10072787694619 1.100313307746131e-015 43.38055912121086 3.10072787694619 0.07874015748031607 43.37882183390003 3.127233759244795 1.098605258144222e-015 43.37882183390003 3.127233759244795 0.07874015748031607 43.37882183390003 7.395007316609055 8.326672684688674e-016 43.37882183390003 3.127233759244795 0.07874015748031607 43.37882183390003 3.127233759244795 1.098605258144222e-015 43.37882183390003 7.395007316609055 0.07874015748031579 43.38400397036494 7.421059675912715 8.326672684688674e-016 43.37882183390003 7.395007316609055 0.07874015748031579 43.37882183390003 7.395007316609055 8.326672684688674e-016 43.38400397036494 7.421059675912715 0.07874015748031579 43.39254228819227 7.446212749130662 8.326672684688674e-016 43.39254228819227 7.446212749130662 0.07874015748031579 43.40429069439674 7.470036160206389 8.326672684688674e-016 43.40429069439674 7.470036160206389 0.07874015748031579 43.41904817049088 7.492122283971291 8.326672684688674e-016 43.41904817049088 7.492122283971291 0.07874015748031579 43.43656221196721 7.512093220724323 8.326672684688674e-016 43.43656221196721 7.512093220724323 0.07874015748031579 43.45653314872024 7.529607262200647 0.07874015748031579 43.45653314872024 7.529607262200647 8.326672684688674e-016 43.47861927248514 7.544364738294798 0.07874015748031579 43.47861927248514 7.544364738294798 8.326672684688674e-016 43.50244268356087 7.556113144499255 0.07874015748031579 43.50244268356087 7.556113144499255 8.326672684688674e-016 43.52759575677882 7.56465146232659 0.07874015748031579 43.52759575677882 7.56465146232659 8.326672684688674e-016 43.55364811608248 7.569833598791506 0.07874015748031579 43.55364811608248 7.569833598791506 8.326672684688674e-016 + + + + + + + + + + 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.1305261922199813 -0.9914448613738196 2.780848713701879e-017 -0.06540312923029371 -0.9978589232385937 2.927210314289912e-017 -0.1305261922199813 -0.9914448613738196 2.780848713701879e-017 -0.06540312923029371 -0.9978589232385937 2.927210314289912e-017 -0.2588190451024848 -0.965925826289078 2.453079183995709e-017 -0.2588190451024848 -0.965925826289078 2.453079183995709e-017 -0.382683432365306 -0.9238795325111974 2.083336789328604e-017 -0.382683432365306 -0.9238795325111974 2.083336789328604e-017 -0.5000000000000238 -0.8660254037844249 1.677947924587394e-017 -0.5000000000000238 -0.8660254037844249 1.677947924587394e-017 -0.6087614290084881 -0.7933533402914136 1.24384890564192e-017 -0.6087614290084881 -0.7933533402914136 1.24384890564192e-017 -0.7071067811864248 -0.7071067811866704 7.884672870593892e-018 -0.7071067811864248 -0.7071067811866704 7.884672870593892e-018 -0.7933533402911389 -0.6087614290088461 3.195947745911922e-018 -0.7933533402911389 -0.6087614290088461 3.195947745911922e-018 -0.8660254037845401 -0.4999999999998245 -1.547460930799239e-018 -0.8660254037845401 -0.4999999999998245 -1.54746093079924e-018 -0.923879532511154 -0.3826834323654104 -6.264392121914531e-018 -0.923879532511154 -0.3826834323654104 -6.264392121914531e-018 -0.9659258262890302 -0.2588190451026624 -1.087413782703309e-017 -0.9659258262890302 -0.2588190451026624 -1.087413782703309e-017 -0.9914448613738499 -0.1305261922197522 -1.529782401905813e-017 -0.9914448613738499 -0.1305261922197522 -1.529782401905813e-017 -0.9978589232385668 -0.06540312923070414 -1.741608127676964e-017 -0.9978589232385668 -0.06540312923070414 -1.741608127676964e-017 -1 6.99914032825858e-035 -1.945976020073421e-017 -1 6.99914032825858e-035 -1.945976020073421e-017 -1 6.99914032825858e-035 -1.945976020073421e-017 -1 6.99914032825858e-035 -1.945976020073421e-017 -0.997858923238512 0.06540312923154029 -2.142010944402561e-017 -0.9914448613737562 0.1305261922204639 -2.328873449013242e-017 -0.9914448613737562 0.1305261922204639 -2.328873449013242e-017 -0.997858923238512 0.06540312923154029 -2.142010944402561e-017 -0.9659258262891491 0.2588190451022194 -2.671923207551683e-017 -0.9659258262891491 0.2588190451022194 -2.671923207551682e-017 -0.9238795325113062 0.3826834323650429 -2.969255619214416e-017 -0.9238795325113063 0.3826834323650429 -2.969255619214416e-017 -0.8660254037844481 0.4999999999999837 -3.215783243998618e-017 -0.8660254037844481 0.4999999999999837 -3.215783243998619e-017 -0.7933533402914976 0.6087614290083786 -3.40728792589387e-017 -0.7933533402914977 0.6087614290083787 -3.407287925893871e-017 -0.7071067811871351 0.7071067811859598 -3.540492966698771e-017 -0.707106781187135 0.70710678118596 -3.54049296669877e-017 -0.6087614290086183 0.7933533402913137 -3.61311919123416e-017 -0.6087614290086183 0.7933533402913137 -3.61311919123416e-017 -0.4999999999992923 0.8660254037848472 -3.623923944660778e-017 -0.4999999999992923 0.8660254037848472 -3.623923944660778e-017 -0.3826834323655242 0.9238795325111068 -3.5727223546533e-017 -0.3826834323655242 0.9238795325111068 -3.5727223546533e-017 -0.2588190451029578 0.9659258262889511 -3.460390494611714e-017 -0.2588190451029578 0.9659258262889511 -3.460390494611714e-017 -0.1305261922198164 0.9914448613738415 -3.28885039380478e-017 -0.1305261922198164 0.9914448613738415 -3.28885039380478e-017 -0.06540312923028883 0.997858923238594 -3.181756156529731e-017 -0.06540312923028883 0.997858923238594 -3.181756156529731e-017 6.767212850674795e-017 1 -3.061037150919461e-017 6.767212850674795e-017 1 -3.061037150919461e-017 6.767212850674795e-017 1 -3.061037150919461e-017 6.767212850674795e-017 1 -3.061037150919461e-017 0.1305261922199325 0.991444861373826 -2.780848713701993e-017 0.06540312922994411 0.9978589232386167 -2.927210314290662e-017 0.06540312922994411 0.9978589232386167 -2.927210314290662e-017 0.1305261922199325 0.991444861373826 -2.780848713701993e-017 0.2588190451023891 0.9659258262891036 -2.453079183995972e-017 0.2588190451023891 0.9659258262891036 -2.453079183995972e-017 0.3826834323652765 0.9238795325112095 -2.083336789328698e-017 0.3826834323652765 0.9238795325112095 -2.083336789328698e-017 0.4999999999998008 0.8660254037845535 -1.677947924588222e-017 0.4999999999998008 0.8660254037845535 -1.677947924588222e-017 0.6087614290084553 0.7933533402914387 -1.24384890564206e-017 0.6087614290084553 0.7933533402914387 -1.24384890564206e-017 0.7071067811866578 0.7071067811864372 -7.884672870582221e-018 0.7071067811866578 0.7071067811864372 -7.884672870582221e-018 0.7933533402916122 0.6087614290082292 -3.195947745883828e-018 0.7933533402916122 0.6087614290082292 -3.195947745883828e-018 0.8660254037845893 0.499999999999739 1.547460930802815e-018 0.8660254037845894 0.4999999999997391 1.547460930802815e-018 0.9238795325109803 0.3826834323658298 6.26439212189831e-018 0.9238795325109803 0.3826834323658298 6.26439212189831e-018 0.9659258262889898 0.2588190451028135 1.087413782702768e-017 0.9659258262889898 0.2588190451028135 1.087413782702768e-017 0.9914448613738075 0.1305261922200738 1.529782401904747e-017 0.9914448613738075 0.1305261922200738 1.529782401904747e-017 0.9978589232385846 0.06540312923043123 1.741608127677834e-017 0.9978589232385846 0.06540312923043123 1.741608127677834e-017 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 0.9659258262890843 -0.2588190451024608 1.416353255915568e-017 0.9807852804032251 -0.1950903220161558 -0 0.9807852804032251 -0.1950903220161558 -0 0.9659258262890843 -0.2588190451024608 1.416353255915568e-017 0.9238795325112965 -0.3826834323650666 2.96925561921447e-017 0.9238795325112965 -0.3826834323650666 2.96925561921447e-017 0.8660254037844343 -0.5000000000000074 3.215783243998664e-017 0.8660254037844343 -0.5000000000000074 3.215783243998664e-017 0.7933533402912668 -0.6087614290086795 3.407287925894342e-017 0.7933533402912668 -0.6087614290086795 3.407287925894342e-017 0.7071067811865319 -0.707106781186563 3.540492966699442e-017 0.7071067811865319 -0.707106781186563 3.540492966699442e-017 0.6087614290087207 -0.7933533402912351 3.613119191234118e-017 0.6087614290087207 -0.7933533402912351 3.613119191234118e-017 0.4999999999999814 -0.8660254037844495 3.623923944660901e-017 0.4999999999999814 -0.8660254037844495 3.623923944660901e-017 0.382683432365068 -0.9238795325112956 3.572722354652991e-017 0.382683432365068 -0.9238795325112956 3.572722354652991e-017 0.2588190451025379 -0.9659258262890638 1.765831679721354e-017 0.2588190451025379 -0.9659258262890638 1.765831679721354e-017 0.1950903220161044 -0.9807852804032353 0 0.1950903220161044 -0.9807852804032353 0 + + + + + + + + + + + + + + +

0 1 2 1 0 3 3 0 4 4 0 5 4 5 6 6 5 7 6 7 8 8 7 9 9 7 10 9 10 11 11 10 12 12 10 13 12 13 14 14 13 15 15 13 16 15 16 17 17 16 18 17 18 19 19 18 20 20 18 21 20 21 22 22 21 23 22 23 24 24 23 25 24 25 26 26 25 27 26 27 28 28 27 29 29 27 30 29 30 31 31 30 32 31 32 33 33 32 34 33 34 35 35 34 36 35 36 37 37 36 38 37 38 39 39 38 40 40 38 41 40 41 42 42 41 43 42 43 44 44 43 45 45 43 46 45 46 47 47 46 48 48 46 49 49 46 50 50 46 51 51 46 52 51 52 53 51 53 54 54 53 55 55 53 56 55 56 57 57 56 58 8 59 60 59 8 9 60 59 61 60 61 62 60 62 63 60 63 64 64 63 65 64 65 66 64 66 67 67 66 68 67 68 69 69 68 70 69 70 71 69 71 72 72 71 73 72 73 74 74 73 75 74 75 76 76 75 77 76 77 78 78 77 79 78 79 80 80 79 81 80 81 82 80 82 83 83 82 84 83 84 85 85 84 86 85 86 87 87 86 88 87 88 89 89 88 90 89 90 91 91 90 92 91 92 93 91 93 94 94 93 95 94 95 96 96 95 97 96 97 98 96 98 50 50 98 99 50 99 49 100 101 102 101 100 103 104 105 106 105 104 107 108 106 109 106 108 104 110 109 111 109 110 108 112 111 113 111 112 110 114 113 115 113 114 112 116 115 117 115 116 114 116 118 119 118 116 117 119 120 121 120 119 118 121 122 123 122 121 120 123 124 125 124 123 122 125 126 127 126 125 124 127 128 129 128 127 126 130 131 132 131 130 133 134 135 136 135 134 137 136 138 139 138 136 135 139 140 141 140 139 138 141 142 143 142 141 140 143 144 145 144 143 142 145 146 147 146 145 144 148 147 146 147 148 149 150 149 148 149 150 151 152 151 150 151 152 153 154 152 155 152 154 153 156 155 157 155 156 154 158 157 159 157 158 156 160 161 162 161 160 163 164 165 166 165 164 167 168 164 169 164 168 167 170 169 171 169 170 168 172 171 173 171 172 170 174 173 175 173 174 172 176 175 177 175 176 174 178 176 177 176 178 179 180 179 178 179 180 181 182 181 180 181 182 183 184 183 182 183 184 185 186 185 184 185 186 187 188 187 186 187 188 189 190 191 192 191 190 193 194 195 196 195 194 197 198 197 194 197 198 199 200 199 198 199 200 201 202 201 200 201 202 203 204 203 202 203 204 205 206 204 207 204 206 205 208 207 209 207 208 206 210 209 211 209 210 208 212 211 213 211 212 210 214 213 215 213 214 212

+
+
+
+ + + + 43.41729449628541 7.412139506376729 -0.1968503937007866 43.4132129304469 3.128359607174164 -0.1968503937007863 43.4132129304469 7.39162008924713 -0.1968503937007866 43.41472915783061 3.105226447609857 -0.1968503937007863 43.41903178359623 3.083595687178518 -0.1968503937007863 43.42438369328506 7.43302360729623 -0.1968503937007866 43.4261209805959 3.062711586259032 -0.1968503937007863 43.4341381633926 7.452803715947015 -0.1968503937007866 43.43587545070344 3.042931477608274 -0.1968503937007863 43.44639100492 7.47114138918596 -0.1968503937007866 43.44812829223088 3.024593804369232 -0.1968503937007863 43.46093256835167 7.487722864339863 -0.1968503937007866 43.46266985566252 3.008012329215369 -0.1968503937007863 43.47751404350557 7.502264427771523 -0.1968503937007866 43.47925133081637 2.993470765783733 -0.1968503937007863 43.49585171674453 7.514517269298941 -0.1968503937007866 43.49758900405537 2.981217924256313 -0.1968503937007863 43.51563182539531 7.524271739406478 -0.1968503937007866 43.51736911270614 2.971463454148768 -0.1968503937007863 43.53651592631481 7.531360936406135 -0.1968503937007866 43.53825321362565 2.964374257149114 -0.1968503937007863 43.55703534344437 7.535442502244626 -0.1968503937007866 43.55988397405696 2.960071631383501 -0.1968503937007863 50.14313047118674 7.535442502244621 -0.1968503937007863 43.58301713362136 2.958555403999797 -0.1968503937007863 50.14313047118665 2.958555403999804 -0.1968503937007863 50.166263630751 2.960071631383512 -0.1968503937007863 50.16626363075097 7.53392627486092 -0.1968503937007863 50.18789439118228 7.529623649095314 -0.1968503937007863 50.1878943911823 2.96437425714911 -0.1968503937007863 50.20877849210176 7.522534452095655 -0.1968503937007863 50.20877849210176 2.971463454148789 -0.1968503937007863 50.22855860075256 7.512779981988107 -0.1968503937007863 50.22855860075259 2.981217924256331 -0.1968503937007863 50.24689627399151 7.500527140460703 -0.1968503937007863 50.24689627399157 2.993470765783735 -0.1968503937007863 50.26347774914542 7.485985577029031 -0.1968503937007863 50.26347774914544 3.008012329215407 -0.1968503937007863 50.27801931257708 7.469404101875151 -0.1968503937007863 50.27801931257705 3.024593804369262 -0.1968503937007863 50.2902721541045 3.042931477608267 -0.1968503937007863 50.29027215410449 7.451066428636207 -0.1968503937007863 50.30002662421204 7.431286319985366 -0.1968503937007863 50.30002662421204 3.062711586259064 -0.1968503937007863 50.30711582121172 7.410402219065904 -0.1968503937007863 50.30711582121167 3.083595687178512 -0.1968503937007863 50.31141844697729 3.105226447609863 -0.1968503937007863 50.31141844697731 7.388771458634578 -0.1968503937007863 50.31293467436102 3.128359607174147 -0.1968503937007863 50.31293467436102 7.365638299070358 -0.1968503937007863 + + + + + + + + + + 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 + + + + + + + + + + + + + + +

0 1 2 1 0 3 3 0 4 4 0 5 4 5 6 6 5 7 6 7 8 8 7 9 8 9 10 10 9 11 10 11 12 12 11 13 12 13 14 14 13 15 14 15 16 16 15 17 16 17 18 18 17 19 18 19 20 20 19 21 20 21 22 22 21 23 22 23 24 24 23 25 25 23 26 26 23 27 26 27 28 26 28 29 29 28 30 29 30 31 31 30 32 31 32 33 33 32 34 33 34 35 35 34 36 35 36 37 37 36 38 37 38 39 39 38 40 40 38 41 40 41 42 40 42 43 43 42 44 43 44 45 45 44 46 46 44 47 46 47 48 48 47 49

+
+
+
+ + + + 50.31141844697731 7.388771458634578 -0.1968503937007863 50.31293467436102 7.365638299070358 0.07874015748031607 50.31293467436102 7.365638299070358 -0.1968503937007863 50.31141844697731 7.388771458634578 0.07874015748031607 50.31293467436102 7.365638299070358 -0.1968503937007863 50.31293467436102 3.128359607174147 0.07874015748031607 50.31293467436102 3.128359607174147 -0.1968503937007863 50.31293467436102 7.365638299070358 0.07874015748031607 50.30711582121172 7.410402219065904 -0.1968503937007863 50.30711582121172 7.410402219065904 0.07874015748031607 50.31293467436102 3.128359607174147 -0.1968503937007863 50.31141844697729 3.105226447609863 0.07874015748031607 50.31141844697729 3.105226447609863 -0.1968503937007863 50.31293467436102 3.128359607174147 0.07874015748031607 50.30002662421204 7.431286319985366 -0.1968503937007863 50.30002662421204 7.431286319985366 0.07874015748031607 50.30711582121167 3.083595687178512 0.07874015748031607 50.30711582121167 3.083595687178512 -0.1968503937007863 50.29027215410449 7.451066428636207 -0.1968503937007863 50.29027215410449 7.451066428636207 0.07874015748031607 50.30002662421204 3.062711586259064 0.07874015748031607 50.30002662421204 3.062711586259064 -0.1968503937007863 50.27801931257708 7.469404101875151 -0.1968503937007863 50.27801931257708 7.469404101875151 0.07874015748031607 50.2902721541045 3.042931477608267 0.07874015748031607 50.2902721541045 3.042931477608267 -0.1968503937007863 50.26347774914542 7.485985577029031 -0.1968503937007863 50.26347774914542 7.485985577029031 0.07874015748031607 50.27801931257705 3.024593804369262 0.07874015748031607 50.27801931257705 3.024593804369262 -0.1968503937007863 50.24689627399151 7.500527140460703 0.07874015748031607 50.24689627399151 7.500527140460703 -0.1968503937007863 50.26347774914544 3.008012329215407 0.07874015748031607 50.26347774914544 3.008012329215407 -0.1968503937007863 50.22855860075256 7.512779981988107 0.07874015748031607 50.22855860075256 7.512779981988107 -0.1968503937007863 50.24689627399157 2.993470765783735 -0.1968503937007863 50.24689627399157 2.993470765783735 0.07874015748031607 50.20877849210176 7.522534452095655 0.07874015748031607 50.20877849210176 7.522534452095655 -0.1968503937007863 50.22855860075259 2.981217924256331 -0.1968503937007863 50.22855860075259 2.981217924256331 0.07874015748031607 50.18789439118228 7.529623649095314 0.07874015748031607 50.18789439118228 7.529623649095314 -0.1968503937007863 50.20877849210176 2.971463454148789 -0.1968503937007863 50.20877849210176 2.971463454148789 0.07874015748031607 50.16626363075097 7.53392627486092 0.07874015748031607 50.16626363075097 7.53392627486092 -0.1968503937007863 50.1878943911823 2.96437425714911 -0.1968503937007863 50.1878943911823 2.96437425714911 0.07874015748031607 50.14313047118674 7.535442502244621 0.07874015748031607 50.14313047118674 7.535442502244621 -0.1968503937007863 50.166263630751 2.960071631383512 -0.1968503937007863 50.166263630751 2.960071631383512 0.07874015748031607 43.55703534344437 7.535442502244626 0.07874015748031579 50.14313047118674 7.535442502244621 -0.1968503937007863 43.55703534344437 7.535442502244626 -0.1968503937007866 50.14313047118674 7.535442502244621 0.07874015748031607 50.14313047118665 2.958555403999804 -0.1968503937007863 50.14313047118665 2.958555403999804 0.07874015748031607 43.53651592631481 7.531360936406135 0.07874015748031579 43.55703534344437 7.535442502244626 -0.1968503937007866 43.53651592631481 7.531360936406135 -0.1968503937007866 43.55703534344437 7.535442502244626 0.07874015748031579 50.14313047118665 2.958555403999804 0.07874015748031607 43.58301713362136 2.958555403999797 -0.1968503937007863 50.14313047118665 2.958555403999804 -0.1968503937007863 43.58301713362136 2.958555403999797 0.07874015748031607 43.51563182539531 7.524271739406478 0.07874015748031579 43.51563182539531 7.524271739406478 -0.1968503937007866 43.58301713362136 2.958555403999797 0.07874015748031607 43.55988397405696 2.960071631383501 -0.1968503937007863 43.58301713362136 2.958555403999797 -0.1968503937007863 43.55988397405696 2.960071631383501 0.07874015748031607 43.49585171674453 7.514517269298941 0.07874015748031579 43.49585171674453 7.514517269298941 -0.1968503937007866 43.53825321362565 2.964374257149114 -0.1968503937007863 43.53825321362565 2.964374257149114 0.07874015748031607 43.47751404350557 7.502264427771523 0.07874015748031579 43.47751404350557 7.502264427771523 -0.1968503937007866 43.51736911270614 2.971463454148768 -0.1968503937007863 43.51736911270614 2.971463454148768 0.07874015748031607 43.46093256835167 7.487722864339863 0.07874015748031579 43.46093256835167 7.487722864339863 -0.1968503937007866 43.49758900405537 2.981217924256313 -0.1968503937007863 43.49758900405537 2.981217924256313 0.07874015748031607 43.44639100492 7.47114138918596 -0.1968503937007866 43.44639100492 7.47114138918596 0.07874015748031579 43.47925133081637 2.993470765783733 -0.1968503937007863 43.47925133081637 2.993470765783733 0.07874015748031607 43.4341381633926 7.452803715947015 -0.1968503937007866 43.4341381633926 7.452803715947015 0.07874015748031579 43.46266985566252 3.008012329215369 -0.1968503937007863 43.46266985566252 3.008012329215369 0.07874015748031607 43.42438369328506 7.43302360729623 -0.1968503937007866 43.42438369328506 7.43302360729623 0.07874015748031579 43.44812829223088 3.024593804369232 0.07874015748031607 43.44812829223088 3.024593804369232 -0.1968503937007863 43.41729449628541 7.412139506376729 -0.1968503937007866 43.41729449628541 7.412139506376729 0.07874015748031579 43.43587545070344 3.042931477608274 0.07874015748031607 43.43587545070344 3.042931477608274 -0.1968503937007863 43.4132129304469 7.39162008924713 -0.1968503937007866 43.4132129304469 7.39162008924713 0.07874015748031579 43.4261209805959 3.062711586259032 0.07874015748031607 43.4261209805959 3.062711586259032 -0.1968503937007863 43.4132129304469 7.39162008924713 0.07874015748031579 43.4132129304469 3.128359607174164 -0.1968503937007863 43.4132129304469 3.128359607174164 0.07874015748031607 43.4132129304469 7.39162008924713 -0.1968503937007866 43.41903178359623 3.083595687178518 0.07874015748031607 43.41903178359623 3.083595687178518 -0.1968503937007863 43.4132129304469 3.128359607174164 0.07874015748031607 43.41472915783061 3.105226447609857 -0.1968503937007863 43.41472915783061 3.105226447609857 0.07874015748031607 43.4132129304469 3.128359607174164 -0.1968503937007863 + + + + + + + + + + 0.9914448613738508 0.1305261922197449 1.55246491908785e-017 0.9978589232385636 0.06540312923075399 1.759089571435054e-017 0.9978589232385636 0.06540312923075399 1.759089571435054e-017 0.9914448613738508 0.1305261922197449 1.55246491908785e-017 1 0 1.95818153218181e-017 1 0 1.95818153218181e-017 1 0 1.95818153218181e-017 1 0 1.95818153218181e-017 0.9659258262890319 0.2588190451026562 1.12018520080126e-017 0.9659258262890319 0.2588190451026562 1.12018520080126e-017 0.9978589232385156 -0.06540312923148701 2.148888258984201e-017 0.9914448613737552 -0.1305261922204699 2.330393116351783e-017 0.9914448613737552 -0.1305261922204699 2.330393116351783e-017 0.9978589232385156 -0.06540312923148701 2.148888258984201e-017 0.9238795325111466 0.3826834323654281 6.687388031556006e-018 0.9238795325111466 0.3826834323654281 6.687388031556006e-018 0.9659258262891463 -0.2588190451022301 2.66273102819097e-017 0.9659258262891463 -0.2588190451022301 2.66273102819097e-017 0.8660254037845753 0.4999999999997635 2.058500991815655e-018 0.8660254037845753 0.4999999999997635 2.058500991815655e-018 0.9238795325113448 -0.3826834323649499 2.949508873891546e-017 0.9238795325113448 -0.3826834323649499 2.949508873891546e-017 0.7933533402911205 0.60876142900887 -2.605607570657765e-018 0.7933533402911205 0.60876142900887 -2.605607570657765e-018 0.866025403784477 -0.4999999999999336 3.18581980500125e-017 0.866025403784477 -0.4999999999999336 3.18581980500125e-017 0.7071067811863823 0.707106781186713 -7.225133465171492e-018 0.7071067811863823 0.707106781186713 -7.225133465171492e-018 0.7933533402914658 -0.6087614290084201 3.367620475970759e-017 0.7933533402914658 -0.6087614290084201 3.367620475970759e-017 0.608761429008534 0.7933533402913785 -1.172103532290912e-017 0.608761429008534 0.7933533402913785 -1.172103532290912e-017 0.7071067811870996 -0.7071067811859956 3.491800226915812e-017 0.7071067811870996 -0.7071067811859956 3.491800226915812e-017 0.5000000000000008 0.8660254037844382 -1.601638701657927e-017 0.5000000000000008 0.8660254037844382 -1.601638701657927e-017 0.6087614290086063 -0.793353340291323 3.556234307869128e-017 0.6087614290086063 -0.793353340291323 3.556234307869128e-017 0.3826834323652957 0.9238795325112014 -2.003769388781576e-017 0.3826834323652957 0.9238795325112014 -2.003769388781576e-017 0.4999999999993188 -0.8660254037848321 3.559820233839578e-017 0.4999999999993188 -0.8660254037848321 3.559820233839578e-017 0.2588190451024929 0.9659258262890758 -2.371615026114718e-017 0.2588190451024929 0.9659258262890758 -2.371615026114718e-017 0.3826834323655604 -0.9238795325110919 3.502496648641106e-017 0.3826834323655604 -0.9238795325110919 3.502496648641106e-017 0.1305261922199533 0.9914448613738235 -2.698881672814551e-017 0.1305261922199533 0.9914448613738235 -2.698881672814551e-017 0.2588190451029568 -0.9659258262889514 3.385244374708522e-017 0.2588190451029568 -0.9659258262889514 3.385244374708522e-017 0.06540312923029935 0.9978589232385934 -2.845518162128279e-017 0.06540312923029935 0.9978589232385934 -2.845518162128279e-017 0.1305261922198004 -0.9914448613738436 3.210069630956563e-017 0.1305261922198004 -0.9914448613738436 3.210069630956563e-017 8.091396214053001e-016 1 -2.979969705820778e-017 8.091396214053001e-016 1 -2.979969705820778e-017 8.091396214053001e-016 1 -2.979969705820778e-017 8.091396214053001e-016 1 -2.979969705820778e-017 0.06540312923028356 -0.9978589232385944 3.101660561739596e-017 0.06540312923028356 -0.9978589232385944 3.101660561739596e-017 -0.2588190451025151 0.9659258262890699 -3.385244374708009e-017 -0.1950903220161407 0.980785280403228 -3.304732689195967e-017 -0.2588190451025151 0.9659258262890699 -3.385244374708009e-017 -0.1950903220161407 0.980785280403228 -3.304732689195967e-017 1.015430344717675e-015 -1 2.979969705820782e-017 1.015430344717675e-015 -1 2.979969705820782e-017 1.015430344717675e-015 -1 2.979969705820782e-017 1.015430344717675e-015 -1 2.979969705820782e-017 -0.3826834323650787 0.9238795325112913 -3.502496648640756e-017 -0.3826834323650787 0.9238795325112913 -3.502496648640756e-017 -0.06540312922995281 -0.9978589232386161 2.845518162129025e-017 -0.1305261922199476 -0.9914448613738243 2.698881672814565e-017 -0.06540312922995281 -0.9978589232386161 2.845518162129025e-017 -0.1305261922199476 -0.9914448613738243 2.698881672814565e-017 -0.5000000000000135 0.8660254037844308 -3.559820233839744e-017 -0.5000000000000135 0.8660254037844308 -3.559820233839744e-017 -0.2588190451023761 -0.9659258262891071 2.371615026115041e-017 -0.2588190451023761 -0.9659258262891071 2.371615026115041e-017 -0.6087614290087011 0.7933533402912499 -3.556234307869096e-017 -0.6087614290087011 0.7933533402912499 -3.556234307869096e-017 -0.3826834323652421 -0.9238795325112237 2.003769388781746e-017 -0.3826834323652421 -0.9238795325112237 2.003769388781746e-017 -0.7071067811865318 0.7071067811865633 -3.491800226916392e-017 -0.7071067811865318 0.7071067811865633 -3.491800226916392e-017 -0.4999999999998345 -0.8660254037845342 1.60163870165854e-017 -0.4999999999998345 -0.8660254037845342 1.60163870165854e-017 -0.7933533402912634 0.6087614290086838 -3.367620475971148e-017 -0.7933533402912634 0.6087614290086838 -3.367620475971148e-017 -0.6087614290084824 -0.7933533402914178 1.172103532291131e-017 -0.6087614290084824 -0.7933533402914178 1.172103532291131e-017 -0.8660254037844439 0.4999999999999909 -3.185819805001356e-017 -0.8660254037844439 0.4999999999999909 -3.185819805001356e-017 -0.7071067811866187 -0.7071067811864763 7.225133465159809e-018 -0.7071067811866187 -0.7071067811864763 7.225133465159809e-018 -0.9238795325113307 0.382683432364984 -2.94950887389162e-017 -0.9238795325113307 0.382683432364984 -2.94950887389162e-017 -0.7933533402916141 -0.6087614290082266 2.605607570628924e-018 -0.7933533402916141 -0.6087614290082266 2.605607570628924e-018 -0.9659258262890716 0.2588190451025084 -2.662731028191653e-017 -0.9659258262890716 0.2588190451025084 -2.662731028191653e-017 -0.8660254037845783 -0.4999999999997583 -2.058500991815872e-018 -0.8660254037845783 -0.4999999999997583 -2.058500991815872e-018 -0.9807852804031837 0.1950903220163633 -2.501918872628857e-017 -0.9807852804031837 0.1950903220163633 -2.501918872628857e-017 -0.9238795325109536 -0.382683432365894 -6.687388031538348e-018 -0.9238795325109536 -0.382683432365894 -6.687388031538348e-018 -1 -1.274856552025012e-033 -1.95818153218181e-017 -1 -1.274856552025012e-033 -1.95818153218181e-017 -1 -1.274856552025012e-033 -1.95818153218181e-017 -1 -1.274856552025012e-033 -1.95818153218181e-017 -0.9659258262890079 -0.2588190451027462 -1.120185200800945e-017 -0.9659258262890079 -0.2588190451027462 -1.120185200800945e-017 -0.9978589232385796 -0.0654031292305077 -1.759089571435819e-017 -0.9914448613738123 -0.130526192220036 -1.552464919086907e-017 -0.9914448613738123 -0.130526192220036 -1.552464919086907e-017 -0.9978589232385796 -0.0654031292305077 -1.759089571435819e-017 + + + + + + + + + + + + + + +

0 1 2 1 0 3 4 5 6 5 4 7 8 3 0 3 8 9 10 11 12 11 10 13 14 9 8 9 14 15 12 16 17 16 12 11 18 15 14 15 18 19 17 20 21 20 17 16 22 19 18 19 22 23 21 24 25 24 21 20 26 23 22 23 26 27 25 28 29 28 25 24 30 26 31 26 30 27 29 32 33 32 29 28 34 31 35 31 34 30 32 36 33 36 32 37 38 35 39 35 38 34 37 40 36 40 37 41 42 39 43 39 42 38 41 44 40 44 41 45 46 43 47 43 46 42 45 48 44 48 45 49 50 47 51 47 50 46 49 52 48 52 49 53 54 55 56 55 54 57 53 58 52 58 53 59 60 61 62 61 60 63 64 65 66 65 64 67 68 62 69 62 68 60 70 71 72 71 70 73 74 69 75 69 74 68 73 76 71 76 73 77 78 75 79 75 78 74 77 80 76 80 77 81 82 79 83 79 82 78 81 84 80 84 81 85 82 86 87 86 82 83 85 88 84 88 85 89 87 90 91 90 87 86 89 92 88 92 89 93 91 94 95 94 91 90 96 92 93 92 96 97 95 98 99 98 95 94 100 97 96 97 100 101 99 102 103 102 99 98 104 101 100 101 104 105 106 107 108 107 106 109 110 105 104 105 110 111 112 113 114 113 112 115 114 111 110 111 114 113

+
+
+
+ + + + 0 0 2.165354330708662 0.1184986753859656 0.2465682045726894 2.165354330708662 0 7.874015748031497 2.165354330708662 0.119594327961949 0.2298517765885317 2.165354330708662 0.1228625387705518 0.2134213713218521 2.165354330708662 0.1282473878187189 0.1975581175621329 2.165354330708662 0.1356567388462747 0.1825334399793274 2.165354330708662 0.1449638158028776 0.1686044149725052 2.165354330708662 0.1560093720213896 0.1560093720213882 2.165354330708662 0.1686044149725068 0.1449638158028763 2.165354330708662 0.1825334399793289 0.1356567388462739 2.165354330708662 0.197558117562134 0.1282473878187185 2.165354330708662 0.2134213713218537 0.1228625387705514 2.165354330708662 0.2298517765885331 0.1195943279619491 2.165354330708662 0.2465682045726913 0.1184986753859656 2.165354330708662 51.18110236220473 0 2.165354330708662 30.0860261920037 0.1184986753859688 2.165354330708662 30.09803909744245 0.1212016043046447 2.165354330708662 30.70679771243117 0.1184986753859656 2.165354330708662 30.10330938016302 0.1244567554178949 2.165354330708662 30.10773656538716 0.1287894127682915 2.165354330708662 30.11110468898 0.1339882234195986 2.165354330708662 30.11324944927784 0.1397995822959414 2.165354330708662 30.11406622194742 0.145940003383379 2.165354330708662 51.06260368681876 0.1184986753859656 2.165354330708662 51.06260368681876 7.755517072645532 2.165354330708662 0.1184986753859656 7.755517072645532 2.165354330708662 51.18110236220473 7.874015748031497 2.165354330708662 0.1184986753859656 2.43930318405221 2.165354330708662 0.1184986753859656 2.804370064010866 2.165354330708662 0.1195943279619488 2.456019612036368 2.165354330708662 0.1228625387705512 2.472450017303047 2.165354330708662 0.1282473878187184 2.488313271062767 2.165354330708662 0.1356567388462739 2.503337948645572 2.165354330708662 0.1449638158028762 2.517266973652394 2.165354330708662 0.1560093720213884 2.529862016603511 2.165354330708662 0.1686044149725052 2.540907572822023 2.165354330708662 0.1825334399793273 2.550214649778626 2.165354330708662 0.1975581175621327 2.557624000806182 2.165354330708662 0.213421371321852 2.563008849854349 2.165354330708662 0.2298517765885315 2.566277060662952 2.165354330708662 0.2465682045726894 2.567372713238935 2.165354330708662 25.61991398185795 2.804370064010866 2.165354330708662 25.56118838034679 2.567372713238936 2.165354330708662 30.09912146437194 0.1713469183847506 2.165354330708662 30.10848249331568 0.1633477397435226 2.165354330708662 30.11162315591949 0.1580084394959358 2.165354330708662 30.11351516370367 0.1521099485644012 2.165354330708662 0 7.874015748031497 2.165354330708662 0 0 0 0 0 2.165354330708662 0 7.874015748031497 0 51.18110236220473 0 2.165354330708662 0 0 0 51.18110236220473 0 0 0 0 2.165354330708662 51.18110236220473 0 0 51.18110236220473 0.7153153851313135 0.604869657207319 51.18110236220473 0 2.165354330708662 51.18110236220473 7.874015748031497 0 51.18110236220473 7.182685229005588 0.604869657207319 51.18110236220473 0.7153153851313138 1.166727690057971 51.18110236220473 7.874015748031497 2.165354330708662 51.18110236220473 7.182685229005587 1.166727690057971 0 7.874015748031497 2.165354330708662 51.18110236220473 7.874015748031497 0 0 7.874015748031497 0 51.18110236220473 7.874015748031497 2.165354330708662 0 7.874015748031497 0 0.346039204183232 7.209720004747907 1.256040330056125e-015 0 0 0 0.3542852686363268 7.272355082731298 1.256040330056125e-015 0.3784615063303982 7.330721683659481 1.256040330056125e-015 0.4169203466197171 7.380842220134569 1.256040330056125e-015 0.4670408830948051 7.419301060423888 1.256040330056125e-015 0.525407484022988 7.443477298117959 1.256040330056125e-015 0.5880425620063782 7.451723362571054 1.256040330056125e-015 51.18110236220473 7.874015748031497 0 0.3460392041832313 0.5491086559751139 1.110223024625157e-015 0.3460392041832319 2.136762732649793 1.110223024625157e-015 0.6506776399897686 7.443477298117959 1.256040330056125e-015 0.7090442409179513 7.419301060423888 1.256040330056125e-015 0.7591647773930393 7.380842220134569 1.256040330056125e-015 0.7976236176823582 7.330721683659481 1.256040330056125e-015 0.8217998553764297 7.272355082731298 1.256040330056125e-015 0.8300459198295244 7.209720004747907 1.256040330056125e-015 43.55364811608248 7.569833598791506 8.326672684688674e-016 0.8300459198295258 3.173087089051805 5.549316253182147e-016 43.52759575677882 7.56465146232659 8.326672684688674e-016 25.50480608586854 2.339832184441669 1.110223024625157e-015 43.50244268356087 7.556113144499255 8.326672684688674e-016 43.47861927248514 7.544364738294798 8.326672684688674e-016 43.45653314872024 7.529607262200647 8.326672684688674e-016 43.43656221196721 7.512093220724323 8.326672684688674e-016 43.41904817049088 7.492122283971291 8.326672684688674e-016 43.40429069439674 7.470036160206389 8.326672684688674e-016 43.39254228819227 7.446212749130662 8.326672684688674e-016 43.38400397036494 7.421059675912715 8.326672684688674e-016 43.37882183390003 7.395007316609055 8.326672684688674e-016 50.144256319116 7.569833598791506 1.090510587941475e-015 50.1707622014146 7.568096311480678 1.090510587941475e-015 50.19681456071828 7.562914175015767 1.090510587941475e-015 50.22196763393622 7.554375857188427 1.090510587941475e-015 50.24579104501194 7.542627450983966 1.090510587941475e-015 50.26787716877683 7.527869974889834 1.090510587941475e-015 50.28784810552988 7.510355933413502 1.090510587941475e-015 50.3053621470062 7.490384996660477 1.090510587941475e-015 50.32011962310036 7.468298872895575 1.118266163557104e-015 50.3318680293048 7.44447546181984 1.118266163557104e-015 50.34040634713218 7.419322388601879 1.118266163557104e-015 50.34558848359706 7.393270029298235 1.118266163557104e-015 50.3473257709079 7.366764146999632 1.118266163557104e-015 50.3473257709079 3.127233759244805 1.103017739216966e-015 50.3473257709079 2.136762732649773 1.110223024625157e-015 50.3473257709079 0.5508869384357039 1.110223024625157e-015 0.5491086559751147 0.346039204183232 1.110223024625157e-015 51.18110236220473 0 0 0.5226027736765072 0.3477764914940557 1.110223024625157e-015 0.4965504143728469 0.3529586279589738 1.110223024625157e-015 0.4713973411549005 0.3614969457863064 1.110223024625157e-015 0.4475739300791731 0.3732453519907652 1.110223024625157e-015 0.4254878063142707 0.3880028280849154 1.110223024625157e-015 0.4055168695612388 0.4055168695612393 1.110223024625157e-015 0.3880028280849136 0.4254878063142707 1.110223024625157e-015 0.3732453519907644 0.4475739300791728 1.110223024625157e-015 0.361496945786306 0.4713973411548998 1.110223024625157e-015 0.352958627958972 0.4965504143728474 1.110223024625157e-015 0.3477764914940549 0.5226027736765067 1.110223024625157e-015 28.98669970978262 0.3460392041831966 1.110223024625157e-015 29.00270410638306 0.3478174866438403 1.110223024625157e-015 50.14425631911605 0.3478174866438403 1.110223024625157e-015 50.17076220141466 0.3495547739546495 1.110223024625157e-015 50.19681456071831 0.35473691041958 1.110223024625157e-015 50.22196763393623 0.3632752282469015 1.110223024625157e-015 50.24579104501201 0.3750236344513794 1.110223024625157e-015 50.26787716877686 0.3897811105455421 1.110223024625157e-015 50.28784810552991 0.407295152021843 1.110223024625157e-015 50.30536214700624 0.4272660887748815 1.110223024625157e-015 50.32011962310041 0.4493522125397739 1.110223024625157e-015 50.33186802930485 0.4731756236154915 1.110223024625157e-015 50.3404063471322 0.498328696833425 1.110223024625157e-015 50.34558848359711 0.5243810561371139 1.110223024625157e-015 43.55538540339332 2.925901594763743 1.109463768595622e-015 50.14425631911605 2.339832184441669 1.110223024625157e-015 43.52933304408965 2.931083731228659 1.109462778393509e-015 43.5041799708717 2.939622049055988 1.109231021428294e-015 43.480356559796 2.951370455260453 1.108772463125903e-015 43.45827043603106 2.96612793135459 1.108094949546031e-015 43.43829949927805 2.98364197283092 1.107210073133866e-015 43.42078545780171 3.003612909583954 1.106132974370159e-015 43.4060279817076 3.025699033348864 1.104882082713383e-015 43.39427957550313 3.04952244442458 1.1034788012666e-015 43.38574125767577 3.074675517642528 1.101947140564425e-015 43.38055912121086 3.10072787694619 1.100313307746131e-015 43.37882183390003 3.127233759244795 1.098605258144222e-015 43.58189128569192 2.924164307452924 1.109233975091996e-015 50.14425631911599 2.924164307452924 1.117398622990049e-015 50.17076220141464 2.925901594763754 1.118280362204888e-015 50.17076220141468 2.338094897130827 1.110223024625157e-015 50.19681456071832 2.931083731228657 1.118760003154504e-015 50.19681456071832 2.332912760665919 1.110223024625157e-015 50.22196763393622 2.939622049056019 1.118829339049262e-015 50.22196763393626 2.324374442838587 1.110223024625157e-015 50.24579104501196 2.951370455260466 1.11848718353279e-015 50.24579104501199 2.312626036634129 1.110223024625157e-015 50.26787716877688 2.966127931354595 1.11773939098083e-015 50.26787716877689 2.297868560539985 1.110223024625157e-015 50.28784810552991 2.98364197283095 1.116598756331273e-015 50.28784810552993 2.280354519063654 1.110223024625157e-015 50.3053621470062 3.003612909583975 1.115084796159225e-015 50.30536214700626 2.260383582310614 1.110223024625157e-015 50.32011962310035 3.025699033348873 1.113223414742969e-015 50.32011962310039 2.238297458545719 1.110223024625157e-015 50.33186802930481 3.049522444424608 1.111046460834616e-015 50.33186802930484 2.214474047469999 1.110223024625157e-015 50.34040634713214 3.074675517642548 1.108591182719098e-015 50.34040634713219 2.189320974252057 1.110223024625157e-015 50.34558848359704 3.100727876946217 1.105899590885709e-015 50.34558848359709 2.163268614948385 1.110223024625157e-015 0.3460392041832334 3.173087089051805 5.549316253182147e-016 0.3477764914940558 2.163268614948401 1.110223024625157e-015 0.354285268636328 3.110452011068415 5.549316253182147e-016 0.3529586279589722 2.189320974252061 1.110223024625157e-015 0.3614969457863068 2.214474047470008 1.110223024625157e-015 0.3784615063303993 3.052085410140232 5.549316253182147e-016 0.3732453519907648 2.238297458545735 1.110223024625157e-015 0.3880028280849145 2.260383582310638 1.110223024625157e-015 0.4169203466197183 3.001964873665144 5.549316253182147e-016 0.4055168695612396 2.280354519063669 1.110223024625157e-015 0.4254878063142705 2.297868560539994 1.110223024625157e-015 0.4670408830948064 2.963506033375825 5.549316253182147e-016 0.4475739300791732 2.312626036634144 1.110223024625157e-015 0.4713973411548998 2.324374442838602 1.110223024625157e-015 0.525407484022989 2.939329795681753 5.549316253182147e-016 0.4965504143728471 2.332912760665936 1.110223024625157e-015 0.5226027736765068 2.338094897130853 1.110223024625157e-015 0.5491086559751146 2.339832184441677 1.110223024625157e-015 0.5880425620063796 2.931083731228659 5.549316253182147e-016 0.6506776399897698 2.939329795681753 5.549316253182147e-016 0.7090442409179527 2.963506033375825 5.549316253182147e-016 0.7591647773930408 3.001964873665144 5.549316253182147e-016 0.7976236176823597 3.052085410140232 5.549316253182147e-016 0.8217998553764312 3.110452011068415 5.549316253182147e-016 + + + + + + + + + + 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 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 -1 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 -0 1 0 -0 1 0 -0 1 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 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 + + + + + + + + + + + + + + +

0 1 2 1 0 3 3 0 4 4 0 5 5 0 6 6 0 7 7 0 8 8 0 9 9 0 10 10 0 11 11 0 12 12 0 13 13 0 14 14 0 15 14 15 16 16 15 17 17 15 18 17 18 19 19 18 20 20 18 21 21 18 22 22 18 23 18 15 24 24 15 25 2 26 27 26 2 1 26 1 28 26 28 29 27 26 25 27 25 15 30 29 28 29 30 31 29 31 32 29 32 33 29 33 34 29 34 35 29 35 36 29 36 37 29 37 38 29 38 39 29 39 40 29 40 41 29 41 42 42 41 43 42 43 44 42 44 18 18 44 45 18 45 46 18 46 47 18 47 23 48 49 50 49 48 51 52 53 54 53 52 55 56 57 58 57 56 59 57 59 60 58 61 62 61 58 57 62 61 63 62 63 60 62 60 59 64 65 66 65 64 67 68 69 70 69 68 71 71 68 72 72 68 73 73 68 74 74 68 75 75 68 76 76 68 77 70 69 78 78 69 79 76 77 80 80 77 81 81 77 82 82 77 83 83 77 84 84 77 85 85 77 86 85 86 87 87 86 88 87 88 89 89 88 90 89 90 91 89 91 92 89 92 93 89 93 94 89 94 95 89 95 96 89 96 97 89 97 98 86 77 99 99 77 100 100 77 101 101 77 102 102 77 103 103 77 104 104 77 105 105 77 106 106 77 107 107 77 108 108 77 109 109 77 110 110 77 111 111 77 112 112 77 113 113 77 114 70 115 116 115 70 117 117 70 118 118 70 119 119 70 120 120 70 121 121 70 122 122 70 123 123 70 124 124 70 125 125 70 126 126 70 127 127 70 78 116 115 128 116 128 129 116 129 130 116 130 131 116 131 132 116 132 133 116 133 134 116 134 135 116 135 136 116 136 137 116 137 138 116 138 139 116 139 140 116 140 141 116 141 114 116 114 77 89 142 143 142 89 144 144 89 145 145 89 146 146 89 147 147 89 148 148 89 149 149 89 150 150 89 151 151 89 152 152 89 153 153 89 154 154 89 98 143 142 155 143 155 156 143 156 157 143 157 158 158 157 159 158 159 160 160 159 161 160 161 162 162 161 163 162 163 164 164 163 165 164 165 166 166 165 167 166 167 168 168 167 169 168 169 170 170 169 171 170 171 172 172 171 173 172 173 174 174 173 175 174 175 176 176 175 177 176 177 178 178 177 112 178 112 113 179 180 79 180 179 181 180 181 182 182 181 183 183 181 184 183 184 185 185 184 186 186 184 187 186 187 188 188 187 189 189 187 190 189 190 191 191 190 192 192 190 193 192 193 194 194 193 195 195 193 196 196 193 197 196 197 89 89 197 198 89 198 199 89 199 200 89 200 201 89 201 202 89 202 87 179 79 69

+
+
+
+ + + + 0.6470483783510791 7.225530565586209 -0.2337572933700505 0.590059644476194 7.209179529129053 -0.2420033578231444 0.5880425620063792 7.209720004747907 -0.2417307881423126 0.6506776399897661 7.197963586567997 -0.2337572933700505 0.5880425620063748 7.193858266663263 -0.2420033578231444 0.7039126674564964 7.240767305930175 -0.209581055675979 0.7090442409179504 7.201789135705585 -0.209581055675979 0.5880425620063785 3.188948827136449 -0.2420033578231452 0.6506776399897699 3.184843507231715 -0.2337572933700513 0.7090442409179538 3.181017958094126 -0.2095810556759798 0.6919288565104798 7.269698784844964 -0.209581055675979 0.6409457296562897 7.240263662831568 -0.2337572933700505 0.752743139522957 7.253851391486414 -0.1711222153866596 0.7591647773930373 7.205074209224319 -0.1711222153866596 0.5900596444761919 3.173627564670658 -0.2420033578231452 0.6470483783510829 3.157276528213503 -0.2337572933700513 0.5880425620063792 3.173087089051805 -0.2417307881423139 0.5254074840229897 7.197963586567996 -0.2337572933700505 0.5880425620063785 3.188948827136449 -0.2420033578231452 0.5254074840229894 3.184843507231715 -0.2337572933700513 0.5880425620063748 7.193858266663263 -0.2420033578231444 0.7039126674564999 3.142039787869536 -0.2095810556759798 0.7591647773930392 3.177732884575392 -0.1711222153866604 0.6728653662742286 7.294542809015757 -0.209581055675979 0.631237817512777 7.252915260254307 -0.2337572933700505 0.7357090600596556 7.294975297149257 -0.1711222153866596 0.7976236176823564 7.20759493479274 -0.121001678911572 0.7902120785753058 7.263891163446743 -0.121001678911572 0.5290367456616765 3.157276528213502 -0.2337572933700513 0.5860254795365677 3.173627564670658 -0.2420033578231452 0.5880425620063792 3.173087089051805 -0.2417307881423139 0.4670408830948055 3.181017958094127 -0.2095810556759798 0.4670408830948049 7.201789135705584 -0.209581055675979 0.5880425620063792 7.209720004747907 -0.2417307881423126 0.5860254795365617 7.209179529129052 -0.2420033578231444 0.5290367456616767 7.225530565586209 -0.2337572933700505 0.6919288565104833 3.113108308954748 -0.2095810556759798 0.6409457296562934 3.142543430968143 -0.2337572933700513 0.7527431395229589 3.128955702313299 -0.1711222153866604 0.7976236176823581 3.175212159006971 -0.1210016789115728 0.6480213421034335 7.313606299252011 -0.209581055675979 0.6185862200900375 7.26262317239782 -0.2337572933700505 0.7086117527844502 7.33028919552598 -0.1711222153866596 0.7693027917821517 7.314370647202324 -0.121001678911572 0.8217998553764282 7.209179529129053 -0.06263507798338919 0.8137660383374742 7.270202427943571 -0.06263507798338919 0.4721724565562595 3.142039787869536 -0.2095810556759798 0.4169203466197199 3.177732884575392 -0.1711222153866604 0.4169203466197176 7.205074209224319 -0.1711222153866596 0.4721724565562592 7.240767305930176 -0.209581055675979 0.6728653662742311 3.088264284783953 -0.2095810556759798 0.6312378175127806 3.129891833545404 -0.2337572933700513 0.7357090600596575 3.087831796650455 -0.1711222153866604 0.7902120785753077 3.118915930352971 -0.1210016789115728 0.8217998553764306 3.173627564670658 -0.06263507798339002 0.6190898631886472 7.325590110198027 -0.209581055675979 0.6038531228446804 7.268725821092609 -0.2337572933700505 0.6732978544077269 7.357386502801186 -0.1711222153866596 0.7360409198764716 7.357718362618001 -0.121001678911572 0.790420694377345 7.326563073950379 -0.06263507798338919 0.8300459198295244 7.209720004747907 1.256040330056125e-015 0.8217998553764297 7.272355082731298 1.256040330056125e-015 0.4841562675022759 3.113108308954748 -0.2095810556759798 0.5351393943564656 3.142543430968144 -0.2337572933700513 0.4233419844898002 3.128955702313298 -0.1711222153866604 0.3784615063303992 7.207594934792739 -0.121001678911572 0.3784615063304005 3.175212159006972 -0.1210016789115728 0.4233419844897982 7.253851391486415 -0.1711222153866596 0.4841562675022756 7.269698784844964 -0.209581055675979 0.5351393943564662 7.240263662831568 -0.2337572933700505 0.6480213421034365 3.069200794547701 -0.2095810556759798 0.6185862200900409 3.120183921401891 -0.2337572933700513 0.7086117527844518 3.052517898273733 -0.1711222153866604 0.7693027917821532 3.068436446597388 -0.1210016789115728 0.8137660383374767 3.112604665856142 -0.06263507798339002 0.8300459198295258 3.173087089051805 5.549316253182147e-016 0.5880425620063783 7.329677564942021 -0.209581055675979 0.5880425620063781 7.270807320915229 -0.2337572933700505 0.6321739487448852 7.374420582264487 -0.1711222153866596 0.6926932044607942 7.390980234523682 -0.121001678911572 0.753283615141812 7.37496105788334 -0.06263507798338919 0.7976236176823582 7.330721683659481 1.256040330056125e-015 0.5032197577385278 3.088264284783953 -0.2095810556759798 0.5448473064999787 3.129891833545404 -0.2337572933700513 0.4403760639531013 3.087831796650455 -0.1711222153866604 0.3858730454374511 3.11891593035297 -0.1210016789115728 0.3542852686363288 7.209179529129052 -0.06263507798338919 0.3542852686363288 3.173627564670658 -0.06263507798339002 0.3858730454374499 7.263891163446743 -0.121001678911572 0.4403760639530996 7.294975297149258 -0.1711222153866596 0.5032197577385272 7.294542809015758 -0.209581055675979 0.5448473064999786 7.252915260254307 -0.2337572933700505 0.6190898631886485 3.057216983601685 -0.2095810556759798 0.6038531228446821 3.114081272707101 -0.2337572933700513 0.6732978544077288 3.025420590998527 -0.1711222153866604 0.7360409198764732 3.025088731181712 -0.1210016789115728 0.7904206943773474 3.056244019849333 -0.06263507798339002 0.8217998553764312 3.110452011068415 5.549316253182147e-016 0.5722320011680755 7.268725821092609 -0.2337572933700505 0.5569952608241093 7.325590110198028 -0.209581055675979 0.5880425620063781 7.380230589550607 -0.1711222153866596 0.6422137207052132 7.411889521316836 -0.121001678911572 0.7048856312088494 7.412098137118874 -0.06263507798338919 0.7591647773930393 7.380842220134569 1.256040330056125e-015 0.5280637819093225 3.069200794547701 -0.2095810556759798 0.5574989039227182 3.120183921401891 -0.2337572933700513 0.467473371228307 3.052517898273733 -0.1711222153866604 0.4067823322306052 3.068436446597388 -0.1210016789115728 0.3623190856752828 3.112604665856142 -0.06263507798339002 0.346039204183232 7.209720004747907 1.256040330056125e-015 0.3460392041832334 3.173087089051805 5.549316253182147e-016 0.3623190856752829 7.27020242794357 -0.06263507798338919 0.406782332230604 7.314370647202324 -0.121001678911572 0.4674733712283056 7.330289195525981 -0.1711222153866596 0.5280637819093215 7.313606299252011 -0.209581055675979 0.5574989039227177 7.26262317239782 -0.2337572933700505 0.5880425620063796 3.111999772884482 -0.2337572933700513 0.5880425620063795 3.05312952885769 -0.2095810556759798 0.6321739487448865 3.008386511535226 -0.1711222153866604 0.692693204460796 2.991826859276031 -0.1210016789115728 0.7532836151418134 3.007846035916371 -0.06263507798339002 0.7976236176823597 3.052085410140232 5.549316253182147e-016 0.5439111752678711 7.374420582264487 -0.1711222153866596 0.5880425620063783 7.41902128965674 -0.121001678911572 0.6485249852020408 7.435443481079003 -0.06263507798338919 0.7090442409179513 7.419301060423888 1.256040330056125e-015 0.5569952608241104 3.057216983601685 -0.2095810556759798 0.5722320011680768 3.114081272707101 -0.2337572933700513 0.5027872696050301 3.025420590998527 -0.1711222153866604 0.4400442041362855 3.025088731181712 -0.1210016789115728 0.3856644296354121 3.056244019849333 -0.06263507798339002 0.354285268636328 3.110452011068415 5.549316253182147e-016 0.3542852686363268 7.272355082731298 1.256040330056125e-015 0.385664429635412 7.326563073950378 -0.06263507798338919 0.4400442041362841 7.357718362618001 -0.121001678911572 0.5027872696050288 7.357386502801186 -0.1711222153866596 0.5880425620063796 3.002576504249106 -0.1711222153866604 0.6422137207052142 2.970917572482877 -0.1210016789115728 0.7048856312088514 2.970708956680837 -0.06263507798339002 0.7591647773930408 3.001964873665144 5.549316253182147e-016 0.5338714033075435 7.411889521316836 -0.121001678911572 0.5880425620063782 7.443406143152849 -0.06263507798338919 0.6506776399897686 7.443477298117959 1.256040330056125e-015 0.5439111752678723 3.008386511535226 -0.1711222153866604 0.4833919195519629 2.991826859276031 -0.1210016789115728 0.4228015088709456 3.007846035916372 -0.06263507798339002 0.3784615063303993 3.052085410140232 5.549316253182147e-016 0.3784615063303982 7.330721683659481 1.256040330056125e-015 0.4228015088709459 7.374961057883341 -0.06263507798338919 0.4833919195519614 7.390980234523682 -0.121001678911572 0.5880425620063796 2.963785804142972 -0.1210016789115728 0.6485249852020425 2.947363612720708 -0.06263507798339002 0.7090442409179527 2.963506033375825 5.549316253182147e-016 0.5275601388107158 7.435443481079003 -0.06263507798338919 0.5880425620063782 7.451723362571054 1.256040330056125e-015 0.5338714033075445 2.970917572482877 -0.1210016789115728 0.4711994928039077 2.970708956680837 -0.06263507798339002 0.4169203466197183 3.001964873665144 5.549316253182147e-016 0.4169203466197171 7.380842220134569 1.256040330056125e-015 0.4711994928039074 7.412098137118874 -0.06263507798338919 0.5880425620063796 2.939400950646861 -0.06263507798339002 0.6506776399897698 2.939329795681753 5.549316253182147e-016 0.525407484022988 7.443477298117959 1.256040330056125e-015 0.5275601388107163 2.947363612720708 -0.06263507798339002 0.4670408830948064 2.963506033375825 5.549316253182147e-016 0.4670408830948051 7.419301060423888 1.256040330056125e-015 0.5880425620063796 2.931083731228659 5.549316253182147e-016 0.525407484022989 2.939329795681753 5.549316253182147e-016 + + + + + + + + + + 0.2980469559637359 0.07455112482027697 -0.9516355089154578 0.129409522551249 0.01703708685546249 -0.9914448613738121 0.129409522551249 0.01703708685546249 -0.9914448613738121 0.2628076869683011 0.01722532585836539 -0.9646944634543336 0.1300206976615136 0.007784386697886409 -0.9914807217003017 0.487749567089461 0.1306921026102494 -0.8631453725296541 0.5022026247522211 0.03291609906116259 -0.8641232864091647 0.1300206976615145 -0.007784386697885729 -0.9914807217003016 0.2628076869683022 -0.01722532585836404 -0.9646944634543334 0.5022026247522249 -0.03291609906116251 -0.8641232864091626 0.4373042984129965 0.2524777544065234 -0.8631453725296547 0.3289889588963535 0.189941863979224 -0.925034244356603 0.6853829641193342 0.1836478117418226 -0.704644359757059 0.7075597098930087 0.04637591353493291 -0.7051301522271769 0.1294095225512511 -0.01703708685545926 -0.9914448613738118 0.2980469559637368 -0.07455112482027632 -0.9516355089154577 0.1294095225512511 -0.01703708685545926 -0.9914448613738118 -0.2628076869683021 0.01722532585836941 -0.9646944634543332 -0.1300206976615204 -0.007784386697888517 -0.9914807217003007 -0.2628076869683041 -0.01722532585836543 -0.9646944634543327 -0.1300206976615192 0.007784386697895602 -0.9914807217003009 0.4877495670894685 -0.1306921026102526 -0.8631453725296494 0.7075597098930115 -0.04637591353493292 -0.7051301522271741 0.3570574644792096 0.3570574644792076 -0.8631453725296554 0.2686183601018445 0.2686183601018439 -0.9250342443566033 0.6144975546712324 0.3547803286058008 -0.7046443597570592 0.8650724726254417 0.05669984544201129 -0.4984322869082181 0.8373882722621905 0.2243775113039457 -0.4984331589077831 -0.2980469559637379 -0.07455112482027781 -0.951635508915457 -0.1294095225512526 -0.01703708685546406 -0.9914448613738116 -0.1294095225512526 -0.01703708685546406 -0.9914448613738116 -0.5022026247522233 -0.03291609906116239 -0.8641232864091635 -0.5022026247522188 0.03291609906116216 -0.8641232864091661 -0.1294095225512497 0.0170370868554802 -0.9914448613738116 -0.1294095225512497 0.0170370868554802 -0.9914448613738116 -0.2980469559637334 0.07455112482028185 -0.9516355089154581 0.4373042984130039 -0.2524777544065295 -0.8631453725296491 0.328988958896355 -0.1899418639792258 -0.9250342443566021 0.6853829641193395 -0.1836478117418259 -0.7046443597570529 0.8650724726254407 -0.05669984544201203 -0.4984322869082199 0.2524777544065273 0.4373042984129941 -0.8631453725296547 0.1899418639792284 0.3289889588963501 -0.9250342443566034 0.5017351523775112 0.5017351523775082 -0.7046443597570581 0.7507817855914651 0.4334640660138978 -0.4984331589077823 0.9640854128455839 0.06318949640755746 -0.2579658975177134 0.9331937336188315 0.2500485073049494 -0.2581185764897834 -0.4877495670894679 -0.1306921026102518 -0.8631453725296499 -0.7075597098930101 -0.0463759135349334 -0.7051301522271755 -0.7075597098930094 0.04637591353493286 -0.7051301522271762 -0.4877495670894583 0.1306921026102496 -0.8631453725296557 0.3570574644792161 -0.3570574644792161 -0.8631453725296491 0.2686183601018471 -0.2686183601018466 -0.9250342443566016 0.6144975546712366 -0.3547803286058063 -0.7046443597570529 0.8373882722621882 -0.2243775113039466 -0.4984331589077866 0.9640854128455844 -0.06318949640755783 -0.2579658975177117 0.1306921026102529 0.4877495670894601 -0.8631453725296541 0.09832114372019474 0.3669395038220337 -0.9250342443566036 0.3547803286058044 0.6144975546712306 -0.704644359757059 0.6130107609582474 0.6130107609582429 -0.4984331589077781 0.8366786123435727 0.4830566220617641 -0.2581185764897827 0.9892858993695024 0.06484122355896389 -0.1308014718420683 0.9575208326510117 0.2565669338448132 -0.1316330638433379 -0.4373042984130037 -0.2524777544065278 -0.8631453725296495 -0.328988958896355 -0.1899418639792242 -0.9250342443566025 -0.6853829641193372 -0.1836478117418237 -0.7046443597570558 -0.865072472625448 0.05669984544201193 -0.4984322869082074 -0.8650724726254442 -0.05669984544201199 -0.4984322869082139 -0.6853829641193361 0.183647811741824 -0.7046443597570568 -0.437304298412995 0.2524777544065209 -0.8631453725296562 -0.3289889588963511 0.1899418639792211 -0.9250342443566044 0.2524777544065291 -0.4373042984130041 -0.8631453725296492 0.1899418639792263 -0.3289889588963555 -0.925034244356602 0.5017351523775135 -0.5017351523775139 -0.7046443597570524 0.750781785591461 -0.4334640660138997 -0.4984331589077866 0.9331937336188322 -0.2500485073049493 -0.2581185764897809 0.9892858993695034 -0.06484122355896398 -0.1308014718420602 1.481513538301518e-016 0.5049555088130492 -0.8631453725296537 2.833507410527474e-016 0.3798837279584447 -0.9250342443566046 0.1836478117418217 0.6853829641193345 -0.7046443597570591 0.4334640660139029 0.750781785591468 -0.4984331589077735 0.6831452263138832 0.6831452263138795 -0.2581185764897826 0.858489692644828 0.4956492551450112 -0.1316330638433374 -0.3570574644792166 -0.3570574644792146 -0.8631453725296495 -0.268618360101847 -0.2686183601018445 -0.9250342443566024 -0.6144975546712351 -0.3547803286058037 -0.7046443597570554 -0.8373882722621904 -0.2243775113039465 -0.4984331589077828 -0.9640854128455852 0.06318949640755761 -0.2579658975177083 -0.9640854128455854 -0.06318949640755829 -0.2579658975177077 -0.8373882722621981 0.224377511303948 -0.4984331589077693 -0.6144975546712339 0.3547803286058023 -0.7046443597570569 -0.3570574644792097 0.3570574644792061 -0.8631453725296557 -0.2686183601018436 0.2686183601018393 -0.925034244356605 0.130692102610254 -0.4877495670894688 -0.863145372529649 0.09832114372019156 -0.366939503822038 -0.9250342443566022 0.3547803286058064 -0.6144975546712369 -0.7046443597570525 0.6130107609582429 -0.6130107609582404 -0.4984331589077868 0.8366786123435729 -0.4830566220617641 -0.2581185764897814 0.9575208326510132 -0.2565669338448152 -0.1316330638433239 -0.09832114372019248 0.36693950382203 -0.9250342443566053 -0.130692102610252 0.4877495670894637 -0.8631453725296522 -5.095627254616813e-016 0.7095606572116078 -0.7046443597570559 0.2243775113039432 0.8373882722621986 -0.4984331589077709 0.483056622061765 0.8366786123435727 -0.2581185764897807 0.700953898806195 0.7009538988061976 -0.131633063843343 -0.2524777544065299 -0.4373042984130035 -0.8631453725296492 -0.1899418639792275 -0.328988958896354 -0.9250342443566021 -0.5017351523775135 -0.501735152377512 -0.7046443597570538 -0.7507817855914644 -0.4334640660138989 -0.4984331589077828 -0.9331937336188333 -0.2500485073049486 -0.2581185764897773 -0.9892858993695011 0.06484122355896468 -0.1308014718420768 -0.9892858993695026 -0.06484122355896477 -0.1308014718420667 -0.933193733618833 0.2500485073049489 -0.2581185764897785 -0.7507817855914721 0.4334640660139016 -0.4984331589077685 -0.5017351523775114 0.5017351523775091 -0.704644359757057 -0.2524777544065261 0.4373042984129952 -0.8631453725296545 -0.1899418639792249 0.3289889588963474 -0.925034244356605 3.120964684059297e-016 -0.3798837279584495 -0.9250342443566026 1.795773985820026e-016 -0.5049555088130583 -0.8631453725296484 0.1836478117418268 -0.6853829641193396 -0.7046443597570526 0.4334640660138992 -0.7507817855914616 -0.4984331589077862 0.6831452263138821 -0.683145226313881 -0.2581185764897815 0.8584896926448293 -0.4956492551450125 -0.131633063843325 -0.1836478117418218 0.6853829641193373 -0.7046443597570562 2.263559080302044e-017 0.8669281320278058 -0.4984331589077708 0.2500485073049453 0.9331937336188334 -0.2581185764897797 0.4956492551450089 0.8584896926448271 -0.1316330638433521 -0.1306921026102543 -0.4877495670894691 -0.8631453725296487 -0.09832114372019264 -0.3669395038220378 -0.9250342443566023 -0.3547803286058062 -0.6144975546712361 -0.7046443597570532 -0.6130107609582444 -0.613010760958241 -0.4984331589077842 -0.8366786123435742 -0.4830566220617643 -0.258118576489777 -0.9575208326510127 -0.2565669338448145 -0.1316330638433294 -0.9575208326510101 0.2565669338448134 -0.13163306384335 -0.8366786123435743 0.4830566220617635 -0.2581185764897779 -0.6130107609582521 0.6130107609582458 -0.498433158907769 -0.3547803286058033 0.6144975546712327 -0.7046443597570575 3.878087999088903e-016 -0.709560657211612 -0.7046443597570518 0.2243775113039441 -0.8373882722621896 -0.4984331589077854 0.4830566220617642 -0.836678612343573 -0.2581185764897814 0.7009538988061992 -0.7009538988061969 -0.1316330638433243 -0.2243775113039425 0.8373882722621988 -0.4984331589077705 -2.360456869878988e-016 0.966113244123529 -0.2581185764897802 0.2565669338448097 0.9575208326510102 -0.1316330638433568 -0.183647811741826 -0.6853829641193396 -0.7046443597570528 -0.4334640660139001 -0.7507817855914613 -0.4984331589077861 -0.6831452263138839 -0.6831452263138803 -0.2581185764897786 -0.8584896926448302 -0.4956492551450097 -0.1316330638433289 -0.8584896926448269 0.4956492551450096 -0.1316330638433514 -0.6831452263138826 0.6831452263138816 -0.2581185764897779 -0.433464066013904 0.7507817855914699 -0.4984331589077699 4.255491070967834e-016 -0.8669281320277973 -0.4984331589077857 0.2500485073049474 -0.9331937336188324 -0.2581185764897815 0.4956492551450117 -0.8584896926448298 -0.1316330638433249 -0.2500485073049449 0.9331937336188337 -0.2581185764897794 -1.801666719264949e-016 0.9912985102900188 -0.1316330638433572 -0.224377511303944 -0.8373882722621894 -0.4984331589077857 -0.4830566220617651 -0.8366786123435727 -0.2581185764897803 -0.7009538988061994 -0.7009538988061961 -0.1316330638433261 -0.7009538988061964 0.7009538988061944 -0.1316330638433522 -0.4830566220617643 0.8366786123435739 -0.2581185764897782 4.630126937070359e-016 -0.9661132441235285 -0.258118576489782 0.2565669338448128 -0.9575208326510133 -0.1316330638433277 -0.2565669338448093 0.9575208326510102 -0.1316330638433571 -0.2500485073049477 -0.9331937336188324 -0.2581185764897814 -0.4956492551450126 -0.8584896926448291 -0.1316330638433255 -0.4956492551450089 0.8584896926448268 -0.1316330638433547 4.684333470088864e-016 -0.9912985102900226 -0.1316330638433289 -0.2565669338448131 -0.9575208326510133 -0.1316330638433277 + + + + + + + + + + + + + + +

0 1 2 1 3 4 3 1 0 5 3 0 3 5 6 3 7 4 7 3 8 6 8 3 8 6 9 10 0 11 0 10 5 12 6 5 6 12 13 8 14 7 14 8 15 15 16 14 17 18 19 18 17 20 8 21 15 21 8 9 13 9 6 9 13 22 23 11 24 11 23 10 25 5 10 5 25 12 12 26 13 26 12 27 18 28 19 28 18 29 30 28 29 17 31 32 31 17 19 33 34 35 35 20 17 20 35 34 15 36 37 36 15 21 9 38 21 38 9 22 22 26 39 26 22 13 40 24 41 24 40 23 42 10 23 10 42 25 25 27 12 27 25 43 27 44 26 44 27 45 19 46 31 46 19 28 32 47 48 47 32 31 49 17 32 17 49 35 37 50 51 50 37 36 21 52 36 52 21 38 38 39 53 39 38 22 39 44 54 44 39 26 55 41 56 41 55 40 57 23 40 23 57 42 42 43 25 43 42 58 43 45 27 45 43 59 45 60 44 60 45 61 28 62 46 62 28 63 31 64 47 64 31 46 65 47 66 47 65 48 67 32 48 32 67 49 68 35 49 35 68 69 51 70 71 70 51 50 36 72 50 72 36 52 52 53 73 53 52 38 53 54 74 54 53 39 54 60 75 60 54 44 76 56 77 56 76 55 78 40 55 40 78 57 79 42 57 42 79 58 58 59 43 59 58 80 59 61 45 61 59 81 63 82 62 82 63 83 46 84 64 84 46 62 66 64 85 64 66 47 86 66 87 66 86 65 65 67 48 67 65 88 89 49 67 49 89 68 90 69 68 69 90 91 71 92 93 92 71 70 50 94 70 94 50 72 72 73 95 73 72 52 73 74 96 74 73 53 74 75 97 75 74 54 76 98 99 98 76 77 78 76 100 76 78 55 101 57 78 57 101 79 102 58 79 58 102 80 80 81 59 81 80 103 83 104 82 104 83 105 62 106 84 106 62 82 85 84 107 84 85 64 87 85 108 85 87 66 109 87 110 87 109 86 86 88 65 88 86 111 88 89 67 89 88 112 113 68 89 68 113 90 114 91 90 91 114 115 116 92 117 92 116 93 70 118 92 118 70 94 95 94 72 94 95 119 95 96 120 96 95 73 96 97 121 97 96 74 99 115 114 115 99 98 100 99 122 99 100 76 123 78 100 78 123 101 124 79 101 79 124 102 125 80 102 80 125 103 105 126 104 126 105 127 82 128 106 128 82 104 107 106 129 106 107 84 108 107 130 107 108 85 110 108 131 108 110 87 109 111 86 111 109 132 111 112 88 112 111 133 112 113 89 113 112 134 135 90 113 90 135 114 127 117 126 117 127 116 92 136 117 136 92 118 119 118 94 118 119 137 120 119 95 119 120 138 120 121 139 121 120 96 122 114 135 114 122 99 140 100 122 100 140 123 141 101 123 101 141 124 142 102 124 102 142 125 104 143 128 143 104 126 144 106 128 106 144 129 130 129 145 129 130 107 131 130 146 130 131 108 132 133 111 133 132 147 133 134 112 134 133 148 134 135 113 135 134 149 126 136 143 136 126 117 137 136 118 136 137 150 138 137 119 137 138 151 139 138 120 138 139 152 149 122 135 122 149 140 153 123 140 123 153 141 154 124 141 124 154 142 155 128 143 128 155 144 156 129 144 129 156 145 146 145 157 145 146 130 147 148 133 148 147 158 148 149 134 149 148 159 150 143 136 143 150 155 151 150 137 150 151 160 152 151 138 151 152 161 159 140 149 140 159 153 162 141 153 141 162 154 163 144 155 144 163 156 164 145 156 145 164 157 158 159 148 159 158 165 160 155 150 155 160 163 161 160 151 160 161 166 165 153 159 153 165 162 167 156 163 156 167 164 166 163 160 163 166 167

+
+
+
+ + + + 0.1184986753859656 2.804370064010866 2.24409448818898 3.802459269029596 5.211752591652259 2.24409448818898 0.1184986753859656 7.755517072645532 2.24409448818898 3.821449895399476 5.203886416651894 2.24409448818898 5.080260594255362 4.709514930755915 2.24409448818898 5.233106487032441 4.689392387225837 2.24409448818898 25.61991398185795 2.804370064010866 2.24409448818898 3.786151648463726 5.224265869022172 2.24409448818898 3.773638371093813 5.240573489588042 2.24409448818898 3.765772196093449 5.259564115957922 2.24409448818898 3.763089190289438 5.279943568328199 2.24409448818898 3.841829347769753 5.201203410847884 2.24409448818898 3.862208800140031 5.203886416651894 2.24409448818898 4.937830896481261 4.768511243258649 2.24409448818898 3.881199426509911 5.211752591652259 2.24409448818898 3.89750704707578 5.224265869022172 2.24409448818898 3.910020324445693 5.240573489588042 2.24409448818898 3.917886499446058 5.259564115957922 2.24409448818898 3.920569505250068 5.279943568328199 2.24409448818898 4.815523742237236 4.862360823532994 2.24409448818898 4.721674161962891 4.984667977777018 2.24409448818898 4.662677849460157 5.127097675551119 2.24409448818898 4.642555305930079 5.279943568328199 2.24409448818898 5.385952379809521 4.709514930755915 2.24409448818898 5.528382077583623 4.768511243258649 2.24409448818898 5.650689231827647 4.862360823532995 2.24409448818898 5.744538812101991 4.984667977777018 2.24409448818898 5.803535124604726 5.12709767555112 2.24409448818898 5.823657668134803 5.279943568328199 2.24409448818898 5.233106487032441 5.870494749430561 2.24409448818898 51.06260368681876 7.755517072645532 2.24409448818898 5.080260594255362 5.850372205900484 2.24409448818898 3.821449895399476 5.356000720004503 2.24409448818898 3.802459269029596 5.348134545004139 2.24409448818898 3.786151648463726 5.335621267634227 2.24409448818898 3.773638371093813 5.319313647068356 2.24409448818898 3.765772196093449 5.300323020698476 2.24409448818898 3.841829347769753 5.358683725808514 2.24409448818898 3.86220880014003 5.356000720004504 2.24409448818898 4.93783089648126 5.791375893397749 2.24409448818898 3.881199426509911 5.348134545004139 2.24409448818898 3.89750704707578 5.335621267634227 2.24409448818898 3.910020324445693 5.319313647068356 2.24409448818898 3.917886499446058 5.300323020698476 2.24409448818898 4.815523742237236 5.697526313123404 2.24409448818898 4.721674161962891 5.57521915887938 2.24409448818898 4.662677849460157 5.432789461105278 2.24409448818898 5.38595237980952 5.850372205900484 2.24409448818898 5.528382077583622 5.791375893397749 2.24409448818898 5.650689231827647 5.697526313123404 2.24409448818898 5.744538812101991 5.575219158879381 2.24409448818898 5.803535124604726 5.432789461105278 2.24409448818898 30.70679771243117 0.1184986753859656 2.24409448818898 51.06260368681876 0.1184986753859656 2.24409448818898 + + + + + + + + + + -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 + + + + + + + + + + + + + + +

0 1 2 1 0 3 3 0 4 4 0 5 5 0 6 2 1 7 2 7 8 2 8 9 2 9 10 3 4 11 11 4 12 12 4 13 12 13 14 14 13 15 15 13 16 16 13 17 17 13 18 18 13 19 18 19 20 18 20 21 18 21 22 5 6 23 23 6 24 24 6 25 25 6 26 26 6 27 27 6 28 2 29 30 29 2 31 31 2 32 32 2 33 33 2 34 34 2 35 35 2 36 36 2 10 31 32 37 31 37 38 31 38 39 39 38 40 39 40 41 39 41 42 39 42 43 39 43 18 39 18 44 44 18 45 45 18 46 46 18 22 30 29 47 30 47 48 30 48 49 30 49 50 30 50 51 30 51 28 30 28 6 30 6 52 30 52 53

+
+
+
+ + + + 3.765772196093449 5.259564115957922 2.204724409448823 3.765772196093449 5.300323020698476 2.204724409448823 3.763089190289438 5.279943568328199 2.204724409448823 3.773638371093813 5.240573489588042 2.204724409448823 3.773638371093813 5.319313647068356 2.204724409448823 3.786151648463726 5.224265869022172 2.204724409448823 3.786151648463726 5.335621267634227 2.204724409448823 3.802459269029596 5.348134545004139 2.204724409448823 3.802459269029596 5.211752591652259 2.204724409448823 3.821449895399476 5.203886416651894 2.204724409448823 3.821449895399476 5.356000720004503 2.204724409448823 3.841829347769753 5.201203410847884 2.204724409448823 3.841829347769753 5.358683725808514 2.204724409448823 3.862208800140031 5.203886416651894 2.204724409448823 3.86220880014003 5.356000720004504 2.204724409448823 3.881199426509911 5.348134545004139 2.204724409448823 3.881199426509911 5.211752591652259 2.204724409448823 3.89750704707578 5.224265869022172 2.204724409448823 3.89750704707578 5.335621267634227 2.204724409448823 3.910020324445693 5.240573489588042 2.204724409448823 3.910020324445693 5.319313647068356 2.204724409448823 3.917886499446058 5.259564115957922 2.204724409448823 3.917886499446058 5.300323020698476 2.204724409448823 3.920569505250068 5.279943568328199 2.204724409448823 + + + + + + + + + + 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 + + + + + + + + + + + + + + +

0 1 2 1 0 3 1 3 4 4 3 5 4 5 6 6 5 7 7 5 8 7 8 9 7 9 10 10 9 11 10 11 12 12 11 13 12 13 14 14 13 15 15 13 16 15 16 17 15 17 18 18 17 19 18 19 20 20 19 21 20 21 22 22 21 23

+
+
+
+ + + + 3.821449895399476 5.203886416651894 2.24409448818898 3.841829347769753 5.201203410847884 2.204724409448823 3.821449895399476 5.203886416651894 2.204724409448823 3.841829347769753 5.201203410847884 2.24409448818898 3.862208800140031 5.203886416651894 2.204724409448823 3.862208800140031 5.203886416651894 2.24409448818898 3.802459269029596 5.211752591652259 2.24409448818898 3.802459269029596 5.211752591652259 2.204724409448823 3.881199426509911 5.211752591652259 2.204724409448823 3.881199426509911 5.211752591652259 2.24409448818898 3.786151648463726 5.224265869022172 2.24409448818898 3.786151648463726 5.224265869022172 2.204724409448823 3.89750704707578 5.224265869022172 2.204724409448823 3.89750704707578 5.224265869022172 2.24409448818898 3.773638371093813 5.240573489588042 2.204724409448823 3.773638371093813 5.240573489588042 2.24409448818898 3.910020324445693 5.240573489588042 2.24409448818898 3.910020324445693 5.240573489588042 2.204724409448823 3.765772196093449 5.259564115957922 2.204724409448823 3.765772196093449 5.259564115957922 2.24409448818898 3.917886499446058 5.259564115957922 2.24409448818898 3.917886499446058 5.259564115957922 2.204724409448823 3.763089190289438 5.279943568328199 2.204724409448823 3.763089190289438 5.279943568328199 2.24409448818898 3.920569505250068 5.279943568328199 2.24409448818898 3.920569505250068 5.279943568328199 2.204724409448823 3.765772196093449 5.300323020698476 2.204724409448823 3.765772196093449 5.300323020698476 2.24409448818898 3.917886499446058 5.300323020698476 2.24409448818898 3.917886499446058 5.300323020698476 2.204724409448823 3.773638371093813 5.319313647068356 2.204724409448823 3.773638371093813 5.319313647068356 2.24409448818898 3.910020324445693 5.319313647068356 2.24409448818898 3.910020324445693 5.319313647068356 2.204724409448823 3.786151648463726 5.335621267634227 2.204724409448823 3.786151648463726 5.335621267634227 2.24409448818898 3.89750704707578 5.335621267634227 2.24409448818898 3.89750704707578 5.335621267634227 2.204724409448823 3.802459269029596 5.348134545004139 2.24409448818898 3.802459269029596 5.348134545004139 2.204724409448823 3.881199426509911 5.348134545004139 2.204724409448823 3.881199426509911 5.348134545004139 2.24409448818898 3.821449895399476 5.356000720004503 2.24409448818898 3.821449895399476 5.356000720004503 2.204724409448823 3.86220880014003 5.356000720004504 2.204724409448823 3.86220880014003 5.356000720004504 2.24409448818898 3.841829347769753 5.358683725808514 2.24409448818898 3.841829347769753 5.358683725808514 2.204724409448823 + + + + + + + + + + 0.2588190451025272 0.9659258262890665 0 0 0.9999999999999999 0 0.2588190451025272 0.9659258262890665 0 0 0.9999999999999999 0 -0.2588190451025272 0.9659258262890665 0 -0.2588190451025272 0.9659258262890665 0 0.5000000000000094 0.8660254037844333 0 0.5000000000000094 0.8660254037844333 0 -0.5000000000000094 0.8660254037844333 0 -0.5000000000000094 0.8660254037844333 0 0.70710678118654 0.707106781186555 0 0.70710678118654 0.707106781186555 0 -0.70710678118654 0.707106781186555 0 -0.70710678118654 0.707106781186555 0 0.8660254037844379 0.5000000000000012 0 0.8660254037844379 0.5000000000000012 0 -0.8660254037844379 0.5000000000000012 0 -0.8660254037844379 0.5000000000000012 0 0.965925826289069 0.2588190451025184 0 0.965925826289069 0.2588190451025184 0 -0.965925826289069 0.2588190451025184 0 -0.965925826289069 0.2588190451025184 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0.965925826289069 -0.2588190451025184 0 0.965925826289069 -0.2588190451025184 0 -0.965925826289069 -0.2588190451025184 0 -0.965925826289069 -0.2588190451025184 0 0.8660254037844423 -0.499999999999994 0 0.8660254037844423 -0.499999999999994 0 -0.8660254037844379 -0.5000000000000012 0 -0.8660254037844379 -0.5000000000000012 0 0.7071067811865415 -0.7071067811865536 0 0.7071067811865415 -0.7071067811865536 0 -0.70710678118654 -0.707106781186555 0 -0.70710678118654 -0.707106781186555 0 0.4999999999999865 -0.8660254037844466 0 0.4999999999999865 -0.8660254037844466 0 -0.5000000000000059 -0.8660254037844354 0 -0.5000000000000059 -0.8660254037844354 0 0.2588190451025286 -0.9659258262890662 0 0.2588190451025286 -0.9659258262890662 0 -0.2588190451025246 -0.9659258262890673 0 -0.2588190451025246 -0.9659258262890673 0 1.998761949593601e-014 -1 0 1.998761949593601e-014 -1 0 + + + + + + + + + + + + + + +

0 1 2 1 0 3 3 4 1 4 3 5 6 2 7 2 6 0 5 8 4 8 5 9 10 7 11 7 10 6 9 12 8 12 9 13 14 10 11 10 14 15 16 12 13 12 16 17 18 15 14 15 18 19 20 17 16 17 20 21 22 19 18 19 22 23 24 21 20 21 24 25 26 23 22 23 26 27 28 25 24 25 28 29 30 27 26 27 30 31 32 29 28 29 32 33 34 31 30 31 34 35 36 33 32 33 36 37 38 34 39 34 38 35 36 40 37 40 36 41 42 39 43 39 42 38 41 44 40 44 41 45 46 43 47 43 46 42 45 47 44 47 45 46

+
+
+
+ + + + 4.662677849460157 5.127097675551119 1.968503937007879 4.662677849460157 5.432789461105278 1.968503937007879 4.642555305930079 5.279943568328199 1.968503937007879 4.681987464823896 5.279943568328199 1.968503937007879 4.700766390122029 5.137303469262347 1.968503937007879 4.721674161962891 4.984667977777018 1.968503937007879 4.755823413291001 5.004384057223927 1.968503937007879 4.815523742237236 4.862360823532994 1.968503937007879 4.843406489187879 4.890243570483637 1.968503937007879 4.937830896481261 4.768511243258649 1.968503937007879 4.95754697592817 4.802660494586758 1.968503937007879 5.080260594255362 4.709514930755915 1.968503937007879 5.090466387966592 4.747603471417786 1.968503937007879 5.233106487032441 4.689392387225837 1.968503937007879 5.233106487032441 4.728824546119654 1.968503937007879 5.385952379809521 4.709514930755915 1.968503937007879 5.375746586098293 4.747603471417786 1.968503937007879 5.508665998136713 4.802660494586758 1.968503937007879 5.528382077583623 4.768511243258649 1.968503937007879 5.622806484877003 4.890243570483638 1.968503937007879 5.650689231827647 4.862360823532995 1.968503937007879 5.710389560773883 5.004384057223929 1.968503937007879 5.744538812101991 4.984667977777018 1.968503937007879 5.765446583942854 5.137303469262349 1.968503937007879 5.803535124604726 5.12709767555112 1.968503937007879 5.784225509240986 5.279943568328199 1.968503937007879 4.700766390122029 5.422583667394049 1.968503937007879 4.721674161962891 5.57521915887938 1.968503937007879 4.755823413291 5.55550307943247 1.968503937007879 4.815523742237236 5.697526313123404 1.968503937007879 4.843406489187879 5.669643566172761 1.968503937007879 4.93783089648126 5.791375893397749 1.968503937007879 4.95754697592817 5.75722664206964 1.968503937007879 5.080260594255362 5.850372205900484 1.968503937007879 5.090466387966591 5.812283665238612 1.968503937007879 5.233106487032441 5.870494749430561 1.968503937007879 5.233106487032441 5.831062590536744 1.968503937007879 5.375746586098291 5.812283665238612 1.968503937007879 5.38595237980952 5.850372205900484 1.968503937007879 5.508665998136713 5.75722664206964 1.968503937007879 5.528382077583622 5.791375893397749 1.968503937007879 5.622806484877003 5.669643566172761 1.968503937007879 5.650689231827647 5.697526313123404 1.968503937007879 5.710389560773883 5.55550307943247 1.968503937007879 5.744538812101991 5.575219158879381 1.968503937007879 5.765446583942854 5.42258366739405 1.968503937007879 5.803535124604726 5.432789461105278 1.968503937007879 5.823657668134803 5.279943568328199 1.968503937007879 + + + + + + + + + + 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 + + + + + + + + + + + + + + +

0 1 2 1 0 3 3 0 4 4 0 5 4 5 6 6 5 7 6 7 8 8 7 9 8 9 10 10 9 11 10 11 12 12 11 13 12 13 14 14 13 15 14 15 16 16 15 17 17 15 18 17 18 19 19 18 20 19 20 21 21 20 22 21 22 23 23 22 24 23 24 25 1 26 27 26 1 3 27 26 28 27 28 29 29 28 30 29 30 31 31 30 32 31 32 33 33 32 34 33 34 35 35 34 36 35 36 37 35 37 38 38 37 39 38 39 40 40 39 41 40 41 42 42 41 43 42 43 44 44 43 45 44 45 46 46 45 25 46 25 24 46 24 47

+
+
+
+ + + + 4.662677849460157 5.432789461105278 1.968503937007879 4.642555305930079 5.279943568328199 2.24409448818898 4.642555305930079 5.279943568328199 1.968503937007879 4.662677849460157 5.432789461105278 2.24409448818898 4.662677849460157 5.127097675551119 2.24409448818898 4.662677849460157 5.127097675551119 1.968503937007879 4.721674161962891 5.57521915887938 1.968503937007879 4.721674161962891 5.57521915887938 2.24409448818898 4.721674161962891 4.984667977777018 2.24409448818898 4.721674161962891 4.984667977777018 1.968503937007879 4.815523742237236 5.697526313123404 1.968503937007879 4.815523742237236 5.697526313123404 2.24409448818898 4.815523742237236 4.862360823532994 2.24409448818898 4.815523742237236 4.862360823532994 1.968503937007879 4.93783089648126 5.791375893397749 2.24409448818898 4.93783089648126 5.791375893397749 1.968503937007879 4.937830896481261 4.768511243258649 1.968503937007879 4.937830896481261 4.768511243258649 2.24409448818898 5.080260594255362 5.850372205900484 2.24409448818898 5.080260594255362 5.850372205900484 1.968503937007879 5.080260594255362 4.709514930755915 1.968503937007879 5.080260594255362 4.709514930755915 2.24409448818898 5.233106487032441 5.870494749430561 2.24409448818898 5.233106487032441 5.870494749430561 1.968503937007879 5.233106487032441 4.689392387225837 1.968503937007879 5.233106487032441 4.689392387225837 2.24409448818898 5.38595237980952 5.850372205900484 2.24409448818898 5.38595237980952 5.850372205900484 1.968503937007879 5.385952379809521 4.709514930755915 1.968503937007879 5.385952379809521 4.709514930755915 2.24409448818898 5.528382077583622 5.791375893397749 2.24409448818898 5.528382077583622 5.791375893397749 1.968503937007879 5.528382077583623 4.768511243258649 1.968503937007879 5.528382077583623 4.768511243258649 2.24409448818898 5.650689231827647 5.697526313123404 2.24409448818898 5.650689231827647 5.697526313123404 1.968503937007879 5.650689231827647 4.862360823532995 1.968503937007879 5.650689231827647 4.862360823532995 2.24409448818898 5.744538812101991 5.575219158879381 1.968503937007879 5.744538812101991 5.575219158879381 2.24409448818898 5.744538812101991 4.984667977777018 2.24409448818898 5.744538812101991 4.984667977777018 1.968503937007879 5.803535124604726 5.432789461105278 1.968503937007879 5.803535124604726 5.432789461105278 2.24409448818898 5.803535124604726 5.12709767555112 2.24409448818898 5.803535124604726 5.12709767555112 1.968503937007879 5.823657668134803 5.279943568328199 1.968503937007879 5.823657668134803 5.279943568328199 2.24409448818898 + + + + + + + + + + 0.9659258262890681 -0.2588190451025217 0 1 -3.65355505721523e-016 0 1 -3.65355505721523e-016 0 0.9659258262890681 -0.2588190451025217 0 0.9659258262890681 0.2588190451025213 0 0.9659258262890681 0.2588190451025213 0 0.8660254037844393 -0.4999999999999991 0 0.8660254037844393 -0.4999999999999991 0 0.8660254037844384 0.5000000000000006 0 0.8660254037844384 0.5000000000000006 0 0.7071067811865488 -0.7071067811865462 0 0.7071067811865488 -0.7071067811865462 0 0.7071067811865462 0.7071067811865488 0 0.7071067811865462 0.7071067811865488 0 0.4999999999999997 -0.8660254037844389 0 0.4999999999999997 -0.8660254037844389 0 0.4999999999999991 0.8660254037844393 0 0.4999999999999991 0.8660254037844393 0 0.2588190451025206 -0.9659258262890682 0 0.2588190451025206 -0.9659258262890682 0 0.2588190451025217 0.9659258262890681 0 0.2588190451025217 0.9659258262890681 0 0 -1 0 0 -1 0 3.65355505721523e-016 1 0 3.65355505721523e-016 1 0 -0.2588190451025217 -0.9659258262890681 0 -0.2588190451025217 -0.9659258262890681 0 -0.2588190451025213 0.9659258262890681 0 -0.2588190451025213 0.9659258262890681 0 -0.4999999999999991 -0.8660254037844393 0 -0.4999999999999991 -0.8660254037844393 0 -0.5000000000000027 0.8660254037844372 0 -0.5000000000000027 0.8660254037844372 0 -0.7071067811865462 -0.7071067811865488 0 -0.7071067811865462 -0.7071067811865488 0 -0.7071067811865491 0.707106781186546 0 -0.7071067811865491 0.707106781186546 0 -0.8660254037844389 -0.4999999999999997 0 -0.8660254037844389 -0.4999999999999997 0 -0.8660254037844384 0.5000000000000006 0 -0.8660254037844384 0.5000000000000006 0 -0.9659258262890682 -0.2588190451025206 0 -0.9659258262890682 -0.2588190451025206 0 -0.9659258262890681 0.2588190451025217 0 -0.9659258262890681 0.2588190451025217 0 -1 0 0 -1 0 0 + + + + + + + + + + + + + + +

0 1 2 1 0 3 2 4 5 4 2 1 6 3 0 3 6 7 5 8 9 8 5 4 10 7 6 7 10 11 9 12 13 12 9 8 14 10 15 10 14 11 12 16 13 16 12 17 18 15 19 15 18 14 17 20 16 20 17 21 22 19 23 19 22 18 21 24 20 24 21 25 26 23 27 23 26 22 25 28 24 28 25 29 30 27 31 27 30 26 29 32 28 32 29 33 34 31 35 31 34 30 33 36 32 36 33 37 34 38 39 38 34 35 40 36 37 36 40 41 39 42 43 42 39 38 44 41 40 41 44 45 43 46 47 46 43 42 47 45 44 45 47 46

+
+
+
+ + + + 4.700766390122029 5.137303469262347 2.125984251968508 4.700766390122029 5.422583667394049 2.125984251968508 4.681987464823896 5.279943568328199 2.125984251968508 4.755823413291001 5.004384057223927 2.125984251968508 4.755823413291 5.55550307943247 2.125984251968508 4.843406489187879 5.669643566172761 2.125984251968508 4.843406489187879 4.890243570483637 2.125984251968508 4.95754697592817 4.802660494586758 2.125984251968508 4.95754697592817 5.75722664206964 2.125984251968508 5.090466387966592 4.747603471417786 2.125984251968508 5.090466387966591 5.812283665238612 2.125984251968508 5.233106487032441 5.831062590536744 2.125984251968508 5.233106487032441 4.728824546119654 2.125984251968508 5.375746586098293 4.747603471417786 2.125984251968508 5.375746586098291 5.812283665238612 2.125984251968508 5.508665998136713 5.75722664206964 2.125984251968508 5.508665998136713 4.802660494586758 2.125984251968508 5.622806484877003 4.890243570483638 2.125984251968508 5.622806484877003 5.669643566172761 2.125984251968508 5.710389560773883 5.004384057223929 2.125984251968508 5.710389560773883 5.55550307943247 2.125984251968508 5.765446583942854 5.137303469262349 2.125984251968508 5.765446583942854 5.42258366739405 2.125984251968508 5.784225509240986 5.279943568328199 2.125984251968508 + + + + + + + + + + 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 + + + + + + + + + + + + + + +

0 1 2 1 0 3 1 3 4 4 3 5 5 3 6 5 6 7 5 7 8 8 7 9 8 9 10 10 9 11 11 9 12 11 12 13 11 13 14 14 13 15 15 13 16 15 16 17 15 17 18 18 17 19 18 19 20 20 19 21 20 21 22 22 21 23

+
+
+
+ + + + 4.700766390122029 5.137303469262347 2.125984251968508 4.755823413291001 5.004384057223927 1.968503937007879 4.755823413291001 5.004384057223927 2.125984251968508 4.700766390122029 5.137303469262347 1.968503937007879 4.843406489187879 4.890243570483637 1.968503937007879 4.843406489187879 4.890243570483637 2.125984251968508 4.681987464823896 5.279943568328199 2.125984251968508 4.681987464823896 5.279943568328199 1.968503937007879 4.95754697592817 4.802660494586758 2.125984251968508 4.95754697592817 4.802660494586758 1.968503937007879 4.700766390122029 5.422583667394049 2.125984251968508 4.700766390122029 5.422583667394049 1.968503937007879 5.090466387966592 4.747603471417786 2.125984251968508 5.090466387966592 4.747603471417786 1.968503937007879 4.755823413291 5.55550307943247 2.125984251968508 4.755823413291 5.55550307943247 1.968503937007879 5.233106487032441 4.728824546119654 2.125984251968508 5.233106487032441 4.728824546119654 1.968503937007879 4.843406489187879 5.669643566172761 2.125984251968508 4.843406489187879 5.669643566172761 1.968503937007879 5.375746586098293 4.747603471417786 2.125984251968508 5.375746586098293 4.747603471417786 1.968503937007879 4.95754697592817 5.75722664206964 1.968503937007879 4.95754697592817 5.75722664206964 2.125984251968508 5.508665998136713 4.802660494586758 2.125984251968508 5.508665998136713 4.802660494586758 1.968503937007879 5.090466387966591 5.812283665238612 1.968503937007879 5.090466387966591 5.812283665238612 2.125984251968508 5.622806484877003 4.890243570483638 2.125984251968508 5.622806484877003 4.890243570483638 1.968503937007879 5.233106487032441 5.831062590536744 1.968503937007879 5.233106487032441 5.831062590536744 2.125984251968508 5.710389560773883 5.004384057223929 1.968503937007879 5.710389560773883 5.004384057223929 2.125984251968508 5.375746586098291 5.812283665238612 1.968503937007879 5.375746586098291 5.812283665238612 2.125984251968508 5.765446583942854 5.137303469262349 1.968503937007879 5.765446583942854 5.137303469262349 2.125984251968508 5.508665998136713 5.75722664206964 1.968503937007879 5.508665998136713 5.75722664206964 2.125984251968508 5.784225509240986 5.279943568328199 1.968503937007879 5.784225509240986 5.279943568328199 2.125984251968508 5.622806484877003 5.669643566172761 1.968503937007879 5.622806484877003 5.669643566172761 2.125984251968508 5.765446583942854 5.42258366739405 1.968503937007879 5.765446583942854 5.42258366739405 2.125984251968508 5.710389560773883 5.55550307943247 2.125984251968508 5.710389560773883 5.55550307943247 1.968503937007879 + + + + + + + + + + -0.9659258262890681 -0.2588190451025219 0 -0.8660254037844379 -0.500000000000001 0 -0.8660254037844379 -0.500000000000001 0 -0.9659258262890681 -0.2588190451025219 0 -0.707106781186548 -0.7071067811865471 0 -0.707106781186548 -0.7071067811865471 0 -1 7.930887807125743e-016 0 -1 7.930887807125743e-016 0 -0.4999999999999981 -0.8660254037844398 0 -0.4999999999999981 -0.8660254037844398 0 -0.9659258262890688 0.2588190451025187 0 -0.9659258262890688 0.2588190451025187 0 -0.2588190451025187 -0.9659258262890688 0 -0.2588190451025187 -0.9659258262890688 0 -0.8660254037844398 0.4999999999999981 0 -0.8660254037844398 0.4999999999999981 0 -7.930887807125743e-016 -1 0 -7.930887807125743e-016 -1 0 -0.7071067811865475 0.7071067811865475 0 -0.7071067811865475 0.7071067811865475 0 0.2588190451025202 -0.9659258262890684 0 0.2588190451025202 -0.9659258262890684 0 -0.4999999999999992 0.8660254037844393 0 -0.4999999999999992 0.8660254037844393 0 0.5000000000000023 -0.8660254037844374 0 0.5000000000000023 -0.8660254037844374 0 -0.2588190451025195 0.9659258262890687 0 -0.2588190451025195 0.9659258262890687 0 0.7071067811865494 -0.7071067811865457 0 0.7071067811865494 -0.7071067811865457 0 3.920888354084637e-016 1 0 3.920888354084637e-016 1 0 0.8660254037844393 -0.4999999999999992 0 0.8660254037844393 -0.4999999999999992 0 0.2588190451025187 0.9659258262890688 0 0.2588190451025187 0.9659258262890688 0 0.9659258262890687 -0.2588190451025199 0 0.9659258262890687 -0.2588190451025199 0 0.4999999999999981 0.8660254037844398 0 0.4999999999999981 0.8660254037844398 0 1 -3.920888354084637e-016 0 1 -3.920888354084637e-016 0 0.7071067811865475 0.7071067811865475 0 0.7071067811865475 0.7071067811865475 0 0.9659258262890687 0.2588190451025195 0 0.9659258262890687 0.2588190451025195 0 0.8660254037844393 0.4999999999999992 0 0.8660254037844393 0.4999999999999992 0 + + + + + + + + + + + + + + +

0 1 2 1 0 3 2 4 5 4 2 1 6 3 0 3 6 7 8 4 9 4 8 5 10 7 6 7 10 11 12 9 13 9 12 8 14 11 10 11 14 15 16 13 17 13 16 12 18 15 14 15 18 19 20 17 21 17 20 16 18 22 19 22 18 23 24 21 25 21 24 20 23 26 22 26 23 27 28 25 29 25 28 24 27 30 26 30 27 31 32 28 29 28 32 33 31 34 30 34 31 35 36 33 32 33 36 37 35 38 34 38 35 39 40 37 36 37 40 41 39 42 38 42 39 43 44 41 40 41 44 45 42 46 47 46 42 43 47 45 44 45 47 46

+
+
+
+ + + + 49.88188976377955 7.182685229005588 0.604869657207319 49.88188976377955 0.7153153851313138 1.166727690057971 49.88188976377955 0.7153153851313135 0.604869657207319 49.88188976377955 7.182685229005587 1.166727690057971 51.18110236220473 0.7153153851313135 0.604869657207319 49.88188976377955 7.182685229005588 0.604869657207319 49.88188976377955 0.7153153851313135 0.604869657207319 51.18110236220473 7.182685229005588 0.604869657207319 51.18110236220473 7.182685229005587 1.166727690057971 49.88188976377955 7.182685229005588 0.604869657207319 51.18110236220473 7.182685229005588 0.604869657207319 49.88188976377955 7.182685229005587 1.166727690057971 51.18110236220473 7.182685229005587 1.166727690057971 49.88188976377955 0.7153153851313138 1.166727690057971 49.88188976377955 7.182685229005587 1.166727690057971 51.18110236220473 0.7153153851313138 1.166727690057971 49.88188976377955 0.7153153851313138 1.166727690057971 51.18110236220473 0.7153153851313135 0.604869657207319 49.88188976377955 0.7153153851313135 0.604869657207319 51.18110236220473 0.7153153851313138 1.166727690057971 + + + + + + + + + + 1 0 0 1 0 0 1 0 0 1 0 0 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -1 -1.580787970928972e-015 -0 -1 -1.580787970928972e-015 -0 -1 -1.580787970928972e-015 -0 -1 -1.580787970928972e-015 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 1 -3.95196992732243e-016 -0 1 -3.95196992732243e-016 -0 1 -3.95196992732243e-016 -0 1 -3.95196992732243e-016 + + + + + + + + + + + + + + +

0 1 2 1 0 3 4 5 6 5 4 7 8 9 10 9 8 11 12 13 14 13 12 15 16 17 18 17 16 19

+
+
+
+ + + + 43.3770845465892 7.368501434310447 8.326672684688674e-016 43.37882183390003 7.395007316609055 8.326672684688674e-016 + + + + + + + + + + + + + +

1 0

+
+
+
+ + + + 43.55364811608248 7.569833598791506 8.326672684688674e-016 43.58015399838109 7.571570886102331 8.326672684688674e-016 + + + + + + + + + + + + + +

1 0

+
+
+
+ + + + 51.06260368681876 0.1184986753859656 0 0 0 0 51.06260368681876 0.1184986753859656 2.165354330708662 + + + + + + + + + + + + + +

1 0 0 2

+
+
+
+ + + + 0 0 2.834645669291339 0 0 2.165354330708662 + + + + + + + + + + + + + +

1 0

+
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + 0.1254901960784314 0.2117647058823529 0.2274509803921569 1 + + + + + + + + + + + 0.2431372549019608 0.3568627450980392 0.4352941176470588 1 + + + + + + + + + + + 0.6627450980392157 0.6627450980392157 0.6627450980392157 1 + + + + + + + + + + + 0 0 0 1 + + + + + + + + + + + 0.2156862745098039 0.3568627450980392 0.3843137254901961 1 + + + + + + + + + + + 0.2431372549019608 0.3568627450980392 0.4352941176470588 1 + + + 1 + + + + + + + + + +
diff --git a/simulators/sim_env/meshes/turtlebot3/sensors/r200.jpg b/simulators/sim_env/meshes/turtlebot3/sensors/r200.jpg new file mode 100755 index 0000000..8956fcf Binary files /dev/null and b/simulators/sim_env/meshes/turtlebot3/sensors/r200.jpg differ diff --git a/simulators/sim_env/meshes/turtlebot3/wheels/left_tire.stl b/simulators/sim_env/meshes/turtlebot3/wheels/left_tire.stl new file mode 100755 index 0000000..29bfa03 Binary files /dev/null and b/simulators/sim_env/meshes/turtlebot3/wheels/left_tire.stl differ diff --git a/simulators/sim_env/meshes/turtlebot3/wheels/right_tire.stl b/simulators/sim_env/meshes/turtlebot3/wheels/right_tire.stl new file mode 100755 index 0000000..43c27e6 Binary files /dev/null and b/simulators/sim_env/meshes/turtlebot3/wheels/right_tire.stl differ diff --git a/simulators/sim_env/models/aws_robomaker_warehouse_ClutteringA_01/materials/textures/aws_robomaker_warehouse_ClutteringA_01.png b/simulators/sim_env/models/aws_robomaker_warehouse_ClutteringA_01/materials/textures/aws_robomaker_warehouse_ClutteringA_01.png new file mode 100755 index 0000000..b28b289 Binary files /dev/null and b/simulators/sim_env/models/aws_robomaker_warehouse_ClutteringA_01/materials/textures/aws_robomaker_warehouse_ClutteringA_01.png differ diff --git a/simulators/sim_env/models/aws_robomaker_warehouse_ClutteringA_01/materials/textures/aws_robomaker_warehouse_ClutteringA_02.png b/simulators/sim_env/models/aws_robomaker_warehouse_ClutteringA_01/materials/textures/aws_robomaker_warehouse_ClutteringA_02.png new file mode 100755 index 0000000..4b7e610 Binary files /dev/null and b/simulators/sim_env/models/aws_robomaker_warehouse_ClutteringA_01/materials/textures/aws_robomaker_warehouse_ClutteringA_02.png differ diff --git a/simulators/sim_env/models/aws_robomaker_warehouse_ClutteringA_01/materials/textures/aws_robomaker_warehouse_ClutteringA_03.png b/simulators/sim_env/models/aws_robomaker_warehouse_ClutteringA_01/materials/textures/aws_robomaker_warehouse_ClutteringA_03.png new file mode 100755 index 0000000..a8f1e1c Binary files /dev/null and b/simulators/sim_env/models/aws_robomaker_warehouse_ClutteringA_01/materials/textures/aws_robomaker_warehouse_ClutteringA_03.png differ diff --git a/simulators/sim_env/models/aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_collision.DAE b/simulators/sim_env/models/aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_collision.DAE new file mode 100755 index 0000000..553d82b --- /dev/null +++ b/simulators/sim_env/models/aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_collision.DAE @@ -0,0 +1,327 @@ + + + FBX COLLADA exporter2019-03-18T11:45:58Z2019-03-18T11:45:58ZZ_UP + + + + + +-94.500908 -100.041384 3.000000 +62.468575 -100.041384 3.000000 +-94.500908 80.061399 3.000000 +62.468575 80.061399 3.000000 +-94.500908 -100.041384 111.551331 +62.468575 -100.041384 111.551331 +-94.500908 80.061399 111.551331 +62.468575 80.061399 111.551331 +29.526070 43.870054 3.000000 +96.793404 43.870054 3.000000 +29.526070 98.479551 3.000000 +96.793404 100.129454 3.000000 +29.526070 43.870054 73.674812 +96.793404 43.870054 73.674812 +29.526070 98.479551 73.674812 +96.793404 100.129454 73.674812 +56.843697 -49.131350 3.000000 +46.691963 22.638792 3.000000 +99.844673 23.109861 3.000000 +107.644112 -43.094973 3.000000 +56.843697 -49.131350 73.674812 +107.644112 -43.094973 73.674812 +99.844673 23.109861 73.674812 +46.691963 22.638792 73.674812 +-108.431084 -32.400026 3.000000 +-108.431084 18.446653 3.000000 +-88.055717 18.917723 3.000000 +-84.168144 -31.578005 3.000000 +-108.431084 -32.400026 73.674812 +-84.168144 -31.578005 73.674812 +-88.055717 18.917723 73.674812 +-108.431084 18.446653 73.674812 + + + + + + + + + + + +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.024520 0.999699 0.000000 +-0.024520 0.999699 0.000000 +-0.024520 0.999699 0.000000 +-0.024520 0.999699 0.000000 +-0.024520 0.999699 0.000000 +-0.024520 0.999699 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.117995 -0.993014 0.000000 +0.117995 -0.993014 0.000000 +0.117995 -0.993014 0.000000 +0.117995 -0.993014 0.000000 +0.117995 -0.993014 0.000000 +0.117995 -0.993014 0.000000 +0.993132 0.116999 0.000000 +0.993132 0.116999 0.000000 +0.993132 0.116999 0.000000 +0.993132 0.116999 0.000000 +0.993132 0.116999 0.000000 +0.993132 0.116999 0.000000 +-0.008862 0.999961 0.000000 +-0.008862 0.999961 0.000000 +-0.008862 0.999961 0.000000 +-0.008862 0.999961 0.000000 +-0.008862 0.999961 0.000000 +-0.008862 0.999961 0.000000 +-0.990144 -0.140054 0.000000 +-0.990144 -0.140054 0.000000 +-0.990144 -0.140054 0.000000 +-0.990144 -0.140054 0.000000 +-0.990144 -0.140054 0.000000 +-0.990144 -0.140054 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.033860 -0.999427 0.000000 +0.033860 -0.999427 0.000000 +0.033860 -0.999427 0.000000 +0.033860 -0.999427 0.000000 +0.033860 -0.999427 0.000000 +0.033860 -0.999427 0.000000 +0.997050 0.076761 0.000000 +0.997050 0.076761 0.000000 +0.997050 0.076761 0.000000 +0.997050 0.076761 0.000000 +0.997050 0.076761 0.000000 +0.997050 0.076761 0.000000 +-0.023113 0.999733 0.000000 +-0.023113 0.999733 0.000000 +-0.023113 0.999733 0.000000 +-0.023113 0.999733 0.000000 +-0.023113 0.999733 0.000000 +-0.023113 0.999733 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 + + + + + + + + + + + +1.000000 0.000000 +0.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +1.000000 0.000000 +0.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +1.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +0.000000 0.000000 +1.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +1.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +0.000000 0.000000 +1.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 + + + + + + + + + + + +

1 0 1 0 1 0 3 2 3 0 3 0 2 4 2 3 5 3 7 6 7 6 7 6 4 8 4 7 9 7 4 10 4 5 11 5 5 12 11 4 13 10 0 14 8 5 15 11 0 16 8 1 17 9 7 18 15 5 19 14 1 20 12 7 21 15 1 22 12 3 23 13 6 24 19 7 25 18 3 26 16 6 27 19 3 28 16 2 29 17 4 30 23 6 31 22 2 32 20 4 33 23 2 34 20 0 35 21 9 36 25 10 37 26 11 38 27 10 39 26 9 40 25 8 41 24 14 42 30 13 43 29 15 44 31 13 45 29 14 46 30 12 47 28 13 48 35 12 49 34 8 50 32 13 51 35 8 52 32 9 53 33 15 54 39 13 55 38 9 56 36 15 57 39 9 58 36 11 59 37 14 60 43 15 61 42 11 62 40 14 63 43 11 64 40 10 65 41 12 66 47 14 67 46 10 68 44 12 69 47 10 70 44 8 71 45 19 72 51 16 73 48 18 74 50 16 75 48 17 76 49 18 77 50 22 78 54 23 79 55 20 80 52 22 81 54 20 82 52 21 83 53 21 84 58 20 85 59 16 86 56 21 87 58 16 88 56 19 89 57 22 90 62 21 91 63 19 92 60 22 93 62 19 94 60 18 95 61 23 96 66 22 97 67 18 98 64 23 99 66 18 100 64 17 101 65 20 102 70 23 103 71 17 104 68 20 105 70 17 106 68 16 107 69 26 108 74 27 109 75 24 110 72 24 111 72 25 112 73 26 113 74 31 114 79 28 115 76 30 116 78 30 117 78 28 118 76 29 119 77 28 120 83 24 121 80 29 122 82 29 123 82 24 124 80 27 125 81 30 126 86 29 127 87 27 128 84 30 129 86 27 130 84 26 131 85 30 132 91 26 133 88 31 134 90 31 135 90 26 136 88 25 137 89 28 138 94 31 139 95 25 140 92 28 141 94 25 142 92 24 143 93

+
+
+
+ + + 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.0000001.000000 + 30.0000000.0000003.333333 + + + + + +
diff --git a/simulators/sim_env/models/aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_visual.DAE b/simulators/sim_env/models/aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_visual.DAE new file mode 100755 index 0000000..7b071bd --- /dev/null +++ b/simulators/sim_env/models/aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_visual.DAE @@ -0,0 +1,1874 @@ + + + FBX COLLADA exporter2019-05-23T10:22:51Z2019-05-23T10:22:51ZZ_UP + + + ../materials/textures/aws_robomaker_warehouse_ClutteringA_01.png + + + ../materials/textures/aws_robomaker_warehouse_ClutteringA_02.png + + + ../materials/textures/aws_robomaker_warehouse_ClutteringA_03.png + + + + + + + + + + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + +0.762349 -0.606361 0.055429 +0.762349 -0.606361 0.494255 +0.673489 0.143674 0.494255 +0.673489 0.143674 0.055429 +1.358378 -0.535747 0.055429 +1.269518 0.214288 0.055429 +1.269519 0.214288 0.494255 +1.358378 -0.535747 0.494255 +0.686616 0.145229 0.494255 +0.727190 -0.442360 0.509501 +0.727190 0.276956 0.509501 +1.223694 0.276958 0.509501 +1.223696 -0.442358 0.509501 +0.654626 0.292200 0.055429 +0.654627 0.292200 0.494255 +0.670540 -0.462913 0.494255 +0.670540 -0.462913 0.055429 +0.054562 0.279554 0.055429 +0.070475 -0.475559 0.055429 +0.070476 -0.475559 0.494255 +0.067778 0.279833 0.494255 +0.054562 0.279554 0.494255 +0.049009 0.284453 0.055429 +0.049009 0.284453 0.494255 +0.064923 -0.470660 0.494255 +0.064923 -0.470661 0.055429 +-0.551056 0.271806 0.055429 +-0.535142 -0.483307 0.055429 +-0.535142 -0.483307 0.494255 +-0.537840 0.272085 0.494255 +-0.551055 0.271806 0.494255 +0.728582 -0.476027 0.055429 +0.728582 -0.476027 0.494255 +0.744496 -1.231140 0.494255 +0.744496 -1.231140 0.055429 +0.128518 -0.488673 0.055429 +0.144431 -1.243786 0.055429 +0.144431 -1.243786 0.494255 +0.141733 -0.488395 0.494255 +0.128518 -0.488673 0.494255 +0.113458 -0.487202 0.055429 +0.113459 -0.487202 0.494255 +0.129372 -1.242315 0.494255 +0.129372 -1.242316 0.055429 +-0.486606 -0.499848 0.055429 +-0.470693 -1.254962 0.055429 +-0.470692 -1.254962 0.494255 +-0.473390 -0.499570 0.494255 +-0.486606 -0.499848 0.494255 +-0.350717 -1.242098 0.502955 +-0.350717 -1.242099 0.941781 +-1.105990 -1.245517 0.941781 +-1.105990 -1.245517 0.502955 +-0.353434 -0.641907 0.502955 +-1.108707 -0.645325 0.502955 +-1.108707 -0.645325 0.941781 +-0.353374 -0.655125 0.941781 +-0.353434 -0.641907 0.941781 +-0.521947 -0.487202 0.055429 +-0.521946 -0.487202 0.494255 +-0.506033 -1.242315 0.494255 +-0.506033 -1.242316 0.055429 +-1.122011 -0.499848 0.055429 +-1.106098 -1.254962 0.055429 +-1.106098 -1.254962 0.494255 +-1.108795 -0.499570 0.494255 +-1.122011 -0.499848 0.494255 +0.414450 -1.246076 0.502955 +0.414450 -1.246077 0.941781 +-0.340823 -1.249495 0.941781 +-0.340823 -1.249495 0.502955 +0.411733 -0.645885 0.502955 +-0.343540 -0.649303 0.502955 +-0.343540 -0.649303 0.941781 +0.411793 -0.659103 0.941781 +0.411733 -0.645884 0.941781 +0.549717 -0.522866 0.457994 +0.549717 -0.522867 0.716063 +-0.436317 -0.570149 0.716063 +-0.436317 -0.570147 0.457994 +0.520747 0.081303 0.457994 +-0.465287 0.034019 0.457994 +0.520748 0.081303 0.716063 +-0.465287 0.034022 0.716063 +0.557365 -0.508447 0.724572 +0.557365 -0.508448 0.982641 +-0.426944 -0.583510 0.982641 +-0.426944 -0.583510 0.724572 +0.511375 0.094665 0.724573 +-0.472935 0.019601 0.724573 +0.511375 0.094664 0.982641 +-0.472935 0.019602 0.982641 +-1.130571 -0.501727 0.514184 +-1.130572 -0.501727 0.953010 +-1.133990 0.253546 0.953010 +-1.133990 0.253546 0.514184 +-0.530380 -0.499010 0.514184 +-0.533798 0.256263 0.514184 +-0.533798 0.256263 0.953010 +-0.543598 -0.499070 0.953010 +-0.530379 -0.499010 0.953010 +-0.590618 -0.387423 0.055429 +-0.590618 -0.387423 0.494255 +-1.345731 -0.403336 0.494255 +-1.345732 -0.403336 0.055429 +-0.603265 0.212642 0.055429 +-1.358378 0.196728 0.055429 +-1.358378 0.196728 0.494255 +-0.602986 0.199426 0.494255 +-0.603265 0.212642 0.494255 +-0.963410 0.251932 0.497822 +-0.963411 0.251932 0.936648 +-0.966830 1.007205 0.936648 +-0.966830 1.007206 0.497822 +-0.363219 0.254649 0.497822 +-0.366637 1.009923 0.497822 +-0.366638 1.009923 0.936648 +-0.376437 0.254589 0.936648 +-0.363219 0.254649 0.936648 +-0.423457 0.366237 0.055429 +-0.423457 0.366236 0.494255 +-1.178570 0.350323 0.494255 +-1.178571 0.350323 0.055429 +-0.436104 0.966301 0.055429 +-1.191217 0.950387 0.055429 +-1.191217 0.950387 0.494255 +-0.435825 0.953085 0.494255 +-0.436104 0.966301 0.494255 +-0.145074 0.178557 0.491724 +-0.145074 0.178557 0.930551 +-0.148493 0.933831 0.930551 +-0.148493 0.933831 0.491724 +0.455118 0.181274 0.491724 +0.451700 0.936548 0.491724 +0.451699 0.936548 0.930551 +0.441899 0.181214 0.930551 +0.455118 0.181274 0.930551 +0.394880 0.292862 0.055429 +0.394880 0.292861 0.494255 +-0.360234 0.276948 0.494255 +-0.360234 0.276948 0.055429 +0.382233 0.892926 0.055429 +-0.372880 0.877013 0.055429 +-0.372880 0.877013 0.494255 +0.382512 0.879710 0.494255 +0.382233 0.892926 0.494255 +0.464209 1.211223 0.487764 +0.464209 1.211223 0.926590 +1.219483 1.214642 0.926590 +1.219483 1.214642 0.487764 +0.466926 0.611031 0.487764 +1.222200 0.614450 0.487764 +1.222200 0.614450 0.926590 +0.466866 0.624250 0.926590 +0.466926 0.611031 0.926590 +1.164522 0.654896 0.055429 +1.164522 0.654896 0.494255 +0.409409 0.638982 0.494255 +0.409408 0.638982 0.055429 +1.151876 1.254961 0.055429 +0.396762 1.239047 0.055429 +0.396762 1.239047 0.494255 +1.152154 1.241745 0.494255 +1.151876 1.254961 0.494255 +-0.145074 0.178557 0.930911 +-0.145074 0.178557 1.369738 +-0.148493 0.933831 1.369738 +-0.148493 0.933831 0.930911 +0.455118 0.181274 0.930911 +0.451700 0.936548 0.930911 +0.451699 0.936548 1.369738 +0.441899 0.181214 1.369738 +0.455118 0.181274 1.369738 +0.557365 -0.508447 0.983359 +0.557365 -0.508448 1.241428 +-0.426944 -0.583510 1.241428 +-0.426944 -0.583510 0.983359 +0.511375 0.094665 0.983359 +-0.472935 0.019601 0.983359 +0.511375 0.094664 1.241428 +-0.472935 0.019602 1.241428 +-1.130571 -0.501727 0.955464 +-1.130572 -0.501727 1.394290 +-1.133990 0.253546 1.394290 +-1.133990 0.253547 0.955464 +-0.530380 -0.499010 0.955464 +-0.533798 0.256263 0.955464 +-0.533798 0.256263 1.394290 +-0.543598 -0.499070 1.394290 +-0.530379 -0.499010 1.394290 +0.727190 -0.442360 0.792406 +1.223696 -0.442358 0.792406 +1.223694 0.276958 0.792406 +0.727190 0.276956 0.792406 + + + + + + + + + + + +0.993055 0.117651 -0.000001 +0.993055 0.117651 -0.000001 +0.993055 0.117651 -0.000001 +0.993055 0.117651 -0.000001 +0.993055 0.117651 -0.000001 +0.993055 0.117651 -0.000001 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.117651 0.993055 0.000000 +0.117651 -0.993055 0.000000 +0.117651 -0.993055 0.000000 +0.117651 -0.993055 0.000000 +0.117651 -0.993055 0.000000 +0.117651 -0.993055 0.000000 +0.117651 -0.993055 0.000000 +-0.993055 -0.117651 0.000000 +-0.993055 -0.117651 0.000000 +-0.993055 -0.117651 0.000000 +-0.993055 -0.117651 0.000000 +-0.993055 -0.117651 0.000000 +-0.993055 -0.117651 0.000000 +-0.117651 0.993055 0.000000 +-0.117651 0.993055 0.000000 +-0.117651 0.993055 0.000000 +-0.117651 0.993055 0.000000 +-0.117651 0.993055 0.000000 +-0.117651 0.993055 0.000000 +0.999778 0.021070 -0.000001 +0.999778 0.021070 -0.000001 +0.999778 0.021070 -0.000001 +0.999778 0.021070 -0.000001 +0.999778 0.021070 -0.000001 +0.999778 0.021070 -0.000001 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.021070 0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.021070 0.999778 0.000000 +0.000000 0.000000 1.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.021070 0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.021070 0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +0.004527 -0.999990 -0.000001 +0.004527 -0.999990 -0.000001 +0.004527 -0.999990 -0.000001 +0.004527 -0.999990 -0.000001 +0.004527 -0.999990 -0.000001 +0.004527 -0.999990 -0.000001 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.999990 0.004527 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.004526 0.999990 0.000000 +-0.004526 0.999990 0.000000 +-0.004526 0.999990 0.000000 +-0.004526 0.999990 0.000000 +-0.004526 0.999990 0.000000 +-0.004526 0.999990 0.000000 +0.999990 0.004527 0.000000 +0.999990 0.004527 0.000000 +0.999990 0.004527 0.000000 +0.999990 0.004527 0.000000 +0.999990 0.004527 0.000000 +0.999990 0.004527 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.021070 0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.999990 0.004527 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.999990 0.004527 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.004526 0.999990 0.000000 +-0.004526 0.999990 0.000000 +-0.004526 0.999990 0.000000 +-0.004526 0.999990 0.000000 +-0.004526 0.999990 0.000000 +-0.004526 0.999990 0.000000 +0.999990 0.004527 0.000000 +0.999990 0.004527 0.000000 +0.999990 0.004527 0.000000 +0.999990 0.004527 0.000000 +0.999990 0.004527 0.000000 +0.999990 0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.004527 -0.999990 0.000000 +0.000000 0.000000 1.000000 +0.004527 -0.999990 0.000000 +0.000000 0.000000 1.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.999778 0.021070 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.004527 -0.999990 0.000000 +0.000000 0.000000 1.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.999778 0.021070 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.004527 -0.999990 0.000000 +0.000000 0.000000 1.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.999778 0.021070 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999990 -0.004527 0.000000 +0.999990 0.004527 0.000000 +0.999990 0.004527 0.000000 +0.999990 0.004527 0.000000 +0.999990 0.004527 0.000000 +0.999990 0.004527 0.000000 +0.999990 0.004527 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.021070 -0.999778 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.999778 0.021070 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.999778 -0.021070 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +-0.999990 -0.004527 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.004527 -0.999990 0.000000 +0.000000 0.000000 1.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +-0.999990 -0.004526 0.000000 +-0.999990 -0.004526 0.000000 +-0.999990 -0.004526 0.000000 +-0.999990 -0.004526 0.000000 +-0.999990 -0.004526 0.000000 +-0.999990 -0.004526 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.004527 -0.999990 0.000000 +0.000000 0.000000 1.000000 +0.004527 -0.999990 0.000000 +0.000000 0.000000 1.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +-0.004527 0.999990 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.999990 0.004526 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.004527 -0.999990 0.000000 +0.047896 -0.998852 -0.000005 +0.047896 -0.998852 -0.000005 +0.047896 -0.998852 -0.000005 +0.047896 -0.998852 -0.000005 +0.047896 -0.998852 -0.000005 +0.047896 -0.998852 -0.000005 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.998852 0.047894 -0.000002 +0.998852 0.047894 -0.000002 +0.998852 0.047894 -0.000002 +0.998852 0.047894 -0.000002 +0.998852 0.047894 -0.000002 +0.998852 0.047894 -0.000002 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.998852 -0.047894 0.000000 +-0.998852 -0.047894 0.000000 +-0.998852 -0.047894 0.000000 +-0.998852 -0.047894 0.000000 +-0.998852 -0.047894 0.000000 +-0.998852 -0.047894 0.000000 +-0.047897 0.998852 -0.000005 +-0.047897 0.998852 -0.000005 +-0.047897 0.998852 -0.000005 +-0.047897 0.998852 -0.000005 +-0.047897 0.998852 -0.000005 +-0.047897 0.998852 -0.000005 +0.076038 -0.997105 -0.000003 +0.076038 -0.997105 -0.000003 +0.076038 -0.997105 -0.000003 +0.076038 -0.997105 -0.000003 +0.076038 -0.997105 -0.000003 +0.076038 -0.997105 -0.000003 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.997105 0.076034 0.000000 +0.997105 0.076034 0.000000 +0.997105 0.076034 0.000000 +0.997105 0.076034 0.000000 +0.997105 0.076034 0.000000 +0.997105 0.076034 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.997105 -0.076035 0.000000 +-0.997105 -0.076035 0.000000 +-0.997105 -0.076035 0.000000 +-0.997105 -0.076035 0.000000 +-0.997105 -0.076035 0.000000 +-0.997105 -0.076035 0.000000 +-0.076039 0.997105 0.000000 +-0.076039 0.997105 0.000000 +-0.076039 0.997105 0.000000 +-0.076039 0.997105 0.000000 +-0.076039 0.997105 0.000000 +-0.076039 0.997105 0.000000 +0.076038 -0.997105 -0.000003 +0.076038 -0.997105 -0.000003 +0.076038 -0.997105 -0.000003 +0.076038 -0.997105 -0.000003 +0.076038 -0.997105 -0.000003 +0.076038 -0.997105 -0.000003 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.997105 0.076034 0.000000 +0.997105 0.076034 0.000000 +0.997105 0.076034 0.000000 +0.997105 0.076034 0.000000 +0.997105 0.076034 0.000000 +0.997105 0.076034 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.997105 -0.076035 0.000000 +-0.997105 -0.076035 0.000000 +-0.997105 -0.076035 0.000000 +-0.997105 -0.076035 0.000000 +-0.997105 -0.076035 0.000000 +-0.997105 -0.076035 0.000000 +-0.076039 0.997105 0.000000 +-0.076039 0.997105 0.000000 +-0.076039 0.997105 0.000000 +-0.076039 0.997105 0.000000 +-0.076039 0.997105 0.000000 +-0.076039 0.997105 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000004 -1.000000 0.000000 +0.000004 -1.000000 0.000000 +0.000004 -1.000000 0.000000 +0.000004 -1.000000 0.000000 +0.000004 -1.000000 0.000000 +0.000004 -1.000000 0.000000 +1.000000 0.000001 0.000000 +1.000000 0.000001 0.000000 +1.000000 0.000001 0.000000 +1.000000 0.000001 0.000000 +1.000000 0.000001 0.000000 +1.000000 0.000001 0.000000 +-0.000004 1.000000 0.000000 +-0.000004 1.000000 0.000000 +-0.000004 1.000000 0.000000 +-0.000004 1.000000 0.000000 +-0.000004 1.000000 0.000000 +-0.000004 1.000000 0.000000 +-1.000000 -0.000001 0.000000 +-1.000000 -0.000001 0.000000 +-1.000000 -0.000001 0.000000 +-1.000000 -0.000001 0.000000 +-1.000000 -0.000001 0.000000 +-1.000000 -0.000001 0.000000 + + + + + + + + + + + +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.505546 0.409621 +0.027038 0.424800 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.506996 0.036168 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.029544 0.035380 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.037422 0.971548 +0.039211 0.698717 +0.407335 0.698761 +0.409054 0.971742 +0.029544 0.043430 +0.570344 0.705031 +0.922325 0.705031 +0.570343 0.962377 +0.914572 0.962378 +0.238676 0.206126 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.691973 +0.217975 0.210005 +0.854670 0.918158 +0.150794 0.918158 +0.078207 0.207809 +0.288362 0.210005 +0.288362 0.695852 +0.854670 0.988546 +0.150794 0.988545 +0.010469 0.693656 +0.010469 0.207809 +0.171204 0.205139 +0.875080 0.205139 +0.875080 0.275526 +0.171204 0.275526 +0.147588 0.210005 +0.854670 0.847771 +0.150794 0.847770 +0.148885 0.207809 +0.854670 0.706996 +0.217975 0.695852 +0.078207 0.693656 +0.150794 0.706996 +0.875080 0.345913 +0.171204 0.345913 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.756345 0.522332 +0.756346 0.715841 +0.016244 0.715841 +0.016243 0.522332 +0.009526 0.514494 +0.009526 0.061000 +0.749636 0.060999 +0.749637 0.514493 +0.771396 0.480706 +0.969477 0.480355 +0.969577 0.938728 +0.771464 0.938319 +0.751630 0.039423 +0.751630 0.498972 +0.007192 0.498972 +0.007192 0.039423 +0.977311 0.498670 +0.779207 0.499082 +0.779286 0.040707 +0.977371 0.041060 +0.016243 0.718111 +0.756344 0.718111 +0.756344 0.911620 +0.016243 0.911620 +0.756345 0.522332 +0.756346 0.715841 +0.016244 0.715841 +0.016243 0.522332 +0.009526 0.514494 +0.009526 0.061000 +0.749636 0.060999 +0.749637 0.514493 +0.771396 0.480706 +0.969477 0.480355 +0.969577 0.938728 +0.771464 0.938319 +0.751630 0.039423 +0.751630 0.498972 +0.007192 0.498972 +0.007192 0.039423 +0.977311 0.498670 +0.779207 0.499082 +0.779286 0.040707 +0.977371 0.041060 +0.016243 0.718111 +0.756344 0.718111 +0.756344 0.911620 +0.016243 0.911620 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.756345 0.522332 +0.756346 0.715841 +0.016244 0.715841 +0.016243 0.522332 +0.009526 0.514494 +0.009526 0.061000 +0.749636 0.060999 +0.749637 0.514493 +0.771396 0.480706 +0.969477 0.480355 +0.969577 0.938728 +0.771464 0.938319 +0.751630 0.039423 +0.751630 0.498972 +0.007192 0.498972 +0.007192 0.039423 +0.977311 0.498670 +0.779207 0.499082 +0.779286 0.040707 +0.977371 0.041060 +0.016243 0.718111 +0.756344 0.718111 +0.756344 0.911620 +0.016243 0.911620 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.077201 0.210005 +0.854670 0.777384 +0.150794 0.777383 +0.219564 0.207809 +0.147588 0.695852 +0.148885 0.693656 +0.875080 0.416300 +0.171204 0.416300 +0.944549 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.240673 0.206126 +0.077201 0.695852 +0.219564 0.693656 +0.875080 0.486687 +0.171204 0.486687 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035379 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035381 +0.029544 0.035381 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035380 +0.029544 0.035381 +0.006814 0.210005 +0.006814 0.695852 +0.287302 0.693656 +0.287302 0.207809 + + + + + + + + + + + +

6 0 6 7 1 7 5 2 5 7 3 7 4 4 4 5 5 5 0 6 8 5 7 10 4 8 11 5 9 10 0 10 8 3 11 9 6 12 15 8 13 20 7 14 14 8 15 20 1 16 13 7 17 14 1 18 13 8 19 20 2 20 12 2 21 12 8 22 20 3 23 566 7 24 19 1 25 16 4 26 18 1 27 16 0 28 17 4 29 18 1 30 1 2 31 2 0 32 0 2 33 2 3 34 3 0 35 0 6 36 23 5 37 21 8 38 24 8 39 24 5 40 21 3 41 22 14 42 54 15 43 55 13 44 53 15 45 55 16 46 56 13 47 53 18 48 60 17 49 57 16 50 59 16 51 59 17 52 57 13 53 58 14 54 63 20 55 64 15 56 62 20 57 64 19 58 61 15 59 62 19 60 61 20 61 64 21 62 65 21 63 65 20 64 64 17 65 567 15 66 67 19 67 68 16 68 66 19 69 68 18 70 69 16 71 66 19 72 72 21 73 73 18 74 71 21 75 73 17 76 70 18 77 71 14 78 75 13 79 76 20 80 74 20 81 74 13 82 76 17 83 77 23 84 79 24 85 80 22 86 78 24 87 80 25 88 81 22 89 78 27 90 85 26 91 82 25 92 84 25 93 84 26 94 82 22 95 83 23 96 88 29 97 89 24 98 87 29 99 89 28 100 86 24 101 87 28 102 86 29 103 89 30 104 90 29 105 89 26 106 568 30 107 90 24 108 92 28 109 93 25 110 91 28 111 93 27 112 94 25 113 91 30 114 98 26 115 95 28 116 97 28 117 97 26 118 95 27 119 96 23 120 100 22 121 101 29 122 99 29 123 99 22 124 101 26 125 102 32 126 104 33 127 105 31 128 103 33 129 105 34 130 106 31 131 103 36 132 110 35 133 107 34 134 109 34 135 109 35 136 107 31 137 108 32 138 113 38 139 114 33 140 112 38 141 114 37 142 111 33 143 112 37 144 111 38 145 114 39 146 115 39 147 115 38 148 114 35 149 569 33 150 117 37 151 118 34 152 116 37 153 118 36 154 119 34 155 116 35 156 120 37 157 122 39 158 123 37 159 122 35 160 120 36 161 121 32 162 125 31 163 126 38 164 124 38 165 124 31 166 126 35 167 127 41 168 129 42 169 130 40 170 128 42 171 130 43 172 131 40 173 128 45 174 135 44 175 132 43 176 134 43 177 134 44 178 132 40 179 133 41 180 138 47 181 139 42 182 137 47 183 139 46 184 136 42 185 137 46 186 136 47 187 139 48 188 140 48 189 140 47 190 139 44 191 570 42 192 142 46 193 143 43 194 141 46 195 143 45 196 144 43 197 141 48 198 148 44 199 145 46 200 147 46 201 147 44 202 145 45 203 146 41 204 150 40 205 151 47 206 149 47 207 149 40 208 151 44 209 152 50 210 154 51 211 155 49 212 153 51 213 155 52 214 156 49 215 153 52 216 159 53 217 157 49 218 158 53 219 157 52 220 159 54 221 160 55 222 161 56 223 164 53 224 571 56 225 164 55 226 161 51 227 162 56 228 164 51 229 162 50 230 163 51 231 167 55 232 168 52 233 166 55 234 168 54 235 169 52 236 166 57 237 173 53 238 170 55 239 172 55 240 172 53 241 170 54 242 171 50 243 175 49 244 176 56 245 174 56 246 174 49 247 176 53 248 177 59 249 179 60 250 180 58 251 178 60 252 180 61 253 181 58 254 178 63 255 185 62 256 182 61 257 184 61 258 184 62 259 182 58 260 183 59 261 188 65 262 189 60 263 187 65 264 189 64 265 186 60 266 187 64 267 186 65 268 189 66 269 190 66 270 190 65 271 189 62 272 572 60 273 192 64 274 193 61 275 191 64 276 193 63 277 194 61 278 191 66 279 198 62 280 195 64 281 197 64 282 197 62 283 195 63 284 196 59 285 200 58 286 201 65 287 199 65 288 199 58 289 201 62 290 202 68 291 204 69 292 205 67 293 203 69 294 205 70 295 206 67 296 203 67 297 208 70 298 209 71 299 207 70 300 209 72 301 210 71 302 207 73 303 211 71 304 573 75 305 215 73 306 211 74 307 214 71 308 573 74 309 214 73 310 211 69 311 212 74 312 214 69 313 212 68 314 213 69 315 217 73 316 218 70 317 216 73 318 218 72 319 219 70 320 216 71 321 220 73 322 222 75 323 223 73 324 222 71 325 220 72 326 221 68 327 225 67 328 226 74 329 224 74 330 224 67 331 226 71 332 227 93 333 277 94 334 278 92 335 276 94 336 278 95 337 279 92 338 276 92 339 281 95 340 282 96 341 280 96 342 280 95 343 282 97 344 283 98 345 284 94 346 285 99 347 287 94 348 285 93 349 286 99 350 287 100 351 288 98 352 284 96 353 574 99 354 287 96 355 574 98 356 284 94 357 290 98 358 291 95 359 289 98 360 291 97 361 292 95 362 289 100 363 296 96 364 293 98 365 295 98 366 295 96 367 293 97 368 294 93 369 298 92 370 299 99 371 297 99 372 297 92 373 299 96 374 300 102 375 302 103 376 303 101 377 301 103 378 303 104 379 304 101 380 301 101 381 306 104 382 307 105 383 305 104 384 307 106 385 308 105 386 305 107 387 309 108 388 312 105 389 575 108 390 312 107 391 309 103 392 310 108 393 312 103 394 310 102 395 311 103 396 315 107 397 316 106 398 317 103 399 315 106 400 317 104 401 314 109 402 321 105 403 318 107 404 320 107 405 320 105 406 318 106 407 319 102 408 323 101 409 324 108 410 322 108 411 322 101 412 324 105 413 325 111 414 327 112 415 328 110 416 326 112 417 328 113 418 329 110 419 326 110 420 331 113 421 332 114 422 330 114 423 330 113 424 332 115 425 333 116 426 334 112 427 335 117 428 337 112 429 335 111 430 336 117 431 337 117 432 337 114 433 576 116 434 334 112 435 340 116 436 341 113 437 339 116 438 341 115 439 342 113 440 339 118 441 346 114 442 343 116 443 345 116 444 345 114 445 343 115 446 344 111 447 348 110 448 349 117 449 347 117 450 347 110 451 349 114 452 350 120 453 352 121 454 353 119 455 351 121 456 353 122 457 354 119 458 351 122 459 357 123 460 355 119 461 356 123 462 355 122 463 357 124 464 358 125 465 359 126 466 362 123 467 577 126 468 362 125 469 359 121 470 360 126 471 362 121 472 360 120 473 361 121 474 365 125 475 366 124 476 367 121 477 365 124 478 367 122 479 364 127 480 371 123 481 368 125 482 370 125 483 370 123 484 368 124 485 369 120 486 373 119 487 374 126 488 372 126 489 372 119 490 374 123 491 375 129 492 377 130 493 378 128 494 376 130 495 378 131 496 379 128 497 376 128 498 381 131 499 382 132 500 380 132 501 380 131 502 382 133 503 383 134 504 384 130 505 385 135 506 387 130 507 385 129 508 386 135 509 387 135 510 387 132 511 578 134 512 384 130 513 390 134 514 391 131 515 389 134 516 391 133 517 392 131 518 389 132 519 393 134 520 395 136 521 396 134 522 395 132 523 393 133 524 394 129 525 398 128 526 399 135 527 397 135 528 397 128 529 399 132 530 400 138 531 402 139 532 403 137 533 401 139 534 403 140 535 404 137 536 401 140 537 407 141 538 405 137 539 406 141 540 405 140 541 407 142 542 408 143 543 409 144 544 412 141 545 579 144 546 412 143 547 409 139 548 410 144 549 412 139 550 410 138 551 411 139 552 415 143 553 416 142 554 417 139 555 415 142 556 417 140 557 414 145 558 421 141 559 418 143 560 420 143 561 420 141 562 418 142 563 419 138 564 423 137 565 424 144 566 422 144 567 422 137 568 424 141 569 425 147 570 427 148 571 428 146 572 426 148 573 428 149 574 429 146 575 426 151 576 433 150 577 430 149 578 432 150 579 430 146 580 431 149 581 432 153 582 437 148 583 435 147 584 436 148 585 435 153 586 437 152 587 434 152 588 434 153 589 437 154 590 438 154 591 438 153 592 437 150 593 580 148 594 440 152 595 441 149 596 439 152 597 441 151 598 442 149 599 439 150 600 443 152 601 445 154 602 446 152 603 445 150 604 443 151 605 444 147 606 448 146 607 449 153 608 447 153 609 447 146 610 449 150 611 450 156 612 452 157 613 453 155 614 451 157 615 453 158 616 454 155 617 451 155 618 456 160 619 458 159 620 455 160 621 458 155 622 456 158 623 457 161 624 459 162 625 462 159 626 581 162 627 462 161 628 459 157 629 460 162 630 462 157 631 460 156 632 461 157 633 465 161 634 466 160 635 467 157 636 465 160 637 467 158 638 464 163 639 471 159 640 468 161 641 470 161 642 470 159 643 468 160 644 469 156 645 473 155 646 474 162 647 472 162 648 472 155 649 474 159 650 475 165 651 477 166 652 478 164 653 476 166 654 478 167 655 479 164 656 476 164 657 481 167 658 482 168 659 480 168 660 480 167 661 482 169 662 483 170 663 484 166 664 485 171 665 487 166 666 485 165 667 486 171 668 487 171 669 487 168 670 582 170 671 484 166 672 490 170 673 491 167 674 489 170 675 491 169 676 492 167 677 489 168 678 493 170 679 495 172 680 496 170 681 495 168 682 493 169 683 494 165 684 498 164 685 499 171 686 497 171 687 497 164 688 499 168 689 500 182 690 526 183 691 527 181 692 525 183 693 527 184 694 528 181 695 525 181 696 530 186 697 532 185 698 529 186 699 532 181 700 530 184 701 531 187 702 533 183 703 534 188 704 536 183 705 534 182 706 535 188 707 536 189 708 537 187 709 533 185 710 583 188 711 536 185 712 583 187 713 533 183 714 539 187 715 540 184 716 538 187 717 540 186 718 541 184 719 538 189 720 545 185 721 542 187 722 544 187 723 544 185 724 542 186 725 543 182 726 547 181 727 548 188 728 546 188 729 546 181 730 548 185 731 549

+

79 732 231 76 733 228 78 734 230 77 735 229 78 736 230 76 737 228 76 738 233 79 739 234 81 740 235 76 741 233 81 742 235 80 743 232 82 744 237 77 745 238 76 746 239 82 747 237 76 748 239 80 749 236 83 750 240 77 751 242 82 752 243 77 753 242 83 754 240 78 755 241 81 756 247 78 757 245 83 758 246 78 759 245 81 760 247 79 761 244 83 762 250 82 763 251 80 764 248 83 765 250 80 766 248 81 767 249 87 768 255 84 769 252 86 770 254 85 771 253 86 772 254 84 773 252 84 774 257 87 775 258 89 776 259 84 777 257 89 778 259 88 779 256 90 780 261 85 781 262 84 782 263 90 783 261 84 784 263 88 785 260 91 786 264 85 787 266 90 788 267 85 789 266 91 790 264 86 791 265 86 792 269 91 793 270 89 794 271 86 795 269 89 796 271 87 797 268 88 798 272 89 799 273 90 800 275 91 801 274 90 802 275 89 803 273 176 804 504 173 805 501 175 806 503 174 807 502 175 808 503 173 809 501 173 810 506 176 811 507 178 812 508 173 813 506 178 814 508 177 815 505 179 816 510 174 817 511 173 818 512 179 819 510 173 820 512 177 821 509 180 822 513 174 823 515 179 824 516 174 825 515 180 826 513 175 827 514 175 828 518 180 829 519 178 830 520 175 831 518 178 832 520 176 833 517 177 834 521 178 835 522 179 836 524 180 837 523 179 838 524 178 839 522

+

9 840 25 10 841 26 12 842 28 12 843 28 10 844 26 11 845 27 192 846 560 193 847 561 191 848 559 193 849 561 190 850 558 191 851 559 191 852 585 190 853 584 9 854 33 191 855 585 9 856 33 12 857 34 192 858 50 191 859 47 12 860 35 192 861 50 12 862 35 11 863 36 193 864 587 192 865 586 11 866 37 193 867 587 11 868 37 10 869 38 190 870 564 193 871 565 10 872 39 190 873 564 10 874 39 9 875 40

+
+
+
+ + + + + + + + + 78.996956 0.000000 0.000000 0.000000 0.000000 78.996956 0.000000 0.000000 0.000000 0.000000 78.996956 0.000000 0.000000 0.000000 0.000000 1.0000001.000000 + 30.0000000.0000003.333333 + + + + + +
diff --git a/simulators/sim_env/models/aws_robomaker_warehouse_ClutteringA_01/model.config b/simulators/sim_env/models/aws_robomaker_warehouse_ClutteringA_01/model.config new file mode 100755 index 0000000..c3bf861 --- /dev/null +++ b/simulators/sim_env/models/aws_robomaker_warehouse_ClutteringA_01/model.config @@ -0,0 +1,11 @@ + + + aws_robomaker_warehouse_ClutteringA_01 + 1.0 + model.sdf + + + + + + diff --git a/simulators/sim_env/models/aws_robomaker_warehouse_ClutteringA_01/model.sdf b/simulators/sim_env/models/aws_robomaker_warehouse_ClutteringA_01/model.sdf new file mode 100755 index 0000000..629f0fc --- /dev/null +++ b/simulators/sim_env/models/aws_robomaker_warehouse_ClutteringA_01/model.sdf @@ -0,0 +1,55 @@ + + + + + + 2 + + 0.841 + 0 + 0 + 0.954 + 0 + 1.422 + + + + + + model://aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + model://aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_visual.DAE + + + 1 + + + 1 + + diff --git a/simulators/sim_env/models/aws_robomaker_warehouse_ClutteringC_01/materials/textures/aws_robomaker_warehouse_ClutteringC_01.png b/simulators/sim_env/models/aws_robomaker_warehouse_ClutteringC_01/materials/textures/aws_robomaker_warehouse_ClutteringC_01.png new file mode 100755 index 0000000..b28b289 Binary files /dev/null and b/simulators/sim_env/models/aws_robomaker_warehouse_ClutteringC_01/materials/textures/aws_robomaker_warehouse_ClutteringC_01.png differ diff --git a/simulators/sim_env/models/aws_robomaker_warehouse_ClutteringC_01/materials/textures/aws_robomaker_warehouse_ClutteringC_02.png b/simulators/sim_env/models/aws_robomaker_warehouse_ClutteringC_01/materials/textures/aws_robomaker_warehouse_ClutteringC_02.png new file mode 100755 index 0000000..4b7e610 Binary files /dev/null and b/simulators/sim_env/models/aws_robomaker_warehouse_ClutteringC_01/materials/textures/aws_robomaker_warehouse_ClutteringC_02.png differ diff --git a/simulators/sim_env/models/aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_collision.DAE b/simulators/sim_env/models/aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_collision.DAE new file mode 100755 index 0000000..4f4fd10 --- /dev/null +++ b/simulators/sim_env/models/aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_collision.DAE @@ -0,0 +1,123 @@ + + + FBX COLLADA exporter2019-03-20T02:46:25Z2019-03-20T02:46:25ZZ_UP + + + + + +-88.666687 -102.994263 3.000000 +88.666687 -102.994263 3.000000 +-88.666687 102.994263 3.000000 +88.666687 102.994263 3.000000 +-88.666687 -102.994263 179.031189 +88.666687 -102.994263 179.031189 +-88.666687 102.994263 179.031189 +88.666687 102.994263 179.031189 + + + + + + + + + + + +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 + + + + + + + + + + + +1.000000 0.000000 +0.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 + + + + + + + + + + + +

1 0 1 0 1 0 3 2 3 0 3 0 2 4 2 3 5 3 7 6 7 6 7 6 4 8 4 7 9 7 4 10 4 5 11 5 5 12 11 4 13 10 0 14 8 5 15 11 0 16 8 1 17 9 7 18 15 5 19 14 1 20 12 7 21 15 1 22 12 3 23 13 6 24 19 7 25 18 3 26 16 6 27 19 3 28 16 2 29 17 4 30 23 6 31 22 2 32 20 4 33 23 2 34 20 0 35 21

+
+
+
+ + + 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.0000001.000000 + 30.0000000.0000003.333333 + + + + + +
diff --git a/simulators/sim_env/models/aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_visual.DAE b/simulators/sim_env/models/aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_visual.DAE new file mode 100755 index 0000000..3507fe5 --- /dev/null +++ b/simulators/sim_env/models/aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_visual.DAE @@ -0,0 +1,2036 @@ + + + FBX COLLADA exporter2019-03-20T02:46:45Z2019-03-20T02:46:45ZZ_UP + + + ../materials/textures/aws_robomaker_warehouse_ClutteringC_01.png + + + + + + + + + + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + +1.067614 0.027155 0.952252 +1.067614 0.027155 1.391078 +1.083528 -0.727958 1.391078 +1.083528 -0.727958 0.952252 +0.467549 0.014509 0.952252 +0.483463 -0.740604 0.952252 +0.483463 -0.740604 1.391078 +0.480766 0.014787 1.391078 +0.467550 0.014509 1.391078 +-0.148068 -0.777457 0.043760 +-0.148068 -0.777457 0.482586 +-1.047329 -0.790820 0.482586 +-1.047329 -0.790820 0.043760 +-0.163129 -0.273580 0.043760 +-1.062389 -0.286942 0.043760 +-1.062389 -0.286943 0.482586 +-0.162797 -0.284678 0.482586 +-0.163129 -0.273580 0.482586 +-0.148068 -0.777457 0.496737 +-0.148068 -0.777457 0.935563 +-1.047329 -0.790820 0.935563 +-1.047329 -0.790820 0.496737 +-0.163129 -0.273580 0.496737 +-1.062389 -0.286942 0.496737 +-1.062389 -0.286943 0.935563 +-0.162797 -0.284678 0.935563 +-0.163129 -0.273580 0.935563 +-0.148068 -0.777457 0.952252 +-0.148068 -0.777457 1.391078 +-1.047329 -0.790820 1.391078 +-1.047329 -0.790820 0.952252 +-0.163129 -0.273580 0.952252 +-1.062389 -0.286942 0.952252 +-1.062389 -0.286943 1.391078 +-0.162797 -0.284678 1.391078 +-0.163129 -0.273580 1.391078 +-0.158738 -0.264175 0.043760 +-0.158738 -0.264175 0.482586 +-1.057999 -0.277538 0.482586 +-1.057999 -0.277538 0.043760 +-0.173799 0.239702 0.043760 +-1.073059 0.226339 0.043760 +-1.073059 0.226339 0.482586 +-0.173467 0.228604 0.482586 +-0.173799 0.239702 0.482586 +-0.158738 -0.264175 0.496737 +-0.158738 -0.264175 0.935563 +-1.057999 -0.277538 0.935563 +-1.057999 -0.277538 0.496737 +-0.173799 0.239702 0.496737 +-1.073059 0.226339 0.496737 +-1.073059 0.226339 0.935563 +-0.173467 0.228604 0.935563 +-0.173799 0.239702 0.935563 +-0.158738 -0.264175 0.952252 +-0.158738 -0.264175 1.391078 +-1.057999 -0.277538 1.391078 +-1.057999 -0.277538 0.952252 +-0.173799 0.239702 0.952252 +-1.073059 0.226339 0.952252 +-1.073059 0.226339 1.391078 +-0.173467 0.228604 1.391078 +-0.173799 0.239702 1.391078 +-0.154016 -0.491365 1.405229 +-0.154016 -0.491365 1.844055 +-1.053276 -0.504728 1.844055 +-1.053276 -0.504728 1.405229 +-0.169076 0.012512 1.405229 +-1.068336 -0.000851 1.405229 +-1.068336 -0.000851 1.844055 +-0.168745 0.001414 1.844055 +-0.169076 0.012512 1.844055 +1.067615 0.027155 0.043760 +1.067615 0.027155 0.482586 +1.083529 -0.727958 0.482586 +1.083529 -0.727958 0.043760 +0.467550 0.014509 0.043760 +0.483464 -0.740604 0.043760 +0.483464 -0.740604 0.482586 +0.480767 0.014787 0.482586 +0.467551 0.014509 0.482586 +1.067615 0.027155 0.496737 +1.067615 0.027155 0.935563 +1.083529 -0.727958 0.935563 +1.083529 -0.727958 0.496737 +0.467550 0.014509 0.496737 +0.483464 -0.740604 0.496737 +0.483464 -0.740604 0.935563 +0.480767 0.014787 0.935563 +0.467551 0.014509 0.935563 +0.456349 0.018195 0.043760 +0.456349 0.018195 0.482586 +0.472263 -0.736918 0.482586 +0.472263 -0.736918 0.043760 +-0.143716 0.005549 0.043760 +-0.127802 -0.749564 0.043760 +-0.127802 -0.749564 0.482586 +-0.130499 0.005827 0.482586 +-0.143715 0.005549 0.482586 +0.456349 0.018195 0.496737 +0.456349 0.018195 0.935563 +0.472263 -0.736918 0.935563 +0.472263 -0.736918 0.496737 +-0.143716 0.005549 0.496737 +-0.127802 -0.749564 0.496737 +-0.127802 -0.749564 0.935563 +-0.130499 0.005827 0.935563 +-0.143715 0.005549 0.935563 +0.456349 0.018195 0.952252 +0.456349 0.018195 1.391078 +0.472263 -0.736918 1.391078 +0.472263 -0.736918 0.952252 +-0.143716 0.005549 0.952252 +-0.127802 -0.749564 0.952252 +-0.127802 -0.749564 1.391078 +-0.130499 0.005827 1.391078 +-0.143715 0.005549 1.391078 +0.890204 -0.520833 1.405229 +0.890204 -0.520833 1.844055 +-0.009057 -0.534196 1.844055 +-0.009057 -0.534196 1.405229 +0.875143 -0.016957 1.405229 +-0.024117 -0.030319 1.405229 +-0.024117 -0.030320 1.844055 +0.875475 -0.028055 1.844055 +0.875143 -0.016957 1.844055 +1.051741 0.790819 0.043760 +1.051741 0.790819 0.482586 +1.067655 0.035707 0.482586 +1.067655 0.035707 0.043760 +0.451676 0.778173 0.043760 +0.467589 0.023060 0.043760 +0.467590 0.023060 0.482586 +0.464892 0.778451 0.482586 +0.451676 0.778173 0.482586 +1.051741 0.790819 0.496737 +1.051741 0.790819 0.935563 +1.067655 0.035707 0.935563 +1.067655 0.035707 0.496737 +0.451676 0.778173 0.496737 +0.467589 0.023060 0.496737 +0.467590 0.023060 0.935563 +0.464892 0.778451 0.935563 +0.451676 0.778173 0.935563 +1.051741 0.790819 0.952252 +1.051741 0.790819 1.391078 +1.067655 0.035707 1.391078 +1.067655 0.035707 0.952252 +0.451676 0.778173 0.952252 +0.467589 0.023060 0.952252 +0.467590 0.023060 1.391078 +0.464892 0.778451 1.391078 +0.451676 0.778173 1.391078 +0.440475 0.781860 0.043760 +0.440475 0.781860 0.482586 +0.456388 0.026747 0.482586 +0.456388 0.026747 0.043760 +-0.159590 0.769213 0.043760 +-0.143677 0.014100 0.043760 +-0.143676 0.014100 0.482586 +-0.146374 0.769491 0.482586 +-0.159590 0.769213 0.482586 +0.440475 0.781860 0.496737 +0.440475 0.781860 0.935563 +0.456388 0.026747 0.935563 +0.456388 0.026747 0.496737 +-0.159590 0.769213 0.496737 +-0.143677 0.014100 0.496737 +-0.143676 0.014100 0.935563 +-0.146374 0.769491 0.935563 +-0.159590 0.769213 0.935563 +0.440475 0.781860 0.952252 +0.440475 0.781860 1.391078 +0.456388 0.026747 1.391078 +0.456388 0.026747 0.952252 +-0.159590 0.769213 0.952252 +-0.143677 0.014100 0.952252 +-0.143676 0.014100 1.391078 +-0.146374 0.769491 1.391078 +-0.159590 0.769213 1.391078 +0.279776 0.779504 1.405229 +0.279776 0.779504 1.844055 +0.295690 0.024391 1.844055 +0.295690 0.024391 1.405229 +-0.320289 0.766858 1.405229 +-0.304376 0.011744 1.405229 +-0.304375 0.011744 1.844055 +-0.307073 0.767136 1.844055 +-0.320289 0.766858 1.844055 +-0.169208 0.239461 0.043760 +-0.169208 0.239461 0.482586 +-1.068468 0.226099 0.482586 +-1.068468 0.226099 0.043760 +-0.184268 0.743338 0.043760 +-1.083529 0.729976 0.043760 +-1.083529 0.729975 0.482586 +-0.183937 0.732240 0.482586 +-0.184268 0.743338 0.482586 +-0.169208 0.239461 0.496737 +-0.169208 0.239461 0.935563 +-1.068468 0.226099 0.935563 +-1.068468 0.226099 0.496737 +-0.184268 0.743338 0.496737 +-1.083529 0.729976 0.496737 +-1.083529 0.729975 0.935563 +-0.183937 0.732240 0.935563 +-0.184268 0.743338 0.935563 +-0.169208 0.239461 0.952252 +-0.169208 0.239461 1.391078 +-1.068468 0.226099 1.391078 +-1.068468 0.226099 0.952252 +-0.184268 0.743338 0.952252 +-1.083529 0.729976 0.952252 +-1.083529 0.729975 1.391078 +-0.183937 0.732240 1.391078 +-0.184268 0.743338 1.391078 + + + + + + + + + + + +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +0.021070 -0.999778 -0.000000 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +0.999554 0.029877 -0.000000 +0.999554 0.029877 -0.000000 +0.999554 0.029877 -0.000000 +0.999554 0.029877 -0.000000 +0.999554 0.029877 -0.000000 +0.999554 0.029877 -0.000000 +0.999554 0.029877 -0.000000 +0.999554 0.029877 -0.000000 +0.999554 0.029877 -0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.999778 0.021070 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +0.021071 -0.999778 -0.000000 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.999778 -0.021070 0.000001 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +-0.021070 0.999778 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 + + + + + + + + + + + +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 + + + + + + + + + + + +

2 0 2 0 1 0 1 2 1 0 3 0 2 4 2 3 5 3 3 6 6 4 7 4 0 8 5 4 9 4 3 10 6 5 11 7 7 12 11 2 13 9 1 14 10 2 15 9 7 16 11 6 17 8 8 18 12 6 19 8 7 20 11 6 21 15 3 22 13 2 23 14 3 24 13 6 25 15 5 26 16 6 27 19 8 28 20 4 29 17 6 30 19 4 31 17 5 32 18 7 33 22 4 34 25 8 35 21 4 36 25 7 37 22 0 38 24 7 39 22 1 40 23 0 41 24 11 42 28 9 43 26 10 44 27 9 45 26 11 46 28 12 47 29 12 48 32 13 49 30 9 50 31 13 51 30 12 52 32 14 53 33 15 54 34 16 55 37 17 56 38 11 57 35 16 58 37 15 59 34 16 60 37 11 61 35 10 62 36 15 63 41 12 64 39 11 65 40 12 66 39 15 67 41 14 68 42 15 69 45 17 70 46 13 71 43 15 72 45 13 73 43 14 74 44 16 75 48 13 76 51 17 77 47 13 78 51 16 79 48 9 80 50 16 81 48 10 82 49 9 83 50 20 84 54 18 85 52 19 86 53 18 87 52 20 88 54 21 89 55 21 90 58 22 91 56 18 92 57 22 93 56 21 94 58 23 95 59 24 96 60 25 97 63 26 98 64 20 99 61 25 100 63 24 101 60 25 102 63 20 103 61 19 104 62 24 105 67 21 106 65 20 107 66 21 108 65 24 109 67 23 110 68 24 111 71 26 112 72 22 113 69 24 114 71 22 115 69 23 116 70 25 117 74 22 118 77 26 119 73 22 120 77 25 121 74 18 122 76 25 123 74 19 124 75 18 125 76 29 126 80 27 127 78 28 128 79 27 129 78 29 130 80 30 131 81 30 132 84 31 133 82 27 134 83 31 135 82 30 136 84 32 137 85 33 138 86 34 139 89 35 140 90 29 141 87 34 142 89 33 143 86 34 144 89 29 145 87 28 146 88 33 147 93 30 148 91 29 149 92 30 150 91 33 151 93 32 152 94 33 153 97 35 154 98 31 155 95 33 156 97 31 157 95 32 158 96 34 159 100 31 160 103 35 161 99 31 162 103 34 163 100 27 164 102 34 165 100 28 166 101 27 167 102 38 168 106 36 169 104 37 170 105 36 171 104 38 172 106 39 173 107 39 174 110 40 175 108 36 176 109 40 177 108 39 178 110 41 179 111 42 180 112 43 181 115 44 182 116 38 183 113 43 184 115 42 185 112 43 186 115 38 187 113 37 188 114 42 189 119 39 190 117 38 191 118 39 192 117 42 193 119 41 194 120 42 195 123 44 196 124 40 197 121 42 198 123 40 199 121 41 200 122 43 201 126 40 202 129 44 203 125 40 204 129 43 205 126 36 206 128 43 207 126 37 208 127 36 209 128 47 210 132 45 211 130 46 212 131 45 213 130 47 214 132 48 215 133 48 216 136 49 217 134 45 218 135 49 219 134 48 220 136 50 221 137 51 222 138 52 223 141 53 224 142 47 225 139 52 226 141 51 227 138 52 228 141 47 229 139 46 230 140 51 231 145 48 232 143 47 233 144 48 234 143 51 235 145 50 236 146 51 237 149 53 238 150 49 239 147 51 240 149 49 241 147 50 242 148 52 243 152 49 244 155 53 245 151 49 246 155 52 247 152 45 248 154 52 249 152 46 250 153 45 251 154 56 252 158 54 253 156 55 254 157 54 255 156 56 256 158 57 257 159 57 258 162 58 259 160 54 260 161 58 261 160 57 262 162 59 263 163 60 264 164 61 265 167 62 266 168 56 267 165 61 268 167 60 269 164 61 270 167 56 271 165 55 272 166 60 273 171 57 274 169 56 275 170 57 276 169 60 277 171 59 278 172 60 279 175 62 280 176 58 281 173 60 282 175 58 283 173 59 284 174 61 285 178 58 286 181 62 287 177 58 288 181 61 289 178 54 290 180 61 291 178 55 292 179 54 293 180 65 294 184 63 295 182 64 296 183 63 297 182 65 298 184 66 299 185 66 300 188 67 301 186 63 302 187 67 303 186 66 304 188 68 305 189 69 306 190 70 307 193 71 308 194 65 309 191 70 310 193 69 311 190 70 312 193 65 313 191 64 314 192 69 315 197 66 316 195 65 317 196 66 318 195 69 319 197 68 320 198 69 321 201 71 322 202 67 323 199 69 324 201 67 325 199 68 326 200 70 327 204 67 328 207 71 329 203 67 330 207 70 331 204 63 332 206 70 333 204 64 334 205 63 335 206 74 336 210 72 337 208 73 338 209 72 339 208 74 340 210 75 341 211 75 342 214 76 343 212 72 344 213 76 345 212 75 346 214 77 347 215 79 348 219 74 349 217 73 350 218 74 351 217 79 352 219 78 353 216 80 354 220 78 355 216 79 356 219 78 357 223 75 358 221 74 359 222 75 360 221 78 361 223 77 362 224 78 363 227 80 364 228 76 365 225 78 366 227 76 367 225 77 368 226 79 369 230 76 370 233 80 371 229 76 372 233 79 373 230 72 374 232 79 375 230 73 376 231 72 377 232 83 378 236 81 379 234 82 380 235 81 381 234 83 382 236 84 383 237 84 384 240 85 385 238 81 386 239 85 387 238 84 388 240 86 389 241 88 390 245 83 391 243 82 392 244 83 393 243 88 394 245 87 395 242 89 396 246 87 397 242 88 398 245 87 399 249 84 400 247 83 401 248 84 402 247 87 403 249 86 404 250 87 405 253 89 406 254 85 407 251 87 408 253 85 409 251 86 410 252 88 411 256 85 412 259 89 413 255 85 414 259 88 415 256 81 416 258 88 417 256 82 418 257 81 419 258 92 420 262 90 421 260 91 422 261 90 423 260 92 424 262 93 425 263 93 426 266 94 427 264 90 428 265 94 429 264 93 430 266 95 431 267 97 432 271 92 433 269 91 434 270 92 435 269 97 436 271 96 437 268 98 438 272 96 439 268 97 440 271 96 441 275 93 442 273 92 443 274 93 444 273 96 445 275 95 446 276 96 447 279 98 448 280 94 449 277 96 450 279 94 451 277 95 452 278 97 453 282 94 454 285 98 455 281 94 456 285 97 457 282 90 458 284 97 459 282 91 460 283 90 461 284 101 462 288 99 463 286 100 464 287 99 465 286 101 466 288 102 467 289 102 468 292 103 469 290 99 470 291 103 471 290 102 472 292 104 473 293 106 474 297 101 475 295 100 476 296 101 477 295 106 478 297 105 479 294 107 480 298 105 481 294 106 482 297 105 483 301 102 484 299 101 485 300 102 486 299 105 487 301 104 488 302 105 489 305 107 490 306 103 491 303 105 492 305 103 493 303 104 494 304 106 495 308 103 496 311 107 497 307 103 498 311 106 499 308 99 500 310 106 501 308 100 502 309 99 503 310 110 504 314 108 505 312 109 506 313 108 507 312 110 508 314 111 509 315 111 510 318 112 511 316 108 512 317 112 513 316 111 514 318 113 515 319 115 516 323 110 517 321 109 518 322 110 519 321 115 520 323 114 521 320 116 522 324 114 523 320 115 524 323 114 525 327 111 526 325 110 527 326 111 528 325 114 529 327 113 530 328 114 531 331 116 532 332 112 533 329 114 534 331 112 535 329 113 536 330 115 537 334 112 538 337 116 539 333 112 540 337 115 541 334 108 542 336 115 543 334 109 544 335 108 545 336 119 546 340 117 547 338 118 548 339 117 549 338 119 550 340 120 551 341 120 552 344 121 553 342 117 554 343 121 555 342 120 556 344 122 557 345 123 558 346 124 559 349 125 560 350 119 561 347 124 562 349 123 563 346 124 564 349 119 565 347 118 566 348 123 567 353 120 568 351 119 569 352 120 570 351 123 571 353 122 572 354 123 573 357 125 574 358 121 575 355 123 576 357 121 577 355 122 578 356 124 579 360 121 580 363 125 581 359 121 582 363 124 583 360 117 584 362 124 585 360 118 586 361 117 587 362 128 588 366 126 589 364 127 590 365 126 591 364 128 592 366 129 593 367 129 594 370 130 595 368 126 596 369 130 597 368 129 598 370 131 599 371 133 600 375 128 601 373 127 602 374 128 603 373 133 604 375 132 605 372 134 606 376 132 607 372 133 608 375 132 609 379 129 610 377 128 611 378 129 612 377 132 613 379 131 614 380 132 615 383 134 616 384 130 617 381 132 618 383 130 619 381 131 620 382 133 621 386 130 622 389 134 623 385 130 624 389 133 625 386 126 626 388 133 627 386 127 628 387 126 629 388 137 630 392 135 631 390 136 632 391 135 633 390 137 634 392 138 635 393 138 636 396 139 637 394 135 638 395 139 639 394 138 640 396 140 641 397 142 642 401 137 643 399 136 644 400 137 645 399 142 646 401 141 647 398 143 648 402 141 649 398 142 650 401 141 651 405 138 652 403 137 653 404 138 654 403 141 655 405 140 656 406 141 657 409 143 658 410 139 659 407 141 660 409 139 661 407 140 662 408 142 663 412 139 664 415 143 665 411 139 666 415 142 667 412 135 668 414 142 669 412 136 670 413 135 671 414 146 672 418 144 673 416 145 674 417 144 675 416 146 676 418 147 677 419 147 678 422 148 679 420 144 680 421 148 681 420 147 682 422 149 683 423 151 684 427 146 685 425 145 686 426 146 687 425 151 688 427 150 689 424 152 690 428 150 691 424 151 692 427 150 693 431 147 694 429 146 695 430 147 696 429 150 697 431 149 698 432 150 699 435 152 700 436 148 701 433 150 702 435 148 703 433 149 704 434 151 705 438 148 706 441 152 707 437 148 708 441 151 709 438 144 710 440 151 711 438 145 712 439 144 713 440 155 714 444 153 715 442 154 716 443 153 717 442 155 718 444 156 719 445 156 720 448 157 721 446 153 722 447 157 723 446 156 724 448 158 725 449 160 726 453 155 727 451 154 728 452 155 729 451 160 730 453 159 731 450 161 732 454 159 733 450 160 734 453 159 735 457 156 736 455 155 737 456 156 738 455 159 739 457 158 740 458 159 741 461 161 742 462 157 743 459 159 744 461 157 745 459 158 746 460 160 747 464 157 748 467 161 749 463 157 750 467 160 751 464 153 752 466 160 753 464 154 754 465 153 755 466 164 756 470 162 757 468 163 758 469 162 759 468 164 760 470 165 761 471 165 762 474 166 763 472 162 764 473 166 765 472 165 766 474 167 767 475 169 768 479 164 769 477 163 770 478 164 771 477 169 772 479 168 773 476 170 774 480 168 775 476 169 776 479 168 777 483 165 778 481 164 779 482 165 780 481 168 781 483 167 782 484 168 783 487 170 784 488 166 785 485 168 786 487 166 787 485 167 788 486 169 789 490 166 790 493 170 791 489 166 792 493 169 793 490 162 794 492 169 795 490 163 796 491 162 797 492 173 798 496 171 799 494 172 800 495 171 801 494 173 802 496 174 803 497 174 804 500 175 805 498 171 806 499 175 807 498 174 808 500 176 809 501 178 810 505 173 811 503 172 812 504 173 813 503 178 814 505 177 815 502 179 816 506 177 817 502 178 818 505 177 819 509 174 820 507 173 821 508 174 822 507 177 823 509 176 824 510 177 825 513 179 826 514 175 827 511 177 828 513 175 829 511 176 830 512 178 831 516 175 832 519 179 833 515 175 834 519 178 835 516 171 836 518 178 837 516 172 838 517 171 839 518 182 840 522 180 841 520 181 842 521 180 843 520 182 844 522 183 845 523 183 846 526 184 847 524 180 848 525 184 849 524 183 850 526 185 851 527 187 852 531 182 853 529 181 854 530 182 855 529 187 856 531 186 857 528 188 858 532 186 859 528 187 860 531 186 861 535 183 862 533 182 863 534 183 864 533 186 865 535 185 866 536 186 867 539 188 868 540 184 869 537 186 870 539 184 871 537 185 872 538 187 873 542 184 874 545 188 875 541 184 876 545 187 877 542 180 878 544 187 879 542 181 880 543 180 881 544 191 882 548 189 883 546 190 884 547 189 885 546 191 886 548 192 887 549 192 888 552 193 889 550 189 890 551 193 891 550 192 892 552 194 893 553 195 894 554 196 895 557 197 896 558 191 897 555 196 898 557 195 899 554 196 900 557 191 901 555 190 902 556 195 903 561 192 904 559 191 905 560 192 906 559 195 907 561 194 908 562 195 909 565 197 910 566 193 911 563 195 912 565 193 913 563 194 914 564 196 915 568 193 916 571 197 917 567 193 918 571 196 919 568 189 920 570 196 921 568 190 922 569 189 923 570 200 924 574 198 925 572 199 926 573 198 927 572 200 928 574 201 929 575 201 930 578 202 931 576 198 932 577 202 933 576 201 934 578 203 935 579 204 936 580 205 937 583 206 938 584 200 939 581 205 940 583 204 941 580 205 942 583 200 943 581 199 944 582 204 945 587 201 946 585 200 947 586 201 948 585 204 949 587 203 950 588 204 951 591 206 952 592 202 953 589 204 954 591 202 955 589 203 956 590 205 957 594 202 958 597 206 959 593 202 960 597 205 961 594 198 962 596 205 963 594 199 964 595 198 965 596 209 966 600 207 967 598 208 968 599 207 969 598 209 970 600 210 971 601 210 972 604 211 973 602 207 974 603 211 975 602 210 976 604 212 977 605 213 978 606 214 979 609 215 980 610 209 981 607 214 982 609 213 983 606 214 984 609 209 985 607 208 986 608 213 987 613 210 988 611 209 989 612 210 990 611 213 991 613 212 992 614 213 993 617 215 994 618 211 995 615 213 996 617 211 997 615 212 998 616 214 999 620 211 1000 623 215 1001 619 211 1002 623 214 1003 620 207 1004 622 214 1005 620 208 1006 621 207 1007 622

+

+

+
+
+
+ + + 1.672138 -114.084068 0.000000 0.000000 95.796867 1.991342 0.000000 0.000000 0.000000 0.000000 95.811455 0.000000 0.000000 0.000000 0.000000 1.0000001.000000 + 30.0000000.0000003.333333 + + + + + +
diff --git a/simulators/sim_env/models/aws_robomaker_warehouse_ClutteringC_01/model.config b/simulators/sim_env/models/aws_robomaker_warehouse_ClutteringC_01/model.config new file mode 100755 index 0000000..b842e6c --- /dev/null +++ b/simulators/sim_env/models/aws_robomaker_warehouse_ClutteringC_01/model.config @@ -0,0 +1,11 @@ + + + aws_robomaker_warehouse_ClutteringC_01 + 1.0 + model.sdf + + + + + + diff --git a/simulators/sim_env/models/aws_robomaker_warehouse_ClutteringC_01/model.sdf b/simulators/sim_env/models/aws_robomaker_warehouse_ClutteringC_01/model.sdf new file mode 100755 index 0000000..334a416 --- /dev/null +++ b/simulators/sim_env/models/aws_robomaker_warehouse_ClutteringC_01/model.sdf @@ -0,0 +1,55 @@ + + + + + + 1 + + 1.558 + 0 + 0 + 1.821 + 0 + 1.892 + + + + + + model://aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + model://aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_visual.DAE + + + 1 + + + 1 + + diff --git a/simulators/sim_env/models/aws_robomaker_warehouse_ClutteringD_01/materials/textures/aws_robomaker_warehouse_ClutteringD_01.png b/simulators/sim_env/models/aws_robomaker_warehouse_ClutteringD_01/materials/textures/aws_robomaker_warehouse_ClutteringD_01.png new file mode 100755 index 0000000..b28b289 Binary files /dev/null and b/simulators/sim_env/models/aws_robomaker_warehouse_ClutteringD_01/materials/textures/aws_robomaker_warehouse_ClutteringD_01.png differ diff --git a/simulators/sim_env/models/aws_robomaker_warehouse_ClutteringD_01/materials/textures/aws_robomaker_warehouse_ClutteringD_02.png b/simulators/sim_env/models/aws_robomaker_warehouse_ClutteringD_01/materials/textures/aws_robomaker_warehouse_ClutteringD_02.png new file mode 100755 index 0000000..4b7e610 Binary files /dev/null and b/simulators/sim_env/models/aws_robomaker_warehouse_ClutteringD_01/materials/textures/aws_robomaker_warehouse_ClutteringD_02.png differ diff --git a/simulators/sim_env/models/aws_robomaker_warehouse_ClutteringD_01/meshes/aws_robomaker_warehouse_ClutteringD_01_collision.DAE b/simulators/sim_env/models/aws_robomaker_warehouse_ClutteringD_01/meshes/aws_robomaker_warehouse_ClutteringD_01_collision.DAE new file mode 100755 index 0000000..08d4955 --- /dev/null +++ b/simulators/sim_env/models/aws_robomaker_warehouse_ClutteringD_01/meshes/aws_robomaker_warehouse_ClutteringD_01_collision.DAE @@ -0,0 +1,123 @@ + + + FBX COLLADA exporter2019-03-25T05:42:49Z2019-03-25T05:42:49ZZ_UP + + + + + +-50.844025 33.298004 -76.084843 +50.844025 33.298004 -76.084843 +-50.844025 182.463806 -76.084846 +50.844025 182.463806 -76.084846 +-50.844025 33.298012 76.084789 +50.844025 33.298012 76.084789 +-50.844025 182.463806 76.084789 +50.844025 182.463806 76.084789 + + + + + + + + + + + +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 -0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 + + + + + + + + + + + +1.000000 0.000000 +0.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 + + + + + + + + + + + +

1 0 1 0 1 0 3 2 3 0 3 0 2 4 2 3 5 3 7 6 7 6 7 6 4 8 4 7 9 7 4 10 4 5 11 5 5 12 11 4 13 10 0 14 8 5 15 11 0 16 8 1 17 9 5 18 14 3 19 13 7 20 15 3 21 13 5 22 14 1 23 12 6 24 19 7 25 18 3 26 16 6 27 19 3 28 16 2 29 17 4 30 23 6 31 22 2 32 20 4 33 23 2 34 20 0 35 21

+
+
+
+ + + 1.000000 0.000000 0.000000 0.000000 0.000000 -0.000000 -1.000000 0.000000 0.000000 1.000000 -0.000000 0.000000 0.000000 0.000000 0.000000 1.0000001.000000 + 30.0000000.0000003.333333 + + + + + +
diff --git a/simulators/sim_env/models/aws_robomaker_warehouse_ClutteringD_01/meshes/aws_robomaker_warehouse_ClutteringD_01_visual.DAE b/simulators/sim_env/models/aws_robomaker_warehouse_ClutteringD_01/meshes/aws_robomaker_warehouse_ClutteringD_01_visual.DAE new file mode 100755 index 0000000..5d51ad6 --- /dev/null +++ b/simulators/sim_env/models/aws_robomaker_warehouse_ClutteringD_01/meshes/aws_robomaker_warehouse_ClutteringD_01_visual.DAE @@ -0,0 +1,1420 @@ + + + FBX COLLADA exporter2019-03-25T05:43:02Z2019-03-25T05:43:02ZZ_UP + + + ../materials/textures/aws_robomaker_warehouse_ClutteringD_01.png + + + + + + + + + + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + +0.009253 -0.503716 0.419458 +0.009253 -0.503716 0.858284 +-0.890007 -0.517079 0.858284 +-0.890007 -0.517079 0.419458 +-0.005807 0.000161 0.419458 +-0.905068 -0.013201 0.419458 +-0.905068 -0.013202 0.858284 +-0.005476 -0.010937 0.858284 +-0.005807 0.000161 0.858284 +0.009254 -0.503716 0.865917 +0.009254 -0.503716 1.304744 +-0.890007 -0.517079 1.304744 +-0.890007 -0.517079 0.865917 +-0.005806 0.000160 0.865917 +-0.905068 -0.013202 0.865917 +-0.905068 -0.013202 1.304744 +-0.005475 -0.010937 1.304744 +-0.005806 0.000160 1.304744 +0.009255 -0.503716 1.310472 +0.009255 -0.503716 1.749298 +-0.890006 -0.517080 1.749298 +-0.890006 -0.517080 1.310472 +-0.005805 0.000160 1.310472 +-0.905068 -0.013202 1.310472 +-0.905067 -0.013203 1.749298 +-0.005474 -0.010937 1.749298 +-0.005805 0.000160 1.749298 +-0.001216 -0.000079 0.419458 +-0.001216 -0.000079 0.858284 +-0.900477 -0.013442 0.858284 +-0.900477 -0.013442 0.419458 +-0.016277 0.503797 0.419458 +-0.915537 0.490435 0.419458 +-0.915537 0.490434 0.858284 +-0.015945 0.492699 0.858284 +-0.016277 0.503797 0.858284 +-0.001215 -0.000080 0.865917 +-0.001215 -0.000080 1.304744 +-0.900476 -0.013443 1.304744 +-0.900476 -0.013443 0.865917 +-0.016275 0.503797 0.865917 +-0.915536 0.490434 0.865917 +-0.915536 0.490434 1.304744 +-0.015945 0.492699 1.304744 +-0.016275 0.503797 1.304744 +-0.001215 -0.000080 1.310472 +-0.001215 -0.000080 1.749298 +-0.900475 -0.013443 1.749298 +-0.900475 -0.013443 1.310472 +-0.016274 0.503797 1.310472 +-0.915535 0.490434 1.310472 +-0.915535 0.490433 1.749298 +-0.015944 0.492698 1.749298 +-0.016274 0.503797 1.749298 +0.915534 -0.490433 0.419458 +0.915534 -0.490433 0.858284 +0.016273 -0.503795 0.858284 +0.016273 -0.503795 0.419458 +0.900473 0.013444 0.419458 +0.001212 0.000082 0.419458 +0.001212 0.000081 0.858284 +0.900805 0.002347 0.858284 +0.900473 0.013444 0.858284 +0.915534 -0.490433 0.865917 +0.915534 -0.490433 1.304744 +0.016273 -0.503796 1.304744 +0.016273 -0.503796 0.865917 +0.900474 0.013444 0.865917 +0.001213 0.000081 0.865917 +0.001213 0.000081 1.304744 +0.900805 0.002346 1.304744 +0.900474 0.013444 1.304744 +0.915535 -0.490433 1.310472 +0.915535 -0.490433 1.749298 +0.016273 -0.503796 1.749298 +0.016273 -0.503796 1.310472 +0.900475 0.013444 1.310472 +0.001214 0.000081 1.310472 +0.001214 0.000081 1.749298 +0.900805 0.002346 1.749298 +0.900475 0.013444 1.749298 +0.905064 0.013204 0.419458 +0.905064 0.013204 0.858284 +0.005803 -0.000159 0.858284 +0.005803 -0.000159 0.419458 +0.890004 0.517081 0.419458 +-0.009257 0.503718 0.419458 +-0.009257 0.503717 0.858284 +0.890335 0.505983 0.858284 +0.890004 0.517081 0.858284 +0.905065 0.013204 0.865917 +0.905065 0.013204 1.304744 +0.005805 -0.000159 1.304744 +0.005805 -0.000159 0.865917 +0.890006 0.517080 0.865917 +-0.009256 0.503718 0.865917 +-0.009256 0.503717 1.304744 +0.890336 0.505982 1.304744 +0.890006 0.517080 1.304744 +0.905066 0.013204 1.310472 +0.905066 0.013204 1.749298 +0.005805 -0.000160 1.749298 +0.005805 -0.000160 1.310472 +0.890006 0.517080 1.310472 +-0.009255 0.503717 1.310472 +-0.009255 0.503716 1.749298 +0.890336 0.505982 1.749298 +0.890006 0.517080 1.749298 +0.009256 -0.503717 1.758337 +0.009256 -0.503717 2.197164 +-0.890004 -0.517080 2.197164 +-0.890004 -0.517080 1.758337 +-0.005803 0.000160 1.758337 +-0.905068 -0.013203 1.758337 +-0.905065 -0.013203 2.197164 +-0.005473 -0.010938 2.197164 +-0.005803 0.000160 2.197164 +-0.001214 -0.000080 1.758337 +-0.001214 -0.000080 2.197164 +-0.900473 -0.013444 2.197164 +-0.900473 -0.013444 1.758337 +-0.016271 0.503796 1.758337 +-0.915534 0.490433 1.758337 +-0.915534 0.490433 2.197164 +-0.015943 0.492697 2.197164 +-0.016271 0.503796 2.197164 +0.915537 -0.490433 1.758337 +0.915537 -0.490433 2.197164 +0.016273 -0.503797 2.197164 +0.016273 -0.503797 1.758337 +0.900476 0.013443 1.758337 +0.001215 0.000080 1.758337 +0.001215 0.000080 2.197164 +0.900805 0.002345 2.197164 +0.900476 0.013443 2.197164 +0.905067 0.013203 1.758337 +0.905067 0.013203 2.197164 +0.005807 -0.000160 2.197164 +0.005807 -0.000160 1.758337 +0.890007 0.517079 1.758337 +-0.009254 0.503716 1.758337 +-0.009254 0.503716 2.197164 +0.890337 0.505981 2.197164 +0.890007 0.517079 2.197164 + + + + + + + + + + + +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029878 -0.000000 +-0.999554 -0.029878 -0.000000 +-0.999554 -0.029878 -0.000000 +-0.999554 -0.029878 -0.000000 +-0.999554 -0.029878 -0.000000 +-0.999554 -0.029878 -0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029879 0.000001 +-0.999554 -0.029879 0.000001 +-0.999554 -0.029879 0.000001 +-0.999554 -0.029879 0.000001 +-0.999554 -0.029879 0.000001 +-0.999554 -0.029879 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.999554 0.029876 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.014859 -0.999890 0.000000 +0.014859 -0.999890 0.000000 +0.014859 -0.999890 0.000000 +0.014859 -0.999890 0.000000 +0.014859 -0.999890 0.000000 +0.014859 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029877 -0.000000 +-0.999554 -0.029877 -0.000000 +-0.999554 -0.029877 -0.000000 +-0.999554 -0.029877 -0.000000 +-0.999554 -0.029877 -0.000000 +-0.999554 -0.029877 -0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.999554 0.029877 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029875 -0.000000 +-0.999554 -0.029875 -0.000000 +-0.999554 -0.029875 -0.000000 +-0.999554 -0.029875 -0.000000 +-0.999554 -0.029875 -0.000000 +-0.999554 -0.029875 -0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +0.999554 0.029877 0.000001 +0.999554 0.029877 0.000001 +0.999554 0.029877 0.000001 +0.999554 0.029877 0.000001 +0.999554 0.029877 0.000001 +0.999554 0.029877 0.000001 +0.999554 0.029877 0.000001 +0.999554 0.029877 0.000001 +0.999554 0.029877 0.000001 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029875 -0.000000 +-0.999554 -0.029875 -0.000000 +-0.999554 -0.029875 -0.000000 +-0.999554 -0.029875 -0.000000 +-0.999554 -0.029875 -0.000000 +-0.999554 -0.029875 -0.000000 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.999554 0.029875 0.000001 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029877 -0.000000 +-0.999554 -0.029877 -0.000000 +-0.999554 -0.029877 -0.000000 +-0.999554 -0.029877 -0.000000 +-0.999554 -0.029877 -0.000000 +-0.999554 -0.029877 -0.000000 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029877 -0.000000 +-0.999554 -0.029877 -0.000000 +-0.999554 -0.029877 -0.000000 +-0.999554 -0.029877 -0.000000 +-0.999554 -0.029877 -0.000000 +-0.999554 -0.029877 -0.000000 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +0.999554 0.029874 0.000002 +0.999554 0.029874 0.000002 +0.999554 0.029874 0.000002 +0.999554 0.029874 0.000002 +0.999554 0.029874 0.000002 +0.999554 0.029874 0.000002 +0.999554 0.029874 0.000002 +0.999554 0.029874 0.000002 +0.999554 0.029874 0.000002 +0.014859 -0.999890 0.000000 +0.014859 -0.999890 0.000000 +0.014859 -0.999890 0.000000 +0.014859 -0.999890 0.000000 +0.014859 -0.999890 0.000000 +0.014859 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029880 0.000003 +-0.999553 -0.029880 0.000003 +-0.999553 -0.029880 0.000003 +-0.999553 -0.029880 0.000003 +-0.999553 -0.029880 0.000003 +-0.999553 -0.029880 0.000003 +-0.014858 0.999890 -0.000000 +-0.014858 0.999890 -0.000000 +-0.014858 0.999890 -0.000000 +-0.014858 0.999890 -0.000000 +-0.014858 0.999890 -0.000000 +-0.014858 0.999890 -0.000000 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.999554 0.029873 0.000002 +0.014859 -0.999890 0.000000 +0.014859 -0.999890 0.000000 +0.014859 -0.999890 0.000000 +0.014859 -0.999890 0.000000 +0.014859 -0.999890 0.000000 +0.014859 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.999554 -0.029876 -0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +0.999554 0.029870 0.000004 +0.999554 0.029870 0.000004 +0.999554 0.029870 0.000004 +0.999554 0.029870 0.000004 +0.999554 0.029870 0.000004 +0.999554 0.029870 0.000004 +0.999554 0.029870 0.000004 +0.999554 0.029870 0.000004 +0.999554 0.029870 0.000004 +0.014859 -0.999890 0.000000 +0.014859 -0.999890 0.000000 +0.014859 -0.999890 0.000000 +0.014859 -0.999890 0.000000 +0.014859 -0.999890 0.000000 +0.014859 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029872 -0.000000 +-0.999554 -0.029872 -0.000000 +-0.999554 -0.029872 -0.000000 +-0.999554 -0.029872 -0.000000 +-0.999554 -0.029872 -0.000000 +-0.999554 -0.029872 -0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +-0.014858 0.999890 0.000000 +0.999554 0.029877 0.000003 +0.999554 0.029877 0.000003 +0.999554 0.029877 0.000003 +0.999554 0.029877 0.000003 +0.999554 0.029877 0.000003 +0.999554 0.029877 0.000003 +0.999554 0.029877 0.000003 +0.999554 0.029877 0.000003 +0.999554 0.029877 0.000003 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.014858 -0.999890 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999554 -0.029877 -0.000000 +-0.999554 -0.029877 -0.000000 +-0.999554 -0.029877 -0.000000 +-0.999554 -0.029877 -0.000000 +-0.999554 -0.029877 -0.000000 +-0.999554 -0.029877 -0.000000 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +-0.014858 0.999890 0.000001 +0.999554 0.029874 0.000002 +0.999554 0.029874 0.000002 +0.999554 0.029874 0.000002 +0.999554 0.029874 0.000002 +0.999554 0.029874 0.000002 +0.999554 0.029874 0.000002 +0.999554 0.029874 0.000002 +0.999554 0.029874 0.000002 +0.999554 0.029874 0.000002 + + + + + + + + + + + +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.692024 +0.027038 0.424800 +0.966910 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.506996 0.036168 +0.489461 0.035380 +0.489461 0.415225 +0.029544 0.415224 +0.029544 0.043430 +0.029544 0.035380 +0.407335 0.698761 +0.409054 0.971742 +0.037422 0.971548 +0.039211 0.698717 +0.505546 0.409621 +0.965459 0.409621 +0.965462 0.676852 +0.505546 0.676852 +0.922325 0.962378 +0.914572 0.962378 +0.570343 0.962377 +0.570344 0.705031 +0.922325 0.705031 + + + + + + + + + + + +

2 0 2 0 1 0 1 2 1 0 3 0 2 4 2 3 5 3 3 6 6 4 7 4 0 8 5 4 9 4 3 10 6 5 11 7 6 12 8 7 13 11 8 14 12 2 15 9 7 16 11 6 17 8 7 18 11 2 19 9 1 20 10 6 21 15 3 22 13 2 23 14 3 24 13 6 25 15 5 26 16 6 27 19 8 28 20 4 29 17 6 30 19 4 31 17 5 32 18 7 33 22 4 34 25 8 35 21 4 36 25 7 37 22 0 38 24 7 39 22 1 40 23 0 41 24 11 42 28 9 43 26 10 44 27 9 45 26 11 46 28 12 47 29 12 48 32 13 49 30 9 50 31 13 51 30 12 52 32 14 53 33 15 54 34 16 55 37 17 56 38 11 57 35 16 58 37 15 59 34 16 60 37 11 61 35 10 62 36 15 63 41 12 64 39 11 65 40 12 66 39 15 67 41 14 68 42 15 69 45 17 70 46 13 71 43 15 72 45 13 73 43 14 74 44 16 75 48 13 76 51 17 77 47 13 78 51 16 79 48 9 80 50 16 81 48 10 82 49 9 83 50 20 84 54 18 85 52 19 86 53 18 87 52 20 88 54 21 89 55 21 90 58 22 91 56 18 92 57 22 93 56 21 94 58 23 95 59 24 96 60 25 97 63 26 98 64 20 99 61 25 100 63 24 101 60 25 102 63 20 103 61 19 104 62 24 105 67 21 106 65 20 107 66 21 108 65 24 109 67 23 110 68 24 111 71 26 112 72 22 113 69 24 114 71 22 115 69 23 116 70 25 117 74 22 118 77 26 119 73 22 120 77 25 121 74 18 122 76 25 123 74 19 124 75 18 125 76 29 126 80 27 127 78 28 128 79 27 129 78 29 130 80 30 131 81 30 132 84 31 133 82 27 134 83 31 135 82 30 136 84 32 137 85 33 138 86 34 139 89 35 140 90 29 141 87 34 142 89 33 143 86 34 144 89 29 145 87 28 146 88 33 147 93 30 148 91 29 149 92 30 150 91 33 151 93 32 152 94 33 153 97 35 154 98 31 155 95 33 156 97 31 157 95 32 158 96 34 159 100 31 160 103 35 161 99 31 162 103 34 163 100 27 164 102 34 165 100 28 166 101 27 167 102 38 168 106 36 169 104 37 170 105 36 171 104 38 172 106 39 173 107 39 174 110 40 175 108 36 176 109 40 177 108 39 178 110 41 179 111 42 180 112 43 181 115 44 182 116 38 183 113 43 184 115 42 185 112 43 186 115 38 187 113 37 188 114 42 189 119 39 190 117 38 191 118 39 192 117 42 193 119 41 194 120 42 195 123 44 196 124 40 197 121 42 198 123 40 199 121 41 200 122 43 201 126 40 202 129 44 203 125 40 204 129 43 205 126 36 206 128 43 207 126 37 208 127 36 209 128 47 210 132 45 211 130 46 212 131 45 213 130 47 214 132 48 215 133 48 216 136 49 217 134 45 218 135 49 219 134 48 220 136 50 221 137 51 222 138 52 223 141 53 224 142 47 225 139 52 226 141 51 227 138 52 228 141 47 229 139 46 230 140 51 231 145 48 232 143 47 233 144 48 234 143 51 235 145 50 236 146 51 237 149 53 238 150 49 239 147 51 240 149 49 241 147 50 242 148 52 243 152 49 244 155 53 245 151 49 246 155 52 247 152 45 248 154 52 249 152 46 250 153 45 251 154 56 252 158 54 253 156 55 254 157 54 255 156 56 256 158 57 257 159 57 258 162 58 259 160 54 260 161 58 261 160 57 262 162 59 263 163 60 264 164 61 265 167 62 266 168 56 267 165 61 268 167 60 269 164 61 270 167 56 271 165 55 272 166 60 273 171 57 274 169 56 275 170 57 276 169 60 277 171 59 278 172 60 279 175 62 280 176 58 281 173 60 282 175 58 283 173 59 284 174 61 285 178 58 286 181 62 287 177 58 288 181 61 289 178 54 290 180 61 291 178 55 292 179 54 293 180 65 294 184 63 295 182 64 296 183 63 297 182 65 298 184 66 299 185 66 300 188 67 301 186 63 302 187 67 303 186 66 304 188 68 305 189 69 306 190 70 307 193 71 308 194 65 309 191 70 310 193 69 311 190 70 312 193 65 313 191 64 314 192 69 315 197 66 316 195 65 317 196 66 318 195 69 319 197 68 320 198 69 321 201 71 322 202 67 323 199 69 324 201 67 325 199 68 326 200 70 327 204 67 328 207 71 329 203 67 330 207 70 331 204 63 332 206 70 333 204 64 334 205 63 335 206 74 336 210 72 337 208 73 338 209 72 339 208 74 340 210 75 341 211 75 342 214 76 343 212 72 344 213 76 345 212 75 346 214 77 347 215 78 348 216 79 349 219 80 350 220 74 351 217 79 352 219 78 353 216 79 354 219 74 355 217 73 356 218 78 357 223 75 358 221 74 359 222 75 360 221 78 361 223 77 362 224 78 363 227 80 364 228 76 365 225 78 366 227 76 367 225 77 368 226 79 369 230 76 370 233 80 371 229 76 372 233 79 373 230 72 374 232 79 375 230 73 376 231 72 377 232 83 378 236 81 379 234 82 380 235 81 381 234 83 382 236 84 383 237 84 384 240 85 385 238 81 386 239 85 387 238 84 388 240 86 389 241 87 390 242 88 391 245 89 392 246 83 393 243 88 394 245 87 395 242 88 396 245 83 397 243 82 398 244 87 399 249 84 400 247 83 401 248 84 402 247 87 403 249 86 404 250 87 405 253 89 406 254 85 407 251 87 408 253 85 409 251 86 410 252 88 411 256 85 412 259 89 413 255 85 414 259 88 415 256 81 416 258 88 417 256 82 418 257 81 419 258 92 420 262 90 421 260 91 422 261 90 423 260 92 424 262 93 425 263 93 426 266 94 427 264 90 428 265 94 429 264 93 430 266 95 431 267 96 432 268 97 433 271 98 434 272 92 435 269 97 436 271 96 437 268 97 438 271 92 439 269 91 440 270 96 441 275 93 442 273 92 443 274 93 444 273 96 445 275 95 446 276 96 447 279 98 448 280 94 449 277 96 450 279 94 451 277 95 452 278 97 453 282 94 454 285 98 455 281 94 456 285 97 457 282 90 458 284 97 459 282 91 460 283 90 461 284 101 462 288 99 463 286 100 464 287 99 465 286 101 466 288 102 467 289 102 468 292 103 469 290 99 470 291 103 471 290 102 472 292 104 473 293 105 474 294 106 475 297 107 476 298 101 477 295 106 478 297 105 479 294 106 480 297 101 481 295 100 482 296 105 483 301 102 484 299 101 485 300 102 486 299 105 487 301 104 488 302 105 489 305 107 490 306 103 491 303 105 492 305 103 493 303 104 494 304 106 495 308 103 496 311 107 497 307 103 498 311 106 499 308 99 500 310 106 501 308 100 502 309 99 503 310 110 504 314 108 505 312 109 506 313 108 507 312 110 508 314 111 509 315 111 510 318 112 511 316 108 512 317 112 513 316 111 514 318 113 515 319 114 516 320 115 517 323 116 518 324 110 519 321 115 520 323 114 521 320 115 522 323 110 523 321 109 524 322 114 525 327 113 526 328 110 527 326 110 528 326 113 529 328 111 530 325 114 531 331 116 532 332 112 533 329 114 534 331 112 535 329 113 536 330 115 537 334 112 538 337 116 539 333 112 540 337 115 541 334 108 542 336 115 543 334 109 544 335 108 545 336 119 546 340 117 547 338 118 548 339 117 549 338 119 550 340 120 551 341 120 552 344 121 553 342 117 554 343 121 555 342 120 556 344 122 557 345 123 558 346 124 559 349 125 560 350 119 561 347 124 562 349 123 563 346 124 564 349 119 565 347 118 566 348 123 567 353 120 568 351 119 569 352 120 570 351 123 571 353 122 572 354 123 573 357 125 574 358 121 575 355 123 576 357 121 577 355 122 578 356 124 579 360 121 580 363 125 581 359 121 582 363 124 583 360 117 584 362 124 585 360 118 586 361 117 587 362 128 588 366 126 589 364 127 590 365 126 591 364 128 592 366 129 593 367 129 594 370 130 595 368 126 596 369 130 597 368 129 598 370 131 599 371 132 600 372 133 601 375 134 602 376 128 603 373 133 604 375 132 605 372 133 606 375 128 607 373 127 608 374 132 609 379 129 610 377 128 611 378 129 612 377 132 613 379 131 614 380 132 615 383 134 616 384 130 617 381 132 618 383 130 619 381 131 620 382 133 621 386 130 622 389 134 623 385 130 624 389 133 625 386 126 626 388 133 627 386 127 628 387 126 629 388 137 630 392 135 631 390 136 632 391 135 633 390 137 634 392 138 635 393 138 636 396 139 637 394 135 638 395 139 639 394 138 640 396 140 641 397 141 642 398 142 643 401 143 644 402 137 645 399 142 646 401 141 647 398 142 648 401 137 649 399 136 650 400 141 651 405 138 652 403 137 653 404 138 654 403 141 655 405 140 656 406 141 657 409 143 658 410 139 659 407 141 660 409 139 661 407 140 662 408 142 663 412 139 664 415 143 665 411 139 666 415 142 667 412 135 668 414 142 669 412 136 670 413 135 671 414

+

+

+
+
+
+ + + 1.447990 -98.791206 0.000000 0.000000 82.955384 1.724405 0.000000 0.000000 0.000000 0.000000 82.968018 0.000000 0.000000 0.000000 0.000000 1.0000001.000000 + 30.0000000.0000003.333333 + + + + + +
diff --git a/simulators/sim_env/models/aws_robomaker_warehouse_ClutteringD_01/model.config b/simulators/sim_env/models/aws_robomaker_warehouse_ClutteringD_01/model.config new file mode 100755 index 0000000..870fdd2 --- /dev/null +++ b/simulators/sim_env/models/aws_robomaker_warehouse_ClutteringD_01/model.config @@ -0,0 +1,11 @@ + + + aws_robomaker_warehouse_ClutteringD_01 + 1.0 + model.sdf + + + + + + diff --git a/simulators/sim_env/models/aws_robomaker_warehouse_ClutteringD_01/model.sdf b/simulators/sim_env/models/aws_robomaker_warehouse_ClutteringD_01/model.sdf new file mode 100755 index 0000000..51ac2cd --- /dev/null +++ b/simulators/sim_env/models/aws_robomaker_warehouse_ClutteringD_01/model.sdf @@ -0,0 +1,55 @@ + + + + + + 1 + + 1.558 + 0 + 0 + 1.821 + 0 + 1.892 + + + + + + model://aws_robomaker_warehouse_ClutteringD_01/meshes/aws_robomaker_warehouse_ClutteringD_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + model://aws_robomaker_warehouse_ClutteringD_01/meshes/aws_robomaker_warehouse_ClutteringD_01_visual.DAE + + + 1 + + +1 + + diff --git a/simulators/sim_env/models/aws_robomaker_warehouse_ShelfD_01/materials/textures/aws_robomaker_warehouse_ShelfD_01.png b/simulators/sim_env/models/aws_robomaker_warehouse_ShelfD_01/materials/textures/aws_robomaker_warehouse_ShelfD_01.png new file mode 100755 index 0000000..d33ba54 Binary files /dev/null and b/simulators/sim_env/models/aws_robomaker_warehouse_ShelfD_01/materials/textures/aws_robomaker_warehouse_ShelfD_01.png differ diff --git a/simulators/sim_env/models/aws_robomaker_warehouse_ShelfD_01/materials/textures/aws_robomaker_warehouse_ShelfD_02.png b/simulators/sim_env/models/aws_robomaker_warehouse_ShelfD_01/materials/textures/aws_robomaker_warehouse_ShelfD_02.png new file mode 100755 index 0000000..4b7e610 Binary files /dev/null and b/simulators/sim_env/models/aws_robomaker_warehouse_ShelfD_01/materials/textures/aws_robomaker_warehouse_ShelfD_02.png differ diff --git a/simulators/sim_env/models/aws_robomaker_warehouse_ShelfD_01/materials/textures/aws_robomaker_warehouse_ShelfD_03.png b/simulators/sim_env/models/aws_robomaker_warehouse_ShelfD_01/materials/textures/aws_robomaker_warehouse_ShelfD_03.png new file mode 100755 index 0000000..b28b289 Binary files /dev/null and b/simulators/sim_env/models/aws_robomaker_warehouse_ShelfD_01/materials/textures/aws_robomaker_warehouse_ShelfD_03.png differ diff --git a/simulators/sim_env/models/aws_robomaker_warehouse_ShelfD_01/materials/textures/aws_robomaker_warehouse_ShelfD_04.png b/simulators/sim_env/models/aws_robomaker_warehouse_ShelfD_01/materials/textures/aws_robomaker_warehouse_ShelfD_04.png new file mode 100755 index 0000000..e76fcdd Binary files /dev/null and b/simulators/sim_env/models/aws_robomaker_warehouse_ShelfD_01/materials/textures/aws_robomaker_warehouse_ShelfD_04.png differ diff --git a/simulators/sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_collision.DAE b/simulators/sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_collision.DAE new file mode 100755 index 0000000..0c5642a --- /dev/null +++ b/simulators/sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_collision.DAE @@ -0,0 +1,327 @@ + + + FBX COLLADA exporter2019-05-15T10:09:41Z2019-05-15T10:09:41ZZ_UP + + + + + +-45.044750 -57.560341 195.803909 +42.866188 -57.560341 195.803955 +-45.044750 133.195770 195.803955 +42.866188 133.195770 195.803986 +-45.044781 -57.560341 -195.804031 +42.866158 -57.560341 -195.804001 +-45.044781 133.195770 -195.803986 +42.866158 133.195770 -195.803970 +-44.361427 -128.142014 1.402283 +42.927315 -128.142014 1.402374 +-44.361427 133.195755 1.402374 +42.927315 133.195755 1.402420 +-44.361412 -128.141998 -4.198639 +42.927338 -128.141998 -4.198563 +-44.361412 133.195786 -4.198517 +42.927338 133.195786 -4.198456 +-44.361458 -128.142029 -190.318237 +42.927284 -128.142029 -190.318130 +42.927284 133.195740 -190.318039 +-44.361458 133.195740 -190.318130 +-44.361443 -128.142014 -195.919159 +-44.361443 133.195770 -195.919022 +42.927307 133.195770 -195.918884 +42.927307 -128.142014 -195.919037 +-44.361401 -128.141998 195.912140 +42.927341 -128.141998 195.912231 +-44.361401 133.195770 195.912231 +42.927341 133.195770 195.912277 +-44.361378 -128.141983 190.311218 +42.927372 -128.141983 190.311295 +-44.361378 133.195801 190.311340 +42.927372 133.195801 190.311401 + + + + + + + + + + + +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +1.000000 -0.000000 0.000004 +1.000000 -0.000000 0.000004 +1.000000 -0.000000 0.000004 +1.000000 -0.000000 0.000004 +1.000000 -0.000000 0.000004 +1.000000 -0.000000 0.000004 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-1.000000 0.000000 -0.000003 +-1.000000 0.000000 -0.000003 +-1.000000 0.000000 -0.000003 +-1.000000 0.000000 -0.000003 +-1.000000 0.000000 -0.000003 +-1.000000 0.000000 -0.000003 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +0.000001 0.000001 -1.000000 +0.000001 0.000001 -1.000000 +0.000001 0.000001 -1.000000 +0.000001 0.000001 -1.000000 +0.000001 0.000001 -1.000000 +0.000001 0.000001 -1.000000 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +1.000000 -0.000000 0.000004 +1.000000 -0.000000 0.000004 +1.000000 -0.000000 0.000004 +1.000000 -0.000000 0.000004 +1.000000 -0.000000 0.000004 +1.000000 -0.000000 0.000004 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-1.000000 0.000000 -0.000003 +-1.000000 0.000000 -0.000003 +-1.000000 0.000000 -0.000003 +-1.000000 0.000000 -0.000003 +-1.000000 0.000000 -0.000003 +-1.000000 0.000000 -0.000003 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +1.000000 -0.000000 0.000005 +1.000000 -0.000000 0.000005 +1.000000 -0.000000 0.000005 +1.000000 -0.000000 0.000005 +1.000000 -0.000000 0.000005 +1.000000 -0.000000 0.000005 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-1.000000 0.000000 -0.000004 +-1.000000 0.000000 -0.000004 +-1.000000 0.000000 -0.000004 +-1.000000 0.000000 -0.000004 +-1.000000 0.000000 -0.000004 +-1.000000 0.000000 -0.000004 + + + + + + + + + + + +1.000000 0.000000 +0.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +1.000000 0.000000 +0.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +1.000000 0.000000 +0.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +1.000000 0.000000 +0.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +1.000000 0.000000 +0.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +1.000000 0.000000 +0.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +1.000000 0.000000 +0.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +1.000000 0.000000 +1.000000 0.000000 +0.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 + + + + + + + + + + + +

2 0 2 0 1 0 3 2 3 3 3 3 0 4 0 1 5 1 7 6 7 5 7 5 4 8 4 4 9 4 6 10 6 7 11 7 5 12 11 1 13 9 0 14 8 0 15 8 4 16 10 5 17 11 7 18 15 3 19 13 1 20 12 1 21 12 5 22 14 7 23 15 2 24 17 7 25 18 6 26 19 7 27 18 2 28 17 3 29 16 0 30 21 6 31 22 4 32 23 6 33 22 0 34 21 2 35 20 10 36 26 8 37 24 11 38 27 11 39 27 8 40 24 9 41 25 15 42 31 13 43 29 12 44 28 12 45 28 14 46 30 15 47 31 12 48 34 9 49 33 8 50 32 9 51 33 12 52 34 13 53 35 13 54 38 11 55 37 9 56 36 11 57 37 13 58 38 15 59 39 15 60 42 14 61 43 11 62 40 10 63 41 11 64 40 14 65 43 14 66 46 12 67 47 10 68 44 8 69 45 10 70 44 12 71 47 19 72 51 16 73 48 18 74 50 18 75 50 16 76 48 17 77 49 22 78 54 23 79 55 20 80 52 20 81 52 21 82 53 22 83 54 20 84 57 17 85 59 16 86 56 17 87 59 20 88 57 23 89 58 23 90 61 18 91 63 17 92 60 18 93 63 23 94 61 22 95 62 22 96 65 21 97 66 18 98 64 19 99 67 18 100 64 21 101 66 21 102 69 20 103 70 19 104 68 16 105 71 19 106 68 20 107 70 26 108 74 24 109 72 27 110 75 27 111 75 24 112 72 25 113 73 31 114 79 29 115 77 28 116 76 28 117 76 30 118 78 31 119 79 28 120 82 25 121 81 24 122 80 25 123 81 28 124 82 29 125 83 29 126 86 27 127 85 25 128 84 27 129 85 29 130 86 31 131 87 31 132 90 30 133 91 27 134 88 26 135 89 27 136 88 30 137 91 30 138 94 28 139 95 26 140 92 24 141 93 26 142 92 28 143 95

+
+
+
+ + + -0.000000 -0.000000 -1.000000 0.000000 -1.000000 0.000000 0.000000 -1.072197 0.000000 1.000000 -0.000000 131.071121 0.000000 0.000000 0.000000 1.0000001.000000 + 30.0000000.0000003.333333 + + + + + +
diff --git a/simulators/sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_visual.DAE b/simulators/sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_visual.DAE new file mode 100755 index 0000000..936caad --- /dev/null +++ b/simulators/sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_visual.DAE @@ -0,0 +1,3947 @@ + + + FBX COLLADA exporter2019-05-27T02:52:26Z2019-05-27T02:52:26ZZ_UP + + + ../materials/textures/aws_robomaker_warehouse_ShelfD_01.png + + + ../materials/textures/aws_robomaker_warehouse_ShelfD_03.png + + + ../materials/textures/aws_robomaker_warehouse_ShelfD_02.png + + + ../materials/textures/aws_robomaker_warehouse_ShelfD_04.png + + + + + + + + + + + + + + + + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + 0.800000 0.800000 0.800000 1.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + +-195.859329 -40.864964 11.286113 +-195.859360 -43.970364 11.286113 +-195.851028 -43.964931 -0.039542 +-195.359573 -41.130783 11.389088 +-190.846634 -43.704540 11.389088 +-195.851028 -40.870392 -0.039542 +-190.355179 -40.870392 -0.039542 +-190.355179 -43.964924 -0.039542 +-190.346863 -40.864960 11.286113 +-190.346848 -43.970367 11.286113 +-195.359573 -43.704540 11.389088 +-190.846634 -41.130779 11.389088 +-195.337234 -41.142639 261.250977 +-195.337234 -43.692688 261.250977 +-190.868851 -41.142639 261.250977 +-190.868851 -43.692688 261.250977 +190.346771 43.270035 11.286113 +190.346771 40.164623 11.286113 +190.355118 40.170067 -0.039542 +190.846558 43.004219 11.389088 +195.359558 40.430462 11.389088 +190.355118 43.264599 -0.039542 +195.850967 43.264603 -0.039542 +195.850967 40.170063 -0.039542 +195.859314 43.270039 11.286113 +195.859314 40.164627 11.286113 +190.846558 40.430454 11.389088 +195.359558 43.004223 11.389088 +190.868851 42.992374 261.250977 +190.868851 40.442318 261.250977 +195.337234 42.992374 261.250977 +195.337219 40.442322 261.250977 +-195.859329 43.269913 11.286113 +-195.859360 40.164501 11.286113 +-195.851028 40.169945 -0.039542 +-195.359573 43.004097 11.389088 +-190.846634 40.430340 11.389088 +-195.851028 43.264477 -0.039542 +-190.355179 43.264481 -0.039542 +-190.355179 40.169941 -0.039542 +-190.346863 43.269917 11.286113 +-190.346848 40.164505 11.286113 +-195.359573 40.430332 11.389088 +-190.846634 43.004101 11.389088 +-195.337234 42.992252 261.250977 +-195.337234 40.442196 261.250977 +-190.868851 42.992252 261.250977 +-190.868851 40.442200 261.250977 +-1.349450 43.269974 11.286113 +-1.349450 40.164562 11.286113 +-1.341129 40.170006 -0.039542 +-0.849689 43.004158 11.389088 +3.663298 40.430401 11.389088 +-1.341129 43.264538 -0.039542 +4.154719 43.264542 -0.039542 +4.154719 40.170002 -0.039542 +4.163049 43.269978 11.286113 +4.163049 40.164566 11.286113 +-0.849689 40.430393 11.389088 +3.663298 43.004162 11.389088 +-0.827415 42.992317 261.250977 +-0.827372 40.442257 261.250977 +3.640989 42.992317 261.250977 +3.641029 40.442261 261.250977 +-1.349419 -40.864902 11.286113 +-1.349419 -43.970303 11.286113 +-1.341098 -43.964870 -0.039542 +-0.849659 -41.130722 11.389088 +3.663328 -43.704479 11.389088 +-1.341098 -40.870331 -0.039542 +4.154749 -40.870331 -0.039542 +4.154749 -43.964863 -0.039542 +4.163079 -40.864899 11.286113 +4.163079 -43.970306 11.286113 +-0.849659 -43.704479 11.389088 +3.663328 -41.130718 11.389088 +-0.827342 -41.142578 261.250977 +-0.827328 -43.692627 261.250977 +3.641059 -41.142570 261.250977 +3.641079 -43.692623 261.250977 +190.346832 -40.864841 11.286113 +190.346817 -43.970242 11.286113 +190.355148 -43.964809 -0.039542 +190.846603 -41.130661 11.389088 +195.359573 -43.704418 11.389088 +190.355164 -40.870270 -0.039542 +195.850998 -40.870270 -0.039542 +195.850998 -43.964802 -0.039542 +195.859329 -40.864838 11.286113 +195.859344 -43.970245 11.286113 +190.846588 -43.704418 11.389088 +195.359573 -41.130657 11.389088 +190.868866 -41.142517 261.250977 +190.868881 -43.692566 261.250977 +195.337250 -41.142517 261.250977 +195.337265 -43.692566 261.250977 +-195.319946 -41.125313 13.878565 +-195.319916 40.434727 66.278061 +-190.886261 -41.125309 13.878560 +-195.319916 40.434727 70.460434 +-190.886246 -41.125320 9.696195 +-190.886246 40.434731 70.460434 +-195.319946 -41.125324 9.696195 +-190.886261 40.434731 66.278061 +-195.319992 -41.186462 144.465973 +-195.320007 40.434692 195.103180 +-195.320007 40.434704 199.280792 +-190.886292 -41.186459 144.465958 +-190.886322 40.434708 199.280792 +-190.886292 -41.186459 141.219635 +-190.886322 40.434696 195.103180 +-195.320007 -41.186462 141.219635 +-195.319946 -41.125320 134.569077 +-195.319916 40.434727 77.097397 +-195.319946 -41.125313 130.386719 +-190.886246 40.434731 77.097397 +-190.886261 40.434731 81.279785 +-190.886261 -41.125309 130.386734 +-190.886246 -41.125313 134.569077 +-195.319916 40.434727 81.279785 +190.824371 -41.125099 13.878565 +190.824371 40.434959 66.278061 +195.258072 -41.125080 13.878560 +190.824371 40.434959 70.460434 +195.258057 40.434978 70.460434 +195.258072 -41.125092 9.696197 +190.824371 -41.125111 9.696197 +195.258057 40.434978 66.278061 +190.824402 -41.186249 144.465973 +190.824356 40.434921 195.103180 +190.824341 40.434937 199.280792 +195.258087 -41.186234 144.465958 +195.258057 40.434948 199.280792 +195.258102 -41.186234 141.219635 +195.258057 40.434937 195.103180 +190.824402 -41.186249 141.219635 +190.824387 -41.125107 134.569061 +190.824402 40.434959 77.097397 +190.824387 -41.125099 130.386719 +195.258072 40.434978 77.097397 +195.258072 40.434978 81.279762 +195.258087 -41.125080 130.386719 +195.258087 -41.125088 134.569061 +190.824402 40.434959 81.279762 +-1.008084 -41.125114 13.878565 +-1.008087 40.434952 66.278061 +3.425621 -41.125095 13.878560 +-1.008087 40.434952 70.460434 +3.425587 40.434975 70.460434 +3.425621 -41.125103 9.696197 +-1.008084 -41.125122 9.696197 +3.425587 40.434975 66.278061 +-1.008060 -41.186264 144.465973 +-1.008118 40.434917 195.103180 +-1.008118 40.434925 199.280792 +3.425625 -41.186237 144.465958 +3.425590 40.434948 199.280792 +3.425625 -41.186237 141.219635 +3.425591 40.434937 195.103180 +-1.008060 -41.186264 141.219635 +-1.008083 -41.125118 134.569061 +-1.008064 40.434952 77.097397 +-1.008083 -41.125114 130.386719 +3.425602 40.434975 77.097397 +3.425602 40.434975 81.279762 +3.425617 -41.125095 130.386719 +3.425617 -41.125099 134.569061 +-1.008064 40.434952 81.279762 +190.734039 -41.267357 256.299133 +190.734024 41.439137 256.299133 +190.734039 -41.267357 259.323669 +190.734024 41.439137 259.323669 +195.278412 -41.267353 256.299133 +195.278397 41.439140 256.299133 +195.278412 -41.267353 259.323669 +195.278397 41.439140 259.323669 +-0.895264 -41.267330 256.299133 +-0.895294 41.439167 256.299133 +-0.895264 -41.267330 259.323669 +-0.895294 41.439167 259.323669 +3.649109 -41.267326 256.299133 +3.649078 41.439171 256.299133 +3.649109 -41.267326 259.323669 +3.649078 41.439171 259.323669 +-195.473846 -41.267296 256.299133 +-195.473846 41.439198 256.299133 +-195.473846 -41.267296 259.323669 +-195.473846 41.439198 259.323669 +-190.929474 -41.267292 256.299133 +-190.929474 41.439201 256.299133 +-190.929474 -41.267292 259.323669 +-190.929474 41.439201 259.323669 +-192.431396 43.978455 242.102509 +193.438141 38.358398 242.087494 +193.430084 38.361370 236.206406 +-192.438629 38.361286 242.092499 +-192.453064 43.978455 236.216309 +-192.438629 38.361286 236.206406 +193.430084 43.984470 236.206406 +193.430084 43.984474 242.092499 +-192.401535 -42.179398 140.859955 +-192.401535 -42.179398 134.975082 +-192.401535 41.115921 134.975082 +193.412735 41.116199 134.975098 +193.412781 -42.179111 134.975098 +-192.401535 41.115925 140.859955 +193.412735 41.116199 140.859955 +193.412781 -42.179111 140.859970 +-192.401535 -42.179398 76.744461 +-192.401535 -42.179398 70.859596 +-192.401535 41.115921 70.859589 +193.412735 41.116199 70.859596 +193.412781 -42.179111 70.859596 +-192.401535 41.115925 76.744453 +193.412735 41.116199 76.744476 +193.412781 -42.179111 76.744469 +193.412735 41.116207 196.922226 +-192.401535 -42.179398 196.922226 +-192.401535 41.115925 202.807083 +193.412781 -42.179111 202.807083 +-192.401535 -42.179394 202.807083 +193.412781 -42.179111 196.922226 +193.412735 41.116207 202.807083 +-192.401535 41.115921 196.922226 +-178.586426 -22.605822 96.767853 +-100.603027 -22.747538 76.381248 +-100.603027 -22.747660 96.767883 +-178.586426 -22.605822 76.381271 +-178.499023 25.176352 76.381271 +-100.516235 25.034750 76.381248 +-100.516235 25.034674 96.767883 +-178.499023 25.176443 96.767868 +-88.826538 -22.605822 96.767853 +-10.843140 -22.747538 76.381248 +-10.843140 -22.747660 96.767883 +-88.826538 -22.605822 76.381271 +-88.739136 25.176352 76.381271 +-10.756348 25.034750 76.381248 +-10.756348 25.034674 96.767883 +-88.739136 25.176443 96.767868 +-88.826538 -22.605829 117.386749 +-10.843140 -22.747545 97.000168 +-10.843140 -22.747667 117.386780 +-88.826538 -22.605829 97.000153 +-88.739136 25.176348 97.000153 +-10.756348 25.034746 97.000168 +-10.756348 25.034670 117.386780 +-88.739136 25.176439 117.386765 +-141.678711 -37.821102 161.109482 +-141.536987 40.162300 140.722885 +-141.536865 40.162300 161.109512 +-141.678711 -37.821102 140.722916 +-189.460815 -37.733696 140.722916 +-189.319214 40.249088 140.722885 +-189.319214 40.249088 161.109512 +-189.460938 -37.733696 161.109512 +-140.153320 40.249947 160.851883 +-140.295044 -37.733456 140.465286 +-140.295166 -37.733456 160.851913 +-140.153320 40.249947 140.465317 +-92.371216 40.162540 140.465317 +-92.512817 -37.820244 140.465286 +-92.512817 -37.820244 160.851913 +-92.371094 40.162540 160.851913 +-141.678711 -37.821102 181.615875 +-141.536987 40.162300 161.229279 +-141.536865 40.162300 181.615906 +-141.678711 -37.821102 161.229309 +-189.460815 -37.733696 161.229309 +-189.319214 40.249088 161.229279 +-189.319214 40.249088 181.615906 +-189.460938 -37.733696 181.615906 +-7.677246 25.034624 161.328079 +-85.660645 25.176350 140.941483 +-85.660645 25.176472 161.328110 +-7.677246 25.034624 140.941513 +-7.764648 -22.747478 140.941513 +-85.747437 -22.605879 140.941483 +-85.747437 -22.605879 161.328110 +-7.764648 -22.747601 161.328110 +-2.784668 17.029882 181.470779 +-79.266479 32.261143 161.084213 +-79.266357 32.261265 181.470810 +-2.784668 17.029882 161.084183 +-12.117798 -29.831873 161.084183 +-88.598877 -14.600979 161.084213 +-88.598877 -14.600979 181.470810 +-12.117798 -29.832056 181.470810 +69.007202 29.278488 123.836227 +69.301392 -25.122681 76.618340 +69.007202 29.278488 76.618340 +69.301392 -25.122711 123.836227 +4.720093 -25.279179 76.618340 +4.426025 29.122051 76.618340 +5.848633 29.125500 123.836227 +4.720459 -25.279179 123.836227 +4.426636 29.122051 123.836227 +136.298462 -25.122673 123.836197 +136.004517 29.278511 76.618362 +136.004517 29.278511 123.836197 +136.298462 -25.122673 76.618362 +71.717651 -25.279171 76.618370 +71.423218 29.122059 76.618370 +72.846191 29.125507 123.836227 +71.717651 -25.279171 123.836227 +71.423462 29.122059 123.836227 +189.951172 -36.224636 75.382462 +137.447266 39.841038 75.382462 +189.951172 39.841278 75.382446 +137.447266 -36.224880 75.382469 +137.447266 39.841038 82.989067 +189.951172 -36.224636 82.989067 +189.951172 39.841278 82.989052 +137.447266 -36.224880 82.989075 +189.951172 -36.224636 83.132347 +137.447266 39.841038 83.132355 +189.951172 39.841278 83.132332 +137.447266 -36.224880 83.132370 +137.447266 39.841038 90.738976 +189.951172 -36.224636 90.738960 +189.951172 39.841278 90.738960 +137.447266 -36.224880 90.738976 +189.950439 -36.224316 90.860062 +137.446289 39.841358 90.860062 +189.950439 39.841599 90.860062 +137.446289 -36.224560 90.860062 +137.446289 39.841358 98.466629 +189.950439 -36.224316 98.466629 +189.950439 39.841599 98.466629 +137.446289 -36.224560 98.466629 +-112.536499 29.278488 250.422791 +-112.242310 -25.122681 203.204910 +-112.536499 29.278488 203.204910 +-112.242310 -25.122711 250.422791 +-176.823608 -25.279179 203.204910 +-177.117676 29.122051 203.204910 +-175.695068 29.125500 250.422791 +-176.823242 -25.279179 250.422791 +-177.117065 29.122051 250.422791 +-18.152100 11.615347 250.422791 +-40.757202 -37.867748 203.204910 +-18.152100 11.615347 203.204910 +-40.757202 -37.867809 250.422791 +-99.419067 -10.857553 203.204910 +-76.813843 38.625538 203.204910 +-75.521606 38.030567 250.422791 +-99.418701 -10.857737 250.422791 +-76.813232 38.625294 250.422791 +82.850586 25.034658 161.436584 +4.867188 25.176378 141.049973 +4.867188 25.176500 161.436615 +82.850586 25.034658 141.049988 +82.763184 -22.747515 141.049988 +4.780396 -22.605909 141.049973 +4.780396 -22.605833 161.436615 +82.763184 -22.747606 161.436584 +82.850586 25.034658 182.055481 +4.867188 25.176382 161.668884 +4.867188 25.176504 182.055511 +82.850586 25.034658 161.668884 +82.763184 -22.747519 161.668884 +4.780396 -22.605909 161.668884 +4.780396 -22.605833 182.055511 +82.763184 -22.747610 182.055481 +135.996216 -38.568268 141.181595 +83.492310 37.497406 141.181595 +135.996216 37.497650 141.181580 +83.492310 -38.568512 141.181595 +83.492310 37.497406 148.788193 +135.996216 -38.568268 148.788193 +135.996216 37.497650 148.788193 +83.492310 -38.568512 148.788208 +135.996216 -38.568268 148.931473 +83.492310 37.497406 148.931488 +135.996216 37.497650 148.931473 +83.492310 -38.568512 148.931503 +83.492310 37.497406 156.538101 +135.996216 -38.568268 156.538101 +135.996216 37.497650 156.538101 +83.492310 -38.568512 156.538101 +135.995483 -38.567944 156.659195 +83.491333 37.497730 156.659195 +135.995483 37.497971 156.659195 +83.491333 -38.568188 156.659195 +83.491333 37.497730 164.265762 +135.995483 -38.567944 164.265762 +135.995483 37.497971 164.265762 +83.491333 -38.568188 164.265762 +142.044067 -42.379524 164.358704 +102.814697 41.308594 164.358688 +154.598511 32.643188 164.358704 +90.260132 -33.714111 164.358688 +102.814697 41.308594 171.965317 +142.044067 -42.379524 171.965332 +154.598511 32.643188 171.965332 +90.260132 -33.714111 171.965317 +142.044067 -42.379524 172.238983 +102.814697 41.308594 172.238968 +154.598511 32.643188 172.238983 +90.260132 -33.714111 172.238968 +102.814697 41.308594 179.845657 +142.044067 -42.379524 179.845642 +154.598511 32.643188 179.845642 +90.260132 -33.714111 179.845657 +189.735352 -38.568268 141.181595 +137.231445 37.497406 141.181595 +189.735352 37.497650 141.181580 +137.231445 -38.568512 141.181595 +137.231445 37.497406 148.788193 +189.735352 -38.568268 148.788193 +189.735352 37.497650 148.788193 +137.231445 -38.568512 148.788208 +189.735352 -38.568268 148.931473 +137.231445 37.497406 148.931488 +189.735352 37.497650 148.931473 +137.231445 -38.568512 148.931503 +137.231445 37.497406 156.538101 +189.735352 -38.568268 156.538101 +189.735352 37.497650 156.538101 +137.231445 -38.568512 156.538101 +82.850586 25.034658 222.664795 +4.867188 25.176378 202.278183 +4.867188 25.176500 222.664825 +82.850586 25.034658 202.278198 +82.763184 -22.747515 202.278198 +4.780396 -22.605909 202.278183 +4.780396 -22.605833 222.664825 +82.763184 -22.747606 222.664795 +102.337402 -31.465485 203.762085 +166.477905 35.082581 203.762085 +176.892090 -16.378141 203.762070 +91.923218 19.995256 203.762100 +166.477905 35.082581 211.368668 +102.337402 -31.465485 211.368668 +176.892090 -16.378141 211.368698 +91.923218 19.995256 211.368698 +102.337402 -31.465485 211.511978 +166.477905 35.082581 211.511978 +176.892090 -16.378141 211.511948 +91.923218 19.995256 211.511993 +166.477905 35.082581 219.118607 +102.337402 -31.465485 219.118576 +176.892090 -16.378141 219.118576 +91.923218 19.995256 219.118607 +102.336304 -31.465559 219.239685 +166.476807 35.082733 219.239685 +176.890991 -16.378218 219.239685 +91.922119 19.995378 219.239685 +166.476807 35.082733 226.846252 +102.336304 -31.465559 226.846252 +176.890991 -16.378218 226.846252 +91.922119 19.995378 226.846252 +102.337402 -31.465477 227.116623 +166.477905 35.082588 227.116623 +176.892090 -16.378136 227.116623 +91.923218 19.995262 227.116623 +166.477905 35.082588 234.723190 +102.337402 -31.465477 234.723190 +176.892090 -16.378136 234.723190 +91.923218 19.995262 234.723206 +-195.319946 -41.125313 13.878565 +190.824371 -41.125099 13.878565 + + + + + + + + + + + +-0.956333 0.263761 0.125924 +-0.951559 -0.257087 -0.168648 +-0.956403 -0.263505 0.125933 +-0.951559 -0.257087 -0.168648 +-0.956333 0.263761 0.125924 +-0.951498 0.257330 -0.168618 +-0.085984 -0.990457 -0.107708 +0.089169 -0.993226 0.074504 +-0.089036 -0.993235 0.074540 +0.089169 -0.993226 0.074504 +-0.085984 -0.990457 -0.107708 +0.086116 -0.990450 -0.107670 +0.956429 -0.263562 0.125613 +0.951558 -0.257089 -0.168647 +0.956359 0.263819 0.125605 +0.956359 0.263819 0.125605 +0.951558 -0.257089 -0.168647 +0.951499 0.257328 -0.168619 +0.086342 0.990400 -0.107949 +-0.089268 0.993198 0.074763 +0.089400 0.993189 0.074727 +-0.089268 0.993198 0.074763 +0.086342 0.990400 -0.107949 +-0.086212 0.990407 -0.107986 +-0.059645 0.051639 0.996883 +-0.178085 -0.324917 0.928824 +-0.059645 -0.051640 0.996883 +-0.178085 -0.324917 0.928824 +-0.059645 0.051639 0.996883 +-0.178122 0.324574 0.928937 +0.256743 -0.799623 0.542850 +-0.059645 -0.051640 0.996883 +-0.178085 -0.324917 0.928824 +-0.059645 -0.051640 0.996883 +0.256743 -0.799623 0.542850 +0.059645 -0.051639 0.996883 +0.178121 0.324575 0.928937 +0.059645 -0.051639 0.996883 +0.178086 -0.324915 0.928825 +0.059645 -0.051639 0.996883 +0.178121 0.324575 0.928937 +0.059645 0.051640 0.996883 +-0.256944 0.799388 0.543100 +0.059645 0.051640 0.996883 +0.178121 0.324575 0.928937 +0.059645 0.051640 0.996883 +-0.256944 0.799388 0.543100 +-0.059645 0.051639 0.996883 +-0.956754 0.286993 -0.047506 +-0.935847 -0.302400 0.180955 +-0.956902 -0.286501 -0.047494 +-0.935847 -0.302400 0.180955 +-0.956754 0.286993 -0.047506 +-0.935699 0.302882 0.180917 +-0.094927 -0.995157 -0.025505 +0.097942 -0.990243 0.099126 +0.094684 -0.995181 -0.025483 +0.097942 -0.990243 0.099126 +-0.094927 -0.995157 -0.025505 +-0.097945 -0.990243 0.099122 +0.957125 -0.285780 -0.047344 +0.935975 -0.302063 0.180856 +0.956974 0.286285 -0.047354 +0.956974 0.286285 -0.047354 +0.935975 -0.302063 0.180856 +0.935830 0.302532 0.180824 +0.094891 0.995160 -0.025542 +0.098119 0.990255 0.098831 +-0.095144 0.995135 -0.025563 +-0.095144 0.995135 -0.025563 +0.098119 0.990255 0.098831 +-0.098117 0.990255 0.098834 +0.673789 -0.697405 -0.244203 +0.226954 -0.935891 -0.269445 +0.000000 0.000000 1.000000 +0.226954 -0.935891 -0.269445 +0.673789 -0.697405 -0.244203 +0.000000 0.000000 1.000000 +-0.956341 0.264048 0.125261 +-0.951550 -0.257121 -0.168644 +-0.956450 -0.263645 0.125275 +-0.951550 -0.257121 -0.168644 +-0.956341 0.264048 0.125261 +-0.951446 0.257519 -0.168624 +-0.089283 -0.993155 0.075314 +-0.086285 -0.990402 -0.107976 +0.089316 -0.993153 0.075303 +0.089316 -0.993153 0.075303 +-0.086285 -0.990402 -0.107976 +0.086320 -0.990400 -0.107968 +0.956375 -0.263778 0.125574 +0.951481 -0.257288 -0.168778 +0.956265 0.264181 0.125560 +0.956265 0.264181 0.125560 +0.951481 -0.257288 -0.168778 +0.951378 0.257683 -0.168759 +0.089277 0.993155 0.075311 +-0.086253 0.990409 -0.107936 +-0.089247 0.993157 0.075321 +-0.086253 0.990409 -0.107936 +0.089277 0.993155 0.075311 +0.086286 0.990407 -0.107928 +-0.178425 0.325176 0.928668 +-0.059706 -0.051712 0.996876 +-0.059706 0.051713 0.996876 +-0.178425 0.325176 0.928668 +-0.178431 -0.325180 0.928666 +-0.059706 -0.051712 0.996876 +0.256999 -0.799754 0.542536 +-0.059706 -0.051712 0.996876 +-0.178431 -0.325180 0.928666 +-0.059706 -0.051712 0.996876 +0.256999 -0.799754 0.542536 +0.059722 -0.051734 0.996873 +0.178656 0.325122 0.928643 +0.059722 -0.051734 0.996873 +0.178585 -0.325143 0.928649 +0.059722 -0.051734 0.996873 +0.178656 0.325122 0.928643 +0.059722 0.051734 0.996874 +0.178656 0.325122 0.928643 +-0.256760 0.799853 0.542503 +-0.059706 0.051713 0.996876 +0.178656 0.325122 0.928643 +-0.059706 0.051713 0.996876 +0.059722 0.051734 0.996874 +-0.956947 0.286356 -0.047456 +-0.935859 0.302824 0.180182 +-0.956803 -0.286841 -0.047442 +-0.956803 -0.286841 -0.047442 +-0.935859 0.302824 0.180182 +-0.935721 -0.303220 0.180234 +-0.094809 -0.995169 -0.025488 +-0.097976 -0.990204 0.099478 +0.094855 -0.995165 -0.025491 +0.094855 -0.995165 -0.025491 +-0.097976 -0.990204 0.099478 +0.098011 -0.990200 0.099489 +0.957038 -0.286079 -0.047293 +0.935925 0.302646 0.180138 +0.957166 0.285648 -0.047304 +0.935925 0.302646 0.180138 +0.957038 -0.286079 -0.047293 +0.935784 -0.303054 0.180183 +0.095311 0.995118 -0.025619 +-0.098322 0.990228 0.098898 +-0.095272 0.995122 -0.025614 +-0.098322 0.990228 0.098898 +0.095311 0.995118 -0.025619 +0.098367 0.990224 0.098898 +0.673762 -0.697531 -0.243917 +0.226358 -0.936044 -0.269414 +0.000000 0.000000 1.000000 +0.226358 -0.936044 -0.269414 +0.673762 -0.697531 -0.243917 +0.000000 0.000000 1.000000 +-0.956289 0.263933 0.125901 +-0.951550 -0.257121 -0.168644 +-0.956398 -0.263530 0.125914 +-0.951550 -0.257121 -0.168644 +-0.956289 0.263933 0.125901 +-0.951446 0.257519 -0.168624 +-0.086211 -0.990407 -0.107986 +0.089337 -0.993152 0.075283 +-0.089204 -0.993161 0.075319 +0.089337 -0.993152 0.075283 +-0.086211 -0.990407 -0.107986 +0.086343 -0.990400 -0.107948 +0.956424 -0.263587 0.125595 +0.951550 -0.257123 -0.168644 +0.956315 0.263991 0.125581 +0.956315 0.263991 0.125581 +0.951550 -0.257123 -0.168644 +0.951446 0.257518 -0.168624 +0.086309 0.990407 -0.107909 +-0.089167 0.993164 0.075327 +0.089299 0.993155 0.075291 +-0.089167 0.993164 0.075327 +0.086309 0.990407 -0.107909 +-0.086179 0.990414 -0.107946 +-0.178090 0.325226 0.928715 +-0.059651 -0.051645 0.996882 +-0.059652 0.051644 0.996882 +-0.178090 0.325226 0.928715 +-0.178095 -0.325230 0.928713 +-0.059651 -0.051645 0.996882 +0.256694 -0.799886 0.542485 +-0.059651 -0.051645 0.996882 +-0.178095 -0.325230 0.928713 +-0.059651 -0.051645 0.996882 +0.256694 -0.799886 0.542485 +0.059652 -0.051644 0.996882 +0.178089 0.325227 0.928715 +0.059652 -0.051644 0.996882 +0.178095 -0.325229 0.928713 +0.059652 -0.051644 0.996882 +0.178089 0.325227 0.928715 +0.059651 0.051645 0.996882 +-0.256630 0.799822 0.542611 +0.059651 0.051645 0.996882 +0.178089 0.325227 0.928715 +0.059651 0.051645 0.996882 +-0.256630 0.799822 0.542611 +-0.059652 0.051644 0.996882 +-0.956880 0.286574 -0.047493 +-0.935838 0.302474 0.180875 +-0.956759 -0.286980 -0.047481 +-0.956759 -0.286980 -0.047481 +-0.935838 0.302474 0.180875 +-0.935700 -0.302870 0.180926 +-0.094892 -0.995161 -0.025495 +0.097974 -0.990204 0.099482 +0.094649 -0.995185 -0.025473 +0.097974 -0.990204 0.099482 +-0.094892 -0.995161 -0.025495 +-0.097976 -0.990204 0.099478 +0.956983 -0.286258 -0.047331 +0.935969 0.302125 0.180782 +0.957099 0.285866 -0.047341 +0.935969 0.302125 0.180782 +0.956983 -0.286258 -0.047331 +0.935829 -0.302532 0.180827 +0.095103 0.995138 -0.025600 +0.098324 0.990228 0.098895 +-0.095356 0.995113 -0.025622 +-0.095356 0.995113 -0.025622 +0.098324 0.990228 0.098895 +-0.098322 0.990228 0.098898 +0.673856 -0.697530 -0.243660 +0.226673 -0.935971 -0.269403 +0.000000 0.000000 1.000000 +0.226673 -0.935971 -0.269403 +0.673856 -0.697530 -0.243660 +0.000000 0.000000 1.000000 +-0.956352 0.263771 0.125762 +-0.951619 -0.256956 -0.168510 +-0.956461 -0.263369 0.125776 +-0.951619 -0.256956 -0.168510 +-0.956352 0.263771 0.125762 +-0.951515 0.257354 -0.168490 +-0.089353 -0.993150 0.075299 +0.086346 -0.990399 -0.107951 +0.089354 -0.993150 0.075299 +0.086346 -0.990399 -0.107951 +-0.089353 -0.993150 0.075299 +-0.086359 -0.990397 -0.107966 +0.956325 -0.263968 0.125553 +0.951413 -0.257453 -0.168912 +0.956215 0.264371 0.125539 +0.956215 0.264371 0.125539 +0.951413 -0.257453 -0.168912 +0.951309 0.257848 -0.168893 +0.089316 0.993152 0.075307 +0.086312 0.990407 -0.107912 +-0.089317 0.993152 0.075306 +-0.089317 0.993152 0.075306 +0.086312 0.990407 -0.107912 +-0.086327 0.990404 -0.107926 +-0.178271 0.325213 0.928685 +-0.059706 -0.051712 0.996876 +-0.059706 0.051711 0.996876 +-0.178271 0.325213 0.928685 +-0.178277 -0.325216 0.928683 +-0.059706 -0.051712 0.996876 +0.256917 -0.799827 0.542467 +-0.059706 -0.051712 0.996876 +-0.178277 -0.325216 0.928683 +-0.059706 -0.051712 0.996876 +0.256917 -0.799827 0.542467 +0.059652 -0.051644 0.996882 +0.178243 0.325190 0.928698 +0.059652 -0.051644 0.996882 +0.178249 -0.325192 0.928697 +0.059652 -0.051644 0.996882 +0.178243 0.325190 0.928698 +0.059651 0.051645 0.996882 +0.178243 0.325190 0.928698 +-0.256620 0.799901 0.542499 +-0.059706 0.051711 0.996876 +0.178243 0.325190 0.928698 +-0.059706 0.051711 0.996876 +0.059651 0.051645 0.996882 +-0.957030 0.286087 -0.047416 +-0.935837 0.303084 0.179859 +-0.956867 -0.286633 -0.047410 +-0.956867 -0.286633 -0.047410 +-0.935837 0.303084 0.179859 +-0.935699 -0.303480 0.179911 +-0.094954 -0.995155 -0.025518 +0.098066 -0.990195 0.099485 +0.094767 -0.995173 -0.025490 +0.098066 -0.990195 0.099485 +-0.094954 -0.995155 -0.025518 +-0.097939 -0.990209 0.099471 +0.956875 -0.286606 -0.047402 +0.936065 0.302173 0.180203 +0.957021 0.286115 -0.047424 +0.936065 0.302173 0.180203 +0.956875 -0.286606 -0.047402 +0.935925 -0.302580 0.180248 +0.095227 0.995126 -0.025611 +-0.098284 0.990233 0.098891 +-0.095347 0.995114 -0.025629 +-0.098284 0.990233 0.098891 +0.095227 0.995126 -0.025611 +0.098417 0.990219 0.098898 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.226395 -0.936031 -0.269427 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.673754 -0.697512 -0.243992 +-0.956396 0.263599 0.125785 +-0.951627 -0.256922 -0.168514 +-0.956465 -0.263343 0.125794 +-0.951627 -0.256922 -0.168514 +-0.956396 0.263599 0.125785 +-0.951567 0.257165 -0.168484 +-0.089186 -0.993223 0.074520 +0.086118 -0.990449 -0.107673 +0.089186 -0.993223 0.074520 +0.086118 -0.990449 -0.107673 +-0.089186 -0.993223 0.074520 +-0.086131 -0.990447 -0.107688 +0.956330 -0.263943 0.125571 +0.951421 -0.257419 -0.168916 +0.956260 0.264199 0.125562 +0.956260 0.264199 0.125562 +0.951421 -0.257419 -0.168916 +0.951362 0.257659 -0.168887 +0.089417 0.993186 0.074743 +0.086345 0.990399 -0.107952 +-0.089418 0.993186 0.074743 +-0.089418 0.993186 0.074743 +0.086345 0.990399 -0.107952 +-0.086360 0.990397 -0.107965 +-0.178304 0.324561 0.928907 +-0.059699 -0.051708 0.996876 +-0.059699 0.051707 0.996876 +-0.178304 0.324561 0.928907 +-0.178267 -0.324903 0.928794 +-0.059699 -0.051708 0.996876 +0.256966 -0.799563 0.542832 +-0.059699 -0.051708 0.996876 +-0.178267 -0.324903 0.928794 +-0.059699 -0.051708 0.996876 +0.256966 -0.799563 0.542832 +0.059645 -0.051639 0.996883 +0.178275 0.324538 0.928920 +0.059645 -0.051639 0.996883 +0.178239 -0.324879 0.928808 +0.059645 -0.051639 0.996883 +0.178275 0.324538 0.928920 +0.059645 0.051640 0.996883 +0.178275 0.324538 0.928920 +-0.256935 0.799467 0.542989 +-0.059699 0.051707 0.996876 +0.178275 0.324538 0.928920 +-0.059699 0.051707 0.996876 +0.059645 0.051640 0.996883 +-0.956866 0.286632 -0.047435 +-0.935846 -0.303009 0.179939 +-0.956902 -0.286501 -0.047494 +-0.935846 -0.303009 0.179939 +-0.956866 0.286632 -0.047435 +-0.935697 0.303492 0.179901 +-0.095030 -0.995147 -0.025535 +0.098035 -0.990234 0.099129 +0.094837 -0.995166 -0.025510 +0.098035 -0.990234 0.099129 +-0.095030 -0.995147 -0.025535 +-0.097908 -0.990248 0.099115 +0.957016 -0.286134 -0.047418 +0.935926 0.302580 0.180245 +0.956863 0.286642 -0.047436 +0.935926 0.302580 0.180245 +0.957016 -0.286134 -0.047418 +0.936071 -0.302110 0.180277 +0.094939 0.995156 -0.025539 +0.098212 0.990246 0.098834 +-0.095136 0.995136 -0.025567 +-0.095136 0.995136 -0.025567 +0.098212 0.990246 0.098834 +-0.098079 0.990259 0.098827 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.226723 -0.935942 -0.269462 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.673674 -0.697371 -0.244617 +-0.956385 0.263876 0.125285 +-0.951559 -0.257087 -0.168648 +-0.956455 -0.263620 0.125293 +-0.951559 -0.257087 -0.168648 +-0.956385 0.263876 0.125285 +-0.951498 0.257330 -0.168618 +-0.089116 -0.993229 0.074535 +0.086092 -0.990450 -0.107689 +0.089148 -0.993226 0.074524 +0.086092 -0.990450 -0.107689 +-0.089116 -0.993229 0.074535 +-0.086054 -0.990453 -0.107695 +0.956379 -0.263753 0.125592 +0.951490 -0.257253 -0.168783 +0.956260 0.264199 0.125562 +0.956260 0.264199 0.125562 +0.951490 -0.257253 -0.168783 +0.951362 0.257659 -0.168887 +0.089378 0.993189 0.074747 +-0.086283 0.990403 -0.107973 +-0.089348 0.993191 0.074758 +-0.086283 0.990403 -0.107973 +0.089378 0.993189 0.074747 +0.086319 0.990400 -0.107968 +-0.178472 0.324536 0.928883 +-0.059699 -0.051708 0.996876 +-0.059699 0.051708 0.996876 +-0.178472 0.324536 0.928883 +-0.178435 -0.324879 0.928771 +-0.059699 -0.051708 0.996876 +0.257002 -0.799500 0.542909 +-0.059699 -0.051708 0.996876 +-0.178435 -0.324879 0.928771 +-0.059699 -0.051708 0.996876 +0.257002 -0.799500 0.542909 +0.059731 -0.051751 0.996872 +0.178702 0.324482 0.928858 +0.059731 -0.051751 0.996872 +0.178666 -0.324823 0.928746 +0.059731 -0.051751 0.996872 +0.178702 0.324482 0.928858 +0.059731 0.051751 0.996872 +0.178702 0.324482 0.928858 +-0.256990 0.799500 0.542914 +-0.059699 0.051708 0.996876 +0.178702 0.324482 0.928858 +-0.059699 0.051708 0.996876 +0.059731 0.051751 0.996872 +-0.956757 0.286982 -0.047514 +-0.935868 -0.302749 0.180262 +-0.956956 -0.286326 -0.047458 +-0.935868 -0.302749 0.180262 +-0.956757 0.286982 -0.047514 +-0.935719 0.303231 0.180224 +-0.094845 -0.995166 -0.025498 +-0.097945 -0.990243 0.099122 +0.094967 -0.995153 -0.025514 +0.094967 -0.995153 -0.025514 +-0.097945 -0.990243 0.099122 +0.097986 -0.990238 0.099129 +0.957180 -0.285601 -0.047306 +0.935931 -0.302584 0.180211 +0.957030 0.286102 -0.047321 +0.957030 0.286102 -0.047321 +0.935931 -0.302584 0.180211 +0.935785 0.303054 0.180179 +0.095140 0.995136 -0.025563 +-0.098117 0.990255 0.098834 +-0.095138 0.995136 -0.025569 +-0.098117 0.990255 0.098834 +0.095140 0.995136 -0.025563 +0.098162 0.990250 0.098834 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.226665 -0.935948 -0.269490 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.673679 -0.697392 -0.244541 +-0.985878 0.095453 -0.137597 +-0.785782 0.352552 -0.508188 +-0.948297 0.180918 -0.260770 +0.188900 -0.559726 0.806860 +0.117083 -0.566086 0.815989 +-0.117067 -0.566069 0.816003 +-0.117067 -0.566069 0.816003 +-0.400048 -0.522404 0.753031 +-0.188881 -0.559749 0.806849 +0.949914 -0.178127 0.256776 +0.986163 -0.094499 0.136209 +0.985921 0.095316 -0.137386 +0.948917 0.179845 -0.259252 +0.985921 0.095316 -0.137386 +0.986163 -0.094499 0.136209 +0.118984 0.565957 -0.815803 +-0.402828 0.521709 -0.752030 +-0.191917 0.559413 -0.806365 +-0.402828 0.521709 -0.752030 +0.118984 0.565957 -0.815803 +-0.118970 0.565940 -0.815818 +-0.986592 -0.090992 0.135485 +-0.986292 0.090913 -0.137707 +-0.949902 0.172190 -0.260838 +-0.986592 -0.090992 0.135485 +-0.949886 -0.174273 0.259509 +-0.986292 0.090913 -0.137707 +-0.127399 -0.552974 0.823401 +0.187097 -0.547674 0.815505 +0.127645 -0.552942 0.823384 +0.187097 -0.547674 0.815505 +-0.127399 -0.552974 0.823401 +-0.187114 -0.547656 0.815513 +0.950045 0.171961 -0.260470 +0.793917 0.334985 -0.507425 +0.986635 -0.090843 0.135274 +0.949880 -0.174293 0.259518 +0.986635 -0.090843 0.135274 +0.793917 0.334985 -0.507425 +-0.128212 0.546391 -0.827659 +-0.189856 0.540902 -0.819378 +0.128199 0.546376 -0.827670 +0.128199 0.546376 -0.827670 +-0.189856 0.540902 -0.819378 +0.190238 0.540878 -0.819305 +-0.952583 -0.166438 -0.254722 +-0.790247 -0.335178 -0.512997 +-0.985580 0.092551 0.141657 +-0.951152 0.168869 0.258442 +-0.985580 0.092551 0.141657 +-0.790247 -0.335178 -0.512997 +-0.191430 -0.536859 -0.821668 +-0.119608 -0.543026 -0.831154 +0.191447 -0.536835 -0.821679 +0.191447 -0.536835 -0.821679 +-0.119608 -0.543026 -0.831154 +0.119633 -0.543044 -0.831139 +0.985626 0.092411 0.141429 +0.985872 -0.091621 -0.140219 +0.952724 -0.166185 -0.254363 +0.985626 0.092411 0.141429 +0.951738 0.167865 0.256935 +0.985872 -0.091621 -0.140219 +-0.194528 0.536525 0.821157 +0.121217 0.542938 0.830978 +0.194545 0.536501 0.821169 +0.121217 0.542938 0.830978 +-0.194528 0.536525 0.821157 +-0.121214 0.542919 0.830991 +-0.985878 0.095453 -0.137597 +-0.785836 0.352512 -0.508131 +-0.948300 0.180912 -0.260762 +0.189033 -0.559712 0.806839 +0.117169 -0.566081 0.815981 +-0.116913 -0.566079 0.816018 +-0.116913 -0.566079 0.816018 +-0.399963 -0.522425 0.753061 +-0.188687 -0.559770 0.806880 +0.949519 -0.178811 0.257762 +0.986075 -0.094797 0.136638 +0.985809 0.095692 -0.137928 +0.948612 0.180368 -0.260006 +0.985809 0.095692 -0.137928 +0.986075 -0.094797 0.136638 +0.119011 0.565956 -0.815801 +-0.402699 0.521741 -0.752077 +-0.191627 0.559445 -0.806412 +-0.402699 0.521741 -0.752077 +0.119011 0.565956 -0.815801 +-0.118817 0.565950 -0.815833 +-0.986517 -0.091247 0.135864 +-0.986322 0.090812 -0.137555 +-0.949604 0.172688 -0.261593 +-0.986517 -0.091247 0.135864 +-0.949961 -0.174146 0.259320 +-0.986322 0.090812 -0.137555 +-0.127234 -0.552986 0.823418 +0.187154 -0.547668 0.815496 +0.127630 -0.552943 0.823386 +0.187154 -0.547668 0.815496 +-0.127234 -0.552986 0.823418 +-0.186852 -0.547684 0.815554 +0.950054 0.171945 -0.260445 +0.793896 0.335000 -0.507449 +0.986635 -0.090843 0.135274 +0.949890 -0.174277 0.259494 +0.986635 -0.090843 0.135274 +0.793896 0.335000 -0.507449 +-0.128057 0.546402 -0.827676 +-0.189613 0.540928 -0.819417 +0.128240 0.546373 -0.827666 +0.128240 0.546373 -0.827666 +-0.189613 0.540928 -0.819417 +0.190188 0.540884 -0.819313 +-0.952535 -0.166521 -0.254848 +-0.790176 -0.335228 -0.513074 +-0.985558 0.092622 0.141765 +-0.951117 0.168929 0.258533 +-0.985558 0.092622 0.141765 +-0.790176 -0.335228 -0.513074 +-0.191162 -0.536887 -0.821711 +-0.119490 -0.543033 -0.831166 +0.191647 -0.536814 -0.821646 +0.191647 -0.536814 -0.821646 +-0.119490 -0.543033 -0.831166 +0.119703 -0.543039 -0.831132 +0.985542 0.092678 0.141836 +0.985795 -0.091868 -0.140598 +0.952450 -0.166654 -0.255081 +0.985542 0.092678 0.141836 +0.951478 0.168306 0.257610 +0.985795 -0.091868 -0.140598 +-0.194599 0.536518 0.821146 +0.121481 0.542921 0.830951 +0.194915 0.536461 0.821107 +0.121481 0.542921 0.830951 +-0.194599 0.536518 0.821146 +-0.121183 0.542921 0.830994 +-0.985856 0.095525 -0.137702 +-0.785680 0.352625 -0.508294 +-0.948300 0.180912 -0.260762 +0.188901 -0.559726 0.806860 +0.117160 -0.566081 0.815982 +-0.116875 -0.566082 0.816022 +-0.949680 -0.178545 0.257350 +-0.399920 -0.522436 0.753077 +-0.116875 -0.566082 0.816022 +-0.116875 -0.566082 0.816022 +-0.399920 -0.522436 0.753077 +-0.188554 -0.559785 0.806901 +0.949368 -0.179071 0.258136 +0.986032 -0.094942 0.136847 +0.985776 0.095802 -0.138086 +0.948459 0.180629 -0.260382 +0.985776 0.095802 -0.138086 +0.986032 -0.094942 0.136847 +0.118945 0.565960 -0.815807 +-0.402578 0.521772 -0.752120 +-0.191581 0.559451 -0.806419 +-0.402578 0.521772 -0.752120 +0.118945 0.565960 -0.815807 +-0.118740 0.565955 -0.815840 +-0.986509 -0.091273 0.135901 +-0.986344 0.090742 -0.137449 +-0.949604 0.172688 -0.261593 +-0.986509 -0.091273 0.135901 +-0.950036 -0.174020 0.259132 +-0.986344 0.090742 -0.137449 +-0.127197 -0.552989 0.823422 +0.187102 -0.547673 0.815504 +0.127672 -0.552940 0.823381 +0.187102 -0.547673 0.815504 +-0.127197 -0.552989 0.823422 +-0.186917 -0.547677 0.815544 +0.949970 0.172086 -0.260659 +0.793655 0.335173 -0.507711 +0.986614 -0.090913 0.135379 +0.949731 -0.174546 0.259895 +0.986614 -0.090913 0.135379 +0.793655 0.335173 -0.507711 +-0.128090 0.546399 -0.827672 +-0.189482 0.540942 -0.819438 +0.128198 0.546376 -0.827670 +0.128198 0.546376 -0.827670 +-0.189482 0.540942 -0.819438 +0.190254 0.540877 -0.819302 +-0.952463 -0.166645 -0.255038 +-0.790096 -0.335284 -0.513160 +-0.985535 0.092693 0.141874 +-0.951044 0.169051 0.258720 +-0.985535 0.092693 0.141874 +-0.790096 -0.335284 -0.513160 +-0.191225 -0.536880 -0.821701 +-0.119451 -0.543036 -0.831170 +0.191581 -0.536821 -0.821657 +0.191581 -0.536821 -0.821657 +-0.119451 -0.543036 -0.831170 +0.119781 -0.543034 -0.831124 +0.985512 0.092773 0.141981 +0.985722 -0.092103 -0.140957 +0.952378 -0.166776 -0.255268 +0.985512 0.092773 0.141981 +0.951260 0.168674 0.258173 +0.985722 -0.092103 -0.140957 +-0.194551 0.536523 0.821154 +0.121467 0.542922 0.830952 +0.195050 0.536446 0.821085 +0.121467 0.542922 0.830952 +-0.194551 0.536523 0.821154 +-0.121223 0.542918 0.830990 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.167885 0.000000 -0.985807 +0.167809 0.000000 -0.985819 +0.167818 0.000000 -0.985818 +0.167809 0.000000 -0.985819 +-0.167885 0.000000 -0.985807 +-0.167884 0.000000 -0.985807 +0.167832 0.000000 0.985816 +-0.167908 0.000000 0.985803 +0.167841 0.000000 0.985814 +-0.167908 0.000000 0.985803 +0.167832 0.000000 0.985816 +-0.167907 0.000000 0.985803 +-0.973544 0.000000 0.228498 +-0.973536 0.000000 -0.228534 +-0.973544 0.000000 0.228500 +-0.973544 0.000000 0.228500 +-0.973536 0.000000 -0.228534 +-0.973535 0.000000 -0.228536 +0.005896 -0.999955 0.007463 +-0.005899 -0.999955 0.007463 +-0.005899 -0.999955 -0.007465 +0.005896 -0.999955 0.007463 +-0.005899 -0.999955 -0.007465 +0.005896 -0.999955 -0.007465 +0.973508 0.000000 0.228655 +0.973493 0.000001 -0.228717 +0.973502 0.000001 0.228679 +0.973502 0.000001 0.228679 +0.973493 0.000001 -0.228717 +0.973487 0.000000 -0.228740 +-0.005894 0.999955 0.007457 +0.005901 0.999955 0.007469 +0.005900 0.999955 -0.007472 +-0.005894 0.999955 0.007457 +0.005900 0.999955 -0.007472 +-0.005894 0.999955 -0.007458 +0.119255 -0.230420 -0.965756 +-0.119296 -0.230417 -0.965752 +-0.119294 0.230486 -0.965736 +0.119255 -0.230420 -0.965756 +-0.119294 0.230486 -0.965736 +0.119260 0.230488 -0.965739 +-0.119278 0.230454 0.965745 +0.119256 -0.230416 0.965757 +0.119256 0.230498 0.965737 +0.119256 -0.230416 0.965757 +-0.119278 0.230454 0.965745 +-0.119277 -0.230394 0.965759 +-0.951550 -0.257151 0.168601 +-0.951532 0.257219 0.168599 +-0.951533 0.257221 -0.168588 +-0.951550 -0.257151 0.168601 +-0.951533 0.257221 -0.168588 +-0.951551 -0.257152 -0.168590 +-0.086139 -0.990439 0.107754 +0.086113 -0.990440 -0.107764 +0.086114 -0.990440 0.107763 +0.086113 -0.990440 -0.107764 +-0.086139 -0.990439 0.107754 +-0.086140 -0.990440 -0.107745 +0.951475 0.257352 0.168716 +0.951493 -0.257284 0.168719 +0.951494 -0.257282 -0.168717 +0.951475 0.257352 0.168716 +0.951494 -0.257282 -0.168717 +0.951476 0.257351 -0.168714 +-0.086168 0.990433 0.107786 +0.086136 0.990435 0.107787 +0.086133 0.990435 -0.107791 +-0.086168 0.990433 0.107786 +0.086133 0.990435 -0.107791 +-0.086168 0.990433 -0.107781 +0.119237 -0.230393 -0.965765 +-0.119278 -0.230390 -0.965760 +-0.119276 0.230459 -0.965744 +0.119237 -0.230393 -0.965765 +-0.119276 0.230459 -0.965744 +0.119242 0.230461 -0.965748 +-0.119295 0.230481 0.965737 +0.119256 -0.230416 0.965757 +0.119256 0.230498 0.965737 +0.119256 -0.230416 0.965757 +-0.119295 0.230481 0.965737 +-0.119295 -0.230422 0.965751 +-0.951533 0.257221 -0.168588 +-0.951551 -0.257151 0.168595 +-0.951533 0.257219 0.168593 +-0.951551 -0.257151 0.168595 +-0.951533 0.257221 -0.168588 +-0.951551 -0.257152 -0.168590 +-0.086139 -0.990439 0.107750 +0.086113 -0.990440 -0.107764 +0.086115 -0.990441 0.107752 +0.086113 -0.990440 -0.107764 +-0.086139 -0.990439 0.107750 +-0.086140 -0.990440 -0.107745 +0.951496 -0.257286 0.168702 +0.951476 0.257351 -0.168714 +0.951477 0.257354 0.168699 +0.951476 0.257351 -0.168714 +0.951496 -0.257286 0.168702 +0.951494 -0.257282 -0.168717 +-0.086168 0.990433 0.107782 +0.086137 0.990437 0.107776 +0.086133 0.990435 -0.107791 +-0.086168 0.990433 0.107782 +0.086133 0.990435 -0.107791 +-0.086168 0.990433 -0.107781 +0.119255 -0.230420 -0.965756 +-0.119296 -0.230417 -0.965752 +-0.119294 0.230486 -0.965736 +0.119255 -0.230420 -0.965756 +-0.119294 0.230486 -0.965736 +0.119260 0.230488 -0.965739 +-0.119261 0.230427 0.965754 +0.119221 -0.230362 0.965774 +0.119222 0.230444 0.965755 +0.119221 -0.230362 0.965774 +-0.119261 0.230427 0.965754 +-0.119260 -0.230367 0.965768 +-0.951548 -0.257149 0.168612 +-0.951530 0.257217 0.168610 +-0.951533 0.257221 -0.168588 +-0.951548 -0.257149 0.168612 +-0.951533 0.257221 -0.168588 +-0.951551 -0.257152 -0.168590 +0.086114 -0.990440 0.107763 +-0.086138 -0.990438 0.107762 +-0.086140 -0.990440 -0.107745 +0.086114 -0.990440 0.107763 +-0.086140 -0.990440 -0.107745 +0.086114 -0.990441 -0.107757 +0.951475 0.257352 0.168716 +0.951493 -0.257284 0.168719 +0.951495 -0.257285 -0.168707 +0.951475 0.257352 0.168716 +0.951495 -0.257285 -0.168707 +0.951477 0.257353 -0.168704 +-0.086168 0.990432 0.107794 +0.086136 0.990436 0.107787 +0.086134 0.990436 -0.107784 +-0.086168 0.990432 0.107794 +0.086134 0.990436 -0.107784 +-0.086168 0.990433 -0.107781 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.002425 0.999997 0.000000 +0.000000 0.000000 1.000000 +0.002423 -0.999997 -0.000001 +0.002423 -0.999997 -0.000001 +0.002423 -0.999997 -0.000001 +0.002423 -0.999997 -0.000001 +0.002423 -0.999997 0.000000 +0.002423 -0.999997 -0.000001 +-0.999985 -0.005401 0.000013 +-0.999985 -0.005401 0.000013 +-0.999985 -0.005401 0.000013 +-0.999985 -0.005401 0.000013 +-0.999985 -0.005401 0.000013 +-0.999985 -0.005405 0.000008 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +0.999985 0.005403 0.000000 +0.999985 0.005403 0.000000 +0.999985 0.005403 0.000000 +0.999985 0.005403 0.000000 +0.999985 0.005403 0.000000 +0.999985 0.005403 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.002424 0.999997 0.000000 +0.000000 0.000000 1.000000 +0.002423 -0.999997 0.000000 +0.002423 -0.999997 0.000000 +0.002423 -0.999997 0.000000 +0.002423 -0.999997 0.000000 +0.002423 -0.999997 0.000000 +0.002423 -0.999997 0.000000 +-0.999985 -0.005408 0.000005 +-0.999985 -0.005408 0.000005 +-0.999985 -0.005408 0.000005 +-0.999985 -0.005408 0.000005 +-0.999985 -0.005408 0.000005 +-0.999985 -0.005412 0.000000 +-0.002423 0.999997 0.000000 +-0.002423 0.999997 0.000000 +-0.002423 0.999997 0.000000 +-0.002423 0.999997 0.000000 +-0.002423 0.999997 0.000000 +-0.002423 0.999997 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.002425 0.999997 0.000000 +0.000000 0.000000 1.000000 +0.002423 -0.999997 -0.000001 +0.002423 -0.999997 -0.000001 +0.002423 -0.999997 -0.000001 +0.002423 -0.999997 -0.000001 +0.002423 -0.999997 0.000000 +0.002423 -0.999997 -0.000001 +-0.999985 -0.005401 0.000013 +-0.999985 -0.005401 0.000013 +-0.999985 -0.005401 0.000013 +-0.999985 -0.005401 0.000013 +-0.999985 -0.005401 0.000013 +-0.999985 -0.005405 0.000008 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +0.909584 -0.415520 -0.000001 +0.909584 -0.415520 0.000000 +0.909584 -0.415520 0.000000 +0.909584 -0.415520 0.000000 +0.909584 -0.415520 0.000000 +0.909584 -0.415520 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.418241 0.908336 -0.000001 +0.000000 0.000000 1.000000 +-0.418235 -0.908339 -0.000001 +-0.418235 -0.908339 -0.000001 +-0.418235 -0.908339 -0.000001 +-0.418235 -0.908339 -0.000001 +-0.418234 -0.908339 0.000000 +-0.418235 -0.908339 -0.000001 +-0.909581 0.415526 0.000014 +-0.909583 0.415522 0.000009 +-0.909581 0.415526 0.000014 +-0.909583 0.415522 0.000009 +-0.909581 0.415526 0.000014 +-0.909581 0.415526 0.000014 +0.418236 0.908339 0.000000 +0.418235 0.908339 -0.000001 +0.418235 0.908339 -0.000001 +0.418235 0.908339 -0.000001 +0.418235 0.908339 -0.000001 +0.418235 0.908339 -0.000001 +-0.001817 -0.999998 0.000000 +-0.001819 -0.999998 -0.000006 +-0.001819 -0.999998 -0.000006 +-0.001819 -0.999998 -0.000006 +-0.001819 -0.999998 -0.000006 +-0.001819 -0.999998 -0.000006 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.999998 -0.001816 0.000000 +0.999998 -0.001816 0.000000 +0.999998 -0.001816 0.000000 +0.999998 -0.001816 0.000000 +0.999998 -0.001816 0.000000 +0.999998 -0.001816 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999998 0.001829 0.000000 +-0.999998 0.001829 0.000000 +-0.999998 0.001829 0.000000 +-0.999998 0.001829 0.000000 +-0.999998 0.001829 0.000000 +-0.999998 0.001829 0.000000 +0.001816 0.999998 0.000004 +0.001818 0.999998 -0.000004 +0.001818 0.999998 -0.000004 +0.001818 0.999998 -0.000004 +0.001818 0.999998 -0.000004 +0.001818 0.999998 -0.000004 +-0.001817 -0.999998 0.000000 +-0.001819 -0.999998 -0.000006 +-0.001819 -0.999998 -0.000006 +-0.001819 -0.999998 -0.000006 +-0.001819 -0.999998 -0.000006 +-0.001819 -0.999998 -0.000006 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.999998 -0.001816 0.000000 +0.999998 -0.001816 0.000000 +0.999998 -0.001816 0.000000 +0.999998 -0.001816 0.000000 +0.999998 -0.001816 0.000000 +0.999998 -0.001816 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999998 0.001829 0.000000 +-0.999998 0.001829 0.000000 +-0.999998 0.001829 0.000000 +-0.999998 0.001829 0.000000 +-0.999998 0.001829 0.000000 +-0.999998 0.001829 0.000000 +0.001816 0.999998 0.000004 +0.001818 0.999998 -0.000004 +0.001818 0.999998 -0.000004 +0.001818 0.999998 -0.000004 +0.001818 0.999998 -0.000004 +0.001818 0.999998 -0.000004 +-0.001817 -0.999998 0.000000 +-0.001819 -0.999998 -0.000006 +-0.001819 -0.999998 -0.000006 +-0.001819 -0.999998 -0.000006 +-0.001819 -0.999998 -0.000006 +-0.001819 -0.999998 -0.000006 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.999998 -0.001816 0.000000 +0.999998 -0.001816 0.000000 +0.999998 -0.001816 0.000000 +0.999998 -0.001816 0.000000 +0.999998 -0.001816 0.000000 +0.999998 -0.001816 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999998 0.001829 0.000000 +-0.999998 0.001829 0.000000 +-0.999998 0.001829 0.000000 +-0.999998 0.001829 0.000000 +-0.999998 0.001829 0.000000 +-0.999998 0.001829 0.000000 +0.001816 0.999998 -0.000004 +0.001818 0.999998 0.000004 +0.001816 0.999998 -0.000004 +0.001816 0.999998 -0.000004 +0.001816 0.999998 -0.000004 +0.001816 0.999998 -0.000004 +0.999998 -0.001817 0.000000 +0.999998 -0.001819 -0.000006 +0.999998 -0.001819 -0.000006 +0.999998 -0.001819 -0.000006 +0.999998 -0.001819 -0.000006 +0.999998 -0.001819 -0.000006 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.001816 0.999998 0.000000 +0.001816 0.999998 0.000000 +0.001816 0.999998 0.000000 +0.001816 0.999998 0.000000 +0.001816 0.999998 0.000000 +0.001816 0.999998 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000001 0.000000 1.000000 +-0.001829 -0.999998 0.000000 +-0.001829 -0.999998 0.000000 +-0.001829 -0.999998 0.000000 +-0.001829 -0.999998 0.000000 +-0.001829 -0.999998 0.000000 +-0.001829 -0.999998 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001817 -0.000006 +-0.999998 0.001817 -0.000006 +-0.999998 0.001817 -0.000006 +-0.999998 0.001817 -0.000006 +-0.999998 0.001817 -0.000006 +-0.999998 0.001817 0.000000 +-0.999998 0.001819 -0.000006 +-0.999998 0.001819 -0.000006 +-0.999998 0.001819 -0.000006 +-0.999998 0.001819 -0.000006 +-0.999998 0.001819 -0.000006 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.001816 -0.999998 0.000000 +-0.001816 -0.999998 0.000000 +-0.001816 -0.999998 0.000000 +-0.001816 -0.999998 0.000000 +-0.001816 -0.999998 0.000000 +-0.001816 -0.999998 0.000000 +-0.000001 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.001829 0.999998 0.000000 +0.001829 0.999998 0.000000 +0.001829 0.999998 0.000000 +0.001829 0.999998 0.000000 +0.001829 0.999998 0.000000 +0.001829 0.999998 0.000000 +0.999998 -0.001816 0.000000 +0.999998 -0.001817 -0.000006 +0.999998 -0.001817 -0.000006 +0.999998 -0.001817 -0.000006 +0.999998 -0.001817 -0.000006 +0.999998 -0.001817 -0.000006 +0.999998 -0.001817 0.000000 +0.999998 -0.001819 -0.000006 +0.999998 -0.001819 -0.000006 +0.999998 -0.001819 -0.000006 +0.999998 -0.001819 -0.000006 +0.999998 -0.001819 -0.000006 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.001816 0.999998 0.000000 +0.001816 0.999998 0.000000 +0.001816 0.999998 0.000000 +0.001816 0.999998 0.000000 +0.001816 0.999998 0.000000 +0.001816 0.999998 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000001 0.000000 1.000000 +-0.001829 -0.999998 0.000000 +-0.001829 -0.999998 0.000000 +-0.001829 -0.999998 0.000000 +-0.001829 -0.999998 0.000000 +-0.001829 -0.999998 0.000000 +-0.001829 -0.999998 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001817 -0.000006 +-0.999998 0.001817 -0.000006 +-0.999998 0.001817 -0.000006 +-0.999998 0.001817 -0.000006 +-0.999998 0.001817 -0.000006 +0.001817 0.999998 0.000000 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000001 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +-0.001816 -0.999998 0.000000 +-0.001817 -0.999998 -0.000006 +-0.001817 -0.999998 -0.000006 +-0.001817 -0.999998 -0.000006 +-0.001817 -0.999998 -0.000006 +-0.001817 -0.999998 -0.000006 +0.195313 0.980741 0.000000 +0.195315 0.980741 -0.000007 +0.195315 0.980741 -0.000007 +0.195315 0.980741 -0.000007 +0.195313 0.980741 0.000000 +0.195315 0.980740 -0.000007 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.980741 0.195313 0.000005 +-0.980741 0.195313 0.000005 +-0.980741 0.195313 0.000005 +-0.980741 0.195313 0.000005 +-0.980741 0.195313 0.000005 +-0.980741 0.195311 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000001 0.000001 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.980738 -0.195326 -0.000002 +0.980738 -0.195326 -0.000002 +0.980738 -0.195326 -0.000002 +0.980738 -0.195326 -0.000002 +0.980738 -0.195326 -0.000002 +0.980738 -0.195327 0.000000 +-0.195311 -0.980741 -0.000009 +-0.195311 -0.980741 -0.000009 +-0.195313 -0.980741 0.000000 +-0.195311 -0.980741 -0.000009 +-0.195311 -0.980741 -0.000009 +-0.195311 -0.980741 -0.000009 +0.001817 0.999998 0.000000 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +-0.001816 -0.999998 0.000004 +-0.001818 -0.999998 -0.000004 +-0.001818 -0.999998 -0.000004 +-0.001818 -0.999998 -0.000004 +-0.001816 -0.999998 0.000004 +-0.001818 -0.999998 -0.000004 +0.001817 0.999998 0.000000 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +-0.001816 -0.999998 -0.000004 +-0.001818 -0.999998 0.000004 +-0.001816 -0.999998 -0.000004 +-0.001816 -0.999998 -0.000004 +-0.001816 -0.999998 -0.000004 +-0.001816 -0.999998 -0.000004 +0.001817 0.999998 0.000000 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +-0.001816 -0.999998 0.000004 +-0.001818 -0.999998 -0.000004 +-0.001818 -0.999998 -0.000004 +-0.001818 -0.999998 -0.000004 +-0.001816 -0.999998 0.000004 +-0.001818 -0.999998 -0.000004 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.000001 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.165043 -0.986286 0.000000 +-0.165043 -0.986286 0.000000 +-0.165043 -0.986286 0.000000 +-0.165043 -0.986286 0.000000 +-0.165043 -0.986286 0.000000 +-0.165043 -0.986286 0.000000 +0.986286 -0.165047 0.000000 +0.986286 -0.165047 0.000000 +0.986286 -0.165047 0.000000 +0.986286 -0.165047 0.000000 +0.986286 -0.165047 0.000000 +0.986286 -0.165047 0.000000 +0.165043 0.986286 0.000000 +0.165043 0.986286 0.000000 +0.165043 0.986286 0.000000 +0.165043 0.986286 0.000000 +0.165043 0.986286 0.000000 +0.165043 0.986286 0.000000 +-0.986286 0.165049 0.000000 +-0.986285 0.165049 0.000000 +-0.986285 0.165048 0.000000 +-0.986286 0.165049 0.000000 +-0.986285 0.165048 0.000000 +-0.986285 0.165049 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.165043 -0.986286 0.000000 +-0.165043 -0.986286 0.000000 +-0.165043 -0.986286 0.000000 +-0.165043 -0.986286 0.000000 +-0.165043 -0.986286 0.000000 +-0.165043 -0.986286 0.000000 +0.986286 -0.165047 0.000000 +0.986286 -0.165047 0.000000 +0.986286 -0.165047 0.000000 +0.986286 -0.165047 0.000000 +0.986286 -0.165047 0.000000 +0.986286 -0.165047 0.000000 +0.165043 0.986286 0.000000 +0.165043 0.986286 0.000000 +0.165043 0.986286 0.000000 +0.165043 0.986286 0.000000 +0.165043 0.986286 0.000000 +0.165043 0.986286 0.000000 +-0.986285 0.165048 0.000000 +-0.986285 0.165048 0.000000 +-0.986285 0.165048 0.000000 +-0.986285 0.165048 0.000000 +-0.986285 0.165048 0.000000 +-0.986285 0.165048 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-0.000001 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000001 0.000000 1.000000 +-0.000001 0.000000 1.000000 +0.000001 0.000000 1.000000 +-0.000001 0.000000 1.000000 +-0.000001 0.000000 1.000000 +-0.000001 0.000000 1.000000 +-0.980131 -0.198351 0.000000 +-0.980131 -0.198351 0.000000 +-0.980131 -0.198351 0.000000 +-0.980131 -0.198351 0.000000 +-0.980131 -0.198351 0.000000 +-0.980131 -0.198351 0.000000 +0.198346 -0.980132 0.000000 +0.198346 -0.980132 0.000000 +0.198346 -0.980132 0.000000 +0.198346 -0.980132 0.000000 +0.198346 -0.980132 0.000000 +0.198346 -0.980132 0.000000 +0.980131 0.198351 0.000000 +0.980131 0.198351 0.000000 +0.980131 0.198351 0.000000 +0.980131 0.198351 0.000000 +0.980131 0.198351 0.000000 +0.980131 0.198351 0.000000 +-0.198345 0.980132 0.000000 +-0.198345 0.980132 0.000000 +-0.198345 0.980132 0.000000 +-0.198345 0.980132 0.000000 +-0.198345 0.980132 0.000000 +-0.198345 0.980132 0.000000 +-0.000001 0.000000 -1.000000 +-0.000001 0.000000 -1.000000 +-0.000001 0.000000 -1.000000 +-0.000001 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000001 0.000000 -1.000000 +0.000000 -0.000001 1.000000 +0.000000 -0.000001 1.000000 +0.000000 -0.000001 1.000000 +0.000000 -0.000001 1.000000 +0.000000 -0.000001 1.000000 +0.000000 -0.000001 1.000000 +-0.980131 -0.198351 0.000000 +-0.980131 -0.198351 0.000000 +-0.980131 -0.198351 0.000000 +-0.980131 -0.198351 0.000000 +-0.980131 -0.198351 0.000000 +-0.980131 -0.198351 0.000000 +0.198346 -0.980132 0.000000 +0.198346 -0.980132 0.000000 +0.198346 -0.980132 0.000000 +0.198346 -0.980132 0.000000 +0.198346 -0.980132 0.000000 +0.198346 -0.980132 0.000000 +0.980131 0.198351 0.000000 +0.980131 0.198351 0.000000 +0.980131 0.198351 0.000000 +0.980131 0.198351 0.000000 +0.980131 0.198351 0.000000 +0.980131 0.198351 0.000000 +-0.198345 0.980132 0.000000 +-0.198345 0.980132 0.000000 +-0.198345 0.980132 0.000000 +-0.198345 0.980132 0.000000 +-0.198345 0.980132 0.000000 +-0.198345 0.980132 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.980131 -0.198350 0.000000 +-0.980131 -0.198350 0.000000 +-0.980131 -0.198350 0.000000 +-0.980131 -0.198350 0.000000 +-0.980131 -0.198350 0.000000 +-0.980131 -0.198350 0.000000 +0.198346 -0.980132 0.000000 +0.198346 -0.980132 0.000000 +0.198346 -0.980132 0.000000 +0.198346 -0.980132 0.000000 +0.198346 -0.980132 0.000000 +0.198346 -0.980132 0.000000 +0.980131 0.198350 0.000000 +0.980131 0.198350 0.000000 +0.980131 0.198350 0.000000 +0.980131 0.198350 0.000000 +0.980131 0.198350 0.000000 +0.980131 0.198350 0.000000 +-0.198346 0.980132 0.000000 +-0.198346 0.980132 0.000000 +-0.198346 0.980132 0.000000 +-0.198346 0.980132 0.000000 +-0.198346 0.980132 0.000000 +-0.198346 0.980132 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.980131 -0.198351 0.000000 +-0.980131 -0.198351 0.000000 +-0.980131 -0.198351 0.000000 +-0.980131 -0.198351 0.000000 +-0.980131 -0.198351 0.000000 +-0.980131 -0.198351 0.000000 +0.198346 -0.980132 0.000000 +0.198346 -0.980132 0.000000 +0.198346 -0.980132 0.000000 +0.198346 -0.980132 0.000000 +0.198346 -0.980132 0.000000 +0.198346 -0.980132 0.000000 +0.980131 0.198351 0.000000 +0.980131 0.198351 0.000000 +0.980131 0.198351 0.000000 +0.980131 0.198351 0.000000 +0.980131 0.198351 0.000000 +0.980131 0.198351 0.000000 +-0.198345 0.980132 0.000000 +-0.198345 0.980132 0.000000 +-0.198345 0.980132 0.000000 +-0.198345 0.980132 0.000000 +-0.198345 0.980132 0.000000 +-0.198345 0.980132 0.000000 + + + + + + + + + + + +0.109020 0.038880 +0.482223 0.042625 +0.108463 0.039541 +0.485226 0.420580 +0.484530 0.420580 +0.484251 0.418555 +0.108657 0.418238 +0.485016 0.418868 +0.108657 0.418238 +0.483024 0.420597 +0.483024 0.420597 +0.110760 0.421926 +0.485227 0.420580 +0.110760 0.421926 +0.484531 0.420580 +0.482733 0.042185 +0.110670 0.040689 +0.111451 0.041893 +0.488313 0.420300 +0.108120 0.417948 +0.108120 0.417948 +0.485263 0.419226 +0.488313 0.420300 +0.484090 0.418566 +0.110622 0.421852 +0.110622 0.421852 +0.110296 0.419281 +0.109371 0.419068 +0.109371 0.419069 +0.110296 0.419281 +0.481478 0.043648 +0.481478 0.043648 +0.484252 0.420631 +0.484252 0.420631 +0.109020 0.038880 +0.482223 0.042625 +0.108463 0.039541 +0.485226 0.420580 +0.484530 0.420580 +0.484252 0.418555 +0.108657 0.418238 +0.485016 0.418868 +0.108657 0.418238 +0.483024 0.420597 +0.483024 0.420597 +0.110760 0.421926 +0.485226 0.420580 +0.110760 0.421926 +0.484531 0.420580 +0.482733 0.042185 +0.110669 0.040688 +0.111451 0.041893 +0.488313 0.420300 +0.108120 0.417948 +0.108120 0.417948 +0.485263 0.419226 +0.488313 0.420300 +0.484092 0.418565 +0.110622 0.421852 +0.110622 0.421852 +0.110296 0.419281 +0.109371 0.419068 +0.109371 0.419069 +0.110296 0.419281 +0.481478 0.043648 +0.481478 0.043648 +0.484252 0.420631 +0.484252 0.420631 +0.109020 0.038880 +0.482223 0.042625 +0.108463 0.039541 +0.485226 0.420580 +0.484530 0.420580 +0.484252 0.418555 +0.108657 0.418238 +0.485016 0.418868 +0.108657 0.418238 +0.483024 0.420597 +0.483024 0.420597 +0.110760 0.421926 +0.485226 0.420580 +0.110760 0.421926 +0.484531 0.420580 +0.482733 0.042185 +0.110670 0.040689 +0.111451 0.041893 +0.488313 0.420300 +0.108120 0.417948 +0.108120 0.417948 +0.485263 0.419226 +0.488313 0.420300 +0.484090 0.418566 +0.110622 0.421852 +0.110622 0.421852 +0.110296 0.419281 +0.109371 0.419068 +0.109371 0.419069 +0.110296 0.419281 +0.481478 0.043648 +0.481478 0.043648 +0.484252 0.420631 +0.484252 0.420631 +0.109020 0.038880 +0.482223 0.042625 +0.108463 0.039541 +0.485226 0.420580 +0.484530 0.420580 +0.484252 0.418555 +0.108657 0.418238 +0.485016 0.418868 +0.108657 0.418238 +0.483024 0.420597 +0.483024 0.420597 +0.110760 0.421926 +0.485226 0.420580 +0.110760 0.421926 +0.484531 0.420580 +0.482733 0.042185 +0.110669 0.040688 +0.111451 0.041893 +0.488313 0.420300 +0.108120 0.417948 +0.108120 0.417948 +0.485263 0.419226 +0.488313 0.420300 +0.484092 0.418565 +0.110622 0.421852 +0.110622 0.421852 +0.110296 0.419281 +0.109371 0.419068 +0.109371 0.419069 +0.110296 0.419281 +0.481478 0.043648 +0.481478 0.043648 +0.484252 0.420631 +0.484252 0.420631 +0.109020 0.038880 +0.482223 0.042625 +0.108463 0.039541 +0.485226 0.420580 +0.484530 0.420580 +0.484252 0.418555 +0.108657 0.418238 +0.485016 0.418868 +0.108657 0.418238 +0.483024 0.420597 +0.483024 0.420597 +0.110760 0.421926 +0.485227 0.420580 +0.110760 0.421926 +0.484531 0.420580 +0.482733 0.042185 +0.110669 0.040688 +0.111451 0.041893 +0.488313 0.420300 +0.108120 0.417948 +0.108120 0.417948 +0.485263 0.419226 +0.488313 0.420300 +0.484092 0.418565 +0.110622 0.421852 +0.110622 0.421852 +0.110296 0.419281 +0.109371 0.419068 +0.109371 0.419069 +0.110296 0.419281 +0.481478 0.043648 +0.481478 0.043648 +0.484252 0.420631 +0.484252 0.420631 +0.109020 0.038880 +0.482223 0.042625 +0.108463 0.039541 +0.485226 0.420580 +0.484530 0.420580 +0.484252 0.418555 +0.108657 0.418238 +0.485016 0.418868 +0.108657 0.418238 +0.483024 0.420597 +0.483024 0.420597 +0.110760 0.421926 +0.485227 0.420580 +0.110760 0.421926 +0.484531 0.420580 +0.482733 0.042185 +0.110670 0.040689 +0.111451 0.041893 +0.488313 0.420300 +0.108120 0.417948 +0.108120 0.417948 +0.485263 0.419226 +0.488313 0.420300 +0.484092 0.418565 +0.110622 0.421852 +0.110622 0.421852 +0.110296 0.419281 +0.109371 0.419068 +0.109371 0.419069 +0.110296 0.419281 +0.481478 0.043648 +0.481478 0.043648 +0.484252 0.420631 +0.484252 0.420631 +0.479846 0.420580 +0.114013 0.420894 +0.478853 0.420580 +0.113937 0.420889 +0.478853 0.420580 +0.478224 0.420580 +0.478224 0.420580 +0.114014 0.420907 +0.480622 0.420580 +0.113936 0.420877 +0.478853 0.420580 +0.114201 0.420162 +0.113941 0.420203 +0.113903 0.420285 +0.113980 0.420279 +0.478224 0.420580 +0.478224 0.420580 +0.113977 0.420238 +0.478853 0.420580 +0.113901 0.420246 +0.478853 0.420580 +0.113977 0.420226 +0.478224 0.420580 +0.478853 0.420580 +0.113938 0.420150 +0.478854 0.420580 +0.114012 0.420873 +0.113935 0.420856 +0.113935 0.420857 +0.114012 0.420872 +0.113979 0.420267 +0.478224 0.420580 +0.478853 0.420580 +0.113941 0.420203 +0.478853 0.420580 +0.478224 0.420580 +0.478224 0.420580 +0.113979 0.420279 +0.478853 0.420580 +0.113903 0.420285 +0.478853 0.420580 +0.114013 0.420894 +0.113936 0.420889 +0.113936 0.420877 +0.114014 0.420907 +0.479846 0.420580 +0.114013 0.420894 +0.478853 0.420580 +0.478853 0.420580 +0.113936 0.420889 +0.478224 0.420580 +0.114014 0.420907 +0.478224 0.420580 +0.480624 0.420580 +0.478853 0.420580 +0.113936 0.420877 +0.114201 0.420162 +0.113941 0.420203 +0.113903 0.420285 +0.113980 0.420279 +0.478224 0.420580 +0.478224 0.420580 +0.113977 0.420238 +0.478853 0.420580 +0.113901 0.420246 +0.478853 0.420580 +0.113977 0.420226 +0.478224 0.420580 +0.478853 0.420580 +0.113938 0.420150 +0.478854 0.420580 +0.114012 0.420873 +0.113935 0.420856 +0.113935 0.420857 +0.114012 0.420872 +0.113979 0.420267 +0.478224 0.420580 +0.478853 0.420580 +0.113941 0.420203 +0.478853 0.420580 +0.478224 0.420580 +0.478224 0.420580 +0.113979 0.420279 +0.478853 0.420580 +0.113903 0.420285 +0.478853 0.420580 +0.114013 0.420894 +0.113936 0.420889 +0.113936 0.420877 +0.114014 0.420907 +0.479846 0.420580 +0.114013 0.420894 +0.478853 0.420580 +0.478853 0.420580 +0.113936 0.420889 +0.478224 0.420580 +0.114014 0.420907 +0.478224 0.420580 +0.480626 0.420580 +0.478853 0.420580 +0.113936 0.420877 +0.114201 0.420162 +0.113941 0.420203 +0.113903 0.420285 +0.113980 0.420279 +0.478224 0.420580 +0.478224 0.420580 +0.113977 0.420238 +0.478853 0.420580 +0.113901 0.420246 +0.478853 0.420580 +0.113977 0.420226 +0.478224 0.420580 +0.478853 0.420580 +0.113938 0.420150 +0.478854 0.420580 +0.114012 0.420873 +0.113935 0.420856 +0.113935 0.420857 +0.114012 0.420872 +0.113979 0.420267 +0.478224 0.420580 +0.478853 0.420580 +0.113941 0.420203 +0.478853 0.420580 +0.478224 0.420580 +0.478224 0.420580 +0.113979 0.420279 +0.478853 0.420580 +0.113903 0.420285 +0.478853 0.420580 +0.114013 0.420894 +0.113936 0.420889 +0.113936 0.420877 +0.114014 0.420907 +0.489049 0.036961 +0.105430 0.036961 +0.489049 0.420580 +0.105430 0.420580 +0.105430 0.036961 +0.489049 0.036961 +0.105430 0.420580 +0.489049 0.420580 +0.105430 0.036961 +0.489049 0.036961 +0.105430 0.420580 +0.489049 0.420580 +0.105430 0.036961 +0.489049 0.036961 +0.105430 0.420580 +0.489049 0.420580 +0.489049 0.036961 +0.105430 0.036961 +0.489049 0.420580 +0.105430 0.420580 +0.105430 0.036961 +0.489049 0.036961 +0.105430 0.420580 +0.489049 0.420580 +0.105430 0.036961 +0.489049 0.036961 +0.105430 0.420580 +0.489049 0.420580 +0.105430 0.036961 +0.489049 0.036961 +0.105430 0.420580 +0.489049 0.420580 +0.489049 0.036961 +0.105430 0.036961 +0.489049 0.420580 +0.105430 0.420580 +0.105430 0.036961 +0.489049 0.036961 +0.105430 0.420580 +0.489049 0.420580 +0.105430 0.036961 +0.489049 0.036961 +0.105430 0.420580 +0.489049 0.420580 +0.105430 0.036961 +0.489049 0.036961 +0.105430 0.420580 +0.489049 0.420580 +0.467426 0.244300 +0.317890 0.040957 +0.467429 0.037310 +0.472758 0.037231 +0.460787 0.037387 +0.466120 0.037309 +0.466120 0.244456 +0.460787 0.244456 +0.109426 0.039190 +0.326357 0.039046 +0.331686 0.039125 +0.331689 0.042629 +0.110978 0.040957 +0.110978 0.037531 +0.317890 0.037531 +0.318047 0.041049 +0.326360 0.044104 +0.331690 0.043948 +0.331690 0.047687 +0.326357 0.047609 +0.109426 0.246102 +0.105999 0.246102 +0.105999 0.039190 +0.109582 0.246194 +0.109738 0.246194 +0.109738 0.246259 +0.318203 0.041049 +0.318203 0.041114 +0.109582 0.246415 +0.109517 0.246415 +0.318047 0.041269 +0.317982 0.041269 +0.109634 0.246185 +0.109582 0.038878 +0.317982 0.041114 +0.110666 0.041049 +0.109738 0.039033 +0.109738 0.039098 +0.110821 0.041049 +0.110886 0.041114 +0.109582 0.039098 +0.109517 0.039033 +0.472758 0.244300 +0.467426 0.037231 +0.110886 0.041269 +0.110821 0.041269 +0.472761 0.037153 +0.472761 0.244379 +0.460784 0.037309 +0.460784 0.037153 +0.110811 0.041124 +0.318047 0.037218 +0.466122 0.037153 +0.466122 0.037309 +0.109517 0.038878 +0.105687 0.246194 +0.318203 0.037374 +0.318203 0.037439 +0.105842 0.246194 +0.105907 0.246259 +0.318047 0.037439 +0.317982 0.037374 +0.105907 0.246415 +0.105842 0.246415 +0.326357 0.042629 +0.331690 0.038969 +0.317982 0.037218 +0.467422 0.244379 +0.105687 0.246259 +0.105687 0.039033 +0.110886 0.037218 +0.110886 0.037374 +0.466123 0.244535 +0.105842 0.038878 +0.110821 0.037439 +0.110666 0.037439 +0.105907 0.038878 +0.105907 0.039033 +0.331692 0.043792 +0.110666 0.037374 +0.105842 0.039098 +0.105687 0.039098 +0.109508 0.246437 +0.105916 0.246311 +0.109803 0.246102 +0.110821 0.037218 +0.318057 0.041124 +0.110978 0.041334 +0.110770 0.037448 +0.331692 0.038968 +0.318268 0.040957 +0.109592 0.039023 +0.331692 0.043947 +0.109803 0.039190 +0.105665 0.246185 +0.105622 0.039190 +0.326355 0.043948 +0.110601 0.040957 +0.317890 0.037153 +0.318057 0.037364 +0.110895 0.037196 +0.105832 0.039023 +0.326353 0.043792 +0.326353 0.047843 +0.326353 0.047687 +0.331692 0.047687 +0.331692 0.047843 +0.326353 0.038968 +0.326353 0.038813 +0.326353 0.042708 +0.460784 0.244535 +0.331692 0.042708 +0.281940 0.050610 +0.278248 0.257787 +0.278293 0.050600 +0.281895 0.257798 +0.368193 0.257639 +0.364549 0.257632 +0.368252 0.050499 +0.364594 0.050444 +0.283384 0.050612 +0.312978 0.259726 +0.105804 0.338885 +0.362544 0.257786 +0.477727 0.037227 +0.474133 0.116347 +0.362473 0.050586 +0.313003 0.338815 +0.484093 0.199272 +0.474140 0.037264 +0.477722 0.116253 +0.487648 0.120214 +0.484098 0.120246 +0.487680 0.199235 +0.283454 0.257811 +0.105778 0.259796 +0.276961 0.050610 +0.273269 0.257787 +0.273314 0.050600 +0.276916 0.257798 +0.378151 0.257639 +0.374507 0.257632 +0.378210 0.050499 +0.374552 0.050444 +0.189941 0.257786 +0.192105 0.050612 +0.271263 0.257786 +0.110782 0.050612 +0.487685 0.037227 +0.484091 0.116347 +0.110852 0.257811 +0.271194 0.050586 +0.474135 0.199272 +0.484098 0.037264 +0.487680 0.116253 +0.477690 0.120214 +0.474140 0.120246 +0.477722 0.199235 +0.189872 0.050586 +0.192174 0.257811 +0.114100 0.042156 +0.321277 0.045848 +0.114090 0.045803 +0.321288 0.042201 +0.373172 0.257639 +0.369528 0.257632 +0.373231 0.050499 +0.105804 0.420207 +0.312978 0.341048 +0.379634 0.037225 +0.458802 0.244353 +0.479212 0.199274 +0.369573 0.050444 +0.482706 0.037227 +0.479112 0.116347 +0.105778 0.341118 +0.479196 0.120231 +0.379713 0.244379 +0.479118 0.037264 +0.482702 0.116253 +0.482824 0.120214 +0.482857 0.199235 +0.313003 0.420137 +0.458717 0.037231 +0.016244 0.715841 +0.756345 0.522332 +0.756346 0.715841 +0.016243 0.522332 +0.009526 0.061000 +0.749637 0.514493 +0.009526 0.514494 +0.749636 0.060999 +0.969477 0.480355 +0.969577 0.938728 +0.771464 0.938319 +0.771396 0.480706 +0.007192 0.039423 +0.751630 0.039423 +0.007192 0.498972 +0.751630 0.498972 +0.779207 0.499082 +0.779286 0.040707 +0.977371 0.041060 +0.977311 0.498670 +0.016243 0.911620 +0.756344 0.718111 +0.756344 0.911620 +0.016243 0.718111 +0.016244 0.715841 +0.756345 0.522332 +0.756346 0.715841 +0.016243 0.522332 +0.009526 0.061000 +0.749637 0.514493 +0.009526 0.514494 +0.749636 0.060999 +0.969477 0.480355 +0.969577 0.938728 +0.771464 0.938319 +0.771396 0.480706 +0.007192 0.039423 +0.751630 0.039423 +0.007192 0.498972 +0.751630 0.498972 +0.779207 0.499082 +0.779286 0.040707 +0.977371 0.041060 +0.977311 0.498670 +0.016243 0.911620 +0.756344 0.718111 +0.756344 0.911620 +0.016243 0.718111 +0.016244 0.715841 +0.756345 0.522332 +0.756346 0.715841 +0.016243 0.522332 +0.009526 0.061000 +0.749637 0.514493 +0.009526 0.514494 +0.749636 0.060999 +0.969477 0.480355 +0.969577 0.938728 +0.771464 0.938319 +0.771396 0.480706 +0.007192 0.039423 +0.751630 0.039423 +0.007192 0.498972 +0.751630 0.498972 +0.779207 0.499082 +0.779286 0.040707 +0.977371 0.041060 +0.977311 0.498670 +0.756344 0.911620 +0.016243 0.718111 +0.756344 0.718111 +0.016243 0.911620 +0.016244 0.715841 +0.756345 0.522332 +0.756346 0.715841 +0.016243 0.522332 +0.009526 0.061000 +0.749637 0.514493 +0.009526 0.514494 +0.749636 0.060999 +0.969477 0.480355 +0.969577 0.938728 +0.771464 0.938319 +0.771396 0.480706 +0.007192 0.039423 +0.751630 0.039423 +0.007192 0.498972 +0.751630 0.498972 +0.779207 0.499082 +0.779286 0.040707 +0.977371 0.041060 +0.977311 0.498670 +0.016243 0.911620 +0.756344 0.718111 +0.756344 0.911620 +0.016243 0.718111 +0.016244 0.715841 +0.756345 0.522332 +0.756346 0.715841 +0.016243 0.522332 +0.009526 0.061000 +0.749637 0.514493 +0.009526 0.514494 +0.749636 0.060999 +0.969477 0.480355 +0.969577 0.938728 +0.771464 0.938319 +0.771396 0.480706 +0.007192 0.039423 +0.751630 0.039423 +0.007192 0.498972 +0.751630 0.498972 +0.779207 0.499082 +0.779286 0.040707 +0.977371 0.041060 +0.977311 0.498670 +0.016243 0.911620 +0.756344 0.718111 +0.756344 0.911620 +0.016243 0.718111 +0.016244 0.715841 +0.756345 0.522332 +0.756346 0.715841 +0.016243 0.522332 +0.009526 0.061000 +0.749637 0.514493 +0.009526 0.514494 +0.749636 0.060999 +0.969477 0.480355 +0.969577 0.938728 +0.771464 0.938319 +0.771396 0.480706 +0.007192 0.039423 +0.751630 0.039423 +0.007192 0.498972 +0.751630 0.498972 +0.779207 0.499082 +0.779286 0.040707 +0.977371 0.041060 +0.977311 0.498670 +0.016243 0.911620 +0.756344 0.718111 +0.756344 0.911620 +0.016243 0.718111 +0.016244 0.715841 +0.756345 0.522332 +0.756346 0.715841 +0.016243 0.522332 +0.009526 0.061000 +0.749637 0.514493 +0.009526 0.514494 +0.749636 0.060999 +0.969477 0.480355 +0.969577 0.938728 +0.771464 0.938319 +0.771396 0.480706 +0.007192 0.039423 +0.751630 0.039423 +0.007192 0.498972 +0.751630 0.498972 +0.779207 0.499082 +0.779286 0.040707 +0.977371 0.041060 +0.977311 0.498670 +0.016243 0.911620 +0.756344 0.718111 +0.756344 0.911620 +0.016243 0.718111 +0.016244 0.715841 +0.756345 0.522332 +0.756346 0.715841 +0.016243 0.522332 +0.009526 0.061000 +0.749637 0.514493 +0.009526 0.514494 +0.749636 0.060999 +0.969477 0.480355 +0.969577 0.938728 +0.771464 0.938319 +0.771396 0.480706 +0.007192 0.039423 +0.751630 0.039423 +0.007192 0.498972 +0.751630 0.498972 +0.779207 0.499082 +0.779286 0.040707 +0.977371 0.041060 +0.977311 0.498670 +0.756344 0.911620 +0.016243 0.718111 +0.756344 0.718111 +0.016243 0.911620 +0.486957 0.692024 +0.027038 0.424800 +0.486954 0.424800 +0.027038 0.692024 +0.506996 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.966910 0.036168 +0.029544 0.043430 +0.489461 0.415225 +0.029544 0.415224 +0.489461 0.035380 +0.029544 0.035380 +0.037422 0.971548 +0.407335 0.698761 +0.409054 0.971742 +0.039211 0.698717 +0.965462 0.676852 +0.505546 0.676852 +0.505546 0.409621 +0.965459 0.409621 +0.914572 0.962378 +0.922325 0.705031 +0.570344 0.705031 +0.570343 0.962377 +0.027038 0.692024 +0.486954 0.424800 +0.486957 0.692024 +0.027038 0.424800 +0.506996 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.966910 0.036168 +0.029544 0.043430 +0.489461 0.415225 +0.029544 0.415224 +0.489461 0.035380 +0.029544 0.035380 +0.037422 0.971548 +0.039211 0.698717 +0.409054 0.971742 +0.407335 0.698761 +0.965462 0.676852 +0.505546 0.676852 +0.505546 0.409621 +0.965459 0.409621 +0.914572 0.962378 +0.922325 0.705031 +0.570344 0.705031 +0.570343 0.962377 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.206126 +1.014936 0.691973 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.206126 +0.170286 0.691973 +0.229772 0.173002 +0.933648 0.102615 +0.933648 0.173002 +0.229772 0.102615 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.206126 +1.014936 0.691973 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.206126 +0.170286 0.691973 +0.229772 0.173002 +0.933648 0.102615 +0.933648 0.173002 +0.229772 0.102615 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.206126 +1.014936 0.691973 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.691973 +0.170286 0.206126 +0.933648 0.173002 +0.229772 0.173002 +0.229772 0.102615 +0.933648 0.102615 +0.486957 0.692024 +0.027038 0.424800 +0.486954 0.424800 +0.027038 0.692024 +0.506996 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.966910 0.036168 +0.029544 0.043430 +0.489461 0.415225 +0.029544 0.415224 +0.489461 0.035380 +0.029544 0.035380 +0.037422 0.971548 +0.407335 0.698761 +0.409054 0.971742 +0.039211 0.698717 +0.965462 0.676852 +0.505546 0.676852 +0.505546 0.409621 +0.965459 0.409621 +0.914572 0.962378 +0.922325 0.705031 +0.570344 0.705031 +0.570343 0.962377 +0.486957 0.692024 +0.027038 0.424800 +0.486954 0.424800 +0.027038 0.692024 +0.506996 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.966910 0.036168 +0.029544 0.043430 +0.489461 0.415225 +0.029544 0.415224 +0.489461 0.035380 +0.037422 0.971548 +0.407335 0.698761 +0.409054 0.971742 +0.039211 0.698717 +0.965462 0.676852 +0.505546 0.676852 +0.505546 0.409621 +0.965459 0.409621 +0.914572 0.962378 +0.922325 0.705031 +0.570344 0.705031 +0.570343 0.962377 +0.016244 0.715841 +0.756345 0.522332 +0.756346 0.715841 +0.016243 0.522332 +0.009526 0.061000 +0.749637 0.514493 +0.009526 0.514494 +0.749636 0.060999 +0.969477 0.480355 +0.969577 0.938728 +0.771464 0.938319 +0.771396 0.480706 +0.007192 0.039423 +0.751630 0.039423 +0.007192 0.498972 +0.751630 0.498972 +0.779207 0.499082 +0.779286 0.040707 +0.977371 0.041060 +0.977311 0.498670 +0.016243 0.911620 +0.756344 0.718111 +0.756344 0.911620 +0.016243 0.718111 +0.016244 0.715841 +0.756345 0.522332 +0.756346 0.715841 +0.016243 0.522332 +0.009526 0.061000 +0.749637 0.514493 +0.009526 0.514494 +0.749636 0.060999 +0.969477 0.480355 +0.969577 0.938728 +0.771464 0.938319 +0.771396 0.480706 +0.007192 0.039423 +0.751630 0.039423 +0.007192 0.498972 +0.751630 0.498972 +0.779207 0.499082 +0.779286 0.040707 +0.977371 0.041060 +0.977311 0.498670 +0.756344 0.911620 +0.016243 0.718111 +0.756344 0.718111 +0.016243 0.911620 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.206126 +1.014936 0.691973 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.206126 +0.170286 0.691973 +0.229772 0.173002 +0.933648 0.102615 +0.933648 0.173002 +0.229772 0.102615 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.206126 +1.014936 0.691973 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.206126 +0.170286 0.691973 +0.229772 0.173002 +0.933648 0.102615 +0.933648 0.173002 +0.229772 0.102615 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.206126 +1.014936 0.691973 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.691973 +0.170286 0.206126 +0.933648 0.173002 +0.229772 0.173002 +0.229772 0.102615 +0.933648 0.102615 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.691973 +1.014936 0.206126 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.691973 +0.170286 0.206126 +0.933648 0.173002 +0.229772 0.173002 +0.229772 0.102615 +0.933648 0.102615 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.206126 +1.014936 0.691973 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.691973 +0.170286 0.206126 +0.933648 0.173002 +0.229772 0.173002 +0.229772 0.102615 +0.933648 0.102615 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.206126 +1.014936 0.691973 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.206126 +0.170286 0.691973 +0.229772 0.173002 +0.933648 0.102615 +0.933648 0.173002 +0.229772 0.102615 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.206126 +1.014936 0.691973 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.206126 +0.170286 0.691973 +0.229772 0.173002 +0.933648 0.102615 +0.933648 0.173002 +0.229772 0.102615 +0.016244 0.715841 +0.756345 0.522332 +0.756346 0.715841 +0.016243 0.522332 +0.009526 0.061000 +0.749637 0.514493 +0.009526 0.514494 +0.749636 0.060999 +0.969477 0.480355 +0.969577 0.938728 +0.771464 0.938319 +0.771396 0.480706 +0.007192 0.039423 +0.751630 0.039423 +0.007192 0.498972 +0.751630 0.498972 +0.779207 0.499082 +0.779286 0.040707 +0.977371 0.041060 +0.977311 0.498670 +0.016243 0.911620 +0.756344 0.718111 +0.756344 0.911620 +0.016243 0.718111 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.206126 +1.014936 0.691973 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.206126 +0.170286 0.691973 +0.229772 0.173002 +0.933648 0.102615 +0.933648 0.173002 +0.229772 0.102615 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.206126 +1.014936 0.691973 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.206126 +0.170286 0.691973 +0.229772 0.173002 +0.933648 0.102615 +0.933648 0.173002 +0.229772 0.102615 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.206126 +1.014936 0.691973 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.691973 +0.170286 0.206126 +0.933648 0.173002 +0.229772 0.173002 +0.229772 0.102615 +0.933648 0.102615 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.206126 +1.014936 0.691973 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.691973 +0.170286 0.206126 +0.229772 0.173002 +0.933648 0.102615 +0.933648 0.173002 +0.229772 0.102615 +0.489049 0.420727 +0.489049 0.420727 +0.489049 0.420727 +0.489049 0.420727 +0.489049 0.420727 +0.489049 0.420727 +0.489049 0.420727 +0.489049 0.420727 +0.489049 0.420727 +0.489049 0.420727 +0.489049 0.420727 +0.489049 0.420727 +0.480370 0.420580 +0.479846 0.420580 +0.480371 0.420580 +0.479846 0.420580 +0.480371 0.420580 +0.479845 0.420580 +0.029544 0.035377 +0.029544 0.035379 +0.029544 0.035377 +0.029544 0.035376 +0.113937 0.420873 + + + + + + + + + + + +

0 0 6 2 1 31 1 2 7 2 3 31 0 4 6 5 5 0 2 6 16 9 7 23 1 8 19 9 9 23 2 10 16 7 11 1 9 12 8 7 13 17 8 14 21 8 15 21 7 16 17 6 17 30 6 18 2 0 19 5 8 20 20 0 21 5 6 22 2 5 23 15 3 24 11 1 25 7 10 26 3 1 27 7 3 28 11 0 29 6 9 30 22 10 31 24 1 32 19 10 33 24 9 34 22 4 35 14 8 36 21 4 37 13 9 38 8 4 39 13 8 40 21 11 41 12 0 42 18 11 43 25 8 44 20 11 45 25 0 46 18 3 47 4 12 48 26 10 49 3 13 50 32 10 51 3 12 52 26 3 53 11 13 54 27 4 55 14 15 56 9 4 57 14 13 58 27 10 59 24 15 60 29 4 61 13 14 62 33 14 63 33 4 64 13 11 65 12 14 66 28 11 67 25 12 68 10 12 69 10 11 70 25 3 71 4 12 72 1187 15 73 1186 14 74 33 15 75 1186 12 76 1187 13 77 32 16 78 40 18 79 65 17 80 41 18 81 65 16 82 40 21 83 34 17 84 53 18 85 50 25 86 57 25 87 57 18 88 50 23 89 35 25 90 42 23 91 51 24 92 55 24 93 55 23 94 51 22 95 64 24 96 54 21 97 49 16 98 39 21 99 49 24 100 54 22 101 36 16 102 40 26 103 37 19 104 45 16 105 40 17 106 41 26 107 37 25 108 56 26 109 58 17 110 53 26 111 58 25 112 56 20 113 48 24 114 55 20 115 47 25 116 42 20 117 47 24 118 55 27 119 46 24 120 54 16 121 52 19 122 38 24 123 54 19 124 38 27 125 59 28 126 60 19 127 45 29 128 66 29 129 66 19 130 45 26 131 37 29 132 61 26 133 58 31 134 43 31 135 43 26 136 58 20 137 48 31 138 63 27 139 46 30 140 67 27 141 46 31 142 63 20 143 47 30 144 62 19 145 38 28 146 44 19 147 38 30 148 62 27 149 59 28 150 1189 31 151 1188 30 152 67 31 153 1188 28 154 1189 29 155 66 32 156 74 34 157 99 33 158 75 34 159 99 32 160 74 37 161 68 34 162 84 41 163 91 33 164 87 41 165 91 34 166 84 39 167 69 41 168 76 39 169 85 40 170 89 40 171 89 39 172 85 38 173 98 38 174 70 32 175 73 40 176 88 32 177 73 38 178 70 37 179 83 32 180 74 42 181 71 35 182 79 32 183 74 33 184 75 42 185 71 41 186 90 42 187 92 33 188 87 42 189 92 41 190 90 36 191 82 40 192 89 36 193 81 41 194 76 36 195 81 40 196 89 43 197 80 32 198 86 43 199 93 40 200 88 43 201 93 32 202 86 35 203 72 44 204 94 35 205 79 45 206 100 45 207 100 35 208 79 42 209 71 45 210 95 36 211 82 47 212 77 36 213 82 45 214 95 42 215 92 47 216 97 43 217 80 46 218 101 43 219 80 47 220 97 36 221 81 46 222 96 43 223 93 44 224 78 44 225 78 43 226 93 35 227 72 44 228 1191 47 229 1190 46 230 101 47 231 1190 44 232 1191 45 233 100 48 234 108 50 235 133 49 236 109 50 237 133 48 238 108 53 239 102 49 240 121 55 241 103 57 242 125 55 243 103 49 244 121 50 245 118 57 246 110 55 247 119 56 248 123 56 249 123 55 250 119 54 251 132 56 252 122 54 253 104 48 254 107 48 255 107 54 256 104 53 257 117 48 258 108 58 259 105 51 260 113 48 261 108 49 262 109 58 263 105 57 264 124 58 265 126 49 266 121 58 267 126 57 268 124 52 269 116 56 270 123 52 271 115 57 272 110 52 273 115 56 274 123 59 275 114 56 276 122 48 277 120 51 278 106 56 279 122 51 280 106 59 281 127 60 282 128 51 283 113 61 284 134 61 285 134 51 286 113 58 287 105 61 288 129 52 289 116 63 290 111 52 291 116 61 292 129 58 293 126 63 294 131 59 295 114 62 296 135 59 297 114 63 298 131 52 299 115 62 300 130 51 301 106 60 302 112 51 303 106 62 304 130 59 305 127 62 306 135 61 307 134 63 308 1192 61 309 134 62 310 135 60 311 1193 64 312 142 66 313 167 65 314 143 66 315 167 64 316 142 69 317 136 65 318 155 71 319 137 73 320 159 71 321 137 65 322 155 66 323 152 73 324 144 71 325 153 72 326 157 72 327 157 71 328 153 70 329 166 72 330 156 70 331 138 64 332 141 64 333 141 70 334 138 69 335 151 64 336 142 74 337 139 67 338 147 64 339 142 65 340 143 74 341 139 73 342 158 74 343 160 65 344 155 74 345 160 73 346 158 68 347 150 72 348 157 68 349 149 73 350 144 68 351 149 72 352 157 75 353 148 72 354 156 64 355 154 67 356 140 72 357 156 67 358 140 75 359 161 76 360 162 74 361 139 77 362 168 74 363 139 76 364 162 67 365 147 77 366 163 68 367 150 79 368 145 68 369 150 77 370 163 74 371 160 79 372 165 75 373 148 78 374 169 75 375 148 79 376 165 68 377 149 78 378 164 75 379 161 76 380 146 76 381 146 75 382 161 67 383 140 78 384 169 77 385 168 79 386 1194 77 387 168 78 388 169 76 389 1195 80 390 176 82 391 201 81 392 177 82 393 201 80 394 176 85 395 170 81 396 189 87 397 171 89 398 193 87 399 171 81 400 189 82 401 186 89 402 178 87 403 187 88 404 191 88 405 191 87 406 187 86 407 200 88 408 190 85 409 185 80 410 175 85 411 185 88 412 190 86 413 172 80 414 176 90 415 173 83 416 181 80 417 176 81 418 177 90 419 173 89 420 192 90 421 194 81 422 189 90 423 194 89 424 192 84 425 184 88 426 191 84 427 183 89 428 178 84 429 183 88 430 191 91 431 182 88 432 190 80 433 188 83 434 174 88 435 190 83 436 174 91 437 195 92 438 196 90 439 173 93 440 202 90 441 173 92 442 196 83 443 181 93 444 197 90 445 194 95 446 179 95 447 179 90 448 194 84 449 184 95 450 199 84 451 183 94 452 203 94 453 203 84 454 183 91 455 182 94 456 198 83 457 174 92 458 180 83 459 174 94 460 198 91 461 195 94 462 203 93 463 202 95 464 1196 93 465 202 94 466 203 92 467 1197 97 468 205 102 469 215 96 470 204 98 471 206 101 472 208 99 473 207 99 474 207 460 475 216 98 476 206 101 477 211 98 478 218 103 479 209 100 480 210 103 481 209 98 482 218 100 483 217 97 484 214 103 485 213 97 486 214 100 487 217 102 488 212 104 489 219 105 490 221 111 491 230 104 492 219 106 493 220 105 494 221 106 495 223 107 496 224 108 497 222 107 498 224 106 499 223 104 500 231 109 501 226 110 502 1198 107 503 233 108 504 225 107 505 233 110 506 1198 111 507 229 105 508 227 109 509 232 109 510 232 105 511 227 110 512 228 113 513 235 114 514 1199 119 515 245 112 516 234 119 517 245 114 518 1199 114 519 237 113 520 246 117 521 236 117 522 236 113 523 246 115 524 238 116 525 239 117 526 241 115 527 248 116 528 239 118 529 240 117 530 241 119 531 244 118 532 243 116 533 247 118 534 243 119 535 244 112 536 242 121 537 250 126 538 260 120 539 249 122 540 251 124 541 252 123 542 253 123 543 253 461 544 261 122 545 251 124 546 255 122 547 263 127 548 254 125 549 256 127 550 254 122 551 263 125 552 262 121 553 258 127 554 259 121 555 258 125 556 262 126 557 257 128 558 264 129 559 266 135 560 275 128 561 264 130 562 265 129 563 266 130 564 268 131 565 269 132 566 267 131 567 269 130 568 268 128 569 276 133 570 271 134 571 1200 131 572 278 132 573 270 131 574 278 134 575 1200 135 576 274 129 577 272 133 578 277 133 579 277 129 580 272 134 581 273 137 582 280 138 583 1201 143 584 290 136 585 279 143 586 290 138 587 1201 138 588 282 137 589 291 141 590 281 141 591 281 137 592 291 139 593 283 140 594 284 141 595 286 139 596 293 140 597 284 142 598 285 141 599 286 143 600 289 142 601 288 140 602 292 142 603 288 143 604 289 136 605 287 145 606 295 150 607 305 144 608 294 146 609 296 148 610 297 147 611 298 145 612 1208 144 613 306 147 614 298 147 615 298 144 616 306 146 617 296 148 618 300 146 619 308 151 620 299 149 621 301 151 622 299 146 623 308 149 624 307 145 625 303 151 626 304 145 627 303 149 628 307 150 629 302 152 630 309 153 631 311 159 632 320 152 633 309 154 634 310 153 635 311 154 636 313 155 637 314 156 638 312 155 639 314 154 640 313 152 641 321 157 642 316 158 643 1202 155 644 323 156 645 315 155 646 323 158 647 1202 159 648 319 153 649 317 157 650 322 157 651 322 153 652 317 158 653 318 161 654 325 162 655 1203 167 656 335 160 657 324 167 658 335 162 659 1203 162 660 327 161 661 336 165 662 326 165 663 326 161 664 336 163 665 328 164 666 329 165 667 331 163 668 338 164 669 329 166 670 330 165 671 331 167 672 334 166 673 333 164 674 337 166 675 333 167 676 334 160 677 332 171 678 342 168 679 339 170 680 341 168 681 339 171 682 342 169 683 340 175 684 346 174 685 345 172 686 343 175 687 346 172 688 343 173 689 344 172 690 349 169 691 348 173 692 350 169 693 348 172 694 349 168 695 347 174 696 354 175 697 353 171 698 351 171 699 351 170 700 352 174 701 354 179 702 358 176 703 355 178 704 357 176 705 355 179 706 358 177 707 356 183 708 362 182 709 361 180 710 359 183 711 362 180 712 359 181 713 360 180 714 365 177 715 364 181 716 366 177 717 364 180 718 365 176 719 363 182 720 370 183 721 369 179 722 367 179 723 367 178 724 368 182 725 370 187 726 374 184 727 371 186 728 373 184 729 371 187 730 374 185 731 372 191 732 378 190 733 377 188 734 375 191 735 378 188 736 375 189 737 376 188 738 381 185 739 380 189 740 382 185 741 380 188 742 381 184 743 379 190 744 386 191 745 385 187 746 383 187 747 383 186 748 384 190 749 386 197 750 429 198 751 430 194 752 390 198 753 430 197 754 429 196 755 387 199 756 394 195 757 392 193 758 393 195 759 392 199 760 394 192 761 436 192 762 451 196 763 396 195 764 398 195 765 398 196 766 396 197 767 452 193 768 475 195 769 486 197 770 473 193 771 475 197 772 473 194 773 437 193 774 406 194 775 483 199 776 405 199 777 405 194 778 483 198 779 404 192 780 470 199 781 488 198 782 478 192 783 470 198 784 478 196 785 469 204 786 513 201 787 510 202 788 521 204 789 513 202 790 521 203 791 507 205 792 508 207 793 509 206 794 522 207 795 509 205 796 508 200 797 514 200 798 515 205 799 519 202 800 518 200 801 515 202 802 518 201 803 520 200 804 501 204 805 502 207 806 500 204 807 502 200 808 501 201 809 499 206 810 512 207 811 516 204 812 511 206 813 512 204 814 511 203 815 517 205 816 504 206 817 506 203 818 505 205 819 504 203 820 505 202 821 503 212 822 537 209 823 534 210 824 545 212 825 537 210 826 545 211 827 531 213 828 532 215 829 533 214 830 546 215 831 533 213 832 532 208 833 538 210 834 542 208 835 539 213 836 543 208 837 539 210 838 542 209 839 544 208 840 525 212 841 526 215 842 524 212 843 526 208 844 525 209 845 523 215 846 540 211 847 541 214 848 536 211 849 541 215 850 540 212 851 535 213 852 528 214 853 530 211 854 529 213 855 528 211 856 529 210 857 527 221 858 562 217 859 555 223 860 569 221 861 562 223 862 569 216 863 554 218 864 556 219 865 557 222 866 564 219 867 557 218 868 556 220 869 570 220 870 558 218 871 563 223 872 567 220 873 558 223 874 567 217 875 568 219 876 548 220 877 549 217 878 547 219 879 548 217 880 547 221 881 550 222 882 561 219 883 565 221 884 560 222 885 561 221 886 560 216 887 566 218 888 552 222 889 559 216 890 553 218 891 552 216 892 553 223 893 551 461 894 525 123 895 123 121 896 121 461 897 525 121 898 121 120 899 120 460 900 460 99 901 99 97 902 97 460 903 460 97 904 97 96 905 96

+

+

291 906 766 289 907 764 288 908 763 288 909 763 289 910 764 290 911 765 289 912 769 292 913 767 290 914 768 292 915 767 293 916 770 290 917 768 288 918 773 294 919 771 291 920 772 294 921 771 295 922 774 291 923 772 295 924 774 294 925 771 296 926 775 294 927 771 293 928 1204 296 929 775 291 930 778 295 931 776 289 932 777 295 933 776 292 934 779 289 935 777 296 936 781 293 937 782 295 938 780 295 939 780 293 940 782 292 941 783 288 942 787 290 943 786 294 944 784 294 945 784 290 946 786 293 947 785 299 948 790 297 949 788 298 950 789 297 951 788 300 952 791 298 953 789 300 954 794 301 955 792 298 956 793 301 957 792 302 958 795 298 959 793 299 960 798 303 961 796 297 962 797 303 963 796 304 964 799 297 965 797 304 966 799 303 967 796 305 968 800 303 969 796 302 970 1205 305 971 800 297 972 803 304 973 801 301 974 802 297 975 803 301 976 802 300 977 804 305 978 806 302 979 807 304 980 805 304 981 805 302 982 807 301 983 808 299 984 812 298 985 811 303 986 809 303 987 809 298 988 811 302 989 810 333 990 870 331 991 868 330 992 867 330 993 867 331 994 868 332 995 869 331 996 873 334 997 871 332 998 872 334 999 871 335 1000 874 332 1001 872 330 1002 877 336 1003 875 333 1004 876 336 1005 875 337 1006 878 333 1007 876 337 1008 878 336 1009 875 338 1010 879 336 1011 875 335 1012 1206 338 1013 879 333 1014 882 337 1015 880 331 1016 881 337 1017 880 334 1018 883 331 1019 881 338 1020 885 335 1021 886 337 1022 884 337 1023 884 335 1024 886 334 1025 887 330 1026 891 332 1027 890 336 1028 888 336 1029 888 332 1030 890 335 1031 889 342 1032 895 340 1033 893 339 1034 892 339 1035 892 340 1036 893 341 1037 894 344 1038 899 341 1039 897 343 1040 896 343 1041 896 341 1042 897 340 1043 898 342 1044 901 339 1045 902 345 1046 900 342 1047 901 345 1048 900 346 1049 903 345 1050 900 344 1051 1207 346 1052 903 342 1053 906 346 1054 904 340 1055 905 346 1056 904 343 1057 907 340 1058 905 347 1059 909 343 1060 911 346 1061 908 343 1062 911 347 1063 909 344 1064 910 339 1065 915 341 1066 914 345 1067 912 345 1068 912 341 1069 914 344 1070 913

+

227 1071 574 225 1072 572 224 1073 571 226 1074 573 224 1075 571 225 1076 572 228 1077 576 225 1078 575 227 1079 578 225 1080 575 228 1081 576 229 1082 577 230 1083 579 226 1084 580 225 1085 581 230 1086 579 225 1087 581 229 1088 582 230 1089 583 231 1090 584 226 1091 585 231 1092 584 224 1093 586 226 1094 585 224 1095 587 231 1096 588 228 1097 589 224 1098 587 228 1099 589 227 1100 590 229 1101 594 228 1102 592 230 1103 591 231 1104 593 230 1105 591 228 1106 592 235 1107 598 233 1108 596 232 1109 595 234 1110 597 232 1111 595 233 1112 596 236 1113 600 233 1114 599 235 1115 602 233 1116 599 236 1117 600 237 1118 601 238 1119 603 234 1120 604 233 1121 605 238 1122 603 233 1123 605 237 1124 606 238 1125 607 239 1126 608 234 1127 609 239 1128 608 232 1129 610 234 1130 609 232 1131 611 239 1132 612 236 1133 613 232 1134 611 236 1135 613 235 1136 614 237 1137 618 236 1138 616 238 1139 615 239 1140 617 238 1141 615 236 1142 616 243 1143 622 241 1144 620 240 1145 619 242 1146 621 240 1147 619 241 1148 620 244 1149 624 241 1150 623 243 1151 626 241 1152 623 244 1153 624 245 1154 625 246 1155 627 242 1156 628 241 1157 629 246 1158 627 241 1159 629 245 1160 630 246 1161 631 247 1162 632 242 1163 633 247 1164 632 240 1165 634 242 1166 633 240 1167 635 247 1168 636 244 1169 637 240 1170 635 244 1171 637 243 1172 638 247 1173 639 246 1174 642 245 1175 640 247 1176 639 245 1177 640 244 1178 641 251 1179 646 249 1180 644 248 1181 643 250 1182 645 248 1183 643 249 1184 644 252 1185 648 249 1186 647 251 1187 650 249 1188 647 252 1189 648 253 1190 649 249 1191 653 254 1192 651 250 1193 652 254 1194 651 249 1195 653 253 1196 654 250 1197 657 254 1198 655 255 1199 656 250 1200 657 255 1201 656 248 1202 658 248 1203 659 255 1204 660 252 1205 661 248 1206 659 252 1207 661 251 1208 662 253 1209 666 252 1210 664 254 1211 663 255 1212 665 254 1213 663 252 1214 664 259 1215 670 257 1216 668 256 1217 667 258 1218 669 256 1219 667 257 1220 668 261 1221 673 257 1222 671 260 1223 672 257 1224 671 259 1225 674 260 1226 672 262 1227 675 258 1228 676 257 1229 677 262 1230 675 257 1231 677 261 1232 678 256 1233 682 258 1234 681 263 1235 680 263 1236 680 258 1237 681 262 1238 679 256 1239 683 263 1240 684 260 1241 685 256 1242 683 260 1243 685 259 1244 686 261 1245 690 260 1246 688 262 1247 687 263 1248 689 262 1249 687 260 1250 688 267 1251 694 265 1252 692 264 1253 691 266 1254 693 264 1255 691 265 1256 692 268 1257 696 265 1258 695 267 1259 698 265 1260 695 268 1261 696 269 1262 697 265 1263 701 270 1264 699 266 1265 700 270 1266 699 265 1267 701 269 1268 702 266 1269 705 270 1270 703 271 1271 704 266 1272 705 271 1273 704 264 1274 706 264 1275 707 271 1276 708 268 1277 709 264 1278 707 268 1279 709 267 1280 710 269 1281 714 268 1282 712 270 1283 711 271 1284 713 270 1285 711 268 1286 712 275 1287 718 273 1288 716 272 1289 715 274 1290 717 272 1291 715 273 1292 716 276 1293 720 277 1294 721 273 1295 719 276 1296 720 273 1297 719 275 1298 722 273 1299 725 278 1300 723 274 1301 724 278 1302 723 273 1303 725 277 1304 726 274 1305 729 279 1306 728 272 1307 730 279 1308 728 274 1309 729 278 1310 727 272 1311 731 279 1312 732 276 1313 733 272 1314 731 276 1315 733 275 1316 734 277 1317 738 276 1318 736 278 1319 735 279 1320 737 278 1321 735 276 1322 736 283 1323 742 282 1324 741 280 1325 739 282 1326 741 283 1327 742 281 1328 740 284 1329 744 285 1330 745 281 1331 743 281 1332 743 283 1333 746 284 1334 744 286 1335 747 282 1336 748 281 1337 749 286 1338 747 281 1339 749 285 1340 750 282 1341 753 287 1342 752 280 1343 754 287 1344 752 282 1345 753 286 1346 751 280 1347 755 287 1348 756 284 1349 757 280 1350 755 284 1351 757 283 1352 758 285 1353 760 287 1354 759 286 1355 762 287 1356 759 285 1357 760 284 1358 761 351 1359 919 349 1360 917 348 1361 916 350 1362 918 348 1363 916 349 1364 917 352 1365 921 353 1366 922 349 1367 920 352 1368 921 349 1369 920 351 1370 923 354 1371 924 350 1372 925 349 1373 926 354 1374 924 349 1375 926 353 1376 927 350 1377 930 355 1378 929 348 1379 931 355 1380 929 350 1381 930 354 1382 928 348 1383 932 355 1384 933 352 1385 934 348 1386 932 352 1387 934 351 1388 935 353 1389 939 355 1390 938 354 1391 936 355 1392 938 353 1393 939 352 1394 937 359 1395 943 357 1396 941 356 1397 940 358 1398 942 356 1399 940 357 1400 941 360 1401 945 361 1402 946 357 1403 944 360 1404 945 357 1405 944 359 1406 947 362 1407 948 358 1408 949 357 1409 950 362 1410 948 357 1411 950 361 1412 951 358 1413 954 363 1414 953 356 1415 955 363 1416 953 358 1417 954 362 1418 952 356 1419 956 363 1420 957 360 1421 958 356 1422 956 360 1423 958 359 1424 959 363 1425 960 362 1426 963 361 1427 961 363 1428 960 361 1429 961 360 1430 962 423 1431 1093 421 1432 1091 420 1433 1090 422 1434 1092 420 1435 1090 421 1436 1091 424 1437 1095 425 1438 1096 421 1439 1094 424 1440 1095 421 1441 1094 423 1442 1097 426 1443 1098 422 1444 1099 421 1445 1100 426 1446 1098 421 1447 1100 425 1448 1101 422 1449 1104 427 1450 1103 420 1451 1105 427 1452 1103 422 1453 1104 426 1454 1102 420 1455 1106 427 1456 1107 424 1457 1108 420 1458 1106 424 1459 1108 423 1460 1109 425 1461 1113 427 1462 1112 426 1463 1110 427 1464 1112 425 1465 1113 424 1466 1111

+

309 1467 816 307 1468 814 306 1469 813 306 1470 813 307 1471 814 308 1472 815 312 1473 819 310 1474 817 311 1475 818 310 1476 817 313 1477 820 311 1478 818 311 1479 818 313 1480 820 309 1481 821 311 1482 818 309 1483 821 306 1484 822 312 1485 819 311 1486 818 306 1487 823 312 1488 819 306 1489 823 308 1490 824 308 1491 826 307 1492 825 312 1493 819 310 1494 817 312 1495 819 307 1496 825 307 1497 830 309 1498 828 310 1499 827 313 1500 829 310 1501 827 309 1502 828 317 1503 834 315 1504 832 314 1505 831 314 1506 831 315 1507 832 316 1508 833 320 1509 837 318 1510 835 319 1511 836 318 1512 835 321 1513 838 319 1514 836 319 1515 836 321 1516 838 317 1517 839 319 1518 836 317 1519 839 314 1520 840 320 1521 837 319 1522 836 314 1523 841 320 1524 837 314 1525 841 316 1526 842 316 1527 844 315 1528 843 320 1529 837 318 1530 835 320 1531 837 315 1532 843 315 1533 848 317 1534 846 318 1535 845 321 1536 847 318 1537 845 317 1538 846 325 1539 852 323 1540 850 322 1541 849 322 1542 849 323 1543 850 324 1544 851 328 1545 855 326 1546 853 327 1547 854 326 1548 853 329 1549 856 327 1550 854 327 1551 854 329 1552 856 325 1553 857 327 1554 854 325 1555 857 322 1556 858 328 1557 855 327 1558 854 322 1559 859 328 1560 855 322 1561 859 324 1562 860 326 1563 853 328 1564 855 324 1565 861 326 1566 853 324 1567 861 323 1568 862 329 1569 863 326 1570 864 323 1571 865 329 1572 863 323 1573 865 325 1574 866 367 1575 967 365 1576 965 364 1577 964 364 1578 964 365 1579 965 366 1580 966 370 1581 970 368 1582 968 369 1583 969 368 1584 968 371 1585 971 369 1586 969 369 1587 969 371 1588 971 367 1589 972 369 1590 969 367 1591 972 364 1592 973 370 1593 970 369 1594 969 364 1595 974 370 1596 970 364 1597 974 366 1598 975 366 1599 977 365 1600 976 370 1601 970 368 1602 968 370 1603 970 365 1604 976 365 1605 981 367 1606 979 368 1607 978 371 1608 980 368 1609 978 367 1610 979 375 1611 985 373 1612 983 372 1613 982 372 1614 982 373 1615 983 374 1616 984 378 1617 988 376 1618 986 377 1619 987 376 1620 986 379 1621 989 377 1622 987 375 1623 990 377 1624 987 379 1625 989 377 1626 987 375 1627 990 372 1628 991 378 1629 988 377 1630 987 372 1631 992 378 1632 988 372 1633 992 374 1634 993 374 1635 995 373 1636 994 378 1637 988 376 1638 986 378 1639 988 373 1640 994 373 1641 999 375 1642 997 376 1643 996 379 1644 998 376 1645 996 375 1646 997 383 1647 1003 381 1648 1001 380 1649 1000 380 1650 1000 381 1651 1001 382 1652 1002 386 1653 1006 384 1654 1004 385 1655 1005 384 1656 1004 387 1657 1007 385 1658 1005 383 1659 1008 385 1660 1005 387 1661 1007 385 1662 1005 383 1663 1008 380 1664 1009 386 1665 1006 385 1666 1005 380 1667 1010 386 1668 1006 380 1669 1010 382 1670 1011 384 1671 1004 386 1672 1006 382 1673 1012 384 1674 1004 382 1675 1012 381 1676 1013 387 1677 1014 384 1678 1015 381 1679 1016 387 1680 1014 381 1681 1016 383 1682 1017 389 1683 1019 388 1684 1018 391 1685 1021 388 1686 1018 389 1687 1019 390 1688 1020 393 1689 1023 394 1690 1024 392 1691 1022 392 1692 1022 395 1693 1025 393 1694 1023 391 1695 1027 388 1696 1026 395 1697 1025 393 1698 1023 395 1699 1025 388 1700 1026 394 1701 1024 393 1702 1023 388 1703 1028 394 1704 1024 388 1705 1028 390 1706 1029 392 1707 1022 394 1708 1024 390 1709 1030 392 1710 1022 390 1711 1030 389 1712 1031 395 1713 1032 392 1714 1033 389 1715 1034 395 1716 1032 389 1717 1034 391 1718 1035 397 1719 1037 396 1720 1036 399 1721 1039 396 1722 1036 397 1723 1037 398 1724 1038 401 1725 1041 402 1726 1042 400 1727 1040 400 1728 1040 403 1729 1043 401 1730 1041 401 1731 1041 403 1732 1043 399 1733 1044 401 1734 1041 399 1735 1044 396 1736 1045 402 1737 1042 401 1738 1041 396 1739 1046 402 1740 1042 396 1741 1046 398 1742 1047 398 1743 1048 400 1744 1040 402 1745 1042 400 1746 1040 398 1747 1048 397 1748 1049 403 1749 1050 400 1750 1051 397 1751 1052 403 1752 1050 397 1753 1052 399 1754 1053 407 1755 1057 405 1756 1055 404 1757 1054 404 1758 1054 405 1759 1055 406 1760 1056 410 1761 1060 408 1762 1058 409 1763 1059 408 1764 1058 411 1765 1061 409 1766 1059 409 1767 1059 411 1768 1061 407 1769 1062 409 1770 1059 407 1771 1062 404 1772 1063 410 1773 1060 409 1774 1059 404 1775 1064 410 1776 1060 404 1777 1064 406 1778 1065 406 1779 1067 405 1780 1066 410 1781 1060 408 1782 1058 410 1783 1060 405 1784 1066 405 1785 1071 407 1786 1069 408 1787 1068 411 1788 1070 408 1789 1068 407 1790 1069 415 1791 1075 413 1792 1073 412 1793 1072 412 1794 1072 413 1795 1073 414 1796 1074 418 1797 1078 416 1798 1076 417 1799 1077 416 1800 1076 419 1801 1079 417 1802 1077 415 1803 1080 417 1804 1077 419 1805 1079 417 1806 1077 415 1807 1080 412 1808 1081 418 1809 1078 417 1810 1077 412 1811 1082 418 1812 1078 412 1813 1082 414 1814 1083 414 1815 1085 413 1816 1084 418 1817 1078 416 1818 1076 418 1819 1078 413 1820 1084 413 1821 1089 415 1822 1087 416 1823 1086 419 1824 1088 416 1825 1086 415 1826 1087 430 1827 1116 428 1828 1114 429 1829 1115 428 1830 1114 431 1831 1117 429 1832 1115 433 1833 1119 432 1834 1118 435 1835 1121 432 1836 1118 433 1837 1119 434 1838 1120 433 1839 1119 435 1840 1121 431 1841 1122 433 1842 1119 431 1843 1122 428 1844 1123 433 1845 1119 430 1846 1125 434 1847 1120 430 1848 1125 433 1849 1119 428 1850 1124 430 1851 1127 432 1852 1118 434 1853 1120 432 1854 1118 430 1855 1127 429 1856 1126 429 1857 1131 431 1858 1129 432 1859 1128 435 1860 1130 432 1861 1128 431 1862 1129 438 1863 1134 436 1864 1132 437 1865 1133 436 1866 1132 439 1867 1135 437 1868 1133 441 1869 1137 440 1870 1136 443 1871 1139 440 1872 1136 441 1873 1137 442 1874 1138 441 1875 1137 443 1876 1139 439 1877 1140 441 1878 1137 439 1879 1140 436 1880 1141 442 1881 1138 441 1882 1137 436 1883 1142 442 1884 1138 436 1885 1142 438 1886 1143 438 1887 1145 437 1888 1144 442 1889 1138 440 1890 1136 442 1891 1138 437 1892 1144 437 1893 1149 439 1894 1147 440 1895 1146 443 1896 1148 440 1897 1146 439 1898 1147 446 1899 1152 444 1900 1150 445 1901 1151 444 1902 1150 447 1903 1153 445 1904 1151 449 1905 1155 448 1906 1154 451 1907 1157 448 1908 1154 449 1909 1155 450 1910 1156 449 1911 1155 451 1912 1157 447 1913 1158 449 1914 1155 447 1915 1158 444 1916 1159 450 1917 1156 449 1918 1155 444 1919 1160 450 1920 1156 444 1921 1160 446 1922 1161 448 1923 1154 450 1924 1156 446 1925 1162 448 1926 1154 446 1927 1162 445 1928 1163 451 1929 1164 448 1930 1165 445 1931 1166 451 1932 1164 445 1933 1166 447 1934 1167 454 1935 1170 452 1936 1168 453 1937 1169 452 1938 1168 455 1939 1171 453 1940 1169 457 1941 1173 456 1942 1172 459 1943 1175 456 1944 1172 457 1945 1173 458 1946 1174 457 1947 1173 459 1948 1175 455 1949 1176 457 1950 1173 455 1951 1176 452 1952 1177 458 1953 1174 457 1954 1173 452 1955 1178 458 1956 1174 452 1957 1178 454 1958 1179 456 1959 1172 458 1960 1174 454 1961 1180 456 1962 1172 454 1963 1180 453 1964 1181 453 1965 1185 455 1966 1183 456 1967 1182 459 1968 1184 456 1969 1182 455 1970 1183

+
+
+
+ + + + + + + + + 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.0000001.000000 + 30.0000000.0000003.333333 + + + + + +
diff --git a/simulators/sim_env/models/aws_robomaker_warehouse_ShelfD_01/model.config b/simulators/sim_env/models/aws_robomaker_warehouse_ShelfD_01/model.config new file mode 100755 index 0000000..c91fbb1 --- /dev/null +++ b/simulators/sim_env/models/aws_robomaker_warehouse_ShelfD_01/model.config @@ -0,0 +1,11 @@ + + + aws_robomaker_warehouse_ShelfD_01 + 1.0 + model.sdf + + + + + + diff --git a/simulators/sim_env/models/aws_robomaker_warehouse_ShelfD_01/model.sdf b/simulators/sim_env/models/aws_robomaker_warehouse_ShelfD_01/model.sdf new file mode 100755 index 0000000..17c326e --- /dev/null +++ b/simulators/sim_env/models/aws_robomaker_warehouse_ShelfD_01/model.sdf @@ -0,0 +1,46 @@ + + + + + + 30 + + 907.144 + 0 + 0 + 104.950 + 0 + 824.248 + + + + + + model://aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + model://aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_visual.DAE + + + 1 + + +1 + + diff --git a/simulators/sim_env/models/aws_robomaker_warehouse_ShelfE_01/materials/textures/aws_robomaker_warehouse_ShelfE_01.png b/simulators/sim_env/models/aws_robomaker_warehouse_ShelfE_01/materials/textures/aws_robomaker_warehouse_ShelfE_01.png new file mode 100755 index 0000000..d33ba54 Binary files /dev/null and b/simulators/sim_env/models/aws_robomaker_warehouse_ShelfE_01/materials/textures/aws_robomaker_warehouse_ShelfE_01.png differ diff --git a/simulators/sim_env/models/aws_robomaker_warehouse_ShelfE_01/materials/textures/aws_robomaker_warehouse_ShelfE_02.png b/simulators/sim_env/models/aws_robomaker_warehouse_ShelfE_01/materials/textures/aws_robomaker_warehouse_ShelfE_02.png new file mode 100755 index 0000000..b28b289 Binary files /dev/null and b/simulators/sim_env/models/aws_robomaker_warehouse_ShelfE_01/materials/textures/aws_robomaker_warehouse_ShelfE_02.png differ diff --git a/simulators/sim_env/models/aws_robomaker_warehouse_ShelfE_01/materials/textures/aws_robomaker_warehouse_ShelfE_03.png b/simulators/sim_env/models/aws_robomaker_warehouse_ShelfE_01/materials/textures/aws_robomaker_warehouse_ShelfE_03.png new file mode 100755 index 0000000..4b7e610 Binary files /dev/null and b/simulators/sim_env/models/aws_robomaker_warehouse_ShelfE_01/materials/textures/aws_robomaker_warehouse_ShelfE_03.png differ diff --git a/simulators/sim_env/models/aws_robomaker_warehouse_ShelfE_01/materials/textures/aws_robomaker_warehouse_ShelfE_04.png b/simulators/sim_env/models/aws_robomaker_warehouse_ShelfE_01/materials/textures/aws_robomaker_warehouse_ShelfE_04.png new file mode 100755 index 0000000..e76fcdd Binary files /dev/null and b/simulators/sim_env/models/aws_robomaker_warehouse_ShelfE_01/materials/textures/aws_robomaker_warehouse_ShelfE_04.png differ diff --git a/simulators/sim_env/models/aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_collision.DAE b/simulators/sim_env/models/aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_collision.DAE new file mode 100755 index 0000000..5922d31 --- /dev/null +++ b/simulators/sim_env/models/aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_collision.DAE @@ -0,0 +1,327 @@ + + + FBX COLLADA exporter2019-05-15T10:11:35Z2019-05-15T10:11:35ZZ_UP + + + + + +-45.044750 -57.560341 195.803909 +42.866188 -57.560341 195.803955 +-45.044750 133.195770 195.803955 +42.866188 133.195770 195.803986 +-45.044781 -57.560341 -195.804031 +42.866158 -57.560341 -195.804001 +-45.044781 133.195770 -195.803986 +42.866158 133.195770 -195.803970 +-44.361427 -128.142014 1.402283 +42.927315 -128.142014 1.402374 +-44.361427 133.195755 1.402374 +42.927315 133.195755 1.402420 +-44.361412 -128.141998 -4.198639 +42.927338 -128.141998 -4.198563 +-44.361412 133.195786 -4.198517 +42.927338 133.195786 -4.198456 +-44.361458 -128.142029 -190.318237 +42.927284 -128.142029 -190.318130 +42.927284 133.195740 -190.318039 +-44.361458 133.195740 -190.318130 +-44.361443 -128.142014 -195.919159 +-44.361443 133.195770 -195.919022 +42.927307 133.195770 -195.918884 +42.927307 -128.142014 -195.919037 +-44.361401 -128.141998 195.912140 +42.927341 -128.141998 195.912231 +-44.361401 133.195770 195.912231 +42.927341 133.195770 195.912277 +-44.361378 -128.141983 190.311218 +42.927372 -128.141983 190.311295 +-44.361378 133.195801 190.311340 +42.927372 133.195801 190.311401 + + + + + + + + + + + +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +-0.000000 -0.000000 1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +1.000000 0.000000 -0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-1.000000 -0.000000 0.000000 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +1.000000 -0.000000 0.000004 +1.000000 -0.000000 0.000004 +1.000000 -0.000000 0.000004 +1.000000 -0.000000 0.000004 +1.000000 -0.000000 0.000004 +1.000000 -0.000000 0.000004 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-1.000000 0.000000 -0.000003 +-1.000000 0.000000 -0.000003 +-1.000000 0.000000 -0.000003 +-1.000000 0.000000 -0.000003 +-1.000000 0.000000 -0.000003 +-1.000000 0.000000 -0.000003 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +0.000001 0.000001 -1.000000 +0.000001 0.000001 -1.000000 +0.000001 0.000001 -1.000000 +0.000001 0.000001 -1.000000 +0.000001 0.000001 -1.000000 +0.000001 0.000001 -1.000000 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +1.000000 -0.000000 0.000004 +1.000000 -0.000000 0.000004 +1.000000 -0.000000 0.000004 +1.000000 -0.000000 0.000004 +1.000000 -0.000000 0.000004 +1.000000 -0.000000 0.000004 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-1.000000 0.000000 -0.000003 +-1.000000 0.000000 -0.000003 +-1.000000 0.000000 -0.000003 +-1.000000 0.000000 -0.000003 +-1.000000 0.000000 -0.000003 +-1.000000 0.000000 -0.000003 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +-0.000001 -0.000000 1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000001 0.000000 -1.000000 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +0.000000 -1.000000 -0.000003 +1.000000 -0.000000 0.000005 +1.000000 -0.000000 0.000005 +1.000000 -0.000000 0.000005 +1.000000 -0.000000 0.000005 +1.000000 -0.000000 0.000005 +1.000000 -0.000000 0.000005 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-0.000000 1.000000 0.000005 +-1.000000 0.000000 -0.000004 +-1.000000 0.000000 -0.000004 +-1.000000 0.000000 -0.000004 +-1.000000 0.000000 -0.000004 +-1.000000 0.000000 -0.000004 +-1.000000 0.000000 -0.000004 + + + + + + + + + + + +1.000000 0.000000 +0.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +1.000000 0.000000 +0.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +1.000000 0.000000 +0.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +1.000000 0.000000 +0.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +1.000000 0.000000 +0.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +1.000000 0.000000 +0.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +1.000000 0.000000 +0.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +1.000000 0.000000 +1.000000 0.000000 +0.000000 0.000000 +1.000000 1.000000 +0.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 +0.000000 0.000000 +1.000000 0.000000 +0.000000 1.000000 +1.000000 1.000000 + + + + + + + + + + + +

2 0 2 0 1 0 3 2 3 3 3 3 0 4 0 1 5 1 7 6 7 5 7 5 4 8 4 4 9 4 6 10 6 7 11 7 5 12 11 1 13 9 0 14 8 0 15 8 4 16 10 5 17 11 7 18 15 3 19 13 1 20 12 1 21 12 5 22 14 7 23 15 2 24 17 7 25 18 6 26 19 7 27 18 2 28 17 3 29 16 0 30 21 6 31 22 4 32 23 6 33 22 0 34 21 2 35 20 10 36 26 8 37 24 11 38 27 11 39 27 8 40 24 9 41 25 15 42 31 13 43 29 12 44 28 12 45 28 14 46 30 15 47 31 12 48 34 9 49 33 8 50 32 9 51 33 12 52 34 13 53 35 13 54 38 11 55 37 9 56 36 11 57 37 13 58 38 15 59 39 15 60 42 14 61 43 11 62 40 10 63 41 11 64 40 14 65 43 14 66 46 12 67 47 10 68 44 8 69 45 10 70 44 12 71 47 19 72 51 16 73 48 18 74 50 18 75 50 16 76 48 17 77 49 22 78 54 23 79 55 20 80 52 20 81 52 21 82 53 22 83 54 20 84 57 17 85 59 16 86 56 17 87 59 20 88 57 23 89 58 23 90 61 18 91 63 17 92 60 18 93 63 23 94 61 22 95 62 22 96 65 21 97 66 18 98 64 19 99 67 18 100 64 21 101 66 21 102 69 20 103 70 19 104 68 16 105 71 19 106 68 20 107 70 26 108 74 24 109 72 27 110 75 27 111 75 24 112 72 25 113 73 31 114 79 29 115 77 28 116 76 28 117 76 30 118 78 31 119 79 28 120 82 25 121 81 24 122 80 25 123 81 28 124 82 29 125 83 29 126 86 27 127 85 25 128 84 27 129 85 29 130 86 31 131 87 31 132 90 30 133 91 27 134 88 26 135 89 27 136 88 30 137 91 30 138 94 28 139 95 26 140 92 24 141 93 26 142 92 28 143 95

+
+
+
+ + + -0.000000 -0.000000 -1.000000 0.000000 -1.000000 0.000000 0.000000 -1.072197 0.000000 1.000000 -0.000000 131.071121 0.000000 0.000000 0.000000 1.0000001.000000 + 30.0000000.0000003.333333 + + + + + +
diff --git a/simulators/sim_env/models/aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_visual.DAE b/simulators/sim_env/models/aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_visual.DAE new file mode 100755 index 0000000..2caad6b --- /dev/null +++ b/simulators/sim_env/models/aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_visual.DAE @@ -0,0 +1,3689 @@ + + + FBX COLLADA exporter2019-05-27T02:53:28Z2019-05-27T02:53:28ZZ_UP + + + ../materials/textures/aws_robomaker_warehouse_ShelfE_01.png + + + ../materials/textures/aws_robomaker_warehouse_ShelfE_03.png + + + ../materials/textures/aws_robomaker_warehouse_ShelfE_02.png + + + ../materials/textures/aws_robomaker_warehouse_ShelfE_03.png + + + + + + + + + + + + + + + + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + 0.800000 0.800000 0.800000 1.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.588000 0.588000 0.588000 1.000000 + + + + + + TRUE + TRUE + ADD + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + +-195.859360 -43.970364 11.286113 +-190.346848 -43.970360 11.286113 +-195.851028 -40.870396 -0.039542 +-195.851028 -43.964931 -0.039542 +-190.355179 -40.870392 -0.039542 +-190.355179 -43.964924 -0.039542 +-195.859344 -40.864964 11.286113 +-190.346863 -40.864960 11.286113 +-195.359573 -41.130783 11.389088 +-195.359573 -43.704540 11.389088 +-190.846634 -41.130779 11.389088 +-190.846634 -43.704540 11.389087 +-195.337234 -41.142639 261.250977 +-195.337234 -43.692688 261.250977 +-190.868851 -41.142639 261.250977 +-190.868851 -43.692688 261.250977 +190.346771 40.164623 11.286113 +195.859314 40.164623 11.286113 +190.355118 43.264595 -0.039542 +190.355118 40.170063 -0.039542 +195.850967 43.264603 -0.039542 +195.850967 40.170067 -0.039542 +190.346802 43.270035 11.286113 +195.859314 43.270039 11.286113 +190.846542 43.004223 11.389088 +190.846558 40.430458 11.389088 +195.359558 43.004227 11.389088 +195.359573 40.430462 11.389087 +190.868851 42.992374 261.250977 +190.868851 40.442318 261.250977 +195.337234 42.992374 261.250977 +195.337219 40.442322 261.250977 +-195.859360 40.164501 11.286113 +-190.346848 40.164501 11.286113 +-195.851028 43.264473 -0.039542 +-195.851028 40.169941 -0.039542 +-190.355179 43.264481 -0.039542 +-190.355179 40.169945 -0.039542 +-195.859344 43.269913 11.286113 +-190.346863 43.269917 11.286113 +-195.359573 43.004101 11.389088 +-195.359573 40.430336 11.389088 +-190.846634 43.004105 11.389088 +-190.846634 40.430340 11.389087 +-195.337234 42.992252 261.250977 +-195.337234 40.442196 261.250977 +-190.868851 42.992252 261.250977 +-190.868851 40.442200 261.250977 +-1.349450 40.164562 11.286113 +4.163049 40.164562 11.286113 +-1.341129 43.264534 -0.039542 +-1.341129 40.170002 -0.039542 +4.154719 43.264542 -0.039542 +4.154719 40.170006 -0.039542 +-1.349450 43.269974 11.286113 +4.163049 43.269978 11.286113 +-0.849689 43.004162 11.389088 +-0.849689 40.430397 11.389088 +3.663298 43.004166 11.389088 +3.663298 40.430401 11.389087 +-0.827415 42.992313 261.250977 +-0.827372 40.442257 261.250977 +3.640989 42.992317 261.250977 +3.641029 40.442265 261.250977 +-1.349419 -43.970303 11.286113 +4.163079 -43.970299 11.286113 +-1.341098 -40.870335 -0.039542 +-1.341098 -43.964870 -0.039542 +4.154749 -40.870331 -0.039542 +4.154749 -43.964863 -0.039542 +-1.349419 -40.864902 11.286113 +4.163079 -40.864899 11.286113 +-0.849659 -41.130722 11.389088 +-0.849659 -43.704479 11.389088 +3.663328 -41.130718 11.389088 +3.663328 -43.704479 11.389087 +-0.827342 -41.142574 261.250977 +-0.827328 -43.692627 261.250977 +3.641059 -41.142570 261.250977 +3.641079 -43.692627 261.250977 +190.346817 -43.970242 11.286113 +195.859329 -43.970238 11.286113 +190.355164 -40.870274 -0.039542 +190.355164 -43.964809 -0.039542 +195.850998 -40.870270 -0.039542 +195.850998 -43.964802 -0.039542 +190.346817 -40.864841 11.286113 +195.859329 -40.864838 11.286113 +190.846588 -41.130661 11.389088 +190.846588 -43.704418 11.389088 +195.359573 -41.130657 11.389088 +195.359573 -43.704418 11.389087 +190.868866 -41.142517 261.250977 +190.868881 -43.692566 261.250977 +195.337250 -41.142517 261.250977 +195.337265 -43.692566 261.250977 +-195.319946 -41.125313 13.878565 +-195.319916 40.434727 66.278061 +-190.886261 -41.125309 13.878560 +-195.319916 40.434727 70.460434 +-190.886246 -41.125320 9.696195 +-190.886246 40.434731 70.460434 +-195.319946 -41.125324 9.696195 +-190.886261 40.434731 66.278061 +-195.319992 -41.186462 144.465973 +-195.320007 40.434692 195.103180 +-195.320007 40.434704 199.280792 +-190.886292 -41.186459 144.465958 +-190.886322 40.434708 199.280792 +-190.886292 -41.186459 141.219635 +-190.886322 40.434696 195.103180 +-195.320007 -41.186462 141.219635 +-195.319946 -41.125320 134.569077 +-195.319916 40.434727 77.097397 +-195.319946 -41.125313 130.386719 +-190.886246 40.434731 77.097397 +-190.886261 40.434731 81.279785 +-190.886261 -41.125309 130.386734 +-190.886246 -41.125313 134.569077 +-195.319916 40.434727 81.279785 +190.824371 -41.125099 13.878565 +190.824371 40.434959 66.278061 +195.258072 -41.125080 13.878560 +190.824371 40.434959 70.460434 +195.258057 40.434978 70.460434 +195.258072 -41.125092 9.696197 +190.824371 -41.125111 9.696197 +195.258057 40.434978 66.278061 +190.824402 -41.186249 144.465973 +190.824356 40.434921 195.103180 +190.824341 40.434937 199.280792 +195.258087 -41.186234 144.465958 +195.258057 40.434948 199.280792 +195.258102 -41.186234 141.219635 +195.258057 40.434937 195.103180 +190.824402 -41.186249 141.219635 +190.824387 -41.125107 134.569061 +190.824402 40.434959 77.097397 +190.824387 -41.125099 130.386719 +195.258072 40.434978 77.097397 +195.258072 40.434978 81.279762 +195.258087 -41.125080 130.386719 +195.258087 -41.125088 134.569061 +190.824402 40.434959 81.279762 +-1.008084 -41.125114 13.878565 +-1.008087 40.434952 66.278061 +3.425621 -41.125095 13.878560 +-1.008087 40.434952 70.460434 +3.425587 40.434975 70.460434 +3.425621 -41.125103 9.696197 +-1.008084 -41.125122 9.696197 +3.425587 40.434975 66.278061 +-1.008060 -41.186264 144.465973 +-1.008118 40.434917 195.103180 +-1.008118 40.434925 199.280792 +3.425625 -41.186237 144.465958 +3.425590 40.434948 199.280792 +3.425625 -41.186237 141.219635 +3.425591 40.434937 195.103180 +-1.008060 -41.186264 141.219635 +-1.008083 -41.125118 134.569061 +-1.008064 40.434952 77.097397 +-1.008083 -41.125114 130.386719 +3.425602 40.434975 77.097397 +3.425602 40.434975 81.279762 +3.425617 -41.125095 130.386719 +3.425617 -41.125099 134.569061 +-1.008064 40.434952 81.279762 +190.734039 -41.267357 256.299133 +190.734024 41.439137 256.299133 +190.734039 -41.267357 259.323669 +190.734024 41.439137 259.323669 +195.278412 -41.267353 256.299133 +195.278397 41.439140 256.299133 +195.278412 -41.267353 259.323669 +195.278397 41.439140 259.323669 +-0.895264 -41.267330 256.299133 +-0.895294 41.439167 256.299133 +-0.895264 -41.267330 259.323669 +-0.895294 41.439167 259.323669 +3.649109 -41.267326 256.299133 +3.649078 41.439171 256.299133 +3.649109 -41.267326 259.323669 +3.649078 41.439171 259.323669 +-195.473846 -41.267296 256.299133 +-195.473846 41.439198 256.299133 +-195.473846 -41.267296 259.323669 +-195.473846 41.439198 259.323669 +-190.929474 -41.267292 256.299133 +-190.929474 41.439201 256.299133 +-190.929474 -41.267292 259.323669 +-190.929474 41.439201 259.323669 +-192.401459 38.361286 242.060989 +193.412613 38.361374 242.060989 +-192.401459 43.984394 236.176102 +-192.401459 38.361290 236.176102 +193.412598 43.984470 236.176102 +193.412613 38.361374 236.176102 +-192.401459 43.984390 242.060989 +193.412628 43.984474 242.060989 +-192.401535 -42.179398 140.859955 +193.412781 -42.179111 140.859970 +-192.401535 41.115921 134.975082 +-192.401505 -42.179394 134.975082 +193.412735 41.116199 134.975098 +193.412781 -42.179108 134.975098 +-192.401535 41.115921 140.859955 +193.412735 41.116199 140.859955 +-192.401535 -42.179398 76.744461 +193.412781 -42.179111 76.744469 +-192.401535 41.115921 70.859589 +-192.401505 -42.179394 70.859589 +193.412735 41.116199 70.859596 +193.412781 -42.179108 70.859596 +-192.401535 41.115921 76.744453 +193.412735 41.116199 76.744476 +-192.401535 41.115921 196.922226 +193.412735 41.116207 196.922226 +-192.401535 -42.179398 196.922226 +-192.401535 -42.179394 202.807083 +193.412781 -42.179111 196.922226 +193.412781 -42.179111 202.807083 +193.412735 41.116207 202.807083 +-192.401535 41.115925 202.807083 +-100.515869 25.034658 96.767853 +-178.499268 25.176374 76.381248 +-178.499268 25.176497 96.767883 +-100.515869 25.034658 76.381271 +-100.603271 -22.747515 76.381271 +-178.586060 -22.605913 76.381248 +-178.586060 -22.605837 96.767883 +-100.603271 -22.747606 96.767868 +-10.756012 25.034658 96.767853 +-88.739410 25.176374 76.381248 +-88.739410 25.176497 96.767883 +-10.756012 25.034658 76.381271 +-10.843414 -22.747515 76.381271 +-88.826202 -22.605913 76.381248 +-88.826202 -22.605837 96.767883 +-10.843414 -22.747606 96.767868 +-136.529434 -37.821102 161.109482 +-136.387711 40.162300 140.722885 +-136.387589 40.162300 161.109512 +-136.529434 -37.821102 140.722916 +-184.311539 -37.733696 140.722916 +-184.169937 40.249088 140.722885 +-184.169937 40.249088 161.109512 +-184.311661 -37.733696 161.109512 +72.596710 29.278488 123.836227 +72.890900 -25.122681 76.618340 +72.596710 29.278488 76.618340 +72.890900 -25.122711 123.836227 +8.309597 -25.279179 76.618340 +8.015530 29.122051 76.618340 +9.438137 29.125500 123.836227 +8.309963 -25.279179 123.836227 +8.016140 29.122051 123.836227 +189.951172 -36.224636 75.382462 +137.447266 39.841038 75.382462 +189.951172 39.841278 75.382446 +137.447266 -36.224880 75.382469 +137.447266 39.841038 82.989067 +189.951172 -36.224636 82.989067 +189.951172 39.841278 82.989052 +137.447266 -36.224880 82.989075 +189.951172 -36.224636 83.132347 +137.447266 39.841038 83.132355 +189.951172 39.841278 83.132332 +137.447266 -36.224880 83.132370 +137.447266 39.841038 90.738976 +189.951172 -36.224636 90.738960 +189.951172 39.841278 90.738960 +137.447266 -36.224880 90.738976 +-112.536499 29.278488 250.422791 +-112.242310 -25.122681 203.204910 +-112.536499 29.278488 203.204910 +-112.242310 -25.122711 250.422791 +-176.823608 -25.279179 203.204910 +-177.117676 29.122051 203.204910 +-175.695068 29.125500 250.422791 +-176.823242 -25.279179 250.422791 +-177.117065 29.122051 250.422791 +95.399185 25.034658 161.436584 +17.415787 25.176378 141.049973 +17.415787 25.176500 161.436615 +95.399185 25.034658 141.049988 +95.311783 -22.747515 141.049988 +17.328995 -22.605909 141.049973 +17.328995 -22.605833 161.436615 +95.311783 -22.747606 161.436584 +95.399185 25.034658 182.055481 +17.415787 25.176382 161.668884 +17.415787 25.176504 182.055511 +95.399185 25.034658 161.668884 +95.311783 -22.747519 161.668884 +17.328995 -22.605909 161.668884 +17.328995 -22.605833 182.055511 +95.311783 -22.747610 182.055481 +82.850586 25.034658 222.664795 +4.867188 25.176378 202.278183 +4.867188 25.176500 222.664825 +82.850586 25.034658 202.278198 +82.763184 -22.747515 202.278198 +4.780396 -22.605909 202.278183 +4.780396 -22.605833 222.664825 +82.763184 -22.747606 222.664795 +-92.589783 -24.403721 203.107849 +-16.469368 28.020813 203.107849 +-16.523869 -24.483076 203.107834 +-92.535278 28.100182 203.107864 +-16.469368 28.020813 210.714432 +-92.589783 -24.403721 210.714432 +-16.523869 -24.483076 210.714462 +-92.535278 28.100182 210.714462 +-92.589783 -24.403721 210.857742 +-16.469368 28.020813 210.857742 +-16.523869 -24.483076 210.857712 +-92.535278 28.100182 210.857758 +-16.469368 28.020813 218.464371 +-92.589783 -24.403721 218.464340 +-16.523869 -24.483076 218.464340 +-92.535278 28.100182 218.464371 +-92.590866 -24.403788 218.585449 +-16.470409 28.020967 218.585449 +-16.524956 -24.483145 218.585449 +-92.536324 28.100309 218.585449 +-16.470409 28.020967 226.192017 +-92.590866 -24.403788 226.192017 +-16.524956 -24.483145 226.192017 +-92.536324 28.100309 226.192017 +162.264526 25.034658 222.664795 +84.281128 25.176378 202.278183 +84.281128 25.176500 222.664825 +162.264526 25.034658 202.278198 +162.177124 -22.747515 202.278198 +84.194336 -22.605909 202.278183 +84.194336 -22.605833 222.664825 +162.177124 -22.747606 222.664795 +162.264526 25.034658 243.283691 +84.281128 25.176382 222.897095 +84.281128 25.176504 243.283722 +162.264526 25.034658 222.897095 +162.177124 -22.747519 222.897095 +84.194336 -22.605909 222.897095 +84.194336 -22.605833 243.283722 +162.177124 -22.747610 243.283691 +66.539444 -9.329350 242.569305 +156.241531 12.946537 242.569305 +137.709412 -36.178265 242.569305 +85.071533 39.795441 242.569305 +156.241531 12.946537 250.175873 +66.539444 -9.329350 250.175873 +137.709412 -36.178265 250.175873 +85.071533 39.795441 250.175873 +-2.835217 29.278488 188.737320 +-2.541027 -25.122681 141.519440 +-2.835217 29.278488 141.519440 +-2.541027 -25.122711 188.737320 +-67.122330 -25.279179 141.519440 +-67.416397 29.122051 141.519440 +-65.993790 29.125500 188.737320 +-67.121964 -25.279179 188.737320 +-67.415787 29.122051 188.737320 +-74.777939 -36.224636 141.372421 +-127.281845 39.841038 141.372421 +-74.777939 39.841278 141.372391 +-127.281845 -36.224880 141.372421 +-127.281845 39.841038 148.979019 +-74.777939 -36.224636 148.979019 +-74.777939 39.841278 148.979004 +-127.281845 -36.224880 148.979019 +-74.777939 -36.224636 149.122299 +-127.281845 39.841038 149.122299 +-74.777939 39.841278 149.122284 +-127.281845 -36.224880 149.122330 +-127.281845 39.841038 156.728928 +-74.777939 -36.224636 156.728912 +-74.777939 39.841278 156.728912 +-127.281845 -36.224880 156.728928 +-74.778671 -36.224316 156.850021 +-127.282822 39.841358 156.850021 +-74.778671 39.841599 156.850021 +-127.282822 -36.224560 156.850021 +-127.282822 39.841358 164.456589 +-74.778671 -36.224316 164.456589 +-74.778671 39.841599 164.456589 +-127.282822 -36.224560 164.456589 +-74.777939 -36.224632 164.726944 +-127.281845 39.841042 164.726944 +-74.777939 39.841278 164.726944 +-127.281845 -36.224876 164.726944 +-127.281845 39.841042 172.333511 +-74.777939 -36.224632 172.333511 +-74.777939 39.841278 172.333511 +-127.281845 -36.224876 172.333542 +130.889359 -36.224636 75.382462 +78.385452 39.841038 75.382462 +130.889359 39.841278 75.382446 +78.385452 -36.224880 75.382469 +78.385452 39.841038 82.989067 +130.889359 -36.224636 82.989067 +130.889359 39.841278 82.989052 +78.385452 -36.224880 82.989075 +130.889359 -36.224636 83.132347 +78.385452 39.841038 83.132355 +130.889359 39.841278 83.132332 +78.385452 -36.224880 83.132370 +78.385452 39.841038 90.738976 +130.889359 -36.224636 90.738960 +130.889359 39.841278 90.738960 +78.385452 -36.224880 90.738976 +130.888626 -36.224316 90.860062 +78.384476 39.841358 90.860062 +130.888626 39.841599 90.860062 +78.384476 -36.224560 90.860062 +78.384476 39.841358 98.466629 +130.888626 -36.224316 98.466629 +130.888626 39.841599 98.466629 +78.384476 -36.224560 98.466629 +130.889359 -36.224632 98.737000 +78.385452 39.841042 98.737000 +130.889359 39.841278 98.737000 +78.385452 -36.224876 98.737000 +78.385452 39.841042 106.343567 +130.889359 -36.224632 106.343567 +130.889359 39.841278 106.343567 +78.385452 -36.224876 106.343582 +169.132980 29.278488 188.737320 +169.427170 -25.122681 141.519440 +169.132980 29.278488 141.519440 +169.427170 -25.122711 188.737320 +104.845879 -25.279179 141.519440 +104.551811 29.122051 141.519440 +105.974419 29.125500 188.737320 +104.846245 -25.279179 188.737320 +104.552422 29.122051 188.737320 + + + + + + + + + + + +0.119405 -0.230384 -0.965746 +-0.119235 -0.230441 -0.965754 +-0.119211 0.230672 -0.965701 +-0.119211 0.230672 -0.965701 +0.119380 0.230616 -0.965694 +0.119405 -0.230384 -0.965746 +-0.956403 -0.263505 0.125933 +-0.956333 0.263761 0.125924 +-0.951498 0.257330 -0.168618 +-0.951498 0.257330 -0.168618 +-0.951559 -0.257087 -0.168648 +-0.956403 -0.263505 0.125933 +0.089169 -0.993226 0.074504 +-0.089036 -0.993235 0.074540 +-0.085984 -0.990457 -0.107708 +-0.085984 -0.990457 -0.107708 +0.086116 -0.990450 -0.107670 +0.089169 -0.993226 0.074504 +0.956359 0.263819 0.125605 +0.956429 -0.263562 0.125613 +0.951558 -0.257089 -0.168647 +0.951558 -0.257089 -0.168647 +0.951499 0.257328 -0.168619 +0.956359 0.263819 0.125605 +-0.089268 0.993198 0.074763 +0.089400 0.993189 0.074727 +0.086342 0.990400 -0.107949 +0.086342 0.990400 -0.107949 +-0.086212 0.990407 -0.107986 +-0.089268 0.993198 0.074763 +-0.059645 -0.051640 0.996883 +-0.059645 0.051639 0.996883 +-0.178122 0.324574 0.928937 +-0.178122 0.324574 0.928937 +-0.178085 -0.324917 0.928824 +-0.059645 -0.051640 0.996883 +0.059645 -0.051639 0.996883 +-0.059645 -0.051640 0.996883 +-0.178085 -0.324917 0.928824 +-0.178085 -0.324917 0.928824 +0.178086 -0.324915 0.928825 +0.059645 -0.051639 0.996883 +0.059645 0.051640 0.996883 +0.059645 -0.051639 0.996883 +0.178086 -0.324915 0.928825 +0.178086 -0.324915 0.928825 +0.178121 0.324575 0.928937 +0.059645 0.051640 0.996883 +-0.059645 0.051639 0.996883 +0.059645 0.051640 0.996883 +0.178121 0.324575 0.928937 +0.178121 0.324575 0.928937 +-0.178122 0.324574 0.928937 +-0.059645 0.051639 0.996883 +-0.956902 -0.286501 -0.047494 +-0.956754 0.286993 -0.047506 +-0.935699 0.302882 0.180917 +-0.935699 0.302882 0.180917 +-0.935847 -0.302400 0.180955 +-0.956902 -0.286501 -0.047494 +0.094684 -0.995181 -0.025483 +-0.094927 -0.995157 -0.025505 +-0.097945 -0.990243 0.099122 +-0.097945 -0.990243 0.099122 +0.097942 -0.990243 0.099126 +0.094684 -0.995181 -0.025483 +0.956974 0.286285 -0.047354 +0.957125 -0.285780 -0.047344 +0.935975 -0.302063 0.180856 +0.935975 -0.302063 0.180856 +0.935830 0.302532 0.180824 +0.956974 0.286285 -0.047354 +-0.095144 0.995135 -0.025563 +0.094891 0.995160 -0.025542 +0.098119 0.990255 0.098831 +0.098119 0.990255 0.098831 +-0.098117 0.990255 0.098834 +-0.095144 0.995135 -0.025563 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.119375 -0.230443 -0.965736 +-0.119330 -0.230456 -0.965738 +-0.119314 0.230833 -0.965650 +-0.119314 0.230833 -0.965650 +0.119359 0.230820 -0.965648 +0.119375 -0.230443 -0.965736 +-0.956450 -0.263645 0.125275 +-0.956341 0.264048 0.125261 +-0.951446 0.257519 -0.168624 +-0.951446 0.257519 -0.168624 +-0.951550 -0.257121 -0.168644 +-0.956450 -0.263645 0.125275 +0.089316 -0.993153 0.075303 +-0.089283 -0.993155 0.075314 +-0.086285 -0.990402 -0.107976 +-0.086285 -0.990402 -0.107976 +0.086320 -0.990400 -0.107968 +0.089316 -0.993153 0.075303 +0.956265 0.264181 0.125560 +0.956375 -0.263778 0.125574 +0.951481 -0.257288 -0.168778 +0.951481 -0.257288 -0.168778 +0.951378 0.257683 -0.168759 +0.956265 0.264181 0.125560 +-0.089247 0.993157 0.075321 +0.089277 0.993155 0.075311 +0.086286 0.990407 -0.107928 +0.086286 0.990407 -0.107928 +-0.086253 0.990409 -0.107936 +-0.089247 0.993157 0.075321 +-0.059706 -0.051712 0.996876 +-0.059706 0.051713 0.996876 +-0.178425 0.325176 0.928668 +-0.178425 0.325176 0.928668 +-0.178431 -0.325180 0.928666 +-0.059706 -0.051712 0.996876 +0.059722 -0.051734 0.996873 +-0.059706 -0.051712 0.996876 +-0.178431 -0.325180 0.928666 +-0.178431 -0.325180 0.928666 +0.178585 -0.325143 0.928649 +0.059722 -0.051734 0.996873 +0.059722 0.051734 0.996874 +0.059722 -0.051734 0.996873 +0.178585 -0.325143 0.928649 +0.178585 -0.325143 0.928649 +0.178656 0.325122 0.928643 +0.059722 0.051734 0.996874 +-0.059706 0.051713 0.996876 +0.059722 0.051734 0.996874 +0.178656 0.325122 0.928643 +0.178656 0.325122 0.928643 +-0.178425 0.325176 0.928668 +-0.059706 0.051713 0.996876 +-0.956803 -0.286841 -0.047442 +-0.956947 0.286356 -0.047456 +-0.935859 0.302824 0.180182 +-0.935859 0.302824 0.180182 +-0.935721 -0.303220 0.180234 +-0.956803 -0.286841 -0.047442 +0.094855 -0.995165 -0.025491 +-0.094809 -0.995169 -0.025488 +-0.097976 -0.990204 0.099478 +-0.097976 -0.990204 0.099478 +0.098011 -0.990200 0.099489 +0.094855 -0.995165 -0.025491 +0.957166 0.285648 -0.047304 +0.957038 -0.286079 -0.047293 +0.935784 -0.303054 0.180183 +0.935784 -0.303054 0.180183 +0.935925 0.302646 0.180138 +0.957166 0.285648 -0.047304 +-0.095272 0.995122 -0.025614 +0.095311 0.995118 -0.025619 +0.098367 0.990224 0.098898 +0.098367 0.990224 0.098898 +-0.098322 0.990228 0.098898 +-0.095272 0.995122 -0.025614 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.119401 -0.230417 -0.965739 +-0.119231 -0.230474 -0.965746 +-0.119216 0.230850 -0.965658 +-0.119216 0.230850 -0.965658 +0.119385 0.230794 -0.965651 +0.119401 -0.230417 -0.965739 +-0.956398 -0.263530 0.125914 +-0.956289 0.263933 0.125901 +-0.951446 0.257519 -0.168624 +-0.951446 0.257519 -0.168624 +-0.951550 -0.257121 -0.168644 +-0.956398 -0.263530 0.125914 +0.089337 -0.993152 0.075283 +-0.089204 -0.993161 0.075319 +-0.086211 -0.990407 -0.107986 +-0.086211 -0.990407 -0.107986 +0.086343 -0.990400 -0.107948 +0.089337 -0.993152 0.075283 +0.956315 0.263991 0.125581 +0.956424 -0.263587 0.125595 +0.951550 -0.257123 -0.168644 +0.951550 -0.257123 -0.168644 +0.951446 0.257518 -0.168624 +0.956315 0.263991 0.125581 +-0.089167 0.993164 0.075327 +0.089299 0.993155 0.075291 +0.086309 0.990407 -0.107909 +0.086309 0.990407 -0.107909 +-0.086179 0.990414 -0.107946 +-0.089167 0.993164 0.075327 +-0.059651 -0.051645 0.996882 +-0.059652 0.051644 0.996882 +-0.178090 0.325226 0.928715 +-0.178090 0.325226 0.928715 +-0.178095 -0.325230 0.928713 +-0.059651 -0.051645 0.996882 +0.059652 -0.051644 0.996882 +-0.059651 -0.051645 0.996882 +-0.178095 -0.325230 0.928713 +-0.178095 -0.325230 0.928713 +0.178095 -0.325229 0.928713 +0.059652 -0.051644 0.996882 +0.059651 0.051645 0.996882 +0.059652 -0.051644 0.996882 +0.178095 -0.325229 0.928713 +0.178095 -0.325229 0.928713 +0.178089 0.325227 0.928715 +0.059651 0.051645 0.996882 +-0.059652 0.051644 0.996882 +0.059651 0.051645 0.996882 +0.178089 0.325227 0.928715 +0.178089 0.325227 0.928715 +-0.178090 0.325226 0.928715 +-0.059652 0.051644 0.996882 +-0.956759 -0.286980 -0.047481 +-0.956880 0.286574 -0.047493 +-0.935838 0.302474 0.180875 +-0.935838 0.302474 0.180875 +-0.935700 -0.302870 0.180926 +-0.956759 -0.286980 -0.047481 +0.094649 -0.995185 -0.025473 +-0.094892 -0.995161 -0.025495 +-0.097976 -0.990204 0.099478 +-0.097976 -0.990204 0.099478 +0.097974 -0.990204 0.099482 +0.094649 -0.995185 -0.025473 +0.957099 0.285866 -0.047341 +0.956983 -0.286258 -0.047331 +0.935829 -0.302532 0.180827 +0.935829 -0.302532 0.180827 +0.935969 0.302125 0.180782 +0.957099 0.285866 -0.047341 +-0.095356 0.995113 -0.025622 +0.095103 0.995138 -0.025600 +0.098324 0.990228 0.098895 +0.098324 0.990228 0.098895 +-0.098322 0.990228 0.098898 +-0.095356 0.995113 -0.025622 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.119406 -0.230420 -0.965737 +-0.119429 -0.230438 -0.965730 +-0.119413 0.230814 -0.965642 +-0.119413 0.230814 -0.965642 +0.119389 0.230797 -0.965649 +0.119406 -0.230420 -0.965737 +-0.956461 -0.263369 0.125776 +-0.956352 0.263771 0.125762 +-0.951515 0.257354 -0.168490 +-0.951515 0.257354 -0.168490 +-0.951619 -0.256956 -0.168510 +-0.956461 -0.263369 0.125776 +0.089354 -0.993150 0.075299 +-0.089353 -0.993150 0.075299 +-0.086359 -0.990397 -0.107966 +-0.086359 -0.990397 -0.107966 +0.086346 -0.990399 -0.107951 +0.089354 -0.993150 0.075299 +0.956215 0.264371 0.125539 +0.956325 -0.263968 0.125553 +0.951413 -0.257453 -0.168912 +0.951413 -0.257453 -0.168912 +0.951309 0.257848 -0.168893 +0.956215 0.264371 0.125539 +-0.089317 0.993152 0.075306 +0.089316 0.993152 0.075307 +0.086312 0.990407 -0.107912 +0.086312 0.990407 -0.107912 +-0.086327 0.990404 -0.107926 +-0.089317 0.993152 0.075306 +-0.059706 -0.051712 0.996876 +-0.059706 0.051711 0.996876 +-0.178271 0.325213 0.928685 +-0.178271 0.325213 0.928685 +-0.178277 -0.325216 0.928683 +-0.059706 -0.051712 0.996876 +0.059652 -0.051644 0.996882 +-0.059706 -0.051712 0.996876 +-0.178277 -0.325216 0.928683 +-0.178277 -0.325216 0.928683 +0.178249 -0.325192 0.928697 +0.059652 -0.051644 0.996882 +0.059651 0.051645 0.996882 +0.059652 -0.051644 0.996882 +0.178249 -0.325192 0.928697 +0.178249 -0.325192 0.928697 +0.178243 0.325190 0.928698 +0.059651 0.051645 0.996882 +-0.059706 0.051711 0.996876 +0.059651 0.051645 0.996882 +0.178243 0.325190 0.928698 +0.178243 0.325190 0.928698 +-0.178271 0.325213 0.928685 +-0.059706 0.051711 0.996876 +-0.956867 -0.286633 -0.047410 +-0.957030 0.286087 -0.047416 +-0.935837 0.303084 0.179859 +-0.935837 0.303084 0.179859 +-0.935699 -0.303480 0.179911 +-0.956867 -0.286633 -0.047410 +0.094767 -0.995173 -0.025490 +-0.094954 -0.995155 -0.025518 +-0.097939 -0.990209 0.099471 +-0.097939 -0.990209 0.099471 +0.098066 -0.990195 0.099485 +0.094767 -0.995173 -0.025490 +0.957021 0.286115 -0.047424 +0.956875 -0.286606 -0.047402 +0.935925 -0.302580 0.180248 +0.935925 -0.302580 0.180248 +0.936065 0.302173 0.180203 +0.957021 0.286115 -0.047424 +-0.095347 0.995114 -0.025629 +0.095227 0.995126 -0.025611 +0.098417 0.990219 0.098898 +0.098417 0.990219 0.098898 +-0.098284 0.990233 0.098891 +-0.095347 0.995114 -0.025629 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.119409 -0.230387 -0.965745 +-0.119432 -0.230405 -0.965738 +-0.119409 0.230636 -0.965686 +-0.119409 0.230636 -0.965686 +0.119385 0.230620 -0.965692 +0.119409 -0.230387 -0.965745 +-0.956465 -0.263343 0.125794 +-0.956396 0.263599 0.125785 +-0.951567 0.257165 -0.168484 +-0.951567 0.257165 -0.168484 +-0.951627 -0.256922 -0.168514 +-0.956465 -0.263343 0.125794 +0.089186 -0.993223 0.074520 +-0.089186 -0.993223 0.074520 +-0.086131 -0.990447 -0.107688 +-0.086131 -0.990447 -0.107688 +0.086118 -0.990449 -0.107673 +0.089186 -0.993223 0.074520 +0.956260 0.264199 0.125562 +0.956330 -0.263943 0.125571 +0.951421 -0.257419 -0.168916 +0.951421 -0.257419 -0.168916 +0.951362 0.257659 -0.168887 +0.956260 0.264199 0.125562 +-0.089418 0.993186 0.074743 +0.089417 0.993186 0.074743 +0.086345 0.990399 -0.107952 +0.086345 0.990399 -0.107952 +-0.086360 0.990397 -0.107965 +-0.089418 0.993186 0.074743 +-0.059699 -0.051708 0.996876 +-0.059699 0.051707 0.996876 +-0.178304 0.324561 0.928907 +-0.178304 0.324561 0.928907 +-0.178267 -0.324903 0.928794 +-0.059699 -0.051708 0.996876 +0.059645 -0.051639 0.996883 +-0.059699 -0.051708 0.996876 +-0.178267 -0.324903 0.928794 +-0.178267 -0.324903 0.928794 +0.178239 -0.324879 0.928808 +0.059645 -0.051639 0.996883 +0.059645 0.051640 0.996883 +0.059645 -0.051639 0.996883 +0.178239 -0.324879 0.928808 +0.178239 -0.324879 0.928808 +0.178275 0.324538 0.928920 +0.059645 0.051640 0.996883 +-0.059699 0.051707 0.996876 +0.059645 0.051640 0.996883 +0.178275 0.324538 0.928920 +0.178275 0.324538 0.928920 +-0.178304 0.324561 0.928907 +-0.059699 0.051707 0.996876 +-0.956902 -0.286501 -0.047494 +-0.956866 0.286632 -0.047435 +-0.935697 0.303492 0.179901 +-0.935697 0.303492 0.179901 +-0.935846 -0.303009 0.179939 +-0.956902 -0.286501 -0.047494 +0.094837 -0.995166 -0.025510 +-0.095030 -0.995147 -0.025535 +-0.097908 -0.990248 0.099115 +-0.097908 -0.990248 0.099115 +0.098035 -0.990234 0.099129 +0.094837 -0.995166 -0.025510 +0.956863 0.286642 -0.047436 +0.957016 -0.286134 -0.047418 +0.936071 -0.302110 0.180277 +0.936071 -0.302110 0.180277 +0.935926 0.302580 0.180245 +0.956863 0.286642 -0.047436 +-0.095136 0.995136 -0.025567 +0.094939 0.995156 -0.025539 +0.098212 0.990246 0.098834 +0.098212 0.990246 0.098834 +-0.098079 0.990259 0.098827 +-0.095136 0.995136 -0.025567 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.119379 -0.230410 -0.965743 +-0.119329 -0.230419 -0.965747 +-0.119305 0.230651 -0.965695 +-0.119305 0.230651 -0.965695 +0.119354 0.230643 -0.965691 +0.119379 -0.230410 -0.965743 +-0.956455 -0.263620 0.125293 +-0.956385 0.263876 0.125285 +-0.951498 0.257330 -0.168618 +-0.951498 0.257330 -0.168618 +-0.951559 -0.257087 -0.168648 +-0.956455 -0.263620 0.125293 +0.089148 -0.993226 0.074524 +-0.089116 -0.993229 0.074535 +-0.086054 -0.990453 -0.107695 +-0.086054 -0.990453 -0.107695 +0.086092 -0.990450 -0.107689 +0.089148 -0.993226 0.074524 +0.956260 0.264199 0.125562 +0.956379 -0.263753 0.125592 +0.951490 -0.257253 -0.168783 +0.951490 -0.257253 -0.168783 +0.951362 0.257659 -0.168887 +0.956260 0.264199 0.125562 +-0.089348 0.993191 0.074758 +0.089378 0.993189 0.074747 +0.086319 0.990400 -0.107968 +0.086319 0.990400 -0.107968 +-0.086283 0.990403 -0.107973 +-0.089348 0.993191 0.074758 +-0.059699 -0.051708 0.996876 +-0.059699 0.051708 0.996876 +-0.178472 0.324536 0.928883 +-0.178472 0.324536 0.928883 +-0.178435 -0.324879 0.928771 +-0.059699 -0.051708 0.996876 +0.059731 -0.051751 0.996872 +-0.059699 -0.051708 0.996876 +-0.178435 -0.324879 0.928771 +-0.178435 -0.324879 0.928771 +0.178666 -0.324823 0.928746 +0.059731 -0.051751 0.996872 +0.059731 0.051751 0.996872 +0.059731 -0.051751 0.996872 +0.178666 -0.324823 0.928746 +0.178666 -0.324823 0.928746 +0.178702 0.324482 0.928858 +0.059731 0.051751 0.996872 +-0.059699 0.051708 0.996876 +0.059731 0.051751 0.996872 +0.178702 0.324482 0.928858 +0.178702 0.324482 0.928858 +-0.178472 0.324536 0.928883 +-0.059699 0.051708 0.996876 +-0.956956 -0.286326 -0.047458 +-0.956757 0.286982 -0.047514 +-0.935719 0.303231 0.180224 +-0.935719 0.303231 0.180224 +-0.935868 -0.302749 0.180262 +-0.956956 -0.286326 -0.047458 +0.094967 -0.995153 -0.025514 +-0.094845 -0.995166 -0.025498 +-0.097945 -0.990243 0.099122 +-0.097945 -0.990243 0.099122 +0.097986 -0.990238 0.099129 +0.094967 -0.995153 -0.025514 +0.957030 0.286102 -0.047321 +0.957180 -0.285601 -0.047306 +0.935931 -0.302584 0.180211 +0.935931 -0.302584 0.180211 +0.935785 0.303054 0.180179 +0.957030 0.286102 -0.047321 +-0.095138 0.995136 -0.025569 +0.095140 0.995136 -0.025563 +0.098162 0.990250 0.098834 +0.098162 0.990250 0.098834 +-0.098117 0.990255 0.098834 +-0.095138 0.995136 -0.025569 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.985978 -0.095115 0.137113 +-0.949755 -0.178415 0.257163 +-0.985878 0.095453 -0.137597 +-0.985878 0.095453 -0.137597 +-0.948297 0.180918 -0.260770 +-0.985978 -0.095115 0.137113 +0.188900 -0.559726 0.806860 +0.117083 -0.566086 0.815989 +-0.117067 -0.566069 0.816003 +-0.117067 -0.566069 0.816003 +-0.188881 -0.559749 0.806849 +0.188900 -0.559726 0.806860 +0.985921 0.095316 -0.137386 +0.949914 -0.178127 0.256776 +0.986163 -0.094499 0.136209 +0.986163 -0.094499 0.136209 +0.948917 0.179845 -0.259252 +0.985921 0.095316 -0.137386 +-0.118970 0.565940 -0.815818 +-0.191917 0.559413 -0.806365 +0.191932 0.559391 -0.806377 +0.191932 0.559391 -0.806377 +0.118984 0.565957 -0.815803 +-0.118970 0.565940 -0.815818 +-0.986292 0.090913 -0.137707 +-0.949902 0.172190 -0.260838 +-0.986592 -0.090992 0.135485 +-0.986592 -0.090992 0.135485 +-0.949886 -0.174273 0.259509 +-0.986292 0.090913 -0.137707 +-0.187114 -0.547656 0.815513 +0.187097 -0.547674 0.815505 +0.127645 -0.552942 0.823384 +0.127645 -0.552942 0.823384 +-0.127399 -0.552974 0.823401 +-0.187114 -0.547656 0.815513 +0.986635 -0.090843 0.135274 +0.950045 0.171961 -0.260470 +0.986295 0.090899 -0.137697 +0.986295 0.090899 -0.137697 +0.949880 -0.174293 0.259518 +0.986635 -0.090843 0.135274 +0.128199 0.546376 -0.827670 +-0.128212 0.546391 -0.827659 +-0.189856 0.540902 -0.819378 +-0.189856 0.540902 -0.819378 +0.190238 0.540878 -0.819305 +0.128199 0.546376 -0.827670 +-0.985580 0.092551 0.141657 +-0.952583 -0.166438 -0.254722 +-0.985690 -0.092197 -0.141119 +-0.985690 -0.092197 -0.141119 +-0.951152 0.168869 0.258442 +-0.985580 0.092551 0.141657 +-0.119608 -0.543026 -0.831154 +0.119633 -0.543044 -0.831139 +0.191447 -0.536835 -0.821679 +0.191447 -0.536835 -0.821679 +-0.191430 -0.536859 -0.821668 +-0.119608 -0.543026 -0.831154 +0.985872 -0.091621 -0.140219 +0.952724 -0.166185 -0.254363 +0.985626 0.092411 0.141429 +0.985626 0.092411 0.141429 +0.951738 0.167865 0.256935 +0.985872 -0.091621 -0.140219 +0.194545 0.536501 0.821169 +-0.194528 0.536525 0.821157 +-0.121214 0.542919 0.830991 +-0.121214 0.542919 0.830991 +0.121217 0.542938 0.830978 +0.194545 0.536501 0.821169 +-0.985980 -0.095111 0.137106 +-0.949749 -0.178426 0.257179 +-0.985878 0.095453 -0.137597 +-0.985878 0.095453 -0.137597 +-0.948300 0.180912 -0.260762 +-0.985980 -0.095111 0.137106 +0.189033 -0.559712 0.806839 +0.117169 -0.566081 0.815981 +-0.116913 -0.566079 0.816018 +-0.116913 -0.566079 0.816018 +-0.188687 -0.559770 0.806880 +0.189033 -0.559712 0.806839 +0.985809 0.095692 -0.137928 +0.949519 -0.178811 0.257762 +0.986075 -0.094797 0.136638 +0.986075 -0.094797 0.136638 +0.948612 0.180368 -0.260006 +0.985809 0.095692 -0.137928 +-0.118817 0.565950 -0.815833 +-0.191627 0.559445 -0.806412 +0.192003 0.559383 -0.806366 +0.192003 0.559383 -0.806366 +0.119011 0.565956 -0.815801 +-0.118817 0.565950 -0.815833 +-0.986322 0.090812 -0.137555 +-0.949604 0.172688 -0.261593 +-0.986517 -0.091247 0.135864 +-0.986517 -0.091247 0.135864 +-0.949961 -0.174146 0.259320 +-0.986322 0.090812 -0.137555 +-0.186852 -0.547684 0.815554 +0.187154 -0.547668 0.815496 +0.127630 -0.552943 0.823386 +0.127630 -0.552943 0.823386 +-0.127234 -0.552986 0.823418 +-0.186852 -0.547684 0.815554 +0.986635 -0.090843 0.135274 +0.950054 0.171945 -0.260445 +0.986295 0.090899 -0.137697 +0.986295 0.090899 -0.137697 +0.949890 -0.174277 0.259494 +0.986635 -0.090843 0.135274 +0.128240 0.546373 -0.827666 +-0.128057 0.546402 -0.827676 +-0.189613 0.540928 -0.819417 +-0.189613 0.540928 -0.819417 +0.190188 0.540884 -0.819313 +0.128240 0.546373 -0.827666 +-0.985558 0.092622 0.141765 +-0.952535 -0.166521 -0.254848 +-0.985679 -0.092233 -0.141174 +-0.985679 -0.092233 -0.141174 +-0.951117 0.168929 0.258533 +-0.985558 0.092622 0.141765 +-0.119490 -0.543033 -0.831166 +0.119703 -0.543039 -0.831132 +0.191647 -0.536814 -0.821646 +0.191647 -0.536814 -0.821646 +-0.191162 -0.536887 -0.821711 +-0.119490 -0.543033 -0.831166 +0.985795 -0.091868 -0.140598 +0.952450 -0.166654 -0.255081 +0.985542 0.092678 0.141836 +0.985542 0.092678 0.141836 +0.951478 0.168306 0.257610 +0.985795 -0.091868 -0.140598 +0.194915 0.536461 0.821107 +-0.194599 0.536518 0.821146 +-0.121183 0.542921 0.830994 +-0.121183 0.542921 0.830994 +0.121481 0.542921 0.830951 +0.194915 0.536461 0.821107 +-0.985980 -0.095111 0.137106 +-0.949680 -0.178545 0.257350 +-0.985856 0.095525 -0.137702 +-0.985856 0.095525 -0.137702 +-0.948300 0.180912 -0.260762 +-0.985980 -0.095111 0.137106 +0.188901 -0.559726 0.806860 +0.117160 -0.566081 0.815982 +-0.116875 -0.566082 0.816022 +-0.116875 -0.566082 0.816022 +-0.188554 -0.559785 0.806901 +0.188901 -0.559726 0.806860 +0.985776 0.095802 -0.138086 +0.949368 -0.179071 0.258136 +0.986032 -0.094942 0.136847 +0.986032 -0.094942 0.136847 +0.948459 0.180629 -0.260382 +0.985776 0.095802 -0.138086 +-0.118740 0.565955 -0.815840 +-0.191581 0.559451 -0.806419 +0.192003 0.559383 -0.806366 +0.192003 0.559383 -0.806366 +0.118945 0.565960 -0.815807 +-0.118740 0.565955 -0.815840 +-0.986344 0.090742 -0.137449 +-0.949604 0.172688 -0.261593 +-0.986509 -0.091273 0.135901 +-0.986509 -0.091273 0.135901 +-0.950036 -0.174020 0.259132 +-0.986344 0.090742 -0.137449 +-0.186917 -0.547677 0.815544 +0.187102 -0.547673 0.815504 +0.127672 -0.552940 0.823381 +0.127672 -0.552940 0.823381 +-0.127197 -0.552989 0.823422 +-0.186917 -0.547677 0.815544 +0.986614 -0.090913 0.135379 +0.949970 0.172086 -0.260659 +0.986252 0.091039 -0.137908 +0.986252 0.091039 -0.137908 +0.949731 -0.174546 0.259895 +0.986614 -0.090913 0.135379 +0.128198 0.546376 -0.827670 +-0.128090 0.546399 -0.827672 +-0.189482 0.540942 -0.819438 +-0.189482 0.540942 -0.819438 +0.190254 0.540877 -0.819302 +0.128198 0.546376 -0.827670 +-0.985535 0.092693 0.141874 +-0.952463 -0.166645 -0.255038 +-0.985657 -0.092303 -0.141281 +-0.985657 -0.092303 -0.141281 +-0.951044 0.169051 0.258720 +-0.985535 0.092693 0.141874 +-0.119451 -0.543036 -0.831170 +0.119781 -0.543034 -0.831124 +0.191581 -0.536821 -0.821657 +0.191581 -0.536821 -0.821657 +-0.191225 -0.536880 -0.821701 +-0.119451 -0.543036 -0.831170 +0.985722 -0.092103 -0.140957 +0.952378 -0.166776 -0.255268 +0.985512 0.092773 0.141981 +0.985512 0.092773 0.141981 +0.951260 0.168674 0.258173 +0.985722 -0.092103 -0.140957 +0.195050 0.536446 0.821085 +-0.194551 0.536523 0.821154 +-0.121223 0.542918 0.830990 +-0.121223 0.542918 0.830990 +0.121467 0.542922 0.830952 +0.195050 0.536446 0.821085 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.167818 0.000000 -0.985818 +-0.167885 0.000000 -0.985807 +-0.167884 0.000000 -0.985807 +-0.167884 0.000000 -0.985807 +0.167809 0.000000 -0.985819 +0.167818 0.000000 -0.985818 +0.167841 0.000000 0.985814 +0.167832 0.000000 0.985816 +-0.167907 0.000000 0.985803 +-0.167907 0.000000 0.985803 +-0.167908 0.000000 0.985803 +0.167841 0.000000 0.985814 +-0.973544 0.000000 0.228500 +-0.973544 0.000000 0.228498 +-0.973536 0.000000 -0.228534 +-0.973536 0.000000 -0.228534 +-0.973535 0.000000 -0.228536 +-0.973544 0.000000 0.228500 +0.005896 -0.999955 0.007463 +-0.005899 -0.999955 0.007463 +-0.005899 -0.999955 -0.007465 +-0.005899 -0.999955 -0.007465 +0.005896 -0.999955 -0.007465 +0.005896 -0.999955 0.007463 +0.973502 0.000001 0.228679 +0.973508 0.000000 0.228655 +0.973493 0.000001 -0.228717 +0.973493 0.000001 -0.228717 +0.973487 0.000000 -0.228740 +0.973502 0.000001 0.228679 +-0.005894 0.999955 0.007457 +0.005901 0.999955 0.007469 +0.005900 0.999955 -0.007472 +0.005900 0.999955 -0.007472 +-0.005894 0.999955 -0.007458 +-0.005894 0.999955 0.007457 +0.119255 -0.230420 -0.965756 +-0.119296 -0.230417 -0.965752 +-0.119294 0.230486 -0.965736 +-0.119294 0.230486 -0.965736 +0.119260 0.230488 -0.965739 +0.119255 -0.230420 -0.965756 +0.119256 -0.230416 0.965757 +0.119256 0.230498 0.965737 +-0.119278 0.230454 0.965745 +-0.119278 0.230454 0.965745 +-0.119277 -0.230394 0.965759 +0.119256 -0.230416 0.965757 +-0.951550 -0.257151 0.168601 +-0.951532 0.257219 0.168599 +-0.951533 0.257221 -0.168588 +-0.951533 0.257221 -0.168588 +-0.951551 -0.257152 -0.168590 +-0.951550 -0.257151 0.168601 +0.086114 -0.990440 0.107763 +-0.086139 -0.990439 0.107754 +-0.086140 -0.990440 -0.107745 +-0.086140 -0.990440 -0.107745 +0.086113 -0.990440 -0.107764 +0.086114 -0.990440 0.107763 +0.951475 0.257352 0.168716 +0.951493 -0.257284 0.168719 +0.951494 -0.257282 -0.168717 +0.951494 -0.257282 -0.168717 +0.951476 0.257351 -0.168714 +0.951475 0.257352 0.168716 +-0.086168 0.990433 0.107786 +0.086136 0.990435 0.107787 +0.086133 0.990435 -0.107791 +0.086133 0.990435 -0.107791 +-0.086168 0.990433 -0.107781 +-0.086168 0.990433 0.107786 +0.119237 -0.230393 -0.965765 +-0.119278 -0.230390 -0.965760 +-0.119276 0.230459 -0.965744 +-0.119276 0.230459 -0.965744 +0.119242 0.230461 -0.965748 +0.119237 -0.230393 -0.965765 +0.119256 -0.230416 0.965757 +0.119256 0.230498 0.965737 +-0.119295 0.230481 0.965737 +-0.119295 0.230481 0.965737 +-0.119295 -0.230422 0.965751 +0.119256 -0.230416 0.965757 +-0.951551 -0.257151 0.168595 +-0.951533 0.257219 0.168593 +-0.951533 0.257221 -0.168588 +-0.951533 0.257221 -0.168588 +-0.951551 -0.257152 -0.168590 +-0.951551 -0.257151 0.168595 +0.086115 -0.990441 0.107752 +-0.086139 -0.990439 0.107750 +-0.086140 -0.990440 -0.107745 +-0.086140 -0.990440 -0.107745 +0.086113 -0.990440 -0.107764 +0.086115 -0.990441 0.107752 +0.951477 0.257354 0.168699 +0.951496 -0.257286 0.168702 +0.951494 -0.257282 -0.168717 +0.951494 -0.257282 -0.168717 +0.951476 0.257351 -0.168714 +0.951477 0.257354 0.168699 +-0.086168 0.990433 0.107782 +0.086137 0.990437 0.107776 +0.086133 0.990435 -0.107791 +0.086133 0.990435 -0.107791 +-0.086168 0.990433 -0.107781 +-0.086168 0.990433 0.107782 +0.119255 -0.230420 -0.965756 +-0.119296 -0.230417 -0.965752 +-0.119294 0.230486 -0.965736 +-0.119294 0.230486 -0.965736 +0.119260 0.230488 -0.965739 +0.119255 -0.230420 -0.965756 +0.119221 -0.230362 0.965774 +0.119222 0.230444 0.965755 +-0.119261 0.230427 0.965754 +-0.119261 0.230427 0.965754 +-0.119260 -0.230367 0.965768 +0.119221 -0.230362 0.965774 +-0.951548 -0.257149 0.168612 +-0.951530 0.257217 0.168610 +-0.951533 0.257221 -0.168588 +-0.951533 0.257221 -0.168588 +-0.951551 -0.257152 -0.168590 +-0.951548 -0.257149 0.168612 +0.086114 -0.990440 0.107763 +-0.086138 -0.990438 0.107762 +-0.086140 -0.990440 -0.107745 +-0.086140 -0.990440 -0.107745 +0.086114 -0.990441 -0.107757 +0.086114 -0.990440 0.107763 +0.951475 0.257352 0.168716 +0.951493 -0.257284 0.168719 +0.951495 -0.257285 -0.168707 +0.951495 -0.257285 -0.168707 +0.951477 0.257353 -0.168704 +0.951475 0.257352 0.168716 +-0.086168 0.990432 0.107794 +0.086136 0.990436 0.107787 +0.086134 0.990436 -0.107784 +0.086134 0.990436 -0.107784 +-0.086168 0.990433 -0.107781 +-0.086168 0.990432 0.107794 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.002423 -0.999997 -0.000001 +0.002423 -0.999997 -0.000001 +0.002423 -0.999997 -0.000001 +0.002423 -0.999997 0.000000 +0.002423 -0.999997 0.000000 +0.002423 -0.999997 0.000000 +-0.999985 -0.005401 0.000013 +-0.999985 -0.005401 0.000013 +-0.999985 -0.005401 0.000013 +-0.999985 -0.005405 0.000008 +-0.999985 -0.005405 0.000008 +-0.999985 -0.005405 0.000008 +-0.002425 0.999997 0.000000 +-0.002425 0.999997 0.000000 +-0.002425 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.002423 -0.999997 -0.000001 +0.002423 -0.999997 -0.000001 +0.002423 -0.999997 -0.000001 +0.002423 -0.999997 0.000000 +0.002423 -0.999997 0.000000 +0.002423 -0.999997 0.000000 +-0.999985 -0.005401 0.000013 +-0.999985 -0.005401 0.000013 +-0.999985 -0.005401 0.000013 +-0.999985 -0.005405 0.000008 +-0.999985 -0.005405 0.000008 +-0.999985 -0.005405 0.000008 +-0.002425 0.999997 0.000000 +-0.002425 0.999997 0.000000 +-0.002425 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.002423 -0.999997 -0.000001 +0.002423 -0.999997 -0.000001 +0.002423 -0.999997 -0.000001 +0.002423 -0.999997 0.000000 +0.002423 -0.999997 0.000000 +0.002423 -0.999997 0.000000 +-0.999985 -0.005401 0.000013 +-0.999985 -0.005401 0.000013 +-0.999985 -0.005401 0.000013 +-0.999985 -0.005405 0.000008 +-0.999985 -0.005405 0.000008 +-0.999985 -0.005405 0.000008 +-0.002425 0.999997 0.000000 +-0.002425 0.999997 0.000000 +-0.002425 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.999985 0.005408 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.002423 -0.999997 -0.000001 +0.002423 -0.999997 -0.000001 +0.002423 -0.999997 -0.000001 +0.002423 -0.999997 0.000000 +0.002423 -0.999997 0.000000 +0.002423 -0.999997 0.000000 +-0.999985 -0.005401 0.000013 +-0.999985 -0.005401 0.000013 +-0.999985 -0.005401 0.000013 +-0.999985 -0.005405 0.000008 +-0.999985 -0.005405 0.000008 +-0.999985 -0.005405 0.000008 +-0.002425 0.999997 0.000000 +-0.002425 0.999997 0.000000 +-0.002425 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +-0.002422 0.999997 0.000000 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.001817 0.999998 0.000000 +0.001817 0.999998 0.000000 +0.001817 0.999998 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +-0.001818 -0.999998 -0.000004 +-0.001818 -0.999998 -0.000004 +-0.001818 -0.999998 -0.000004 +-0.001816 -0.999998 0.000004 +-0.001816 -0.999998 0.000004 +-0.001816 -0.999998 0.000004 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.001817 0.999998 0.000000 +0.001817 0.999998 0.000000 +0.001817 0.999998 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +-0.001818 -0.999998 -0.000004 +-0.001818 -0.999998 -0.000004 +-0.001818 -0.999998 -0.000004 +-0.001816 -0.999998 0.000004 +-0.001816 -0.999998 0.000004 +-0.001816 -0.999998 0.000004 +0.999998 -0.001819 -0.000006 +0.999998 -0.001819 -0.000006 +0.999998 -0.001819 -0.000006 +0.999998 -0.001817 0.000000 +0.999998 -0.001817 0.000000 +0.999998 -0.001817 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.001816 0.999998 0.000000 +0.001816 0.999998 0.000000 +0.001816 0.999998 0.000000 +0.001816 0.999998 0.000000 +0.001816 0.999998 0.000000 +0.001816 0.999998 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000001 0.000000 1.000000 +0.000001 0.000000 1.000000 +0.000001 0.000000 1.000000 +-0.001829 -0.999998 0.000000 +-0.001829 -0.999998 0.000000 +-0.001829 -0.999998 0.000000 +-0.001829 -0.999998 0.000000 +-0.001829 -0.999998 0.000000 +-0.001829 -0.999998 0.000000 +-0.999998 0.001817 -0.000006 +-0.999998 0.001817 -0.000006 +-0.999998 0.001817 -0.000006 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.001817 0.999998 0.000000 +0.001817 0.999998 0.000000 +0.001817 0.999998 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +-0.001818 -0.999998 -0.000004 +-0.001818 -0.999998 -0.000004 +-0.001818 -0.999998 -0.000004 +-0.001816 -0.999998 0.000004 +-0.001816 -0.999998 0.000004 +-0.001816 -0.999998 0.000004 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.001817 0.999998 0.000000 +0.001817 0.999998 0.000000 +0.001817 0.999998 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +-0.001816 -0.999998 -0.000004 +-0.001816 -0.999998 -0.000004 +-0.001816 -0.999998 -0.000004 +-0.001818 -0.999998 0.000004 +-0.001818 -0.999998 0.000004 +-0.001818 -0.999998 0.000004 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.001817 0.999998 0.000000 +0.001817 0.999998 0.000000 +0.001817 0.999998 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +-0.001818 -0.999998 -0.000004 +-0.001818 -0.999998 -0.000004 +-0.001818 -0.999998 -0.000004 +-0.001816 -0.999998 0.000004 +-0.001816 -0.999998 0.000004 +-0.001816 -0.999998 0.000004 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.001817 0.999998 0.000000 +0.001817 0.999998 0.000000 +0.001817 0.999998 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +-0.001818 -0.999998 -0.000004 +-0.001818 -0.999998 -0.000004 +-0.001818 -0.999998 -0.000004 +-0.001816 -0.999998 0.000004 +-0.001816 -0.999998 0.000004 +-0.001816 -0.999998 0.000004 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.001819 0.999998 -0.000006 +0.001817 0.999998 0.000000 +0.001817 0.999998 0.000000 +0.001817 0.999998 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +-0.999998 0.001816 0.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +0.999998 -0.001829 0.000000 +-0.001816 -0.999998 -0.000004 +-0.001816 -0.999998 -0.000004 +-0.001816 -0.999998 -0.000004 +-0.001818 -0.999998 0.000004 +-0.001818 -0.999998 0.000004 +-0.001818 -0.999998 0.000004 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000001 1.000000 +0.000000 0.000001 1.000000 +0.000000 0.000001 1.000000 +0.000000 -0.000001 1.000000 +0.000000 -0.000001 1.000000 +0.000000 -0.000001 1.000000 +-0.999999 0.001038 0.000000 +-0.999999 0.001038 0.000000 +-0.999999 0.001038 0.000000 +-0.999999 0.001038 0.000000 +-0.999999 0.001038 0.000000 +-0.999999 0.001038 0.000000 +-0.001043 -0.999999 0.000000 +-0.001043 -1.000000 0.000000 +-0.001043 -0.999999 0.000000 +-0.001043 -0.999999 0.000000 +-0.001043 -0.999999 0.000000 +-0.001043 -0.999999 0.000000 +0.999999 -0.001038 0.000000 +1.000000 -0.001038 0.000000 +0.999999 -0.001038 0.000000 +1.000000 -0.001038 0.000000 +1.000000 -0.001038 0.000000 +1.000000 -0.001038 0.000000 +0.001043 0.999999 0.000000 +0.001043 0.999999 0.000000 +0.001043 0.999999 0.000000 +0.001043 0.999999 0.000000 +0.001043 0.999999 0.000000 +0.001043 0.999999 0.000000 +0.000000 0.000001 -1.000000 +0.000000 0.000001 -1.000000 +0.000000 0.000001 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 -0.000001 1.000000 +0.000000 -0.000001 1.000000 +0.000000 -0.000001 1.000000 +0.000000 -0.000001 1.000000 +0.000000 -0.000001 1.000000 +0.000000 -0.000001 1.000000 +-0.999999 0.001038 0.000000 +-0.999999 0.001038 0.000000 +-1.000000 0.001038 0.000000 +-1.000000 0.001038 0.000000 +-0.999999 0.001038 0.000000 +-1.000000 0.001038 0.000000 +-0.001043 -0.999999 0.000000 +-0.001043 -0.999999 0.000000 +-0.001043 -0.999999 0.000000 +-0.001043 -0.999999 0.000000 +-0.001043 -0.999999 0.000000 +-0.001043 -0.999999 0.000000 +1.000000 -0.001038 0.000000 +0.999999 -0.001038 0.000000 +0.999999 -0.001038 0.000000 +1.000000 -0.001038 0.000000 +0.999999 -0.001038 0.000000 +0.999999 -0.001038 0.000000 +0.001043 0.999999 0.000000 +0.001043 0.999999 0.000000 +0.001043 0.999999 0.000000 +0.001043 0.999999 0.000000 +0.001043 0.999999 0.000000 +0.001043 0.999999 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.999999 0.001039 0.000000 +-0.999999 0.001039 0.000000 +-1.000000 0.001039 0.000000 +-1.000000 0.001039 0.000000 +-0.999999 0.001039 0.000000 +-0.999999 0.001039 0.000000 +-0.001043 -0.999999 0.000000 +-0.001043 -0.999999 0.000000 +-0.001043 -0.999999 0.000000 +-0.001043 -0.999999 0.000000 +-0.001043 -0.999999 0.000000 +-0.001043 -0.999999 0.000000 +0.999999 -0.001039 0.000000 +0.999999 -0.001039 0.000000 +1.000000 -0.001039 0.000000 +1.000000 -0.001039 0.000000 +0.999999 -0.001039 0.000000 +0.999999 -0.001039 0.000000 +0.001043 0.999999 0.000000 +0.001043 0.999999 0.000000 +0.001043 0.999999 0.000000 +0.001043 0.999999 0.000000 +0.001043 0.999999 0.000000 +0.001043 0.999999 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +-0.935637 0.352964 0.000000 +-0.935637 0.352964 0.000000 +-0.935637 0.352964 0.000000 +-0.935637 0.352964 0.000000 +-0.935637 0.352964 0.000000 +-0.935637 0.352964 0.000000 +-0.352969 -0.935635 0.000000 +-0.352969 -0.935635 0.000000 +-0.352969 -0.935635 0.000000 +-0.352969 -0.935635 0.000000 +-0.352969 -0.935635 0.000000 +-0.352969 -0.935635 0.000000 +0.935637 -0.352965 0.000000 +0.935637 -0.352965 0.000000 +0.935637 -0.352965 0.000000 +0.935637 -0.352965 0.000000 +0.935637 -0.352965 0.000000 +0.935637 -0.352965 0.000000 +0.352969 0.935635 0.000000 +0.352969 0.935635 0.000000 +0.352969 0.935635 0.000000 +0.352969 0.935635 0.000000 +0.352969 0.935635 0.000000 +0.352969 0.935635 0.000000 +-0.000001 0.000000 -1.000000 +-0.000001 0.000000 -1.000000 +-0.000001 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +-0.000001 0.000000 -1.000000 +-0.000001 0.000000 -1.000000 +-0.000001 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000001 0.000000 1.000000 +0.000001 0.000000 1.000000 +0.000001 0.000000 1.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +0.000005 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-0.000005 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 + + + + + + + + + + + +0.480507 0.045007 +0.480507 0.412535 +0.108983 0.413764 +0.108319 0.417867 +0.108120 0.417948 +0.108319 0.417867 +0.108120 0.417948 +0.485016 0.418868 +0.485263 0.418876 +0.109020 0.038880 +0.109020 0.042880 +0.108667 0.039200 +0.481756 0.043443 +0.482223 0.042625 +0.485110 0.418890 +0.485263 0.419226 +0.484531 0.420580 +0.484252 0.420580 +0.484252 0.420580 +0.484531 0.420580 +0.482229 0.042758 +0.481756 0.043443 +0.110650 0.039983 +0.110831 0.039988 +0.110760 0.421926 +0.110622 0.421852 +0.110622 0.421852 +0.110760 0.421926 +0.484252 0.420631 +0.109614 0.418992 +0.484531 0.420630 +0.109371 0.419085 +0.484252 0.420631 +0.109614 0.418992 +0.484531 0.420630 +0.109371 0.419085 +0.480507 0.045007 +0.480507 0.412535 +0.108983 0.413764 +0.108319 0.417867 +0.108120 0.417948 +0.108319 0.417867 +0.108120 0.417948 +0.485016 0.418868 +0.485263 0.418876 +0.109020 0.038880 +0.109020 0.042880 +0.108667 0.039200 +0.481756 0.043443 +0.482223 0.042625 +0.485110 0.418890 +0.485263 0.419226 +0.484531 0.420580 +0.484252 0.420580 +0.484252 0.420580 +0.484531 0.420580 +0.482229 0.042758 +0.481756 0.043443 +0.110650 0.039983 +0.110831 0.039988 +0.110760 0.421926 +0.110622 0.421852 +0.110622 0.421852 +0.110760 0.421926 +0.484252 0.420631 +0.109614 0.418992 +0.484531 0.420630 +0.109371 0.419085 +0.484252 0.420631 +0.109614 0.418992 +0.484531 0.420630 +0.109371 0.419085 +0.480507 0.045007 +0.480507 0.412535 +0.108983 0.413764 +0.108319 0.417867 +0.108120 0.417948 +0.108319 0.417867 +0.108120 0.417948 +0.485016 0.418868 +0.485263 0.418876 +0.109020 0.038880 +0.109020 0.042880 +0.108667 0.039200 +0.481756 0.043443 +0.482223 0.042625 +0.485110 0.418890 +0.485263 0.419226 +0.484531 0.420580 +0.484252 0.420580 +0.484252 0.420580 +0.484531 0.420580 +0.482229 0.042758 +0.481756 0.043443 +0.110650 0.039983 +0.110831 0.039988 +0.110760 0.421926 +0.110622 0.421852 +0.110622 0.421852 +0.110760 0.421926 +0.484252 0.420631 +0.109614 0.418992 +0.484531 0.420630 +0.109371 0.419085 +0.484252 0.420631 +0.109614 0.418992 +0.484531 0.420630 +0.109371 0.419085 +0.480507 0.045007 +0.480507 0.412535 +0.108983 0.413764 +0.108319 0.417867 +0.108120 0.417948 +0.108319 0.417867 +0.108120 0.417948 +0.485016 0.418868 +0.485263 0.418876 +0.109020 0.038880 +0.109020 0.042880 +0.108667 0.039200 +0.481756 0.043443 +0.482223 0.042625 +0.485110 0.418890 +0.485263 0.419226 +0.484531 0.420580 +0.484252 0.420580 +0.484252 0.420580 +0.484531 0.420580 +0.482229 0.042758 +0.481756 0.043443 +0.110650 0.039983 +0.110831 0.039988 +0.110760 0.421926 +0.110622 0.421852 +0.110622 0.421852 +0.110760 0.421926 +0.484252 0.420631 +0.109614 0.418992 +0.484531 0.420630 +0.109371 0.419085 +0.484252 0.420631 +0.109614 0.418992 +0.484531 0.420630 +0.109371 0.419085 +0.480507 0.045007 +0.480507 0.412535 +0.108983 0.413764 +0.108319 0.417867 +0.108120 0.417948 +0.108319 0.417867 +0.108120 0.417948 +0.485016 0.418868 +0.485263 0.418876 +0.109020 0.038880 +0.109020 0.042880 +0.108667 0.039200 +0.481756 0.043443 +0.482223 0.042625 +0.485110 0.418890 +0.485263 0.419226 +0.484531 0.420580 +0.484252 0.420580 +0.484252 0.420580 +0.484531 0.420580 +0.482229 0.042758 +0.481756 0.043443 +0.110650 0.039983 +0.110831 0.039988 +0.110760 0.421926 +0.110622 0.421852 +0.110622 0.421852 +0.110760 0.421926 +0.484252 0.420631 +0.109614 0.418992 +0.484531 0.420630 +0.109371 0.419085 +0.484252 0.420631 +0.109614 0.418992 +0.484531 0.420630 +0.109371 0.419085 +0.480507 0.045007 +0.480507 0.412535 +0.108983 0.413764 +0.108319 0.417867 +0.108120 0.417948 +0.108319 0.417867 +0.108120 0.417948 +0.485016 0.418868 +0.485263 0.418876 +0.109020 0.038880 +0.109020 0.042880 +0.108667 0.039200 +0.481756 0.043443 +0.482223 0.042625 +0.485110 0.418890 +0.485263 0.419226 +0.484531 0.420580 +0.484252 0.420580 +0.484252 0.420580 +0.484531 0.420580 +0.482229 0.042758 +0.481756 0.043443 +0.110650 0.039983 +0.110831 0.039988 +0.110760 0.421926 +0.110622 0.421852 +0.110622 0.421852 +0.110760 0.421926 +0.484252 0.420631 +0.109614 0.418992 +0.484531 0.420630 +0.109371 0.419085 +0.484252 0.420631 +0.109614 0.418992 +0.484531 0.420630 +0.109371 0.419085 +0.478224 0.420580 +0.114013 0.420894 +0.478224 0.420580 +0.478853 0.420580 +0.113937 0.420889 +0.478853 0.420580 +0.478224 0.420580 +0.478224 0.420580 +0.114014 0.420907 +0.478853 0.420580 +0.113936 0.420877 +0.478853 0.420580 +0.113979 0.420267 +0.113904 0.420297 +0.113903 0.420285 +0.113980 0.420279 +0.478224 0.420580 +0.478224 0.420580 +0.113977 0.420238 +0.478853 0.420580 +0.113901 0.420246 +0.478853 0.420580 +0.478224 0.420580 +0.113977 0.420226 +0.478224 0.420580 +0.478853 0.420580 +0.113901 0.420258 +0.478854 0.420580 +0.114012 0.420873 +0.113935 0.420856 +0.113935 0.420857 +0.114012 0.420872 +0.478224 0.420580 +0.113979 0.420267 +0.478224 0.420580 +0.478853 0.420580 +0.113904 0.420297 +0.478853 0.420580 +0.478224 0.420580 +0.478224 0.420580 +0.113979 0.420279 +0.478853 0.420580 +0.113903 0.420285 +0.478853 0.420580 +0.114013 0.420894 +0.113936 0.420889 +0.113936 0.420877 +0.114014 0.420907 +0.478224 0.420580 +0.478224 0.420580 +0.114013 0.420894 +0.478853 0.420580 +0.478853 0.420580 +0.113936 0.420889 +0.478224 0.420580 +0.114014 0.420907 +0.478224 0.420580 +0.478853 0.420580 +0.478853 0.420580 +0.113936 0.420877 +0.113979 0.420267 +0.113904 0.420297 +0.113903 0.420285 +0.113980 0.420279 +0.478224 0.420580 +0.478224 0.420580 +0.113977 0.420238 +0.478853 0.420580 +0.113901 0.420246 +0.478853 0.420580 +0.478224 0.420580 +0.113977 0.420226 +0.478224 0.420580 +0.478853 0.420580 +0.113901 0.420258 +0.478854 0.420580 +0.114012 0.420873 +0.113935 0.420856 +0.113935 0.420857 +0.114012 0.420872 +0.478224 0.420580 +0.113979 0.420267 +0.478224 0.420580 +0.478853 0.420580 +0.113904 0.420297 +0.478853 0.420580 +0.478224 0.420580 +0.478224 0.420580 +0.113979 0.420279 +0.478853 0.420580 +0.113903 0.420285 +0.478853 0.420580 +0.114013 0.420894 +0.113936 0.420889 +0.113936 0.420877 +0.114014 0.420907 +0.478224 0.420580 +0.478224 0.420580 +0.114013 0.420894 +0.478853 0.420580 +0.478853 0.420580 +0.113936 0.420889 +0.478224 0.420580 +0.114014 0.420907 +0.478224 0.420580 +0.478853 0.420580 +0.478853 0.420580 +0.113936 0.420877 +0.113979 0.420267 +0.113904 0.420297 +0.113903 0.420285 +0.113980 0.420279 +0.478224 0.420580 +0.478224 0.420580 +0.113977 0.420238 +0.478853 0.420580 +0.113901 0.420246 +0.478853 0.420580 +0.478224 0.420580 +0.113977 0.420226 +0.478224 0.420580 +0.478853 0.420580 +0.113901 0.420258 +0.478854 0.420580 +0.114012 0.420873 +0.113935 0.420856 +0.113935 0.420857 +0.114012 0.420872 +0.478224 0.420580 +0.113979 0.420267 +0.478224 0.420580 +0.478853 0.420580 +0.113904 0.420297 +0.478853 0.420580 +0.478224 0.420580 +0.478224 0.420580 +0.113979 0.420279 +0.478853 0.420580 +0.113903 0.420285 +0.478853 0.420580 +0.114013 0.420894 +0.113936 0.420889 +0.113936 0.420877 +0.114014 0.420907 +0.489049 0.036961 +0.105430 0.036961 +0.489049 0.420580 +0.105430 0.420580 +0.105430 0.036961 +0.489049 0.036961 +0.105430 0.420580 +0.489049 0.420580 +0.105430 0.036961 +0.489049 0.036961 +0.105430 0.420580 +0.489049 0.420580 +0.105430 0.036961 +0.489049 0.036961 +0.105430 0.420580 +0.489049 0.420580 +0.489049 0.036961 +0.105430 0.036961 +0.489049 0.420580 +0.105430 0.420580 +0.105430 0.036961 +0.489049 0.036961 +0.105430 0.420580 +0.489049 0.420580 +0.105430 0.036961 +0.489049 0.036961 +0.105430 0.420580 +0.489049 0.420580 +0.105430 0.036961 +0.489049 0.036961 +0.105430 0.420580 +0.489049 0.420580 +0.489049 0.036961 +0.105430 0.036961 +0.489049 0.420580 +0.105430 0.420580 +0.105430 0.036961 +0.489049 0.036961 +0.105430 0.420580 +0.489049 0.420580 +0.105430 0.036961 +0.489049 0.036961 +0.105430 0.420580 +0.489049 0.420580 +0.105430 0.036961 +0.489049 0.036961 +0.105430 0.420580 +0.489049 0.420580 +0.467426 0.244300 +0.467426 0.037231 +0.472758 0.037231 +0.326355 0.038969 +0.331690 0.038969 +0.331689 0.042629 +0.110811 0.041124 +0.110811 0.037364 +0.331690 0.047687 +0.326355 0.047687 +0.105832 0.246269 +0.472758 0.244300 +0.460786 0.037309 +0.466120 0.037309 +0.326357 0.042629 +0.466120 0.244456 +0.109592 0.246269 +0.318057 0.041124 +0.331690 0.043948 +0.109592 0.039023 +0.318057 0.037364 +0.105832 0.039023 +0.326355 0.043948 +0.460787 0.244456 +0.281892 0.257795 +0.278296 0.257795 +0.278296 0.050602 +0.281892 0.050602 +0.368191 0.050504 +0.364597 0.257639 +0.364599 0.050504 +0.368191 0.257582 +0.283385 0.257786 +0.283384 0.050612 +0.362543 0.050612 +0.362544 0.257786 +0.487685 0.120209 +0.487685 0.199272 +0.474133 0.116347 +0.474135 0.037227 +0.312987 0.338839 +0.105849 0.338894 +0.484093 0.199272 +0.484093 0.120209 +0.477727 0.116290 +0.477727 0.037227 +0.105794 0.259772 +0.312932 0.259717 +0.276913 0.257795 +0.273317 0.257795 +0.273317 0.050602 +0.276913 0.050602 +0.378149 0.050504 +0.374555 0.257639 +0.374557 0.050504 +0.189941 0.050612 +0.189941 0.257786 +0.110783 0.257786 +0.110782 0.050612 +0.477727 0.120209 +0.477727 0.199272 +0.378149 0.257582 +0.484091 0.116347 +0.484093 0.037227 +0.271218 0.050602 +0.271273 0.257740 +0.474135 0.199272 +0.474135 0.120209 +0.487685 0.116290 +0.487685 0.037227 +0.192150 0.257795 +0.192095 0.050658 +0.321285 0.042204 +0.321285 0.045800 +0.114092 0.045800 +0.114092 0.042204 +0.373170 0.050504 +0.369576 0.257639 +0.369578 0.050504 +0.312978 0.420207 +0.105804 0.420207 +0.105804 0.341048 +0.312978 0.341048 +0.482861 0.120209 +0.482861 0.199272 +0.479212 0.199274 +0.479212 0.120207 +0.373170 0.257582 +0.479112 0.116347 +0.479114 0.037227 +0.458811 0.244307 +0.379689 0.244363 +0.482706 0.116290 +0.482706 0.037227 +0.379634 0.037225 +0.458754 0.037227 +0.016244 0.715841 +0.756345 0.522332 +0.756346 0.715841 +0.016243 0.522332 +0.009526 0.061000 +0.749637 0.514493 +0.009526 0.514494 +0.749636 0.060999 +0.969477 0.480355 +0.969577 0.938728 +0.771464 0.938319 +0.771396 0.480706 +0.007192 0.039423 +0.751630 0.039423 +0.007192 0.498972 +0.751630 0.498972 +0.779207 0.499082 +0.779286 0.040707 +0.977371 0.041060 +0.977311 0.498670 +0.016243 0.911620 +0.756344 0.718111 +0.756344 0.911620 +0.016243 0.718111 +0.016244 0.715841 +0.756345 0.522332 +0.756346 0.715841 +0.016243 0.522332 +0.009526 0.061000 +0.749637 0.514493 +0.009526 0.514494 +0.749636 0.060999 +0.969477 0.480355 +0.969577 0.938728 +0.771464 0.938319 +0.771396 0.480706 +0.007192 0.039423 +0.751630 0.039423 +0.007192 0.498972 +0.751630 0.498972 +0.779207 0.499082 +0.779286 0.040707 +0.977371 0.041060 +0.977311 0.498670 +0.016243 0.911620 +0.756344 0.718111 +0.756344 0.911620 +0.016243 0.718111 +0.016244 0.715841 +0.756345 0.522332 +0.756346 0.715841 +0.016243 0.522332 +0.009526 0.061000 +0.749637 0.514493 +0.009526 0.514494 +0.749636 0.060999 +0.969477 0.480355 +0.969577 0.938728 +0.771464 0.938319 +0.771396 0.480706 +0.007192 0.039423 +0.751630 0.039423 +0.007192 0.498972 +0.751630 0.498972 +0.779207 0.499082 +0.779286 0.040707 +0.977371 0.041060 +0.977311 0.498670 +0.016243 0.911620 +0.756344 0.718111 +0.756344 0.911620 +0.016243 0.718111 +0.486957 0.692024 +0.027038 0.424800 +0.486954 0.424800 +0.027038 0.692024 +0.506996 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.966910 0.036168 +0.029544 0.043430 +0.489461 0.415225 +0.029544 0.415224 +0.489461 0.035380 +0.029544 0.035380 +0.037422 0.971548 +0.407335 0.698761 +0.409054 0.971742 +0.039211 0.698717 +0.965462 0.676852 +0.505546 0.676852 +0.505546 0.409621 +0.965459 0.409621 +0.914572 0.962378 +0.922325 0.705031 +0.922325 0.962378 +0.570344 0.705031 +0.570343 0.962377 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.206126 +1.014936 0.691973 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.206126 +0.170286 0.691973 +0.229772 0.173002 +0.933648 0.102615 +0.933648 0.173002 +0.229772 0.102615 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.206126 +1.014936 0.691973 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.206126 +0.170286 0.691973 +0.229772 0.173002 +0.933648 0.102615 +0.933648 0.173002 +0.229772 0.102615 +0.486957 0.692024 +0.027038 0.424800 +0.486954 0.424800 +0.027038 0.692024 +0.506996 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.966910 0.036168 +0.029544 0.043430 +0.489461 0.415225 +0.029544 0.415224 +0.489461 0.035380 +0.029544 0.035380 +0.037422 0.971548 +0.407335 0.698761 +0.409054 0.971742 +0.039211 0.698717 +0.965462 0.676852 +0.505546 0.676852 +0.505546 0.409621 +0.965459 0.409621 +0.914572 0.962378 +0.922325 0.705031 +0.922325 0.962378 +0.570344 0.705031 +0.570343 0.962377 +0.016244 0.715841 +0.756345 0.522332 +0.756346 0.715841 +0.016243 0.522332 +0.009526 0.061000 +0.749637 0.514493 +0.009526 0.514494 +0.749636 0.060999 +0.969477 0.480355 +0.969577 0.938728 +0.771464 0.938319 +0.771396 0.480706 +0.007192 0.039423 +0.751630 0.039423 +0.007192 0.498972 +0.751630 0.498972 +0.779207 0.499082 +0.779286 0.040707 +0.977371 0.041060 +0.977311 0.498670 +0.016243 0.911620 +0.756344 0.718111 +0.756344 0.911620 +0.016243 0.718111 +0.016244 0.715841 +0.756345 0.522332 +0.756346 0.715841 +0.016243 0.522332 +0.009526 0.061000 +0.749637 0.514493 +0.009526 0.514494 +0.749636 0.060999 +0.969477 0.480355 +0.969577 0.938728 +0.771464 0.938319 +0.771396 0.480706 +0.007192 0.039423 +0.751630 0.039423 +0.007192 0.498972 +0.751630 0.498972 +0.779207 0.499082 +0.779286 0.040707 +0.977371 0.041060 +0.977311 0.498670 +0.756344 0.911620 +0.016243 0.718111 +0.756344 0.718111 +0.016243 0.911620 +0.016244 0.715841 +0.756345 0.522332 +0.756346 0.715841 +0.016243 0.522332 +0.009526 0.061000 +0.749637 0.514493 +0.009526 0.514494 +0.749636 0.060999 +0.969477 0.480355 +0.969577 0.938728 +0.771464 0.938319 +0.771396 0.480706 +0.007192 0.039423 +0.751630 0.039423 +0.007192 0.498972 +0.751630 0.498972 +0.779207 0.499082 +0.779286 0.040707 +0.977371 0.041060 +0.977311 0.498670 +0.016243 0.911620 +0.756344 0.718111 +0.756344 0.911620 +0.016243 0.718111 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.206126 +1.014936 0.691973 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.206126 +0.170286 0.691973 +0.229772 0.173002 +0.933648 0.102615 +0.933648 0.173002 +0.229772 0.102615 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.206126 +1.014936 0.691973 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.206126 +0.170286 0.691973 +0.229772 0.173002 +0.933648 0.102615 +0.933648 0.173002 +0.229772 0.102615 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.206126 +1.014936 0.691973 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.691973 +0.170286 0.206126 +0.933648 0.173002 +0.229772 0.173002 +0.229772 0.102615 +0.933648 0.102615 +0.016244 0.715841 +0.756345 0.522332 +0.756346 0.715841 +0.016243 0.522332 +0.009526 0.061000 +0.749637 0.514493 +0.009526 0.514494 +0.749636 0.060999 +0.969477 0.480355 +0.969577 0.938728 +0.771464 0.938319 +0.771396 0.480706 +0.007192 0.039423 +0.751630 0.039423 +0.007192 0.498972 +0.751630 0.498972 +0.779207 0.499082 +0.779286 0.040707 +0.977371 0.041060 +0.977311 0.498670 +0.016243 0.911620 +0.756344 0.718111 +0.756344 0.911620 +0.016243 0.718111 +0.016244 0.715841 +0.756345 0.522332 +0.756346 0.715841 +0.016243 0.522332 +0.009526 0.061000 +0.749637 0.514493 +0.009526 0.514494 +0.749636 0.060999 +0.969477 0.480355 +0.969577 0.938728 +0.771464 0.938319 +0.771396 0.480706 +0.007192 0.039423 +0.751630 0.039423 +0.007192 0.498972 +0.751630 0.498972 +0.779207 0.499082 +0.779286 0.040707 +0.977371 0.041060 +0.977311 0.498670 +0.756344 0.911620 +0.016243 0.718111 +0.756344 0.718111 +0.016243 0.911620 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.206126 +1.014936 0.691973 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.691973 +0.170286 0.206126 +0.933648 0.173002 +0.229772 0.173002 +0.229772 0.102615 +0.933648 0.102615 +0.486957 0.692024 +0.027038 0.424800 +0.486954 0.424800 +0.027038 0.692024 +0.506996 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.966910 0.036168 +0.029544 0.043430 +0.489461 0.415225 +0.029544 0.415224 +0.489461 0.035380 +0.029544 0.035380 +0.037422 0.971548 +0.407335 0.698761 +0.409054 0.971742 +0.039211 0.698717 +0.965462 0.676852 +0.505546 0.676852 +0.505546 0.409621 +0.965459 0.409621 +0.914572 0.962378 +0.922325 0.705031 +0.922325 0.962378 +0.570344 0.705031 +0.570343 0.962377 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.206126 +1.014936 0.691973 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.206126 +0.170286 0.691973 +0.229772 0.173002 +0.933648 0.102615 +0.933648 0.173002 +0.229772 0.102615 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.206126 +1.014936 0.691973 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.206126 +0.170286 0.691973 +0.229772 0.173002 +0.933648 0.102615 +0.933648 0.173002 +0.229772 0.102615 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.206126 +1.014936 0.691973 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.691973 +0.170286 0.206126 +0.933648 0.173002 +0.229772 0.173002 +0.229772 0.102615 +0.933648 0.102615 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.206126 +1.014936 0.691973 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.691973 +0.170286 0.206126 +0.229772 0.173002 +0.933648 0.102615 +0.933648 0.173002 +0.229772 0.102615 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.206126 +1.014936 0.691973 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.206126 +0.170286 0.691973 +0.229772 0.173002 +0.933648 0.102615 +0.933648 0.173002 +0.229772 0.102615 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.206126 +1.014936 0.691973 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.206126 +0.170286 0.691973 +0.229772 0.173002 +0.933648 0.102615 +0.933648 0.173002 +0.229772 0.102615 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.206126 +1.014936 0.691973 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.691973 +0.170286 0.206126 +0.933648 0.173002 +0.229772 0.173002 +0.229772 0.102615 +0.933648 0.102615 +0.238676 0.691973 +0.942551 0.206126 +0.942551 0.691973 +0.238676 0.206126 +0.240673 0.206126 +0.944549 0.691973 +0.240673 0.691973 +0.944549 0.206126 +1.014936 0.206126 +1.014936 0.691973 +0.944549 0.762361 +0.240673 0.762360 +0.170286 0.691973 +0.170286 0.206126 +0.229772 0.173002 +0.933648 0.102615 +0.933648 0.173002 +0.229772 0.102615 +0.486957 0.692024 +0.027038 0.424800 +0.486954 0.424800 +0.027038 0.692024 +0.506996 0.036168 +0.966910 0.401663 +0.506996 0.401663 +0.966910 0.036168 +0.029544 0.043430 +0.489461 0.415225 +0.029544 0.415224 +0.489461 0.035380 +0.029544 0.035380 +0.037422 0.971548 +0.407335 0.698761 +0.409054 0.971742 +0.039211 0.698717 +0.965462 0.676852 +0.505546 0.676852 +0.505546 0.409621 +0.965459 0.409621 +0.914572 0.962378 +0.922325 0.705031 +0.922325 0.962378 +0.570344 0.705031 +0.570343 0.962377 + + + + + + + + + + + +

5 0 2 3 1 10 2 2 0 2 3 0 4 4 1 5 5 2 0 6 7 6 7 3 2 8 9 2 9 9 3 10 12 0 11 7 1 12 8 0 13 4 3 14 22 3 15 22 5 16 13 1 17 8 7 18 15 1 19 5 5 20 23 5 21 23 4 22 21 7 23 15 6 24 14 7 25 6 4 26 11 4 27 11 2 28 20 6 29 14 9 30 17 8 31 24 6 32 3 6 33 3 0 34 7 9 35 17 11 36 19 9 37 25 0 38 4 0 39 4 1 40 8 11 41 19 10 42 18 11 43 27 1 44 5 1 45 5 7 46 15 10 47 18 8 48 16 10 49 26 7 50 6 7 51 6 6 52 14 8 53 16 13 54 28 12 55 29 8 56 24 8 57 24 9 58 17 13 59 28 15 60 30 13 61 31 9 62 25 9 63 25 11 64 19 15 65 30 14 66 32 15 67 33 11 68 27 11 69 27 10 70 18 14 71 32 12 72 34 14 73 35 10 74 26 10 75 26 8 76 16 12 77 34 12 78 34 13 79 28 15 80 30 15 81 30 14 82 32 12 83 34 21 84 38 19 85 46 18 86 36 18 87 36 20 88 37 21 89 38 16 90 43 22 91 39 18 92 45 18 93 45 19 94 48 16 95 43 17 96 44 16 97 40 19 98 58 19 99 58 21 100 49 17 101 44 23 102 51 17 103 41 21 104 59 21 105 59 20 106 57 23 107 51 22 108 50 23 109 42 20 110 47 20 111 47 18 112 56 22 113 50 25 114 53 24 115 60 22 116 39 22 117 39 16 118 43 25 119 53 27 120 55 25 121 61 16 122 40 16 123 40 17 124 44 27 125 55 26 126 54 27 127 63 17 128 41 17 129 41 23 130 51 26 131 54 24 132 52 26 133 62 23 134 42 23 135 42 22 136 50 24 137 52 29 138 64 28 139 65 24 140 60 24 141 60 25 142 53 29 143 64 31 144 66 29 145 67 25 146 61 25 147 61 27 148 55 31 149 66 30 150 68 31 151 69 27 152 63 27 153 63 26 154 54 30 155 68 28 156 70 30 157 71 26 158 62 26 159 62 24 160 52 28 161 70 28 162 70 29 163 64 31 164 66 31 165 66 30 166 68 28 167 70 37 168 74 35 169 82 34 170 72 34 171 72 36 172 73 37 173 74 32 174 79 38 175 75 34 176 81 34 177 81 35 178 84 32 179 79 33 180 80 32 181 76 35 182 94 35 183 94 37 184 85 33 185 80 39 186 87 33 187 77 37 188 95 37 189 95 36 190 93 39 191 87 38 192 86 39 193 78 36 194 83 36 195 83 34 196 92 38 197 86 41 198 89 40 199 96 38 200 75 38 201 75 32 202 79 41 203 89 43 204 91 41 205 97 32 206 76 32 207 76 33 208 80 43 209 91 42 210 90 43 211 99 33 212 77 33 213 77 39 214 87 42 215 90 40 216 88 42 217 98 39 218 78 39 219 78 38 220 86 40 221 88 45 222 100 44 223 101 40 224 96 40 225 96 41 226 89 45 227 100 47 228 102 45 229 103 41 230 97 41 231 97 43 232 91 47 233 102 46 234 104 47 235 105 43 236 99 43 237 99 42 238 90 46 239 104 44 240 106 46 241 107 42 242 98 42 243 98 40 244 88 44 245 106 44 246 106 45 247 100 47 248 102 47 249 102 46 250 104 44 251 106 53 252 110 51 253 118 50 254 108 50 255 108 52 256 109 53 257 110 48 258 115 54 259 111 50 260 117 50 261 117 51 262 120 48 263 115 49 264 116 48 265 112 51 266 130 51 267 130 53 268 121 49 269 116 55 270 123 49 271 113 53 272 131 53 273 131 52 274 129 55 275 123 54 276 122 55 277 114 52 278 119 52 279 119 50 280 128 54 281 122 57 282 125 56 283 132 54 284 111 54 285 111 48 286 115 57 287 125 59 288 127 57 289 133 48 290 112 48 291 112 49 292 116 59 293 127 58 294 126 59 295 135 49 296 113 49 297 113 55 298 123 58 299 126 56 300 124 58 301 134 55 302 114 55 303 114 54 304 122 56 305 124 61 306 136 60 307 137 56 308 132 56 309 132 57 310 125 61 311 136 63 312 138 61 313 139 57 314 133 57 315 133 59 316 127 63 317 138 62 318 140 63 319 141 59 320 135 59 321 135 58 322 126 62 323 140 60 324 142 62 325 143 58 326 134 58 327 134 56 328 124 60 329 142 60 330 142 61 331 136 63 332 138 63 333 138 62 334 140 60 335 142 69 336 146 67 337 154 66 338 144 66 339 144 68 340 145 69 341 146 64 342 151 70 343 147 66 344 153 66 345 153 67 346 156 64 347 151 65 348 152 64 349 148 67 350 166 67 351 166 69 352 157 65 353 152 71 354 159 65 355 149 69 356 167 69 357 167 68 358 165 71 359 159 70 360 158 71 361 150 68 362 155 68 363 155 66 364 164 70 365 158 73 366 161 72 367 168 70 368 147 70 369 147 64 370 151 73 371 161 75 372 163 73 373 169 64 374 148 64 375 148 65 376 152 75 377 163 74 378 162 75 379 171 65 380 149 65 381 149 71 382 159 74 383 162 72 384 160 74 385 170 71 386 150 71 387 150 70 388 158 72 389 160 77 390 172 76 391 173 72 392 168 72 393 168 73 394 161 77 395 172 79 396 174 77 397 175 73 398 169 73 399 169 75 400 163 79 401 174 78 402 176 79 403 177 75 404 171 75 405 171 74 406 162 78 407 176 76 408 178 78 409 179 74 410 170 74 411 170 72 412 160 76 413 178 76 414 178 77 415 172 79 416 174 79 417 174 78 418 176 76 419 178 85 420 182 83 421 190 82 422 180 82 423 180 84 424 181 85 425 182 80 426 187 86 427 183 82 428 189 82 429 189 83 430 192 80 431 187 81 432 188 80 433 184 83 434 202 83 435 202 85 436 193 81 437 188 87 438 195 81 439 185 85 440 203 85 441 203 84 442 201 87 443 195 86 444 194 87 445 186 84 446 191 84 447 191 82 448 200 86 449 194 89 450 197 88 451 204 86 452 183 86 453 183 80 454 187 89 455 197 91 456 199 89 457 205 80 458 184 80 459 184 81 460 188 91 461 199 90 462 198 91 463 207 81 464 185 81 465 185 87 466 195 90 467 198 88 468 196 90 469 206 87 470 186 87 471 186 86 472 194 88 473 196 93 474 208 92 475 209 88 476 204 88 477 204 89 478 197 93 479 208 95 480 210 93 481 211 89 482 205 89 483 205 91 484 199 95 485 210 94 486 212 95 487 213 91 488 207 91 489 207 90 490 198 94 491 212 92 492 214 94 493 215 90 494 206 90 495 206 88 496 196 92 497 214 92 498 214 93 499 208 95 500 210 95 501 210 94 502 212 92 503 214 96 504 216 99 505 218 97 506 217 97 507 217 102 508 228 96 509 216 98 510 219 101 511 221 99 512 220 99 513 220 96 514 229 98 515 219 103 516 222 101 517 224 98 518 231 98 519 231 100 520 223 103 521 222 102 522 225 97 523 227 103 524 226 103 525 226 100 526 230 102 527 225 105 528 234 111 529 244 104 530 232 104 531 232 106 532 233 105 533 234 104 534 245 107 535 237 108 536 235 108 537 235 106 538 236 104 539 245 107 540 247 109 541 240 110 542 238 110 543 238 108 544 239 107 545 247 109 546 246 111 547 243 105 548 241 105 549 241 110 550 242 109 551 246 119 552 260 113 553 250 114 554 248 114 555 248 112 556 249 119 557 260 113 558 261 115 559 253 117 560 251 117 561 251 114 562 252 113 563 261 117 564 256 115 565 263 116 566 254 116 567 254 118 568 255 117 569 256 116 570 262 119 571 259 112 572 257 112 573 257 118 574 258 116 575 262 120 576 264 123 577 265 121 578 266 121 579 266 126 580 276 120 581 264 122 582 267 124 583 268 123 584 269 123 585 269 120 586 277 122 587 267 127 588 270 124 589 271 122 590 279 122 591 279 125 592 272 127 593 270 126 594 273 121 595 274 127 596 275 127 597 275 125 598 278 126 599 273 129 600 282 135 601 292 128 602 280 128 603 280 130 604 281 129 605 282 128 606 293 131 607 285 132 608 283 132 609 283 130 610 284 128 611 293 131 612 295 133 613 288 134 614 286 134 615 286 132 616 287 131 617 295 133 618 294 135 619 291 129 620 289 129 621 289 134 622 290 133 623 294 143 624 308 137 625 298 138 626 296 138 627 296 136 628 297 143 629 308 137 630 309 139 631 301 141 632 299 141 633 299 138 634 300 137 635 309 141 636 304 139 637 311 140 638 302 140 639 302 142 640 303 141 641 304 140 642 310 143 643 307 136 644 305 136 645 305 142 646 306 140 647 310 144 648 312 147 649 313 145 650 314 145 651 314 150 652 324 144 653 312 146 654 315 148 655 316 147 656 317 147 657 317 144 658 325 146 659 315 151 660 318 148 661 319 146 662 327 146 663 327 149 664 320 151 665 318 150 666 321 145 667 322 151 668 323 151 669 323 149 670 326 150 671 321 153 672 330 159 673 340 152 674 328 152 675 328 154 676 329 153 677 330 152 678 341 155 679 333 156 680 331 156 681 331 154 682 332 152 683 341 155 684 343 157 685 336 158 686 334 158 687 334 156 688 335 155 689 343 157 690 342 159 691 339 153 692 337 153 693 337 158 694 338 157 695 342 167 696 356 161 697 346 162 698 344 162 699 344 160 700 345 167 701 356 161 702 357 163 703 349 165 704 347 165 705 347 162 706 348 161 707 357 165 708 352 163 709 359 164 710 350 164 711 350 166 712 351 165 713 352 164 714 358 167 715 355 160 716 353 160 717 353 166 718 354 164 719 358 168 720 360 170 721 362 171 722 363 171 723 363 169 724 361 168 725 360 172 726 364 173 727 365 175 728 367 175 729 367 174 730 366 172 731 364 168 732 368 169 733 369 173 734 371 173 735 371 172 736 370 168 737 368 171 738 372 170 739 373 174 740 375 174 741 375 175 742 374 171 743 372 176 744 376 178 745 378 179 746 379 179 747 379 177 748 377 176 749 376 180 750 380 181 751 381 183 752 383 183 753 383 182 754 382 180 755 380 176 756 384 177 757 385 181 758 387 181 759 387 180 760 386 176 761 384 179 762 388 178 763 389 182 764 391 182 765 391 183 766 390 179 767 388 184 768 392 186 769 394 187 770 395 187 771 395 185 772 393 184 773 392 188 774 396 189 775 397 191 776 399 191 777 399 190 778 398 188 779 396 184 780 400 185 781 401 189 782 403 189 783 403 188 784 402 184 785 400 187 786 404 186 787 405 190 788 407 190 789 407 191 790 406 187 791 404 197 792 410 195 793 419 194 794 408 194 795 408 196 796 409 197 797 410 193 798 423 199 799 431 198 800 420 198 801 420 192 802 421 193 803 423 192 804 413 198 805 422 194 806 411 194 807 411 195 808 412 192 809 413 193 810 415 192 811 428 195 812 425 195 813 425 197 814 414 193 815 415 199 816 416 193 817 417 197 818 430 197 819 430 196 820 426 199 821 416 198 822 418 199 823 429 196 824 427 196 825 427 194 826 424 198 827 418 205 828 442 203 829 443 202 830 440 202 831 440 204 832 441 205 833 442 201 834 449 207 835 454 206 836 455 206 837 455 200 838 448 201 839 449 200 840 450 206 841 451 202 842 444 202 843 444 203 844 445 200 845 450 201 846 433 200 847 434 203 848 435 203 849 435 205 850 432 201 851 433 207 852 446 201 853 447 205 854 453 205 855 453 204 856 452 207 857 446 206 858 437 207 859 438 204 860 436 204 861 436 202 862 439 206 863 437 213 864 465 211 865 466 210 866 463 210 867 463 212 868 464 213 869 465 209 870 473 215 871 478 214 872 479 214 873 479 208 874 472 209 875 473 208 876 474 214 877 475 210 878 467 210 879 467 211 880 468 208 881 474 209 882 457 208 883 458 211 884 459 211 885 459 213 886 456 209 887 457 215 888 470 209 889 471 213 890 477 213 891 477 212 892 476 215 893 470 214 894 461 215 895 462 212 896 460 212 897 460 210 898 469 214 899 461 220 900 489 218 901 490 216 902 487 216 903 487 217 904 488 220 905 489 221 906 498 222 907 499 223 908 502 223 909 502 219 910 503 221 911 498 219 912 493 223 913 494 216 914 491 216 915 491 218 916 492 219 917 493 221 918 481 219 919 482 218 920 483 218 921 483 220 922 480 221 923 481 222 924 496 221 925 497 220 926 501 220 927 501 217 928 500 222 929 496 223 930 485 222 931 486 217 932 484 217 933 484 216 934 495 223 935 485

+

+

248 936 576 249 937 577 250 938 578 249 939 577 248 940 576 251 941 579 252 942 580 250 943 581 249 944 582 250 945 581 252 946 580 253 947 583 254 948 584 251 949 585 248 950 586 251 951 585 254 952 584 255 953 587 256 954 588 255 955 587 254 956 584 255 957 589 249 958 590 251 959 591 249 960 590 255 961 589 252 962 592 255 963 593 256 964 594 253 965 595 255 966 593 253 967 595 252 968 596 254 969 597 253 970 598 256 971 599 253 972 598 254 973 597 250 974 600 254 975 597 248 976 601 250 977 600 273 978 638 274 979 639 275 980 640 274 981 639 273 982 638 276 983 641 277 984 642 275 985 643 274 986 644 275 987 643 277 988 642 278 989 645 279 990 646 276 991 647 273 992 648 276 993 647 279 994 646 280 995 649 281 996 650 280 997 649 279 998 646 280 999 651 274 1000 652 276 1001 653 274 1002 652 280 1003 651 277 1004 654 280 1005 655 281 1006 656 278 1007 657 280 1008 655 278 1009 657 277 1010 658 279 1011 659 278 1012 660 281 1013 661 278 1014 660 279 1015 659 275 1016 662 279 1017 659 273 1018 663 275 1019 662 354 1020 856 355 1021 857 356 1022 858 355 1023 857 354 1024 856 357 1025 859 358 1026 860 356 1027 861 355 1028 862 356 1029 861 358 1030 860 359 1031 863 360 1032 864 357 1033 865 354 1034 866 357 1035 865 360 1036 864 361 1037 867 362 1038 868 361 1039 867 360 1040 864 361 1041 869 355 1042 870 357 1043 871 355 1044 870 361 1045 869 358 1046 872 361 1047 873 362 1048 874 359 1049 875 361 1050 873 359 1051 875 358 1052 876 360 1053 877 359 1054 878 362 1055 879 359 1056 878 360 1057 877 356 1058 880 360 1059 877 354 1060 881 356 1061 880 427 1062 1026 428 1063 1027 429 1064 1028 428 1065 1027 427 1066 1026 430 1067 1029 431 1068 1030 429 1069 1031 428 1070 1032 429 1071 1031 431 1072 1030 432 1073 1033 433 1074 1034 430 1075 1035 427 1076 1036 430 1077 1035 433 1078 1034 434 1079 1037 435 1080 1038 434 1081 1037 433 1082 1034 434 1083 1039 428 1084 1040 430 1085 1041 428 1086 1040 434 1087 1039 431 1088 1042 434 1089 1043 435 1090 1044 432 1091 1045 434 1092 1043 432 1093 1045 431 1094 1046 433 1095 1047 432 1096 1048 435 1097 1049 432 1098 1048 433 1099 1047 429 1100 1050 433 1101 1047 427 1102 1051 429 1103 1050

+

224 1104 504 225 1105 505 226 1106 506 225 1107 505 224 1108 504 227 1109 507 225 1110 508 228 1111 509 229 1112 510 228 1113 509 225 1114 508 227 1115 511 230 1116 512 226 1117 513 225 1118 514 230 1119 512 225 1120 514 229 1121 515 230 1122 516 231 1123 517 226 1124 518 231 1125 517 224 1126 519 226 1127 518 224 1128 520 231 1129 521 228 1130 522 224 1131 520 228 1132 522 227 1133 523 230 1134 524 228 1135 525 231 1136 526 228 1137 525 230 1138 524 229 1139 527 232 1140 528 233 1141 529 234 1142 530 233 1143 529 232 1144 528 235 1145 531 233 1146 532 236 1147 533 237 1148 534 236 1149 533 233 1150 532 235 1151 535 238 1152 536 234 1153 537 233 1154 538 238 1155 536 233 1156 538 237 1157 539 238 1158 540 239 1159 541 234 1160 542 239 1161 541 232 1162 543 234 1163 542 232 1164 544 239 1165 545 236 1166 546 232 1167 544 236 1168 546 235 1169 547 238 1170 548 236 1171 549 239 1172 550 236 1173 549 238 1174 548 237 1175 551 240 1176 552 241 1177 553 242 1178 554 241 1179 553 240 1180 552 243 1181 555 241 1182 556 244 1183 557 245 1184 558 244 1185 557 241 1186 556 243 1187 559 246 1188 560 242 1189 561 241 1190 562 246 1191 560 241 1192 562 245 1193 563 246 1194 564 247 1195 565 242 1196 566 247 1197 565 240 1198 567 242 1199 566 240 1200 568 247 1201 569 244 1202 570 240 1203 568 244 1204 570 243 1205 571 246 1206 572 244 1207 573 247 1208 574 244 1209 573 246 1210 572 245 1211 575 282 1212 664 283 1213 665 284 1214 666 283 1215 665 282 1216 664 285 1217 667 283 1218 668 286 1219 669 287 1220 670 286 1221 669 283 1222 668 285 1223 671 288 1224 672 284 1225 673 283 1226 674 288 1227 672 283 1228 674 287 1229 675 288 1230 676 289 1231 677 284 1232 678 289 1233 677 282 1234 679 284 1235 678 282 1236 680 289 1237 681 286 1238 682 282 1239 680 286 1240 682 285 1241 683 288 1242 684 286 1243 685 289 1244 686 286 1245 685 288 1246 684 287 1247 687 290 1248 688 291 1249 689 292 1250 690 291 1251 689 290 1252 688 293 1253 691 291 1254 692 294 1255 693 295 1256 694 294 1257 693 291 1258 692 293 1259 695 296 1260 696 292 1261 697 291 1262 698 296 1263 696 291 1264 698 295 1265 699 296 1266 700 297 1267 701 292 1268 702 297 1269 701 290 1270 703 292 1271 702 290 1272 704 297 1273 705 294 1274 706 290 1275 704 294 1276 706 293 1277 707 297 1278 708 295 1279 709 294 1280 710 295 1281 709 297 1282 708 296 1283 711 298 1284 712 299 1285 713 300 1286 714 299 1287 713 298 1288 712 301 1289 715 299 1290 716 302 1291 717 303 1292 718 302 1293 717 299 1294 716 301 1295 719 304 1296 720 300 1297 721 299 1298 722 304 1299 720 299 1300 722 303 1301 723 304 1302 724 305 1303 725 300 1304 726 305 1305 725 298 1306 727 300 1307 726 298 1308 728 305 1309 729 302 1310 730 298 1311 728 302 1312 730 301 1313 731 304 1314 732 302 1315 733 305 1316 734 302 1317 733 304 1318 732 303 1319 735 330 1320 790 331 1321 791 332 1322 792 331 1323 791 330 1324 790 333 1325 793 331 1326 794 334 1327 795 335 1328 796 334 1329 795 331 1330 794 333 1331 797 336 1332 798 332 1333 799 331 1334 800 336 1335 798 331 1336 800 335 1337 801 336 1338 802 337 1339 803 332 1340 804 337 1341 803 330 1342 805 332 1343 804 330 1344 806 337 1345 807 334 1346 808 330 1347 806 334 1348 808 333 1349 809 336 1350 810 334 1351 811 337 1352 812 334 1353 811 336 1354 810 335 1355 813 338 1356 814 339 1357 815 340 1358 816 339 1359 815 338 1360 814 341 1361 817 339 1362 818 342 1363 819 343 1364 820 342 1365 819 339 1366 818 341 1367 821 344 1368 822 340 1369 823 339 1370 824 344 1371 822 339 1372 824 343 1373 825 344 1374 826 345 1375 827 340 1376 828 345 1377 827 338 1378 829 340 1379 828 338 1380 830 345 1381 831 342 1382 832 338 1383 830 342 1384 832 341 1385 833 345 1386 834 343 1387 835 342 1388 836 343 1389 835 345 1390 834 344 1391 837

+

257 1392 602 258 1393 603 259 1394 604 258 1395 603 257 1396 602 260 1397 605 261 1398 606 262 1399 607 263 1400 608 262 1401 607 261 1402 606 264 1403 609 262 1404 607 264 1405 609 260 1406 610 262 1407 607 260 1408 610 257 1409 611 263 1410 608 262 1411 607 257 1412 612 263 1413 608 257 1414 612 259 1415 613 263 1416 608 258 1417 614 261 1418 606 258 1419 614 263 1420 608 259 1421 615 261 1422 616 260 1423 617 264 1424 618 260 1425 617 261 1426 616 258 1427 619 265 1428 620 266 1429 621 267 1430 622 266 1431 621 265 1432 620 268 1433 623 269 1434 624 270 1435 625 271 1436 626 270 1437 625 269 1438 624 272 1439 627 270 1440 625 272 1441 627 268 1442 628 270 1443 625 268 1444 628 265 1445 629 271 1446 626 270 1447 625 265 1448 630 271 1449 626 265 1450 630 267 1451 631 271 1452 626 266 1453 632 269 1454 624 266 1455 632 271 1456 626 267 1457 633 269 1458 634 268 1459 635 272 1460 636 268 1461 635 269 1462 634 266 1463 637 306 1464 736 307 1465 737 308 1466 738 307 1467 737 306 1468 736 309 1469 739 310 1470 740 311 1471 741 312 1472 742 311 1473 741 310 1474 740 313 1475 743 311 1476 741 313 1477 743 309 1478 744 311 1479 741 309 1480 744 306 1481 745 312 1482 742 311 1483 741 306 1484 746 312 1485 742 306 1486 746 308 1487 747 312 1488 742 307 1489 748 310 1490 740 307 1491 748 312 1492 742 308 1493 749 310 1494 750 309 1495 751 313 1496 752 309 1497 751 310 1498 750 307 1499 753 314 1500 754 315 1501 755 316 1502 756 315 1503 755 314 1504 754 317 1505 757 318 1506 758 319 1507 759 320 1508 760 319 1509 759 318 1510 758 321 1511 761 319 1512 759 321 1513 761 317 1514 762 319 1515 759 317 1516 762 314 1517 763 320 1518 760 319 1519 759 314 1520 764 320 1521 760 314 1522 764 316 1523 765 320 1524 760 315 1525 766 318 1526 758 315 1527 766 320 1528 760 316 1529 767 318 1530 768 317 1531 769 321 1532 770 317 1533 769 318 1534 768 315 1535 771 322 1536 772 323 1537 773 324 1538 774 323 1539 773 322 1540 772 325 1541 775 326 1542 776 327 1543 777 328 1544 778 327 1545 777 326 1546 776 329 1547 779 327 1548 777 329 1549 779 325 1550 780 327 1551 777 325 1552 780 322 1553 781 328 1554 778 327 1555 777 322 1556 782 328 1557 778 322 1558 782 324 1559 783 326 1560 776 328 1561 778 324 1562 784 326 1563 776 324 1564 784 323 1565 785 329 1566 786 326 1567 787 323 1568 788 329 1569 786 323 1570 788 325 1571 789 346 1572 838 347 1573 839 348 1574 840 347 1575 839 346 1576 838 349 1577 841 350 1578 842 351 1579 843 352 1580 844 351 1581 843 350 1582 842 353 1583 845 351 1584 843 353 1585 845 349 1586 846 351 1587 843 349 1588 846 346 1589 847 352 1590 844 351 1591 843 346 1592 848 352 1593 844 346 1594 848 348 1595 849 350 1596 842 352 1597 844 348 1598 850 350 1599 842 348 1600 850 347 1601 851 353 1602 852 350 1603 853 347 1604 854 353 1605 852 347 1606 854 349 1607 855 363 1608 882 364 1609 883 365 1610 884 364 1611 883 363 1612 882 366 1613 885 367 1614 886 368 1615 887 369 1616 888 368 1617 887 367 1618 886 370 1619 889 368 1620 887 370 1621 889 366 1622 890 368 1623 887 366 1624 890 363 1625 891 369 1626 888 368 1627 887 363 1628 892 369 1629 888 363 1630 892 365 1631 893 369 1632 888 364 1633 894 367 1634 886 364 1635 894 369 1636 888 365 1637 895 367 1638 896 366 1639 897 370 1640 898 366 1641 897 367 1642 896 364 1643 899 371 1644 900 372 1645 901 373 1646 902 372 1647 901 371 1648 900 374 1649 903 375 1650 904 376 1651 905 377 1652 906 376 1653 905 375 1654 904 378 1655 907 376 1656 905 378 1657 907 374 1658 908 376 1659 905 374 1660 908 371 1661 909 377 1662 906 376 1663 905 371 1664 910 377 1665 906 371 1666 910 373 1667 911 377 1668 906 372 1669 912 375 1670 904 372 1671 912 377 1672 906 373 1673 913 375 1674 914 374 1675 915 378 1676 916 374 1677 915 375 1678 914 372 1679 917 379 1680 918 380 1681 919 381 1682 920 380 1683 919 379 1684 918 382 1685 921 383 1686 922 384 1687 923 385 1688 924 384 1689 923 383 1690 922 386 1691 925 384 1692 923 386 1693 925 382 1694 926 384 1695 923 382 1696 926 379 1697 927 385 1698 924 384 1699 923 379 1700 928 385 1701 924 379 1702 928 381 1703 929 383 1704 922 385 1705 924 381 1706 930 383 1707 922 381 1708 930 380 1709 931 386 1710 932 383 1711 933 380 1712 934 386 1713 932 380 1714 934 382 1715 935 387 1716 936 388 1717 937 389 1718 938 388 1719 937 387 1720 936 390 1721 939 391 1722 940 392 1723 941 393 1724 942 392 1725 941 391 1726 940 394 1727 943 392 1728 941 394 1729 943 390 1730 944 392 1731 941 390 1732 944 387 1733 945 393 1734 942 392 1735 941 387 1736 946 393 1737 942 387 1738 946 389 1739 947 391 1740 940 393 1741 942 389 1742 948 391 1743 940 389 1744 948 388 1745 949 391 1746 950 390 1747 951 394 1748 952 390 1749 951 391 1750 950 388 1751 953 395 1752 954 396 1753 955 397 1754 956 396 1755 955 395 1756 954 398 1757 957 399 1758 958 400 1759 959 401 1760 960 400 1761 959 399 1762 958 402 1763 961 400 1764 959 402 1765 961 398 1766 962 400 1767 959 398 1768 962 395 1769 963 401 1770 960 400 1771 959 395 1772 964 401 1773 960 395 1774 964 397 1775 965 401 1776 960 396 1777 966 399 1778 958 396 1779 966 401 1780 960 397 1781 967 399 1782 968 398 1783 969 402 1784 970 398 1785 969 399 1786 968 396 1787 971 403 1788 972 404 1789 973 405 1790 974 404 1791 973 403 1792 972 406 1793 975 407 1794 976 408 1795 977 409 1796 978 408 1797 977 407 1798 976 410 1799 979 408 1800 977 410 1801 979 406 1802 980 408 1803 977 406 1804 980 403 1805 981 409 1806 978 408 1807 977 403 1808 982 409 1809 978 403 1810 982 405 1811 983 409 1812 978 404 1813 984 407 1814 976 404 1815 984 409 1816 978 405 1817 985 407 1818 986 406 1819 987 410 1820 988 406 1821 987 407 1822 986 404 1823 989 411 1824 990 412 1825 991 413 1826 992 412 1827 991 411 1828 990 414 1829 993 415 1830 994 416 1831 995 417 1832 996 416 1833 995 415 1834 994 418 1835 997 416 1836 995 418 1837 997 414 1838 998 416 1839 995 414 1840 998 411 1841 999 417 1842 996 416 1843 995 411 1844 1000 417 1845 996 411 1846 1000 413 1847 1001 415 1848 994 417 1849 996 413 1850 1002 415 1851 994 413 1852 1002 412 1853 1003 418 1854 1004 415 1855 1005 412 1856 1006 418 1857 1004 412 1858 1006 414 1859 1007 419 1860 1008 420 1861 1009 421 1862 1010 420 1863 1009 419 1864 1008 422 1865 1011 423 1866 1012 424 1867 1013 425 1868 1014 424 1869 1013 423 1870 1012 426 1871 1015 424 1872 1013 426 1873 1015 422 1874 1016 424 1875 1013 422 1876 1016 419 1877 1017 425 1878 1014 424 1879 1013 419 1880 1018 425 1881 1014 419 1882 1018 421 1883 1019 423 1884 1012 425 1885 1014 421 1886 1020 423 1887 1012 421 1888 1020 420 1889 1021 423 1890 1022 422 1891 1023 426 1892 1024 422 1893 1023 423 1894 1022 420 1895 1025

+
+
+
+ + + + + + + + + 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 3.020157 0.000000 0.000000 0.000000 1.0000001.000000 + 30.0000000.0000003.333333 + + + + + +
diff --git a/simulators/sim_env/models/aws_robomaker_warehouse_ShelfE_01/model.config b/simulators/sim_env/models/aws_robomaker_warehouse_ShelfE_01/model.config new file mode 100755 index 0000000..cddf840 --- /dev/null +++ b/simulators/sim_env/models/aws_robomaker_warehouse_ShelfE_01/model.config @@ -0,0 +1,11 @@ + + + aws_robomaker_warehouse_ShelfE_01 + 1.0 + model.sdf + + + + + + diff --git a/simulators/sim_env/models/aws_robomaker_warehouse_ShelfE_01/model.sdf b/simulators/sim_env/models/aws_robomaker_warehouse_ShelfE_01/model.sdf new file mode 100755 index 0000000..d615c9e --- /dev/null +++ b/simulators/sim_env/models/aws_robomaker_warehouse_ShelfE_01/model.sdf @@ -0,0 +1,46 @@ + + + + + + 30 + + 907.144 + 0 + 0 + 104.950 + 0 + 824.248 + + + + + + model://aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + model://aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_visual.DAE + + + 1 + + +1 + + diff --git a/simulators/sim_env/models/construction_cone/materials/textures/Construction_Cone_Diffuse.png b/simulators/sim_env/models/construction_cone/materials/textures/Construction_Cone_Diffuse.png new file mode 100755 index 0000000..181004a Binary files /dev/null and b/simulators/sim_env/models/construction_cone/materials/textures/Construction_Cone_Diffuse.png differ diff --git a/simulators/sim_env/models/construction_cone/meshes/construction_cone.dae b/simulators/sim_env/models/construction_cone/meshes/construction_cone.dae new file mode 100755 index 0000000..dd66929 --- /dev/null +++ b/simulators/sim_env/models/construction_cone/meshes/construction_cone.dae @@ -0,0 +1,163 @@ + + + + + Cole + OpenCOLLADA for 3ds Max; Version: 1.3.1; Revision: 847M; Platform: x64; Configuration: Release_Max2012_static + + 2013-01-29T21:43:10 + 2013-01-29T21:43:10 + + Z_UP + + + + + + + Construction_Cone_Diffuse_tga + + + + + Construction_Cone_Diffuse_tga-surface + + + + + + 0.2 0.2 0.2 1 + + + 0.5882353 0.5882353 0.5882353 1 + + + + + + 0.9 0.9 0.9 1 + + + 27 + + + 0 0 0 1 + + + 1 1 1 1 + + + 1 + + + + + + + + 0 + 0 + 0 + 1.5 + 0 + 3 + 1 + 0 + + + 1 + 1 + 0 + 0.1 + 0 + + + + + + + + + + + + + + + -0.6700001 -0.99 0 0.6700001 -0.99 0 -0.99 0.6700001 0 0.99 0.6700001 0 -0.6700001 -0.99 0.2590999 0.99 -0.6700001 0.2590999 -0.99 0.6700001 0.2590999 0.6700001 0.99 0.2590999 -0.99 -0.6700001 0 0.99 -0.6700001 0 -0.6700001 0.99 0 0.6700001 0.99 0 -0.95 -0.6534315 0.2990999 0.6700001 -0.99 0.2590999 -0.6534315 0.95 0.2990999 0.99 0.6700001 0.2590999 -0.6534315 -0.95 0.2990999 0.95 -0.6534315 0.2990999 -0.95 0.6534315 0.2990999 0.6534315 0.95 0.2990999 -0.99 -0.6700001 0.2590999 0.6534315 -0.95 0.2990999 -0.6700001 0.99 0.2590999 0.95 0.6534315 0.2990999 -0.3953661 0.661109 0.2990999 -0.6611091 0.3953661 0.2990999 -0.6611091 -0.3953659 0.2990999 0.2031441 -3.55414e-9 4.26 0.1759279 0.1015721 4.26 0.101572 0.175928 4.26 -7.64086e-8 0.2031442 4.26 -0.1015722 0.175928 4.26 -0.1759281 0.1015721 4.26 -0.2031442 2.71198e-8 4.26 -0.1759281 -0.101572 4.26 -0.1015722 -0.175928 4.26 -1.61973e-7 -0.2031442 4.26 0.1015719 -0.1759281 4.26 0.1759279 -0.1015722 4.26 0.1308598 -6.48709e-9 4.26 0.1133279 0.06542993 4.26 0.06542987 0.113328 4.26 -8.19175e-8 0.1308599 4.26 -0.06543002 0.113328 4.26 -0.113328 0.06542993 4.26 -0.1308599 1.32722e-8 4.26 -0.1133281 -0.06542991 4.26 -0.06543004 -0.113328 4.26 -1.37036e-7 -0.1308599 4.26 0.06542981 -0.113328 4.26 0.1133279 -0.06543003 4.26 -8.75443e-8 -2.48353e-9 4.039184 0.7649804 -3.17423e-8 0.2990999 0.6611091 0.3953661 0.2990999 0.395366 0.6611091 0.2990999 -0.3953663 -0.661109 0.2990999 -3.30479e-7 -0.7649803 0.2990999 0.3953657 -0.6611092 0.2990999 0.661109 -0.3953665 0.2990999 -0.3529956 0.6114063 0.3566594 -0.6114063 0.3529956 0.3566594 -0.7059912 8.38732e-8 0.3566594 -0.7649803 8.87532e-8 0.2990999 -0.6114064 -0.3529955 0.3566594 0.7059912 -2.8389e-8 0.3566594 0.6114063 0.3529956 0.3566594 0.3529955 0.6114064 0.3566594 -5.3236e-8 0.7059911 0.3566594 -5.06183e-8 0.7649804 0.2990999 -0.3529958 -0.6114062 0.3566594 -3.20017e-7 -0.7059911 0.3566594 0.3529952 -0.6114064 0.3566594 0.6114061 -0.352996 0.3566594 0.1670019 -5.02061e-9 4.286964 0.1446279 0.083501 4.286964 0.08350094 0.144628 4.286964 -7.91631e-8 0.1670021 4.286964 -0.08350109 0.144628 4.286964 -0.144628 0.083501 4.286964 -0.1670021 2.0196e-8 4.286964 -0.1446281 -0.08350097 4.286964 -0.08350111 -0.144628 4.286964 -1.49504e-7 -0.1670021 4.286964 0.08350086 -0.144628 4.286964 0.1446279 -0.08350112 4.286964 + + + + + + + + + + 0 0 -1 0 0 -1 0 0 -0.9999999 0 0 -1 0 0 -1 0 0 -0.9999999 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.9999999 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.9999999 0 0 -1 -0.3826835 -0.9238794 0 0.3826834 -0.9238794 0 0.3556998 -0.8587351 0.3688518 0.3556998 -0.8587351 0.3688518 -0.3556998 -0.8587351 0.3688518 -0.3826835 -0.9238794 0 0.9238794 -0.3826835 0 0.9238794 0.3826834 0 0.8587351 0.3556998 0.3688518 0.8587351 0.3556998 0.3688518 0.8587351 -0.3556998 0.3688518 0.9238794 -0.3826835 0 0.3826835 0.9238794 0 -0.3826834 0.9238794 0 -0.3556998 0.8587351 0.3688518 -0.3556998 0.8587351 0.3688518 0.3556998 0.8587351 0.3688518 0.3826835 0.9238794 0 -0.9238794 0.3826835 0 -0.9238794 -0.3826834 0 -0.8587351 -0.3556998 0.3688518 -0.8587351 -0.3556998 0.3688518 -0.8587351 0.3556998 0.3688518 -0.9238794 0.3826835 0 0.3826834 -0.9238794 0 0.9238794 -0.3826835 0 0.8587351 -0.3556998 0.3688518 0.8587351 -0.3556998 0.3688518 0.3556998 -0.8587351 0.3688518 0.3826834 -0.9238794 0 -0.3556998 -0.8587351 0.3688518 -0.8587351 -0.3556998 0.3688518 -0.9238794 -0.3826834 0 -0.9238794 -0.3826834 0 -0.3826835 -0.9238794 0 -0.3556998 -0.8587351 0.3688518 0.9238794 0.3826834 0 0.3826835 0.9238794 0 0.3556998 0.8587351 0.3688518 0.3556998 0.8587351 0.3688518 0.8587351 0.3556998 0.3688518 0.9238794 0.3826834 0 -0.3826834 0.9238794 0 -0.9238794 0.3826835 0 -0.8587351 0.3556998 0.3688518 -0.8587351 0.3556998 0.3688518 -0.3556998 0.8587351 0.3688518 -0.3826834 0.9238794 0 -0.1675019 -0.4043854 0.8991193 -0.3556998 -0.8587351 0.3688518 0.3556998 -0.8587351 0.3688518 0.3556998 -0.8587351 0.3688518 0.1675019 -0.4043854 0.8991193 -0.1675019 -0.4043854 0.8991193 0.4043854 -0.1675019 0.8991193 0.8587351 -0.3556998 0.3688518 0.8587351 0.3556998 0.3688518 0.8587351 0.3556998 0.3688518 0.4043854 0.1675019 0.8991192 0.4043854 -0.1675019 0.8991193 0.1675019 0.4043854 0.8991193 0.3556998 0.8587351 0.3688518 -0.3556998 0.8587351 0.3688518 -0.3556998 0.8587351 0.3688518 -0.1675019 0.4043854 0.8991192 0.1675019 0.4043854 0.8991193 -0.4043854 0.1675019 0.8991193 -0.8587351 0.3556998 0.3688518 -0.8587351 -0.3556998 0.3688518 -0.8587351 -0.3556998 0.3688518 -0.4043854 -0.1675019 0.8991193 -0.4043854 0.1675019 0.8991193 -0.3556998 -0.8587351 0.3688518 -0.1675019 -0.4043854 0.8991193 -0.4043854 -0.1675019 0.8991193 -0.4043854 -0.1675019 0.8991193 -0.8587351 -0.3556998 0.3688518 -0.3556998 -0.8587351 0.3688518 0.8587351 -0.3556998 0.3688518 0.4043854 -0.1675019 0.8991193 0.1675019 -0.4043854 0.8991193 0.1675019 -0.4043854 0.8991193 0.3556998 -0.8587351 0.3688518 0.8587351 -0.3556998 0.3688518 -0.8587351 0.3556998 0.3688518 -0.4043854 0.1675019 0.8991193 -0.1675019 0.4043854 0.8991192 -0.1675019 0.4043854 0.8991192 -0.3556998 0.8587351 0.3688518 -0.8587351 0.3556998 0.3688518 0.3556998 0.8587351 0.3688518 0.1675019 0.4043854 0.8991193 0.4043854 0.1675019 0.8991192 0.4043854 0.1675019 0.8991192 0.8587351 0.3556998 0.3688518 0.3556998 0.8587351 0.3688518 -5.89176e-4 -0.3213188 0.9469709 -0.1675019 -0.4043854 0.8991193 0.1675019 -0.4043854 0.8991193 0.7604591 0.4390513 0.4784723 0.8781026 -8.55713e-8 0.4784723 0.8825297 -9.93156e-4 0.4702555 0.8825297 -9.93156e-4 0.4702555 0.7603678 0.4268155 0.4895605 0.7604591 0.4390513 0.4784723 0.4390514 0.7604591 0.4784723 0.7604591 0.4390513 0.4784723 0.7603678 0.4268155 0.4895605 0.7603678 0.4268155 0.4895605 0.4260493 0.7612234 0.4888977 0.4390514 0.7604591 0.4784723 -4.19125e-8 0.8781027 0.4784722 0.4390514 0.7604591 0.4784723 0.4260493 0.7612234 0.4888977 0.4260493 0.7612234 0.4888977 9.92869e-4 0.8825298 0.4702554 -4.19125e-8 0.8781027 0.4784722 -0.4390515 0.7604591 0.4784722 -4.19125e-8 0.8781027 0.4784722 9.92869e-4 0.8825298 0.4702554 9.92869e-4 0.8825298 0.4702554 -0.4268156 0.7603678 0.4895603 -0.4390515 0.7604591 0.4784722 -0.7604593 0.4390512 0.4784723 -0.4390515 0.7604591 0.4784722 -0.4268156 0.7603678 0.4895603 -0.4268156 0.7603678 0.4895603 -0.7612233 0.4260494 0.4888977 -0.7604593 0.4390512 0.4784723 -0.8781026 1.14561e-7 0.4784722 -0.7604593 0.4390512 0.4784723 -0.7612233 0.4260494 0.4888977 -0.7612233 0.4260494 0.4888977 -0.88253 9.93171e-4 0.470255 -0.8781026 1.14561e-7 0.4784722 -0.7604594 -0.4390511 0.4784722 -0.8781026 1.14561e-7 0.4784722 -0.88253 9.93171e-4 0.470255 -0.88253 9.93171e-4 0.470255 -0.7603679 -0.4268154 0.4895604 -0.7604594 -0.4390511 0.4784722 -0.4390517 -0.7604589 0.4784723 -0.7604594 -0.4390511 0.4784722 -0.7603679 -0.4268154 0.4895604 -0.7603679 -0.4268154 0.4895604 -0.4260495 -0.7612232 0.4888977 -0.4390517 -0.7604589 0.4784723 -4.07948e-7 -0.8781026 0.4784723 -0.4390517 -0.7604589 0.4784723 -0.4260495 -0.7612232 0.4888977 -0.4260495 -0.7612232 0.4888977 -9.93358e-4 -0.8825299 0.4702552 -4.07948e-7 -0.8781026 0.4784723 0.439051 -0.7604594 0.4784723 -4.07948e-7 -0.8781026 0.4784723 -9.93358e-4 -0.8825299 0.4702552 -9.93358e-4 -0.8825299 0.4702552 0.4268149 -0.7603682 0.4895602 0.439051 -0.7604594 0.4784723 0.7604589 -0.4390516 0.4784723 0.439051 -0.7604594 0.4784723 0.4268149 -0.7603682 0.4895602 0.4268149 -0.7603682 0.4895602 0.7612231 -0.4260497 0.4888979 0.7604589 -0.4390516 0.4784723 0.7604591 0.4390513 0.4784723 0.085531 0.0493813 0.995111 0.09876256 -2.98196e-8 0.995111 0.09876256 -2.98196e-8 0.995111 0.8781026 -8.55713e-8 0.4784723 0.7604591 0.4390513 0.4784723 0.4390514 0.7604591 0.4784723 0.04938133 0.08553088 0.995111 0.085531 0.0493813 0.995111 0.085531 0.0493813 0.995111 0.7604591 0.4390513 0.4784723 0.4390514 0.7604591 0.4784723 -4.19125e-8 0.8781027 0.4784722 -1.19279e-8 0.09876285 0.995111 0.04938133 0.08553088 0.995111 0.04938133 0.08553088 0.995111 0.4390514 0.7604591 0.4784723 -4.19125e-8 0.8781027 0.4784722 -0.4390515 0.7604591 0.4784722 -0.04938135 0.08553088 0.995111 -1.19279e-8 0.09876285 0.995111 -1.19279e-8 0.09876285 0.995111 -4.19125e-8 0.8781027 0.4784722 -0.4390515 0.7604591 0.4784722 -0.7604593 0.4390512 0.4784723 -0.08553085 0.04938125 0.995111 -0.04938135 0.08553088 0.995111 -0.04938135 0.08553088 0.995111 -0.4390515 0.7604591 0.4784722 -0.7604593 0.4390512 0.4784723 -0.8781026 1.14561e-7 0.4784722 -0.09876245 -1.19279e-8 0.9951111 -0.08553085 0.04938125 0.995111 -0.08553085 0.04938125 0.995111 -0.7604593 0.4390512 0.4784723 -0.8781026 1.14561e-7 0.4784722 -0.7604594 -0.4390511 0.4784722 -0.08553112 -0.04938136 0.995111 -0.09876245 -1.19279e-8 0.9951111 -0.09876245 -1.19279e-8 0.9951111 -0.8781026 1.14561e-7 0.4784722 -0.7604594 -0.4390511 0.4784722 -0.4390517 -0.7604589 0.4784723 -0.04938127 -0.08553074 0.995111 -0.08553112 -0.04938136 0.995111 -0.08553112 -0.04938136 0.995111 -0.7604594 -0.4390511 0.4784722 -0.4390517 -0.7604589 0.4784723 -4.07948e-7 -0.8781026 0.4784723 -6.11303e-8 -0.09876278 0.995111 -0.04938127 -0.08553074 0.995111 -0.04938127 -0.08553074 0.995111 -0.4390517 -0.7604589 0.4784723 -4.07948e-7 -0.8781026 0.4784723 0.439051 -0.7604594 0.4784723 0.04938125 -0.08553097 0.995111 -6.11303e-8 -0.09876278 0.995111 -6.11303e-8 -0.09876278 0.995111 -4.07948e-7 -0.8781026 0.4784723 0.439051 -0.7604594 0.4784723 0.7604589 -0.4390516 0.4784723 0.085531 -0.04938136 0.995111 0.04938125 -0.08553097 0.995111 0.04938125 -0.08553097 0.995111 0.439051 -0.7604594 0.4784723 0.7604589 -0.4390516 0.4784723 0.8781026 -8.55713e-8 0.4784723 0.09876256 -2.98196e-8 0.995111 0.085531 -0.04938136 0.995111 0.085531 -0.04938136 0.995111 0.7604589 -0.4390516 0.4784723 0.8781026 -8.55713e-8 0.4784723 -0.7283275 8.65657e-8 0.6852294 -0.63075 -0.3641636 0.6852295 -5.0053e-7 1.10967e-7 1 -0.63075 -0.3641636 0.6852295 -0.3641638 -0.6307498 0.6852294 -5.0053e-7 1.10967e-7 1 -0.3641638 -0.6307498 0.6852294 3.36644e-8 -0.7283272 0.6852295 -5.0053e-7 1.10967e-7 1 3.36644e-8 -0.7283272 0.6852295 0.3641639 -0.6307499 0.6852294 -5.0053e-7 1.10967e-7 1 0.3641639 -0.6307499 0.6852294 0.6307502 -0.3641636 0.6852294 -5.0053e-7 1.10967e-7 1 0.6307502 -0.3641636 0.6852294 0.7283275 -1.15421e-7 0.6852292 -5.0053e-7 1.10967e-7 1 0.7283275 -1.15421e-7 0.6852292 0.6307502 0.3641634 0.6852292 -5.0053e-7 1.10967e-7 1 0.6307502 0.3641634 0.6852292 0.364164 0.6307499 0.6852294 -5.0053e-7 1.10967e-7 1 0.364164 0.6307499 0.6852294 4.03973e-7 0.7283273 0.6852295 -5.0053e-7 1.10967e-7 1 4.03973e-7 0.7283273 0.6852295 -0.3641634 0.6307502 0.6852295 -5.0053e-7 1.10967e-7 1 -0.3641634 0.6307502 0.6852295 -0.6307498 0.3641639 0.6852294 -5.0053e-7 1.10967e-7 1 -0.6307498 0.3641639 0.6852294 -0.7283275 8.65657e-8 0.6852294 -5.0053e-7 1.10967e-7 1 0.8781026 -8.55713e-8 0.4784723 0.7604589 -0.4390516 0.4784723 0.7612231 -0.4260497 0.4888979 0.7612231 -0.4260497 0.4888979 0.8825297 -9.93156e-4 0.4702555 0.8781026 -8.55713e-8 0.4784723 0.3213185 -5.89113e-4 0.946971 0.259068 -0.1555171 0.9532567 0.4043854 -0.1675019 0.8991193 0.4043854 0.1675019 0.8991192 0.2591634 0.156163 0.9531251 0.3213185 -5.89113e-4 0.946971 0.3213185 -5.89113e-4 0.946971 0.4043854 -0.1675019 0.8991193 0.4043854 0.1675019 0.8991192 0.1675019 -0.4043854 0.8991193 0.1561631 -0.2591637 0.9531249 -5.89176e-4 -0.3213188 0.9469709 -0.321319 5.89105e-4 0.9469708 -0.4043854 0.1675019 0.8991193 -0.4043854 -0.1675019 0.8991193 0.1675019 -0.4043854 0.8991193 0.4043854 -0.1675019 0.8991193 0.259068 -0.1555171 0.9532567 0.259068 -0.1555171 0.9532567 0.1561631 -0.2591637 0.9531249 0.1675019 -0.4043854 0.8991193 -0.1675019 -0.4043854 0.8991193 -5.89176e-4 -0.3213188 0.9469709 -0.1555173 -0.2590682 0.9532565 -0.1555173 -0.2590682 0.9532565 -0.2591636 -0.1561632 0.9531251 -0.4043854 -0.1675019 0.8991193 -0.4043854 -0.1675019 0.8991193 -0.1675019 -0.4043854 0.8991193 -0.1555173 -0.2590682 0.9532565 -0.4043854 -0.1675019 0.8991193 -0.2591636 -0.1561632 0.9531251 -0.321319 5.89105e-4 0.9469708 5.89e-4 0.3213186 0.946971 0.1675019 0.4043854 0.8991193 -0.1675019 0.4043854 0.8991192 -0.4043854 0.1675019 0.8991193 -0.321319 5.89105e-4 0.9469708 -0.2590683 0.1555172 0.9532565 -0.2590683 0.1555172 0.9532565 -0.1561632 0.2591636 0.9531249 -0.1675019 0.4043854 0.8991192 -0.1675019 0.4043854 0.8991192 -0.4043854 0.1675019 0.8991193 -0.2590683 0.1555172 0.9532565 -0.1675019 0.4043854 0.8991192 -0.1561632 0.2591636 0.9531249 5.89e-4 0.3213186 0.946971 0.2591634 0.156163 0.9531251 0.4043854 0.1675019 0.8991192 0.1675019 0.4043854 0.8991193 0.1675019 0.4043854 0.8991193 0.1555172 0.2590683 0.9532565 0.2591634 0.156163 0.9531251 0.1675019 0.4043854 0.8991193 5.89e-4 0.3213186 0.946971 0.1555172 0.2590683 0.9532565 -0.2590683 0.1555172 0.9532565 -0.7612233 0.4260494 0.4888977 -0.4268156 0.7603678 0.4895603 -0.4268156 0.7603678 0.4895603 -0.1561632 0.2591636 0.9531249 -0.2590683 0.1555172 0.9532565 -0.321319 5.89105e-4 0.9469708 -0.88253 9.93171e-4 0.470255 -0.7612233 0.4260494 0.4888977 -0.7612233 0.4260494 0.4888977 -0.2590683 0.1555172 0.9532565 -0.321319 5.89105e-4 0.9469708 -0.2591636 -0.1561632 0.9531251 -0.7603679 -0.4268154 0.4895604 -0.88253 9.93171e-4 0.470255 -0.88253 9.93171e-4 0.470255 -0.321319 5.89105e-4 0.9469708 -0.2591636 -0.1561632 0.9531251 -0.1555173 -0.2590682 0.9532565 -0.4260495 -0.7612232 0.4888977 -0.7603679 -0.4268154 0.4895604 -0.7603679 -0.4268154 0.4895604 -0.2591636 -0.1561632 0.9531251 -0.1555173 -0.2590682 0.9532565 0.8825297 -9.93156e-4 0.4702555 0.3213185 -5.89113e-4 0.946971 0.2591634 0.156163 0.9531251 0.2591634 0.156163 0.9531251 0.7603678 0.4268155 0.4895605 0.8825297 -9.93156e-4 0.4702555 0.7603678 0.4268155 0.4895605 0.2591634 0.156163 0.9531251 0.1555172 0.2590683 0.9532565 0.1555172 0.2590683 0.9532565 0.4260493 0.7612234 0.4888977 0.7603678 0.4268155 0.4895605 0.4260493 0.7612234 0.4888977 0.1555172 0.2590683 0.9532565 5.89e-4 0.3213186 0.946971 5.89e-4 0.3213186 0.946971 9.92869e-4 0.8825298 0.4702554 0.4260493 0.7612234 0.4888977 9.92869e-4 0.8825298 0.4702554 5.89e-4 0.3213186 0.946971 -0.1561632 0.2591636 0.9531249 -0.1561632 0.2591636 0.9531249 -0.4268156 0.7603678 0.4895603 9.92869e-4 0.8825298 0.4702554 -0.4260495 -0.7612232 0.4888977 -0.1555173 -0.2590682 0.9532565 -5.89176e-4 -0.3213188 0.9469709 -5.89176e-4 -0.3213188 0.9469709 -9.93358e-4 -0.8825299 0.4702552 -0.4260495 -0.7612232 0.4888977 -9.93358e-4 -0.8825299 0.4702552 -5.89176e-4 -0.3213188 0.9469709 0.1561631 -0.2591637 0.9531249 0.1561631 -0.2591637 0.9531249 0.4268149 -0.7603682 0.4895602 -9.93358e-4 -0.8825299 0.4702552 0.7612231 -0.4260497 0.4888979 0.259068 -0.1555171 0.9532567 0.3213185 -5.89113e-4 0.946971 0.3213185 -5.89113e-4 0.946971 0.8825297 -9.93156e-4 0.4702555 0.7612231 -0.4260497 0.4888979 0.4268149 -0.7603682 0.4895602 0.1561631 -0.2591637 0.9531249 0.259068 -0.1555171 0.9532567 0.259068 -0.1555171 0.9532567 0.7612231 -0.4260497 0.4888979 0.4268149 -0.7603682 0.4895602 -0.63075 -0.3641636 0.6852295 -0.7283275 8.65657e-8 0.6852294 0.09876256 -2.98196e-8 0.995111 0.09876256 -2.98196e-8 0.995111 0.085531 0.0493813 0.995111 -0.63075 -0.3641636 0.6852295 -0.3641638 -0.6307498 0.6852294 -0.63075 -0.3641636 0.6852295 0.085531 0.0493813 0.995111 0.085531 0.0493813 0.995111 0.04938133 0.08553088 0.995111 -0.3641638 -0.6307498 0.6852294 3.36644e-8 -0.7283272 0.6852295 -0.3641638 -0.6307498 0.6852294 0.04938133 0.08553088 0.995111 0.04938133 0.08553088 0.995111 -1.19279e-8 0.09876285 0.995111 3.36644e-8 -0.7283272 0.6852295 0.3641639 -0.6307499 0.6852294 3.36644e-8 -0.7283272 0.6852295 -1.19279e-8 0.09876285 0.995111 -1.19279e-8 0.09876285 0.995111 -0.04938135 0.08553088 0.995111 0.3641639 -0.6307499 0.6852294 0.6307502 -0.3641636 0.6852294 0.3641639 -0.6307499 0.6852294 -0.04938135 0.08553088 0.995111 -0.04938135 0.08553088 0.995111 -0.08553085 0.04938125 0.995111 0.6307502 -0.3641636 0.6852294 0.7283275 -1.15421e-7 0.6852292 0.6307502 -0.3641636 0.6852294 -0.08553085 0.04938125 0.995111 -0.08553085 0.04938125 0.995111 -0.09876245 -1.19279e-8 0.9951111 0.7283275 -1.15421e-7 0.6852292 0.6307502 0.3641634 0.6852292 0.7283275 -1.15421e-7 0.6852292 -0.09876245 -1.19279e-8 0.9951111 -0.09876245 -1.19279e-8 0.9951111 -0.08553112 -0.04938136 0.995111 0.6307502 0.3641634 0.6852292 0.364164 0.6307499 0.6852294 0.6307502 0.3641634 0.6852292 -0.08553112 -0.04938136 0.995111 -0.08553112 -0.04938136 0.995111 -0.04938127 -0.08553074 0.995111 0.364164 0.6307499 0.6852294 4.03973e-7 0.7283273 0.6852295 0.364164 0.6307499 0.6852294 -0.04938127 -0.08553074 0.995111 -0.04938127 -0.08553074 0.995111 -6.11303e-8 -0.09876278 0.995111 4.03973e-7 0.7283273 0.6852295 -0.3641634 0.6307502 0.6852295 4.03973e-7 0.7283273 0.6852295 -6.11303e-8 -0.09876278 0.995111 -6.11303e-8 -0.09876278 0.995111 0.04938125 -0.08553097 0.995111 -0.3641634 0.6307502 0.6852295 -0.6307498 0.3641639 0.6852294 -0.3641634 0.6307502 0.6852295 0.04938125 -0.08553097 0.995111 0.04938125 -0.08553097 0.995111 0.085531 -0.04938136 0.995111 -0.6307498 0.3641639 0.6852294 -0.7283275 8.65657e-8 0.6852294 -0.6307498 0.3641639 0.6852294 0.085531 -0.04938136 0.995111 0.085531 -0.04938136 0.995111 0.09876256 -2.98196e-8 0.995111 -0.7283275 8.65657e-8 0.6852294 + + + + + + + + + + 0.1437581 0.00176994 0 0.001868038 0.1436598 0 0.001868038 0.7378242 0 0.1437581 0.879714 0 0.7379224 0.879714 0 0.8798124 0.7378242 0 0.8798124 0.1436598 0 0.7379224 0.00176994 0 0.2315648 0.8947714 0 0.8777048 0.8947714 0 0.8777048 0.9911309 0 0.2315648 0.9911309 0 0.6607696 0.8947714 0 0.01462963 0.8947714 0 0.01462963 0.9911309 0 0.6607696 0.9911309 0 0.2315648 0.8947714 0 0.01462963 0.8947714 0 0.01462963 0.9911309 0 0.2315648 0.9911309 0 0.2315648 0.8947714 0 0.8777048 0.8947714 0 0.8777048 0.9911309 0 0.2315648 0.9911309 0 0.1511046 0.0195062 0 0.1437581 0.00176994 0 0.7379224 0.00176994 0 0.7305759 0.0195062 0 0.862076 0.1510065 0 0.8798124 0.1436598 0 0.8798124 0.7378242 0 0.862076 0.7304776 0 0.8777048 0.8947714 0 0.8777048 0.9911309 0 0.01462966 0.8947714 0 0.01462966 0.9911309 0 0.8777048 0.8947714 0 0.8777048 0.9911309 0 0.6607696 0.8947714 0 0.6607696 0.9911309 0 0.7305759 0.8619778 0 0.7379224 0.879714 0 0.1437581 0.879714 0 0.1511046 0.8619778 0 0.01960441 0.7304776 0 0.001868038 0.7378242 0 0.001868038 0.1436598 0 0.01960441 0.1510065 0 0.4408401 0.101545 0 0.7800373 0.440742 0 0.73398 0.2654341 0 0.7339801 0.6160498 0 0.6161479 0.1476021 0 0.1016432 0.4407421 0 0.2655323 0.1476022 0 0.1477004 0.2654344 0 0.9909106 0.02534963 0 0.95882 0.9952412 0 0.95882 0.9952412 0 0.4408402 0.7799391 0 0.9909106 0.02534963 0 0.1477004 0.6160498 0 0.2655324 0.7338818 0 0.616148 0.733882 0 0.9909106 0.02534963 0 0.95882 0.9952412 0 0.9909106 0.02534963 0 0.95882 0.9952412 0 0.9909106 0.02534963 0 0.95882 0.9952412 0 0.9909106 0.02534963 0 0.95882 0.9952412 0 0.9909106 0.02534963 0 0.95882 0.9952412 0 0.9909106 0.02534963 0 0.95882 0.9952412 0 0.9909106 0.02534963 0 0.95882 0.9952412 0 0.9909106 0.02534963 0 0.95882 0.9952412 0 0.9008009 0.02534953 0 0.9245095 0.8332815 0 0.9168261 0.8619881 0 0.9063684 0.8559547 0 0.9124359 0.8332815 0 0.8958218 0.8830132 0 0.8897823 0.87256 0 0.8671146 0.8907121 0 0.8671146 0.8786399 0 0.8384076 0.8830132 0 0.844447 0.8725598 0 0.8174033 0.8619881 0 0.827861 0.8559547 0 0.8097203 0.8332815 0 0.9328915 0.995241 0 0.9909106 0.02534963 0 0.95882 0.9952412 0 0.9948128 0.004677464 0 0.9948128 0.004677464 0 0.9948128 0.004677464 0 0.9948128 0.004677464 0 0.9948128 0.004677464 0 0.9948128 0.004677464 0 0.9948128 0.004677464 0 0.9948128 0.004677464 0 0.9948128 0.004677464 0 0.9948128 0.004677464 0 0.8217939 0.8332815 0 0.8174038 0.8045748 0 0.8278614 0.8106082 0 0.8384079 0.7835498 0 0.8968989 0.00467754 0 0.8444473 0.7940032 0 0.8671147 0.7758506 0 0.8671148 0.7879229 0 0.9948128 0.004677464 0 0.9008009 0.02534953 0 0.9328915 0.995241 0 0.8968989 0.00467754 0 0.9328915 0.995241 0 0.9008009 0.02534953 0 0.8968989 0.00467754 0 0.9008009 0.02534953 0 0.9328915 0.995241 0 0.8968989 0.00467754 0 0.9008009 0.02534953 0 0.9328915 0.995241 0 0.8968989 0.00467754 0 0.9008009 0.02534953 0 0.9328915 0.995241 0 0.8968989 0.00467754 0 0.9008009 0.02534953 0 0.9328915 0.995241 0 0.8968989 0.00467754 0 0.9008009 0.02534953 0 0.9328915 0.995241 0 0.8968989 0.00467754 0 0.9008009 0.02534953 0 0.9328915 0.995241 0 0.8958219 0.7835494 0 0.8897825 0.7940028 0 0.9168262 0.8045747 0 0.9063686 0.810608 0 0.9003624 0.8332815 0 0.8959104 0.8499218 0 0.07186812 0.8145298 0 0.8837424 0.8621067 0 0.8671146 0.8665676 0 0.8504869 0.8621064 0 0.8383189 0.8499219 0 0.8338675 0.8332815 0 0.8383192 0.816641 0 0.8504872 0.8044562 0 0.8671148 0.7999952 0 0.8837426 0.804456 0 0.8959106 0.8166408 0 0.8968989 0.00467754 0 0.9008009 0.02534953 0 0.9328915 0.995241 0 0.8968989 0.00467754 0 0.9008009 0.02534953 0 0.9328915 0.995241 0 0.8968989 0.00467754 0 0.9008009 0.02534953 0 0.9909106 0.02534963 0 0.95882 0.9952412 0 0.9948128 0.004677464 0 0.9328915 0.995241 0 0.8968989 0.00467754 0 0.10907 0.8724196 0 0.09262928 0.8801363 0 0.07474211 0.8832843 0 0.05665355 0.8816417 0 0.03962392 0.8753226 0 0.02484011 0.864767 0 0.01333255 0.8507085 0 0.005904772 0.8341299 0 0.003073875 0.816187 0 0.00503601 0.7981309 0 0.0116534 0.7812185 0 0.02246423 0.7666267 0 0.1229187 0.8606709 0 0.6607696 0.8947714 0 0.6607696 0.9911309 0 0.01462966 0.8947714 0 0.01462966 0.9911309 0 + + + + + + + + + + + + + + + +

8 0 1 2 1 2 10 2 3 10 3 3 11 4 4 3 5 5 8 6 1 10 7 3 3 8 5 3 9 5 9 10 6 1 11 7 8 12 1 3 13 5 1 14 7 0 15 0 8 16 1 1 17 7 0 18 8 1 19 36 13 20 37 13 21 37 4 22 11 0 23 8 9 24 12 3 25 184 15 26 185 15 27 185 5 28 15 9 29 12 11 30 16 10 31 32 22 32 33 22 33 33 7 34 19 11 35 16 2 36 182 8 37 34 20 38 35 20 39 35 6 40 183 2 41 182 1 42 9 9 43 12 5 44 15 5 45 15 13 46 10 1 47 9 4 48 39 20 49 22 8 50 21 8 51 21 0 52 38 4 53 39 3 54 13 11 55 16 7 56 19 7 57 19 15 58 14 3 59 13 10 60 17 2 61 20 6 62 23 6 63 23 22 64 18 10 65 17 16 66 24 4 67 25 13 68 26 13 69 26 21 70 27 16 71 24 17 72 28 5 73 29 15 74 30 15 75 30 23 76 31 17 77 28 19 78 40 7 79 41 22 80 42 22 81 42 14 82 43 19 83 40 18 84 44 6 85 45 20 86 46 20 87 46 12 88 47 18 89 44 4 90 25 16 91 24 12 92 47 12 93 47 20 94 46 4 95 25 5 96 29 17 97 28 21 98 27 21 99 27 13 100 26 5 101 29 6 102 45 18 103 44 14 104 43 14 105 43 22 106 42 6 107 45 7 108 41 19 109 40 23 110 31 23 111 31 15 112 30 7 113 41 56 114 48 16 115 24 21 116 27 28 117 57 27 118 119 64 119 120 64 120 120 65 121 56 28 122 57 29 123 65 28 124 123 65 125 122 65 126 122 66 127 64 29 128 65 30 129 67 29 130 126 66 131 125 66 132 125 67 133 66 30 134 67 31 135 69 30 136 129 67 137 128 67 138 128 59 139 68 31 140 69 32 141 71 31 142 132 59 143 131 59 144 131 60 145 70 32 146 71 33 147 73 32 148 135 60 149 134 60 150 134 61 151 72 33 152 73 34 153 75 33 154 138 61 155 137 61 156 137 63 157 74 34 158 75 35 159 77 34 160 158 63 161 157 63 162 157 69 163 76 35 164 77 36 165 79 35 166 161 69 167 160 69 168 160 70 169 78 36 170 79 37 171 165 36 172 167 70 173 163 70 174 163 71 175 164 37 176 165 38 177 96 37 178 94 71 179 80 71 180 80 72 181 95 38 182 96 28 183 82 74 184 83 73 185 84 73 186 84 27 187 81 28 188 82 29 189 85 75 190 86 74 191 83 74 192 83 28 193 82 29 194 85 30 195 87 76 196 88 75 197 86 75 198 86 29 199 85 30 200 87 31 201 89 77 202 90 76 203 88 76 204 88 30 205 87 31 206 89 32 207 91 78 208 92 77 209 90 77 210 90 31 211 89 32 212 91 33 213 93 79 214 107 78 215 92 78 216 92 32 217 91 33 218 93 34 219 108 80 220 109 79 221 107 79 222 107 33 223 93 34 224 108 35 225 110 81 226 112 80 227 109 80 228 109 34 229 108 35 230 110 36 231 113 82 232 114 81 233 112 81 234 112 35 235 110 36 236 113 37 237 139 83 238 140 82 239 114 82 240 114 36 241 113 37 242 139 38 243 141 84 244 142 83 245 140 83 246 140 37 247 139 38 248 141 27 249 81 73 250 84 84 251 142 84 252 142 38 253 141 27 254 81 39 255 169 40 256 170 51 257 145 40 258 170 41 259 171 51 260 145 41 261 171 42 262 172 51 263 145 42 264 172 43 265 173 51 266 145 43 267 173 44 268 174 51 269 145 44 270 174 45 271 175 51 272 145 45 273 175 46 274 176 51 275 145 46 276 176 47 277 177 51 278 145 47 279 177 48 280 178 51 281 145 48 282 178 49 283 179 51 284 145 49 285 179 50 286 180 51 287 145 50 288 181 39 289 169 51 290 145 27 291 58 38 292 117 72 293 116 72 294 116 64 295 60 27 296 58 52 297 49 58 298 50 17 299 28 23 300 31 53 301 51 52 302 49 52 303 49 17 304 28 23 305 31 21 306 27 57 307 52 56 308 48 62 309 53 18 310 44 12 311 47 21 312 27 17 313 28 58 314 50 58 315 50 57 316 52 21 317 27 16 318 24 56 319 48 55 320 54 55 321 54 26 322 55 12 323 47 12 324 47 16 325 24 55 326 54 12 327 47 26 328 55 62 329 53 68 330 59 19 331 40 14 332 43 18 333 44 62 334 53 25 335 61 25 336 61 24 337 62 14 338 43 14 339 43 18 340 44 25 341 61 14 342 43 24 343 62 68 344 59 53 345 51 23 346 31 19 347 40 19 348 40 54 349 63 53 350 51 19 351 40 68 352 59 54 353 63 25 354 97 60 355 70 59 356 131 59 357 131 24 358 133 25 359 97 62 360 99 61 361 72 60 362 134 60 363 134 25 364 136 62 365 99 26 366 100 63 367 74 61 368 137 61 369 137 62 370 156 26 371 100 55 372 101 69 373 76 63 374 157 63 375 157 26 376 159 55 377 101 64 378 120 52 379 121 53 380 103 53 381 103 65 382 56 64 383 120 65 384 122 53 385 124 54 386 104 54 387 104 66 388 64 65 389 122 66 390 125 54 391 127 68 392 105 68 393 105 67 394 66 66 395 125 67 396 128 68 397 130 24 398 98 24 399 98 59 400 68 67 401 128 69 402 160 55 403 162 56 404 106 56 405 106 70 406 78 69 407 160 70 408 163 56 409 168 57 410 166 57 411 166 71 412 164 70 413 163 72 414 116 58 415 118 52 416 102 52 417 102 64 418 60 72 419 116 71 420 80 57 421 111 58 422 115 58 423 115 72 424 95 71 425 80 40 426 144 39 427 143 73 428 84 73 429 84 74 430 83 40 431 144 41 432 146 40 433 144 74 434 83 74 435 83 75 436 86 41 437 146 42 438 147 41 439 146 75 440 86 75 441 86 76 442 88 42 443 147 43 444 148 42 445 147 76 446 88 76 447 88 77 448 90 43 449 148 44 450 149 43 451 148 77 452 90 77 453 90 78 454 92 44 455 149 45 456 150 44 457 149 78 458 92 78 459 92 79 460 107 45 461 150 46 462 151 45 463 150 79 464 107 79 465 107 80 466 109 46 467 151 47 468 152 46 469 151 80 470 109 80 471 109 81 472 112 47 473 152 48 474 153 47 475 152 81 476 112 81 477 112 82 478 114 48 479 153 49 480 154 48 481 153 82 482 114 82 483 114 83 484 140 49 485 154 50 486 155 49 487 154 83 488 140 83 489 140 84 490 142 50 491 155 39 492 143 50 493 155 84 494 142 84 495 142 73 496 84 39 497 143

+
+
+
+
+ + + + + 0 0 0 + + + + + + + ../materials/textures/Construction_Cone_Diffuse.png + + + + + + + + + + + + + + + + + + + + + + + +
diff --git a/simulators/sim_env/models/construction_cone/model-1_3.sdf b/simulators/sim_env/models/construction_cone/model-1_3.sdf new file mode 100755 index 0000000..63f095a --- /dev/null +++ b/simulators/sim_env/models/construction_cone/model-1_3.sdf @@ -0,0 +1,24 @@ + + + + true + + + + + 10 10 10 + model://construction_cone/meshes/construction_cone.dae + + + + + + + 10 10 10 + model://construction_cone/meshes/construction_cone.dae + + + + + + diff --git a/simulators/sim_env/models/construction_cone/model-1_4.sdf b/simulators/sim_env/models/construction_cone/model-1_4.sdf new file mode 100755 index 0000000..0f5b99e --- /dev/null +++ b/simulators/sim_env/models/construction_cone/model-1_4.sdf @@ -0,0 +1,23 @@ + + + + + + + + 10 10 10 + model://construction_cone/meshes/construction_cone.dae + + + + + + + 10 10 10 + model://construction_cone/meshes/construction_cone.dae + + + + + + diff --git a/simulators/sim_env/models/construction_cone/model.config b/simulators/sim_env/models/construction_cone/model.config new file mode 100755 index 0000000..76bea74 --- /dev/null +++ b/simulators/sim_env/models/construction_cone/model.config @@ -0,0 +1,24 @@ + + + + Construction Cone + 1.0 + model-1_3.sdf + model-1_4.sdf + model.sdf + + + Cole Biesemeyer + cole.bsmr@gmail.com + + + + Nate Koenig + nate@osrfoundation.com + + + + An orange construction cone + + + diff --git a/simulators/sim_env/models/construction_cone/model.sdf b/simulators/sim_env/models/construction_cone/model.sdf new file mode 100755 index 0000000..36558ca --- /dev/null +++ b/simulators/sim_env/models/construction_cone/model.sdf @@ -0,0 +1,23 @@ + + + + + + + + 10 10 10 + model://construction_cone/meshes/construction_cone.dae + + + + + + + 10 10 10 + model://construction_cone/meshes/construction_cone.dae + + + + + + diff --git a/simulators/sim_env/models/construction_cone/thumbnails/1.png b/simulators/sim_env/models/construction_cone/thumbnails/1.png new file mode 100755 index 0000000..4d8852e Binary files /dev/null and b/simulators/sim_env/models/construction_cone/thumbnails/1.png differ diff --git a/simulators/sim_env/models/construction_cone/thumbnails/2.png b/simulators/sim_env/models/construction_cone/thumbnails/2.png new file mode 100755 index 0000000..9b8e34f Binary files /dev/null and b/simulators/sim_env/models/construction_cone/thumbnails/2.png differ diff --git a/simulators/sim_env/models/construction_cone/thumbnails/3.png b/simulators/sim_env/models/construction_cone/thumbnails/3.png new file mode 100755 index 0000000..e9c6700 Binary files /dev/null and b/simulators/sim_env/models/construction_cone/thumbnails/3.png differ diff --git a/simulators/sim_env/models/construction_cone/thumbnails/4.png b/simulators/sim_env/models/construction_cone/thumbnails/4.png new file mode 100755 index 0000000..ea8d3f6 Binary files /dev/null and b/simulators/sim_env/models/construction_cone/thumbnails/4.png differ diff --git a/simulators/sim_env/models/construction_cone/thumbnails/5.png b/simulators/sim_env/models/construction_cone/thumbnails/5.png new file mode 100755 index 0000000..6f0013a Binary files /dev/null and b/simulators/sim_env/models/construction_cone/thumbnails/5.png differ diff --git a/simulators/sim_env/models/dumpster/materials/scripts/dumpster.material b/simulators/sim_env/models/dumpster/materials/scripts/dumpster.material new file mode 100755 index 0000000..346419e --- /dev/null +++ b/simulators/sim_env/models/dumpster/materials/scripts/dumpster.material @@ -0,0 +1,29 @@ +material Dumpster/Diffuse +{ + receive_shadows off + technique + { + pass + { + texture_unit + { + texture Dumpster_Diffuse.png + } + } + } +} + +material Dumpster/Specular +{ + receive_shadows off + technique + { + pass + { + texture_unit + { + texture Dumpster_Spec.png + } + } + } +} diff --git a/simulators/sim_env/models/dumpster/materials/textures/Dumpster_Diffuse.png b/simulators/sim_env/models/dumpster/materials/textures/Dumpster_Diffuse.png new file mode 100755 index 0000000..9a0d075 Binary files /dev/null and b/simulators/sim_env/models/dumpster/materials/textures/Dumpster_Diffuse.png differ diff --git a/simulators/sim_env/models/dumpster/materials/textures/Dumpster_Spec.png b/simulators/sim_env/models/dumpster/materials/textures/Dumpster_Spec.png new file mode 100755 index 0000000..5f1db77 Binary files /dev/null and b/simulators/sim_env/models/dumpster/materials/textures/Dumpster_Spec.png differ diff --git a/simulators/sim_env/models/dumpster/meshes/dumpster.dae b/simulators/sim_env/models/dumpster/meshes/dumpster.dae new file mode 100755 index 0000000..558ffbe --- /dev/null +++ b/simulators/sim_env/models/dumpster/meshes/dumpster.dae @@ -0,0 +1,151 @@ + + + + + Cole + OpenCOLLADA for 3ds Max; Version: 1.3.1; Revision: 847M; Platform: x64; Configuration: Release_Max2012_static + file:///C:/Users/Cole/Desktop/Houses.max + + 2012-12-21T07:25:58 + 2012-12-21T07:25:58 + + Z_UP + + + + + + + + 0 0 0 1 + + + 1 1 1 1 + + + 1 1 1 1 + + + 0.9 0.9 0.9 1 + + + 9.999999 + + + 0 0 0 1 + + + 1 1 1 1 + + + 1 + + + + + + + + 0 + 0 + 0 + 1.5 + 0 + 3 + 1 + 0 + + + 1 + 1 + 0 + 0.1 + 0 + + + + + + + + + + + + + + + -117.064 -66.54276 80.57549 117.064 -66.54274 80.57549 117.0641 66.54275 92.16394 -117.0641 66.54276 92.16394 -123.4201 -66.54275 71.68295 123.4201 -66.54274 71.68295 123.4201 66.54275 83.27138 -123.4201 66.54275 83.27138 -4.36579e-9 -66.54274 80.57549 -4.36579e-9 66.54276 92.16394 -107.9518 -56.97194 81.40887 -9.112272 -56.97193 81.40887 -9.112273 56.97194 91.33056 -107.9518 56.97193 91.33056 9.112275 -56.97193 81.40887 107.9518 -56.97193 81.40887 107.9518 56.97193 91.33056 9.112274 56.97194 91.33056 -104.1622 -52.50466 85.51634 -12.90184 -52.50464 85.51634 -12.90184 50.17763 94.45743 -104.1622 50.17762 94.45743 12.90183 -52.50464 85.51634 104.1622 -52.50464 85.51634 104.1622 50.17763 94.45743 12.90184 50.17763 94.45743 -117.064 -66.54276 76.12923 117.064 -66.54274 76.12923 -123.4201 -66.54276 76.12923 123.4201 -66.54274 76.12923 123.4201 66.54274 87.71766 -123.4201 66.54276 87.71766 117.0641 66.54274 87.71765 -117.0641 66.54276 87.71765 -119.0646 -62.32199 5.261956 119.0646 -62.32199 5.261956 -119.0646 62.32199 5.261956 119.0646 62.32199 5.261956 -119.0646 -62.32199 72.39811 119.0646 -62.32198 72.39811 -119.0646 62.32199 83.2515 119.0646 62.32199 83.2515 -133.0051 -60.6758 40.45187 -133.0051 60.67581 40.45186 -133.0051 -60.6758 59.54535 -133.0051 60.67581 59.54534 -117.7992 60.67581 40.45186 -117.7991 -60.6758 40.45187 -117.7991 -60.6758 59.54535 -117.7992 60.67581 59.54534 -117.7991 -55.50943 59.32564 -133.0051 -55.50943 59.32564 -117.7991 -55.50942 70.82291 -117.7991 -0.9310553 59.32563 -133.0051 -0.9310552 59.32563 -117.7992 -0.9310533 70.82291 -117.7992 51.06681 59.32563 -133.0051 51.06681 59.32563 -117.7992 51.06682 70.82291 -117.7991 -55.50942 40.5337 -133.0051 -55.50942 40.5337 -117.7991 -55.50941 28.46272 -117.7991 -0.9310608 40.5337 -133.005 -0.9310608 40.5337 -117.7992 -0.931047 28.46272 -117.7992 51.06681 40.5337 -133.005 51.06681 40.5337 -117.7992 51.06683 28.46272 -117.7991 -60.67579 40.95409 -132.1043 -60.67579 40.95409 -132.1043 -60.67579 59.05108 -117.7991 -60.67579 59.05108 -117.7991 60.6758 59.05107 -132.1043 60.67579 59.05107 -132.1043 60.67579 40.95408 -117.7991 60.6758 40.95408 133.0051 -60.6758 40.45186 133.0051 60.6758 40.45186 133.0051 -60.6758 59.54534 133.0051 60.6758 59.54534 117.7992 60.6758 40.45186 117.7991 -60.6758 40.45186 117.7991 -60.6758 59.54534 117.7992 60.6758 59.54534 117.7991 -55.50943 59.32563 133.0051 -55.50943 59.32563 117.7991 -55.50943 70.82291 117.7991 -0.931063 59.32563 133.0051 -0.9310629 59.32563 117.7992 -0.9310625 70.82291 117.7992 51.06681 59.32563 133.0051 51.06681 59.32563 117.7992 51.06681 70.82291 117.7991 -55.50943 40.53369 133.0051 -55.50943 40.53369 117.7991 -55.50941 28.46271 117.7991 -0.931066 40.53369 133.005 -0.931066 40.53369 117.7992 -0.9310507 28.46272 117.7992 51.06681 40.5337 133.005 51.06681 40.5337 117.7992 51.06683 28.46272 117.7991 -60.6758 40.95408 132.1043 -60.6758 40.95408 132.1043 -60.6758 59.05107 117.7991 -60.6758 59.05107 117.7991 60.67579 59.05107 132.1043 60.67578 59.05107 132.1043 60.67578 40.95409 117.7991 60.67579 40.95409 113.3478 58.32795 -3.411682 103.901 58.32795 -3.411682 103.7664 58.24448 3.488155 111.4482 57.70047 5.261964 105.7996 47.78352 5.261964 113.4813 49.13156 3.693572 103.7664 60.55251 -4.037542 113.4813 59.77285 -4.680214 103.7664 57.30566 -4.680214 113.4813 55.84048 -4.111968 103.7664 59.77285 -4.680214 113.4813 60.55251 -4.037542 103.7664 55.84048 -4.111968 113.4813 57.30566 -4.680214 105.7995 57.70047 5.261964 113.4813 58.24448 3.488154 103.7664 49.13156 3.693573 111.4482 47.78352 5.261964 111.1219 51.37268 -0.7140532 106.1269 51.37268 -0.7140532 106.1269 50.2967 -3.411682 111.1219 50.2967 -3.411682 111.1219 54.31232 1.260748 106.1269 54.31233 1.260748 111.1219 58.32795 1.983576 106.127 58.32795 1.983576 111.1219 62.34357 1.260748 106.127 62.34357 1.260748 111.1219 65.28322 -0.7140529 106.127 65.28322 -0.7140529 111.1219 66.35918 -3.411681 106.127 66.35919 -3.411681 111.1219 65.28322 -6.10931 106.127 65.28322 -6.10931 111.1219 62.34357 -8.084112 106.127 62.34357 -8.084112 111.1219 58.32795 -8.80694 106.127 58.32795 -8.80694 111.1219 54.31233 -8.084114 106.127 54.31233 -8.084114 111.1219 51.37269 -6.109314 106.1269 51.37269 -6.109314 113.3478 -47.29527 -3.41169 103.901 -47.29527 -3.41169 103.7664 -47.37874 3.488148 111.4482 -47.92274 5.261956 105.7995 -57.8397 5.261957 113.4813 -56.49165 3.693564 103.7664 -45.07071 -4.037549 113.4813 -45.85036 -4.680222 103.7664 -48.31756 -4.680222 113.4813 -49.78273 -4.111976 103.7664 -45.85036 -4.680222 113.4813 -45.07071 -4.037549 103.7664 -49.78273 -4.111976 113.4813 -48.31756 -4.680222 105.7995 -47.92274 5.261957 113.4813 -47.37874 3.488147 103.7664 -56.49165 3.693565 111.4482 -57.8397 5.261956 111.1219 -54.25053 -0.7140608 106.1269 -54.25053 -0.7140608 106.1269 -55.32651 -3.41169 111.1219 -55.32651 -3.41169 111.1219 -51.31089 1.260741 106.1269 -51.31089 1.260741 111.1219 -47.29527 1.983568 106.1269 -47.29527 1.983568 111.1219 -43.27965 1.260741 106.1269 -43.27965 1.260741 111.1219 -40.34 -0.7140605 106.1269 -40.34 -0.7140605 111.1219 -39.26403 -3.411689 106.1269 -39.26402 -3.411689 111.1219 -40.34 -6.109318 106.1269 -40.34 -6.109318 111.1219 -43.27965 -8.08412 106.1269 -43.27965 -8.08412 111.1219 -47.29527 -8.806948 106.1269 -47.29527 -8.806948 111.1219 -51.31089 -8.084122 106.1269 -51.31089 -8.084122 111.1219 -54.25053 -6.109322 106.1269 -54.25053 -6.109322 -113.3478 58.32795 -3.411682 -103.901 58.32795 -3.411682 -103.7664 58.24448 3.488155 -111.4482 57.70047 5.261964 -105.7996 47.78352 5.261964 -113.4813 49.13156 3.693572 -103.7664 60.55251 -4.037542 -113.4813 59.77285 -4.680214 -103.7664 57.30566 -4.680214 -113.4813 55.84048 -4.111968 -103.7664 59.77285 -4.680214 -113.4813 60.55251 -4.037542 -103.7664 55.84048 -4.111968 -113.4813 57.30566 -4.680214 -105.7995 57.70047 5.261964 -113.4813 58.24448 3.488154 -103.7664 49.13156 3.693573 -111.4482 47.78352 5.261964 -111.1219 51.37268 -0.7140532 -106.1269 51.37268 -0.7140532 -106.1269 50.2967 -3.411682 -111.1219 50.2967 -3.411682 -111.1219 54.31232 1.260748 -106.1269 54.31233 1.260748 -111.1219 58.32795 1.983576 -106.127 58.32795 1.983576 -111.1219 62.34357 1.260748 -106.127 62.34357 1.260748 -111.1219 65.28322 -0.7140529 -106.127 65.28322 -0.7140529 -111.1219 66.35918 -3.411681 -106.127 66.35919 -3.411681 -111.1219 65.28322 -6.10931 -106.127 65.28322 -6.10931 -111.1219 62.34357 -8.084112 -106.127 62.34357 -8.084112 -111.1219 58.32795 -8.80694 -106.127 58.32795 -8.80694 -111.1219 54.31233 -8.084114 -106.127 54.31233 -8.084114 -111.1219 51.37269 -6.109314 -106.1269 51.37269 -6.109314 -113.3478 -47.29527 -3.41169 -103.901 -47.29527 -3.41169 -103.7664 -47.37874 3.488148 -111.4482 -47.92274 5.261956 -105.7995 -57.8397 5.261957 -113.4813 -56.49165 3.693564 -103.7664 -45.07071 -4.037549 -113.4813 -45.85036 -4.680222 -103.7664 -48.31756 -4.680222 -113.4813 -49.78273 -4.111976 -103.7664 -45.85036 -4.680222 -113.4813 -45.07071 -4.037549 -103.7664 -49.78273 -4.111976 -113.4813 -48.31756 -4.680222 -105.7995 -47.92274 5.261957 -113.4813 -47.37874 3.488147 -103.7664 -56.49165 3.693565 -111.4482 -57.8397 5.261956 -111.1219 -54.25053 -0.7140608 -106.1269 -54.25053 -0.7140608 -106.1269 -55.32651 -3.41169 -111.1219 -55.32651 -3.41169 -111.1219 -51.31089 1.260741 -106.1269 -51.31089 1.260741 -111.1219 -47.29527 1.983568 -106.1269 -47.29527 1.983568 -111.1219 -43.27965 1.260741 -106.1269 -43.27965 1.260741 -111.1219 -40.34 -0.7140605 -106.1269 -40.34 -0.7140605 -111.1219 -39.26403 -3.411689 -106.1269 -39.26402 -3.411689 -111.1219 -40.34 -6.109318 -106.1269 -40.34 -6.109318 -111.1219 -43.27965 -8.08412 -106.1269 -43.27965 -8.08412 -111.1219 -47.29527 -8.806948 -106.1269 -47.29527 -8.806948 -111.1219 -51.31089 -8.084122 -106.1269 -51.31089 -8.084122 -111.1219 -54.25053 -6.109322 -106.1269 -54.25053 -6.109322 + + + + + + + + + + 1.81302e-8 -0.08674703 0.9962304 1.81302e-8 -0.08674704 0.9962304 1.81302e-8 -0.08674703 0.9962304 7.25207e-9 -0.08674701 0.9962304 7.25208e-9 -0.08674702 0.9962304 7.25208e-9 -0.08674701 0.9962304 0 -1 -1.7159e-6 0 -1 -1.7159e-6 0 -1 -1.7159e-6 1 -1.14654e-7 -1.96735e-13 1 -1.14654e-7 -1.96735e-13 1 -1.14654e-7 -1.96735e-13 1 -2.0674e-7 1.7159e-6 1 -2.0674e-7 1.7159e-6 1 -2.0674e-7 1.7159e-6 -2.05967e-12 1 1.7159e-6 -2.05967e-12 1 1.7159e-6 -2.05967e-12 1 1.7159e-6 -1 -2.0674e-7 1.7159e-6 -1 -2.0674e-7 1.7159e-6 -1 -2.0674e-7 1.7159e-6 -1 -1.14654e-7 1.96735e-13 -1 -1.14654e-7 1.96735e-13 -1 -1.14654e-7 1.96735e-13 0 0.08674686 -0.9962304 0 0.08674686 -0.9962304 0 0.08674686 -0.9962303 -2.68119e-9 0.08674686 -0.9962304 -2.68119e-9 0.08674686 -0.9962304 -2.68119e-9 0.08674686 -0.9962304 0 -0.08674702 0.9962304 0 -0.08674702 0.9962304 0 -0.08674702 0.9962304 0 -0.08674703 0.9962304 0 -0.08674703 0.9962304 0 -0.08674703 0.9962304 1.13071e-8 -0.08674711 0.9962304 1.13071e-8 -0.08674711 0.9962304 1.13071e-8 -0.08674712 0.9962304 6.69598e-9 -0.08674706 0.9962304 6.69598e-9 -0.08674706 0.9962304 6.69598e-9 -0.08674704 0.9962303 -5.64072e-8 -0.08674697 0.9962304 -5.64073e-8 -0.08674698 0.9962304 -5.64073e-8 -0.08674698 0.9962304 1.75689e-7 -0.08674695 0.9962304 1.75689e-7 -0.08674695 0.9962303 1.75689e-7 -0.08674696 0.9962304 0 -0.08674698 0.9962304 0 -0.08674699 0.9962304 0 -0.08674698 0.9962303 3.34799e-9 -0.08674703 0.9962304 3.34799e-9 -0.08674703 0.9962304 3.34799e-9 -0.08674704 0.9962304 -1.06547e-7 -0.08674696 0.9962304 -1.06547e-7 -0.08674696 0.9962303 -1.06547e-7 -0.08674696 0.9962303 4.39221e-8 -0.08674695 0.9962304 4.39221e-8 -0.08674695 0.9962303 4.39221e-8 -0.08674695 0.9962303 0 -0.08674712 0.9962304 0 -0.08674712 0.9962304 0 -0.08674712 0.9962303 0 -0.08674712 0.9962304 0 -0.08674712 0.9962304 0 -0.08674712 0.9962304 -8.14771e-8 -0.08674698 0.9962304 -8.14771e-8 -0.08674699 0.9962304 -8.14771e-8 -0.08674699 0.9962304 1.75688e-7 -0.08674695 0.9962304 1.75689e-7 -0.08674696 0.9962304 1.75689e-7 -0.08674696 0.9962304 -5.65355e-9 -0.08674702 0.9962304 -5.65355e-9 -0.08674702 0.9962304 -5.65355e-9 -0.08674703 0.9962304 -3.34799e-9 -0.08674705 0.9962304 -3.34799e-9 -0.08674705 0.9962304 -3.34799e-9 -0.08674704 0.9962303 -1.62954e-7 -0.08674697 0.9962304 -1.62954e-7 -0.08674698 0.9962304 -1.62954e-7 -0.08674698 0.9962304 6.58832e-8 -0.08674695 0.9962304 6.58832e-8 -0.08674695 0.9962303 6.58832e-8 -0.08674696 0.9962304 5.2245e-8 -0.6768386 0.7361315 5.2245e-8 -0.6768386 0.7361315 5.2245e-8 -0.6768386 0.7361315 1.4146e-7 -0.6768396 0.7361307 1.4146e-7 -0.6768395 0.7361305 1.4146e-7 -0.6768396 0.7361305 0.6990312 -0.06203205 0.7123956 0.6990312 -0.06203205 0.7123955 0.6990312 -0.06203205 0.7123955 0.6990324 -0.06203187 0.7123944 0.6990324 -0.06203188 0.7123944 0.6990324 -0.06203188 0.7123944 -1.61353e-8 0.4180698 0.908415 -1.61353e-8 0.4180698 0.9084149 -1.61353e-8 0.4180698 0.9084148 -3.49508e-8 0.41807 0.9084148 -3.49508e-8 0.41807 0.9084148 -3.49508e-8 0.41807 0.9084148 -0.6990329 -0.06203192 0.7123939 -0.699033 -0.06203193 0.7123939 -0.6990329 -0.06203192 0.7123939 -0.6990336 -0.06203181 0.7123931 -0.6990337 -0.06203182 0.7123932 -0.6990336 -0.06203182 0.7123931 0 -0.6768386 0.7361314 0 -0.6768386 0.7361314 0 -0.6768386 0.7361314 0 -0.6768386 0.7361314 0 -0.6768386 0.7361315 0 -0.6768386 0.7361314 0.6990328 -0.062032 0.7123939 0.6990328 -0.062032 0.7123939 0.6990328 -0.062032 0.7123939 0.6990343 -0.06203176 0.7123926 0.6990343 -0.06203177 0.7123925 0.6990343 -0.06203176 0.7123925 1.61353e-8 0.4180698 0.9084149 1.61353e-8 0.4180698 0.9084149 1.61353e-8 0.4180698 0.9084148 0 0.4180699 0.9084148 0 0.4180699 0.9084148 0 0.4180699 0.9084148 -0.6990326 -0.06203187 0.7123942 -0.6990326 -0.06203187 0.7123942 -0.6990326 -0.06203187 0.7123941 -0.6990325 -0.06203188 0.7123942 -0.6990325 -0.06203187 0.7123942 -0.6990325 -0.06203187 0.7123942 1.30346e-7 -1 2.23661e-13 1.30346e-7 -1 2.23661e-13 1.30346e-7 -1 2.23661e-13 1 -5.7327e-8 9.83675e-14 1 -5.7327e-8 9.83675e-14 1 -5.7327e-8 9.83675e-14 1 -5.7327e-8 0 1 -5.7327e-8 0 1 -5.7327e-8 0 6.51728e-8 1 -1.7159e-6 6.51728e-8 1 -1.7159e-6 6.51728e-8 1 -1.7159e-6 -1 -3.56152e-7 3.4318e-6 -1 -3.56152e-7 3.4318e-6 -1 -3.56152e-7 3.4318e-6 -1 -7.98951e-8 -1.71591e-6 -1 -7.98951e-8 -1.71591e-6 -1 -7.98951e-8 -1.71591e-6 -1.19582e-6 -0.08674681 0.9962304 -1.19582e-6 -0.08674681 0.9962304 -1.19582e-6 -0.0867468 0.9962304 0 -0.08674686 0.9962304 0 -0.08674686 0.9962304 0 -0.08674686 0.9962304 0 -0.08674679 0.9962304 0 -0.08674679 0.9962304 0 -0.0867468 0.9962305 1.19582e-6 -0.08674684 0.9962304 1.19582e-6 -0.08674683 0.9962304 1.19582e-6 -0.08674684 0.9962305 6.51728e-8 -1 9.31654e-8 6.51728e-8 -1 9.31654e-8 6.51728e-8 -1 9.31654e-8 3.09082e-8 -1 -1.76009e-6 3.09082e-8 -1 -1.76009e-6 3.09082e-8 -1 -1.76009e-6 0 -1 0 0 -1 0 0 -1 0 6.51728e-8 1 -1.80907e-6 6.51728e-8 1 -1.80907e-6 6.51728e-8 1 -1.80907e-6 0 1 1.71591e-6 0 1 1.71591e-6 0 1 1.71591e-6 -2.05968e-12 1 -1.7159e-6 -2.05968e-12 1 -1.7159e-6 -2.05968e-12 1 -1.7159e-6 0 0 -1 0 0 -1 0 0 -1 0 0 -1 2.64339e-8 -1 1.98806e-8 0 -1 1.13641e-7 5.60496e-9 -1 9.37601e-8 3.20389e-8 -1 -3.64092e-15 1 -4.57961e-8 7.3192e-8 1 0 0 1 -2.26282e-8 3.61647e-8 1 -7.11048e-8 1.13641e-7 0 1 0 0 1 0 0 1 0 0 1 0 -1 -4.19571e-8 3.57437e-8 -1 0 1.13641e-7 -1 -2.14508e-8 7.38154e-8 -1 -6.12095e-8 0 0 -1 0 0 -1 0 0 -1 0 6.51728e-8 -1 1.71591e-6 6.51728e-8 -1 1.71591e-6 6.51728e-8 -1 1.71591e-6 0 1 0 0 1 0 0 1 0 6.51728e-8 1 -1.7159e-6 6.51728e-8 1 -1.7159e-6 6.51728e-8 1 -1.7159e-6 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -9.43052e-8 -1 0 -9.43052e-8 -1 0 -9.43052e-8 -1 0 -9.43052e-8 -1 0 6.28702e-8 1 0 6.28702e-8 1 0 6.28702e-8 1 0 6.28702e-8 1 0 -1 3.31791e-7 0 -1 3.31791e-7 0 -1 3.31791e-7 -3.91983e-9 -1 1.76264e-7 -3.91983e-9 -1 1.76264e-7 -3.91983e-9 -1 1.76264e-7 0 -1 6.63582e-7 0 -1 6.63582e-7 0 -1 6.63582e-7 0 1 6.32044e-7 0 1 6.32044e-7 0 1 6.32044e-7 0 1 1.14558e-6 0 1 1.14558e-6 0 1 1.14558e-6 0 1 1.58011e-6 0 1 1.58011e-6 0 1 1.58011e-6 0 -1 1.51913e-5 0 -1 1.51913e-5 0 -1 1.51913e-5 0 -1 1.51913e-5 0 -1 1.51913e-5 0 -1 1.51913e-5 8.4697e-6 -1 0 8.4697e-6 -1 0 8.4697e-6 -1 0 8.46969e-6 -1 0 8.46969e-6 -1 0 8.46969e-6 -1 0 0 -1 -1.54357e-5 0 -1 -1.54357e-5 0 -1 -1.54357e-5 0 -1 -1.54357e-5 0 -1 -1.54357e-5 0 -1 -1.54357e-5 -5.3333e-7 1 -3.08711e-5 -5.3333e-7 1 -3.08711e-5 -5.3333e-7 1 -3.08711e-5 0 1 -4.63067e-5 0 1 -4.63067e-5 0 1 -4.63067e-5 2.54091e-5 1 0 2.54091e-5 1 0 2.54091e-5 1 0 2.54091e-5 1 0 2.54091e-5 1 0 2.54091e-5 1 0 -5.3333e-7 1 4.65302e-5 -5.3333e-7 1 4.65302e-5 -5.3333e-7 1 4.65302e-5 0 1 3.03824e-5 0 1 3.03824e-5 0 1 3.03824e-5 0 -9.43053e-8 -1 0 -9.43053e-8 -1 0 -9.43053e-8 -1 5.02959e-14 -9.43053e-8 -1 5.02959e-14 -9.43053e-8 -1 5.02959e-14 -9.43053e-8 -1 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 6.28702e-8 1 0 6.28702e-8 1 0 6.28702e-8 1 -3.35306e-14 6.28702e-8 1 -3.35306e-14 6.28702e-8 1 -3.35306e-14 6.28702e-8 1 1 0 0 1 0 0 1 0 0 1 0 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 0 -1 3.31791e-7 0 -1 3.31791e-7 0 -1 3.31791e-7 3.91983e-9 -1 4.66582e-8 3.91983e-9 -1 4.66582e-8 3.91983e-9 -1 4.66582e-8 0 -1 3.31791e-7 0 -1 3.31791e-7 0 -1 3.31791e-7 0 1 9.48067e-7 0 1 9.48067e-7 0 1 9.48067e-7 0 1 1.26903e-6 0 1 1.26903e-6 0 1 1.26903e-6 0 1 1.26409e-6 0 1 1.26409e-6 0 1 1.26409e-6 0 -1 1.51913e-5 0 -1 1.51913e-5 0 -1 1.51913e-5 0 -1 1.51913e-5 0 -1 1.51913e-5 0 -1 1.51913e-5 -8.46969e-6 -1 0 -8.46969e-6 -1 0 -8.46969e-6 -1 0 -8.4697e-6 -1 0 -8.4697e-6 -1 0 -8.4697e-6 -1 0 0 -1 -1.54358e-5 0 -1 -1.54358e-5 0 -1 -1.54358e-5 -4.11615e-12 -1 -1.54357e-5 -4.11615e-12 -1 -1.54357e-5 -4.11615e-12 -1 -1.54357e-5 0 1 -4.6307e-5 0 1 -4.6307e-5 0 1 -4.6307e-5 5.3333e-7 1 -3.08714e-5 5.3333e-7 1 -3.08714e-5 5.3333e-7 1 -3.08714e-5 -2.54091e-5 1 0 -2.54091e-5 1 0 -2.54091e-5 1 0 -2.54091e-5 1 0 -2.54091e-5 1 0 -2.54091e-5 1 0 0 1 3.03824e-5 0 1 3.03824e-5 0 1 3.03824e-5 5.3333e-7 1 4.65302e-5 5.3333e-7 1 4.65302e-5 5.3333e-7 1 4.65302e-5 0 0 -1 0 0 -1 0 0 -1 -2.66665e-7 -3.14351e-8 -1 -2.66665e-7 -3.14351e-8 -1 -2.66665e-7 -3.14351e-8 -1 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1.67653e-14 -3.14351e-8 1 -1.67653e-14 -3.14351e-8 1 -1.67653e-14 -3.14351e-8 1 0 -3.14351e-8 1 0 -3.14351e-8 1 0 -3.14351e-8 1 -0.5454323 -0.6567053 0.5208088 -0.5446157 -0.8386856 -3.3364e-7 0.5446158 -0.8386857 -3.3364e-7 0.5454323 -0.6567054 0.5208087 -0.5364977 -0.3231358 0.7795855 0.5364974 -0.3231364 0.7795854 -0.5289139 3.98039e-7 0.8486755 0.5289146 0 0.8486751 -0.5364971 0.3231357 0.7795859 0.5364975 0.3231356 0.7795857 -0.5454319 0.6567059 0.5208086 0.5454323 0.656706 0.5208079 -0.5446154 0.8386858 -2.59888e-7 0.5446169 0.838685 -2.59887e-7 -0.5454316 0.656706 -0.5208085 0.545432 0.6567063 -0.5208076 -0.5364971 0.3231359 -0.7795858 0.5364975 0.3231358 -0.7795856 -0.5289141 2.82577e-7 -0.8486753 0.5289146 2.73462e-7 -0.8486751 -0.5364966 -0.3231357 -0.7795863 0.5364974 -0.3231361 -0.7795856 -0.5454326 -0.6567047 -0.5208093 0.5454323 -0.6567051 -0.520809 8.44155e-8 4.28132e-14 1 8.44157e-8 1.29887e-13 1 8.44156e-8 8.70734e-14 1 8.44154e-8 0 1 1 7.28977e-7 -1.99512e-7 1 -5.68638e-7 -1.46618e-6 1 1.79763e-7 -2.56882e-7 1 6.53096e-7 -7.50626e-8 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.6547342 0.01703374 0.7556672 -0.6547342 0.01703374 0.7556672 -0.6547342 0.01703374 0.7556672 -0.6108003 -9.39812e-7 0.7917847 -0.6108003 -9.39812e-7 0.7917847 -0.6108003 -9.39812e-7 0.7917847 0.603204 0.01797461 0.7973844 0.603204 0.01797461 0.7973844 0.603204 0.01797461 0.7973844 0.6574215 0 0.753523 0.6574215 0 0.7535231 0.6574215 0 0.7535231 -1 3.61252e-7 -1.32459e-7 1 -8.42921e-8 1.20417e-8 -0.5454323 -0.6567053 0.5208088 -0.5446157 -0.8386856 -3.3364e-7 0.5446158 -0.8386857 -3.3364e-7 0.5454323 -0.6567054 0.5208087 -0.5364977 -0.3231358 0.7795855 0.5364974 -0.3231364 0.7795854 -0.5289139 3.98039e-7 0.8486755 0.5289146 0 0.8486751 -0.5364971 0.323136 0.7795858 0.5364975 0.3231359 0.7795855 -0.5454319 0.6567056 0.5208088 0.5454323 0.6567059 0.5208081 -0.5446153 0.838686 -2.73936e-7 0.5446168 0.8386851 -2.87984e-7 -0.5454318 0.6567059 -0.5208086 0.5454322 0.6567062 -0.5208079 -0.5364971 0.3231361 -0.7795857 0.5364975 0.3231361 -0.7795855 -0.5289141 2.82577e-7 -0.8486753 0.5289146 2.73462e-7 -0.8486751 -0.5364966 -0.3231357 -0.7795863 0.5364974 -0.3231361 -0.7795856 -0.5454326 -0.6567047 -0.5208093 0.5454323 -0.6567051 -0.520809 8.44155e-8 4.28132e-14 1 8.44157e-8 1.29887e-13 1 8.44156e-8 8.70734e-14 1 8.44154e-8 0 1 1 7.28977e-7 -1.99512e-7 1 -5.68638e-7 -1.46618e-6 1 1.79763e-7 -2.56882e-7 1 6.53096e-7 -7.50626e-8 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.6547342 0.01703374 0.7556672 -0.6547342 0.01703374 0.7556672 -0.6547342 0.01703374 0.7556672 -0.6108003 -9.39812e-7 0.7917847 -0.6108003 -9.39812e-7 0.7917847 -0.6108003 -9.39812e-7 0.7917847 0.603204 0.01797461 0.7973844 0.603204 0.01797461 0.7973844 0.603204 0.01797461 0.7973844 0.6574215 0 0.753523 0.6574215 0 0.7535231 0.6574215 0 0.7535231 -1 3.71956e-7 -1.75274e-7 1 -3.61252e-8 3.34492e-8 0.5454323 -0.6567053 0.5208088 -0.5454323 -0.6567054 0.5208087 -0.5446158 -0.8386857 -3.3364e-7 0.5446158 -0.8386856 -3.3364e-7 0.5364977 -0.3231358 0.7795855 -0.5364974 -0.3231364 0.7795854 0.5289139 3.96519e-7 0.8486755 -0.5289146 0 0.8486751 0.5364971 0.3231357 0.7795859 -0.5364975 0.3231356 0.7795857 0.5454319 0.6567059 0.5208086 -0.5454323 0.656706 0.5208079 0.5446154 0.8386858 -2.59888e-7 -0.5446169 0.838685 -2.59887e-7 0.5454316 0.656706 -0.5208085 -0.545432 0.6567063 -0.5208076 0.5364971 0.3231359 -0.7795858 -0.5364975 0.3231358 -0.7795855 0.5289141 2.765e-7 -0.8486753 -0.5289146 2.82577e-7 -0.8486751 0.5364966 -0.3231357 -0.7795863 -0.5364974 -0.3231361 -0.7795856 0.5454326 -0.6567047 -0.5208093 -0.5454323 -0.6567051 -0.520809 -8.44155e-8 4.28132e-14 1 -8.44154e-8 0 1 -8.44156e-8 8.70734e-14 1 -8.44157e-8 1.29887e-13 1 -1 0 0 -1 0 0 -1 1.79763e-7 -2.56882e-7 -1 6.53096e-7 -7.50626e-8 -1 -5.68638e-7 -1.46618e-6 -1 7.28977e-7 -1.99512e-7 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.6108003 -9.39812e-7 0.7917847 0.6108003 -9.39812e-7 0.7917847 0.6108003 -9.39812e-7 0.7917847 0.6547342 0.01703374 0.7556672 0.6547342 0.01703374 0.7556672 0.6547342 0.01703374 0.7556672 -0.6574215 0 0.7535231 -0.6574215 0 0.7535231 -0.6574215 0 0.753523 -0.603204 0.01797461 0.7973844 -0.603204 0.01797461 0.7973844 -0.603204 0.01797461 0.7973844 1 3.559e-7 -1.39818e-7 -1 -7.89402e-8 1.27107e-8 0.5454323 -0.6567053 0.5208088 -0.5454323 -0.6567054 0.5208087 -0.5446158 -0.8386857 -3.3364e-7 0.5446158 -0.8386856 -3.3364e-7 0.5364977 -0.3231358 0.7795855 -0.5364974 -0.3231364 0.7795854 0.5289139 3.96519e-7 0.8486755 -0.5289146 0 0.8486751 0.5364971 0.323136 0.7795858 -0.5364975 0.3231359 0.7795855 0.5454319 0.6567056 0.5208088 -0.5454323 0.6567058 0.520808 0.5446153 0.838686 -2.70424e-7 -0.5446167 0.8386851 -2.84472e-7 0.5454318 0.6567059 -0.5208086 -0.5454322 0.6567062 -0.5208078 0.5364971 0.3231361 -0.7795857 -0.5364975 0.3231361 -0.7795855 0.5289141 2.765e-7 -0.8486753 -0.5289146 2.82577e-7 -0.8486751 0.5364966 -0.3231357 -0.7795863 -0.5364974 -0.3231361 -0.7795856 0.5454326 -0.6567047 -0.5208093 -0.5454323 -0.6567051 -0.520809 -8.44155e-8 4.28132e-14 1 -8.44154e-8 0 1 -8.44156e-8 8.70734e-14 1 -8.44157e-8 1.29887e-13 1 -1 0 0 -1 0 0 -1 1.79763e-7 -2.56882e-7 -1 6.53096e-7 -7.50626e-8 -1 -5.68638e-7 -1.46618e-6 -1 7.28977e-7 -1.99512e-7 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.6108003 -9.39812e-7 0.7917847 0.6108003 -9.39812e-7 0.7917847 0.6108003 -9.39812e-7 0.7917847 0.6547342 0.01703374 0.7556672 0.6547342 0.01703374 0.7556672 0.6547342 0.01703374 0.7556672 -0.6574215 0 0.7535231 -0.6574215 0 0.7535231 -0.6574215 0 0.753523 -0.603204 0.01797461 0.7973844 -0.603204 0.01797461 0.7973844 -0.603204 0.01797461 0.7973844 1 3.71956e-7 -1.61226e-7 -1 -3.07733e-8 2.34145e-8 + + + + + + + + + + 0.7826015 0.9369037 0 0.6145632 0.9369035 0 0.6145632 0.9256275 0 0.1692367 0.374373 0 0.9774077 0.9790846 0 0.9681181 0.9680098 0 0.9774077 0.9680098 0 0.614563 0.9020004 0 0.1590733 0.3756632 0 0.7826015 0.9369192 0 0.7310616 0.7648342 0 0.7310616 0.5933624 0 0.9597374 0.5933623 0 0.9597374 0.7648342 0 0.7310621 0.764834 0 0.7310621 0.5933622 0 0.959738 0.5933622 0 0.959738 0.764834 0 0.7102768 0.7719547 0 0.7102768 0.586242 0 0.9741519 0.5855267 0 0.9832734 0.7719547 0 0.7103205 0.7719543 0 0.7103205 0.5862418 0 0.9741523 0.5855266 0 0.9832308 0.7719544 0 0.9506399 0.9369194 0 0.95064 0.9256432 0 0.6145631 0.9256428 0 0.6145631 0.936919 0 0.6238527 0.8909256 0 0.614563 0.8909256 0 0.6166412 0.9790846 0 0.6259308 0.9680098 0 0.6166412 0.9680098 0 0.9753309 0.9020004 0 0.9660412 0.8909256 0 0.9753309 0.8909256 0 0.4456427 0.01043226 0 0.4456428 0.2686733 0 0.888405 0.2686733 0 0.888405 0.01043212 0 0.6825423 0.5850404 0 0.429824 0.5850404 0 0.429824 0.8353747 0 0.6825423 0.8005369 0 0.9576652 0.5501504 0 0.4451446 0.5501504 0 0.429824 0.5850404 0 0.6825423 0.5850404 0 0.3508784 0.8381392 0 0.01041424 0.8381393 0 0.6825423 0.8005369 0 0.429824 0.8353747 0 0.01041424 0.6395635 0 0.3508784 0.6395634 0 0.4451446 0.2928227 0 0.9576651 0.2928227 0 0.4027264 0.6159363 0 0.2065703 0.6159363 0 0.2218391 0.5950645 0 0.3874576 0.5950646 0 0.2065704 0.325707 0 0.2218392 0.3465789 0 0.4027265 0.3257072 0 0.3874577 0.346579 0 0.01041424 0.6159362 0 0.02568305 0.5950643 0 0.1913015 0.5950645 0 0.01041433 0.325707 0 0.02568314 0.3465789 0 0.1913016 0.3465789 0 0.7203978 0.7715055 0 0.7203978 0.5855269 0 0.9832734 0.586242 0 0.9741519 0.7715055 0 0.7213348 0.7705687 0 0.7203982 0.5855267 0 0.9832308 0.5862418 0 0.9750888 0.7705689 0 0.4220157 0.01043212 0 0.01041424 0.01043212 0 0.01041424 0.3020799 0 0.4220156 0.30208 0 0.6890678 0.8615139 0 0.9425469 0.8614903 0 0.9415262 0.8497827 0 0.6880471 0.8498063 0 0.9417936 0.8407978 0 0.6883143 0.8408216 0 0.9425477 0.8614916 0 0.6890687 0.8615351 0 0.688047 0.8498275 0 0.9415261 0.8497832 0 0.6883131 0.8408427 0 0.9417922 0.8407978 0 0.95064 0.9256278 0 0.95064 0.9369039 0 0.169226 0.586325 0 0.1590625 0.5876153 0 0.159073 0.3756633 0 0.1692364 0.3743731 0 0.1590629 0.5876153 0 0.1692263 0.5863249 0 0.311544 0.9412726 0 0.01113467 0.9412726 0 0.01113467 0.894006 0 0.311544 0.894006 0 0.01113467 0.9789155 0 0.311544 0.856363 0 0.561259 0.905852 0 0.561259 0.9403802 0 0.1378004 0.5221345 0 0.1378004 0.4752338 0 0.07389515 0.5221345 0 0.1378004 0.5221345 0 0.1378004 0.4752338 0 0.07389515 0.5221345 0 0.1378004 0.5221345 0 0.1378004 0.4752338 0 0.07389515 0.5221345 0 0.1378004 0.5221345 0 0.1378004 0.4752338 0 0.07389515 0.5221345 0 0.1378004 0.5221345 0 0.1378004 0.4752338 0 0.07389515 0.5221345 0 0.1378004 0.5221345 0 0.1378004 0.4752338 0 0.07389515 0.5221345 0 0.03471501 0.5861259 0 0.311544 0.9789155 0 0.03471501 0.5390165 0 0.01113479 0.856363 0 0.3297207 0.9403802 0 0.561259 0.878558 0 0.3297207 0.905852 0 0.03742649 0.5418071 0 0.03742649 0.5861259 0 0.1378004 0.5390165 0 0.1351318 0.5418071 0 0.1378004 0.5861259 0 0.1351318 0.5861259 0 0.1378004 0.5861259 0 0.1378004 0.5390165 0 0.1351318 0.5418071 0 0.1351318 0.5861259 0 0.03471501 0.5390165 0 0.03742653 0.5418071 0 0.03471501 0.5861259 0 0.03742653 0.5861259 0 0.3297207 0.878558 0 0.561259 0.9676743 0 0.3297207 0.9676741 0 0.311544 0.9412726 0 0.01113467 0.9412726 0 0.01113467 0.894006 0 0.311544 0.894006 0 0.01113467 0.9789155 0 0.311544 0.856363 0 0.561259 0.905852 0 0.561259 0.9403802 0 0.1378004 0.5221345 0 0.1378004 0.4752338 0 0.07389515 0.5221345 0 0.1378004 0.5221345 0 0.1378004 0.4752338 0 0.07389515 0.5221345 0 0.1378004 0.5221345 0 0.1378004 0.4752338 0 0.07389515 0.5221345 0 0.1378004 0.5221345 0 0.1378004 0.4752338 0 0.07389515 0.5221345 0 0.1378004 0.5221345 0 0.1378004 0.4752338 0 0.07389515 0.5221345 0 0.1378004 0.5221345 0 0.1378004 0.4752338 0 0.07389515 0.5221345 0 0.03471501 0.5861259 0 0.311544 0.9789155 0 0.03471501 0.5390165 0 0.01113479 0.856363 0 0.3297207 0.9403802 0 0.561259 0.878558 0 0.3297207 0.905852 0 0.03742649 0.5418071 0 0.03742649 0.5861259 0 0.1378004 0.5390165 0 0.1351318 0.5418071 0 0.1378004 0.5861259 0 0.1351318 0.5861259 0 0.1378004 0.5861259 0 0.1378004 0.5390165 0 0.1351318 0.5418071 0 0.1351318 0.5861259 0 0.03471501 0.5390165 0 0.03742653 0.5418071 0 0.03471501 0.5861259 0 0.03742653 0.5861259 0 0.3297207 0.878558 0 0.561259 0.9676743 0 0.3297207 0.9676741 0 0.3687613 0.5371519 0 0.3349051 0.5371519 0 0.3349051 0.5117077 0 0.3687613 0.5117077 0 0.2747087 0.5278894 0 0.2613961 0.5509475 0 0.2613961 0.5243223 0 0.2613961 0.5243223 0 0.2613961 0.5509475 0 0.2747087 0.5278894 0 0.2844543 0.537635 0 0.2844543 0.537635 0 0.2880213 0.5509475 0 0.2880213 0.5509475 0 0.2844543 0.5642601 0 0.2844543 0.5642601 0 0.2747087 0.5740057 0 0.2747087 0.5740057 0 0.2613961 0.5775728 0 0.2613961 0.5775728 0 0.2480834 0.5740057 0 0.2480834 0.5740057 0 0.2383379 0.5642601 0 0.2383379 0.5642601 0 0.2347707 0.5509475 0 0.2347707 0.5509475 0 0.2383379 0.537635 0 0.2383379 0.537635 0 0.2480834 0.5278894 0 0.2480834 0.5278894 0 0.370621 0.4995614 0 0.339505 0.5001452 0 0.3626311 0.4652385 0 0.3676492 0.4627341 0 0.376072 0.4628268 0 0.3787153 0.4657509 0 0.3395052 0.5487143 0 0.3706211 0.5492984 0 0.3787152 0.583109 0 0.3760718 0.586033 0 0.3676491 0.5861259 0 0.3626309 0.5836214 0 0.3042072 0.4005728 0 0.3194318 0.4005728 0 0.3194318 0.4182728 0 0.3042072 0.4182728 0 0.3042072 0.3828728 0 0.3194318 0.3828728 0 0.3042072 0.3651728 0 0.3194318 0.3651728 0 0.3042072 0.5775728 0 0.3194318 0.5775728 0 0.3042072 0.5598728 1.19209e-7 0.3194318 0.5598728 1.19209e-7 0.3042072 0.5421728 0 0.3194318 0.5421728 0 0.3042072 0.5244728 0 0.3194318 0.5244728 0 0.3042072 0.5067728 0 0.3194318 0.5067728 0 0.3042072 0.4890728 -2.38419e-7 0.3194318 0.4890728 -2.38419e-7 0.3042072 0.4713729 0 0.3194318 0.4713729 0 0.3042072 0.4536728 0 0.3194318 0.4536728 0 0.3042072 0.4359728 -2.38419e-7 0.3194318 0.4359728 -2.38419e-7 0.3687613 0.5371519 0 0.3349051 0.5371519 0 0.3349051 0.5117077 0 0.3687613 0.5117077 0 0.2747087 0.5278894 0 0.2613961 0.5509475 0 0.2613961 0.5243223 0 0.2613961 0.5243223 0 0.2613961 0.5509475 0 0.2747087 0.5278894 0 0.2844543 0.537635 0 0.2844543 0.537635 0 0.2880213 0.5509475 0 0.2880213 0.5509475 0 0.2844543 0.5642601 0 0.2844543 0.5642601 0 0.2747087 0.5740057 0 0.2747087 0.5740057 0 0.2613961 0.5775728 0 0.2613961 0.5775728 0 0.2480834 0.5740057 0 0.2480834 0.5740057 0 0.2383379 0.5642601 0 0.2383379 0.5642601 0 0.2347707 0.5509475 0 0.2347707 0.5509475 0 0.2383379 0.537635 0 0.2383379 0.537635 0 0.2480834 0.5278894 0 0.2480834 0.5278894 0 0.370621 0.4995614 0 0.339505 0.5001452 0 0.3626311 0.4652385 0 0.3676492 0.4627341 0 0.376072 0.4628268 0 0.3787153 0.4657509 0 0.3395052 0.5487143 0 0.3706211 0.5492984 0 0.3787152 0.583109 0 0.3760718 0.586033 0 0.3676491 0.5861259 0 0.3626309 0.5836214 0 0.3042072 0.4005728 0 0.3194318 0.4005728 0 0.3194318 0.4182728 0 0.3042072 0.4182728 0 0.3042072 0.3828728 0 0.3194318 0.3828728 0 0.3042072 0.3651728 0 0.3194318 0.3651728 0 0.3042072 0.5775728 0 0.3194318 0.5775728 0 0.3042072 0.5598728 1.19209e-7 0.3194318 0.5598728 1.19209e-7 0.3042072 0.5421728 0 0.3194318 0.5421728 0 0.3042072 0.5244728 0 0.3194318 0.5244728 0 0.3042072 0.5067728 0 0.3194318 0.5067728 0 0.3042072 0.4890728 -2.38419e-7 0.3194318 0.4890728 -2.38419e-7 0.3042072 0.4713729 0 0.3194318 0.4713729 0 0.3042072 0.4536728 0 0.3194318 0.4536728 0 0.3042072 0.4359728 -2.38419e-7 0.3194318 0.4359728 -2.38419e-7 0.3687613 0.5371519 0 0.3349051 0.5371519 0 0.3349051 0.5117077 0 0.3687613 0.5117077 0 0.2747087 0.5278894 0 0.2613961 0.5509475 0 0.2613961 0.5243223 0 0.2613961 0.5243223 0 0.2613961 0.5509475 0 0.2747087 0.5278894 0 0.2844543 0.537635 0 0.2844543 0.537635 0 0.2880213 0.5509475 0 0.2880213 0.5509475 0 0.2844543 0.5642601 0 0.2844543 0.5642601 0 0.2747087 0.5740057 0 0.2747087 0.5740057 0 0.2613961 0.5775728 0 0.2613961 0.5775728 0 0.2480834 0.5740057 0 0.2480834 0.5740057 0 0.2383379 0.5642601 0 0.2383379 0.5642601 0 0.2347707 0.5509475 0 0.2347707 0.5509475 0 0.2383379 0.537635 0 0.2383379 0.537635 0 0.2480834 0.5278894 0 0.2480834 0.5278894 0 0.370621 0.4995614 0 0.339505 0.5001452 0 0.3626311 0.4652385 0 0.3676492 0.4627341 0 0.376072 0.4628268 0 0.3787153 0.4657509 0 0.3395052 0.5487143 0 0.3706211 0.5492984 0 0.3787152 0.583109 0 0.3760718 0.586033 0 0.3676491 0.5861259 0 0.3626309 0.5836214 0 0.3042072 0.4005728 0 0.3194318 0.4005728 0 0.3194318 0.4182728 0 0.3042072 0.4182728 0 0.3042072 0.3828728 0 0.3194318 0.3828728 0 0.3042072 0.3651728 0 0.3194318 0.3651728 0 0.3042072 0.5775728 0 0.3194318 0.5775728 0 0.3042072 0.5598728 1.19209e-7 0.3194318 0.5598728 1.19209e-7 0.3042072 0.5421728 0 0.3194318 0.5421728 0 0.3042072 0.5244728 0 0.3194318 0.5244728 0 0.3042072 0.5067728 0 0.3194318 0.5067728 0 0.3042072 0.4890728 -2.38419e-7 0.3194318 0.4890728 -2.38419e-7 0.3042072 0.4713729 0 0.3194318 0.4713729 0 0.3042072 0.4536728 0 0.3194318 0.4536728 0 0.3042072 0.4359728 -2.38419e-7 0.3194318 0.4359728 -2.38419e-7 0.3687613 0.5371519 0 0.3349051 0.5371519 0 0.3349051 0.5117077 0 0.3687613 0.5117077 0 0.2747087 0.5278894 0 0.2613961 0.5509475 0 0.2613961 0.5243223 0 0.2613961 0.5243223 0 0.2613961 0.5509475 0 0.2747087 0.5278894 0 0.2844543 0.537635 0 0.2844543 0.537635 0 0.2880213 0.5509475 0 0.2880213 0.5509475 0 0.2844543 0.5642601 0 0.2844543 0.5642601 0 0.2747087 0.5740057 0 0.2747087 0.5740057 0 0.2613961 0.5775728 0 0.2613961 0.5775728 0 0.2480834 0.5740057 0 0.2480834 0.5740057 0 0.2383379 0.5642601 0 0.2383379 0.5642601 0 0.2347707 0.5509475 0 0.2347707 0.5509475 0 0.2383379 0.537635 0 0.2383379 0.537635 0 0.2480834 0.5278894 0 0.2480834 0.5278894 0 0.370621 0.4995614 0 0.339505 0.5001452 0 0.3626311 0.4652385 0 0.3676492 0.4627341 0 0.376072 0.4628268 0 0.3787153 0.4657509 0 0.3395052 0.5487143 0 0.3706211 0.5492984 0 0.3787152 0.583109 0 0.3760718 0.586033 0 0.3676491 0.5861259 0 0.3626309 0.5836214 0 0.3042072 0.4005728 0 0.3194318 0.4005728 0 0.3194318 0.4182728 0 0.3042072 0.4182728 0 0.3042072 0.3828728 0 0.3194318 0.3828728 0 0.3042072 0.3651728 0 0.3194318 0.3651728 0 0.3042072 0.5775728 0 0.3194318 0.5775728 0 0.3042072 0.5598728 1.19209e-7 0.3194318 0.5598728 1.19209e-7 0.3042072 0.5421728 0 0.3194318 0.5421728 0 0.3042072 0.5244728 0 0.3194318 0.5244728 0 0.3042072 0.5067728 0 0.3194318 0.5067728 0 0.3042072 0.4890728 -2.38419e-7 0.3194318 0.4890728 -2.38419e-7 0.3042072 0.4713729 0 0.3194318 0.4713729 0 0.3042072 0.4536728 0 0.3194318 0.4536728 0 0.3042072 0.4359728 -2.38419e-7 0.3194318 0.4359728 -2.38419e-7 + + + + + + + + + + + + + + + +

18 0 10 19 1 11 20 2 12 20 3 12 21 4 13 18 5 10 4 6 4 26 7 5 28 8 6 6 9 91 30 10 92 29 11 93 29 12 93 5 13 90 6 14 91 6 15 7 32 16 30 30 17 31 7 18 84 4 19 85 28 20 86 28 21 86 31 22 87 7 23 84 7 24 83 6 25 82 5 26 81 5 27 81 4 28 80 7 29 83 22 30 14 23 31 15 24 32 16 24 33 16 25 34 17 22 35 14 0 36 58 8 37 59 11 38 60 11 39 60 10 40 61 0 41 58 8 42 59 9 43 62 12 44 63 12 45 63 11 46 60 8 47 59 9 48 62 3 49 64 13 50 65 13 51 65 12 52 63 9 53 62 3 54 64 0 55 58 10 56 61 10 57 61 13 58 65 3 59 64 8 60 59 1 61 66 15 62 67 15 63 67 14 64 68 8 65 59 1 66 66 2 67 69 16 68 70 16 69 70 15 70 67 1 71 66 2 72 69 9 73 62 17 74 71 17 75 71 16 76 70 2 77 69 9 78 62 8 79 59 14 80 68 14 81 68 17 82 71 9 83 62 10 84 18 11 85 19 19 86 11 19 87 11 18 88 10 10 89 18 20 90 12 19 91 11 11 92 73 11 93 73 12 94 20 20 95 12 12 96 74 13 97 21 21 98 13 21 99 13 20 100 12 12 101 74 10 102 72 18 103 10 21 104 13 21 105 13 13 106 75 10 107 72 14 108 22 15 109 23 23 110 15 23 111 15 22 112 14 14 113 22 24 114 16 23 115 15 15 116 77 15 117 77 16 118 24 24 119 16 16 120 78 17 121 25 25 122 17 25 123 17 24 124 16 16 125 78 14 126 76 22 127 14 25 128 17 25 129 17 17 130 79 14 131 76 8 132 0 0 133 1 26 134 2 32 135 98 2 136 99 1 137 100 1 138 100 27 139 101 32 140 98 9 141 9 2 142 26 32 143 27 0 144 8 3 145 102 33 146 103 33 147 103 26 148 3 0 149 8 30 150 92 32 151 94 27 152 95 27 153 95 29 154 93 30 155 92 28 156 86 26 157 88 33 158 89 33 159 89 31 160 87 28 161 86 5 162 32 27 163 33 26 164 5 26 165 5 4 166 4 5 167 32 5 168 32 29 169 34 27 170 33 7 171 35 33 172 36 32 173 30 32 174 30 6 175 7 7 176 35 7 177 35 31 178 37 33 179 36 34 180 38 36 181 39 37 182 40 37 182 40 35 183 41 34 180 38 34 184 46 35 185 47 39 186 56 39 186 56 38 187 57 34 184 46 35 188 42 37 189 43 41 190 44 41 190 44 39 191 45 35 188 42 37 192 50 36 193 51 40 194 54 40 194 54 41 195 55 37 192 50 36 196 48 34 197 49 38 198 52 38 198 52 40 199 53 36 196 48 27 200 96 1 201 97 8 202 0 8 203 0 26 204 2 27 205 96 33 206 28 3 207 29 9 208 9 9 209 9 32 210 27 33 211 28 42 212 104 44 213 107 45 214 106 45 214 106 43 215 105 42 212 104 43 216 105 46 217 108 47 218 131 47 218 131 42 219 104 43 216 105 44 220 107 48 221 109 49 222 133 49 222 133 45 223 106 44 220 107 50 224 112 52 225 114 51 226 113 53 227 115 55 228 117 54 229 116 56 230 118 58 231 120 57 232 119 59 233 121 61 234 123 60 235 122 62 236 124 64 237 126 63 238 125 65 239 127 67 240 129 66 241 128 47 242 130 68 243 138 69 244 137 69 245 137 42 246 132 47 247 130 42 248 132 69 249 137 70 250 140 70 251 140 44 252 139 42 253 132 44 254 139 70 255 140 71 256 142 71 257 142 48 258 141 44 259 139 49 260 143 72 261 146 73 262 145 73 263 145 45 264 144 49 265 143 45 266 144 73 267 145 74 268 148 74 269 148 43 270 147 45 271 144 43 272 147 74 273 148 75 274 150 75 275 150 46 276 149 43 277 147 72 278 153 71 279 152 70 280 111 70 281 111 73 282 134 72 283 153 73 284 134 70 285 111 69 286 110 69 287 110 74 288 136 73 289 134 74 290 136 69 291 110 68 292 135 68 293 135 75 294 151 74 295 136 76 296 154 77 297 155 79 298 156 79 298 156 78 299 157 76 296 154 77 300 155 76 301 154 81 302 181 81 302 181 80 303 158 77 300 155 78 304 157 79 305 156 83 306 183 83 306 183 82 307 159 78 304 157 84 308 162 85 309 163 86 310 164 87 311 165 88 312 166 89 313 167 90 314 168 91 315 169 92 316 170 93 317 171 94 318 172 95 319 173 96 320 174 97 321 175 98 322 176 99 323 177 100 324 178 101 325 179 81 326 180 76 327 182 103 328 187 103 329 187 102 330 188 81 331 180 76 332 182 78 333 189 104 334 190 104 335 190 103 336 187 76 337 182 78 338 189 82 339 191 105 340 192 105 341 192 104 342 190 78 343 189 83 344 193 79 345 194 107 346 195 107 347 195 106 348 196 83 349 193 79 350 194 77 351 197 108 352 198 108 353 198 107 354 195 79 355 194 77 356 197 80 357 199 109 358 200 109 359 200 108 360 198 77 361 197 106 362 203 107 363 184 104 364 161 104 365 161 105 366 202 106 367 203 107 368 184 108 369 186 103 370 160 103 371 160 104 372 161 107 373 184 108 374 186 109 375 201 102 376 185 102 377 185 103 378 160 108 379 186 129 380 247 130 381 248 131 382 249 131 382 249 128 383 246 129 380 247 133 384 251 129 380 247 128 383 246 128 383 246 132 385 250 133 384 251 135 386 253 133 384 251 132 385 250 132 385 250 134 387 252 135 386 253 137 388 257 135 386 255 134 387 254 134 387 254 136 389 256 137 388 257 139 390 259 137 388 257 136 389 256 136 389 256 138 391 258 139 390 259 141 392 261 139 390 259 138 391 258 138 391 258 140 393 260 141 392 261 143 394 263 141 392 261 140 393 260 140 393 260 142 395 262 143 394 263 145 396 265 143 394 263 142 395 262 142 395 262 144 397 264 145 396 265 147 398 267 145 396 265 144 397 264 144 397 264 146 399 266 147 398 267 149 400 269 147 398 267 146 399 266 146 399 266 148 401 268 149 400 269 151 402 271 149 400 269 148 401 268 148 401 268 150 403 270 151 402 271 130 381 248 151 402 271 150 403 270 150 403 270 131 382 249 130 381 248 124 404 204 114 405 205 127 406 206 127 406 206 113 407 207 124 404 204 115 408 235 119 409 236 123 410 237 125 411 234 115 408 235 123 410 237 123 410 237 117 412 238 121 413 239 125 411 234 123 410 237 121 413 239 112 414 241 116 415 242 120 416 243 126 417 240 112 414 241 120 416 243 120 416 243 118 418 244 122 419 245 126 417 240 120 416 243 122 419 245 124 420 204 112 421 241 126 422 240 126 423 240 114 424 205 124 425 204 127 426 206 115 427 235 125 428 234 125 429 234 113 430 207 127 431 206 129 380 208 111 432 209 130 381 210 131 382 211 110 433 212 128 383 213 133 384 214 111 432 209 129 380 208 128 383 213 110 433 212 132 385 215 135 386 216 111 432 209 133 384 214 132 385 215 110 433 212 134 387 217 137 388 218 111 432 209 135 386 216 134 387 217 110 433 212 136 389 219 139 390 220 111 432 209 137 388 218 136 389 219 110 433 212 138 391 221 141 392 222 111 432 209 139 390 220 138 391 221 110 433 212 140 393 223 143 394 224 111 432 209 141 392 222 140 393 223 110 433 212 142 395 225 145 396 226 111 432 209 143 394 224 142 395 225 110 433 212 144 397 227 147 398 228 111 432 209 145 396 226 144 397 227 110 433 212 146 399 229 149 400 230 111 432 209 147 398 228 146 399 229 110 433 212 148 401 231 151 402 232 111 432 209 149 400 230 148 401 231 110 433 212 150 403 233 130 381 210 111 432 209 151 402 232 150 403 233 110 433 212 131 382 211 171 434 315 172 435 316 173 436 317 173 436 317 170 437 314 171 434 315 175 438 319 171 434 315 170 437 314 170 437 314 174 439 318 175 438 319 177 440 321 175 438 319 174 439 318 174 439 318 176 441 320 177 440 321 179 442 325 177 440 323 176 441 322 176 441 322 178 443 324 179 442 325 181 444 327 179 442 325 178 443 324 178 443 324 180 445 326 181 444 327 183 446 329 181 444 327 180 445 326 180 445 326 182 447 328 183 446 329 185 448 331 183 446 329 182 447 328 182 447 328 184 449 330 185 448 331 187 450 333 185 448 331 184 449 330 184 449 330 186 451 332 187 450 333 189 452 335 187 450 333 186 451 332 186 451 332 188 453 334 189 452 335 191 454 337 189 452 335 188 453 334 188 453 334 190 455 336 191 454 337 193 456 339 191 454 337 190 455 336 190 455 336 192 457 338 193 456 339 172 435 316 193 456 339 192 457 338 192 457 338 173 436 317 172 435 316 166 458 272 156 459 273 169 460 274 169 460 274 155 461 275 166 458 272 157 462 303 161 463 304 165 464 305 167 465 302 157 462 303 165 464 305 165 464 305 159 466 306 163 467 307 167 465 302 165 464 305 163 467 307 154 468 309 158 469 310 162 470 311 168 471 308 154 468 309 162 470 311 162 470 311 160 472 312 164 473 313 168 471 308 162 470 311 164 473 313 166 474 272 154 475 309 168 476 308 168 477 308 156 478 273 166 479 272 169 480 274 157 481 303 167 482 302 167 483 302 155 484 275 169 485 274 171 434 276 153 486 277 172 435 278 173 436 279 152 487 280 170 437 281 175 438 282 153 486 277 171 434 276 170 437 281 152 487 280 174 439 283 177 440 284 153 486 277 175 438 282 174 439 283 152 487 280 176 441 285 179 442 286 153 486 277 177 440 284 176 441 285 152 487 280 178 443 287 181 444 288 153 486 277 179 442 286 178 443 287 152 487 280 180 445 289 183 446 290 153 486 277 181 444 288 180 445 289 152 487 280 182 447 291 185 448 292 153 486 277 183 446 290 182 447 291 152 487 280 184 449 293 187 450 294 153 486 277 185 448 292 184 449 293 152 487 280 186 451 295 189 452 296 153 486 277 187 450 294 186 451 295 152 487 280 188 453 297 191 454 298 153 486 277 189 452 296 188 453 297 152 487 280 190 455 299 193 456 300 153 486 277 191 454 298 190 455 299 152 487 280 192 457 301 172 435 278 153 486 277 193 456 300 192 457 301 152 487 280 173 436 279 213 488 383 212 489 382 215 490 385 215 490 385 214 491 384 213 488 383 217 492 387 216 493 386 212 489 382 212 489 382 213 488 383 217 492 387 219 494 389 218 495 388 216 493 386 216 493 386 217 492 387 219 494 389 221 496 393 220 497 392 218 495 390 218 495 390 219 494 391 221 496 393 223 498 395 222 499 394 220 497 392 220 497 392 221 496 393 223 498 395 225 500 397 224 501 396 222 499 394 222 499 394 223 498 395 225 500 397 227 502 399 226 503 398 224 501 396 224 501 396 225 500 397 227 502 399 229 504 401 228 505 400 226 503 398 226 503 398 227 502 399 229 504 401 231 506 403 230 507 402 228 505 400 228 505 400 229 504 401 231 506 403 233 508 405 232 509 404 230 507 402 230 507 402 231 506 403 233 508 405 235 510 407 234 511 406 232 509 404 232 509 404 233 508 405 235 510 407 214 491 384 215 490 385 234 511 406 234 511 406 235 510 407 214 491 384 208 512 340 197 513 343 211 514 342 211 514 342 198 515 341 208 512 340 205 516 375 201 517 374 207 518 373 209 519 370 205 516 375 207 518 373 207 518 373 203 520 372 199 521 371 209 519 370 207 518 373 199 521 371 206 522 381 202 523 380 204 524 379 210 525 376 206 522 381 204 524 379 204 524 379 200 526 378 196 527 377 210 525 376 204 524 379 196 527 377 208 528 340 198 529 341 210 530 376 210 531 376 196 532 377 208 533 340 211 534 342 197 535 343 209 536 370 209 537 370 199 538 371 211 539 342 213 488 344 214 491 346 195 540 345 215 490 347 212 489 349 194 541 348 217 492 350 213 488 344 195 540 345 212 489 349 216 493 351 194 541 348 219 494 352 217 492 350 195 540 345 216 493 351 218 495 353 194 541 348 221 496 354 219 494 352 195 540 345 218 495 353 220 497 355 194 541 348 223 498 356 221 496 354 195 540 345 220 497 355 222 499 357 194 541 348 225 500 358 223 498 356 195 540 345 222 499 357 224 501 359 194 541 348 227 502 360 225 500 358 195 540 345 224 501 359 226 503 361 194 541 348 229 504 362 227 502 360 195 540 345 226 503 361 228 505 363 194 541 348 231 506 364 229 504 362 195 540 345 228 505 363 230 507 365 194 541 348 233 508 366 231 506 364 195 540 345 230 507 365 232 509 367 194 541 348 235 510 368 233 508 366 195 540 345 232 509 367 234 511 369 194 541 348 214 491 346 235 510 368 195 540 345 234 511 369 215 490 347 194 541 348 255 542 451 254 543 450 257 544 453 257 544 453 256 545 452 255 542 451 259 546 455 258 547 454 254 543 450 254 543 450 255 542 451 259 546 455 261 548 457 260 549 456 258 547 454 258 547 454 259 546 455 261 548 457 263 550 461 262 551 460 260 549 458 260 549 458 261 548 459 263 550 461 265 552 463 264 553 462 262 551 460 262 551 460 263 550 461 265 552 463 267 554 465 266 555 464 264 553 462 264 553 462 265 552 463 267 554 465 269 556 467 268 557 466 266 555 464 266 555 464 267 554 465 269 556 467 271 558 469 270 559 468 268 557 466 268 557 466 269 556 467 271 558 469 273 560 471 272 561 470 270 559 468 270 559 468 271 558 469 273 560 471 275 562 473 274 563 472 272 561 470 272 561 470 273 560 471 275 562 473 277 564 475 276 565 474 274 563 472 274 563 472 275 562 473 277 564 475 256 545 452 257 544 453 276 565 474 276 565 474 277 564 475 256 545 452 250 566 408 239 567 411 253 568 410 253 568 410 240 569 409 250 566 408 247 570 443 243 571 442 249 572 441 251 573 438 247 570 443 249 572 441 249 572 441 245 574 440 241 575 439 251 573 438 249 572 441 241 575 439 248 576 449 244 577 448 246 578 447 252 579 444 248 576 449 246 578 447 246 578 447 242 580 446 238 581 445 252 579 444 246 578 447 238 581 445 250 582 408 240 583 409 252 584 444 252 585 444 238 586 445 250 587 408 253 588 410 239 589 411 251 590 438 251 591 438 241 592 439 253 593 410 255 542 412 256 545 414 237 594 413 257 544 415 254 543 417 236 595 416 259 546 418 255 542 412 237 594 413 254 543 417 258 547 419 236 595 416 261 548 420 259 546 418 237 594 413 258 547 419 260 549 421 236 595 416 263 550 422 261 548 420 237 594 413 260 549 421 262 551 423 236 595 416 265 552 424 263 550 422 237 594 413 262 551 423 264 553 425 236 595 416 267 554 426 265 552 424 237 594 413 264 553 425 266 555 427 236 595 416 269 556 428 267 554 426 237 594 413 266 555 427 268 557 429 236 595 416 271 558 430 269 556 428 237 594 413 268 557 429 270 559 431 236 595 416 273 560 432 271 558 430 237 594 413 270 559 431 272 561 433 236 595 416 275 562 434 273 560 432 237 594 413 272 561 433 274 563 435 236 595 416 277 564 436 275 562 434 237 594 413 274 563 435 276 565 437 236 595 416 256 545 414 277 564 436 237 594 413 276 565 437 257 544 415 236 595 416

+
+
+
+
+ + + + + 0 0 0 + + + + + + + + + + + 0.2471926 0.3027847 0.4507179 + + 1 0 0 0 0 1 0 0 0 0 1 8.72673 0 0 0 1 + + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/simulators/sim_env/models/dumpster/model-1_3.sdf b/simulators/sim_env/models/dumpster/model-1_3.sdf new file mode 100755 index 0000000..b756920 --- /dev/null +++ b/simulators/sim_env/models/dumpster/model-1_3.sdf @@ -0,0 +1,28 @@ + + + + + + + + model://dumpster/meshes/dumpster.dae + + + + + + + model://dumpster/meshes/dumpster.dae + + + + + + + + + diff --git a/simulators/sim_env/models/dumpster/model-1_4.sdf b/simulators/sim_env/models/dumpster/model-1_4.sdf new file mode 100755 index 0000000..cdc66f1 --- /dev/null +++ b/simulators/sim_env/models/dumpster/model-1_4.sdf @@ -0,0 +1,28 @@ + + + + + + + + model://dumpster/meshes/dumpster.dae + + + + + + + model://dumpster/meshes/dumpster.dae + + + + + + + + + diff --git a/simulators/sim_env/models/dumpster/model.config b/simulators/sim_env/models/dumpster/model.config new file mode 100755 index 0000000..27cc821 --- /dev/null +++ b/simulators/sim_env/models/dumpster/model.config @@ -0,0 +1,24 @@ + + + + Dumpster + 1.0 + model-1_3.sdf + model-1_4.sdf + model.sdf + + + Cole Biesemeyer + cole.bsmr@gmail.com + + + + Nate Koenig + natekoenig@gmail.com + + + + A dumpster. + + + diff --git a/simulators/sim_env/models/dumpster/model.sdf b/simulators/sim_env/models/dumpster/model.sdf new file mode 100755 index 0000000..bb505f8 --- /dev/null +++ b/simulators/sim_env/models/dumpster/model.sdf @@ -0,0 +1,30 @@ + + + + + + + + 1.5 1.5 1.5 + model://dumpster/meshes/dumpster.dae + + + + + + + 1.5 1.5 1.5 + model://dumpster/meshes/dumpster.dae + + + + + + + + + diff --git a/simulators/sim_env/models/dumpster/thumbnails/1.png b/simulators/sim_env/models/dumpster/thumbnails/1.png new file mode 100755 index 0000000..c0e53a2 Binary files /dev/null and b/simulators/sim_env/models/dumpster/thumbnails/1.png differ diff --git a/simulators/sim_env/models/dumpster/thumbnails/2.png b/simulators/sim_env/models/dumpster/thumbnails/2.png new file mode 100755 index 0000000..1516378 Binary files /dev/null and b/simulators/sim_env/models/dumpster/thumbnails/2.png differ diff --git a/simulators/sim_env/models/dumpster/thumbnails/3.png b/simulators/sim_env/models/dumpster/thumbnails/3.png new file mode 100755 index 0000000..60af9e3 Binary files /dev/null and b/simulators/sim_env/models/dumpster/thumbnails/3.png differ diff --git a/simulators/sim_env/models/dumpster/thumbnails/4.png b/simulators/sim_env/models/dumpster/thumbnails/4.png new file mode 100755 index 0000000..1fd3be9 Binary files /dev/null and b/simulators/sim_env/models/dumpster/thumbnails/4.png differ diff --git a/simulators/sim_env/models/dumpster/thumbnails/5.png b/simulators/sim_env/models/dumpster/thumbnails/5.png new file mode 100755 index 0000000..fa6a893 Binary files /dev/null and b/simulators/sim_env/models/dumpster/thumbnails/5.png differ diff --git a/simulators/sim_env/models/shipping_container_conveyor_ariac/materials/textures/ShippingContainer.png b/simulators/sim_env/models/shipping_container_conveyor_ariac/materials/textures/ShippingContainer.png new file mode 100755 index 0000000..0ec6e8d Binary files /dev/null and b/simulators/sim_env/models/shipping_container_conveyor_ariac/materials/textures/ShippingContainer.png differ diff --git a/simulators/sim_env/models/shipping_container_conveyor_ariac/meshes/ShippingContainer_Textured.mtl b/simulators/sim_env/models/shipping_container_conveyor_ariac/meshes/ShippingContainer_Textured.mtl new file mode 100755 index 0000000..4caf9e1 --- /dev/null +++ b/simulators/sim_env/models/shipping_container_conveyor_ariac/meshes/ShippingContainer_Textured.mtl @@ -0,0 +1,16 @@ +# 3ds Max Wavefront OBJ Exporter v0.97b - (c)2007 guruware +# File Created: 19.01.2018 17:10:24 + +newmtl ShippingContainer + Ns 10.0000 + Ni 1.5000 + d 1.0000 + Tr 0.0000 + Tf 1.0000 1.0000 1.0000 + illum 2 + Ka 0.5882 0.5882 0.5882 + Kd 0.5882 0.5882 0.5882 + Ks 0.0000 0.0000 0.0000 + Ke 0.0000 0.0000 0.0000 + map_Ka ShippingContainer.png + map_Kd ShippingContainer.png diff --git a/simulators/sim_env/models/shipping_container_conveyor_ariac/meshes/ShippingContainer_Textured.obj b/simulators/sim_env/models/shipping_container_conveyor_ariac/meshes/ShippingContainer_Textured.obj new file mode 100755 index 0000000..e1c71c7 --- /dev/null +++ b/simulators/sim_env/models/shipping_container_conveyor_ariac/meshes/ShippingContainer_Textured.obj @@ -0,0 +1,23779 @@ +H +# 3ds Max Wavefront OBJ Exporter v0.97b - (c)2007 guruware +# File Created: 19.01.2018 17:10:24 + +mtllib ShippingContainer_Textured.mtl + +# +# object Bins +# + +v -1.2393 -3.3319 0.2962 +v -1.2160 -3.3319 0.3986 +v -1.2160 -2.2041 0.3986 +v -1.2393 -2.2041 0.2962 +v -0.6966 -2.2041 0.2101 +v -0.7048 -2.2041 0.1743 +v -0.6966 -3.3319 0.2101 +v -0.7048 -3.3319 0.1743 +v -1.1814 -3.2991 0.3907 +v -0.7312 -3.2991 0.2180 +v -0.7366 -3.2991 0.1943 +v -1.2020 -3.2991 0.3004 +v -1.1814 -2.2369 0.3907 +v -0.7312 -2.2369 0.2180 +v -0.7366 -2.2369 0.1943 +v -1.2020 -2.2369 0.3004 +v -1.2393 -3.3319 0.9862 +v -1.2160 -3.3319 1.0886 +v -1.2160 -2.2041 1.0886 +v -1.2393 -2.2041 0.9862 +v -0.6966 -2.2041 0.9001 +v -0.7048 -2.2041 0.8643 +v -0.6966 -3.3319 0.9001 +v -0.7048 -3.3319 0.8643 +v -1.1814 -3.2991 1.0807 +v -0.7312 -3.2991 0.9080 +v -0.7366 -3.2991 0.8843 +v -1.2020 -3.2991 0.9904 +v -1.1814 -2.2369 1.0807 +v -0.7312 -2.2369 0.9080 +v -0.7366 -2.2369 0.8843 +v -1.2020 -2.2369 0.9904 +v -1.2393 -2.1703 0.2962 +v -1.2160 -2.1703 0.3986 +v -1.2160 -1.0424 0.3986 +v -1.2393 -1.0424 0.2962 +v -0.6966 -1.0424 0.2101 +v -0.7048 -1.0424 0.1743 +v -0.6966 -2.1703 0.2101 +v -0.7048 -2.1703 0.1743 +v -1.1814 -2.1375 0.3907 +v -0.7312 -2.1375 0.2180 +v -0.7366 -2.1375 0.1943 +v -1.2020 -2.1375 0.3004 +v -1.1814 -1.0752 0.3907 +v -0.7312 -1.0752 0.2180 +v -0.7366 -1.0752 0.1943 +v -1.2020 -1.0752 0.3004 +v -1.2393 -2.1703 0.9862 +v -1.2160 -2.1703 1.0886 +v -1.2160 -1.0424 1.0886 +v -1.2393 -1.0424 0.9862 +v -0.6966 -1.0424 0.9001 +v -0.7048 -1.0424 0.8643 +v -0.6966 -2.1703 0.9001 +v -0.7048 -2.1703 0.8643 +v -1.1814 -2.1375 1.0807 +v -0.7312 -2.1375 0.9080 +v -0.7366 -2.1375 0.8843 +v -1.2020 -2.1375 0.9904 +v -1.1814 -1.0752 1.0807 +v -0.7312 -1.0752 0.9080 +v -0.7366 -1.0752 0.8843 +v -1.2020 -1.0752 0.9904 +v -1.2393 -1.0086 0.2962 +v -1.2160 -1.0086 0.3986 +v -1.2160 0.1192 0.3986 +v -1.2393 0.1192 0.2962 +v -0.6966 0.1192 0.2101 +v -0.7048 0.1192 0.1743 +v -0.6966 -1.0086 0.2101 +v -0.7048 -1.0086 0.1743 +v -1.1814 -0.9758 0.3907 +v -0.7312 -0.9758 0.2180 +v -0.7366 -0.9758 0.1943 +v -1.2020 -0.9758 0.3004 +v -1.1814 0.0865 0.3907 +v -0.7312 0.0865 0.2180 +v -0.7366 0.0865 0.1943 +v -1.2020 0.0865 0.3004 +v -1.2393 -1.0086 0.9862 +v -1.2160 -1.0086 1.0886 +v -1.2160 0.1192 1.0886 +v -1.2393 0.1192 0.9862 +v -0.6966 0.1192 0.9001 +v -0.7048 0.1192 0.8643 +v -0.6966 -1.0086 0.9001 +v -0.7048 -1.0086 0.8643 +v -1.1814 -0.9758 1.0807 +v -0.7312 -0.9758 0.9080 +v -0.7366 -0.9758 0.8843 +v -1.2020 -0.9758 0.9904 +v -1.1814 0.0865 1.0807 +v -0.7312 0.0865 0.9080 +v -0.7366 0.0865 0.8843 +v -1.2020 0.0865 0.9904 +v -1.2393 0.1531 0.2962 +v -1.2160 0.1531 0.3986 +v -1.2160 1.2809 0.3986 +v -1.2393 1.2809 0.2962 +v -0.6966 1.2809 0.2101 +v -0.7048 1.2809 0.1743 +v -0.6966 0.1531 0.2101 +v -0.7048 0.1531 0.1743 +v -1.1814 0.1859 0.3907 +v -0.7312 0.1859 0.2180 +v -0.7366 0.1859 0.1943 +v -1.2020 0.1859 0.3004 +v -1.1814 1.2481 0.3907 +v -0.7312 1.2481 0.2180 +v -0.7366 1.2481 0.1943 +v -1.2020 1.2481 0.3004 +v -1.2393 0.1531 0.9862 +v -1.2160 0.1531 1.0886 +v -1.2160 1.2809 1.0886 +v -1.2393 1.2809 0.9862 +v -0.6966 1.2809 0.9001 +v -0.7048 1.2809 0.8643 +v -0.6966 0.1531 0.9001 +v -0.7048 0.1531 0.8643 +v -1.1814 0.1859 1.0807 +v -0.7312 0.1859 0.9080 +v -0.7366 0.1859 0.8843 +v -1.2020 0.1859 0.9904 +v -1.1814 1.2481 1.0807 +v -0.7312 1.2481 0.9080 +v -0.7366 1.2481 0.8843 +v -1.2020 1.2481 0.9904 +v -1.2393 1.3147 0.2962 +v -1.2160 1.3147 0.3986 +v -1.2160 2.4426 0.3986 +v -1.2393 2.4426 0.2962 +v -0.6966 2.4426 0.2101 +v -0.7048 2.4426 0.1743 +v -0.6966 1.3147 0.2101 +v -0.7048 1.3147 0.1743 +v -1.1814 1.3475 0.3907 +v -0.7312 1.3475 0.2180 +v -0.7366 1.3475 0.1943 +v -1.2020 1.3475 0.3004 +v -1.1814 2.4098 0.3907 +v -0.7312 2.4098 0.2180 +v -0.7366 2.4098 0.1943 +v -1.2020 2.4098 0.3004 +v -1.2393 1.3147 0.9862 +v -1.2160 1.3147 1.0886 +v -1.2160 2.4426 1.0886 +v -1.2393 2.4426 0.9862 +v -0.6966 2.4426 0.9001 +v -0.7048 2.4426 0.8643 +v -0.6966 1.3147 0.9001 +v -0.7048 1.3147 0.8643 +v -1.1814 1.3475 1.0807 +v -0.7312 1.3475 0.9080 +v -0.7366 1.3475 0.8843 +v -1.2020 1.3475 0.9904 +v -1.1814 2.4098 1.0807 +v -0.7312 2.4098 0.9080 +v -0.7366 2.4098 0.8843 +v -1.2020 2.4098 0.9904 +v -1.2393 2.4764 0.2962 +v -1.2160 2.4764 0.3986 +v -1.2160 3.6042 0.3986 +v -1.2393 3.6042 0.2962 +v -0.6966 3.6042 0.2101 +v -0.7048 3.6042 0.1743 +v -0.6966 2.4764 0.2101 +v -0.7048 2.4764 0.1743 +v -1.1814 2.5092 0.3907 +v -0.7312 2.5092 0.2180 +v -0.7366 2.5092 0.1943 +v -1.2020 2.5092 0.3004 +v -1.1814 3.5715 0.3907 +v -0.7312 3.5715 0.2180 +v -0.7366 3.5715 0.1943 +v -1.2020 3.5715 0.3004 +v -1.2393 2.4764 0.9862 +v -1.2160 2.4764 1.0886 +v -1.2160 3.6042 1.0886 +v -1.2393 3.6042 0.9862 +v -0.6966 3.6042 0.9001 +v -0.7048 3.6042 0.8643 +v -0.6966 2.4764 0.9001 +v -0.7048 2.4764 0.8643 +v -1.1814 2.5092 1.0807 +v -0.7312 2.5092 0.9080 +v -0.7366 2.5092 0.8843 +v -1.2020 2.5092 0.9904 +v -1.1814 3.5715 1.0807 +v -0.7312 3.5715 0.9080 +v -0.7366 3.5715 0.8843 +v -1.2020 3.5715 0.9904 +v -1.2393 3.6381 0.2962 +v -1.2160 3.6381 0.3986 +v -1.2160 4.7659 0.3986 +v -1.2393 4.7659 0.2962 +v -0.6966 4.7659 0.2101 +v -0.7048 4.7659 0.1743 +v -0.6966 3.6381 0.2101 +v -0.7048 3.6381 0.1743 +v -1.1814 3.6709 0.3907 +v -0.7312 3.6709 0.2180 +v -0.7366 3.6709 0.1943 +v -1.2020 3.6709 0.3004 +v -1.1814 4.7331 0.3907 +v -0.7312 4.7331 0.2180 +v -0.7366 4.7331 0.1943 +v -1.2020 4.7331 0.3004 +v -1.2393 3.6381 0.9862 +v -1.2160 3.6381 1.0886 +v -1.2160 4.7659 1.0886 +v -1.2393 4.7659 0.9862 +v -0.6966 4.7659 0.9001 +v -0.7048 4.7659 0.8643 +v -0.6966 3.6381 0.9001 +v -0.7048 3.6381 0.8643 +v -1.1814 3.6709 1.0807 +v -0.7312 3.6709 0.9080 +v -0.7366 3.6709 0.8843 +v -1.2020 3.6709 0.9904 +v -1.1814 4.7331 1.0807 +v -0.7312 4.7331 0.9080 +v -0.7366 4.7331 0.8843 +v -1.2020 4.7331 0.9904 +v -1.2393 4.7997 0.2962 +v -1.2160 4.7997 0.3986 +v -1.2160 5.9276 0.3986 +v -1.2393 5.9276 0.2962 +v -0.6966 5.9276 0.2101 +v -0.7048 5.9276 0.1743 +v -0.6966 4.7997 0.2101 +v -0.7048 4.7997 0.1743 +v -1.1814 4.8325 0.3907 +v -0.7312 4.8325 0.2180 +v -0.7366 4.8325 0.1943 +v -1.2020 4.8325 0.3004 +v -1.1814 5.8948 0.3907 +v -0.7312 5.8948 0.2180 +v -0.7366 5.8948 0.1943 +v -1.2020 5.8948 0.3004 +v -1.2393 4.7997 0.9862 +v -1.2160 4.7997 1.0886 +v -1.2160 5.9276 1.0886 +v -1.2393 5.9276 0.9862 +v -0.6966 5.9276 0.9001 +v -0.7048 5.9276 0.8643 +v -0.6966 4.7997 0.9001 +v -0.7048 4.7997 0.8643 +v -1.1814 4.8325 1.0807 +v -0.7312 4.8325 0.9080 +v -0.7366 4.8325 0.8843 +v -1.2020 4.8325 0.9904 +v -1.1814 5.8948 1.0807 +v -0.7312 5.8948 0.9080 +v -0.7366 5.8948 0.8843 +v -1.2020 5.8948 0.9904 +v -1.2393 5.9614 0.2962 +v -1.2160 5.9614 0.3986 +v -1.2160 7.0892 0.3986 +v -1.2393 7.0892 0.2962 +v -0.6966 7.0892 0.2101 +v -0.7048 7.0892 0.1743 +v -0.6966 5.9614 0.2101 +v -0.7048 5.9614 0.1743 +v -1.1814 5.9942 0.3907 +v -0.7312 5.9942 0.2180 +v -0.7366 5.9942 0.1943 +v -1.2020 5.9942 0.3004 +v -1.1814 7.0565 0.3907 +v -0.7312 7.0565 0.2180 +v -0.7366 7.0565 0.1943 +v -1.2020 7.0565 0.3004 +v -1.2393 5.9614 0.9862 +v -1.2160 5.9614 1.0886 +v -1.2160 7.0892 1.0886 +v -1.2393 7.0892 0.9862 +v -0.6966 7.0892 0.9001 +v -0.7048 7.0892 0.8643 +v -0.6966 5.9614 0.9001 +v -0.7048 5.9614 0.8643 +v -1.1814 5.9942 1.0807 +v -0.7312 5.9942 0.9080 +v -0.7366 5.9942 0.8843 +v -1.2020 5.9942 0.9904 +v -1.1814 7.0565 1.0807 +v -0.7312 7.0565 0.9080 +v -0.7366 7.0565 0.8843 +v -1.2020 7.0565 0.9904 +v -1.2393 7.1231 0.2962 +v -1.2160 7.1231 0.3986 +v -1.2160 8.2509 0.3986 +v -1.2393 8.2509 0.2962 +v -0.6966 8.2509 0.2101 +v -0.7048 8.2509 0.1743 +v -0.6966 7.1231 0.2101 +v -0.7048 7.1231 0.1743 +v -1.1814 7.1559 0.3907 +v -0.7312 7.1559 0.2180 +v -0.7366 7.1559 0.1943 +v -1.2020 7.1559 0.3004 +v -1.1814 8.2181 0.3907 +v -0.7312 8.2181 0.2180 +v -0.7366 8.2181 0.1943 +v -1.2020 8.2181 0.3004 +v -1.2393 7.1231 0.9862 +v -1.2160 7.1231 1.0886 +v -1.2160 8.2509 1.0886 +v -1.2393 8.2509 0.9862 +v -0.6966 8.2509 0.9001 +v -0.7048 8.2509 0.8643 +v -0.6966 7.1231 0.9001 +v -0.7048 7.1231 0.8643 +v -1.1814 7.1559 1.0807 +v -0.7312 7.1559 0.9080 +v -0.7366 7.1559 0.8843 +v -1.2020 7.1559 0.9904 +v -1.1814 8.2181 1.0807 +v -0.7312 8.2181 0.9080 +v -0.7366 8.2181 0.8843 +v -1.2020 8.2181 0.9904 +v -1.2393 -3.3319 1.6762 +v -1.2160 -3.3319 1.7786 +v -1.2160 -2.2041 1.7786 +v -1.2393 -2.2041 1.6762 +v -0.6966 -2.2041 1.5901 +v -0.7048 -2.2041 1.5543 +v -0.6966 -3.3319 1.5901 +v -0.7048 -3.3319 1.5543 +v -1.1814 -3.2991 1.7707 +v -0.7312 -3.2991 1.5979 +v -0.7366 -3.2991 1.5743 +v -1.2020 -3.2991 1.6804 +v -1.1814 -2.2369 1.7707 +v -0.7312 -2.2369 1.5980 +v -0.7366 -2.2369 1.5743 +v -1.2020 -2.2369 1.6804 +v -1.2393 -2.1703 1.6762 +v -1.2160 -2.1703 1.7786 +v -1.2160 -1.0424 1.7786 +v -1.2393 -1.0424 1.6762 +v -0.6966 -1.0424 1.5901 +v -0.7048 -1.0424 1.5543 +v -0.6966 -2.1703 1.5901 +v -0.7048 -2.1703 1.5543 +v -1.1814 -2.1375 1.7707 +v -0.7312 -2.1375 1.5980 +v -0.7366 -2.1375 1.5743 +v -1.2020 -2.1375 1.6804 +v -1.1814 -1.0752 1.7707 +v -0.7312 -1.0752 1.5980 +v -0.7366 -1.0752 1.5743 +v -1.2020 -1.0752 1.6804 +v -1.2393 -1.0086 1.6762 +v -1.2160 -1.0086 1.7786 +v -1.2160 0.1192 1.7786 +v -1.2393 0.1192 1.6762 +v -0.6966 0.1192 1.5901 +v -0.7048 0.1192 1.5543 +v -0.6966 -1.0086 1.5901 +v -0.7048 -1.0086 1.5543 +v -1.1814 -0.9758 1.7707 +v -0.7312 -0.9758 1.5980 +v -0.7366 -0.9758 1.5743 +v -1.2020 -0.9758 1.6804 +v -1.1814 0.0865 1.7707 +v -0.7312 0.0865 1.5980 +v -0.7366 0.0865 1.5743 +v -1.2020 0.0865 1.6804 +v -1.2393 0.1531 1.6762 +v -1.2160 0.1531 1.7786 +v -1.2160 1.2809 1.7786 +v -1.2393 1.2809 1.6762 +v -0.6966 1.2809 1.5901 +v -0.7048 1.2809 1.5543 +v -0.6966 0.1531 1.5901 +v -0.7048 0.1531 1.5543 +v -1.1814 0.1859 1.7707 +v -0.7312 0.1859 1.5980 +v -0.7366 0.1859 1.5743 +v -1.2020 0.1859 1.6804 +v -1.1814 1.2481 1.7707 +v -0.7312 1.2481 1.5980 +v -0.7366 1.2481 1.5743 +v -1.2020 1.2481 1.6804 +v -1.2393 1.3147 1.6762 +v -1.2160 1.3147 1.7786 +v -1.2160 2.4426 1.7786 +v -1.2393 2.4426 1.6762 +v -0.6966 2.4426 1.5901 +v -0.7048 2.4426 1.5543 +v -0.6966 1.3147 1.5901 +v -0.7048 1.3147 1.5543 +v -1.1814 1.3475 1.7707 +v -0.7312 1.3475 1.5980 +v -0.7366 1.3475 1.5743 +v -1.2020 1.3475 1.6804 +v -1.1814 2.4098 1.7707 +v -0.7312 2.4098 1.5980 +v -0.7366 2.4098 1.5743 +v -1.2020 2.4098 1.6804 +v -1.2393 2.4764 1.6762 +v -1.2160 2.4764 1.7786 +v -1.2160 3.6042 1.7786 +v -1.2393 3.6042 1.6762 +v -0.6966 3.6042 1.5901 +v -0.7048 3.6042 1.5543 +v -0.6966 2.4764 1.5901 +v -0.7048 2.4764 1.5543 +v -1.1814 2.5092 1.7707 +v -0.7312 2.5092 1.5980 +v -0.7366 2.5092 1.5743 +v -1.2020 2.5092 1.6804 +v -1.1814 3.5715 1.7707 +v -0.7312 3.5715 1.5980 +v -0.7366 3.5715 1.5743 +v -1.2020 3.5715 1.6804 +v -1.2393 3.6381 1.6762 +v -1.2160 3.6381 1.7786 +v -1.2160 4.7659 1.7786 +v -1.2393 4.7659 1.6762 +v -0.6966 4.7659 1.5901 +v -0.7048 4.7659 1.5543 +v -0.6966 3.6381 1.5901 +v -0.7048 3.6381 1.5543 +v -1.1814 3.6709 1.7707 +v -0.7312 3.6709 1.5980 +v -0.7366 3.6709 1.5743 +v -1.2020 3.6709 1.6804 +v -1.1814 4.7331 1.7707 +v -0.7312 4.7331 1.5980 +v -0.7366 4.7331 1.5743 +v -1.2020 4.7331 1.6804 +v -1.2393 4.7997 1.6762 +v -1.2160 4.7997 1.7786 +v -1.2160 5.9276 1.7786 +v -1.2393 5.9276 1.6762 +v -0.6966 5.9276 1.5901 +v -0.7048 5.9276 1.5543 +v -0.6966 4.7997 1.5901 +v -0.7048 4.7997 1.5543 +v -1.1814 4.8325 1.7707 +v -0.7312 4.8325 1.5980 +v -0.7366 4.8325 1.5743 +v -1.2020 4.8325 1.6804 +v -1.1814 5.8948 1.7707 +v -0.7312 5.8948 1.5980 +v -0.7366 5.8948 1.5743 +v -1.2020 5.8948 1.6804 +v -1.2393 5.9614 1.6762 +v -1.2160 5.9614 1.7786 +v -1.2160 7.0892 1.7786 +v -1.2393 7.0892 1.6762 +v -0.6966 7.0892 1.5901 +v -0.7048 7.0892 1.5543 +v -0.6966 5.9614 1.5901 +v -0.7048 5.9614 1.5543 +v -1.1814 5.9942 1.7707 +v -0.7312 5.9942 1.5980 +v -0.7366 5.9942 1.5743 +v -1.2020 5.9942 1.6804 +v -1.1814 7.0565 1.7707 +v -0.7312 7.0565 1.5980 +v -0.7366 7.0565 1.5743 +v -1.2020 7.0565 1.6804 +v -1.2393 7.1231 1.6762 +v -1.2160 7.1231 1.7786 +v -1.2160 8.2509 1.7786 +v -1.2393 8.2509 1.6762 +v -0.6966 8.2509 1.5901 +v -0.7048 8.2509 1.5543 +v -0.6966 7.1231 1.5901 +v -0.7048 7.1231 1.5543 +v -1.1814 7.1559 1.7707 +v -0.7312 7.1559 1.5980 +v -0.7366 7.1559 1.5743 +v -1.2020 7.1559 1.6804 +v -1.1814 8.2181 1.7707 +v -0.7312 8.2181 1.5980 +v -0.7366 8.2181 1.5743 +v -1.2020 8.2181 1.6804 +# 480 vertices + +vn -0.9750 -0.0000 0.2222 +vn 0.0000 1.0000 0.0000 +vn 0.9750 0.0000 -0.2222 +vn 0.0000 -1.0000 0.0000 +vn -0.2222 0.0000 -0.9750 +vn 0.2222 -0.0000 0.9750 +vn 0.3491 0.0000 0.9371 +vn 0.2223 -0.0000 0.9750 +vn 0.3491 -0.0000 0.9371 +vn -0.0000 1.0000 0.0000 +vn 0.0000 -1.0000 -0.0000 +vn -0.0000 -1.0000 -0.0000 +# 12 vertex normals + +vt 0.6653 0.3563 0.0000 +vt 0.6658 0.3593 0.0000 +vt 0.6658 0.3593 0.0000 +vt 0.6653 0.3563 0.0000 +vt 0.6766 0.3539 0.0000 +vt 0.6764 0.3528 0.0000 +vt 0.6766 0.3539 0.0000 +vt 0.6764 0.3528 0.0000 +vt 0.6665 0.3591 0.0000 +vt 0.6758 0.3541 0.0000 +vt 0.6757 0.3534 0.0000 +vt 0.6661 0.3565 0.0000 +vt 0.6665 0.3591 0.0000 +vt 0.6758 0.3541 0.0000 +vt 0.6757 0.3534 0.0000 +vt 0.6661 0.3565 0.0000 +vt 0.6653 0.3762 0.0000 +vt 0.6658 0.3792 0.0000 +vt 0.6658 0.3792 0.0000 +vt 0.6653 0.3762 0.0000 +vt 0.6766 0.3738 0.0000 +vt 0.6764 0.3727 0.0000 +vt 0.6766 0.3738 0.0000 +vt 0.6764 0.3727 0.0000 +vt 0.6665 0.3790 0.0000 +vt 0.6758 0.3740 0.0000 +vt 0.6757 0.3733 0.0000 +vt 0.6661 0.3764 0.0000 +vt 0.6665 0.3790 0.0000 +vt 0.6758 0.3740 0.0000 +vt 0.6757 0.3733 0.0000 +vt 0.6661 0.3764 0.0000 +vt 0.6653 0.3563 0.0000 +vt 0.6658 0.3593 0.0000 +vt 0.6658 0.3593 0.0000 +vt 0.6653 0.3563 0.0000 +vt 0.6766 0.3539 0.0000 +vt 0.6764 0.3528 0.0000 +vt 0.6766 0.3539 0.0000 +vt 0.6764 0.3528 0.0000 +vt 0.6665 0.3591 0.0000 +vt 0.6758 0.3541 0.0000 +vt 0.6757 0.3534 0.0000 +vt 0.6661 0.3565 0.0000 +vt 0.6665 0.3591 0.0000 +vt 0.6758 0.3541 0.0000 +vt 0.6757 0.3534 0.0000 +vt 0.6661 0.3565 0.0000 +vt 0.6653 0.3762 0.0000 +vt 0.6658 0.3792 0.0000 +vt 0.6658 0.3792 0.0000 +vt 0.6653 0.3762 0.0000 +vt 0.6766 0.3738 0.0000 +vt 0.6764 0.3727 0.0000 +vt 0.6766 0.3738 0.0000 +vt 0.6764 0.3727 0.0000 +vt 0.6665 0.3790 0.0000 +vt 0.6758 0.3740 0.0000 +vt 0.6757 0.3733 0.0000 +vt 0.6661 0.3764 0.0000 +vt 0.6665 0.3790 0.0000 +vt 0.6758 0.3740 0.0000 +vt 0.6757 0.3733 0.0000 +vt 0.6661 0.3764 0.0000 +vt 0.6653 0.3563 0.0000 +vt 0.6658 0.3593 0.0000 +vt 0.6658 0.3593 0.0000 +vt 0.6653 0.3563 0.0000 +vt 0.6766 0.3539 0.0000 +vt 0.6764 0.3528 0.0000 +vt 0.6766 0.3539 0.0000 +vt 0.6764 0.3528 0.0000 +vt 0.6665 0.3591 0.0000 +vt 0.6758 0.3541 0.0000 +vt 0.6757 0.3534 0.0000 +vt 0.6661 0.3565 0.0000 +vt 0.6665 0.3591 0.0000 +vt 0.6758 0.3541 0.0000 +vt 0.6757 0.3534 0.0000 +vt 0.6661 0.3565 0.0000 +vt 0.6653 0.3762 0.0000 +vt 0.6658 0.3792 0.0000 +vt 0.6658 0.3792 0.0000 +vt 0.6653 0.3762 0.0000 +vt 0.6766 0.3738 0.0000 +vt 0.6764 0.3727 0.0000 +vt 0.6766 0.3738 0.0000 +vt 0.6764 0.3727 0.0000 +vt 0.6665 0.3790 0.0000 +vt 0.6758 0.3740 0.0000 +vt 0.6757 0.3733 0.0000 +vt 0.6661 0.3764 0.0000 +vt 0.6665 0.3790 0.0000 +vt 0.6758 0.3740 0.0000 +vt 0.6757 0.3733 0.0000 +vt 0.6661 0.3764 0.0000 +vt 0.6653 0.3563 0.0000 +vt 0.6658 0.3593 0.0000 +vt 0.6658 0.3593 0.0000 +vt 0.6653 0.3563 0.0000 +vt 0.6766 0.3539 0.0000 +vt 0.6764 0.3528 0.0000 +vt 0.6766 0.3539 0.0000 +vt 0.6764 0.3528 0.0000 +vt 0.6665 0.3591 0.0000 +vt 0.6758 0.3541 0.0000 +vt 0.6757 0.3534 0.0000 +vt 0.6661 0.3565 0.0000 +vt 0.6665 0.3591 0.0000 +vt 0.6758 0.3541 0.0000 +vt 0.6757 0.3534 0.0000 +vt 0.6661 0.3565 0.0000 +vt 0.6653 0.3762 0.0000 +vt 0.6658 0.3792 0.0000 +vt 0.6658 0.3792 0.0000 +vt 0.6653 0.3762 0.0000 +vt 0.6766 0.3738 0.0000 +vt 0.6764 0.3727 0.0000 +vt 0.6766 0.3738 0.0000 +vt 0.6764 0.3727 0.0000 +vt 0.6665 0.3790 0.0000 +vt 0.6758 0.3740 0.0000 +vt 0.6757 0.3733 0.0000 +vt 0.6661 0.3764 0.0000 +vt 0.6665 0.3790 0.0000 +vt 0.6758 0.3740 0.0000 +vt 0.6757 0.3733 0.0000 +vt 0.6661 0.3764 0.0000 +vt 0.6653 0.3563 0.0000 +vt 0.6658 0.3593 0.0000 +vt 0.6658 0.3593 0.0000 +vt 0.6653 0.3563 0.0000 +vt 0.6766 0.3539 0.0000 +vt 0.6764 0.3528 0.0000 +vt 0.6766 0.3539 0.0000 +vt 0.6764 0.3528 0.0000 +vt 0.6665 0.3591 0.0000 +vt 0.6758 0.3541 0.0000 +vt 0.6757 0.3534 0.0000 +vt 0.6661 0.3565 0.0000 +vt 0.6665 0.3591 0.0000 +vt 0.6758 0.3541 0.0000 +vt 0.6757 0.3534 0.0000 +vt 0.6661 0.3565 0.0000 +vt 0.6653 0.3762 0.0000 +vt 0.6658 0.3792 0.0000 +vt 0.6658 0.3792 0.0000 +vt 0.6653 0.3762 0.0000 +vt 0.6766 0.3738 0.0000 +vt 0.6764 0.3727 0.0000 +vt 0.6766 0.3738 0.0000 +vt 0.6764 0.3727 0.0000 +vt 0.6665 0.3790 0.0000 +vt 0.6758 0.3740 0.0000 +vt 0.6757 0.3733 0.0000 +vt 0.6661 0.3764 0.0000 +vt 0.6665 0.3790 0.0000 +vt 0.6758 0.3740 0.0000 +vt 0.6757 0.3733 0.0000 +vt 0.6661 0.3764 0.0000 +vt 0.6653 0.3563 0.0000 +vt 0.6658 0.3593 0.0000 +vt 0.6658 0.3593 0.0000 +vt 0.6653 0.3563 0.0000 +vt 0.6766 0.3539 0.0000 +vt 0.6764 0.3528 0.0000 +vt 0.6766 0.3539 0.0000 +vt 0.6764 0.3528 0.0000 +vt 0.6665 0.3591 0.0000 +vt 0.6758 0.3541 0.0000 +vt 0.6757 0.3534 0.0000 +vt 0.6661 0.3565 0.0000 +vt 0.6665 0.3591 0.0000 +vt 0.6758 0.3541 0.0000 +vt 0.6757 0.3534 0.0000 +vt 0.6661 0.3565 0.0000 +vt 0.6653 0.3762 0.0000 +vt 0.6658 0.3792 0.0000 +vt 0.6658 0.3792 0.0000 +vt 0.6653 0.3762 0.0000 +vt 0.6766 0.3738 0.0000 +vt 0.6764 0.3727 0.0000 +vt 0.6766 0.3738 0.0000 +vt 0.6764 0.3727 0.0000 +vt 0.6665 0.3790 0.0000 +vt 0.6758 0.3740 0.0000 +vt 0.6757 0.3733 0.0000 +vt 0.6661 0.3764 0.0000 +vt 0.6665 0.3790 0.0000 +vt 0.6758 0.3740 0.0000 +vt 0.6757 0.3733 0.0000 +vt 0.6661 0.3764 0.0000 +vt 0.6653 0.3563 0.0000 +vt 0.6658 0.3593 0.0000 +vt 0.6658 0.3593 0.0000 +vt 0.6653 0.3563 0.0000 +vt 0.6766 0.3539 0.0000 +vt 0.6764 0.3528 0.0000 +vt 0.6766 0.3539 0.0000 +vt 0.6764 0.3528 0.0000 +vt 0.6665 0.3591 0.0000 +vt 0.6758 0.3541 0.0000 +vt 0.6757 0.3534 0.0000 +vt 0.6661 0.3565 0.0000 +vt 0.6665 0.3591 0.0000 +vt 0.6758 0.3541 0.0000 +vt 0.6757 0.3534 0.0000 +vt 0.6661 0.3565 0.0000 +vt 0.6653 0.3762 0.0000 +vt 0.6658 0.3792 0.0000 +vt 0.6658 0.3792 0.0000 +vt 0.6653 0.3762 0.0000 +vt 0.6766 0.3738 0.0000 +vt 0.6764 0.3727 0.0000 +vt 0.6766 0.3738 0.0000 +vt 0.6764 0.3727 0.0000 +vt 0.6665 0.3790 0.0000 +vt 0.6758 0.3740 0.0000 +vt 0.6757 0.3733 0.0000 +vt 0.6661 0.3764 0.0000 +vt 0.6665 0.3790 0.0000 +vt 0.6758 0.3740 0.0000 +vt 0.6757 0.3733 0.0000 +vt 0.6661 0.3764 0.0000 +vt 0.6653 0.3563 0.0000 +vt 0.6658 0.3593 0.0000 +vt 0.6658 0.3593 0.0000 +vt 0.6653 0.3563 0.0000 +vt 0.6766 0.3539 0.0000 +vt 0.6764 0.3528 0.0000 +vt 0.6766 0.3539 0.0000 +vt 0.6764 0.3528 0.0000 +vt 0.6665 0.3591 0.0000 +vt 0.6758 0.3541 0.0000 +vt 0.6757 0.3534 0.0000 +vt 0.6661 0.3565 0.0000 +vt 0.6665 0.3591 0.0000 +vt 0.6758 0.3541 0.0000 +vt 0.6757 0.3534 0.0000 +vt 0.6661 0.3565 0.0000 +vt 0.6653 0.3762 0.0000 +vt 0.6658 0.3792 0.0000 +vt 0.6658 0.3792 0.0000 +vt 0.6653 0.3762 0.0000 +vt 0.6766 0.3738 0.0000 +vt 0.6764 0.3727 0.0000 +vt 0.6766 0.3738 0.0000 +vt 0.6764 0.3727 0.0000 +vt 0.6665 0.3790 0.0000 +vt 0.6758 0.3740 0.0000 +vt 0.6757 0.3733 0.0000 +vt 0.6661 0.3764 0.0000 +vt 0.6665 0.3790 0.0000 +vt 0.6758 0.3740 0.0000 +vt 0.6757 0.3733 0.0000 +vt 0.6661 0.3764 0.0000 +vt 0.6653 0.3563 0.0000 +vt 0.6658 0.3593 0.0000 +vt 0.6658 0.3593 0.0000 +vt 0.6653 0.3563 0.0000 +vt 0.6766 0.3539 0.0000 +vt 0.6764 0.3528 0.0000 +vt 0.6766 0.3539 0.0000 +vt 0.6764 0.3528 0.0000 +vt 0.6665 0.3591 0.0000 +vt 0.6758 0.3541 0.0000 +vt 0.6757 0.3534 0.0000 +vt 0.6661 0.3565 0.0000 +vt 0.6665 0.3591 0.0000 +vt 0.6758 0.3541 0.0000 +vt 0.6757 0.3534 0.0000 +vt 0.6661 0.3565 0.0000 +vt 0.6653 0.3762 0.0000 +vt 0.6658 0.3792 0.0000 +vt 0.6658 0.3792 0.0000 +vt 0.6653 0.3762 0.0000 +vt 0.6766 0.3738 0.0000 +vt 0.6764 0.3727 0.0000 +vt 0.6766 0.3738 0.0000 +vt 0.6764 0.3727 0.0000 +vt 0.6665 0.3790 0.0000 +vt 0.6758 0.3740 0.0000 +vt 0.6757 0.3733 0.0000 +vt 0.6661 0.3764 0.0000 +vt 0.6665 0.3790 0.0000 +vt 0.6758 0.3740 0.0000 +vt 0.6757 0.3733 0.0000 +vt 0.6661 0.3764 0.0000 +vt 0.6653 0.3563 0.0000 +vt 0.6658 0.3593 0.0000 +vt 0.6658 0.3593 0.0000 +vt 0.6653 0.3563 0.0000 +vt 0.6766 0.3539 0.0000 +vt 0.6764 0.3528 0.0000 +vt 0.6766 0.3539 0.0000 +vt 0.6764 0.3528 0.0000 +vt 0.6665 0.3591 0.0000 +vt 0.6758 0.3541 0.0000 +vt 0.6757 0.3534 0.0000 +vt 0.6661 0.3565 0.0000 +vt 0.6665 0.3591 0.0000 +vt 0.6758 0.3541 0.0000 +vt 0.6757 0.3534 0.0000 +vt 0.6661 0.3565 0.0000 +vt 0.6653 0.3762 0.0000 +vt 0.6658 0.3792 0.0000 +vt 0.6658 0.3792 0.0000 +vt 0.6653 0.3762 0.0000 +vt 0.6766 0.3738 0.0000 +vt 0.6764 0.3727 0.0000 +vt 0.6766 0.3738 0.0000 +vt 0.6764 0.3727 0.0000 +vt 0.6665 0.3790 0.0000 +vt 0.6758 0.3740 0.0000 +vt 0.6757 0.3733 0.0000 +vt 0.6661 0.3764 0.0000 +vt 0.6665 0.3790 0.0000 +vt 0.6758 0.3740 0.0000 +vt 0.6757 0.3733 0.0000 +vt 0.6661 0.3764 0.0000 +vt 0.6653 0.3961 0.0000 +vt 0.6658 0.3991 0.0000 +vt 0.6658 0.3991 0.0000 +vt 0.6653 0.3961 0.0000 +vt 0.6766 0.3936 0.0000 +vt 0.6764 0.3926 0.0000 +vt 0.6766 0.3936 0.0000 +vt 0.6764 0.3926 0.0000 +vt 0.6665 0.3989 0.0000 +vt 0.6758 0.3939 0.0000 +vt 0.6757 0.3932 0.0000 +vt 0.6661 0.3962 0.0000 +vt 0.6665 0.3989 0.0000 +vt 0.6758 0.3939 0.0000 +vt 0.6757 0.3932 0.0000 +vt 0.6661 0.3962 0.0000 +vt 0.6653 0.3961 0.0000 +vt 0.6658 0.3991 0.0000 +vt 0.6658 0.3991 0.0000 +vt 0.6653 0.3961 0.0000 +vt 0.6766 0.3936 0.0000 +vt 0.6764 0.3926 0.0000 +vt 0.6766 0.3936 0.0000 +vt 0.6764 0.3926 0.0000 +vt 0.6665 0.3989 0.0000 +vt 0.6758 0.3939 0.0000 +vt 0.6757 0.3932 0.0000 +vt 0.6661 0.3962 0.0000 +vt 0.6665 0.3989 0.0000 +vt 0.6758 0.3939 0.0000 +vt 0.6757 0.3932 0.0000 +vt 0.6661 0.3962 0.0000 +vt 0.6653 0.3961 0.0000 +vt 0.6658 0.3991 0.0000 +vt 0.6658 0.3991 0.0000 +vt 0.6653 0.3961 0.0000 +vt 0.6766 0.3936 0.0000 +vt 0.6764 0.3926 0.0000 +vt 0.6766 0.3936 0.0000 +vt 0.6764 0.3926 0.0000 +vt 0.6665 0.3989 0.0000 +vt 0.6758 0.3939 0.0000 +vt 0.6757 0.3932 0.0000 +vt 0.6661 0.3962 0.0000 +vt 0.6665 0.3989 0.0000 +vt 0.6758 0.3939 0.0000 +vt 0.6757 0.3932 0.0000 +vt 0.6661 0.3962 0.0000 +vt 0.6653 0.3961 0.0000 +vt 0.6658 0.3991 0.0000 +vt 0.6658 0.3991 0.0000 +vt 0.6653 0.3961 0.0000 +vt 0.6766 0.3936 0.0000 +vt 0.6764 0.3926 0.0000 +vt 0.6766 0.3936 0.0000 +vt 0.6764 0.3926 0.0000 +vt 0.6665 0.3989 0.0000 +vt 0.6758 0.3939 0.0000 +vt 0.6757 0.3932 0.0000 +vt 0.6661 0.3962 0.0000 +vt 0.6665 0.3989 0.0000 +vt 0.6758 0.3939 0.0000 +vt 0.6757 0.3932 0.0000 +vt 0.6661 0.3962 0.0000 +vt 0.6653 0.3961 0.0000 +vt 0.6658 0.3991 0.0000 +vt 0.6658 0.3991 0.0000 +vt 0.6653 0.3961 0.0000 +vt 0.6766 0.3936 0.0000 +vt 0.6764 0.3926 0.0000 +vt 0.6766 0.3936 0.0000 +vt 0.6764 0.3926 0.0000 +vt 0.6665 0.3989 0.0000 +vt 0.6758 0.3939 0.0000 +vt 0.6757 0.3932 0.0000 +vt 0.6661 0.3962 0.0000 +vt 0.6665 0.3989 0.0000 +vt 0.6758 0.3939 0.0000 +vt 0.6757 0.3932 0.0000 +vt 0.6661 0.3962 0.0000 +vt 0.6653 0.3961 0.0000 +vt 0.6658 0.3991 0.0000 +vt 0.6658 0.3991 0.0000 +vt 0.6653 0.3961 0.0000 +vt 0.6766 0.3936 0.0000 +vt 0.6764 0.3926 0.0000 +vt 0.6766 0.3936 0.0000 +vt 0.6764 0.3926 0.0000 +vt 0.6665 0.3989 0.0000 +vt 0.6758 0.3939 0.0000 +vt 0.6757 0.3932 0.0000 +vt 0.6661 0.3962 0.0000 +vt 0.6665 0.3989 0.0000 +vt 0.6758 0.3939 0.0000 +vt 0.6757 0.3932 0.0000 +vt 0.6661 0.3962 0.0000 +vt 0.6653 0.3961 0.0000 +vt 0.6658 0.3991 0.0000 +vt 0.6658 0.3991 0.0000 +vt 0.6653 0.3961 0.0000 +vt 0.6766 0.3936 0.0000 +vt 0.6764 0.3926 0.0000 +vt 0.6766 0.3936 0.0000 +vt 0.6764 0.3926 0.0000 +vt 0.6665 0.3989 0.0000 +vt 0.6758 0.3939 0.0000 +vt 0.6757 0.3932 0.0000 +vt 0.6661 0.3962 0.0000 +vt 0.6665 0.3989 0.0000 +vt 0.6758 0.3939 0.0000 +vt 0.6757 0.3932 0.0000 +vt 0.6661 0.3962 0.0000 +vt 0.6653 0.3961 0.0000 +vt 0.6658 0.3991 0.0000 +vt 0.6658 0.3991 0.0000 +vt 0.6653 0.3961 0.0000 +vt 0.6766 0.3936 0.0000 +vt 0.6764 0.3926 0.0000 +vt 0.6766 0.3936 0.0000 +vt 0.6764 0.3926 0.0000 +vt 0.6665 0.3989 0.0000 +vt 0.6758 0.3939 0.0000 +vt 0.6757 0.3932 0.0000 +vt 0.6661 0.3962 0.0000 +vt 0.6665 0.3989 0.0000 +vt 0.6758 0.3939 0.0000 +vt 0.6757 0.3932 0.0000 +vt 0.6661 0.3962 0.0000 +vt 0.6653 0.3961 0.0000 +vt 0.6658 0.3991 0.0000 +vt 0.6658 0.3991 0.0000 +vt 0.6653 0.3961 0.0000 +vt 0.6766 0.3936 0.0000 +vt 0.6764 0.3926 0.0000 +vt 0.6766 0.3936 0.0000 +vt 0.6764 0.3926 0.0000 +vt 0.6665 0.3989 0.0000 +vt 0.6758 0.3939 0.0000 +vt 0.6757 0.3932 0.0000 +vt 0.6661 0.3962 0.0000 +vt 0.6665 0.3989 0.0000 +vt 0.6758 0.3939 0.0000 +vt 0.6757 0.3932 0.0000 +vt 0.6661 0.3962 0.0000 +vt 0.6653 0.3961 0.0000 +vt 0.6658 0.3991 0.0000 +vt 0.6658 0.3991 0.0000 +vt 0.6653 0.3961 0.0000 +vt 0.6766 0.3936 0.0000 +vt 0.6764 0.3926 0.0000 +vt 0.6766 0.3936 0.0000 +vt 0.6764 0.3926 0.0000 +vt 0.6665 0.3989 0.0000 +vt 0.6758 0.3939 0.0000 +vt 0.6757 0.3932 0.0000 +vt 0.6661 0.3962 0.0000 +vt 0.6665 0.3989 0.0000 +vt 0.6758 0.3939 0.0000 +vt 0.6757 0.3932 0.0000 +vt 0.6661 0.3962 0.0000 +# 480 texture coords + +# g Bins +# usemtl ShippingContainer +# s off +# f 1/1/1 2/2/1 3/3/1 4/4/1 +# f 4/4/2 3/3/2 5/5/2 6/6/2 +# f 6/6/3 5/5/3 7/7/3 8/8/3 +# f 8/8/4 7/7/4 2/2/4 1/1/4 +# f 4/4/5 6/6/5 8/8/5 1/1/5 +# f 9/9/2 10/10/2 11/11/2 12/12/2 +# f 9/9/6 13/13/6 3/3/6 2/2/6 +# f 13/13/7 14/14/7 5/5/7 3/3/7 +# f 14/14/8 10/10/8 7/7/8 5/5/8 +# f 10/10/9 9/9/9 2/2/9 7/7/9 +# f 15/15/6 16/16/6 12/12/6 11/11/6 +# f 14/14/4 13/13/4 16/16/4 15/15/4 +# f 10/10/1 14/14/1 15/15/1 11/11/1 +# f 13/13/3 9/9/3 12/12/3 16/16/3 +# f 17/17/1 18/18/1 19/19/1 20/20/1 +# f 20/20/2 19/19/2 21/21/2 22/22/2 +# f 22/22/3 21/21/3 23/23/3 24/24/3 +# f 24/24/4 23/23/4 18/18/4 17/17/4 +# f 20/20/5 22/22/5 24/24/5 17/17/5 +# f 25/25/2 26/26/2 27/27/2 28/28/2 +# f 25/25/8 29/29/8 19/19/8 18/18/8 +# f 29/29/9 30/30/9 21/21/9 19/19/9 +# f 30/30/6 26/26/6 23/23/6 21/21/6 +# f 26/26/7 25/25/7 18/18/7 23/23/7 +# f 31/31/6 32/32/6 28/28/6 27/27/6 +# f 30/30/4 29/29/4 32/32/4 31/31/4 +# f 26/26/1 30/30/1 31/31/1 27/27/1 +# f 29/29/3 25/25/3 28/28/3 32/32/3 +# f 33/33/1 34/34/1 35/35/1 36/36/1 +# f 36/36/2 35/35/2 37/37/2 38/38/2 +# f 38/38/3 37/37/3 39/39/3 40/40/3 +# f 40/40/4 39/39/4 34/34/4 33/33/4 +# f 36/36/5 38/38/5 40/40/5 33/33/5 +# f 41/41/2 42/42/2 43/43/2 44/44/2 +# f 41/41/6 45/45/6 35/35/6 34/34/6 +# f 45/45/7 46/46/7 37/37/7 35/35/7 +# f 46/46/8 42/42/8 39/39/8 37/37/8 +# f 42/42/9 41/41/9 34/34/9 39/39/9 +# f 47/47/6 48/48/6 44/44/6 43/43/6 +# f 46/46/4 45/45/4 48/48/4 47/47/4 +# f 42/42/1 46/46/1 47/47/1 43/43/1 +# f 45/45/3 41/41/3 44/44/3 48/48/3 +# f 49/49/1 50/50/1 51/51/1 52/52/1 +# f 52/52/2 51/51/2 53/53/2 54/54/2 +# f 54/54/3 53/53/3 55/55/3 56/56/3 +# f 56/56/4 55/55/4 50/50/4 49/49/4 +# f 52/52/5 54/54/5 56/56/5 49/49/5 +# f 57/57/2 58/58/2 59/59/2 60/60/2 +# f 57/57/8 61/61/8 51/51/8 50/50/8 +# f 61/61/9 62/62/9 53/53/9 51/51/9 +# f 62/62/6 58/58/6 55/55/6 53/53/6 +# f 58/58/7 57/57/7 50/50/7 55/55/7 +# f 63/63/6 64/64/6 60/60/6 59/59/6 +# f 62/62/4 61/61/4 64/64/4 63/63/4 +# f 58/58/1 62/62/1 63/63/1 59/59/1 +# f 61/61/3 57/57/3 60/60/3 64/64/3 +# f 65/65/1 66/66/1 67/67/1 68/68/1 +# f 68/68/10 67/67/10 69/69/10 70/70/10 +# f 70/70/3 69/69/3 71/71/3 72/72/3 +# f 72/72/11 71/71/11 66/66/11 65/65/11 +# f 68/68/5 70/70/5 72/72/5 65/65/5 +# f 73/73/10 74/74/10 75/75/10 76/76/10 +# f 73/73/6 77/77/6 67/67/6 66/66/6 +# f 77/77/7 78/78/7 69/69/7 67/67/7 +# f 78/78/8 74/74/8 71/71/8 69/69/8 +# f 74/74/9 73/73/9 66/66/9 71/71/9 +# f 79/79/6 80/80/6 76/76/6 75/75/6 +# f 78/78/11 77/77/11 80/80/11 79/79/11 +# f 74/74/1 78/78/1 79/79/1 75/75/1 +# f 77/77/3 73/73/3 76/76/3 80/80/3 +# f 81/81/1 82/82/1 83/83/1 84/84/1 +# f 84/84/2 83/83/2 85/85/2 86/86/2 +# f 86/86/3 85/85/3 87/87/3 88/88/3 +# f 88/88/4 87/87/4 82/82/4 81/81/4 +# f 84/84/5 86/86/5 88/88/5 81/81/5 +# f 89/89/2 90/90/2 91/91/2 92/92/2 +# f 89/89/8 93/93/8 83/83/8 82/82/8 +# f 93/93/9 94/94/9 85/85/9 83/83/9 +# f 94/94/6 90/90/6 87/87/6 85/85/6 +# f 90/90/7 89/89/7 82/82/7 87/87/7 +# f 95/95/6 96/96/6 92/92/6 91/91/6 +# f 94/94/12 93/93/12 96/96/12 95/95/12 +# f 90/90/1 94/94/1 95/95/1 91/91/1 +# f 93/93/3 89/89/3 92/92/3 96/96/3 +# f 97/97/1 98/98/1 99/99/1 100/100/1 +# f 100/100/10 99/99/10 101/101/10 102/102/10 +# f 102/102/3 101/101/3 103/103/3 104/104/3 +# f 104/104/11 103/103/11 98/98/11 97/97/11 +# f 100/100/5 102/102/5 104/104/5 97/97/5 +# f 105/105/10 106/106/10 107/107/10 108/108/10 +# f 105/105/6 109/109/6 99/99/6 98/98/6 +# f 109/109/7 110/110/7 101/101/7 99/99/7 +# f 110/110/8 106/106/8 103/103/8 101/101/8 +# f 106/106/9 105/105/9 98/98/9 103/103/9 +# f 111/111/6 112/112/6 108/108/6 107/107/6 +# f 110/110/11 109/109/11 112/112/11 111/111/11 +# f 106/106/1 110/110/1 111/111/1 107/107/1 +# f 109/109/3 105/105/3 108/108/3 112/112/3 +# f 113/113/1 114/114/1 115/115/1 116/116/1 +# f 116/116/2 115/115/2 117/117/2 118/118/2 +# f 118/118/3 117/117/3 119/119/3 120/120/3 +# f 120/120/11 119/119/11 114/114/11 113/113/11 +# f 116/116/5 118/118/5 120/120/5 113/113/5 +# f 121/121/10 122/122/10 123/123/10 124/124/10 +# f 121/121/8 125/125/8 115/115/8 114/114/8 +# f 125/125/9 126/126/9 117/117/9 115/115/9 +# f 126/126/6 122/122/6 119/119/6 117/117/6 +# f 122/122/7 121/121/7 114/114/7 119/119/7 +# f 127/127/6 128/128/6 124/124/6 123/123/6 +# f 126/126/4 125/125/4 128/128/4 127/127/4 +# f 122/122/1 126/126/1 127/127/1 123/123/1 +# f 125/125/3 121/121/3 124/124/3 128/128/3 +# f 129/129/1 130/130/1 131/131/1 132/132/1 +# f 132/132/2 131/131/2 133/133/2 134/134/2 +# f 134/134/3 133/133/3 135/135/3 136/136/3 +# f 136/136/11 135/135/11 130/130/11 129/129/11 +# f 132/132/5 134/134/5 136/136/5 129/129/5 +# f 137/137/10 138/138/10 139/139/10 140/140/10 +# f 137/137/6 141/141/6 131/131/6 130/130/6 +# f 141/141/7 142/142/7 133/133/7 131/131/7 +# f 142/142/8 138/138/8 135/135/8 133/133/8 +# f 138/138/9 137/137/9 130/130/9 135/135/9 +# f 143/143/6 144/144/6 140/140/6 139/139/6 +# f 142/142/4 141/141/4 144/144/4 143/143/4 +# f 138/138/1 142/142/1 143/143/1 139/139/1 +# f 141/141/3 137/137/3 140/140/3 144/144/3 +# f 145/145/1 146/146/1 147/147/1 148/148/1 +# f 148/148/2 147/147/2 149/149/2 150/150/2 +# f 150/150/3 149/149/3 151/151/3 152/152/3 +# f 152/152/12 151/151/12 146/146/12 145/145/12 +# f 148/148/5 150/150/5 152/152/5 145/145/5 +# f 153/153/2 154/154/2 155/155/2 156/156/2 +# f 153/153/8 157/157/8 147/147/8 146/146/8 +# f 157/157/9 158/158/9 149/149/9 147/147/9 +# f 158/158/6 154/154/6 151/151/6 149/149/6 +# f 154/154/7 153/153/7 146/146/7 151/151/7 +# f 159/159/6 160/160/6 156/156/6 155/155/6 +# f 158/158/4 157/157/4 160/160/4 159/159/4 +# f 154/154/1 158/158/1 159/159/1 155/155/1 +# f 157/157/3 153/153/3 156/156/3 160/160/3 +# f 161/161/1 162/162/1 163/163/1 164/164/1 +# f 164/164/2 163/163/2 165/165/2 166/166/2 +# f 166/166/3 165/165/3 167/167/3 168/168/3 +# f 168/168/4 167/167/4 162/162/4 161/161/4 +# f 164/164/5 166/166/5 168/168/5 161/161/5 +# f 169/169/2 170/170/2 171/171/2 172/172/2 +# f 169/169/6 173/173/6 163/163/6 162/162/6 +# f 173/173/7 174/174/7 165/165/7 163/163/7 +# f 174/174/8 170/170/8 167/167/8 165/165/8 +# f 170/170/9 169/169/9 162/162/9 167/167/9 +# f 175/175/6 176/176/6 172/172/6 171/171/6 +# f 174/174/4 173/173/4 176/176/4 175/175/4 +# f 170/170/1 174/174/1 175/175/1 171/171/1 +# f 173/173/3 169/169/3 172/172/3 176/176/3 +# f 177/177/1 178/178/1 179/179/1 180/180/1 +# f 180/180/2 179/179/2 181/181/2 182/182/2 +# f 182/182/3 181/181/3 183/183/3 184/184/3 +# f 184/184/4 183/183/4 178/178/4 177/177/4 +# f 180/180/5 182/182/5 184/184/5 177/177/5 +# f 185/185/2 186/186/2 187/187/2 188/188/2 +# f 185/185/8 189/189/8 179/179/8 178/178/8 +# f 189/189/9 190/190/9 181/181/9 179/179/9 +# f 190/190/6 186/186/6 183/183/6 181/181/6 +# f 186/186/7 185/185/7 178/178/7 183/183/7 +# f 191/191/6 192/192/6 188/188/6 187/187/6 +# f 190/190/4 189/189/4 192/192/4 191/191/4 +# f 186/186/1 190/190/1 191/191/1 187/187/1 +# f 189/189/3 185/185/3 188/188/3 192/192/3 +# f 193/193/1 194/194/1 195/195/1 196/196/1 +# f 196/196/2 195/195/2 197/197/2 198/198/2 +# f 198/198/3 197/197/3 199/199/3 200/200/3 +# f 200/200/4 199/199/4 194/194/4 193/193/4 +# f 196/196/5 198/198/5 200/200/5 193/193/5 +# f 201/201/2 202/202/2 203/203/2 204/204/2 +# f 201/201/6 205/205/6 195/195/6 194/194/6 +# f 205/205/7 206/206/7 197/197/7 195/195/7 +# f 206/206/8 202/202/8 199/199/8 197/197/8 +# f 202/202/9 201/201/9 194/194/9 199/199/9 +# f 207/207/6 208/208/6 204/204/6 203/203/6 +# f 206/206/4 205/205/4 208/208/4 207/207/4 +# f 202/202/1 206/206/1 207/207/1 203/203/1 +# f 205/205/3 201/201/3 204/204/3 208/208/3 +# f 209/209/1 210/210/1 211/211/1 212/212/1 +# f 212/212/2 211/211/2 213/213/2 214/214/2 +# f 214/214/3 213/213/3 215/215/3 216/216/3 +# f 216/216/4 215/215/4 210/210/4 209/209/4 +# f 212/212/5 214/214/5 216/216/5 209/209/5 +# f 217/217/2 218/218/2 219/219/2 220/220/2 +# f 217/217/8 221/221/8 211/211/8 210/210/8 +# f 221/221/9 222/222/9 213/213/9 211/211/9 +# f 222/222/6 218/218/6 215/215/6 213/213/6 +# f 218/218/7 217/217/7 210/210/7 215/215/7 +# f 223/223/6 224/224/6 220/220/6 219/219/6 +# f 222/222/4 221/221/4 224/224/4 223/223/4 +# f 218/218/1 222/222/1 223/223/1 219/219/1 +# f 221/221/3 217/217/3 220/220/3 224/224/3 +# f 225/225/1 226/226/1 227/227/1 228/228/1 +# f 228/228/2 227/227/2 229/229/2 230/230/2 +# f 230/230/3 229/229/3 231/231/3 232/232/3 +# f 232/232/4 231/231/4 226/226/4 225/225/4 +# f 228/228/5 230/230/5 232/232/5 225/225/5 +# f 233/233/2 234/234/2 235/235/2 236/236/2 +# f 233/233/6 237/237/6 227/227/6 226/226/6 +# f 237/237/7 238/238/7 229/229/7 227/227/7 +# f 238/238/8 234/234/8 231/231/8 229/229/8 +# f 234/234/9 233/233/9 226/226/9 231/231/9 +# f 239/239/6 240/240/6 236/236/6 235/235/6 +# f 238/238/4 237/237/4 240/240/4 239/239/4 +# f 234/234/1 238/238/1 239/239/1 235/235/1 +# f 237/237/3 233/233/3 236/236/3 240/240/3 +# f 241/241/1 242/242/1 243/243/1 244/244/1 +# f 244/244/2 243/243/2 245/245/2 246/246/2 +# f 246/246/3 245/245/3 247/247/3 248/248/3 +# f 248/248/4 247/247/4 242/242/4 241/241/4 +# f 244/244/5 246/246/5 248/248/5 241/241/5 +# f 249/249/2 250/250/2 251/251/2 252/252/2 +# f 249/249/8 253/253/8 243/243/8 242/242/8 +# f 253/253/9 254/254/9 245/245/9 243/243/9 +# f 254/254/6 250/250/6 247/247/6 245/245/6 +# f 250/250/7 249/249/7 242/242/7 247/247/7 +# f 255/255/6 256/256/6 252/252/6 251/251/6 +# f 254/254/4 253/253/4 256/256/4 255/255/4 +# f 250/250/1 254/254/1 255/255/1 251/251/1 +# f 253/253/3 249/249/3 252/252/3 256/256/3 +# f 257/257/1 258/258/1 259/259/1 260/260/1 +# f 260/260/2 259/259/2 261/261/2 262/262/2 +# f 262/262/3 261/261/3 263/263/3 264/264/3 +# f 264/264/4 263/263/4 258/258/4 257/257/4 +# f 260/260/5 262/262/5 264/264/5 257/257/5 +# f 265/265/2 266/266/2 267/267/2 268/268/2 +# f 265/265/6 269/269/6 259/259/6 258/258/6 +# f 269/269/7 270/270/7 261/261/7 259/259/7 +# f 270/270/8 266/266/8 263/263/8 261/261/8 +# f 266/266/9 265/265/9 258/258/9 263/263/9 +# f 271/271/6 272/272/6 268/268/6 267/267/6 +# f 270/270/4 269/269/4 272/272/4 271/271/4 +# f 266/266/1 270/270/1 271/271/1 267/267/1 +# f 269/269/3 265/265/3 268/268/3 272/272/3 +# f 273/273/1 274/274/1 275/275/1 276/276/1 +# f 276/276/2 275/275/2 277/277/2 278/278/2 +# f 278/278/3 277/277/3 279/279/3 280/280/3 +# f 280/280/4 279/279/4 274/274/4 273/273/4 +# f 276/276/5 278/278/5 280/280/5 273/273/5 +# f 281/281/2 282/282/2 283/283/2 284/284/2 +# f 281/281/8 285/285/8 275/275/8 274/274/8 +# f 285/285/9 286/286/9 277/277/9 275/275/9 +# f 286/286/6 282/282/6 279/279/6 277/277/6 +# f 282/282/7 281/281/7 274/274/7 279/279/7 +# f 287/287/6 288/288/6 284/284/6 283/283/6 +# f 286/286/4 285/285/4 288/288/4 287/287/4 +# f 282/282/1 286/286/1 287/287/1 283/283/1 +# f 285/285/3 281/281/3 284/284/3 288/288/3 +# f 289/289/1 290/290/1 291/291/1 292/292/1 +# f 292/292/2 291/291/2 293/293/2 294/294/2 +# f 294/294/3 293/293/3 295/295/3 296/296/3 +# f 296/296/4 295/295/4 290/290/4 289/289/4 +# f 292/292/5 294/294/5 296/296/5 289/289/5 +# f 297/297/2 298/298/2 299/299/2 300/300/2 +# f 297/297/6 301/301/6 291/291/6 290/290/6 +# f 301/301/7 302/302/7 293/293/7 291/291/7 +# f 302/302/8 298/298/8 295/295/8 293/293/8 +# f 298/298/9 297/297/9 290/290/9 295/295/9 +# f 303/303/6 304/304/6 300/300/6 299/299/6 +# f 302/302/4 301/301/4 304/304/4 303/303/4 +# f 298/298/1 302/302/1 303/303/1 299/299/1 +# f 301/301/3 297/297/3 300/300/3 304/304/3 +# f 305/305/1 306/306/1 307/307/1 308/308/1 +# f 308/308/2 307/307/2 309/309/2 310/310/2 +# f 310/310/3 309/309/3 311/311/3 312/312/3 +# f 312/312/4 311/311/4 306/306/4 305/305/4 +# f 308/308/5 310/310/5 312/312/5 305/305/5 +# f 313/313/2 314/314/2 315/315/2 316/316/2 +# f 313/313/8 317/317/8 307/307/8 306/306/8 +# f 317/317/9 318/318/9 309/309/9 307/307/9 +# f 318/318/6 314/314/6 311/311/6 309/309/6 +# f 314/314/7 313/313/7 306/306/7 311/311/7 +# f 319/319/6 320/320/6 316/316/6 315/315/6 +# f 318/318/4 317/317/4 320/320/4 319/319/4 +# f 314/314/1 318/318/1 319/319/1 315/315/1 +# f 317/317/3 313/313/3 316/316/3 320/320/3 +# f 321/321/1 322/322/1 323/323/1 324/324/1 +# f 324/324/2 323/323/2 325/325/2 326/326/2 +# f 326/326/3 325/325/3 327/327/3 328/328/3 +# f 328/328/4 327/327/4 322/322/4 321/321/4 +# f 324/324/5 326/326/5 328/328/5 321/321/5 +# f 329/329/2 330/330/2 331/331/2 332/332/2 +# f 329/329/8 333/333/8 323/323/8 322/322/8 +# f 333/333/9 334/334/9 325/325/9 323/323/9 +# f 334/334/6 330/330/6 327/327/6 325/325/6 +# f 330/330/7 329/329/7 322/322/7 327/327/7 +# f 335/335/6 336/336/6 332/332/6 331/331/6 +# f 334/334/12 333/333/12 336/336/12 335/335/12 +# f 330/330/1 334/334/1 335/335/1 331/331/1 +# f 333/333/3 329/329/3 332/332/3 336/336/3 +# f 337/337/1 338/338/1 339/339/1 340/340/1 +# f 340/340/2 339/339/2 341/341/2 342/342/2 +# f 342/342/3 341/341/3 343/343/3 344/344/3 +# f 344/344/4 343/343/4 338/338/4 337/337/4 +# f 340/340/5 342/342/5 344/344/5 337/337/5 +# f 345/345/2 346/346/2 347/347/2 348/348/2 +# f 345/345/8 349/349/8 339/339/8 338/338/8 +# f 349/349/9 350/350/9 341/341/9 339/339/9 +# f 350/350/6 346/346/6 343/343/6 341/341/6 +# f 346/346/7 345/345/7 338/338/7 343/343/7 +# f 351/351/6 352/352/6 348/348/6 347/347/6 +# f 350/350/4 349/349/4 352/352/4 351/351/4 +# f 346/346/1 350/350/1 351/351/1 347/347/1 +# f 349/349/3 345/345/3 348/348/3 352/352/3 +# f 353/353/1 354/354/1 355/355/1 356/356/1 +# f 356/356/2 355/355/2 357/357/2 358/358/2 +# f 358/358/3 357/357/3 359/359/3 360/360/3 +# f 360/360/4 359/359/4 354/354/4 353/353/4 +# f 356/356/5 358/358/5 360/360/5 353/353/5 +# f 361/361/2 362/362/2 363/363/2 364/364/2 +# f 361/361/8 365/365/8 355/355/8 354/354/8 +# f 365/365/9 366/366/9 357/357/9 355/355/9 +# f 366/366/6 362/362/6 359/359/6 357/357/6 +# f 362/362/7 361/361/7 354/354/7 359/359/7 +# f 367/367/6 368/368/6 364/364/6 363/363/6 +# f 366/366/12 365/365/12 368/368/12 367/367/12 +# f 362/362/1 366/366/1 367/367/1 363/363/1 +# f 365/365/3 361/361/3 364/364/3 368/368/3 +# f 369/369/1 370/370/1 371/371/1 372/372/1 +# f 372/372/2 371/371/2 373/373/2 374/374/2 +# f 374/374/3 373/373/3 375/375/3 376/376/3 +# f 376/376/12 375/375/12 370/370/12 369/369/12 +# f 372/372/5 374/374/5 376/376/5 369/369/5 +# f 377/377/2 378/378/2 379/379/2 380/380/2 +# f 377/377/8 381/381/8 371/371/8 370/370/8 +# f 381/381/9 382/382/9 373/373/9 371/371/9 +# f 382/382/6 378/378/6 375/375/6 373/373/6 +# f 378/378/7 377/377/7 370/370/7 375/375/7 +# f 383/383/6 384/384/6 380/380/6 379/379/6 +# f 382/382/4 381/381/4 384/384/4 383/383/4 +# f 378/378/1 382/382/1 383/383/1 379/379/1 +# f 381/381/3 377/377/3 380/380/3 384/384/3 +# f 385/385/1 386/386/1 387/387/1 388/388/1 +# f 388/388/2 387/387/2 389/389/2 390/390/2 +# f 390/390/3 389/389/3 391/391/3 392/392/3 +# f 392/392/4 391/391/4 386/386/4 385/385/4 +# f 388/388/5 390/390/5 392/392/5 385/385/5 +# f 393/393/2 394/394/2 395/395/2 396/396/2 +# f 393/393/8 397/397/8 387/387/8 386/386/8 +# f 397/397/9 398/398/9 389/389/9 387/387/9 +# f 398/398/6 394/394/6 391/391/6 389/389/6 +# f 394/394/7 393/393/7 386/386/7 391/391/7 +# f 399/399/6 400/400/6 396/396/6 395/395/6 +# f 398/398/12 397/397/12 400/400/12 399/399/12 +# f 394/394/1 398/398/1 399/399/1 395/395/1 +# f 397/397/3 393/393/3 396/396/3 400/400/3 +# f 401/401/1 402/402/1 403/403/1 404/404/1 +# f 404/404/2 403/403/2 405/405/2 406/406/2 +# f 406/406/3 405/405/3 407/407/3 408/408/3 +# f 408/408/12 407/407/12 402/402/12 401/401/12 +# f 404/404/5 406/406/5 408/408/5 401/401/5 +# f 409/409/2 410/410/2 411/411/2 412/412/2 +# f 409/409/8 413/413/8 403/403/8 402/402/8 +# f 413/413/9 414/414/9 405/405/9 403/403/9 +# f 414/414/6 410/410/6 407/407/6 405/405/6 +# f 410/410/7 409/409/7 402/402/7 407/407/7 +# f 415/415/6 416/416/6 412/412/6 411/411/6 +# f 414/414/4 413/413/4 416/416/4 415/415/4 +# f 410/410/1 414/414/1 415/415/1 411/411/1 +# f 413/413/3 409/409/3 412/412/3 416/416/3 +# f 417/417/1 418/418/1 419/419/1 420/420/1 +# f 420/420/2 419/419/2 421/421/2 422/422/2 +# f 422/422/3 421/421/3 423/423/3 424/424/3 +# f 424/424/4 423/423/4 418/418/4 417/417/4 +# f 420/420/5 422/422/5 424/424/5 417/417/5 +# f 425/425/2 426/426/2 427/427/2 428/428/2 +# f 425/425/8 429/429/8 419/419/8 418/418/8 +# f 429/429/9 430/430/9 421/421/9 419/419/9 +# f 430/430/6 426/426/6 423/423/6 421/421/6 +# f 426/426/7 425/425/7 418/418/7 423/423/7 +# f 431/431/6 432/432/6 428/428/6 427/427/6 +# f 430/430/4 429/429/4 432/432/4 431/431/4 +# f 426/426/1 430/430/1 431/431/1 427/427/1 +# f 429/429/3 425/425/3 428/428/3 432/432/3 +# f 433/433/1 434/434/1 435/435/1 436/436/1 +# f 436/436/2 435/435/2 437/437/2 438/438/2 +# f 438/438/3 437/437/3 439/439/3 440/440/3 +# f 440/440/4 439/439/4 434/434/4 433/433/4 +# f 436/436/5 438/438/5 440/440/5 433/433/5 +# f 441/441/2 442/442/2 443/443/2 444/444/2 +# f 441/441/8 445/445/8 435/435/8 434/434/8 +# f 445/445/9 446/446/9 437/437/9 435/435/9 +# f 446/446/6 442/442/6 439/439/6 437/437/6 +# f 442/442/7 441/441/7 434/434/7 439/439/7 +# f 447/447/6 448/448/6 444/444/6 443/443/6 +# f 446/446/4 445/445/4 448/448/4 447/447/4 +# f 442/442/1 446/446/1 447/447/1 443/443/1 +# f 445/445/3 441/441/3 444/444/3 448/448/3 +# f 449/449/1 450/450/1 451/451/1 452/452/1 +# f 452/452/2 451/451/2 453/453/2 454/454/2 +# f 454/454/3 453/453/3 455/455/3 456/456/3 +# f 456/456/4 455/455/4 450/450/4 449/449/4 +# f 452/452/5 454/454/5 456/456/5 449/449/5 +# f 457/457/2 458/458/2 459/459/2 460/460/2 +# f 457/457/8 461/461/8 451/451/8 450/450/8 +# f 461/461/9 462/462/9 453/453/9 451/451/9 +# f 462/462/6 458/458/6 455/455/6 453/453/6 +# f 458/458/7 457/457/7 450/450/7 455/455/7 +# f 463/463/6 464/464/6 460/460/6 459/459/6 +# f 462/462/4 461/461/4 464/464/4 463/463/4 +# f 458/458/1 462/462/1 463/463/1 459/459/1 +# f 461/461/3 457/457/3 460/460/3 464/464/3 +# f 465/465/1 466/466/1 467/467/1 468/468/1 +# f 468/468/2 467/467/2 469/469/2 470/470/2 +# f 470/470/3 469/469/3 471/471/3 472/472/3 +# f 472/472/4 471/471/4 466/466/4 465/465/4 +# f 468/468/5 470/470/5 472/472/5 465/465/5 +# f 473/473/2 474/474/2 475/475/2 476/476/2 +# f 473/473/8 477/477/8 467/467/8 466/466/8 +# f 477/477/9 478/478/9 469/469/9 467/467/9 +# f 478/478/6 474/474/6 471/471/6 469/469/6 +# f 474/474/7 473/473/7 466/466/7 471/471/7 +# f 479/479/6 480/480/6 476/476/6 475/475/6 +# f 478/478/4 477/477/4 480/480/4 479/479/4 +# f 474/474/1 478/478/1 479/479/1 475/475/1 +# f 477/477/3 473/473/3 476/476/3 480/480/3 +# 420 polygons + +# +# object Ramp +# + +v 0.5730 -3.8867 0.2299 +v 0.5730 -3.9787 0.2228 +v 0.9461 -3.9787 0.2228 +v 0.9461 -3.8867 0.2299 +v 0.5730 -4.3866 0.0533 +v 0.5730 -4.4896 0.0556 +v 0.9461 -4.4896 0.0556 +v 0.9461 -4.3866 0.0533 +v 0.9461 -3.4507 0.4659 +v 0.9461 -3.4508 0.4659 +v 0.9461 -3.3962 0.4659 +v 0.9461 -3.3864 0.4408 +v 0.9461 -3.4121 0.4408 +v 0.5730 -3.7945 0.2331 +v 0.9461 -3.7945 0.2331 +v 0.5730 -4.3315 0.0689 +v 0.9461 -4.3315 0.0689 +v 0.5730 -3.7057 0.2467 +v 0.9461 -3.7057 0.2467 +v 0.5730 -4.2767 0.1018 +v 0.9461 -4.2767 0.1018 +v 0.5730 -3.3864 0.1946 +v 0.5730 -3.3864 0.4408 +v 0.9873 -3.3864 0.1946 +v 0.5730 -3.6235 0.2699 +v 0.9461 -3.6235 0.2699 +v 0.5730 -4.2188 0.1439 +v 0.9461 -4.2188 0.1439 +v 0.5730 -3.7179 0.1946 +v 0.9873 -3.7179 0.1946 +v 0.5730 -3.5513 0.3020 +v 0.9461 -3.5513 0.3020 +v 0.5730 -4.1480 0.1789 +v 0.9461 -4.1480 0.1789 +v 0.5730 -3.7179 0.0218 +v 0.9873 -3.7179 0.0218 +v 0.5730 -3.4969 0.3523 +v 0.9461 -3.4969 0.3523 +v 0.5730 -4.0669 0.2056 +v 0.9461 -4.0669 0.2056 +v 0.5730 -5.0383 0.0556 +v 0.9461 -5.0383 0.0556 +v 0.5730 -5.0817 0.0218 +v 0.9461 -5.0817 0.0218 +v 0.5730 -3.4655 0.3940 +v 0.9461 -3.4655 0.3940 +v 0.9461 -4.2286 0.1690 +v 0.9461 -4.1578 0.2041 +v 0.9461 -4.2864 0.1269 +v 0.5730 -3.4121 0.4408 +v 0.9873 -3.3864 0.4408 +v 0.9461 -4.3413 0.0941 +v 0.5730 -3.4438 0.4280 +v 0.9461 -3.4438 0.4280 +v 0.9461 -4.3964 0.0785 +v 0.9461 -3.5067 0.3774 +v 0.9461 -3.4753 0.4191 +v 0.9873 -4.3997 0.0218 +v 0.9669 -4.3932 0.0218 +v 0.9461 -4.4994 0.0807 +v 0.9461 -3.5611 0.3271 +v 0.9461 -3.9885 0.2479 +v 0.9873 -3.9885 0.2479 +v 0.9873 -3.8965 0.2550 +v 0.9461 -3.8965 0.2550 +v 0.9873 -4.4994 0.0807 +v 0.9873 -4.3964 0.0785 +v 0.9873 -3.4753 0.4191 +v 0.9873 -3.4508 0.4659 +v 0.9873 -3.8043 0.2583 +v 0.9461 -3.8043 0.2583 +v 0.9873 -4.3413 0.0941 +v 0.9873 -3.3962 0.4659 +v 0.9873 -3.7154 0.2718 +v 0.9461 -3.7154 0.2718 +v 0.9873 -4.2864 0.1269 +v 0.9873 -3.6333 0.2951 +v 0.9461 -3.6333 0.2951 +v 0.9873 -4.2286 0.1690 +v 0.9873 -3.5611 0.3271 +v 0.9873 -4.1578 0.2041 +v 0.9873 -3.5067 0.3774 +v 0.9873 -4.0767 0.2307 +v 0.9461 -4.0767 0.2307 +v 0.9461 -5.0481 0.0807 +v 0.9873 -5.0481 0.0807 +v 0.9461 -5.0915 0.0470 +v 0.9873 -5.0915 0.0470 +v 0.9873 -5.0817 0.0218 +v 0.9667 -4.3996 0.0218 +v 0.9650 -4.3966 0.0218 +v 0.5730 -5.0812 0.0218 +v 0.5730 -3.7184 0.0218 +v 0.1999 -3.8867 0.2299 +v 0.1999 -3.9787 0.2228 +v 0.1999 -4.3866 0.0533 +v 0.1999 -4.4896 0.0556 +v 0.1999 -3.4507 0.4659 +v 0.1999 -3.4121 0.4408 +v 0.1999 -3.3864 0.4408 +v 0.1999 -3.3962 0.4659 +v 0.1999 -3.4508 0.4659 +v 0.1999 -3.7945 0.2331 +v 0.1999 -4.3315 0.0689 +v 0.1999 -3.7057 0.2467 +v 0.1999 -4.2767 0.1018 +v 0.1587 -3.3864 0.1946 +v 0.1999 -3.6235 0.2699 +v 0.1999 -4.2188 0.1439 +v 0.1587 -3.7179 0.1946 +v 0.1999 -3.5513 0.3020 +v 0.1999 -4.1480 0.1789 +v 0.1587 -3.7179 0.0218 +v 0.1999 -3.4969 0.3523 +v 0.1999 -4.0669 0.2056 +v 0.1999 -5.0383 0.0556 +v 0.1999 -5.0817 0.0218 +v 0.1999 -3.4655 0.3940 +v 0.1999 -4.1578 0.2041 +v 0.1999 -4.2286 0.1690 +v 0.1999 -4.2864 0.1269 +v 0.1587 -3.3864 0.4408 +v 0.1999 -4.3413 0.0941 +v 0.1999 -3.4438 0.4280 +v 0.1999 -4.3964 0.0785 +v 0.1999 -3.4753 0.4191 +v 0.1999 -3.5067 0.3774 +v 0.1791 -4.3932 0.0218 +v 0.1587 -4.3997 0.0218 +v 0.1999 -4.4994 0.0807 +v 0.1999 -3.5611 0.3271 +v 0.1999 -3.9885 0.2479 +v 0.1999 -3.8965 0.2550 +v 0.1587 -3.8965 0.2550 +v 0.1587 -3.9885 0.2479 +v 0.1587 -4.3964 0.0785 +v 0.1587 -4.4994 0.0807 +v 0.1587 -3.4508 0.4659 +v 0.1587 -3.4753 0.4191 +v 0.1999 -3.8043 0.2583 +v 0.1587 -3.8043 0.2583 +v 0.1587 -4.3413 0.0941 +v 0.1587 -3.3962 0.4659 +v 0.1999 -3.7154 0.2718 +v 0.1587 -3.7154 0.2718 +v 0.1587 -4.2864 0.1269 +v 0.1999 -3.6333 0.2951 +v 0.1587 -3.6333 0.2951 +v 0.1587 -4.2286 0.1690 +v 0.1587 -3.5611 0.3271 +v 0.1587 -4.1578 0.2041 +v 0.1587 -3.5067 0.3774 +v 0.1999 -4.0767 0.2307 +v 0.1587 -4.0767 0.2307 +v 0.1999 -5.0481 0.0807 +v 0.1587 -5.0481 0.0807 +v 0.1999 -5.0915 0.0470 +v 0.1587 -5.0915 0.0470 +v 0.1587 -5.0817 0.0218 +v 0.1793 -4.3996 0.0218 +v 0.1810 -4.3966 0.0218 +# 161 vertices + +vn 0.0000 -0.0562 0.9984 +vn 0.0000 -0.1344 0.9909 +vn 0.0000 -0.1265 0.9920 +vn 0.0000 0.0111 0.9999 +vn -1.0000 0.0000 0.0000 +vn 0.0000 -0.0931 0.9957 +vn 0.0000 -0.3965 0.9180 +vn 0.0000 -0.2118 0.9773 +vn 0.0000 -0.5518 0.8340 +vn 0.0000 1.0000 0.0000 +vn 0.0000 -0.3401 0.9404 +vn 0.0000 -0.5179 0.8554 +vn 0.0000 0.0000 -1.0000 +vn 0.0000 -0.5497 0.8354 +vn 0.0000 -0.3788 0.9255 +vn 0.0000 -0.7418 0.6706 +vn 0.0000 -0.2522 0.9677 +vn 0.0000 -0.3250 0.9457 +vn 0.0000 -0.6147 0.7888 +vn 0.0000 -0.8216 0.5701 +vn 0.0000 0.0000 1.0000 +vn 0.0000 -0.1904 0.9817 +vn 0.0000 -0.6388 0.7693 +vn 0.0000 -0.8450 0.5348 +vn 0.0000 -0.5174 0.8557 +vn 0.0000 0.5646 0.8254 +vn 0.0000 -0.3400 0.9404 +vn 0.0000 -0.9640 0.2657 +vn 0.0000 -0.9320 -0.3625 +vn 0.0000 0.9320 0.3625 +vn 1.0000 0.0000 0.0000 +vn 1.0000 -0.0000 0.0000 +vn -0.0000 0.0000 -1.0000 +vn -0.0000 0.0000 1.0000 +vn -0.0000 -0.1904 0.9817 +vn -0.0000 -0.6388 0.7693 +vn -1.0000 -0.0000 0.0000 +# 37 vertex normals + +vt 0.3743 0.1303 0.0000 +vt 0.3666 0.1303 0.0000 +vt 0.3666 0.1301 0.0000 +vt 0.3743 0.1301 0.0000 +vt 0.3743 0.1252 0.0000 +vt 0.3666 0.1252 0.0000 +vt 0.3666 0.1253 0.0000 +vt 0.3743 0.1253 0.0000 +vt 0.3743 0.1371 0.0000 +vt 0.3743 0.1371 0.0000 +vt 0.3743 0.1371 0.0000 +vt 0.3743 0.1364 0.0000 +vt 0.3743 0.1364 0.0000 +vt 0.3743 0.1304 0.0000 +vt 0.3666 0.1304 0.0000 +vt 0.3743 0.1256 0.0000 +vt 0.3666 0.1256 0.0000 +vt 0.3743 0.1308 0.0000 +vt 0.3666 0.1308 0.0000 +vt 0.3743 0.1266 0.0000 +vt 0.3666 0.1266 0.0000 +vt 0.3752 0.1293 0.0000 +vt 0.3666 0.1293 0.0000 +vt 0.3666 0.1364 0.0000 +vt 0.3743 0.1314 0.0000 +vt 0.3666 0.1314 0.0000 +vt 0.3743 0.1278 0.0000 +vt 0.3666 0.1278 0.0000 +vt 0.3752 0.1293 0.0000 +vt 0.3666 0.1293 0.0000 +vt 0.3743 0.1324 0.0000 +vt 0.3666 0.1324 0.0000 +vt 0.3743 0.1288 0.0000 +vt 0.3666 0.1288 0.0000 +vt 0.3752 0.1243 0.0000 +vt 0.3666 0.1243 0.0000 +vt 0.3743 0.1338 0.0000 +vt 0.3666 0.1338 0.0000 +vt 0.3743 0.1296 0.0000 +vt 0.3666 0.1296 0.0000 +vt 0.3666 0.1253 0.0000 +vt 0.3743 0.1253 0.0000 +vt 0.3666 0.1243 0.0000 +vt 0.3743 0.1243 0.0000 +vt 0.3743 0.1350 0.0000 +vt 0.3666 0.1350 0.0000 +vt 0.3743 0.1285 0.0000 +vt 0.3743 0.1295 0.0000 +vt 0.3743 0.1273 0.0000 +vt 0.3666 0.1364 0.0000 +vt 0.3752 0.1364 0.0000 +vt 0.3743 0.1264 0.0000 +vt 0.3743 0.1360 0.0000 +vt 0.3666 0.1360 0.0000 +vt 0.3743 0.1259 0.0000 +vt 0.3743 0.1345 0.0000 +vt 0.3743 0.1357 0.0000 +vt 0.3752 0.1243 0.0000 +vt 0.3747 0.1243 0.0000 +vt 0.3743 0.1260 0.0000 +vt 0.3743 0.1331 0.0000 +vt 0.3743 0.1308 0.0000 +vt 0.3752 0.1308 0.0000 +vt 0.3752 0.1310 0.0000 +vt 0.3743 0.1310 0.0000 +vt 0.3752 0.1260 0.0000 +vt 0.3752 0.1259 0.0000 +vt 0.3752 0.1357 0.0000 +vt 0.3752 0.1371 0.0000 +vt 0.3752 0.1311 0.0000 +vt 0.3743 0.1311 0.0000 +vt 0.3752 0.1264 0.0000 +vt 0.3752 0.1371 0.0000 +vt 0.3752 0.1315 0.0000 +vt 0.3743 0.1315 0.0000 +vt 0.3752 0.1273 0.0000 +vt 0.3752 0.1322 0.0000 +vt 0.3743 0.1322 0.0000 +vt 0.3752 0.1285 0.0000 +vt 0.3752 0.1331 0.0000 +vt 0.3752 0.1295 0.0000 +vt 0.3752 0.1345 0.0000 +vt 0.3752 0.1303 0.0000 +vt 0.3743 0.1303 0.0000 +vt 0.3743 0.1260 0.0000 +vt 0.3752 0.1260 0.0000 +vt 0.3743 0.1250 0.0000 +vt 0.3752 0.1250 0.0000 +vt 0.3752 0.1243 0.0000 +vt 0.3752 0.1243 0.0000 +vt 0.3752 0.1243 0.0000 +vt 0.3747 0.1243 0.0000 +vt 0.3747 0.1243 0.0000 +vt 0.3666 0.1243 0.0000 +vt 0.3666 0.1243 0.0000 +vt 0.3588 0.1303 0.0000 +vt 0.3588 0.1301 0.0000 +vt 0.3588 0.1252 0.0000 +vt 0.3588 0.1253 0.0000 +vt 0.3588 0.1371 0.0000 +vt 0.3588 0.1364 0.0000 +vt 0.3588 0.1364 0.0000 +vt 0.3588 0.1371 0.0000 +vt 0.3588 0.1371 0.0000 +vt 0.3588 0.1304 0.0000 +vt 0.3588 0.1256 0.0000 +vt 0.3588 0.1308 0.0000 +vt 0.3588 0.1266 0.0000 +vt 0.3579 0.1293 0.0000 +vt 0.3588 0.1314 0.0000 +vt 0.3588 0.1278 0.0000 +vt 0.3579 0.1293 0.0000 +vt 0.3588 0.1324 0.0000 +vt 0.3588 0.1288 0.0000 +vt 0.3579 0.1243 0.0000 +vt 0.3588 0.1338 0.0000 +vt 0.3588 0.1296 0.0000 +vt 0.3588 0.1253 0.0000 +vt 0.3588 0.1243 0.0000 +vt 0.3588 0.1350 0.0000 +vt 0.3588 0.1295 0.0000 +vt 0.3588 0.1285 0.0000 +vt 0.3588 0.1273 0.0000 +vt 0.3579 0.1364 0.0000 +vt 0.3588 0.1264 0.0000 +vt 0.3588 0.1360 0.0000 +vt 0.3588 0.1259 0.0000 +vt 0.3588 0.1357 0.0000 +vt 0.3588 0.1345 0.0000 +vt 0.3584 0.1243 0.0000 +vt 0.3579 0.1243 0.0000 +vt 0.3588 0.1260 0.0000 +vt 0.3588 0.1331 0.0000 +vt 0.3588 0.1308 0.0000 +vt 0.3588 0.1310 0.0000 +vt 0.3579 0.1310 0.0000 +vt 0.3579 0.1308 0.0000 +vt 0.3579 0.1259 0.0000 +vt 0.3579 0.1260 0.0000 +vt 0.3579 0.1371 0.0000 +vt 0.3579 0.1357 0.0000 +vt 0.3588 0.1311 0.0000 +vt 0.3579 0.1311 0.0000 +vt 0.3579 0.1264 0.0000 +vt 0.3579 0.1371 0.0000 +vt 0.3588 0.1315 0.0000 +vt 0.3579 0.1315 0.0000 +vt 0.3579 0.1273 0.0000 +vt 0.3588 0.1322 0.0000 +vt 0.3579 0.1322 0.0000 +vt 0.3579 0.1285 0.0000 +vt 0.3579 0.1331 0.0000 +vt 0.3579 0.1295 0.0000 +vt 0.3579 0.1345 0.0000 +vt 0.3588 0.1303 0.0000 +vt 0.3579 0.1303 0.0000 +vt 0.3588 0.1260 0.0000 +vt 0.3579 0.1260 0.0000 +vt 0.3588 0.1250 0.0000 +vt 0.3579 0.1250 0.0000 +vt 0.3579 0.1243 0.0000 +vt 0.3579 0.1243 0.0000 +vt 0.3579 0.1243 0.0000 +vt 0.3584 0.1243 0.0000 +vt 0.3584 0.1243 0.0000 +# 165 texture coords + +g Ramp +usemtl ShippingContainer +s 1 +f 481/482/13 482/483/14 483/484/14 484/481/13 +f 485/486/15 486/487/16 487/488/16 488/485/15 +s off +f 489/489/17 490/490/17 491/491/17 492/492/17 493/493/17 +s 1 +f 494/495/18 481/482/13 484/481/13 495/494/18 +f 496/497/19 485/486/15 488/485/15 497/496/19 +f 498/499/20 494/495/18 495/494/18 499/498/20 +f 500/501/21 496/497/19 497/496/19 501/500/21 +s off +f 502/503/22 503/504/22 492/492/22 504/502/22 +s 1 +f 505/506/23 498/499/20 499/498/20 506/505/23 +f 507/508/24 500/501/21 501/500/21 508/507/24 +s off +f 509/510/25 502/503/25 504/502/25 510/509/25 +s 1 +f 511/512/26 505/506/23 506/505/23 512/511/26 +f 513/514/27 507/508/24 508/507/24 514/513/27 +s off +f 515/516/22 509/510/22 510/509/22 516/515/22 +s 1 +f 517/518/28 511/512/26 512/511/26 518/517/28 +f 519/520/29 513/514/27 514/513/27 520/519/29 +f 486/487/16 521/521/30 522/522/30 487/488/16 +f 482/483/14 519/520/29 520/519/29 483/484/14 +f 521/521/30 523/523/31 524/524/31 522/522/30 +f 525/526/32 517/518/28 518/517/28 526/525/32 +s off +f 508/507/17 527/527/17 528/528/17 514/513/17 +f 501/500/17 529/529/17 527/527/17 508/507/17 +s 1 +f 503/504/33 530/530/34 493/493/34 492/492/33 +s off +f 492/492/22 531/531/22 504/502/22 +f 497/496/17 532/532/17 529/529/17 501/500/17 +s 1 +f 533/534/35 525/526/32 526/525/32 534/533/35 +s off +f 488/485/17 535/535/17 532/532/17 497/496/17 +f 518/517/17 536/536/17 537/537/17 526/525/17 +f 516/515/25 538/538/25 539/539/25 +f 487/488/17 540/540/17 535/535/17 488/485/17 +f 541/541/17 536/536/17 518/517/17 512/511/17 +s 2 +f 542/542/14 543/543/14 544/544/13 545/545/13 +f 540/540/16 546/546/16 547/547/15 535/535/15 +f 537/537/36 548/548/36 549/549/37 490/490/37 +f 545/545/13 544/544/13 550/550/18 551/551/18 +f 535/535/15 547/547/15 552/552/19 532/532/19 +f 490/490/37 549/549/37 553/553/38 491/491/38 +f 551/551/18 550/550/18 554/554/20 555/555/20 +f 532/532/19 552/552/19 556/556/21 529/529/21 +f 555/555/20 554/554/20 557/557/39 558/558/39 +f 529/529/21 556/556/21 559/559/24 527/527/24 +f 558/558/39 557/557/39 560/560/26 541/541/26 +f 527/527/24 559/559/24 561/561/27 528/528/27 +f 541/541/26 560/560/26 562/562/28 536/536/28 +f 528/528/27 561/561/27 563/563/29 564/564/29 +f 565/565/30 566/566/30 546/546/16 540/540/16 +f 564/564/29 563/563/29 543/543/14 542/542/14 +f 567/567/40 568/568/40 566/566/30 565/565/30 +f 536/536/28 562/562/28 548/548/36 537/537/36 +s off +f 514/513/17 528/528/17 564/564/17 520/519/17 +f 520/519/17 564/564/17 542/542/17 483/484/17 +s 2 +f 569/569/41 568/568/40 567/567/40 524/524/41 +s off +f 483/484/17 542/542/17 545/545/17 484/481/17 +f 524/524/17 567/567/17 565/565/17 522/522/17 +f 484/481/17 545/545/17 551/551/17 495/494/17 +s 2 +f 492/492/42 491/491/38 553/553/38 531/531/42 +s off +f 495/494/17 551/551/17 555/555/17 499/498/17 +f 499/498/17 555/555/17 558/558/17 506/505/17 +f 506/505/17 558/558/17 541/541/17 512/511/17 +f 565/565/17 540/540/17 487/488/17 522/522/17 +f 566/566/43 568/568/43 569/569/43 +f 526/525/17 537/537/17 490/490/17 489/489/17 534/533/17 +f 534/533/17 489/489/17 493/493/17 +f 538/538/43 547/547/43 546/546/43 +f 566/566/44 569/569/44 538/538/44 546/546/44 +f 538/538/44 552/552/44 547/547/44 +f 552/552/43 516/515/43 516/570/43 556/556/43 +f 552/552/43 538/538/43 516/515/43 +f 559/559/43 516/570/43 516/571/43 561/561/43 +f 559/559/43 556/556/43 516/570/43 +f 543/543/43 563/563/43 516/571/43 +f 563/563/43 561/561/43 516/571/43 +f 516/515/43 550/550/43 544/544/43 +f 544/544/43 543/543/43 516/571/43 516/570/43 516/515/43 +f 510/509/43 554/554/43 550/550/43 +f 550/550/43 516/515/43 510/509/43 +f 504/502/43 560/560/43 557/557/43 +f 554/554/43 510/509/43 504/502/43 +f 557/557/43 554/554/43 504/502/43 +f 531/531/43 553/553/43 549/549/43 +f 548/548/43 504/502/43 531/531/43 +f 531/531/43 549/549/43 548/548/43 +f 562/562/43 560/560/43 504/502/43 +f 504/502/43 548/548/43 562/562/43 +f 538/538/25 569/569/25 524/524/25 570/572/25 539/539/25 +f 539/539/45 570/572/45 571/573/45 +f 524/524/45 523/523/45 572/574/45 571/573/45 570/572/45 +f 571/573/45 572/574/45 573/575/45 +f 516/515/45 539/539/45 571/573/45 573/575/45 515/516/45 +s 1 +f 534/533/35 493/493/34 530/530/34 533/534/35 +f 481/482/13 574/576/13 575/577/14 482/483/14 +f 485/486/15 576/578/15 577/579/16 486/487/16 +s off +f 578/580/43 579/581/43 580/582/43 581/583/43 582/584/43 +s 1 +f 494/495/18 583/585/18 574/576/13 481/482/13 +f 496/497/19 584/586/19 576/578/15 485/486/15 +f 498/499/20 585/587/20 583/585/18 494/495/18 +f 500/501/21 586/588/21 584/586/19 496/497/19 +s off +f 502/503/22 587/589/22 580/582/22 503/504/22 +s 1 +f 505/506/23 588/590/23 585/587/20 498/499/20 +f 507/508/24 589/591/24 586/588/21 500/501/21 +s off +f 509/510/25 590/592/25 587/589/25 502/503/25 +s 1 +f 511/512/26 591/593/26 588/590/23 505/506/23 +f 513/514/27 592/594/27 589/591/24 507/508/24 +s off +f 515/516/22 593/595/22 590/592/22 509/510/22 +s 1 +f 517/518/28 594/596/28 591/593/26 511/512/26 +f 519/520/29 595/597/29 592/594/27 513/514/27 +f 486/487/16 577/579/16 596/598/30 521/521/30 +f 482/483/14 575/577/14 595/597/29 519/520/29 +f 521/521/30 596/598/30 597/599/31 523/523/31 +f 525/526/32 598/600/32 594/596/28 517/518/28 +s off +f 589/591/43 592/594/43 599/601/43 600/602/43 +f 586/588/43 589/591/43 600/602/43 601/603/43 +s 1 +f 503/504/33 580/582/46 579/581/47 530/530/34 +s off +f 580/582/22 587/589/22 602/604/22 +f 584/586/43 586/588/43 601/603/43 603/605/43 +s 1 +f 533/534/35 604/606/48 598/600/32 525/526/32 +s off +f 576/578/43 584/586/43 603/605/43 605/607/43 +f 594/596/43 598/600/43 606/608/43 607/609/43 +f 593/595/45 608/610/45 609/611/45 +f 577/579/43 576/578/43 605/607/43 610/612/43 +f 611/613/43 591/593/43 594/596/43 607/609/43 +s 2 +f 612/614/14 613/615/13 614/616/13 615/617/14 +f 610/612/16 605/607/15 616/618/15 617/619/16 +f 606/608/36 582/584/37 618/620/37 619/621/36 +f 613/615/13 620/622/18 621/623/18 614/616/13 +f 605/607/15 603/605/19 622/624/19 616/618/15 +f 582/584/37 581/583/38 623/625/38 618/620/37 +f 620/622/18 624/626/20 625/627/20 621/623/18 +f 603/605/19 601/603/21 626/628/21 622/624/19 +f 624/626/20 627/629/39 628/630/39 625/627/20 +f 601/603/21 600/602/24 629/631/24 626/628/21 +f 627/629/39 611/613/26 630/632/26 628/630/39 +f 600/602/24 599/601/27 631/633/27 629/631/24 +f 611/613/26 607/609/28 632/634/28 630/632/26 +f 599/601/27 633/635/29 634/636/29 631/633/27 +f 635/637/30 610/612/16 617/619/16 636/638/30 +f 633/635/29 612/614/14 615/617/14 634/636/29 +f 637/639/40 635/637/30 636/638/30 638/640/40 +f 607/609/28 606/608/36 619/621/36 632/634/28 +s off +f 592/594/43 595/597/43 633/635/43 599/601/43 +f 595/597/43 575/577/43 612/614/43 633/635/43 +s 2 +f 639/641/41 597/599/41 637/639/40 638/640/40 +s off +f 575/577/43 574/576/43 613/615/43 612/614/43 +f 597/599/43 596/598/43 635/637/43 637/639/43 +f 574/576/43 583/585/43 620/622/43 613/615/43 +s 2 +f 580/582/42 602/604/42 623/625/38 581/583/38 +s off +f 583/585/43 585/587/43 624/626/43 620/622/43 +f 585/587/43 588/590/43 627/629/43 624/626/43 +f 588/590/43 591/593/43 611/613/43 627/629/43 +f 635/637/43 596/598/43 577/579/43 610/612/43 +f 636/638/17 639/641/17 638/640/17 +f 598/600/43 604/606/43 578/580/43 582/584/43 606/608/43 +f 604/606/43 579/581/43 578/580/43 +f 609/611/17 617/619/17 616/618/17 +f 636/638/49 617/619/49 609/611/49 639/641/49 +f 609/611/49 616/618/49 622/624/49 +f 622/624/17 626/628/17 593/642/17 593/595/17 +f 622/624/17 593/595/17 609/611/17 +f 629/631/17 631/633/17 593/643/17 593/642/17 +f 629/631/17 593/642/17 626/628/17 +f 615/617/17 593/643/17 634/636/17 +f 634/636/17 593/643/17 631/633/17 +f 593/595/17 614/616/17 621/623/17 +f 614/616/17 593/595/17 593/642/17 593/643/17 615/617/17 +f 590/592/17 621/623/17 625/627/17 +f 621/623/17 590/592/17 593/595/17 +f 587/589/17 628/630/17 630/632/17 +f 625/627/17 587/589/17 590/592/17 +f 628/630/17 587/589/17 625/627/17 +f 602/604/17 618/620/17 623/625/17 +f 619/621/17 602/604/17 587/589/17 +f 602/604/17 619/621/17 618/620/17 +f 632/634/17 587/589/17 630/632/17 +f 587/589/17 632/634/17 619/621/17 +f 609/611/45 608/610/45 640/644/45 597/599/45 639/641/45 +f 608/610/25 641/645/25 640/644/25 +f 572/574/25 523/523/25 597/599/25 640/644/25 641/645/25 +f 641/645/25 573/575/25 572/574/25 +f 641/645/25 608/610/25 593/595/25 515/516/25 573/575/25 +s 1 +f 604/606/48 533/534/35 530/530/34 579/581/47 +# 134 polygons - 46 triangles + +# +# object Wall_Left +# + +v -1.3424 8.3594 2.5926 +v -1.3424 8.3594 0.1548 +v -1.3424 8.2430 0.1548 +v -1.3424 8.2430 2.5926 +v -1.2735 8.4013 0.1548 +v -1.2735 8.4013 2.5926 +v -1.2735 8.4450 2.5926 +v -1.2735 8.4450 0.1548 +v -1.2735 8.2011 0.1548 +v -1.2735 8.2011 2.5926 +v -1.3424 8.0739 2.5926 +v -1.3424 8.0739 0.1548 +v -1.3424 7.9575 0.1548 +v -1.3424 7.9575 2.5926 +v -1.2735 8.1158 0.1548 +v -1.2735 8.1158 2.5926 +v -1.2735 8.1584 2.5926 +v -1.2735 8.1584 0.1548 +v -1.2735 7.9156 0.1548 +v -1.2735 7.9156 2.5926 +v -1.3424 7.7884 2.5926 +v -1.3424 7.7884 0.1548 +v -1.3424 7.6720 0.1548 +v -1.3424 7.6720 2.5926 +v -1.2735 7.8303 0.1548 +v -1.2735 7.8303 2.5926 +v -1.2735 7.8729 2.5926 +v -1.2735 7.8729 0.1548 +v -1.2735 7.6301 0.1548 +v -1.2735 7.6301 2.5926 +v -1.3424 7.2174 2.5926 +v -1.3424 7.2174 0.1548 +v -1.3424 7.1010 0.1548 +v -1.3424 7.1010 2.5926 +v -1.2735 7.2593 0.1548 +v -1.2735 7.2593 2.5926 +v -1.2735 7.3019 2.5926 +v -1.2735 7.3446 2.5926 +v -1.2735 7.3446 0.1548 +v -1.2735 7.3019 0.1548 +v -1.2735 7.0591 0.1548 +v -1.2735 7.0591 2.5926 +v -1.3424 6.9319 2.5926 +v -1.3424 6.9319 0.1548 +v -1.3424 6.8155 0.1548 +v -1.3424 6.8155 2.5926 +v -1.2735 6.9738 0.1548 +v -1.2735 6.9738 2.5926 +v -1.2735 7.0164 2.5926 +v -1.2735 7.0164 0.1548 +v -1.2735 6.7736 0.1548 +v -1.2735 6.7736 2.5926 +v -1.3424 6.0754 2.5926 +v -1.3424 6.0754 0.1548 +v -1.3424 5.9590 0.1548 +v -1.3424 5.9590 2.5926 +v -1.2735 6.1173 0.1548 +v -1.2735 6.1173 2.5926 +v -1.2735 6.1599 2.5926 +v -1.2735 6.2026 2.5926 +v -1.2735 6.2026 0.1548 +v -1.2735 6.1599 0.1548 +v -1.2735 5.9171 0.1548 +v -1.2735 5.9171 2.5926 +v -1.3424 7.5029 2.5926 +v -1.3424 7.5029 0.1548 +v -1.3424 7.3865 0.1548 +v -1.3424 7.3865 2.5926 +v -1.2735 7.5448 0.1548 +v -1.2735 7.5448 2.5926 +v -1.2735 7.5874 2.5926 +v -1.2735 7.5874 0.1548 +v -1.3424 6.6464 2.5926 +v -1.3424 6.6464 0.1548 +v -1.3424 6.5300 0.1548 +v -1.3424 6.5300 2.5926 +v -1.2735 6.6883 0.1548 +v -1.2735 6.6883 2.5926 +v -1.2735 6.7309 2.5926 +v -1.2735 6.7309 0.1548 +v -1.2735 6.4881 0.1548 +v -1.2735 6.4881 2.5926 +v -1.3424 6.3609 2.5926 +v -1.3424 6.3609 0.1548 +v -1.3424 6.2445 0.1548 +v -1.3424 6.2445 2.5926 +v -1.2735 6.4028 0.1548 +v -1.2735 6.4028 2.5926 +v -1.2735 6.4454 2.5926 +v -1.2735 6.4454 0.1548 +v -1.3424 5.7899 2.5926 +v -1.3424 5.7899 0.1548 +v -1.3424 5.6735 0.1548 +v -1.3424 5.6735 2.5926 +v -1.2735 5.8318 0.1548 +v -1.2735 5.8318 2.5926 +v -1.2735 5.8744 2.5926 +v -1.2735 5.8744 0.1548 +v -1.2735 5.6316 0.1548 +v -1.2735 5.6316 2.5926 +v -1.3424 5.5044 2.5926 +v -1.3424 5.5044 0.1548 +v -1.3424 5.3880 0.1548 +v -1.3424 5.3880 2.5926 +v -1.2735 5.5463 0.1548 +v -1.2735 5.5463 2.5926 +v -1.2735 5.5889 2.5926 +v -1.2735 5.5889 0.1548 +v -1.2735 5.3461 0.1548 +v -1.2735 5.3461 2.5926 +v -1.3424 4.3624 2.5926 +v -1.3424 4.3624 0.1548 +v -1.3424 4.2460 0.1548 +v -1.3424 4.2460 2.5926 +v -1.2735 4.4043 0.1548 +v -1.2735 4.4043 2.5926 +v -1.2735 4.4469 2.5926 +v -1.2735 4.4896 2.5926 +v -1.2735 4.4896 0.1548 +v -1.2735 4.4469 0.1548 +v -1.2735 4.2041 0.1548 +v -1.2735 4.2041 2.5926 +v -1.3424 4.0769 2.5926 +v -1.3424 4.0769 0.1548 +v -1.3424 3.9605 0.1548 +v -1.3424 3.9605 2.5926 +v -1.2735 4.1188 0.1548 +v -1.2735 4.1188 2.5926 +v -1.2735 4.1614 2.5926 +v -1.2735 4.1614 0.1548 +v -1.2735 3.9186 0.1548 +v -1.2735 3.9186 2.5926 +v -1.3424 5.2189 2.5926 +v -1.3424 5.2189 0.1548 +v -1.3424 5.1025 0.1548 +v -1.3424 5.1025 2.5926 +v -1.2735 5.2608 0.1548 +v -1.2735 5.2608 2.5926 +v -1.2735 5.3034 2.5926 +v -1.2735 5.3034 0.1548 +v -1.2735 5.0606 0.1548 +v -1.2735 5.0606 2.5926 +v -1.3424 4.6479 2.5926 +v -1.3424 4.6479 0.1548 +v -1.3424 4.5315 0.1548 +v -1.3424 4.5315 2.5926 +v -1.2735 4.6898 0.1548 +v -1.2735 4.6898 2.5926 +v -1.2735 4.7324 2.5926 +v -1.2735 4.7751 2.5926 +v -1.2735 4.7751 0.1548 +v -1.2735 4.7324 0.1548 +v -1.3424 4.9334 2.5926 +v -1.3424 4.9334 0.1548 +v -1.3424 4.8170 0.1548 +v -1.3424 4.8170 2.5926 +v -1.2735 4.9753 0.1548 +v -1.2735 4.9753 2.5926 +v -1.2735 5.0179 2.5926 +v -1.2735 5.0179 0.1548 +v -1.3424 3.7914 2.5926 +v -1.3424 3.7914 0.1548 +v -1.3424 3.6750 0.1548 +v -1.3424 3.6750 2.5926 +v -1.2735 3.8333 0.1548 +v -1.2735 3.8333 2.5926 +v -1.2735 3.8759 2.5926 +v -1.2735 3.8759 0.1548 +v -1.2735 3.6331 0.1548 +v -1.2735 3.6331 2.5926 +v -1.3424 3.2204 2.5926 +v -1.3424 3.2204 0.1548 +v -1.3424 3.1040 0.1548 +v -1.3424 3.1040 2.5926 +v -1.2735 3.2623 0.1548 +v -1.2735 3.2623 2.5926 +v -1.2735 3.3049 2.5926 +v -1.2735 3.3476 2.5926 +v -1.2735 3.3476 0.1548 +v -1.2735 3.3049 0.1548 +v -1.2735 3.0621 0.1548 +v -1.2735 3.0621 2.5926 +v -1.3424 2.6494 2.5926 +v -1.3424 2.6494 0.1548 +v -1.3424 2.5330 0.1548 +v -1.3424 2.5330 2.5926 +v -1.2735 2.6913 0.1548 +v -1.2735 2.6913 2.5926 +v -1.2735 2.7339 2.5926 +v -1.2735 2.7766 2.5926 +v -1.2735 2.7766 0.1548 +v -1.2735 2.7339 0.1548 +v -1.2735 2.4911 0.1548 +v -1.2735 2.4911 2.5926 +v -1.3424 2.0784 2.5926 +v -1.3424 2.0784 0.1548 +v -1.3424 1.9620 0.1548 +v -1.3424 1.9620 2.5926 +v -1.2735 2.1203 0.1548 +v -1.2735 2.1203 2.5926 +v -1.2735 2.1629 2.5926 +v -1.2735 2.2056 2.5926 +v -1.2735 2.2056 0.1548 +v -1.2735 2.1629 0.1548 +v -1.2735 1.9201 0.1548 +v -1.2735 1.9201 2.5926 +v -1.3424 1.7929 2.5926 +v -1.3424 1.7929 0.1548 +v -1.3424 1.6765 0.1548 +v -1.3424 1.6765 2.5926 +v -1.2735 1.8348 0.1548 +v -1.2735 1.8348 2.5926 +v -1.2735 1.8774 2.5926 +v -1.2735 1.8774 0.1548 +v -1.2735 1.6346 0.1548 +v -1.2735 1.6346 2.5926 +v -1.3424 3.5059 2.5926 +v -1.3424 3.5059 0.1548 +v -1.3424 3.3895 0.1548 +v -1.3424 3.3895 2.5926 +v -1.2735 3.5478 0.1548 +v -1.2735 3.5478 2.5926 +v -1.2735 3.5904 2.5926 +v -1.2735 3.5904 0.1548 +v -1.3424 2.9349 2.5926 +v -1.3424 2.9349 0.1548 +v -1.3424 2.8185 0.1548 +v -1.3424 2.8185 2.5926 +v -1.2735 2.9768 0.1548 +v -1.2735 2.9768 2.5926 +v -1.2735 3.0194 2.5926 +v -1.2735 3.0194 0.1548 +v -1.3424 2.3639 2.5926 +v -1.3424 2.3639 0.1548 +v -1.3424 2.2475 0.1548 +v -1.3424 2.2475 2.5926 +v -1.2735 2.4058 0.1548 +v -1.2735 2.4058 2.5926 +v -1.2735 2.4484 2.5926 +v -1.2735 2.4484 0.1548 +v -1.3424 1.5074 2.5926 +v -1.3424 1.5074 0.1548 +v -1.3424 1.3910 0.1548 +v -1.3424 1.3910 2.5926 +v -1.2735 1.5493 0.1548 +v -1.2735 1.5493 2.5926 +v -1.2735 1.5919 2.5926 +v -1.2735 1.5919 0.1548 +v -1.2735 1.3491 0.1548 +v -1.2735 1.3491 2.5926 +v -1.3424 1.2219 2.5926 +v -1.3424 1.2219 0.1548 +v -1.3424 1.1055 0.1548 +v -1.3424 1.1055 2.5926 +v -1.2735 1.2638 0.1548 +v -1.2735 1.2638 2.5926 +v -1.2735 1.3064 2.5926 +v -1.2735 1.3064 0.1548 +v -1.2735 1.0636 0.1548 +v -1.2735 1.0636 2.5926 +v -1.3424 0.9364 2.5926 +v -1.3424 0.9364 0.1548 +v -1.3424 0.8200 0.1548 +v -1.3424 0.8200 2.5926 +v -1.2735 0.9783 0.1548 +v -1.2735 0.9783 2.5926 +v -1.2735 1.0209 2.5926 +v -1.2735 1.0209 0.1548 +v -1.2735 0.7781 0.1548 +v -1.2735 0.7781 2.5926 +v -1.3424 0.6509 2.5926 +v -1.3424 0.6509 0.1548 +v -1.3424 0.5345 0.1548 +v -1.3424 0.5345 2.5926 +v -1.2735 0.6928 0.1548 +v -1.2735 0.6928 2.5926 +v -1.2735 0.7354 2.5926 +v -1.2735 0.7354 0.1548 +v -1.2735 0.4926 0.1548 +v -1.2735 0.4926 2.5926 +v -1.3424 0.3654 2.5926 +v -1.3424 0.3654 0.1548 +v -1.3424 0.2490 0.1548 +v -1.3424 0.2490 2.5926 +v -1.2735 0.4073 0.1548 +v -1.2735 0.4073 2.5926 +v -1.2735 0.4499 2.5926 +v -1.2735 0.4499 0.1548 +v -1.2735 0.2071 0.1548 +v -1.2735 0.2071 2.5926 +v -1.3424 0.0799 2.5926 +v -1.3424 0.0799 0.1548 +v -1.3424 -0.0365 0.1548 +v -1.3424 -0.0365 2.5926 +v -1.2735 0.1218 0.1548 +v -1.2735 0.1218 2.5926 +v -1.2735 0.1644 2.5926 +v -1.2735 0.1644 0.1548 +v -1.2735 -0.0784 0.1548 +v -1.2735 -0.0784 2.5926 +v -1.3424 -0.2056 2.5926 +v -1.3424 -0.2056 0.1548 +v -1.3424 -0.3220 0.1548 +v -1.3424 -0.3220 2.5926 +v -1.2735 -0.1637 0.1548 +v -1.2735 -0.1637 2.5926 +v -1.2735 -0.1211 2.5926 +v -1.2735 -0.1211 0.1548 +v -1.2735 -0.3639 0.1548 +v -1.2735 -0.3639 2.5926 +v -1.3424 -0.4911 2.5926 +v -1.3424 -0.4911 0.1548 +v -1.3424 -0.6075 0.1548 +v -1.3424 -0.6075 2.5926 +v -1.2735 -0.4492 0.1548 +v -1.2735 -0.4492 2.5926 +v -1.2735 -0.4066 2.5926 +v -1.2735 -0.4066 0.1548 +v -1.2735 -0.6494 0.1548 +v -1.2735 -0.6494 2.5926 +v -1.3424 -0.7766 2.5926 +v -1.3424 -0.7766 0.1548 +v -1.3424 -0.8930 0.1548 +v -1.3424 -0.8930 2.5926 +v -1.2735 -0.7347 0.1548 +v -1.2735 -0.7347 2.5926 +v -1.2735 -0.6921 2.5926 +v -1.2735 -0.6921 0.1548 +v -1.2735 -0.9349 0.1548 +v -1.2735 -0.9349 2.5926 +v -1.3424 -1.0621 2.5926 +v -1.3424 -1.0621 0.1548 +v -1.3424 -1.1785 0.1548 +v -1.3424 -1.1785 2.5926 +v -1.2735 -1.0202 0.1548 +v -1.2735 -1.0202 2.5926 +v -1.2735 -0.9776 2.5926 +v -1.2735 -0.9776 0.1548 +v -1.2735 -1.2204 0.1548 +v -1.2735 -1.2204 2.5926 +v -1.3424 -1.3476 2.5926 +v -1.3424 -1.3476 0.1548 +v -1.3424 -1.4640 0.1548 +v -1.3424 -1.4640 2.5926 +v -1.2735 -1.3057 0.1548 +v -1.2735 -1.3057 2.5926 +v -1.2735 -1.2631 2.5926 +v -1.2735 -1.2631 0.1548 +v -1.2735 -1.5059 0.1548 +v -1.2735 -1.5059 2.5926 +v -1.3424 -1.6331 2.5926 +v -1.3424 -1.6331 0.1548 +v -1.3424 -1.7495 0.1548 +v -1.3424 -1.7495 2.5926 +v -1.2735 -1.5912 0.1548 +v -1.2735 -1.5912 2.5926 +v -1.2735 -1.5486 2.5926 +v -1.2735 -1.5486 0.1548 +v -1.2735 -1.7914 0.1548 +v -1.2735 -1.7914 2.5926 +v -1.3424 -1.9186 2.5926 +v -1.3424 -1.9186 0.1548 +v -1.3424 -2.0350 0.1548 +v -1.3424 -2.0350 2.5926 +v -1.2735 -1.8767 0.1548 +v -1.2735 -1.8767 2.5926 +v -1.2735 -1.8341 2.5926 +v -1.2735 -1.8341 0.1548 +v -1.2735 -2.0769 0.1548 +v -1.2735 -2.0769 2.5926 +v -1.3424 -2.2041 2.5926 +v -1.3424 -2.2041 0.1548 +v -1.3424 -2.3205 0.1548 +v -1.3424 -2.3205 2.5926 +v -1.2735 -2.1622 0.1548 +v -1.2735 -2.1622 2.5926 +v -1.2735 -2.1196 2.5926 +v -1.2735 -2.1196 0.1548 +v -1.2735 -2.3624 0.1548 +v -1.2735 -2.3624 2.5926 +v -1.3424 -2.4896 2.5926 +v -1.3424 -2.4896 0.1548 +v -1.3424 -2.6060 0.1548 +v -1.3424 -2.6060 2.5926 +v -1.2735 -2.4477 0.1548 +v -1.2735 -2.4477 2.5926 +v -1.2735 -2.4051 2.5926 +v -1.2735 -2.4051 0.1548 +v -1.2735 -2.6479 0.1548 +v -1.2735 -2.6479 2.5926 +v -1.3424 -3.0606 2.5926 +v -1.3424 -3.0606 0.1548 +v -1.3424 -3.1770 0.1548 +v -1.3424 -3.1770 2.5926 +v -1.2735 -3.0187 0.1548 +v -1.2735 -3.0187 2.5926 +v -1.2735 -2.9761 2.5926 +v -1.2735 -2.9334 2.5926 +v -1.2735 -2.9334 0.1548 +v -1.2735 -2.9761 0.1548 +v -1.2735 -3.2189 0.1548 +v -1.2735 -3.2189 2.5926 +v -1.3424 -3.3461 2.5926 +v -1.3424 -3.3461 0.1548 +v -1.3424 -3.4625 0.1548 +v -1.3424 -3.4625 2.5926 +v -1.2735 -3.5044 2.5926 +v -1.2735 -3.5044 0.1548 +v -1.2735 -3.5482 0.1548 +v -1.2735 -3.5482 2.5926 +v -1.2735 -3.3042 0.1548 +v -1.2735 -3.3042 2.5926 +v -1.2735 -3.2616 2.5926 +v -1.2735 -3.2616 0.1548 +v -1.3424 -2.7751 2.5926 +v -1.3424 -2.7751 0.1548 +v -1.3424 -2.8915 0.1548 +v -1.3424 -2.8915 2.5926 +v -1.2735 -2.7332 0.1548 +v -1.2735 -2.7332 2.5926 +v -1.2735 -2.6906 2.5926 +v -1.2735 -2.6906 0.1548 +v -1.3406 8.2440 0.1548 +v -1.3406 8.3584 0.1548 +v -1.3406 8.3584 2.5926 +v -1.3406 8.2440 2.5926 +v -1.2715 8.4450 2.5926 +v -1.2717 8.4003 2.5926 +v -1.2717 8.4003 0.1548 +v -1.2715 8.4450 0.1548 +v -1.2717 8.2021 0.1548 +v -1.2717 8.2021 2.5926 +v -1.3406 7.9585 0.1548 +v -1.3406 8.0729 0.1548 +v -1.3406 8.0729 2.5926 +v -1.3406 7.9585 2.5926 +v -1.2715 8.1584 2.5926 +v -1.2717 8.1148 2.5926 +v -1.2717 8.1148 0.1548 +v -1.2715 8.1584 0.1548 +v -1.2717 7.9166 0.1548 +v -1.2717 7.9166 2.5926 +v -1.3406 7.6730 0.1548 +v -1.3406 7.7874 0.1548 +v -1.3406 7.7874 2.5926 +v -1.3406 7.6730 2.5926 +v -1.2715 7.8729 2.5926 +v -1.2717 7.8293 2.5926 +v -1.2717 7.8293 0.1548 +v -1.2715 7.8729 0.1548 +v -1.2717 7.6311 0.1548 +v -1.2717 7.6311 2.5926 +v -1.3406 7.1020 0.1548 +v -1.3406 7.2164 0.1548 +v -1.3406 7.2164 2.5926 +v -1.3406 7.1020 2.5926 +v -1.2715 7.3019 2.5926 +v -1.2717 7.2583 2.5926 +v -1.2717 7.2583 0.1548 +v -1.2715 7.3019 0.1548 +v -1.2717 7.3456 0.1548 +v -1.2717 7.3456 2.5926 +v -1.2717 7.0601 0.1548 +v -1.2717 7.0601 2.5926 +v -1.3406 6.8165 0.1548 +v -1.3406 6.9309 0.1548 +v -1.3406 6.9309 2.5926 +v -1.3406 6.8165 2.5926 +v -1.2715 7.0164 2.5926 +v -1.2717 6.9728 2.5926 +v -1.2717 6.9728 0.1548 +v -1.2715 7.0164 0.1548 +v -1.2717 6.7746 0.1548 +v -1.2717 6.7746 2.5926 +v -1.3406 5.9600 0.1548 +v -1.3406 6.0744 0.1548 +v -1.3406 6.0744 2.5926 +v -1.3406 5.9600 2.5926 +v -1.2715 6.1599 2.5926 +v -1.2717 6.1163 2.5926 +v -1.2717 6.1163 0.1548 +v -1.2715 6.1599 0.1548 +v -1.2717 6.2036 0.1548 +v -1.2717 6.2036 2.5926 +v -1.2717 5.9181 0.1548 +v -1.2717 5.9181 2.5926 +v -1.3406 7.3875 0.1548 +v -1.3406 7.5019 0.1548 +v -1.3406 7.5019 2.5926 +v -1.3406 7.3875 2.5926 +v -1.2715 7.5874 2.5926 +v -1.2717 7.5438 2.5926 +v -1.2717 7.5438 0.1548 +v -1.2715 7.5874 0.1548 +v -1.3406 6.5310 0.1548 +v -1.3406 6.6454 0.1548 +v -1.3406 6.6454 2.5926 +v -1.3406 6.5310 2.5926 +v -1.2715 6.7309 2.5926 +v -1.2717 6.6873 2.5926 +v -1.2717 6.6873 0.1548 +v -1.2715 6.7309 0.1548 +v -1.2717 6.4891 0.1548 +v -1.2717 6.4891 2.5926 +v -1.3406 6.2455 0.1548 +v -1.3406 6.3599 0.1548 +v -1.3406 6.3599 2.5926 +v -1.3406 6.2455 2.5926 +v -1.2715 6.4454 2.5926 +v -1.2717 6.4018 2.5926 +v -1.2717 6.4018 0.1548 +v -1.2715 6.4454 0.1548 +v -1.3406 5.6745 0.1548 +v -1.3406 5.7889 0.1548 +v -1.3406 5.7889 2.5926 +v -1.3406 5.6745 2.5926 +v -1.2715 5.8744 2.5926 +v -1.2717 5.8308 2.5926 +v -1.2717 5.8308 0.1548 +v -1.2715 5.8744 0.1548 +v -1.2717 5.6326 0.1548 +v -1.2717 5.6326 2.5926 +v -1.3406 5.3890 0.1548 +v -1.3406 5.5034 0.1548 +v -1.3406 5.5034 2.5926 +v -1.3406 5.3890 2.5926 +v -1.2715 5.5889 2.5926 +v -1.2717 5.5453 2.5926 +v -1.2717 5.5453 0.1548 +v -1.2715 5.5889 0.1548 +v -1.2717 5.3471 0.1548 +v -1.2717 5.3471 2.5926 +v -1.3406 4.2470 0.1548 +v -1.3406 4.3614 0.1548 +v -1.3406 4.3614 2.5926 +v -1.3406 4.2470 2.5926 +v -1.2715 4.4469 2.5926 +v -1.2717 4.4033 2.5926 +v -1.2717 4.4033 0.1548 +v -1.2715 4.4469 0.1548 +v -1.2717 4.4906 0.1548 +v -1.2717 4.4906 2.5926 +v -1.2717 4.2051 0.1548 +v -1.2717 4.2051 2.5926 +v -1.3406 3.9615 0.1548 +v -1.3406 4.0759 0.1548 +v -1.3406 4.0759 2.5926 +v -1.3406 3.9615 2.5926 +v -1.2715 4.1614 2.5926 +v -1.2717 4.1178 2.5926 +v -1.2717 4.1178 0.1548 +v -1.2715 4.1614 0.1548 +v -1.2717 3.9196 0.1548 +v -1.2717 3.9196 2.5926 +v -1.3406 5.1035 0.1548 +v -1.3406 5.2179 0.1548 +v -1.3406 5.2179 2.5926 +v -1.3406 5.1035 2.5926 +v -1.2715 5.3034 2.5926 +v -1.2717 5.2598 2.5926 +v -1.2717 5.2598 0.1548 +v -1.2715 5.3034 0.1548 +v -1.2717 5.0616 0.1548 +v -1.2717 5.0616 2.5926 +v -1.3406 4.5325 0.1548 +v -1.3406 4.6469 0.1548 +v -1.3406 4.6469 2.5926 +v -1.3406 4.5325 2.5926 +v -1.2715 4.7324 2.5926 +v -1.2717 4.6888 2.5926 +v -1.2717 4.6888 0.1548 +v -1.2715 4.7324 0.1548 +v -1.2717 4.7761 0.1548 +v -1.2717 4.7761 2.5926 +v -1.3406 4.8180 0.1548 +v -1.3406 4.9324 0.1548 +v -1.3406 4.9324 2.5926 +v -1.3406 4.8180 2.5926 +v -1.2715 5.0179 2.5926 +v -1.2717 4.9743 2.5926 +v -1.2717 4.9743 0.1548 +v -1.2715 5.0179 0.1548 +v -1.3406 3.6760 0.1548 +v -1.3406 3.7904 0.1548 +v -1.3406 3.7904 2.5926 +v -1.3406 3.6760 2.5926 +v -1.2715 3.8759 2.5926 +v -1.2717 3.8323 2.5926 +v -1.2717 3.8323 0.1548 +v -1.2715 3.8759 0.1548 +v -1.2717 3.6341 0.1548 +v -1.2717 3.6341 2.5926 +v -1.3406 3.1050 0.1548 +v -1.3406 3.2194 0.1548 +v -1.3406 3.2194 2.5926 +v -1.3406 3.1050 2.5926 +v -1.2715 3.3049 2.5926 +v -1.2717 3.2613 2.5926 +v -1.2717 3.2613 0.1548 +v -1.2715 3.3049 0.1548 +v -1.2717 3.3486 0.1548 +v -1.2717 3.3486 2.5926 +v -1.2717 3.0631 0.1548 +v -1.2717 3.0631 2.5926 +v -1.3406 2.5340 0.1548 +v -1.3406 2.6484 0.1548 +v -1.3406 2.6484 2.5926 +v -1.3406 2.5340 2.5926 +v -1.2715 2.7339 2.5926 +v -1.2717 2.6903 2.5926 +v -1.2717 2.6903 0.1548 +v -1.2715 2.7339 0.1548 +v -1.2717 2.7776 0.1548 +v -1.2717 2.7776 2.5926 +v -1.2717 2.4921 0.1548 +v -1.2717 2.4921 2.5926 +v -1.3406 1.9630 0.1548 +v -1.3406 2.0774 0.1548 +v -1.3406 2.0774 2.5926 +v -1.3406 1.9630 2.5926 +v -1.2715 2.1629 2.5926 +v -1.2717 2.1193 2.5926 +v -1.2717 2.1193 0.1548 +v -1.2715 2.1629 0.1548 +v -1.2717 2.2066 0.1548 +v -1.2717 2.2066 2.5926 +v -1.2717 1.9211 0.1548 +v -1.2717 1.9211 2.5926 +v -1.3406 1.6775 0.1548 +v -1.3406 1.7919 0.1548 +v -1.3406 1.7919 2.5926 +v -1.3406 1.6775 2.5926 +v -1.2715 1.8774 2.5926 +v -1.2717 1.8338 2.5926 +v -1.2717 1.8338 0.1548 +v -1.2715 1.8774 0.1548 +v -1.2717 1.6356 0.1548 +v -1.2717 1.6356 2.5926 +v -1.3406 3.3905 0.1548 +v -1.3406 3.5049 0.1548 +v -1.3406 3.5049 2.5926 +v -1.3406 3.3905 2.5926 +v -1.2715 3.5904 2.5926 +v -1.2717 3.5468 2.5926 +v -1.2717 3.5468 0.1548 +v -1.2715 3.5904 0.1548 +v -1.3406 2.8195 0.1548 +v -1.3406 2.9339 0.1548 +v -1.3406 2.9339 2.5926 +v -1.3406 2.8195 2.5926 +v -1.2715 3.0194 2.5926 +v -1.2717 2.9758 2.5926 +v -1.2717 2.9758 0.1548 +v -1.2715 3.0194 0.1548 +v -1.3406 2.2485 0.1548 +v -1.3406 2.3629 0.1548 +v -1.3406 2.3629 2.5926 +v -1.3406 2.2485 2.5926 +v -1.2715 2.4484 2.5926 +v -1.2717 2.4048 2.5926 +v -1.2717 2.4048 0.1548 +v -1.2715 2.4484 0.1548 +v -1.3406 1.3920 0.1548 +v -1.3406 1.5064 0.1548 +v -1.3406 1.5064 2.5926 +v -1.3406 1.3920 2.5926 +v -1.2715 1.5919 2.5926 +v -1.2717 1.5483 2.5926 +v -1.2717 1.5483 0.1548 +v -1.2715 1.5919 0.1548 +v -1.2717 1.3501 0.1548 +v -1.2717 1.3501 2.5926 +v -1.3406 1.1065 0.1548 +v -1.3406 1.2209 0.1548 +v -1.3406 1.2209 2.5926 +v -1.3406 1.1065 2.5926 +v -1.2715 1.3064 2.5926 +v -1.2717 1.2628 2.5926 +v -1.2717 1.2628 0.1548 +v -1.2715 1.3064 0.1548 +v -1.2717 1.0646 0.1548 +v -1.2717 1.0646 2.5926 +v -1.3406 0.8210 0.1548 +v -1.3406 0.9354 0.1548 +v -1.3406 0.9354 2.5926 +v -1.3406 0.8210 2.5926 +v -1.2715 1.0209 2.5926 +v -1.2717 0.9773 2.5926 +v -1.2717 0.9773 0.1548 +v -1.2715 1.0209 0.1548 +v -1.2717 0.7791 0.1548 +v -1.2717 0.7791 2.5926 +v -1.3406 0.5355 0.1548 +v -1.3406 0.6499 0.1548 +v -1.3406 0.6499 2.5926 +v -1.3406 0.5355 2.5926 +v -1.2715 0.7354 2.5926 +v -1.2717 0.6918 2.5926 +v -1.2717 0.6918 0.1548 +v -1.2715 0.7354 0.1548 +v -1.2717 0.4936 0.1548 +v -1.2717 0.4936 2.5926 +v -1.3406 0.2500 0.1548 +v -1.3406 0.3644 0.1548 +v -1.3406 0.3644 2.5926 +v -1.3406 0.2500 2.5926 +v -1.2715 0.4499 2.5926 +v -1.2717 0.4063 2.5926 +v -1.2717 0.4063 0.1548 +v -1.2715 0.4499 0.1548 +v -1.2717 0.2081 0.1548 +v -1.2717 0.2081 2.5926 +v -1.3406 -0.0355 0.1548 +v -1.3406 0.0789 0.1548 +v -1.3406 0.0789 2.5926 +v -1.3406 -0.0355 2.5926 +v -1.2715 0.1644 2.5926 +v -1.2717 0.1208 2.5926 +v -1.2717 0.1208 0.1548 +v -1.2715 0.1644 0.1548 +v -1.2717 -0.0774 0.1548 +v -1.2717 -0.0774 2.5926 +v -1.3406 -0.3210 0.1548 +v -1.3406 -0.2066 0.1548 +v -1.3406 -0.2066 2.5926 +v -1.3406 -0.3210 2.5926 +v -1.2715 -0.1211 2.5926 +v -1.2717 -0.1647 2.5926 +v -1.2717 -0.1647 0.1548 +v -1.2715 -0.1211 0.1548 +v -1.2717 -0.3629 0.1548 +v -1.2717 -0.3629 2.5926 +v -1.3406 -0.6065 0.1548 +v -1.3406 -0.4921 0.1548 +v -1.3406 -0.4921 2.5926 +v -1.3406 -0.6065 2.5926 +v -1.2715 -0.4066 2.5926 +v -1.2717 -0.4502 2.5926 +v -1.2717 -0.4502 0.1548 +v -1.2715 -0.4066 0.1548 +v -1.2717 -0.6484 0.1548 +v -1.2717 -0.6484 2.5926 +v -1.3406 -0.8920 0.1548 +v -1.3406 -0.7776 0.1548 +v -1.3406 -0.7776 2.5926 +v -1.3406 -0.8920 2.5926 +v -1.2715 -0.6921 2.5926 +v -1.2717 -0.7357 2.5926 +v -1.2717 -0.7357 0.1548 +v -1.2715 -0.6921 0.1548 +v -1.2717 -0.9339 0.1548 +v -1.2717 -0.9339 2.5926 +v -1.3406 -1.1775 0.1548 +v -1.3406 -1.0631 0.1548 +v -1.3406 -1.0631 2.5926 +v -1.3406 -1.1775 2.5926 +v -1.2715 -0.9776 2.5926 +v -1.2717 -1.0212 2.5926 +v -1.2717 -1.0212 0.1548 +v -1.2715 -0.9776 0.1548 +v -1.2717 -1.2194 0.1548 +v -1.2717 -1.2194 2.5926 +v -1.3406 -1.4630 0.1548 +v -1.3406 -1.3486 0.1548 +v -1.3406 -1.3486 2.5926 +v -1.3406 -1.4630 2.5926 +v -1.2715 -1.2631 2.5926 +v -1.2717 -1.3067 2.5926 +v -1.2717 -1.3067 0.1548 +v -1.2715 -1.2631 0.1548 +v -1.2717 -1.5049 0.1548 +v -1.2717 -1.5049 2.5926 +v -1.3406 -1.7485 0.1548 +v -1.3406 -1.6341 0.1548 +v -1.3406 -1.6341 2.5926 +v -1.3406 -1.7485 2.5926 +v -1.2715 -1.5486 2.5926 +v -1.2717 -1.5922 2.5926 +v -1.2717 -1.5922 0.1548 +v -1.2715 -1.5486 0.1548 +v -1.2717 -1.7904 0.1548 +v -1.2717 -1.7904 2.5926 +v -1.3406 -2.0340 0.1548 +v -1.3406 -1.9196 0.1548 +v -1.3406 -1.9196 2.5926 +v -1.3406 -2.0340 2.5926 +v -1.2715 -1.8341 2.5926 +v -1.2717 -1.8777 2.5926 +v -1.2717 -1.8777 0.1548 +v -1.2715 -1.8341 0.1548 +v -1.2717 -2.0759 0.1548 +v -1.2717 -2.0759 2.5926 +v -1.3406 -2.3195 0.1548 +v -1.3406 -2.2051 0.1548 +v -1.3406 -2.2051 2.5926 +v -1.3406 -2.3195 2.5926 +v -1.2715 -2.1196 2.5926 +v -1.2717 -2.1632 2.5926 +v -1.2717 -2.1632 0.1548 +v -1.2715 -2.1196 0.1548 +v -1.2717 -2.3614 0.1548 +v -1.2717 -2.3614 2.5926 +v -1.3406 -2.6050 0.1548 +v -1.3406 -2.4906 0.1548 +v -1.3406 -2.4906 2.5926 +v -1.3406 -2.6050 2.5926 +v -1.2715 -2.4051 2.5926 +v -1.2717 -2.4487 2.5926 +v -1.2717 -2.4487 0.1548 +v -1.2715 -2.4051 0.1548 +v -1.2717 -2.6469 0.1548 +v -1.2717 -2.6469 2.5926 +v -1.3406 -3.1760 0.1548 +v -1.3406 -3.0616 0.1548 +v -1.3406 -3.0616 2.5926 +v -1.3406 -3.1760 2.5926 +v -1.2715 -2.9761 2.5926 +v -1.2717 -3.0197 2.5926 +v -1.2717 -3.0197 0.1548 +v -1.2715 -2.9761 0.1548 +v -1.2717 -2.9324 0.1548 +v -1.2717 -2.9324 2.5926 +v -1.2717 -3.2179 0.1548 +v -1.2717 -3.2179 2.5926 +v -1.3406 -3.4615 0.1548 +v -1.3406 -3.3471 0.1548 +v -1.3406 -3.3471 2.5926 +v -1.3406 -3.4615 2.5926 +v -1.2715 -3.5482 0.1548 +v -1.2717 -3.5034 0.1548 +v -1.2717 -3.5034 2.5926 +v -1.2715 -3.5482 2.5926 +v -1.2715 -3.2616 2.5926 +v -1.2717 -3.3052 2.5926 +v -1.2717 -3.3052 0.1548 +v -1.2715 -3.2616 0.1548 +v -1.3406 -2.8905 0.1548 +v -1.3406 -2.7761 0.1548 +v -1.3406 -2.7761 2.5926 +v -1.3406 -2.8905 2.5926 +v -1.2715 -2.6906 2.5926 +v -1.2717 -2.7342 2.5926 +v -1.2717 -2.7342 0.1548 +v -1.2715 -2.6906 0.1548 +# 844 vertices + +vn -1.0000 0.0000 -0.0000 +vn -0.5196 -0.8544 -0.0000 +vn -0.5196 0.8544 -0.0000 +vn -1.0000 -0.0000 -0.0000 +vn -0.5196 0.8544 0.0000 +vn 1.0000 -0.0000 0.0000 +vn 1.0000 -0.0057 0.0000 +vn 0.5196 0.8544 0.0000 +vn 0.5196 -0.8544 0.0000 +vn 1.0000 0.0000 0.0000 +vn 0.5196 -0.8544 -0.0000 +vn 1.0000 0.0057 0.0000 +# 12 vertex normals + +vt 0.6632 0.3523 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.4225 0.0000 +vt 0.6632 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.3523 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.6646 0.4225 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0588 0.0885 0.0000 +vt 0.0588 0.1588 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0588 0.0885 0.0000 +vt 0.0588 0.1588 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0588 0.0885 0.0000 +vt 0.0588 0.1588 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0588 0.0885 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0588 0.1588 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0588 0.0885 0.0000 +vt 0.0588 0.1588 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0588 0.0885 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0588 0.1588 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0588 0.0885 0.0000 +vt 0.0588 0.1588 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0588 0.0885 0.0000 +vt 0.0588 0.1588 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0588 0.0885 0.0000 +vt 0.0588 0.1588 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0588 0.0885 0.0000 +vt 0.0588 0.1588 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0588 0.0885 0.0000 +vt 0.0588 0.1588 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0588 0.0885 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0588 0.1588 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0588 0.0885 0.0000 +vt 0.0588 0.1588 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0588 0.0885 0.0000 +vt 0.0588 0.1588 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0588 0.0885 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0588 0.1588 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0588 0.0885 0.0000 +vt 0.0588 0.1588 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0588 0.0885 0.0000 +vt 0.0588 0.1588 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0588 0.0885 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0588 0.1588 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0588 0.0885 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0588 0.1588 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0588 0.0885 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0588 0.1588 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0588 0.0885 0.0000 +vt 0.0588 0.1588 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0588 0.0885 0.0000 +vt 0.0588 0.1588 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0588 0.0885 0.0000 +vt 0.0588 0.1588 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0588 0.0885 0.0000 +vt 0.0588 0.1588 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0588 0.0885 0.0000 +vt 0.0588 0.1588 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0588 0.0885 0.0000 +vt 0.0588 0.1588 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0588 0.0885 0.0000 +vt 0.0588 0.1588 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0588 0.0885 0.0000 +vt 0.0588 0.1588 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0588 0.0885 0.0000 +vt 0.0588 0.1588 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0588 0.0885 0.0000 +vt 0.0588 0.1588 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0588 0.0885 0.0000 +vt 0.0588 0.1588 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0588 0.0885 0.0000 +vt 0.0588 0.1588 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0588 0.0885 0.0000 +vt 0.0588 0.1588 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0588 0.0885 0.0000 +vt 0.0588 0.1588 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0588 0.0885 0.0000 +vt 0.0588 0.1588 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0588 0.0885 0.0000 +vt 0.0588 0.1588 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0588 0.0885 0.0000 +vt 0.0588 0.1588 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0588 0.0885 0.0000 +vt 0.0588 0.1588 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0588 0.0885 0.0000 +vt 0.0588 0.1588 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0588 0.0885 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0588 0.1588 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0588 0.1588 0.0000 +vt 0.0588 0.0885 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0588 0.0885 0.0000 +vt 0.0588 0.1588 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.1588 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0573 0.0885 0.0000 +vt 0.0588 0.0885 0.0000 +vt 0.0588 0.1588 0.0000 +vt 0.0587 0.1588 0.0000 +vt 0.0587 0.0885 0.0000 +# 844 texture coords + +# g Wall_Left +# usemtl ShippingContainer +# s off +# f 642/648/50 643/649/50 644/646/50 645/647/50 +# f 646/652/50 647/653/50 648/650/50 649/651/50 +# f 645/647/51 644/646/51 650/654/51 651/655/51 +# f 643/649/52 642/648/52 647/653/52 646/652/52 +# f 652/658/50 653/659/50 654/656/50 655/657/50 +# f 656/661/53 657/662/53 658/663/53 651/655/53 650/654/53 659/660/53 +# f 655/657/51 654/656/51 660/664/51 661/665/51 +# f 653/659/54 652/658/54 657/662/54 656/661/54 +# f 662/668/50 663/669/50 664/666/50 665/667/50 +# f 666/671/50 667/672/50 668/673/50 661/665/50 660/664/50 669/670/50 +# f 665/667/51 664/666/51 670/674/51 671/675/51 +# f 663/669/54 662/668/54 667/672/54 666/671/54 +# f 672/678/50 673/679/50 674/676/50 675/677/50 +# f 676/683/53 677/684/53 678/685/53 679/680/53 680/681/53 681/682/53 +# f 675/677/51 674/676/51 682/686/51 683/687/51 +# f 673/679/54 672/678/54 677/684/54 676/683/54 +# f 684/690/53 685/691/53 686/688/53 687/689/53 +# f 688/693/50 689/694/50 690/695/50 683/687/50 682/686/50 691/692/50 +# f 687/689/51 686/688/51 692/696/51 693/697/51 +# f 685/691/52 684/690/52 689/694/52 688/693/52 +# f 694/700/50 695/701/50 696/698/50 697/699/50 +# f 698/705/50 699/706/50 700/707/50 701/702/50 702/703/50 703/704/50 +# f 697/699/51 696/698/51 704/708/51 705/709/51 +# f 695/701/52 694/700/52 699/706/52 698/705/52 +# f 706/712/50 707/713/50 708/710/50 709/711/50 +# f 710/715/50 711/716/50 712/717/50 671/675/50 670/674/50 713/714/50 +# f 709/711/51 708/710/51 680/681/51 679/680/51 +# f 707/713/52 706/712/52 711/716/52 710/715/52 +# f 714/720/50 715/721/50 716/718/50 717/719/50 +# f 718/723/50 719/724/50 720/725/50 693/697/50 692/696/50 721/722/50 +# f 717/719/51 716/718/51 722/726/51 723/727/51 +# f 715/721/52 714/720/52 719/724/52 718/723/52 +# f 724/730/50 725/731/50 726/728/50 727/729/50 +# f 728/733/53 729/734/53 730/735/53 723/727/53 722/726/53 731/732/53 +# f 727/729/51 726/728/51 702/703/51 701/702/51 +# f 725/731/54 724/730/54 729/734/54 728/733/54 +# f 732/738/50 733/739/50 734/736/50 735/737/50 +# f 736/741/50 737/742/50 738/743/50 705/709/50 704/708/50 739/740/50 +# f 735/737/51 734/736/51 740/744/51 741/745/51 +# f 733/739/52 732/738/52 737/742/52 736/741/52 +# f 742/748/50 743/749/50 744/746/50 745/747/50 +# f 746/751/50 747/752/50 748/753/50 741/745/50 740/744/50 749/750/50 +# f 745/747/51 744/746/51 750/754/51 751/755/51 +# f 743/749/54 742/748/54 747/752/54 746/751/54 +# f 752/758/50 753/759/50 754/756/50 755/757/50 +# f 756/763/53 757/764/53 758/765/53 759/760/53 760/761/53 761/762/53 +# f 755/757/51 754/756/51 762/766/51 763/767/51 +# f 753/759/54 752/758/54 757/764/54 756/763/54 +# f 764/770/50 765/771/50 766/768/50 767/769/50 +# f 768/773/50 769/774/50 770/775/50 763/767/50 762/766/50 771/772/50 +# f 767/769/51 766/768/51 772/776/51 773/777/51 +# f 765/771/54 764/770/54 769/774/54 768/773/54 +# f 774/780/50 775/781/50 776/778/50 777/779/50 +# f 778/783/50 779/784/50 780/785/50 751/755/50 750/754/50 781/782/50 +# f 777/779/51 776/778/51 782/786/51 783/787/51 +# f 775/781/52 774/780/52 779/784/52 778/783/52 +# f 784/790/50 785/791/50 786/788/50 787/789/50 +# f 788/795/50 789/796/50 790/797/50 791/792/50 792/793/50 793/794/50 +# f 787/789/51 786/788/51 760/761/51 759/760/51 +# f 785/791/54 784/790/54 789/796/54 788/795/54 +# f 794/800/50 795/801/50 796/798/50 797/799/50 +# f 798/803/53 799/804/53 800/805/53 783/787/53 782/786/53 801/802/53 +# f 797/799/51 796/798/51 792/793/51 791/792/51 +# f 795/801/52 794/800/52 799/804/52 798/803/52 +# f 802/808/50 803/809/50 804/806/50 805/807/50 +# f 806/811/53 807/812/53 808/813/53 773/777/53 772/776/53 809/810/53 +# f 805/807/51 804/806/51 810/814/51 811/815/51 +# f 803/809/54 802/808/54 807/812/54 806/811/54 +# f 812/818/50 813/819/50 814/816/50 815/817/50 +# f 816/823/50 817/824/50 818/825/50 819/820/50 820/821/50 821/822/50 +# f 815/817/51 814/816/51 822/826/51 823/827/51 +# f 813/819/54 812/818/54 817/824/54 816/823/54 +# f 824/830/50 825/831/50 826/828/50 827/829/50 +# f 828/835/50 829/836/50 830/837/50 831/832/50 832/833/50 833/834/50 +# f 827/829/51 826/828/51 834/838/51 835/839/51 +# f 825/831/54 824/830/54 829/836/54 828/835/54 +# f 836/842/50 837/843/50 838/840/50 839/841/50 +# f 840/847/53 841/848/53 842/849/53 843/844/53 844/845/53 845/846/53 +# f 839/841/51 838/840/51 846/850/51 847/851/51 +# f 837/843/54 836/842/54 841/848/54 840/847/54 +# f 848/854/50 849/855/50 850/852/50 851/853/50 +# f 852/857/50 853/858/50 854/859/50 847/851/50 846/850/50 855/856/50 +# f 851/853/51 850/852/51 856/860/51 857/861/51 +# f 849/855/54 848/854/54 853/858/54 852/857/54 +# f 858/864/50 859/865/50 860/862/50 861/863/50 +# f 862/867/53 863/868/53 864/869/53 811/815/53 810/814/53 865/866/53 +# f 861/863/51 860/862/51 820/821/51 819/820/51 +# f 859/865/54 858/864/54 863/868/54 862/867/54 +# f 866/872/50 867/873/50 868/870/50 869/871/50 +# f 870/875/50 871/876/50 872/877/50 823/827/50 822/826/50 873/874/50 +# f 869/871/51 868/870/51 832/833/51 831/832/51 +# f 867/873/54 866/872/54 871/876/54 870/875/54 +# f 874/880/50 875/881/50 876/878/50 877/879/50 +# f 878/883/50 879/884/50 880/885/50 835/839/50 834/838/50 881/882/50 +# f 877/879/51 876/878/51 844/845/51 843/844/51 +# f 875/881/54 874/880/54 879/884/54 878/883/54 +# f 882/888/50 883/889/50 884/886/50 885/887/50 +# f 886/891/53 887/892/53 888/893/53 857/861/53 856/860/53 889/890/53 +# f 885/887/51 884/886/51 890/894/51 891/895/51 +# f 883/889/54 882/888/54 887/892/54 886/891/54 +# f 892/898/50 893/899/50 894/896/50 895/897/50 +# f 896/901/50 897/902/50 898/903/50 891/895/50 890/894/50 899/900/50 +# f 895/897/51 894/896/51 900/904/51 901/905/51 +# f 893/899/54 892/898/54 897/902/54 896/901/54 +# f 902/908/50 903/909/50 904/906/50 905/907/50 +# f 906/911/50 907/912/50 908/913/50 901/905/50 900/904/50 909/910/50 +# f 905/907/51 904/906/51 910/914/51 911/915/51 +# f 903/909/54 902/908/54 907/912/54 906/911/54 +# f 912/918/50 913/919/50 914/916/50 915/917/50 +# f 916/921/53 917/922/53 918/923/53 911/915/53 910/914/53 919/920/53 +# f 915/917/51 914/916/51 920/924/51 921/925/51 +# f 913/919/54 912/918/54 917/922/54 916/921/54 +# f 922/928/50 923/929/50 924/926/50 925/927/50 +# f 926/931/50 927/932/50 928/933/50 921/925/50 920/924/50 929/930/50 +# f 925/927/51 924/926/51 930/934/51 931/935/51 +# f 923/929/54 922/928/54 927/932/54 926/931/54 +# f 932/938/50 933/939/50 934/936/50 935/937/50 +# f 936/941/50 937/942/50 938/943/50 931/935/50 930/934/50 939/940/50 +# f 935/937/51 934/936/51 940/944/51 941/945/51 +# f 933/939/54 932/938/54 937/942/54 936/941/54 +# f 942/948/50 943/949/50 944/946/50 945/947/50 +# f 946/951/53 947/952/53 948/953/53 941/945/53 940/944/53 949/950/53 +# f 945/947/51 944/946/51 950/954/51 951/955/51 +# f 943/949/52 942/948/52 947/952/52 946/951/52 +# f 952/958/50 953/959/50 954/956/50 955/957/50 +# f 956/961/50 957/962/50 958/963/50 951/955/50 950/954/50 959/960/50 +# f 955/957/51 954/956/51 960/964/51 961/965/51 +# f 953/959/54 952/958/54 957/962/54 956/961/54 +# f 962/968/50 963/969/50 964/966/50 965/967/50 +# f 966/971/50 967/972/50 968/973/50 961/965/50 960/964/50 969/970/50 +# f 965/967/51 964/966/51 970/974/51 971/975/51 +# f 963/969/54 962/968/54 967/972/54 966/971/54 +# f 972/978/50 973/979/50 974/976/50 975/977/50 +# f 976/981/50 977/982/50 978/983/50 971/975/50 970/974/50 979/980/50 +# f 975/977/51 974/976/51 980/984/51 981/985/51 +# f 973/979/54 972/978/54 977/982/54 976/981/54 +# f 982/988/50 983/989/50 984/986/50 985/987/50 +# f 986/991/53 987/992/53 988/993/53 981/985/53 980/984/53 989/990/53 +# f 985/987/51 984/986/51 990/994/51 991/995/51 +# f 983/989/52 982/988/52 987/992/52 986/991/52 +# f 992/998/50 993/999/50 994/996/50 995/997/50 +# f 996/1001/53 997/1002/53 998/1003/53 991/995/53 990/994/53 999/1000/53 +# f 995/997/51 994/996/51 1000/1004/51 1001/1005/51 +# f 993/999/54 992/998/54 997/1002/54 996/1001/54 +# f 1002/1008/50 1003/1009/50 1004/1006/50 1005/1007/50 +# f 1006/1011/50 1007/1012/50 1008/1013/50 1001/1005/50 1000/1004/50 1009/1010/50 +# f 1005/1007/51 1004/1006/51 1010/1014/51 1011/1015/51 +# f 1003/1009/54 1002/1008/54 1007/1012/54 1006/1011/54 +# f 1012/1018/50 1013/1019/50 1014/1016/50 1015/1017/50 +# f 1016/1021/53 1017/1022/53 1018/1023/53 1011/1015/53 1010/1014/53 1019/1020/53 +# f 1015/1017/51 1014/1016/51 1020/1024/51 1021/1025/51 +# f 1013/1019/54 1012/1018/54 1017/1022/54 1016/1021/54 +# f 1022/1028/50 1023/1029/50 1024/1026/50 1025/1027/50 +# f 1026/1031/50 1027/1032/50 1028/1033/50 1021/1025/50 1020/1024/50 1029/1030/50 +# f 1025/1027/51 1024/1026/51 1030/1034/51 1031/1035/51 +# f 1023/1029/54 1022/1028/54 1027/1032/54 1026/1031/54 +# f 1032/1038/50 1033/1039/50 1034/1036/50 1035/1037/50 +# f 1036/1043/53 1037/1044/53 1038/1045/53 1039/1040/53 1040/1041/53 1041/1042/53 +# f 1035/1037/51 1034/1036/51 1042/1046/51 1043/1047/51 +# f 1033/1039/54 1032/1038/54 1037/1044/54 1036/1043/54 +# f 1044/1050/50 1045/1051/50 1046/1048/50 1047/1049/50 +# f 1048/1054/50 1049/1055/50 1050/1052/50 1051/1053/50 +# f 1052/1057/50 1053/1058/50 1054/1059/50 1043/1047/50 1042/1046/50 1055/1056/50 +# f 1047/1049/51 1046/1048/51 1049/1055/51 1048/1054/51 +# f 1045/1051/54 1044/1050/54 1053/1058/54 1052/1057/54 +# f 1056/1062/50 1057/1063/50 1058/1060/50 1059/1061/50 +# f 1060/1065/50 1061/1066/50 1062/1067/50 1031/1035/50 1030/1034/50 1063/1064/50 +# f 1059/1061/51 1058/1060/51 1040/1041/51 1039/1040/51 +# f 1057/1063/54 1056/1062/54 1061/1066/54 1060/1065/54 +# f 1064/1070/55 1065/1071/55 1066/1068/55 1067/1069/55 +# f 1068/1074/56 1069/1075/56 1070/1072/56 1071/1073/56 +# f 1072/1077/57 1064/1070/57 1067/1069/57 1073/1076/57 +# f 1069/1075/58 1066/1068/58 1065/1071/58 1070/1072/58 +# f 1074/1080/55 1075/1081/55 1076/1078/55 1077/1079/55 +# f 1078/1083/59 1079/1084/59 1080/1085/59 1081/1082/59 1072/1077/59 1073/1076/59 +# f 1082/1087/57 1074/1080/57 1077/1079/57 1083/1086/57 +# f 1079/1084/58 1076/1078/58 1075/1081/58 1080/1085/58 +# f 1084/1090/55 1085/1091/55 1086/1088/55 1087/1089/55 +# f 1088/1093/55 1089/1094/55 1090/1095/55 1091/1092/55 1082/1087/55 1083/1086/55 +# f 1092/1097/57 1084/1090/57 1087/1089/57 1093/1096/57 +# f 1089/1094/58 1086/1088/58 1085/1091/58 1090/1095/58 +# f 1094/1100/55 1095/1101/55 1096/1098/55 1097/1099/55 +# f 1098/1105/59 1099/1106/59 1100/1107/59 1101/1102/59 1102/1103/59 1103/1104/59 +# f 1104/1109/57 1094/1100/57 1097/1099/57 1105/1108/57 +# f 1099/1106/58 1096/1098/58 1095/1101/58 1100/1107/58 +# f 1106/1112/59 1107/1113/59 1108/1110/59 1109/1111/59 +# f 1110/1115/55 1111/1116/55 1112/1117/55 1113/1114/55 1104/1109/55 1105/1108/55 +# f 1114/1119/57 1106/1112/57 1109/1111/57 1115/1118/57 +# f 1111/1116/58 1108/1110/58 1107/1113/58 1112/1117/58 +# f 1116/1122/59 1117/1123/59 1118/1120/59 1119/1121/59 +# f 1120/1127/55 1121/1128/55 1122/1129/55 1123/1124/55 1124/1125/55 1125/1126/55 +# f 1126/1131/57 1116/1122/57 1119/1121/57 1127/1130/57 +# f 1121/1128/60 1118/1120/60 1117/1123/60 1122/1129/60 +# f 1128/1134/55 1129/1135/55 1130/1132/55 1131/1133/55 +# f 1132/1137/55 1133/1138/55 1134/1139/55 1135/1136/55 1092/1097/55 1093/1096/55 +# f 1102/1103/57 1128/1134/57 1131/1133/57 1103/1104/57 +# f 1133/1138/58 1130/1132/58 1129/1135/58 1134/1139/58 +# f 1136/1142/55 1137/1143/55 1138/1140/55 1139/1141/55 +# f 1140/1145/59 1141/1146/59 1142/1147/59 1143/1144/59 1114/1119/59 1115/1118/59 +# f 1144/1149/57 1136/1142/57 1139/1141/57 1145/1148/57 +# f 1141/1146/58 1138/1140/58 1137/1143/58 1142/1147/58 +# f 1146/1152/55 1147/1153/55 1148/1150/55 1149/1151/55 +# f 1150/1155/59 1151/1156/59 1152/1157/59 1153/1154/59 1144/1149/59 1145/1148/59 +# f 1124/1125/57 1146/1152/57 1149/1151/57 1125/1126/57 +# f 1151/1156/58 1148/1150/58 1147/1153/58 1152/1157/58 +# f 1154/1160/55 1155/1161/55 1156/1158/55 1157/1159/55 +# f 1158/1163/59 1159/1164/59 1160/1165/59 1161/1162/59 1126/1131/59 1127/1130/59 +# f 1162/1167/57 1154/1160/57 1157/1159/57 1163/1166/57 +# f 1159/1164/58 1156/1158/58 1155/1161/58 1160/1165/58 +# f 1164/1170/59 1165/1171/59 1166/1168/59 1167/1169/59 +# f 1168/1173/55 1169/1174/55 1170/1175/55 1171/1172/55 1162/1167/55 1163/1166/55 +# f 1172/1177/57 1164/1170/57 1167/1169/57 1173/1176/57 +# f 1169/1174/60 1166/1168/60 1165/1171/60 1170/1175/60 +# f 1174/1180/55 1175/1181/55 1176/1178/55 1177/1179/55 +# f 1178/1185/59 1179/1186/59 1180/1187/59 1181/1182/59 1182/1183/59 1183/1184/59 +# f 1184/1189/57 1174/1180/57 1177/1179/57 1185/1188/57 +# f 1179/1186/60 1176/1178/60 1175/1181/60 1180/1187/60 +# f 1186/1192/55 1187/1193/55 1188/1190/55 1189/1191/55 +# f 1190/1195/55 1191/1196/55 1192/1197/55 1193/1194/55 1184/1189/55 1185/1188/55 +# f 1194/1199/57 1186/1192/57 1189/1191/57 1195/1198/57 +# f 1191/1196/60 1188/1190/60 1187/1193/60 1192/1197/60 +# f 1196/1202/55 1197/1203/55 1198/1200/55 1199/1201/55 +# f 1200/1205/59 1201/1206/59 1202/1207/59 1203/1204/59 1172/1177/59 1173/1176/59 +# f 1204/1209/57 1196/1202/57 1199/1201/57 1205/1208/57 +# f 1201/1206/60 1198/1200/60 1197/1203/60 1202/1207/60 +# f 1206/1212/59 1207/1213/59 1208/1210/59 1209/1211/59 +# f 1210/1217/55 1211/1218/55 1212/1219/55 1213/1214/55 1214/1215/55 1215/1216/55 +# f 1182/1183/57 1206/1212/57 1209/1211/57 1183/1184/57 +# f 1211/1218/60 1208/1210/60 1207/1213/60 1212/1219/60 +# f 1216/1222/55 1217/1223/55 1218/1220/55 1219/1221/55 +# f 1220/1225/59 1221/1226/59 1222/1227/59 1223/1224/59 1204/1209/59 1205/1208/59 +# f 1214/1215/57 1216/1222/57 1219/1221/57 1215/1216/57 +# f 1221/1226/58 1218/1220/58 1217/1223/58 1222/1227/58 +# f 1224/1230/55 1225/1231/55 1226/1228/55 1227/1229/55 +# f 1228/1233/59 1229/1234/59 1230/1235/59 1231/1232/59 1194/1199/59 1195/1198/59 +# f 1232/1237/57 1224/1230/57 1227/1229/57 1233/1236/57 +# f 1229/1234/58 1226/1228/58 1225/1231/58 1230/1235/58 +# f 1234/1240/55 1235/1241/55 1236/1238/55 1237/1239/55 +# f 1238/1245/55 1239/1246/55 1240/1247/55 1241/1242/55 1242/1243/55 1243/1244/55 +# f 1244/1249/57 1234/1240/57 1237/1239/57 1245/1248/57 +# f 1239/1246/58 1236/1238/58 1235/1241/58 1240/1247/58 +# f 1246/1252/55 1247/1253/55 1248/1250/55 1249/1251/55 +# f 1250/1257/55 1251/1258/55 1252/1259/55 1253/1254/55 1254/1255/55 1255/1256/55 +# f 1256/1261/57 1246/1252/57 1249/1251/57 1257/1260/57 +# f 1251/1258/60 1248/1250/60 1247/1253/60 1252/1259/60 +# f 1258/1264/55 1259/1265/55 1260/1262/55 1261/1263/55 +# f 1262/1269/59 1263/1270/59 1264/1271/59 1265/1266/59 1266/1267/59 1267/1268/59 +# f 1268/1273/57 1258/1264/57 1261/1263/57 1269/1272/57 +# f 1263/1270/60 1260/1262/60 1259/1265/60 1264/1271/60 +# f 1270/1276/59 1271/1277/59 1272/1274/59 1273/1275/59 +# f 1274/1279/55 1275/1280/55 1276/1281/55 1277/1278/55 1268/1273/55 1269/1272/55 +# f 1278/1283/57 1270/1276/57 1273/1275/57 1279/1282/57 +# f 1275/1280/60 1272/1274/60 1271/1277/60 1276/1281/60 +# f 1280/1286/55 1281/1287/55 1282/1284/55 1283/1285/55 +# f 1284/1289/59 1285/1290/59 1286/1291/59 1287/1288/59 1232/1237/59 1233/1236/59 +# f 1242/1243/57 1280/1286/57 1283/1285/57 1243/1244/57 +# f 1285/1290/60 1282/1284/60 1281/1287/60 1286/1291/60 +# f 1288/1294/55 1289/1295/55 1290/1292/55 1291/1293/55 +# f 1292/1297/59 1293/1298/59 1294/1299/59 1295/1296/59 1244/1249/59 1245/1248/59 +# f 1254/1255/57 1288/1294/57 1291/1293/57 1255/1256/57 +# f 1293/1298/60 1290/1292/60 1289/1295/60 1294/1299/60 +# f 1296/1302/55 1297/1303/55 1298/1300/55 1299/1301/55 +# f 1300/1305/59 1301/1306/59 1302/1307/59 1303/1304/59 1256/1261/59 1257/1260/59 +# f 1266/1267/57 1296/1302/57 1299/1301/57 1267/1268/57 +# f 1301/1306/60 1298/1300/60 1297/1303/60 1302/1307/60 +# f 1304/1310/55 1305/1311/55 1306/1308/55 1307/1309/55 +# f 1308/1313/59 1309/1314/59 1310/1315/59 1311/1312/59 1278/1283/59 1279/1282/59 +# f 1312/1317/57 1304/1310/57 1307/1309/57 1313/1316/57 +# f 1309/1314/60 1306/1308/60 1305/1311/60 1310/1315/60 +# f 1314/1320/59 1315/1321/59 1316/1318/59 1317/1319/59 +# f 1318/1323/59 1319/1324/59 1320/1325/59 1321/1322/59 1312/1317/59 1313/1316/59 +# f 1322/1327/57 1314/1320/57 1317/1319/57 1323/1326/57 +# f 1319/1324/60 1316/1318/60 1315/1321/60 1320/1325/60 +# f 1324/1330/59 1325/1331/59 1326/1328/59 1327/1329/59 +# f 1328/1333/55 1329/1334/55 1330/1335/55 1331/1332/55 1322/1327/55 1323/1326/55 +# f 1332/1337/57 1324/1330/57 1327/1329/57 1333/1336/57 +# f 1329/1334/60 1326/1328/60 1325/1331/60 1330/1335/60 +# f 1334/1340/55 1335/1341/55 1336/1338/55 1337/1339/55 +# f 1338/1343/59 1339/1344/59 1340/1345/59 1341/1342/59 1332/1337/59 1333/1336/59 +# f 1342/1347/57 1334/1340/57 1337/1339/57 1343/1346/57 +# f 1339/1344/60 1336/1338/60 1335/1341/60 1340/1345/60 +# f 1344/1350/59 1345/1351/59 1346/1348/59 1347/1349/59 +# f 1348/1353/55 1349/1354/55 1350/1355/55 1351/1352/55 1342/1347/55 1343/1346/55 +# f 1352/1357/57 1344/1350/57 1347/1349/57 1353/1356/57 +# f 1349/1354/60 1346/1348/60 1345/1351/60 1350/1355/60 +# f 1354/1360/55 1355/1361/55 1356/1358/55 1357/1359/55 +# f 1358/1363/59 1359/1364/59 1360/1365/59 1361/1362/59 1352/1357/59 1353/1356/59 +# f 1362/1367/57 1354/1360/57 1357/1359/57 1363/1366/57 +# f 1359/1364/60 1356/1358/60 1355/1361/60 1360/1365/60 +# f 1364/1370/55 1365/1371/55 1366/1368/55 1367/1369/55 +# f 1368/1373/59 1369/1374/59 1370/1375/59 1371/1372/59 1362/1367/59 1363/1366/59 +# f 1372/1377/57 1364/1370/57 1367/1369/57 1373/1376/57 +# f 1369/1374/58 1366/1368/58 1365/1371/58 1370/1375/58 +# f 1374/1380/59 1375/1381/59 1376/1378/59 1377/1379/59 +# f 1378/1383/55 1379/1384/55 1380/1385/55 1381/1382/55 1372/1377/55 1373/1376/55 +# f 1382/1387/57 1374/1380/57 1377/1379/57 1383/1386/57 +# f 1379/1384/60 1376/1378/60 1375/1381/60 1380/1385/60 +# f 1384/1390/55 1385/1391/55 1386/1388/55 1387/1389/55 +# f 1388/1393/55 1389/1394/55 1390/1395/55 1391/1392/55 1382/1387/55 1383/1386/55 +# f 1392/1397/57 1384/1390/57 1387/1389/57 1393/1396/57 +# f 1389/1394/58 1386/1388/58 1385/1391/58 1390/1395/58 +# f 1394/1400/59 1395/1401/59 1396/1398/59 1397/1399/59 +# f 1398/1403/55 1399/1404/55 1400/1405/55 1401/1402/55 1392/1397/55 1393/1396/55 +# f 1402/1407/57 1394/1400/57 1397/1399/57 1403/1406/57 +# f 1399/1404/60 1396/1398/60 1395/1401/60 1400/1405/60 +# f 1404/1410/55 1405/1411/55 1406/1408/55 1407/1409/55 +# f 1408/1413/59 1409/1414/59 1410/1415/59 1411/1412/59 1402/1407/59 1403/1406/59 +# f 1412/1417/57 1404/1410/57 1407/1409/57 1413/1416/57 +# f 1409/1414/60 1406/1408/60 1405/1411/60 1410/1415/60 +# f 1414/1420/55 1415/1421/55 1416/1418/55 1417/1419/55 +# f 1418/1423/59 1419/1424/59 1420/1425/59 1421/1422/59 1412/1417/59 1413/1416/59 +# f 1422/1427/57 1414/1420/57 1417/1419/57 1423/1426/57 +# f 1419/1424/60 1416/1418/60 1415/1421/60 1420/1425/60 +# f 1424/1430/59 1425/1431/59 1426/1428/59 1427/1429/59 +# f 1428/1433/55 1429/1434/55 1430/1435/55 1431/1432/55 1422/1427/55 1423/1426/55 +# f 1432/1437/57 1424/1430/57 1427/1429/57 1433/1436/57 +# f 1429/1434/60 1426/1428/60 1425/1431/60 1430/1435/60 +# f 1434/1440/55 1435/1441/55 1436/1438/55 1437/1439/55 +# f 1438/1443/59 1439/1444/59 1440/1445/59 1441/1442/59 1432/1437/59 1433/1436/59 +# f 1442/1447/57 1434/1440/57 1437/1439/57 1443/1446/57 +# f 1439/1444/60 1436/1438/60 1435/1441/60 1440/1445/60 +# f 1444/1450/55 1445/1451/55 1446/1448/55 1447/1449/55 +# f 1448/1453/59 1449/1454/59 1450/1455/59 1451/1452/59 1442/1447/59 1443/1446/59 +# f 1452/1457/57 1444/1450/57 1447/1449/57 1453/1456/57 +# f 1449/1454/60 1446/1448/60 1445/1451/60 1450/1455/60 +# f 1454/1460/55 1455/1461/55 1456/1458/55 1457/1459/55 +# f 1458/1465/59 1459/1466/59 1460/1467/59 1461/1462/59 1462/1463/59 1463/1464/59 +# f 1464/1469/57 1454/1460/57 1457/1459/57 1465/1468/57 +# f 1459/1466/60 1456/1458/60 1455/1461/60 1460/1467/60 +# f 1466/1472/59 1467/1473/59 1468/1470/59 1469/1471/59 +# f 1470/1476/61 1471/1477/61 1472/1474/61 1473/1475/61 +# f 1474/1479/55 1475/1480/55 1476/1481/55 1477/1478/55 1464/1469/55 1465/1468/55 +# f 1471/1477/57 1466/1472/57 1469/1471/57 1472/1474/57 +# f 1475/1480/60 1468/1470/60 1467/1473/60 1476/1481/60 +# f 1478/1484/55 1479/1485/55 1480/1482/55 1481/1483/55 +# f 1482/1487/59 1483/1488/59 1484/1489/59 1485/1486/59 1452/1457/59 1453/1456/59 +# f 1462/1463/57 1478/1484/57 1481/1483/57 1463/1464/57 +# f 1483/1488/60 1480/1482/60 1479/1485/60 1484/1489/60 +# 338 polygons + +# +# object Wall_Back +# + +v 0.9096 8.5559 2.5926 +v 0.9096 8.5559 0.1805 +v 0.7932 8.5559 0.1805 +v 0.7932 8.5559 2.5926 +v 0.9515 8.4870 0.1805 +v 0.9515 8.4870 2.5926 +v 0.9952 8.4870 2.5926 +v 0.9952 8.4870 0.1805 +v 0.7513 8.4870 0.1805 +v 0.7513 8.4870 2.5926 +v 0.6241 8.5559 2.5926 +v 0.6241 8.5559 0.1805 +v 0.5077 8.5559 0.1805 +v 0.5077 8.5559 2.5926 +v 0.6660 8.4870 0.1805 +v 0.6660 8.4870 2.5926 +v 0.7086 8.4870 2.5926 +v 0.7086 8.4870 0.1805 +v 0.4658 8.4870 0.1805 +v 0.4658 8.4870 2.5926 +v 0.3386 8.5559 2.5926 +v 0.3386 8.5559 0.1805 +v 0.2222 8.5559 0.1805 +v 0.2222 8.5559 2.5926 +v 0.3805 8.4870 0.1805 +v 0.3805 8.4870 2.5926 +v 0.4231 8.4870 2.5926 +v 0.4231 8.4870 0.1805 +v 0.1803 8.4870 0.1805 +v 0.1803 8.4870 2.5926 +v -0.2324 8.5559 2.5926 +v -0.2324 8.5559 0.1805 +v -0.3488 8.5559 0.1805 +v -0.3488 8.5559 2.5926 +v -0.1905 8.4870 0.1805 +v -0.1905 8.4870 2.5926 +v -0.1479 8.4870 2.5926 +v -0.1052 8.4870 2.5926 +v -0.1052 8.4870 0.1805 +v -0.1479 8.4870 0.1805 +v -0.3907 8.4870 0.1805 +v -0.3907 8.4870 2.5926 +v -0.5179 8.5559 2.5926 +v -0.5179 8.5559 0.1805 +v -0.6343 8.5559 0.1805 +v -0.6343 8.5559 2.5926 +v -0.4760 8.4870 0.1805 +v -0.4760 8.4870 2.5926 +v -0.4334 8.4870 2.5926 +v -0.4334 8.4870 0.1805 +v -0.6762 8.4870 0.1805 +v -0.6762 8.4870 2.5926 +v -1.3325 8.4870 0.1805 +v -1.3325 8.4870 2.5926 +v -1.2899 8.4870 2.5926 +v -1.2472 8.4870 2.5926 +v -1.2472 8.4870 0.1805 +v -1.2899 8.4870 0.1805 +v 0.0531 8.5559 2.5926 +v 0.0531 8.5559 0.1805 +v -0.0633 8.5559 0.1805 +v -0.0633 8.5559 2.5926 +v 0.0950 8.4870 0.1805 +v 0.0950 8.4870 2.5926 +v 0.1376 8.4870 2.5926 +v 0.1376 8.4870 0.1805 +v -0.8034 8.5559 2.5926 +v -0.8034 8.5559 0.1805 +v -0.9198 8.5559 0.1805 +v -0.9198 8.5559 2.5926 +v -0.7615 8.4870 0.1805 +v -0.7615 8.4870 2.5926 +v -0.7189 8.4870 2.5926 +v -0.7189 8.4870 0.1805 +v -0.9617 8.4870 0.1805 +v -0.9617 8.4870 2.5926 +v -1.0889 8.5559 2.5926 +v -1.0889 8.5559 0.1805 +v -1.2053 8.5559 0.1805 +v -1.2053 8.5559 2.5926 +v -1.0470 8.4870 0.1805 +v -1.0470 8.4870 2.5926 +v -1.0044 8.4870 2.5926 +v -1.0044 8.4870 0.1805 +v 0.7942 8.5541 0.1805 +v 0.9086 8.5541 0.1805 +v 0.9086 8.5541 2.5926 +v 0.7942 8.5541 2.5926 +v 0.9952 8.4850 2.5926 +v 0.9505 8.4852 2.5926 +v 0.9505 8.4852 0.1805 +v 0.9952 8.4850 0.1805 +v 0.7522 8.4852 0.1805 +v 0.7522 8.4852 2.5926 +v 0.5087 8.5541 0.1805 +v 0.6231 8.5541 0.1805 +v 0.6231 8.5541 2.5926 +v 0.5087 8.5541 2.5926 +v 0.7086 8.4850 2.5926 +v 0.6650 8.4852 2.5926 +v 0.6650 8.4852 0.1805 +v 0.7086 8.4850 0.1805 +v 0.4667 8.4852 0.1805 +v 0.4667 8.4852 2.5926 +v 0.2232 8.5541 0.1805 +v 0.3376 8.5541 0.1805 +v 0.3376 8.5541 2.5926 +v 0.2232 8.5541 2.5926 +v 0.4231 8.4850 2.5926 +v 0.3795 8.4852 2.5926 +v 0.3795 8.4852 0.1805 +v 0.4231 8.4850 0.1805 +v 0.1812 8.4852 0.1805 +v 0.1812 8.4852 2.5926 +v -0.3478 8.5541 0.1805 +v -0.2334 8.5541 0.1805 +v -0.2334 8.5541 2.5926 +v -0.3478 8.5541 2.5926 +v -0.1479 8.4850 2.5926 +v -0.1915 8.4852 2.5926 +v -0.1915 8.4852 0.1805 +v -0.1479 8.4850 0.1805 +v -0.1043 8.4852 0.1805 +v -0.1043 8.4852 2.5926 +v -0.3898 8.4852 0.1805 +v -0.3898 8.4852 2.5926 +v -0.6333 8.5541 0.1805 +v -0.5189 8.5541 0.1805 +v -0.5189 8.5541 2.5926 +v -0.6333 8.5541 2.5926 +v -0.4334 8.4850 2.5926 +v -0.4770 8.4852 2.5926 +v -0.4770 8.4852 0.1805 +v -0.4334 8.4850 0.1805 +v -0.6753 8.4852 0.1805 +v -0.6753 8.4852 2.5926 +v -1.2899 8.4850 2.5926 +v -1.3325 8.4850 2.5926 +v -1.3325 8.4850 0.1805 +v -1.2899 8.4850 0.1805 +v -1.2463 8.4852 0.1805 +v -1.2463 8.4852 2.5926 +v -0.0623 8.5541 0.1805 +v 0.0521 8.5541 0.1805 +v 0.0521 8.5541 2.5926 +v -0.0623 8.5541 2.5926 +v 0.1376 8.4850 2.5926 +v 0.0940 8.4852 2.5926 +v 0.0940 8.4852 0.1805 +v 0.1376 8.4850 0.1805 +v -0.9188 8.5541 0.1805 +v -0.8044 8.5541 0.1805 +v -0.8044 8.5541 2.5926 +v -0.9188 8.5541 2.5926 +v -0.7189 8.4850 2.5926 +v -0.7625 8.4852 2.5926 +v -0.7625 8.4852 0.1805 +v -0.7189 8.4850 0.1805 +v -0.9608 8.4852 0.1805 +v -0.9608 8.4852 2.5926 +v -1.2043 8.5541 0.1805 +v -1.0899 8.5541 0.1805 +v -1.0899 8.5541 2.5926 +v -1.2043 8.5541 2.5926 +v -1.0044 8.4850 2.5926 +v -1.0480 8.4852 2.5926 +v -1.0480 8.4852 0.1805 +v -1.0044 8.4850 0.1805 +# 168 vertices + +vn 0.0000 1.0000 0.0000 +vn -0.8544 0.5196 -0.0000 +vn 0.8544 0.5196 0.0000 +vn -0.8544 0.5197 -0.0000 +vn -0.0000 -1.0000 0.0000 +vn -0.0058 -1.0000 -0.0000 +vn 0.8544 -0.5196 0.0000 +vn -0.8544 -0.5196 -0.0000 +vn 0.8544 -0.5197 0.0000 +vn -0.0000 -1.0000 -0.0000 +vn -0.8544 -0.5197 -0.0000 +vn 0.0030 -1.0000 0.0000 +# 12 vertex normals + +vt 0.1016 0.0892 0.0000 +vt 0.1016 0.1588 0.0000 +vt 0.1041 0.1588 0.0000 +vt 0.1041 0.0892 0.0000 +vt 0.1058 0.1588 0.0000 +vt 0.1058 0.0892 0.0000 +vt 0.1049 0.0892 0.0000 +vt 0.1049 0.1588 0.0000 +vt 0.1008 0.0892 0.0000 +vt 0.1008 0.1588 0.0000 +vt 0.0957 0.0892 0.0000 +vt 0.0957 0.1588 0.0000 +vt 0.0981 0.1588 0.0000 +vt 0.0981 0.0892 0.0000 +vt 0.0999 0.0892 0.0000 +vt 0.0990 0.0892 0.0000 +vt 0.0990 0.1588 0.0000 +vt 0.0999 0.1588 0.0000 +vt 0.0948 0.0892 0.0000 +vt 0.0948 0.1588 0.0000 +vt 0.0898 0.0892 0.0000 +vt 0.0898 0.1588 0.0000 +vt 0.0922 0.1588 0.0000 +vt 0.0922 0.0892 0.0000 +vt 0.0940 0.0892 0.0000 +vt 0.0931 0.0892 0.0000 +vt 0.0931 0.1588 0.0000 +vt 0.0940 0.1588 0.0000 +vt 0.0889 0.0892 0.0000 +vt 0.0889 0.1588 0.0000 +vt 0.0779 0.0892 0.0000 +vt 0.0779 0.1588 0.0000 +vt 0.0803 0.1588 0.0000 +vt 0.0803 0.0892 0.0000 +vt 0.0830 0.1588 0.0000 +vt 0.0830 0.0892 0.0000 +vt 0.0821 0.0892 0.0000 +vt 0.0812 0.0892 0.0000 +vt 0.0812 0.1588 0.0000 +vt 0.0821 0.1588 0.0000 +vt 0.0770 0.0892 0.0000 +vt 0.0770 0.1588 0.0000 +vt 0.0720 0.0892 0.0000 +vt 0.0720 0.1588 0.0000 +vt 0.0744 0.1588 0.0000 +vt 0.0744 0.0892 0.0000 +vt 0.0762 0.0892 0.0000 +vt 0.0753 0.0892 0.0000 +vt 0.0753 0.1588 0.0000 +vt 0.0762 0.1588 0.0000 +vt 0.0711 0.0892 0.0000 +vt 0.0711 0.1588 0.0000 +vt 0.0593 0.1588 0.0000 +vt 0.0593 0.0892 0.0000 +vt 0.0584 0.0892 0.0000 +vt 0.0575 0.0892 0.0000 +vt 0.0575 0.1588 0.0000 +vt 0.0584 0.1588 0.0000 +vt 0.0838 0.0892 0.0000 +vt 0.0838 0.1588 0.0000 +vt 0.0863 0.1588 0.0000 +vt 0.0863 0.0892 0.0000 +vt 0.0880 0.0892 0.0000 +vt 0.0871 0.0892 0.0000 +vt 0.0871 0.1588 0.0000 +vt 0.0880 0.1588 0.0000 +vt 0.0661 0.0892 0.0000 +vt 0.0661 0.1588 0.0000 +vt 0.0685 0.1588 0.0000 +vt 0.0685 0.0892 0.0000 +vt 0.0702 0.0892 0.0000 +vt 0.0693 0.0892 0.0000 +vt 0.0693 0.1588 0.0000 +vt 0.0702 0.1588 0.0000 +vt 0.0652 0.0892 0.0000 +vt 0.0652 0.1588 0.0000 +vt 0.0601 0.0892 0.0000 +vt 0.0601 0.1588 0.0000 +vt 0.0625 0.1588 0.0000 +vt 0.0625 0.0892 0.0000 +vt 0.0643 0.0892 0.0000 +vt 0.0634 0.0892 0.0000 +vt 0.0634 0.1588 0.0000 +vt 0.0643 0.1588 0.0000 +vt 0.1040 0.1588 0.0000 +vt 0.1017 0.1588 0.0000 +vt 0.1017 0.0892 0.0000 +vt 0.1040 0.0892 0.0000 +vt 0.1049 0.0892 0.0000 +vt 0.1058 0.0892 0.0000 +vt 0.1058 0.1588 0.0000 +vt 0.1049 0.1588 0.0000 +vt 0.1008 0.1588 0.0000 +vt 0.1008 0.0892 0.0000 +vt 0.0981 0.1588 0.0000 +vt 0.0957 0.1588 0.0000 +vt 0.0957 0.0892 0.0000 +vt 0.0981 0.0892 0.0000 +vt 0.0999 0.0892 0.0000 +vt 0.0999 0.1588 0.0000 +vt 0.0990 0.1588 0.0000 +vt 0.0990 0.0892 0.0000 +vt 0.0949 0.1588 0.0000 +vt 0.0949 0.0892 0.0000 +vt 0.0922 0.1588 0.0000 +vt 0.0898 0.1588 0.0000 +vt 0.0898 0.0892 0.0000 +vt 0.0922 0.0892 0.0000 +vt 0.0940 0.0892 0.0000 +vt 0.0940 0.1588 0.0000 +vt 0.0930 0.1588 0.0000 +vt 0.0930 0.0892 0.0000 +vt 0.0889 0.1588 0.0000 +vt 0.0889 0.0892 0.0000 +vt 0.0803 0.1588 0.0000 +vt 0.0779 0.1588 0.0000 +vt 0.0779 0.0892 0.0000 +vt 0.0803 0.0892 0.0000 +vt 0.0821 0.0892 0.0000 +vt 0.0830 0.0892 0.0000 +vt 0.0830 0.1588 0.0000 +vt 0.0821 0.1588 0.0000 +vt 0.0812 0.1588 0.0000 +vt 0.0812 0.0892 0.0000 +vt 0.0771 0.1588 0.0000 +vt 0.0771 0.0892 0.0000 +vt 0.0744 0.1588 0.0000 +vt 0.0720 0.1588 0.0000 +vt 0.0720 0.0892 0.0000 +vt 0.0744 0.0892 0.0000 +vt 0.0762 0.0892 0.0000 +vt 0.0762 0.1588 0.0000 +vt 0.0753 0.1588 0.0000 +vt 0.0753 0.0892 0.0000 +vt 0.0711 0.1588 0.0000 +vt 0.0711 0.0892 0.0000 +vt 0.0584 0.0892 0.0000 +vt 0.0593 0.0892 0.0000 +vt 0.0593 0.1588 0.0000 +vt 0.0584 0.1588 0.0000 +vt 0.0575 0.1588 0.0000 +vt 0.0575 0.0892 0.0000 +vt 0.0862 0.1588 0.0000 +vt 0.0839 0.1588 0.0000 +vt 0.0839 0.0892 0.0000 +vt 0.0862 0.0892 0.0000 +vt 0.0880 0.0892 0.0000 +vt 0.0880 0.1588 0.0000 +vt 0.0871 0.1588 0.0000 +vt 0.0871 0.0892 0.0000 +vt 0.0685 0.1588 0.0000 +vt 0.0661 0.1588 0.0000 +vt 0.0661 0.0892 0.0000 +vt 0.0685 0.0892 0.0000 +vt 0.0702 0.0892 0.0000 +vt 0.0702 0.1588 0.0000 +vt 0.0693 0.1588 0.0000 +vt 0.0693 0.0892 0.0000 +vt 0.0652 0.1588 0.0000 +vt 0.0652 0.0892 0.0000 +vt 0.0625 0.1588 0.0000 +vt 0.0601 0.1588 0.0000 +vt 0.0601 0.0892 0.0000 +vt 0.0625 0.0892 0.0000 +vt 0.0643 0.0892 0.0000 +vt 0.0643 0.1588 0.0000 +vt 0.0634 0.1588 0.0000 +vt 0.0634 0.0892 0.0000 +# 168 texture coords + +# g Wall_Back +# usemtl ShippingContainer +# s off +# f 1486/1492/62 1487/1493/62 1488/1490/62 1489/1491/62 +# f 1490/1496/62 1491/1497/62 1492/1494/62 1493/1495/62 +# f 1489/1491/63 1488/1490/63 1494/1498/63 1495/1499/63 +# f 1487/1493/64 1486/1492/64 1491/1497/64 1490/1496/64 +# f 1496/1502/62 1497/1503/62 1498/1500/62 1499/1501/62 +# f 1500/1505/62 1501/1506/62 1502/1507/62 1495/1499/62 1494/1498/62 1503/1504/62 +# f 1499/1501/63 1498/1500/63 1504/1508/63 1505/1509/63 +# f 1497/1503/64 1496/1502/64 1501/1506/64 1500/1505/64 +# f 1506/1512/62 1507/1513/62 1508/1510/62 1509/1511/62 +# f 1510/1515/62 1511/1516/62 1512/1517/62 1505/1509/62 1504/1508/62 1513/1514/62 +# f 1509/1511/63 1508/1510/63 1514/1518/63 1515/1519/63 +# f 1507/1513/64 1506/1512/64 1511/1516/64 1510/1515/64 +# f 1516/1522/62 1517/1523/62 1518/1520/62 1519/1521/62 +# f 1520/1527/62 1521/1528/62 1522/1529/62 1523/1524/62 1524/1525/62 1525/1526/62 +# f 1519/1521/63 1518/1520/63 1526/1530/63 1527/1531/63 +# f 1517/1523/64 1516/1522/64 1521/1528/64 1520/1527/64 +# f 1528/1534/62 1529/1535/62 1530/1532/62 1531/1533/62 +# f 1532/1537/62 1533/1538/62 1534/1539/62 1527/1531/62 1526/1530/62 1535/1536/62 +# f 1531/1533/63 1530/1532/63 1536/1540/63 1537/1541/63 +# f 1529/1535/64 1528/1534/64 1533/1538/64 1532/1537/64 +# f 1538/1545/62 1539/1546/62 1540/1547/62 1541/1542/62 1542/1543/62 1543/1544/62 +# f 1544/1550/62 1545/1551/62 1546/1548/62 1547/1549/62 +# f 1548/1553/62 1549/1554/62 1550/1555/62 1515/1519/62 1514/1518/62 1551/1552/62 +# f 1547/1549/65 1546/1548/65 1524/1525/65 1523/1524/65 +# f 1545/1551/64 1544/1550/64 1549/1554/64 1548/1553/64 +# f 1552/1558/62 1553/1559/62 1554/1556/62 1555/1557/62 +# f 1556/1561/62 1557/1562/62 1558/1563/62 1537/1541/62 1536/1540/62 1559/1560/62 +# f 1555/1557/63 1554/1556/63 1560/1564/63 1561/1565/63 +# f 1553/1559/64 1552/1558/64 1557/1562/64 1556/1561/64 +# f 1562/1568/62 1563/1569/62 1564/1566/62 1565/1567/62 +# f 1566/1571/62 1567/1572/62 1568/1573/62 1561/1565/62 1560/1564/62 1569/1570/62 +# f 1565/1567/63 1564/1566/63 1542/1543/63 1541/1542/63 +# f 1563/1569/64 1562/1568/64 1567/1572/64 1566/1571/64 +# f 1570/1576/66 1571/1577/66 1572/1574/66 1573/1575/66 +# f 1574/1580/67 1575/1581/67 1576/1578/67 1577/1579/67 +# f 1578/1583/68 1570/1576/68 1573/1575/68 1579/1582/68 +# f 1575/1581/69 1572/1574/69 1571/1577/69 1576/1578/69 +# f 1580/1586/66 1581/1587/66 1582/1584/66 1583/1585/66 +# f 1584/1589/66 1585/1590/66 1586/1591/66 1587/1588/66 1578/1583/66 1579/1582/66 +# f 1588/1593/68 1580/1586/68 1583/1585/68 1589/1592/68 +# f 1585/1590/69 1582/1584/69 1581/1587/69 1586/1591/69 +# f 1590/1596/66 1591/1597/66 1592/1594/66 1593/1595/66 +# f 1594/1599/66 1595/1600/66 1596/1601/66 1597/1598/66 1588/1593/66 1589/1592/66 +# f 1598/1603/68 1590/1596/68 1593/1595/68 1599/1602/68 +# f 1595/1600/69 1592/1594/69 1591/1597/69 1596/1601/69 +# f 1600/1606/66 1601/1607/66 1602/1604/66 1603/1605/66 +# f 1604/1611/66 1605/1612/66 1606/1613/66 1607/1608/66 1608/1609/66 1609/1610/66 +# f 1610/1615/70 1600/1606/70 1603/1605/70 1611/1614/70 +# f 1605/1612/69 1602/1604/69 1601/1607/69 1606/1613/69 +# f 1612/1618/71 1613/1619/71 1614/1616/71 1615/1617/71 +# f 1616/1621/71 1617/1622/71 1618/1623/71 1619/1620/71 1610/1615/71 1611/1614/71 +# f 1620/1625/68 1612/1618/68 1615/1617/68 1621/1624/68 +# f 1617/1622/72 1614/1616/72 1613/1619/72 1618/1623/72 +# f 1622/1629/73 1623/1630/73 1624/1631/73 1625/1626/73 1626/1627/73 1627/1628/73 +# f 1628/1634/66 1629/1635/66 1630/1632/66 1631/1633/66 +# f 1632/1637/66 1633/1638/66 1634/1639/66 1635/1636/66 1598/1603/66 1599/1602/66 +# f 1608/1609/70 1628/1634/70 1631/1633/70 1609/1610/70 +# f 1633/1638/69 1630/1632/69 1629/1635/69 1634/1639/69 +# f 1636/1642/66 1637/1643/66 1638/1640/66 1639/1641/66 +# f 1640/1645/66 1641/1646/66 1642/1647/66 1643/1644/66 1620/1625/66 1621/1624/66 +# f 1644/1649/68 1636/1642/68 1639/1641/68 1645/1648/68 +# f 1641/1646/69 1638/1640/69 1637/1643/69 1642/1647/69 +# f 1646/1652/66 1647/1653/66 1648/1650/66 1649/1651/66 +# f 1650/1655/66 1651/1656/66 1652/1657/66 1653/1654/66 1644/1649/66 1645/1648/66 +# f 1626/1627/68 1646/1652/68 1649/1651/68 1627/1628/68 +# f 1651/1656/69 1648/1650/69 1647/1653/69 1652/1657/69 +# 66 polygons + +# +# object Roof +# + +v 0.9660 8.3434 2.7114 +v -1.3271 8.3434 2.7114 +v -1.3271 8.2270 2.7114 +v 0.9660 8.2270 2.7114 +v -1.3271 8.3853 2.6425 +v 0.9660 8.3853 2.6425 +v 0.9660 8.4291 2.6425 +v -1.3271 8.4291 2.6425 +v -1.3271 8.1851 2.6425 +v 0.9660 8.1851 2.6425 +v 0.9660 8.0579 2.7114 +v -1.3271 8.0579 2.7114 +v -1.3271 7.9415 2.7114 +v 0.9660 7.9415 2.7114 +v -1.3271 8.0998 2.6425 +v 0.9660 8.0998 2.6425 +v 0.9660 8.1425 2.6425 +v -1.3271 8.1425 2.6425 +v -1.3271 7.8996 2.6425 +v 0.9660 7.8996 2.6425 +v 0.9660 7.7724 2.7114 +v -1.3271 7.7724 2.7114 +v -1.3271 7.6560 2.7114 +v 0.9660 7.6560 2.7114 +v -1.3271 7.8143 2.6425 +v 0.9660 7.8143 2.6425 +v 0.9660 7.8570 2.6425 +v -1.3271 7.8570 2.6425 +v -1.3271 7.6141 2.6425 +v 0.9660 7.6141 2.6425 +v 0.9660 7.2014 2.7114 +v -1.3271 7.2014 2.7114 +v -1.3271 7.0850 2.7114 +v 0.9660 7.0850 2.7114 +v -1.3271 7.2433 2.6425 +v 0.9660 7.2433 2.6425 +v 0.9660 7.2860 2.6425 +v 0.9660 7.3286 2.6425 +v -1.3271 7.3286 2.6425 +v -1.3271 7.2860 2.6425 +v -1.3271 7.0431 2.6425 +v 0.9660 7.0431 2.6425 +v 0.9660 6.9159 2.7114 +v -1.3271 6.9159 2.7114 +v -1.3271 6.7995 2.7114 +v 0.9660 6.7995 2.7114 +v -1.3271 6.9578 2.6425 +v 0.9660 6.9578 2.6425 +v 0.9660 7.0005 2.6425 +v -1.3271 7.0005 2.6425 +v -1.3271 6.7576 2.6425 +v 0.9660 6.7576 2.6425 +v 0.9660 6.0594 2.7114 +v -1.3271 6.0594 2.7114 +v -1.3271 5.9430 2.7114 +v 0.9660 5.9430 2.7114 +v -1.3271 6.1013 2.6425 +v 0.9660 6.1013 2.6425 +v 0.9660 6.1440 2.6425 +v 0.9660 6.1866 2.6425 +v -1.3271 6.1866 2.6425 +v -1.3271 6.1440 2.6425 +v -1.3271 5.9011 2.6425 +v 0.9660 5.9011 2.6425 +v 0.9660 7.4869 2.7114 +v -1.3271 7.4869 2.7114 +v -1.3271 7.3705 2.7114 +v 0.9660 7.3705 2.7114 +v -1.3271 7.5288 2.6425 +v 0.9660 7.5288 2.6425 +v 0.9660 7.5715 2.6425 +v -1.3271 7.5715 2.6425 +v 0.9660 6.6304 2.7114 +v -1.3271 6.6304 2.7114 +v -1.3271 6.5140 2.7114 +v 0.9660 6.5140 2.7114 +v -1.3271 6.6723 2.6425 +v 0.9660 6.6723 2.6425 +v 0.9660 6.7150 2.6425 +v -1.3271 6.7150 2.6425 +v -1.3271 6.4721 2.6425 +v 0.9660 6.4721 2.6425 +v 0.9660 6.3449 2.7114 +v -1.3271 6.3449 2.7114 +v -1.3271 6.2285 2.7114 +v 0.9660 6.2285 2.7114 +v -1.3271 6.3868 2.6425 +v 0.9660 6.3868 2.6425 +v 0.9660 6.4295 2.6425 +v -1.3271 6.4295 2.6425 +v 0.9660 5.7739 2.7114 +v -1.3271 5.7739 2.7114 +v -1.3271 5.6575 2.7114 +v 0.9660 5.6575 2.7114 +v -1.3271 5.8158 2.6425 +v 0.9660 5.8158 2.6425 +v 0.9660 5.8585 2.6425 +v -1.3271 5.8585 2.6425 +v -1.3271 5.6156 2.6425 +v 0.9660 5.6156 2.6425 +v 0.9660 5.4884 2.7114 +v -1.3271 5.4884 2.7114 +v -1.3271 5.3720 2.7114 +v 0.9660 5.3720 2.7114 +v -1.3271 5.5303 2.6425 +v 0.9660 5.5303 2.6425 +v 0.9660 5.5730 2.6425 +v -1.3271 5.5730 2.6425 +v -1.3271 5.3301 2.6425 +v 0.9660 5.3301 2.6425 +v 0.9660 4.3464 2.7114 +v -1.3271 4.3464 2.7114 +v -1.3271 4.2300 2.7114 +v 0.9660 4.2300 2.7114 +v -1.3271 4.3883 2.6425 +v 0.9660 4.3883 2.6425 +v 0.9660 4.4310 2.6425 +v 0.9660 4.4736 2.6425 +v -1.3271 4.4736 2.6425 +v -1.3271 4.4310 2.6425 +v -1.3271 4.1881 2.6425 +v 0.9660 4.1881 2.6425 +v 0.9660 4.0609 2.7114 +v -1.3271 4.0609 2.7114 +v -1.3271 3.9445 2.7114 +v 0.9660 3.9445 2.7114 +v -1.3271 4.1028 2.6425 +v 0.9660 4.1028 2.6425 +v 0.9660 4.1455 2.6425 +v -1.3271 4.1455 2.6425 +v -1.3271 3.9026 2.6425 +v 0.9660 3.9026 2.6425 +v 0.9660 5.2029 2.7114 +v -1.3271 5.2029 2.7114 +v -1.3271 5.0865 2.7114 +v 0.9660 5.0865 2.7114 +v -1.3271 5.2448 2.6425 +v 0.9660 5.2448 2.6425 +v 0.9660 5.2875 2.6425 +v -1.3271 5.2875 2.6425 +v -1.3271 5.0446 2.6425 +v 0.9660 5.0446 2.6425 +v 0.9660 4.6319 2.7114 +v -1.3271 4.6319 2.7114 +v -1.3271 4.5155 2.7114 +v 0.9660 4.5155 2.7114 +v -1.3271 4.6738 2.6425 +v 0.9660 4.6738 2.6425 +v 0.9660 4.7165 2.6425 +v 0.9660 4.7591 2.6425 +v -1.3271 4.7591 2.6425 +v -1.3271 4.7165 2.6425 +v 0.9660 4.9174 2.7114 +v -1.3271 4.9174 2.7114 +v -1.3271 4.8010 2.7114 +v 0.9660 4.8010 2.7114 +v -1.3271 4.9593 2.6425 +v 0.9660 4.9593 2.6425 +v 0.9660 5.0020 2.6425 +v -1.3271 5.0020 2.6425 +v 0.9660 3.7754 2.7114 +v -1.3271 3.7754 2.7114 +v -1.3271 3.6590 2.7114 +v 0.9660 3.6590 2.7114 +v -1.3271 3.8173 2.6425 +v 0.9660 3.8173 2.6425 +v 0.9660 3.8600 2.6425 +v -1.3271 3.8600 2.6425 +v -1.3271 3.6171 2.6425 +v 0.9660 3.6171 2.6425 +v 0.9660 3.2044 2.7114 +v -1.3271 3.2044 2.7114 +v -1.3271 3.0880 2.7114 +v 0.9660 3.0880 2.7114 +v -1.3271 3.2463 2.6425 +v 0.9660 3.2463 2.6425 +v 0.9660 3.2890 2.6425 +v 0.9660 3.3316 2.6425 +v -1.3271 3.3316 2.6425 +v -1.3271 3.2890 2.6425 +v -1.3271 3.0461 2.6425 +v 0.9660 3.0461 2.6425 +v 0.9660 2.6334 2.7114 +v -1.3271 2.6334 2.7114 +v -1.3271 2.5170 2.7114 +v 0.9660 2.5170 2.7114 +v -1.3271 2.6753 2.6425 +v 0.9660 2.6753 2.6425 +v 0.9660 2.7180 2.6425 +v 0.9660 2.7606 2.6425 +v -1.3271 2.7606 2.6425 +v -1.3271 2.7180 2.6425 +v -1.3271 2.4751 2.6425 +v 0.9660 2.4751 2.6425 +v 0.9660 2.0624 2.7114 +v -1.3271 2.0624 2.7114 +v -1.3271 1.9460 2.7114 +v 0.9660 1.9460 2.7114 +v -1.3271 2.1043 2.6425 +v 0.9660 2.1043 2.6425 +v 0.9660 2.1470 2.6425 +v 0.9660 2.1896 2.6425 +v -1.3271 2.1896 2.6425 +v -1.3271 2.1470 2.6425 +v -1.3271 1.9041 2.6425 +v 0.9660 1.9041 2.6425 +v 0.9660 1.7769 2.7114 +v -1.3271 1.7769 2.7114 +v -1.3271 1.6605 2.7114 +v 0.9660 1.6605 2.7114 +v -1.3271 1.8188 2.6425 +v 0.9660 1.8188 2.6425 +v 0.9660 1.8615 2.6425 +v -1.3271 1.8615 2.6425 +v -1.3271 1.6186 2.6425 +v 0.9660 1.6186 2.6425 +v 0.9660 3.4899 2.7114 +v -1.3271 3.4899 2.7114 +v -1.3271 3.3735 2.7114 +v 0.9660 3.3735 2.7114 +v -1.3271 3.5318 2.6425 +v 0.9660 3.5318 2.6425 +v 0.9660 3.5745 2.6425 +v -1.3271 3.5745 2.6425 +v 0.9660 2.9189 2.7114 +v -1.3271 2.9189 2.7114 +v -1.3271 2.8025 2.7114 +v 0.9660 2.8025 2.7114 +v -1.3271 2.9608 2.6425 +v 0.9660 2.9608 2.6425 +v 0.9660 3.0035 2.6425 +v -1.3271 3.0035 2.6425 +v 0.9660 2.3479 2.7114 +v -1.3271 2.3479 2.7114 +v -1.3271 2.2315 2.7114 +v 0.9660 2.2315 2.7114 +v -1.3271 2.3898 2.6425 +v 0.9660 2.3898 2.6425 +v 0.9660 2.4325 2.6425 +v -1.3271 2.4325 2.6425 +v 0.9660 1.4914 2.7114 +v -1.3271 1.4914 2.7114 +v -1.3271 1.3750 2.7114 +v 0.9660 1.3750 2.7114 +v -1.3271 1.5333 2.6425 +v 0.9660 1.5333 2.6425 +v 0.9660 1.5760 2.6425 +v -1.3271 1.5760 2.6425 +v -1.3271 1.3331 2.6425 +v 0.9660 1.3331 2.6425 +v 0.9660 1.2059 2.7114 +v -1.3271 1.2059 2.7114 +v -1.3271 1.0895 2.7114 +v 0.9660 1.0895 2.7114 +v -1.3271 1.2478 2.6425 +v 0.9660 1.2478 2.6425 +v 0.9660 1.2905 2.6425 +v -1.3271 1.2905 2.6425 +v -1.3271 1.0476 2.6425 +v 0.9660 1.0476 2.6425 +v 0.9660 0.9204 2.7114 +v -1.3271 0.9204 2.7114 +v -1.3271 0.8040 2.7114 +v 0.9660 0.8040 2.7114 +v -1.3271 0.9623 2.6425 +v 0.9660 0.9623 2.6425 +v 0.9660 1.0050 2.6425 +v -1.3271 1.0050 2.6425 +v -1.3271 0.7621 2.6425 +v 0.9660 0.7621 2.6425 +v 0.9660 0.6349 2.7114 +v -1.3271 0.6349 2.7114 +v -1.3271 0.5185 2.7114 +v 0.9660 0.5185 2.7114 +v -1.3271 0.6768 2.6425 +v 0.9660 0.6768 2.6425 +v 0.9660 0.7195 2.6425 +v -1.3271 0.7195 2.6425 +v -1.3271 0.4766 2.6425 +v 0.9660 0.4766 2.6425 +v 0.9660 0.3494 2.7114 +v -1.3271 0.3494 2.7114 +v -1.3271 0.2330 2.7114 +v 0.9660 0.2330 2.7114 +v -1.3271 0.3913 2.6425 +v 0.9660 0.3913 2.6425 +v 0.9660 0.4340 2.6425 +v -1.3271 0.4340 2.6425 +v -1.3271 0.1911 2.6425 +v 0.9660 0.1911 2.6425 +v 0.9660 0.0639 2.7114 +v -1.3271 0.0639 2.7114 +v -1.3271 -0.0525 2.7114 +v 0.9660 -0.0525 2.7114 +v -1.3271 0.1058 2.6425 +v 0.9660 0.1058 2.6425 +v 0.9660 0.1485 2.6425 +v -1.3271 0.1485 2.6425 +v -1.3271 -0.0944 2.6425 +v 0.9660 -0.0944 2.6425 +v 0.9660 -0.2216 2.7114 +v -1.3271 -0.2216 2.7114 +v -1.3271 -0.3380 2.7114 +v 0.9660 -0.3380 2.7114 +v -1.3271 -0.1797 2.6425 +v 0.9660 -0.1797 2.6425 +v 0.9660 -0.1370 2.6425 +v -1.3271 -0.1370 2.6425 +v -1.3271 -0.3799 2.6425 +v 0.9660 -0.3799 2.6425 +v 0.9660 -0.5071 2.7114 +v -1.3271 -0.5071 2.7114 +v -1.3271 -0.6235 2.7114 +v 0.9660 -0.6235 2.7114 +v -1.3271 -0.4652 2.6425 +v 0.9660 -0.4652 2.6425 +v 0.9660 -0.4225 2.6425 +v -1.3271 -0.4225 2.6425 +v -1.3271 -0.6654 2.6425 +v 0.9660 -0.6654 2.6425 +v 0.9660 -0.7926 2.7114 +v -1.3271 -0.7926 2.7114 +v -1.3271 -0.9090 2.7114 +v 0.9660 -0.9090 2.7114 +v -1.3271 -0.7507 2.6425 +v 0.9660 -0.7507 2.6425 +v 0.9660 -0.7080 2.6425 +v -1.3271 -0.7080 2.6425 +v -1.3271 -0.9509 2.6425 +v 0.9660 -0.9509 2.6425 +v 0.9660 -1.0781 2.7114 +v -1.3271 -1.0781 2.7114 +v -1.3271 -1.1945 2.7114 +v 0.9660 -1.1945 2.7114 +v -1.3271 -1.0362 2.6425 +v 0.9660 -1.0362 2.6425 +v 0.9660 -0.9935 2.6425 +v -1.3271 -0.9935 2.6425 +v -1.3271 -1.2364 2.6425 +v 0.9660 -1.2364 2.6425 +v 0.9660 -1.3636 2.7114 +v -1.3271 -1.3636 2.7114 +v -1.3271 -1.4800 2.7114 +v 0.9660 -1.4800 2.7114 +v -1.3271 -1.3217 2.6425 +v 0.9660 -1.3217 2.6425 +v 0.9660 -1.2790 2.6425 +v -1.3271 -1.2790 2.6425 +v -1.3271 -1.5219 2.6425 +v 0.9660 -1.5219 2.6425 +v 0.9660 -1.6491 2.7114 +v -1.3271 -1.6491 2.7114 +v -1.3271 -1.7655 2.7114 +v 0.9660 -1.7655 2.7114 +v -1.3271 -1.6072 2.6425 +v 0.9660 -1.6072 2.6425 +v 0.9660 -1.5645 2.6425 +v -1.3271 -1.5645 2.6425 +v -1.3271 -1.8074 2.6425 +v 0.9660 -1.8074 2.6425 +v 0.9660 -1.9346 2.7114 +v -1.3271 -1.9346 2.7114 +v -1.3271 -2.0510 2.7114 +v 0.9660 -2.0510 2.7114 +v -1.3271 -1.8927 2.6425 +v 0.9660 -1.8927 2.6425 +v 0.9660 -1.8500 2.6425 +v -1.3271 -1.8500 2.6425 +v -1.3271 -2.0929 2.6425 +v 0.9660 -2.0929 2.6425 +v 0.9660 -2.2201 2.7114 +v -1.3271 -2.2201 2.7114 +v -1.3271 -2.3365 2.7114 +v 0.9660 -2.3365 2.7114 +v -1.3271 -2.1782 2.6425 +v 0.9660 -2.1782 2.6425 +v 0.9660 -2.1355 2.6425 +v -1.3271 -2.1355 2.6425 +v -1.3271 -2.3784 2.6425 +v 0.9660 -2.3784 2.6425 +v 0.9660 -2.5056 2.7114 +v -1.3271 -2.5056 2.7114 +v -1.3271 -2.6220 2.7114 +v 0.9660 -2.6220 2.7114 +v -1.3271 -2.4637 2.6425 +v 0.9660 -2.4637 2.6425 +v 0.9660 -2.4210 2.6425 +v -1.3271 -2.4210 2.6425 +v -1.3271 -2.6639 2.6425 +v 0.9660 -2.6639 2.6425 +v 0.9660 -3.0766 2.7114 +v -1.3271 -3.0766 2.7114 +v -1.3271 -3.1930 2.7114 +v 0.9660 -3.1930 2.7114 +v -1.3271 -3.0347 2.6425 +v 0.9660 -3.0347 2.6425 +v 0.9660 -2.9920 2.6425 +v 0.9660 -2.9494 2.6425 +v -1.3271 -2.9494 2.6425 +v -1.3271 -2.9920 2.6425 +v -1.3271 -3.2349 2.6425 +v 0.9660 -3.2349 2.6425 +v 0.9660 -3.3621 2.7114 +v -1.3271 -3.3621 2.7114 +v -1.3271 -3.4785 2.7114 +v 0.9660 -3.4785 2.7114 +v 0.9660 -3.5204 2.6425 +v -1.3271 -3.5204 2.6425 +v -1.3271 -3.5641 2.6425 +v 0.9660 -3.5641 2.6425 +v -1.3271 -3.3202 2.6425 +v 0.9660 -3.3202 2.6425 +v 0.9660 -3.2775 2.6425 +v -1.3271 -3.2775 2.6425 +v 0.9660 -2.7911 2.7114 +v -1.3271 -2.7911 2.7114 +v -1.3271 -2.9075 2.7114 +v 0.9660 -2.9075 2.7114 +v -1.3271 -2.7492 2.6425 +v 0.9660 -2.7492 2.6425 +v 0.9660 -2.7065 2.6425 +v -1.3271 -2.7065 2.6425 +v -1.3271 8.2280 2.7096 +v -1.3271 8.3424 2.7096 +v 0.9660 8.3424 2.7096 +v 0.9660 8.2280 2.7096 +v 0.9660 8.4291 2.6405 +v 0.9660 8.3843 2.6407 +v -1.3271 8.3843 2.6407 +v -1.3271 8.4291 2.6405 +v -1.3271 8.1861 2.6407 +v 0.9660 8.1861 2.6407 +v -1.3271 7.9425 2.7096 +v -1.3271 8.0569 2.7096 +v 0.9660 8.0569 2.7096 +v 0.9660 7.9425 2.7096 +v 0.9660 8.1425 2.6405 +v 0.9660 8.0988 2.6407 +v -1.3271 8.0988 2.6407 +v -1.3271 8.1425 2.6405 +v -1.3271 7.9006 2.6407 +v 0.9660 7.9006 2.6407 +v -1.3271 7.6570 2.7096 +v -1.3271 7.7714 2.7096 +v 0.9660 7.7714 2.7096 +v 0.9660 7.6570 2.7096 +v 0.9660 7.8570 2.6405 +v 0.9660 7.8133 2.6407 +v -1.3271 7.8133 2.6407 +v -1.3271 7.8570 2.6405 +v -1.3271 7.6151 2.6407 +v 0.9660 7.6151 2.6407 +v -1.3271 7.0860 2.7096 +v -1.3271 7.2004 2.7096 +v 0.9660 7.2004 2.7096 +v 0.9660 7.0860 2.7096 +v 0.9660 7.2860 2.6405 +v 0.9660 7.2423 2.6407 +v -1.3271 7.2423 2.6407 +v -1.3271 7.2860 2.6405 +v -1.3271 7.3296 2.6407 +v 0.9660 7.3296 2.6407 +v -1.3271 7.0441 2.6407 +v 0.9660 7.0441 2.6407 +v -1.3271 6.8005 2.7096 +v -1.3271 6.9149 2.7096 +v 0.9660 6.9149 2.7096 +v 0.9660 6.8005 2.7096 +v 0.9660 7.0005 2.6405 +v 0.9660 6.9568 2.6407 +v -1.3271 6.9568 2.6407 +v -1.3271 7.0005 2.6405 +v -1.3271 6.7586 2.6407 +v 0.9660 6.7586 2.6407 +v -1.3271 5.9440 2.7096 +v -1.3271 6.0584 2.7096 +v 0.9660 6.0584 2.7096 +v 0.9660 5.9440 2.7096 +v 0.9660 6.1440 2.6405 +v 0.9660 6.1003 2.6407 +v -1.3271 6.1003 2.6407 +v -1.3271 6.1440 2.6405 +v -1.3271 6.1876 2.6407 +v 0.9660 6.1876 2.6407 +v -1.3271 5.9021 2.6407 +v 0.9660 5.9021 2.6407 +v -1.3271 7.3715 2.7096 +v -1.3271 7.4859 2.7096 +v 0.9660 7.4859 2.7096 +v 0.9660 7.3715 2.7096 +v 0.9660 7.5715 2.6405 +v 0.9660 7.5278 2.6407 +v -1.3271 7.5278 2.6407 +v -1.3271 7.5715 2.6405 +v -1.3271 6.5150 2.7096 +v -1.3271 6.6294 2.7096 +v 0.9660 6.6294 2.7096 +v 0.9660 6.5150 2.7096 +v 0.9660 6.7150 2.6405 +v 0.9660 6.6713 2.6407 +v -1.3271 6.6713 2.6407 +v -1.3271 6.7150 2.6405 +v -1.3271 6.4731 2.6407 +v 0.9660 6.4731 2.6407 +v -1.3271 6.2295 2.7096 +v -1.3271 6.3439 2.7096 +v 0.9660 6.3439 2.7096 +v 0.9660 6.2295 2.7096 +v 0.9660 6.4295 2.6405 +v 0.9660 6.3858 2.6407 +v -1.3271 6.3858 2.6407 +v -1.3271 6.4295 2.6405 +v -1.3271 5.6585 2.7096 +v -1.3271 5.7729 2.7096 +v 0.9660 5.7729 2.7096 +v 0.9660 5.6585 2.7096 +v 0.9660 5.8585 2.6405 +v 0.9660 5.8148 2.6407 +v -1.3271 5.8148 2.6407 +v -1.3271 5.8585 2.6405 +v -1.3271 5.6166 2.6407 +v 0.9660 5.6166 2.6407 +v -1.3271 5.3730 2.7096 +v -1.3271 5.4874 2.7096 +v 0.9660 5.4874 2.7096 +v 0.9660 5.3730 2.7096 +v 0.9660 5.5730 2.6405 +v 0.9660 5.5293 2.6407 +v -1.3271 5.5293 2.6407 +v -1.3271 5.5730 2.6405 +v -1.3271 5.3311 2.6407 +v 0.9660 5.3311 2.6407 +v -1.3271 4.2310 2.7096 +v -1.3271 4.3454 2.7096 +v 0.9660 4.3454 2.7096 +v 0.9660 4.2310 2.7096 +v 0.9660 4.4310 2.6405 +v 0.9660 4.3873 2.6407 +v -1.3271 4.3873 2.6407 +v -1.3271 4.4310 2.6405 +v -1.3271 4.4746 2.6407 +v 0.9660 4.4746 2.6407 +v -1.3271 4.1891 2.6407 +v 0.9660 4.1891 2.6407 +v -1.3271 3.9455 2.7096 +v -1.3271 4.0599 2.7096 +v 0.9660 4.0599 2.7096 +v 0.9660 3.9455 2.7096 +v 0.9660 4.1455 2.6405 +v 0.9660 4.1018 2.6407 +v -1.3271 4.1018 2.6407 +v -1.3271 4.1455 2.6405 +v -1.3271 3.9036 2.6407 +v 0.9660 3.9036 2.6407 +v -1.3271 5.0875 2.7096 +v -1.3271 5.2019 2.7096 +v 0.9660 5.2019 2.7096 +v 0.9660 5.0875 2.7096 +v 0.9660 5.2875 2.6405 +v 0.9660 5.2438 2.6407 +v -1.3271 5.2438 2.6407 +v -1.3271 5.2875 2.6405 +v -1.3271 5.0456 2.6407 +v 0.9660 5.0456 2.6407 +v -1.3271 4.5165 2.7096 +v -1.3271 4.6309 2.7096 +v 0.9660 4.6309 2.7096 +v 0.9660 4.5165 2.7096 +v 0.9660 4.7165 2.6405 +v 0.9660 4.6728 2.6407 +v -1.3271 4.6728 2.6407 +v -1.3271 4.7165 2.6405 +v -1.3271 4.7601 2.6407 +v 0.9660 4.7601 2.6407 +v -1.3271 4.8020 2.7096 +v -1.3271 4.9164 2.7096 +v 0.9660 4.9164 2.7096 +v 0.9660 4.8020 2.7096 +v 0.9660 5.0020 2.6405 +v 0.9660 4.9583 2.6407 +v -1.3271 4.9583 2.6407 +v -1.3271 5.0020 2.6405 +v -1.3271 3.6600 2.7096 +v -1.3271 3.7744 2.7096 +v 0.9660 3.7744 2.7096 +v 0.9660 3.6600 2.7096 +v 0.9660 3.8600 2.6405 +v 0.9660 3.8163 2.6407 +v -1.3271 3.8163 2.6407 +v -1.3271 3.8600 2.6405 +v -1.3271 3.6181 2.6407 +v 0.9660 3.6181 2.6407 +v -1.3271 3.0890 2.7096 +v -1.3271 3.2034 2.7096 +v 0.9660 3.2034 2.7096 +v 0.9660 3.0890 2.7096 +v 0.9660 3.2890 2.6405 +v 0.9660 3.2453 2.6407 +v -1.3271 3.2453 2.6407 +v -1.3271 3.2890 2.6405 +v -1.3271 3.3326 2.6407 +v 0.9660 3.3326 2.6407 +v -1.3271 3.0471 2.6407 +v 0.9660 3.0471 2.6407 +v -1.3271 2.5180 2.7096 +v -1.3271 2.6324 2.7096 +v 0.9660 2.6324 2.7096 +v 0.9660 2.5180 2.7096 +v 0.9660 2.7180 2.6405 +v 0.9660 2.6743 2.6407 +v -1.3271 2.6743 2.6407 +v -1.3271 2.7180 2.6405 +v -1.3271 2.7616 2.6407 +v 0.9660 2.7616 2.6407 +v -1.3271 2.4761 2.6407 +v 0.9660 2.4761 2.6407 +v -1.3271 1.9470 2.7096 +v -1.3271 2.0614 2.7096 +v 0.9660 2.0614 2.7096 +v 0.9660 1.9470 2.7096 +v 0.9660 2.1470 2.6405 +v 0.9660 2.1033 2.6407 +v -1.3271 2.1033 2.6407 +v -1.3271 2.1470 2.6405 +v -1.3271 2.1906 2.6407 +v 0.9660 2.1906 2.6407 +v -1.3271 1.9051 2.6407 +v 0.9660 1.9051 2.6407 +v -1.3271 1.6615 2.7096 +v -1.3271 1.7759 2.7096 +v 0.9660 1.7759 2.7096 +v 0.9660 1.6615 2.7096 +v 0.9660 1.8615 2.6405 +v 0.9660 1.8178 2.6407 +v -1.3271 1.8178 2.6407 +v -1.3271 1.8615 2.6405 +v -1.3271 1.6196 2.6407 +v 0.9660 1.6196 2.6407 +v -1.3271 3.3745 2.7096 +v -1.3271 3.4889 2.7096 +v 0.9660 3.4889 2.7096 +v 0.9660 3.3745 2.7096 +v 0.9660 3.5745 2.6405 +v 0.9660 3.5308 2.6407 +v -1.3271 3.5308 2.6407 +v -1.3271 3.5745 2.6405 +v -1.3271 2.8035 2.7096 +v -1.3271 2.9179 2.7096 +v 0.9660 2.9179 2.7096 +v 0.9660 2.8035 2.7096 +v 0.9660 3.0035 2.6405 +v 0.9660 2.9598 2.6407 +v -1.3271 2.9598 2.6407 +v -1.3271 3.0035 2.6405 +v -1.3271 2.2325 2.7096 +v -1.3271 2.3469 2.7096 +v 0.9660 2.3469 2.7096 +v 0.9660 2.2325 2.7096 +v 0.9660 2.4325 2.6405 +v 0.9660 2.3888 2.6407 +v -1.3271 2.3888 2.6407 +v -1.3271 2.4325 2.6405 +v -1.3271 1.3760 2.7096 +v -1.3271 1.4904 2.7096 +v 0.9660 1.4904 2.7096 +v 0.9660 1.3760 2.7096 +v 0.9660 1.5760 2.6405 +v 0.9660 1.5323 2.6407 +v -1.3271 1.5323 2.6407 +v -1.3271 1.5760 2.6405 +v -1.3271 1.3341 2.6407 +v 0.9660 1.3341 2.6407 +v -1.3271 1.0905 2.7096 +v -1.3271 1.2049 2.7096 +v 0.9660 1.2049 2.7096 +v 0.9660 1.0905 2.7096 +v 0.9660 1.2905 2.6405 +v 0.9660 1.2468 2.6407 +v -1.3271 1.2468 2.6407 +v -1.3271 1.2905 2.6405 +v -1.3271 1.0486 2.6407 +v 0.9660 1.0486 2.6407 +v -1.3271 0.8050 2.7096 +v -1.3271 0.9194 2.7096 +v 0.9660 0.9194 2.7096 +v 0.9660 0.8050 2.7096 +v 0.9660 1.0050 2.6405 +v 0.9660 0.9613 2.6407 +v -1.3271 0.9613 2.6407 +v -1.3271 1.0050 2.6405 +v -1.3271 0.7631 2.6407 +v 0.9660 0.7631 2.6407 +v -1.3271 0.5195 2.7096 +v -1.3271 0.6339 2.7096 +v 0.9660 0.6339 2.7096 +v 0.9660 0.5195 2.7096 +v 0.9660 0.7195 2.6405 +v 0.9660 0.6758 2.6407 +v -1.3271 0.6758 2.6407 +v -1.3271 0.7195 2.6405 +v -1.3271 0.4776 2.6407 +v 0.9660 0.4776 2.6407 +v -1.3271 0.2340 2.7096 +v -1.3271 0.3484 2.7096 +v 0.9660 0.3484 2.7096 +v 0.9660 0.2340 2.7096 +v 0.9660 0.4340 2.6405 +v 0.9660 0.3903 2.6407 +v -1.3271 0.3903 2.6407 +v -1.3271 0.4340 2.6405 +v -1.3271 0.1921 2.6407 +v 0.9660 0.1921 2.6407 +v -1.3271 -0.0515 2.7096 +v -1.3271 0.0629 2.7096 +v 0.9660 0.0629 2.7096 +v 0.9660 -0.0515 2.7096 +v 0.9660 0.1485 2.6405 +v 0.9660 0.1048 2.6407 +v -1.3271 0.1048 2.6407 +v -1.3271 0.1485 2.6405 +v -1.3271 -0.0934 2.6407 +v 0.9660 -0.0934 2.6407 +v -1.3271 -0.3370 2.7096 +v -1.3271 -0.2226 2.7096 +v 0.9660 -0.2226 2.7096 +v 0.9660 -0.3370 2.7096 +v 0.9660 -0.1370 2.6405 +v 0.9660 -0.1807 2.6407 +v -1.3271 -0.1807 2.6407 +v -1.3271 -0.1370 2.6405 +v -1.3271 -0.3789 2.6407 +v 0.9660 -0.3789 2.6407 +v -1.3271 -0.6225 2.7096 +v -1.3271 -0.5081 2.7096 +v 0.9660 -0.5081 2.7096 +v 0.9660 -0.6225 2.7096 +v 0.9660 -0.4225 2.6405 +v 0.9660 -0.4662 2.6407 +v -1.3271 -0.4662 2.6407 +v -1.3271 -0.4225 2.6405 +v -1.3271 -0.6644 2.6407 +v 0.9660 -0.6644 2.6407 +v -1.3271 -0.9080 2.7096 +v -1.3271 -0.7936 2.7096 +v 0.9660 -0.7936 2.7096 +v 0.9660 -0.9080 2.7096 +v 0.9660 -0.7080 2.6405 +v 0.9660 -0.7517 2.6407 +v -1.3271 -0.7517 2.6407 +v -1.3271 -0.7080 2.6405 +v -1.3271 -0.9499 2.6407 +v 0.9660 -0.9499 2.6407 +v -1.3271 -1.1935 2.7096 +v -1.3271 -1.0791 2.7096 +v 0.9660 -1.0791 2.7096 +v 0.9660 -1.1935 2.7096 +v 0.9660 -0.9935 2.6405 +v 0.9660 -1.0372 2.6407 +v -1.3271 -1.0372 2.6407 +v -1.3271 -0.9935 2.6405 +v -1.3271 -1.2354 2.6407 +v 0.9660 -1.2354 2.6407 +v -1.3271 -1.4790 2.7096 +v -1.3271 -1.3646 2.7096 +v 0.9660 -1.3646 2.7096 +v 0.9660 -1.4790 2.7096 +v 0.9660 -1.2790 2.6405 +v 0.9660 -1.3227 2.6407 +v -1.3271 -1.3227 2.6407 +v -1.3271 -1.2790 2.6405 +v -1.3271 -1.5209 2.6407 +v 0.9660 -1.5209 2.6407 +v -1.3271 -1.7645 2.7096 +v -1.3271 -1.6501 2.7096 +v 0.9660 -1.6501 2.7096 +v 0.9660 -1.7645 2.7096 +v 0.9660 -1.5645 2.6405 +v 0.9660 -1.6082 2.6407 +v -1.3271 -1.6082 2.6407 +v -1.3271 -1.5645 2.6405 +v -1.3271 -1.8064 2.6407 +v 0.9660 -1.8064 2.6407 +v -1.3271 -2.0500 2.7096 +v -1.3271 -1.9356 2.7096 +v 0.9660 -1.9356 2.7096 +v 0.9660 -2.0500 2.7096 +v 0.9660 -1.8500 2.6405 +v 0.9660 -1.8937 2.6407 +v -1.3271 -1.8937 2.6407 +v -1.3271 -1.8500 2.6405 +v -1.3271 -2.0919 2.6407 +v 0.9660 -2.0919 2.6407 +v -1.3271 -2.3355 2.7096 +v -1.3271 -2.2211 2.7096 +v 0.9660 -2.2211 2.7096 +v 0.9660 -2.3355 2.7096 +v 0.9660 -2.1355 2.6405 +v 0.9660 -2.1792 2.6407 +v -1.3271 -2.1792 2.6407 +v -1.3271 -2.1355 2.6405 +v -1.3271 -2.3774 2.6407 +v 0.9660 -2.3774 2.6407 +v -1.3271 -2.6210 2.7096 +v -1.3271 -2.5066 2.7096 +v 0.9660 -2.5066 2.7096 +v 0.9660 -2.6210 2.7096 +v 0.9660 -2.4210 2.6405 +v 0.9660 -2.4647 2.6407 +v -1.3271 -2.4647 2.6407 +v -1.3271 -2.4210 2.6405 +v -1.3271 -2.6629 2.6407 +v 0.9660 -2.6629 2.6407 +v -1.3271 -3.1920 2.7096 +v -1.3271 -3.0776 2.7096 +v 0.9660 -3.0776 2.7096 +v 0.9660 -3.1920 2.7096 +v 0.9660 -2.9920 2.6405 +v 0.9660 -3.0357 2.6407 +v -1.3271 -3.0357 2.6407 +v -1.3271 -2.9920 2.6405 +v -1.3271 -2.9484 2.6407 +v 0.9660 -2.9484 2.6407 +v -1.3271 -3.2339 2.6407 +v 0.9660 -3.2339 2.6407 +v -1.3271 -3.4775 2.7096 +v -1.3271 -3.3631 2.7096 +v 0.9660 -3.3631 2.7096 +v 0.9660 -3.4775 2.7096 +v -1.3271 -3.5641 2.6405 +v -1.3271 -3.5194 2.6407 +v 0.9660 -3.5194 2.6407 +v 0.9660 -3.5641 2.6405 +v 0.9660 -3.2775 2.6405 +v 0.9660 -3.3212 2.6407 +v -1.3271 -3.3212 2.6407 +v -1.3271 -3.2775 2.6405 +v -1.3271 -2.9065 2.7096 +v -1.3271 -2.7921 2.7096 +v 0.9660 -2.7921 2.7096 +v 0.9660 -2.9065 2.7096 +v 0.9660 -2.7065 2.6405 +v 0.9660 -2.7502 2.6407 +v -1.3271 -2.7502 2.6407 +v -1.3271 -2.7065 2.6405 +# 844 vertices + +vn 0.0000 0.0000 1.0000 +vn -0.0000 -0.8544 0.5196 +vn 0.0000 0.8544 0.5196 +vn 0.0000 -0.0000 1.0000 +vn 0.0000 -0.8544 0.5196 +vn 0.0000 0.0000 -1.0000 +vn -0.0000 -0.0057 -1.0000 +vn 0.0000 0.8544 -0.5196 +vn -0.0000 -0.8544 -0.5196 +vn -0.0000 0.0000 -1.0000 +vn -0.0000 -0.0000 -1.0000 +vn -0.0000 0.8544 -0.5196 +vn 0.0000 -0.8544 -0.5196 +vn -0.0000 0.0057 -1.0000 +# 14 vertex normals + +vt 0.0576 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.1052 0.1622 0.0000 +vt 0.0576 0.1622 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.0576 0.1601 0.0000 +vt 0.1052 0.1601 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1601 0.0000 +vt 0.1052 0.1601 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1601 0.0000 +vt 0.1052 0.1601 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1601 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.1052 0.1601 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1601 0.0000 +vt 0.1052 0.1601 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1601 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.1052 0.1601 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1601 0.0000 +vt 0.1052 0.1601 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1601 0.0000 +vt 0.1052 0.1601 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1601 0.0000 +vt 0.1052 0.1601 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1601 0.0000 +vt 0.1052 0.1601 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1601 0.0000 +vt 0.1052 0.1601 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1601 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.1052 0.1601 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1601 0.0000 +vt 0.1052 0.1601 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1601 0.0000 +vt 0.1052 0.1601 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1601 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.1052 0.1601 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1601 0.0000 +vt 0.1052 0.1601 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1601 0.0000 +vt 0.1052 0.1601 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1601 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.1052 0.1601 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1601 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.1052 0.1601 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1601 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.1052 0.1601 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1601 0.0000 +vt 0.1052 0.1601 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1601 0.0000 +vt 0.1052 0.1601 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1601 0.0000 +vt 0.1052 0.1601 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1601 0.0000 +vt 0.1052 0.1601 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1601 0.0000 +vt 0.1052 0.1601 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1601 0.0000 +vt 0.1052 0.1601 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1601 0.0000 +vt 0.1052 0.1601 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1601 0.0000 +vt 0.1052 0.1601 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1601 0.0000 +vt 0.1052 0.1601 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1601 0.0000 +vt 0.1052 0.1601 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1601 0.0000 +vt 0.1052 0.1601 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1601 0.0000 +vt 0.1052 0.1601 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1601 0.0000 +vt 0.1052 0.1601 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1601 0.0000 +vt 0.1052 0.1601 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1601 0.0000 +vt 0.1052 0.1601 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1601 0.0000 +vt 0.1052 0.1601 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1601 0.0000 +vt 0.1052 0.1601 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1601 0.0000 +vt 0.1052 0.1601 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1601 0.0000 +vt 0.1052 0.1601 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1601 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.1052 0.1601 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.1052 0.1601 0.0000 +vt 0.0576 0.1601 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.0576 0.1601 0.0000 +vt 0.1052 0.1601 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.1052 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1621 0.0000 +vt 0.0576 0.1601 0.0000 +vt 0.1052 0.1601 0.0000 +vt 0.1052 0.1602 0.0000 +vt 0.0576 0.1602 0.0000 +# 844 texture coords + +# g Roof +# usemtl ShippingContainer +# s off +# f 1654/1660/74 1655/1661/74 1656/1658/74 1657/1659/74 +# f 1658/1664/74 1659/1665/74 1660/1662/74 1661/1663/74 +# f 1657/1659/75 1656/1658/75 1662/1666/75 1663/1667/75 +# f 1655/1661/76 1654/1660/76 1659/1665/76 1658/1664/76 +# f 1664/1670/74 1665/1671/74 1666/1668/74 1667/1669/74 +# f 1668/1673/77 1669/1674/77 1670/1675/77 1663/1667/77 1662/1666/77 1671/1672/77 +# f 1667/1669/78 1666/1668/78 1672/1676/78 1673/1677/78 +# f 1665/1671/76 1664/1670/76 1669/1674/76 1668/1673/76 +# f 1674/1680/77 1675/1681/77 1676/1678/77 1677/1679/77 +# f 1678/1683/74 1679/1684/74 1680/1685/74 1673/1677/74 1672/1676/74 1681/1682/74 +# f 1677/1679/75 1676/1678/75 1682/1686/75 1683/1687/75 +# f 1675/1681/76 1674/1680/76 1679/1684/76 1678/1683/76 +# f 1684/1690/74 1685/1691/74 1686/1688/74 1687/1689/74 +# f 1688/1695/77 1689/1696/77 1690/1697/77 1691/1692/77 1692/1693/77 1693/1694/77 +# f 1687/1689/78 1686/1688/78 1694/1698/78 1695/1699/78 +# f 1685/1691/76 1684/1690/76 1689/1696/76 1688/1695/76 +# f 1696/1702/74 1697/1703/74 1698/1700/74 1699/1701/74 +# f 1700/1705/74 1701/1706/74 1702/1707/74 1695/1699/74 1694/1698/74 1703/1704/74 +# f 1699/1701/75 1698/1700/75 1704/1708/75 1705/1709/75 +# f 1697/1703/76 1696/1702/76 1701/1706/76 1700/1705/76 +# f 1706/1712/74 1707/1713/74 1708/1710/74 1709/1711/74 +# f 1710/1717/74 1711/1718/74 1712/1719/74 1713/1714/74 1714/1715/74 1715/1716/74 +# f 1709/1711/75 1708/1710/75 1716/1720/75 1717/1721/75 +# f 1707/1713/76 1706/1712/76 1711/1718/76 1710/1717/76 +# f 1718/1724/74 1719/1725/74 1720/1722/74 1721/1723/74 +# f 1722/1727/77 1723/1728/77 1724/1729/77 1683/1687/77 1682/1686/77 1725/1726/77 +# f 1721/1723/75 1720/1722/75 1692/1693/75 1691/1692/75 +# f 1719/1725/76 1718/1724/76 1723/1728/76 1722/1727/76 +# f 1726/1732/77 1727/1733/77 1728/1730/77 1729/1731/77 +# f 1730/1735/77 1731/1736/77 1732/1737/77 1705/1709/77 1704/1708/77 1733/1734/77 +# f 1729/1731/75 1728/1730/75 1734/1738/75 1735/1739/75 +# f 1727/1733/76 1726/1732/76 1731/1736/76 1730/1735/76 +# f 1736/1742/74 1737/1743/74 1738/1740/74 1739/1741/74 +# f 1740/1745/74 1741/1746/74 1742/1747/74 1735/1739/74 1734/1738/74 1743/1744/74 +# f 1739/1741/75 1738/1740/75 1714/1715/75 1713/1714/75 +# f 1737/1743/76 1736/1742/76 1741/1746/76 1740/1745/76 +# f 1744/1750/74 1745/1751/74 1746/1748/74 1747/1749/74 +# f 1748/1753/77 1749/1754/77 1750/1755/77 1717/1721/77 1716/1720/77 1751/1752/77 +# f 1747/1749/75 1746/1748/75 1752/1756/75 1753/1757/75 +# f 1745/1751/76 1744/1750/76 1749/1754/76 1748/1753/76 +# f 1754/1760/74 1755/1761/74 1756/1758/74 1757/1759/74 +# f 1758/1763/74 1759/1764/74 1760/1765/74 1753/1757/74 1752/1756/74 1761/1762/74 +# f 1757/1759/75 1756/1758/75 1762/1766/75 1763/1767/75 +# f 1755/1761/76 1754/1760/76 1759/1764/76 1758/1763/76 +# f 1764/1770/74 1765/1771/74 1766/1768/74 1767/1769/74 +# f 1768/1775/77 1769/1776/77 1770/1777/77 1771/1772/77 1772/1773/77 1773/1774/77 +# f 1767/1769/75 1766/1768/75 1774/1778/75 1775/1779/75 +# f 1765/1771/76 1764/1770/76 1769/1776/76 1768/1775/76 +# f 1776/1782/74 1777/1783/74 1778/1780/74 1779/1781/74 +# f 1780/1785/77 1781/1786/77 1782/1787/77 1775/1779/77 1774/1778/77 1783/1784/77 +# f 1779/1781/75 1778/1780/75 1784/1788/75 1785/1789/75 +# f 1777/1783/76 1776/1782/76 1781/1786/76 1780/1785/76 +# f 1786/1792/74 1787/1793/74 1788/1790/74 1789/1791/74 +# f 1790/1795/74 1791/1796/74 1792/1797/74 1763/1767/74 1762/1766/74 1793/1794/74 +# f 1789/1791/75 1788/1790/75 1794/1798/75 1795/1799/75 +# f 1787/1793/76 1786/1792/76 1791/1796/76 1790/1795/76 +# f 1796/1802/74 1797/1803/74 1798/1800/74 1799/1801/74 +# f 1800/1807/74 1801/1808/74 1802/1809/74 1803/1804/74 1804/1805/74 1805/1806/74 +# f 1799/1801/75 1798/1800/75 1772/1773/75 1771/1772/75 +# f 1797/1803/76 1796/1802/76 1801/1808/76 1800/1807/76 +# f 1806/1812/74 1807/1813/74 1808/1810/74 1809/1811/74 +# f 1810/1815/74 1811/1816/74 1812/1817/74 1795/1799/74 1794/1798/74 1813/1814/74 +# f 1809/1811/75 1808/1810/75 1804/1805/75 1803/1804/75 +# f 1807/1813/76 1806/1812/76 1811/1816/76 1810/1815/76 +# f 1814/1820/74 1815/1821/74 1816/1818/74 1817/1819/74 +# f 1818/1823/74 1819/1824/74 1820/1825/74 1785/1789/74 1784/1788/74 1821/1822/74 +# f 1817/1819/75 1816/1818/75 1822/1826/75 1823/1827/75 +# f 1815/1821/76 1814/1820/76 1819/1824/76 1818/1823/76 +# f 1824/1830/74 1825/1831/74 1826/1828/74 1827/1829/74 +# f 1828/1835/74 1829/1836/74 1830/1837/74 1831/1832/74 1832/1833/74 1833/1834/74 +# f 1827/1829/75 1826/1828/75 1834/1838/75 1835/1839/75 +# f 1825/1831/76 1824/1830/76 1829/1836/76 1828/1835/76 +# f 1836/1842/74 1837/1843/74 1838/1840/74 1839/1841/74 +# f 1840/1847/77 1841/1848/77 1842/1849/77 1843/1844/77 1844/1845/77 1845/1846/77 +# f 1839/1841/75 1838/1840/75 1846/1850/75 1847/1851/75 +# f 1837/1843/76 1836/1842/76 1841/1848/76 1840/1847/76 +# f 1848/1854/77 1849/1855/77 1850/1852/77 1851/1853/77 +# f 1852/1859/77 1853/1860/77 1854/1861/77 1855/1856/77 1856/1857/77 1857/1858/77 +# f 1851/1853/75 1850/1852/75 1858/1862/75 1859/1863/75 +# f 1849/1855/76 1848/1854/76 1853/1860/76 1852/1859/76 +# f 1860/1866/74 1861/1867/74 1862/1864/74 1863/1865/74 +# f 1864/1869/77 1865/1870/77 1866/1871/77 1859/1863/77 1858/1862/77 1867/1868/77 +# f 1863/1865/78 1862/1864/78 1868/1872/78 1869/1873/78 +# f 1861/1867/76 1860/1866/76 1865/1870/76 1864/1869/76 +# f 1870/1876/74 1871/1877/74 1872/1874/74 1873/1875/74 +# f 1874/1879/77 1875/1880/77 1876/1881/77 1823/1827/77 1822/1826/77 1877/1878/77 +# f 1873/1875/75 1872/1874/75 1832/1833/75 1831/1832/75 +# f 1871/1877/76 1870/1876/76 1875/1880/76 1874/1879/76 +# f 1878/1884/74 1879/1885/74 1880/1882/74 1881/1883/74 +# f 1882/1887/77 1883/1888/77 1884/1889/77 1835/1839/77 1834/1838/77 1885/1886/77 +# f 1881/1883/75 1880/1882/75 1844/1845/75 1843/1844/75 +# f 1879/1885/76 1878/1884/76 1883/1888/76 1882/1887/76 +# f 1886/1892/74 1887/1893/74 1888/1890/74 1889/1891/74 +# f 1890/1895/77 1891/1896/77 1892/1897/77 1847/1851/77 1846/1850/77 1893/1894/77 +# f 1889/1891/75 1888/1890/75 1856/1857/75 1855/1856/75 +# f 1887/1893/76 1886/1892/76 1891/1896/76 1890/1895/76 +# f 1894/1900/74 1895/1901/74 1896/1898/74 1897/1899/74 +# f 1898/1903/77 1899/1904/77 1900/1905/77 1869/1873/77 1868/1872/77 1901/1902/77 +# f 1897/1899/78 1896/1898/78 1902/1906/78 1903/1907/78 +# f 1895/1901/76 1894/1900/76 1899/1904/76 1898/1903/76 +# f 1904/1910/74 1905/1911/74 1906/1908/74 1907/1909/74 +# f 1908/1913/77 1909/1914/77 1910/1915/77 1903/1907/77 1902/1906/77 1911/1912/77 +# f 1907/1909/78 1906/1908/78 1912/1916/78 1913/1917/78 +# f 1905/1911/76 1904/1910/76 1909/1914/76 1908/1913/76 +# f 1914/1920/77 1915/1921/77 1916/1918/77 1917/1919/77 +# f 1918/1923/74 1919/1924/74 1920/1925/74 1913/1917/74 1912/1916/74 1921/1922/74 +# f 1917/1919/78 1916/1918/78 1922/1926/78 1923/1927/78 +# f 1915/1921/76 1914/1920/76 1919/1924/76 1918/1923/76 +# f 1924/1930/74 1925/1931/74 1926/1928/74 1927/1929/74 +# f 1928/1933/77 1929/1934/77 1930/1935/77 1923/1927/77 1922/1926/77 1931/1932/77 +# f 1927/1929/78 1926/1928/78 1932/1936/78 1933/1937/78 +# f 1925/1931/76 1924/1930/76 1929/1934/76 1928/1933/76 +# f 1934/1940/74 1935/1941/74 1936/1938/74 1937/1939/74 +# f 1938/1943/74 1939/1944/74 1940/1945/74 1933/1937/74 1932/1936/74 1941/1942/74 +# f 1937/1939/78 1936/1938/78 1942/1946/78 1943/1947/78 +# f 1935/1941/76 1934/1940/76 1939/1944/76 1938/1943/76 +# f 1944/1950/74 1945/1951/74 1946/1948/74 1947/1949/74 +# f 1948/1953/77 1949/1954/77 1950/1955/77 1943/1947/77 1942/1946/77 1951/1952/77 +# f 1947/1949/78 1946/1948/78 1952/1956/78 1953/1957/78 +# f 1945/1951/76 1944/1950/76 1949/1954/76 1948/1953/76 +# f 1954/1960/74 1955/1961/74 1956/1958/74 1957/1959/74 +# f 1958/1963/74 1959/1964/74 1960/1965/74 1953/1957/74 1952/1956/74 1961/1962/74 +# f 1957/1959/78 1956/1958/78 1962/1966/78 1963/1967/78 +# f 1955/1961/76 1954/1960/76 1959/1964/76 1958/1963/76 +# f 1964/1970/74 1965/1971/74 1966/1968/74 1967/1969/74 +# f 1968/1973/74 1969/1974/74 1970/1975/74 1963/1967/74 1962/1966/74 1971/1972/74 +# f 1967/1969/78 1966/1968/78 1972/1976/78 1973/1977/78 +# f 1965/1971/76 1964/1970/76 1969/1974/76 1968/1973/76 +# f 1974/1980/74 1975/1981/74 1976/1978/74 1977/1979/74 +# f 1978/1983/74 1979/1984/74 1980/1985/74 1973/1977/74 1972/1976/74 1981/1982/74 +# f 1977/1979/78 1976/1978/78 1982/1986/78 1983/1987/78 +# f 1975/1981/76 1974/1980/76 1979/1984/76 1978/1983/76 +# f 1984/1990/74 1985/1991/74 1986/1988/74 1987/1989/74 +# f 1988/1993/74 1989/1994/74 1990/1995/74 1983/1987/74 1982/1986/74 1991/1992/74 +# f 1987/1989/78 1986/1988/78 1992/1996/78 1993/1997/78 +# f 1985/1991/76 1984/1990/76 1989/1994/76 1988/1993/76 +# f 1994/2000/77 1995/2001/77 1996/1998/77 1997/1999/77 +# f 1998/2003/74 1999/2004/74 2000/2005/74 1993/1997/74 1992/1996/74 2001/2002/74 +# f 1997/1999/78 1996/1998/78 2002/2006/78 2003/2007/78 +# f 1995/2001/76 1994/2000/76 1999/2004/76 1998/2003/76 +# f 2004/2010/74 2005/2011/74 2006/2008/74 2007/2009/74 +# f 2008/2013/77 2009/2014/77 2010/2015/77 2003/2007/77 2002/2006/77 2011/2012/77 +# f 2007/2009/78 2006/2008/78 2012/2016/78 2013/2017/78 +# f 2005/2011/76 2004/2010/76 2009/2014/76 2008/2013/76 +# f 2014/2020/74 2015/2021/74 2016/2018/74 2017/2019/74 +# f 2018/2023/74 2019/2024/74 2020/2025/74 2013/2017/74 2012/2016/74 2021/2022/74 +# f 2017/2019/78 2016/2018/78 2022/2026/78 2023/2027/78 +# f 2015/2021/76 2014/2020/76 2019/2024/76 2018/2023/76 +# f 2024/2030/74 2025/2031/74 2026/2028/74 2027/2029/74 +# f 2028/2033/77 2029/2034/77 2030/2035/77 2023/2027/77 2022/2026/77 2031/2032/77 +# f 2027/2029/78 2026/2028/78 2032/2036/78 2033/2037/78 +# f 2025/2031/76 2024/2030/76 2029/2034/76 2028/2033/76 +# f 2034/2040/74 2035/2041/74 2036/2038/74 2037/2039/74 +# f 2038/2043/74 2039/2044/74 2040/2045/74 2033/2037/74 2032/2036/74 2041/2042/74 +# f 2037/2039/78 2036/2038/78 2042/2046/78 2043/2047/78 +# f 2035/2041/76 2034/2040/76 2039/2044/76 2038/2043/76 +# f 2044/2050/74 2045/2051/74 2046/2048/74 2047/2049/74 +# f 2048/2055/74 2049/2056/74 2050/2057/74 2051/2052/74 2052/2053/74 2053/2054/74 +# f 2047/2049/78 2046/2048/78 2054/2058/78 2055/2059/78 +# f 2045/2051/76 2044/2050/76 2049/2056/76 2048/2055/76 +# f 2056/2062/74 2057/2063/74 2058/2060/74 2059/2061/74 +# f 2060/2066/74 2061/2067/74 2062/2064/74 2063/2065/74 +# f 2064/2069/74 2065/2070/74 2066/2071/74 2055/2059/74 2054/2058/74 2067/2068/74 +# f 2059/2061/78 2058/2060/78 2061/2067/78 2060/2066/78 +# f 2057/2063/76 2056/2062/76 2065/2070/76 2064/2069/76 +# f 2068/2074/77 2069/2075/77 2070/2072/77 2071/2073/77 +# f 2072/2077/77 2073/2078/77 2074/2079/77 2043/2047/77 2042/2046/77 2075/2076/77 +# f 2071/2073/78 2070/2072/78 2052/2053/78 2051/2052/78 +# f 2069/2075/76 2068/2074/76 2073/2078/76 2072/2077/76 +# f 2076/2082/79 2077/2083/79 2078/2080/79 2079/2081/79 +# f 2080/2086/80 2081/2087/80 2082/2084/80 2083/2085/80 +# f 2084/2089/81 2076/2082/81 2079/2081/81 2085/2088/81 +# f 2081/2087/82 2078/2080/82 2077/2083/82 2082/2084/82 +# f 2086/2092/83 2087/2093/83 2088/2090/83 2089/2091/83 +# f 2090/2095/83 2091/2096/83 2092/2097/83 2093/2094/83 2084/2089/83 2085/2088/83 +# f 2094/2099/81 2086/2092/81 2089/2091/81 2095/2098/81 +# f 2091/2096/82 2088/2090/82 2087/2093/82 2092/2097/82 +# f 2096/2102/83 2097/2103/83 2098/2100/83 2099/2101/83 +# f 2100/2105/84 2101/2106/84 2102/2107/84 2103/2104/84 2094/2099/84 2095/2098/84 +# f 2104/2109/81 2096/2102/81 2099/2101/81 2105/2108/81 +# f 2101/2106/82 2098/2100/82 2097/2103/82 2102/2107/82 +# f 2106/2112/83 2107/2113/83 2108/2110/83 2109/2111/83 +# f 2110/2117/83 2111/2118/83 2112/2119/83 2113/2114/83 2114/2115/83 2115/2116/83 +# f 2116/2121/81 2106/2112/81 2109/2111/81 2117/2120/81 +# f 2111/2118/82 2108/2110/82 2107/2113/82 2112/2119/82 +# f 2118/2124/83 2119/2125/83 2120/2122/83 2121/2123/83 +# f 2122/2127/83 2123/2128/83 2124/2129/83 2125/2126/83 2116/2121/83 2117/2120/83 +# f 2126/2131/81 2118/2124/81 2121/2123/81 2127/2130/81 +# f 2123/2128/82 2120/2122/82 2119/2125/82 2124/2129/82 +# f 2128/2134/79 2129/2135/79 2130/2132/79 2131/2133/79 +# f 2132/2139/79 2133/2140/79 2134/2141/79 2135/2136/79 2136/2137/79 2137/2138/79 +# f 2138/2143/81 2128/2134/81 2131/2133/81 2139/2142/81 +# f 2133/2140/82 2130/2132/82 2129/2135/82 2134/2141/82 +# f 2140/2146/79 2141/2147/79 2142/2144/79 2143/2145/79 +# f 2144/2149/84 2145/2150/84 2146/2151/84 2147/2148/84 2104/2109/84 2105/2108/84 +# f 2114/2115/81 2140/2146/81 2143/2145/81 2115/2116/81 +# f 2145/2150/82 2142/2144/82 2141/2147/82 2146/2151/82 +# f 2148/2154/84 2149/2155/84 2150/2152/84 2151/2153/84 +# f 2152/2157/83 2153/2158/83 2154/2159/83 2155/2156/83 2126/2131/83 2127/2130/83 +# f 2156/2161/85 2148/2154/85 2151/2153/85 2157/2160/85 +# f 2153/2158/82 2150/2152/82 2149/2155/82 2154/2159/82 +# f 2158/2164/79 2159/2165/79 2160/2162/79 2161/2163/79 +# f 2162/2167/83 2163/2168/83 2164/2169/83 2165/2166/83 2156/2161/83 2157/2160/83 +# f 2136/2137/81 2158/2164/81 2161/2163/81 2137/2138/81 +# f 2163/2168/82 2160/2162/82 2159/2165/82 2164/2169/82 +# f 2166/2172/79 2167/2173/79 2168/2170/79 2169/2171/79 +# f 2170/2175/83 2171/2176/83 2172/2177/83 2173/2174/83 2138/2143/83 2139/2142/83 +# f 2174/2179/81 2166/2172/81 2169/2171/81 2175/2178/81 +# f 2171/2176/82 2168/2170/82 2167/2173/82 2172/2177/82 +# f 2176/2182/79 2177/2183/79 2178/2180/79 2179/2181/79 +# f 2180/2185/79 2181/2186/79 2182/2187/79 2183/2184/79 2174/2179/79 2175/2178/79 +# f 2184/2189/81 2176/2182/81 2179/2181/81 2185/2188/81 +# f 2181/2186/82 2178/2180/82 2177/2183/82 2182/2187/82 +# f 2186/2192/84 2187/2193/84 2188/2190/84 2189/2191/84 +# f 2190/2197/83 2191/2198/83 2192/2199/83 2193/2194/83 2194/2195/83 2195/2196/83 +# f 2196/2201/81 2186/2192/81 2189/2191/81 2197/2200/81 +# f 2191/2198/82 2188/2190/82 2187/2193/82 2192/2199/82 +# f 2198/2204/84 2199/2205/84 2200/2202/84 2201/2203/84 +# f 2202/2207/84 2203/2208/84 2204/2209/84 2205/2206/84 2196/2201/84 2197/2200/84 +# f 2206/2211/81 2198/2204/81 2201/2203/81 2207/2210/81 +# f 2203/2208/82 2200/2202/82 2199/2205/82 2204/2209/82 +# f 2208/2214/79 2209/2215/79 2210/2212/79 2211/2213/79 +# f 2212/2217/83 2213/2218/83 2214/2219/83 2215/2216/83 2184/2189/83 2185/2188/83 +# f 2216/2221/81 2208/2214/81 2211/2213/81 2217/2220/81 +# f 2213/2218/82 2210/2212/82 2209/2215/82 2214/2219/82 +# f 2218/2224/83 2219/2225/83 2220/2222/83 2221/2223/83 +# f 2222/2229/84 2223/2230/84 2224/2231/84 2225/2226/84 2226/2227/84 2227/2228/84 +# f 2194/2195/81 2218/2224/81 2221/2223/81 2195/2196/81 +# f 2223/2230/82 2220/2222/82 2219/2225/82 2224/2231/82 +# f 2228/2234/83 2229/2235/83 2230/2232/83 2231/2233/83 +# f 2232/2237/84 2233/2238/84 2234/2239/84 2235/2236/84 2216/2221/84 2217/2220/84 +# f 2226/2227/81 2228/2234/81 2231/2233/81 2227/2228/81 +# f 2233/2238/82 2230/2232/82 2229/2235/82 2234/2239/82 +# f 2236/2242/79 2237/2243/79 2238/2240/79 2239/2241/79 +# f 2240/2245/83 2241/2246/83 2242/2247/83 2243/2244/83 2206/2211/83 2207/2210/83 +# f 2244/2249/81 2236/2242/81 2239/2241/81 2245/2248/81 +# f 2241/2246/82 2238/2240/82 2237/2243/82 2242/2247/82 +# f 2246/2252/83 2247/2253/83 2248/2250/83 2249/2251/83 +# f 2250/2257/83 2251/2258/83 2252/2259/83 2253/2254/83 2254/2255/83 2255/2256/83 +# f 2256/2261/81 2246/2252/81 2249/2251/81 2257/2260/81 +# f 2251/2258/82 2248/2250/82 2247/2253/82 2252/2259/82 +# f 2258/2264/79 2259/2265/79 2260/2262/79 2261/2263/79 +# f 2262/2269/84 2263/2270/84 2264/2271/84 2265/2266/84 2266/2267/84 2267/2268/84 +# f 2268/2273/81 2258/2264/81 2261/2263/81 2269/2272/81 +# f 2263/2270/82 2260/2262/82 2259/2265/82 2264/2271/82 +# f 2270/2276/84 2271/2277/84 2272/2274/84 2273/2275/84 +# f 2274/2281/83 2275/2282/83 2276/2283/83 2277/2278/83 2278/2279/83 2279/2280/83 +# f 2280/2285/81 2270/2276/81 2273/2275/81 2281/2284/81 +# f 2275/2282/82 2272/2274/82 2271/2277/82 2276/2283/82 +# f 2282/2288/84 2283/2289/84 2284/2286/84 2285/2287/84 +# f 2286/2291/84 2287/2292/84 2288/2293/84 2289/2290/84 2280/2285/84 2281/2284/84 +# f 2290/2295/85 2282/2288/85 2285/2287/85 2291/2294/85 +# f 2287/2292/82 2284/2286/82 2283/2289/82 2288/2293/82 +# f 2292/2298/83 2293/2299/83 2294/2296/83 2295/2297/83 +# f 2296/2301/83 2297/2302/83 2298/2303/83 2299/2300/83 2244/2249/83 2245/2248/83 +# f 2254/2255/81 2292/2298/81 2295/2297/81 2255/2256/81 +# f 2297/2302/82 2294/2296/82 2293/2299/82 2298/2303/82 +# f 2300/2306/79 2301/2307/79 2302/2304/79 2303/2305/79 +# f 2304/2309/84 2305/2310/84 2306/2311/84 2307/2308/84 2256/2261/84 2257/2260/84 +# f 2266/2267/81 2300/2306/81 2303/2305/81 2267/2268/81 +# f 2305/2310/82 2302/2304/82 2301/2307/82 2306/2311/82 +# f 2308/2314/83 2309/2315/83 2310/2312/83 2311/2313/83 +# f 2312/2317/83 2313/2318/83 2314/2319/83 2315/2316/83 2268/2273/83 2269/2272/83 +# f 2278/2279/81 2308/2314/81 2311/2313/81 2279/2280/81 +# f 2313/2318/82 2310/2312/82 2309/2315/82 2314/2319/82 +# f 2316/2322/79 2317/2323/79 2318/2320/79 2319/2321/79 +# f 2320/2325/83 2321/2326/83 2322/2327/83 2323/2324/83 2290/2295/83 2291/2294/83 +# f 2324/2329/81 2316/2322/81 2319/2321/81 2325/2328/81 +# f 2321/2326/86 2318/2320/86 2317/2323/86 2322/2327/86 +# f 2326/2332/83 2327/2333/83 2328/2330/83 2329/2331/83 +# f 2330/2335/83 2331/2336/83 2332/2337/83 2333/2334/83 2324/2329/83 2325/2328/83 +# f 2334/2339/85 2326/2332/85 2329/2331/85 2335/2338/85 +# f 2331/2336/82 2328/2330/82 2327/2333/82 2332/2337/82 +# f 2336/2342/83 2337/2343/83 2338/2340/83 2339/2341/83 +# f 2340/2345/84 2341/2346/84 2342/2347/84 2343/2344/84 2334/2339/84 2335/2338/84 +# f 2344/2349/85 2336/2342/85 2339/2341/85 2345/2348/85 +# f 2341/2346/82 2338/2340/82 2337/2343/82 2342/2347/82 +# f 2346/2352/79 2347/2353/79 2348/2350/79 2349/2351/79 +# f 2350/2355/84 2351/2356/84 2352/2357/84 2353/2354/84 2344/2349/84 2345/2348/84 +# f 2354/2359/85 2346/2352/85 2349/2351/85 2355/2358/85 +# f 2351/2356/82 2348/2350/82 2347/2353/82 2352/2357/82 +# f 2356/2362/79 2357/2363/79 2358/2360/79 2359/2361/79 +# f 2360/2365/84 2361/2366/84 2362/2367/84 2363/2364/84 2354/2359/84 2355/2358/84 +# f 2364/2369/85 2356/2362/85 2359/2361/85 2365/2368/85 +# f 2361/2366/82 2358/2360/82 2357/2363/82 2362/2367/82 +# f 2366/2372/79 2367/2373/79 2368/2370/79 2369/2371/79 +# f 2370/2375/83 2371/2376/83 2372/2377/83 2373/2374/83 2364/2369/83 2365/2368/83 +# f 2374/2379/81 2366/2372/81 2369/2371/81 2375/2378/81 +# f 2371/2376/86 2368/2370/86 2367/2373/86 2372/2377/86 +# f 2376/2382/79 2377/2383/79 2378/2380/79 2379/2381/79 +# f 2380/2385/79 2381/2386/79 2382/2387/79 2383/2384/79 2374/2379/79 2375/2378/79 +# f 2384/2389/81 2376/2382/81 2379/2381/81 2385/2388/81 +# f 2381/2386/86 2378/2380/86 2377/2383/86 2382/2387/86 +# f 2386/2392/79 2387/2393/79 2388/2390/79 2389/2391/79 +# f 2390/2395/79 2391/2396/79 2392/2397/79 2393/2394/79 2384/2389/79 2385/2388/79 +# f 2394/2399/81 2386/2392/81 2389/2391/81 2395/2398/81 +# f 2391/2396/86 2388/2390/86 2387/2393/86 2392/2397/86 +# f 2396/2402/79 2397/2403/79 2398/2400/79 2399/2401/79 +# f 2400/2405/83 2401/2406/83 2402/2407/83 2403/2404/83 2394/2399/83 2395/2398/83 +# f 2404/2409/81 2396/2402/81 2399/2401/81 2405/2408/81 +# f 2401/2406/86 2398/2400/86 2397/2403/86 2402/2407/86 +# f 2406/2412/79 2407/2413/79 2408/2410/79 2409/2411/79 +# f 2410/2415/84 2411/2416/84 2412/2417/84 2413/2414/84 2404/2409/84 2405/2408/84 +# f 2414/2419/81 2406/2412/81 2409/2411/81 2415/2418/81 +# f 2411/2416/86 2408/2410/86 2407/2413/86 2412/2417/86 +# f 2416/2422/83 2417/2423/83 2418/2420/83 2419/2421/83 +# f 2420/2425/83 2421/2426/83 2422/2427/83 2423/2424/83 2414/2419/83 2415/2418/83 +# f 2424/2429/85 2416/2422/85 2419/2421/85 2425/2428/85 +# f 2421/2426/82 2418/2420/82 2417/2423/82 2422/2427/82 +# f 2426/2432/79 2427/2433/79 2428/2430/79 2429/2431/79 +# f 2430/2435/84 2431/2436/84 2432/2437/84 2433/2434/84 2424/2429/84 2425/2428/84 +# f 2434/2439/85 2426/2432/85 2429/2431/85 2435/2438/85 +# f 2431/2436/82 2428/2430/82 2427/2433/82 2432/2437/82 +# f 2436/2442/79 2437/2443/79 2438/2440/79 2439/2441/79 +# f 2440/2445/84 2441/2446/84 2442/2447/84 2443/2444/84 2434/2439/84 2435/2438/84 +# f 2444/2449/85 2436/2442/85 2439/2441/85 2445/2448/85 +# f 2441/2446/82 2438/2440/82 2437/2443/82 2442/2447/82 +# f 2446/2452/83 2447/2453/83 2448/2450/83 2449/2451/83 +# f 2450/2455/83 2451/2456/83 2452/2457/83 2453/2454/83 2444/2449/83 2445/2448/83 +# f 2454/2459/85 2446/2452/85 2449/2451/85 2455/2458/85 +# f 2451/2456/82 2448/2450/82 2447/2453/82 2452/2457/82 +# f 2456/2462/83 2457/2463/83 2458/2460/83 2459/2461/83 +# f 2460/2465/83 2461/2466/83 2462/2467/83 2463/2464/83 2454/2459/83 2455/2458/83 +# f 2464/2469/85 2456/2462/85 2459/2461/85 2465/2468/85 +# f 2461/2466/82 2458/2460/82 2457/2463/82 2462/2467/82 +# f 2466/2472/79 2467/2473/79 2468/2470/79 2469/2471/79 +# f 2470/2477/83 2471/2478/83 2472/2479/83 2473/2474/83 2474/2475/83 2475/2476/83 +# f 2476/2481/81 2466/2472/81 2469/2471/81 2477/2480/81 +# f 2471/2478/86 2468/2470/86 2467/2473/86 2472/2479/86 +# f 2478/2484/79 2479/2485/79 2480/2482/79 2481/2483/79 +# f 2482/2488/87 2483/2489/87 2484/2486/87 2485/2487/87 +# f 2486/2491/84 2487/2492/84 2488/2493/84 2489/2490/84 2476/2481/84 2477/2480/84 +# f 2483/2489/81 2478/2484/81 2481/2483/81 2484/2486/81 +# f 2487/2492/86 2480/2482/86 2479/2485/86 2488/2493/86 +# f 2490/2496/84 2491/2497/84 2492/2494/84 2493/2495/84 +# f 2494/2499/83 2495/2500/83 2496/2501/83 2497/2498/83 2464/2469/83 2465/2468/83 +# f 2474/2475/85 2490/2496/85 2493/2495/85 2475/2476/85 +# f 2495/2500/82 2492/2494/82 2491/2497/82 2496/2501/82 +# 338 polygons + +# +# object Wall_Right +# + +v 1.0728 8.3594 2.5926 +v 1.0728 8.2430 2.5926 +v 1.0728 8.2430 0.1548 +v 1.0728 8.3594 0.1548 +v 1.0038 8.4013 0.1548 +v 1.0038 8.4450 0.1548 +v 1.0038 8.4450 2.5926 +v 1.0038 8.4013 2.5926 +v 1.0038 8.2011 2.5926 +v 1.0038 8.2011 0.1548 +v 1.0728 8.0739 2.5926 +v 1.0728 7.9575 2.5926 +v 1.0728 7.9575 0.1548 +v 1.0728 8.0739 0.1548 +v 1.0038 8.1584 2.5926 +v 1.0038 8.1158 2.5926 +v 1.0038 8.1158 0.1548 +v 1.0038 8.1584 0.1548 +v 1.0038 7.9156 2.5926 +v 1.0038 7.9156 0.1548 +v 1.0728 7.7884 2.5926 +v 1.0728 7.6720 2.5926 +v 1.0728 7.6720 0.1548 +v 1.0728 7.7884 0.1548 +v 1.0038 7.8729 2.5926 +v 1.0038 7.8303 2.5926 +v 1.0038 7.8303 0.1548 +v 1.0038 7.8729 0.1548 +v 1.0038 7.6301 2.5926 +v 1.0038 7.6301 0.1548 +v 1.0728 7.2174 2.5926 +v 1.0728 7.1010 2.5926 +v 1.0728 7.1010 0.1548 +v 1.0728 7.2174 0.1548 +v 1.0038 7.3019 2.5926 +v 1.0038 7.2593 2.5926 +v 1.0038 7.2593 0.1548 +v 1.0038 7.3019 0.1548 +v 1.0038 7.3446 0.1548 +v 1.0038 7.3446 2.5926 +v 1.0038 7.0591 2.5926 +v 1.0038 7.0591 0.1548 +v 1.0728 6.9319 2.5926 +v 1.0728 6.8155 2.5926 +v 1.0728 6.8155 0.1548 +v 1.0728 6.9319 0.1548 +v 1.0038 7.0164 2.5926 +v 1.0038 6.9738 2.5926 +v 1.0038 6.9738 0.1548 +v 1.0038 7.0164 0.1548 +v 1.0038 6.7736 2.5926 +v 1.0038 6.7736 0.1548 +v 1.0728 6.0754 2.5926 +v 1.0728 5.9590 2.5926 +v 1.0728 5.9590 0.1548 +v 1.0728 6.0754 0.1548 +v 1.0038 6.1599 2.5926 +v 1.0038 6.1173 2.5926 +v 1.0038 6.1173 0.1548 +v 1.0038 6.1599 0.1548 +v 1.0038 6.2026 0.1548 +v 1.0038 6.2026 2.5926 +v 1.0038 5.9171 2.5926 +v 1.0038 5.9171 0.1548 +v 1.0728 7.5029 2.5926 +v 1.0728 7.3865 2.5926 +v 1.0728 7.3865 0.1548 +v 1.0728 7.5029 0.1548 +v 1.0038 7.5874 2.5926 +v 1.0038 7.5448 2.5926 +v 1.0038 7.5448 0.1548 +v 1.0038 7.5874 0.1548 +v 1.0728 6.6464 2.5926 +v 1.0728 6.5300 2.5926 +v 1.0728 6.5300 0.1548 +v 1.0728 6.6464 0.1548 +v 1.0038 6.7309 2.5926 +v 1.0038 6.6883 2.5926 +v 1.0038 6.6883 0.1548 +v 1.0038 6.7309 0.1548 +v 1.0038 6.4881 2.5926 +v 1.0038 6.4881 0.1548 +v 1.0728 6.3609 2.5926 +v 1.0728 6.2445 2.5926 +v 1.0728 6.2445 0.1548 +v 1.0728 6.3609 0.1548 +v 1.0038 6.4454 2.5926 +v 1.0038 6.4028 2.5926 +v 1.0038 6.4028 0.1548 +v 1.0038 6.4454 0.1548 +v 1.0728 5.7899 2.5926 +v 1.0728 5.6735 2.5926 +v 1.0728 5.6735 0.1548 +v 1.0728 5.7899 0.1548 +v 1.0038 5.8744 2.5926 +v 1.0038 5.8318 2.5926 +v 1.0038 5.8318 0.1548 +v 1.0038 5.8744 0.1548 +v 1.0038 5.6316 2.5926 +v 1.0038 5.6316 0.1548 +v 1.0728 5.5044 2.5926 +v 1.0728 5.3880 2.5926 +v 1.0728 5.3880 0.1548 +v 1.0728 5.5044 0.1548 +v 1.0038 5.5889 2.5926 +v 1.0038 5.5463 2.5926 +v 1.0038 5.5463 0.1548 +v 1.0038 5.5889 0.1548 +v 1.0038 5.3461 2.5926 +v 1.0038 5.3461 0.1548 +v 1.0728 4.3624 2.5926 +v 1.0728 4.2460 2.5926 +v 1.0728 4.2460 0.1548 +v 1.0728 4.3624 0.1548 +v 1.0038 4.4469 2.5926 +v 1.0038 4.4043 2.5926 +v 1.0038 4.4043 0.1548 +v 1.0038 4.4469 0.1548 +v 1.0038 4.4896 0.1548 +v 1.0038 4.4896 2.5926 +v 1.0038 4.2041 2.5926 +v 1.0038 4.2041 0.1548 +v 1.0728 4.0769 2.5926 +v 1.0728 3.9605 2.5926 +v 1.0728 3.9605 0.1548 +v 1.0728 4.0769 0.1548 +v 1.0038 4.1614 2.5926 +v 1.0038 4.1188 2.5926 +v 1.0038 4.1188 0.1548 +v 1.0038 4.1614 0.1548 +v 1.0038 3.9186 2.5926 +v 1.0038 3.9186 0.1548 +v 1.0728 5.2189 2.5926 +v 1.0728 5.1025 2.5926 +v 1.0728 5.1025 0.1548 +v 1.0728 5.2189 0.1548 +v 1.0038 5.3034 2.5926 +v 1.0038 5.2608 2.5926 +v 1.0038 5.2608 0.1548 +v 1.0038 5.3034 0.1548 +v 1.0038 5.0606 2.5926 +v 1.0038 5.0606 0.1548 +v 1.0728 4.6479 2.5926 +v 1.0728 4.5315 2.5926 +v 1.0728 4.5315 0.1548 +v 1.0728 4.6479 0.1548 +v 1.0038 4.7324 2.5926 +v 1.0038 4.6898 2.5926 +v 1.0038 4.6898 0.1548 +v 1.0038 4.7324 0.1548 +v 1.0038 4.7751 0.1548 +v 1.0038 4.7751 2.5926 +v 1.0728 4.9334 2.5926 +v 1.0728 4.8170 2.5926 +v 1.0728 4.8170 0.1548 +v 1.0728 4.9334 0.1548 +v 1.0038 5.0179 2.5926 +v 1.0038 4.9753 2.5926 +v 1.0038 4.9753 0.1548 +v 1.0038 5.0179 0.1548 +v 1.0728 3.7914 2.5926 +v 1.0728 3.6750 2.5926 +v 1.0728 3.6750 0.1548 +v 1.0728 3.7914 0.1548 +v 1.0038 3.8759 2.5926 +v 1.0038 3.8333 2.5926 +v 1.0038 3.8333 0.1548 +v 1.0038 3.8759 0.1548 +v 1.0038 3.6331 2.5926 +v 1.0038 3.6331 0.1548 +v 1.0728 3.2204 2.5926 +v 1.0728 3.1040 2.5926 +v 1.0728 3.1040 0.1548 +v 1.0728 3.2204 0.1548 +v 1.0038 3.3049 2.5926 +v 1.0038 3.2623 2.5926 +v 1.0038 3.2623 0.1548 +v 1.0038 3.3049 0.1548 +v 1.0038 3.3476 0.1548 +v 1.0038 3.3476 2.5926 +v 1.0038 3.0621 2.5926 +v 1.0038 3.0621 0.1548 +v 1.0728 2.6494 2.5926 +v 1.0728 2.5330 2.5926 +v 1.0728 2.5330 0.1548 +v 1.0728 2.6494 0.1548 +v 1.0038 2.7339 2.5926 +v 1.0038 2.6913 2.5926 +v 1.0038 2.6913 0.1548 +v 1.0038 2.7339 0.1548 +v 1.0038 2.7766 0.1548 +v 1.0038 2.7766 2.5926 +v 1.0038 2.4911 2.5926 +v 1.0038 2.4911 0.1548 +v 1.0728 2.0784 2.5926 +v 1.0728 1.9620 2.5926 +v 1.0728 1.9620 0.1548 +v 1.0728 2.0784 0.1548 +v 1.0038 2.1629 2.5926 +v 1.0038 2.1203 2.5926 +v 1.0038 2.1203 0.1548 +v 1.0038 2.1629 0.1548 +v 1.0038 2.2056 0.1548 +v 1.0038 2.2056 2.5926 +v 1.0038 1.9201 2.5926 +v 1.0038 1.9201 0.1548 +v 1.0728 1.7929 2.5926 +v 1.0728 1.6765 2.5926 +v 1.0728 1.6765 0.1548 +v 1.0728 1.7929 0.1548 +v 1.0038 1.8774 2.5926 +v 1.0038 1.8348 2.5926 +v 1.0038 1.8348 0.1548 +v 1.0038 1.8774 0.1548 +v 1.0038 1.6346 2.5926 +v 1.0038 1.6346 0.1548 +v 1.0728 3.5059 2.5926 +v 1.0728 3.3895 2.5926 +v 1.0728 3.3895 0.1548 +v 1.0728 3.5059 0.1548 +v 1.0038 3.5904 2.5926 +v 1.0038 3.5478 2.5926 +v 1.0038 3.5478 0.1548 +v 1.0038 3.5904 0.1548 +v 1.0728 2.9349 2.5926 +v 1.0728 2.8185 2.5926 +v 1.0728 2.8185 0.1548 +v 1.0728 2.9349 0.1548 +v 1.0038 3.0194 2.5926 +v 1.0038 2.9768 2.5926 +v 1.0038 2.9768 0.1548 +v 1.0038 3.0194 0.1548 +v 1.0728 2.3639 2.5926 +v 1.0728 2.2475 2.5926 +v 1.0728 2.2475 0.1548 +v 1.0728 2.3639 0.1548 +v 1.0038 2.4484 2.5926 +v 1.0038 2.4058 2.5926 +v 1.0038 2.4058 0.1548 +v 1.0038 2.4484 0.1548 +v 1.0728 1.5074 2.5926 +v 1.0728 1.3910 2.5926 +v 1.0728 1.3910 0.1548 +v 1.0728 1.5074 0.1548 +v 1.0038 1.5919 2.5926 +v 1.0038 1.5493 2.5926 +v 1.0038 1.5493 0.1548 +v 1.0038 1.5919 0.1548 +v 1.0038 1.3491 2.5926 +v 1.0038 1.3491 0.1548 +v 1.0728 1.2219 2.5926 +v 1.0728 1.1055 2.5926 +v 1.0728 1.1055 0.1548 +v 1.0728 1.2219 0.1548 +v 1.0038 1.3064 2.5926 +v 1.0038 1.2638 2.5926 +v 1.0038 1.2638 0.1548 +v 1.0038 1.3064 0.1548 +v 1.0038 1.0636 2.5926 +v 1.0038 1.0636 0.1548 +v 1.0728 0.9364 2.5926 +v 1.0728 0.8200 2.5926 +v 1.0728 0.8200 0.1548 +v 1.0728 0.9364 0.1548 +v 1.0038 1.0209 2.5926 +v 1.0038 0.9783 2.5926 +v 1.0038 0.9783 0.1548 +v 1.0038 1.0209 0.1548 +v 1.0038 0.7781 2.5926 +v 1.0038 0.7781 0.1548 +v 1.0728 0.6509 2.5926 +v 1.0728 0.5345 2.5926 +v 1.0728 0.5345 0.1548 +v 1.0728 0.6509 0.1548 +v 1.0038 0.7354 2.5926 +v 1.0038 0.6928 2.5926 +v 1.0038 0.6928 0.1548 +v 1.0038 0.7354 0.1548 +v 1.0038 0.4926 2.5926 +v 1.0038 0.4926 0.1548 +v 1.0728 0.3654 2.5926 +v 1.0728 0.2490 2.5926 +v 1.0728 0.2490 0.1548 +v 1.0728 0.3654 0.1548 +v 1.0038 0.4499 2.5926 +v 1.0038 0.4073 2.5926 +v 1.0038 0.4073 0.1548 +v 1.0038 0.4499 0.1548 +v 1.0038 0.2071 2.5926 +v 1.0038 0.2071 0.1548 +v 1.0728 0.0799 2.5926 +v 1.0728 -0.0365 2.5926 +v 1.0728 -0.0365 0.1548 +v 1.0728 0.0799 0.1548 +v 1.0038 0.1644 2.5926 +v 1.0038 0.1218 2.5926 +v 1.0038 0.1218 0.1548 +v 1.0038 0.1644 0.1548 +v 1.0038 -0.0784 2.5926 +v 1.0038 -0.0784 0.1548 +v 1.0728 -0.2056 2.5926 +v 1.0728 -0.3220 2.5926 +v 1.0728 -0.3220 0.1548 +v 1.0728 -0.2056 0.1548 +v 1.0038 -0.1211 2.5926 +v 1.0038 -0.1637 2.5926 +v 1.0038 -0.1637 0.1548 +v 1.0038 -0.1211 0.1548 +v 1.0038 -0.3639 2.5926 +v 1.0038 -0.3639 0.1548 +v 1.0728 -0.4911 2.5926 +v 1.0728 -0.6075 2.5926 +v 1.0728 -0.6075 0.1548 +v 1.0728 -0.4911 0.1548 +v 1.0038 -0.4066 2.5926 +v 1.0038 -0.4492 2.5926 +v 1.0039 -0.4492 0.1548 +v 1.0039 -0.4066 0.1548 +v 1.0038 -0.6494 2.5926 +v 1.0039 -0.6494 0.1548 +v 1.0728 -0.7766 2.5926 +v 1.0728 -0.8930 2.5926 +v 1.0728 -0.8930 0.1548 +v 1.0728 -0.7766 0.1548 +v 1.0038 -0.6921 2.5926 +v 1.0038 -0.7347 2.5926 +v 1.0039 -0.7347 0.1548 +v 1.0039 -0.6921 0.1548 +v 1.0038 -0.9349 2.5926 +v 1.0039 -0.9349 0.1548 +v 1.0728 -1.0621 2.5926 +v 1.0728 -1.1785 2.5926 +v 1.0728 -1.1785 0.1548 +v 1.0728 -1.0621 0.1548 +v 1.0038 -0.9776 2.5926 +v 1.0038 -1.0202 2.5926 +v 1.0039 -1.0202 0.1548 +v 1.0039 -0.9776 0.1548 +v 1.0038 -1.2204 2.5926 +v 1.0039 -1.2204 0.1548 +v 1.0728 -1.3476 2.5926 +v 1.0728 -1.4640 2.5926 +v 1.0728 -1.4640 0.1548 +v 1.0728 -1.3476 0.1548 +v 1.0038 -1.2631 2.5926 +v 1.0038 -1.3057 2.5926 +v 1.0039 -1.3057 0.1548 +v 1.0039 -1.2631 0.1548 +v 1.0038 -1.5059 2.5926 +v 1.0039 -1.5059 0.1548 +v 1.0728 -1.6331 2.5926 +v 1.0728 -1.7495 2.5926 +v 1.0728 -1.7495 0.1548 +v 1.0728 -1.6331 0.1548 +v 1.0038 -1.5486 2.5926 +v 1.0038 -1.5912 2.5926 +v 1.0039 -1.5912 0.1548 +v 1.0039 -1.5486 0.1548 +v 1.0038 -1.7914 2.5926 +v 1.0039 -1.7914 0.1548 +v 1.0728 -1.9186 2.5926 +v 1.0728 -2.0350 2.5926 +v 1.0728 -2.0350 0.1548 +v 1.0728 -1.9186 0.1548 +v 1.0038 -1.8341 2.5926 +v 1.0038 -1.8767 2.5926 +v 1.0039 -1.8767 0.1548 +v 1.0039 -1.8341 0.1548 +v 1.0038 -2.0769 2.5926 +v 1.0039 -2.0769 0.1548 +v 1.0728 -2.2041 2.5926 +v 1.0728 -2.3205 2.5926 +v 1.0728 -2.3205 0.1548 +v 1.0728 -2.2041 0.1548 +v 1.0038 -2.1196 2.5926 +v 1.0038 -2.1622 2.5926 +v 1.0039 -2.1622 0.1548 +v 1.0039 -2.1196 0.1548 +v 1.0038 -2.3624 2.5926 +v 1.0039 -2.3624 0.1548 +v 1.0728 -2.4896 2.5926 +v 1.0728 -2.6060 2.5926 +v 1.0728 -2.6060 0.1548 +v 1.0728 -2.4896 0.1548 +v 1.0038 -2.4051 2.5926 +v 1.0038 -2.4477 2.5926 +v 1.0039 -2.4477 0.1548 +v 1.0039 -2.4051 0.1548 +v 1.0038 -2.6479 2.5926 +v 1.0039 -2.6479 0.1548 +v 1.0728 -3.0606 2.5926 +v 1.0728 -3.1770 2.5926 +v 1.0728 -3.1770 0.1548 +v 1.0728 -3.0606 0.1548 +v 1.0038 -2.9761 2.5926 +v 1.0038 -3.0187 2.5926 +v 1.0039 -3.0187 0.1548 +v 1.0039 -2.9761 0.1548 +v 1.0039 -2.9334 0.1548 +v 1.0038 -2.9334 2.5926 +v 1.0038 -3.2189 2.5926 +v 1.0039 -3.2189 0.1548 +v 1.0728 -3.3461 2.5926 +v 1.0728 -3.4625 2.5926 +v 1.0728 -3.4625 0.1548 +v 1.0728 -3.3461 0.1548 +v 1.0038 -3.5044 2.5926 +v 1.0038 -3.5482 2.5926 +v 1.0039 -3.5482 0.1548 +v 1.0039 -3.5044 0.1548 +v 1.0038 -3.2616 2.5926 +v 1.0038 -3.3042 2.5926 +v 1.0039 -3.3042 0.1548 +v 1.0039 -3.2616 0.1548 +v 1.0728 -2.7751 2.5926 +v 1.0728 -2.8915 2.5926 +v 1.0728 -2.8915 0.1548 +v 1.0728 -2.7751 0.1548 +v 1.0038 -2.6906 2.5926 +v 1.0038 -2.7332 2.5926 +v 1.0039 -2.7332 0.1548 +v 1.0039 -2.6906 0.1548 +v 1.0710 8.2440 0.1548 +v 1.0710 8.2440 2.5926 +v 1.0710 8.3584 2.5926 +v 1.0710 8.3584 0.1548 +v 1.0018 8.4450 2.5926 +v 1.0018 8.4450 0.1548 +v 1.0021 8.4003 0.1548 +v 1.0021 8.4003 2.5926 +v 1.0021 8.2021 0.1548 +v 1.0021 8.2021 2.5926 +v 1.0710 7.9585 0.1548 +v 1.0710 7.9585 2.5926 +v 1.0710 8.0729 2.5926 +v 1.0710 8.0729 0.1548 +v 1.0021 8.1148 0.1548 +v 1.0021 8.1148 2.5926 +v 1.0018 8.1584 2.5926 +v 1.0018 8.1584 0.1548 +v 1.0021 7.9166 0.1548 +v 1.0021 7.9166 2.5926 +v 1.0710 7.6730 0.1548 +v 1.0710 7.6730 2.5926 +v 1.0710 7.7874 2.5926 +v 1.0710 7.7874 0.1548 +v 1.0021 7.8293 0.1548 +v 1.0021 7.8293 2.5926 +v 1.0018 7.8729 2.5926 +v 1.0018 7.8729 0.1548 +v 1.0021 7.6311 0.1548 +v 1.0021 7.6311 2.5926 +v 1.0710 7.1020 0.1548 +v 1.0710 7.1020 2.5926 +v 1.0710 7.2164 2.5926 +v 1.0710 7.2164 0.1548 +v 1.0021 7.2583 0.1548 +v 1.0021 7.2583 2.5926 +v 1.0018 7.3019 2.5926 +v 1.0021 7.3456 2.5926 +v 1.0021 7.3456 0.1548 +v 1.0018 7.3019 0.1548 +v 1.0021 7.0601 0.1548 +v 1.0021 7.0601 2.5926 +v 1.0710 6.8165 0.1548 +v 1.0710 6.8165 2.5926 +v 1.0710 6.9309 2.5926 +v 1.0710 6.9309 0.1548 +v 1.0021 6.9728 0.1548 +v 1.0021 6.9728 2.5926 +v 1.0018 7.0164 2.5926 +v 1.0018 7.0164 0.1548 +v 1.0021 6.7746 0.1548 +v 1.0021 6.7746 2.5926 +v 1.0710 5.9600 0.1548 +v 1.0710 5.9600 2.5926 +v 1.0710 6.0744 2.5926 +v 1.0710 6.0744 0.1548 +v 1.0021 6.1163 0.1548 +v 1.0021 6.1163 2.5926 +v 1.0018 6.1599 2.5926 +v 1.0021 6.2036 2.5926 +v 1.0021 6.2036 0.1548 +v 1.0018 6.1599 0.1548 +v 1.0021 5.9181 0.1548 +v 1.0021 5.9181 2.5926 +v 1.0710 7.3875 0.1548 +v 1.0710 7.3875 2.5926 +v 1.0710 7.5019 2.5926 +v 1.0710 7.5019 0.1548 +v 1.0021 7.5438 0.1548 +v 1.0021 7.5438 2.5926 +v 1.0018 7.5874 2.5926 +v 1.0018 7.5874 0.1548 +v 1.0710 6.5310 0.1548 +v 1.0710 6.5310 2.5926 +v 1.0710 6.6454 2.5926 +v 1.0710 6.6454 0.1548 +v 1.0021 6.6873 0.1548 +v 1.0021 6.6873 2.5926 +v 1.0018 6.7309 2.5926 +v 1.0018 6.7309 0.1548 +v 1.0021 6.4891 0.1548 +v 1.0021 6.4891 2.5926 +v 1.0710 6.2455 0.1548 +v 1.0710 6.2455 2.5926 +v 1.0710 6.3599 2.5926 +v 1.0710 6.3599 0.1548 +v 1.0021 6.4018 0.1548 +v 1.0021 6.4018 2.5926 +v 1.0018 6.4454 2.5926 +v 1.0018 6.4454 0.1548 +v 1.0710 5.6745 0.1548 +v 1.0710 5.6745 2.5926 +v 1.0710 5.7889 2.5926 +v 1.0710 5.7889 0.1548 +v 1.0021 5.8308 0.1548 +v 1.0021 5.8308 2.5926 +v 1.0018 5.8744 2.5926 +v 1.0018 5.8744 0.1548 +v 1.0021 5.6326 0.1548 +v 1.0021 5.6326 2.5926 +v 1.0710 5.3890 0.1548 +v 1.0710 5.3890 2.5926 +v 1.0710 5.5034 2.5926 +v 1.0710 5.5034 0.1548 +v 1.0021 5.5453 0.1548 +v 1.0021 5.5453 2.5926 +v 1.0018 5.5889 2.5926 +v 1.0018 5.5889 0.1548 +v 1.0021 5.3471 0.1548 +v 1.0021 5.3471 2.5926 +v 1.0710 4.2470 0.1548 +v 1.0710 4.2470 2.5926 +v 1.0710 4.3614 2.5926 +v 1.0710 4.3614 0.1548 +v 1.0021 4.4033 0.1548 +v 1.0021 4.4033 2.5926 +v 1.0018 4.4469 2.5926 +v 1.0021 4.4906 2.5926 +v 1.0021 4.4906 0.1548 +v 1.0018 4.4469 0.1548 +v 1.0021 4.2051 0.1548 +v 1.0021 4.2051 2.5926 +v 1.0710 3.9615 0.1548 +v 1.0710 3.9615 2.5926 +v 1.0710 4.0759 2.5926 +v 1.0710 4.0759 0.1548 +v 1.0021 4.1178 0.1548 +v 1.0021 4.1178 2.5926 +v 1.0018 4.1614 2.5926 +v 1.0018 4.1614 0.1548 +v 1.0021 3.9196 0.1548 +v 1.0021 3.9196 2.5926 +v 1.0710 5.1035 0.1548 +v 1.0710 5.1035 2.5926 +v 1.0710 5.2179 2.5926 +v 1.0710 5.2179 0.1548 +v 1.0021 5.2598 0.1548 +v 1.0021 5.2598 2.5926 +v 1.0018 5.3034 2.5926 +v 1.0018 5.3034 0.1548 +v 1.0021 5.0616 0.1548 +v 1.0021 5.0616 2.5926 +v 1.0710 4.5325 0.1548 +v 1.0710 4.5325 2.5926 +v 1.0710 4.6469 2.5926 +v 1.0710 4.6469 0.1548 +v 1.0021 4.6888 0.1548 +v 1.0021 4.6888 2.5926 +v 1.0018 4.7324 2.5926 +v 1.0021 4.7761 2.5926 +v 1.0021 4.7761 0.1548 +v 1.0018 4.7324 0.1548 +v 1.0710 4.8180 0.1548 +v 1.0710 4.8180 2.5926 +v 1.0710 4.9324 2.5926 +v 1.0710 4.9324 0.1548 +v 1.0021 4.9743 0.1548 +v 1.0021 4.9743 2.5926 +v 1.0018 5.0179 2.5926 +v 1.0018 5.0179 0.1548 +v 1.0710 3.6760 0.1548 +v 1.0710 3.6760 2.5926 +v 1.0710 3.7904 2.5926 +v 1.0710 3.7904 0.1548 +v 1.0021 3.8323 0.1548 +v 1.0021 3.8323 2.5926 +v 1.0018 3.8759 2.5926 +v 1.0018 3.8759 0.1548 +v 1.0021 3.6341 0.1548 +v 1.0021 3.6341 2.5926 +v 1.0710 3.1050 0.1548 +v 1.0710 3.1050 2.5926 +v 1.0710 3.2194 2.5926 +v 1.0710 3.2194 0.1548 +v 1.0021 3.2613 0.1548 +v 1.0021 3.2613 2.5926 +v 1.0018 3.3049 2.5926 +v 1.0021 3.3486 2.5926 +v 1.0021 3.3486 0.1548 +v 1.0018 3.3049 0.1548 +v 1.0021 3.0631 0.1548 +v 1.0021 3.0631 2.5926 +v 1.0710 2.5340 0.1548 +v 1.0710 2.5340 2.5926 +v 1.0710 2.6484 2.5926 +v 1.0710 2.6484 0.1548 +v 1.0021 2.6903 0.1548 +v 1.0021 2.6903 2.5926 +v 1.0018 2.7339 2.5926 +v 1.0021 2.7776 2.5926 +v 1.0021 2.7776 0.1548 +v 1.0018 2.7339 0.1548 +v 1.0021 2.4921 0.1548 +v 1.0021 2.4921 2.5926 +v 1.0710 1.9630 0.1548 +v 1.0710 1.9630 2.5926 +v 1.0710 2.0774 2.5926 +v 1.0710 2.0774 0.1548 +v 1.0021 2.1193 0.1548 +v 1.0021 2.1193 2.5926 +v 1.0018 2.1629 2.5926 +v 1.0021 2.2066 2.5926 +v 1.0021 2.2066 0.1548 +v 1.0018 2.1629 0.1548 +v 1.0021 1.9211 0.1548 +v 1.0021 1.9211 2.5926 +v 1.0710 1.6775 0.1548 +v 1.0710 1.6775 2.5926 +v 1.0710 1.7919 2.5926 +v 1.0710 1.7919 0.1548 +v 1.0021 1.8338 0.1548 +v 1.0021 1.8338 2.5926 +v 1.0018 1.8774 2.5926 +v 1.0018 1.8774 0.1548 +v 1.0021 1.6356 0.1548 +v 1.0021 1.6356 2.5926 +v 1.0710 3.3905 0.1548 +v 1.0710 3.3905 2.5926 +v 1.0710 3.5049 2.5926 +v 1.0710 3.5049 0.1548 +v 1.0021 3.5468 0.1548 +v 1.0021 3.5468 2.5926 +v 1.0018 3.5904 2.5926 +v 1.0018 3.5904 0.1548 +v 1.0710 2.8195 0.1548 +v 1.0710 2.8195 2.5926 +v 1.0710 2.9339 2.5926 +v 1.0710 2.9339 0.1548 +v 1.0021 2.9758 0.1548 +v 1.0021 2.9758 2.5926 +v 1.0018 3.0194 2.5926 +v 1.0018 3.0194 0.1548 +v 1.0710 2.2485 0.1548 +v 1.0710 2.2485 2.5926 +v 1.0710 2.3629 2.5926 +v 1.0710 2.3629 0.1548 +v 1.0021 2.4048 0.1548 +v 1.0021 2.4048 2.5926 +v 1.0018 2.4484 2.5926 +v 1.0018 2.4484 0.1548 +v 1.0710 1.3920 0.1548 +v 1.0710 1.3920 2.5926 +v 1.0710 1.5064 2.5926 +v 1.0710 1.5064 0.1548 +v 1.0021 1.5483 0.1548 +v 1.0021 1.5483 2.5926 +v 1.0018 1.5919 2.5926 +v 1.0018 1.5919 0.1548 +v 1.0021 1.3501 0.1548 +v 1.0021 1.3501 2.5926 +v 1.0710 1.1065 0.1548 +v 1.0710 1.1065 2.5926 +v 1.0710 1.2209 2.5926 +v 1.0710 1.2209 0.1548 +v 1.0021 1.2628 0.1548 +v 1.0021 1.2628 2.5926 +v 1.0018 1.3064 2.5926 +v 1.0018 1.3064 0.1548 +v 1.0021 1.0646 0.1548 +v 1.0021 1.0646 2.5926 +v 1.0710 0.8210 0.1548 +v 1.0710 0.8210 2.5926 +v 1.0710 0.9354 2.5926 +v 1.0710 0.9354 0.1548 +v 1.0021 0.9773 0.1548 +v 1.0021 0.9773 2.5926 +v 1.0018 1.0209 2.5926 +v 1.0018 1.0209 0.1548 +v 1.0021 0.7791 0.1548 +v 1.0021 0.7791 2.5926 +v 1.0710 0.5355 0.1548 +v 1.0710 0.5355 2.5926 +v 1.0710 0.6499 2.5926 +v 1.0710 0.6499 0.1548 +v 1.0021 0.6918 0.1548 +v 1.0021 0.6918 2.5926 +v 1.0018 0.7354 2.5926 +v 1.0019 0.7354 0.1548 +v 1.0021 0.4936 0.1548 +v 1.0021 0.4936 2.5926 +v 1.0710 0.2500 0.1548 +v 1.0710 0.2500 2.5926 +v 1.0710 0.3644 2.5926 +v 1.0710 0.3644 0.1548 +v 1.0021 0.4063 0.1548 +v 1.0021 0.4063 2.5926 +v 1.0018 0.4499 2.5926 +v 1.0019 0.4499 0.1548 +v 1.0021 0.2081 0.1548 +v 1.0021 0.2081 2.5926 +v 1.0710 -0.0355 0.1548 +v 1.0710 -0.0355 2.5926 +v 1.0710 0.0789 2.5926 +v 1.0710 0.0789 0.1548 +v 1.0021 0.1208 0.1548 +v 1.0021 0.1208 2.5926 +v 1.0018 0.1644 2.5926 +v 1.0019 0.1644 0.1548 +v 1.0021 -0.0774 0.1548 +v 1.0021 -0.0774 2.5926 +v 1.0710 -0.3210 0.1548 +v 1.0710 -0.3210 2.5926 +v 1.0710 -0.2066 2.5926 +v 1.0710 -0.2066 0.1548 +v 1.0021 -0.1647 0.1548 +v 1.0021 -0.1647 2.5926 +v 1.0018 -0.1211 2.5926 +v 1.0019 -0.1211 0.1548 +v 1.0021 -0.3629 0.1548 +v 1.0021 -0.3629 2.5926 +v 1.0710 -0.6065 0.1548 +v 1.0710 -0.6065 2.5926 +v 1.0710 -0.4921 2.5926 +v 1.0710 -0.4921 0.1548 +v 1.0021 -0.4502 0.1548 +v 1.0021 -0.4502 2.5926 +v 1.0018 -0.4066 2.5926 +v 1.0019 -0.4066 0.1548 +v 1.0021 -0.6484 0.1548 +v 1.0021 -0.6484 2.5926 +v 1.0710 -0.8920 0.1548 +v 1.0710 -0.8920 2.5926 +v 1.0710 -0.7776 2.5926 +v 1.0710 -0.7776 0.1548 +v 1.0021 -0.7357 0.1548 +v 1.0021 -0.7357 2.5926 +v 1.0018 -0.6921 2.5926 +v 1.0019 -0.6921 0.1548 +v 1.0021 -0.9339 0.1548 +v 1.0021 -0.9339 2.5926 +v 1.0710 -1.1775 0.1548 +v 1.0710 -1.1775 2.5926 +v 1.0710 -1.0631 2.5926 +v 1.0710 -1.0631 0.1548 +v 1.0021 -1.0212 0.1548 +v 1.0021 -1.0212 2.5926 +v 1.0018 -0.9776 2.5926 +v 1.0019 -0.9776 0.1548 +v 1.0021 -1.2194 0.1548 +v 1.0021 -1.2194 2.5926 +v 1.0710 -1.4630 0.1548 +v 1.0710 -1.4630 2.5926 +v 1.0710 -1.3486 2.5926 +v 1.0710 -1.3486 0.1548 +v 1.0021 -1.3067 0.1548 +v 1.0021 -1.3067 2.5926 +v 1.0018 -1.2631 2.5926 +v 1.0019 -1.2631 0.1548 +v 1.0021 -1.5049 0.1548 +v 1.0021 -1.5049 2.5926 +v 1.0710 -1.7485 0.1548 +v 1.0710 -1.7485 2.5926 +v 1.0710 -1.6341 2.5926 +v 1.0710 -1.6341 0.1548 +v 1.0021 -1.5922 0.1548 +v 1.0021 -1.5922 2.5926 +v 1.0018 -1.5486 2.5926 +v 1.0019 -1.5486 0.1548 +v 1.0021 -1.7904 0.1548 +v 1.0021 -1.7904 2.5926 +v 1.0710 -2.0340 0.1548 +v 1.0710 -2.0340 2.5926 +v 1.0710 -1.9196 2.5926 +v 1.0710 -1.9196 0.1548 +v 1.0021 -1.8777 0.1548 +v 1.0021 -1.8777 2.5926 +v 1.0018 -1.8341 2.5926 +v 1.0019 -1.8341 0.1548 +v 1.0021 -2.0759 0.1548 +v 1.0021 -2.0759 2.5926 +v 1.0710 -2.3195 0.1548 +v 1.0710 -2.3195 2.5926 +v 1.0710 -2.2051 2.5926 +v 1.0710 -2.2051 0.1548 +v 1.0021 -2.1632 0.1548 +v 1.0021 -2.1632 2.5926 +v 1.0018 -2.1196 2.5926 +v 1.0019 -2.1196 0.1548 +v 1.0021 -2.3614 0.1548 +v 1.0021 -2.3614 2.5926 +v 1.0710 -2.6050 0.1548 +v 1.0710 -2.6050 2.5926 +v 1.0710 -2.4906 2.5926 +v 1.0710 -2.4906 0.1548 +v 1.0021 -2.4487 0.1548 +v 1.0021 -2.4487 2.5926 +v 1.0018 -2.4051 2.5926 +v 1.0019 -2.4051 0.1548 +v 1.0021 -2.6469 0.1548 +v 1.0021 -2.6469 2.5926 +v 1.0710 -3.1760 0.1548 +v 1.0710 -3.1760 2.5926 +v 1.0710 -3.0616 2.5926 +v 1.0710 -3.0616 0.1548 +v 1.0021 -3.0197 0.1548 +v 1.0021 -3.0197 2.5926 +v 1.0018 -2.9761 2.5926 +v 1.0021 -2.9324 2.5926 +v 1.0021 -2.9324 0.1548 +v 1.0019 -2.9761 0.1548 +v 1.0021 -3.2179 0.1548 +v 1.0021 -3.2179 2.5926 +v 1.0710 -3.4615 0.1548 +v 1.0710 -3.4615 2.5926 +v 1.0710 -3.3471 2.5926 +v 1.0710 -3.3471 0.1548 +v 1.0019 -3.5482 0.1548 +v 1.0019 -3.5482 2.5926 +v 1.0021 -3.5034 2.5926 +v 1.0021 -3.5034 0.1548 +v 1.0021 -3.3052 0.1548 +v 1.0021 -3.3052 2.5926 +v 1.0019 -3.2616 2.5926 +v 1.0019 -3.2616 0.1548 +v 1.0710 -2.8905 0.1548 +v 1.0710 -2.8905 2.5926 +v 1.0710 -2.7761 2.5926 +v 1.0710 -2.7761 0.1548 +v 1.0021 -2.7342 0.1548 +v 1.0021 -2.7342 2.5926 +v 1.0018 -2.6906 2.5926 +v 1.0019 -2.6906 0.1548 +# 844 vertices + +vn 1.0000 0.0000 0.0000 +vn 0.5196 -0.8544 0.0000 +vn 0.5196 0.8544 0.0000 +vn 1.0000 -0.0000 0.0000 +vn 0.5196 0.8544 -0.0000 +vn -1.0000 -0.0000 -0.0000 +vn -1.0000 -0.0057 -0.0000 +vn -0.5196 0.8544 -0.0000 +vn -0.5196 -0.8544 -0.0000 +vn -1.0000 0.0000 -0.0000 +vn -0.5196 0.8544 0.0000 +vn -0.5196 -0.8544 0.0000 +vn -1.0000 0.0057 -0.0000 +# 13 vertex normals + +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.0885 0.0000 +vt 0.1074 0.1588 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.0885 0.0000 +vt 0.1060 0.1588 0.0000 +vt 0.1060 0.1588 0.0000 +# 844 texture coords + +# g Wall_Right +# usemtl ShippingContainer +# s off +# f 2498/2504/88 2499/2505/88 2500/2502/88 2501/2503/88 +# f 2502/2508/88 2503/2509/88 2504/2506/88 2505/2507/88 +# f 2499/2505/89 2506/2511/89 2507/2510/89 2500/2502/89 +# f 2501/2503/90 2502/2508/90 2505/2507/90 2498/2504/90 +# f 2508/2514/88 2509/2515/88 2510/2512/88 2511/2513/88 +# f 2512/2517/91 2513/2518/91 2514/2519/91 2515/2516/91 2507/2510/91 2506/2511/91 +# f 2509/2515/89 2516/2521/89 2517/2520/89 2510/2512/89 +# f 2511/2513/90 2514/2519/90 2513/2518/90 2508/2514/90 +# f 2518/2524/88 2519/2525/88 2520/2522/88 2521/2523/88 +# f 2522/2527/88 2523/2528/88 2524/2529/88 2525/2526/88 2517/2520/88 2516/2521/88 +# f 2519/2525/89 2526/2531/89 2527/2530/89 2520/2522/89 +# f 2521/2523/90 2524/2529/90 2523/2528/90 2518/2524/90 +# f 2528/2534/88 2529/2535/88 2530/2532/88 2531/2533/88 +# f 2532/2539/88 2533/2540/88 2534/2541/88 2535/2536/88 2536/2537/88 2537/2538/88 +# f 2529/2535/89 2538/2543/89 2539/2542/89 2530/2532/89 +# f 2531/2533/90 2534/2541/90 2533/2540/90 2528/2534/90 +# f 2540/2546/88 2541/2547/88 2542/2544/88 2543/2545/88 +# f 2544/2549/88 2545/2550/88 2546/2551/88 2547/2548/88 2539/2542/88 2538/2543/88 +# f 2541/2547/89 2548/2553/89 2549/2552/89 2542/2544/89 +# f 2543/2545/90 2546/2551/90 2545/2550/90 2540/2546/90 +# f 2550/2556/88 2551/2557/88 2552/2554/88 2553/2555/88 +# f 2554/2561/88 2555/2562/88 2556/2563/88 2557/2558/88 2558/2559/88 2559/2560/88 +# f 2551/2557/89 2560/2565/89 2561/2564/89 2552/2554/89 +# f 2553/2555/90 2556/2563/90 2555/2562/90 2550/2556/90 +# f 2562/2568/88 2563/2569/88 2564/2566/88 2565/2567/88 +# f 2566/2571/88 2567/2572/88 2568/2573/88 2569/2570/88 2527/2530/88 2526/2531/88 +# f 2563/2569/89 2537/2538/89 2536/2537/89 2564/2566/89 +# f 2565/2567/90 2568/2573/90 2567/2572/90 2562/2568/90 +# f 2570/2576/88 2571/2577/88 2572/2574/88 2573/2575/88 +# f 2574/2579/91 2575/2580/91 2576/2581/91 2577/2578/91 2549/2552/91 2548/2553/91 +# f 2571/2577/89 2578/2583/89 2579/2582/89 2572/2574/89 +# f 2573/2575/92 2576/2581/92 2575/2580/92 2570/2576/92 +# f 2580/2586/88 2581/2587/88 2582/2584/88 2583/2585/88 +# f 2584/2589/91 2585/2590/91 2586/2591/91 2587/2588/91 2579/2582/91 2578/2583/91 +# f 2581/2587/89 2559/2560/89 2558/2559/89 2582/2584/89 +# f 2583/2585/90 2586/2591/90 2585/2590/90 2580/2586/90 +# f 2588/2594/88 2589/2595/88 2590/2592/88 2591/2593/88 +# f 2592/2597/91 2593/2598/91 2594/2599/91 2595/2596/91 2561/2564/91 2560/2565/91 +# f 2589/2595/89 2596/2601/89 2597/2600/89 2590/2592/89 +# f 2591/2593/90 2594/2599/90 2593/2598/90 2588/2594/90 +# f 2598/2604/88 2599/2605/88 2600/2602/88 2601/2603/88 +# f 2602/2607/88 2603/2608/88 2604/2609/88 2605/2606/88 2597/2600/88 2596/2601/88 +# f 2599/2605/89 2606/2611/89 2607/2610/89 2600/2602/89 +# f 2601/2603/90 2604/2609/90 2603/2608/90 2598/2604/90 +# f 2608/2614/88 2609/2615/88 2610/2612/88 2611/2613/88 +# f 2612/2619/91 2613/2620/91 2614/2621/91 2615/2616/91 2616/2617/91 2617/2618/91 +# f 2609/2615/89 2618/2623/89 2619/2622/89 2610/2612/89 +# f 2611/2613/90 2614/2621/90 2613/2620/90 2608/2614/90 +# f 2620/2626/88 2621/2627/88 2622/2624/88 2623/2625/88 +# f 2624/2629/88 2625/2630/88 2626/2631/88 2627/2628/88 2619/2622/88 2618/2623/88 +# f 2621/2627/89 2628/2633/89 2629/2632/89 2622/2624/89 +# f 2623/2625/90 2626/2631/90 2625/2630/90 2620/2626/90 +# f 2630/2636/88 2631/2637/88 2632/2634/88 2633/2635/88 +# f 2634/2639/88 2635/2640/88 2636/2641/88 2637/2638/88 2607/2610/88 2606/2611/88 +# f 2631/2637/89 2638/2643/89 2639/2642/89 2632/2634/89 +# f 2633/2635/90 2636/2641/90 2635/2640/90 2630/2636/90 +# f 2640/2646/88 2641/2647/88 2642/2644/88 2643/2645/88 +# f 2644/2651/88 2645/2652/88 2646/2653/88 2647/2648/88 2648/2649/88 2649/2650/88 +# f 2641/2647/89 2617/2618/89 2616/2617/89 2642/2644/89 +# f 2643/2645/90 2646/2653/90 2645/2652/90 2640/2646/90 +# f 2650/2656/88 2651/2657/88 2652/2654/88 2653/2655/88 +# f 2654/2659/88 2655/2660/88 2656/2661/88 2657/2658/88 2639/2642/88 2638/2643/88 +# f 2651/2657/89 2649/2650/89 2648/2649/89 2652/2654/89 +# f 2653/2655/90 2656/2661/90 2655/2660/90 2650/2656/90 +# f 2658/2664/88 2659/2665/88 2660/2662/88 2661/2663/88 +# f 2662/2667/91 2663/2668/91 2664/2669/91 2665/2666/91 2629/2632/91 2628/2633/91 +# f 2659/2665/89 2666/2671/89 2667/2670/89 2660/2662/89 +# f 2661/2663/90 2664/2669/90 2663/2668/90 2658/2664/90 +# f 2668/2674/88 2669/2675/88 2670/2672/88 2671/2673/88 +# f 2672/2679/88 2673/2680/88 2674/2681/88 2675/2676/88 2676/2677/88 2677/2678/88 +# f 2669/2675/89 2678/2683/89 2679/2682/89 2670/2672/89 +# f 2671/2673/90 2674/2681/90 2673/2680/90 2668/2674/90 +# f 2680/2686/88 2681/2687/88 2682/2684/88 2683/2685/88 +# f 2684/2691/88 2685/2692/88 2686/2693/88 2687/2688/88 2688/2689/88 2689/2690/88 +# f 2681/2687/89 2690/2695/89 2691/2694/89 2682/2684/89 +# f 2683/2685/90 2686/2693/90 2685/2692/90 2680/2686/90 +# f 2692/2698/88 2693/2699/88 2694/2696/88 2695/2697/88 +# f 2696/2703/91 2697/2704/91 2698/2705/91 2699/2700/91 2700/2701/91 2701/2702/91 +# f 2693/2699/89 2702/2707/89 2703/2706/89 2694/2696/89 +# f 2695/2697/90 2698/2705/90 2697/2704/90 2692/2698/90 +# f 2704/2710/88 2705/2711/88 2706/2708/88 2707/2709/88 +# f 2708/2713/88 2709/2714/88 2710/2715/88 2711/2712/88 2703/2706/88 2702/2707/88 +# f 2705/2711/89 2712/2717/89 2713/2716/89 2706/2708/89 +# f 2707/2709/90 2710/2715/90 2709/2714/90 2704/2710/90 +# f 2714/2720/88 2715/2721/88 2716/2718/88 2717/2719/88 +# f 2718/2723/91 2719/2724/91 2720/2725/91 2721/2722/91 2667/2670/91 2666/2671/91 +# f 2715/2721/89 2677/2678/89 2676/2677/89 2716/2718/89 +# f 2717/2719/90 2720/2725/90 2719/2724/90 2714/2720/90 +# f 2722/2728/88 2723/2729/88 2724/2726/88 2725/2727/88 +# f 2726/2731/91 2727/2732/91 2728/2733/91 2729/2730/91 2679/2682/91 2678/2683/91 +# f 2723/2729/89 2689/2690/89 2688/2689/89 2724/2726/89 +# f 2725/2727/90 2728/2733/90 2727/2732/90 2722/2728/90 +# f 2730/2736/88 2731/2737/88 2732/2734/88 2733/2735/88 +# f 2734/2739/91 2735/2740/91 2736/2741/91 2737/2738/91 2691/2694/91 2690/2695/91 +# f 2731/2737/89 2701/2702/89 2700/2701/89 2732/2734/89 +# f 2733/2735/90 2736/2741/90 2735/2740/90 2730/2736/90 +# f 2738/2744/88 2739/2745/88 2740/2742/88 2741/2743/88 +# f 2742/2747/88 2743/2748/88 2744/2749/88 2745/2746/88 2713/2716/88 2712/2717/88 +# f 2739/2745/89 2746/2751/89 2747/2750/89 2740/2742/89 +# f 2741/2743/90 2744/2749/90 2743/2748/90 2738/2744/90 +# f 2748/2754/88 2749/2755/88 2750/2752/88 2751/2753/88 +# f 2752/2757/88 2753/2758/88 2754/2759/88 2755/2756/88 2747/2750/88 2746/2751/88 +# f 2749/2755/89 2756/2761/89 2757/2760/89 2750/2752/89 +# f 2751/2753/90 2754/2759/90 2753/2758/90 2748/2754/90 +# f 2758/2764/88 2759/2765/88 2760/2762/88 2761/2763/88 +# f 2762/2767/88 2763/2768/88 2764/2769/88 2765/2766/88 2757/2760/88 2756/2761/88 +# f 2759/2765/89 2766/2771/89 2767/2770/89 2760/2762/89 +# f 2761/2763/90 2764/2769/90 2763/2768/90 2758/2764/90 +# f 2768/2774/88 2769/2775/88 2770/2772/88 2771/2773/88 +# f 2772/2777/88 2773/2778/88 2774/2779/88 2775/2776/88 2767/2770/88 2766/2771/88 +# f 2769/2775/89 2776/2781/89 2777/2780/89 2770/2772/89 +# f 2771/2773/90 2774/2779/90 2773/2778/90 2768/2774/90 +# f 2778/2784/88 2779/2785/88 2780/2782/88 2781/2783/88 +# f 2782/2787/88 2783/2788/88 2784/2789/88 2785/2786/88 2777/2780/88 2776/2781/88 +# f 2779/2785/89 2786/2791/89 2787/2790/89 2780/2782/89 +# f 2781/2783/90 2784/2789/90 2783/2788/90 2778/2784/90 +# f 2788/2794/88 2789/2795/88 2790/2792/88 2791/2793/88 +# f 2792/2797/88 2793/2798/88 2794/2799/88 2795/2796/88 2787/2790/88 2786/2791/88 +# f 2789/2795/89 2796/2801/89 2797/2800/89 2790/2792/89 +# f 2791/2793/90 2794/2799/90 2793/2798/90 2788/2794/90 +# f 2798/2804/88 2799/2805/88 2800/2802/88 2801/2803/88 +# f 2802/2807/88 2803/2808/88 2804/2809/88 2805/2806/88 2797/2800/88 2796/2801/88 +# f 2799/2805/89 2806/2811/89 2807/2810/89 2800/2802/89 +# f 2801/2803/90 2804/2809/90 2803/2808/90 2798/2804/90 +# f 2808/2814/88 2809/2815/88 2810/2812/88 2811/2813/88 +# f 2812/2817/88 2813/2818/88 2814/2819/88 2815/2816/88 2807/2810/88 2806/2811/88 +# f 2809/2815/89 2816/2821/89 2817/2820/89 2810/2812/89 +# f 2811/2813/90 2814/2819/90 2813/2818/90 2808/2814/90 +# f 2818/2824/88 2819/2825/88 2820/2822/88 2821/2823/88 +# f 2822/2827/88 2823/2828/88 2824/2829/88 2825/2826/88 2817/2820/88 2816/2821/88 +# f 2819/2825/89 2826/2831/89 2827/2830/89 2820/2822/89 +# f 2821/2823/90 2824/2829/90 2823/2828/90 2818/2824/90 +# f 2828/2834/88 2829/2835/88 2830/2832/88 2831/2833/88 +# f 2832/2837/88 2833/2838/88 2834/2839/88 2835/2836/88 2827/2830/88 2826/2831/88 +# f 2829/2835/89 2836/2841/89 2837/2840/89 2830/2832/89 +# f 2831/2833/90 2834/2839/90 2833/2838/90 2828/2834/90 +# f 2838/2844/88 2839/2845/88 2840/2842/88 2841/2843/88 +# f 2842/2847/91 2843/2848/91 2844/2849/91 2845/2846/91 2837/2840/91 2836/2841/91 +# f 2839/2845/89 2846/2851/89 2847/2850/89 2840/2842/89 +# f 2841/2843/90 2844/2849/90 2843/2848/90 2838/2844/90 +# f 2848/2854/88 2849/2855/88 2850/2852/88 2851/2853/88 +# f 2852/2857/91 2853/2858/91 2854/2859/91 2855/2856/91 2847/2850/91 2846/2851/91 +# f 2849/2855/89 2856/2861/89 2857/2860/89 2850/2852/89 +# f 2851/2853/90 2854/2859/90 2853/2858/90 2848/2854/90 +# f 2858/2864/88 2859/2865/88 2860/2862/88 2861/2863/88 +# f 2862/2867/88 2863/2868/88 2864/2869/88 2865/2866/88 2857/2860/88 2856/2861/88 +# f 2859/2865/89 2866/2871/89 2867/2870/89 2860/2862/89 +# f 2861/2863/90 2864/2869/90 2863/2868/90 2858/2864/90 +# f 2868/2874/88 2869/2875/88 2870/2872/88 2871/2873/88 +# f 2872/2877/91 2873/2878/91 2874/2879/91 2875/2876/91 2867/2870/91 2866/2871/91 +# f 2869/2875/89 2876/2881/89 2877/2880/89 2870/2872/89 +# f 2871/2873/90 2874/2879/90 2873/2878/90 2868/2874/90 +# f 2878/2884/88 2879/2885/88 2880/2882/88 2881/2883/88 +# f 2882/2887/88 2883/2888/88 2884/2889/88 2885/2886/88 2877/2880/88 2876/2881/88 +# f 2879/2885/89 2886/2891/89 2887/2890/89 2880/2882/89 +# f 2881/2883/90 2884/2889/90 2883/2888/90 2878/2884/90 +# f 2888/2894/88 2889/2895/88 2890/2892/88 2891/2893/88 +# f 2892/2899/88 2893/2900/88 2894/2901/88 2895/2896/88 2896/2897/88 2897/2898/88 +# f 2889/2895/89 2898/2903/89 2899/2902/89 2890/2892/89 +# f 2891/2893/90 2894/2901/90 2893/2900/90 2888/2894/90 +# f 2900/2906/88 2901/2907/88 2902/2904/88 2903/2905/88 +# f 2904/2910/88 2905/2911/88 2906/2908/88 2907/2909/88 +# f 2908/2913/88 2909/2914/88 2910/2915/88 2911/2912/88 2899/2902/88 2898/2903/88 +# f 2901/2907/89 2904/2910/89 2907/2909/89 2902/2904/89 +# f 2903/2905/90 2910/2915/90 2909/2914/90 2900/2906/90 +# f 2912/2918/88 2913/2919/88 2914/2916/88 2915/2917/88 +# f 2916/2921/88 2917/2922/88 2918/2923/88 2919/2920/88 2887/2890/88 2886/2891/88 +# f 2913/2919/89 2897/2898/89 2896/2897/89 2914/2916/89 +# f 2915/2917/90 2918/2923/90 2917/2922/90 2912/2918/90 +# f 2920/2926/93 2921/2927/93 2922/2924/93 2923/2925/93 +# f 2924/2930/94 2925/2931/94 2926/2928/94 2927/2929/94 +# f 2928/2932/95 2929/2933/95 2921/2927/95 2920/2926/95 +# f 2927/2929/96 2926/2928/96 2923/2925/96 2922/2924/96 +# f 2930/2936/93 2931/2937/93 2932/2934/93 2933/2935/93 +# f 2934/2939/97 2935/2940/97 2936/2941/97 2929/2933/97 2928/2932/97 2937/2938/97 +# f 2938/2942/98 2939/2943/98 2931/2937/98 2930/2936/98 +# f 2935/2940/96 2934/2939/96 2933/2935/96 2932/2934/96 +# f 2940/2946/93 2941/2947/93 2942/2944/93 2943/2945/93 +# f 2944/2949/93 2945/2950/93 2946/2951/93 2939/2943/93 2938/2942/93 2947/2948/93 +# f 2948/2952/95 2949/2953/95 2941/2947/95 2940/2946/95 +# f 2945/2950/96 2944/2949/96 2943/2945/96 2942/2944/96 +# f 2950/2956/93 2951/2957/93 2952/2954/93 2953/2955/93 +# f 2954/2961/97 2955/2962/97 2956/2963/97 2957/2958/97 2958/2959/97 2959/2960/97 +# f 2960/2964/95 2961/2965/95 2951/2957/95 2950/2956/95 +# f 2955/2962/96 2954/2961/96 2953/2955/96 2952/2954/96 +# f 2962/2968/97 2963/2969/97 2964/2966/97 2965/2967/97 +# f 2966/2971/97 2967/2972/97 2968/2973/97 2961/2965/97 2960/2964/97 2969/2970/97 +# f 2970/2974/95 2971/2975/95 2963/2969/95 2962/2968/95 +# f 2967/2972/96 2966/2971/96 2965/2967/96 2964/2966/96 +# f 2972/2978/97 2973/2979/97 2974/2976/97 2975/2977/97 +# f 2976/2983/93 2977/2984/93 2978/2985/93 2979/2980/93 2980/2981/93 2981/2982/93 +# f 2982/2986/95 2983/2987/95 2973/2979/95 2972/2978/95 +# f 2977/2984/96 2976/2983/96 2975/2977/96 2974/2976/96 +# f 2984/2990/93 2985/2991/93 2986/2988/93 2987/2989/93 +# f 2988/2993/97 2989/2994/97 2990/2995/97 2949/2953/97 2948/2952/97 2991/2992/97 +# f 2958/2959/95 2957/2958/95 2985/2991/95 2984/2990/95 +# f 2989/2994/96 2988/2993/96 2987/2989/96 2986/2988/96 +# f 2992/2998/97 2993/2999/97 2994/2996/97 2995/2997/97 +# f 2996/3001/97 2997/3002/97 2998/3003/97 2971/2975/97 2970/2974/97 2999/3000/97 +# f 3000/3004/95 3001/3005/95 2993/2999/95 2992/2998/95 +# f 2997/3002/99 2996/3001/99 2995/2997/99 2994/2996/99 +# f 3002/3008/97 3003/3009/97 3004/3006/97 3005/3007/97 +# f 3006/3011/97 3007/3012/97 3008/3013/97 3001/3005/97 3000/3004/97 3009/3010/97 +# f 2980/2981/95 2979/2980/95 3003/3009/95 3002/3008/95 +# f 3007/3012/96 3006/3011/96 3005/3007/96 3004/3006/96 +# f 3010/3016/97 3011/3017/97 3012/3014/97 3013/3015/97 +# f 3014/3019/97 3015/3020/97 3016/3021/97 2983/2987/97 2982/2986/97 3017/3018/97 +# f 3018/3022/95 3019/3023/95 3011/3017/95 3010/3016/95 +# f 3015/3020/96 3014/3019/96 3013/3015/96 3012/3014/96 +# f 3020/3026/97 3021/3027/97 3022/3024/97 3023/3025/97 +# f 3024/3029/97 3025/3030/97 3026/3031/97 3019/3023/97 3018/3022/97 3027/3028/97 +# f 3028/3032/95 3029/3033/95 3021/3027/95 3020/3026/95 +# f 3025/3030/96 3024/3029/96 3023/3025/96 3022/3024/96 +# f 3030/3036/97 3031/3037/97 3032/3034/97 3033/3035/97 +# f 3034/3041/97 3035/3042/97 3036/3043/97 3037/3038/97 3038/3039/97 3039/3040/97 +# f 3040/3044/95 3041/3045/95 3031/3037/95 3030/3036/95 +# f 3035/3042/96 3034/3041/96 3033/3035/96 3032/3034/96 +# f 3042/3048/93 3043/3049/93 3044/3046/93 3045/3047/93 +# f 3046/3051/93 3047/3052/93 3048/3053/93 3041/3045/93 3040/3044/93 3049/3050/93 +# f 3050/3054/95 3051/3055/95 3043/3049/95 3042/3048/95 +# f 3047/3052/96 3046/3051/96 3045/3047/96 3044/3046/96 +# f 3052/3058/97 3053/3059/97 3054/3056/97 3055/3057/97 +# f 3056/3061/97 3057/3062/97 3058/3063/97 3029/3033/97 3028/3032/97 3059/3060/97 +# f 3060/3064/95 3061/3065/95 3053/3059/95 3052/3058/95 +# f 3057/3062/96 3056/3061/96 3055/3057/96 3054/3056/96 +# f 3062/3068/97 3063/3069/97 3064/3066/97 3065/3067/97 +# f 3066/3073/93 3067/3074/93 3068/3075/93 3069/3070/93 3070/3071/93 3071/3072/93 +# f 3038/3039/95 3037/3038/95 3063/3069/95 3062/3068/95 +# f 3067/3074/96 3066/3073/96 3065/3067/96 3064/3066/96 +# f 3072/3078/97 3073/3079/97 3074/3076/97 3075/3077/97 +# f 3076/3081/97 3077/3082/97 3078/3083/97 3061/3065/97 3060/3064/97 3079/3080/97 +# f 3070/3071/95 3069/3070/95 3073/3079/95 3072/3078/95 +# f 3077/3082/96 3076/3081/96 3075/3077/96 3074/3076/96 +# f 3080/3086/93 3081/3087/93 3082/3084/93 3083/3085/93 +# f 3084/3089/97 3085/3090/97 3086/3091/97 3051/3055/97 3050/3054/97 3087/3088/97 +# f 3088/3092/95 3089/3093/95 3081/3087/95 3080/3086/95 +# f 3085/3090/96 3084/3089/96 3083/3085/96 3082/3084/96 +# f 3090/3096/93 3091/3097/93 3092/3094/93 3093/3095/93 +# f 3094/3101/93 3095/3102/93 3096/3103/93 3097/3098/93 3098/3099/93 3099/3100/93 +# f 3100/3104/95 3101/3105/95 3091/3097/95 3090/3096/95 +# f 3095/3102/96 3094/3101/96 3093/3095/96 3092/3094/96 +# f 3102/3108/93 3103/3109/93 3104/3106/93 3105/3107/93 +# f 3106/3113/93 3107/3114/93 3108/3115/93 3109/3110/93 3110/3111/93 3111/3112/93 +# f 3112/3116/95 3113/3117/95 3103/3109/95 3102/3108/95 +# f 3107/3114/96 3106/3113/96 3105/3107/96 3104/3106/96 +# f 3114/3120/93 3115/3121/93 3116/3118/93 3117/3119/93 +# f 3118/3125/97 3119/3126/97 3120/3127/97 3121/3122/97 3122/3123/97 3123/3124/97 +# f 3124/3128/95 3125/3129/95 3115/3121/95 3114/3120/95 +# f 3119/3126/96 3118/3125/96 3117/3119/96 3116/3118/96 +# f 3126/3132/93 3127/3133/93 3128/3130/93 3129/3131/93 +# f 3130/3135/97 3131/3136/97 3132/3137/97 3125/3129/97 3124/3128/97 3133/3134/97 +# f 3134/3138/95 3135/3139/95 3127/3133/95 3126/3132/95 +# f 3131/3136/96 3130/3135/96 3129/3131/96 3128/3130/96 +# f 3136/3142/93 3137/3143/93 3138/3140/93 3139/3141/93 +# f 3140/3145/97 3141/3146/97 3142/3147/97 3089/3093/97 3088/3092/97 3143/3144/97 +# f 3098/3099/95 3097/3098/95 3137/3143/95 3136/3142/95 +# f 3141/3146/96 3140/3145/96 3139/3141/96 3138/3140/96 +# f 3144/3150/93 3145/3151/93 3146/3148/93 3147/3149/93 +# f 3148/3153/97 3149/3154/97 3150/3155/97 3101/3105/97 3100/3104/97 3151/3152/97 +# f 3110/3111/95 3109/3110/95 3145/3151/95 3144/3150/95 +# f 3149/3154/96 3148/3153/96 3147/3149/96 3146/3148/96 +# f 3152/3158/93 3153/3159/93 3154/3156/93 3155/3157/93 +# f 3156/3161/97 3157/3162/97 3158/3163/97 3113/3117/97 3112/3116/97 3159/3160/97 +# f 3122/3123/95 3121/3122/95 3153/3159/95 3152/3158/95 +# f 3157/3162/96 3156/3161/96 3155/3157/96 3154/3156/96 +# f 3160/3166/93 3161/3167/93 3162/3164/93 3163/3165/93 +# f 3164/3169/97 3165/3170/97 3166/3171/97 3135/3139/97 3134/3138/97 3167/3168/97 +# f 3168/3172/95 3169/3173/95 3161/3167/95 3160/3166/95 +# f 3165/3170/96 3164/3169/96 3163/3165/96 3162/3164/96 +# f 3170/3176/93 3171/3177/93 3172/3174/93 3173/3175/93 +# f 3174/3179/97 3175/3180/97 3176/3181/97 3169/3173/97 3168/3172/97 3177/3178/97 +# f 3178/3182/95 3179/3183/95 3171/3177/95 3170/3176/95 +# f 3175/3180/96 3174/3179/96 3173/3175/96 3172/3174/96 +# f 3180/3186/97 3181/3187/97 3182/3184/97 3183/3185/97 +# f 3184/3189/97 3185/3190/97 3186/3191/97 3179/3183/97 3178/3182/97 3187/3188/97 +# f 3188/3192/95 3189/3193/95 3181/3187/95 3180/3186/95 +# f 3185/3190/96 3184/3189/96 3183/3185/96 3182/3184/96 +# f 3190/3196/97 3191/3197/97 3192/3194/97 3193/3195/97 +# f 3194/3199/97 3195/3200/97 3196/3201/97 3189/3193/97 3188/3192/97 3197/3198/97 +# f 3198/3202/95 3199/3203/95 3191/3197/95 3190/3196/95 +# f 3195/3200/96 3194/3199/96 3193/3195/96 3192/3194/96 +# f 3200/3206/97 3201/3207/97 3202/3204/97 3203/3205/97 +# f 3204/3209/93 3205/3210/93 3206/3211/93 3199/3203/93 3198/3202/93 3207/3208/93 +# f 3208/3212/95 3209/3213/95 3201/3207/95 3200/3206/95 +# f 3205/3210/96 3204/3209/96 3203/3205/96 3202/3204/96 +# f 3210/3216/97 3211/3217/97 3212/3214/97 3213/3215/97 +# f 3214/3219/97 3215/3220/97 3216/3221/97 3209/3213/97 3208/3212/97 3217/3218/97 +# f 3218/3222/95 3219/3223/95 3211/3217/95 3210/3216/95 +# f 3215/3220/96 3214/3219/96 3213/3215/96 3212/3214/96 +# f 3220/3226/97 3221/3227/97 3222/3224/97 3223/3225/97 +# f 3224/3229/97 3225/3230/97 3226/3231/97 3219/3223/97 3218/3222/97 3227/3228/97 +# f 3228/3232/95 3229/3233/95 3221/3227/95 3220/3226/95 +# f 3225/3230/96 3224/3229/96 3223/3225/96 3222/3224/96 +# f 3230/3236/97 3231/3237/97 3232/3234/97 3233/3235/97 +# f 3234/3239/93 3235/3240/93 3236/3241/93 3229/3233/93 3228/3232/93 3237/3238/93 +# f 3238/3242/95 3239/3243/95 3231/3237/95 3230/3236/95 +# f 3235/3240/96 3234/3239/96 3233/3235/96 3232/3234/96 +# f 3240/3246/93 3241/3247/93 3242/3244/93 3243/3245/93 +# f 3244/3249/97 3245/3250/97 3246/3251/97 3239/3243/97 3238/3242/97 3247/3248/97 +# f 3248/3252/95 3249/3253/95 3241/3247/95 3240/3246/95 +# f 3245/3250/96 3244/3249/96 3243/3245/96 3242/3244/96 +# f 3250/3256/93 3251/3257/93 3252/3254/93 3253/3255/93 +# f 3254/3259/97 3255/3260/97 3256/3261/97 3249/3253/97 3248/3252/97 3257/3258/97 +# f 3258/3262/95 3259/3263/95 3251/3257/95 3250/3256/95 +# f 3255/3260/96 3254/3259/96 3253/3255/96 3252/3254/96 +# f 3260/3266/93 3261/3267/93 3262/3264/93 3263/3265/93 +# f 3264/3269/97 3265/3270/97 3266/3271/97 3259/3263/97 3258/3262/97 3267/3268/97 +# f 3268/3272/95 3269/3273/95 3261/3267/95 3260/3266/95 +# f 3265/3270/96 3264/3269/96 3263/3265/96 3262/3264/96 +# f 3270/3276/93 3271/3277/93 3272/3274/93 3273/3275/93 +# f 3274/3279/97 3275/3280/97 3276/3281/97 3269/3273/97 3268/3272/97 3277/3278/97 +# f 3278/3282/95 3279/3283/95 3271/3277/95 3270/3276/95 +# f 3275/3280/96 3274/3279/96 3273/3275/96 3272/3274/96 +# f 3280/3286/93 3281/3287/93 3282/3284/93 3283/3285/93 +# f 3284/3289/97 3285/3290/97 3286/3291/97 3279/3283/97 3278/3282/97 3287/3288/97 +# f 3288/3292/95 3289/3293/95 3281/3287/95 3280/3286/95 +# f 3285/3290/96 3284/3289/96 3283/3285/96 3282/3284/96 +# f 3290/3296/93 3291/3297/93 3292/3294/93 3293/3295/93 +# f 3294/3299/97 3295/3300/97 3296/3301/97 3289/3293/97 3288/3292/97 3297/3298/97 +# f 3298/3302/95 3299/3303/95 3291/3297/95 3290/3296/95 +# f 3295/3300/96 3294/3299/96 3293/3295/96 3292/3294/96 +# f 3300/3306/97 3301/3307/97 3302/3304/97 3303/3305/97 +# f 3304/3309/97 3305/3310/97 3306/3311/97 3299/3303/97 3298/3302/97 3307/3308/97 +# f 3308/3312/95 3309/3313/95 3301/3307/95 3300/3306/95 +# f 3305/3310/96 3304/3309/96 3303/3305/96 3302/3304/96 +# f 3310/3316/97 3311/3317/97 3312/3314/97 3313/3315/97 +# f 3314/3321/97 3315/3322/97 3316/3323/97 3317/3318/97 3318/3319/97 3319/3320/97 +# f 3320/3324/95 3321/3325/95 3311/3317/95 3310/3316/95 +# f 3315/3322/96 3314/3321/96 3313/3315/96 3312/3314/96 +# f 3322/3328/97 3323/3329/97 3324/3326/97 3325/3327/97 +# f 3326/3332/100 3327/3333/100 3328/3330/100 3329/3331/100 +# f 3330/3335/97 3331/3336/97 3332/3337/97 3321/3325/97 3320/3324/97 3333/3334/97 +# f 3329/3331/95 3328/3330/95 3323/3329/95 3322/3328/95 +# f 3331/3336/96 3330/3335/96 3325/3327/96 3324/3326/96 +# f 3334/3340/97 3335/3341/97 3336/3338/97 3337/3339/97 +# f 3338/3343/97 3339/3344/97 3340/3345/97 3309/3313/97 3308/3312/97 3341/3342/97 +# f 3318/3319/95 3317/3318/95 3335/3341/95 3334/3340/95 +# f 3339/3344/96 3338/3343/96 3337/3339/96 3336/3338/96 +# 338 polygons + +# +# object Floor +# + +v 0.8985 -3.4712 0.0795 +v 0.8980 8.4565 0.0820 +v 0.8472 8.4565 0.0820 +v 0.8472 -3.4712 0.0820 +v 0.9052 -3.4725 0.1529 +v 0.9913 -3.4712 0.0795 +v 0.9846 -3.4725 0.1529 +v 0.9846 8.4413 0.1529 +v 0.9052 8.4413 0.1529 +v 1.0426 -3.4712 0.0820 +v 1.0426 8.4565 0.0820 +v 0.9919 8.4565 0.0820 +v 0.7031 -3.4712 0.0795 +v 0.7026 8.4565 0.0820 +v 0.6518 8.4565 0.0820 +v 0.6518 -3.4712 0.0820 +v 0.7098 -3.4725 0.1529 +v 0.7959 -3.4712 0.0795 +v 0.7892 -3.4725 0.1529 +v 0.7892 8.4413 0.1529 +v 0.7098 8.4413 0.1529 +v 0.7965 8.4565 0.0820 +v 0.5077 -3.4712 0.0795 +v 0.5072 8.4565 0.0820 +v 0.4564 8.4565 0.0820 +v 0.4564 -3.4712 0.0820 +v 0.5144 -3.4725 0.1529 +v 0.6005 -3.4712 0.0795 +v 0.5938 -3.4725 0.1529 +v 0.5938 8.4413 0.1529 +v 0.5144 8.4413 0.1529 +v 0.6011 8.4565 0.0820 +v 0.3123 -3.4712 0.0795 +v 0.3118 8.4565 0.0820 +v 0.2610 8.4565 0.0820 +v 0.2610 -3.4712 0.0820 +v 0.3190 -3.4725 0.1529 +v 0.4051 -3.4712 0.0795 +v 0.3984 -3.4725 0.1529 +v 0.3984 8.4413 0.1529 +v 0.3190 8.4413 0.1529 +v 0.4057 8.4565 0.0820 +v 0.1169 -3.4712 0.0795 +v 0.1164 8.4565 0.0820 +v 0.0656 8.4565 0.0820 +v 0.0656 -3.4712 0.0820 +v 0.1236 -3.4725 0.1529 +v 0.2097 -3.4712 0.0795 +v 0.2030 -3.4725 0.1529 +v 0.2030 8.4413 0.1529 +v 0.1236 8.4413 0.1529 +v 0.2103 8.4565 0.0820 +v -0.0785 -3.4712 0.0795 +v -0.0790 8.4565 0.0820 +v -0.1298 8.4565 0.0820 +v -0.1298 -3.4712 0.0820 +v -0.0718 -3.4725 0.1529 +v 0.0143 -3.4712 0.0795 +v 0.0076 -3.4725 0.1529 +v 0.0076 8.4413 0.1529 +v -0.0718 8.4413 0.1529 +v 0.0149 8.4565 0.0820 +v -0.4693 -3.4712 0.0795 +v -0.4698 8.4565 0.0820 +v -0.5206 8.4565 0.0820 +v -0.5206 -3.4712 0.0820 +v -0.4626 -3.4725 0.1529 +v -0.3765 -3.4712 0.0795 +v -0.3832 -3.4725 0.1529 +v -0.3832 8.4413 0.1529 +v -0.4626 8.4413 0.1529 +v -0.3252 -3.4712 0.0820 +v -0.3252 8.4565 0.0820 +v -0.3759 8.4565 0.0820 +v -0.8601 -3.4712 0.0795 +v -0.8606 8.4565 0.0820 +v -0.9114 8.4565 0.0820 +v -0.9114 -3.4712 0.0820 +v -0.8534 -3.4725 0.1529 +v -0.7673 -3.4712 0.0795 +v -0.7740 -3.4725 0.1529 +v -0.7740 8.4413 0.1529 +v -0.8534 8.4413 0.1529 +v -0.7160 -3.4712 0.0820 +v -0.7160 8.4565 0.0820 +v -0.7667 8.4565 0.0820 +v -0.2739 -3.4712 0.0795 +v -0.2744 8.4565 0.0820 +v -0.2672 -3.4725 0.1529 +v -0.1811 -3.4712 0.0795 +v -0.1878 -3.4725 0.1529 +v -0.1878 8.4413 0.1529 +v -0.2672 8.4413 0.1529 +v -0.1805 8.4565 0.0820 +v -1.2509 -3.4712 0.0795 +v -1.2514 8.4565 0.0820 +v -1.3021 8.4565 0.0820 +v -1.3021 -3.4712 0.0820 +v -1.2442 -3.4725 0.1529 +v -1.1581 -3.4712 0.0795 +v -1.1648 -3.4725 0.1529 +v -1.1648 8.4413 0.1529 +v -1.2442 8.4413 0.1529 +v -1.1068 -3.4712 0.0820 +v -1.1068 8.4565 0.0820 +v -1.1575 8.4565 0.0820 +v -1.0555 -3.4712 0.0795 +v -1.0560 8.4565 0.0820 +v -1.0488 -3.4725 0.1529 +v -0.9627 -3.4712 0.0795 +v -0.9694 -3.4725 0.1529 +v -0.9694 8.4413 0.1529 +v -1.0488 8.4413 0.1529 +v -0.9621 8.4565 0.0820 +v -0.6647 -3.4712 0.0795 +v -0.6652 8.4565 0.0820 +v -0.6580 -3.4725 0.1529 +v -0.5719 -3.4712 0.0795 +v -0.5786 -3.4725 0.1529 +v -0.5786 8.4413 0.1529 +v -0.6580 8.4413 0.1529 +v -0.5713 8.4565 0.0820 +v 0.8472 8.4565 0.0720 +v 0.9028 8.4514 0.0749 +v 0.9041 -3.4657 0.0732 +v 0.8472 -3.4712 0.0720 +v 0.9857 -3.4657 0.0732 +v 0.9107 -3.4666 0.1470 +v 0.9791 -3.4666 0.1470 +v 0.9108 8.4362 0.1464 +v 0.9791 8.4362 0.1464 +v 0.9871 8.4514 0.0749 +v 1.0426 8.4565 0.0720 +v 1.0431 -3.4712 0.0720 +v 0.6518 8.4565 0.0720 +v 0.7074 8.4514 0.0749 +v 0.7087 -3.4657 0.0732 +v 0.6518 -3.4712 0.0720 +v 0.7903 -3.4657 0.0732 +v 0.7153 -3.4666 0.1470 +v 0.7837 -3.4666 0.1470 +v 0.7154 8.4362 0.1464 +v 0.7837 8.4362 0.1464 +v 0.7917 8.4514 0.0749 +v 0.4564 8.4565 0.0720 +v 0.5120 8.4514 0.0749 +v 0.5133 -3.4657 0.0732 +v 0.4564 -3.4712 0.0720 +v 0.5949 -3.4657 0.0732 +v 0.5199 -3.4666 0.1470 +v 0.5883 -3.4666 0.1470 +v 0.5200 8.4362 0.1464 +v 0.5883 8.4362 0.1464 +v 0.5963 8.4514 0.0749 +v 0.2610 8.4565 0.0720 +v 0.3166 8.4514 0.0749 +v 0.3179 -3.4657 0.0732 +v 0.2610 -3.4712 0.0720 +v 0.3995 -3.4657 0.0732 +v 0.3245 -3.4666 0.1470 +v 0.3929 -3.4666 0.1470 +v 0.3246 8.4362 0.1464 +v 0.3929 8.4362 0.1464 +v 0.4009 8.4514 0.0749 +v 0.0656 8.4565 0.0720 +v 0.1212 8.4514 0.0749 +v 0.1225 -3.4657 0.0732 +v 0.0656 -3.4712 0.0720 +v 0.2041 -3.4657 0.0732 +v 0.1291 -3.4666 0.1470 +v 0.1975 -3.4666 0.1470 +v 0.1292 8.4362 0.1464 +v 0.1975 8.4362 0.1464 +v 0.2055 8.4514 0.0749 +v -0.1298 8.4565 0.0720 +v -0.0742 8.4514 0.0749 +v -0.0729 -3.4657 0.0732 +v -0.1298 -3.4712 0.0720 +v 0.0087 -3.4657 0.0732 +v -0.0663 -3.4666 0.1470 +v 0.0021 -3.4666 0.1470 +v -0.0662 8.4362 0.1464 +v 0.0021 8.4362 0.1464 +v 0.0101 8.4514 0.0749 +v -0.5206 8.4565 0.0720 +v -0.4650 8.4514 0.0749 +v -0.4637 -3.4657 0.0732 +v -0.5206 -3.4712 0.0720 +v -0.3821 -3.4657 0.0732 +v -0.4571 -3.4666 0.1470 +v -0.3887 -3.4666 0.1470 +v -0.4570 8.4362 0.1464 +v -0.3887 8.4362 0.1464 +v -0.3807 8.4514 0.0749 +v -0.3252 8.4565 0.0720 +v -0.3252 -3.4712 0.0720 +v -0.9114 8.4565 0.0720 +v -0.8558 8.4514 0.0749 +v -0.8545 -3.4657 0.0732 +v -0.9114 -3.4712 0.0720 +v -0.7729 -3.4657 0.0732 +v -0.8479 -3.4666 0.1470 +v -0.7795 -3.4666 0.1470 +v -0.8478 8.4362 0.1464 +v -0.7795 8.4362 0.1464 +v -0.7715 8.4514 0.0749 +v -0.7160 8.4565 0.0720 +v -0.7160 -3.4712 0.0720 +v -0.2696 8.4514 0.0749 +v -0.2683 -3.4657 0.0732 +v -0.1867 -3.4657 0.0732 +v -0.2617 -3.4666 0.1470 +v -0.1933 -3.4666 0.1470 +v -0.2616 8.4362 0.1464 +v -0.1933 8.4362 0.1464 +v -0.1853 8.4514 0.0749 +v -1.3021 8.4565 0.0720 +v -1.2466 8.4514 0.0749 +v -1.2453 -3.4657 0.0732 +v -1.3026 -3.4712 0.0720 +v -1.1637 -3.4657 0.0732 +v -1.2387 -3.4666 0.1470 +v -1.1703 -3.4666 0.1470 +v -1.2386 8.4362 0.1464 +v -1.1703 8.4362 0.1464 +v -1.1623 8.4514 0.0749 +v -1.1068 8.4565 0.0720 +v -1.1068 -3.4712 0.0720 +v -1.0512 8.4514 0.0749 +v -1.0499 -3.4657 0.0732 +v -0.9683 -3.4657 0.0732 +v -1.0433 -3.4666 0.1470 +v -0.9749 -3.4666 0.1470 +v -1.0432 8.4362 0.1464 +v -0.9749 8.4362 0.1464 +v -0.9669 8.4514 0.0749 +v -0.6604 8.4514 0.0749 +v -0.6591 -3.4657 0.0732 +v -0.5775 -3.4657 0.0732 +v -0.6525 -3.4666 0.1470 +v -0.5841 -3.4666 0.1470 +v -0.6524 8.4362 0.1464 +v -0.5841 8.4362 0.1464 +v -0.5761 8.4514 0.0749 +# 244 vertices + +vn -0.5568 -0.5476 0.6245 +vn -0.4797 0.5094 0.7144 +vn 0.0001 -0.0001 1.0000 +vn -0.5474 -0.5880 0.5955 +vn 0.5567 -0.5478 0.6245 +vn 0.5474 -0.5880 0.5955 +vn 0.5540 0.5110 0.6573 +vn -0.5540 0.5110 0.6573 +vn -0.0492 -0.0002 0.9988 +vn 0.0000 -0.0000 1.0000 +vn 0.4796 0.5095 0.7144 +vn 0.5568 -0.5478 0.6245 +vn -0.5568 -0.5477 0.6245 +vn 0.0001 -0.0002 1.0000 +vn 0.0494 -0.0000 0.9988 +vn -0.0000 0.0001 -1.0000 +vn 0.4913 -0.4877 -0.7217 +vn 0.5701 0.5238 -0.6329 +vn -0.0001 0.0001 -1.0000 +vn -0.5700 0.5240 -0.6328 +vn 0.5481 0.5861 -0.5967 +vn -0.5481 0.5861 -0.5967 +vn 0.5506 -0.5118 -0.6595 +vn -0.5506 -0.5118 -0.6595 +vn -0.4912 -0.4878 -0.7217 +vn -0.0514 -0.0000 -0.9987 +vn -0.0212 0.0001 -0.9998 +vn -0.5701 0.5239 -0.6329 +vn 0.0513 0.0001 -0.9987 +vn 0.5701 0.5239 -0.6328 +vn 0.0210 -0.0000 -0.9998 +# 31 vertex normals + +vt 0.1028 0.0864 0.0000 +vt 0.1028 0.0864 0.0000 +vt 0.1038 0.0863 0.0000 +vt 0.1038 0.0864 0.0000 +vt 0.1058 0.0863 0.0000 +vt 0.1056 0.0884 0.0000 +vt 0.1040 0.0884 0.0000 +vt 0.1040 0.0884 0.0000 +vt 0.1056 0.0884 0.0000 +vt 0.1058 0.0864 0.0000 +vt 0.1068 0.0864 0.0000 +vt 0.1068 0.0864 0.0000 +vt 0.0987 0.0864 0.0000 +vt 0.0987 0.0864 0.0000 +vt 0.0998 0.0863 0.0000 +vt 0.0998 0.0864 0.0000 +vt 0.1017 0.0863 0.0000 +vt 0.1016 0.0884 0.0000 +vt 0.0999 0.0884 0.0000 +vt 0.0999 0.0884 0.0000 +vt 0.1016 0.0884 0.0000 +vt 0.1017 0.0864 0.0000 +vt 0.0946 0.0864 0.0000 +vt 0.0946 0.0864 0.0000 +vt 0.0957 0.0863 0.0000 +vt 0.0957 0.0864 0.0000 +vt 0.0976 0.0863 0.0000 +vt 0.0975 0.0884 0.0000 +vt 0.0958 0.0884 0.0000 +vt 0.0958 0.0884 0.0000 +vt 0.0975 0.0884 0.0000 +vt 0.0976 0.0864 0.0000 +vt 0.0906 0.0864 0.0000 +vt 0.0906 0.0864 0.0000 +vt 0.0917 0.0863 0.0000 +vt 0.0916 0.0864 0.0000 +vt 0.0936 0.0863 0.0000 +vt 0.0934 0.0884 0.0000 +vt 0.0918 0.0884 0.0000 +vt 0.0918 0.0884 0.0000 +vt 0.0934 0.0884 0.0000 +vt 0.0936 0.0864 0.0000 +vt 0.0865 0.0864 0.0000 +vt 0.0865 0.0864 0.0000 +vt 0.0876 0.0863 0.0000 +vt 0.0876 0.0864 0.0000 +vt 0.0895 0.0863 0.0000 +vt 0.0894 0.0884 0.0000 +vt 0.0877 0.0884 0.0000 +vt 0.0877 0.0884 0.0000 +vt 0.0894 0.0884 0.0000 +vt 0.0895 0.0864 0.0000 +vt 0.0825 0.0864 0.0000 +vt 0.0825 0.0864 0.0000 +vt 0.0835 0.0863 0.0000 +vt 0.0835 0.0864 0.0000 +vt 0.0855 0.0863 0.0000 +vt 0.0853 0.0884 0.0000 +vt 0.0837 0.0884 0.0000 +vt 0.0837 0.0884 0.0000 +vt 0.0853 0.0884 0.0000 +vt 0.0855 0.0864 0.0000 +vt 0.0743 0.0864 0.0000 +vt 0.0743 0.0864 0.0000 +vt 0.0754 0.0863 0.0000 +vt 0.0754 0.0864 0.0000 +vt 0.0773 0.0863 0.0000 +vt 0.0772 0.0884 0.0000 +vt 0.0756 0.0884 0.0000 +vt 0.0756 0.0884 0.0000 +vt 0.0772 0.0884 0.0000 +vt 0.0774 0.0864 0.0000 +vt 0.0784 0.0864 0.0000 +vt 0.0784 0.0864 0.0000 +vt 0.0662 0.0864 0.0000 +vt 0.0662 0.0864 0.0000 +vt 0.0673 0.0863 0.0000 +vt 0.0673 0.0864 0.0000 +vt 0.0692 0.0863 0.0000 +vt 0.0691 0.0884 0.0000 +vt 0.0674 0.0884 0.0000 +vt 0.0674 0.0884 0.0000 +vt 0.0691 0.0884 0.0000 +vt 0.0692 0.0864 0.0000 +vt 0.0703 0.0864 0.0000 +vt 0.0703 0.0864 0.0000 +vt 0.0795 0.0863 0.0000 +vt 0.0795 0.0864 0.0000 +vt 0.0814 0.0863 0.0000 +vt 0.0813 0.0884 0.0000 +vt 0.0796 0.0884 0.0000 +vt 0.0796 0.0884 0.0000 +vt 0.0813 0.0884 0.0000 +vt 0.0814 0.0864 0.0000 +vt 0.0581 0.0864 0.0000 +vt 0.0581 0.0864 0.0000 +vt 0.0592 0.0863 0.0000 +vt 0.0592 0.0864 0.0000 +vt 0.0611 0.0863 0.0000 +vt 0.0610 0.0884 0.0000 +vt 0.0593 0.0884 0.0000 +vt 0.0593 0.0884 0.0000 +vt 0.0610 0.0884 0.0000 +vt 0.0611 0.0864 0.0000 +vt 0.0622 0.0864 0.0000 +vt 0.0622 0.0864 0.0000 +vt 0.0632 0.0863 0.0000 +vt 0.0632 0.0864 0.0000 +vt 0.0652 0.0863 0.0000 +vt 0.0650 0.0884 0.0000 +vt 0.0634 0.0884 0.0000 +vt 0.0634 0.0884 0.0000 +vt 0.0650 0.0884 0.0000 +vt 0.0652 0.0864 0.0000 +vt 0.0714 0.0863 0.0000 +vt 0.0713 0.0864 0.0000 +vt 0.0733 0.0863 0.0000 +vt 0.0731 0.0884 0.0000 +vt 0.0715 0.0884 0.0000 +vt 0.0715 0.0884 0.0000 +vt 0.0731 0.0884 0.0000 +vt 0.0733 0.0864 0.0000 +vt 0.1039 0.0861 0.0000 +vt 0.1028 0.0861 0.0000 +vt 0.1028 0.0861 0.0000 +vt 0.1039 0.0862 0.0000 +vt 0.1041 0.0883 0.0000 +vt 0.1055 0.0883 0.0000 +vt 0.1056 0.0861 0.0000 +vt 0.1041 0.0882 0.0000 +vt 0.1055 0.0882 0.0000 +vt 0.1068 0.0861 0.0000 +vt 0.1057 0.0862 0.0000 +vt 0.1068 0.0861 0.0000 +vt 0.0999 0.0861 0.0000 +vt 0.0987 0.0861 0.0000 +vt 0.0987 0.0861 0.0000 +vt 0.0999 0.0862 0.0000 +vt 0.1000 0.0883 0.0000 +vt 0.1014 0.0883 0.0000 +vt 0.1016 0.0861 0.0000 +vt 0.1000 0.0882 0.0000 +vt 0.1014 0.0882 0.0000 +vt 0.1016 0.0862 0.0000 +vt 0.0958 0.0861 0.0000 +vt 0.0946 0.0861 0.0000 +vt 0.0946 0.0861 0.0000 +vt 0.0958 0.0862 0.0000 +vt 0.0960 0.0883 0.0000 +vt 0.0974 0.0883 0.0000 +vt 0.0975 0.0861 0.0000 +vt 0.0960 0.0882 0.0000 +vt 0.0974 0.0882 0.0000 +vt 0.0975 0.0862 0.0000 +vt 0.0918 0.0861 0.0000 +vt 0.0906 0.0861 0.0000 +vt 0.0906 0.0861 0.0000 +vt 0.0917 0.0862 0.0000 +vt 0.0919 0.0883 0.0000 +vt 0.0933 0.0883 0.0000 +vt 0.0935 0.0861 0.0000 +vt 0.0919 0.0882 0.0000 +vt 0.0933 0.0882 0.0000 +vt 0.0935 0.0862 0.0000 +vt 0.0877 0.0861 0.0000 +vt 0.0865 0.0861 0.0000 +vt 0.0865 0.0861 0.0000 +vt 0.0877 0.0862 0.0000 +vt 0.0878 0.0883 0.0000 +vt 0.0893 0.0883 0.0000 +vt 0.0894 0.0861 0.0000 +vt 0.0878 0.0882 0.0000 +vt 0.0893 0.0882 0.0000 +vt 0.0894 0.0862 0.0000 +vt 0.0836 0.0861 0.0000 +vt 0.0825 0.0861 0.0000 +vt 0.0825 0.0861 0.0000 +vt 0.0836 0.0862 0.0000 +vt 0.0838 0.0883 0.0000 +vt 0.0852 0.0883 0.0000 +vt 0.0853 0.0861 0.0000 +vt 0.0838 0.0882 0.0000 +vt 0.0852 0.0882 0.0000 +vt 0.0854 0.0862 0.0000 +vt 0.0755 0.0861 0.0000 +vt 0.0743 0.0861 0.0000 +vt 0.0743 0.0861 0.0000 +vt 0.0755 0.0862 0.0000 +vt 0.0757 0.0883 0.0000 +vt 0.0771 0.0883 0.0000 +vt 0.0772 0.0861 0.0000 +vt 0.0757 0.0882 0.0000 +vt 0.0771 0.0882 0.0000 +vt 0.0784 0.0861 0.0000 +vt 0.0773 0.0862 0.0000 +vt 0.0784 0.0861 0.0000 +vt 0.0674 0.0861 0.0000 +vt 0.0662 0.0861 0.0000 +vt 0.0662 0.0861 0.0000 +vt 0.0674 0.0862 0.0000 +vt 0.0675 0.0883 0.0000 +vt 0.0690 0.0883 0.0000 +vt 0.0691 0.0861 0.0000 +vt 0.0676 0.0882 0.0000 +vt 0.0690 0.0882 0.0000 +vt 0.0703 0.0861 0.0000 +vt 0.0691 0.0862 0.0000 +vt 0.0703 0.0861 0.0000 +vt 0.0796 0.0861 0.0000 +vt 0.0796 0.0862 0.0000 +vt 0.0797 0.0883 0.0000 +vt 0.0811 0.0883 0.0000 +vt 0.0813 0.0861 0.0000 +vt 0.0797 0.0882 0.0000 +vt 0.0811 0.0882 0.0000 +vt 0.0813 0.0862 0.0000 +vt 0.0593 0.0861 0.0000 +vt 0.0581 0.0861 0.0000 +vt 0.0581 0.0861 0.0000 +vt 0.0593 0.0862 0.0000 +vt 0.0594 0.0883 0.0000 +vt 0.0609 0.0883 0.0000 +vt 0.0610 0.0861 0.0000 +vt 0.0594 0.0882 0.0000 +vt 0.0609 0.0882 0.0000 +vt 0.0622 0.0861 0.0000 +vt 0.0610 0.0862 0.0000 +vt 0.0622 0.0861 0.0000 +vt 0.0634 0.0861 0.0000 +vt 0.0633 0.0862 0.0000 +vt 0.0635 0.0883 0.0000 +vt 0.0649 0.0883 0.0000 +vt 0.0650 0.0861 0.0000 +vt 0.0635 0.0882 0.0000 +vt 0.0649 0.0882 0.0000 +vt 0.0651 0.0862 0.0000 +vt 0.0715 0.0861 0.0000 +vt 0.0714 0.0862 0.0000 +vt 0.0716 0.0883 0.0000 +vt 0.0730 0.0883 0.0000 +vt 0.0732 0.0861 0.0000 +vt 0.0716 0.0882 0.0000 +vt 0.0730 0.0882 0.0000 +vt 0.0732 0.0862 0.0000 +# 244 texture coords + +# g Floor +# usemtl ShippingContainer +# s 1 +# f 3342/3348/101 3343/3349/102 3344/3346/103 3345/3347/103 +# f 3346/3352/104 3342/3348/101 3347/3350/105 3348/3351/106 +# f 3348/3351/106 3349/3354/107 3350/3353/108 3346/3352/104 +# f 3351/3356/109 3352/3357/110 3353/3355/111 3347/3350/105 +# f 3349/3354/107 3353/3355/111 3343/3349/102 3350/3353/108 +# f 3350/3353/108 3343/3349/102 3342/3348/101 3346/3352/104 +# f 3349/3354/107 3348/3351/106 3347/3350/105 3353/3355/111 +# f 3354/3360/101 3355/3361/102 3356/3358/103 3357/3359/103 +# f 3358/3364/104 3354/3360/101 3359/3362/112 3360/3363/106 +# f 3360/3363/106 3361/3366/107 3362/3365/108 3358/3364/104 +# f 3345/3347/103 3344/3346/103 3363/3367/111 3359/3362/112 +# f 3361/3366/107 3363/3367/111 3355/3361/102 3362/3365/108 +# f 3362/3365/108 3355/3361/102 3354/3360/101 3358/3364/104 +# f 3361/3366/107 3360/3363/106 3359/3362/112 3363/3367/111 +# f 3364/3370/101 3365/3371/102 3366/3368/103 3367/3369/103 +# f 3368/3374/104 3364/3370/101 3369/3372/112 3370/3373/106 +# f 3370/3373/106 3371/3376/107 3372/3375/108 3368/3374/104 +# f 3357/3359/103 3356/3358/103 3373/3377/111 3369/3372/112 +# f 3371/3376/107 3373/3377/111 3365/3371/102 3372/3375/108 +# f 3372/3375/108 3365/3371/102 3364/3370/101 3368/3374/104 +# f 3371/3376/107 3370/3373/106 3369/3372/112 3373/3377/111 +# f 3374/3380/101 3375/3381/102 3376/3378/103 3377/3379/103 +# f 3378/3384/104 3374/3380/101 3379/3382/112 3380/3383/106 +# f 3380/3383/106 3381/3386/107 3382/3385/108 3378/3384/104 +# f 3367/3369/103 3366/3368/103 3383/3387/111 3379/3382/112 +# f 3381/3386/107 3383/3387/111 3375/3381/102 3382/3385/108 +# f 3382/3385/108 3375/3381/102 3374/3380/101 3378/3384/104 +# f 3381/3386/107 3380/3383/106 3379/3382/112 3383/3387/111 +# f 3384/3390/101 3385/3391/102 3386/3388/103 3387/3389/103 +# f 3388/3394/104 3384/3390/101 3389/3392/112 3390/3393/106 +# f 3390/3393/106 3391/3396/107 3392/3395/108 3388/3394/104 +# f 3377/3379/103 3376/3378/103 3393/3397/111 3389/3392/112 +# f 3391/3396/107 3393/3397/111 3385/3391/102 3392/3395/108 +# f 3392/3395/108 3385/3391/102 3384/3390/101 3388/3394/104 +# f 3391/3396/107 3390/3393/106 3389/3392/112 3393/3397/111 +# f 3394/3400/101 3395/3401/102 3396/3398/103 3397/3399/103 +# f 3398/3404/104 3394/3400/101 3399/3402/112 3400/3403/106 +# f 3400/3403/106 3401/3406/107 3402/3405/108 3398/3404/104 +# f 3387/3389/103 3386/3388/103 3403/3407/111 3399/3402/112 +# f 3401/3406/107 3403/3407/111 3395/3401/102 3402/3405/108 +# f 3402/3405/108 3395/3401/102 3394/3400/101 3398/3404/104 +# f 3401/3406/107 3400/3403/106 3399/3402/112 3403/3407/111 +# f 3404/3410/101 3405/3411/102 3406/3408/103 3407/3409/103 +# f 3408/3414/104 3404/3410/101 3409/3412/112 3410/3413/106 +# f 3410/3413/106 3411/3416/107 3412/3415/108 3408/3414/104 +# f 3413/3418/103 3414/3419/103 3415/3417/111 3409/3412/112 +# f 3411/3416/107 3415/3417/111 3405/3411/102 3412/3415/108 +# f 3412/3415/108 3405/3411/102 3404/3410/101 3408/3414/104 +# f 3411/3416/107 3410/3413/106 3409/3412/112 3415/3417/111 +# f 3416/3422/101 3417/3423/102 3418/3420/103 3419/3421/103 +# f 3420/3426/104 3416/3422/101 3421/3424/112 3422/3425/106 +# f 3422/3425/106 3423/3428/107 3424/3427/108 3420/3426/104 +# f 3425/3430/103 3426/3431/103 3427/3429/111 3421/3424/112 +# f 3423/3428/107 3427/3429/111 3417/3423/102 3424/3427/108 +# f 3424/3427/108 3417/3423/102 3416/3422/101 3420/3426/104 +# f 3423/3428/107 3422/3425/106 3421/3424/112 3427/3429/111 +# f 3428/3432/101 3429/3433/102 3414/3419/103 3413/3418/103 +# f 3430/3436/104 3428/3432/101 3431/3434/112 3432/3435/106 +# f 3432/3435/106 3433/3438/107 3434/3437/108 3430/3436/104 +# f 3397/3399/103 3396/3398/103 3435/3439/111 3431/3434/112 +# f 3433/3438/107 3435/3439/111 3429/3433/102 3434/3437/108 +# f 3434/3437/108 3429/3433/102 3428/3432/101 3430/3436/104 +# f 3433/3438/107 3432/3435/106 3431/3434/112 3435/3439/111 +# f 3436/3442/113 3437/3443/102 3438/3440/114 3439/3441/115 +# f 3440/3446/104 3436/3442/113 3441/3444/112 3442/3445/106 +# f 3442/3445/106 3443/3448/107 3444/3447/108 3440/3446/104 +# f 3445/3450/103 3446/3451/103 3447/3449/111 3441/3444/112 +# f 3443/3448/107 3447/3449/111 3437/3443/102 3444/3447/108 +# f 3444/3447/108 3437/3443/102 3436/3442/113 3440/3446/104 +# f 3443/3448/107 3442/3445/106 3441/3444/112 3447/3449/111 +# f 3448/3452/101 3449/3453/102 3446/3451/103 3445/3450/103 +# f 3450/3456/104 3448/3452/101 3451/3454/112 3452/3455/106 +# f 3452/3455/106 3453/3458/107 3454/3457/108 3450/3456/104 +# f 3419/3421/103 3418/3420/103 3455/3459/111 3451/3454/112 +# f 3453/3458/107 3455/3459/111 3449/3453/102 3454/3457/108 +# f 3454/3457/108 3449/3453/102 3448/3452/101 3450/3456/104 +# f 3453/3458/107 3452/3455/106 3451/3454/112 3455/3459/111 +# f 3456/3460/101 3457/3461/102 3426/3431/103 3425/3430/103 +# f 3458/3464/104 3456/3460/101 3459/3462/112 3460/3463/106 +# f 3460/3463/106 3461/3466/107 3462/3465/108 3458/3464/104 +# f 3407/3409/103 3406/3408/103 3463/3467/111 3459/3462/112 +# f 3461/3466/107 3463/3467/111 3457/3461/102 3462/3465/108 +# f 3462/3465/108 3457/3461/102 3456/3460/101 3458/3464/104 +# f 3461/3466/107 3460/3463/106 3459/3462/112 3463/3467/111 +# f 3464/3470/116 3465/3471/117 3466/3468/118 3467/3469/119 +# f 3468/3474/120 3466/3468/118 3469/3472/121 3470/3473/122 +# f 3471/3475/123 3472/3476/124 3470/3473/122 3469/3472/121 +# f 3473/3478/125 3474/3479/126 3475/3477/127 3468/3474/120 +# f 3465/3471/117 3473/3478/125 3472/3476/124 3471/3475/123 +# f 3466/3468/118 3465/3471/117 3471/3475/123 3469/3472/121 +# f 3468/3474/120 3470/3473/122 3472/3476/124 3473/3478/125 +# f 3476/3482/116 3477/3483/117 3478/3480/118 3479/3481/119 +# f 3480/3486/128 3478/3480/118 3481/3484/121 3482/3485/122 +# f 3483/3487/123 3484/3488/124 3482/3485/122 3481/3484/121 +# f 3485/3489/125 3464/3470/116 3467/3469/119 3480/3486/128 +# f 3477/3483/117 3485/3489/125 3484/3488/124 3483/3487/123 +# f 3478/3480/118 3477/3483/117 3483/3487/123 3481/3484/121 +# f 3480/3486/128 3482/3485/122 3484/3488/124 3485/3489/125 +# f 3486/3492/116 3487/3493/117 3488/3490/118 3489/3491/119 +# f 3490/3496/128 3488/3490/118 3491/3494/121 3492/3495/122 +# f 3493/3497/123 3494/3498/124 3492/3495/122 3491/3494/121 +# f 3495/3499/125 3476/3482/116 3479/3481/119 3490/3496/128 +# f 3487/3493/117 3495/3499/125 3494/3498/124 3493/3497/123 +# f 3488/3490/118 3487/3493/117 3493/3497/123 3491/3494/121 +# f 3490/3496/128 3492/3495/122 3494/3498/124 3495/3499/125 +# f 3496/3502/116 3497/3503/117 3498/3500/118 3499/3501/119 +# f 3500/3506/128 3498/3500/118 3501/3504/121 3502/3505/122 +# f 3503/3507/123 3504/3508/124 3502/3505/122 3501/3504/121 +# f 3505/3509/125 3486/3492/116 3489/3491/119 3500/3506/128 +# f 3497/3503/117 3505/3509/125 3504/3508/124 3503/3507/123 +# f 3498/3500/118 3497/3503/117 3503/3507/123 3501/3504/121 +# f 3500/3506/128 3502/3505/122 3504/3508/124 3505/3509/125 +# f 3506/3512/116 3507/3513/117 3508/3510/118 3509/3511/119 +# f 3510/3516/128 3508/3510/118 3511/3514/121 3512/3515/122 +# f 3513/3517/123 3514/3518/124 3512/3515/122 3511/3514/121 +# f 3515/3519/125 3496/3502/116 3499/3501/119 3510/3516/128 +# f 3507/3513/117 3515/3519/125 3514/3518/124 3513/3517/123 +# f 3508/3510/118 3507/3513/117 3513/3517/123 3511/3514/121 +# f 3510/3516/128 3512/3515/122 3514/3518/124 3515/3519/125 +# f 3516/3522/116 3517/3523/117 3518/3520/118 3519/3521/119 +# f 3520/3526/128 3518/3520/118 3521/3524/121 3522/3525/122 +# f 3523/3527/123 3524/3528/124 3522/3525/122 3521/3524/121 +# f 3525/3529/125 3506/3512/116 3509/3511/119 3520/3526/128 +# f 3517/3523/117 3525/3529/125 3524/3528/124 3523/3527/123 +# f 3518/3520/118 3517/3523/117 3523/3527/123 3521/3524/121 +# f 3520/3526/128 3522/3525/122 3524/3528/124 3525/3529/125 +# f 3526/3532/116 3527/3533/117 3528/3530/118 3529/3531/119 +# f 3530/3536/128 3528/3530/118 3531/3534/121 3532/3535/122 +# f 3533/3537/123 3534/3538/124 3532/3535/122 3531/3534/121 +# f 3535/3540/125 3536/3541/116 3537/3539/119 3530/3536/128 +# f 3527/3533/117 3535/3540/125 3534/3538/124 3533/3537/123 +# f 3528/3530/118 3527/3533/117 3533/3537/123 3531/3534/121 +# f 3530/3536/128 3532/3535/122 3534/3538/124 3535/3540/125 +# f 3538/3544/116 3539/3545/117 3540/3542/118 3541/3543/119 +# f 3542/3548/128 3540/3542/118 3543/3546/121 3544/3547/122 +# f 3545/3549/123 3546/3550/124 3544/3547/122 3543/3546/121 +# f 3547/3552/125 3548/3553/116 3549/3551/119 3542/3548/128 +# f 3539/3545/117 3547/3552/125 3546/3550/124 3545/3549/123 +# f 3540/3542/118 3539/3545/117 3545/3549/123 3543/3546/121 +# f 3542/3548/128 3544/3547/122 3546/3550/124 3547/3552/125 +# f 3536/3541/116 3550/3555/117 3551/3554/118 3537/3539/119 +# f 3552/3558/128 3551/3554/118 3553/3556/121 3554/3557/122 +# f 3555/3559/123 3556/3560/124 3554/3557/122 3553/3556/121 +# f 3557/3561/125 3516/3522/116 3519/3521/119 3552/3558/128 +# f 3550/3555/117 3557/3561/125 3556/3560/124 3555/3559/123 +# f 3551/3554/118 3550/3555/117 3555/3559/123 3553/3556/121 +# f 3552/3558/128 3554/3557/122 3556/3560/124 3557/3561/125 +# f 3558/3564/129 3559/3565/117 3560/3562/130 3561/3563/131 +# f 3562/3568/128 3560/3562/130 3563/3566/121 3564/3567/122 +# f 3565/3569/123 3566/3570/124 3564/3567/122 3563/3566/121 +# f 3567/3572/125 3568/3573/116 3569/3571/119 3562/3568/128 +# f 3559/3565/117 3567/3572/125 3566/3570/124 3565/3569/123 +# f 3560/3562/130 3559/3565/117 3565/3569/123 3563/3566/121 +# f 3562/3568/128 3564/3567/122 3566/3570/124 3567/3572/125 +# f 3568/3573/116 3570/3575/117 3571/3574/118 3569/3571/119 +# f 3572/3578/128 3571/3574/118 3573/3576/121 3574/3577/122 +# f 3575/3579/123 3576/3580/124 3574/3577/122 3573/3576/121 +# f 3577/3581/125 3538/3544/116 3541/3543/119 3572/3578/128 +# f 3570/3575/117 3577/3581/125 3576/3580/124 3575/3579/123 +# f 3571/3574/118 3570/3575/117 3575/3579/123 3573/3576/121 +# f 3572/3578/128 3574/3577/122 3576/3580/124 3577/3581/125 +# f 3548/3553/116 3578/3583/117 3579/3582/118 3549/3551/119 +# f 3580/3586/128 3579/3582/118 3581/3584/121 3582/3585/122 +# f 3583/3587/123 3584/3588/124 3582/3585/122 3581/3584/121 +# f 3585/3589/125 3526/3532/116 3529/3531/119 3580/3586/128 +# f 3578/3583/117 3585/3589/125 3584/3588/124 3583/3587/123 +# f 3579/3582/118 3578/3583/117 3583/3587/123 3581/3584/121 +# f 3580/3586/128 3582/3585/122 3584/3588/124 3585/3589/125 +# 168 polygons + +# +# object Conveyor +# + +v 0.9697 -2.4738 0.4403 +v 0.9697 -3.3630 0.4391 +v 0.8896 -3.3630 0.4391 +v 0.8896 -2.4738 0.4403 +v 0.5609 -2.4745 0.3119 +v 0.5609 -3.3630 0.3223 +v 0.8635 -3.3630 0.3223 +v 0.8635 -2.4738 0.3235 +v 0.8635 -2.4738 0.4687 +v 0.8635 -3.3630 0.4675 +v 0.9697 -3.3630 0.4675 +v 0.9697 -2.4738 0.4687 +v 0.8896 -2.4738 0.1823 +v 0.8896 -3.3630 0.1812 +v 0.9697 -3.3630 0.1812 +v 0.9697 -2.4738 0.1823 +v 0.9697 -2.4738 0.1549 +v 0.9697 -3.3630 0.1538 +v 0.8635 -3.3630 0.1538 +v 0.8635 -2.4738 0.1549 +v 0.8635 -2.4738 0.2979 +v 0.8635 -3.3630 0.2968 +v 0.5609 -3.3630 0.2968 +v 0.8896 -3.0560 0.2141 +v 0.8635 -3.0560 0.2141 +v 0.8635 -3.0679 0.2416 +v 0.8896 -3.0679 0.2416 +v 0.8635 -3.0560 0.2690 +v 0.8896 -3.0560 0.2690 +v 0.8896 -2.8771 0.2779 +v 0.8635 -2.8771 0.2779 +v 0.8635 -2.8425 0.2690 +v 0.8896 -2.8425 0.2690 +v 0.8896 -3.0214 0.2052 +v 0.8635 -3.0214 0.2052 +v 0.8896 -2.8306 0.2416 +v 0.8635 -2.8306 0.2416 +v 0.8635 -2.8425 0.2141 +v 0.8896 -2.8425 0.2141 +v 0.8896 -2.8771 0.2052 +v 0.8635 -2.8771 0.2052 +v 0.8635 -3.0214 0.2779 +v 0.8896 -3.0214 0.2779 +v 0.1521 -2.4738 0.4403 +v 0.2322 -2.4738 0.4403 +v 0.2322 -3.3630 0.4391 +v 0.1521 -3.3630 0.4391 +v 0.2583 -2.4738 0.3235 +v 0.2583 -3.3630 0.3223 +v 0.2583 -2.4738 0.4687 +v 0.1521 -2.4738 0.4687 +v 0.1521 -3.3630 0.4675 +v 0.2583 -3.3630 0.4675 +v 0.2322 -2.4738 0.1823 +v 0.1521 -2.4738 0.1823 +v 0.1521 -3.3630 0.1812 +v 0.2322 -3.3630 0.1812 +v 0.1521 -2.4738 0.1549 +v 0.2583 -2.4738 0.1549 +v 0.2583 -3.3630 0.1538 +v 0.1521 -3.3630 0.1538 +v 0.2583 -2.4738 0.2979 +v 0.2583 -3.3630 0.2968 +v 0.2322 -3.0560 0.2141 +v 0.2322 -3.0679 0.2416 +v 0.2583 -3.0679 0.2416 +v 0.2583 -3.0560 0.2141 +v 0.2322 -3.0560 0.2690 +v 0.2583 -3.0560 0.2690 +v 0.2322 -2.8771 0.2779 +v 0.2322 -2.8425 0.2690 +v 0.2583 -2.8425 0.2690 +v 0.2583 -2.8771 0.2779 +v 0.2322 -3.0214 0.2052 +v 0.2583 -3.0214 0.2052 +v 0.2322 -2.8306 0.2416 +v 0.2322 -2.8425 0.2141 +v 0.2583 -2.8425 0.2141 +v 0.2583 -2.8306 0.2416 +v 0.2322 -2.8771 0.2052 +v 0.2583 -2.8771 0.2052 +v 0.2322 -3.0214 0.2779 +v 0.2583 -3.0214 0.2779 +v 0.9697 -1.5838 0.4403 +v 0.8896 -1.5838 0.4403 +v 0.5609 -1.5845 0.3119 +v 0.5609 -2.4730 0.3223 +v 0.8635 -1.5838 0.3235 +v 0.8635 -1.5838 0.4687 +v 0.9697 -1.5838 0.4687 +v 0.8896 -1.5838 0.1823 +v 0.9697 -1.5838 0.1823 +v 0.9697 -1.5838 0.1549 +v 0.8635 -1.5838 0.1549 +v 0.8635 -1.5838 0.2979 +v 0.5609 -2.4730 0.2968 +v 0.8896 -2.1660 0.2141 +v 0.8635 -2.1660 0.2141 +v 0.8635 -2.1779 0.2416 +v 0.8896 -2.1779 0.2416 +v 0.8635 -2.1660 0.2690 +v 0.8896 -2.1660 0.2690 +v 0.8896 -1.9871 0.2779 +v 0.8635 -1.9871 0.2779 +v 0.8635 -1.9525 0.2690 +v 0.8896 -1.9525 0.2690 +v 0.8896 -2.1314 0.2052 +v 0.8635 -2.1314 0.2052 +v 0.8896 -1.9406 0.2416 +v 0.8635 -1.9406 0.2416 +v 0.8635 -1.9525 0.2141 +v 0.8896 -1.9525 0.2141 +v 0.8896 -1.9871 0.2052 +v 0.8635 -1.9871 0.2052 +v 0.8635 -2.1314 0.2779 +v 0.8896 -2.1314 0.2779 +v 0.1521 -1.5838 0.4403 +v 0.2322 -1.5838 0.4403 +v 0.2583 -1.5838 0.3235 +v 0.2583 -1.5838 0.4687 +v 0.1521 -1.5838 0.4687 +v 0.2322 -1.5838 0.1823 +v 0.1521 -1.5838 0.1823 +v 0.1521 -1.5838 0.1549 +v 0.2583 -1.5838 0.1549 +v 0.2583 -1.5838 0.2979 +v 0.2322 -2.1660 0.2141 +v 0.2322 -2.1779 0.2416 +v 0.2583 -2.1779 0.2416 +v 0.2583 -2.1660 0.2141 +v 0.2322 -2.1660 0.2690 +v 0.2583 -2.1660 0.2690 +v 0.2322 -1.9871 0.2779 +v 0.2322 -1.9525 0.2690 +v 0.2583 -1.9525 0.2690 +v 0.2583 -1.9871 0.2779 +v 0.2322 -2.1314 0.2052 +v 0.2583 -2.1314 0.2052 +v 0.2322 -1.9406 0.2416 +v 0.2322 -1.9525 0.2141 +v 0.2583 -1.9525 0.2141 +v 0.2583 -1.9406 0.2416 +v 0.2322 -1.9871 0.2052 +v 0.2583 -1.9871 0.2052 +v 0.2322 -2.1314 0.2779 +v 0.2583 -2.1314 0.2779 +v 0.9697 -0.6938 0.4403 +v 0.8896 -0.6938 0.4403 +v 0.5609 -0.6945 0.3119 +v 0.5609 -1.5830 0.3223 +v 0.8635 -0.6938 0.3235 +v 0.8635 -0.6938 0.4687 +v 0.9697 -0.6938 0.4687 +v 0.8896 -0.6938 0.1823 +v 0.9697 -0.6938 0.1823 +v 0.9697 -0.6938 0.1549 +v 0.8635 -0.6938 0.1549 +v 0.8635 -0.6938 0.2979 +v 0.5609 -1.5830 0.2968 +v 0.8896 -1.2760 0.2141 +v 0.8635 -1.2760 0.2141 +v 0.8635 -1.2879 0.2416 +v 0.8896 -1.2879 0.2416 +v 0.8635 -1.2760 0.2690 +v 0.8896 -1.2760 0.2690 +v 0.8896 -1.0971 0.2779 +v 0.8635 -1.0971 0.2779 +v 0.8635 -1.0625 0.2690 +v 0.8896 -1.0625 0.2690 +v 0.8896 -1.2414 0.2052 +v 0.8635 -1.2414 0.2052 +v 0.8896 -1.0506 0.2416 +v 0.8635 -1.0506 0.2416 +v 0.8635 -1.0625 0.2141 +v 0.8896 -1.0625 0.2141 +v 0.8896 -1.0971 0.2052 +v 0.8635 -1.0971 0.2052 +v 0.8635 -1.2414 0.2779 +v 0.8896 -1.2414 0.2779 +v 0.1521 -0.6938 0.4403 +v 0.2322 -0.6938 0.4403 +v 0.2583 -0.6938 0.3235 +v 0.2583 -0.6938 0.4687 +v 0.1521 -0.6938 0.4687 +v 0.2322 -0.6938 0.1823 +v 0.1521 -0.6938 0.1823 +v 0.1521 -0.6938 0.1549 +v 0.2583 -0.6938 0.1549 +v 0.2583 -0.6938 0.2979 +v 0.2322 -1.2760 0.2141 +v 0.2322 -1.2879 0.2416 +v 0.2583 -1.2879 0.2416 +v 0.2583 -1.2760 0.2141 +v 0.2322 -1.2760 0.2690 +v 0.2583 -1.2760 0.2690 +v 0.2322 -1.0971 0.2779 +v 0.2322 -1.0625 0.2690 +v 0.2583 -1.0625 0.2690 +v 0.2583 -1.0971 0.2779 +v 0.2322 -1.2414 0.2052 +v 0.2583 -1.2414 0.2052 +v 0.2322 -1.0506 0.2416 +v 0.2322 -1.0625 0.2141 +v 0.2583 -1.0625 0.2141 +v 0.2583 -1.0506 0.2416 +v 0.2322 -1.0971 0.2052 +v 0.2583 -1.0971 0.2052 +v 0.2322 -1.2414 0.2779 +v 0.2583 -1.2414 0.2779 +v 0.9697 0.1962 0.4403 +v 0.8896 0.1962 0.4403 +v 0.5609 0.1955 0.3119 +v 0.5609 -0.6930 0.3223 +v 0.8635 0.1962 0.3235 +v 0.8635 0.1962 0.4687 +v 0.9697 0.1962 0.4687 +v 0.8896 0.1962 0.1823 +v 0.9697 0.1962 0.1823 +v 0.9697 0.1962 0.1549 +v 0.8635 0.1962 0.1549 +v 0.8635 0.1962 0.2979 +v 0.5609 -0.6930 0.2968 +v 0.8896 -0.3860 0.2141 +v 0.8635 -0.3860 0.2141 +v 0.8635 -0.3979 0.2416 +v 0.8896 -0.3979 0.2416 +v 0.8635 -0.3860 0.2690 +v 0.8896 -0.3860 0.2690 +v 0.8896 -0.2071 0.2779 +v 0.8635 -0.2071 0.2779 +v 0.8635 -0.1725 0.2690 +v 0.8896 -0.1725 0.2690 +v 0.8896 -0.3514 0.2052 +v 0.8635 -0.3514 0.2052 +v 0.8896 -0.1606 0.2416 +v 0.8635 -0.1606 0.2416 +v 0.8635 -0.1725 0.2141 +v 0.8896 -0.1725 0.2141 +v 0.8896 -0.2071 0.2052 +v 0.8635 -0.2071 0.2052 +v 0.8635 -0.3514 0.2779 +v 0.8896 -0.3514 0.2779 +v 0.1521 0.1962 0.4403 +v 0.2322 0.1962 0.4403 +v 0.2583 0.1962 0.3235 +v 0.2583 0.1962 0.4687 +v 0.1521 0.1962 0.4687 +v 0.2322 0.1962 0.1823 +v 0.1521 0.1962 0.1823 +v 0.1521 0.1962 0.1549 +v 0.2583 0.1962 0.1549 +v 0.2583 0.1962 0.2979 +v 0.2322 -0.3860 0.2141 +v 0.2322 -0.3979 0.2416 +v 0.2583 -0.3979 0.2416 +v 0.2583 -0.3860 0.2141 +v 0.2322 -0.3860 0.2690 +v 0.2583 -0.3860 0.2690 +v 0.2322 -0.2071 0.2779 +v 0.2322 -0.1725 0.2690 +v 0.2583 -0.1725 0.2690 +v 0.2583 -0.2071 0.2779 +v 0.2322 -0.3514 0.2052 +v 0.2583 -0.3514 0.2052 +v 0.2322 -0.1606 0.2416 +v 0.2322 -0.1725 0.2141 +v 0.2583 -0.1725 0.2141 +v 0.2583 -0.1606 0.2416 +v 0.2322 -0.2071 0.2052 +v 0.2583 -0.2071 0.2052 +v 0.2322 -0.3514 0.2779 +v 0.2583 -0.3514 0.2779 +v 0.9697 1.0862 0.4403 +v 0.8896 1.0862 0.4403 +v 0.5609 1.0855 0.3119 +v 0.5609 0.1970 0.3223 +v 0.8635 1.0862 0.3235 +v 0.8635 1.0862 0.4687 +v 0.9697 1.0862 0.4687 +v 0.8896 1.0862 0.1823 +v 0.9697 1.0862 0.1823 +v 0.9697 1.0862 0.1549 +v 0.8635 1.0862 0.1549 +v 0.8635 1.0862 0.2979 +v 0.5609 0.1970 0.2968 +v 0.8896 0.5040 0.2141 +v 0.8635 0.5040 0.2141 +v 0.8635 0.4921 0.2416 +v 0.8896 0.4921 0.2416 +v 0.8635 0.5040 0.2690 +v 0.8896 0.5040 0.2690 +v 0.8896 0.6829 0.2779 +v 0.8635 0.6829 0.2779 +v 0.8635 0.7175 0.2690 +v 0.8896 0.7175 0.2690 +v 0.8896 0.5386 0.2052 +v 0.8635 0.5386 0.2052 +v 0.8896 0.7294 0.2416 +v 0.8635 0.7294 0.2416 +v 0.8635 0.7175 0.2141 +v 0.8896 0.7175 0.2141 +v 0.8896 0.6829 0.2052 +v 0.8635 0.6829 0.2052 +v 0.8635 0.5386 0.2779 +v 0.8896 0.5386 0.2779 +v 0.1521 1.0862 0.4403 +v 0.2322 1.0862 0.4403 +v 0.2583 1.0862 0.3235 +v 0.2583 1.0862 0.4687 +v 0.1521 1.0862 0.4687 +v 0.2322 1.0862 0.1823 +v 0.1521 1.0862 0.1823 +v 0.1521 1.0862 0.1549 +v 0.2583 1.0862 0.1549 +v 0.2583 1.0862 0.2979 +v 0.2322 0.5040 0.2141 +v 0.2322 0.4921 0.2416 +v 0.2583 0.4921 0.2416 +v 0.2583 0.5040 0.2141 +v 0.2322 0.5040 0.2690 +v 0.2583 0.5040 0.2690 +v 0.2322 0.6829 0.2779 +v 0.2322 0.7175 0.2690 +v 0.2583 0.7175 0.2690 +v 0.2583 0.6829 0.2779 +v 0.2322 0.5386 0.2052 +v 0.2583 0.5386 0.2052 +v 0.2322 0.7294 0.2416 +v 0.2322 0.7175 0.2141 +v 0.2583 0.7175 0.2141 +v 0.2583 0.7294 0.2416 +v 0.2322 0.6829 0.2052 +v 0.2583 0.6829 0.2052 +v 0.2322 0.5386 0.2779 +v 0.2583 0.5386 0.2779 +v 0.9697 1.9762 0.4403 +v 0.8896 1.9762 0.4403 +v 0.5609 1.9755 0.3119 +v 0.5609 1.0870 0.3223 +v 0.8635 1.9762 0.3235 +v 0.8635 1.9762 0.4687 +v 0.9697 1.9762 0.4687 +v 0.8896 1.9762 0.1823 +v 0.9697 1.9762 0.1823 +v 0.9697 1.9762 0.1549 +v 0.8635 1.9762 0.1549 +v 0.8635 1.9762 0.2979 +v 0.5609 1.0870 0.2968 +v 0.8896 1.3940 0.2141 +v 0.8635 1.3940 0.2141 +v 0.8635 1.3821 0.2416 +v 0.8896 1.3821 0.2416 +v 0.8635 1.3940 0.2690 +v 0.8896 1.3940 0.2690 +v 0.8896 1.5729 0.2779 +v 0.8635 1.5729 0.2779 +v 0.8635 1.6075 0.2690 +v 0.8896 1.6075 0.2690 +v 0.8896 1.4286 0.2052 +v 0.8635 1.4286 0.2052 +v 0.8896 1.6194 0.2416 +v 0.8635 1.6194 0.2416 +v 0.8635 1.6075 0.2141 +v 0.8896 1.6075 0.2141 +v 0.8896 1.5729 0.2052 +v 0.8635 1.5729 0.2052 +v 0.8635 1.4286 0.2779 +v 0.8896 1.4286 0.2779 +v 0.1521 1.9762 0.4403 +v 0.2322 1.9762 0.4403 +v 0.2583 1.9762 0.3235 +v 0.2583 1.9762 0.4687 +v 0.1521 1.9762 0.4687 +v 0.2322 1.9762 0.1823 +v 0.1521 1.9762 0.1823 +v 0.1521 1.9762 0.1549 +v 0.2583 1.9762 0.1549 +v 0.2583 1.9762 0.2979 +v 0.2322 1.3940 0.2141 +v 0.2322 1.3821 0.2416 +v 0.2583 1.3821 0.2416 +v 0.2583 1.3940 0.2141 +v 0.2322 1.3940 0.2690 +v 0.2583 1.3940 0.2690 +v 0.2322 1.5729 0.2779 +v 0.2322 1.6075 0.2690 +v 0.2583 1.6075 0.2690 +v 0.2583 1.5729 0.2779 +v 0.2322 1.4286 0.2052 +v 0.2583 1.4286 0.2052 +v 0.2322 1.6194 0.2416 +v 0.2322 1.6075 0.2141 +v 0.2583 1.6075 0.2141 +v 0.2583 1.6194 0.2416 +v 0.2322 1.5729 0.2052 +v 0.2583 1.5729 0.2052 +v 0.2322 1.4286 0.2779 +v 0.2583 1.4286 0.2779 +v 0.9697 2.8662 0.4403 +v 0.8896 2.8662 0.4403 +v 0.5609 2.8655 0.3119 +v 0.5609 1.9770 0.3223 +v 0.8635 2.8662 0.3235 +v 0.8635 2.8662 0.4687 +v 0.9697 2.8662 0.4687 +v 0.8896 2.8662 0.1823 +v 0.9697 2.8662 0.1823 +v 0.9697 2.8662 0.1549 +v 0.8635 2.8662 0.1549 +v 0.8635 2.8662 0.2979 +v 0.5609 1.9770 0.2968 +v 0.8896 2.2840 0.2141 +v 0.8635 2.2840 0.2141 +v 0.8635 2.2721 0.2416 +v 0.8896 2.2721 0.2416 +v 0.8635 2.2840 0.2690 +v 0.8896 2.2840 0.2690 +v 0.8896 2.4629 0.2779 +v 0.8635 2.4629 0.2779 +v 0.8635 2.4975 0.2690 +v 0.8896 2.4975 0.2690 +v 0.8896 2.3186 0.2052 +v 0.8635 2.3186 0.2052 +v 0.8896 2.5094 0.2416 +v 0.8635 2.5094 0.2416 +v 0.8635 2.4975 0.2141 +v 0.8896 2.4975 0.2141 +v 0.8896 2.4629 0.2052 +v 0.8635 2.4629 0.2052 +v 0.8635 2.3186 0.2779 +v 0.8896 2.3186 0.2779 +v 0.1521 2.8662 0.4403 +v 0.2322 2.8662 0.4403 +v 0.2583 2.8662 0.3235 +v 0.2583 2.8662 0.4687 +v 0.1521 2.8662 0.4687 +v 0.2322 2.8662 0.1823 +v 0.1521 2.8662 0.1823 +v 0.1521 2.8662 0.1549 +v 0.2583 2.8662 0.1549 +v 0.2583 2.8662 0.2979 +v 0.2322 2.2840 0.2141 +v 0.2322 2.2721 0.2416 +v 0.2583 2.2721 0.2416 +v 0.2583 2.2840 0.2141 +v 0.2322 2.2840 0.2690 +v 0.2583 2.2840 0.2690 +v 0.2322 2.4629 0.2779 +v 0.2322 2.4975 0.2690 +v 0.2583 2.4975 0.2690 +v 0.2583 2.4629 0.2779 +v 0.2322 2.3186 0.2052 +v 0.2583 2.3186 0.2052 +v 0.2322 2.5094 0.2416 +v 0.2322 2.4975 0.2141 +v 0.2583 2.4975 0.2141 +v 0.2583 2.5094 0.2416 +v 0.2322 2.4629 0.2052 +v 0.2583 2.4629 0.2052 +v 0.2322 2.3186 0.2779 +v 0.2583 2.3186 0.2779 +v 0.9697 3.7562 0.4403 +v 0.8896 3.7562 0.4403 +v 0.5609 3.7555 0.3119 +v 0.5609 2.8670 0.3223 +v 0.8635 3.7562 0.3235 +v 0.8635 3.7562 0.4687 +v 0.9697 3.7562 0.4687 +v 0.8896 3.7562 0.1823 +v 0.9697 3.7562 0.1823 +v 0.9697 3.7562 0.1549 +v 0.8635 3.7562 0.1549 +v 0.8635 3.7562 0.2979 +v 0.5609 2.8670 0.2968 +v 0.8896 3.1740 0.2141 +v 0.8635 3.1740 0.2141 +v 0.8635 3.1621 0.2416 +v 0.8896 3.1621 0.2416 +v 0.8635 3.1740 0.2690 +v 0.8896 3.1740 0.2690 +v 0.8896 3.3529 0.2779 +v 0.8635 3.3529 0.2779 +v 0.8635 3.3875 0.2690 +v 0.8896 3.3875 0.2690 +v 0.8896 3.2086 0.2052 +v 0.8635 3.2086 0.2052 +v 0.8896 3.3994 0.2416 +v 0.8635 3.3994 0.2416 +v 0.8635 3.3875 0.2141 +v 0.8896 3.3875 0.2141 +v 0.8896 3.3529 0.2052 +v 0.8635 3.3529 0.2052 +v 0.8635 3.2086 0.2779 +v 0.8896 3.2086 0.2779 +v 0.1521 3.7562 0.4403 +v 0.2322 3.7562 0.4403 +v 0.2583 3.7562 0.3235 +v 0.2583 3.7562 0.4687 +v 0.1521 3.7562 0.4687 +v 0.2322 3.7562 0.1823 +v 0.1521 3.7562 0.1823 +v 0.1521 3.7562 0.1549 +v 0.2583 3.7562 0.1549 +v 0.2583 3.7562 0.2979 +v 0.2322 3.1740 0.2141 +v 0.2322 3.1621 0.2416 +v 0.2583 3.1621 0.2416 +v 0.2583 3.1740 0.2141 +v 0.2322 3.1740 0.2690 +v 0.2583 3.1740 0.2690 +v 0.2322 3.3529 0.2779 +v 0.2322 3.3875 0.2690 +v 0.2583 3.3875 0.2690 +v 0.2583 3.3529 0.2779 +v 0.2322 3.2086 0.2052 +v 0.2583 3.2086 0.2052 +v 0.2322 3.3994 0.2416 +v 0.2322 3.3875 0.2141 +v 0.2583 3.3875 0.2141 +v 0.2583 3.3994 0.2416 +v 0.2322 3.3529 0.2052 +v 0.2583 3.3529 0.2052 +v 0.2322 3.2086 0.2779 +v 0.2583 3.2086 0.2779 +v 0.9697 4.6462 0.4403 +v 0.8896 4.6462 0.4403 +v 0.5609 4.6455 0.3119 +v 0.5609 3.7570 0.3223 +v 0.8635 4.6462 0.3235 +v 0.8635 4.6462 0.4687 +v 0.9697 4.6462 0.4687 +v 0.8896 4.6462 0.1823 +v 0.9697 4.6462 0.1823 +v 0.9697 4.6462 0.1549 +v 0.8635 4.6462 0.1549 +v 0.8635 4.6462 0.2979 +v 0.5609 3.7570 0.2968 +v 0.8896 4.0640 0.2141 +v 0.8635 4.0640 0.2141 +v 0.8635 4.0521 0.2416 +v 0.8896 4.0521 0.2416 +v 0.8635 4.0640 0.2690 +v 0.8896 4.0640 0.2690 +v 0.8896 4.2429 0.2779 +v 0.8635 4.2429 0.2779 +v 0.8635 4.2775 0.2690 +v 0.8896 4.2775 0.2690 +v 0.8896 4.0986 0.2052 +v 0.8635 4.0986 0.2052 +v 0.8896 4.2894 0.2416 +v 0.8635 4.2894 0.2416 +v 0.8635 4.2775 0.2141 +v 0.8896 4.2775 0.2141 +v 0.8896 4.2429 0.2052 +v 0.8635 4.2429 0.2052 +v 0.8635 4.0986 0.2779 +v 0.8896 4.0986 0.2779 +v 0.1521 4.6462 0.4403 +v 0.2322 4.6462 0.4403 +v 0.2583 4.6462 0.3235 +v 0.2583 4.6462 0.4687 +v 0.1521 4.6462 0.4687 +v 0.2322 4.6462 0.1823 +v 0.1521 4.6462 0.1823 +v 0.1521 4.6462 0.1549 +v 0.2583 4.6462 0.1549 +v 0.2583 4.6462 0.2979 +v 0.2322 4.0640 0.2141 +v 0.2322 4.0521 0.2416 +v 0.2583 4.0521 0.2416 +v 0.2583 4.0640 0.2141 +v 0.2322 4.0640 0.2690 +v 0.2583 4.0640 0.2690 +v 0.2322 4.2429 0.2779 +v 0.2322 4.2775 0.2690 +v 0.2583 4.2775 0.2690 +v 0.2583 4.2429 0.2779 +v 0.2322 4.0986 0.2052 +v 0.2583 4.0986 0.2052 +v 0.2322 4.2894 0.2416 +v 0.2322 4.2775 0.2141 +v 0.2583 4.2775 0.2141 +v 0.2583 4.2894 0.2416 +v 0.2322 4.2429 0.2052 +v 0.2583 4.2429 0.2052 +v 0.2322 4.0986 0.2779 +v 0.2583 4.0986 0.2779 +v 0.9697 5.5362 0.4403 +v 0.8896 5.5362 0.4403 +v 0.5609 5.5355 0.3119 +v 0.5609 4.6470 0.3223 +v 0.8635 5.5362 0.3235 +v 0.8635 5.5362 0.4687 +v 0.9697 5.5362 0.4687 +v 0.8896 5.5362 0.1823 +v 0.9697 5.5362 0.1823 +v 0.9697 5.5362 0.1549 +v 0.8635 5.5362 0.1549 +v 0.8635 5.5362 0.2979 +v 0.5609 4.6470 0.2968 +v 0.8896 4.9540 0.2141 +v 0.8635 4.9540 0.2141 +v 0.8635 4.9421 0.2416 +v 0.8896 4.9421 0.2416 +v 0.8635 4.9540 0.2690 +v 0.8896 4.9540 0.2690 +v 0.8896 5.1329 0.2779 +v 0.8635 5.1329 0.2779 +v 0.8635 5.1675 0.2690 +v 0.8896 5.1675 0.2690 +v 0.8896 4.9886 0.2052 +v 0.8635 4.9886 0.2052 +v 0.8896 5.1794 0.2416 +v 0.8635 5.1794 0.2416 +v 0.8635 5.1675 0.2141 +v 0.8896 5.1675 0.2141 +v 0.8896 5.1329 0.2052 +v 0.8635 5.1329 0.2052 +v 0.8635 4.9886 0.2779 +v 0.8896 4.9886 0.2779 +v 0.1521 5.5362 0.4403 +v 0.2322 5.5362 0.4403 +v 0.2583 5.5362 0.3235 +v 0.2583 5.5362 0.4687 +v 0.1521 5.5362 0.4687 +v 0.2322 5.5362 0.1823 +v 0.1521 5.5362 0.1823 +v 0.1521 5.5362 0.1549 +v 0.2583 5.5362 0.1549 +v 0.2583 5.5362 0.2979 +v 0.2322 4.9540 0.2141 +v 0.2322 4.9421 0.2416 +v 0.2583 4.9421 0.2416 +v 0.2583 4.9540 0.2141 +v 0.2322 4.9540 0.2690 +v 0.2583 4.9540 0.2690 +v 0.2322 5.1329 0.2779 +v 0.2322 5.1675 0.2690 +v 0.2583 5.1675 0.2690 +v 0.2583 5.1329 0.2779 +v 0.2322 4.9886 0.2052 +v 0.2583 4.9886 0.2052 +v 0.2322 5.1794 0.2416 +v 0.2322 5.1675 0.2141 +v 0.2583 5.1675 0.2141 +v 0.2583 5.1794 0.2416 +v 0.2322 5.1329 0.2052 +v 0.2583 5.1329 0.2052 +v 0.2322 4.9886 0.2779 +v 0.2583 4.9886 0.2779 +v 0.9697 6.4262 0.4403 +v 0.8896 6.4262 0.4403 +v 0.5609 6.4255 0.3119 +v 0.5609 5.5370 0.3223 +v 0.8635 6.4262 0.3235 +v 0.8635 6.4262 0.4687 +v 0.9697 6.4262 0.4687 +v 0.8896 6.4262 0.1823 +v 0.9697 6.4262 0.1823 +v 0.9697 6.4262 0.1549 +v 0.8635 6.4262 0.1549 +v 0.8635 6.4262 0.2979 +v 0.5609 5.5370 0.2968 +v 0.8896 5.8440 0.2141 +v 0.8635 5.8440 0.2141 +v 0.8635 5.8321 0.2416 +v 0.8896 5.8321 0.2416 +v 0.8635 5.8440 0.2690 +v 0.8896 5.8440 0.2690 +v 0.8896 6.0229 0.2779 +v 0.8635 6.0229 0.2779 +v 0.8635 6.0575 0.2690 +v 0.8896 6.0575 0.2690 +v 0.8896 5.8786 0.2052 +v 0.8635 5.8786 0.2052 +v 0.8896 6.0694 0.2416 +v 0.8635 6.0694 0.2416 +v 0.8635 6.0575 0.2141 +v 0.8896 6.0575 0.2141 +v 0.8896 6.0229 0.2052 +v 0.8635 6.0229 0.2052 +v 0.8635 5.8786 0.2779 +v 0.8896 5.8786 0.2779 +v 0.1521 6.4262 0.4403 +v 0.2322 6.4262 0.4403 +v 0.2583 6.4262 0.3235 +v 0.2583 6.4262 0.4687 +v 0.1521 6.4262 0.4687 +v 0.2322 6.4262 0.1823 +v 0.1521 6.4262 0.1823 +v 0.1521 6.4262 0.1549 +v 0.2583 6.4262 0.1549 +v 0.2583 6.4262 0.2979 +v 0.2322 5.8440 0.2141 +v 0.2322 5.8321 0.2416 +v 0.2583 5.8321 0.2416 +v 0.2583 5.8440 0.2141 +v 0.2322 5.8440 0.2690 +v 0.2583 5.8440 0.2690 +v 0.2322 6.0229 0.2779 +v 0.2322 6.0575 0.2690 +v 0.2583 6.0575 0.2690 +v 0.2583 6.0229 0.2779 +v 0.2322 5.8786 0.2052 +v 0.2583 5.8786 0.2052 +v 0.2322 6.0694 0.2416 +v 0.2322 6.0575 0.2141 +v 0.2583 6.0575 0.2141 +v 0.2583 6.0694 0.2416 +v 0.2322 6.0229 0.2052 +v 0.2583 6.0229 0.2052 +v 0.2322 5.8786 0.2779 +v 0.2583 5.8786 0.2779 +v 0.9697 7.3162 0.4403 +v 0.8896 7.3162 0.4403 +v 0.5609 7.3155 0.3119 +v 0.5609 6.4270 0.3223 +v 0.8635 7.3162 0.3235 +v 0.8635 7.3162 0.4687 +v 0.9697 7.3162 0.4687 +v 0.8896 7.3162 0.1823 +v 0.9697 7.3162 0.1823 +v 0.9697 7.3162 0.1549 +v 0.8635 7.3162 0.1549 +v 0.8635 7.3162 0.2979 +v 0.5609 6.4270 0.2968 +v 0.8896 6.7340 0.2141 +v 0.8635 6.7340 0.2141 +v 0.8635 6.7221 0.2416 +v 0.8896 6.7221 0.2416 +v 0.8635 6.7340 0.2690 +v 0.8896 6.7340 0.2690 +v 0.8896 6.9129 0.2779 +v 0.8635 6.9129 0.2779 +v 0.8635 6.9475 0.2690 +v 0.8896 6.9475 0.2690 +v 0.8896 6.7686 0.2052 +v 0.8635 6.7686 0.2052 +v 0.8896 6.9594 0.2416 +v 0.8635 6.9594 0.2416 +v 0.8635 6.9475 0.2141 +v 0.8896 6.9475 0.2141 +v 0.8896 6.9129 0.2052 +v 0.8635 6.9129 0.2052 +v 0.8635 6.7686 0.2779 +v 0.8896 6.7686 0.2779 +v 0.1521 7.3162 0.4403 +v 0.2322 7.3162 0.4403 +v 0.2583 7.3162 0.3235 +v 0.2583 7.3162 0.4687 +v 0.1521 7.3162 0.4687 +v 0.2322 7.3162 0.1823 +v 0.1521 7.3162 0.1823 +v 0.1521 7.3162 0.1549 +v 0.2583 7.3162 0.1549 +v 0.2583 7.3162 0.2979 +v 0.2322 6.7340 0.2141 +v 0.2322 6.7221 0.2416 +v 0.2583 6.7221 0.2416 +v 0.2583 6.7340 0.2141 +v 0.2322 6.7340 0.2690 +v 0.2583 6.7340 0.2690 +v 0.2322 6.9129 0.2779 +v 0.2322 6.9475 0.2690 +v 0.2583 6.9475 0.2690 +v 0.2583 6.9129 0.2779 +v 0.2322 6.7686 0.2052 +v 0.2583 6.7686 0.2052 +v 0.2322 6.9594 0.2416 +v 0.2322 6.9475 0.2141 +v 0.2583 6.9475 0.2141 +v 0.2583 6.9594 0.2416 +v 0.2322 6.9129 0.2052 +v 0.2583 6.9129 0.2052 +v 0.2322 6.7686 0.2779 +v 0.2583 6.7686 0.2779 +v 0.9697 8.2055 0.4414 +v 0.8896 8.2055 0.4414 +v 0.5609 8.2055 0.3119 +v 0.5609 7.3170 0.3223 +v 0.8635 8.2055 0.3247 +v 0.8635 8.2055 0.4698 +v 0.9697 8.2055 0.4698 +v 0.8896 8.2055 0.1835 +v 0.9697 8.2055 0.1835 +v 0.9697 8.2055 0.1561 +v 0.8635 8.2055 0.1561 +v 0.8635 8.2055 0.2991 +v 0.5609 7.3170 0.2968 +v 0.8896 7.6240 0.2141 +v 0.8635 7.6240 0.2141 +v 0.8635 7.6121 0.2416 +v 0.8896 7.6121 0.2416 +v 0.8635 7.6240 0.2690 +v 0.8896 7.6240 0.2690 +v 0.8896 7.8029 0.2779 +v 0.8635 7.8029 0.2779 +v 0.8635 7.8375 0.2690 +v 0.8896 7.8375 0.2690 +v 0.8896 7.6586 0.2052 +v 0.8635 7.6586 0.2052 +v 0.8896 7.8494 0.2416 +v 0.8635 7.8494 0.2416 +v 0.8635 7.8375 0.2141 +v 0.8896 7.8375 0.2141 +v 0.8896 7.8029 0.2052 +v 0.8635 7.8029 0.2052 +v 0.8635 7.6586 0.2779 +v 0.8896 7.6586 0.2779 +v 0.1521 8.2055 0.4414 +v 0.2322 8.2055 0.4414 +v 0.2583 8.2055 0.3247 +v 0.2583 8.2055 0.4698 +v 0.1521 8.2055 0.4698 +v 0.2322 8.2055 0.1835 +v 0.1521 8.2055 0.1835 +v 0.1521 8.2055 0.1561 +v 0.2583 8.2055 0.1561 +v 0.2583 8.2055 0.2991 +v 0.2322 7.6240 0.2141 +v 0.2322 7.6121 0.2416 +v 0.2583 7.6121 0.2416 +v 0.2583 7.6240 0.2141 +v 0.2322 7.6240 0.2690 +v 0.2583 7.6240 0.2690 +v 0.2322 7.8029 0.2779 +v 0.2322 7.8375 0.2690 +v 0.2583 7.8375 0.2690 +v 0.2583 7.8029 0.2779 +v 0.2322 7.6586 0.2052 +v 0.2583 7.6586 0.2052 +v 0.2322 7.8494 0.2416 +v 0.2322 7.8375 0.2141 +v 0.2583 7.8375 0.2141 +v 0.2583 7.8494 0.2416 +v 0.2322 7.8029 0.2052 +v 0.2583 7.8029 0.2052 +v 0.2322 7.6586 0.2779 +v 0.2583 7.6586 0.2779 +# 839 vertices + +vn 0.0000 0.0013 -1.0000 +vn -0.0192 0.0052 0.9998 +vn 0.0000 -0.0013 1.0000 +vn -0.0231 0.0092 -0.9997 +vn -1.0000 0.0000 0.0000 +vn 1.0000 -0.0000 0.0000 +vn 0.0000 0.9174 0.3979 +vn 0.0000 0.9174 -0.3979 +vn 0.0000 -0.2482 -0.9687 +vn -0.0000 0.2482 0.9687 +vn 0.0000 -0.9174 0.3979 +vn 0.0000 -0.0000 1.0000 +vn 0.0000 0.2482 -0.9687 +vn 0.0000 -0.9174 -0.3979 +vn 0.0000 0.0000 -1.0000 +vn 0.0000 -0.2482 0.9687 +vn -1.0000 -0.0000 -0.0000 +vn -1.0000 0.0000 -0.0000 +vn 1.0000 0.0000 0.0000 +vn 1.0000 -0.0000 -0.0000 +vn -1.0000 -0.0000 0.0000 +vn 0.0192 0.0052 0.9998 +vn 0.0231 0.0092 -0.9997 +vn 0.0000 0.2482 0.9687 +vn -0.0000 -0.0000 1.0000 +vn 1.0000 0.0000 -0.0000 +vn 0.0000 -0.0000 -1.0000 +vn -0.0211 0.0059 0.9998 +vn 0.0000 0.0000 1.0000 +vn -0.0211 0.0085 -0.9997 +vn 0.0211 0.0059 0.9998 +vn 0.0211 0.0085 -0.9997 +vn -0.0000 0.9174 0.3979 +vn 0.0000 0.9174 -0.3980 +vn -0.0230 0.0052 0.9997 +vn -0.0192 0.0092 -0.9998 +vn 0.0230 0.0052 0.9997 +vn 0.0192 0.0092 -0.9998 +vn -0.0000 -0.9998 0.0210 +vn -0.0028 -0.9909 0.1349 +vn 0.0000 -0.9909 0.1349 +vn 0.0028 -0.9909 0.1349 +vn 0.0020 -0.9956 -0.0937 +vn -0.0000 -0.9956 -0.0937 +vn -0.0020 -0.9956 -0.0937 +vn 0.0000 -1.0000 0.0000 +vn -0.0029 -0.9909 0.1349 +vn 0.0029 -0.9909 0.1349 +vn -0.0028 -0.9909 0.1348 +vn 0.0000 -0.9909 0.1348 +vn 0.0028 -0.9909 0.1348 +vn -0.0029 -0.9908 0.1349 +vn 0.0029 -0.9908 0.1349 +vn 0.0000 -0.9998 0.0210 +vn 0.0020 -0.9956 -0.0936 +vn -0.0000 -0.9956 -0.0936 +vn -0.0020 -0.9956 -0.0936 +vn 0.0000 1.0000 0.0000 +# 58 vertex normals + +vt 0.6170 0.1315 0.0000 +vt 0.6170 0.1315 0.0000 +vt 0.6153 0.1315 0.0000 +vt 0.6153 0.1315 0.0000 +vt 0.6085 0.1278 0.0000 +vt 0.6085 0.1281 0.0000 +vt 0.6148 0.1281 0.0000 +vt 0.6148 0.1282 0.0000 +vt 0.6148 0.1324 0.0000 +vt 0.6148 0.1323 0.0000 +vt 0.6170 0.1323 0.0000 +vt 0.6170 0.1324 0.0000 +vt 0.6153 0.1241 0.0000 +vt 0.6153 0.1241 0.0000 +vt 0.6170 0.1241 0.0000 +vt 0.6170 0.1241 0.0000 +vt 0.6170 0.1233 0.0000 +vt 0.6170 0.1233 0.0000 +vt 0.6148 0.1233 0.0000 +vt 0.6148 0.1233 0.0000 +vt 0.6148 0.1274 0.0000 +vt 0.6148 0.1274 0.0000 +vt 0.6085 0.1274 0.0000 +vt 0.6153 0.1250 0.0000 +vt 0.6148 0.1250 0.0000 +vt 0.6148 0.1258 0.0000 +vt 0.6153 0.1258 0.0000 +vt 0.6148 0.1266 0.0000 +vt 0.6153 0.1266 0.0000 +vt 0.6153 0.1269 0.0000 +vt 0.6148 0.1269 0.0000 +vt 0.6148 0.1266 0.0000 +vt 0.6153 0.1266 0.0000 +vt 0.6153 0.1248 0.0000 +vt 0.6148 0.1248 0.0000 +vt 0.6153 0.1258 0.0000 +vt 0.6148 0.1258 0.0000 +vt 0.6148 0.1250 0.0000 +vt 0.6153 0.1250 0.0000 +vt 0.6153 0.1248 0.0000 +vt 0.6148 0.1248 0.0000 +vt 0.6148 0.1269 0.0000 +vt 0.6153 0.1269 0.0000 +vt 0.6000 0.1315 0.0000 +vt 0.6017 0.1315 0.0000 +vt 0.6017 0.1315 0.0000 +vt 0.6000 0.1315 0.0000 +vt 0.6022 0.1282 0.0000 +vt 0.6022 0.1281 0.0000 +vt 0.6022 0.1324 0.0000 +vt 0.6000 0.1324 0.0000 +vt 0.6000 0.1323 0.0000 +vt 0.6022 0.1323 0.0000 +vt 0.6017 0.1241 0.0000 +vt 0.6000 0.1241 0.0000 +vt 0.6000 0.1241 0.0000 +vt 0.6017 0.1241 0.0000 +vt 0.6000 0.1233 0.0000 +vt 0.6022 0.1233 0.0000 +vt 0.6022 0.1233 0.0000 +vt 0.6000 0.1233 0.0000 +vt 0.6022 0.1274 0.0000 +vt 0.6022 0.1274 0.0000 +vt 0.6017 0.1250 0.0000 +vt 0.6017 0.1258 0.0000 +vt 0.6022 0.1258 0.0000 +vt 0.6022 0.1250 0.0000 +vt 0.6017 0.1266 0.0000 +vt 0.6022 0.1266 0.0000 +vt 0.6017 0.1269 0.0000 +vt 0.6017 0.1266 0.0000 +vt 0.6022 0.1266 0.0000 +vt 0.6022 0.1269 0.0000 +vt 0.6017 0.1248 0.0000 +vt 0.6022 0.1248 0.0000 +vt 0.6017 0.1258 0.0000 +vt 0.6017 0.1250 0.0000 +vt 0.6022 0.1250 0.0000 +vt 0.6022 0.1258 0.0000 +vt 0.6017 0.1248 0.0000 +vt 0.6022 0.1248 0.0000 +vt 0.6017 0.1269 0.0000 +vt 0.6022 0.1269 0.0000 +vt 0.6170 0.1315 0.0000 +vt 0.6153 0.1315 0.0000 +vt 0.6085 0.1278 0.0000 +vt 0.6085 0.1281 0.0000 +vt 0.6148 0.1282 0.0000 +vt 0.6148 0.1324 0.0000 +vt 0.6170 0.1324 0.0000 +vt 0.6153 0.1241 0.0000 +vt 0.6170 0.1241 0.0000 +vt 0.6170 0.1233 0.0000 +vt 0.6148 0.1233 0.0000 +vt 0.6148 0.1274 0.0000 +vt 0.6085 0.1274 0.0000 +vt 0.6153 0.1250 0.0000 +vt 0.6148 0.1250 0.0000 +vt 0.6148 0.1258 0.0000 +vt 0.6153 0.1258 0.0000 +vt 0.6148 0.1266 0.0000 +vt 0.6153 0.1266 0.0000 +vt 0.6153 0.1269 0.0000 +vt 0.6148 0.1269 0.0000 +vt 0.6148 0.1266 0.0000 +vt 0.6153 0.1266 0.0000 +vt 0.6153 0.1248 0.0000 +vt 0.6148 0.1248 0.0000 +vt 0.6153 0.1258 0.0000 +vt 0.6148 0.1258 0.0000 +vt 0.6148 0.1250 0.0000 +vt 0.6153 0.1250 0.0000 +vt 0.6153 0.1248 0.0000 +vt 0.6148 0.1248 0.0000 +vt 0.6148 0.1269 0.0000 +vt 0.6153 0.1269 0.0000 +vt 0.6000 0.1315 0.0000 +vt 0.6017 0.1315 0.0000 +vt 0.6022 0.1282 0.0000 +vt 0.6022 0.1324 0.0000 +vt 0.6000 0.1324 0.0000 +vt 0.6017 0.1241 0.0000 +vt 0.6000 0.1241 0.0000 +vt 0.6000 0.1233 0.0000 +vt 0.6022 0.1233 0.0000 +vt 0.6022 0.1274 0.0000 +vt 0.6017 0.1250 0.0000 +vt 0.6017 0.1258 0.0000 +vt 0.6022 0.1258 0.0000 +vt 0.6022 0.1250 0.0000 +vt 0.6017 0.1266 0.0000 +vt 0.6022 0.1266 0.0000 +vt 0.6017 0.1269 0.0000 +vt 0.6017 0.1266 0.0000 +vt 0.6022 0.1266 0.0000 +vt 0.6022 0.1269 0.0000 +vt 0.6017 0.1248 0.0000 +vt 0.6022 0.1248 0.0000 +vt 0.6017 0.1258 0.0000 +vt 0.6017 0.1250 0.0000 +vt 0.6022 0.1250 0.0000 +vt 0.6022 0.1258 0.0000 +vt 0.6017 0.1248 0.0000 +vt 0.6022 0.1248 0.0000 +vt 0.6017 0.1269 0.0000 +vt 0.6022 0.1269 0.0000 +vt 0.6170 0.1315 0.0000 +vt 0.6153 0.1315 0.0000 +vt 0.6085 0.1278 0.0000 +vt 0.6085 0.1281 0.0000 +vt 0.6148 0.1282 0.0000 +vt 0.6148 0.1324 0.0000 +vt 0.6170 0.1324 0.0000 +vt 0.6153 0.1241 0.0000 +vt 0.6170 0.1241 0.0000 +vt 0.6170 0.1233 0.0000 +vt 0.6148 0.1233 0.0000 +vt 0.6148 0.1274 0.0000 +vt 0.6085 0.1274 0.0000 +vt 0.6153 0.1250 0.0000 +vt 0.6148 0.1250 0.0000 +vt 0.6148 0.1258 0.0000 +vt 0.6153 0.1258 0.0000 +vt 0.6148 0.1266 0.0000 +vt 0.6153 0.1266 0.0000 +vt 0.6153 0.1269 0.0000 +vt 0.6148 0.1269 0.0000 +vt 0.6148 0.1266 0.0000 +vt 0.6153 0.1266 0.0000 +vt 0.6153 0.1248 0.0000 +vt 0.6148 0.1248 0.0000 +vt 0.6153 0.1258 0.0000 +vt 0.6148 0.1258 0.0000 +vt 0.6148 0.1250 0.0000 +vt 0.6153 0.1250 0.0000 +vt 0.6153 0.1248 0.0000 +vt 0.6148 0.1248 0.0000 +vt 0.6148 0.1269 0.0000 +vt 0.6153 0.1269 0.0000 +vt 0.6000 0.1315 0.0000 +vt 0.6017 0.1315 0.0000 +vt 0.6022 0.1282 0.0000 +vt 0.6022 0.1324 0.0000 +vt 0.6000 0.1324 0.0000 +vt 0.6017 0.1241 0.0000 +vt 0.6000 0.1241 0.0000 +vt 0.6000 0.1233 0.0000 +vt 0.6022 0.1233 0.0000 +vt 0.6022 0.1274 0.0000 +vt 0.6017 0.1250 0.0000 +vt 0.6017 0.1258 0.0000 +vt 0.6022 0.1258 0.0000 +vt 0.6022 0.1250 0.0000 +vt 0.6017 0.1266 0.0000 +vt 0.6022 0.1266 0.0000 +vt 0.6017 0.1269 0.0000 +vt 0.6017 0.1266 0.0000 +vt 0.6022 0.1266 0.0000 +vt 0.6022 0.1269 0.0000 +vt 0.6017 0.1248 0.0000 +vt 0.6022 0.1248 0.0000 +vt 0.6017 0.1258 0.0000 +vt 0.6017 0.1250 0.0000 +vt 0.6022 0.1250 0.0000 +vt 0.6022 0.1258 0.0000 +vt 0.6017 0.1248 0.0000 +vt 0.6022 0.1248 0.0000 +vt 0.6017 0.1269 0.0000 +vt 0.6022 0.1269 0.0000 +vt 0.6170 0.1315 0.0000 +vt 0.6153 0.1315 0.0000 +vt 0.6085 0.1278 0.0000 +vt 0.6085 0.1281 0.0000 +vt 0.6148 0.1282 0.0000 +vt 0.6148 0.1324 0.0000 +vt 0.6170 0.1324 0.0000 +vt 0.6153 0.1241 0.0000 +vt 0.6170 0.1241 0.0000 +vt 0.6170 0.1233 0.0000 +vt 0.6148 0.1233 0.0000 +vt 0.6148 0.1274 0.0000 +vt 0.6085 0.1274 0.0000 +vt 0.6153 0.1250 0.0000 +vt 0.6148 0.1250 0.0000 +vt 0.6148 0.1258 0.0000 +vt 0.6153 0.1258 0.0000 +vt 0.6148 0.1266 0.0000 +vt 0.6153 0.1266 0.0000 +vt 0.6153 0.1269 0.0000 +vt 0.6148 0.1269 0.0000 +vt 0.6148 0.1266 0.0000 +vt 0.6153 0.1266 0.0000 +vt 0.6153 0.1248 0.0000 +vt 0.6148 0.1248 0.0000 +vt 0.6153 0.1258 0.0000 +vt 0.6148 0.1258 0.0000 +vt 0.6148 0.1250 0.0000 +vt 0.6153 0.1250 0.0000 +vt 0.6153 0.1248 0.0000 +vt 0.6148 0.1248 0.0000 +vt 0.6148 0.1269 0.0000 +vt 0.6153 0.1269 0.0000 +vt 0.6000 0.1315 0.0000 +vt 0.6017 0.1315 0.0000 +vt 0.6022 0.1282 0.0000 +vt 0.6022 0.1324 0.0000 +vt 0.6000 0.1324 0.0000 +vt 0.6017 0.1241 0.0000 +vt 0.6000 0.1241 0.0000 +vt 0.6000 0.1233 0.0000 +vt 0.6022 0.1233 0.0000 +vt 0.6022 0.1274 0.0000 +vt 0.6017 0.1250 0.0000 +vt 0.6017 0.1258 0.0000 +vt 0.6022 0.1258 0.0000 +vt 0.6022 0.1250 0.0000 +vt 0.6017 0.1266 0.0000 +vt 0.6022 0.1266 0.0000 +vt 0.6017 0.1269 0.0000 +vt 0.6017 0.1266 0.0000 +vt 0.6022 0.1266 0.0000 +vt 0.6022 0.1269 0.0000 +vt 0.6017 0.1248 0.0000 +vt 0.6022 0.1248 0.0000 +vt 0.6017 0.1258 0.0000 +vt 0.6017 0.1250 0.0000 +vt 0.6022 0.1250 0.0000 +vt 0.6022 0.1258 0.0000 +vt 0.6017 0.1248 0.0000 +vt 0.6022 0.1248 0.0000 +vt 0.6017 0.1269 0.0000 +vt 0.6022 0.1269 0.0000 +vt 0.6170 0.1315 0.0000 +vt 0.6153 0.1315 0.0000 +vt 0.6085 0.1278 0.0000 +vt 0.6085 0.1281 0.0000 +vt 0.6148 0.1282 0.0000 +vt 0.6148 0.1324 0.0000 +vt 0.6170 0.1324 0.0000 +vt 0.6153 0.1241 0.0000 +vt 0.6170 0.1241 0.0000 +vt 0.6170 0.1233 0.0000 +vt 0.6148 0.1233 0.0000 +vt 0.6148 0.1274 0.0000 +vt 0.6085 0.1274 0.0000 +vt 0.6153 0.1250 0.0000 +vt 0.6148 0.1250 0.0000 +vt 0.6148 0.1258 0.0000 +vt 0.6153 0.1258 0.0000 +vt 0.6148 0.1266 0.0000 +vt 0.6153 0.1266 0.0000 +vt 0.6153 0.1269 0.0000 +vt 0.6148 0.1269 0.0000 +vt 0.6148 0.1266 0.0000 +vt 0.6153 0.1266 0.0000 +vt 0.6153 0.1248 0.0000 +vt 0.6148 0.1248 0.0000 +vt 0.6153 0.1258 0.0000 +vt 0.6148 0.1258 0.0000 +vt 0.6148 0.1250 0.0000 +vt 0.6153 0.1250 0.0000 +vt 0.6153 0.1248 0.0000 +vt 0.6148 0.1248 0.0000 +vt 0.6148 0.1269 0.0000 +vt 0.6153 0.1269 0.0000 +vt 0.6000 0.1315 0.0000 +vt 0.6017 0.1315 0.0000 +vt 0.6022 0.1282 0.0000 +vt 0.6022 0.1324 0.0000 +vt 0.6000 0.1324 0.0000 +vt 0.6017 0.1241 0.0000 +vt 0.6000 0.1241 0.0000 +vt 0.6000 0.1233 0.0000 +vt 0.6022 0.1233 0.0000 +vt 0.6022 0.1274 0.0000 +vt 0.6017 0.1250 0.0000 +vt 0.6017 0.1258 0.0000 +vt 0.6022 0.1258 0.0000 +vt 0.6022 0.1250 0.0000 +vt 0.6017 0.1266 0.0000 +vt 0.6022 0.1266 0.0000 +vt 0.6017 0.1269 0.0000 +vt 0.6017 0.1266 0.0000 +vt 0.6022 0.1266 0.0000 +vt 0.6022 0.1269 0.0000 +vt 0.6017 0.1248 0.0000 +vt 0.6022 0.1248 0.0000 +vt 0.6017 0.1258 0.0000 +vt 0.6017 0.1250 0.0000 +vt 0.6022 0.1250 0.0000 +vt 0.6022 0.1258 0.0000 +vt 0.6017 0.1248 0.0000 +vt 0.6022 0.1248 0.0000 +vt 0.6017 0.1269 0.0000 +vt 0.6022 0.1269 0.0000 +vt 0.6170 0.1315 0.0000 +vt 0.6153 0.1315 0.0000 +vt 0.6085 0.1278 0.0000 +vt 0.6085 0.1281 0.0000 +vt 0.6148 0.1282 0.0000 +vt 0.6148 0.1324 0.0000 +vt 0.6170 0.1324 0.0000 +vt 0.6153 0.1241 0.0000 +vt 0.6170 0.1241 0.0000 +vt 0.6170 0.1233 0.0000 +vt 0.6148 0.1233 0.0000 +vt 0.6148 0.1274 0.0000 +vt 0.6085 0.1274 0.0000 +vt 0.6153 0.1250 0.0000 +vt 0.6148 0.1250 0.0000 +vt 0.6148 0.1258 0.0000 +vt 0.6153 0.1258 0.0000 +vt 0.6148 0.1266 0.0000 +vt 0.6153 0.1266 0.0000 +vt 0.6153 0.1269 0.0000 +vt 0.6148 0.1269 0.0000 +vt 0.6148 0.1266 0.0000 +vt 0.6153 0.1266 0.0000 +vt 0.6153 0.1248 0.0000 +vt 0.6148 0.1248 0.0000 +vt 0.6153 0.1258 0.0000 +vt 0.6148 0.1258 0.0000 +vt 0.6148 0.1250 0.0000 +vt 0.6153 0.1250 0.0000 +vt 0.6153 0.1248 0.0000 +vt 0.6148 0.1248 0.0000 +vt 0.6148 0.1269 0.0000 +vt 0.6153 0.1269 0.0000 +vt 0.6000 0.1315 0.0000 +vt 0.6017 0.1315 0.0000 +vt 0.6022 0.1282 0.0000 +vt 0.6022 0.1324 0.0000 +vt 0.6000 0.1324 0.0000 +vt 0.6017 0.1241 0.0000 +vt 0.6000 0.1241 0.0000 +vt 0.6000 0.1233 0.0000 +vt 0.6022 0.1233 0.0000 +vt 0.6022 0.1274 0.0000 +vt 0.6017 0.1250 0.0000 +vt 0.6017 0.1258 0.0000 +vt 0.6022 0.1258 0.0000 +vt 0.6022 0.1250 0.0000 +vt 0.6017 0.1266 0.0000 +vt 0.6022 0.1266 0.0000 +vt 0.6017 0.1269 0.0000 +vt 0.6017 0.1266 0.0000 +vt 0.6022 0.1266 0.0000 +vt 0.6022 0.1269 0.0000 +vt 0.6017 0.1248 0.0000 +vt 0.6022 0.1248 0.0000 +vt 0.6017 0.1258 0.0000 +vt 0.6017 0.1250 0.0000 +vt 0.6022 0.1250 0.0000 +vt 0.6022 0.1258 0.0000 +vt 0.6017 0.1248 0.0000 +vt 0.6022 0.1248 0.0000 +vt 0.6017 0.1269 0.0000 +vt 0.6022 0.1269 0.0000 +vt 0.6170 0.1315 0.0000 +vt 0.6153 0.1315 0.0000 +vt 0.6085 0.1278 0.0000 +vt 0.6085 0.1281 0.0000 +vt 0.6148 0.1282 0.0000 +vt 0.6148 0.1324 0.0000 +vt 0.6170 0.1324 0.0000 +vt 0.6153 0.1241 0.0000 +vt 0.6170 0.1241 0.0000 +vt 0.6170 0.1233 0.0000 +vt 0.6148 0.1233 0.0000 +vt 0.6148 0.1274 0.0000 +vt 0.6085 0.1274 0.0000 +vt 0.6153 0.1250 0.0000 +vt 0.6148 0.1250 0.0000 +vt 0.6148 0.1258 0.0000 +vt 0.6153 0.1258 0.0000 +vt 0.6148 0.1266 0.0000 +vt 0.6153 0.1266 0.0000 +vt 0.6153 0.1269 0.0000 +vt 0.6148 0.1269 0.0000 +vt 0.6148 0.1266 0.0000 +vt 0.6153 0.1266 0.0000 +vt 0.6153 0.1248 0.0000 +vt 0.6148 0.1248 0.0000 +vt 0.6153 0.1258 0.0000 +vt 0.6148 0.1258 0.0000 +vt 0.6148 0.1250 0.0000 +vt 0.6153 0.1250 0.0000 +vt 0.6153 0.1248 0.0000 +vt 0.6148 0.1248 0.0000 +vt 0.6148 0.1269 0.0000 +vt 0.6153 0.1269 0.0000 +vt 0.6000 0.1315 0.0000 +vt 0.6017 0.1315 0.0000 +vt 0.6022 0.1282 0.0000 +vt 0.6022 0.1324 0.0000 +vt 0.6000 0.1324 0.0000 +vt 0.6017 0.1241 0.0000 +vt 0.6000 0.1241 0.0000 +vt 0.6000 0.1233 0.0000 +vt 0.6022 0.1233 0.0000 +vt 0.6022 0.1274 0.0000 +vt 0.6017 0.1250 0.0000 +vt 0.6017 0.1258 0.0000 +vt 0.6022 0.1258 0.0000 +vt 0.6022 0.1250 0.0000 +vt 0.6017 0.1266 0.0000 +vt 0.6022 0.1266 0.0000 +vt 0.6017 0.1269 0.0000 +vt 0.6017 0.1266 0.0000 +vt 0.6022 0.1266 0.0000 +vt 0.6022 0.1269 0.0000 +vt 0.6017 0.1248 0.0000 +vt 0.6022 0.1248 0.0000 +vt 0.6017 0.1258 0.0000 +vt 0.6017 0.1250 0.0000 +vt 0.6022 0.1250 0.0000 +vt 0.6022 0.1258 0.0000 +vt 0.6017 0.1248 0.0000 +vt 0.6022 0.1248 0.0000 +vt 0.6017 0.1269 0.0000 +vt 0.6022 0.1269 0.0000 +vt 0.6170 0.1315 0.0000 +vt 0.6153 0.1315 0.0000 +vt 0.6085 0.1278 0.0000 +vt 0.6085 0.1281 0.0000 +vt 0.6148 0.1282 0.0000 +vt 0.6148 0.1324 0.0000 +vt 0.6170 0.1324 0.0000 +vt 0.6153 0.1241 0.0000 +vt 0.6170 0.1241 0.0000 +vt 0.6170 0.1233 0.0000 +vt 0.6148 0.1233 0.0000 +vt 0.6148 0.1274 0.0000 +vt 0.6085 0.1274 0.0000 +vt 0.6153 0.1250 0.0000 +vt 0.6148 0.1250 0.0000 +vt 0.6148 0.1258 0.0000 +vt 0.6153 0.1258 0.0000 +vt 0.6148 0.1266 0.0000 +vt 0.6153 0.1266 0.0000 +vt 0.6153 0.1269 0.0000 +vt 0.6148 0.1269 0.0000 +vt 0.6148 0.1266 0.0000 +vt 0.6153 0.1266 0.0000 +vt 0.6153 0.1248 0.0000 +vt 0.6148 0.1248 0.0000 +vt 0.6153 0.1258 0.0000 +vt 0.6148 0.1258 0.0000 +vt 0.6148 0.1250 0.0000 +vt 0.6153 0.1250 0.0000 +vt 0.6153 0.1248 0.0000 +vt 0.6148 0.1248 0.0000 +vt 0.6148 0.1269 0.0000 +vt 0.6153 0.1269 0.0000 +vt 0.6000 0.1315 0.0000 +vt 0.6017 0.1315 0.0000 +vt 0.6022 0.1282 0.0000 +vt 0.6022 0.1324 0.0000 +vt 0.6000 0.1324 0.0000 +vt 0.6017 0.1241 0.0000 +vt 0.6000 0.1241 0.0000 +vt 0.6000 0.1233 0.0000 +vt 0.6022 0.1233 0.0000 +vt 0.6022 0.1274 0.0000 +vt 0.6017 0.1250 0.0000 +vt 0.6017 0.1258 0.0000 +vt 0.6022 0.1258 0.0000 +vt 0.6022 0.1250 0.0000 +vt 0.6017 0.1266 0.0000 +vt 0.6022 0.1266 0.0000 +vt 0.6017 0.1269 0.0000 +vt 0.6017 0.1266 0.0000 +vt 0.6022 0.1266 0.0000 +vt 0.6022 0.1269 0.0000 +vt 0.6017 0.1248 0.0000 +vt 0.6022 0.1248 0.0000 +vt 0.6017 0.1258 0.0000 +vt 0.6017 0.1250 0.0000 +vt 0.6022 0.1250 0.0000 +vt 0.6022 0.1258 0.0000 +vt 0.6017 0.1248 0.0000 +vt 0.6022 0.1248 0.0000 +vt 0.6017 0.1269 0.0000 +vt 0.6022 0.1269 0.0000 +vt 0.6170 0.1315 0.0000 +vt 0.6153 0.1315 0.0000 +vt 0.6085 0.1278 0.0000 +vt 0.6085 0.1281 0.0000 +vt 0.6148 0.1282 0.0000 +vt 0.6148 0.1324 0.0000 +vt 0.6170 0.1324 0.0000 +vt 0.6153 0.1241 0.0000 +vt 0.6170 0.1241 0.0000 +vt 0.6170 0.1233 0.0000 +vt 0.6148 0.1233 0.0000 +vt 0.6148 0.1274 0.0000 +vt 0.6085 0.1274 0.0000 +vt 0.6153 0.1250 0.0000 +vt 0.6148 0.1250 0.0000 +vt 0.6148 0.1258 0.0000 +vt 0.6153 0.1258 0.0000 +vt 0.6148 0.1266 0.0000 +vt 0.6153 0.1266 0.0000 +vt 0.6153 0.1269 0.0000 +vt 0.6148 0.1269 0.0000 +vt 0.6148 0.1266 0.0000 +vt 0.6153 0.1266 0.0000 +vt 0.6153 0.1248 0.0000 +vt 0.6148 0.1248 0.0000 +vt 0.6153 0.1258 0.0000 +vt 0.6148 0.1258 0.0000 +vt 0.6148 0.1250 0.0000 +vt 0.6153 0.1250 0.0000 +vt 0.6153 0.1248 0.0000 +vt 0.6148 0.1248 0.0000 +vt 0.6148 0.1269 0.0000 +vt 0.6153 0.1269 0.0000 +vt 0.6000 0.1315 0.0000 +vt 0.6017 0.1315 0.0000 +vt 0.6022 0.1282 0.0000 +vt 0.6022 0.1324 0.0000 +vt 0.6000 0.1324 0.0000 +vt 0.6017 0.1241 0.0000 +vt 0.6000 0.1241 0.0000 +vt 0.6000 0.1233 0.0000 +vt 0.6022 0.1233 0.0000 +vt 0.6022 0.1274 0.0000 +vt 0.6017 0.1250 0.0000 +vt 0.6017 0.1258 0.0000 +vt 0.6022 0.1258 0.0000 +vt 0.6022 0.1250 0.0000 +vt 0.6017 0.1266 0.0000 +vt 0.6022 0.1266 0.0000 +vt 0.6017 0.1269 0.0000 +vt 0.6017 0.1266 0.0000 +vt 0.6022 0.1266 0.0000 +vt 0.6022 0.1269 0.0000 +vt 0.6017 0.1248 0.0000 +vt 0.6022 0.1248 0.0000 +vt 0.6017 0.1258 0.0000 +vt 0.6017 0.1250 0.0000 +vt 0.6022 0.1250 0.0000 +vt 0.6022 0.1258 0.0000 +vt 0.6017 0.1248 0.0000 +vt 0.6022 0.1248 0.0000 +vt 0.6017 0.1269 0.0000 +vt 0.6022 0.1269 0.0000 +vt 0.6170 0.1315 0.0000 +vt 0.6153 0.1315 0.0000 +vt 0.6085 0.1278 0.0000 +vt 0.6085 0.1281 0.0000 +vt 0.6148 0.1282 0.0000 +vt 0.6148 0.1324 0.0000 +vt 0.6170 0.1324 0.0000 +vt 0.6153 0.1241 0.0000 +vt 0.6170 0.1241 0.0000 +vt 0.6170 0.1233 0.0000 +vt 0.6148 0.1233 0.0000 +vt 0.6148 0.1274 0.0000 +vt 0.6085 0.1274 0.0000 +vt 0.6153 0.1250 0.0000 +vt 0.6148 0.1250 0.0000 +vt 0.6148 0.1258 0.0000 +vt 0.6153 0.1258 0.0000 +vt 0.6148 0.1266 0.0000 +vt 0.6153 0.1266 0.0000 +vt 0.6153 0.1269 0.0000 +vt 0.6148 0.1269 0.0000 +vt 0.6148 0.1266 0.0000 +vt 0.6153 0.1266 0.0000 +vt 0.6153 0.1248 0.0000 +vt 0.6148 0.1248 0.0000 +vt 0.6153 0.1258 0.0000 +vt 0.6148 0.1258 0.0000 +vt 0.6148 0.1250 0.0000 +vt 0.6153 0.1250 0.0000 +vt 0.6153 0.1248 0.0000 +vt 0.6148 0.1248 0.0000 +vt 0.6148 0.1269 0.0000 +vt 0.6153 0.1269 0.0000 +vt 0.6000 0.1315 0.0000 +vt 0.6017 0.1315 0.0000 +vt 0.6022 0.1282 0.0000 +vt 0.6022 0.1324 0.0000 +vt 0.6000 0.1324 0.0000 +vt 0.6017 0.1241 0.0000 +vt 0.6000 0.1241 0.0000 +vt 0.6000 0.1233 0.0000 +vt 0.6022 0.1233 0.0000 +vt 0.6022 0.1274 0.0000 +vt 0.6017 0.1250 0.0000 +vt 0.6017 0.1258 0.0000 +vt 0.6022 0.1258 0.0000 +vt 0.6022 0.1250 0.0000 +vt 0.6017 0.1266 0.0000 +vt 0.6022 0.1266 0.0000 +vt 0.6017 0.1269 0.0000 +vt 0.6017 0.1266 0.0000 +vt 0.6022 0.1266 0.0000 +vt 0.6022 0.1269 0.0000 +vt 0.6017 0.1248 0.0000 +vt 0.6022 0.1248 0.0000 +vt 0.6017 0.1258 0.0000 +vt 0.6017 0.1250 0.0000 +vt 0.6022 0.1250 0.0000 +vt 0.6022 0.1258 0.0000 +vt 0.6017 0.1248 0.0000 +vt 0.6022 0.1248 0.0000 +vt 0.6017 0.1269 0.0000 +vt 0.6022 0.1269 0.0000 +vt 0.6170 0.1315 0.0000 +vt 0.6153 0.1315 0.0000 +vt 0.6085 0.1278 0.0000 +vt 0.6085 0.1281 0.0000 +vt 0.6148 0.1282 0.0000 +vt 0.6148 0.1324 0.0000 +vt 0.6170 0.1324 0.0000 +vt 0.6153 0.1241 0.0000 +vt 0.6170 0.1241 0.0000 +vt 0.6170 0.1233 0.0000 +vt 0.6148 0.1233 0.0000 +vt 0.6148 0.1274 0.0000 +vt 0.6085 0.1274 0.0000 +vt 0.6153 0.1250 0.0000 +vt 0.6148 0.1250 0.0000 +vt 0.6148 0.1258 0.0000 +vt 0.6153 0.1258 0.0000 +vt 0.6148 0.1266 0.0000 +vt 0.6153 0.1266 0.0000 +vt 0.6153 0.1269 0.0000 +vt 0.6148 0.1269 0.0000 +vt 0.6148 0.1266 0.0000 +vt 0.6153 0.1266 0.0000 +vt 0.6153 0.1248 0.0000 +vt 0.6148 0.1248 0.0000 +vt 0.6153 0.1258 0.0000 +vt 0.6148 0.1258 0.0000 +vt 0.6148 0.1250 0.0000 +vt 0.6153 0.1250 0.0000 +vt 0.6153 0.1248 0.0000 +vt 0.6148 0.1248 0.0000 +vt 0.6148 0.1269 0.0000 +vt 0.6153 0.1269 0.0000 +vt 0.6000 0.1315 0.0000 +vt 0.6017 0.1315 0.0000 +vt 0.6022 0.1282 0.0000 +vt 0.6022 0.1324 0.0000 +vt 0.6000 0.1324 0.0000 +vt 0.6017 0.1241 0.0000 +vt 0.6000 0.1241 0.0000 +vt 0.6000 0.1233 0.0000 +vt 0.6022 0.1233 0.0000 +vt 0.6022 0.1274 0.0000 +vt 0.6017 0.1250 0.0000 +vt 0.6017 0.1258 0.0000 +vt 0.6022 0.1258 0.0000 +vt 0.6022 0.1250 0.0000 +vt 0.6017 0.1266 0.0000 +vt 0.6022 0.1266 0.0000 +vt 0.6017 0.1269 0.0000 +vt 0.6017 0.1266 0.0000 +vt 0.6022 0.1266 0.0000 +vt 0.6022 0.1269 0.0000 +vt 0.6017 0.1248 0.0000 +vt 0.6022 0.1248 0.0000 +vt 0.6017 0.1258 0.0000 +vt 0.6017 0.1250 0.0000 +vt 0.6022 0.1250 0.0000 +vt 0.6022 0.1258 0.0000 +vt 0.6017 0.1248 0.0000 +vt 0.6022 0.1248 0.0000 +vt 0.6017 0.1269 0.0000 +vt 0.6022 0.1269 0.0000 +vt 0.6170 0.1315 0.0000 +vt 0.6153 0.1315 0.0000 +vt 0.6085 0.1278 0.0000 +vt 0.6085 0.1281 0.0000 +vt 0.6148 0.1282 0.0000 +vt 0.6148 0.1324 0.0000 +vt 0.6170 0.1324 0.0000 +vt 0.6153 0.1241 0.0000 +vt 0.6170 0.1241 0.0000 +vt 0.6170 0.1233 0.0000 +vt 0.6148 0.1233 0.0000 +vt 0.6148 0.1274 0.0000 +vt 0.6085 0.1274 0.0000 +vt 0.6153 0.1250 0.0000 +vt 0.6148 0.1250 0.0000 +vt 0.6148 0.1258 0.0000 +vt 0.6153 0.1258 0.0000 +vt 0.6148 0.1266 0.0000 +vt 0.6153 0.1266 0.0000 +vt 0.6153 0.1269 0.0000 +vt 0.6148 0.1269 0.0000 +vt 0.6148 0.1266 0.0000 +vt 0.6153 0.1266 0.0000 +vt 0.6153 0.1248 0.0000 +vt 0.6148 0.1248 0.0000 +vt 0.6153 0.1258 0.0000 +vt 0.6148 0.1258 0.0000 +vt 0.6148 0.1250 0.0000 +vt 0.6153 0.1250 0.0000 +vt 0.6153 0.1248 0.0000 +vt 0.6148 0.1248 0.0000 +vt 0.6148 0.1269 0.0000 +vt 0.6153 0.1269 0.0000 +vt 0.6000 0.1315 0.0000 +vt 0.6017 0.1315 0.0000 +vt 0.6022 0.1282 0.0000 +vt 0.6022 0.1324 0.0000 +vt 0.6000 0.1324 0.0000 +vt 0.6017 0.1241 0.0000 +vt 0.6000 0.1241 0.0000 +vt 0.6000 0.1233 0.0000 +vt 0.6022 0.1233 0.0000 +vt 0.6022 0.1274 0.0000 +vt 0.6017 0.1250 0.0000 +vt 0.6017 0.1258 0.0000 +vt 0.6022 0.1258 0.0000 +vt 0.6022 0.1250 0.0000 +vt 0.6017 0.1266 0.0000 +vt 0.6022 0.1266 0.0000 +vt 0.6017 0.1269 0.0000 +vt 0.6017 0.1266 0.0000 +vt 0.6022 0.1266 0.0000 +vt 0.6022 0.1269 0.0000 +vt 0.6017 0.1248 0.0000 +vt 0.6022 0.1248 0.0000 +vt 0.6017 0.1258 0.0000 +vt 0.6017 0.1250 0.0000 +vt 0.6022 0.1250 0.0000 +vt 0.6022 0.1258 0.0000 +vt 0.6017 0.1248 0.0000 +vt 0.6022 0.1248 0.0000 +vt 0.6017 0.1269 0.0000 +vt 0.6022 0.1269 0.0000 +vt 0.6170 0.1316 0.0000 +vt 0.6153 0.1316 0.0000 +vt 0.6085 0.1278 0.0000 +vt 0.6085 0.1281 0.0000 +vt 0.6148 0.1282 0.0000 +vt 0.6148 0.1324 0.0000 +vt 0.6170 0.1324 0.0000 +vt 0.6153 0.1241 0.0000 +vt 0.6170 0.1241 0.0000 +vt 0.6170 0.1234 0.0000 +vt 0.6148 0.1234 0.0000 +vt 0.6148 0.1275 0.0000 +vt 0.6085 0.1274 0.0000 +vt 0.6153 0.1250 0.0000 +vt 0.6148 0.1250 0.0000 +vt 0.6148 0.1258 0.0000 +vt 0.6153 0.1258 0.0000 +vt 0.6148 0.1266 0.0000 +vt 0.6153 0.1266 0.0000 +vt 0.6153 0.1269 0.0000 +vt 0.6148 0.1269 0.0000 +vt 0.6148 0.1266 0.0000 +vt 0.6153 0.1266 0.0000 +vt 0.6153 0.1248 0.0000 +vt 0.6148 0.1248 0.0000 +vt 0.6153 0.1258 0.0000 +vt 0.6148 0.1258 0.0000 +vt 0.6148 0.1250 0.0000 +vt 0.6153 0.1250 0.0000 +vt 0.6153 0.1248 0.0000 +vt 0.6148 0.1248 0.0000 +vt 0.6148 0.1269 0.0000 +vt 0.6153 0.1269 0.0000 +vt 0.6000 0.1316 0.0000 +vt 0.6017 0.1316 0.0000 +vt 0.6022 0.1282 0.0000 +vt 0.6022 0.1324 0.0000 +vt 0.6000 0.1324 0.0000 +vt 0.6017 0.1241 0.0000 +vt 0.6000 0.1241 0.0000 +vt 0.6000 0.1234 0.0000 +vt 0.6022 0.1234 0.0000 +vt 0.6022 0.1275 0.0000 +vt 0.6017 0.1250 0.0000 +vt 0.6017 0.1258 0.0000 +vt 0.6022 0.1258 0.0000 +vt 0.6022 0.1250 0.0000 +vt 0.6017 0.1266 0.0000 +vt 0.6022 0.1266 0.0000 +vt 0.6017 0.1269 0.0000 +vt 0.6017 0.1266 0.0000 +vt 0.6022 0.1266 0.0000 +vt 0.6022 0.1269 0.0000 +vt 0.6017 0.1248 0.0000 +vt 0.6022 0.1248 0.0000 +vt 0.6017 0.1258 0.0000 +vt 0.6017 0.1250 0.0000 +vt 0.6022 0.1250 0.0000 +vt 0.6022 0.1258 0.0000 +vt 0.6017 0.1248 0.0000 +vt 0.6022 0.1248 0.0000 +vt 0.6017 0.1269 0.0000 +vt 0.6022 0.1269 0.0000 +# 839 texture coords + +g Conveyor +usemtl ShippingContainer +s off +f 3586/3590/132 3587/3591/132 3588/3592/132 3589/3593/132 +f 3590/3594/133 3591/3595/133 3592/3596/133 3593/3597/133 +f 3594/3598/134 3595/3599/134 3596/3600/134 3597/3601/134 +f 3598/3602/134 3599/3603/134 3600/3604/134 3601/3605/134 +f 3602/3606/132 3603/3607/132 3604/3608/132 3605/3609/132 +f 3606/3610/135 3607/3611/135 3608/3612/135 3590/3594/135 +f 3593/3597/136 3592/3596/136 3595/3599/136 3594/3598/136 +f 3597/3601/137 3596/3600/137 3587/3591/137 3586/3590/137 +f 3601/3605/137 3600/3604/137 3603/3607/137 3602/3606/137 +f 3609/3613/138 3610/3614/138 3611/3615/138 3612/3616/138 +f 3612/3616/139 3611/3615/139 3613/3617/139 3614/3618/139 +f 3615/3619/140 3616/3620/140 3617/3621/140 3618/3622/140 +f 3619/3623/141 3620/3624/141 3610/3614/141 3609/3613/141 +f 3621/3625/142 3622/3626/142 3623/3627/142 3624/3628/142 +f 3625/3629/143 3626/3630/143 3620/3624/143 3619/3623/143 +f 3614/3618/144 3613/3617/144 3627/3631/144 3628/3632/144 +f 3618/3622/145 3617/3621/145 3622/3626/145 3621/3625/145 +f 3628/3632/146 3627/3631/146 3616/3620/146 3615/3619/146 +f 3624/3628/147 3623/3627/147 3626/3630/147 3625/3629/147 +f 3626/3630/148 3623/3627/148 3605/3609/148 +f 3605/3609/136 3623/3627/136 3606/3610/136 +f 3623/3627/136 3622/3626/136 3606/3610/136 +f 3617/3621/149 3606/3610/149 3622/3626/149 +f 3616/3620/136 3606/3610/136 3617/3621/136 +f 3607/3611/136 3606/3610/136 3616/3620/136 3627/3631/136 +f 3609/3613/150 3612/3616/150 3599/3603/150 +f 3612/3616/150 3614/3618/150 3588/3592/150 3599/3603/150 +f 3615/3619/151 3618/3622/151 3589/3593/151 +f 3619/3623/150 3609/3613/150 3599/3603/150 +f 3621/3625/137 3624/3628/137 3598/3602/137 +f 3625/3629/137 3619/3623/137 3599/3603/137 3598/3602/137 +f 3614/3618/150 3628/3632/150 3588/3592/150 +f 3618/3622/151 3621/3625/151 3598/3602/151 3589/3593/151 +f 3628/3632/151 3615/3619/151 3589/3593/151 3588/3592/151 +f 3624/3628/137 3625/3629/137 3598/3602/137 +f 3607/3611/136 3627/3631/136 3613/3617/136 +f 3611/3615/136 3604/3608/136 3607/3611/136 +f 3607/3611/148 3613/3617/148 3611/3615/148 +f 3604/3608/152 3611/3615/152 3610/3614/152 +f 3620/3624/149 3626/3630/149 3605/3609/149 3604/3608/149 +f 3604/3608/149 3610/3614/149 3620/3624/149 +f 3629/3633/132 3630/3634/132 3631/3635/132 3632/3636/132 +f 3590/3594/153 3633/3637/153 3634/3638/153 3591/3595/153 +f 3635/3639/134 3636/3640/134 3637/3641/134 3638/3642/134 +f 3639/3643/134 3640/3644/134 3641/3645/134 3642/3646/134 +f 3643/3647/132 3644/3648/132 3645/3649/132 3646/3650/132 +f 3647/3651/154 3590/3594/154 3608/3612/154 3648/3652/154 +f 3633/3637/150 3635/3639/150 3638/3642/150 3634/3638/150 +f 3636/3640/152 3629/3633/152 3632/3636/152 3637/3641/152 +f 3640/3644/152 3643/3647/152 3646/3650/152 3641/3645/152 +f 3649/3653/138 3650/3654/138 3651/3655/138 3652/3656/138 +f 3650/3654/139 3653/3657/139 3654/3658/139 3651/3655/139 +f 3655/3659/140 3656/3660/140 3657/3661/140 3658/3662/140 +f 3659/3663/155 3649/3653/155 3652/3656/155 3660/3664/155 +f 3661/3665/142 3662/3666/142 3663/3667/142 3664/3668/142 +f 3665/3669/156 3659/3663/156 3660/3664/156 3666/3670/156 +f 3653/3657/144 3667/3671/144 3668/3672/144 3654/3658/144 +f 3656/3660/145 3661/3665/145 3664/3668/145 3657/3661/145 +f 3667/3671/146 3655/3659/146 3658/3662/146 3668/3672/146 +f 3662/3666/147 3665/3669/147 3666/3670/147 3663/3667/147 +f 3666/3670/151 3644/3648/151 3663/3667/151 +f 3644/3648/150 3647/3651/150 3663/3667/150 +f 3663/3667/150 3647/3651/150 3664/3668/150 +f 3657/3661/157 3664/3668/157 3647/3651/157 +f 3658/3662/150 3657/3661/150 3647/3651/150 +f 3648/3652/150 3668/3672/150 3658/3662/150 3647/3651/150 +f 3649/3653/136 3642/3646/136 3650/3654/136 +f 3650/3654/136 3642/3646/136 3631/3635/136 3653/3657/136 +f 3655/3659/148 3630/3634/148 3656/3660/148 +f 3659/3663/136 3642/3646/136 3649/3653/136 +f 3661/3665/152 3639/3643/152 3662/3666/152 +f 3665/3669/152 3639/3643/152 3642/3646/152 3659/3663/152 +f 3653/3657/136 3631/3635/136 3667/3671/136 +f 3656/3660/148 3630/3634/148 3639/3643/148 3661/3665/148 +f 3667/3671/148 3631/3635/148 3630/3634/148 3655/3659/148 +f 3662/3666/152 3639/3643/152 3665/3669/152 +f 3648/3652/150 3654/3658/150 3668/3672/150 +f 3651/3655/150 3648/3652/150 3645/3649/150 +f 3648/3652/151 3651/3655/151 3654/3658/151 +f 3645/3649/137 3652/3656/137 3651/3655/137 +f 3660/3664/157 3645/3649/157 3644/3648/157 3666/3670/157 +f 3645/3649/157 3660/3664/157 3652/3656/157 +f 3669/3673/158 3586/3590/158 3589/3593/158 3670/3674/158 +f 3671/3675/159 3672/3676/159 3593/3597/159 3673/3677/159 +f 3674/3678/143 3594/3598/143 3597/3601/143 3675/3679/143 +f 3676/3680/160 3598/3602/160 3601/3605/160 3677/3681/160 +f 3678/3682/146 3602/3606/146 3605/3609/146 3679/3683/146 +f 3680/3684/161 3606/3610/161 3681/3685/161 3671/3675/161 +f 3673/3677/136 3593/3597/136 3594/3598/136 3674/3678/136 +f 3675/3679/150 3597/3601/150 3586/3590/150 3669/3673/150 +f 3677/3681/150 3601/3605/150 3602/3606/150 3678/3682/150 +f 3682/3686/138 3683/3687/138 3684/3688/138 3685/3689/138 +f 3685/3689/139 3684/3688/139 3686/3690/139 3687/3691/139 +f 3688/3692/140 3689/3693/140 3690/3694/140 3691/3695/140 +f 3692/3696/141 3693/3697/141 3683/3687/141 3682/3686/141 +f 3694/3698/142 3695/3699/142 3696/3700/142 3697/3701/142 +f 3698/3702/143 3699/3703/143 3693/3697/143 3692/3696/143 +f 3687/3691/144 3686/3690/144 3700/3704/144 3701/3705/144 +f 3691/3695/145 3690/3694/145 3695/3699/145 3694/3698/145 +f 3701/3705/146 3700/3704/146 3689/3693/146 3688/3692/146 +f 3697/3701/147 3696/3700/147 3699/3703/147 3698/3702/147 +f 3699/3703/148 3696/3700/148 3679/3683/148 +f 3679/3683/136 3696/3700/136 3680/3684/136 +f 3696/3700/136 3695/3699/136 3680/3684/136 +f 3690/3694/149 3680/3684/149 3695/3699/149 +f 3689/3693/136 3680/3684/136 3690/3694/136 +f 3606/3610/136 3680/3684/136 3689/3693/136 3700/3704/136 +f 3682/3686/150 3685/3689/150 3598/3602/150 +f 3685/3689/157 3687/3691/157 3589/3593/157 3598/3602/157 +f 3688/3692/151 3691/3695/151 3670/3674/151 +f 3692/3696/150 3682/3686/150 3598/3602/150 +f 3694/3698/137 3697/3701/137 3676/3680/137 +f 3698/3702/137 3692/3696/137 3598/3602/137 3676/3680/137 +f 3687/3691/157 3701/3705/157 3589/3593/157 +f 3691/3695/151 3694/3698/151 3676/3680/151 3670/3674/151 +f 3701/3705/157 3688/3692/157 3670/3674/157 3589/3593/157 +f 3697/3701/137 3698/3702/137 3676/3680/137 +f 3606/3610/152 3700/3704/152 3686/3690/152 +f 3684/3688/152 3605/3609/152 3606/3610/152 +f 3606/3610/148 3686/3690/148 3684/3688/148 +f 3605/3609/152 3684/3688/152 3683/3687/152 +f 3693/3697/149 3699/3703/149 3679/3683/149 3605/3609/149 +f 3605/3609/149 3683/3687/149 3693/3697/149 +f 3702/3706/158 3703/3707/158 3630/3634/158 3629/3633/158 +f 3671/3675/162 3704/3708/162 3633/3637/162 3672/3676/162 +f 3705/3709/143 3706/3710/143 3636/3640/143 3635/3639/143 +f 3707/3711/160 3708/3712/160 3640/3644/160 3639/3643/160 +f 3709/3713/146 3710/3714/146 3644/3648/146 3643/3647/146 +f 3711/3715/163 3671/3675/163 3681/3685/163 3647/3651/163 +f 3704/3708/150 3705/3709/150 3635/3639/150 3633/3637/150 +f 3706/3710/136 3702/3706/136 3629/3633/136 3636/3640/136 +f 3708/3712/136 3709/3713/136 3643/3647/136 3640/3644/136 +f 3712/3716/164 3713/3717/164 3714/3718/164 3715/3719/164 +f 3713/3717/139 3716/3720/139 3717/3721/139 3714/3718/139 +f 3718/3722/140 3719/3723/140 3720/3724/140 3721/3725/140 +f 3722/3726/155 3712/3716/155 3715/3719/155 3723/3727/155 +f 3724/3728/142 3725/3729/142 3726/3730/142 3727/3731/142 +f 3728/3732/156 3722/3726/156 3723/3727/156 3729/3733/156 +f 3716/3720/144 3730/3734/144 3731/3735/144 3717/3721/144 +f 3719/3723/145 3724/3728/145 3727/3731/145 3720/3724/145 +f 3730/3734/146 3718/3722/146 3721/3725/146 3731/3735/146 +f 3725/3729/147 3728/3732/147 3729/3733/147 3726/3730/147 +f 3729/3733/151 3710/3714/151 3726/3730/151 +f 3710/3714/150 3711/3715/150 3726/3730/150 +f 3726/3730/150 3711/3715/150 3727/3731/150 +f 3720/3724/157 3727/3731/157 3711/3715/157 +f 3721/3725/150 3720/3724/150 3711/3715/150 +f 3647/3651/150 3731/3735/150 3721/3725/150 3711/3715/150 +f 3712/3716/136 3639/3643/136 3713/3717/136 +f 3713/3717/149 3639/3643/149 3630/3634/149 3716/3720/149 +f 3718/3722/148 3703/3707/148 3719/3723/148 +f 3722/3726/136 3639/3643/136 3712/3716/136 +f 3724/3728/152 3707/3711/152 3725/3729/152 +f 3728/3732/152 3707/3711/152 3639/3643/152 3722/3726/152 +f 3716/3720/149 3630/3634/149 3730/3734/149 +f 3719/3723/148 3703/3707/148 3707/3711/148 3724/3728/148 +f 3730/3734/149 3630/3634/149 3703/3707/149 3718/3722/149 +f 3725/3729/152 3707/3711/152 3728/3732/152 +f 3647/3651/137 3717/3721/137 3731/3735/137 +f 3714/3718/137 3647/3651/137 3644/3648/137 +f 3647/3651/151 3714/3718/151 3717/3721/151 +f 3644/3648/137 3715/3719/137 3714/3718/137 +f 3723/3727/157 3644/3648/157 3710/3714/157 3729/3733/157 +f 3644/3648/157 3723/3727/157 3715/3719/157 +f 3732/3736/146 3669/3673/146 3670/3674/146 3733/3737/146 +f 3734/3738/159 3735/3739/159 3673/3677/159 3736/3740/159 +f 3737/3741/160 3674/3678/160 3675/3679/160 3738/3742/160 +f 3739/3743/160 3676/3680/160 3677/3681/160 3740/3744/160 +f 3741/3745/146 3678/3682/146 3679/3683/146 3742/3746/146 +f 3743/3747/161 3680/3684/161 3744/3748/161 3734/3738/161 +f 3736/3740/136 3673/3677/136 3674/3678/136 3737/3741/136 +f 3738/3742/150 3675/3679/150 3669/3673/150 3732/3736/150 +f 3740/3744/150 3677/3681/150 3678/3682/150 3741/3745/150 +f 3745/3749/138 3746/3750/138 3747/3751/138 3748/3752/138 +f 3748/3752/139 3747/3751/139 3749/3753/139 3750/3754/139 +f 3751/3755/140 3752/3756/140 3753/3757/140 3754/3758/140 +f 3755/3759/141 3756/3760/141 3746/3750/141 3745/3749/141 +f 3757/3761/142 3758/3762/142 3759/3763/142 3760/3764/142 +f 3761/3765/143 3762/3766/143 3756/3760/143 3755/3759/143 +f 3750/3754/144 3749/3753/144 3763/3767/144 3764/3768/144 +f 3754/3758/145 3753/3757/145 3758/3762/145 3757/3761/145 +f 3764/3768/146 3763/3767/146 3752/3756/146 3751/3755/146 +f 3760/3764/147 3759/3763/147 3762/3766/147 3761/3765/147 +f 3762/3766/148 3759/3763/148 3742/3746/148 +f 3742/3746/136 3759/3763/136 3743/3747/136 +f 3759/3763/136 3758/3762/136 3743/3747/136 +f 3753/3757/149 3743/3747/149 3758/3762/149 +f 3752/3756/136 3743/3747/136 3753/3757/136 +f 3680/3684/152 3743/3747/152 3752/3756/152 3763/3767/152 +f 3745/3749/150 3748/3752/150 3676/3680/150 +f 3748/3752/157 3750/3754/157 3670/3674/157 3676/3680/157 +f 3751/3755/151 3754/3758/151 3733/3737/151 +f 3755/3759/150 3745/3749/150 3676/3680/150 +f 3757/3761/137 3760/3764/137 3739/3743/137 +f 3761/3765/137 3755/3759/137 3676/3680/137 3739/3743/137 +f 3750/3754/157 3764/3768/157 3670/3674/157 +f 3754/3758/151 3757/3761/151 3739/3743/151 3733/3737/151 +f 3764/3768/157 3751/3755/157 3733/3737/157 3670/3674/157 +f 3760/3764/137 3761/3765/137 3739/3743/137 +f 3680/3684/152 3763/3767/152 3749/3753/152 +f 3747/3751/152 3679/3683/152 3680/3684/152 +f 3680/3684/148 3749/3753/148 3747/3751/148 +f 3679/3683/152 3747/3751/152 3746/3750/152 +f 3756/3760/149 3762/3766/149 3742/3746/149 3679/3683/149 +f 3679/3683/149 3746/3750/149 3756/3760/149 +f 3765/3769/146 3766/3770/146 3703/3707/146 3702/3706/146 +f 3734/3738/162 3767/3771/162 3704/3708/162 3735/3739/162 +f 3768/3772/160 3769/3773/160 3706/3710/160 3705/3709/160 +f 3770/3774/160 3771/3775/160 3708/3712/160 3707/3711/160 +f 3772/3776/146 3773/3777/146 3710/3714/146 3709/3713/146 +f 3774/3778/163 3734/3738/163 3744/3748/163 3711/3715/163 +f 3767/3771/150 3768/3772/150 3705/3709/150 3704/3708/150 +f 3769/3773/136 3765/3769/136 3702/3706/136 3706/3710/136 +f 3771/3775/136 3772/3776/136 3709/3713/136 3708/3712/136 +f 3775/3779/138 3776/3780/138 3777/3781/138 3778/3782/138 +f 3776/3780/139 3779/3783/139 3780/3784/139 3777/3781/139 +f 3781/3785/140 3782/3786/140 3783/3787/140 3784/3788/140 +f 3785/3789/155 3775/3779/155 3778/3782/155 3786/3790/155 +f 3787/3791/142 3788/3792/142 3789/3793/142 3790/3794/142 +f 3791/3795/156 3785/3789/156 3786/3790/156 3792/3796/156 +f 3779/3783/144 3793/3797/144 3794/3798/144 3780/3784/144 +f 3782/3786/145 3787/3791/145 3790/3794/145 3783/3787/145 +f 3793/3797/146 3781/3785/146 3784/3788/146 3794/3798/146 +f 3788/3792/147 3791/3795/147 3792/3796/147 3789/3793/147 +f 3792/3796/151 3773/3777/151 3789/3793/151 +f 3773/3777/150 3774/3778/150 3789/3793/150 +f 3789/3793/150 3774/3778/150 3790/3794/150 +f 3783/3787/157 3790/3794/157 3774/3778/157 +f 3784/3788/150 3783/3787/150 3774/3778/150 +f 3711/3715/137 3794/3798/137 3784/3788/137 3774/3778/137 +f 3775/3779/136 3707/3711/136 3776/3780/136 +f 3776/3780/149 3707/3711/149 3703/3707/149 3779/3783/149 +f 3781/3785/148 3766/3770/148 3782/3786/148 +f 3785/3789/136 3707/3711/136 3775/3779/136 +f 3787/3791/152 3770/3774/152 3788/3792/152 +f 3791/3795/152 3770/3774/152 3707/3711/152 3785/3789/152 +f 3779/3783/149 3703/3707/149 3793/3797/149 +f 3782/3786/148 3766/3770/148 3770/3774/148 3787/3791/148 +f 3793/3797/149 3703/3707/149 3766/3770/149 3781/3785/149 +f 3788/3792/152 3770/3774/152 3791/3795/152 +f 3711/3715/137 3780/3784/137 3794/3798/137 +f 3777/3781/137 3711/3715/137 3710/3714/137 +f 3711/3715/151 3777/3781/151 3780/3784/151 +f 3710/3714/137 3778/3782/137 3777/3781/137 +f 3786/3790/157 3710/3714/157 3773/3777/157 3792/3796/157 +f 3710/3714/157 3786/3790/157 3778/3782/157 +f 3795/3799/158 3732/3736/158 3733/3737/158 3796/3800/158 +f 3797/3801/159 3798/3802/159 3736/3740/159 3799/3803/159 +f 3800/3804/160 3737/3741/160 3738/3742/160 3801/3805/160 +f 3802/3806/160 3739/3743/160 3740/3744/160 3803/3807/160 +f 3804/3808/146 3741/3745/146 3742/3746/146 3805/3809/146 +f 3806/3810/161 3743/3747/161 3807/3811/161 3797/3801/161 +f 3799/3803/136 3736/3740/136 3737/3741/136 3800/3804/136 +f 3801/3805/150 3738/3742/150 3732/3736/150 3795/3799/150 +f 3803/3807/150 3740/3744/150 3741/3745/150 3804/3808/150 +f 3808/3812/138 3809/3813/138 3810/3814/138 3811/3815/138 +f 3811/3815/139 3810/3814/139 3812/3816/139 3813/3817/139 +f 3814/3818/140 3815/3819/140 3816/3820/140 3817/3821/140 +f 3818/3822/141 3819/3823/141 3809/3813/141 3808/3812/141 +f 3820/3824/142 3821/3825/142 3822/3826/142 3823/3827/142 +f 3824/3828/143 3825/3829/143 3819/3823/143 3818/3822/143 +f 3813/3817/144 3812/3816/144 3826/3830/144 3827/3831/144 +f 3817/3821/145 3816/3820/145 3821/3825/145 3820/3824/145 +f 3827/3831/146 3826/3830/146 3815/3819/146 3814/3818/146 +f 3823/3827/147 3822/3826/147 3825/3829/147 3824/3828/147 +f 3825/3829/148 3822/3826/148 3805/3809/148 +f 3805/3809/136 3822/3826/136 3806/3810/136 +f 3822/3826/136 3821/3825/136 3806/3810/136 +f 3816/3820/149 3806/3810/149 3821/3825/149 +f 3815/3819/136 3806/3810/136 3816/3820/136 +f 3743/3747/152 3806/3810/152 3815/3819/152 3826/3830/152 +f 3808/3812/150 3811/3815/150 3739/3743/150 +f 3811/3815/157 3813/3817/157 3733/3737/157 3739/3743/157 +f 3814/3818/151 3817/3821/151 3796/3800/151 +f 3818/3822/150 3808/3812/150 3739/3743/150 +f 3820/3824/137 3823/3827/137 3802/3806/137 +f 3824/3828/137 3818/3822/137 3739/3743/137 3802/3806/137 +f 3813/3817/157 3827/3831/157 3733/3737/157 +f 3817/3821/151 3820/3824/151 3802/3806/151 3796/3800/151 +f 3827/3831/157 3814/3818/157 3796/3800/157 3733/3737/157 +f 3823/3827/137 3824/3828/137 3802/3806/137 +f 3743/3747/152 3826/3830/152 3812/3816/152 +f 3810/3814/152 3742/3746/152 3743/3747/152 +f 3743/3747/148 3812/3816/148 3810/3814/148 +f 3742/3746/152 3810/3814/152 3809/3813/152 +f 3819/3823/149 3825/3829/149 3805/3809/149 3742/3746/149 +f 3742/3746/149 3809/3813/149 3819/3823/149 +f 3828/3832/158 3829/3833/158 3766/3770/158 3765/3769/158 +f 3797/3801/162 3830/3834/162 3767/3771/162 3798/3802/162 +f 3831/3835/160 3832/3836/160 3769/3773/160 3768/3772/160 +f 3833/3837/160 3834/3838/160 3771/3775/160 3770/3774/160 +f 3835/3839/146 3836/3840/146 3773/3777/146 3772/3776/146 +f 3837/3841/163 3797/3801/163 3807/3811/163 3774/3778/163 +f 3830/3834/150 3831/3835/150 3768/3772/150 3767/3771/150 +f 3832/3836/136 3828/3832/136 3765/3769/136 3769/3773/136 +f 3834/3838/136 3835/3839/136 3772/3776/136 3771/3775/136 +f 3838/3842/138 3839/3843/138 3840/3844/138 3841/3845/138 +f 3839/3843/139 3842/3846/139 3843/3847/139 3840/3844/139 +f 3844/3848/140 3845/3849/140 3846/3850/140 3847/3851/140 +f 3848/3852/155 3838/3842/155 3841/3845/155 3849/3853/155 +f 3850/3854/142 3851/3855/142 3852/3856/142 3853/3857/142 +f 3854/3858/156 3848/3852/156 3849/3853/156 3855/3859/156 +f 3842/3846/144 3856/3860/144 3857/3861/144 3843/3847/144 +f 3845/3849/145 3850/3854/145 3853/3857/145 3846/3850/145 +f 3856/3860/146 3844/3848/146 3847/3851/146 3857/3861/146 +f 3851/3855/147 3854/3858/147 3855/3859/147 3852/3856/147 +f 3855/3859/151 3836/3840/151 3852/3856/151 +f 3836/3840/150 3837/3841/150 3852/3856/150 +f 3852/3856/150 3837/3841/150 3853/3857/150 +f 3846/3850/157 3853/3857/157 3837/3841/157 +f 3847/3851/150 3846/3850/150 3837/3841/150 +f 3774/3778/137 3857/3861/137 3847/3851/137 3837/3841/137 +f 3838/3842/136 3770/3774/136 3839/3843/136 +f 3839/3843/149 3770/3774/149 3766/3770/149 3842/3846/149 +f 3844/3848/148 3829/3833/148 3845/3849/148 +f 3848/3852/136 3770/3774/136 3838/3842/136 +f 3850/3854/152 3833/3837/152 3851/3855/152 +f 3854/3858/152 3833/3837/152 3770/3774/152 3848/3852/152 +f 3842/3846/149 3766/3770/149 3856/3860/149 +f 3845/3849/148 3829/3833/148 3833/3837/148 3850/3854/148 +f 3856/3860/149 3766/3770/149 3829/3833/149 3844/3848/149 +f 3851/3855/152 3833/3837/152 3854/3858/152 +f 3774/3778/137 3843/3847/137 3857/3861/137 +f 3840/3844/137 3774/3778/137 3773/3777/137 +f 3774/3778/151 3840/3844/151 3843/3847/151 +f 3773/3777/137 3841/3845/137 3840/3844/137 +f 3849/3853/157 3773/3777/157 3836/3840/157 3855/3859/157 +f 3773/3777/157 3849/3853/157 3841/3845/157 +f 3858/3862/146 3795/3799/146 3796/3800/146 3859/3863/146 +f 3860/3864/159 3861/3865/159 3799/3803/159 3862/3866/159 +f 3863/3867/143 3800/3804/143 3801/3805/143 3864/3868/143 +f 3865/3869/160 3802/3806/160 3803/3807/160 3866/3870/160 +f 3867/3871/146 3804/3808/146 3805/3809/146 3868/3872/146 +f 3869/3873/161 3806/3810/161 3870/3874/161 3860/3864/161 +f 3862/3866/136 3799/3803/136 3800/3804/136 3863/3867/136 +f 3864/3868/150 3801/3805/150 3795/3799/150 3858/3862/150 +f 3866/3870/150 3803/3807/150 3804/3808/150 3867/3871/150 +f 3871/3875/138 3872/3876/138 3873/3877/138 3874/3878/138 +f 3874/3878/139 3873/3877/139 3875/3879/139 3876/3880/139 +f 3877/3881/140 3878/3882/140 3879/3883/140 3880/3884/140 +f 3881/3885/141 3882/3886/141 3872/3876/141 3871/3875/141 +f 3883/3887/142 3884/3888/142 3885/3889/142 3886/3890/142 +f 3887/3891/143 3888/3892/143 3882/3886/143 3881/3885/143 +f 3876/3880/144 3875/3879/144 3889/3893/144 3890/3894/144 +f 3880/3884/145 3879/3883/145 3884/3888/145 3883/3887/145 +f 3890/3894/146 3889/3893/146 3878/3882/146 3877/3881/146 +f 3886/3890/147 3885/3889/147 3888/3892/147 3887/3891/147 +f 3888/3892/148 3885/3889/148 3868/3872/148 +f 3868/3872/136 3885/3889/136 3869/3873/136 +f 3885/3889/136 3884/3888/136 3869/3873/136 +f 3879/3883/149 3869/3873/149 3884/3888/149 +f 3878/3882/136 3869/3873/136 3879/3883/136 +f 3806/3810/136 3869/3873/136 3878/3882/136 3889/3893/136 +f 3871/3875/150 3874/3878/150 3802/3806/150 +f 3874/3878/157 3876/3880/157 3796/3800/157 3802/3806/157 +f 3877/3881/151 3880/3884/151 3859/3863/151 +f 3881/3885/150 3871/3875/150 3802/3806/150 +f 3883/3887/137 3886/3890/137 3865/3869/137 +f 3887/3891/137 3881/3885/137 3802/3806/137 3865/3869/137 +f 3876/3880/157 3890/3894/157 3796/3800/157 +f 3880/3884/151 3883/3887/151 3865/3869/151 3859/3863/151 +f 3890/3894/157 3877/3881/157 3859/3863/157 3796/3800/157 +f 3886/3890/137 3887/3891/137 3865/3869/137 +f 3806/3810/152 3889/3893/152 3875/3879/152 +f 3873/3877/148 3805/3809/148 3806/3810/148 +f 3806/3810/148 3875/3879/148 3873/3877/148 +f 3805/3809/152 3873/3877/152 3872/3876/152 +f 3882/3886/149 3888/3892/149 3868/3872/149 3805/3809/149 +f 3805/3809/149 3872/3876/149 3882/3886/149 +f 3891/3895/146 3892/3896/146 3829/3833/146 3828/3832/146 +f 3860/3864/162 3893/3897/162 3830/3834/162 3861/3865/162 +f 3894/3898/143 3895/3899/143 3832/3836/143 3831/3835/143 +f 3896/3900/160 3897/3901/160 3834/3838/160 3833/3837/160 +f 3898/3902/146 3899/3903/146 3836/3840/146 3835/3839/146 +f 3900/3904/163 3860/3864/163 3870/3874/163 3837/3841/163 +f 3893/3897/150 3894/3898/150 3831/3835/150 3830/3834/150 +f 3895/3899/136 3891/3895/136 3828/3832/136 3832/3836/136 +f 3897/3901/136 3898/3902/136 3835/3839/136 3834/3838/136 +f 3901/3905/164 3902/3906/164 3903/3907/164 3904/3908/164 +f 3902/3906/139 3905/3909/139 3906/3910/139 3903/3907/139 +f 3907/3911/140 3908/3912/140 3909/3913/140 3910/3914/140 +f 3911/3915/155 3901/3905/155 3904/3908/155 3912/3916/155 +f 3913/3917/142 3914/3918/142 3915/3919/142 3916/3920/142 +f 3917/3921/156 3911/3915/156 3912/3916/156 3918/3922/156 +f 3905/3909/144 3919/3923/144 3920/3924/144 3906/3910/144 +f 3908/3912/145 3913/3917/145 3916/3920/145 3909/3913/145 +f 3919/3923/146 3907/3911/146 3910/3914/146 3920/3924/146 +f 3914/3918/147 3917/3921/147 3918/3922/147 3915/3919/147 +f 3918/3922/151 3899/3903/151 3915/3919/151 +f 3899/3903/150 3900/3904/150 3915/3919/150 +f 3915/3919/150 3900/3904/150 3916/3920/150 +f 3909/3913/157 3916/3920/157 3900/3904/157 +f 3910/3914/150 3909/3913/150 3900/3904/150 +f 3837/3841/150 3920/3924/150 3910/3914/150 3900/3904/150 +f 3901/3905/136 3833/3837/136 3902/3906/136 +f 3902/3906/149 3833/3837/149 3829/3833/149 3905/3909/149 +f 3907/3911/148 3892/3896/148 3908/3912/148 +f 3911/3915/136 3833/3837/136 3901/3905/136 +f 3913/3917/152 3896/3900/152 3914/3918/152 +f 3917/3921/152 3896/3900/152 3833/3837/152 3911/3915/152 +f 3905/3909/149 3829/3833/149 3919/3923/149 +f 3908/3912/148 3892/3896/148 3896/3900/148 3913/3917/148 +f 3919/3923/149 3829/3833/149 3892/3896/149 3907/3911/149 +f 3914/3918/152 3896/3900/152 3917/3921/152 +f 3837/3841/137 3906/3910/137 3920/3924/137 +f 3903/3907/151 3837/3841/151 3836/3840/151 +f 3837/3841/151 3903/3907/151 3906/3910/151 +f 3836/3840/137 3904/3908/137 3903/3907/137 +f 3912/3916/157 3836/3840/157 3899/3903/157 3918/3922/157 +f 3836/3840/157 3912/3916/157 3904/3908/157 +f 3921/3925/146 3858/3862/146 3859/3863/146 3922/3926/146 +f 3923/3927/159 3924/3928/159 3862/3866/159 3925/3929/159 +f 3926/3930/160 3863/3867/160 3864/3868/160 3927/3931/160 +f 3928/3932/160 3865/3869/160 3866/3870/160 3929/3933/160 +f 3930/3934/158 3867/3871/158 3868/3872/158 3931/3935/158 +f 3932/3936/161 3869/3873/161 3933/3937/161 3923/3927/161 +f 3925/3929/136 3862/3866/136 3863/3867/136 3926/3930/136 +f 3927/3931/150 3864/3868/150 3858/3862/150 3921/3925/150 +f 3929/3933/150 3866/3870/150 3867/3871/150 3930/3934/150 +f 3934/3938/138 3935/3939/138 3936/3940/138 3937/3941/138 +f 3937/3941/139 3936/3940/139 3938/3942/139 3939/3943/139 +f 3940/3944/140 3941/3945/140 3942/3946/140 3943/3947/140 +f 3944/3948/141 3945/3949/141 3935/3939/141 3934/3938/141 +f 3946/3950/142 3947/3951/142 3948/3952/142 3949/3953/142 +f 3950/3954/143 3951/3955/143 3945/3949/143 3944/3948/143 +f 3939/3943/144 3938/3942/144 3952/3956/144 3953/3957/144 +f 3943/3947/145 3942/3946/145 3947/3951/145 3946/3950/145 +f 3953/3957/146 3952/3956/146 3941/3945/146 3940/3944/146 +f 3949/3953/147 3948/3952/147 3951/3955/147 3950/3954/147 +f 3951/3955/148 3948/3952/148 3931/3935/148 +f 3931/3935/136 3948/3952/136 3932/3936/136 +f 3948/3952/136 3947/3951/136 3932/3936/136 +f 3942/3946/149 3932/3936/149 3947/3951/149 +f 3941/3945/136 3932/3936/136 3942/3946/136 +f 3869/3873/152 3932/3936/152 3941/3945/152 3952/3956/152 +f 3934/3938/150 3937/3941/150 3865/3869/150 +f 3937/3941/157 3939/3943/157 3859/3863/157 3865/3869/157 +f 3940/3944/151 3943/3947/151 3922/3926/151 +f 3944/3948/150 3934/3938/150 3865/3869/150 +f 3946/3950/137 3949/3953/137 3928/3932/137 +f 3950/3954/137 3944/3948/137 3865/3869/137 3928/3932/137 +f 3939/3943/157 3953/3957/157 3859/3863/157 +f 3943/3947/151 3946/3950/151 3928/3932/151 3922/3926/151 +f 3953/3957/157 3940/3944/157 3922/3926/157 3859/3863/157 +f 3949/3953/137 3950/3954/137 3928/3932/137 +f 3869/3873/152 3952/3956/152 3938/3942/152 +f 3936/3940/148 3868/3872/148 3869/3873/148 +f 3869/3873/148 3938/3942/148 3936/3940/148 +f 3868/3872/152 3936/3940/152 3935/3939/152 +f 3945/3949/149 3951/3955/149 3931/3935/149 3868/3872/149 +f 3868/3872/149 3935/3939/149 3945/3949/149 +f 3954/3958/146 3955/3959/146 3892/3896/146 3891/3895/146 +f 3923/3927/162 3956/3960/162 3893/3897/162 3924/3928/162 +f 3957/3961/160 3958/3962/160 3895/3899/160 3894/3898/160 +f 3959/3963/160 3960/3964/160 3897/3901/160 3896/3900/160 +f 3961/3965/158 3962/3966/158 3899/3903/158 3898/3902/158 +f 3963/3967/163 3923/3927/163 3933/3937/163 3900/3904/163 +f 3956/3960/150 3957/3961/150 3894/3898/150 3893/3897/150 +f 3958/3962/136 3954/3958/136 3891/3895/136 3895/3899/136 +f 3960/3964/136 3961/3965/136 3898/3902/136 3897/3901/136 +f 3964/3968/164 3965/3969/164 3966/3970/164 3967/3971/164 +f 3965/3969/139 3968/3972/139 3969/3973/139 3966/3970/139 +f 3970/3974/140 3971/3975/140 3972/3976/140 3973/3977/140 +f 3974/3978/155 3964/3968/155 3967/3971/155 3975/3979/155 +f 3976/3980/142 3977/3981/142 3978/3982/142 3979/3983/142 +f 3980/3984/156 3974/3978/156 3975/3979/156 3981/3985/156 +f 3968/3972/144 3982/3986/144 3983/3987/144 3969/3973/144 +f 3971/3975/145 3976/3980/145 3979/3983/145 3972/3976/145 +f 3982/3986/146 3970/3974/146 3973/3977/146 3983/3987/146 +f 3977/3981/147 3980/3984/147 3981/3985/147 3978/3982/147 +f 3981/3985/151 3962/3966/151 3978/3982/151 +f 3962/3966/150 3963/3967/150 3978/3982/150 +f 3978/3982/150 3963/3967/150 3979/3983/150 +f 3972/3976/157 3979/3983/157 3963/3967/157 +f 3973/3977/150 3972/3976/150 3963/3967/150 +f 3900/3904/137 3983/3987/137 3973/3977/137 3963/3967/137 +f 3964/3968/136 3896/3900/136 3965/3969/136 +f 3965/3969/149 3896/3900/149 3892/3896/149 3968/3972/149 +f 3970/3974/148 3955/3959/148 3971/3975/148 +f 3974/3978/136 3896/3900/136 3964/3968/136 +f 3976/3980/152 3959/3963/152 3977/3981/152 +f 3980/3984/152 3959/3963/152 3896/3900/152 3974/3978/152 +f 3968/3972/149 3892/3896/149 3982/3986/149 +f 3971/3975/148 3955/3959/148 3959/3963/148 3976/3980/148 +f 3982/3986/149 3892/3896/149 3955/3959/149 3970/3974/149 +f 3977/3981/152 3959/3963/152 3980/3984/152 +f 3900/3904/137 3969/3973/137 3983/3987/137 +f 3966/3970/151 3900/3904/151 3899/3903/151 +f 3900/3904/151 3966/3970/151 3969/3973/151 +f 3899/3903/137 3967/3971/137 3966/3970/137 +f 3975/3979/157 3899/3903/157 3962/3966/157 3981/3985/157 +f 3899/3903/157 3975/3979/157 3967/3971/157 +f 3984/3988/158 3921/3925/158 3922/3926/158 3985/3989/158 +f 3986/3990/159 3987/3991/159 3925/3929/159 3988/3992/159 +f 3989/3993/143 3926/3930/143 3927/3931/143 3990/3994/143 +f 3991/3995/160 3928/3932/160 3929/3933/160 3992/3996/160 +f 3993/3997/146 3930/3934/146 3931/3935/146 3994/3998/146 +f 3995/3999/161 3932/3936/161 3996/4000/161 3986/3990/161 +f 3988/3992/136 3925/3929/136 3926/3930/136 3989/3993/136 +f 3990/3994/150 3927/3931/150 3921/3925/150 3984/3988/150 +f 3992/3996/150 3929/3933/150 3930/3934/150 3993/3997/150 +f 3997/4001/138 3998/4002/138 3999/4003/138 4000/4004/138 +f 4000/4004/139 3999/4003/139 4001/4005/139 4002/4006/139 +f 4003/4007/140 4004/4008/140 4005/4009/140 4006/4010/140 +f 4007/4011/141 4008/4012/141 3998/4002/141 3997/4001/141 +f 4009/4013/142 4010/4014/142 4011/4015/142 4012/4016/142 +f 4013/4017/143 4014/4018/143 4008/4012/143 4007/4011/143 +f 4002/4006/144 4001/4005/144 4015/4019/144 4016/4020/144 +f 4006/4010/145 4005/4009/145 4010/4014/145 4009/4013/145 +f 4016/4020/146 4015/4019/146 4004/4008/146 4003/4007/146 +f 4012/4016/147 4011/4015/147 4014/4018/147 4013/4017/147 +f 4014/4018/148 4011/4015/148 3994/3998/148 +f 3994/3998/136 4011/4015/136 3995/3999/136 +f 4011/4015/136 4010/4014/136 3995/3999/136 +f 4005/4009/149 3995/3999/149 4010/4014/149 +f 4004/4008/136 3995/3999/136 4005/4009/136 +f 3932/3936/136 3995/3999/136 4004/4008/136 4015/4019/136 +f 3997/4001/150 4000/4004/150 3928/3932/150 +f 4000/4004/157 4002/4006/157 3922/3926/157 3928/3932/157 +f 4003/4007/151 4006/4010/151 3985/3989/151 +f 4007/4011/150 3997/4001/150 3928/3932/150 +f 4009/4013/137 4012/4016/137 3991/3995/137 +f 4013/4017/137 4007/4011/137 3928/3932/137 3991/3995/137 +f 4002/4006/157 4016/4020/157 3922/3926/157 +f 4006/4010/151 4009/4013/151 3991/3995/151 3985/3989/151 +f 4016/4020/151 4003/4007/151 3985/3989/151 3922/3926/151 +f 4012/4016/137 4013/4017/137 3991/3995/137 +f 3932/3936/152 4015/4019/152 4001/4005/152 +f 3999/4003/152 3931/3935/152 3932/3936/152 +f 3932/3936/148 4001/4005/148 3999/4003/148 +f 3931/3935/152 3999/4003/152 3998/4002/152 +f 4008/4012/149 4014/4018/149 3994/3998/149 3931/3935/149 +f 3931/3935/149 3998/4002/149 4008/4012/149 +f 4017/4021/158 4018/4022/158 3955/3959/158 3954/3958/158 +f 3986/3990/162 4019/4023/162 3956/3960/162 3987/3991/162 +f 4020/4024/143 4021/4025/143 3958/3962/143 3957/3961/143 +f 4022/4026/160 4023/4027/160 3960/3964/160 3959/3963/160 +f 4024/4028/146 4025/4029/146 3962/3966/146 3961/3965/146 +f 4026/4030/163 3986/3990/163 3996/4000/163 3963/3967/163 +f 4019/4023/150 4020/4024/150 3957/3961/150 3956/3960/150 +f 4021/4025/136 4017/4021/136 3954/3958/136 3958/3962/136 +f 4023/4027/136 4024/4028/136 3961/3965/136 3960/3964/136 +f 4027/4031/164 4028/4032/164 4029/4033/164 4030/4034/164 +f 4028/4032/139 4031/4035/139 4032/4036/139 4029/4033/139 +f 4033/4037/140 4034/4038/140 4035/4039/140 4036/4040/140 +f 4037/4041/155 4027/4031/155 4030/4034/155 4038/4042/155 +f 4039/4043/142 4040/4044/142 4041/4045/142 4042/4046/142 +f 4043/4047/156 4037/4041/156 4038/4042/156 4044/4048/156 +f 4031/4035/144 4045/4049/144 4046/4050/144 4032/4036/144 +f 4034/4038/145 4039/4043/145 4042/4046/145 4035/4039/145 +f 4045/4049/146 4033/4037/146 4036/4040/146 4046/4050/146 +f 4040/4044/147 4043/4047/147 4044/4048/147 4041/4045/147 +f 4044/4048/151 4025/4029/151 4041/4045/151 +f 4025/4029/150 4026/4030/150 4041/4045/150 +f 4041/4045/150 4026/4030/150 4042/4046/150 +f 4035/4039/157 4042/4046/157 4026/4030/157 +f 4036/4040/150 4035/4039/150 4026/4030/150 +f 3963/3967/150 4046/4050/150 4036/4040/150 4026/4030/150 +f 4027/4031/136 3959/3963/136 4028/4032/136 +f 4028/4032/149 3959/3963/149 3955/3959/149 4031/4035/149 +f 4033/4037/148 4018/4022/148 4034/4038/148 +f 4037/4041/136 3959/3963/136 4027/4031/136 +f 4039/4043/152 4022/4026/152 4040/4044/152 +f 4043/4047/152 4022/4026/152 3959/3963/152 4037/4041/152 +f 4031/4035/149 3955/3959/149 4045/4049/149 +f 4034/4038/148 4018/4022/148 4022/4026/148 4039/4043/148 +f 4045/4049/148 3955/3959/148 4018/4022/148 4033/4037/148 +f 4040/4044/152 4022/4026/152 4043/4047/152 +f 3963/3967/137 4032/4036/137 4046/4050/137 +f 4029/4033/137 3963/3967/137 3962/3966/137 +f 3963/3967/151 4029/4033/151 4032/4036/151 +f 3962/3966/137 4030/4034/137 4029/4033/137 +f 4038/4042/157 3962/3966/157 4025/4029/157 4044/4048/157 +f 3962/3966/157 4038/4042/157 4030/4034/157 +f 4047/4051/146 3984/3988/146 3985/3989/146 4048/4052/146 +f 4049/4053/159 4050/4054/159 3988/3992/159 4051/4055/159 +f 4052/4056/160 3989/3993/160 3990/3994/160 4053/4057/160 +f 4054/4058/160 3991/3995/160 3992/3996/160 4055/4059/160 +f 4056/4060/146 3993/3997/146 3994/3998/146 4057/4061/146 +f 4058/4062/161 3995/3999/161 4059/4063/161 4049/4053/161 +f 4051/4055/136 3988/3992/136 3989/3993/136 4052/4056/136 +f 4053/4057/150 3990/3994/150 3984/3988/150 4047/4051/150 +f 4055/4059/150 3992/3996/150 3993/3997/150 4056/4060/150 +f 4060/4064/138 4061/4065/138 4062/4066/138 4063/4067/138 +f 4063/4067/139 4062/4066/139 4064/4068/139 4065/4069/139 +f 4066/4070/140 4067/4071/140 4068/4072/140 4069/4073/140 +f 4070/4074/155 4071/4075/155 4061/4065/155 4060/4064/155 +f 4072/4076/142 4073/4077/142 4074/4078/142 4075/4079/142 +f 4076/4080/143 4077/4081/143 4071/4075/143 4070/4074/143 +f 4065/4069/144 4064/4068/144 4078/4082/144 4079/4083/144 +f 4069/4073/145 4068/4072/145 4073/4077/145 4072/4076/145 +f 4079/4083/146 4078/4082/146 4067/4071/146 4066/4070/146 +f 4075/4079/147 4074/4078/147 4077/4081/147 4076/4080/147 +f 4077/4081/148 4074/4078/148 4057/4061/148 +f 4057/4061/136 4074/4078/136 4058/4062/136 +f 4074/4078/136 4073/4077/136 4058/4062/136 +f 4068/4072/149 4058/4062/149 4073/4077/149 +f 4067/4071/136 4058/4062/136 4068/4072/136 +f 3995/3999/136 4058/4062/136 4067/4071/136 4078/4082/136 +f 4060/4064/150 4063/4067/150 3991/3995/150 +f 4063/4067/157 4065/4069/157 3985/3989/157 3991/3995/157 +f 4066/4070/151 4069/4073/151 4048/4052/151 +f 4070/4074/150 4060/4064/150 3991/3995/150 +f 4072/4076/137 4075/4079/137 4054/4058/137 +f 4076/4080/137 4070/4074/137 3991/3995/137 4054/4058/137 +f 4065/4069/157 4079/4083/157 3985/3989/157 +f 4069/4073/151 4072/4076/151 4054/4058/151 4048/4052/151 +f 4079/4083/157 4066/4070/157 4048/4052/157 3985/3989/157 +f 4075/4079/137 4076/4080/137 4054/4058/137 +f 3995/3999/152 4078/4082/152 4064/4068/152 +f 4062/4066/152 3994/3998/152 3995/3999/152 +f 3995/3999/148 4064/4068/148 4062/4066/148 +f 3994/3998/152 4062/4066/152 4061/4065/152 +f 4071/4075/149 4077/4081/149 4057/4061/149 3994/3998/149 +f 3994/3998/149 4061/4065/149 4071/4075/149 +f 4080/4084/146 4081/4085/146 4018/4022/146 4017/4021/146 +f 4049/4053/162 4082/4086/162 4019/4023/162 4050/4054/162 +f 4083/4087/160 4084/4088/160 4021/4025/160 4020/4024/160 +f 4085/4089/160 4086/4090/160 4023/4027/160 4022/4026/160 +f 4087/4091/146 4088/4092/146 4025/4029/146 4024/4028/146 +f 4089/4093/163 4049/4053/163 4059/4063/163 4026/4030/163 +f 4082/4086/150 4083/4087/150 4020/4024/150 4019/4023/150 +f 4084/4088/136 4080/4084/136 4017/4021/136 4021/4025/136 +f 4086/4090/136 4087/4091/136 4024/4028/136 4023/4027/136 +f 4090/4094/164 4091/4095/164 4092/4096/164 4093/4097/164 +f 4091/4095/139 4094/4098/139 4095/4099/139 4092/4096/139 +f 4096/4100/140 4097/4101/140 4098/4102/140 4099/4103/140 +f 4100/4104/141 4090/4094/141 4093/4097/141 4101/4105/141 +f 4102/4106/142 4103/4107/142 4104/4108/142 4105/4109/142 +f 4106/4110/143 4100/4104/143 4101/4105/143 4107/4111/143 +f 4094/4098/144 4108/4112/144 4109/4113/144 4095/4099/144 +f 4097/4101/145 4102/4106/145 4105/4109/145 4098/4102/145 +f 4108/4112/146 4096/4100/146 4099/4103/146 4109/4113/146 +f 4103/4107/147 4106/4110/147 4107/4111/147 4104/4108/147 +f 4107/4111/151 4088/4092/151 4104/4108/151 +f 4088/4092/150 4089/4093/150 4104/4108/150 +f 4104/4108/150 4089/4093/150 4105/4109/150 +f 4098/4102/157 4105/4109/157 4089/4093/157 +f 4099/4103/150 4098/4102/150 4089/4093/150 +f 4026/4030/150 4109/4113/150 4099/4103/150 4089/4093/150 +f 4090/4094/136 4022/4026/136 4091/4095/136 +f 4091/4095/149 4022/4026/149 4018/4022/149 4094/4098/149 +f 4096/4100/148 4081/4085/148 4097/4101/148 +f 4100/4104/136 4022/4026/136 4090/4094/136 +f 4102/4106/152 4085/4089/152 4103/4107/152 +f 4106/4110/152 4085/4089/152 4022/4026/152 4100/4104/152 +f 4094/4098/149 4018/4022/149 4108/4112/149 +f 4097/4101/148 4081/4085/148 4085/4089/148 4102/4106/148 +f 4108/4112/149 4018/4022/149 4081/4085/149 4096/4100/149 +f 4103/4107/152 4085/4089/152 4106/4110/152 +f 4026/4030/137 4095/4099/137 4109/4113/137 +f 4092/4096/137 4026/4030/137 4025/4029/137 +f 4026/4030/151 4092/4096/151 4095/4099/151 +f 4025/4029/137 4093/4097/137 4092/4096/137 +f 4101/4105/157 4025/4029/157 4088/4092/157 4107/4111/157 +f 4025/4029/157 4101/4105/157 4093/4097/157 +f 4110/4114/158 4047/4051/158 4048/4052/158 4111/4115/158 +f 4112/4116/159 4113/4117/159 4051/4055/159 4114/4118/159 +f 4115/4119/160 4052/4056/160 4053/4057/160 4116/4120/160 +f 4117/4121/160 4054/4058/160 4055/4059/160 4118/4122/160 +f 4119/4123/158 4056/4060/158 4057/4061/158 4120/4124/158 +f 4121/4125/161 4058/4062/161 4122/4126/161 4112/4116/161 +f 4114/4118/136 4051/4055/136 4052/4056/136 4115/4119/136 +f 4116/4120/150 4053/4057/150 4047/4051/150 4110/4114/150 +f 4118/4122/150 4055/4059/150 4056/4060/150 4119/4123/150 +f 4123/4127/138 4124/4128/138 4125/4129/138 4126/4130/138 +f 4126/4130/139 4125/4129/139 4127/4131/139 4128/4132/139 +f 4129/4133/140 4130/4134/140 4131/4135/140 4132/4136/140 +f 4133/4137/141 4134/4138/141 4124/4128/141 4123/4127/141 +f 4135/4139/142 4136/4140/142 4137/4141/142 4138/4142/142 +f 4139/4143/143 4140/4144/143 4134/4138/143 4133/4137/143 +f 4128/4132/144 4127/4131/144 4141/4145/144 4142/4146/144 +f 4132/4136/145 4131/4135/145 4136/4140/145 4135/4139/145 +f 4142/4146/146 4141/4145/146 4130/4134/146 4129/4133/146 +f 4138/4142/147 4137/4141/147 4140/4144/147 4139/4143/147 +f 4140/4144/148 4137/4141/148 4120/4124/148 +f 4120/4124/136 4137/4141/136 4121/4125/136 +f 4137/4141/136 4136/4140/136 4121/4125/136 +f 4131/4135/149 4121/4125/149 4136/4140/149 +f 4130/4134/136 4121/4125/136 4131/4135/136 +f 4058/4062/136 4121/4125/136 4130/4134/136 4141/4145/136 +f 4123/4127/150 4126/4130/150 4054/4058/150 +f 4126/4130/157 4128/4132/157 4048/4052/157 4054/4058/157 +f 4129/4133/151 4132/4136/151 4111/4115/151 +f 4133/4137/150 4123/4127/150 4054/4058/150 +f 4135/4139/137 4138/4142/137 4117/4121/137 +f 4139/4143/137 4133/4137/137 4054/4058/137 4117/4121/137 +f 4128/4132/157 4142/4146/157 4048/4052/157 +f 4132/4136/151 4135/4139/151 4117/4121/151 4111/4115/151 +f 4142/4146/157 4129/4133/157 4111/4115/157 4048/4052/157 +f 4138/4142/137 4139/4143/137 4117/4121/137 +f 4058/4062/152 4141/4145/152 4127/4131/152 +f 4125/4129/152 4057/4061/152 4058/4062/152 +f 4058/4062/148 4127/4131/148 4125/4129/148 +f 4057/4061/152 4125/4129/152 4124/4128/152 +f 4134/4138/149 4140/4144/149 4120/4124/149 4057/4061/149 +f 4057/4061/149 4124/4128/149 4134/4138/149 +f 4143/4147/158 4144/4148/158 4081/4085/158 4080/4084/158 +f 4112/4116/162 4145/4149/162 4082/4086/162 4113/4117/162 +f 4146/4150/160 4147/4151/160 4084/4088/160 4083/4087/160 +f 4148/4152/160 4149/4153/160 4086/4090/160 4085/4089/160 +f 4150/4154/158 4151/4155/158 4088/4092/158 4087/4091/158 +f 4152/4156/163 4112/4116/163 4122/4126/163 4089/4093/163 +f 4145/4149/150 4146/4150/150 4083/4087/150 4082/4086/150 +f 4147/4151/136 4143/4147/136 4080/4084/136 4084/4088/136 +f 4149/4153/136 4150/4154/136 4087/4091/136 4086/4090/136 +f 4153/4157/164 4154/4158/164 4155/4159/164 4156/4160/164 +f 4154/4158/139 4157/4161/139 4158/4162/139 4155/4159/139 +f 4159/4163/140 4160/4164/140 4161/4165/140 4162/4166/140 +f 4163/4167/155 4153/4157/155 4156/4160/155 4164/4168/155 +f 4165/4169/142 4166/4170/142 4167/4171/142 4168/4172/142 +f 4169/4173/156 4163/4167/156 4164/4168/156 4170/4174/156 +f 4157/4161/144 4171/4175/144 4172/4176/144 4158/4162/144 +f 4160/4164/145 4165/4169/145 4168/4172/145 4161/4165/145 +f 4171/4175/146 4159/4163/146 4162/4166/146 4172/4176/146 +f 4166/4170/147 4169/4173/147 4170/4174/147 4167/4171/147 +f 4170/4174/151 4151/4155/151 4167/4171/151 +f 4151/4155/150 4152/4156/150 4167/4171/150 +f 4167/4171/150 4152/4156/150 4168/4172/150 +f 4161/4165/157 4168/4172/157 4152/4156/157 +f 4162/4166/150 4161/4165/150 4152/4156/150 +f 4089/4093/150 4172/4176/150 4162/4166/150 4152/4156/150 +f 4153/4157/136 4085/4089/136 4154/4158/136 +f 4154/4158/149 4085/4089/149 4081/4085/149 4157/4161/149 +f 4159/4163/148 4144/4148/148 4160/4164/148 +f 4163/4167/136 4085/4089/136 4153/4157/136 +f 4165/4169/152 4148/4152/152 4166/4170/152 +f 4169/4173/152 4148/4152/152 4085/4089/152 4163/4167/152 +f 4157/4161/149 4081/4085/149 4171/4175/149 +f 4160/4164/148 4144/4148/148 4148/4152/148 4165/4169/148 +f 4171/4175/149 4081/4085/149 4144/4148/149 4159/4163/149 +f 4166/4170/152 4148/4152/152 4169/4173/152 +f 4089/4093/137 4158/4162/137 4172/4176/137 +f 4155/4159/137 4089/4093/137 4088/4092/137 +f 4089/4093/151 4155/4159/151 4158/4162/151 +f 4088/4092/137 4156/4160/137 4155/4159/137 +f 4164/4168/157 4088/4092/157 4151/4155/157 4170/4174/157 +f 4088/4092/157 4164/4168/157 4156/4160/157 +f 4173/4177/146 4110/4114/146 4111/4115/146 4174/4178/146 +f 4175/4179/159 4176/4180/159 4114/4118/159 4177/4181/159 +f 4178/4182/160 4115/4119/160 4116/4120/160 4179/4183/160 +f 4180/4184/143 4117/4121/143 4118/4122/143 4181/4185/143 +f 4182/4186/146 4119/4123/146 4120/4124/146 4183/4187/146 +f 4184/4188/161 4121/4125/161 4185/4189/161 4175/4179/161 +f 4177/4181/136 4114/4118/136 4115/4119/136 4178/4182/136 +f 4179/4183/150 4116/4120/150 4110/4114/150 4173/4177/150 +f 4181/4185/150 4118/4122/150 4119/4123/150 4182/4186/150 +f 4186/4190/138 4187/4191/138 4188/4192/138 4189/4193/138 +f 4189/4193/165 4188/4192/165 4190/4194/165 4191/4195/165 +f 4192/4196/140 4193/4197/140 4194/4198/140 4195/4199/140 +f 4196/4200/141 4197/4201/141 4187/4191/141 4186/4190/141 +f 4198/4202/142 4199/4203/142 4200/4204/142 4201/4205/142 +f 4202/4206/143 4203/4207/143 4197/4201/143 4196/4200/143 +f 4191/4195/144 4190/4194/144 4204/4208/144 4205/4209/144 +f 4195/4199/145 4194/4198/145 4199/4203/145 4198/4202/145 +f 4205/4209/146 4204/4208/146 4193/4197/146 4192/4196/146 +f 4201/4205/147 4200/4204/147 4203/4207/147 4202/4206/147 +f 4203/4207/148 4200/4204/148 4183/4187/148 +f 4183/4187/136 4200/4204/136 4184/4188/136 +f 4200/4204/136 4199/4203/136 4184/4188/136 +f 4194/4198/149 4184/4188/149 4199/4203/149 +f 4193/4197/136 4184/4188/136 4194/4198/136 +f 4121/4125/152 4184/4188/152 4193/4197/152 4204/4208/152 +f 4186/4190/150 4189/4193/150 4117/4121/150 +f 4189/4193/157 4191/4195/157 4111/4115/157 4117/4121/157 +f 4192/4196/151 4195/4199/151 4174/4178/151 +f 4196/4200/150 4186/4190/150 4117/4121/150 +f 4198/4202/137 4201/4205/137 4180/4184/137 +f 4202/4206/137 4196/4200/137 4117/4121/137 4180/4184/137 +f 4191/4195/157 4205/4209/157 4111/4115/157 +f 4195/4199/151 4198/4202/151 4180/4184/151 4174/4178/151 +f 4205/4209/157 4192/4196/157 4174/4178/157 4111/4115/157 +f 4201/4205/137 4202/4206/137 4180/4184/137 +f 4121/4125/152 4204/4208/152 4190/4194/152 +f 4188/4192/152 4120/4124/152 4121/4125/152 +f 4121/4125/148 4190/4194/148 4188/4192/148 +f 4120/4124/152 4188/4192/152 4187/4191/152 +f 4197/4201/149 4203/4207/149 4183/4187/149 4120/4124/149 +f 4120/4124/149 4187/4191/149 4197/4201/149 +f 4206/4210/146 4207/4211/146 4144/4148/146 4143/4147/146 +f 4175/4179/162 4208/4212/162 4145/4149/162 4176/4180/162 +f 4209/4213/160 4210/4214/160 4147/4151/160 4146/4150/160 +f 4211/4215/143 4212/4216/143 4149/4153/143 4148/4152/143 +f 4213/4217/146 4214/4218/146 4151/4155/146 4150/4154/146 +f 4215/4219/163 4175/4179/163 4185/4189/163 4152/4156/163 +f 4208/4212/150 4209/4213/150 4146/4150/150 4145/4149/150 +f 4210/4214/136 4206/4210/136 4143/4147/136 4147/4151/136 +f 4212/4216/136 4213/4217/136 4150/4154/136 4149/4153/136 +f 4216/4220/138 4217/4221/138 4218/4222/138 4219/4223/138 +f 4217/4221/165 4220/4224/165 4221/4225/165 4218/4222/165 +f 4222/4226/140 4223/4227/140 4224/4228/140 4225/4229/140 +f 4226/4230/155 4216/4220/155 4219/4223/155 4227/4231/155 +f 4228/4232/142 4229/4233/142 4230/4234/142 4231/4235/142 +f 4232/4236/156 4226/4230/156 4227/4231/156 4233/4237/156 +f 4220/4224/144 4234/4238/144 4235/4239/144 4221/4225/144 +f 4223/4227/145 4228/4232/145 4231/4235/145 4224/4228/145 +f 4234/4238/146 4222/4226/146 4225/4229/146 4235/4239/146 +f 4229/4233/147 4232/4236/147 4233/4237/147 4230/4234/147 +f 4233/4237/151 4214/4218/151 4230/4234/151 +f 4214/4218/150 4215/4219/150 4230/4234/150 +f 4230/4234/150 4215/4219/150 4231/4235/150 +f 4224/4228/157 4231/4235/157 4215/4219/157 +f 4225/4229/150 4224/4228/150 4215/4219/150 +f 4152/4156/137 4235/4239/137 4225/4229/137 4215/4219/137 +f 4216/4220/136 4148/4152/136 4217/4221/136 +f 4217/4221/149 4148/4152/149 4144/4148/149 4220/4224/149 +f 4222/4226/148 4207/4211/148 4223/4227/148 +f 4226/4230/136 4148/4152/136 4216/4220/136 +f 4228/4232/152 4211/4215/152 4229/4233/152 +f 4232/4236/152 4211/4215/152 4148/4152/152 4226/4230/152 +f 4220/4224/149 4144/4148/149 4234/4238/149 +f 4223/4227/148 4207/4211/148 4211/4215/148 4228/4232/148 +f 4234/4238/149 4144/4148/149 4207/4211/149 4222/4226/149 +f 4229/4233/152 4211/4215/152 4232/4236/152 +f 4152/4156/137 4221/4225/137 4235/4239/137 +f 4218/4222/137 4152/4156/137 4151/4155/137 +f 4152/4156/151 4218/4222/151 4221/4225/151 +f 4151/4155/137 4219/4223/137 4218/4222/137 +f 4227/4231/157 4151/4155/157 4214/4218/157 4233/4237/157 +f 4151/4155/157 4227/4231/157 4219/4223/157 +f 4236/4240/146 4173/4177/146 4174/4178/146 4237/4241/146 +f 4238/4242/159 4239/4243/159 4177/4181/159 4240/4244/159 +f 4241/4245/160 4178/4182/160 4179/4183/160 4242/4246/160 +f 4243/4247/160 4180/4184/160 4181/4185/160 4244/4248/160 +f 4245/4249/146 4182/4186/146 4183/4187/146 4246/4250/146 +f 4247/4251/161 4184/4188/161 4248/4252/161 4238/4242/161 +f 4240/4244/136 4177/4181/136 4178/4182/136 4241/4245/136 +f 4242/4246/150 4179/4183/150 4173/4177/150 4236/4240/150 +f 4244/4248/150 4181/4185/150 4182/4186/150 4245/4249/150 +f 4249/4253/138 4250/4254/138 4251/4255/138 4252/4256/138 +f 4252/4256/139 4251/4255/139 4253/4257/139 4254/4258/139 +f 4255/4259/140 4256/4260/140 4257/4261/140 4258/4262/140 +f 4259/4263/141 4260/4264/141 4250/4254/141 4249/4253/141 +f 4261/4265/142 4262/4266/142 4263/4267/142 4264/4268/142 +f 4265/4269/143 4266/4270/143 4260/4264/143 4259/4263/143 +f 4254/4258/144 4253/4257/144 4267/4271/144 4268/4272/144 +f 4258/4262/145 4257/4261/145 4262/4266/145 4261/4265/145 +f 4268/4272/146 4267/4271/146 4256/4260/146 4255/4259/146 +f 4264/4268/147 4263/4267/147 4266/4270/147 4265/4269/147 +f 4266/4270/148 4263/4267/148 4246/4250/148 +f 4246/4250/136 4263/4267/136 4247/4251/136 +f 4263/4267/136 4262/4266/136 4247/4251/136 +f 4257/4261/149 4247/4251/149 4262/4266/149 +f 4256/4260/136 4247/4251/136 4257/4261/136 +f 4184/4188/136 4247/4251/136 4256/4260/136 4267/4271/136 +f 4249/4253/150 4252/4256/150 4180/4184/150 +f 4252/4256/157 4254/4258/157 4174/4178/157 4180/4184/157 +f 4255/4259/151 4258/4262/151 4237/4241/151 +f 4259/4263/150 4249/4253/150 4180/4184/150 +f 4261/4265/137 4264/4268/137 4243/4247/137 +f 4265/4269/137 4259/4263/137 4180/4184/137 4243/4247/137 +f 4254/4258/157 4268/4272/157 4174/4178/157 +f 4258/4262/151 4261/4265/151 4243/4247/151 4237/4241/151 +f 4268/4272/157 4255/4259/157 4237/4241/157 4174/4178/157 +f 4264/4268/137 4265/4269/137 4243/4247/137 +f 4184/4188/152 4267/4271/152 4253/4257/152 +f 4251/4255/152 4183/4187/152 4184/4188/152 +f 4184/4188/148 4253/4257/148 4251/4255/148 +f 4183/4187/152 4251/4255/152 4250/4254/152 +f 4260/4264/149 4266/4270/149 4246/4250/149 4183/4187/149 +f 4183/4187/149 4250/4254/149 4260/4264/149 +f 4269/4273/146 4270/4274/146 4207/4211/146 4206/4210/146 +f 4238/4242/162 4271/4275/162 4208/4212/162 4239/4243/162 +f 4272/4276/160 4273/4277/160 4210/4214/160 4209/4213/160 +f 4274/4278/160 4275/4279/160 4212/4216/160 4211/4215/160 +f 4276/4280/146 4277/4281/146 4214/4218/146 4213/4217/146 +f 4278/4282/163 4238/4242/163 4248/4252/163 4215/4219/163 +f 4271/4275/150 4272/4276/150 4209/4213/150 4208/4212/150 +f 4273/4277/136 4269/4273/136 4206/4210/136 4210/4214/136 +f 4275/4279/136 4276/4280/136 4213/4217/136 4212/4216/136 +f 4279/4283/164 4280/4284/164 4281/4285/164 4282/4286/164 +f 4280/4284/139 4283/4287/139 4284/4288/139 4281/4285/139 +f 4285/4289/140 4286/4290/140 4287/4291/140 4288/4292/140 +f 4289/4293/155 4279/4283/155 4282/4286/155 4290/4294/155 +f 4291/4295/142 4292/4296/142 4293/4297/142 4294/4298/142 +f 4295/4299/156 4289/4293/156 4290/4294/156 4296/4300/156 +f 4283/4287/144 4297/4301/144 4298/4302/144 4284/4288/144 +f 4286/4290/145 4291/4295/145 4294/4298/145 4287/4291/145 +f 4297/4301/146 4285/4289/146 4288/4292/146 4298/4302/146 +f 4292/4296/147 4295/4299/147 4296/4300/147 4293/4297/147 +f 4296/4300/151 4277/4281/151 4293/4297/151 +f 4277/4281/150 4278/4282/150 4293/4297/150 +f 4293/4297/150 4278/4282/150 4294/4298/150 +f 4287/4291/157 4294/4298/157 4278/4282/157 +f 4288/4292/150 4287/4291/150 4278/4282/150 +f 4215/4219/150 4298/4302/150 4288/4292/150 4278/4282/150 +f 4279/4283/136 4211/4215/136 4280/4284/136 +f 4280/4284/149 4211/4215/149 4207/4211/149 4283/4287/149 +f 4285/4289/148 4270/4274/148 4286/4290/148 +f 4289/4293/136 4211/4215/136 4279/4283/136 +f 4291/4295/152 4274/4278/152 4292/4296/152 +f 4295/4299/152 4274/4278/152 4211/4215/152 4289/4293/152 +f 4283/4287/149 4207/4211/149 4297/4301/149 +f 4286/4290/148 4270/4274/148 4274/4278/148 4291/4295/148 +f 4297/4301/149 4207/4211/149 4270/4274/149 4285/4289/149 +f 4292/4296/152 4274/4278/152 4295/4299/152 +f 4215/4219/137 4284/4288/137 4298/4302/137 +f 4281/4285/137 4215/4219/137 4214/4218/137 +f 4215/4219/151 4281/4285/151 4284/4288/151 +f 4214/4218/137 4282/4286/137 4281/4285/137 +f 4290/4294/157 4214/4218/157 4277/4281/157 4296/4300/157 +f 4214/4218/157 4290/4294/157 4282/4286/157 +f 4299/4303/146 4236/4240/146 4237/4241/146 4300/4304/146 +f 4301/4305/159 4302/4306/159 4240/4244/159 4303/4307/159 +f 4304/4308/160 4241/4245/160 4242/4246/160 4305/4309/160 +f 4306/4310/160 4243/4247/160 4244/4248/160 4307/4311/160 +f 4308/4312/146 4245/4249/146 4246/4250/146 4309/4313/146 +f 4310/4314/161 4247/4251/161 4311/4315/161 4301/4305/161 +f 4303/4307/136 4240/4244/136 4241/4245/136 4304/4308/136 +f 4305/4309/150 4242/4246/150 4236/4240/150 4299/4303/150 +f 4307/4311/150 4244/4248/150 4245/4249/150 4308/4312/150 +f 4312/4316/138 4313/4317/138 4314/4318/138 4315/4319/138 +f 4315/4319/139 4314/4318/139 4316/4320/139 4317/4321/139 +f 4318/4322/140 4319/4323/140 4320/4324/140 4321/4325/140 +f 4322/4326/141 4323/4327/141 4313/4317/141 4312/4316/141 +f 4324/4328/142 4325/4329/142 4326/4330/142 4327/4331/142 +f 4328/4332/143 4329/4333/143 4323/4327/143 4322/4326/143 +f 4317/4321/144 4316/4320/144 4330/4334/144 4331/4335/144 +f 4321/4325/145 4320/4324/145 4325/4329/145 4324/4328/145 +f 4331/4335/146 4330/4334/146 4319/4323/146 4318/4322/146 +f 4327/4331/147 4326/4330/147 4329/4333/147 4328/4332/147 +f 4329/4333/148 4326/4330/148 4309/4313/148 +f 4309/4313/136 4326/4330/136 4310/4314/136 +f 4326/4330/136 4325/4329/136 4310/4314/136 +f 4320/4324/149 4310/4314/149 4325/4329/149 +f 4319/4323/136 4310/4314/136 4320/4324/136 +f 4247/4251/152 4310/4314/152 4319/4323/152 4330/4334/152 +f 4312/4316/150 4315/4319/150 4243/4247/150 +f 4315/4319/157 4317/4321/157 4237/4241/157 4243/4247/157 +f 4318/4322/151 4321/4325/151 4300/4304/151 +f 4322/4326/150 4312/4316/150 4243/4247/150 +f 4324/4328/137 4327/4331/137 4306/4310/137 +f 4328/4332/137 4322/4326/137 4243/4247/137 4306/4310/137 +f 4317/4321/157 4331/4335/157 4237/4241/157 +f 4321/4325/151 4324/4328/151 4306/4310/151 4300/4304/151 +f 4331/4335/157 4318/4322/157 4300/4304/157 4237/4241/157 +f 4327/4331/137 4328/4332/137 4306/4310/137 +f 4247/4251/152 4330/4334/152 4316/4320/152 +f 4314/4318/152 4246/4250/152 4247/4251/152 +f 4247/4251/148 4316/4320/148 4314/4318/148 +f 4246/4250/152 4314/4318/152 4313/4317/152 +f 4323/4327/149 4329/4333/149 4309/4313/149 4246/4250/149 +f 4246/4250/149 4313/4317/149 4323/4327/149 +f 4332/4336/146 4333/4337/146 4270/4274/146 4269/4273/146 +f 4301/4305/162 4334/4338/162 4271/4275/162 4302/4306/162 +f 4335/4339/160 4336/4340/160 4273/4277/160 4272/4276/160 +f 4337/4341/160 4338/4342/160 4275/4279/160 4274/4278/160 +f 4339/4343/146 4340/4344/146 4277/4281/146 4276/4280/146 +f 4341/4345/163 4301/4305/163 4311/4315/163 4278/4282/163 +f 4334/4338/150 4335/4339/150 4272/4276/150 4271/4275/150 +f 4336/4340/136 4332/4336/136 4269/4273/136 4273/4277/136 +f 4338/4342/136 4339/4343/136 4276/4280/136 4275/4279/136 +f 4342/4346/138 4343/4347/138 4344/4348/138 4345/4349/138 +f 4343/4347/139 4346/4350/139 4347/4351/139 4344/4348/139 +f 4348/4352/140 4349/4353/140 4350/4354/140 4351/4355/140 +f 4352/4356/155 4342/4346/155 4345/4349/155 4353/4357/155 +f 4354/4358/142 4355/4359/142 4356/4360/142 4357/4361/142 +f 4358/4362/156 4352/4356/156 4353/4357/156 4359/4363/156 +f 4346/4350/144 4360/4364/144 4361/4365/144 4347/4351/144 +f 4349/4353/145 4354/4358/145 4357/4361/145 4350/4354/145 +f 4360/4364/146 4348/4352/146 4351/4355/146 4361/4365/146 +f 4355/4359/147 4358/4362/147 4359/4363/147 4356/4360/147 +f 4359/4363/151 4340/4344/151 4356/4360/151 +f 4340/4344/150 4341/4345/150 4356/4360/150 +f 4356/4360/150 4341/4345/150 4357/4361/150 +f 4350/4354/157 4357/4361/157 4341/4345/157 +f 4351/4355/150 4350/4354/150 4341/4345/150 +f 4278/4282/137 4361/4365/137 4351/4355/137 4341/4345/137 +f 4342/4346/136 4274/4278/136 4343/4347/136 +f 4343/4347/149 4274/4278/149 4270/4274/149 4346/4350/149 +f 4348/4352/148 4333/4337/148 4349/4353/148 +f 4352/4356/136 4274/4278/136 4342/4346/136 +f 4354/4358/152 4337/4341/152 4355/4359/152 +f 4358/4362/152 4337/4341/152 4274/4278/152 4352/4356/152 +f 4346/4350/149 4270/4274/149 4360/4364/149 +f 4349/4353/148 4333/4337/148 4337/4341/148 4354/4358/148 +f 4360/4364/149 4270/4274/149 4333/4337/149 4348/4352/149 +f 4355/4359/152 4337/4341/152 4358/4362/152 +f 4278/4282/137 4347/4351/137 4361/4365/137 +f 4344/4348/137 4278/4282/137 4277/4281/137 +f 4278/4282/151 4344/4348/151 4347/4351/151 +f 4277/4281/137 4345/4349/137 4344/4348/137 +f 4353/4357/157 4277/4281/157 4340/4344/157 4359/4363/157 +f 4277/4281/157 4353/4357/157 4345/4349/157 +f 4362/4366/132 4299/4303/132 4300/4304/132 4363/4367/132 +f 4364/4368/166 4365/4369/166 4303/4307/166 4366/4370/166 +f 4367/4371/134 4304/4308/134 4305/4309/134 4368/4372/134 +f 4369/4373/134 4306/4310/134 4307/4311/134 4370/4374/134 +f 4371/4375/132 4308/4312/132 4309/4313/132 4372/4376/132 +f 4373/4377/167 4310/4314/167 4374/4378/167 4364/4368/167 +f 4366/4370/136 4303/4307/136 4304/4308/136 4367/4371/136 +f 4368/4372/137 4305/4309/137 4299/4303/137 4362/4366/137 +f 4370/4374/137 4307/4311/137 4308/4312/137 4371/4375/137 +f 4375/4379/138 4376/4380/138 4377/4381/138 4378/4382/138 +f 4378/4382/139 4377/4381/139 4379/4383/139 4380/4384/139 +f 4381/4385/140 4382/4386/140 4383/4387/140 4384/4388/140 +f 4385/4389/155 4386/4390/155 4376/4380/155 4375/4379/155 +f 4387/4391/142 4388/4392/142 4389/4393/142 4390/4394/142 +f 4391/4395/143 4392/4396/143 4386/4390/143 4385/4389/143 +f 4380/4384/144 4379/4383/144 4393/4397/144 4394/4398/144 +f 4384/4388/145 4383/4387/145 4388/4392/145 4387/4391/145 +f 4394/4398/146 4393/4397/146 4382/4386/146 4381/4385/146 +f 4390/4394/147 4389/4393/147 4392/4396/147 4391/4395/147 +f 4392/4396/149 4389/4393/149 4372/4376/149 +f 4372/4376/136 4389/4393/136 4373/4377/136 +f 4389/4393/136 4388/4392/136 4373/4377/136 +f 4383/4387/149 4373/4377/149 4388/4392/149 +f 4382/4386/136 4373/4377/136 4383/4387/136 +f 4310/4314/136 4373/4377/136 4382/4386/136 4393/4397/136 +f 4375/4379/150 4378/4382/150 4306/4310/150 +f 4378/4382/157 4380/4384/157 4300/4304/157 4306/4310/157 +f 4381/4385/151 4384/4388/151 4363/4367/151 +f 4385/4389/150 4375/4379/150 4306/4310/150 +f 4387/4391/137 4390/4394/137 4369/4373/137 +f 4391/4395/137 4385/4389/137 4306/4310/137 4369/4373/137 +f 4380/4384/157 4394/4398/157 4300/4304/157 +f 4384/4388/151 4387/4391/151 4369/4373/151 4363/4367/151 +f 4394/4398/151 4381/4385/151 4363/4367/151 4300/4304/151 +f 4390/4394/137 4391/4395/137 4369/4373/137 +f 4310/4314/152 4393/4397/152 4379/4383/152 +f 4377/4381/152 4309/4313/152 4310/4314/152 +f 4310/4314/148 4379/4383/148 4377/4381/148 +f 4309/4313/152 4377/4381/152 4376/4380/152 +f 4386/4390/149 4392/4396/149 4372/4376/149 4309/4313/149 +f 4309/4313/149 4376/4380/149 4386/4390/149 +f 4395/4399/132 4396/4400/132 4333/4337/132 4332/4336/132 +f 4364/4368/168 4397/4401/168 4334/4338/168 4365/4369/168 +f 4398/4402/134 4399/4403/134 4336/4340/134 4335/4339/134 +f 4400/4404/134 4401/4405/134 4338/4342/134 4337/4341/134 +f 4402/4406/132 4403/4407/132 4340/4344/132 4339/4343/132 +f 4404/4408/169 4364/4368/169 4374/4378/169 4341/4345/169 +f 4397/4401/150 4398/4402/150 4335/4339/150 4334/4338/150 +f 4399/4403/152 4395/4399/152 4332/4336/152 4336/4340/152 +f 4401/4405/152 4402/4406/152 4339/4343/152 4338/4342/152 +f 4405/4409/138 4406/4410/138 4407/4411/138 4408/4412/138 +f 4406/4410/139 4409/4413/139 4410/4414/139 4407/4411/139 +f 4411/4415/140 4412/4416/140 4413/4417/140 4414/4418/140 +f 4415/4419/155 4405/4409/155 4408/4412/155 4416/4420/155 +f 4417/4421/142 4418/4422/142 4419/4423/142 4420/4424/142 +f 4421/4425/143 4415/4419/143 4416/4420/143 4422/4426/143 +f 4409/4413/144 4423/4427/144 4424/4428/144 4410/4414/144 +f 4412/4416/145 4417/4421/145 4420/4424/145 4413/4417/145 +f 4423/4427/146 4411/4415/146 4414/4418/146 4424/4428/146 +f 4418/4422/147 4421/4425/147 4422/4426/147 4419/4423/147 +f 4422/4426/157 4403/4407/157 4419/4423/157 +f 4403/4407/150 4404/4408/150 4419/4423/150 +f 4419/4423/150 4404/4408/150 4420/4424/150 +f 4413/4417/157 4420/4424/157 4404/4408/157 +f 4414/4418/150 4413/4417/150 4404/4408/150 +f 4341/4345/150 4424/4428/150 4414/4418/150 4404/4408/150 +f 4405/4409/136 4337/4341/136 4406/4410/136 +f 4406/4410/149 4337/4341/149 4333/4337/149 4409/4413/149 +f 4411/4415/148 4396/4400/148 4412/4416/148 +f 4415/4419/136 4337/4341/136 4405/4409/136 +f 4417/4421/152 4400/4404/152 4418/4422/152 +f 4421/4425/152 4400/4404/152 4337/4341/152 4415/4419/152 +f 4409/4413/149 4333/4337/149 4423/4427/149 +f 4412/4416/148 4396/4400/148 4400/4404/148 4417/4421/148 +f 4423/4427/148 4333/4337/148 4396/4400/148 4411/4415/148 +f 4418/4422/152 4400/4404/152 4421/4425/152 +f 4341/4345/137 4410/4414/137 4424/4428/137 +f 4407/4411/137 4341/4345/137 4340/4344/137 +f 4341/4345/151 4407/4411/151 4410/4414/151 +f 4340/4344/137 4408/4412/137 4407/4411/137 +f 4416/4420/157 4340/4344/157 4403/4407/157 4422/4426/157 +f 4340/4344/157 4416/4420/157 4408/4412/157 +s 1 +f 3590/3594/170 3593/3597/171 3672/3676/172 3633/3637/173 +f 3590/3594/170 3647/3651/174 3681/3685/175 3606/3610/176 +f 3642/3646/177 3641/3645/177 3646/3650/177 3645/3649/177 3648/3652/177 3608/3612/177 3607/3611/177 3604/3608/177 3603/3607/177 3600/3604/177 3599/3603/177 3588/3592/177 3587/3591/177 3596/3600/177 3595/3599/177 3592/3596/177 3591/3595/177 3634/3638/177 3638/3642/177 3637/3641/177 3632/3636/177 3631/3635/177 +f 3671/3675/170 3673/3677/171 3735/3739/172 3704/3708/173 +f 3671/3675/170 3711/3715/174 3744/3748/175 3680/3684/176 +f 3734/3738/170 3736/3740/171 3798/3802/172 3767/3771/173 +f 3734/3738/170 3774/3778/174 3807/3811/175 3743/3747/176 +f 3797/3801/170 3799/3803/178 3861/3865/172 3830/3834/179 +f 3797/3801/170 3837/3841/174 3870/3874/175 3806/3810/176 +f 3860/3864/170 3862/3866/171 3924/3928/172 3893/3897/173 +f 3860/3864/170 3900/3904/174 3933/3937/175 3869/3873/176 +f 3923/3927/170 3925/3929/171 3987/3991/172 3956/3960/173 +f 3923/3927/170 3963/3967/174 3996/4000/175 3932/3936/176 +f 3986/3990/170 3988/3992/178 4050/4054/172 4019/4023/179 +f 3986/3990/170 4026/4030/174 4059/4063/175 3995/3999/176 +f 4049/4053/170 4051/4055/171 4113/4117/172 4082/4086/173 +f 4049/4053/170 4089/4093/174 4122/4126/175 4058/4062/176 +f 4112/4116/170 4114/4118/171 4176/4180/172 4145/4149/173 +f 4112/4116/170 4152/4156/174 4185/4189/175 4121/4125/176 +f 4175/4179/170 4177/4181/180 4239/4243/181 4208/4212/182 +f 4175/4179/170 4215/4219/174 4248/4252/175 4184/4188/176 +f 4238/4242/170 4240/4244/183 4302/4306/172 4271/4275/184 +f 4238/4242/170 4278/4282/174 4311/4315/175 4247/4251/176 +f 4301/4305/185 4303/4307/180 4365/4369/181 4334/4338/182 +f 4301/4305/185 4341/4345/186 4374/4378/187 4310/4314/188 +f 4367/4371/189 4368/4372/189 4362/4366/189 4363/4367/189 4369/4373/189 4370/4374/189 4371/4375/189 4372/4376/189 4373/4377/189 4364/4368/189 4366/4370/189 +f 4403/4407/189 4402/4406/189 4401/4405/189 4400/4404/189 4396/4400/189 4395/4399/189 4399/4403/189 4398/4402/189 4397/4401/189 4364/4368/189 4404/4408/189 +# 677 polygons - 416 triangles + +# +# object Conveyor_Rollers +# + +v 0.8735 -3.2957 0.3987 +v 0.8735 -3.2822 0.4311 +v 0.2483 -3.2822 0.4311 +v 0.2483 -3.2957 0.3987 +v 0.8735 -3.2498 0.4446 +v 0.2483 -3.2498 0.4446 +v 0.8735 -3.2173 0.4311 +v 0.2483 -3.2173 0.4311 +v 0.8735 -3.2039 0.3987 +v 0.2483 -3.2039 0.3987 +v 0.8735 -3.2173 0.3662 +v 0.2483 -3.2173 0.3662 +v 0.8735 -3.2498 0.3528 +v 0.2483 -3.2498 0.3528 +v 0.8735 -3.2822 0.3662 +v 0.2483 -3.2822 0.3662 +v 0.8735 -3.1757 0.3987 +v 0.8735 -3.1622 0.4311 +v 0.2483 -3.1622 0.4311 +v 0.2483 -3.1757 0.3987 +v 0.8735 -3.1298 0.4446 +v 0.2483 -3.1298 0.4446 +v 0.8735 -3.0973 0.4311 +v 0.2483 -3.0973 0.4311 +v 0.8735 -3.0839 0.3987 +v 0.2483 -3.0839 0.3987 +v 0.8735 -3.0973 0.3662 +v 0.2483 -3.0973 0.3662 +v 0.8735 -3.1298 0.3528 +v 0.2483 -3.1298 0.3528 +v 0.8735 -3.1622 0.3662 +v 0.2483 -3.1622 0.3662 +v 0.8735 -3.0557 0.3987 +v 0.8735 -3.0422 0.4311 +v 0.2483 -3.0422 0.4311 +v 0.2483 -3.0557 0.3987 +v 0.8735 -3.0098 0.4446 +v 0.2483 -3.0098 0.4446 +v 0.8735 -2.9773 0.4311 +v 0.2483 -2.9773 0.4311 +v 0.8735 -2.9639 0.3987 +v 0.2483 -2.9639 0.3987 +v 0.8735 -2.9773 0.3662 +v 0.2483 -2.9773 0.3662 +v 0.8735 -3.0098 0.3528 +v 0.2483 -3.0098 0.3528 +v 0.8735 -3.0422 0.3662 +v 0.2483 -3.0422 0.3662 +v 0.8735 -2.9357 0.3987 +v 0.8735 -2.9222 0.4311 +v 0.2483 -2.9222 0.4311 +v 0.2483 -2.9357 0.3987 +v 0.8735 -2.8898 0.4446 +v 0.2483 -2.8898 0.4446 +v 0.8735 -2.8573 0.4311 +v 0.2483 -2.8573 0.4311 +v 0.8735 -2.8439 0.3987 +v 0.2483 -2.8439 0.3987 +v 0.8735 -2.8573 0.3662 +v 0.2483 -2.8573 0.3662 +v 0.8735 -2.8898 0.3528 +v 0.2483 -2.8898 0.3528 +v 0.8735 -2.9222 0.3662 +v 0.2483 -2.9222 0.3662 +v 0.8735 -2.8157 0.3987 +v 0.8735 -2.8022 0.4311 +v 0.2483 -2.8022 0.4311 +v 0.2483 -2.8157 0.3987 +v 0.8735 -2.7698 0.4446 +v 0.2483 -2.7698 0.4446 +v 0.8735 -2.7373 0.4311 +v 0.2483 -2.7373 0.4311 +v 0.8735 -2.7239 0.3987 +v 0.2483 -2.7239 0.3987 +v 0.8735 -2.7373 0.3662 +v 0.2483 -2.7373 0.3662 +v 0.8735 -2.7698 0.3528 +v 0.2483 -2.7698 0.3528 +v 0.8735 -2.8022 0.3662 +v 0.2483 -2.8022 0.3662 +v 0.8735 -2.6957 0.3987 +v 0.8735 -2.6822 0.4311 +v 0.2483 -2.6822 0.4311 +v 0.2483 -2.6957 0.3987 +v 0.8735 -2.6498 0.4446 +v 0.2483 -2.6498 0.4446 +v 0.8735 -2.6173 0.4311 +v 0.2483 -2.6173 0.4311 +v 0.8735 -2.6039 0.3987 +v 0.2483 -2.6039 0.3987 +v 0.8735 -2.6173 0.3662 +v 0.2483 -2.6173 0.3662 +v 0.8735 -2.6498 0.3528 +v 0.2483 -2.6498 0.3528 +v 0.8735 -2.6822 0.3662 +v 0.2483 -2.6822 0.3662 +v 0.8735 -2.5757 0.3987 +v 0.8735 -2.5622 0.4311 +v 0.2483 -2.5622 0.4311 +v 0.2483 -2.5757 0.3987 +v 0.8735 -2.5298 0.4446 +v 0.2483 -2.5298 0.4446 +v 0.8735 -2.4973 0.4311 +v 0.2483 -2.4973 0.4311 +v 0.8735 -2.4839 0.3987 +v 0.2483 -2.4839 0.3987 +v 0.8735 -2.4973 0.3662 +v 0.2483 -2.4973 0.3662 +v 0.8735 -2.5298 0.3528 +v 0.2483 -2.5298 0.3528 +v 0.8735 -2.5622 0.3662 +v 0.2483 -2.5622 0.3662 +v 0.8735 -2.4557 0.3987 +v 0.8735 -2.4422 0.4311 +v 0.2483 -2.4422 0.4311 +v 0.2483 -2.4557 0.3987 +v 0.8735 -2.4098 0.4446 +v 0.2483 -2.4098 0.4446 +v 0.8735 -2.3773 0.4311 +v 0.2483 -2.3773 0.4311 +v 0.8735 -2.3639 0.3987 +v 0.2483 -2.3639 0.3987 +v 0.8735 -2.3773 0.3662 +v 0.2483 -2.3773 0.3662 +v 0.8735 -2.4098 0.3528 +v 0.2483 -2.4098 0.3528 +v 0.8735 -2.4422 0.3662 +v 0.2483 -2.4422 0.3662 +v 0.8735 -2.3357 0.3987 +v 0.8735 -2.3222 0.4311 +v 0.2483 -2.3222 0.4311 +v 0.2483 -2.3357 0.3987 +v 0.8735 -2.2898 0.4446 +v 0.2483 -2.2898 0.4446 +v 0.8735 -2.2573 0.4311 +v 0.2483 -2.2573 0.4311 +v 0.8735 -2.2439 0.3987 +v 0.2483 -2.2439 0.3987 +v 0.8735 -2.2573 0.3662 +v 0.2483 -2.2573 0.3662 +v 0.8735 -2.2898 0.3528 +v 0.2483 -2.2898 0.3528 +v 0.8735 -2.3222 0.3662 +v 0.2483 -2.3222 0.3662 +v 0.8735 -2.2157 0.3987 +v 0.8735 -2.2022 0.4311 +v 0.2483 -2.2022 0.4311 +v 0.2483 -2.2157 0.3987 +v 0.8735 -2.1698 0.4446 +v 0.2483 -2.1698 0.4446 +v 0.8735 -2.1373 0.4311 +v 0.2483 -2.1373 0.4311 +v 0.8735 -2.1239 0.3987 +v 0.2483 -2.1239 0.3987 +v 0.8735 -2.1373 0.3662 +v 0.2483 -2.1373 0.3662 +v 0.8735 -2.1698 0.3528 +v 0.2483 -2.1698 0.3528 +v 0.8735 -2.2022 0.3662 +v 0.2483 -2.2022 0.3662 +v 0.8735 -2.0957 0.3987 +v 0.8735 -2.0822 0.4311 +v 0.2483 -2.0822 0.4311 +v 0.2483 -2.0957 0.3987 +v 0.8735 -2.0498 0.4446 +v 0.2483 -2.0498 0.4446 +v 0.8735 -2.0173 0.4311 +v 0.2483 -2.0173 0.4311 +v 0.8735 -2.0039 0.3987 +v 0.2483 -2.0039 0.3987 +v 0.8735 -2.0173 0.3662 +v 0.2483 -2.0173 0.3662 +v 0.8735 -2.0498 0.3528 +v 0.2483 -2.0498 0.3528 +v 0.8735 -2.0822 0.3662 +v 0.2483 -2.0822 0.3662 +v 0.8735 -1.9757 0.3987 +v 0.8735 -1.9622 0.4311 +v 0.2483 -1.9622 0.4311 +v 0.2483 -1.9757 0.3987 +v 0.8735 -1.9298 0.4446 +v 0.2483 -1.9298 0.4446 +v 0.8735 -1.8973 0.4311 +v 0.2483 -1.8973 0.4311 +v 0.8735 -1.8839 0.3987 +v 0.2483 -1.8839 0.3987 +v 0.8735 -1.8973 0.3662 +v 0.2483 -1.8973 0.3662 +v 0.8735 -1.9298 0.3528 +v 0.2483 -1.9298 0.3528 +v 0.8735 -1.9622 0.3662 +v 0.2483 -1.9622 0.3662 +v 0.8735 -1.8557 0.3987 +v 0.8735 -1.8422 0.4311 +v 0.2483 -1.8422 0.4311 +v 0.2483 -1.8557 0.3987 +v 0.8735 -1.8098 0.4446 +v 0.2483 -1.8098 0.4446 +v 0.8735 -1.7773 0.4311 +v 0.2483 -1.7773 0.4311 +v 0.8735 -1.7639 0.3987 +v 0.2483 -1.7639 0.3987 +v 0.8735 -1.7773 0.3662 +v 0.2483 -1.7773 0.3662 +v 0.8735 -1.8098 0.3528 +v 0.2483 -1.8098 0.3528 +v 0.8735 -1.8422 0.3662 +v 0.2483 -1.8422 0.3662 +v 0.8735 -1.7357 0.3987 +v 0.8735 -1.7222 0.4311 +v 0.2483 -1.7222 0.4311 +v 0.2483 -1.7357 0.3987 +v 0.8735 -1.6898 0.4446 +v 0.2483 -1.6898 0.4446 +v 0.8735 -1.6573 0.4311 +v 0.2483 -1.6573 0.4311 +v 0.8735 -1.6439 0.3987 +v 0.2483 -1.6439 0.3987 +v 0.8735 -1.6573 0.3662 +v 0.2483 -1.6573 0.3662 +v 0.8735 -1.6898 0.3528 +v 0.2483 -1.6898 0.3528 +v 0.8735 -1.7222 0.3662 +v 0.2483 -1.7222 0.3662 +v 0.8735 -1.6157 0.3987 +v 0.8735 -1.6022 0.4311 +v 0.2483 -1.6022 0.4311 +v 0.2483 -1.6157 0.3987 +v 0.8735 -1.5698 0.4446 +v 0.2483 -1.5698 0.4446 +v 0.8735 -1.5373 0.4311 +v 0.2483 -1.5373 0.4311 +v 0.8735 -1.5239 0.3987 +v 0.2483 -1.5239 0.3987 +v 0.8735 -1.5373 0.3662 +v 0.2483 -1.5373 0.3662 +v 0.8735 -1.5698 0.3528 +v 0.2483 -1.5698 0.3528 +v 0.8735 -1.6022 0.3662 +v 0.2483 -1.6022 0.3662 +v 0.8735 -1.4957 0.3987 +v 0.8735 -1.4822 0.4311 +v 0.2483 -1.4822 0.4311 +v 0.2483 -1.4957 0.3987 +v 0.8735 -1.4498 0.4446 +v 0.2483 -1.4498 0.4446 +v 0.8735 -1.4173 0.4311 +v 0.2483 -1.4173 0.4311 +v 0.8735 -1.4039 0.3987 +v 0.2483 -1.4039 0.3987 +v 0.8735 -1.4173 0.3662 +v 0.2483 -1.4173 0.3662 +v 0.8735 -1.4498 0.3528 +v 0.2483 -1.4498 0.3528 +v 0.8735 -1.4822 0.3662 +v 0.2483 -1.4822 0.3662 +v 0.8735 -1.3757 0.3987 +v 0.8735 -1.3622 0.4311 +v 0.2483 -1.3622 0.4311 +v 0.2483 -1.3757 0.3987 +v 0.8735 -1.3298 0.4446 +v 0.2483 -1.3298 0.4446 +v 0.8735 -1.2973 0.4311 +v 0.2483 -1.2973 0.4311 +v 0.8735 -1.2839 0.3987 +v 0.2483 -1.2839 0.3987 +v 0.8735 -1.2973 0.3662 +v 0.2483 -1.2973 0.3662 +v 0.8735 -1.3298 0.3528 +v 0.2483 -1.3298 0.3528 +v 0.8735 -1.3622 0.3662 +v 0.2483 -1.3622 0.3662 +v 0.8735 -1.2557 0.3987 +v 0.8735 -1.2422 0.4311 +v 0.2483 -1.2422 0.4311 +v 0.2483 -1.2557 0.3987 +v 0.8735 -1.2098 0.4446 +v 0.2483 -1.2098 0.4446 +v 0.8735 -1.1773 0.4311 +v 0.2483 -1.1773 0.4311 +v 0.8735 -1.1639 0.3987 +v 0.2483 -1.1639 0.3987 +v 0.8735 -1.1773 0.3662 +v 0.2483 -1.1773 0.3662 +v 0.8735 -1.2098 0.3528 +v 0.2483 -1.2098 0.3528 +v 0.8735 -1.2422 0.3662 +v 0.2483 -1.2422 0.3662 +v 0.8735 -1.1357 0.3987 +v 0.8735 -1.1222 0.4311 +v 0.2483 -1.1222 0.4311 +v 0.2483 -1.1357 0.3987 +v 0.8735 -1.0898 0.4446 +v 0.2483 -1.0898 0.4446 +v 0.8735 -1.0573 0.4311 +v 0.2483 -1.0573 0.4311 +v 0.8735 -1.0439 0.3987 +v 0.2483 -1.0439 0.3987 +v 0.8735 -1.0573 0.3662 +v 0.2483 -1.0573 0.3662 +v 0.8735 -1.0898 0.3528 +v 0.2483 -1.0898 0.3528 +v 0.8735 -1.1222 0.3662 +v 0.2483 -1.1222 0.3662 +v 0.8735 -1.0157 0.3987 +v 0.8735 -1.0022 0.4311 +v 0.2483 -1.0022 0.4311 +v 0.2483 -1.0157 0.3987 +v 0.8735 -0.9698 0.4446 +v 0.2483 -0.9698 0.4446 +v 0.8735 -0.9373 0.4311 +v 0.2483 -0.9373 0.4311 +v 0.8735 -0.9239 0.3987 +v 0.2483 -0.9239 0.3987 +v 0.8735 -0.9373 0.3662 +v 0.2483 -0.9373 0.3662 +v 0.8735 -0.9698 0.3528 +v 0.2483 -0.9698 0.3528 +v 0.8735 -1.0022 0.3662 +v 0.2483 -1.0022 0.3662 +v 0.8735 -0.8957 0.3987 +v 0.8735 -0.8822 0.4311 +v 0.2483 -0.8822 0.4311 +v 0.2483 -0.8957 0.3987 +v 0.8735 -0.8498 0.4446 +v 0.2483 -0.8498 0.4446 +v 0.8735 -0.8173 0.4311 +v 0.2483 -0.8173 0.4311 +v 0.8735 -0.8039 0.3987 +v 0.2483 -0.8039 0.3987 +v 0.8735 -0.8173 0.3662 +v 0.2483 -0.8173 0.3662 +v 0.8735 -0.8498 0.3528 +v 0.2483 -0.8498 0.3528 +v 0.8735 -0.8822 0.3662 +v 0.2483 -0.8822 0.3662 +v 0.8735 -0.7757 0.3987 +v 0.8735 -0.7622 0.4311 +v 0.2483 -0.7622 0.4311 +v 0.2483 -0.7757 0.3987 +v 0.8735 -0.7298 0.4446 +v 0.2483 -0.7298 0.4446 +v 0.8735 -0.6973 0.4311 +v 0.2483 -0.6973 0.4311 +v 0.8735 -0.6839 0.3987 +v 0.2483 -0.6839 0.3987 +v 0.8735 -0.6973 0.3662 +v 0.2483 -0.6973 0.3662 +v 0.8735 -0.7298 0.3528 +v 0.2483 -0.7298 0.3528 +v 0.8735 -0.7622 0.3662 +v 0.2483 -0.7622 0.3662 +v 0.8735 -0.6557 0.3987 +v 0.8735 -0.6422 0.4311 +v 0.2483 -0.6422 0.4311 +v 0.2483 -0.6557 0.3987 +v 0.8735 -0.6098 0.4446 +v 0.2483 -0.6098 0.4446 +v 0.8735 -0.5773 0.4311 +v 0.2483 -0.5773 0.4311 +v 0.8735 -0.5639 0.3987 +v 0.2483 -0.5639 0.3987 +v 0.8735 -0.5773 0.3662 +v 0.2483 -0.5773 0.3662 +v 0.8735 -0.6098 0.3528 +v 0.2483 -0.6098 0.3528 +v 0.8735 -0.6422 0.3662 +v 0.2483 -0.6422 0.3662 +v 0.8735 -0.5357 0.3987 +v 0.8735 -0.5222 0.4311 +v 0.2483 -0.5222 0.4311 +v 0.2483 -0.5357 0.3987 +v 0.8735 -0.4898 0.4446 +v 0.2483 -0.4898 0.4446 +v 0.8735 -0.4573 0.4311 +v 0.2483 -0.4573 0.4311 +v 0.8735 -0.4439 0.3987 +v 0.2483 -0.4439 0.3987 +v 0.8735 -0.4573 0.3662 +v 0.2483 -0.4573 0.3662 +v 0.8735 -0.4898 0.3528 +v 0.2483 -0.4898 0.3528 +v 0.8735 -0.5222 0.3662 +v 0.2483 -0.5222 0.3662 +v 0.8735 -0.4157 0.3987 +v 0.8735 -0.4022 0.4311 +v 0.2483 -0.4022 0.4311 +v 0.2483 -0.4157 0.3987 +v 0.8735 -0.3698 0.4446 +v 0.2483 -0.3698 0.4446 +v 0.8735 -0.3373 0.4311 +v 0.2483 -0.3373 0.4311 +v 0.8735 -0.3239 0.3987 +v 0.2483 -0.3239 0.3987 +v 0.8735 -0.3373 0.3662 +v 0.2483 -0.3373 0.3662 +v 0.8735 -0.3698 0.3528 +v 0.2483 -0.3698 0.3528 +v 0.8735 -0.4022 0.3662 +v 0.2483 -0.4022 0.3662 +v 0.8735 -0.2957 0.3987 +v 0.8735 -0.2822 0.4311 +v 0.2483 -0.2822 0.4311 +v 0.2483 -0.2957 0.3987 +v 0.8735 -0.2498 0.4446 +v 0.2483 -0.2498 0.4446 +v 0.8735 -0.2173 0.4311 +v 0.2483 -0.2173 0.4311 +v 0.8735 -0.2039 0.3987 +v 0.2483 -0.2039 0.3987 +v 0.8735 -0.2173 0.3662 +v 0.2483 -0.2173 0.3662 +v 0.8735 -0.2498 0.3528 +v 0.2483 -0.2498 0.3528 +v 0.8735 -0.2822 0.3662 +v 0.2483 -0.2822 0.3662 +v 0.8735 -0.1757 0.3987 +v 0.8735 -0.1622 0.4311 +v 0.2483 -0.1622 0.4311 +v 0.2483 -0.1757 0.3987 +v 0.8735 -0.1298 0.4446 +v 0.2483 -0.1298 0.4446 +v 0.8735 -0.0973 0.4311 +v 0.2483 -0.0973 0.4311 +v 0.8735 -0.0839 0.3987 +v 0.2483 -0.0839 0.3987 +v 0.8735 -0.0973 0.3662 +v 0.2483 -0.0973 0.3662 +v 0.8735 -0.1298 0.3528 +v 0.2483 -0.1298 0.3528 +v 0.8735 -0.1622 0.3662 +v 0.2483 -0.1622 0.3662 +v 0.8735 -0.0557 0.3987 +v 0.8735 -0.0422 0.4311 +v 0.2483 -0.0422 0.4311 +v 0.2483 -0.0557 0.3987 +v 0.8735 -0.0098 0.4446 +v 0.2483 -0.0098 0.4446 +v 0.8735 0.0227 0.4311 +v 0.2483 0.0227 0.4311 +v 0.8735 0.0361 0.3987 +v 0.2483 0.0361 0.3987 +v 0.8735 0.0227 0.3662 +v 0.2483 0.0227 0.3662 +v 0.8735 -0.0098 0.3528 +v 0.2483 -0.0098 0.3528 +v 0.8735 -0.0422 0.3662 +v 0.2483 -0.0422 0.3662 +v 0.8735 0.0643 0.3987 +v 0.8735 0.0778 0.4311 +v 0.2483 0.0778 0.4311 +v 0.2483 0.0643 0.3987 +v 0.8735 0.1102 0.4446 +v 0.2483 0.1102 0.4446 +v 0.8735 0.1427 0.4311 +v 0.2483 0.1427 0.4311 +v 0.8735 0.1561 0.3987 +v 0.2483 0.1561 0.3987 +v 0.8735 0.1427 0.3662 +v 0.2483 0.1427 0.3662 +v 0.8735 0.1102 0.3528 +v 0.2483 0.1102 0.3528 +v 0.8735 0.0778 0.3662 +v 0.2483 0.0778 0.3662 +v 0.8735 0.1843 0.3987 +v 0.8735 0.1978 0.4311 +v 0.2483 0.1978 0.4311 +v 0.2483 0.1843 0.3987 +v 0.8735 0.2302 0.4446 +v 0.2483 0.2302 0.4446 +v 0.8735 0.2627 0.4311 +v 0.2483 0.2627 0.4311 +v 0.8735 0.2761 0.3987 +v 0.2483 0.2761 0.3987 +v 0.8735 0.2627 0.3662 +v 0.2483 0.2627 0.3662 +v 0.8735 0.2302 0.3528 +v 0.2483 0.2302 0.3528 +v 0.8735 0.1978 0.3662 +v 0.2483 0.1978 0.3662 +v 0.8735 0.3043 0.3987 +v 0.8735 0.3178 0.4311 +v 0.2483 0.3178 0.4311 +v 0.2483 0.3043 0.3987 +v 0.8735 0.3502 0.4446 +v 0.2483 0.3502 0.4446 +v 0.8735 0.3827 0.4311 +v 0.2483 0.3827 0.4311 +v 0.8735 0.3961 0.3987 +v 0.2483 0.3961 0.3987 +v 0.8735 0.3827 0.3662 +v 0.2483 0.3827 0.3662 +v 0.8735 0.3502 0.3528 +v 0.2483 0.3502 0.3528 +v 0.8735 0.3178 0.3662 +v 0.2483 0.3178 0.3662 +v 0.8735 0.4243 0.3987 +v 0.8735 0.4378 0.4311 +v 0.2483 0.4378 0.4311 +v 0.2483 0.4243 0.3987 +v 0.8735 0.4702 0.4446 +v 0.2483 0.4702 0.4446 +v 0.8735 0.5027 0.4311 +v 0.2483 0.5027 0.4311 +v 0.8735 0.5161 0.3987 +v 0.2483 0.5161 0.3987 +v 0.8735 0.5027 0.3662 +v 0.2483 0.5027 0.3662 +v 0.8735 0.4702 0.3528 +v 0.2483 0.4702 0.3528 +v 0.8735 0.4378 0.3662 +v 0.2483 0.4378 0.3662 +v 0.8735 0.5443 0.3987 +v 0.8735 0.5578 0.4311 +v 0.2483 0.5578 0.4311 +v 0.2483 0.5443 0.3987 +v 0.8735 0.5902 0.4446 +v 0.2483 0.5902 0.4446 +v 0.8735 0.6227 0.4311 +v 0.2483 0.6227 0.4311 +v 0.8735 0.6361 0.3987 +v 0.2483 0.6361 0.3987 +v 0.8735 0.6227 0.3662 +v 0.2483 0.6227 0.3662 +v 0.8735 0.5902 0.3528 +v 0.2483 0.5902 0.3528 +v 0.8735 0.5578 0.3662 +v 0.2483 0.5578 0.3662 +v 0.8735 0.6643 0.3987 +v 0.8735 0.6778 0.4311 +v 0.2483 0.6778 0.4311 +v 0.2483 0.6643 0.3987 +v 0.8735 0.7102 0.4446 +v 0.2483 0.7102 0.4446 +v 0.8735 0.7427 0.4311 +v 0.2483 0.7427 0.4311 +v 0.8735 0.7561 0.3987 +v 0.2483 0.7561 0.3987 +v 0.8735 0.7427 0.3662 +v 0.2483 0.7427 0.3662 +v 0.8735 0.7102 0.3528 +v 0.2483 0.7102 0.3528 +v 0.8735 0.6778 0.3662 +v 0.2483 0.6778 0.3662 +v 0.8735 0.7843 0.3987 +v 0.8735 0.7978 0.4311 +v 0.2483 0.7978 0.4311 +v 0.2483 0.7843 0.3987 +v 0.8735 0.8302 0.4446 +v 0.2483 0.8302 0.4446 +v 0.8735 0.8627 0.4311 +v 0.2483 0.8627 0.4311 +v 0.8735 0.8761 0.3987 +v 0.2483 0.8761 0.3987 +v 0.8735 0.8627 0.3662 +v 0.2483 0.8627 0.3662 +v 0.8735 0.8302 0.3528 +v 0.2483 0.8302 0.3528 +v 0.8735 0.7978 0.3662 +v 0.2483 0.7978 0.3662 +v 0.8735 0.9043 0.3987 +v 0.8735 0.9178 0.4311 +v 0.2483 0.9178 0.4311 +v 0.2483 0.9043 0.3987 +v 0.8735 0.9502 0.4446 +v 0.2483 0.9502 0.4446 +v 0.8735 0.9827 0.4311 +v 0.2483 0.9827 0.4311 +v 0.8735 0.9961 0.3987 +v 0.2483 0.9961 0.3987 +v 0.8735 0.9827 0.3662 +v 0.2483 0.9827 0.3662 +v 0.8735 0.9502 0.3528 +v 0.2483 0.9502 0.3528 +v 0.8735 0.9178 0.3662 +v 0.2483 0.9178 0.3662 +v 0.8735 1.0243 0.3987 +v 0.8735 1.0378 0.4311 +v 0.2483 1.0378 0.4311 +v 0.2483 1.0243 0.3987 +v 0.8735 1.0702 0.4446 +v 0.2483 1.0702 0.4446 +v 0.8735 1.1027 0.4311 +v 0.2483 1.1027 0.4311 +v 0.8735 1.1161 0.3987 +v 0.2483 1.1161 0.3987 +v 0.8735 1.1027 0.3662 +v 0.2483 1.1027 0.3662 +v 0.8735 1.0702 0.3528 +v 0.2483 1.0702 0.3528 +v 0.8735 1.0378 0.3662 +v 0.2483 1.0378 0.3662 +v 0.8735 1.1443 0.3987 +v 0.8735 1.1578 0.4311 +v 0.2483 1.1578 0.4311 +v 0.2483 1.1443 0.3987 +v 0.8735 1.1902 0.4446 +v 0.2483 1.1902 0.4446 +v 0.8735 1.2227 0.4311 +v 0.2483 1.2227 0.4311 +v 0.8735 1.2361 0.3987 +v 0.2483 1.2361 0.3987 +v 0.8735 1.2227 0.3662 +v 0.2483 1.2227 0.3662 +v 0.8735 1.1902 0.3528 +v 0.2483 1.1902 0.3528 +v 0.8735 1.1578 0.3662 +v 0.2483 1.1578 0.3662 +v 0.8735 1.2643 0.3987 +v 0.8735 1.2778 0.4311 +v 0.2483 1.2778 0.4311 +v 0.2483 1.2643 0.3987 +v 0.8735 1.3102 0.4446 +v 0.2483 1.3102 0.4446 +v 0.8735 1.3427 0.4311 +v 0.2483 1.3427 0.4311 +v 0.8735 1.3561 0.3987 +v 0.2483 1.3561 0.3987 +v 0.8735 1.3427 0.3662 +v 0.2483 1.3427 0.3662 +v 0.8735 1.3102 0.3528 +v 0.2483 1.3102 0.3528 +v 0.8735 1.2778 0.3662 +v 0.2483 1.2778 0.3662 +v 0.8735 1.3843 0.3987 +v 0.8735 1.3978 0.4311 +v 0.2483 1.3978 0.4311 +v 0.2483 1.3843 0.3987 +v 0.8735 1.4302 0.4446 +v 0.2483 1.4302 0.4446 +v 0.8735 1.4627 0.4311 +v 0.2483 1.4627 0.4311 +v 0.8735 1.4761 0.3987 +v 0.2483 1.4761 0.3987 +v 0.8735 1.4627 0.3662 +v 0.2483 1.4627 0.3662 +v 0.8735 1.4302 0.3528 +v 0.2483 1.4302 0.3528 +v 0.8735 1.3978 0.3662 +v 0.2483 1.3978 0.3662 +v 0.8735 1.5043 0.3987 +v 0.8735 1.5178 0.4311 +v 0.2483 1.5178 0.4311 +v 0.2483 1.5043 0.3987 +v 0.8735 1.5502 0.4446 +v 0.2483 1.5502 0.4446 +v 0.8735 1.5827 0.4311 +v 0.2483 1.5827 0.4311 +v 0.8735 1.5961 0.3987 +v 0.2483 1.5961 0.3987 +v 0.8735 1.5827 0.3662 +v 0.2483 1.5827 0.3662 +v 0.8735 1.5502 0.3528 +v 0.2483 1.5502 0.3528 +v 0.8735 1.5178 0.3662 +v 0.2483 1.5178 0.3662 +v 0.8735 1.6243 0.3987 +v 0.8735 1.6378 0.4311 +v 0.2483 1.6378 0.4311 +v 0.2483 1.6243 0.3987 +v 0.8735 1.6702 0.4446 +v 0.2483 1.6702 0.4446 +v 0.8735 1.7027 0.4311 +v 0.2483 1.7027 0.4311 +v 0.8735 1.7161 0.3987 +v 0.2483 1.7161 0.3987 +v 0.8735 1.7027 0.3662 +v 0.2483 1.7027 0.3662 +v 0.8735 1.6702 0.3528 +v 0.2483 1.6702 0.3528 +v 0.8735 1.6378 0.3662 +v 0.2483 1.6378 0.3662 +v 0.8735 1.7443 0.3987 +v 0.8735 1.7578 0.4311 +v 0.2483 1.7578 0.4311 +v 0.2483 1.7443 0.3987 +v 0.8735 1.7902 0.4446 +v 0.2483 1.7902 0.4446 +v 0.8735 1.8227 0.4311 +v 0.2483 1.8227 0.4311 +v 0.8735 1.8361 0.3987 +v 0.2483 1.8361 0.3987 +v 0.8735 1.8227 0.3662 +v 0.2483 1.8227 0.3662 +v 0.8735 1.7902 0.3528 +v 0.2483 1.7902 0.3528 +v 0.8735 1.7578 0.3662 +v 0.2483 1.7578 0.3662 +v 0.8735 1.8643 0.3987 +v 0.8735 1.8778 0.4311 +v 0.2483 1.8778 0.4311 +v 0.2483 1.8643 0.3987 +v 0.8735 1.9102 0.4446 +v 0.2483 1.9102 0.4446 +v 0.8735 1.9427 0.4311 +v 0.2483 1.9427 0.4311 +v 0.8735 1.9561 0.3987 +v 0.2483 1.9561 0.3987 +v 0.8735 1.9427 0.3662 +v 0.2483 1.9427 0.3662 +v 0.8735 1.9102 0.3528 +v 0.2483 1.9102 0.3528 +v 0.8735 1.8778 0.3662 +v 0.2483 1.8778 0.3662 +v 0.8735 1.9843 0.3987 +v 0.8735 1.9978 0.4311 +v 0.2483 1.9978 0.4311 +v 0.2483 1.9843 0.3987 +v 0.8735 2.0302 0.4446 +v 0.2483 2.0302 0.4446 +v 0.8735 2.0627 0.4311 +v 0.2483 2.0627 0.4311 +v 0.8735 2.0761 0.3987 +v 0.2483 2.0761 0.3987 +v 0.8735 2.0627 0.3662 +v 0.2483 2.0627 0.3662 +v 0.8735 2.0302 0.3528 +v 0.2483 2.0302 0.3528 +v 0.8735 1.9978 0.3662 +v 0.2483 1.9978 0.3662 +v 0.8735 2.1043 0.3987 +v 0.8735 2.1178 0.4311 +v 0.2483 2.1178 0.4311 +v 0.2483 2.1043 0.3987 +v 0.8735 2.1502 0.4446 +v 0.2483 2.1502 0.4446 +v 0.8735 2.1827 0.4311 +v 0.2483 2.1827 0.4311 +v 0.8735 2.1961 0.3987 +v 0.2483 2.1961 0.3987 +v 0.8735 2.1827 0.3662 +v 0.2483 2.1827 0.3662 +v 0.8735 2.1502 0.3528 +v 0.2483 2.1502 0.3528 +v 0.8735 2.1178 0.3662 +v 0.2483 2.1178 0.3662 +v 0.8735 2.2243 0.3987 +v 0.8735 2.2378 0.4311 +v 0.2483 2.2378 0.4311 +v 0.2483 2.2243 0.3987 +v 0.8735 2.2702 0.4446 +v 0.2483 2.2702 0.4446 +v 0.8735 2.3027 0.4311 +v 0.2483 2.3027 0.4311 +v 0.8735 2.3161 0.3987 +v 0.2483 2.3161 0.3987 +v 0.8735 2.3027 0.3662 +v 0.2483 2.3027 0.3662 +v 0.8735 2.2702 0.3528 +v 0.2483 2.2702 0.3528 +v 0.8735 2.2378 0.3662 +v 0.2483 2.2378 0.3662 +v 0.8735 2.3443 0.3987 +v 0.8735 2.3578 0.4311 +v 0.2483 2.3578 0.4311 +v 0.2483 2.3443 0.3987 +v 0.8735 2.3902 0.4446 +v 0.2483 2.3902 0.4446 +v 0.8735 2.4227 0.4311 +v 0.2483 2.4227 0.4311 +v 0.8735 2.4361 0.3987 +v 0.2483 2.4361 0.3987 +v 0.8735 2.4227 0.3662 +v 0.2483 2.4227 0.3662 +v 0.8735 2.3902 0.3528 +v 0.2483 2.3902 0.3528 +v 0.8735 2.3578 0.3662 +v 0.2483 2.3578 0.3662 +v 0.8735 2.4643 0.3987 +v 0.8735 2.4778 0.4311 +v 0.2483 2.4778 0.4311 +v 0.2483 2.4643 0.3987 +v 0.8735 2.5102 0.4446 +v 0.2483 2.5102 0.4446 +v 0.8735 2.5427 0.4311 +v 0.2483 2.5427 0.4311 +v 0.8735 2.5561 0.3987 +v 0.2483 2.5561 0.3987 +v 0.8735 2.5427 0.3662 +v 0.2483 2.5427 0.3662 +v 0.8735 2.5102 0.3528 +v 0.2483 2.5102 0.3528 +v 0.8735 2.4778 0.3662 +v 0.2483 2.4778 0.3662 +v 0.8735 2.5843 0.3987 +v 0.8735 2.5978 0.4311 +v 0.2483 2.5978 0.4311 +v 0.2483 2.5843 0.3987 +v 0.8735 2.6302 0.4446 +v 0.2483 2.6302 0.4446 +v 0.8735 2.6627 0.4311 +v 0.2483 2.6627 0.4311 +v 0.8735 2.6761 0.3987 +v 0.2483 2.6761 0.3987 +v 0.8735 2.6627 0.3662 +v 0.2483 2.6627 0.3662 +v 0.8735 2.6302 0.3528 +v 0.2483 2.6302 0.3528 +v 0.8735 2.5978 0.3662 +v 0.2483 2.5978 0.3662 +v 0.8735 2.7043 0.3987 +v 0.8735 2.7178 0.4311 +v 0.2483 2.7178 0.4311 +v 0.2483 2.7043 0.3987 +v 0.8735 2.7502 0.4446 +v 0.2483 2.7502 0.4446 +v 0.8735 2.7827 0.4311 +v 0.2483 2.7827 0.4311 +v 0.8735 2.7961 0.3987 +v 0.2483 2.7961 0.3987 +v 0.8735 2.7827 0.3662 +v 0.2483 2.7827 0.3662 +v 0.8735 2.7502 0.3528 +v 0.2483 2.7502 0.3528 +v 0.8735 2.7178 0.3662 +v 0.2483 2.7178 0.3662 +v 0.8735 2.8243 0.3987 +v 0.8735 2.8378 0.4311 +v 0.2483 2.8378 0.4311 +v 0.2483 2.8243 0.3987 +v 0.8735 2.8702 0.4446 +v 0.2483 2.8702 0.4446 +v 0.8735 2.9027 0.4311 +v 0.2483 2.9027 0.4311 +v 0.8735 2.9161 0.3987 +v 0.2483 2.9161 0.3987 +v 0.8735 2.9027 0.3662 +v 0.2483 2.9027 0.3662 +v 0.8735 2.8702 0.3528 +v 0.2483 2.8702 0.3528 +v 0.8735 2.8378 0.3662 +v 0.2483 2.8378 0.3662 +v 0.8735 2.9443 0.3987 +v 0.8735 2.9578 0.4311 +v 0.2483 2.9578 0.4311 +v 0.2483 2.9443 0.3987 +v 0.8735 2.9902 0.4446 +v 0.2483 2.9902 0.4446 +v 0.8735 3.0227 0.4311 +v 0.2483 3.0227 0.4311 +v 0.8735 3.0361 0.3987 +v 0.2483 3.0361 0.3987 +v 0.8735 3.0227 0.3662 +v 0.2483 3.0227 0.3662 +v 0.8735 2.9902 0.3528 +v 0.2483 2.9902 0.3528 +v 0.8735 2.9578 0.3662 +v 0.2483 2.9578 0.3662 +v 0.8735 3.0643 0.3987 +v 0.8735 3.0778 0.4311 +v 0.2483 3.0778 0.4311 +v 0.2483 3.0643 0.3987 +v 0.8735 3.1102 0.4446 +v 0.2483 3.1102 0.4446 +v 0.8735 3.1427 0.4311 +v 0.2483 3.1427 0.4311 +v 0.8735 3.1561 0.3987 +v 0.2483 3.1561 0.3987 +v 0.8735 3.1427 0.3662 +v 0.2483 3.1427 0.3662 +v 0.8735 3.1102 0.3528 +v 0.2483 3.1102 0.3528 +v 0.8735 3.0778 0.3662 +v 0.2483 3.0778 0.3662 +v 0.8735 3.1843 0.3987 +v 0.8735 3.1978 0.4311 +v 0.2483 3.1978 0.4311 +v 0.2483 3.1843 0.3987 +v 0.8735 3.2302 0.4446 +v 0.2483 3.2302 0.4446 +v 0.8735 3.2627 0.4311 +v 0.2483 3.2627 0.4311 +v 0.8735 3.2761 0.3987 +v 0.2483 3.2761 0.3987 +v 0.8735 3.2627 0.3662 +v 0.2483 3.2627 0.3662 +v 0.8735 3.2302 0.3528 +v 0.2483 3.2302 0.3528 +v 0.8735 3.1978 0.3662 +v 0.2483 3.1978 0.3662 +v 0.8735 3.3043 0.3987 +v 0.8735 3.3178 0.4311 +v 0.2483 3.3178 0.4311 +v 0.2483 3.3043 0.3987 +v 0.8735 3.3502 0.4446 +v 0.2483 3.3502 0.4446 +v 0.8735 3.3827 0.4311 +v 0.2483 3.3827 0.4311 +v 0.8735 3.3961 0.3987 +v 0.2483 3.3961 0.3987 +v 0.8735 3.3827 0.3662 +v 0.2483 3.3827 0.3662 +v 0.8735 3.3502 0.3528 +v 0.2483 3.3502 0.3528 +v 0.8735 3.3178 0.3662 +v 0.2483 3.3178 0.3662 +v 0.8735 3.4243 0.3987 +v 0.8735 3.4378 0.4311 +v 0.2483 3.4378 0.4311 +v 0.2483 3.4243 0.3987 +v 0.8735 3.4702 0.4446 +v 0.2483 3.4702 0.4446 +v 0.8735 3.5027 0.4311 +v 0.2483 3.5027 0.4311 +v 0.8735 3.5161 0.3987 +v 0.2483 3.5161 0.3987 +v 0.8735 3.5027 0.3662 +v 0.2483 3.5027 0.3662 +v 0.8735 3.4702 0.3528 +v 0.2483 3.4702 0.3528 +v 0.8735 3.4378 0.3662 +v 0.2483 3.4378 0.3662 +v 0.8735 3.5443 0.3987 +v 0.8735 3.5578 0.4311 +v 0.2483 3.5578 0.4311 +v 0.2483 3.5443 0.3987 +v 0.8735 3.5902 0.4446 +v 0.2483 3.5902 0.4446 +v 0.8735 3.6227 0.4311 +v 0.2483 3.6227 0.4311 +v 0.8735 3.6361 0.3987 +v 0.2483 3.6361 0.3987 +v 0.8735 3.6227 0.3662 +v 0.2483 3.6227 0.3662 +v 0.8735 3.5902 0.3528 +v 0.2483 3.5902 0.3528 +v 0.8735 3.5578 0.3662 +v 0.2483 3.5578 0.3662 +v 0.8735 3.6643 0.3987 +v 0.8735 3.6778 0.4311 +v 0.2483 3.6778 0.4311 +v 0.2483 3.6643 0.3987 +v 0.8735 3.7102 0.4446 +v 0.2483 3.7102 0.4446 +v 0.8735 3.7427 0.4311 +v 0.2483 3.7427 0.4311 +v 0.8735 3.7561 0.3987 +v 0.2483 3.7561 0.3987 +v 0.8735 3.7427 0.3662 +v 0.2483 3.7427 0.3662 +v 0.8735 3.7102 0.3528 +v 0.2483 3.7102 0.3528 +v 0.8735 3.6778 0.3662 +v 0.2483 3.6778 0.3662 +v 0.8735 3.7843 0.3987 +v 0.8735 3.7978 0.4311 +v 0.2483 3.7978 0.4311 +v 0.2483 3.7843 0.3987 +v 0.8735 3.8302 0.4446 +v 0.2483 3.8302 0.4446 +v 0.8735 3.8627 0.4311 +v 0.2483 3.8627 0.4311 +v 0.8735 3.8761 0.3987 +v 0.2483 3.8761 0.3987 +v 0.8735 3.8627 0.3662 +v 0.2483 3.8627 0.3662 +v 0.8735 3.8302 0.3528 +v 0.2483 3.8302 0.3528 +v 0.8735 3.7978 0.3662 +v 0.2483 3.7978 0.3662 +v 0.8735 3.9043 0.3987 +v 0.8735 3.9178 0.4311 +v 0.2483 3.9178 0.4311 +v 0.2483 3.9043 0.3987 +v 0.8735 3.9502 0.4446 +v 0.2483 3.9502 0.4446 +v 0.8735 3.9827 0.4311 +v 0.2483 3.9827 0.4311 +v 0.8735 3.9961 0.3987 +v 0.2483 3.9961 0.3987 +v 0.8735 3.9827 0.3662 +v 0.2483 3.9827 0.3662 +v 0.8735 3.9502 0.3528 +v 0.2483 3.9502 0.3528 +v 0.8735 3.9178 0.3662 +v 0.2483 3.9178 0.3662 +v 0.8735 4.0243 0.3987 +v 0.8735 4.0378 0.4311 +v 0.2483 4.0378 0.4311 +v 0.2483 4.0243 0.3987 +v 0.8735 4.0702 0.4446 +v 0.2483 4.0702 0.4446 +v 0.8735 4.1027 0.4311 +v 0.2483 4.1027 0.4311 +v 0.8735 4.1161 0.3987 +v 0.2483 4.1161 0.3987 +v 0.8735 4.1027 0.3662 +v 0.2483 4.1027 0.3662 +v 0.8735 4.0702 0.3528 +v 0.2483 4.0702 0.3528 +v 0.8735 4.0378 0.3662 +v 0.2483 4.0378 0.3662 +v 0.8736 4.1443 0.3987 +v 0.8736 4.1578 0.4311 +v 0.2483 4.1578 0.4311 +v 0.2483 4.1443 0.3987 +v 0.8736 4.1902 0.4446 +v 0.2483 4.1902 0.4446 +v 0.8736 4.2227 0.4311 +v 0.2483 4.2227 0.4311 +v 0.8736 4.2361 0.3987 +v 0.2483 4.2361 0.3987 +v 0.8736 4.2227 0.3662 +v 0.2483 4.2227 0.3662 +v 0.8736 4.1902 0.3528 +v 0.2483 4.1902 0.3528 +v 0.8736 4.1578 0.3662 +v 0.2483 4.1578 0.3662 +v 0.8735 4.2643 0.3987 +v 0.8735 4.2778 0.4311 +v 0.2483 4.2778 0.4311 +v 0.2483 4.2643 0.3987 +v 0.8735 4.3102 0.4446 +v 0.2483 4.3102 0.4446 +v 0.8736 4.3427 0.4311 +v 0.2483 4.3427 0.4311 +v 0.8736 4.3561 0.3987 +v 0.2483 4.3561 0.3987 +v 0.8736 4.3427 0.3662 +v 0.2483 4.3427 0.3662 +v 0.8736 4.3102 0.3528 +v 0.2483 4.3102 0.3528 +v 0.8735 4.2778 0.3662 +v 0.2483 4.2778 0.3662 +v 0.8736 4.3843 0.3987 +v 0.8736 4.3978 0.4311 +v 0.2483 4.3978 0.4311 +v 0.2483 4.3843 0.3987 +v 0.8736 4.4302 0.4446 +v 0.2483 4.4302 0.4446 +v 0.8736 4.4627 0.4311 +v 0.2483 4.4627 0.4311 +v 0.8736 4.4761 0.3987 +v 0.2483 4.4761 0.3987 +v 0.8736 4.4627 0.3662 +v 0.2483 4.4627 0.3662 +v 0.8736 4.4302 0.3528 +v 0.2483 4.4302 0.3528 +v 0.8736 4.3978 0.3662 +v 0.2483 4.3978 0.3662 +v 0.8736 4.5043 0.3987 +v 0.8736 4.5178 0.4311 +v 0.2483 4.5178 0.4311 +v 0.2483 4.5043 0.3987 +v 0.8736 4.5502 0.4446 +v 0.2483 4.5502 0.4446 +v 0.8736 4.5827 0.4311 +v 0.2483 4.5827 0.4311 +v 0.8736 4.5961 0.3987 +v 0.2483 4.5961 0.3987 +v 0.8736 4.5827 0.3662 +v 0.2483 4.5827 0.3662 +v 0.8736 4.5502 0.3528 +v 0.2483 4.5502 0.3528 +v 0.8736 4.5178 0.3662 +v 0.2483 4.5178 0.3662 +v 0.8736 4.6243 0.3987 +v 0.8736 4.6378 0.4311 +v 0.2483 4.6378 0.4311 +v 0.2483 4.6243 0.3987 +v 0.8736 4.6702 0.4446 +v 0.2483 4.6702 0.4446 +v 0.8736 4.7027 0.4311 +v 0.2483 4.7027 0.4311 +v 0.8736 4.7161 0.3987 +v 0.2483 4.7161 0.3987 +v 0.8736 4.7027 0.3662 +v 0.2483 4.7027 0.3662 +v 0.8736 4.6702 0.3528 +v 0.2483 4.6702 0.3528 +v 0.8736 4.6378 0.3662 +v 0.2483 4.6378 0.3662 +v 0.8736 4.7443 0.3987 +v 0.8736 4.7578 0.4311 +v 0.2483 4.7578 0.4311 +v 0.2483 4.7443 0.3987 +v 0.8736 4.7902 0.4446 +v 0.2483 4.7902 0.4446 +v 0.8736 4.8227 0.4311 +v 0.2483 4.8227 0.4311 +v 0.8736 4.8361 0.3987 +v 0.2483 4.8361 0.3987 +v 0.8736 4.8227 0.3662 +v 0.2483 4.8227 0.3662 +v 0.8736 4.7902 0.3528 +v 0.2483 4.7902 0.3528 +v 0.8736 4.7578 0.3662 +v 0.2483 4.7578 0.3662 +v 0.8736 4.8643 0.3987 +v 0.8736 4.8778 0.4311 +v 0.2483 4.8778 0.4311 +v 0.2483 4.8643 0.3987 +v 0.8736 4.9102 0.4446 +v 0.2483 4.9102 0.4446 +v 0.8736 4.9427 0.4311 +v 0.2483 4.9427 0.4311 +v 0.8736 4.9561 0.3987 +v 0.2483 4.9561 0.3987 +v 0.8736 4.9427 0.3662 +v 0.2483 4.9427 0.3662 +v 0.8736 4.9102 0.3528 +v 0.2483 4.9102 0.3528 +v 0.8736 4.8778 0.3662 +v 0.2483 4.8778 0.3662 +v 0.8736 4.9843 0.3987 +v 0.8736 4.9978 0.4311 +v 0.2483 4.9978 0.4311 +v 0.2483 4.9843 0.3987 +v 0.8736 5.0302 0.4446 +v 0.2483 5.0302 0.4446 +v 0.8736 5.0627 0.4311 +v 0.2483 5.0627 0.4311 +v 0.8736 5.0761 0.3987 +v 0.2483 5.0761 0.3987 +v 0.8736 5.0627 0.3662 +v 0.2483 5.0627 0.3662 +v 0.8736 5.0302 0.3528 +v 0.2483 5.0302 0.3528 +v 0.8736 4.9978 0.3662 +v 0.2483 4.9978 0.3662 +v 0.8736 5.1043 0.3987 +v 0.8736 5.1178 0.4311 +v 0.2483 5.1178 0.4311 +v 0.2483 5.1043 0.3987 +v 0.8736 5.1502 0.4446 +v 0.2483 5.1502 0.4446 +v 0.8736 5.1827 0.4311 +v 0.2483 5.1827 0.4311 +v 0.8736 5.1961 0.3987 +v 0.2483 5.1961 0.3987 +v 0.8736 5.1827 0.3662 +v 0.2483 5.1827 0.3662 +v 0.8736 5.1502 0.3528 +v 0.2483 5.1502 0.3528 +v 0.8736 5.1178 0.3662 +v 0.2483 5.1178 0.3662 +v 0.8736 5.2243 0.3987 +v 0.8736 5.2378 0.4311 +v 0.2483 5.2378 0.4311 +v 0.2483 5.2243 0.3987 +v 0.8736 5.2702 0.4446 +v 0.2483 5.2702 0.4446 +v 0.8736 5.3027 0.4311 +v 0.2483 5.3027 0.4311 +v 0.8736 5.3161 0.3987 +v 0.2483 5.3161 0.3987 +v 0.8736 5.3027 0.3662 +v 0.2483 5.3027 0.3662 +v 0.8736 5.2702 0.3528 +v 0.2483 5.2702 0.3528 +v 0.8736 5.2378 0.3662 +v 0.2483 5.2378 0.3662 +v 0.8736 5.3443 0.3987 +v 0.8736 5.3578 0.4311 +v 0.2483 5.3578 0.4311 +v 0.2483 5.3443 0.3987 +v 0.8736 5.3902 0.4446 +v 0.2483 5.3902 0.4446 +v 0.8736 5.4227 0.4311 +v 0.2483 5.4227 0.4311 +v 0.8736 5.4361 0.3987 +v 0.2483 5.4361 0.3987 +v 0.8736 5.4227 0.3662 +v 0.2483 5.4227 0.3662 +v 0.8736 5.3902 0.3528 +v 0.2483 5.3902 0.3528 +v 0.8736 5.3578 0.3662 +v 0.2483 5.3578 0.3662 +v 0.8736 5.4643 0.3987 +v 0.8736 5.4778 0.4311 +v 0.2483 5.4778 0.4311 +v 0.2483 5.4643 0.3987 +v 0.8736 5.5102 0.4446 +v 0.2483 5.5102 0.4446 +v 0.8736 5.5427 0.4311 +v 0.2483 5.5427 0.4311 +v 0.8736 5.5561 0.3987 +v 0.2483 5.5561 0.3987 +v 0.8736 5.5427 0.3662 +v 0.2483 5.5427 0.3662 +v 0.8736 5.5102 0.3528 +v 0.2483 5.5102 0.3528 +v 0.8736 5.4778 0.3662 +v 0.2483 5.4778 0.3662 +v 0.8736 5.5843 0.3987 +v 0.8736 5.5978 0.4311 +v 0.2483 5.5978 0.4311 +v 0.2483 5.5843 0.3987 +v 0.8736 5.6302 0.4446 +v 0.2483 5.6302 0.4446 +v 0.8736 5.6627 0.4311 +v 0.2483 5.6627 0.4311 +v 0.8736 5.6761 0.3987 +v 0.2483 5.6761 0.3987 +v 0.8736 5.6627 0.3662 +v 0.2483 5.6627 0.3662 +v 0.8736 5.6302 0.3528 +v 0.2483 5.6302 0.3528 +v 0.8736 5.5978 0.3662 +v 0.2483 5.5978 0.3662 +v 0.8736 5.7043 0.3987 +v 0.8736 5.7178 0.4311 +v 0.2483 5.7178 0.4311 +v 0.2483 5.7043 0.3987 +v 0.8736 5.7502 0.4446 +v 0.2483 5.7502 0.4446 +v 0.8736 5.7827 0.4311 +v 0.2483 5.7827 0.4311 +v 0.8736 5.7961 0.3987 +v 0.2483 5.7961 0.3987 +v 0.8736 5.7827 0.3662 +v 0.2483 5.7827 0.3662 +v 0.8736 5.7502 0.3528 +v 0.2483 5.7502 0.3528 +v 0.8736 5.7178 0.3662 +v 0.2483 5.7178 0.3662 +v 0.8736 5.8243 0.3987 +v 0.8736 5.8378 0.4311 +v 0.2483 5.8378 0.4311 +v 0.2483 5.8243 0.3987 +v 0.8736 5.8702 0.4446 +v 0.2483 5.8702 0.4446 +v 0.8736 5.9027 0.4311 +v 0.2483 5.9027 0.4311 +v 0.8736 5.9161 0.3987 +v 0.2483 5.9161 0.3987 +v 0.8736 5.9027 0.3662 +v 0.2483 5.9027 0.3662 +v 0.8736 5.8702 0.3528 +v 0.2483 5.8702 0.3528 +v 0.8736 5.8378 0.3662 +v 0.2483 5.8378 0.3662 +v 0.8736 5.9443 0.3987 +v 0.8736 5.9578 0.4311 +v 0.2483 5.9578 0.4311 +v 0.2483 5.9443 0.3987 +v 0.8736 5.9902 0.4446 +v 0.2483 5.9902 0.4446 +v 0.8736 6.0227 0.4311 +v 0.2483 6.0227 0.4311 +v 0.8736 6.0361 0.3987 +v 0.2483 6.0361 0.3987 +v 0.8736 6.0227 0.3662 +v 0.2483 6.0227 0.3662 +v 0.8736 5.9902 0.3528 +v 0.2483 5.9902 0.3528 +v 0.8736 5.9578 0.3662 +v 0.2483 5.9578 0.3662 +v 0.8736 6.0643 0.3987 +v 0.8736 6.0778 0.4311 +v 0.2483 6.0778 0.4311 +v 0.2483 6.0643 0.3987 +v 0.8736 6.1102 0.4446 +v 0.2483 6.1102 0.4446 +v 0.8736 6.1427 0.4311 +v 0.2483 6.1427 0.4311 +v 0.8736 6.1561 0.3987 +v 0.2483 6.1561 0.3987 +v 0.8736 6.1427 0.3662 +v 0.2483 6.1427 0.3662 +v 0.8736 6.1102 0.3528 +v 0.2483 6.1102 0.3528 +v 0.8736 6.0778 0.3662 +v 0.2483 6.0778 0.3662 +v 0.8736 6.1843 0.3987 +v 0.8736 6.1978 0.4311 +v 0.2483 6.1978 0.4311 +v 0.2483 6.1843 0.3987 +v 0.8736 6.2302 0.4446 +v 0.2483 6.2302 0.4446 +v 0.8736 6.2627 0.4311 +v 0.2483 6.2627 0.4311 +v 0.8736 6.2761 0.3987 +v 0.2483 6.2761 0.3987 +v 0.8736 6.2627 0.3662 +v 0.2483 6.2627 0.3662 +v 0.8736 6.2302 0.3528 +v 0.2483 6.2302 0.3528 +v 0.8736 6.1978 0.3662 +v 0.2483 6.1978 0.3662 +v 0.8736 6.3043 0.3987 +v 0.8736 6.3178 0.4311 +v 0.2483 6.3178 0.4311 +v 0.2483 6.3043 0.3987 +v 0.8736 6.3502 0.4446 +v 0.2483 6.3502 0.4446 +v 0.8736 6.3827 0.4311 +v 0.2483 6.3827 0.4311 +v 0.8736 6.3961 0.3987 +v 0.2483 6.3961 0.3987 +v 0.8736 6.3827 0.3662 +v 0.2483 6.3827 0.3662 +v 0.8736 6.3502 0.3528 +v 0.2483 6.3502 0.3528 +v 0.8736 6.3178 0.3662 +v 0.2483 6.3178 0.3662 +v 0.8736 6.4243 0.3987 +v 0.8736 6.4378 0.4311 +v 0.2483 6.4378 0.4311 +v 0.2483 6.4243 0.3987 +v 0.8736 6.4702 0.4446 +v 0.2483 6.4702 0.4446 +v 0.8736 6.5027 0.4311 +v 0.2483 6.5027 0.4311 +v 0.8736 6.5161 0.3987 +v 0.2483 6.5161 0.3987 +v 0.8736 6.5027 0.3662 +v 0.2483 6.5027 0.3662 +v 0.8736 6.4702 0.3528 +v 0.2483 6.4702 0.3528 +v 0.8736 6.4378 0.3662 +v 0.2483 6.4378 0.3662 +v 0.8736 6.5443 0.3987 +v 0.8736 6.5578 0.4311 +v 0.2483 6.5578 0.4311 +v 0.2483 6.5443 0.3987 +v 0.8736 6.5902 0.4446 +v 0.2483 6.5902 0.4446 +v 0.8736 6.6227 0.4311 +v 0.2483 6.6227 0.4311 +v 0.8736 6.6361 0.3987 +v 0.2483 6.6361 0.3987 +v 0.8736 6.6227 0.3662 +v 0.2483 6.6227 0.3662 +v 0.8736 6.5902 0.3528 +v 0.2483 6.5902 0.3528 +v 0.8736 6.5578 0.3662 +v 0.2483 6.5578 0.3662 +v 0.8736 6.6643 0.3987 +v 0.8736 6.6778 0.4311 +v 0.2483 6.6778 0.4311 +v 0.2483 6.6643 0.3987 +v 0.8736 6.7102 0.4446 +v 0.2483 6.7102 0.4446 +v 0.8736 6.7427 0.4311 +v 0.2483 6.7427 0.4311 +v 0.8736 6.7561 0.3987 +v 0.2483 6.7561 0.3987 +v 0.8736 6.7427 0.3662 +v 0.2483 6.7427 0.3662 +v 0.8736 6.7102 0.3528 +v 0.2483 6.7102 0.3528 +v 0.8736 6.6778 0.3662 +v 0.2483 6.6778 0.3662 +v 0.8736 6.7843 0.3987 +v 0.8736 6.7978 0.4311 +v 0.2483 6.7978 0.4311 +v 0.2483 6.7843 0.3987 +v 0.8736 6.8302 0.4446 +v 0.2483 6.8302 0.4446 +v 0.8736 6.8627 0.4311 +v 0.2483 6.8627 0.4311 +v 0.8736 6.8761 0.3987 +v 0.2483 6.8761 0.3987 +v 0.8736 6.8627 0.3662 +v 0.2483 6.8627 0.3662 +v 0.8736 6.8302 0.3528 +v 0.2483 6.8302 0.3528 +v 0.8736 6.7978 0.3662 +v 0.2483 6.7978 0.3662 +v 0.8736 6.9043 0.3987 +v 0.8736 6.9178 0.4311 +v 0.2483 6.9178 0.4311 +v 0.2483 6.9043 0.3987 +v 0.8736 6.9502 0.4446 +v 0.2483 6.9502 0.4446 +v 0.8736 6.9827 0.4311 +v 0.2483 6.9827 0.4311 +v 0.8736 6.9961 0.3987 +v 0.2483 6.9961 0.3987 +v 0.8736 6.9827 0.3662 +v 0.2483 6.9827 0.3662 +v 0.8736 6.9502 0.3528 +v 0.2483 6.9502 0.3528 +v 0.8736 6.9178 0.3662 +v 0.2483 6.9178 0.3662 +v 0.8736 7.0243 0.3987 +v 0.8736 7.0378 0.4311 +v 0.2483 7.0378 0.4311 +v 0.2483 7.0243 0.3987 +v 0.8736 7.0702 0.4446 +v 0.2483 7.0702 0.4446 +v 0.8736 7.1027 0.4311 +v 0.2483 7.1027 0.4311 +v 0.8736 7.1161 0.3987 +v 0.2483 7.1161 0.3987 +v 0.8736 7.1027 0.3662 +v 0.2483 7.1027 0.3662 +v 0.8736 7.0702 0.3528 +v 0.2483 7.0702 0.3528 +v 0.8736 7.0378 0.3662 +v 0.2483 7.0378 0.3662 +v 0.8736 7.1443 0.3987 +v 0.8736 7.1578 0.4311 +v 0.2483 7.1578 0.4311 +v 0.2483 7.1443 0.3987 +v 0.8736 7.1902 0.4446 +v 0.2483 7.1902 0.4446 +v 0.8736 7.2227 0.4311 +v 0.2483 7.2227 0.4311 +v 0.8736 7.2361 0.3987 +v 0.2483 7.2361 0.3987 +v 0.8736 7.2227 0.3662 +v 0.2483 7.2227 0.3662 +v 0.8736 7.1902 0.3528 +v 0.2483 7.1902 0.3528 +v 0.8736 7.1578 0.3662 +v 0.2483 7.1578 0.3662 +v 0.8736 7.2643 0.3987 +v 0.8736 7.2778 0.4311 +v 0.2483 7.2778 0.4311 +v 0.2483 7.2643 0.3987 +v 0.8736 7.3102 0.4446 +v 0.2483 7.3102 0.4446 +v 0.8736 7.3427 0.4311 +v 0.2483 7.3427 0.4311 +v 0.8736 7.3561 0.3987 +v 0.2483 7.3561 0.3987 +v 0.8736 7.3427 0.3662 +v 0.2483 7.3427 0.3662 +v 0.8736 7.3102 0.3528 +v 0.2483 7.3102 0.3528 +v 0.8736 7.2778 0.3662 +v 0.2483 7.2778 0.3662 +v 0.8736 7.3843 0.3987 +v 0.8736 7.3978 0.4311 +v 0.2483 7.3978 0.4311 +v 0.2483 7.3843 0.3987 +v 0.8736 7.4302 0.4446 +v 0.2483 7.4302 0.4446 +v 0.8736 7.4627 0.4311 +v 0.2483 7.4627 0.4311 +v 0.8736 7.4761 0.3987 +v 0.2483 7.4761 0.3987 +v 0.8736 7.4627 0.3662 +v 0.2483 7.4627 0.3662 +v 0.8736 7.4302 0.3528 +v 0.2483 7.4302 0.3528 +v 0.8736 7.3978 0.3662 +v 0.2483 7.3978 0.3662 +v 0.8736 7.5043 0.3987 +v 0.8736 7.5178 0.4311 +v 0.2483 7.5178 0.4311 +v 0.2483 7.5043 0.3987 +v 0.8736 7.5502 0.4446 +v 0.2483 7.5502 0.4446 +v 0.8736 7.5827 0.4311 +v 0.2483 7.5827 0.4311 +v 0.8736 7.5961 0.3987 +v 0.2483 7.5961 0.3987 +v 0.8736 7.5827 0.3662 +v 0.2483 7.5827 0.3662 +v 0.8736 7.5502 0.3528 +v 0.2483 7.5502 0.3528 +v 0.8736 7.5178 0.3662 +v 0.2483 7.5178 0.3662 +v 0.8736 7.6243 0.3987 +v 0.8736 7.6378 0.4311 +v 0.2483 7.6378 0.4311 +v 0.2483 7.6243 0.3987 +v 0.8736 7.6702 0.4446 +v 0.2483 7.6702 0.4446 +v 0.8736 7.7027 0.4311 +v 0.2483 7.7027 0.4311 +v 0.8736 7.7161 0.3987 +v 0.2483 7.7161 0.3987 +v 0.8736 7.7027 0.3662 +v 0.2483 7.7027 0.3662 +v 0.8736 7.6702 0.3528 +v 0.2483 7.6702 0.3528 +v 0.8736 7.6378 0.3662 +v 0.2483 7.6378 0.3662 +v 0.8736 7.7443 0.3987 +v 0.8736 7.7578 0.4311 +v 0.2483 7.7578 0.4311 +v 0.2483 7.7443 0.3987 +v 0.8736 7.7902 0.4446 +v 0.2483 7.7902 0.4446 +v 0.8736 7.8227 0.4311 +v 0.2483 7.8227 0.4311 +v 0.8736 7.8361 0.3987 +v 0.2483 7.8361 0.3987 +v 0.8736 7.8227 0.3662 +v 0.2483 7.8227 0.3662 +v 0.8736 7.7902 0.3528 +v 0.2483 7.7902 0.3528 +v 0.8736 7.7578 0.3662 +v 0.2483 7.7578 0.3662 +v 0.8736 7.8643 0.3987 +v 0.8736 7.8778 0.4311 +v 0.2483 7.8778 0.4311 +v 0.2483 7.8643 0.3987 +v 0.8736 7.9102 0.4446 +v 0.2483 7.9102 0.4446 +v 0.8736 7.9427 0.4311 +v 0.2483 7.9427 0.4311 +v 0.8736 7.9561 0.3987 +v 0.2483 7.9561 0.3987 +v 0.8736 7.9427 0.3662 +v 0.2483 7.9427 0.3662 +v 0.8736 7.9102 0.3528 +v 0.2483 7.9102 0.3528 +v 0.8736 7.8778 0.3662 +v 0.2483 7.8778 0.3662 +v 0.8736 7.9843 0.3987 +v 0.8736 7.9978 0.4311 +v 0.2483 7.9978 0.4311 +v 0.2483 7.9843 0.3987 +v 0.8736 8.0302 0.4446 +v 0.2483 8.0302 0.4446 +v 0.8736 8.0627 0.4311 +v 0.2483 8.0627 0.4311 +v 0.8736 8.0761 0.3987 +v 0.2483 8.0761 0.3987 +v 0.8736 8.0627 0.3662 +v 0.2483 8.0627 0.3662 +v 0.8736 8.0302 0.3528 +v 0.2483 8.0302 0.3528 +v 0.8736 7.9978 0.3662 +v 0.2483 7.9978 0.3662 +v 0.8736 8.1043 0.3987 +v 0.8736 8.1178 0.4311 +v 0.2483 8.1178 0.4311 +v 0.2483 8.1043 0.3987 +v 0.8736 8.1502 0.4446 +v 0.2483 8.1502 0.4446 +v 0.8736 8.1827 0.4311 +v 0.2483 8.1827 0.4311 +v 0.8736 8.1961 0.3987 +v 0.2483 8.1961 0.3987 +v 0.8736 8.1827 0.3662 +v 0.2483 8.1827 0.3662 +v 0.8736 8.1502 0.3528 +v 0.2483 8.1502 0.3528 +v 0.8736 8.1178 0.3662 +v 0.2483 8.1178 0.3662 +# 1536 vertices + +vn 0.0000 -1.0000 0.0000 +vn -0.0000 -0.7071 0.7071 +vn -0.0000 -1.0000 -0.0000 +vn -0.0000 -0.0000 1.0000 +vn -0.0000 0.7071 0.7071 +vn 0.0000 1.0000 0.0000 +vn 0.0000 0.7071 -0.7071 +vn 0.0000 -0.0000 -1.0000 +vn 0.0000 -0.7071 -0.7071 +vn 0.0000 -1.0000 -0.0000 +vn -0.0000 0.0000 1.0000 +vn -0.0000 1.0000 0.0000 +vn 0.0000 1.0000 -0.0000 +vn 0.0000 0.0000 -1.0000 +vn -0.0000 -1.0000 0.0000 +vn -0.0000 1.0000 -0.0000 +vn -0.0000 -0.7071 -0.7071 +vn 0.0000 0.7071 0.7071 +# 18 vertex normals + +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3674 0.0000 +vt 0.3716 0.3674 0.0000 +vt 0.3846 0.3670 0.0000 +vt 0.3716 0.3670 0.0000 +vt 0.3846 0.3661 0.0000 +vt 0.3716 0.3661 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +vt 0.3846 0.3648 0.0000 +vt 0.3716 0.3648 0.0000 +vt 0.3846 0.3652 0.0000 +vt 0.3716 0.3652 0.0000 +# 1536 texture coords + +g Conveyor_Rollers +usemtl ShippingContainer +s 8 +f 4425/4429/190 4426/4430/191 4427/4431/191 4428/4432/192 +f 4426/4430/191 4429/4433/193 4430/4434/193 4427/4431/191 +f 4429/4433/193 4431/4435/194 4432/4436/194 4430/4434/193 +f 4431/4435/194 4433/4437/195 4434/4438/195 4432/4436/194 +f 4433/4437/195 4435/4439/196 4436/4440/196 4434/4438/195 +f 4435/4439/196 4437/4441/197 4438/4442/197 4436/4440/196 +f 4437/4441/197 4439/4443/198 4440/4444/198 4438/4442/197 +f 4439/4443/198 4425/4429/190 4428/4432/192 4440/4444/198 +f 4441/4445/190 4442/4446/191 4443/4447/191 4444/4448/199 +f 4442/4446/191 4445/4449/193 4446/4450/200 4443/4447/191 +f 4445/4449/193 4447/4451/194 4448/4452/194 4446/4450/200 +f 4447/4451/194 4449/4453/201 4450/4454/202 4448/4452/194 +f 4449/4453/201 4451/4455/196 4452/4456/196 4450/4454/202 +f 4451/4455/196 4453/4457/203 4454/4458/203 4452/4456/196 +f 4453/4457/203 4455/4459/198 4456/4460/198 4454/4458/203 +f 4455/4459/198 4441/4445/190 4444/4448/199 4456/4460/198 +f 4457/4461/204 4458/4462/191 4459/4463/191 4460/4464/192 +f 4458/4462/191 4461/4465/200 4462/4466/193 4459/4463/191 +f 4461/4465/200 4463/4467/194 4464/4468/194 4462/4466/193 +f 4463/4467/194 4465/4469/205 4466/4470/202 4464/4468/194 +f 4465/4469/205 4467/4471/196 4468/4472/196 4466/4470/202 +f 4467/4471/196 4469/4473/203 4470/4474/197 4468/4472/196 +f 4469/4473/203 4471/4475/206 4472/4476/198 4470/4474/197 +f 4471/4475/206 4457/4461/204 4460/4464/192 4472/4476/198 +f 4473/4477/190 4474/4478/191 4475/4479/191 4476/4480/192 +f 4474/4478/191 4477/4481/193 4478/4482/200 4475/4479/191 +f 4477/4481/193 4479/4483/194 4480/4484/194 4478/4482/200 +f 4479/4483/194 4481/4485/201 4482/4486/202 4480/4484/194 +f 4481/4485/201 4483/4487/196 4484/4488/196 4482/4486/202 +f 4483/4487/196 4485/4489/197 4486/4490/203 4484/4488/196 +f 4485/4489/197 4487/4491/198 4488/4492/198 4486/4490/203 +f 4487/4491/198 4473/4477/190 4476/4480/192 4488/4492/198 +f 4489/4493/204 4490/4494/191 4491/4495/191 4492/4496/204 +f 4490/4494/191 4493/4497/200 4494/4498/193 4491/4495/191 +f 4493/4497/200 4495/4499/207 4496/4500/194 4494/4498/193 +f 4495/4499/207 4497/4501/195 4498/4502/202 4496/4500/194 +f 4497/4501/195 4499/4503/196 4500/4504/196 4498/4502/202 +f 4499/4503/196 4501/4505/203 4502/4506/197 4500/4504/196 +f 4501/4505/203 4503/4507/198 4504/4508/198 4502/4506/197 +f 4503/4507/198 4489/4493/204 4492/4496/204 4504/4508/198 +f 4505/4509/192 4506/4510/191 4507/4511/191 4508/4512/192 +f 4506/4510/191 4509/4513/193 4510/4514/200 4507/4511/191 +f 4509/4513/193 4511/4515/194 4512/4516/194 4510/4514/200 +f 4511/4515/194 4513/4517/202 4514/4518/202 4512/4516/194 +f 4513/4517/202 4515/4519/196 4516/4520/196 4514/4518/202 +f 4515/4519/196 4517/4521/197 4518/4522/203 4516/4520/196 +f 4517/4521/197 4519/4523/198 4520/4524/198 4518/4522/203 +f 4519/4523/198 4505/4509/192 4508/4512/192 4520/4524/198 +f 4521/4525/192 4522/4526/191 4523/4527/191 4524/4528/192 +f 4522/4526/191 4525/4529/200 4526/4530/193 4523/4527/191 +f 4525/4529/200 4527/4531/194 4528/4532/194 4526/4530/193 +f 4527/4531/194 4529/4533/202 4530/4534/202 4528/4532/194 +f 4529/4533/202 4531/4535/196 4532/4536/196 4530/4534/202 +f 4531/4535/196 4533/4537/203 4534/4538/197 4532/4536/196 +f 4533/4537/203 4535/4539/198 4536/4540/198 4534/4538/197 +f 4535/4539/198 4521/4525/192 4524/4528/192 4536/4540/198 +f 4537/4541/199 4538/4542/191 4539/4543/191 4540/4544/199 +f 4538/4542/191 4541/4545/193 4542/4546/193 4539/4543/191 +f 4541/4545/193 4543/4547/194 4544/4548/194 4542/4546/193 +f 4543/4547/194 4545/4549/202 4546/4550/195 4544/4548/194 +f 4545/4549/202 4547/4551/196 4548/4552/196 4546/4550/195 +f 4547/4551/196 4549/4553/197 4550/4554/197 4548/4552/196 +f 4549/4553/197 4551/4555/198 4552/4556/198 4550/4554/197 +f 4551/4555/198 4537/4541/199 4540/4544/199 4552/4556/198 +f 4553/4557/204 4554/4558/191 4555/4559/191 4556/4560/204 +f 4554/4558/191 4557/4561/200 4558/4562/193 4555/4559/191 +f 4557/4561/200 4559/4563/194 4560/4564/194 4558/4562/193 +f 4559/4563/194 4561/4565/202 4562/4566/202 4560/4564/194 +f 4561/4565/202 4563/4567/196 4564/4568/196 4562/4566/202 +f 4563/4567/196 4565/4569/197 4566/4570/197 4564/4568/196 +f 4565/4569/197 4567/4571/198 4568/4572/198 4566/4570/197 +f 4567/4571/198 4553/4557/204 4556/4560/204 4568/4572/198 +f 4569/4573/204 4570/4574/191 4571/4575/191 4572/4576/204 +f 4570/4574/191 4573/4577/193 4574/4578/200 4571/4575/191 +f 4573/4577/193 4575/4579/194 4576/4580/194 4574/4578/200 +f 4575/4579/194 4577/4581/201 4578/4582/202 4576/4580/194 +f 4577/4581/201 4579/4583/196 4580/4584/196 4578/4582/202 +f 4579/4583/196 4581/4585/197 4582/4586/203 4580/4584/196 +f 4581/4585/197 4583/4587/206 4584/4588/206 4582/4586/203 +f 4583/4587/206 4569/4573/204 4572/4576/204 4584/4588/206 +f 4585/4589/192 4586/4590/191 4587/4591/191 4588/4592/204 +f 4586/4590/191 4589/4593/193 4590/4594/193 4587/4591/191 +f 4589/4593/193 4591/4595/194 4592/4596/194 4590/4594/193 +f 4591/4595/194 4593/4597/202 4594/4598/201 4592/4596/194 +f 4593/4597/202 4595/4599/196 4596/4600/196 4594/4598/201 +f 4595/4599/196 4597/4601/197 4598/4602/197 4596/4600/196 +f 4597/4601/197 4599/4603/198 4600/4604/198 4598/4602/197 +f 4599/4603/198 4585/4589/192 4588/4592/204 4600/4604/198 +f 4601/4605/192 4602/4606/191 4603/4607/191 4604/4608/190 +f 4602/4606/191 4605/4609/193 4606/4610/193 4603/4607/191 +f 4605/4609/193 4607/4611/207 4608/4612/194 4606/4610/193 +f 4607/4611/207 4609/4613/202 4610/4614/195 4608/4612/194 +f 4609/4613/202 4611/4615/196 4612/4616/196 4610/4614/195 +f 4611/4615/196 4613/4617/197 4614/4618/197 4612/4616/196 +f 4613/4617/197 4615/4619/198 4616/4620/198 4614/4618/197 +f 4615/4619/198 4601/4605/192 4604/4608/190 4616/4620/198 +f 4617/4621/192 4618/4622/191 4619/4623/191 4620/4624/199 +f 4618/4622/191 4621/4625/200 4622/4626/200 4619/4623/191 +f 4621/4625/200 4623/4627/194 4624/4628/194 4622/4626/200 +f 4623/4627/194 4625/4629/202 4626/4630/205 4624/4628/194 +f 4625/4629/202 4627/4631/196 4628/4632/196 4626/4630/205 +f 4627/4631/196 4629/4633/203 4630/4634/203 4628/4632/196 +f 4629/4633/203 4631/4635/198 4632/4636/198 4630/4634/203 +f 4631/4635/198 4617/4621/192 4620/4624/199 4632/4636/198 +f 4633/4637/192 4634/4638/191 4635/4639/191 4636/4640/204 +f 4634/4638/191 4637/4641/193 4638/4642/200 4635/4639/191 +f 4637/4641/193 4639/4643/194 4640/4644/194 4638/4642/200 +f 4639/4643/194 4641/4645/202 4642/4646/205 4640/4644/194 +f 4641/4645/202 4643/4647/196 4644/4648/196 4642/4646/205 +f 4643/4647/196 4645/4649/197 4646/4650/203 4644/4648/196 +f 4645/4649/197 4647/4651/206 4648/4652/198 4646/4650/203 +f 4647/4651/206 4633/4637/192 4636/4640/204 4648/4652/198 +f 4649/4653/204 4650/4654/191 4651/4655/191 4652/4656/199 +f 4650/4654/191 4653/4657/200 4654/4658/200 4651/4655/191 +f 4653/4657/200 4655/4659/194 4656/4660/194 4654/4658/200 +f 4655/4659/194 4657/4661/201 4658/4662/202 4656/4660/194 +f 4657/4661/201 4659/4663/196 4660/4664/196 4658/4662/202 +f 4659/4663/196 4661/4665/203 4662/4666/203 4660/4664/196 +f 4661/4665/203 4663/4667/198 4664/4668/198 4662/4666/203 +f 4663/4667/198 4649/4653/204 4652/4656/199 4664/4668/198 +f 4665/4669/204 4666/4670/191 4667/4671/191 4668/4672/190 +f 4666/4670/191 4669/4673/193 4670/4674/193 4667/4671/191 +f 4669/4673/193 4671/4675/194 4672/4676/194 4670/4674/193 +f 4671/4675/194 4673/4677/195 4674/4678/201 4672/4676/194 +f 4673/4677/195 4675/4679/196 4676/4680/196 4674/4678/201 +f 4675/4679/196 4677/4681/197 4678/4682/197 4676/4680/196 +f 4677/4681/197 4679/4683/198 4680/4684/198 4678/4682/197 +f 4679/4683/198 4665/4669/204 4668/4672/190 4680/4684/198 +f 4681/4685/192 4682/4686/191 4683/4687/191 4684/4688/190 +f 4682/4686/191 4685/4689/200 4686/4690/200 4683/4687/191 +f 4685/4689/200 4687/4691/194 4688/4692/194 4686/4690/200 +f 4687/4691/194 4689/4693/195 4690/4694/201 4688/4692/194 +f 4689/4693/195 4691/4695/196 4692/4696/196 4690/4694/201 +f 4691/4695/196 4693/4697/203 4694/4698/203 4692/4696/196 +f 4693/4697/203 4695/4699/198 4696/4700/198 4694/4698/203 +f 4695/4699/198 4681/4685/192 4684/4688/190 4696/4700/198 +f 4697/4701/204 4698/4702/191 4699/4703/191 4700/4704/204 +f 4698/4702/191 4701/4705/200 4702/4706/200 4699/4703/191 +f 4701/4705/200 4703/4707/194 4704/4708/194 4702/4706/200 +f 4703/4707/194 4705/4709/201 4706/4710/201 4704/4708/194 +f 4705/4709/201 4707/4711/196 4708/4712/196 4706/4710/201 +f 4707/4711/196 4709/4713/203 4710/4714/203 4708/4712/196 +f 4709/4713/203 4711/4715/198 4712/4716/198 4710/4714/203 +f 4711/4715/198 4697/4701/204 4700/4704/204 4712/4716/198 +f 4713/4717/204 4714/4718/191 4715/4719/191 4716/4720/204 +f 4714/4718/191 4717/4721/193 4718/4722/193 4715/4719/191 +f 4717/4721/193 4719/4723/194 4720/4724/194 4718/4722/193 +f 4719/4723/194 4721/4725/201 4722/4726/201 4720/4724/194 +f 4721/4725/201 4723/4727/196 4724/4728/196 4722/4726/201 +f 4723/4727/196 4725/4729/197 4726/4730/197 4724/4728/196 +f 4725/4729/197 4727/4731/198 4728/4732/198 4726/4730/197 +f 4727/4731/198 4713/4717/204 4716/4720/204 4728/4732/198 +f 4729/4733/204 4730/4734/191 4731/4735/191 4732/4736/204 +f 4730/4734/191 4733/4737/193 4734/4738/193 4731/4735/191 +f 4733/4737/193 4735/4739/194 4736/4740/194 4734/4738/193 +f 4735/4739/194 4737/4741/201 4738/4742/201 4736/4740/194 +f 4737/4741/201 4739/4743/196 4740/4744/196 4738/4742/201 +f 4739/4743/196 4741/4745/197 4742/4746/197 4740/4744/196 +f 4741/4745/197 4743/4747/198 4744/4748/198 4742/4746/197 +f 4743/4747/198 4729/4733/204 4732/4736/204 4744/4748/198 +f 4745/4749/204 4746/4750/191 4747/4751/191 4748/4752/204 +f 4746/4750/191 4749/4753/193 4750/4754/193 4747/4751/191 +f 4749/4753/193 4751/4755/194 4752/4756/194 4750/4754/193 +f 4751/4755/194 4753/4757/201 4754/4758/201 4752/4756/194 +f 4753/4757/201 4755/4759/196 4756/4760/196 4754/4758/201 +f 4755/4759/196 4757/4761/197 4758/4762/197 4756/4760/196 +f 4757/4761/197 4759/4763/198 4760/4764/198 4758/4762/197 +f 4759/4763/198 4745/4749/204 4748/4752/204 4760/4764/198 +f 4761/4765/190 4762/4766/191 4763/4767/191 4764/4768/192 +f 4762/4766/191 4765/4769/200 4766/4770/200 4763/4767/191 +f 4765/4769/200 4767/4771/194 4768/4772/194 4766/4770/200 +f 4767/4771/194 4769/4773/201 4770/4774/202 4768/4772/194 +f 4769/4773/201 4771/4775/196 4772/4776/196 4770/4774/202 +f 4771/4775/196 4773/4777/203 4774/4778/203 4772/4776/196 +f 4773/4777/203 4775/4779/198 4776/4780/198 4774/4778/203 +f 4775/4779/198 4761/4765/190 4764/4768/192 4776/4780/198 +f 4777/4781/190 4778/4782/191 4779/4783/191 4780/4784/199 +f 4778/4782/191 4781/4785/200 4782/4786/193 4779/4783/191 +f 4781/4785/200 4783/4787/194 4784/4788/194 4782/4786/193 +f 4783/4787/194 4785/4789/202 4786/4790/202 4784/4788/194 +f 4785/4789/202 4787/4791/196 4788/4792/196 4786/4790/202 +f 4787/4791/196 4789/4793/203 4790/4794/197 4788/4792/196 +f 4789/4793/203 4791/4795/198 4792/4796/198 4790/4794/197 +f 4791/4795/198 4777/4781/190 4780/4784/199 4792/4796/198 +f 4793/4797/190 4794/4798/191 4795/4799/191 4796/4800/192 +f 4794/4798/191 4797/4801/200 4798/4802/193 4795/4799/191 +f 4797/4801/200 4799/4803/194 4800/4804/194 4798/4802/193 +f 4799/4803/194 4801/4805/201 4802/4806/202 4800/4804/194 +f 4801/4805/201 4803/4807/196 4804/4808/196 4802/4806/202 +f 4803/4807/196 4805/4809/197 4806/4810/197 4804/4808/196 +f 4805/4809/197 4807/4811/198 4808/4812/198 4806/4810/197 +f 4807/4811/198 4793/4797/190 4796/4800/192 4808/4812/198 +f 4809/4813/190 4810/4814/191 4811/4815/191 4812/4816/192 +f 4810/4814/191 4813/4817/200 4814/4818/200 4811/4815/191 +f 4813/4817/200 4815/4819/194 4816/4820/194 4814/4818/200 +f 4815/4819/194 4817/4821/201 4818/4822/202 4816/4820/194 +f 4817/4821/201 4819/4823/196 4820/4824/196 4818/4822/202 +f 4819/4823/196 4821/4825/203 4822/4826/203 4820/4824/196 +f 4821/4825/203 4823/4827/198 4824/4828/198 4822/4826/203 +f 4823/4827/198 4809/4813/190 4812/4816/192 4824/4828/198 +f 4825/4829/190 4826/4830/191 4827/4831/191 4828/4832/192 +f 4826/4830/191 4829/4833/200 4830/4834/193 4827/4831/191 +f 4829/4833/200 4831/4835/194 4832/4836/194 4830/4834/193 +f 4831/4835/194 4833/4837/201 4834/4838/202 4832/4836/194 +f 4833/4837/201 4835/4839/196 4836/4840/196 4834/4838/202 +f 4835/4839/196 4837/4841/203 4838/4842/203 4836/4840/196 +f 4837/4841/203 4839/4843/198 4840/4844/198 4838/4842/203 +f 4839/4843/198 4825/4829/190 4828/4832/192 4840/4844/198 +f 4841/4845/199 4842/4846/191 4843/4847/191 4844/4848/192 +f 4842/4846/191 4845/4849/200 4846/4850/193 4843/4847/191 +f 4845/4849/200 4847/4851/194 4848/4852/194 4846/4850/193 +f 4847/4851/194 4849/4853/201 4850/4854/202 4848/4852/194 +f 4849/4853/201 4851/4855/196 4852/4856/196 4850/4854/202 +f 4851/4855/196 4853/4857/203 4854/4858/197 4852/4856/196 +f 4853/4857/203 4855/4859/198 4856/4860/198 4854/4858/197 +f 4855/4859/198 4841/4845/199 4844/4848/192 4856/4860/198 +f 4857/4861/190 4858/4862/191 4859/4863/191 4860/4864/199 +f 4858/4862/191 4861/4865/200 4862/4866/200 4859/4863/191 +f 4861/4865/200 4863/4867/194 4864/4868/194 4862/4866/200 +f 4863/4867/194 4865/4869/201 4866/4870/195 4864/4868/194 +f 4865/4869/201 4867/4871/196 4868/4872/196 4866/4870/195 +f 4867/4871/196 4869/4873/203 4870/4874/203 4868/4872/196 +f 4869/4873/203 4871/4875/198 4872/4876/198 4870/4874/203 +f 4871/4875/198 4857/4861/190 4860/4864/199 4872/4876/198 +f 4873/4877/190 4874/4878/191 4875/4879/191 4876/4880/192 +f 4874/4878/191 4877/4881/200 4878/4882/200 4875/4879/191 +f 4877/4881/200 4879/4883/194 4880/4884/194 4878/4882/200 +f 4879/4883/194 4881/4885/201 4882/4886/202 4880/4884/194 +f 4881/4885/201 4883/4887/196 4884/4888/196 4882/4886/202 +f 4883/4887/196 4885/4889/203 4886/4890/203 4884/4888/196 +f 4885/4889/203 4887/4891/198 4888/4892/198 4886/4890/203 +f 4887/4891/198 4873/4877/190 4876/4880/192 4888/4892/198 +f 4889/4893/190 4890/4894/191 4891/4895/191 4892/4896/192 +f 4890/4894/191 4893/4897/193 4894/4898/193 4891/4895/191 +f 4893/4897/193 4895/4899/194 4896/4900/194 4894/4898/193 +f 4895/4899/194 4897/4901/201 4898/4902/202 4896/4900/194 +f 4897/4901/201 4899/4903/196 4900/4904/196 4898/4902/202 +f 4899/4903/196 4901/4905/197 4902/4906/197 4900/4904/196 +f 4901/4905/197 4903/4907/198 4904/4908/198 4902/4906/197 +f 4903/4907/198 4889/4893/190 4892/4896/192 4904/4908/198 +f 4905/4909/190 4906/4910/191 4907/4911/191 4908/4912/192 +f 4906/4910/191 4909/4913/200 4910/4914/193 4907/4911/191 +f 4909/4913/200 4911/4915/194 4912/4916/194 4910/4914/193 +f 4911/4915/194 4913/4917/201 4914/4918/202 4912/4916/194 +f 4913/4917/201 4915/4919/196 4916/4920/196 4914/4918/202 +f 4915/4919/196 4917/4921/203 4918/4922/197 4916/4920/196 +f 4917/4921/203 4919/4923/198 4920/4924/198 4918/4922/197 +f 4919/4923/198 4905/4909/190 4908/4912/192 4920/4924/198 +f 4921/4925/204 4922/4926/191 4923/4927/191 4924/4928/204 +f 4922/4926/191 4925/4929/200 4926/4930/200 4923/4927/191 +f 4925/4929/200 4927/4931/194 4928/4932/194 4926/4930/200 +f 4927/4931/194 4929/4933/202 4930/4934/201 4928/4932/194 +f 4929/4933/202 4931/4935/196 4932/4936/196 4930/4934/201 +f 4931/4935/196 4933/4937/203 4934/4938/203 4932/4936/196 +f 4933/4937/203 4935/4939/198 4936/4940/198 4934/4938/203 +f 4935/4939/198 4921/4925/204 4924/4928/204 4936/4940/198 +f 4937/4941/192 4938/4942/191 4939/4943/191 4940/4944/199 +f 4938/4942/191 4941/4945/200 4942/4946/200 4939/4943/191 +f 4941/4945/200 4943/4947/194 4944/4948/194 4942/4946/200 +f 4943/4947/194 4945/4949/202 4946/4950/205 4944/4948/194 +f 4945/4949/202 4947/4951/196 4948/4952/196 4946/4950/205 +f 4947/4951/196 4949/4953/203 4950/4954/203 4948/4952/196 +f 4949/4953/203 4951/4955/198 4952/4956/198 4950/4954/203 +f 4951/4955/198 4937/4941/192 4940/4944/199 4952/4956/198 +f 4953/4957/192 4954/4958/191 4955/4959/191 4956/4960/190 +f 4954/4958/191 4957/4961/193 4958/4962/193 4955/4959/191 +f 4957/4961/193 4959/4963/194 4960/4964/194 4958/4962/193 +f 4959/4963/194 4961/4965/202 4962/4966/205 4960/4964/194 +f 4961/4965/202 4963/4967/196 4964/4968/196 4962/4966/205 +f 4963/4967/196 4965/4969/197 4966/4970/197 4964/4968/196 +f 4965/4969/197 4967/4971/198 4968/4972/198 4966/4970/197 +f 4967/4971/198 4953/4957/192 4956/4960/190 4968/4972/198 +f 4969/4973/192 4970/4974/191 4971/4975/191 4972/4976/199 +f 4970/4974/191 4973/4977/193 4974/4978/193 4971/4975/191 +f 4973/4977/193 4975/4979/194 4976/4980/194 4974/4978/193 +f 4975/4979/194 4977/4981/202 4978/4982/205 4976/4980/194 +f 4977/4981/202 4979/4983/196 4980/4984/196 4978/4982/205 +f 4979/4983/196 4981/4985/203 4982/4986/197 4980/4984/196 +f 4981/4985/203 4983/4987/198 4984/4988/198 4982/4986/197 +f 4983/4987/198 4969/4973/192 4972/4976/199 4984/4988/198 +f 4985/4989/192 4986/4990/191 4987/4991/191 4988/4992/199 +f 4986/4990/191 4989/4993/200 4990/4994/200 4987/4991/191 +f 4989/4993/200 4991/4995/194 4992/4996/194 4990/4994/200 +f 4991/4995/194 4993/4997/202 4994/4998/201 4992/4996/194 +f 4993/4997/202 4995/4999/196 4996/5000/196 4994/4998/201 +f 4995/4999/196 4997/5001/203 4998/5002/203 4996/5000/196 +f 4997/5001/203 4999/5003/198 5000/5004/198 4998/5002/203 +f 4999/5003/198 4985/4989/192 4988/4992/199 5000/5004/198 +f 5001/5005/204 5002/5006/191 5003/5007/191 5004/5008/190 +f 5002/5006/191 5005/5009/193 5006/5010/193 5003/5007/191 +f 5005/5009/193 5007/5011/194 5008/5012/194 5006/5010/193 +f 5007/5011/194 5009/5013/195 5010/5014/201 5008/5012/194 +f 5009/5013/195 5011/5015/196 5012/5016/196 5010/5014/201 +f 5011/5015/196 5013/5017/197 5014/5018/197 5012/5016/196 +f 5013/5017/197 5015/5019/198 5016/5020/198 5014/5018/197 +f 5015/5019/198 5001/5005/204 5004/5008/190 5016/5020/198 +f 5017/5021/204 5018/5022/191 5019/5023/191 5020/5024/190 +f 5018/5022/191 5021/5025/193 5022/5026/193 5019/5023/191 +f 5021/5025/193 5023/5027/194 5024/5028/194 5022/5026/193 +f 5023/5027/194 5025/5029/202 5026/5030/201 5024/5028/194 +f 5025/5029/202 5027/5031/196 5028/5032/196 5026/5030/201 +f 5027/5031/196 5029/5033/197 5030/5034/197 5028/5032/196 +f 5029/5033/197 5031/5035/198 5032/5036/198 5030/5034/197 +f 5031/5035/198 5017/5021/204 5020/5024/190 5032/5036/198 +f 5033/5037/192 5034/5038/191 5035/5039/191 5036/5040/190 +f 5034/5038/191 5037/5041/200 5038/5042/200 5035/5039/191 +f 5037/5041/200 5039/5043/194 5040/5044/194 5038/5042/200 +f 5039/5043/194 5041/5045/202 5042/5046/201 5040/5044/194 +f 5041/5045/202 5043/5047/196 5044/5048/196 5042/5046/201 +f 5043/5047/196 5045/5049/203 5046/5050/203 5044/5048/196 +f 5045/5049/203 5047/5051/198 5048/5052/198 5046/5050/203 +f 5047/5051/198 5033/5037/192 5036/5040/190 5048/5052/198 +f 5049/5053/192 5050/5054/191 5051/5055/191 5052/5056/190 +f 5050/5054/191 5053/5057/200 5054/5058/200 5051/5055/191 +f 5053/5057/200 5055/5059/194 5056/5060/194 5054/5058/200 +f 5055/5059/194 5057/5061/202 5058/5062/201 5056/5060/194 +f 5057/5061/202 5059/5063/196 5060/5064/196 5058/5062/201 +f 5059/5063/196 5061/5065/203 5062/5066/203 5060/5064/196 +f 5061/5065/203 5063/5067/198 5064/5068/198 5062/5066/203 +f 5063/5067/198 5049/5053/192 5052/5056/190 5064/5068/198 +f 5065/5069/192 5066/5070/191 5067/5071/191 5068/5072/190 +f 5066/5070/191 5069/5073/193 5070/5074/193 5067/5071/191 +f 5069/5073/193 5071/5075/194 5072/5076/194 5070/5074/193 +f 5071/5075/194 5073/5077/202 5074/5078/201 5072/5076/194 +f 5073/5077/202 5075/5079/196 5076/5080/196 5074/5078/201 +f 5075/5079/196 5077/5081/197 5078/5082/197 5076/5080/196 +f 5077/5081/197 5079/5083/198 5080/5084/198 5078/5082/197 +f 5079/5083/198 5065/5069/192 5068/5072/190 5080/5084/198 +f 5081/5085/204 5082/5086/191 5083/5087/191 5084/5088/204 +f 5082/5086/191 5085/5089/193 5086/5090/193 5083/5087/191 +f 5085/5089/193 5087/5091/194 5088/5092/194 5086/5090/193 +f 5087/5091/194 5089/5093/201 5090/5094/201 5088/5092/194 +f 5089/5093/201 5091/5095/196 5092/5096/196 5090/5094/201 +f 5091/5095/196 5093/5097/197 5094/5098/197 5092/5096/196 +f 5093/5097/197 5095/5099/198 5096/5100/198 5094/5098/197 +f 5095/5099/198 5081/5085/204 5084/5088/204 5096/5100/198 +f 5097/5101/204 5098/5102/191 5099/5103/191 5100/5104/190 +f 5098/5102/191 5101/5105/200 5102/5106/200 5099/5103/191 +f 5101/5105/200 5103/5107/194 5104/5108/194 5102/5106/200 +f 5103/5107/194 5105/5109/195 5106/5110/201 5104/5108/194 +f 5105/5109/195 5107/5111/196 5108/5112/196 5106/5110/201 +f 5107/5111/196 5109/5113/203 5110/5114/203 5108/5112/196 +f 5109/5113/203 5111/5115/198 5112/5116/198 5110/5114/203 +f 5111/5115/198 5097/5101/204 5100/5104/190 5112/5116/198 +f 5113/5117/204 5114/5118/191 5115/5119/191 5116/5120/190 +f 5114/5118/191 5117/5121/200 5118/5122/200 5115/5119/191 +f 5117/5121/200 5119/5123/194 5120/5124/194 5118/5122/200 +f 5119/5123/194 5121/5125/195 5122/5126/201 5120/5124/194 +f 5121/5125/195 5123/5127/196 5124/5128/196 5122/5126/201 +f 5123/5127/196 5125/5129/203 5126/5130/203 5124/5128/196 +f 5125/5129/203 5127/5131/198 5128/5132/198 5126/5130/203 +f 5127/5131/198 5113/5117/204 5116/5120/190 5128/5132/198 +f 5129/5133/204 5130/5134/191 5131/5135/191 5132/5136/199 +f 5130/5134/191 5133/5137/193 5134/5138/193 5131/5135/191 +f 5133/5137/193 5135/5139/194 5136/5140/194 5134/5138/193 +f 5135/5139/194 5137/5141/201 5138/5142/202 5136/5140/194 +f 5137/5141/201 5139/5143/196 5140/5144/196 5138/5142/202 +f 5139/5143/196 5141/5145/197 5142/5146/197 5140/5144/196 +f 5141/5145/197 5143/5147/198 5144/5148/198 5142/5146/197 +f 5143/5147/198 5129/5133/204 5132/5136/199 5144/5148/198 +f 5145/5149/204 5146/5150/191 5147/5151/191 5148/5152/204 +f 5146/5150/191 5149/5153/193 5150/5154/193 5147/5151/191 +f 5149/5153/193 5151/5155/194 5152/5156/194 5150/5154/193 +f 5151/5155/194 5153/5157/201 5154/5158/202 5152/5156/194 +f 5153/5157/201 5155/5159/196 5156/5160/196 5154/5158/202 +f 5155/5159/196 5157/5161/197 5158/5162/197 5156/5160/196 +f 5157/5161/197 5159/5163/198 5160/5164/198 5158/5162/197 +f 5159/5163/198 5145/5149/204 5148/5152/204 5160/5164/198 +f 5161/5165/190 5162/5166/191 5163/5167/191 5164/5168/204 +f 5162/5166/191 5165/5169/200 5166/5170/200 5163/5167/191 +f 5165/5169/200 5167/5171/194 5168/5172/194 5166/5170/200 +f 5167/5171/194 5169/5173/201 5170/5174/202 5168/5172/194 +f 5169/5173/201 5171/5175/196 5172/5176/196 5170/5174/202 +f 5171/5175/196 5173/5177/203 5174/5178/203 5172/5176/196 +f 5173/5177/203 5175/5179/198 5176/5180/198 5174/5178/203 +f 5175/5179/198 5161/5165/190 5164/5168/204 5176/5180/198 +f 5177/5181/199 5178/5182/191 5179/5183/191 5180/5184/192 +f 5178/5182/191 5181/5185/200 5182/5186/193 5179/5183/191 +f 5181/5185/200 5183/5187/194 5184/5188/194 5182/5186/193 +f 5183/5187/194 5185/5189/201 5186/5190/195 5184/5188/194 +f 5185/5189/201 5187/5191/196 5188/5192/196 5186/5190/195 +f 5187/5191/196 5189/5193/197 5190/5194/197 5188/5192/196 +f 5189/5193/197 5191/5195/198 5192/5196/198 5190/5194/197 +f 5191/5195/198 5177/5181/199 5180/5184/192 5192/5196/198 +f 5193/5197/190 5194/5198/191 5195/5199/191 5196/5200/199 +f 5194/5198/191 5197/5201/200 5198/5202/200 5195/5199/191 +f 5197/5201/200 5199/5203/194 5200/5204/194 5198/5202/200 +f 5199/5203/194 5201/5205/201 5202/5206/202 5200/5204/194 +f 5201/5205/201 5203/5207/196 5204/5208/196 5202/5206/202 +f 5203/5207/196 5205/5209/203 5206/5210/203 5204/5208/196 +f 5205/5209/203 5207/5211/198 5208/5212/198 5206/5210/203 +f 5207/5211/198 5193/5197/190 5196/5200/199 5208/5212/198 +f 5209/5213/190 5210/5214/191 5211/5215/191 5212/5216/192 +f 5210/5214/191 5213/5217/193 5214/5218/193 5211/5215/191 +f 5213/5217/193 5215/5219/194 5216/5220/194 5214/5218/193 +f 5215/5219/194 5217/5221/205 5218/5222/202 5216/5220/194 +f 5217/5221/205 5219/5223/196 5220/5224/196 5218/5222/202 +f 5219/5223/196 5221/5225/197 5222/5226/197 5220/5224/196 +f 5221/5225/197 5223/5227/198 5224/5228/198 5222/5226/197 +f 5223/5227/198 5209/5213/190 5212/5216/192 5224/5228/198 +f 5225/5229/190 5226/5230/191 5227/5231/191 5228/5232/192 +f 5226/5230/191 5229/5233/200 5230/5234/200 5227/5231/191 +f 5229/5233/200 5231/5235/194 5232/5236/194 5230/5234/200 +f 5231/5235/194 5233/5237/201 5234/5238/202 5232/5236/194 +f 5233/5237/201 5235/5239/196 5236/5240/196 5234/5238/202 +f 5235/5239/196 5237/5241/203 5238/5242/203 5236/5240/196 +f 5237/5241/203 5239/5243/198 5240/5244/198 5238/5242/203 +f 5239/5243/198 5225/5229/190 5228/5232/192 5240/5244/198 +f 5241/5245/190 5242/5246/191 5243/5247/191 5244/5248/192 +f 5242/5246/191 5245/5249/193 5246/5250/193 5243/5247/191 +f 5245/5249/193 5247/5251/194 5248/5252/194 5246/5250/193 +f 5247/5251/194 5249/5253/201 5250/5254/202 5248/5252/194 +f 5249/5253/201 5251/5255/196 5252/5256/196 5250/5254/202 +f 5251/5255/196 5253/5257/197 5254/5258/197 5252/5256/196 +f 5253/5257/197 5255/5259/198 5256/5260/198 5254/5258/197 +f 5255/5259/198 5241/5245/190 5244/5248/192 5256/5260/198 +f 5257/5261/190 5258/5262/191 5259/5263/191 5260/5264/204 +f 5258/5262/191 5261/5265/193 5262/5266/193 5259/5263/191 +f 5261/5265/193 5263/5267/194 5264/5268/194 5262/5266/193 +f 5263/5267/194 5265/5269/201 5266/5270/195 5264/5268/194 +f 5265/5269/201 5267/5271/196 5268/5272/196 5266/5270/195 +f 5267/5271/196 5269/5273/197 5270/5274/197 5268/5272/196 +f 5269/5273/197 5271/5275/198 5272/5276/198 5270/5274/197 +f 5271/5275/198 5257/5261/190 5260/5264/204 5272/5276/198 +f 5273/5277/204 5274/5278/191 5275/5279/191 5276/5280/204 +f 5274/5278/191 5277/5281/193 5278/5282/193 5275/5279/191 +f 5277/5281/193 5279/5283/194 5280/5284/194 5278/5282/193 +f 5279/5283/194 5281/5285/201 5282/5286/202 5280/5284/194 +f 5281/5285/201 5283/5287/196 5284/5288/196 5282/5286/202 +f 5283/5287/196 5285/5289/203 5286/5290/197 5284/5288/196 +f 5285/5289/203 5287/5291/198 5288/5292/198 5286/5290/197 +f 5287/5291/198 5273/5277/204 5276/5280/204 5288/5292/198 +f 5289/5293/190 5290/5294/191 5291/5295/191 5292/5296/199 +f 5290/5294/191 5293/5297/200 5294/5298/200 5291/5295/191 +f 5293/5297/200 5295/5299/194 5296/5300/194 5294/5298/200 +f 5295/5299/194 5297/5301/201 5298/5302/202 5296/5300/194 +f 5297/5301/201 5299/5303/196 5300/5304/196 5298/5302/202 +f 5299/5303/196 5301/5305/203 5302/5306/203 5300/5304/196 +f 5301/5305/203 5303/5307/198 5304/5308/198 5302/5306/203 +f 5303/5307/198 5289/5293/190 5292/5296/199 5304/5308/198 +f 5305/5309/190 5306/5310/191 5307/5311/191 5308/5312/192 +f 5306/5310/191 5309/5313/193 5310/5314/200 5307/5311/191 +f 5309/5313/193 5311/5315/194 5312/5316/194 5310/5314/200 +f 5311/5315/194 5313/5317/201 5314/5318/202 5312/5316/194 +f 5313/5317/201 5315/5319/196 5316/5320/196 5314/5318/202 +f 5315/5319/196 5317/5321/203 5318/5322/197 5316/5320/196 +f 5317/5321/203 5319/5323/198 5320/5324/198 5318/5322/197 +f 5319/5323/198 5305/5309/190 5308/5312/192 5320/5324/198 +f 5321/5325/190 5322/5326/191 5323/5327/191 5324/5328/192 +f 5322/5326/191 5325/5329/200 5326/5330/200 5323/5327/191 +f 5325/5329/200 5327/5331/194 5328/5332/194 5326/5330/200 +f 5327/5331/194 5329/5333/201 5330/5334/202 5328/5332/194 +f 5329/5333/201 5331/5335/196 5332/5336/196 5330/5334/202 +f 5331/5335/196 5333/5337/203 5334/5338/203 5332/5336/196 +f 5333/5337/203 5335/5339/198 5336/5340/198 5334/5338/203 +f 5335/5339/198 5321/5325/190 5324/5328/192 5336/5340/198 +f 5337/5341/190 5338/5342/191 5339/5343/191 5340/5344/192 +f 5338/5342/191 5341/5345/193 5342/5346/193 5339/5343/191 +f 5341/5345/193 5343/5347/194 5344/5348/194 5342/5346/193 +f 5343/5347/194 5345/5349/201 5346/5350/202 5344/5348/194 +f 5345/5349/201 5347/5351/196 5348/5352/196 5346/5350/202 +f 5347/5351/196 5349/5353/197 5350/5354/197 5348/5352/196 +f 5349/5353/197 5351/5355/198 5352/5356/198 5350/5354/197 +f 5351/5355/198 5337/5341/190 5340/5344/192 5352/5356/198 +f 5353/5357/199 5354/5358/191 5355/5359/191 5356/5360/204 +f 5354/5358/191 5357/5361/193 5358/5362/193 5355/5359/191 +f 5357/5361/193 5359/5363/194 5360/5364/194 5358/5362/193 +f 5359/5363/194 5361/5365/201 5362/5366/202 5360/5364/194 +f 5361/5365/201 5363/5367/196 5364/5368/196 5362/5366/202 +f 5363/5367/196 5365/5369/197 5366/5370/197 5364/5368/196 +f 5365/5369/197 5367/5371/198 5368/5372/198 5366/5370/197 +f 5367/5371/198 5353/5357/199 5356/5360/204 5368/5372/198 +f 5369/5373/199 5370/5374/191 5371/5375/191 5372/5376/199 +f 5370/5374/191 5373/5377/200 5374/5378/200 5371/5375/191 +f 5373/5377/200 5375/5379/194 5376/5380/194 5374/5378/200 +f 5375/5379/194 5377/5381/202 5378/5382/201 5376/5380/194 +f 5377/5381/202 5379/5383/196 5380/5384/196 5378/5382/201 +f 5379/5383/196 5381/5385/203 5382/5386/203 5380/5384/196 +f 5381/5385/203 5383/5387/198 5384/5388/198 5382/5386/203 +f 5383/5387/198 5369/5373/199 5372/5376/199 5384/5388/198 +f 5385/5389/199 5386/5390/191 5387/5391/191 5388/5392/199 +f 5386/5390/191 5389/5393/193 5390/5394/193 5387/5391/191 +f 5389/5393/193 5391/5395/194 5392/5396/194 5390/5394/193 +f 5391/5395/194 5393/5397/202 5394/5398/202 5392/5396/194 +f 5393/5397/202 5395/5399/196 5396/5400/196 5394/5398/202 +f 5395/5399/196 5397/5401/203 5398/5402/203 5396/5400/196 +f 5397/5401/203 5399/5403/198 5400/5404/198 5398/5402/203 +f 5399/5403/198 5385/5389/199 5388/5392/199 5400/5404/198 +f 5401/5405/199 5402/5406/191 5403/5407/191 5404/5408/199 +f 5402/5406/191 5405/5409/193 5406/5410/193 5403/5407/191 +f 5405/5409/193 5407/5411/194 5408/5412/194 5406/5410/193 +f 5407/5411/194 5409/5413/202 5410/5414/202 5408/5412/194 +f 5409/5413/202 5411/5415/196 5412/5416/196 5410/5414/202 +f 5411/5415/196 5413/5417/197 5414/5418/197 5412/5416/196 +f 5413/5417/197 5415/5419/198 5416/5420/198 5414/5418/197 +f 5415/5419/198 5401/5405/199 5404/5408/199 5416/5420/198 +f 5417/5421/190 5418/5422/191 5419/5423/191 5420/5424/204 +f 5418/5422/191 5421/5425/193 5422/5426/193 5419/5423/191 +f 5421/5425/193 5423/5427/194 5424/5428/194 5422/5426/193 +f 5423/5427/194 5425/5429/201 5426/5430/202 5424/5428/194 +f 5425/5429/201 5427/5431/196 5428/5432/196 5426/5430/202 +f 5427/5431/196 5429/5433/197 5430/5434/197 5428/5432/196 +f 5429/5433/197 5431/5435/198 5432/5436/198 5430/5434/197 +f 5431/5435/198 5417/5421/190 5420/5424/204 5432/5436/198 +f 5433/5437/192 5434/5438/191 5435/5439/191 5436/5440/190 +f 5434/5438/191 5437/5441/200 5438/5442/200 5435/5439/191 +f 5437/5441/200 5439/5443/194 5440/5444/194 5438/5442/200 +f 5439/5443/194 5441/5445/202 5442/5446/201 5440/5444/194 +f 5441/5445/202 5443/5447/196 5444/5448/196 5442/5446/201 +f 5443/5447/196 5445/5449/203 5446/5450/203 5444/5448/196 +f 5445/5449/203 5447/5451/198 5448/5452/198 5446/5450/203 +f 5447/5451/198 5433/5437/192 5436/5440/190 5448/5452/198 +f 5449/5453/192 5450/5454/191 5451/5455/191 5452/5456/190 +f 5450/5454/191 5453/5457/200 5454/5458/200 5451/5455/191 +f 5453/5457/200 5455/5459/194 5456/5460/194 5454/5458/200 +f 5455/5459/194 5457/5461/202 5458/5462/201 5456/5460/194 +f 5457/5461/202 5459/5463/196 5460/5464/196 5458/5462/201 +f 5459/5463/196 5461/5465/203 5462/5466/203 5460/5464/196 +f 5461/5465/203 5463/5467/198 5464/5468/198 5462/5466/203 +f 5463/5467/198 5449/5453/192 5452/5456/190 5464/5468/198 +f 5465/5469/192 5466/5470/191 5467/5471/191 5468/5472/190 +f 5466/5470/191 5469/5473/200 5470/5474/200 5467/5471/191 +f 5469/5473/200 5471/5475/194 5472/5476/194 5470/5474/200 +f 5471/5475/194 5473/5477/202 5474/5478/205 5472/5476/194 +f 5473/5477/202 5475/5479/196 5476/5480/196 5474/5478/205 +f 5475/5479/196 5477/5481/203 5478/5482/203 5476/5480/196 +f 5477/5481/203 5479/5483/198 5480/5484/198 5478/5482/203 +f 5479/5483/198 5465/5469/192 5468/5472/190 5480/5484/198 +f 5481/5485/192 5482/5486/191 5483/5487/191 5484/5488/190 +f 5482/5486/191 5485/5489/193 5486/5490/193 5483/5487/191 +f 5485/5489/193 5487/5491/194 5488/5492/194 5486/5490/193 +f 5487/5491/194 5489/5493/202 5490/5494/205 5488/5492/194 +f 5489/5493/202 5491/5495/196 5492/5496/196 5490/5494/205 +f 5491/5495/196 5493/5497/197 5494/5498/197 5492/5496/196 +f 5493/5497/197 5495/5499/198 5496/5500/198 5494/5498/197 +f 5495/5499/198 5481/5485/192 5484/5488/190 5496/5500/198 +f 5497/5501/192 5498/5502/191 5499/5503/191 5500/5504/199 +f 5498/5502/191 5501/5505/200 5502/5506/200 5499/5503/191 +f 5501/5505/200 5503/5507/194 5504/5508/194 5502/5506/200 +f 5503/5507/194 5505/5509/202 5506/5510/201 5504/5508/194 +f 5505/5509/202 5507/5511/196 5508/5512/196 5506/5510/201 +f 5507/5511/196 5509/5513/203 5510/5514/203 5508/5512/196 +f 5509/5513/203 5511/5515/198 5512/5516/198 5510/5514/203 +f 5511/5515/198 5497/5501/192 5500/5504/199 5512/5516/198 +f 5513/5517/204 5514/5518/191 5515/5519/191 5516/5520/190 +f 5514/5518/191 5517/5521/200 5518/5522/193 5515/5519/191 +f 5517/5521/200 5519/5523/194 5520/5524/194 5518/5522/193 +f 5519/5523/194 5521/5525/195 5522/5526/201 5520/5524/194 +f 5521/5525/195 5523/5527/196 5524/5528/196 5522/5526/201 +f 5523/5527/196 5525/5529/197 5526/5530/203 5524/5528/196 +f 5525/5529/197 5527/5531/198 5528/5532/198 5526/5530/203 +f 5527/5531/198 5513/5517/204 5516/5520/190 5528/5532/198 +f 5529/5533/204 5530/5534/191 5531/5535/191 5532/5536/190 +f 5530/5534/191 5533/5537/193 5534/5538/193 5531/5535/191 +f 5533/5537/193 5535/5539/194 5536/5540/194 5534/5538/193 +f 5535/5539/194 5537/5541/195 5538/5542/201 5536/5540/194 +f 5537/5541/195 5539/5543/196 5540/5544/196 5538/5542/201 +f 5539/5543/196 5541/5545/197 5542/5546/197 5540/5544/196 +f 5541/5545/197 5543/5547/198 5544/5548/198 5542/5546/197 +f 5543/5547/198 5529/5533/204 5532/5536/190 5544/5548/198 +f 5545/5549/204 5546/5550/191 5547/5551/191 5548/5552/204 +f 5546/5550/191 5549/5553/200 5550/5554/200 5547/5551/191 +f 5549/5553/200 5551/5555/194 5552/5556/194 5550/5554/200 +f 5551/5555/194 5553/5557/201 5554/5558/201 5552/5556/194 +f 5553/5557/201 5555/5559/196 5556/5560/196 5554/5558/201 +f 5555/5559/196 5557/5561/203 5558/5562/203 5556/5560/196 +f 5557/5561/203 5559/5563/198 5560/5564/198 5558/5562/203 +f 5559/5563/198 5545/5549/204 5548/5552/204 5560/5564/198 +f 5561/5565/204 5562/5566/191 5563/5567/191 5564/5568/204 +f 5562/5566/191 5565/5569/193 5566/5570/193 5563/5567/191 +f 5565/5569/193 5567/5571/194 5568/5572/194 5566/5570/193 +f 5567/5571/194 5569/5573/201 5570/5574/201 5568/5572/194 +f 5569/5573/201 5571/5575/196 5572/5576/196 5570/5574/201 +f 5571/5575/196 5573/5577/197 5574/5578/197 5572/5576/196 +f 5573/5577/197 5575/5579/198 5576/5580/198 5574/5578/197 +f 5575/5579/198 5561/5565/204 5564/5568/204 5576/5580/198 +f 5577/5581/204 5578/5582/191 5579/5583/191 5580/5584/204 +f 5578/5582/191 5581/5585/193 5582/5586/193 5579/5583/191 +f 5581/5585/193 5583/5587/194 5584/5588/194 5582/5586/193 +f 5583/5587/194 5585/5589/202 5586/5590/201 5584/5588/194 +f 5585/5589/202 5587/5591/196 5588/5592/196 5586/5590/201 +f 5587/5591/196 5589/5593/197 5590/5594/197 5588/5592/196 +f 5589/5593/197 5591/5595/198 5592/5596/198 5590/5594/197 +f 5591/5595/198 5577/5581/204 5580/5584/204 5592/5596/198 +f 5593/5597/204 5594/5598/191 5595/5599/191 5596/5600/204 +f 5594/5598/191 5597/5601/193 5598/5602/193 5595/5599/191 +f 5597/5601/193 5599/5603/194 5600/5604/194 5598/5602/193 +f 5599/5603/194 5601/5605/201 5602/5606/201 5600/5604/194 +f 5601/5605/201 5603/5607/196 5604/5608/196 5602/5606/201 +f 5603/5607/196 5605/5609/197 5606/5610/197 5604/5608/196 +f 5605/5609/197 5607/5611/198 5608/5612/198 5606/5610/197 +f 5607/5611/198 5593/5597/204 5596/5600/204 5608/5612/198 +f 5609/5613/204 5610/5614/191 5611/5615/191 5612/5616/204 +f 5610/5614/191 5613/5617/200 5614/5618/200 5611/5615/191 +f 5613/5617/200 5615/5619/194 5616/5620/194 5614/5618/200 +f 5615/5619/194 5617/5621/201 5618/5622/201 5616/5620/194 +f 5617/5621/201 5619/5623/196 5620/5624/196 5618/5622/201 +f 5619/5623/196 5621/5625/203 5622/5626/203 5620/5624/196 +f 5621/5625/203 5623/5627/198 5624/5628/198 5622/5626/203 +f 5623/5627/198 5609/5613/204 5612/5616/204 5624/5628/198 +f 5625/5629/190 5626/5630/191 5627/5631/191 5628/5632/192 +f 5626/5630/191 5629/5633/200 5630/5634/200 5627/5631/191 +f 5629/5633/200 5631/5635/194 5632/5636/194 5630/5634/200 +f 5631/5635/194 5633/5637/201 5634/5638/202 5632/5636/194 +f 5633/5637/201 5635/5639/196 5636/5640/196 5634/5638/202 +f 5635/5639/196 5637/5641/203 5638/5642/203 5636/5640/196 +f 5637/5641/203 5639/5643/198 5640/5644/198 5638/5642/203 +f 5639/5643/198 5625/5629/190 5628/5632/192 5640/5644/198 +f 5641/5645/199 5642/5646/191 5643/5647/191 5644/5648/192 +f 5642/5646/191 5645/5649/193 5646/5650/193 5643/5647/191 +f 5645/5649/193 5647/5651/194 5648/5652/194 5646/5650/193 +f 5647/5651/194 5649/5653/201 5650/5654/202 5648/5652/194 +f 5649/5653/201 5651/5655/196 5652/5656/196 5650/5654/202 +f 5651/5655/196 5653/5657/197 5654/5658/197 5652/5656/196 +f 5653/5657/197 5655/5659/198 5656/5660/198 5654/5658/197 +f 5655/5659/198 5641/5645/199 5644/5648/192 5656/5660/198 +f 5657/5661/190 5658/5662/191 5659/5663/191 5660/5664/192 +f 5658/5662/191 5661/5665/200 5662/5666/193 5659/5663/191 +f 5661/5665/200 5663/5667/194 5664/5668/194 5662/5666/193 +f 5663/5667/194 5665/5669/201 5666/5670/202 5664/5668/194 +f 5665/5669/201 5667/5671/196 5668/5672/196 5666/5670/202 +f 5667/5671/196 5669/5673/197 5670/5674/203 5668/5672/196 +f 5669/5673/197 5671/5675/198 5672/5676/198 5670/5674/203 +f 5671/5675/198 5657/5661/190 5660/5664/192 5672/5676/198 +f 5673/5677/190 5674/5678/191 5675/5679/191 5676/5680/192 +f 5674/5678/191 5677/5681/200 5678/5682/200 5675/5679/191 +f 5677/5681/200 5679/5683/194 5680/5684/194 5678/5682/200 +f 5679/5683/194 5681/5685/201 5682/5686/202 5680/5684/194 +f 5681/5685/201 5683/5687/196 5684/5688/196 5682/5686/202 +f 5683/5687/196 5685/5689/203 5686/5690/203 5684/5688/196 +f 5685/5689/203 5687/5691/198 5688/5692/198 5686/5690/203 +f 5687/5691/198 5673/5677/190 5676/5680/192 5688/5692/198 +f 5689/5693/190 5690/5694/191 5691/5695/191 5692/5696/192 +f 5690/5694/191 5693/5697/200 5694/5698/200 5691/5695/191 +f 5693/5697/200 5695/5699/194 5696/5700/194 5694/5698/200 +f 5695/5699/194 5697/5701/201 5698/5702/195 5696/5700/194 +f 5697/5701/201 5699/5703/196 5700/5704/196 5698/5702/195 +f 5699/5703/196 5701/5705/203 5702/5706/203 5700/5704/196 +f 5701/5705/203 5703/5707/198 5704/5708/198 5702/5706/203 +f 5703/5707/198 5689/5693/190 5692/5696/192 5704/5708/198 +f 5705/5709/190 5706/5710/191 5707/5711/191 5708/5712/199 +f 5706/5710/191 5709/5713/193 5710/5714/193 5707/5711/191 +f 5709/5713/193 5711/5715/194 5712/5716/194 5710/5714/193 +f 5711/5715/194 5713/5717/201 5714/5718/202 5712/5716/194 +f 5713/5717/201 5715/5719/196 5716/5720/196 5714/5718/202 +f 5715/5719/196 5717/5721/197 5718/5722/197 5716/5720/196 +f 5717/5721/197 5719/5723/198 5720/5724/198 5718/5722/197 +f 5719/5723/198 5705/5709/190 5708/5712/199 5720/5724/198 +f 5721/5725/190 5722/5726/191 5723/5727/191 5724/5728/192 +f 5722/5726/191 5725/5729/193 5726/5730/193 5723/5727/191 +f 5725/5729/193 5727/5731/194 5728/5732/194 5726/5730/193 +f 5727/5731/194 5729/5733/201 5730/5734/202 5728/5732/194 +f 5729/5733/201 5731/5735/196 5732/5736/196 5730/5734/202 +f 5731/5735/196 5733/5737/197 5734/5738/197 5732/5736/196 +f 5733/5737/197 5735/5739/198 5736/5740/198 5734/5738/197 +f 5735/5739/198 5721/5725/190 5724/5728/192 5736/5740/198 +f 5737/5741/190 5738/5742/191 5739/5743/191 5740/5744/192 +f 5738/5742/191 5741/5745/193 5742/5746/193 5739/5743/191 +f 5741/5745/193 5743/5747/194 5744/5748/194 5742/5746/193 +f 5743/5747/194 5745/5749/205 5746/5750/202 5744/5748/194 +f 5745/5749/205 5747/5751/196 5748/5752/196 5746/5750/202 +f 5747/5751/196 5749/5753/197 5750/5754/197 5748/5752/196 +f 5749/5753/197 5751/5755/198 5752/5756/198 5750/5754/197 +f 5751/5755/198 5737/5741/190 5740/5744/192 5752/5756/198 +f 5753/5757/190 5754/5758/191 5755/5759/191 5756/5760/192 +f 5754/5758/191 5757/5761/193 5758/5762/193 5755/5759/191 +f 5757/5761/193 5759/5763/194 5760/5764/194 5758/5762/193 +f 5759/5763/194 5761/5765/201 5762/5766/195 5760/5764/194 +f 5761/5765/201 5763/5767/196 5764/5768/196 5762/5766/195 +f 5763/5767/196 5765/5769/197 5766/5770/197 5764/5768/196 +f 5765/5769/197 5767/5771/198 5768/5772/198 5766/5770/197 +f 5767/5771/198 5753/5757/190 5756/5760/192 5768/5772/198 +f 5769/5773/192 5770/5774/191 5771/5775/191 5772/5776/204 +f 5770/5774/191 5773/5777/200 5774/5778/200 5771/5775/191 +f 5773/5777/200 5775/5779/194 5776/5780/194 5774/5778/200 +f 5775/5779/194 5777/5781/202 5778/5782/201 5776/5780/194 +f 5777/5781/202 5779/5783/196 5780/5784/196 5778/5782/201 +f 5779/5783/196 5781/5785/203 5782/5786/203 5780/5784/196 +f 5781/5785/203 5783/5787/198 5784/5788/198 5782/5786/203 +f 5783/5787/198 5769/5773/192 5772/5776/204 5784/5788/198 +f 5785/5789/192 5786/5790/191 5787/5791/191 5788/5792/199 +f 5786/5790/191 5789/5793/200 5790/5794/200 5787/5791/191 +f 5789/5793/200 5791/5795/194 5792/5796/194 5790/5794/200 +f 5791/5795/194 5793/5797/202 5794/5798/205 5792/5796/194 +f 5793/5797/202 5795/5799/196 5796/5800/196 5794/5798/205 +f 5795/5799/196 5797/5801/203 5798/5802/203 5796/5800/196 +f 5797/5801/203 5799/5803/198 5800/5804/198 5798/5802/203 +f 5799/5803/198 5785/5789/192 5788/5792/199 5800/5804/198 +f 5801/5805/192 5802/5806/191 5803/5807/191 5804/5808/190 +f 5802/5806/191 5805/5809/200 5806/5810/193 5803/5807/191 +f 5805/5809/200 5807/5811/194 5808/5812/194 5806/5810/193 +f 5807/5811/194 5809/5813/202 5810/5814/205 5808/5812/194 +f 5809/5813/202 5811/5815/196 5812/5816/196 5810/5814/205 +f 5811/5815/196 5813/5817/203 5814/5818/203 5812/5816/196 +f 5813/5817/203 5815/5819/198 5816/5820/198 5814/5818/203 +f 5815/5819/198 5801/5805/192 5804/5808/190 5816/5820/198 +f 5817/5821/192 5818/5822/191 5819/5823/191 5820/5824/199 +f 5818/5822/191 5821/5825/200 5822/5826/200 5819/5823/191 +f 5821/5825/200 5823/5827/194 5824/5828/194 5822/5826/200 +f 5823/5827/194 5825/5829/202 5826/5830/201 5824/5828/194 +f 5825/5829/202 5827/5831/196 5828/5832/196 5826/5830/201 +f 5827/5831/196 5829/5833/203 5830/5834/203 5828/5832/196 +f 5829/5833/203 5831/5835/198 5832/5836/198 5830/5834/203 +f 5831/5835/198 5817/5821/192 5820/5824/199 5832/5836/198 +f 5833/5837/192 5834/5838/191 5835/5839/191 5836/5840/199 +f 5834/5838/191 5837/5841/200 5838/5842/200 5835/5839/191 +f 5837/5841/200 5839/5843/194 5840/5844/194 5838/5842/200 +f 5839/5843/194 5841/5845/202 5842/5846/205 5840/5844/194 +f 5841/5845/202 5843/5847/196 5844/5848/196 5842/5846/205 +f 5843/5847/196 5845/5849/203 5846/5850/203 5844/5848/196 +f 5845/5849/203 5847/5851/198 5848/5852/198 5846/5850/203 +f 5847/5851/198 5833/5837/192 5836/5840/199 5848/5852/198 +f 5849/5853/204 5850/5854/191 5851/5855/191 5852/5856/199 +f 5850/5854/191 5853/5857/200 5854/5858/200 5851/5855/191 +f 5853/5857/200 5855/5859/194 5856/5860/194 5854/5858/200 +f 5855/5859/194 5857/5861/201 5858/5862/202 5856/5860/194 +f 5857/5861/201 5859/5863/196 5860/5864/196 5858/5862/202 +f 5859/5863/196 5861/5865/203 5862/5866/203 5860/5864/196 +f 5861/5865/203 5863/5867/198 5864/5868/198 5862/5866/203 +f 5863/5867/198 5849/5853/204 5852/5856/199 5864/5868/198 +f 5865/5869/204 5866/5870/191 5867/5871/191 5868/5872/190 +f 5866/5870/191 5869/5873/193 5870/5874/193 5867/5871/191 +f 5869/5873/193 5871/5875/194 5872/5876/194 5870/5874/193 +f 5871/5875/194 5873/5877/195 5874/5878/201 5872/5876/194 +f 5873/5877/195 5875/5879/196 5876/5880/196 5874/5878/201 +f 5875/5879/196 5877/5881/197 5878/5882/197 5876/5880/196 +f 5877/5881/197 5879/5883/198 5880/5884/198 5878/5882/197 +f 5879/5883/198 5865/5869/204 5868/5872/190 5880/5884/198 +f 5881/5885/192 5882/5886/191 5883/5887/191 5884/5888/190 +f 5882/5886/191 5885/5889/200 5886/5890/200 5883/5887/191 +f 5885/5889/200 5887/5891/194 5888/5892/194 5886/5890/200 +f 5887/5891/194 5889/5893/202 5890/5894/201 5888/5892/194 +f 5889/5893/202 5891/5895/196 5892/5896/196 5890/5894/201 +f 5891/5895/196 5893/5897/197 5894/5898/203 5892/5896/196 +f 5893/5897/197 5895/5899/198 5896/5900/198 5894/5898/203 +f 5895/5899/198 5881/5885/192 5884/5888/190 5896/5900/198 +f 5897/5901/192 5898/5902/191 5899/5903/191 5900/5904/190 +f 5898/5902/191 5901/5905/200 5902/5906/200 5899/5903/191 +f 5901/5905/200 5903/5907/194 5904/5908/194 5902/5906/200 +f 5903/5907/194 5905/5909/202 5906/5910/201 5904/5908/194 +f 5905/5909/202 5907/5911/196 5908/5912/196 5906/5910/201 +f 5907/5911/196 5909/5913/203 5910/5914/203 5908/5912/196 +f 5909/5913/203 5911/5915/198 5912/5916/198 5910/5914/203 +f 5911/5915/198 5897/5901/192 5900/5904/190 5912/5916/198 +f 5913/5917/192 5914/5918/191 5915/5919/191 5916/5920/190 +f 5914/5918/191 5917/5921/200 5918/5922/200 5915/5919/191 +f 5917/5921/200 5919/5923/194 5920/5924/194 5918/5922/200 +f 5919/5923/194 5921/5925/202 5922/5926/201 5920/5924/194 +f 5921/5925/202 5923/5927/196 5924/5928/196 5922/5926/201 +f 5923/5927/196 5925/5929/203 5926/5930/203 5924/5928/196 +f 5925/5929/203 5927/5931/198 5928/5932/198 5926/5930/203 +f 5927/5931/198 5913/5917/192 5916/5920/190 5928/5932/198 +f 5929/5933/204 5930/5934/191 5931/5935/191 5932/5936/204 +f 5930/5934/191 5933/5937/193 5934/5938/193 5931/5935/191 +f 5933/5937/193 5935/5939/194 5936/5940/194 5934/5938/193 +f 5935/5939/194 5937/5941/201 5938/5942/201 5936/5940/194 +f 5937/5941/201 5939/5943/196 5940/5944/196 5938/5942/201 +f 5939/5943/196 5941/5945/197 5942/5946/197 5940/5944/196 +f 5941/5945/197 5943/5947/198 5944/5948/198 5942/5946/197 +f 5943/5947/198 5929/5933/204 5932/5936/204 5944/5948/198 +f 5945/5949/192 5946/5950/191 5947/5951/191 5948/5952/190 +f 5946/5950/191 5949/5953/193 5950/5954/193 5947/5951/191 +f 5949/5953/193 5951/5955/194 5952/5956/194 5950/5954/193 +f 5951/5955/194 5953/5957/195 5954/5958/201 5952/5956/194 +f 5953/5957/195 5955/5959/196 5956/5960/196 5954/5958/201 +f 5955/5959/196 5957/5961/197 5958/5962/197 5956/5960/196 +f 5957/5961/197 5959/5963/198 5960/5964/198 5958/5962/197 +f 5959/5963/198 5945/5949/192 5948/5952/190 5960/5964/198 +# 768 polygons + +# +# object Frame_Bins +# + +v -0.6906 -3.3403 0.8593 +v -0.6906 8.2628 0.8593 +v -0.6816 8.2628 0.8503 +v -0.6816 -3.3403 0.8503 +v -0.6816 -3.3403 0.8683 +v -0.6816 8.2628 0.8683 +v -0.6726 -3.3403 0.8593 +v -0.6726 8.2628 0.8593 +v -0.6906 -3.3403 1.5597 +v -0.6906 8.2628 1.5597 +v -0.6816 8.2628 1.5507 +v -0.6816 -3.3403 1.5507 +v -0.6816 -3.3403 1.5687 +v -0.6816 8.2628 1.5687 +v -0.6726 -3.3403 1.5597 +v -0.6726 8.2628 1.5597 +v -1.2489 -2.1662 2.2606 +v -1.2489 -2.1662 0.1615 +v -1.2399 -2.1752 0.1705 +v -1.2399 -2.1752 2.2516 +v -1.2399 -2.1572 2.2696 +v -1.2399 -2.1572 0.1525 +v -1.2309 -2.1662 2.2606 +v -1.2309 -2.1662 0.1615 +v -0.6905 -2.1662 2.2606 +v -0.6905 -2.1662 0.1615 +v -0.6815 -2.1752 0.1705 +v -0.6815 -2.1752 2.2516 +v -0.6815 -2.1572 2.2696 +v -0.6815 -2.1572 0.1525 +v -0.6725 -2.1662 2.2606 +v -0.6725 -2.1662 0.1615 +v -1.2489 -1.0062 2.2606 +v -1.2489 -1.0062 0.1615 +v -1.2399 -1.0152 0.1705 +v -1.2399 -1.0152 2.2516 +v -1.2399 -0.9972 2.2696 +v -1.2399 -0.9972 0.1525 +v -1.2309 -1.0062 2.2606 +v -1.2309 -1.0062 0.1615 +v -0.6905 -1.0062 2.2606 +v -0.6905 -1.0062 0.1615 +v -0.6815 -1.0152 0.1705 +v -0.6815 -1.0152 2.2516 +v -0.6815 -0.9972 2.2696 +v -0.6815 -0.9972 0.1525 +v -0.6725 -1.0062 2.2606 +v -0.6725 -1.0062 0.1615 +v -1.2489 0.1538 2.2606 +v -1.2489 0.1538 0.1615 +v -1.2399 0.1448 0.1705 +v -1.2399 0.1448 2.2516 +v -1.2399 0.1628 2.2696 +v -1.2399 0.1628 0.1525 +v -1.2309 0.1538 2.2606 +v -1.2309 0.1538 0.1615 +v -0.6905 0.1538 2.2606 +v -0.6905 0.1538 0.1615 +v -0.6815 0.1448 0.1705 +v -0.6815 0.1448 2.2516 +v -0.6815 0.1628 2.2696 +v -0.6815 0.1628 0.1525 +v -0.6725 0.1538 2.2606 +v -0.6725 0.1538 0.1615 +v -1.2489 1.3138 2.2606 +v -1.2489 1.3138 0.1615 +v -1.2399 1.3048 0.1705 +v -1.2399 1.3048 2.2516 +v -1.2399 1.3228 2.2696 +v -1.2399 1.3228 0.1525 +v -1.2309 1.3138 2.2606 +v -1.2309 1.3138 0.1615 +v -0.6905 1.3138 2.2606 +v -0.6905 1.3138 0.1615 +v -0.6815 1.3048 0.1705 +v -0.6815 1.3048 2.2516 +v -0.6815 1.3228 2.2696 +v -0.6815 1.3228 0.1525 +v -0.6725 1.3138 2.2606 +v -0.6725 1.3138 0.1615 +v -1.2489 2.4738 2.2606 +v -1.2489 2.4738 0.1615 +v -1.2399 2.4648 0.1705 +v -1.2399 2.4648 2.2516 +v -1.2399 2.4828 2.2696 +v -1.2399 2.4828 0.1525 +v -1.2309 2.4738 2.2606 +v -1.2309 2.4738 0.1615 +v -0.6905 2.4738 2.2606 +v -0.6905 2.4738 0.1615 +v -0.6815 2.4648 0.1705 +v -0.6815 2.4648 2.2516 +v -0.6815 2.4828 2.2696 +v -0.6815 2.4828 0.1525 +v -0.6725 2.4738 2.2606 +v -0.6725 2.4738 0.1615 +v -1.2489 3.6338 2.2606 +v -1.2489 3.6338 0.1615 +v -1.2399 3.6248 0.1705 +v -1.2399 3.6248 2.2516 +v -1.2399 3.6428 2.2696 +v -1.2399 3.6428 0.1525 +v -1.2309 3.6338 2.2606 +v -1.2309 3.6338 0.1615 +v -0.6905 3.6338 2.2606 +v -0.6905 3.6338 0.1615 +v -0.6815 3.6248 0.1705 +v -0.6815 3.6248 2.2516 +v -0.6815 3.6428 2.2696 +v -0.6815 3.6428 0.1525 +v -0.6725 3.6338 2.2606 +v -0.6725 3.6338 0.1615 +v -1.2489 4.7938 2.2606 +v -1.2489 4.7938 0.1615 +v -1.2399 4.7848 0.1705 +v -1.2399 4.7848 2.2516 +v -1.2399 4.8028 2.2696 +v -1.2399 4.8028 0.1525 +v -1.2309 4.7938 2.2606 +v -1.2309 4.7938 0.1615 +v -0.6905 4.7938 2.2606 +v -0.6905 4.7938 0.1615 +v -0.6815 4.7848 0.1705 +v -0.6815 4.7848 2.2516 +v -0.6815 4.8028 2.2696 +v -0.6815 4.8028 0.1525 +v -0.6725 4.7938 2.2606 +v -0.6725 4.7938 0.1615 +v -0.6905 -3.3379 2.2606 +v -0.6905 8.2638 2.2606 +v -0.6815 8.2548 2.2516 +v -0.6815 -3.3289 2.2516 +v -0.6815 -3.3469 2.2696 +v -0.6815 8.2728 2.2696 +v -0.6725 -3.3379 2.2606 +v -0.6725 8.2638 2.2606 +v -0.6905 -3.3379 0.1615 +v -0.6815 -3.3289 0.1705 +v -0.6815 -3.3469 0.1525 +v -0.6725 -3.3379 0.1615 +v -0.6905 8.2638 0.1615 +v -0.6815 8.2548 0.1705 +v -0.6815 8.2728 0.1525 +v -0.6725 8.2638 0.1615 +v -1.2363 0.1466 0.1613 +v -0.6820 0.1466 0.1613 +v -0.6820 0.1376 0.1523 +v -1.2363 0.1376 0.1523 +v -1.2363 0.1376 0.1703 +v -0.6820 0.1376 0.1703 +v -1.2363 0.1286 0.1613 +v -0.6820 0.1286 0.1613 +v -1.2363 -1.0143 0.1613 +v -0.6820 -1.0143 0.1613 +v -0.6820 -1.0233 0.1523 +v -1.2363 -1.0233 0.1523 +v -1.2363 -1.0233 0.1703 +v -0.6820 -1.0233 0.1703 +v -1.2363 -1.0323 0.1613 +v -0.6820 -1.0323 0.1613 +v -1.2363 -2.1786 0.1613 +v -0.6820 -2.1786 0.1613 +v -0.6820 -2.1876 0.1523 +v -1.2363 -2.1876 0.1523 +v -1.2363 -2.1876 0.1703 +v -0.6820 -2.1876 0.1703 +v -1.2363 -2.1966 0.1613 +v -0.6820 -2.1966 0.1613 +v -1.2363 -2.1786 0.8604 +v -0.6820 -2.1786 0.8604 +v -0.6820 -2.1876 0.8514 +v -1.2363 -2.1876 0.8514 +v -1.2363 -2.1876 0.8694 +v -0.6820 -2.1876 0.8694 +v -1.2363 -2.1966 0.8604 +v -0.6820 -2.1966 0.8604 +v -1.2363 -2.1786 1.5597 +v -0.6820 -2.1786 1.5597 +v -0.6820 -2.1876 1.5507 +v -1.2363 -2.1876 1.5507 +v -1.2363 -2.1876 1.5687 +v -0.6820 -2.1876 1.5687 +v -1.2363 -2.1966 1.5597 +v -0.6820 -2.1966 1.5597 +v -1.2363 -2.1786 2.2598 +v -0.6820 -2.1786 2.2598 +v -0.6820 -2.1876 2.2508 +v -1.2363 -2.1876 2.2508 +v -1.2363 -2.1876 2.2688 +v -0.6820 -2.1876 2.2688 +v -1.2363 -2.1966 2.2598 +v -0.6820 -2.1966 2.2598 +v -1.2459 -3.3379 2.2606 +v -1.2459 8.2638 2.2606 +v -1.2369 8.2548 2.2516 +v -1.2369 -3.3289 2.2516 +v -1.2369 -3.3469 2.2696 +v -1.2369 8.2728 2.2696 +v -1.2279 -3.3379 2.2606 +v -1.2279 8.2638 2.2606 +v -1.2459 -3.3379 0.1615 +v -1.2369 -3.3289 0.1705 +v -1.2369 -3.3469 0.1525 +v -1.2279 -3.3379 0.1615 +v -1.2459 8.2638 0.1615 +v -1.2369 8.2548 0.1705 +v -1.2369 8.2728 0.1525 +v -1.2279 8.2638 0.1615 +v -1.2363 -3.3256 0.1613 +v -0.6820 -3.3256 0.1613 +v -0.6820 -3.3346 0.1523 +v -1.2363 -3.3346 0.1523 +v -1.2363 -3.3346 0.1703 +v -0.6820 -3.3346 0.1703 +v -1.2363 -3.3436 0.1613 +v -0.6820 -3.3436 0.1613 +v -1.2363 -3.3256 0.8604 +v -0.6820 -3.3256 0.8604 +v -0.6820 -3.3346 0.8514 +v -1.2363 -3.3346 0.8514 +v -1.2363 -3.3346 0.8694 +v -0.6820 -3.3346 0.8694 +v -1.2363 -3.3436 0.8604 +v -0.6820 -3.3436 0.8604 +v -1.2363 -3.3256 1.5597 +v -0.6820 -3.3256 1.5597 +v -0.6820 -3.3346 1.5507 +v -1.2363 -3.3346 1.5507 +v -1.2363 -3.3346 1.5687 +v -0.6820 -3.3346 1.5687 +v -1.2363 -3.3436 1.5597 +v -0.6820 -3.3436 1.5597 +v -1.2363 -3.3256 2.2598 +v -0.6820 -3.3256 2.2598 +v -0.6820 -3.3346 2.2508 +v -1.2363 -3.3346 2.2508 +v -1.2363 -3.3346 2.2688 +v -0.6820 -3.3346 2.2688 +v -1.2363 -3.3436 2.2598 +v -0.6820 -3.3436 2.2598 +v -1.2363 -1.0143 2.2598 +v -0.6820 -1.0143 2.2598 +v -0.6820 -1.0233 2.2508 +v -1.2363 -1.0233 2.2508 +v -1.2363 -1.0233 2.2688 +v -0.6820 -1.0233 2.2688 +v -1.2363 -1.0323 2.2598 +v -0.6820 -1.0323 2.2598 +v -1.2363 -1.0143 1.5597 +v -0.6820 -1.0143 1.5597 +v -0.6820 -1.0233 1.5507 +v -1.2363 -1.0233 1.5507 +v -1.2363 -1.0233 1.5687 +v -0.6820 -1.0233 1.5687 +v -1.2363 -1.0323 1.5597 +v -0.6820 -1.0323 1.5597 +v -1.2363 -1.0143 0.8604 +v -0.6820 -1.0143 0.8604 +v -0.6820 -1.0233 0.8514 +v -1.2363 -1.0233 0.8514 +v -1.2363 -1.0233 0.8694 +v -0.6820 -1.0233 0.8694 +v -1.2363 -1.0323 0.8604 +v -0.6820 -1.0323 0.8604 +v -1.2363 0.1466 0.8604 +v -0.6820 0.1466 0.8604 +v -0.6820 0.1376 0.8514 +v -1.2363 0.1376 0.8514 +v -1.2363 0.1376 0.8694 +v -0.6820 0.1376 0.8694 +v -1.2363 0.1286 0.8604 +v -0.6820 0.1286 0.8604 +v -1.2363 0.1466 2.2598 +v -0.6820 0.1466 2.2598 +v -0.6820 0.1376 2.2508 +v -1.2363 0.1376 2.2508 +v -1.2363 0.1376 2.2688 +v -0.6820 0.1376 2.2688 +v -1.2363 0.1286 2.2598 +v -0.6820 0.1286 2.2598 +v -1.2363 1.3097 2.2598 +v -0.6820 1.3097 2.2598 +v -0.6820 1.3007 2.2508 +v -1.2363 1.3007 2.2508 +v -1.2363 1.3007 2.2688 +v -0.6820 1.3007 2.2688 +v -1.2363 1.2917 2.2598 +v -0.6820 1.2917 2.2598 +v -1.2363 2.4753 2.2598 +v -0.6820 2.4753 2.2598 +v -0.6820 2.4663 2.2508 +v -1.2363 2.4663 2.2508 +v -1.2363 2.4663 2.2688 +v -0.6820 2.4663 2.2688 +v -1.2363 2.4573 2.2598 +v -0.6820 2.4573 2.2598 +v -1.2363 3.6340 2.2598 +v -0.6820 3.6340 2.2598 +v -0.6820 3.6250 2.2508 +v -1.2363 3.6250 2.2508 +v -1.2363 3.6250 2.2688 +v -0.6820 3.6250 2.2688 +v -1.2363 3.6160 2.2598 +v -0.6820 3.6160 2.2598 +v -1.2363 4.7925 2.2598 +v -0.6820 4.7925 2.2598 +v -0.6820 4.7835 2.2508 +v -1.2363 4.7835 2.2508 +v -1.2363 4.7835 2.2688 +v -0.6820 4.7835 2.2688 +v -1.2363 4.7745 2.2598 +v -0.6820 4.7745 2.2598 +v -1.2363 5.9592 2.2598 +v -0.6820 5.9592 2.2598 +v -0.6820 5.9502 2.2508 +v -1.2363 5.9502 2.2508 +v -1.2363 5.9502 2.2688 +v -0.6820 5.9502 2.2688 +v -1.2363 5.9412 2.2598 +v -0.6820 5.9412 2.2598 +v -1.2489 5.9538 2.2606 +v -1.2489 5.9538 0.1615 +v -1.2399 5.9448 0.1705 +v -1.2399 5.9448 2.2516 +v -1.2399 5.9628 2.2696 +v -1.2399 5.9628 0.1525 +v -1.2309 5.9538 2.2606 +v -1.2309 5.9538 0.1615 +v -0.6905 5.9538 2.2606 +v -0.6905 5.9538 0.1615 +v -0.6815 5.9448 0.1705 +v -0.6815 5.9448 2.2516 +v -0.6815 5.9628 2.2696 +v -0.6815 5.9628 0.1525 +v -0.6725 5.9538 2.2606 +v -0.6725 5.9538 0.1615 +v -1.2363 7.1196 2.2598 +v -0.6820 7.1196 2.2598 +v -0.6820 7.1106 2.2508 +v -1.2363 7.1106 2.2508 +v -1.2363 7.1106 2.2688 +v -0.6820 7.1106 2.2688 +v -1.2363 7.1016 2.2598 +v -0.6820 7.1016 2.2598 +v -1.2489 7.1138 2.2606 +v -1.2489 7.1138 0.1615 +v -1.2399 7.1048 0.1705 +v -1.2399 7.1048 2.2516 +v -1.2399 7.1228 2.2696 +v -1.2399 7.1228 0.1525 +v -1.2309 7.1138 2.2606 +v -1.2309 7.1138 0.1615 +v -0.6905 7.1138 2.2606 +v -0.6905 7.1138 0.1615 +v -0.6815 7.1048 0.1705 +v -0.6815 7.1048 2.2516 +v -0.6815 7.1228 2.2696 +v -0.6815 7.1228 0.1525 +v -0.6725 7.1138 2.2606 +v -0.6725 7.1138 0.1615 +v -1.2363 8.2724 1.5597 +v -0.6820 8.2724 1.5597 +v -0.6820 8.2634 1.5507 +v -1.2363 8.2634 1.5507 +v -1.2363 8.2634 1.5687 +v -0.6820 8.2634 1.5687 +v -1.2363 8.2544 1.5597 +v -0.6820 8.2544 1.5597 +v -1.2458 -3.3403 1.5597 +v -1.2458 8.2628 1.5597 +v -1.2368 8.2628 1.5507 +v -1.2368 -3.3403 1.5507 +v -1.2368 -3.3403 1.5687 +v -1.2368 8.2628 1.5687 +v -1.2278 -3.3403 1.5597 +v -1.2278 8.2628 1.5597 +v -1.2458 -3.3403 0.8593 +v -1.2458 8.2628 0.8593 +v -1.2368 8.2628 0.8503 +v -1.2368 -3.3403 0.8503 +v -1.2368 -3.3403 0.8683 +v -1.2368 8.2628 0.8683 +v -1.2278 -3.3403 0.8593 +v -1.2278 8.2628 0.8593 +v -1.2363 8.2724 0.8604 +v -0.6820 8.2724 0.8604 +v -0.6820 8.2634 0.8514 +v -1.2363 8.2634 0.8514 +v -1.2363 8.2634 0.8694 +v -0.6820 8.2634 0.8694 +v -1.2363 8.2544 0.8604 +v -0.6820 8.2544 0.8604 +v -1.2363 8.2724 0.1613 +v -0.6820 8.2724 0.1613 +v -0.6820 8.2634 0.1523 +v -1.2363 8.2634 0.1523 +v -1.2363 8.2634 0.1703 +v -0.6820 8.2634 0.1703 +v -1.2363 8.2544 0.1613 +v -0.6820 8.2544 0.1613 +v -1.2363 7.1196 0.1613 +v -0.6820 7.1196 0.1613 +v -0.6820 7.1106 0.1523 +v -1.2363 7.1106 0.1523 +v -1.2363 7.1106 0.1703 +v -0.6820 7.1106 0.1703 +v -1.2363 7.1016 0.1613 +v -0.6820 7.1016 0.1613 +v -1.2363 7.1196 0.8604 +v -0.6820 7.1196 0.8604 +v -0.6820 7.1106 0.8514 +v -1.2363 7.1106 0.8514 +v -1.2363 7.1106 0.8694 +v -0.6820 7.1106 0.8694 +v -1.2363 7.1016 0.8604 +v -0.6820 7.1016 0.8604 +v -1.2363 7.1196 1.5597 +v -0.6820 7.1196 1.5597 +v -0.6820 7.1106 1.5507 +v -1.2363 7.1106 1.5507 +v -1.2363 7.1106 1.5687 +v -0.6820 7.1106 1.5687 +v -1.2363 7.1016 1.5597 +v -0.6820 7.1016 1.5597 +v -1.2363 5.9592 0.1613 +v -0.6820 5.9592 0.1613 +v -0.6820 5.9502 0.1523 +v -1.2363 5.9502 0.1523 +v -1.2363 5.9502 0.1703 +v -0.6820 5.9502 0.1703 +v -1.2363 5.9412 0.1613 +v -0.6820 5.9412 0.1613 +v -1.2363 4.7925 0.1613 +v -0.6820 4.7925 0.1613 +v -0.6820 4.7835 0.1523 +v -1.2363 4.7835 0.1523 +v -1.2363 4.7835 0.1703 +v -0.6820 4.7835 0.1703 +v -1.2363 4.7745 0.1613 +v -0.6820 4.7745 0.1613 +v -1.2363 5.9592 0.8604 +v -0.6820 5.9592 0.8604 +v -0.6820 5.9502 0.8514 +v -1.2363 5.9502 0.8514 +v -1.2363 5.9502 0.8694 +v -0.6820 5.9502 0.8694 +v -1.2363 5.9412 0.8604 +v -0.6820 5.9412 0.8604 +v -1.2363 4.7925 0.8604 +v -0.6820 4.7925 0.8604 +v -0.6820 4.7835 0.8514 +v -1.2363 4.7835 0.8514 +v -1.2363 4.7835 0.8694 +v -0.6820 4.7835 0.8694 +v -1.2363 4.7745 0.8604 +v -0.6820 4.7745 0.8604 +v -1.2363 4.7925 1.5597 +v -0.6820 4.7925 1.5597 +v -0.6820 4.7835 1.5507 +v -1.2363 4.7835 1.5507 +v -1.2363 4.7835 1.5687 +v -0.6820 4.7835 1.5687 +v -1.2363 4.7745 1.5597 +v -0.6820 4.7745 1.5597 +v -1.2363 5.9592 1.5597 +v -0.6820 5.9592 1.5597 +v -0.6820 5.9502 1.5507 +v -1.2363 5.9502 1.5507 +v -1.2363 5.9502 1.5687 +v -0.6820 5.9502 1.5687 +v -1.2363 5.9412 1.5597 +v -0.6820 5.9412 1.5597 +v -1.2363 3.6340 1.5597 +v -0.6820 3.6340 1.5597 +v -0.6820 3.6250 1.5507 +v -1.2363 3.6250 1.5507 +v -1.2363 3.6250 1.5687 +v -0.6820 3.6250 1.5687 +v -1.2363 3.6160 1.5597 +v -0.6820 3.6160 1.5597 +v -1.2363 3.6340 0.8604 +v -0.6820 3.6340 0.8604 +v -0.6820 3.6250 0.8514 +v -1.2363 3.6250 0.8514 +v -1.2363 3.6250 0.8694 +v -0.6820 3.6250 0.8694 +v -1.2363 3.6160 0.8604 +v -0.6820 3.6160 0.8604 +v -1.2363 3.6340 0.1613 +v -0.6820 3.6340 0.1613 +v -0.6820 3.6250 0.1523 +v -1.2363 3.6250 0.1523 +v -1.2363 3.6250 0.1703 +v -0.6820 3.6250 0.1703 +v -1.2363 3.6160 0.1613 +v -0.6820 3.6160 0.1613 +v -1.2363 2.4753 0.1613 +v -0.6820 2.4753 0.1613 +v -0.6820 2.4663 0.1523 +v -1.2363 2.4663 0.1523 +v -1.2363 2.4663 0.1703 +v -0.6820 2.4663 0.1703 +v -1.2363 2.4573 0.1613 +v -0.6820 2.4573 0.1613 +v -1.2363 2.4753 0.8604 +v -0.6820 2.4753 0.8604 +v -0.6820 2.4663 0.8514 +v -1.2363 2.4663 0.8514 +v -1.2363 2.4663 0.8694 +v -0.6820 2.4663 0.8694 +v -1.2363 2.4573 0.8604 +v -0.6820 2.4573 0.8604 +v -1.2363 2.4753 1.5597 +v -0.6820 2.4753 1.5597 +v -0.6820 2.4663 1.5507 +v -1.2363 2.4663 1.5507 +v -1.2363 2.4663 1.5687 +v -0.6820 2.4663 1.5687 +v -1.2363 2.4573 1.5597 +v -0.6820 2.4573 1.5597 +v -1.2363 1.3097 1.5597 +v -0.6820 1.3097 1.5597 +v -0.6820 1.3007 1.5507 +v -1.2363 1.3007 1.5507 +v -1.2363 1.3007 1.5687 +v -0.6820 1.3007 1.5687 +v -1.2363 1.2917 1.5597 +v -0.6820 1.2917 1.5597 +v -1.2363 1.3097 0.8604 +v -0.6820 1.3097 0.8604 +v -0.6820 1.3007 0.8514 +v -1.2363 1.3007 0.8514 +v -1.2363 1.3007 0.8694 +v -0.6820 1.3007 0.8694 +v -1.2363 1.2917 0.8604 +v -0.6820 1.2917 0.8604 +v -1.2363 1.3097 0.1613 +v -0.6820 1.3097 0.1613 +v -0.6820 1.3007 0.1523 +v -1.2363 1.3007 0.1523 +v -1.2363 1.3007 0.1703 +v -0.6820 1.3007 0.1703 +v -1.2363 1.2917 0.1613 +v -0.6820 1.2917 0.1613 +v -1.2363 0.1466 1.5597 +v -0.6820 0.1466 1.5597 +v -0.6820 0.1376 1.5507 +v -1.2363 0.1376 1.5507 +v -1.2363 0.1376 1.5687 +v -0.6820 0.1376 1.5687 +v -1.2363 0.1286 1.5597 +v -0.6820 0.1286 1.5597 +v -1.2363 8.2724 2.2598 +v -0.6820 8.2724 2.2598 +v -0.6820 8.2634 2.2508 +v -1.2363 8.2634 2.2508 +v -1.2363 8.2634 2.2688 +v -0.6820 8.2634 2.2688 +v -1.2363 8.2544 2.2598 +v -0.6820 8.2544 2.2598 +# 560 vertices + +vn -0.7071 0.0000 -0.7071 +vn -0.7071 0.0000 0.7071 +vn 0.7071 -0.0000 0.7071 +vn 0.7071 -0.0000 -0.7071 +vn -0.7071 -0.7071 -0.0000 +vn -0.7071 0.7071 0.0000 +vn 0.7071 0.7071 0.0000 +vn 0.7071 -0.7071 -0.0000 +vn -0.7071 0.7071 -0.0000 +vn 0.7071 -0.7071 0.0000 +vn 0.0000 0.7071 -0.7071 +vn -0.0000 0.7071 0.7071 +vn -0.0000 -0.7071 0.7071 +vn 0.0000 -0.7071 -0.7071 +vn 0.0000 0.7071 0.7071 +vn 0.0000 -0.7071 0.7071 +vn -0.7072 0.7071 0.0000 +vn 0.7072 0.7071 0.0000 +# 18 vertex normals + +vt 0.3698 0.3558 0.0000 +vt 0.3698 0.3558 0.0000 +vt 0.3696 0.3561 0.0000 +vt 0.3696 0.3561 0.0000 +vt 0.3698 0.3564 0.0000 +vt 0.3698 0.3564 0.0000 +vt 0.3700 0.3561 0.0000 +vt 0.3700 0.3561 0.0000 +vt 0.3698 0.3760 0.0000 +vt 0.3698 0.3760 0.0000 +vt 0.3696 0.3763 0.0000 +vt 0.3696 0.3763 0.0000 +vt 0.3698 0.3765 0.0000 +vt 0.3698 0.3765 0.0000 +vt 0.3700 0.3763 0.0000 +vt 0.3700 0.3763 0.0000 +vt 0.3582 0.3362 0.0000 +vt 0.3582 0.3962 0.0000 +vt 0.3580 0.3965 0.0000 +vt 0.3580 0.3360 0.0000 +vt 0.3582 0.3967 0.0000 +vt 0.3582 0.3357 0.0000 +vt 0.3584 0.3965 0.0000 +vt 0.3584 0.3360 0.0000 +vt 0.3698 0.3362 0.0000 +vt 0.3698 0.3962 0.0000 +vt 0.3696 0.3965 0.0000 +vt 0.3696 0.3360 0.0000 +vt 0.3698 0.3967 0.0000 +vt 0.3698 0.3357 0.0000 +vt 0.3700 0.3965 0.0000 +vt 0.3700 0.3360 0.0000 +vt 0.3582 0.3362 0.0000 +vt 0.3582 0.3962 0.0000 +vt 0.3580 0.3965 0.0000 +vt 0.3580 0.3360 0.0000 +vt 0.3582 0.3967 0.0000 +vt 0.3582 0.3357 0.0000 +vt 0.3584 0.3965 0.0000 +vt 0.3584 0.3360 0.0000 +vt 0.3698 0.3362 0.0000 +vt 0.3698 0.3962 0.0000 +vt 0.3696 0.3965 0.0000 +vt 0.3696 0.3360 0.0000 +vt 0.3698 0.3967 0.0000 +vt 0.3698 0.3357 0.0000 +vt 0.3700 0.3965 0.0000 +vt 0.3700 0.3360 0.0000 +vt 0.3582 0.3362 0.0000 +vt 0.3582 0.3962 0.0000 +vt 0.3580 0.3965 0.0000 +vt 0.3580 0.3360 0.0000 +vt 0.3582 0.3967 0.0000 +vt 0.3582 0.3357 0.0000 +vt 0.3584 0.3965 0.0000 +vt 0.3584 0.3360 0.0000 +vt 0.3698 0.3362 0.0000 +vt 0.3698 0.3962 0.0000 +vt 0.3696 0.3965 0.0000 +vt 0.3696 0.3360 0.0000 +vt 0.3698 0.3967 0.0000 +vt 0.3698 0.3357 0.0000 +vt 0.3700 0.3965 0.0000 +vt 0.3700 0.3360 0.0000 +vt 0.3582 0.3362 0.0000 +vt 0.3582 0.3962 0.0000 +vt 0.3580 0.3965 0.0000 +vt 0.3580 0.3360 0.0000 +vt 0.3582 0.3967 0.0000 +vt 0.3582 0.3357 0.0000 +vt 0.3584 0.3965 0.0000 +vt 0.3584 0.3360 0.0000 +vt 0.3698 0.3362 0.0000 +vt 0.3698 0.3962 0.0000 +vt 0.3696 0.3965 0.0000 +vt 0.3696 0.3360 0.0000 +vt 0.3698 0.3967 0.0000 +vt 0.3698 0.3357 0.0000 +vt 0.3700 0.3965 0.0000 +vt 0.3700 0.3360 0.0000 +vt 0.3582 0.3362 0.0000 +vt 0.3582 0.3962 0.0000 +vt 0.3580 0.3965 0.0000 +vt 0.3580 0.3360 0.0000 +vt 0.3582 0.3967 0.0000 +vt 0.3582 0.3357 0.0000 +vt 0.3584 0.3965 0.0000 +vt 0.3584 0.3360 0.0000 +vt 0.3698 0.3362 0.0000 +vt 0.3698 0.3962 0.0000 +vt 0.3696 0.3965 0.0000 +vt 0.3696 0.3360 0.0000 +vt 0.3698 0.3967 0.0000 +vt 0.3698 0.3357 0.0000 +vt 0.3700 0.3965 0.0000 +vt 0.3700 0.3360 0.0000 +vt 0.3582 0.3362 0.0000 +vt 0.3582 0.3962 0.0000 +vt 0.3580 0.3965 0.0000 +vt 0.3580 0.3360 0.0000 +vt 0.3582 0.3967 0.0000 +vt 0.3582 0.3357 0.0000 +vt 0.3584 0.3965 0.0000 +vt 0.3584 0.3360 0.0000 +vt 0.3698 0.3362 0.0000 +vt 0.3698 0.3962 0.0000 +vt 0.3696 0.3965 0.0000 +vt 0.3696 0.3360 0.0000 +vt 0.3698 0.3967 0.0000 +vt 0.3698 0.3357 0.0000 +vt 0.3700 0.3965 0.0000 +vt 0.3700 0.3360 0.0000 +vt 0.3582 0.3362 0.0000 +vt 0.3582 0.3962 0.0000 +vt 0.3580 0.3965 0.0000 +vt 0.3580 0.3360 0.0000 +vt 0.3582 0.3967 0.0000 +vt 0.3582 0.3357 0.0000 +vt 0.3584 0.3965 0.0000 +vt 0.3584 0.3360 0.0000 +vt 0.3698 0.3362 0.0000 +vt 0.3698 0.3962 0.0000 +vt 0.3696 0.3965 0.0000 +vt 0.3696 0.3360 0.0000 +vt 0.3698 0.3967 0.0000 +vt 0.3698 0.3357 0.0000 +vt 0.3700 0.3965 0.0000 +vt 0.3700 0.3360 0.0000 +vt 0.3698 0.3962 0.0000 +vt 0.3698 0.3962 0.0000 +vt 0.3696 0.3965 0.0000 +vt 0.3696 0.3965 0.0000 +vt 0.3698 0.3967 0.0000 +vt 0.3698 0.3967 0.0000 +vt 0.3700 0.3965 0.0000 +vt 0.3700 0.3965 0.0000 +vt 0.3698 0.3362 0.0000 +vt 0.3696 0.3360 0.0000 +vt 0.3698 0.3357 0.0000 +vt 0.3700 0.3360 0.0000 +vt 0.3698 0.3362 0.0000 +vt 0.3696 0.3360 0.0000 +vt 0.3698 0.3357 0.0000 +vt 0.3700 0.3360 0.0000 +vt 0.3698 0.3357 0.0000 +vt 0.3583 0.3357 0.0000 +vt 0.3583 0.3360 0.0000 +vt 0.3698 0.3360 0.0000 +vt 0.3583 0.3362 0.0000 +vt 0.3698 0.3362 0.0000 +vt 0.3583 0.3360 0.0000 +vt 0.3698 0.3360 0.0000 +vt 0.3698 0.3357 0.0000 +vt 0.3583 0.3357 0.0000 +vt 0.3583 0.3360 0.0000 +vt 0.3698 0.3360 0.0000 +vt 0.3583 0.3362 0.0000 +vt 0.3698 0.3362 0.0000 +vt 0.3583 0.3360 0.0000 +vt 0.3698 0.3360 0.0000 +vt 0.3698 0.3357 0.0000 +vt 0.3583 0.3357 0.0000 +vt 0.3583 0.3360 0.0000 +vt 0.3698 0.3360 0.0000 +vt 0.3583 0.3362 0.0000 +vt 0.3698 0.3362 0.0000 +vt 0.3583 0.3360 0.0000 +vt 0.3698 0.3360 0.0000 +vt 0.3698 0.3559 0.0000 +vt 0.3583 0.3559 0.0000 +vt 0.3583 0.3561 0.0000 +vt 0.3698 0.3561 0.0000 +vt 0.3583 0.3564 0.0000 +vt 0.3698 0.3564 0.0000 +vt 0.3583 0.3561 0.0000 +vt 0.3698 0.3561 0.0000 +vt 0.3698 0.3760 0.0000 +vt 0.3583 0.3760 0.0000 +vt 0.3583 0.3763 0.0000 +vt 0.3698 0.3763 0.0000 +vt 0.3583 0.3765 0.0000 +vt 0.3698 0.3765 0.0000 +vt 0.3583 0.3763 0.0000 +vt 0.3698 0.3763 0.0000 +vt 0.3698 0.3962 0.0000 +vt 0.3583 0.3962 0.0000 +vt 0.3583 0.3965 0.0000 +vt 0.3698 0.3965 0.0000 +vt 0.3583 0.3967 0.0000 +vt 0.3698 0.3967 0.0000 +vt 0.3583 0.3965 0.0000 +vt 0.3698 0.3965 0.0000 +vt 0.3583 0.3962 0.0000 +vt 0.3583 0.3962 0.0000 +vt 0.3581 0.3965 0.0000 +vt 0.3581 0.3965 0.0000 +vt 0.3583 0.3967 0.0000 +vt 0.3583 0.3967 0.0000 +vt 0.3585 0.3965 0.0000 +vt 0.3585 0.3965 0.0000 +vt 0.3583 0.3362 0.0000 +vt 0.3581 0.3360 0.0000 +vt 0.3583 0.3357 0.0000 +vt 0.3585 0.3360 0.0000 +vt 0.3583 0.3362 0.0000 +vt 0.3581 0.3360 0.0000 +vt 0.3583 0.3357 0.0000 +vt 0.3585 0.3360 0.0000 +vt 0.3698 0.3357 0.0000 +vt 0.3583 0.3357 0.0000 +vt 0.3583 0.3360 0.0000 +vt 0.3698 0.3360 0.0000 +vt 0.3583 0.3362 0.0000 +vt 0.3698 0.3362 0.0000 +vt 0.3583 0.3360 0.0000 +vt 0.3698 0.3360 0.0000 +vt 0.3698 0.3559 0.0000 +vt 0.3583 0.3559 0.0000 +vt 0.3583 0.3561 0.0000 +vt 0.3698 0.3561 0.0000 +vt 0.3583 0.3564 0.0000 +vt 0.3698 0.3564 0.0000 +vt 0.3583 0.3561 0.0000 +vt 0.3698 0.3561 0.0000 +vt 0.3698 0.3760 0.0000 +vt 0.3583 0.3760 0.0000 +vt 0.3583 0.3763 0.0000 +vt 0.3698 0.3763 0.0000 +vt 0.3583 0.3765 0.0000 +vt 0.3698 0.3765 0.0000 +vt 0.3583 0.3763 0.0000 +vt 0.3698 0.3763 0.0000 +vt 0.3698 0.3962 0.0000 +vt 0.3583 0.3962 0.0000 +vt 0.3583 0.3965 0.0000 +vt 0.3698 0.3965 0.0000 +vt 0.3583 0.3967 0.0000 +vt 0.3698 0.3967 0.0000 +vt 0.3583 0.3965 0.0000 +vt 0.3698 0.3965 0.0000 +vt 0.3698 0.3962 0.0000 +vt 0.3583 0.3962 0.0000 +vt 0.3583 0.3965 0.0000 +vt 0.3698 0.3965 0.0000 +vt 0.3583 0.3967 0.0000 +vt 0.3698 0.3967 0.0000 +vt 0.3583 0.3965 0.0000 +vt 0.3698 0.3965 0.0000 +vt 0.3698 0.3760 0.0000 +vt 0.3583 0.3760 0.0000 +vt 0.3583 0.3763 0.0000 +vt 0.3698 0.3763 0.0000 +vt 0.3583 0.3765 0.0000 +vt 0.3698 0.3765 0.0000 +vt 0.3583 0.3763 0.0000 +vt 0.3698 0.3763 0.0000 +vt 0.3698 0.3559 0.0000 +vt 0.3583 0.3559 0.0000 +vt 0.3583 0.3561 0.0000 +vt 0.3698 0.3561 0.0000 +vt 0.3583 0.3564 0.0000 +vt 0.3698 0.3564 0.0000 +vt 0.3583 0.3561 0.0000 +vt 0.3698 0.3561 0.0000 +vt 0.3698 0.3559 0.0000 +vt 0.3583 0.3559 0.0000 +vt 0.3583 0.3561 0.0000 +vt 0.3698 0.3561 0.0000 +vt 0.3583 0.3564 0.0000 +vt 0.3698 0.3564 0.0000 +vt 0.3583 0.3561 0.0000 +vt 0.3698 0.3561 0.0000 +vt 0.3698 0.3962 0.0000 +vt 0.3583 0.3962 0.0000 +vt 0.3583 0.3965 0.0000 +vt 0.3698 0.3965 0.0000 +vt 0.3583 0.3967 0.0000 +vt 0.3698 0.3967 0.0000 +vt 0.3583 0.3965 0.0000 +vt 0.3698 0.3965 0.0000 +vt 0.3698 0.3962 0.0000 +vt 0.3583 0.3962 0.0000 +vt 0.3583 0.3965 0.0000 +vt 0.3698 0.3965 0.0000 +vt 0.3583 0.3967 0.0000 +vt 0.3698 0.3967 0.0000 +vt 0.3583 0.3965 0.0000 +vt 0.3698 0.3965 0.0000 +vt 0.3698 0.3962 0.0000 +vt 0.3583 0.3962 0.0000 +vt 0.3583 0.3965 0.0000 +vt 0.3698 0.3965 0.0000 +vt 0.3583 0.3967 0.0000 +vt 0.3698 0.3967 0.0000 +vt 0.3583 0.3965 0.0000 +vt 0.3698 0.3965 0.0000 +vt 0.3698 0.3962 0.0000 +vt 0.3583 0.3962 0.0000 +vt 0.3583 0.3965 0.0000 +vt 0.3698 0.3965 0.0000 +vt 0.3583 0.3967 0.0000 +vt 0.3698 0.3967 0.0000 +vt 0.3583 0.3965 0.0000 +vt 0.3698 0.3965 0.0000 +vt 0.3698 0.3962 0.0000 +vt 0.3583 0.3962 0.0000 +vt 0.3583 0.3965 0.0000 +vt 0.3698 0.3965 0.0000 +vt 0.3583 0.3967 0.0000 +vt 0.3698 0.3967 0.0000 +vt 0.3583 0.3965 0.0000 +vt 0.3698 0.3965 0.0000 +vt 0.3698 0.3962 0.0000 +vt 0.3583 0.3962 0.0000 +vt 0.3583 0.3965 0.0000 +vt 0.3698 0.3965 0.0000 +vt 0.3583 0.3967 0.0000 +vt 0.3698 0.3967 0.0000 +vt 0.3583 0.3965 0.0000 +vt 0.3698 0.3965 0.0000 +vt 0.3582 0.3362 0.0000 +vt 0.3582 0.3962 0.0000 +vt 0.3580 0.3965 0.0000 +vt 0.3580 0.3360 0.0000 +vt 0.3582 0.3967 0.0000 +vt 0.3582 0.3357 0.0000 +vt 0.3584 0.3965 0.0000 +vt 0.3584 0.3360 0.0000 +vt 0.3698 0.3362 0.0000 +vt 0.3698 0.3962 0.0000 +vt 0.3696 0.3965 0.0000 +vt 0.3696 0.3360 0.0000 +vt 0.3698 0.3967 0.0000 +vt 0.3698 0.3357 0.0000 +vt 0.3700 0.3965 0.0000 +vt 0.3700 0.3360 0.0000 +vt 0.3698 0.3962 0.0000 +vt 0.3583 0.3962 0.0000 +vt 0.3583 0.3965 0.0000 +vt 0.3698 0.3965 0.0000 +vt 0.3583 0.3967 0.0000 +vt 0.3698 0.3967 0.0000 +vt 0.3583 0.3965 0.0000 +vt 0.3698 0.3965 0.0000 +vt 0.3582 0.3362 0.0000 +vt 0.3582 0.3962 0.0000 +vt 0.3580 0.3965 0.0000 +vt 0.3580 0.3360 0.0000 +vt 0.3582 0.3967 0.0000 +vt 0.3582 0.3357 0.0000 +vt 0.3584 0.3965 0.0000 +vt 0.3584 0.3360 0.0000 +vt 0.3698 0.3362 0.0000 +vt 0.3698 0.3962 0.0000 +vt 0.3696 0.3965 0.0000 +vt 0.3696 0.3360 0.0000 +vt 0.3698 0.3967 0.0000 +vt 0.3698 0.3357 0.0000 +vt 0.3700 0.3965 0.0000 +vt 0.3700 0.3360 0.0000 +vt 0.3698 0.3760 0.0000 +vt 0.3583 0.3760 0.0000 +vt 0.3583 0.3763 0.0000 +vt 0.3698 0.3763 0.0000 +vt 0.3583 0.3765 0.0000 +vt 0.3698 0.3765 0.0000 +vt 0.3583 0.3763 0.0000 +vt 0.3698 0.3763 0.0000 +vt 0.3583 0.3760 0.0000 +vt 0.3583 0.3760 0.0000 +vt 0.3581 0.3763 0.0000 +vt 0.3581 0.3763 0.0000 +vt 0.3583 0.3765 0.0000 +vt 0.3583 0.3765 0.0000 +vt 0.3585 0.3763 0.0000 +vt 0.3585 0.3763 0.0000 +vt 0.3583 0.3558 0.0000 +vt 0.3583 0.3558 0.0000 +vt 0.3581 0.3561 0.0000 +vt 0.3581 0.3561 0.0000 +vt 0.3583 0.3564 0.0000 +vt 0.3583 0.3564 0.0000 +vt 0.3585 0.3561 0.0000 +vt 0.3585 0.3561 0.0000 +vt 0.3698 0.3559 0.0000 +vt 0.3583 0.3559 0.0000 +vt 0.3583 0.3561 0.0000 +vt 0.3698 0.3561 0.0000 +vt 0.3583 0.3564 0.0000 +vt 0.3698 0.3564 0.0000 +vt 0.3583 0.3561 0.0000 +vt 0.3698 0.3561 0.0000 +vt 0.3698 0.3357 0.0000 +vt 0.3583 0.3357 0.0000 +vt 0.3583 0.3360 0.0000 +vt 0.3698 0.3360 0.0000 +vt 0.3583 0.3362 0.0000 +vt 0.3698 0.3362 0.0000 +vt 0.3583 0.3360 0.0000 +vt 0.3698 0.3360 0.0000 +vt 0.3698 0.3357 0.0000 +vt 0.3583 0.3357 0.0000 +vt 0.3583 0.3360 0.0000 +vt 0.3698 0.3360 0.0000 +vt 0.3583 0.3362 0.0000 +vt 0.3698 0.3362 0.0000 +vt 0.3583 0.3360 0.0000 +vt 0.3698 0.3360 0.0000 +vt 0.3698 0.3559 0.0000 +vt 0.3583 0.3559 0.0000 +vt 0.3583 0.3561 0.0000 +vt 0.3698 0.3561 0.0000 +vt 0.3583 0.3564 0.0000 +vt 0.3698 0.3564 0.0000 +vt 0.3583 0.3561 0.0000 +vt 0.3698 0.3561 0.0000 +vt 0.3698 0.3760 0.0000 +vt 0.3583 0.3760 0.0000 +vt 0.3583 0.3763 0.0000 +vt 0.3698 0.3763 0.0000 +vt 0.3583 0.3765 0.0000 +vt 0.3698 0.3765 0.0000 +vt 0.3583 0.3763 0.0000 +vt 0.3698 0.3763 0.0000 +vt 0.3698 0.3357 0.0000 +vt 0.3583 0.3357 0.0000 +vt 0.3583 0.3360 0.0000 +vt 0.3698 0.3360 0.0000 +vt 0.3583 0.3362 0.0000 +vt 0.3698 0.3362 0.0000 +vt 0.3583 0.3360 0.0000 +vt 0.3698 0.3360 0.0000 +vt 0.3698 0.3357 0.0000 +vt 0.3583 0.3357 0.0000 +vt 0.3583 0.3360 0.0000 +vt 0.3698 0.3360 0.0000 +vt 0.3583 0.3362 0.0000 +vt 0.3698 0.3362 0.0000 +vt 0.3583 0.3360 0.0000 +vt 0.3698 0.3360 0.0000 +vt 0.3698 0.3559 0.0000 +vt 0.3583 0.3559 0.0000 +vt 0.3583 0.3561 0.0000 +vt 0.3698 0.3561 0.0000 +vt 0.3583 0.3564 0.0000 +vt 0.3698 0.3564 0.0000 +vt 0.3583 0.3561 0.0000 +vt 0.3698 0.3561 0.0000 +vt 0.3698 0.3559 0.0000 +vt 0.3583 0.3559 0.0000 +vt 0.3583 0.3561 0.0000 +vt 0.3698 0.3561 0.0000 +vt 0.3583 0.3564 0.0000 +vt 0.3698 0.3564 0.0000 +vt 0.3583 0.3561 0.0000 +vt 0.3698 0.3561 0.0000 +vt 0.3698 0.3760 0.0000 +vt 0.3583 0.3760 0.0000 +vt 0.3583 0.3763 0.0000 +vt 0.3698 0.3763 0.0000 +vt 0.3583 0.3765 0.0000 +vt 0.3698 0.3765 0.0000 +vt 0.3583 0.3763 0.0000 +vt 0.3698 0.3763 0.0000 +vt 0.3698 0.3760 0.0000 +vt 0.3583 0.3760 0.0000 +vt 0.3583 0.3763 0.0000 +vt 0.3698 0.3763 0.0000 +vt 0.3583 0.3765 0.0000 +vt 0.3698 0.3765 0.0000 +vt 0.3583 0.3763 0.0000 +vt 0.3698 0.3763 0.0000 +vt 0.3698 0.3760 0.0000 +vt 0.3583 0.3760 0.0000 +vt 0.3583 0.3763 0.0000 +vt 0.3698 0.3763 0.0000 +vt 0.3583 0.3765 0.0000 +vt 0.3698 0.3765 0.0000 +vt 0.3583 0.3763 0.0000 +vt 0.3698 0.3763 0.0000 +vt 0.3698 0.3559 0.0000 +vt 0.3583 0.3559 0.0000 +vt 0.3583 0.3561 0.0000 +vt 0.3698 0.3561 0.0000 +vt 0.3583 0.3564 0.0000 +vt 0.3698 0.3564 0.0000 +vt 0.3583 0.3561 0.0000 +vt 0.3698 0.3561 0.0000 +vt 0.3698 0.3357 0.0000 +vt 0.3583 0.3357 0.0000 +vt 0.3583 0.3360 0.0000 +vt 0.3698 0.3360 0.0000 +vt 0.3583 0.3362 0.0000 +vt 0.3698 0.3362 0.0000 +vt 0.3583 0.3360 0.0000 +vt 0.3698 0.3360 0.0000 +vt 0.3698 0.3357 0.0000 +vt 0.3583 0.3357 0.0000 +vt 0.3583 0.3360 0.0000 +vt 0.3698 0.3360 0.0000 +vt 0.3583 0.3362 0.0000 +vt 0.3698 0.3362 0.0000 +vt 0.3583 0.3360 0.0000 +vt 0.3698 0.3360 0.0000 +vt 0.3698 0.3559 0.0000 +vt 0.3583 0.3559 0.0000 +vt 0.3583 0.3561 0.0000 +vt 0.3698 0.3561 0.0000 +vt 0.3583 0.3564 0.0000 +vt 0.3698 0.3564 0.0000 +vt 0.3583 0.3561 0.0000 +vt 0.3698 0.3561 0.0000 +vt 0.3698 0.3760 0.0000 +vt 0.3583 0.3760 0.0000 +vt 0.3583 0.3763 0.0000 +vt 0.3698 0.3763 0.0000 +vt 0.3583 0.3765 0.0000 +vt 0.3698 0.3765 0.0000 +vt 0.3583 0.3763 0.0000 +vt 0.3698 0.3763 0.0000 +vt 0.3698 0.3760 0.0000 +vt 0.3583 0.3760 0.0000 +vt 0.3583 0.3763 0.0000 +vt 0.3698 0.3763 0.0000 +vt 0.3583 0.3765 0.0000 +vt 0.3698 0.3765 0.0000 +vt 0.3583 0.3763 0.0000 +vt 0.3698 0.3763 0.0000 +vt 0.3698 0.3559 0.0000 +vt 0.3583 0.3559 0.0000 +vt 0.3583 0.3561 0.0000 +vt 0.3698 0.3561 0.0000 +vt 0.3583 0.3564 0.0000 +vt 0.3698 0.3564 0.0000 +vt 0.3583 0.3561 0.0000 +vt 0.3698 0.3561 0.0000 +vt 0.3698 0.3357 0.0000 +vt 0.3583 0.3357 0.0000 +vt 0.3583 0.3360 0.0000 +vt 0.3698 0.3360 0.0000 +vt 0.3583 0.3362 0.0000 +vt 0.3698 0.3362 0.0000 +vt 0.3583 0.3360 0.0000 +vt 0.3698 0.3360 0.0000 +vt 0.3698 0.3760 0.0000 +vt 0.3583 0.3760 0.0000 +vt 0.3583 0.3763 0.0000 +vt 0.3698 0.3763 0.0000 +vt 0.3583 0.3765 0.0000 +vt 0.3698 0.3765 0.0000 +vt 0.3583 0.3763 0.0000 +vt 0.3698 0.3763 0.0000 +vt 0.3698 0.3962 0.0000 +vt 0.3583 0.3962 0.0000 +vt 0.3583 0.3965 0.0000 +vt 0.3698 0.3965 0.0000 +vt 0.3583 0.3967 0.0000 +vt 0.3698 0.3967 0.0000 +vt 0.3583 0.3965 0.0000 +vt 0.3698 0.3965 0.0000 +# 560 texture coords + +# g Frame_Bins +# usemtl ShippingContainer +# s 1 +# f 5961/5967/208 5962/5968/208 5963/5965/208 5964/5966/208 +# s 2 +# f 5965/5969/209 5966/5970/209 5962/5968/209 5961/5967/209 +# s 1 +# f 5967/5971/210 5968/5972/210 5966/5970/210 5965/5969/210 +# s 2 +# f 5964/5966/211 5963/5965/211 5968/5972/211 5967/5971/211 +# s 1 +# f 5969/5975/208 5970/5976/208 5971/5973/208 5972/5974/208 +# s 2 +# f 5973/5977/209 5974/5978/209 5970/5976/209 5969/5975/209 +# s 1 +# f 5975/5979/210 5976/5980/210 5974/5978/210 5973/5977/210 +# s 2 +# f 5972/5974/211 5971/5973/211 5976/5980/211 5975/5979/211 +# s 4 +# f 5977/5983/212 5978/5984/212 5979/5981/212 5980/5982/212 +# s 8 +# f 5981/5985/213 5982/5986/213 5978/5984/213 5977/5983/213 +# s 4 +# f 5983/5987/214 5984/5988/214 5982/5986/214 5981/5985/214 +# s 8 +# f 5980/5982/215 5979/5981/215 5984/5988/215 5983/5987/215 +# s 4 +# f 5985/5991/212 5986/5992/212 5987/5989/212 5988/5990/212 +# s 8 +# f 5989/5993/213 5990/5994/213 5986/5992/213 5985/5991/213 +# s 4 +# f 5991/5995/214 5992/5996/214 5990/5994/214 5989/5993/214 +# s 8 +# f 5988/5990/215 5987/5989/215 5992/5996/215 5991/5995/215 +# s 4 +# f 5993/5999/212 5994/6000/212 5995/5997/212 5996/5998/212 +# s 8 +# f 5997/6001/213 5998/6002/213 5994/6000/213 5993/5999/213 +# s 4 +# f 5999/6003/214 6000/6004/214 5998/6002/214 5997/6001/214 +# s 8 +# f 5996/5998/215 5995/5997/215 6000/6004/215 5999/6003/215 +# s 4 +# f 6001/6007/212 6002/6008/212 6003/6005/212 6004/6006/212 +# s 8 +# f 6005/6009/213 6006/6010/213 6002/6008/213 6001/6007/213 +# s 4 +# f 6007/6011/214 6008/6012/214 6006/6010/214 6005/6009/214 +# s 8 +# f 6004/6006/215 6003/6005/215 6008/6012/215 6007/6011/215 +# s 4 +# f 6009/6015/212 6010/6016/212 6011/6013/212 6012/6014/212 +# s 8 +# f 6013/6017/213 6014/6018/213 6010/6016/213 6009/6015/213 +# s 4 +# f 6015/6019/214 6016/6020/214 6014/6018/214 6013/6017/214 +# s 8 +# f 6012/6014/215 6011/6013/215 6016/6020/215 6015/6019/215 +# s 4 +# f 6017/6023/212 6018/6024/212 6019/6021/212 6020/6022/212 +# s 8 +# f 6021/6025/213 6022/6026/213 6018/6024/213 6017/6023/213 +# s 4 +# f 6023/6027/214 6024/6028/214 6022/6026/214 6021/6025/214 +# s 8 +# f 6020/6022/215 6019/6021/215 6024/6028/215 6023/6027/215 +# s 4 +# f 6025/6031/212 6026/6032/212 6027/6029/212 6028/6030/212 +# s 8 +# f 6029/6033/213 6030/6034/213 6026/6032/213 6025/6031/213 +# s 4 +# f 6031/6035/214 6032/6036/214 6030/6034/214 6029/6033/214 +# s 8 +# f 6028/6030/215 6027/6029/215 6032/6036/215 6031/6035/215 +# s 4 +# f 6033/6039/212 6034/6040/212 6035/6037/212 6036/6038/212 +# s 8 +# f 6037/6041/213 6038/6042/213 6034/6040/213 6033/6039/213 +# s 4 +# f 6039/6043/214 6040/6044/214 6038/6042/214 6037/6041/214 +# s 8 +# f 6036/6038/215 6035/6037/215 6040/6044/215 6039/6043/215 +# s 4 +# f 6041/6047/212 6042/6048/212 6043/6045/212 6044/6046/212 +# s 8 +# f 6045/6049/213 6046/6050/213 6042/6048/213 6041/6047/213 +# s 4 +# f 6047/6051/214 6048/6052/214 6046/6050/214 6045/6049/214 +# s 8 +# f 6044/6046/215 6043/6045/215 6048/6052/215 6047/6051/215 +# s 4 +# f 6049/6055/212 6050/6056/212 6051/6053/212 6052/6054/212 +# s 8 +# f 6053/6057/213 6054/6058/213 6050/6056/213 6049/6055/213 +# s 4 +# f 6055/6059/214 6056/6060/214 6054/6058/214 6053/6057/214 +# s 8 +# f 6052/6054/215 6051/6053/215 6056/6060/215 6055/6059/215 +# s 4 +# f 6057/6063/212 6058/6064/212 6059/6061/212 6060/6062/212 +# s 8 +# f 6061/6065/213 6062/6066/213 6058/6064/213 6057/6063/213 +# s 4 +# f 6063/6067/214 6064/6068/214 6062/6066/214 6061/6065/214 +# s 8 +# f 6060/6062/215 6059/6061/215 6064/6068/215 6063/6067/215 +# s 4 +# f 6065/6071/212 6066/6072/212 6067/6069/212 6068/6070/212 +# s 8 +# f 6069/6073/213 6070/6074/213 6066/6072/213 6065/6071/213 +# s 4 +# f 6071/6075/214 6072/6076/214 6070/6074/214 6069/6073/214 +# s 8 +# f 6068/6070/215 6067/6069/215 6072/6076/215 6071/6075/215 +# s 4 +# f 6073/6079/212 6074/6080/212 6075/6077/212 6076/6078/212 +# s 8 +# f 6077/6081/213 6078/6082/213 6074/6080/213 6073/6079/213 +# s 4 +# f 6079/6083/214 6080/6084/214 6078/6082/214 6077/6081/214 +# s 8 +# f 6076/6078/215 6075/6077/215 6080/6084/215 6079/6083/215 +# s 4 +# f 6081/6087/212 6082/6088/212 6083/6085/212 6084/6086/212 +# s 8 +# f 6085/6089/213 6086/6090/213 6082/6088/213 6081/6087/213 +# s 4 +# f 6087/6091/214 6088/6092/214 6086/6090/214 6085/6089/214 +# s 8 +# f 6084/6086/215 6083/6085/215 6088/6092/215 6087/6091/215 +# s 1 +# f 6089/6095/208 6090/6096/208 6091/6093/208 6092/6094/208 +# s 2 +# f 6093/6097/209 6094/6098/209 6090/6096/209 6089/6095/209 +# s 1 +# f 6095/6099/210 6096/6100/210 6094/6098/210 6093/6097/210 +# s 2 +# f 6092/6094/211 6091/6093/211 6096/6100/211 6095/6099/211 +# s 4 +# f 6097/6102/216 6089/6095/216 6092/6094/216 6098/6101/216 +# s 8 +# f 6099/6103/212 6093/6097/212 6089/6095/212 6097/6102/212 +# s 4 +# f 6100/6104/215 6095/6099/217 6093/6097/217 6099/6103/215 +# s 8 +# f 6098/6101/214 6092/6094/214 6095/6099/214 6100/6104/214 +# s 1 +# f 6101/6106/209 6097/6102/209 6098/6101/209 6102/6105/209 +# s 2 +# f 6103/6107/208 6099/6103/208 6097/6102/208 6101/6106/208 +# s 1 +# f 6104/6108/211 6100/6104/211 6099/6103/211 6103/6107/211 +# s 2 +# f 6102/6105/210 6098/6101/210 6100/6104/210 6104/6108/210 +# s 4 +# f 6090/6096/212 6101/6106/212 6102/6105/212 6091/6093/212 +# s 8 +# f 6094/6098/213 6103/6107/213 6101/6106/213 6090/6096/213 +# s 4 +# f 6096/6100/214 6104/6108/214 6103/6107/214 6094/6098/214 +# s 8 +# f 6091/6093/215 6102/6105/215 6104/6108/215 6096/6100/215 +# s 1 +# f 6105/6111/218 6106/6112/218 6107/6109/218 6108/6110/218 +# s 2 +# f 6109/6113/219 6110/6114/219 6106/6112/219 6105/6111/219 +# s 1 +# f 6111/6115/220 6112/6116/220 6110/6114/220 6109/6113/220 +# s 2 +# f 6108/6110/221 6107/6109/221 6112/6116/221 6111/6115/221 +# s 1 +# f 6113/6119/218 6114/6120/218 6115/6117/218 6116/6118/218 +# s 2 +# f 6117/6121/219 6118/6122/219 6114/6120/219 6113/6119/219 +# s 1 +# f 6119/6123/220 6120/6124/220 6118/6122/220 6117/6121/220 +# s 2 +# f 6116/6118/221 6115/6117/221 6120/6124/221 6119/6123/221 +# s 1 +# f 6121/6127/218 6122/6128/218 6123/6125/218 6124/6126/218 +# s 2 +# f 6125/6129/219 6126/6130/219 6122/6128/219 6121/6127/219 +# s 1 +# f 6127/6131/220 6128/6132/220 6126/6130/220 6125/6129/220 +# s 2 +# f 6124/6126/221 6123/6125/221 6128/6132/221 6127/6131/221 +# s 1 +# f 6129/6135/218 6130/6136/218 6131/6133/218 6132/6134/218 +# s 2 +# f 6133/6137/219 6134/6138/219 6130/6136/219 6129/6135/219 +# s 1 +# f 6135/6139/220 6136/6140/220 6134/6138/220 6133/6137/220 +# s 2 +# f 6132/6134/221 6131/6133/221 6136/6140/221 6135/6139/221 +# s 1 +# f 6137/6143/218 6138/6144/218 6139/6141/218 6140/6142/218 +# s 2 +# f 6141/6145/219 6142/6146/219 6138/6144/219 6137/6143/219 +# s 1 +# f 6143/6147/220 6144/6148/220 6142/6146/220 6141/6145/220 +# s 2 +# f 6140/6142/221 6139/6141/221 6144/6148/221 6143/6147/221 +# s 1 +# f 6145/6151/218 6146/6152/218 6147/6149/218 6148/6150/218 +# s 2 +# f 6149/6153/219 6150/6154/219 6146/6152/219 6145/6151/222 +# s 1 +# f 6151/6155/220 6152/6156/223 6150/6154/220 6149/6153/220 +# s 2 +# f 6148/6150/221 6147/6149/221 6152/6156/221 6151/6155/221 +# s 1 +# f 6153/6159/208 6154/6160/208 6155/6157/208 6156/6158/208 +# s 2 +# f 6157/6161/209 6158/6162/209 6154/6160/209 6153/6159/209 +# s 1 +# f 6159/6163/210 6160/6164/210 6158/6162/210 6157/6161/210 +# s 2 +# f 6156/6158/211 6155/6157/211 6160/6164/211 6159/6163/211 +# s 4 +# f 6161/6166/213 6153/6159/216 6156/6158/216 6162/6165/213 +# s 8 +# f 6163/6167/212 6157/6161/212 6153/6159/212 6161/6166/212 +# s 4 +# f 6164/6168/215 6159/6163/217 6157/6161/217 6163/6167/215 +# s 8 +# f 6162/6165/214 6156/6158/214 6159/6163/214 6164/6168/214 +# s 1 +# f 6165/6170/209 6161/6166/209 6162/6165/209 6166/6169/209 +# s 2 +# f 6167/6171/208 6163/6167/208 6161/6166/208 6165/6170/208 +# s 1 +# f 6168/6172/211 6164/6168/211 6163/6167/211 6167/6171/211 +# s 2 +# f 6166/6169/210 6162/6165/210 6164/6168/210 6168/6172/210 +# s 4 +# f 6154/6160/212 6165/6170/212 6166/6169/212 6155/6157/212 +# s 8 +# f 6158/6162/213 6167/6171/213 6165/6170/213 6154/6160/213 +# s 4 +# f 6160/6164/214 6168/6172/214 6167/6171/214 6158/6162/214 +# s 8 +# f 6155/6157/215 6166/6169/215 6168/6172/215 6160/6164/215 +# s 1 +# f 6169/6175/218 6170/6176/218 6171/6173/218 6172/6174/218 +# s 2 +# f 6173/6177/219 6174/6178/219 6170/6176/219 6169/6175/219 +# s 1 +# f 6175/6179/220 6176/6180/220 6174/6178/220 6173/6177/220 +# s 2 +# f 6172/6174/221 6171/6173/221 6176/6180/221 6175/6179/221 +# s 1 +# f 6177/6183/218 6178/6184/218 6179/6181/218 6180/6182/218 +# s 2 +# f 6181/6185/219 6182/6186/219 6178/6184/219 6177/6183/219 +# s 1 +# f 6183/6187/220 6184/6188/220 6182/6186/220 6181/6185/220 +# s 2 +# f 6180/6182/221 6179/6181/221 6184/6188/221 6183/6187/221 +# s 1 +# f 6185/6191/218 6186/6192/218 6187/6189/218 6188/6190/218 +# s 2 +# f 6189/6193/219 6190/6194/219 6186/6192/219 6185/6191/219 +# s 1 +# f 6191/6195/220 6192/6196/220 6190/6194/220 6189/6193/220 +# s 2 +# f 6188/6190/221 6187/6189/221 6192/6196/221 6191/6195/221 +# s 1 +# f 6193/6199/218 6194/6200/218 6195/6197/218 6196/6198/218 +# s 2 +# f 6197/6201/219 6198/6202/219 6194/6200/219 6193/6199/222 +# s 1 +# f 6199/6203/220 6200/6204/223 6198/6202/220 6197/6201/220 +# s 2 +# f 6196/6198/221 6195/6197/221 6200/6204/221 6199/6203/221 +# s 1 +# f 6201/6207/218 6202/6208/218 6203/6205/218 6204/6206/218 +# s 2 +# f 6205/6209/219 6206/6210/222 6202/6208/219 6201/6207/219 +# s 1 +# f 6207/6211/220 6208/6212/220 6206/6210/220 6205/6209/223 +# s 2 +# f 6204/6206/221 6203/6205/221 6208/6212/221 6207/6211/221 +# s 1 +# f 6209/6215/218 6210/6216/218 6211/6213/218 6212/6214/218 +# s 2 +# f 6213/6217/219 6214/6218/219 6210/6216/219 6209/6215/219 +# s 1 +# f 6215/6219/220 6216/6220/220 6214/6218/220 6213/6217/220 +# s 2 +# f 6212/6214/221 6211/6213/221 6216/6220/221 6215/6219/221 +# s 1 +# f 6217/6223/218 6218/6224/218 6219/6221/218 6220/6222/218 +# s 2 +# f 6221/6225/219 6222/6226/219 6218/6224/219 6217/6223/219 +# s 1 +# f 6223/6227/220 6224/6228/220 6222/6226/220 6221/6225/220 +# s 2 +# f 6220/6222/221 6219/6221/221 6224/6228/221 6223/6227/221 +# s 1 +# f 6225/6231/218 6226/6232/218 6227/6229/218 6228/6230/218 +# s 2 +# f 6229/6233/219 6230/6234/219 6226/6232/219 6225/6231/219 +# s 1 +# f 6231/6235/220 6232/6236/220 6230/6234/220 6229/6233/220 +# s 2 +# f 6228/6230/221 6227/6229/221 6232/6236/221 6231/6235/221 +# s 1 +# f 6233/6239/218 6234/6240/218 6235/6237/218 6236/6238/218 +# s 2 +# f 6237/6241/219 6238/6242/219 6234/6240/219 6233/6239/219 +# s 1 +# f 6239/6243/220 6240/6244/220 6238/6242/220 6237/6241/220 +# s 2 +# f 6236/6238/221 6235/6237/221 6240/6244/221 6239/6243/221 +# s 1 +# f 6241/6247/218 6242/6248/218 6243/6245/218 6244/6246/218 +# s 2 +# f 6245/6249/219 6246/6250/219 6242/6248/219 6241/6247/219 +# s 1 +# f 6247/6251/220 6248/6252/220 6246/6250/220 6245/6249/220 +# s 2 +# f 6244/6246/221 6243/6245/221 6248/6252/221 6247/6251/221 +# s 1 +# f 6249/6255/218 6250/6256/218 6251/6253/218 6252/6254/218 +# s 2 +# f 6253/6257/219 6254/6258/219 6250/6256/219 6249/6255/219 +# s 1 +# f 6255/6259/220 6256/6260/220 6254/6258/220 6253/6257/220 +# s 2 +# f 6252/6254/221 6251/6253/221 6256/6260/221 6255/6259/221 +# s 1 +# f 6257/6263/218 6258/6264/218 6259/6261/218 6260/6262/218 +# s 2 +# f 6261/6265/222 6262/6266/222 6258/6264/222 6257/6263/222 +# s 1 +# f 6263/6267/223 6264/6268/223 6262/6266/223 6261/6265/223 +# s 2 +# f 6260/6262/221 6259/6261/221 6264/6268/221 6263/6267/221 +# s 1 +# f 6265/6271/218 6266/6272/218 6267/6269/218 6268/6270/218 +# s 2 +# f 6269/6273/222 6270/6274/222 6266/6272/222 6265/6271/222 +# s 1 +# f 6271/6275/223 6272/6276/223 6270/6274/223 6269/6273/223 +# s 2 +# f 6268/6270/221 6267/6269/221 6272/6276/221 6271/6275/221 +# s 1 +# f 6273/6279/218 6274/6280/218 6275/6277/218 6276/6278/218 +# s 2 +# f 6277/6281/222 6278/6282/222 6274/6280/222 6273/6279/222 +# s 1 +# f 6279/6283/223 6280/6284/223 6278/6282/223 6277/6281/223 +# s 2 +# f 6276/6278/221 6275/6277/221 6280/6284/221 6279/6283/221 +# s 4 +# f 6281/6287/212 6282/6288/212 6283/6285/212 6284/6286/212 +# s 8 +# f 6285/6289/213 6286/6290/213 6282/6288/213 6281/6287/213 +# s 4 +# f 6287/6291/214 6288/6292/214 6286/6290/214 6285/6289/214 +# s 8 +# f 6284/6286/215 6283/6285/215 6288/6292/215 6287/6291/215 +# s 4 +# f 6289/6295/212 6290/6296/212 6291/6293/212 6292/6294/212 +# s 8 +# f 6293/6297/213 6294/6298/213 6290/6296/213 6289/6295/213 +# s 4 +# f 6295/6299/214 6296/6300/214 6294/6298/214 6293/6297/214 +# s 8 +# f 6292/6294/215 6291/6293/215 6296/6300/215 6295/6299/215 +# s 1 +# f 6297/6303/218 6298/6304/218 6299/6301/218 6300/6302/218 +# s 2 +# f 6301/6305/219 6302/6306/219 6298/6304/219 6297/6303/219 +# s 1 +# f 6303/6307/220 6304/6308/220 6302/6306/220 6301/6305/220 +# s 2 +# f 6300/6302/221 6299/6301/221 6304/6308/221 6303/6307/221 +# s 4 +# f 6305/6311/212 6306/6312/212 6307/6309/212 6308/6310/212 +# s 8 +# f 6309/6313/224 6310/6314/216 6306/6312/216 6305/6311/224 +# s 4 +# f 6311/6315/225 6312/6316/214 6310/6314/214 6309/6313/225 +# s 8 +# f 6308/6310/215 6307/6309/217 6312/6316/215 6311/6315/215 +# s 4 +# f 6313/6319/212 6314/6320/212 6315/6317/212 6316/6318/212 +# s 8 +# f 6317/6321/224 6318/6322/216 6314/6320/216 6313/6319/224 +# s 4 +# f 6319/6323/225 6320/6324/214 6318/6322/214 6317/6321/225 +# s 8 +# f 6316/6318/215 6315/6317/215 6320/6324/215 6319/6323/215 +# s 1 +# f 6321/6327/218 6322/6328/218 6323/6325/218 6324/6326/218 +# s 2 +# f 6325/6329/219 6326/6330/219 6322/6328/219 6321/6327/219 +# s 1 +# f 6327/6331/220 6328/6332/220 6326/6330/220 6325/6329/220 +# s 2 +# f 6324/6326/221 6323/6325/221 6328/6332/221 6327/6331/221 +# s 1 +# f 6329/6335/208 6330/6336/208 6331/6333/208 6332/6334/208 +# s 2 +# f 6333/6337/209 6334/6338/209 6330/6336/209 6329/6335/209 +# s 1 +# f 6335/6339/210 6336/6340/210 6334/6338/210 6333/6337/210 +# s 2 +# f 6332/6334/211 6331/6333/211 6336/6340/211 6335/6339/211 +# s 1 +# f 6337/6343/208 6338/6344/208 6339/6341/208 6340/6342/208 +# s 2 +# f 6341/6345/209 6342/6346/209 6338/6344/209 6337/6343/209 +# s 1 +# f 6343/6347/210 6344/6348/210 6342/6346/210 6341/6345/210 +# s 2 +# f 6340/6342/211 6339/6341/211 6344/6348/211 6343/6347/211 +# s 1 +# f 6345/6351/218 6346/6352/218 6347/6349/218 6348/6350/218 +# s 2 +# f 6349/6353/219 6350/6354/219 6346/6352/219 6345/6351/219 +# s 1 +# f 6351/6355/220 6352/6356/220 6350/6354/220 6349/6353/220 +# s 2 +# f 6348/6350/221 6347/6349/221 6352/6356/221 6351/6355/221 +# s 1 +# f 6353/6359/218 6354/6360/218 6355/6357/218 6356/6358/218 +# s 2 +# f 6357/6361/219 6358/6362/219 6354/6360/219 6353/6359/219 +# s 1 +# f 6359/6363/220 6360/6364/220 6358/6362/220 6357/6361/220 +# s 2 +# f 6356/6358/221 6355/6357/221 6360/6364/221 6359/6363/221 +# s 1 +# f 6361/6367/218 6362/6368/218 6363/6365/218 6364/6366/218 +# s 2 +# f 6365/6369/219 6366/6370/219 6362/6368/219 6361/6367/219 +# s 1 +# f 6367/6371/220 6368/6372/220 6366/6370/220 6365/6369/220 +# s 2 +# f 6364/6366/221 6363/6365/221 6368/6372/221 6367/6371/221 +# s 1 +# f 6369/6375/218 6370/6376/218 6371/6373/218 6372/6374/218 +# s 2 +# f 6373/6377/219 6374/6378/219 6370/6376/219 6369/6375/219 +# s 1 +# f 6375/6379/220 6376/6380/220 6374/6378/220 6373/6377/220 +# s 2 +# f 6372/6374/221 6371/6373/221 6376/6380/221 6375/6379/221 +# s 1 +# f 6377/6383/218 6378/6384/218 6379/6381/218 6380/6382/218 +# s 2 +# f 6381/6385/219 6382/6386/219 6378/6384/219 6377/6383/219 +# s 1 +# f 6383/6387/220 6384/6388/220 6382/6386/220 6381/6385/220 +# s 2 +# f 6380/6382/221 6379/6381/221 6384/6388/221 6383/6387/221 +# s 1 +# f 6385/6391/218 6386/6392/218 6387/6389/218 6388/6390/218 +# s 2 +# f 6389/6393/219 6390/6394/219 6386/6392/219 6385/6391/219 +# s 1 +# f 6391/6395/220 6392/6396/220 6390/6394/220 6389/6393/220 +# s 2 +# f 6388/6390/221 6387/6389/221 6392/6396/221 6391/6395/221 +# s 1 +# f 6393/6399/218 6394/6400/218 6395/6397/218 6396/6398/218 +# s 2 +# f 6397/6401/219 6398/6402/219 6394/6400/219 6393/6399/219 +# s 1 +# f 6399/6403/220 6400/6404/220 6398/6402/220 6397/6401/220 +# s 2 +# f 6396/6398/221 6395/6397/221 6400/6404/221 6399/6403/221 +# s 1 +# f 6401/6407/218 6402/6408/218 6403/6405/218 6404/6406/218 +# s 2 +# f 6405/6409/219 6406/6410/219 6402/6408/219 6401/6407/219 +# s 1 +# f 6407/6411/220 6408/6412/220 6406/6410/220 6405/6409/220 +# s 2 +# f 6404/6406/221 6403/6405/221 6408/6412/221 6407/6411/221 +# s 1 +# f 6409/6415/218 6410/6416/218 6411/6413/218 6412/6414/218 +# s 2 +# f 6413/6417/219 6414/6418/219 6410/6416/219 6409/6415/219 +# s 1 +# f 6415/6419/220 6416/6420/220 6414/6418/220 6413/6417/220 +# s 2 +# f 6412/6414/221 6411/6413/221 6416/6420/221 6415/6419/221 +# s 1 +# f 6417/6423/218 6418/6424/218 6419/6421/218 6420/6422/218 +# s 2 +# f 6421/6425/219 6422/6426/219 6418/6424/219 6417/6423/219 +# s 1 +# f 6423/6427/220 6424/6428/220 6422/6426/220 6421/6425/220 +# s 2 +# f 6420/6422/221 6419/6421/221 6424/6428/221 6423/6427/221 +# s 1 +# f 6425/6431/218 6426/6432/218 6427/6429/218 6428/6430/218 +# s 2 +# f 6429/6433/219 6430/6434/219 6426/6432/219 6425/6431/219 +# s 1 +# f 6431/6435/220 6432/6436/220 6430/6434/220 6429/6433/220 +# s 2 +# f 6428/6430/221 6427/6429/221 6432/6436/221 6431/6435/221 +# s 1 +# f 6433/6439/218 6434/6440/218 6435/6437/218 6436/6438/218 +# s 2 +# f 6437/6441/219 6438/6442/219 6434/6440/219 6433/6439/219 +# s 1 +# f 6439/6443/220 6440/6444/220 6438/6442/220 6437/6441/220 +# s 2 +# f 6436/6438/221 6435/6437/221 6440/6444/221 6439/6443/221 +# s 1 +# f 6441/6447/218 6442/6448/218 6443/6445/218 6444/6446/218 +# s 2 +# f 6445/6449/219 6446/6450/219 6442/6448/219 6441/6447/219 +# s 1 +# f 6447/6451/220 6448/6452/220 6446/6450/220 6445/6449/220 +# s 2 +# f 6444/6446/221 6443/6445/221 6448/6452/221 6447/6451/221 +# s 1 +# f 6449/6455/218 6450/6456/218 6451/6453/218 6452/6454/218 +# s 2 +# f 6453/6457/219 6454/6458/219 6450/6456/219 6449/6455/219 +# s 1 +# f 6455/6459/220 6456/6460/220 6454/6458/220 6453/6457/220 +# s 2 +# f 6452/6454/221 6451/6453/221 6456/6460/221 6455/6459/221 +# s 1 +# f 6457/6463/218 6458/6464/218 6459/6461/218 6460/6462/218 +# s 2 +# f 6461/6465/219 6462/6466/219 6458/6464/219 6457/6463/219 +# s 1 +# f 6463/6467/220 6464/6468/220 6462/6466/220 6461/6465/220 +# s 2 +# f 6460/6462/221 6459/6461/221 6464/6468/221 6463/6467/221 +# s 1 +# f 6465/6471/218 6466/6472/218 6467/6469/218 6468/6470/218 +# s 2 +# f 6469/6473/219 6470/6474/219 6466/6472/219 6465/6471/219 +# s 1 +# f 6471/6475/220 6472/6476/220 6470/6474/220 6469/6473/220 +# s 2 +# f 6468/6470/221 6467/6469/221 6472/6476/221 6471/6475/221 +# s 1 +# f 6473/6479/218 6474/6480/218 6475/6477/218 6476/6478/218 +# s 2 +# f 6477/6481/219 6478/6482/219 6474/6480/219 6473/6479/219 +# s 1 +# f 6479/6483/220 6480/6484/220 6478/6482/220 6477/6481/220 +# s 2 +# f 6476/6478/221 6475/6477/221 6480/6484/221 6479/6483/221 +# s 1 +# f 6481/6487/218 6482/6488/218 6483/6485/218 6484/6486/218 +# s 2 +# f 6485/6489/219 6486/6490/219 6482/6488/219 6481/6487/219 +# s 1 +# f 6487/6491/220 6488/6492/220 6486/6490/220 6485/6489/220 +# s 2 +# f 6484/6486/221 6483/6485/221 6488/6492/221 6487/6491/221 +# s 1 +# f 6489/6495/218 6490/6496/218 6491/6493/218 6492/6494/218 +# s 2 +# f 6493/6497/219 6494/6498/219 6490/6496/219 6489/6495/219 +# s 1 +# f 6495/6499/220 6496/6500/220 6494/6498/220 6493/6497/220 +# s 2 +# f 6492/6494/221 6491/6493/221 6496/6500/221 6495/6499/221 +# s 1 +# f 6497/6503/218 6498/6504/218 6499/6501/218 6500/6502/218 +# s 2 +# f 6501/6505/219 6502/6506/219 6498/6504/219 6497/6503/219 +# s 1 +# f 6503/6507/220 6504/6508/220 6502/6506/220 6501/6505/220 +# s 2 +# f 6500/6502/221 6499/6501/221 6504/6508/221 6503/6507/221 +# s 1 +# f 6505/6511/218 6506/6512/218 6507/6509/218 6508/6510/218 +# s 2 +# f 6509/6513/219 6510/6514/219 6506/6512/219 6505/6511/219 +# s 1 +# f 6511/6515/220 6512/6516/220 6510/6514/220 6509/6513/220 +# s 2 +# f 6508/6510/221 6507/6509/221 6512/6516/221 6511/6515/221 +# s 1 +# f 6513/6519/218 6514/6520/218 6515/6517/218 6516/6518/218 +# s 2 +# f 6517/6521/219 6518/6522/219 6514/6520/219 6513/6519/219 +# s 1 +# f 6519/6523/220 6520/6524/220 6518/6522/220 6517/6521/220 +# s 2 +# f 6516/6518/221 6515/6517/221 6520/6524/221 6519/6523/221 +# 296 polygons + +# +# object Door_Left +# + +v -0.2370 -3.6387 2.5709 +v -1.2165 -3.6387 2.5709 +v -1.2165 -3.6387 2.3198 +v -0.2370 -3.6387 2.3198 +v -0.2370 -3.5712 1.1048 +v -1.2165 -3.5712 1.1048 +v -1.2165 -3.5712 1.0053 +v -0.2370 -3.5712 1.0053 +v -0.2370 -3.5712 1.7643 +v -1.2165 -3.5712 1.7643 +v -1.2165 -3.5712 1.6666 +v -0.2370 -3.5712 1.6666 +v -0.2370 -3.6387 1.6295 +v -1.2165 -3.6387 1.6295 +v -1.2165 -3.6387 1.5336 +v -0.2370 -3.6387 1.5336 +v -0.2370 -3.6387 0.4529 +v -1.2165 -3.6387 0.4529 +v -1.2165 -3.6387 0.2061 +v -0.2370 -3.6387 0.2061 +v -0.2370 -3.5712 0.6102 +v -1.2165 -3.5712 0.6102 +v -1.2165 -3.5712 0.5141 +v -0.2370 -3.5712 0.5141 +v -0.2370 -3.6387 0.9385 +v -1.2165 -3.6387 0.9385 +v -1.2165 -3.6387 0.6792 +v -0.2370 -3.6387 0.6792 +v -0.2370 -3.6387 1.2410 +v -1.2165 -3.6387 1.2410 +v -1.2165 -3.6387 1.1430 +v -0.2370 -3.6387 1.1430 +v -0.2370 -3.5712 1.4923 +v -1.2165 -3.5712 1.4923 +v -1.2165 -3.5712 1.2794 +v -0.2370 -3.5712 1.2794 +v -0.2370 -3.6387 2.0884 +v -1.2165 -3.6387 2.0884 +v -1.2165 -3.6387 1.8317 +v -0.2370 -3.6387 1.8317 +v -0.2370 -3.5712 2.2612 +v -1.2165 -3.5712 2.2612 +v -1.2165 -3.5712 2.1574 +v -0.2370 -3.5712 2.1574 +v -1.2165 -3.6369 2.3207 +v -1.2165 -3.6367 2.5709 +v -0.2370 -3.6367 2.5709 +v -0.2370 -3.6369 2.3207 +v -1.2165 -3.5693 1.0046 +v -1.2165 -3.5694 1.1058 +v -0.2370 -3.5694 1.1058 +v -0.2370 -3.5693 1.0046 +v -1.2165 -3.5694 1.6656 +v -1.2165 -3.5693 1.7651 +v -0.2370 -3.5693 1.7651 +v -0.2370 -3.5694 1.6656 +v -1.2165 -3.6370 1.5346 +v -1.2165 -3.6370 1.6285 +v -0.2370 -3.6370 1.6285 +v -0.2370 -3.6370 1.5346 +v -1.2165 -3.6367 0.2061 +v -1.2165 -3.6369 0.4521 +v -0.2370 -3.6369 0.4521 +v -0.2370 -3.6367 0.2061 +v -1.2165 -3.5693 0.5133 +v -1.2165 -3.5693 0.6109 +v -0.2370 -3.5693 0.6109 +v -0.2370 -3.5693 0.5133 +v -1.2165 -3.6369 0.6799 +v -1.2165 -3.6369 0.9377 +v -0.2370 -3.6369 0.9377 +v -0.2370 -3.6369 0.6799 +v -1.2165 -3.6370 1.1440 +v -1.2165 -3.6370 1.2400 +v -0.2370 -3.6370 1.2400 +v -0.2370 -3.6370 1.1440 +v -1.2165 -3.5694 1.2784 +v -1.2165 -3.5694 1.4932 +v -0.2370 -3.5694 1.4932 +v -0.2370 -3.5694 1.2784 +v -1.2165 -3.6369 1.8325 +v -1.2165 -3.6369 2.0876 +v -0.2370 -3.6369 2.0876 +v -0.2370 -3.6369 1.8325 +v -1.2165 -3.5693 2.1566 +v -1.2165 -3.5693 2.2620 +v -0.2370 -3.5693 2.2620 +v -0.2370 -3.5693 2.1566 +v -1.3265 -3.6434 1.6272 +v -1.3344 -3.6243 1.6272 +v -1.3344 -3.6243 1.7236 +v -1.3265 -3.6434 1.7236 +v -1.3535 -3.6164 1.6272 +v -1.3535 -3.6164 1.7236 +v -1.3725 -3.6243 1.6272 +v -1.3725 -3.6243 1.7236 +v -1.3804 -3.6434 1.6272 +v -1.3804 -3.6434 1.7236 +v -1.3746 -3.6636 1.6272 +v -1.3746 -3.6636 1.7236 +v -1.3621 -3.6714 1.6272 +v -1.3621 -3.6714 1.7236 +v -1.3477 -3.6722 1.6272 +v -1.3477 -3.6722 1.7236 +v -1.2286 -3.6582 1.6272 +v -1.2286 -3.6582 1.7236 +v -1.2399 -3.6623 1.7236 +v -1.2399 -3.6623 1.6272 +v -1.3245 -3.6663 1.7236 +v -1.3245 -3.6663 1.6272 +v -1.3265 -3.6934 1.7236 +v -1.3265 -3.6934 1.6272 +v -1.2826 -3.6589 1.7236 +v -1.2826 -3.6589 1.6272 +v -1.2841 -3.6791 1.7236 +v -1.2841 -3.6791 1.6272 +v -1.2751 -3.6497 1.7236 +v -1.2751 -3.6497 1.6272 +v -1.2754 -3.6638 1.7236 +v -1.2754 -3.6638 1.6272 +v -1.2243 -3.6490 1.7236 +v -1.2243 -3.6490 1.6272 +v -1.3265 -3.6434 2.1936 +v -1.3344 -3.6243 2.1936 +v -1.3344 -3.6243 2.2900 +v -1.3265 -3.6434 2.2900 +v -1.3535 -3.6164 2.1936 +v -1.3535 -3.6164 2.2900 +v -1.3725 -3.6243 2.1936 +v -1.3725 -3.6243 2.2900 +v -1.3804 -3.6434 2.1936 +v -1.3804 -3.6434 2.2900 +v -1.3746 -3.6636 2.1936 +v -1.3746 -3.6636 2.2900 +v -1.3621 -3.6714 2.1936 +v -1.3621 -3.6714 2.2900 +v -1.3477 -3.6722 2.1936 +v -1.3477 -3.6722 2.2900 +v -1.2286 -3.6582 2.1936 +v -1.2286 -3.6582 2.2900 +v -1.2399 -3.6623 2.2900 +v -1.2399 -3.6623 2.1936 +v -1.3245 -3.6663 2.2900 +v -1.3245 -3.6663 2.1936 +v -1.3265 -3.6934 2.2900 +v -1.3265 -3.6934 2.1936 +v -1.2826 -3.6589 2.2900 +v -1.2826 -3.6589 2.1936 +v -1.2841 -3.6791 2.2900 +v -1.2841 -3.6791 2.1936 +v -1.2751 -3.6497 2.2900 +v -1.2751 -3.6497 2.1936 +v -1.2754 -3.6638 2.2900 +v -1.2754 -3.6638 2.1936 +v -1.2243 -3.6490 2.2900 +v -1.2243 -3.6490 2.1936 +v -1.3265 -3.6434 1.0602 +v -1.3344 -3.6243 1.0602 +v -1.3344 -3.6243 1.1566 +v -1.3265 -3.6434 1.1566 +v -1.3535 -3.6164 1.0602 +v -1.3535 -3.6164 1.1566 +v -1.3725 -3.6243 1.0602 +v -1.3725 -3.6243 1.1566 +v -1.3804 -3.6434 1.0602 +v -1.3804 -3.6434 1.1566 +v -1.3746 -3.6636 1.0602 +v -1.3746 -3.6636 1.1566 +v -1.3621 -3.6714 1.0602 +v -1.3621 -3.6714 1.1566 +v -1.3477 -3.6722 1.0602 +v -1.3477 -3.6722 1.1566 +v -1.2286 -3.6582 1.0602 +v -1.2286 -3.6582 1.1566 +v -1.2399 -3.6623 1.1566 +v -1.2399 -3.6623 1.0602 +v -1.3245 -3.6663 1.1566 +v -1.3245 -3.6663 1.0602 +v -1.3265 -3.6934 1.1566 +v -1.3265 -3.6934 1.0602 +v -1.2826 -3.6589 1.1566 +v -1.2826 -3.6589 1.0602 +v -1.2841 -3.6791 1.1566 +v -1.2841 -3.6791 1.0602 +v -1.2751 -3.6497 1.1566 +v -1.2751 -3.6497 1.0602 +v -1.2754 -3.6638 1.1566 +v -1.2754 -3.6638 1.0602 +v -1.2243 -3.6490 1.1566 +v -1.2243 -3.6490 1.0602 +v -1.3265 -3.6434 0.4938 +v -1.3344 -3.6243 0.4938 +v -1.3344 -3.6243 0.5903 +v -1.3265 -3.6434 0.5903 +v -1.3535 -3.6164 0.4938 +v -1.3535 -3.6164 0.5903 +v -1.3725 -3.6243 0.4938 +v -1.3725 -3.6243 0.5903 +v -1.3804 -3.6434 0.4938 +v -1.3804 -3.6434 0.5903 +v -1.3746 -3.6636 0.4938 +v -1.3746 -3.6636 0.5903 +v -1.3621 -3.6714 0.4938 +v -1.3621 -3.6714 0.5903 +v -1.3477 -3.6722 0.4938 +v -1.3477 -3.6722 0.5903 +v -1.2286 -3.6582 0.4938 +v -1.2286 -3.6582 0.5903 +v -1.2399 -3.6623 0.5903 +v -1.2399 -3.6623 0.4938 +v -1.3245 -3.6663 0.5903 +v -1.3245 -3.6663 0.4938 +v -1.3265 -3.6934 0.5903 +v -1.3265 -3.6934 0.4938 +v -1.2826 -3.6589 0.5903 +v -1.2826 -3.6589 0.4938 +v -1.2841 -3.6791 0.5903 +v -1.2841 -3.6791 0.4938 +v -1.2751 -3.6497 0.5903 +v -1.2751 -3.6497 0.4938 +v -1.2754 -3.6638 0.5903 +v -1.2754 -3.6638 0.4938 +v -1.2243 -3.6490 0.5903 +v -1.2243 -3.6490 0.4938 +v -1.2917 -3.6513 0.2231 +v -1.2917 -3.5549 0.2231 +v -1.1991 -3.5549 0.2231 +v -1.1991 -3.6513 0.2231 +v -1.2917 -3.6513 2.5520 +v -1.1991 -3.6513 2.5520 +v -1.1991 -3.5549 2.5520 +v -1.2917 -3.5549 2.5520 +v -0.2472 -3.6513 0.2231 +v -0.2472 -3.5549 0.2231 +v -0.1480 -3.5549 0.2231 +v -0.1480 -3.6513 0.2231 +v -0.2472 -3.6513 2.5520 +v -0.1480 -3.6513 2.5520 +v -0.1480 -3.5549 2.5520 +v -0.2472 -3.5549 2.5520 +v -1.3269 -3.6578 0.1820 +v -1.3269 -3.4682 0.1820 +v -1.2899 -3.4682 0.1820 +v -1.2899 -3.6578 0.1820 +v -1.3269 -3.6578 2.5888 +v -1.2899 -3.6578 2.5888 +v -1.2899 -3.4682 2.5888 +v -1.3269 -3.4682 2.5888 +v -1.2899 -3.6578 0.2257 +v -1.2899 -3.6578 2.5478 +v -0.1478 -3.4682 0.1820 +v -0.1478 -3.4682 0.2257 +v -0.1478 -3.6578 0.2257 +v -0.1478 -3.6578 0.1820 +v -1.2899 -3.4682 2.5478 +v -1.2899 -3.4682 0.2257 +v -0.1486 -3.4682 2.5888 +v -0.1486 -3.6578 2.5888 +v -0.1486 -3.6578 2.5478 +v -0.1486 -3.4682 2.5478 +v -0.7793 -3.6763 0.1624 +v -0.7793 -3.6763 2.5946 +v -0.7738 -3.6896 2.5946 +v -0.7738 -3.6896 0.1624 +v -0.7925 -3.6708 0.1624 +v -0.7925 -3.6708 2.5946 +v -0.8058 -3.6763 0.1624 +v -0.8058 -3.6763 2.5946 +v -0.8112 -3.6896 0.1624 +v -0.8112 -3.6896 2.5946 +v -0.8058 -3.7028 0.1624 +v -0.8058 -3.7028 2.5946 +v -0.7925 -3.7083 0.1624 +v -0.7925 -3.7083 2.5946 +v -0.7793 -3.7028 0.1624 +v -0.7793 -3.7028 2.5946 +v -0.7925 -3.6675 0.0876 +v -0.7769 -3.6740 0.0876 +v -0.7705 -3.6896 0.0876 +v -0.7769 -3.7051 0.0876 +v -0.7925 -3.7116 0.0876 +v -0.8081 -3.7051 0.0876 +v -0.8146 -3.6896 0.0876 +v -0.8081 -3.6740 0.0876 +v -0.8100 -3.7070 2.6725 +v -0.7925 -3.7143 2.6725 +v -0.7750 -3.7070 2.6725 +v -0.7678 -3.6896 2.6725 +v -0.7750 -3.6721 2.6725 +v -0.7925 -3.6648 2.6725 +v -0.8100 -3.6721 2.6725 +v -0.8173 -3.6896 2.6725 +v -0.7750 -3.6721 2.6031 +v -0.7678 -3.6896 2.6031 +v -0.7925 -3.6648 2.6031 +v -0.8100 -3.6721 2.6031 +v -0.8173 -3.6896 2.6031 +v -0.8100 -3.7070 2.6031 +v -0.7925 -3.7143 2.6031 +v -0.7750 -3.7070 2.6031 +v -0.7705 -3.6896 0.1571 +v -0.7769 -3.6740 0.1571 +v -0.7769 -3.7051 0.1571 +v -0.7925 -3.7116 0.1571 +v -0.8081 -3.7051 0.1571 +v -0.8146 -3.6896 0.1571 +v -0.8081 -3.6740 0.1571 +v -0.7925 -3.6675 0.1571 +v -0.7489 -3.6534 1.9075 +v -0.7679 -3.6776 1.9075 +v -0.8171 -3.6776 1.9075 +v -0.8361 -3.6534 1.9075 +v -0.8361 -3.6379 1.9075 +v -0.7489 -3.6379 1.9075 +v -0.8171 -3.6776 1.9732 +v -0.7679 -3.6776 1.9732 +v -0.7489 -3.6534 1.9732 +v -0.7489 -3.6379 1.9732 +v -0.8361 -3.6379 1.9732 +v -0.8361 -3.6534 1.9732 +v -0.7751 -3.7019 1.9075 +v -0.7751 -3.7019 1.9732 +v -0.7925 -3.7103 1.9732 +v -0.7925 -3.7103 1.9075 +v -0.8100 -3.7019 1.9075 +v -0.8100 -3.7019 1.9732 +v -0.4531 -3.6534 1.9075 +v -0.4721 -3.6776 1.9075 +v -0.5213 -3.6776 1.9075 +v -0.5403 -3.6534 1.9075 +v -0.5403 -3.6379 1.9075 +v -0.4531 -3.6379 1.9075 +v -0.5213 -3.6776 1.9732 +v -0.4721 -3.6776 1.9732 +v -0.4531 -3.6534 1.9732 +v -0.4531 -3.6379 1.9732 +v -0.5403 -3.6379 1.9732 +v -0.5403 -3.6534 1.9732 +v -0.4793 -3.7019 1.9075 +v -0.4793 -3.7019 1.9732 +v -0.4967 -3.7103 1.9732 +v -0.4967 -3.7103 1.9075 +v -0.5142 -3.7019 1.9075 +v -0.5142 -3.7019 1.9732 +v -0.4531 -3.6534 2.3917 +v -0.4721 -3.6776 2.3917 +v -0.5213 -3.6776 2.3917 +v -0.5403 -3.6534 2.3917 +v -0.5403 -3.6379 2.3917 +v -0.4531 -3.6379 2.3917 +v -0.5213 -3.6776 2.5261 +v -0.4721 -3.6776 2.5261 +v -0.4531 -3.6534 2.5261 +v -0.4531 -3.6379 2.5261 +v -0.5403 -3.6379 2.5261 +v -0.5403 -3.6534 2.5261 +v -0.4793 -3.7019 2.3917 +v -0.4793 -3.7019 2.5261 +v -0.4967 -3.7103 2.5261 +v -0.4967 -3.7103 2.3917 +v -0.5142 -3.7019 2.3917 +v -0.5142 -3.7019 2.5261 +v -0.7489 -3.6534 2.3917 +v -0.7679 -3.6776 2.3917 +v -0.8171 -3.6776 2.3917 +v -0.8361 -3.6534 2.3917 +v -0.8361 -3.6379 2.3917 +v -0.7489 -3.6379 2.3917 +v -0.8171 -3.6776 2.5261 +v -0.7679 -3.6776 2.5261 +v -0.7489 -3.6534 2.5261 +v -0.7489 -3.6379 2.5261 +v -0.8361 -3.6379 2.5261 +v -0.8361 -3.6534 2.5261 +v -0.7751 -3.7019 2.3917 +v -0.7751 -3.7019 2.5261 +v -0.7925 -3.7103 2.5261 +v -0.7925 -3.7103 2.3917 +v -0.8100 -3.7019 2.3917 +v -0.8100 -3.7019 2.5261 +v -0.7489 -3.6534 0.7872 +v -0.7679 -3.6776 0.7872 +v -0.8171 -3.6776 0.7872 +v -0.8361 -3.6534 0.7872 +v -0.8361 -3.6379 0.7872 +v -0.7489 -3.6379 0.7872 +v -0.8171 -3.6776 0.8529 +v -0.7679 -3.6776 0.8529 +v -0.7489 -3.6534 0.8529 +v -0.7489 -3.6379 0.8529 +v -0.8361 -3.6379 0.8529 +v -0.8361 -3.6534 0.8529 +v -0.7751 -3.7019 0.7872 +v -0.7751 -3.7019 0.8529 +v -0.7925 -3.7103 0.8529 +v -0.7925 -3.7103 0.7872 +v -0.8100 -3.7019 0.7872 +v -0.8100 -3.7019 0.8529 +v -0.7489 -3.6534 0.2305 +v -0.7679 -3.6776 0.2305 +v -0.8171 -3.6776 0.2305 +v -0.8361 -3.6534 0.2305 +v -0.8361 -3.6379 0.2305 +v -0.7489 -3.6379 0.2305 +v -0.8171 -3.6776 0.3650 +v -0.7679 -3.6776 0.3650 +v -0.7489 -3.6534 0.3650 +v -0.7489 -3.6379 0.3650 +v -0.8361 -3.6379 0.3650 +v -0.8361 -3.6534 0.3650 +v -0.7751 -3.7019 0.2305 +v -0.7751 -3.7019 0.3650 +v -0.7925 -3.7103 0.3650 +v -0.7925 -3.7103 0.2305 +v -0.8100 -3.7019 0.2305 +v -0.8100 -3.7019 0.3650 +v -0.4531 -3.6534 0.2305 +v -0.4721 -3.6776 0.2305 +v -0.5213 -3.6776 0.2305 +v -0.5403 -3.6534 0.2305 +v -0.5403 -3.6379 0.2305 +v -0.4531 -3.6379 0.2305 +v -0.5213 -3.6776 0.3650 +v -0.4721 -3.6776 0.3650 +v -0.4531 -3.6534 0.3650 +v -0.4531 -3.6379 0.3650 +v -0.5403 -3.6379 0.3650 +v -0.5403 -3.6534 0.3650 +v -0.4793 -3.7019 0.2305 +v -0.4793 -3.7019 0.3650 +v -0.4967 -3.7103 0.3650 +v -0.4967 -3.7103 0.2305 +v -0.5142 -3.7019 0.2305 +v -0.5142 -3.7019 0.3650 +v -0.4835 -3.6763 0.1624 +v -0.4835 -3.6763 2.5946 +v -0.4780 -3.6896 2.5946 +v -0.4780 -3.6896 0.1624 +v -0.4967 -3.6708 0.1624 +v -0.4967 -3.6708 2.5946 +v -0.5100 -3.6763 0.1624 +v -0.5100 -3.6763 2.5946 +v -0.5155 -3.6896 0.1624 +v -0.5155 -3.6896 2.5946 +v -0.5100 -3.7028 0.1624 +v -0.5100 -3.7028 2.5946 +v -0.4967 -3.7083 0.1624 +v -0.4967 -3.7083 2.5946 +v -0.4835 -3.7028 0.1624 +v -0.4835 -3.7028 2.5946 +v -0.4967 -3.6675 0.0876 +v -0.4812 -3.6740 0.0876 +v -0.4747 -3.6896 0.0876 +v -0.4812 -3.7051 0.0876 +v -0.4967 -3.7116 0.0876 +v -0.5123 -3.7051 0.0876 +v -0.5188 -3.6896 0.0876 +v -0.5123 -3.6740 0.0876 +v -0.5142 -3.7070 2.6725 +v -0.4967 -3.7143 2.6725 +v -0.4793 -3.7070 2.6725 +v -0.4720 -3.6896 2.6725 +v -0.4793 -3.6721 2.6725 +v -0.4967 -3.6648 2.6725 +v -0.5142 -3.6721 2.6725 +v -0.5215 -3.6896 2.6725 +v -0.4793 -3.6721 2.6031 +v -0.4720 -3.6896 2.6031 +v -0.4967 -3.6648 2.6031 +v -0.5142 -3.6721 2.6031 +v -0.5215 -3.6896 2.6031 +v -0.5142 -3.7070 2.6031 +v -0.4967 -3.7143 2.6031 +v -0.4793 -3.7070 2.6031 +v -0.4747 -3.6896 0.1571 +v -0.4812 -3.6740 0.1571 +v -0.4812 -3.7051 0.1571 +v -0.4967 -3.7116 0.1571 +v -0.5123 -3.7051 0.1571 +v -0.5188 -3.6896 0.1571 +v -0.5123 -3.6740 0.1571 +v -0.4967 -3.6675 0.1571 +v -0.4531 -3.6534 0.7872 +v -0.4721 -3.6776 0.7872 +v -0.5213 -3.6776 0.7872 +v -0.5403 -3.6534 0.7872 +v -0.5403 -3.6379 0.7872 +v -0.4531 -3.6379 0.7872 +v -0.5213 -3.6776 0.8529 +v -0.4721 -3.6776 0.8529 +v -0.4531 -3.6534 0.8529 +v -0.4531 -3.6379 0.8529 +v -0.5403 -3.6379 0.8529 +v -0.5403 -3.6534 0.8529 +v -0.4793 -3.7019 0.7872 +v -0.4793 -3.7019 0.8529 +v -0.4967 -3.7103 0.8529 +v -0.4967 -3.7103 0.7872 +v -0.5142 -3.7019 0.7872 +v -0.5142 -3.7019 0.8529 +v -0.7625 -3.6871 1.5502 +v -0.7625 -3.6916 1.5502 +v -0.7823 -3.6944 1.5417 +v -0.7823 -3.6847 1.5417 +v -0.7325 -3.6802 1.5521 +v -0.7437 -3.6915 1.5502 +v -0.7437 -3.6870 1.5502 +v -0.7325 -3.6757 1.5521 +v -0.7325 -3.6757 1.5808 +v -0.7437 -3.6870 1.5826 +v -0.7437 -3.6915 1.5826 +v -0.7325 -3.6802 1.5808 +v -0.5956 -3.6664 1.5765 +v -0.5408 -3.6709 1.5737 +v -0.5382 -3.6710 1.5701 +v -0.5375 -3.6710 1.5664 +v -0.5382 -3.6710 1.5627 +v -0.5408 -3.6709 1.5592 +v -0.5956 -3.6664 1.5563 +v -0.6034 -3.6609 1.5765 +v -0.6034 -3.6654 1.5765 +v -0.5956 -3.6708 1.5765 +v -0.6808 -3.6654 1.5563 +v -0.6808 -3.6654 1.5626 +v -0.7325 -3.6802 1.5611 +v -0.7437 -3.6915 1.5605 +v -0.7437 -3.6915 1.5723 +v -0.7325 -3.6802 1.5717 +v -0.5956 -3.6708 1.5563 +v -0.5408 -3.6754 1.5592 +v -0.5382 -3.6755 1.5627 +v -0.5375 -3.6755 1.5664 +v -0.5382 -3.6755 1.5701 +v -0.5408 -3.6754 1.5737 +v -0.5957 -3.6708 1.5699 +v -0.5957 -3.6708 1.5629 +v -0.6034 -3.6654 1.5703 +v -0.6034 -3.6654 1.5563 +v -0.6034 -3.6654 1.5626 +v -0.6034 -3.6609 1.5563 +v -0.6808 -3.6609 1.5765 +v -0.6808 -3.6654 1.5765 +v -0.6808 -3.6609 1.5563 +v -0.6808 -3.6654 1.5703 +v -0.7293 -3.6886 1.5713 +v -0.6777 -3.6707 1.5699 +v -0.7625 -3.6916 1.5826 +v -0.7823 -3.6944 1.5912 +v -0.6777 -3.6707 1.5629 +v -0.7408 -3.6907 1.5720 +v -0.7408 -3.6907 1.5609 +v -0.7625 -3.6871 1.5826 +v -0.7823 -3.6847 1.5912 +v -0.7293 -3.6886 1.5615 +v -0.6512 -3.6653 1.5486 +v -0.6315 -3.6653 1.5486 +v -0.6315 -3.6728 1.5613 +v -0.6512 -3.6728 1.5613 +v -0.6315 -3.6728 1.5731 +v -0.6315 -3.6653 1.5859 +v -0.6512 -3.6653 1.5859 +v -0.6512 -3.6728 1.5731 +v -0.6512 -3.6439 1.5504 +v -0.6512 -3.6439 1.5840 +v -0.6512 -3.6376 1.5847 +v -0.6512 -3.6376 1.5497 +v -0.6512 -3.6455 1.5590 +v -0.6315 -3.6455 1.5590 +v -0.6315 -3.6455 1.5755 +v -0.6512 -3.6455 1.5755 +v -0.6413 -3.6439 1.5443 +v -0.6413 -3.6439 1.5901 +v -0.6315 -3.6439 1.5504 +v -0.6315 -3.6439 1.5840 +v -0.6413 -3.6376 1.5434 +v -0.6315 -3.6376 1.5847 +v -0.6413 -3.6376 1.5910 +v -0.6315 -3.6376 1.5497 +v -0.7625 -3.6871 1.1792 +v -0.7625 -3.6916 1.1792 +v -0.7823 -3.6944 1.1706 +v -0.7823 -3.6847 1.1706 +v -0.7325 -3.6802 1.1810 +v -0.7437 -3.6915 1.1792 +v -0.7437 -3.6870 1.1792 +v -0.7325 -3.6757 1.1810 +v -0.7325 -3.6757 1.2098 +v -0.7437 -3.6870 1.2116 +v -0.7437 -3.6915 1.2116 +v -0.7325 -3.6802 1.2098 +v -0.5956 -3.6664 1.2055 +v -0.5408 -3.6709 1.2026 +v -0.5382 -3.6710 1.1991 +v -0.5375 -3.6710 1.1954 +v -0.5382 -3.6710 1.1917 +v -0.5408 -3.6709 1.1881 +v -0.5956 -3.6664 1.1853 +v -0.6034 -3.6609 1.2055 +v -0.6034 -3.6654 1.2055 +v -0.5956 -3.6708 1.2055 +v -0.6808 -3.6654 1.1853 +v -0.6808 -3.6654 1.1915 +v -0.7325 -3.6802 1.1901 +v -0.7437 -3.6915 1.1895 +v -0.7437 -3.6915 1.2013 +v -0.7325 -3.6802 1.2007 +v -0.5956 -3.6708 1.1853 +v -0.5408 -3.6754 1.1881 +v -0.5382 -3.6755 1.1917 +v -0.5375 -3.6755 1.1954 +v -0.5382 -3.6755 1.1991 +v -0.5408 -3.6754 1.2026 +v -0.5957 -3.6708 1.1989 +v -0.5957 -3.6708 1.1919 +v -0.6034 -3.6654 1.1993 +v -0.6034 -3.6654 1.1853 +v -0.6034 -3.6654 1.1915 +v -0.6034 -3.6609 1.1853 +v -0.6808 -3.6609 1.2055 +v -0.6808 -3.6654 1.2055 +v -0.6808 -3.6609 1.1853 +v -0.6808 -3.6654 1.1993 +v -0.7293 -3.6886 1.2003 +v -0.6777 -3.6707 1.1989 +v -0.7625 -3.6916 1.2116 +v -0.7823 -3.6944 1.2201 +v -0.6777 -3.6707 1.1919 +v -0.7408 -3.6907 1.2009 +v -0.7408 -3.6907 1.1899 +v -0.7625 -3.6871 1.2116 +v -0.7823 -3.6847 1.2201 +v -0.7293 -3.6886 1.1905 +v -0.6512 -3.6653 1.1775 +v -0.6315 -3.6653 1.1775 +v -0.6315 -3.6728 1.1902 +v -0.6512 -3.6728 1.1902 +v -0.6315 -3.6728 1.2021 +v -0.6315 -3.6653 1.2148 +v -0.6512 -3.6653 1.2148 +v -0.6512 -3.6728 1.2021 +v -0.6512 -3.6439 1.1794 +v -0.6512 -3.6439 1.2130 +v -0.6512 -3.6376 1.2137 +v -0.6512 -3.6376 1.1787 +v -0.6512 -3.6455 1.1879 +v -0.6315 -3.6455 1.1879 +v -0.6315 -3.6455 1.2044 +v -0.6512 -3.6455 1.2044 +v -0.6413 -3.6439 1.1733 +v -0.6413 -3.6439 1.2191 +v -0.6315 -3.6439 1.1794 +v -0.6315 -3.6439 1.2130 +v -0.6413 -3.6376 1.1723 +v -0.6315 -3.6376 1.2137 +v -0.6413 -3.6376 1.2200 +v -0.6315 -3.6376 1.1787 +v -0.4632 -3.6871 1.5502 +v -0.4632 -3.6916 1.5502 +v -0.4830 -3.6944 1.5417 +v -0.4830 -3.6847 1.5417 +v -0.4331 -3.6802 1.5521 +v -0.4444 -3.6915 1.5502 +v -0.4444 -3.6870 1.5502 +v -0.4331 -3.6757 1.5521 +v -0.4331 -3.6757 1.5808 +v -0.4444 -3.6870 1.5826 +v -0.4444 -3.6915 1.5826 +v -0.4331 -3.6802 1.5808 +v -0.2963 -3.6664 1.5765 +v -0.2414 -3.6709 1.5737 +v -0.2388 -3.6710 1.5701 +v -0.2382 -3.6710 1.5664 +v -0.2388 -3.6710 1.5627 +v -0.2414 -3.6709 1.5592 +v -0.2963 -3.6664 1.5563 +v -0.3040 -3.6609 1.5765 +v -0.3040 -3.6654 1.5765 +v -0.2963 -3.6708 1.5765 +v -0.3814 -3.6654 1.5563 +v -0.3814 -3.6654 1.5626 +v -0.4331 -3.6802 1.5611 +v -0.4444 -3.6915 1.5605 +v -0.4444 -3.6915 1.5723 +v -0.4331 -3.6802 1.5717 +v -0.2963 -3.6708 1.5563 +v -0.2414 -3.6754 1.5592 +v -0.2388 -3.6755 1.5627 +v -0.2382 -3.6755 1.5664 +v -0.2388 -3.6755 1.5701 +v -0.2414 -3.6754 1.5737 +v -0.2963 -3.6708 1.5699 +v -0.2963 -3.6708 1.5629 +v -0.3040 -3.6654 1.5703 +v -0.3040 -3.6654 1.5563 +v -0.3040 -3.6654 1.5626 +v -0.3040 -3.6609 1.5563 +v -0.3814 -3.6609 1.5765 +v -0.3814 -3.6654 1.5765 +v -0.3814 -3.6609 1.5563 +v -0.3814 -3.6654 1.5703 +v -0.4300 -3.6886 1.5713 +v -0.3783 -3.6707 1.5699 +v -0.4632 -3.6916 1.5826 +v -0.4830 -3.6944 1.5912 +v -0.3783 -3.6707 1.5629 +v -0.4414 -3.6907 1.5720 +v -0.4414 -3.6907 1.5609 +v -0.4632 -3.6871 1.5826 +v -0.4830 -3.6847 1.5912 +v -0.4300 -3.6886 1.5615 +v -0.3518 -3.6653 1.5486 +v -0.3321 -3.6653 1.5486 +v -0.3321 -3.6728 1.5613 +v -0.3518 -3.6728 1.5613 +v -0.3321 -3.6728 1.5731 +v -0.3321 -3.6653 1.5859 +v -0.3518 -3.6653 1.5859 +v -0.3518 -3.6728 1.5731 +v -0.3518 -3.6439 1.5504 +v -0.3518 -3.6439 1.5840 +v -0.3518 -3.6376 1.5847 +v -0.3518 -3.6376 1.5497 +v -0.3518 -3.6455 1.5590 +v -0.3321 -3.6455 1.5590 +v -0.3321 -3.6455 1.5755 +v -0.3518 -3.6455 1.5755 +v -0.3419 -3.6439 1.5443 +v -0.3419 -3.6439 1.5901 +v -0.3321 -3.6439 1.5504 +v -0.3321 -3.6439 1.5840 +v -0.3419 -3.6376 1.5434 +v -0.3321 -3.6376 1.5847 +v -0.3419 -3.6376 1.5910 +v -0.3321 -3.6376 1.5497 +v -0.4632 -3.6871 1.1792 +v -0.4632 -3.6916 1.1792 +v -0.4830 -3.6944 1.1706 +v -0.4830 -3.6847 1.1706 +v -0.4331 -3.6802 1.1810 +v -0.4444 -3.6915 1.1792 +v -0.4444 -3.6870 1.1792 +v -0.4331 -3.6757 1.1810 +v -0.4331 -3.6757 1.2098 +v -0.4444 -3.6870 1.2116 +v -0.4444 -3.6915 1.2116 +v -0.4331 -3.6802 1.2098 +v -0.2963 -3.6664 1.2055 +v -0.2414 -3.6709 1.2026 +v -0.2388 -3.6710 1.1991 +v -0.2382 -3.6710 1.1954 +v -0.2388 -3.6710 1.1917 +v -0.2414 -3.6709 1.1881 +v -0.2963 -3.6664 1.1853 +v -0.3040 -3.6609 1.2055 +v -0.3040 -3.6654 1.2055 +v -0.2963 -3.6708 1.2055 +v -0.3814 -3.6654 1.1853 +v -0.3814 -3.6654 1.1915 +v -0.4331 -3.6802 1.1901 +v -0.4444 -3.6915 1.1895 +v -0.4444 -3.6915 1.2013 +v -0.4331 -3.6802 1.2007 +v -0.2963 -3.6708 1.1853 +v -0.2414 -3.6754 1.1881 +v -0.2388 -3.6755 1.1917 +v -0.2382 -3.6755 1.1954 +v -0.2388 -3.6755 1.1991 +v -0.2414 -3.6754 1.2026 +v -0.2963 -3.6708 1.1989 +v -0.2963 -3.6708 1.1919 +v -0.3040 -3.6654 1.1993 +v -0.3040 -3.6654 1.1853 +v -0.3040 -3.6654 1.1915 +v -0.3040 -3.6609 1.1853 +v -0.3814 -3.6609 1.2055 +v -0.3814 -3.6654 1.2055 +v -0.3814 -3.6609 1.1853 +v -0.3814 -3.6654 1.1993 +v -0.4300 -3.6886 1.2003 +v -0.3783 -3.6707 1.1989 +v -0.4632 -3.6916 1.2116 +v -0.4830 -3.6944 1.2201 +v -0.3783 -3.6707 1.1919 +v -0.4414 -3.6907 1.2009 +v -0.4414 -3.6907 1.1899 +v -0.4632 -3.6871 1.2116 +v -0.4830 -3.6847 1.2201 +v -0.4300 -3.6886 1.1905 +v -0.3518 -3.6653 1.1775 +v -0.3321 -3.6653 1.1775 +v -0.3321 -3.6728 1.1902 +v -0.3518 -3.6728 1.1902 +v -0.3321 -3.6728 1.2021 +v -0.3321 -3.6653 1.2148 +v -0.3518 -3.6653 1.2148 +v -0.3518 -3.6728 1.2021 +v -0.3518 -3.6439 1.1794 +v -0.3518 -3.6439 1.2130 +v -0.3518 -3.6376 1.2137 +v -0.3518 -3.6376 1.1787 +v -0.3518 -3.6455 1.1879 +v -0.3321 -3.6455 1.1879 +v -0.3321 -3.6455 1.2044 +v -0.3518 -3.6455 1.2044 +v -0.3419 -3.6439 1.1733 +v -0.3419 -3.6439 1.2191 +v -0.3321 -3.6439 1.1794 +v -0.3321 -3.6439 1.2130 +v -0.3419 -3.6376 1.1723 +v -0.3321 -3.6376 1.2137 +v -0.3419 -3.6376 1.2200 +v -0.3321 -3.6376 1.1787 +# 812 vertices + +vn 0.0000 -1.0000 0.0000 +vn 0.0000 -1.0000 -0.0000 +vn -0.0000 -0.7034 0.7108 +vn 0.0000 -0.4923 -0.8704 +vn -0.0000 -0.4813 0.8766 +vn 0.0000 -0.7062 -0.7080 +vn 0.0000 -0.6717 0.7409 +vn 0.0000 -0.7143 -0.6998 +vn 0.0000 -0.4945 0.8692 +vn 0.0000 -0.5216 -0.8532 +vn 0.0000 -0.7145 0.6997 +vn 0.0000 -0.6554 -0.7553 +vn 0.0000 1.0000 -0.0007 +vn -0.0000 1.0000 0.0012 +vn 0.0000 1.0000 -0.0013 +vn -0.0000 1.0000 0.0002 +vn 0.0000 1.0000 0.0007 +vn 0.0000 1.0000 -0.0002 +vn -0.0000 1.0000 0.0000 +vn 0.0000 1.0000 -0.0000 +vn 0.0000 1.0000 -0.0001 +vn 0.0000 1.0000 0.0003 +vn 0.0000 0.7034 -0.7108 +vn -0.0000 0.4923 0.8704 +vn 0.0000 0.4813 -0.8766 +vn 0.0000 0.7062 0.7080 +vn 0.0000 0.6717 -0.7409 +vn -0.0000 0.7143 0.6998 +vn 0.0000 0.4945 -0.8692 +vn -0.0000 0.5216 0.8532 +vn 0.0000 0.7145 -0.6997 +vn 0.0000 0.6554 0.7553 +vn 0.9239 0.3827 0.0000 +vn 0.7071 0.7071 0.0000 +vn 0.0000 1.0000 0.0000 +vn -0.7071 0.7071 0.0000 +vn -0.9985 0.0554 0.0000 +vn -0.7981 -0.6025 0.0000 +vn -0.3010 -0.9536 0.0000 +vn -0.0522 -0.9986 0.0000 +vn 0.6739 -0.7389 0.0000 +vn 0.3448 -0.9387 0.0000 +vn 0.0000 0.0000 -1.0000 +vn 0.0000 0.0000 1.0000 +vn 0.9962 0.0872 0.0000 +vn -0.7081 -0.7062 0.0000 +vn -0.1730 0.9849 0.0000 +vn 0.3184 -0.9480 0.0000 +vn -0.7744 0.6327 0.0000 +vn 0.8709 -0.4915 0.0000 +vn -0.0133 0.9999 0.0000 +vn 0.0406 -0.9992 0.0000 +vn 0.9030 -0.4296 0.0000 +vn 0.6738 -0.7389 0.0000 +vn -0.7081 -0.7061 0.0000 +vn 1.0000 0.0000 0.0000 +vn -1.0000 0.0000 0.0000 +vn 1.0000 -0.0000 0.0000 +vn -1.0000 -0.0000 0.0000 +vn -0.7071 -0.7071 0.0000 +vn 0.7071 -0.7071 0.0000 +vn 0.5779 0.5778 -0.5763 +vn 0.8172 -0.0000 -0.5763 +vn 0.5779 0.5779 -0.5763 +vn -0.0000 0.8172 -0.5763 +vn -0.5779 0.5778 -0.5763 +vn -0.5779 0.5779 -0.5763 +vn -0.8172 -0.0000 -0.5763 +vn -0.5779 -0.5779 -0.5763 +vn 0.0000 -0.8172 -0.5763 +vn 0.5779 -0.5779 -0.5763 +vn 0.8502 -0.0000 0.5264 +vn 0.8502 0.0000 0.5264 +vn 0.6012 0.6012 0.5264 +vn 0.6012 -0.6012 0.5264 +vn -0.0000 -0.8502 0.5264 +vn -0.6012 -0.6012 0.5264 +vn -0.8502 -0.0000 0.5264 +vn -0.6012 0.6012 0.5264 +vn -0.0000 0.8502 0.5264 +vn 0.9239 -0.3827 0.0000 +vn 0.3827 -0.9239 0.0000 +vn -0.3827 -0.9239 0.0000 +vn -0.9239 -0.3827 0.0000 +vn -0.9239 0.3827 0.0000 +vn -0.3827 0.9239 0.0000 +vn 0.3827 0.9239 0.0000 +vn -0.8889 -0.4581 0.0000 +vn -0.7872 -0.6167 0.0000 +vn 0.7624 -0.6471 0.0000 +vn -0.0000 -1.0000 0.0000 +vn -0.7624 -0.6471 0.0000 +vn 0.8889 -0.4581 0.0000 +vn 0.7872 -0.6167 0.0000 +vn 0.0000 -0.0000 1.0000 +vn 0.5778 -0.5779 -0.5763 +vn 0.3962 -0.0000 -0.9182 +vn 0.1605 0.0000 -0.9870 +vn 0.1604 0.0000 0.9871 +vn 0.0812 0.9967 0.0000 +vn 0.2762 -0.9611 0.0000 +vn 0.7073 -0.7069 0.0000 +vn -0.0817 -0.9967 -0.0000 +vn -0.5766 -0.8170 -0.0000 +vn 0.0519 -0.0002 0.9987 +vn -0.5766 -0.8170 0.0000 +vn -0.0000 0.0000 1.0000 +vn 0.0519 -0.0002 -0.9987 +vn 0.5767 0.8170 0.0000 +vn 0.0392 -0.0369 0.9985 +vn 0.1369 -0.9906 0.0000 +vn -0.0014 -1.0000 0.0000 +vn 0.2460 -0.9693 0.0000 +vn 0.1236 0.9923 0.0000 +vn -0.7073 0.7069 0.0000 +vn 0.3962 0.0000 0.9182 +vn 0.0757 -0.0371 -0.9964 +vn -0.0000 -0.0699 -0.9976 +vn 0.0757 -0.0371 0.9964 +vn -0.0000 -0.0699 0.9976 +vn 0.3278 -0.9447 0.0000 +vn 0.0392 -0.0369 -0.9985 +vn 0.0823 0.0000 -0.9966 +vn -0.2762 0.9611 0.0000 +vn 0.0824 0.0000 0.9966 +vn 0.1808 -0.9835 0.0000 +vn 0.8076 0.0002 -0.5897 +vn 0.9843 0.0002 -0.1768 +vn 0.9844 0.0002 0.1759 +vn 0.8070 0.0002 0.5906 +vn 0.0000 -0.8604 -0.5096 +vn 0.0000 -0.8604 0.5096 +vn -0.8996 -0.0470 -0.4341 +vn -0.8996 -0.0470 0.4341 +vn -0.8590 -0.0612 0.5082 +vn -0.8590 -0.0612 -0.5082 +vn 0.0000 0.4650 -0.8853 +vn 0.0000 0.4650 0.8853 +vn -0.0433 -0.9893 -0.1391 +vn 0.0000 -0.9897 -0.1429 +vn 0.0433 -0.9893 -0.1391 +vn 0.0000 -0.9897 0.1429 +vn -0.1146 -0.9759 0.1856 +vn -0.0433 -0.9893 0.1391 +vn 0.8996 -0.0470 -0.4341 +vn 0.8996 -0.0470 0.4341 +vn 0.0000 -0.1458 -0.9893 +vn 0.0000 -0.1339 -0.9910 +vn 0.8590 -0.0612 0.5082 +vn 0.0000 -0.1458 0.9893 +vn -0.0000 -0.1338 0.9910 +vn 0.8590 -0.0612 -0.5082 +vn 0.0433 -0.9893 0.1391 +vn 0.1146 -0.9759 0.1856 +vn -0.1146 -0.9759 -0.1856 +vn 0.1146 -0.9759 -0.1856 +vn 0.3962 0.0000 -0.9182 +vn 0.0811 0.9967 0.0000 +vn 0.5767 0.8169 0.0000 +vn 0.2458 -0.9693 0.0000 +vn 0.1237 0.9923 0.0000 +vn 0.0757 -0.0370 -0.9964 +vn 0.1809 -0.9835 0.0000 +vn 0.9843 0.0003 -0.1768 +vn 0.8070 0.0002 0.5905 +vn 0.0000 -0.1339 0.9910 +vn 0.9843 0.0003 -0.1767 +vn -0.8997 -0.0470 -0.4341 +vn -0.8590 -0.0612 -0.5083 +vn 0.8997 -0.0470 -0.4341 +vn 0.0000 -0.1338 0.9910 +vn 0.0012 -0.0000 -1.0000 +vn 0.0071 -1.0000 0.0000 +vn -0.0071 1.0000 -0.0000 +vn 0.0012 0.0000 1.0000 +vn 0.0012 0.0000 -1.0000 +vn 0.0072 -1.0000 0.0000 +vn -0.0072 1.0000 0.0000 +# 178 vertex normals + +vt 0.0599 0.1509 0.0000 +vt 0.0802 0.1509 0.0000 +vt 0.0802 0.1581 0.0000 +vt 0.0599 0.1581 0.0000 +vt 0.0599 0.1130 0.0000 +vt 0.0802 0.1130 0.0000 +vt 0.0802 0.1159 0.0000 +vt 0.0599 0.1159 0.0000 +vt 0.0599 0.1321 0.0000 +vt 0.0802 0.1321 0.0000 +vt 0.0802 0.1349 0.0000 +vt 0.0599 0.1349 0.0000 +vt 0.0599 0.1282 0.0000 +vt 0.0802 0.1282 0.0000 +vt 0.0802 0.1310 0.0000 +vt 0.0599 0.1310 0.0000 +vt 0.0599 0.0900 0.0000 +vt 0.0802 0.0900 0.0000 +vt 0.0802 0.0971 0.0000 +vt 0.0599 0.0971 0.0000 +vt 0.0599 0.0988 0.0000 +vt 0.0802 0.0988 0.0000 +vt 0.0802 0.1016 0.0000 +vt 0.0599 0.1016 0.0000 +vt 0.0599 0.1036 0.0000 +vt 0.0802 0.1036 0.0000 +vt 0.0802 0.1111 0.0000 +vt 0.0599 0.1111 0.0000 +vt 0.0599 0.1170 0.0000 +vt 0.0802 0.1170 0.0000 +vt 0.0802 0.1198 0.0000 +vt 0.0599 0.1198 0.0000 +vt 0.0599 0.1209 0.0000 +vt 0.0802 0.1209 0.0000 +vt 0.0802 0.1270 0.0000 +vt 0.0599 0.1270 0.0000 +vt 0.0599 0.1368 0.0000 +vt 0.0802 0.1368 0.0000 +vt 0.0802 0.1442 0.0000 +vt 0.0599 0.1442 0.0000 +vt 0.0599 0.1462 0.0000 +vt 0.0802 0.1462 0.0000 +vt 0.0802 0.1492 0.0000 +vt 0.0599 0.1492 0.0000 +vt 0.0802 0.1581 0.0000 +vt 0.0802 0.1509 0.0000 +vt 0.0599 0.1509 0.0000 +vt 0.0599 0.1581 0.0000 +vt 0.0802 0.1159 0.0000 +vt 0.0802 0.1130 0.0000 +vt 0.0599 0.1130 0.0000 +vt 0.0599 0.1159 0.0000 +vt 0.0802 0.1349 0.0000 +vt 0.0802 0.1320 0.0000 +vt 0.0599 0.1320 0.0000 +vt 0.0599 0.1349 0.0000 +vt 0.0802 0.1310 0.0000 +vt 0.0802 0.1283 0.0000 +vt 0.0599 0.1283 0.0000 +vt 0.0599 0.1310 0.0000 +vt 0.0802 0.0971 0.0000 +vt 0.0802 0.0900 0.0000 +vt 0.0599 0.0900 0.0000 +vt 0.0599 0.0971 0.0000 +vt 0.0802 0.1016 0.0000 +vt 0.0802 0.0988 0.0000 +vt 0.0599 0.0988 0.0000 +vt 0.0599 0.1016 0.0000 +vt 0.0802 0.1111 0.0000 +vt 0.0802 0.1036 0.0000 +vt 0.0599 0.1036 0.0000 +vt 0.0599 0.1111 0.0000 +vt 0.0802 0.1198 0.0000 +vt 0.0802 0.1170 0.0000 +vt 0.0599 0.1170 0.0000 +vt 0.0599 0.1198 0.0000 +vt 0.0802 0.1271 0.0000 +vt 0.0802 0.1209 0.0000 +vt 0.0599 0.1209 0.0000 +vt 0.0599 0.1271 0.0000 +vt 0.0802 0.1442 0.0000 +vt 0.0802 0.1369 0.0000 +vt 0.0599 0.1369 0.0000 +vt 0.0599 0.1442 0.0000 +vt 0.0802 0.1492 0.0000 +vt 0.0802 0.1462 0.0000 +vt 0.0599 0.1462 0.0000 +vt 0.0599 0.1492 0.0000 +vt 0.0576 0.1309 0.0000 +vt 0.0574 0.1309 0.0000 +vt 0.0574 0.1337 0.0000 +vt 0.0576 0.1337 0.0000 +vt 0.0570 0.1309 0.0000 +vt 0.0570 0.1337 0.0000 +vt 0.0567 0.1309 0.0000 +vt 0.0567 0.1337 0.0000 +vt 0.0565 0.1309 0.0000 +vt 0.0565 0.1337 0.0000 +vt 0.0566 0.1309 0.0000 +vt 0.0566 0.1337 0.0000 +vt 0.0569 0.1309 0.0000 +vt 0.0569 0.1337 0.0000 +vt 0.0572 0.1309 0.0000 +vt 0.0572 0.1337 0.0000 +vt 0.0594 0.1309 0.0000 +vt 0.0596 0.1309 0.0000 +vt 0.0596 0.1337 0.0000 +vt 0.0594 0.1337 0.0000 +vt 0.0576 0.1337 0.0000 +vt 0.0576 0.1309 0.0000 +vt 0.0576 0.1337 0.0000 +vt 0.0576 0.1309 0.0000 +vt 0.0585 0.1337 0.0000 +vt 0.0585 0.1309 0.0000 +vt 0.0585 0.1337 0.0000 +vt 0.0585 0.1309 0.0000 +vt 0.0587 0.1337 0.0000 +vt 0.0587 0.1309 0.0000 +vt 0.0587 0.1337 0.0000 +vt 0.0587 0.1309 0.0000 +vt 0.0597 0.1337 0.0000 +vt 0.0597 0.1309 0.0000 +vt 0.0576 0.1473 0.0000 +vt 0.0574 0.1473 0.0000 +vt 0.0574 0.1500 0.0000 +vt 0.0576 0.1500 0.0000 +vt 0.0570 0.1473 0.0000 +vt 0.0570 0.1500 0.0000 +vt 0.0567 0.1473 0.0000 +vt 0.0567 0.1500 0.0000 +vt 0.0565 0.1473 0.0000 +vt 0.0565 0.1500 0.0000 +vt 0.0566 0.1473 0.0000 +vt 0.0566 0.1500 0.0000 +vt 0.0569 0.1473 0.0000 +vt 0.0569 0.1500 0.0000 +vt 0.0572 0.1473 0.0000 +vt 0.0572 0.1500 0.0000 +vt 0.0594 0.1473 0.0000 +vt 0.0596 0.1473 0.0000 +vt 0.0596 0.1500 0.0000 +vt 0.0594 0.1500 0.0000 +vt 0.0576 0.1500 0.0000 +vt 0.0576 0.1473 0.0000 +vt 0.0576 0.1500 0.0000 +vt 0.0576 0.1473 0.0000 +vt 0.0585 0.1500 0.0000 +vt 0.0585 0.1473 0.0000 +vt 0.0585 0.1500 0.0000 +vt 0.0585 0.1473 0.0000 +vt 0.0587 0.1500 0.0000 +vt 0.0587 0.1473 0.0000 +vt 0.0587 0.1500 0.0000 +vt 0.0587 0.1473 0.0000 +vt 0.0597 0.1500 0.0000 +vt 0.0597 0.1473 0.0000 +vt 0.0576 0.1146 0.0000 +vt 0.0574 0.1146 0.0000 +vt 0.0574 0.1174 0.0000 +vt 0.0576 0.1174 0.0000 +vt 0.0570 0.1146 0.0000 +vt 0.0570 0.1174 0.0000 +vt 0.0567 0.1146 0.0000 +vt 0.0567 0.1174 0.0000 +vt 0.0565 0.1146 0.0000 +vt 0.0565 0.1174 0.0000 +vt 0.0566 0.1146 0.0000 +vt 0.0566 0.1174 0.0000 +vt 0.0569 0.1146 0.0000 +vt 0.0569 0.1174 0.0000 +vt 0.0572 0.1146 0.0000 +vt 0.0572 0.1174 0.0000 +vt 0.0594 0.1146 0.0000 +vt 0.0596 0.1146 0.0000 +vt 0.0596 0.1174 0.0000 +vt 0.0594 0.1174 0.0000 +vt 0.0576 0.1174 0.0000 +vt 0.0576 0.1146 0.0000 +vt 0.0576 0.1174 0.0000 +vt 0.0576 0.1146 0.0000 +vt 0.0585 0.1174 0.0000 +vt 0.0585 0.1146 0.0000 +vt 0.0585 0.1174 0.0000 +vt 0.0585 0.1146 0.0000 +vt 0.0587 0.1174 0.0000 +vt 0.0587 0.1146 0.0000 +vt 0.0587 0.1174 0.0000 +vt 0.0587 0.1146 0.0000 +vt 0.0597 0.1174 0.0000 +vt 0.0597 0.1146 0.0000 +vt 0.0576 0.0983 0.0000 +vt 0.0574 0.0983 0.0000 +vt 0.0574 0.1010 0.0000 +vt 0.0576 0.1010 0.0000 +vt 0.0570 0.0983 0.0000 +vt 0.0570 0.1010 0.0000 +vt 0.0567 0.0983 0.0000 +vt 0.0567 0.1010 0.0000 +vt 0.0565 0.0983 0.0000 +vt 0.0565 0.1010 0.0000 +vt 0.0566 0.0983 0.0000 +vt 0.0566 0.1010 0.0000 +vt 0.0569 0.0983 0.0000 +vt 0.0569 0.1010 0.0000 +vt 0.0572 0.0983 0.0000 +vt 0.0572 0.1010 0.0000 +vt 0.0594 0.0983 0.0000 +vt 0.0596 0.0983 0.0000 +vt 0.0596 0.1010 0.0000 +vt 0.0594 0.1010 0.0000 +vt 0.0576 0.1010 0.0000 +vt 0.0576 0.0983 0.0000 +vt 0.0576 0.1010 0.0000 +vt 0.0576 0.0983 0.0000 +vt 0.0585 0.1010 0.0000 +vt 0.0585 0.0983 0.0000 +vt 0.0585 0.1010 0.0000 +vt 0.0585 0.0983 0.0000 +vt 0.0587 0.1010 0.0000 +vt 0.0587 0.0983 0.0000 +vt 0.0587 0.1010 0.0000 +vt 0.0587 0.0983 0.0000 +vt 0.0597 0.1010 0.0000 +vt 0.0597 0.0983 0.0000 +vt 0.0583 0.0905 0.0000 +vt 0.0583 0.0905 0.0000 +vt 0.0603 0.0905 0.0000 +vt 0.0603 0.0905 0.0000 +vt 0.0583 0.1576 0.0000 +vt 0.0603 0.1576 0.0000 +vt 0.0603 0.1576 0.0000 +vt 0.0583 0.1576 0.0000 +vt 0.0800 0.0905 0.0000 +vt 0.0800 0.0905 0.0000 +vt 0.0821 0.0905 0.0000 +vt 0.0821 0.0905 0.0000 +vt 0.0800 0.1576 0.0000 +vt 0.0821 0.1576 0.0000 +vt 0.0821 0.1576 0.0000 +vt 0.0800 0.1576 0.0000 +vt 0.1112 0.3345 0.0000 +vt 0.1112 0.3345 0.0000 +vt 0.1119 0.3345 0.0000 +vt 0.1119 0.3345 0.0000 +vt 0.1112 0.4039 0.0000 +vt 0.1119 0.4039 0.0000 +vt 0.1119 0.4039 0.0000 +vt 0.1112 0.4039 0.0000 +vt 0.1119 0.3358 0.0000 +vt 0.1119 0.4027 0.0000 +vt 0.1357 0.3345 0.0000 +vt 0.1357 0.3345 0.0000 +vt 0.1357 0.3358 0.0000 +vt 0.1357 0.3358 0.0000 +vt 0.1119 0.4027 0.0000 +vt 0.1119 0.3358 0.0000 +vt 0.1357 0.4027 0.0000 +vt 0.1357 0.4039 0.0000 +vt 0.1357 0.4039 0.0000 +vt 0.1357 0.4027 0.0000 +vt 0.3671 0.3376 0.0000 +vt 0.3670 0.3376 0.0000 +vt 0.3670 0.4077 0.0000 +vt 0.3671 0.4077 0.0000 +vt 0.3667 0.3376 0.0000 +vt 0.3667 0.4077 0.0000 +vt 0.3664 0.3376 0.0000 +vt 0.3664 0.4077 0.0000 +vt 0.3663 0.3376 0.0000 +vt 0.3663 0.4077 0.0000 +vt 0.3664 0.3376 0.0000 +vt 0.3664 0.4077 0.0000 +vt 0.3667 0.3376 0.0000 +vt 0.3667 0.4077 0.0000 +vt 0.3670 0.3376 0.0000 +vt 0.3670 0.4077 0.0000 +vt 0.3670 0.3354 0.0000 +vt 0.3667 0.3354 0.0000 +vt 0.3664 0.3354 0.0000 +vt 0.3663 0.3354 0.0000 +vt 0.3664 0.3354 0.0000 +vt 0.3667 0.3354 0.0000 +vt 0.3670 0.3354 0.0000 +vt 0.3672 0.3354 0.0000 +vt 0.3672 0.4099 0.0000 +vt 0.3671 0.4099 0.0000 +vt 0.3667 0.4099 0.0000 +vt 0.3664 0.4099 0.0000 +vt 0.3662 0.4099 0.0000 +vt 0.3664 0.4099 0.0000 +vt 0.3667 0.4099 0.0000 +vt 0.3671 0.4099 0.0000 +vt 0.3671 0.4079 0.0000 +vt 0.3672 0.4079 0.0000 +vt 0.3667 0.4079 0.0000 +vt 0.3664 0.4079 0.0000 +vt 0.3662 0.4079 0.0000 +vt 0.3664 0.4079 0.0000 +vt 0.3667 0.4079 0.0000 +vt 0.3671 0.4079 0.0000 +vt 0.3672 0.3374 0.0000 +vt 0.3670 0.3374 0.0000 +vt 0.3670 0.3374 0.0000 +vt 0.3667 0.3374 0.0000 +vt 0.3664 0.3374 0.0000 +vt 0.3663 0.3374 0.0000 +vt 0.3664 0.3374 0.0000 +vt 0.3667 0.3374 0.0000 +vt 0.3658 0.3879 0.0000 +vt 0.3658 0.3879 0.0000 +vt 0.3676 0.3879 0.0000 +vt 0.3676 0.3879 0.0000 +vt 0.3672 0.3879 0.0000 +vt 0.3662 0.3879 0.0000 +vt 0.3658 0.3898 0.0000 +vt 0.3662 0.3898 0.0000 +vt 0.3672 0.3898 0.0000 +vt 0.3676 0.3898 0.0000 +vt 0.3676 0.3898 0.0000 +vt 0.3658 0.3898 0.0000 +vt 0.3667 0.3879 0.0000 +vt 0.3671 0.3879 0.0000 +vt 0.3671 0.3898 0.0000 +vt 0.3667 0.3898 0.0000 +vt 0.3664 0.3879 0.0000 +vt 0.3664 0.3898 0.0000 +vt 0.3720 0.3879 0.0000 +vt 0.3720 0.3879 0.0000 +vt 0.3738 0.3879 0.0000 +vt 0.3738 0.3879 0.0000 +vt 0.3734 0.3879 0.0000 +vt 0.3724 0.3879 0.0000 +vt 0.3720 0.3898 0.0000 +vt 0.3724 0.3898 0.0000 +vt 0.3734 0.3898 0.0000 +vt 0.3738 0.3898 0.0000 +vt 0.3738 0.3898 0.0000 +vt 0.3720 0.3898 0.0000 +vt 0.3729 0.3879 0.0000 +vt 0.3732 0.3879 0.0000 +vt 0.3732 0.3898 0.0000 +vt 0.3729 0.3898 0.0000 +vt 0.3725 0.3879 0.0000 +vt 0.3725 0.3898 0.0000 +vt 0.3720 0.4019 0.0000 +vt 0.3720 0.4019 0.0000 +vt 0.3738 0.4019 0.0000 +vt 0.3738 0.4019 0.0000 +vt 0.3734 0.4019 0.0000 +vt 0.3724 0.4019 0.0000 +vt 0.3720 0.4057 0.0000 +vt 0.3724 0.4057 0.0000 +vt 0.3734 0.4057 0.0000 +vt 0.3738 0.4057 0.0000 +vt 0.3738 0.4057 0.0000 +vt 0.3720 0.4057 0.0000 +vt 0.3729 0.4019 0.0000 +vt 0.3732 0.4019 0.0000 +vt 0.3732 0.4057 0.0000 +vt 0.3729 0.4057 0.0000 +vt 0.3725 0.4019 0.0000 +vt 0.3725 0.4057 0.0000 +vt 0.3658 0.4019 0.0000 +vt 0.3658 0.4019 0.0000 +vt 0.3676 0.4019 0.0000 +vt 0.3676 0.4019 0.0000 +vt 0.3672 0.4019 0.0000 +vt 0.3662 0.4019 0.0000 +vt 0.3658 0.4057 0.0000 +vt 0.3662 0.4057 0.0000 +vt 0.3672 0.4057 0.0000 +vt 0.3676 0.4057 0.0000 +vt 0.3676 0.4057 0.0000 +vt 0.3658 0.4057 0.0000 +vt 0.3667 0.4019 0.0000 +vt 0.3671 0.4019 0.0000 +vt 0.3671 0.4057 0.0000 +vt 0.3667 0.4057 0.0000 +vt 0.3664 0.4019 0.0000 +vt 0.3664 0.4057 0.0000 +vt 0.3658 0.3556 0.0000 +vt 0.3658 0.3556 0.0000 +vt 0.3676 0.3556 0.0000 +vt 0.3676 0.3556 0.0000 +vt 0.3672 0.3556 0.0000 +vt 0.3662 0.3556 0.0000 +vt 0.3658 0.3575 0.0000 +vt 0.3662 0.3575 0.0000 +vt 0.3672 0.3575 0.0000 +vt 0.3676 0.3575 0.0000 +vt 0.3676 0.3575 0.0000 +vt 0.3658 0.3575 0.0000 +vt 0.3667 0.3556 0.0000 +vt 0.3671 0.3556 0.0000 +vt 0.3671 0.3575 0.0000 +vt 0.3667 0.3575 0.0000 +vt 0.3664 0.3556 0.0000 +vt 0.3664 0.3575 0.0000 +vt 0.3658 0.3396 0.0000 +vt 0.3658 0.3396 0.0000 +vt 0.3676 0.3396 0.0000 +vt 0.3676 0.3396 0.0000 +vt 0.3672 0.3396 0.0000 +vt 0.3662 0.3396 0.0000 +vt 0.3658 0.3434 0.0000 +vt 0.3662 0.3434 0.0000 +vt 0.3672 0.3434 0.0000 +vt 0.3676 0.3434 0.0000 +vt 0.3676 0.3434 0.0000 +vt 0.3658 0.3434 0.0000 +vt 0.3667 0.3396 0.0000 +vt 0.3671 0.3396 0.0000 +vt 0.3671 0.3434 0.0000 +vt 0.3667 0.3434 0.0000 +vt 0.3664 0.3396 0.0000 +vt 0.3664 0.3434 0.0000 +vt 0.3720 0.3396 0.0000 +vt 0.3720 0.3396 0.0000 +vt 0.3738 0.3396 0.0000 +vt 0.3738 0.3396 0.0000 +vt 0.3734 0.3396 0.0000 +vt 0.3724 0.3396 0.0000 +vt 0.3720 0.3434 0.0000 +vt 0.3724 0.3434 0.0000 +vt 0.3734 0.3434 0.0000 +vt 0.3738 0.3434 0.0000 +vt 0.3738 0.3434 0.0000 +vt 0.3720 0.3434 0.0000 +vt 0.3729 0.3396 0.0000 +vt 0.3732 0.3396 0.0000 +vt 0.3732 0.3434 0.0000 +vt 0.3729 0.3434 0.0000 +vt 0.3725 0.3396 0.0000 +vt 0.3725 0.3434 0.0000 +vt 0.3733 0.3376 0.0000 +vt 0.3731 0.3376 0.0000 +vt 0.3731 0.4077 0.0000 +vt 0.3733 0.4077 0.0000 +vt 0.3729 0.3376 0.0000 +vt 0.3729 0.4077 0.0000 +vt 0.3726 0.3376 0.0000 +vt 0.3726 0.4077 0.0000 +vt 0.3725 0.3376 0.0000 +vt 0.3725 0.4077 0.0000 +vt 0.3726 0.3376 0.0000 +vt 0.3726 0.4077 0.0000 +vt 0.3729 0.3376 0.0000 +vt 0.3729 0.4077 0.0000 +vt 0.3731 0.3376 0.0000 +vt 0.3731 0.4077 0.0000 +vt 0.3732 0.3354 0.0000 +vt 0.3729 0.3354 0.0000 +vt 0.3725 0.3354 0.0000 +vt 0.3724 0.3354 0.0000 +vt 0.3725 0.3354 0.0000 +vt 0.3729 0.3354 0.0000 +vt 0.3732 0.3354 0.0000 +vt 0.3733 0.3354 0.0000 +vt 0.3734 0.4099 0.0000 +vt 0.3732 0.4099 0.0000 +vt 0.3729 0.4099 0.0000 +vt 0.3725 0.4099 0.0000 +vt 0.3724 0.4099 0.0000 +vt 0.3725 0.4099 0.0000 +vt 0.3729 0.4099 0.0000 +vt 0.3732 0.4099 0.0000 +vt 0.3732 0.4079 0.0000 +vt 0.3734 0.4079 0.0000 +vt 0.3729 0.4079 0.0000 +vt 0.3725 0.4079 0.0000 +vt 0.3724 0.4079 0.0000 +vt 0.3725 0.4079 0.0000 +vt 0.3729 0.4079 0.0000 +vt 0.3732 0.4079 0.0000 +vt 0.3733 0.3374 0.0000 +vt 0.3732 0.3374 0.0000 +vt 0.3732 0.3374 0.0000 +vt 0.3729 0.3374 0.0000 +vt 0.3725 0.3374 0.0000 +vt 0.3724 0.3374 0.0000 +vt 0.3725 0.3374 0.0000 +vt 0.3729 0.3374 0.0000 +vt 0.3720 0.3556 0.0000 +vt 0.3720 0.3556 0.0000 +vt 0.3738 0.3556 0.0000 +vt 0.3738 0.3556 0.0000 +vt 0.3734 0.3556 0.0000 +vt 0.3724 0.3556 0.0000 +vt 0.3720 0.3575 0.0000 +vt 0.3724 0.3575 0.0000 +vt 0.3734 0.3575 0.0000 +vt 0.3738 0.3575 0.0000 +vt 0.3738 0.3575 0.0000 +vt 0.3720 0.3575 0.0000 +vt 0.3729 0.3556 0.0000 +vt 0.3732 0.3556 0.0000 +vt 0.3732 0.3575 0.0000 +vt 0.3729 0.3575 0.0000 +vt 0.3725 0.3556 0.0000 +vt 0.3725 0.3575 0.0000 +vt 0.3669 0.3773 0.0000 +vt 0.3669 0.3773 0.0000 +vt 0.3673 0.3776 0.0000 +vt 0.3673 0.3776 0.0000 +vt 0.3677 0.3776 0.0000 +vt 0.3677 0.3776 0.0000 +vt 0.3680 0.3776 0.0000 +vt 0.3680 0.3776 0.0000 +vt 0.3677 0.3785 0.0000 +vt 0.3677 0.3785 0.0000 +vt 0.3680 0.3785 0.0000 +vt 0.3680 0.3785 0.0000 +vt 0.3708 0.3784 0.0000 +vt 0.3720 0.3783 0.0000 +vt 0.3720 0.3782 0.0000 +vt 0.3720 0.3781 0.0000 +vt 0.3720 0.3780 0.0000 +vt 0.3720 0.3779 0.0000 +vt 0.3708 0.3778 0.0000 +vt 0.3707 0.3784 0.0000 +vt 0.3707 0.3784 0.0000 +vt 0.3708 0.3784 0.0000 +vt 0.3690 0.3778 0.0000 +vt 0.3690 0.3780 0.0000 +vt 0.3680 0.3779 0.0000 +vt 0.3677 0.3779 0.0000 +vt 0.3677 0.3782 0.0000 +vt 0.3680 0.3782 0.0000 +vt 0.3708 0.3778 0.0000 +vt 0.3720 0.3779 0.0000 +vt 0.3720 0.3780 0.0000 +vt 0.3720 0.3781 0.0000 +vt 0.3720 0.3782 0.0000 +vt 0.3720 0.3783 0.0000 +vt 0.3708 0.3782 0.0000 +vt 0.3708 0.3780 0.0000 +vt 0.3707 0.3782 0.0000 +vt 0.3707 0.3778 0.0000 +vt 0.3707 0.3780 0.0000 +vt 0.3707 0.3778 0.0000 +vt 0.3690 0.3784 0.0000 +vt 0.3690 0.3784 0.0000 +vt 0.3690 0.3778 0.0000 +vt 0.3690 0.3782 0.0000 +vt 0.3680 0.3782 0.0000 +vt 0.3691 0.3782 0.0000 +vt 0.3669 0.3788 0.0000 +vt 0.3673 0.3785 0.0000 +vt 0.3691 0.3780 0.0000 +vt 0.3678 0.3779 0.0000 +vt 0.3678 0.3782 0.0000 +vt 0.3669 0.3788 0.0000 +vt 0.3673 0.3785 0.0000 +vt 0.3680 0.3779 0.0000 +vt 0.3697 0.3779 0.0000 +vt 0.3697 0.3775 0.0000 +vt 0.3701 0.3775 0.0000 +vt 0.3701 0.3779 0.0000 +vt 0.3697 0.3783 0.0000 +vt 0.3701 0.3783 0.0000 +vt 0.3701 0.3786 0.0000 +vt 0.3697 0.3786 0.0000 +vt 0.3697 0.3776 0.0000 +vt 0.3697 0.3776 0.0000 +vt 0.3697 0.3786 0.0000 +vt 0.3697 0.3786 0.0000 +vt 0.3697 0.3778 0.0000 +vt 0.3701 0.3778 0.0000 +vt 0.3701 0.3783 0.0000 +vt 0.3697 0.3783 0.0000 +vt 0.3699 0.3774 0.0000 +vt 0.3699 0.3787 0.0000 +vt 0.3701 0.3776 0.0000 +vt 0.3701 0.3786 0.0000 +vt 0.3699 0.3774 0.0000 +vt 0.3701 0.3786 0.0000 +vt 0.3699 0.3788 0.0000 +vt 0.3701 0.3776 0.0000 +vt 0.3669 0.3667 0.0000 +vt 0.3669 0.3667 0.0000 +vt 0.3673 0.3669 0.0000 +vt 0.3673 0.3669 0.0000 +vt 0.3677 0.3669 0.0000 +vt 0.3677 0.3669 0.0000 +vt 0.3680 0.3670 0.0000 +vt 0.3680 0.3670 0.0000 +vt 0.3677 0.3678 0.0000 +vt 0.3677 0.3678 0.0000 +vt 0.3680 0.3678 0.0000 +vt 0.3680 0.3678 0.0000 +vt 0.3708 0.3677 0.0000 +vt 0.3720 0.3676 0.0000 +vt 0.3720 0.3675 0.0000 +vt 0.3720 0.3674 0.0000 +vt 0.3720 0.3673 0.0000 +vt 0.3720 0.3672 0.0000 +vt 0.3708 0.3671 0.0000 +vt 0.3707 0.3677 0.0000 +vt 0.3707 0.3677 0.0000 +vt 0.3708 0.3677 0.0000 +vt 0.3690 0.3671 0.0000 +vt 0.3690 0.3673 0.0000 +vt 0.3680 0.3672 0.0000 +vt 0.3677 0.3672 0.0000 +vt 0.3677 0.3675 0.0000 +vt 0.3680 0.3675 0.0000 +vt 0.3708 0.3671 0.0000 +vt 0.3720 0.3672 0.0000 +vt 0.3720 0.3673 0.0000 +vt 0.3720 0.3674 0.0000 +vt 0.3720 0.3675 0.0000 +vt 0.3720 0.3676 0.0000 +vt 0.3708 0.3675 0.0000 +vt 0.3708 0.3673 0.0000 +vt 0.3707 0.3675 0.0000 +vt 0.3707 0.3671 0.0000 +vt 0.3707 0.3673 0.0000 +vt 0.3707 0.3671 0.0000 +vt 0.3690 0.3677 0.0000 +vt 0.3690 0.3677 0.0000 +vt 0.3690 0.3671 0.0000 +vt 0.3690 0.3675 0.0000 +vt 0.3680 0.3675 0.0000 +vt 0.3691 0.3675 0.0000 +vt 0.3669 0.3681 0.0000 +vt 0.3673 0.3678 0.0000 +vt 0.3691 0.3673 0.0000 +vt 0.3678 0.3672 0.0000 +vt 0.3678 0.3675 0.0000 +vt 0.3669 0.3681 0.0000 +vt 0.3673 0.3678 0.0000 +vt 0.3680 0.3672 0.0000 +vt 0.3697 0.3672 0.0000 +vt 0.3697 0.3669 0.0000 +vt 0.3701 0.3669 0.0000 +vt 0.3701 0.3672 0.0000 +vt 0.3697 0.3676 0.0000 +vt 0.3701 0.3676 0.0000 +vt 0.3701 0.3679 0.0000 +vt 0.3697 0.3679 0.0000 +vt 0.3697 0.3669 0.0000 +vt 0.3697 0.3669 0.0000 +vt 0.3697 0.3679 0.0000 +vt 0.3697 0.3679 0.0000 +vt 0.3697 0.3672 0.0000 +vt 0.3701 0.3672 0.0000 +vt 0.3701 0.3676 0.0000 +vt 0.3697 0.3676 0.0000 +vt 0.3699 0.3667 0.0000 +vt 0.3699 0.3680 0.0000 +vt 0.3701 0.3669 0.0000 +vt 0.3701 0.3679 0.0000 +vt 0.3699 0.3667 0.0000 +vt 0.3701 0.3679 0.0000 +vt 0.3699 0.3681 0.0000 +vt 0.3701 0.3669 0.0000 +vt 0.3732 0.3773 0.0000 +vt 0.3732 0.3773 0.0000 +vt 0.3736 0.3776 0.0000 +vt 0.3736 0.3776 0.0000 +vt 0.3740 0.3776 0.0000 +vt 0.3740 0.3776 0.0000 +vt 0.3742 0.3776 0.0000 +vt 0.3742 0.3776 0.0000 +vt 0.3740 0.3785 0.0000 +vt 0.3740 0.3785 0.0000 +vt 0.3742 0.3785 0.0000 +vt 0.3742 0.3785 0.0000 +vt 0.3770 0.3784 0.0000 +vt 0.3782 0.3783 0.0000 +vt 0.3782 0.3782 0.0000 +vt 0.3782 0.3781 0.0000 +vt 0.3782 0.3780 0.0000 +vt 0.3782 0.3779 0.0000 +vt 0.3770 0.3778 0.0000 +vt 0.3769 0.3784 0.0000 +vt 0.3769 0.3784 0.0000 +vt 0.3770 0.3784 0.0000 +vt 0.3753 0.3778 0.0000 +vt 0.3753 0.3780 0.0000 +vt 0.3742 0.3779 0.0000 +vt 0.3740 0.3779 0.0000 +vt 0.3740 0.3782 0.0000 +vt 0.3742 0.3782 0.0000 +vt 0.3770 0.3778 0.0000 +vt 0.3782 0.3779 0.0000 +vt 0.3782 0.3780 0.0000 +vt 0.3782 0.3781 0.0000 +vt 0.3782 0.3782 0.0000 +vt 0.3782 0.3783 0.0000 +vt 0.3770 0.3782 0.0000 +vt 0.3770 0.3780 0.0000 +vt 0.3769 0.3782 0.0000 +vt 0.3769 0.3778 0.0000 +vt 0.3769 0.3780 0.0000 +vt 0.3769 0.3778 0.0000 +vt 0.3753 0.3784 0.0000 +vt 0.3753 0.3784 0.0000 +vt 0.3753 0.3778 0.0000 +vt 0.3753 0.3782 0.0000 +vt 0.3743 0.3782 0.0000 +vt 0.3753 0.3782 0.0000 +vt 0.3732 0.3788 0.0000 +vt 0.3736 0.3785 0.0000 +vt 0.3753 0.3780 0.0000 +vt 0.3740 0.3779 0.0000 +vt 0.3740 0.3782 0.0000 +vt 0.3732 0.3788 0.0000 +vt 0.3736 0.3785 0.0000 +vt 0.3743 0.3779 0.0000 +vt 0.3759 0.3779 0.0000 +vt 0.3759 0.3775 0.0000 +vt 0.3763 0.3775 0.0000 +vt 0.3763 0.3779 0.0000 +vt 0.3759 0.3783 0.0000 +vt 0.3763 0.3783 0.0000 +vt 0.3763 0.3786 0.0000 +vt 0.3759 0.3786 0.0000 +vt 0.3759 0.3776 0.0000 +vt 0.3759 0.3776 0.0000 +vt 0.3759 0.3786 0.0000 +vt 0.3759 0.3786 0.0000 +vt 0.3759 0.3778 0.0000 +vt 0.3763 0.3778 0.0000 +vt 0.3763 0.3783 0.0000 +vt 0.3759 0.3783 0.0000 +vt 0.3761 0.3774 0.0000 +vt 0.3761 0.3787 0.0000 +vt 0.3763 0.3776 0.0000 +vt 0.3763 0.3786 0.0000 +vt 0.3761 0.3774 0.0000 +vt 0.3763 0.3786 0.0000 +vt 0.3761 0.3788 0.0000 +vt 0.3763 0.3776 0.0000 +vt 0.3732 0.3667 0.0000 +vt 0.3732 0.3667 0.0000 +vt 0.3736 0.3669 0.0000 +vt 0.3736 0.3669 0.0000 +vt 0.3740 0.3669 0.0000 +vt 0.3740 0.3669 0.0000 +vt 0.3742 0.3670 0.0000 +vt 0.3742 0.3670 0.0000 +vt 0.3740 0.3678 0.0000 +vt 0.3740 0.3678 0.0000 +vt 0.3742 0.3678 0.0000 +vt 0.3742 0.3678 0.0000 +vt 0.3770 0.3677 0.0000 +vt 0.3782 0.3676 0.0000 +vt 0.3782 0.3675 0.0000 +vt 0.3782 0.3674 0.0000 +vt 0.3782 0.3673 0.0000 +vt 0.3782 0.3672 0.0000 +vt 0.3770 0.3671 0.0000 +vt 0.3769 0.3677 0.0000 +vt 0.3769 0.3677 0.0000 +vt 0.3770 0.3677 0.0000 +vt 0.3753 0.3671 0.0000 +vt 0.3753 0.3673 0.0000 +vt 0.3742 0.3672 0.0000 +vt 0.3740 0.3672 0.0000 +vt 0.3740 0.3675 0.0000 +vt 0.3742 0.3675 0.0000 +vt 0.3770 0.3671 0.0000 +vt 0.3782 0.3672 0.0000 +vt 0.3782 0.3673 0.0000 +vt 0.3782 0.3674 0.0000 +vt 0.3782 0.3675 0.0000 +vt 0.3782 0.3676 0.0000 +vt 0.3770 0.3675 0.0000 +vt 0.3770 0.3673 0.0000 +vt 0.3769 0.3675 0.0000 +vt 0.3769 0.3671 0.0000 +vt 0.3769 0.3673 0.0000 +vt 0.3769 0.3671 0.0000 +vt 0.3753 0.3677 0.0000 +vt 0.3753 0.3677 0.0000 +vt 0.3753 0.3671 0.0000 +vt 0.3753 0.3675 0.0000 +vt 0.3743 0.3675 0.0000 +vt 0.3753 0.3675 0.0000 +vt 0.3732 0.3681 0.0000 +vt 0.3736 0.3678 0.0000 +vt 0.3753 0.3673 0.0000 +vt 0.3740 0.3672 0.0000 +vt 0.3740 0.3675 0.0000 +vt 0.3732 0.3681 0.0000 +vt 0.3736 0.3678 0.0000 +vt 0.3743 0.3672 0.0000 +vt 0.3759 0.3672 0.0000 +vt 0.3759 0.3669 0.0000 +vt 0.3763 0.3669 0.0000 +vt 0.3763 0.3672 0.0000 +vt 0.3759 0.3676 0.0000 +vt 0.3763 0.3676 0.0000 +vt 0.3763 0.3679 0.0000 +vt 0.3759 0.3679 0.0000 +vt 0.3759 0.3669 0.0000 +vt 0.3759 0.3669 0.0000 +vt 0.3759 0.3679 0.0000 +vt 0.3759 0.3679 0.0000 +vt 0.3759 0.3672 0.0000 +vt 0.3763 0.3672 0.0000 +vt 0.3763 0.3676 0.0000 +vt 0.3759 0.3676 0.0000 +vt 0.3761 0.3667 0.0000 +vt 0.3761 0.3680 0.0000 +vt 0.3763 0.3669 0.0000 +vt 0.3763 0.3679 0.0000 +vt 0.3761 0.3667 0.0000 +vt 0.3763 0.3679 0.0000 +vt 0.3761 0.3681 0.0000 +vt 0.3763 0.3669 0.0000 +# 812 texture coords + +# g Door_Left +# usemtl ShippingContainer +# s off +# f 6521/6527/226 6522/6528/226 6523/6525/226 6524/6526/226 +# f 6525/6531/226 6526/6532/226 6527/6529/226 6528/6530/226 +# f 6529/6535/226 6530/6536/226 6531/6533/226 6532/6534/226 +# f 6533/6539/226 6534/6540/226 6535/6537/226 6536/6538/226 +# f 6537/6543/227 6538/6544/227 6539/6541/227 6540/6542/227 +# f 6541/6547/226 6542/6548/226 6543/6545/226 6544/6546/226 +# f 6545/6551/226 6546/6552/226 6547/6549/226 6548/6550/226 +# f 6549/6555/226 6550/6556/226 6551/6553/226 6552/6554/226 +# f 6553/6559/226 6554/6560/226 6555/6557/226 6556/6558/226 +# f 6557/6563/226 6558/6564/226 6559/6561/226 6560/6562/226 +# f 6561/6567/226 6562/6568/226 6563/6565/226 6564/6566/226 +# f 6528/6530/228 6527/6529/228 6546/6552/228 6545/6551/228 +# f 6526/6532/229 6525/6531/229 6552/6554/229 6551/6553/229 +# f 6532/6534/230 6531/6533/230 6534/6540/230 6533/6539/230 +# f 6530/6536/231 6529/6535/231 6560/6562/231 6559/6561/231 +# f 6544/6546/232 6543/6545/232 6538/6544/232 6537/6543/232 +# f 6542/6548/233 6541/6547/233 6548/6550/233 6547/6549/233 +# f 6556/6558/234 6555/6557/234 6550/6556/234 6549/6555/234 +# f 6554/6560/235 6553/6559/235 6536/6538/235 6535/6537/235 +# f 6564/6566/236 6563/6565/236 6558/6564/236 6557/6563/236 +# f 6562/6568/237 6561/6567/237 6524/6526/237 6523/6525/237 +# f 6565/6571/238 6566/6572/238 6567/6569/238 6568/6570/238 +# f 6569/6575/239 6570/6576/239 6571/6573/239 6572/6574/239 +# f 6573/6579/240 6574/6580/240 6575/6577/240 6576/6578/240 +# f 6577/6583/241 6578/6584/241 6579/6581/241 6580/6582/241 +# f 6581/6587/242 6582/6588/242 6583/6585/242 6584/6586/242 +# f 6585/6591/243 6586/6592/243 6587/6589/243 6588/6590/243 +# f 6589/6595/244 6590/6596/244 6591/6593/244 6592/6594/244 +# f 6593/6599/245 6594/6600/245 6595/6597/245 6596/6598/245 +# f 6597/6603/246 6598/6604/246 6599/6601/246 6600/6602/246 +# f 6601/6607/245 6602/6608/245 6603/6605/245 6604/6606/245 +# f 6605/6611/247 6606/6612/247 6607/6609/247 6608/6610/247 +# f 6590/6596/248 6569/6575/248 6572/6574/248 6591/6593/248 +# f 6596/6598/249 6571/6573/249 6570/6576/249 6593/6599/249 +# f 6578/6584/250 6573/6579/250 6576/6578/250 6579/6581/250 +# f 6604/6606/251 6575/6577/251 6574/6580/251 6601/6607/251 +# f 6582/6588/252 6585/6591/252 6588/6590/252 6583/6585/252 +# f 6592/6594/253 6587/6589/253 6586/6592/253 6589/6595/253 +# f 6594/6600/254 6597/6603/254 6600/6602/254 6595/6597/254 +# f 6580/6582/255 6599/6601/255 6598/6604/255 6577/6583/255 +# f 6602/6608/256 6605/6611/256 6608/6610/256 6603/6605/256 +# f 6568/6570/257 6607/6609/257 6606/6612/257 6565/6571/257 +# s 8 +# f 6609/6613/258 6610/6614/259 6611/6615/259 6612/6616/258 +# f 6610/6614/259 6613/6617/260 6614/6618/244 6611/6615/259 +# f 6613/6617/260 6615/6619/261 6616/6620/261 6614/6618/244 +# f 6615/6619/261 6617/6621/262 6618/6622/262 6616/6620/261 +# f 6617/6621/262 6619/6623/263 6620/6624/263 6618/6622/262 +# f 6619/6623/263 6621/6625/264 6622/6626/264 6620/6624/263 +# f 6621/6625/264 6623/6627/265 6624/6628/265 6622/6626/264 +# f 6625/6630/266 6626/6631/266 6627/6632/267 6628/6629/267 +# s 1 +# f 6613/6617/268 6610/6614/268 6609/6613/268 6623/6627/268 6621/6625/268 6619/6623/268 6617/6621/268 6615/6619/268 +# f 6620/6624/269 6622/6626/269 6624/6628/269 6612/6616/269 6611/6615/269 6614/6618/269 6616/6620/269 6618/6622/269 +# s off +# f 6609/6613/270 6612/6616/270 6629/6633/270 6630/6634/270 +# f 6612/6616/269 6624/6628/269 6631/6635/269 6629/6633/269 +# f 6624/6628/271 6623/6627/271 6632/6636/271 6631/6635/271 +# f 6623/6627/268 6609/6613/268 6630/6634/268 6632/6636/268 +# f 6630/6634/272 6629/6633/272 6633/6637/272 6634/6638/272 +# f 6629/6633/269 6631/6635/269 6635/6639/269 6633/6637/269 +# f 6631/6635/273 6632/6636/273 6636/6640/273 6635/6639/273 +# f 6632/6636/268 6630/6634/268 6634/6638/268 6636/6640/268 +# f 6634/6638/274 6633/6637/274 6637/6641/274 6638/6642/274 +# f 6633/6637/269 6635/6639/269 6639/6643/269 6637/6641/269 +# f 6635/6639/275 6636/6640/275 6640/6644/275 6639/6643/275 +# f 6636/6640/268 6634/6638/268 6638/6642/268 6640/6644/268 +# f 6638/6642/276 6637/6641/276 6641/6645/276 6642/6646/276 +# f 6637/6641/269 6639/6643/269 6627/6632/269 6626/6631/269 6641/6645/269 +# f 6639/6643/277 6640/6644/277 6628/6629/277 6627/6632/277 +# f 6640/6644/268 6638/6642/268 6642/6646/268 6625/6630/268 6628/6629/268 +# s 8 +# f 6642/6646/278 6641/6645/278 6626/6631/266 6625/6630/266 +# f 6643/6647/258 6644/6648/259 6645/6649/259 6646/6650/258 +# f 6644/6648/259 6647/6651/260 6648/6652/260 6645/6649/259 +# f 6647/6651/260 6649/6653/261 6650/6654/261 6648/6652/260 +# f 6649/6653/261 6651/6655/262 6652/6656/262 6650/6654/261 +# f 6651/6655/262 6653/6657/263 6654/6658/263 6652/6656/262 +# f 6653/6657/263 6655/6659/264 6656/6660/264 6654/6658/263 +# f 6655/6659/264 6657/6661/265 6658/6662/265 6656/6660/264 +# f 6659/6664/279 6660/6665/279 6661/6666/267 6662/6663/267 +# s 1 +# f 6647/6651/268 6644/6648/268 6643/6647/268 6657/6661/268 6655/6659/268 6653/6657/268 6651/6655/268 6649/6653/268 +# f 6654/6658/269 6656/6660/269 6658/6662/269 6646/6650/269 6645/6649/269 6648/6652/269 6650/6654/269 6652/6656/269 +# s off +# f 6643/6647/270 6646/6650/270 6663/6667/270 6664/6668/270 +# f 6646/6650/269 6658/6662/269 6665/6669/269 6663/6667/269 +# f 6658/6662/271 6657/6661/271 6666/6670/271 6665/6669/271 +# f 6657/6661/268 6643/6647/268 6664/6668/268 6666/6670/268 +# f 6664/6668/272 6663/6667/272 6667/6671/272 6668/6672/272 +# f 6663/6667/269 6665/6669/269 6669/6673/269 6667/6671/269 +# f 6665/6669/273 6666/6670/273 6670/6674/273 6669/6673/273 +# f 6666/6670/268 6664/6668/268 6668/6672/268 6670/6674/268 +# f 6668/6672/274 6667/6671/274 6671/6675/274 6672/6676/274 +# f 6667/6671/269 6669/6673/269 6673/6677/269 6671/6675/269 +# f 6669/6673/275 6670/6674/275 6674/6678/275 6673/6677/275 +# f 6670/6674/268 6668/6672/268 6672/6676/268 6674/6678/268 +# f 6672/6676/276 6671/6675/276 6675/6679/276 6676/6680/276 +# f 6671/6675/269 6673/6677/269 6661/6666/269 6660/6665/269 6675/6679/269 +# f 6673/6677/277 6674/6678/277 6662/6663/277 6661/6666/277 +# f 6674/6678/268 6672/6676/268 6676/6680/268 6659/6664/268 6662/6663/268 +# s 8 +# f 6676/6680/278 6675/6679/278 6660/6665/279 6659/6664/279 +# f 6677/6681/258 6678/6682/259 6679/6683/259 6680/6684/258 +# f 6678/6682/259 6681/6685/260 6682/6686/260 6679/6683/259 +# f 6681/6685/260 6683/6687/261 6684/6688/261 6682/6686/260 +# f 6683/6687/261 6685/6689/262 6686/6690/262 6684/6688/261 +# f 6685/6689/262 6687/6691/263 6688/6692/263 6686/6690/262 +# f 6687/6691/263 6689/6693/264 6690/6694/264 6688/6692/263 +# f 6689/6693/264 6691/6695/265 6692/6696/265 6690/6694/264 +# f 6693/6698/266 6694/6699/266 6695/6700/267 6696/6697/267 +# s 1 +# f 6681/6685/268 6678/6682/268 6677/6681/268 6691/6695/268 6689/6693/268 6687/6691/268 6685/6689/268 6683/6687/268 +# f 6688/6692/269 6690/6694/269 6692/6696/269 6680/6684/269 6679/6683/269 6682/6686/269 6684/6688/269 6686/6690/269 +# s off +# f 6677/6681/270 6680/6684/270 6697/6701/270 6698/6702/270 +# f 6680/6684/269 6692/6696/269 6699/6703/269 6697/6701/269 +# f 6692/6696/280 6691/6695/280 6700/6704/280 6699/6703/280 +# f 6691/6695/268 6677/6681/268 6698/6702/268 6700/6704/268 +# f 6698/6702/272 6697/6701/272 6701/6705/272 6702/6706/272 +# f 6697/6701/269 6699/6703/269 6703/6707/269 6701/6705/269 +# f 6699/6703/273 6700/6704/273 6704/6708/273 6703/6707/273 +# f 6700/6704/268 6698/6702/268 6702/6706/268 6704/6708/268 +# f 6702/6706/274 6701/6705/274 6705/6709/274 6706/6710/274 +# f 6701/6705/269 6703/6707/269 6707/6711/269 6705/6709/269 +# f 6703/6707/275 6704/6708/275 6708/6712/275 6707/6711/275 +# f 6704/6708/268 6702/6706/268 6706/6710/268 6708/6712/268 +# f 6706/6710/276 6705/6709/276 6709/6713/276 6710/6714/276 +# f 6705/6709/269 6707/6711/269 6695/6700/269 6694/6699/269 6709/6713/269 +# f 6707/6711/277 6708/6712/277 6696/6697/277 6695/6700/277 +# f 6708/6712/268 6706/6710/268 6710/6714/268 6693/6698/268 6696/6697/268 +# s 8 +# f 6710/6714/278 6709/6713/278 6694/6699/266 6693/6698/266 +# f 6711/6715/258 6712/6716/259 6713/6717/259 6714/6718/258 +# f 6712/6716/259 6715/6719/244 6716/6720/260 6713/6717/259 +# f 6715/6719/244 6717/6721/261 6718/6722/261 6716/6720/260 +# f 6717/6721/261 6719/6723/262 6720/6724/262 6718/6722/261 +# f 6719/6723/262 6721/6725/263 6722/6726/263 6720/6724/262 +# f 6721/6725/263 6723/6727/264 6724/6728/264 6722/6726/263 +# f 6723/6727/264 6725/6729/265 6726/6730/265 6724/6728/264 +# f 6727/6732/279 6728/6733/279 6729/6734/267 6730/6731/267 +# s 1 +# f 6715/6719/268 6712/6716/268 6711/6715/268 6725/6729/268 6723/6727/268 6721/6725/268 6719/6723/268 6717/6721/268 +# f 6722/6726/269 6724/6728/269 6726/6730/269 6714/6718/269 6713/6717/269 6716/6720/269 6718/6722/269 6720/6724/269 +# s off +# f 6711/6715/270 6714/6718/270 6731/6735/270 6732/6736/270 +# f 6714/6718/269 6726/6730/269 6733/6737/269 6731/6735/269 +# f 6726/6730/271 6725/6729/271 6734/6738/271 6733/6737/271 +# f 6725/6729/268 6711/6715/268 6732/6736/268 6734/6738/268 +# f 6732/6736/272 6731/6735/272 6735/6739/272 6736/6740/272 +# f 6731/6735/269 6733/6737/269 6737/6741/269 6735/6739/269 +# f 6733/6737/273 6734/6738/273 6738/6742/273 6737/6741/273 +# f 6734/6738/268 6732/6736/268 6736/6740/268 6738/6742/268 +# f 6736/6740/274 6735/6739/274 6739/6743/274 6740/6744/274 +# f 6735/6739/269 6737/6741/269 6741/6745/269 6739/6743/269 +# f 6737/6741/275 6738/6742/275 6742/6746/275 6741/6745/275 +# f 6738/6742/268 6736/6740/268 6740/6744/268 6742/6746/268 +# f 6740/6744/276 6739/6743/276 6743/6747/276 6744/6748/276 +# f 6739/6743/269 6741/6745/269 6729/6734/269 6728/6733/269 6743/6747/269 +# f 6741/6745/277 6742/6746/277 6730/6731/277 6729/6734/277 +# f 6742/6746/268 6740/6744/268 6744/6748/268 6727/6732/268 6730/6731/268 +# s 8 +# f 6744/6748/278 6743/6747/278 6728/6733/279 6727/6732/279 +# s 2 +# f 6745/6749/268 6746/6750/268 6747/6751/268 6748/6752/268 +# s 4 +# f 6749/6753/269 6750/6754/269 6751/6755/269 6752/6756/269 +# s 8 +# f 6745/6749/226 6748/6752/226 6750/6754/226 6749/6753/226 +# s 16 +# f 6748/6752/281 6747/6751/281 6751/6755/281 6750/6754/281 +# s 32 +# f 6747/6751/260 6746/6750/260 6752/6756/260 6751/6755/260 +# s 64 +# f 6746/6750/282 6745/6749/282 6749/6753/282 6752/6756/282 +# s 2 +# f 6753/6757/268 6754/6758/268 6755/6759/268 6756/6760/268 +# s 4 +# f 6757/6761/269 6758/6762/269 6759/6763/269 6760/6764/269 +# s 8 +# f 6753/6757/226 6756/6760/226 6758/6762/226 6757/6761/226 +# s 16 +# f 6756/6760/281 6755/6759/281 6759/6763/281 6758/6762/281 +# s 32 +# f 6755/6759/260 6754/6758/260 6760/6764/260 6759/6763/260 +# s 64 +# f 6754/6758/282 6753/6757/282 6757/6761/282 6760/6764/282 +# s 2 +# f 6761/6765/268 6762/6766/268 6763/6767/268 6764/6768/268 +# s 4 +# f 6765/6769/269 6766/6770/269 6767/6771/269 6768/6772/269 +# s 8 +# f 6761/6765/226 6764/6768/226 6769/6773/226 6770/6774/226 6766/6770/226 6765/6769/226 +# s 16 +# f 6771/6776/281 6772/6777/281 6773/6778/281 6774/6775/281 +# s 32 +# f 6768/6772/260 6767/6771/260 6775/6779/260 6776/6780/260 6763/6767/260 6762/6766/260 +# s 64 +# f 6762/6766/282 6761/6765/282 6765/6769/282 6768/6772/282 +# s 16 +# f 6775/6779/281 6770/6774/281 6769/6773/281 6776/6780/281 +# s off +# f 6764/6768/268 6763/6767/268 6771/6776/268 6774/6775/268 +# f 6763/6767/260 6776/6780/260 6772/6777/260 6771/6776/260 +# f 6776/6780/269 6769/6773/269 6773/6778/269 6772/6777/269 +# f 6769/6773/226 6764/6768/226 6774/6775/226 6773/6778/226 +# s 16 +# f 6777/6782/281 6778/6783/281 6779/6784/281 6780/6781/281 +# s off +# f 6767/6771/269 6766/6770/269 6778/6783/269 6777/6782/269 +# f 6766/6770/226 6770/6774/226 6779/6784/226 6778/6783/226 +# f 6770/6774/268 6775/6779/268 6780/6781/268 6779/6784/268 +# f 6775/6779/260 6767/6771/260 6777/6782/260 6780/6781/260 +# s 8 +# f 6781/6786/259 6782/6787/259 6783/6788/283 6784/6785/283 +# f 6785/6789/260 6786/6790/244 6782/6787/259 6781/6786/259 +# f 6787/6791/261 6788/6792/261 6786/6790/244 6785/6789/260 +# f 6789/6793/284 6790/6794/284 6788/6792/261 6787/6791/261 +# f 6791/6795/285 6792/6796/285 6790/6794/284 6789/6793/284 +# f 6793/6797/226 6794/6798/226 6792/6796/285 6791/6795/285 +# f 6795/6799/286 6796/6800/286 6794/6798/226 6793/6797/226 +# f 6784/6785/283 6783/6788/283 6796/6800/286 6795/6799/286 +# s 1 +# f 6797/6806/268 6798/6807/268 6799/6808/268 6800/6801/268 6801/6802/268 6802/6803/268 6803/6804/268 6804/6805/268 +# f 6805/6814/269 6806/6815/269 6807/6816/269 6808/6809/269 6809/6810/269 6810/6811/269 6811/6812/269 6812/6813/269 +# s 2048 +# f 6813/6817/287 6814/6818/288 6783/6788/288 6782/6787/289 +# f 6815/6819/290 6813/6817/287 6782/6787/289 6786/6790/290 +# f 6816/6820/291 6815/6819/290 6786/6790/290 6788/6792/292 +# f 6817/6821/293 6816/6820/291 6788/6792/292 6790/6794/293 +# f 6818/6822/294 6817/6821/293 6790/6794/293 6792/6796/294 +# f 6819/6823/295 6818/6822/294 6792/6796/294 6794/6798/295 +# f 6820/6824/296 6819/6823/295 6794/6798/295 6796/6800/296 +# f 6814/6818/288 6820/6824/296 6796/6800/296 6783/6788/288 +# s 8 +# f 6809/6810/259 6808/6809/283 6814/6818/283 6813/6817/259 +# f 6810/6811/260 6809/6810/259 6813/6817/259 6815/6819/260 +# f 6811/6812/261 6810/6811/260 6815/6819/260 6816/6820/261 +# f 6812/6813/284 6811/6812/261 6816/6820/261 6817/6821/284 +# f 6805/6814/285 6812/6813/284 6817/6821/284 6818/6822/285 +# f 6806/6815/226 6805/6814/285 6818/6822/285 6819/6823/226 +# f 6807/6816/286 6806/6815/226 6819/6823/226 6820/6824/286 +# f 6808/6809/283 6807/6816/286 6820/6824/286 6814/6818/283 +# s 2048 +# f 6784/6785/297 6821/6825/298 6822/6826/299 6781/6786/299 +# f 6795/6799/300 6823/6827/300 6821/6825/298 6784/6785/297 +# f 6793/6797/301 6824/6828/301 6823/6827/300 6795/6799/300 +# f 6791/6795/302 6825/6829/302 6824/6828/301 6793/6797/301 +# f 6789/6793/303 6826/6830/303 6825/6829/302 6791/6795/302 +# f 6787/6791/304 6827/6831/304 6826/6830/303 6789/6793/303 +# f 6785/6789/305 6828/6832/305 6827/6831/304 6787/6791/304 +# f 6781/6786/299 6822/6826/299 6828/6832/305 6785/6789/305 +# s off +# f 6799/6808/258 6798/6807/258 6822/6826/258 6821/6825/258 +# f 6800/6801/306 6799/6808/306 6821/6825/306 6823/6827/306 +# f 6801/6802/307 6800/6801/307 6823/6827/307 6824/6828/307 +# f 6802/6803/308 6801/6802/308 6824/6828/308 6825/6829/308 +# f 6803/6804/309 6802/6803/309 6825/6829/309 6826/6830/309 +# f 6804/6805/310 6803/6804/310 6826/6830/310 6827/6831/310 +# f 6797/6806/311 6804/6805/311 6827/6831/311 6828/6832/311 +# f 6798/6807/312 6797/6806/312 6828/6832/312 6822/6826/312 +# f 6829/6836/268 6830/6837/268 6831/6838/268 6832/6833/268 6833/6834/268 6834/6835/268 +# f 6835/6840/269 6836/6841/269 6837/6842/269 6838/6843/269 6839/6844/269 6840/6839/269 +# s 1 +# f 6831/6838/313 6835/6840/313 6840/6839/314 6832/6833/314 +# s off +# f 6829/6836/281 6834/6835/281 6838/6843/281 6837/6842/281 +# f 6833/6834/282 6832/6833/282 6840/6839/282 6839/6844/282 +# s 1 +# f 6841/6846/315 6842/6847/315 6843/6848/316 6844/6845/316 +# s off +# f 6841/6846/268 6844/6845/268 6845/6849/268 +# f 6846/6850/269 6843/6848/269 6842/6847/269 +# s 1 +# f 6844/6845/316 6843/6848/316 6846/6850/317 6845/6849/317 +# f 6830/6837/318 6836/6841/318 6842/6847/315 6841/6846/315 +# s off +# f 6841/6846/268 6845/6849/268 6831/6838/268 6830/6837/268 +# f 6846/6850/269 6842/6847/269 6836/6841/269 6835/6840/269 +# s 1 +# f 6845/6849/317 6846/6850/317 6835/6840/313 6831/6838/313 +# f 6829/6836/319 6837/6842/319 6836/6841/318 6830/6837/318 +# s off +# f 6847/6854/268 6848/6855/268 6849/6856/268 6850/6851/268 6851/6852/268 6852/6853/268 +# f 6853/6858/269 6854/6859/269 6855/6860/269 6856/6861/269 6857/6862/269 6858/6857/269 +# s 1 +# f 6849/6856/313 6853/6858/313 6858/6857/314 6850/6851/314 +# s off +# f 6847/6854/281 6852/6853/281 6856/6861/281 6855/6860/281 +# f 6851/6852/284 6850/6851/284 6858/6857/284 6857/6862/284 +# s 1 +# f 6859/6864/315 6860/6865/315 6861/6866/316 6862/6863/316 +# s off +# f 6859/6864/268 6862/6863/268 6863/6867/268 +# f 6864/6868/269 6861/6866/269 6860/6865/269 +# s 1 +# f 6862/6863/316 6861/6866/316 6864/6868/317 6863/6867/317 +# f 6848/6855/318 6854/6859/318 6860/6865/315 6859/6864/315 +# s off +# f 6859/6864/268 6863/6867/268 6849/6856/268 6848/6855/268 +# f 6864/6868/269 6860/6865/269 6854/6859/269 6853/6858/269 +# s 1 +# f 6863/6867/317 6864/6868/317 6853/6858/313 6849/6856/313 +# f 6847/6854/319 6855/6860/319 6854/6859/318 6848/6855/318 +# s off +# f 6865/6872/268 6866/6873/268 6867/6874/268 6868/6869/268 6869/6870/268 6870/6871/268 +# f 6871/6876/269 6872/6877/269 6873/6878/269 6874/6879/269 6875/6880/269 6876/6875/269 +# s 1 +# f 6867/6874/313 6871/6876/313 6876/6875/314 6868/6869/314 +# s off +# f 6865/6872/281 6870/6871/281 6874/6879/281 6873/6878/281 +# f 6869/6870/284 6868/6869/284 6876/6875/284 6875/6880/284 +# s 1 +# f 6877/6882/315 6878/6883/315 6879/6884/316 6880/6881/316 +# s off +# f 6877/6882/268 6880/6881/268 6881/6885/268 +# f 6882/6886/269 6879/6884/269 6878/6883/269 +# s 1 +# f 6880/6881/316 6879/6884/316 6882/6886/317 6881/6885/317 +# f 6866/6873/318 6872/6877/318 6878/6883/315 6877/6882/315 +# s off +# f 6877/6882/268 6881/6885/268 6867/6874/268 6866/6873/268 +# f 6882/6886/269 6878/6883/269 6872/6877/269 6871/6876/269 +# s 1 +# f 6881/6885/317 6882/6886/317 6871/6876/313 6867/6874/313 +# f 6865/6872/319 6873/6878/319 6872/6877/318 6866/6873/318 +# s off +# f 6883/6890/268 6884/6891/268 6885/6892/268 6886/6887/268 6887/6888/268 6888/6889/268 +# f 6889/6894/269 6890/6895/269 6891/6896/269 6892/6897/269 6893/6898/269 6894/6893/269 +# s 1 +# f 6885/6892/313 6889/6894/313 6894/6893/314 6886/6887/314 +# s off +# f 6883/6890/281 6888/6889/281 6892/6897/281 6891/6896/281 +# f 6887/6888/282 6886/6887/282 6894/6893/282 6893/6898/282 +# s 1 +# f 6895/6900/315 6896/6901/315 6897/6902/316 6898/6899/316 +# s off +# f 6895/6900/268 6898/6899/268 6899/6903/268 +# f 6900/6904/269 6897/6902/269 6896/6901/269 +# s 1 +# f 6898/6899/316 6897/6902/316 6900/6904/317 6899/6903/317 +# f 6884/6891/318 6890/6895/318 6896/6901/315 6895/6900/315 +# s off +# f 6895/6900/268 6899/6903/268 6885/6892/268 6884/6891/268 +# f 6900/6904/269 6896/6901/269 6890/6895/269 6889/6894/269 +# s 1 +# f 6899/6903/317 6900/6904/317 6889/6894/313 6885/6892/313 +# f 6883/6890/319 6891/6896/319 6890/6895/318 6884/6891/318 +# s off +# f 6901/6908/268 6902/6909/268 6903/6910/268 6904/6905/268 6905/6906/268 6906/6907/268 +# f 6907/6912/269 6908/6913/269 6909/6914/269 6910/6915/269 6911/6916/269 6912/6911/269 +# s 1 +# f 6903/6910/313 6907/6912/313 6912/6911/314 6904/6905/314 +# s off +# f 6901/6908/281 6906/6907/281 6910/6915/281 6909/6914/281 +# f 6905/6906/282 6904/6905/282 6912/6911/282 6911/6916/282 +# s 1 +# f 6913/6918/315 6914/6919/315 6915/6920/316 6916/6917/316 +# s off +# f 6913/6918/268 6916/6917/268 6917/6921/268 +# f 6918/6922/269 6915/6920/269 6914/6919/269 +# s 1 +# f 6916/6917/316 6915/6920/316 6918/6922/317 6917/6921/317 +# f 6902/6909/318 6908/6913/318 6914/6919/315 6913/6918/315 +# s off +# f 6913/6918/268 6917/6921/268 6903/6910/268 6902/6909/268 +# f 6918/6922/269 6914/6919/269 6908/6913/269 6907/6912/269 +# s 1 +# f 6917/6921/317 6918/6922/317 6907/6912/313 6903/6910/313 +# f 6901/6908/319 6909/6914/319 6908/6913/318 6902/6909/318 +# s off +# f 6919/6926/268 6920/6927/268 6921/6928/268 6922/6923/268 6923/6924/268 6924/6925/268 +# f 6925/6930/320 6926/6931/320 6927/6932/320 6928/6933/320 6929/6934/320 6930/6929/320 +# s 1 +# f 6921/6928/313 6925/6930/313 6930/6929/314 6922/6923/314 +# s off +# f 6919/6926/281 6924/6925/281 6928/6933/281 6927/6932/281 +# f 6923/6924/282 6922/6923/282 6930/6929/282 6929/6934/282 +# s 1 +# f 6931/6936/315 6932/6937/315 6933/6938/316 6934/6935/316 +# s off +# f 6931/6936/268 6934/6935/268 6935/6939/268 +# f 6936/6940/269 6933/6938/269 6932/6937/269 +# s 1 +# f 6934/6935/316 6933/6938/316 6936/6940/317 6935/6939/317 +# f 6920/6927/318 6926/6931/318 6932/6937/315 6931/6936/315 +# s off +# f 6931/6936/268 6935/6939/268 6921/6928/268 6920/6927/268 +# f 6936/6940/269 6932/6937/269 6926/6931/269 6925/6930/269 +# s 1 +# f 6935/6939/317 6936/6940/317 6925/6930/313 6921/6928/313 +# f 6919/6926/319 6927/6932/319 6926/6931/318 6920/6927/318 +# s off +# f 6937/6944/268 6938/6945/268 6939/6946/268 6940/6941/268 6941/6942/268 6942/6943/268 +# f 6943/6948/320 6944/6949/320 6945/6950/320 6946/6951/320 6947/6952/320 6948/6947/320 +# s 1 +# f 6939/6946/313 6943/6948/313 6948/6947/314 6940/6941/314 +# s off +# f 6937/6944/281 6942/6943/281 6946/6951/281 6945/6950/281 +# f 6941/6942/284 6940/6941/284 6948/6947/284 6947/6952/284 +# s 1 +# f 6949/6954/315 6950/6955/315 6951/6956/316 6952/6953/316 +# s off +# f 6949/6954/268 6952/6953/268 6953/6957/268 +# f 6954/6958/269 6951/6956/269 6950/6955/269 +# s 1 +# f 6952/6953/316 6951/6956/316 6954/6958/317 6953/6957/317 +# f 6938/6945/318 6944/6949/318 6950/6955/315 6949/6954/315 +# s off +# f 6949/6954/268 6953/6957/268 6939/6946/268 6938/6945/268 +# f 6954/6958/269 6950/6955/269 6944/6949/269 6943/6948/269 +# s 1 +# f 6953/6957/317 6954/6958/317 6943/6948/313 6939/6946/313 +# f 6937/6944/319 6945/6950/319 6944/6949/318 6938/6945/318 +# s 8 +# f 6955/6960/259 6956/6961/259 6957/6962/283 6958/6959/283 +# f 6959/6963/260 6960/6964/260 6956/6961/259 6955/6960/259 +# f 6961/6965/261 6962/6966/261 6960/6964/260 6959/6963/260 +# f 6963/6967/284 6964/6968/284 6962/6966/261 6961/6965/261 +# f 6965/6969/285 6966/6970/285 6964/6968/284 6963/6967/284 +# f 6967/6971/226 6968/6972/226 6966/6970/285 6965/6969/285 +# f 6969/6973/286 6970/6974/286 6968/6972/226 6967/6971/226 +# f 6958/6959/283 6957/6962/283 6970/6974/286 6969/6973/286 +# s 1 +# f 6971/6980/268 6972/6981/268 6973/6982/268 6974/6975/268 6975/6976/268 6976/6977/268 6977/6978/268 6978/6979/268 +# f 6979/6988/269 6980/6989/269 6981/6990/269 6982/6983/269 6983/6984/269 6984/6985/269 6985/6986/269 6986/6987/269 +# s 2048 +# f 6987/6991/287 6988/6992/288 6957/6962/288 6956/6961/289 +# f 6989/6993/290 6987/6991/287 6956/6961/289 6960/6964/290 +# f 6990/6994/292 6989/6993/290 6960/6964/290 6962/6966/292 +# f 6991/6995/293 6990/6994/292 6962/6966/292 6964/6968/293 +# f 6992/6996/294 6991/6995/293 6964/6968/293 6966/6970/294 +# f 6993/6997/295 6992/6996/294 6966/6970/294 6968/6972/295 +# f 6994/6998/296 6993/6997/295 6968/6972/295 6970/6974/321 +# f 6988/6992/288 6994/6998/296 6970/6974/321 6957/6962/288 +# s 8 +# f 6983/6984/259 6982/6983/283 6988/6992/283 6987/6991/259 +# f 6984/6985/244 6983/6984/259 6987/6991/259 6989/6993/244 +# f 6985/6986/261 6984/6985/244 6989/6993/244 6990/6994/261 +# f 6986/6987/284 6985/6986/261 6990/6994/261 6991/6995/284 +# f 6979/6988/285 6986/6987/284 6991/6995/284 6992/6996/285 +# f 6980/6989/316 6979/6988/285 6992/6996/285 6993/6997/316 +# f 6981/6990/286 6980/6989/316 6993/6997/316 6994/6998/286 +# f 6982/6983/283 6981/6990/286 6994/6998/286 6988/6992/283 +# s 2048 +# f 6958/6959/297 6995/6999/297 6996/7000/299 6955/6960/299 +# f 6969/6973/300 6997/7001/300 6995/6999/297 6958/6959/297 +# f 6967/6971/301 6998/7002/301 6997/7001/300 6969/6973/300 +# f 6965/6969/302 6999/7003/302 6998/7002/301 6967/6971/301 +# f 6963/6967/303 7000/7004/303 6999/7003/302 6965/6969/302 +# f 6961/6965/304 7001/7005/304 7000/7004/303 6963/6967/303 +# f 6959/6963/305 7002/7006/305 7001/7005/304 6961/6965/304 +# f 6955/6960/299 6996/7000/299 7002/7006/305 6959/6963/305 +# s off +# f 6973/6982/258 6972/6981/258 6996/7000/258 6995/6999/258 +# f 6974/6975/306 6973/6982/306 6995/6999/306 6997/7001/306 +# f 6975/6976/307 6974/6975/307 6997/7001/307 6998/7002/307 +# f 6976/6977/308 6975/6976/308 6998/7002/308 6999/7003/308 +# f 6977/6978/309 6976/6977/309 6999/7003/309 7000/7004/309 +# f 6978/6979/310 6977/6978/310 7000/7004/310 7001/7005/310 +# f 6971/6980/311 6978/6979/311 7001/7005/311 7002/7006/311 +# f 6972/6981/312 6971/6980/312 7002/7006/312 6996/7000/312 +# f 7003/7010/268 7004/7011/268 7005/7012/268 7006/7007/268 7007/7008/268 7008/7009/268 +# f 7009/7014/269 7010/7015/269 7011/7016/269 7012/7017/269 7013/7018/269 7014/7013/269 +# s 1 +# f 7005/7012/313 7009/7014/313 7014/7013/314 7006/7007/314 +# s off +# f 7003/7010/281 7008/7009/281 7012/7017/281 7011/7016/281 +# f 7007/7008/284 7006/7007/284 7014/7013/284 7013/7018/284 +# s 1 +# f 7015/7020/315 7016/7021/315 7017/7022/316 7018/7019/316 +# s off +# f 7015/7020/268 7018/7019/268 7019/7023/268 +# f 7020/7024/269 7017/7022/269 7016/7021/269 +# s 1 +# f 7018/7019/316 7017/7022/316 7020/7024/317 7019/7023/317 +# f 7004/7011/318 7010/7015/318 7016/7021/315 7015/7020/315 +# s off +# f 7015/7020/268 7019/7023/268 7005/7012/268 7004/7011/268 +# f 7020/7024/269 7016/7021/269 7010/7015/269 7009/7014/269 +# s 1 +# f 7019/7023/317 7020/7024/317 7009/7014/313 7005/7012/313 +# f 7003/7010/319 7011/7016/319 7010/7015/318 7004/7011/318 +# s off +# f 7021/7027/322 7022/7028/322 7023/7025/322 7024/7026/322 +# f 7025/7032/323 7026/7029/323 7027/7030/323 7028/7031/323 +# f 7029/7036/324 7030/7033/324 7031/7034/324 7032/7035/324 +# f 7033/7037/325 7034/7038/325 7035/7039/325 7036/7040/325 7037/7041/325 7038/7042/325 7039/7043/325 +# f 7033/7037/269 7040/7044/269 7041/7045/269 7042/7046/269 +# f 7025/7032/326 7043/7047/326 7044/7048/326 7045/7049/326 +# f 7026/7029/327 7025/7032/327 7045/7049/327 7046/7050/327 +# f 7047/7051/327 7048/7052/327 7032/7035/327 7031/7034/327 +# f 7049/7053/328 7050/7054/328 7051/7055/328 7052/7056/328 7053/7057/328 7054/7058/328 7042/7046/328 7055/7059/328 7056/7060/328 +# f 7057/7061/329 7055/7059/329 7042/7046/329 7041/7045/329 +# f 7034/7038/330 7033/7037/330 7042/7046/330 7054/7058/330 +# f 7058/7062/331 7049/7053/331 7056/7060/331 7059/7063/331 +# f 7049/7053/268 7058/7062/268 7060/7064/268 7039/7043/268 +# f 7043/7047/226 7058/7062/226 7059/7063/226 7044/7048/226 +# f 7040/7044/332 7061/7065/332 7062/7066/332 7041/7045/332 +# f 7060/7064/260 7063/7067/260 7061/7065/260 7040/7044/260 +# f 7064/7068/226 7057/7061/226 7041/7045/226 7062/7066/226 +# f 7058/7062/268 7043/7047/268 7063/7067/268 7060/7064/268 +# f 7050/7054/333 7049/7053/333 7039/7043/333 7038/7042/333 +# f 7039/7043/334 7060/7064/334 7040/7044/334 7033/7037/334 +# f 7048/7052/335 7065/7069/335 7066/7070/335 7064/7068/335 +# f 7023/7025/336 7022/7028/336 7067/7072/336 7068/7071/336 +# f 7056/7060/337 7055/7059/337 7066/7070/337 7069/7073/337 +# f 7070/7075/338 7047/7051/338 7046/7050/338 7071/7074/338 +# f 7072/7077/339 7021/7027/339 7024/7026/339 7073/7076/339 +# f 7027/7030/340 7030/7033/340 7029/7036/340 7028/7031/340 +# f 7067/7072/341 7072/7077/341 7073/7076/341 7068/7071/341 +# f 7071/7074/342 7046/7050/342 7045/7049/342 7074/7078/342 +# f 7056/7060/343 7069/7073/343 7044/7048/343 7059/7063/343 +# f 7047/7051/344 7070/7075/344 7065/7069/344 7048/7052/344 +# f 7055/7059/345 7057/7061/345 7064/7068/345 7066/7070/345 +# f 7066/7070/346 7065/7069/346 7074/7078/346 7069/7073/346 +# f 7074/7078/347 7045/7049/347 7044/7048/347 7069/7073/347 +# f 7043/7047/348 7025/7032/348 7028/7031/348 7063/7067/348 +# f 7063/7067/349 7028/7031/349 7029/7036/349 7061/7065/349 +# f 7061/7065/350 7029/7036/350 7032/7035/350 7062/7066/350 +# f 7048/7052/326 7064/7068/326 7062/7066/326 7032/7035/326 +# f 7070/7075/351 7071/7074/351 7074/7078/351 7065/7069/351 +# f 7037/7041/352 7051/7055/352 7050/7054/352 7038/7042/352 +# f 7036/7040/353 7052/7056/353 7051/7055/353 7037/7041/353 +# f 7035/7039/354 7053/7057/354 7052/7056/354 7036/7040/354 +# f 7034/7038/355 7054/7058/355 7053/7057/355 7035/7039/355 +# f 7075/7080/356 7076/7081/356 7077/7082/356 7078/7079/356 +# f 7079/7084/357 7080/7085/357 7081/7086/357 7082/7083/357 +# f 7078/7079/226 7077/7082/226 7079/7084/226 7082/7083/226 +# f 7076/7081/281 7080/7085/281 7079/7084/281 7077/7082/281 +# s 1 +# f 7083/7088/358 7084/7089/359 7085/7090/360 7086/7087/361 +# s off +# f 7087/7091/362 7088/7092/362 7076/7081/362 7075/7080/362 +# f 7089/7093/363 7090/7094/363 7081/7086/363 7080/7085/363 +# f 7088/7092/281 7089/7093/281 7080/7085/281 7076/7081/281 +# f 7078/7079/282 7082/7083/282 7081/7086/282 7075/7080/282 +# f 7075/7080/282 7081/7086/282 7090/7094/282 7087/7091/282 +# s 2 +# f 7087/7091/364 7091/7095/365 7088/7092/366 +# f 7092/7096/367 7084/7089/368 7090/7094/369 +# s 1 +# f 7093/7097/370 7094/7098/371 7089/7093/281 7088/7092/281 +# f 7087/7091/282 7090/7094/282 7084/7089/359 7083/7088/358 +# f 7086/7087/361 7095/7099/372 7091/7095/373 7083/7088/358 +# f 7096/7100/374 7097/7101/375 7092/7096/376 7094/7098/371 +# f 7098/7102/377 7096/7100/374 7094/7098/371 7093/7097/370 +# f 7098/7102/377 7093/7097/370 7091/7095/373 7095/7099/372 +# f 7085/7090/360 7084/7089/359 7092/7096/376 7097/7101/375 +# s 2 +# f 7089/7093/378 7094/7098/379 7092/7096/367 +# f 7092/7096/367 7090/7094/369 7089/7093/378 +# f 7087/7091/364 7083/7088/380 7091/7095/365 +# f 7091/7095/365 7093/7097/381 7088/7092/366 +# s off +# f 7099/7105/382 7100/7106/382 7101/7103/382 7102/7104/382 +# f 7103/7110/323 7104/7107/323 7105/7108/323 7106/7109/323 +# f 7107/7114/324 7108/7111/324 7109/7112/324 7110/7113/324 +# f 7111/7115/383 7112/7116/383 7113/7117/383 7114/7118/383 7115/7119/383 7116/7120/383 7117/7121/383 +# f 7111/7115/269 7118/7122/269 7119/7123/269 7120/7124/269 +# f 7103/7110/326 7121/7125/326 7122/7126/326 7123/7127/326 +# f 7104/7107/327 7103/7110/327 7123/7127/327 7124/7128/327 +# f 7125/7129/327 7126/7130/327 7110/7113/327 7109/7112/327 +# f 7127/7131/328 7128/7132/328 7129/7133/328 7130/7134/328 7131/7135/328 7132/7136/328 7120/7124/328 7133/7137/328 7134/7138/328 +# f 7135/7139/331 7133/7137/331 7120/7124/331 7119/7123/331 +# f 7112/7116/330 7111/7115/330 7120/7124/330 7132/7136/330 +# f 7136/7140/329 7127/7131/329 7134/7138/329 7137/7141/329 +# f 7127/7131/268 7136/7140/268 7138/7142/268 7117/7121/268 +# f 7121/7125/226 7136/7140/226 7137/7141/226 7122/7126/226 +# f 7118/7122/332 7139/7143/332 7140/7144/332 7119/7123/332 +# f 7138/7142/260 7141/7145/260 7139/7143/260 7118/7122/260 +# f 7142/7146/226 7135/7139/226 7119/7123/226 7140/7144/226 +# f 7136/7140/268 7121/7125/268 7141/7145/268 7138/7142/268 +# f 7128/7132/333 7127/7131/333 7117/7121/333 7116/7120/333 +# f 7117/7121/384 7138/7142/384 7118/7122/384 7111/7115/384 +# f 7126/7130/335 7143/7147/335 7144/7148/335 7142/7146/335 +# f 7101/7103/336 7100/7106/336 7145/7150/336 7146/7149/336 +# f 7134/7138/337 7133/7137/337 7144/7148/337 7147/7151/337 +# f 7148/7153/385 7125/7129/385 7124/7128/385 7149/7152/385 +# f 7150/7155/386 7099/7105/386 7102/7104/386 7151/7154/386 +# f 7105/7108/340 7108/7111/340 7107/7114/340 7106/7109/340 +# f 7145/7150/341 7150/7155/341 7151/7154/341 7146/7149/341 +# f 7149/7152/387 7124/7128/387 7123/7127/387 7152/7156/387 +# f 7134/7138/343 7147/7151/343 7122/7126/343 7137/7141/343 +# f 7125/7129/344 7148/7153/344 7143/7147/344 7126/7130/344 +# f 7133/7137/345 7135/7139/345 7142/7146/345 7144/7148/345 +# f 7144/7148/346 7143/7147/346 7152/7156/346 7147/7151/346 +# f 7152/7156/347 7123/7127/347 7122/7126/347 7147/7151/347 +# f 7121/7125/348 7103/7110/348 7106/7109/348 7141/7145/348 +# f 7141/7145/349 7106/7109/349 7107/7114/349 7139/7143/349 +# f 7139/7143/350 7107/7114/350 7110/7113/350 7140/7144/350 +# f 7126/7130/326 7142/7146/326 7140/7144/326 7110/7113/326 +# f 7148/7153/388 7149/7152/388 7152/7156/388 7143/7147/388 +# f 7115/7119/352 7129/7133/352 7128/7132/352 7116/7120/352 +# f 7114/7118/389 7130/7134/389 7129/7133/389 7115/7119/389 +# f 7113/7117/354 7131/7135/354 7130/7134/354 7114/7118/354 +# f 7112/7116/390 7132/7136/390 7131/7135/390 7113/7117/390 +# f 7153/7158/356 7154/7159/356 7155/7160/356 7156/7157/356 +# f 7157/7162/357 7158/7163/357 7159/7164/357 7160/7161/357 +# f 7156/7157/226 7155/7160/226 7157/7162/226 7160/7161/226 +# f 7154/7159/281 7158/7163/281 7157/7162/281 7155/7160/281 +# s 1 +# f 7161/7166/358 7162/7167/359 7163/7168/360 7164/7165/361 +# s off +# f 7165/7169/362 7166/7170/362 7154/7159/362 7153/7158/362 +# f 7167/7171/363 7168/7172/363 7159/7164/363 7158/7163/363 +# f 7166/7170/281 7167/7171/281 7158/7163/281 7154/7159/281 +# f 7156/7157/282 7160/7161/282 7159/7164/282 7153/7158/282 +# f 7153/7158/282 7159/7164/282 7168/7172/282 7165/7169/282 +# s 2 +# f 7165/7169/364 7169/7173/365 7166/7170/366 +# f 7170/7174/367 7162/7167/368 7168/7172/369 +# s 1 +# f 7171/7175/370 7172/7176/371 7167/7171/281 7166/7170/281 +# f 7165/7169/282 7168/7172/282 7162/7167/359 7161/7166/358 +# f 7164/7165/361 7173/7177/372 7169/7173/373 7161/7166/358 +# f 7174/7178/374 7175/7179/375 7170/7174/391 7172/7176/371 +# f 7176/7180/377 7174/7178/374 7172/7176/371 7171/7175/370 +# f 7176/7180/377 7171/7175/370 7169/7173/373 7173/7177/372 +# f 7163/7168/360 7162/7167/359 7170/7174/391 7175/7179/375 +# s 2 +# f 7167/7171/378 7172/7176/379 7170/7174/367 +# f 7170/7174/367 7168/7172/369 7167/7171/378 +# f 7165/7169/364 7161/7166/380 7169/7173/365 +# f 7169/7173/365 7171/7175/381 7166/7170/366 +# s off +# f 7177/7183/382 7178/7184/382 7179/7181/382 7180/7182/382 +# f 7181/7188/323 7182/7185/323 7183/7186/323 7184/7187/323 +# f 7185/7192/324 7186/7189/324 7187/7190/324 7188/7191/324 +# f 7189/7193/383 7190/7194/383 7191/7195/383 7192/7196/383 7193/7197/383 7194/7198/383 7195/7199/383 +# f 7189/7193/269 7196/7200/269 7197/7201/269 7198/7202/269 +# f 7181/7188/326 7199/7203/326 7200/7204/326 7201/7205/326 +# f 7182/7185/327 7181/7188/327 7201/7205/327 7202/7206/327 +# f 7203/7207/327 7204/7208/327 7188/7191/327 7187/7190/327 +# f 7205/7209/328 7206/7210/328 7207/7211/328 7208/7212/328 7209/7213/328 7210/7214/328 7198/7202/328 7211/7215/328 7212/7216/328 +# f 7213/7217/329 7211/7215/329 7198/7202/329 7197/7201/329 +# f 7190/7194/330 7189/7193/330 7198/7202/330 7210/7214/330 +# f 7214/7218/331 7205/7209/331 7212/7216/331 7215/7219/331 +# f 7205/7209/268 7214/7218/268 7216/7220/268 7195/7199/268 +# f 7199/7203/226 7214/7218/226 7215/7219/226 7200/7204/226 +# f 7196/7200/332 7217/7221/332 7218/7222/332 7197/7201/332 +# f 7216/7220/260 7219/7223/260 7217/7221/260 7196/7200/260 +# f 7220/7224/226 7213/7217/226 7197/7201/226 7218/7222/226 +# f 7214/7218/268 7199/7203/268 7219/7223/268 7216/7220/268 +# f 7206/7210/333 7205/7209/333 7195/7199/333 7194/7198/333 +# f 7195/7199/384 7216/7220/384 7196/7200/384 7189/7193/384 +# f 7204/7208/335 7221/7225/335 7222/7226/335 7220/7224/335 +# f 7179/7181/336 7178/7184/336 7223/7228/336 7224/7227/336 +# f 7212/7216/337 7211/7215/337 7222/7226/337 7225/7229/337 +# f 7226/7231/338 7203/7207/338 7202/7206/338 7227/7230/338 +# f 7228/7233/386 7177/7183/386 7180/7182/386 7229/7232/386 +# f 7183/7186/340 7186/7189/340 7185/7192/340 7184/7187/340 +# f 7223/7228/341 7228/7233/341 7229/7232/341 7224/7227/341 +# f 7227/7230/342 7202/7206/342 7201/7205/342 7230/7234/342 +# f 7212/7216/343 7225/7229/343 7200/7204/343 7215/7219/343 +# f 7203/7207/344 7226/7231/344 7221/7225/344 7204/7208/344 +# f 7211/7215/345 7213/7217/345 7220/7224/345 7222/7226/345 +# f 7222/7226/346 7221/7225/346 7230/7234/346 7225/7229/346 +# f 7230/7234/347 7201/7205/347 7200/7204/347 7225/7229/347 +# f 7199/7203/348 7181/7188/348 7184/7187/348 7219/7223/348 +# f 7219/7223/349 7184/7187/349 7185/7192/349 7217/7221/349 +# f 7217/7221/350 7185/7192/350 7188/7191/350 7218/7222/350 +# f 7204/7208/326 7220/7224/326 7218/7222/326 7188/7191/326 +# f 7226/7231/351 7227/7230/351 7230/7234/351 7221/7225/351 +# f 7193/7197/352 7207/7211/352 7206/7210/352 7194/7198/352 +# f 7192/7196/392 7208/7212/392 7207/7211/392 7193/7197/392 +# f 7191/7195/354 7209/7213/354 7208/7212/354 7192/7196/354 +# f 7190/7194/355 7210/7214/355 7209/7213/355 7191/7195/355 +# f 7231/7236/356 7232/7237/356 7233/7238/356 7234/7235/356 +# f 7235/7240/357 7236/7241/357 7237/7242/357 7238/7239/357 +# f 7234/7235/226 7233/7238/226 7235/7240/226 7238/7239/226 +# f 7232/7237/281 7236/7241/281 7235/7240/281 7233/7238/281 +# s 1 +# f 7239/7244/393 7240/7245/359 7241/7246/360 7242/7243/394 +# s off +# f 7243/7247/362 7244/7248/362 7232/7237/362 7231/7236/362 +# f 7245/7249/363 7246/7250/363 7237/7242/363 7236/7241/363 +# f 7244/7248/281 7245/7249/281 7236/7241/281 7232/7237/281 +# f 7234/7235/282 7238/7239/282 7237/7242/282 7231/7236/282 +# f 7231/7236/282 7237/7242/282 7246/7250/282 7243/7247/282 +# s 2 +# f 7243/7247/364 7247/7251/365 7244/7248/366 +# f 7248/7252/367 7240/7245/368 7246/7250/369 +# s 1 +# f 7249/7253/395 7250/7254/371 7245/7249/281 7244/7248/281 +# f 7243/7247/282 7246/7250/282 7240/7245/359 7239/7244/393 +# f 7242/7243/394 7251/7255/372 7247/7251/373 7239/7244/393 +# f 7252/7256/374 7253/7257/375 7248/7252/396 7250/7254/371 +# f 7254/7258/377 7252/7256/374 7250/7254/371 7249/7253/395 +# f 7254/7258/377 7249/7253/395 7247/7251/373 7251/7255/372 +# f 7241/7246/360 7240/7245/359 7248/7252/396 7253/7257/375 +# s 2 +# f 7245/7249/378 7250/7254/379 7248/7252/367 +# f 7248/7252/367 7246/7250/369 7245/7249/378 +# f 7243/7247/364 7239/7244/380 7247/7251/365 +# f 7247/7251/365 7249/7253/381 7244/7248/366 +# s off +# f 7255/7261/382 7256/7262/382 7257/7259/382 7258/7260/382 +# f 7259/7266/323 7260/7263/323 7261/7264/323 7262/7265/323 +# f 7263/7270/324 7264/7267/324 7265/7268/324 7266/7269/324 +# f 7267/7271/383 7268/7272/383 7269/7273/383 7270/7274/383 7271/7275/383 7272/7276/383 7273/7277/383 +# f 7267/7271/269 7274/7278/269 7275/7279/269 7276/7280/269 +# f 7259/7266/326 7277/7281/326 7278/7282/326 7279/7283/326 +# f 7260/7263/327 7259/7266/327 7279/7283/327 7280/7284/327 +# f 7281/7285/327 7282/7286/327 7266/7269/327 7265/7268/327 +# f 7283/7287/328 7284/7288/328 7285/7289/328 7286/7290/328 7287/7291/328 7288/7292/328 7276/7280/328 7289/7293/328 7290/7294/328 +# f 7291/7295/331 7289/7293/331 7276/7280/331 7275/7279/331 +# f 7268/7272/330 7267/7271/330 7276/7280/330 7288/7292/330 +# f 7292/7296/329 7283/7287/329 7290/7294/329 7293/7297/329 +# f 7283/7287/268 7292/7296/268 7294/7298/268 7273/7277/268 +# f 7277/7281/226 7292/7296/226 7293/7297/226 7278/7282/226 +# f 7274/7278/332 7295/7299/332 7296/7300/332 7275/7279/332 +# f 7294/7298/260 7297/7301/260 7295/7299/260 7274/7278/260 +# f 7298/7302/226 7291/7295/226 7275/7279/226 7296/7300/226 +# f 7292/7296/268 7277/7281/268 7297/7301/268 7294/7298/268 +# f 7284/7288/333 7283/7287/333 7273/7277/333 7272/7276/333 +# f 7273/7277/384 7294/7298/384 7274/7278/384 7267/7271/384 +# f 7282/7286/335 7299/7303/335 7300/7304/335 7298/7302/335 +# f 7257/7259/336 7256/7262/336 7301/7306/336 7302/7305/336 +# f 7290/7294/337 7289/7293/337 7300/7304/337 7303/7307/337 +# f 7304/7309/385 7281/7285/385 7280/7284/385 7305/7308/385 +# f 7306/7311/386 7255/7261/386 7258/7260/386 7307/7310/386 +# f 7261/7264/340 7264/7267/340 7263/7270/340 7262/7265/340 +# f 7301/7306/341 7306/7311/341 7307/7310/341 7302/7305/341 +# f 7305/7308/387 7280/7284/387 7279/7283/387 7308/7312/387 +# f 7290/7294/343 7303/7307/343 7278/7282/343 7293/7297/343 +# f 7281/7285/344 7304/7309/344 7299/7303/344 7282/7286/344 +# f 7289/7293/345 7291/7295/345 7298/7302/345 7300/7304/345 +# f 7300/7304/346 7299/7303/346 7308/7312/346 7303/7307/346 +# f 7308/7312/347 7279/7283/347 7278/7282/347 7303/7307/347 +# f 7277/7281/348 7259/7266/348 7262/7265/348 7297/7301/348 +# f 7297/7301/349 7262/7265/349 7263/7270/349 7295/7299/349 +# f 7295/7299/350 7263/7270/350 7266/7269/350 7296/7300/350 +# f 7282/7286/326 7298/7302/326 7296/7300/326 7266/7269/326 +# f 7304/7309/388 7305/7308/388 7308/7312/388 7299/7303/388 +# f 7271/7275/352 7285/7289/352 7284/7288/352 7272/7276/352 +# f 7270/7274/389 7286/7290/389 7285/7289/389 7271/7275/389 +# f 7269/7273/354 7287/7291/354 7286/7290/354 7270/7274/354 +# f 7268/7272/390 7288/7292/390 7287/7291/390 7269/7273/390 +# f 7309/7314/356 7310/7315/356 7311/7316/356 7312/7313/356 +# f 7313/7318/357 7314/7319/357 7315/7320/357 7316/7317/357 +# f 7312/7313/226 7311/7316/226 7313/7318/226 7316/7317/226 +# f 7310/7315/281 7314/7319/281 7313/7318/281 7311/7316/281 +# s 1 +# f 7317/7322/358 7318/7323/359 7319/7324/360 7320/7321/361 +# s off +# f 7321/7325/362 7322/7326/362 7310/7315/362 7309/7314/362 +# f 7323/7327/363 7324/7328/363 7315/7320/363 7314/7319/363 +# f 7322/7326/281 7323/7327/281 7314/7319/281 7310/7315/281 +# f 7312/7313/282 7316/7317/282 7315/7320/282 7309/7314/282 +# f 7309/7314/282 7315/7320/282 7324/7328/282 7321/7325/282 +# s 2 +# f 7321/7325/364 7325/7329/365 7322/7326/366 +# f 7326/7330/367 7318/7323/368 7324/7328/369 +# s 1 +# f 7327/7331/370 7328/7332/371 7323/7327/281 7322/7326/281 +# f 7321/7325/282 7324/7328/282 7318/7323/359 7317/7322/358 +# f 7320/7321/361 7329/7333/372 7325/7329/373 7317/7322/358 +# f 7330/7334/374 7331/7335/375 7326/7330/391 7328/7332/371 +# f 7332/7336/377 7330/7334/374 7328/7332/371 7327/7331/370 +# f 7332/7336/377 7327/7331/370 7325/7329/373 7329/7333/372 +# f 7319/7324/360 7318/7323/359 7326/7330/391 7331/7335/375 +# s 2 +# f 7323/7327/378 7328/7332/379 7326/7330/367 +# f 7326/7330/367 7324/7328/369 7323/7327/378 +# f 7321/7325/364 7317/7322/380 7325/7329/365 +# f 7325/7329/365 7327/7331/381 7322/7326/366 +# s off +# f 7026/7029/397 7022/7028/397 7021/7027/397 7027/7030/397 +# f 7022/7028/398 7026/7029/398 7046/7050/398 7047/7051/398 7031/7034/398 7067/7072/398 +# f 7030/7033/399 7027/7030/399 7021/7027/399 7072/7077/399 +# f 7030/7033/400 7072/7077/400 7067/7072/400 7031/7034/400 +# f 7104/7107/401 7100/7106/401 7099/7105/401 7105/7108/401 +# f 7100/7106/402 7104/7107/402 7124/7128/402 7125/7129/402 7109/7112/402 7145/7150/402 +# f 7108/7111/403 7105/7108/403 7099/7105/403 7150/7155/403 +# f 7108/7111/400 7150/7155/400 7145/7150/400 7109/7112/400 +# f 7182/7185/401 7178/7184/401 7177/7183/401 7183/7186/401 +# f 7178/7184/402 7182/7185/402 7202/7206/402 7203/7207/402 7187/7190/402 7223/7228/402 +# f 7186/7189/403 7183/7186/403 7177/7183/403 7228/7233/403 +# f 7186/7189/400 7228/7233/400 7223/7228/400 7187/7190/400 +# f 7260/7263/401 7256/7262/401 7255/7261/401 7261/7264/401 +# f 7256/7262/402 7260/7263/402 7280/7284/402 7281/7285/402 7265/7268/402 7301/7306/402 +# f 7264/7267/403 7261/7264/403 7255/7261/403 7306/7311/403 +# f 7264/7267/400 7306/7311/400 7301/7306/400 7265/7268/400 +# 610 polygons - 40 triangles + +# +# object Filler +# + +v -0.1204 6.1624 2.0358 +v -0.1204 8.3466 2.0358 +v 0.6784 8.3466 2.0358 +v 0.6784 6.1624 2.0358 +v 0.6784 6.1624 2.6289 +v -0.1204 6.1624 2.6289 +v 0.6784 8.3466 2.6289 +v -0.1204 8.3466 2.6289 +v 0.0095 6.9072 1.2368 +v 0.0095 8.1619 1.2368 +v 0.6236 8.1619 1.2368 +v 0.6236 6.9072 1.2368 +v 0.6236 6.9072 2.0815 +v 0.0095 6.9072 2.0815 +v 0.6236 8.1618 2.0815 +v 0.0095 8.1618 2.0815 +# 16 vertices + +vn 0.0000 0.0000 -1.0000 +vn 0.0000 -1.0000 0.0000 +vn 1.0000 0.0000 0.0000 +vn 0.0000 1.0000 0.0000 +vn -1.0000 0.0000 0.0000 +# 5 vertex normals + +vt 0.3078 0.3409 0.0000 +vt 0.3078 0.3409 0.0000 +vt 0.3244 0.3409 0.0000 +vt 0.3244 0.3409 0.0000 +vt 0.3244 0.3580 0.0000 +vt 0.3078 0.3580 0.0000 +vt 0.3244 0.3580 0.0000 +vt 0.3078 0.3580 0.0000 +vt 0.3105 0.3178 0.0000 +vt 0.3105 0.3178 0.0000 +vt 0.3232 0.3178 0.0000 +vt 0.3232 0.3178 0.0000 +vt 0.3232 0.3422 0.0000 +vt 0.3105 0.3422 0.0000 +vt 0.3232 0.3422 0.0000 +vt 0.3105 0.3422 0.0000 +# 16 texture coords + +# g Filler +# usemtl ShippingContainer +# s 2 +# f 7333/7337/404 7334/7338/404 7335/7339/404 7336/7340/404 +# s 8 +# f 7333/7337/405 7336/7340/405 7337/7341/405 7338/7342/405 +# s 16 +# f 7336/7340/406 7335/7339/406 7339/7343/406 7337/7341/406 +# s 32 +# f 7335/7339/407 7334/7338/407 7340/7344/407 7339/7343/407 +# s 64 +# f 7334/7338/408 7333/7337/408 7338/7342/408 7340/7344/408 +# s 2 +# f 7341/7345/404 7342/7346/404 7343/7347/404 7344/7348/404 +# s 8 +# f 7341/7345/405 7344/7348/405 7345/7349/405 7346/7350/405 +# s 16 +# f 7344/7348/406 7343/7347/406 7347/7351/406 7345/7349/406 +# s 32 +# f 7343/7347/407 7342/7346/407 7348/7352/407 7347/7351/407 +# s 64 +# f 7342/7346/408 7341/7345/408 7346/7350/408 7348/7352/408 +# 10 polygons + +# +# object Door_Right +# + +v 1.0952 -3.6297 0.1820 +v 1.1321 -3.6297 0.1820 +v 1.1321 -3.8193 0.1820 +v 1.0952 -3.8193 0.1820 +v 1.0952 -3.6297 2.5888 +v 1.0952 -3.8193 2.5888 +v 1.1321 -3.8193 2.5888 +v 1.1321 -3.6297 2.5888 +v 1.1321 -3.6297 2.5478 +v 1.1321 -3.6297 0.2257 +v 2.2742 -3.8193 0.1820 +v 2.2742 -3.6297 0.1820 +v 2.2742 -3.6297 0.2257 +v 2.2742 -3.8193 0.2257 +v 1.1321 -3.8193 2.5478 +v 1.1321 -3.8193 0.2257 +v 2.2735 -3.8193 2.5888 +v 2.2735 -3.8193 2.5478 +v 2.2735 -3.6297 2.5478 +v 2.2735 -3.6297 2.5888 +v 2.1851 -3.6488 2.5709 +v 2.1851 -3.6488 2.3198 +v 1.2055 -3.6488 2.3198 +v 1.2055 -3.6488 2.5709 +v 2.1851 -3.7163 1.1048 +v 2.1851 -3.7163 1.0053 +v 1.2055 -3.7163 1.0053 +v 1.2055 -3.7163 1.1048 +v 2.1851 -3.7163 1.7643 +v 2.1851 -3.7163 1.6666 +v 1.2055 -3.7163 1.6666 +v 1.2055 -3.7163 1.7643 +v 2.1851 -3.6488 1.6295 +v 2.1851 -3.6488 1.5336 +v 1.2055 -3.6488 1.5336 +v 1.2055 -3.6488 1.6295 +v 2.1851 -3.6488 0.4529 +v 2.1851 -3.6488 0.2061 +v 1.2055 -3.6488 0.2061 +v 1.2055 -3.6488 0.4529 +v 2.1851 -3.7163 0.6102 +v 2.1851 -3.7163 0.5141 +v 1.2055 -3.7163 0.5141 +v 1.2055 -3.7163 0.6102 +v 2.1851 -3.6488 0.9385 +v 2.1851 -3.6488 0.6792 +v 1.2055 -3.6488 0.6792 +v 1.2055 -3.6488 0.9385 +v 2.1851 -3.6488 1.2410 +v 2.1851 -3.6488 1.1430 +v 1.2055 -3.6488 1.1430 +v 1.2055 -3.6488 1.2410 +v 2.1851 -3.7163 1.4923 +v 2.1851 -3.7163 1.2794 +v 1.2055 -3.7163 1.2794 +v 1.2055 -3.7163 1.4923 +v 2.1851 -3.6488 2.0884 +v 2.1851 -3.6488 1.8317 +v 1.2055 -3.6488 1.8317 +v 1.2055 -3.6488 2.0884 +v 2.1851 -3.7163 2.2612 +v 2.1851 -3.7163 2.1574 +v 1.2055 -3.7163 2.1574 +v 1.2055 -3.7163 2.2612 +v 1.2055 -3.6506 2.3207 +v 2.1851 -3.6506 2.3207 +v 2.1851 -3.6508 2.5709 +v 1.2055 -3.6508 2.5709 +v 1.2055 -3.7182 1.0046 +v 2.1851 -3.7182 1.0046 +v 2.1851 -3.7181 1.1058 +v 1.2055 -3.7181 1.1058 +v 1.2055 -3.7181 1.6656 +v 2.1851 -3.7181 1.6656 +v 2.1851 -3.7182 1.7651 +v 1.2055 -3.7182 1.7651 +v 1.2055 -3.6505 1.5346 +v 2.1851 -3.6505 1.5346 +v 2.1851 -3.6505 1.6285 +v 1.2055 -3.6505 1.6285 +v 1.2055 -3.6508 0.2061 +v 2.1851 -3.6508 0.2061 +v 2.1851 -3.6506 0.4521 +v 1.2055 -3.6506 0.4521 +v 1.2055 -3.7182 0.5133 +v 2.1851 -3.7182 0.5133 +v 2.1851 -3.7182 0.6109 +v 1.2055 -3.7182 0.6109 +v 1.2055 -3.6506 0.6799 +v 2.1851 -3.6506 0.6799 +v 2.1851 -3.6506 0.9377 +v 1.2055 -3.6506 0.9377 +v 1.2055 -3.6505 1.1440 +v 2.1851 -3.6505 1.1440 +v 2.1851 -3.6505 1.2400 +v 1.2055 -3.6505 1.2400 +v 1.2055 -3.7181 1.2784 +v 2.1851 -3.7181 1.2784 +v 2.1851 -3.7181 1.4932 +v 1.2055 -3.7181 1.4932 +v 1.2055 -3.6506 1.8325 +v 2.1851 -3.6506 1.8325 +v 2.1851 -3.6506 2.0876 +v 1.2055 -3.6506 2.0876 +v 1.2055 -3.7182 2.1566 +v 2.1851 -3.7182 2.1566 +v 2.1851 -3.7182 2.2620 +v 1.2055 -3.7182 2.2620 +v 1.1303 -3.6363 0.2231 +v 1.2229 -3.6363 0.2231 +v 1.2229 -3.7326 0.2231 +v 1.1303 -3.7326 0.2231 +v 1.1303 -3.6363 2.5520 +v 1.1303 -3.7326 2.5520 +v 1.2229 -3.7326 2.5520 +v 1.2229 -3.6363 2.5520 +v 2.1748 -3.6363 0.2231 +v 2.2741 -3.6363 0.2231 +v 2.2741 -3.7326 0.2231 +v 2.1748 -3.7326 0.2231 +v 2.1748 -3.6363 2.5520 +v 2.1748 -3.7326 2.5520 +v 2.2741 -3.7326 2.5520 +v 2.2741 -3.6363 2.5520 +v 1.9689 -3.6341 1.9075 +v 1.9689 -3.6494 1.9075 +v 1.8817 -3.6494 1.9075 +v 1.8817 -3.6341 1.9075 +v 1.9007 -3.6099 1.9075 +v 1.9499 -3.6099 1.9075 +v 1.9689 -3.6341 1.9732 +v 1.9499 -3.6099 1.9732 +v 1.9007 -3.6099 1.9732 +v 1.8817 -3.6341 1.9732 +v 1.8817 -3.6494 1.9732 +v 1.9689 -3.6494 1.9732 +v 1.9427 -3.5856 1.9075 +v 1.9253 -3.5772 1.9075 +v 1.9253 -3.5772 1.9732 +v 1.9427 -3.5856 1.9732 +v 1.9079 -3.5856 1.9075 +v 1.9079 -3.5856 1.9732 +v 1.9689 -3.6341 2.3917 +v 1.9689 -3.6494 2.3917 +v 1.8817 -3.6494 2.3917 +v 1.8817 -3.6341 2.3917 +v 1.9007 -3.6099 2.3917 +v 1.9499 -3.6099 2.3917 +v 1.9689 -3.6341 2.5261 +v 1.9499 -3.6099 2.5261 +v 1.9007 -3.6099 2.5261 +v 1.8817 -3.6341 2.5261 +v 1.8817 -3.6494 2.5261 +v 1.9689 -3.6494 2.5261 +v 1.9427 -3.5856 2.3917 +v 1.9253 -3.5772 2.3917 +v 1.9253 -3.5772 2.5261 +v 1.9427 -3.5856 2.5261 +v 1.9079 -3.5856 2.3917 +v 1.9079 -3.5856 2.5261 +v 1.6731 -3.6341 2.3917 +v 1.6731 -3.6494 2.3917 +v 1.5859 -3.6494 2.3917 +v 1.5859 -3.6341 2.3917 +v 1.6049 -3.6099 2.3917 +v 1.6541 -3.6099 2.3917 +v 1.6731 -3.6341 2.5261 +v 1.6541 -3.6099 2.5261 +v 1.6049 -3.6099 2.5261 +v 1.5859 -3.6341 2.5261 +v 1.5859 -3.6494 2.5261 +v 1.6731 -3.6494 2.5261 +v 1.6469 -3.5856 2.3917 +v 1.6295 -3.5772 2.3917 +v 1.6295 -3.5772 2.5261 +v 1.6469 -3.5856 2.5261 +v 1.6121 -3.5856 2.3917 +v 1.6121 -3.5856 2.5261 +v 1.6427 -3.6112 0.1624 +v 1.6482 -3.5980 0.1624 +v 1.6482 -3.5980 2.5946 +v 1.6427 -3.6112 2.5946 +v 1.6295 -3.6167 0.1624 +v 1.6295 -3.6167 2.5946 +v 1.6163 -3.6112 0.1624 +v 1.6163 -3.6112 2.5946 +v 1.6108 -3.5980 0.1624 +v 1.6108 -3.5980 2.5946 +v 1.6163 -3.5847 0.1624 +v 1.6163 -3.5847 2.5946 +v 1.6295 -3.5792 0.1624 +v 1.6295 -3.5792 2.5946 +v 1.6427 -3.5847 0.1624 +v 1.6427 -3.5847 2.5946 +v 1.6075 -3.5980 0.0876 +v 1.6139 -3.5824 0.0876 +v 1.6295 -3.5759 0.0876 +v 1.6451 -3.5824 0.0876 +v 1.6515 -3.5980 0.0876 +v 1.6451 -3.6135 0.0876 +v 1.6295 -3.6200 0.0876 +v 1.6139 -3.6135 0.0876 +v 1.6120 -3.6154 2.6725 +v 1.6295 -3.6227 2.6725 +v 1.6470 -3.6154 2.6725 +v 1.6543 -3.5980 2.6725 +v 1.6470 -3.5805 2.6725 +v 1.6295 -3.5732 2.6725 +v 1.6120 -3.5805 2.6725 +v 1.6048 -3.5980 2.6725 +v 1.6470 -3.6154 2.6031 +v 1.6543 -3.5980 2.6031 +v 1.6295 -3.6227 2.6031 +v 1.6120 -3.6154 2.6031 +v 1.6048 -3.5980 2.6031 +v 1.6120 -3.5805 2.6031 +v 1.6295 -3.5732 2.6031 +v 1.6470 -3.5805 2.6031 +v 1.6451 -3.6135 0.1571 +v 1.6515 -3.5980 0.1571 +v 1.6451 -3.5824 0.1571 +v 1.6295 -3.5759 0.1571 +v 1.6139 -3.5824 0.1571 +v 1.6075 -3.5980 0.1571 +v 1.6139 -3.6135 0.1571 +v 1.6295 -3.6200 0.1571 +v 1.9385 -3.6112 0.1624 +v 1.9440 -3.5980 0.1624 +v 1.9440 -3.5980 2.5946 +v 1.9385 -3.6112 2.5946 +v 1.9253 -3.6167 0.1624 +v 1.9253 -3.6167 2.5946 +v 1.9121 -3.6112 0.1624 +v 1.9121 -3.6112 2.5946 +v 1.9066 -3.5980 0.1624 +v 1.9066 -3.5980 2.5946 +v 1.9121 -3.5847 0.1624 +v 1.9121 -3.5847 2.5946 +v 1.9253 -3.5792 0.1624 +v 1.9253 -3.5792 2.5946 +v 1.9385 -3.5847 0.1624 +v 1.9385 -3.5847 2.5946 +v 1.9033 -3.5980 0.0876 +v 1.9097 -3.5824 0.0876 +v 1.9253 -3.5759 0.0876 +v 1.9409 -3.5824 0.0876 +v 1.9473 -3.5980 0.0876 +v 1.9409 -3.6135 0.0876 +v 1.9253 -3.6200 0.0876 +v 1.9097 -3.6135 0.0876 +v 1.9078 -3.6154 2.6725 +v 1.9253 -3.6227 2.6725 +v 1.9428 -3.6154 2.6725 +v 1.9500 -3.5980 2.6725 +v 1.9428 -3.5805 2.6725 +v 1.9253 -3.5732 2.6725 +v 1.9078 -3.5805 2.6725 +v 1.9006 -3.5980 2.6725 +v 1.9428 -3.6154 2.6031 +v 1.9500 -3.5980 2.6031 +v 1.9253 -3.6227 2.6031 +v 1.9078 -3.6154 2.6031 +v 1.9006 -3.5980 2.6031 +v 1.9078 -3.5805 2.6031 +v 1.9253 -3.5732 2.6031 +v 1.9428 -3.5805 2.6031 +v 1.9409 -3.6135 0.1571 +v 1.9473 -3.5980 0.1571 +v 1.9409 -3.5824 0.1571 +v 1.9253 -3.5759 0.1571 +v 1.9097 -3.5824 0.1571 +v 1.9033 -3.5980 0.1571 +v 1.9097 -3.6135 0.1571 +v 1.9253 -3.6200 0.1571 +v 1.6731 -3.6341 1.9075 +v 1.6731 -3.6494 1.9075 +v 1.5859 -3.6494 1.9075 +v 1.5859 -3.6341 1.9075 +v 1.6049 -3.6099 1.9075 +v 1.6541 -3.6099 1.9075 +v 1.6731 -3.6341 1.9732 +v 1.6541 -3.6099 1.9732 +v 1.6049 -3.6099 1.9732 +v 1.5859 -3.6341 1.9732 +v 1.5859 -3.6494 1.9732 +v 1.6731 -3.6494 1.9732 +v 1.6469 -3.5856 1.9075 +v 1.6295 -3.5772 1.9075 +v 1.6295 -3.5772 1.9732 +v 1.6469 -3.5856 1.9732 +v 1.6121 -3.5856 1.9075 +v 1.6121 -3.5856 1.9732 +v 1.9689 -3.6341 0.7872 +v 1.9689 -3.6494 0.7872 +v 1.8817 -3.6494 0.7872 +v 1.8817 -3.6341 0.7872 +v 1.9007 -3.6099 0.7872 +v 1.9499 -3.6099 0.7872 +v 1.9689 -3.6341 0.8529 +v 1.9499 -3.6099 0.8529 +v 1.9007 -3.6099 0.8529 +v 1.8817 -3.6341 0.8529 +v 1.8817 -3.6494 0.8529 +v 1.9689 -3.6494 0.8529 +v 1.9427 -3.5856 0.7872 +v 1.9253 -3.5772 0.7872 +v 1.9253 -3.5772 0.8529 +v 1.9427 -3.5856 0.8529 +v 1.9079 -3.5856 0.7872 +v 1.9079 -3.5856 0.8529 +v 1.6731 -3.6341 0.7872 +v 1.6731 -3.6494 0.7872 +v 1.5859 -3.6494 0.7872 +v 1.5859 -3.6341 0.7872 +v 1.6049 -3.6099 0.7872 +v 1.6541 -3.6099 0.7872 +v 1.6731 -3.6341 0.8529 +v 1.6541 -3.6099 0.8529 +v 1.6049 -3.6099 0.8529 +v 1.5859 -3.6341 0.8529 +v 1.5859 -3.6494 0.8529 +v 1.6731 -3.6494 0.8529 +v 1.6469 -3.5856 0.7872 +v 1.6295 -3.5772 0.7872 +v 1.6295 -3.5772 0.8529 +v 1.6469 -3.5856 0.8529 +v 1.6121 -3.5856 0.7872 +v 1.6121 -3.5856 0.8529 +v 1.6731 -3.6341 0.2305 +v 1.6731 -3.6494 0.2305 +v 1.5859 -3.6494 0.2305 +v 1.5859 -3.6341 0.2305 +v 1.6049 -3.6099 0.2305 +v 1.6541 -3.6099 0.2305 +v 1.6731 -3.6341 0.3650 +v 1.6541 -3.6099 0.3650 +v 1.6049 -3.6099 0.3650 +v 1.5859 -3.6341 0.3650 +v 1.5859 -3.6494 0.3650 +v 1.6731 -3.6494 0.3650 +v 1.6469 -3.5856 0.2305 +v 1.6295 -3.5772 0.2305 +v 1.6295 -3.5772 0.3650 +v 1.6469 -3.5856 0.3650 +v 1.6121 -3.5856 0.2305 +v 1.6121 -3.5856 0.3650 +v 1.9689 -3.6341 0.2305 +v 1.9689 -3.6494 0.2305 +v 1.8817 -3.6494 0.2305 +v 1.8817 -3.6341 0.2305 +v 1.9007 -3.6099 0.2305 +v 1.9499 -3.6099 0.2305 +v 1.9689 -3.6341 0.3650 +v 1.9499 -3.6099 0.3650 +v 1.9007 -3.6099 0.3650 +v 1.8817 -3.6341 0.3650 +v 1.8817 -3.6494 0.3650 +v 1.9689 -3.6494 0.3650 +v 1.9427 -3.5856 0.2305 +v 1.9253 -3.5772 0.2305 +v 1.9253 -3.5772 0.3650 +v 1.9427 -3.5856 0.3650 +v 1.9079 -3.5856 0.2305 +v 1.9079 -3.5856 0.3650 +v 1.6595 -3.6004 1.5502 +v 1.6397 -3.6029 1.5417 +v 1.6397 -3.5932 1.5417 +v 1.6595 -3.5959 1.5502 +v 1.6896 -3.6073 1.5521 +v 1.6896 -3.6118 1.5521 +v 1.6783 -3.6005 1.5502 +v 1.6783 -3.5960 1.5502 +v 1.6896 -3.6118 1.5808 +v 1.6896 -3.6073 1.5808 +v 1.6783 -3.5960 1.5826 +v 1.6783 -3.6005 1.5826 +v 1.8264 -3.6211 1.5765 +v 1.8264 -3.6211 1.5563 +v 1.8812 -3.6166 1.5592 +v 1.8838 -3.6165 1.5627 +v 1.8845 -3.6165 1.5664 +v 1.8838 -3.6165 1.5701 +v 1.8812 -3.6166 1.5737 +v 1.8264 -3.6167 1.5765 +v 1.8187 -3.6221 1.5765 +v 1.8187 -3.6266 1.5765 +v 1.6896 -3.6073 1.5611 +v 1.7412 -3.6221 1.5626 +v 1.7412 -3.6221 1.5563 +v 1.6783 -3.5960 1.5605 +v 1.6783 -3.5960 1.5723 +v 1.6896 -3.6073 1.5717 +v 1.8264 -3.6167 1.5563 +v 1.8264 -3.6167 1.5629 +v 1.8264 -3.6167 1.5699 +v 1.8812 -3.6121 1.5737 +v 1.8838 -3.6120 1.5701 +v 1.8845 -3.6120 1.5664 +v 1.8838 -3.6120 1.5627 +v 1.8812 -3.6121 1.5592 +v 1.8187 -3.6221 1.5703 +v 1.8187 -3.6221 1.5563 +v 1.8187 -3.6221 1.5626 +v 1.8187 -3.6266 1.5563 +v 1.7412 -3.6221 1.5765 +v 1.7412 -3.6266 1.5765 +v 1.7412 -3.6266 1.5563 +v 1.7412 -3.6221 1.5703 +v 1.7444 -3.6168 1.5699 +v 1.6927 -3.5989 1.5713 +v 1.6397 -3.5932 1.5912 +v 1.6595 -3.5959 1.5826 +v 1.7444 -3.6168 1.5629 +v 1.6813 -3.5968 1.5720 +v 1.6813 -3.5968 1.5609 +v 1.6595 -3.6004 1.5826 +v 1.6397 -3.6029 1.5912 +v 1.6927 -3.5989 1.5615 +v 1.7709 -3.6222 1.5486 +v 1.7709 -3.6147 1.5613 +v 1.7906 -3.6147 1.5613 +v 1.7906 -3.6222 1.5486 +v 1.7906 -3.6147 1.5731 +v 1.7709 -3.6147 1.5731 +v 1.7709 -3.6222 1.5859 +v 1.7906 -3.6222 1.5859 +v 1.7709 -3.6436 1.5504 +v 1.7709 -3.6499 1.5497 +v 1.7709 -3.6499 1.5847 +v 1.7709 -3.6436 1.5840 +v 1.7709 -3.6420 1.5590 +v 1.7906 -3.6420 1.5590 +v 1.7906 -3.6420 1.5755 +v 1.7709 -3.6420 1.5755 +v 1.7807 -3.6436 1.5443 +v 1.7807 -3.6436 1.5901 +v 1.7906 -3.6436 1.5504 +v 1.7906 -3.6436 1.5840 +v 1.7807 -3.6499 1.5434 +v 1.7906 -3.6499 1.5847 +v 1.7807 -3.6499 1.5910 +v 1.7906 -3.6499 1.5497 +v 1.6595 -3.6004 1.1792 +v 1.6397 -3.6029 1.1706 +v 1.6397 -3.5932 1.1706 +v 1.6595 -3.5959 1.1792 +v 1.6896 -3.6073 1.1810 +v 1.6896 -3.6118 1.1810 +v 1.6783 -3.6005 1.1792 +v 1.6783 -3.5960 1.1792 +v 1.6896 -3.6118 1.2098 +v 1.6896 -3.6073 1.2098 +v 1.6783 -3.5960 1.2116 +v 1.6783 -3.6005 1.2116 +v 1.8264 -3.6211 1.2055 +v 1.8264 -3.6211 1.1853 +v 1.8812 -3.6166 1.1881 +v 1.8838 -3.6165 1.1917 +v 1.8845 -3.6165 1.1954 +v 1.8838 -3.6165 1.1991 +v 1.8812 -3.6166 1.2026 +v 1.8264 -3.6167 1.2055 +v 1.8187 -3.6221 1.2055 +v 1.8187 -3.6266 1.2055 +v 1.6896 -3.6073 1.1901 +v 1.7412 -3.6221 1.1915 +v 1.7412 -3.6221 1.1853 +v 1.6783 -3.5960 1.1895 +v 1.6783 -3.5960 1.2013 +v 1.6896 -3.6073 1.2007 +v 1.8264 -3.6167 1.1853 +v 1.8264 -3.6167 1.1919 +v 1.8264 -3.6167 1.1989 +v 1.8812 -3.6121 1.2026 +v 1.8838 -3.6120 1.1991 +v 1.8845 -3.6120 1.1954 +v 1.8838 -3.6120 1.1917 +v 1.8812 -3.6121 1.1881 +v 1.8187 -3.6221 1.1993 +v 1.8187 -3.6221 1.1853 +v 1.8187 -3.6221 1.1915 +v 1.8187 -3.6266 1.1853 +v 1.7412 -3.6221 1.2055 +v 1.7412 -3.6266 1.2055 +v 1.7412 -3.6266 1.1853 +v 1.7412 -3.6221 1.1993 +v 1.7444 -3.6168 1.1989 +v 1.6927 -3.5989 1.2003 +v 1.6397 -3.5932 1.2201 +v 1.6595 -3.5959 1.2116 +v 1.7444 -3.6168 1.1919 +v 1.6813 -3.5968 1.2009 +v 1.6813 -3.5968 1.1899 +v 1.6595 -3.6004 1.2116 +v 1.6397 -3.6029 1.2201 +v 1.6927 -3.5989 1.1905 +v 1.7709 -3.6222 1.1775 +v 1.7709 -3.6147 1.1902 +v 1.7906 -3.6147 1.1902 +v 1.7906 -3.6222 1.1775 +v 1.7906 -3.6147 1.2021 +v 1.7709 -3.6147 1.2021 +v 1.7709 -3.6222 1.2148 +v 1.7906 -3.6222 1.2148 +v 1.7709 -3.6436 1.1794 +v 1.7709 -3.6499 1.1787 +v 1.7709 -3.6499 1.2137 +v 1.7709 -3.6436 1.2130 +v 1.7709 -3.6420 1.1879 +v 1.7906 -3.6420 1.1879 +v 1.7906 -3.6420 1.2044 +v 1.7709 -3.6420 1.2044 +v 1.7807 -3.6436 1.1733 +v 1.7807 -3.6436 1.2191 +v 1.7906 -3.6436 1.1794 +v 1.7906 -3.6436 1.2130 +v 1.7807 -3.6499 1.1723 +v 1.7906 -3.6499 1.2137 +v 1.7807 -3.6499 1.2200 +v 1.7906 -3.6499 1.1787 +v 1.9589 -3.6004 1.5502 +v 1.9391 -3.6029 1.5417 +v 1.9391 -3.5932 1.5417 +v 1.9589 -3.5959 1.5502 +v 1.9889 -3.6073 1.5521 +v 1.9889 -3.6118 1.5521 +v 1.9777 -3.6005 1.5502 +v 1.9777 -3.5960 1.5502 +v 1.9889 -3.6118 1.5808 +v 1.9889 -3.6073 1.5808 +v 1.9777 -3.5960 1.5826 +v 1.9777 -3.6005 1.5826 +v 2.1258 -3.6211 1.5765 +v 2.1258 -3.6211 1.5563 +v 2.1806 -3.6166 1.5592 +v 2.1832 -3.6165 1.5627 +v 2.1839 -3.6165 1.5664 +v 2.1832 -3.6165 1.5701 +v 2.1806 -3.6166 1.5737 +v 2.1258 -3.6167 1.5765 +v 2.1180 -3.6221 1.5765 +v 2.1180 -3.6266 1.5765 +v 1.9889 -3.6073 1.5611 +v 2.0406 -3.6221 1.5626 +v 2.0406 -3.6221 1.5563 +v 1.9777 -3.5960 1.5605 +v 1.9777 -3.5960 1.5723 +v 1.9889 -3.6073 1.5717 +v 2.1258 -3.6167 1.5563 +v 2.1257 -3.6167 1.5629 +v 2.1257 -3.6167 1.5699 +v 2.1806 -3.6121 1.5737 +v 2.1832 -3.6120 1.5701 +v 2.1839 -3.6120 1.5664 +v 2.1832 -3.6120 1.5627 +v 2.1806 -3.6121 1.5592 +v 2.1180 -3.6221 1.5703 +v 2.1180 -3.6221 1.5563 +v 2.1180 -3.6221 1.5626 +v 2.1180 -3.6266 1.5563 +v 2.0406 -3.6221 1.5765 +v 2.0406 -3.6266 1.5765 +v 2.0406 -3.6266 1.5563 +v 2.0406 -3.6221 1.5703 +v 2.0437 -3.6168 1.5699 +v 1.9921 -3.5989 1.5713 +v 1.9391 -3.5932 1.5912 +v 1.9589 -3.5959 1.5826 +v 2.0437 -3.6168 1.5629 +v 1.9806 -3.5968 1.5720 +v 1.9806 -3.5968 1.5609 +v 1.9589 -3.6004 1.5826 +v 1.9391 -3.6029 1.5912 +v 1.9921 -3.5989 1.5615 +v 2.0703 -3.6222 1.5486 +v 2.0703 -3.6147 1.5613 +v 2.0900 -3.6147 1.5613 +v 2.0900 -3.6222 1.5486 +v 2.0900 -3.6147 1.5731 +v 2.0703 -3.6147 1.5731 +v 2.0703 -3.6222 1.5859 +v 2.0900 -3.6222 1.5859 +v 2.0703 -3.6436 1.5504 +v 2.0703 -3.6499 1.5497 +v 2.0703 -3.6499 1.5847 +v 2.0703 -3.6436 1.5840 +v 2.0703 -3.6420 1.5590 +v 2.0900 -3.6420 1.5590 +v 2.0900 -3.6420 1.5755 +v 2.0703 -3.6420 1.5755 +v 2.0801 -3.6436 1.5443 +v 2.0801 -3.6436 1.5901 +v 2.0900 -3.6436 1.5504 +v 2.0900 -3.6436 1.5840 +v 2.0801 -3.6499 1.5434 +v 2.0900 -3.6499 1.5847 +v 2.0801 -3.6499 1.5910 +v 2.0900 -3.6499 1.5497 +v 1.9589 -3.6004 1.1792 +v 1.9391 -3.6029 1.1706 +v 1.9391 -3.5932 1.1706 +v 1.9589 -3.5959 1.1792 +v 1.9889 -3.6073 1.1810 +v 1.9889 -3.6118 1.1810 +v 1.9777 -3.6005 1.1792 +v 1.9777 -3.5960 1.1792 +v 1.9889 -3.6118 1.2098 +v 1.9889 -3.6073 1.2098 +v 1.9777 -3.5960 1.2116 +v 1.9777 -3.6005 1.2116 +v 2.1258 -3.6211 1.2055 +v 2.1258 -3.6211 1.1853 +v 2.1806 -3.6166 1.1881 +v 2.1832 -3.6165 1.1917 +v 2.1839 -3.6165 1.1954 +v 2.1832 -3.6165 1.1991 +v 2.1806 -3.6166 1.2026 +v 2.1258 -3.6167 1.2055 +v 2.1180 -3.6221 1.2055 +v 2.1180 -3.6266 1.2055 +v 1.9889 -3.6073 1.1901 +v 2.0406 -3.6221 1.1915 +v 2.0406 -3.6221 1.1853 +v 1.9777 -3.5960 1.1895 +v 1.9777 -3.5960 1.2013 +v 1.9889 -3.6073 1.2007 +v 2.1258 -3.6167 1.1853 +v 2.1257 -3.6167 1.1919 +v 2.1257 -3.6167 1.1989 +v 2.1806 -3.6121 1.2026 +v 2.1832 -3.6120 1.1991 +v 2.1839 -3.6120 1.1954 +v 2.1832 -3.6120 1.1917 +v 2.1806 -3.6121 1.1881 +v 2.1180 -3.6221 1.1993 +v 2.1180 -3.6221 1.1853 +v 2.1180 -3.6221 1.1915 +v 2.1180 -3.6266 1.1853 +v 2.0406 -3.6221 1.2055 +v 2.0406 -3.6266 1.2055 +v 2.0406 -3.6266 1.1853 +v 2.0406 -3.6221 1.1993 +v 2.0437 -3.6168 1.1989 +v 1.9921 -3.5989 1.2003 +v 1.9391 -3.5932 1.2201 +v 1.9589 -3.5959 1.2116 +v 2.0437 -3.6168 1.1919 +v 1.9806 -3.5968 1.2009 +v 1.9806 -3.5968 1.1899 +v 1.9589 -3.6004 1.2116 +v 1.9391 -3.6029 1.2201 +v 1.9921 -3.5989 1.1905 +v 2.0703 -3.6222 1.1775 +v 2.0703 -3.6147 1.1902 +v 2.0900 -3.6147 1.1902 +v 2.0900 -3.6222 1.1775 +v 2.0900 -3.6147 1.2021 +v 2.0703 -3.6147 1.2021 +v 2.0703 -3.6222 1.2148 +v 2.0900 -3.6222 1.2148 +v 2.0703 -3.6436 1.1794 +v 2.0703 -3.6499 1.1787 +v 2.0703 -3.6499 1.2137 +v 2.0703 -3.6436 1.2130 +v 2.0703 -3.6420 1.1879 +v 2.0900 -3.6420 1.1879 +v 2.0900 -3.6420 1.2044 +v 2.0703 -3.6420 1.2044 +v 2.0801 -3.6436 1.1733 +v 2.0801 -3.6436 1.2191 +v 2.0900 -3.6436 1.1794 +v 2.0900 -3.6436 1.2130 +v 2.0801 -3.6499 1.1723 +v 2.0900 -3.6499 1.2137 +v 2.0801 -3.6499 1.2200 +v 2.0900 -3.6499 1.1787 +v 1.0955 -3.6441 2.1936 +v 1.0955 -3.6441 2.2900 +v 1.0876 -3.6632 2.2900 +v 1.0876 -3.6632 2.1936 +v 1.0686 -3.6711 2.2900 +v 1.0686 -3.6711 2.1936 +v 1.0495 -3.6632 2.2900 +v 1.0495 -3.6632 2.1936 +v 1.0416 -3.6441 2.2900 +v 1.0416 -3.6441 2.1936 +v 1.0475 -3.6239 2.2900 +v 1.0475 -3.6239 2.1936 +v 1.0600 -3.6161 2.2900 +v 1.0600 -3.6161 2.1936 +v 1.0743 -3.6153 2.2900 +v 1.0743 -3.6153 2.1936 +v 1.1934 -3.6293 2.1936 +v 1.1821 -3.6252 2.1936 +v 1.1821 -3.6252 2.2900 +v 1.1934 -3.6293 2.2900 +v 1.0975 -3.6213 2.1936 +v 1.0975 -3.6213 2.2900 +v 1.0955 -3.5941 2.2900 +v 1.0955 -3.5941 2.1936 +v 1.1394 -3.6286 2.1936 +v 1.1394 -3.6286 2.2900 +v 1.1380 -3.6084 2.2900 +v 1.1380 -3.6084 2.1936 +v 1.1469 -3.6378 2.1936 +v 1.1469 -3.6378 2.2900 +v 1.1466 -3.6237 2.2900 +v 1.1466 -3.6237 2.1936 +v 1.1978 -3.6385 2.1936 +v 1.1978 -3.6385 2.2900 +v 1.0955 -3.6441 1.6272 +v 1.0955 -3.6441 1.7236 +v 1.0876 -3.6632 1.7236 +v 1.0876 -3.6632 1.6272 +v 1.0686 -3.6711 1.7236 +v 1.0686 -3.6711 1.6272 +v 1.0495 -3.6632 1.7236 +v 1.0495 -3.6632 1.6272 +v 1.0416 -3.6441 1.7236 +v 1.0416 -3.6441 1.6272 +v 1.0475 -3.6239 1.7236 +v 1.0475 -3.6239 1.6272 +v 1.0600 -3.6161 1.7236 +v 1.0600 -3.6161 1.6272 +v 1.0743 -3.6153 1.7236 +v 1.0743 -3.6153 1.6272 +v 1.1934 -3.6293 1.6272 +v 1.1821 -3.6252 1.6272 +v 1.1821 -3.6252 1.7236 +v 1.1934 -3.6293 1.7236 +v 1.0975 -3.6213 1.6272 +v 1.0975 -3.6213 1.7236 +v 1.0955 -3.5941 1.7236 +v 1.0955 -3.5941 1.6272 +v 1.1394 -3.6286 1.6272 +v 1.1394 -3.6286 1.7236 +v 1.1380 -3.6084 1.7236 +v 1.1380 -3.6084 1.6272 +v 1.1469 -3.6378 1.6272 +v 1.1469 -3.6378 1.7236 +v 1.1466 -3.6237 1.7236 +v 1.1466 -3.6237 1.6272 +v 1.1978 -3.6385 1.6272 +v 1.1978 -3.6385 1.7236 +v 1.0955 -3.6441 1.0602 +v 1.0955 -3.6441 1.1566 +v 1.0876 -3.6632 1.1566 +v 1.0876 -3.6632 1.0602 +v 1.0686 -3.6711 1.1566 +v 1.0686 -3.6711 1.0602 +v 1.0495 -3.6632 1.1566 +v 1.0495 -3.6632 1.0602 +v 1.0416 -3.6441 1.1566 +v 1.0416 -3.6441 1.0602 +v 1.0475 -3.6239 1.1566 +v 1.0475 -3.6239 1.0602 +v 1.0600 -3.6161 1.1566 +v 1.0600 -3.6161 1.0602 +v 1.0743 -3.6153 1.1566 +v 1.0743 -3.6153 1.0602 +v 1.1934 -3.6293 1.0602 +v 1.1821 -3.6252 1.0602 +v 1.1821 -3.6252 1.1566 +v 1.1934 -3.6293 1.1566 +v 1.0975 -3.6213 1.0602 +v 1.0975 -3.6213 1.1566 +v 1.0955 -3.5941 1.1566 +v 1.0955 -3.5941 1.0602 +v 1.1394 -3.6286 1.0602 +v 1.1394 -3.6286 1.1566 +v 1.1380 -3.6084 1.1566 +v 1.1380 -3.6084 1.0602 +v 1.1469 -3.6378 1.0602 +v 1.1469 -3.6378 1.1566 +v 1.1466 -3.6237 1.1566 +v 1.1466 -3.6237 1.0602 +v 1.1978 -3.6385 1.0602 +v 1.1978 -3.6385 1.1566 +v 1.0955 -3.6441 0.4938 +v 1.0955 -3.6441 0.5903 +v 1.0876 -3.6632 0.5903 +v 1.0876 -3.6632 0.4938 +v 1.0686 -3.6711 0.5903 +v 1.0686 -3.6711 0.4938 +v 1.0495 -3.6632 0.5903 +v 1.0495 -3.6632 0.4938 +v 1.0416 -3.6441 0.5903 +v 1.0416 -3.6441 0.4938 +v 1.0475 -3.6239 0.5903 +v 1.0475 -3.6239 0.4938 +v 1.0600 -3.6161 0.5903 +v 1.0600 -3.6161 0.4938 +v 1.0743 -3.6153 0.5903 +v 1.0743 -3.6153 0.4938 +v 1.1934 -3.6293 0.4938 +v 1.1821 -3.6252 0.4938 +v 1.1821 -3.6252 0.5903 +v 1.1934 -3.6293 0.5903 +v 1.0975 -3.6213 0.4938 +v 1.0975 -3.6213 0.5903 +v 1.0955 -3.5941 0.5903 +v 1.0955 -3.5941 0.4938 +v 1.1394 -3.6286 0.4938 +v 1.1394 -3.6286 0.5903 +v 1.1380 -3.6084 0.5903 +v 1.1380 -3.6084 0.4938 +v 1.1469 -3.6378 0.4938 +v 1.1469 -3.6378 0.5903 +v 1.1466 -3.6237 0.5903 +v 1.1466 -3.6237 0.4938 +v 1.1978 -3.6385 0.4938 +v 1.1978 -3.6385 0.5903 +# 812 vertices + +vn 0.0000 0.0000 -1.0000 +vn 0.0000 0.0000 1.0000 +vn -0.0000 1.0000 0.0000 +vn 0.0000 1.0000 0.0000 +vn 1.0000 0.0000 0.0000 +vn -0.0000 -1.0000 -0.0000 +vn 0.0000 -1.0000 0.0000 +vn 0.0000 -1.0000 -0.0000 +vn -1.0000 0.0000 0.0000 +vn -0.0000 -1.0000 0.0000 +vn -0.0000 -0.0000 1.0000 +vn 0.0000 1.0000 -0.0000 +vn 0.0000 0.7034 0.7108 +vn 0.0000 0.4923 -0.8704 +vn 0.0000 0.4813 0.8766 +vn 0.0000 0.7062 -0.7080 +vn 0.0000 0.6717 0.7408 +vn 0.0000 0.7143 -0.6998 +vn 0.0000 0.4945 0.8692 +vn 0.0000 0.5216 -0.8532 +vn 0.0000 0.7145 0.6997 +vn 0.0000 0.6554 -0.7553 +vn -0.0000 -1.0000 -0.0007 +vn -0.0000 -1.0000 0.0012 +vn -0.0000 -1.0000 -0.0013 +vn 0.0000 -1.0000 0.0002 +vn 0.0000 -1.0000 0.0007 +vn -0.0000 -1.0000 -0.0002 +vn -0.0000 -1.0000 -0.0001 +vn 0.0000 -1.0000 0.0003 +vn -0.0000 -0.7034 -0.7108 +vn -0.0000 -0.4923 0.8704 +vn -0.0000 -0.4813 -0.8766 +vn -0.0000 -0.7062 0.7080 +vn -0.0000 -0.6717 -0.7409 +vn -0.0000 -0.7143 0.6998 +vn -0.0000 -0.4945 -0.8692 +vn -0.0000 -0.5216 0.8532 +vn 0.0000 -0.7145 -0.6997 +vn -0.0000 -0.6554 0.7553 +vn -0.8889 0.4581 0.0000 +vn -0.7872 0.6167 0.0000 +vn 0.7624 0.6471 0.0000 +vn -0.7624 0.6471 0.0000 +vn 0.8889 0.4581 0.0000 +vn 0.7872 0.6167 0.0000 +vn 0.7071 -0.7071 0.0000 +vn 0.7071 -0.7071 -0.0000 +vn -0.7071 -0.7071 -0.0000 +vn -0.7071 -0.7071 0.0000 +vn -0.7071 0.7071 0.0000 +vn 0.7071 0.7071 0.0000 +vn 0.5778 -0.5778 -0.5764 +vn 0.8172 0.0000 -0.5764 +vn 0.0000 -0.8172 -0.5763 +vn -0.5778 -0.5778 -0.5764 +vn -0.5779 -0.5778 -0.5764 +vn -0.8172 0.0000 -0.5764 +vn -0.8172 -0.0000 -0.5764 +vn -0.5778 0.5778 -0.5764 +vn 0.0000 0.8172 -0.5764 +vn 0.5778 0.5778 -0.5764 +vn 0.8502 0.0000 0.5264 +vn 0.6012 -0.6012 0.5264 +vn 0.6012 0.6012 0.5264 +vn -0.0000 0.8502 0.5264 +vn -0.6012 0.6012 0.5264 +vn -0.8502 -0.0000 0.5264 +vn -0.6012 -0.6012 0.5264 +vn 0.0000 -0.8502 0.5264 +vn 0.9239 -0.3827 0.0000 +vn 0.9239 0.3827 0.0000 +vn 0.3827 0.9239 0.0000 +vn -0.3827 0.9239 0.0000 +vn -0.9239 0.3827 0.0000 +vn -0.9239 -0.3827 0.0000 +vn -0.3827 -0.9239 0.0000 +vn 0.3827 -0.9239 0.0000 +vn 0.3962 0.0000 -0.9182 +vn 0.1605 0.0000 -0.9870 +vn 0.1604 0.0000 0.9871 +vn 0.0811 -0.9967 0.0000 +vn 0.2762 0.9611 0.0000 +vn 0.7073 0.7069 0.0000 +vn -0.0817 0.9967 -0.0000 +vn -0.5766 0.8170 -0.0000 +vn 0.0519 0.0002 0.9987 +vn -0.5766 0.8170 0.0000 +vn -0.0000 0.0000 1.0000 +vn 0.0519 0.0002 -0.9987 +vn 0.5767 -0.8169 0.0000 +vn 0.0392 0.0369 0.9985 +vn 0.1369 0.9906 0.0000 +vn -0.0014 1.0000 0.0000 +vn 0.2460 0.9693 0.0000 +vn 0.1236 -0.9923 0.0000 +vn -0.7073 -0.7069 0.0000 +vn 0.3962 0.0000 0.9182 +vn 0.0757 0.0371 -0.9964 +vn -0.0000 0.0699 -0.9976 +vn 0.0757 0.0371 0.9964 +vn -0.0000 0.0699 0.9976 +vn 0.3278 0.9447 0.0000 +vn 0.0392 0.0369 -0.9985 +vn 0.0823 0.0000 -0.9966 +vn -0.2762 -0.9611 0.0000 +vn 0.0824 0.0000 0.9966 +vn 0.1808 0.9835 0.0000 +vn 0.8076 -0.0002 -0.5897 +vn 0.9843 -0.0002 -0.1768 +vn 0.9844 -0.0002 0.1759 +vn 0.8070 -0.0002 0.5906 +vn 0.0000 0.8604 -0.5096 +vn 0.0000 0.8604 0.5096 +vn -0.8996 0.0470 -0.4341 +vn -0.8590 0.0612 -0.5082 +vn -0.8590 0.0612 0.5082 +vn -0.8996 0.0470 0.4341 +vn 0.0000 -0.4650 -0.8853 +vn 0.0000 -0.4650 0.8853 +vn -0.0433 0.9893 -0.1390 +vn 0.0433 0.9893 -0.1390 +vn -0.0000 0.9897 -0.1428 +vn -0.0000 0.9897 0.1428 +vn -0.0433 0.9893 0.1390 +vn -0.1146 0.9759 0.1855 +vn 0.8996 0.0470 -0.4341 +vn 0.8996 0.0470 0.4341 +vn -0.0000 0.1339 -0.9910 +vn -0.0000 0.1458 -0.9893 +vn 0.8590 0.0612 0.5082 +vn -0.0000 0.1339 0.9910 +vn -0.0000 0.1458 0.9893 +vn 0.8590 0.0612 -0.5082 +vn 0.0433 0.9893 0.1390 +vn 0.1146 0.9759 0.1855 +vn -0.1146 0.9759 -0.1855 +vn 0.1146 0.9759 -0.1855 +vn 0.5767 -0.8170 0.0000 +vn 0.2457 0.9693 0.0000 +vn 0.1237 -0.9923 0.0000 +vn 0.0757 0.0370 -0.9964 +vn 0.1809 0.9835 0.0000 +vn 0.9843 -0.0003 -0.1768 +vn -0.0000 0.1338 -0.9910 +vn -0.8590 0.0612 -0.5083 +vn 0.0000 0.9897 0.1428 +vn 0.0000 0.1339 -0.9910 +vn 0.0000 0.1458 -0.9893 +vn 0.0000 0.1339 0.9910 +vn 0.0000 0.1458 0.9893 +vn 0.8590 0.0612 -0.5083 +vn 0.9842 -0.0003 -0.1768 +vn -0.0433 0.9893 -0.1391 +vn 0.0433 0.9893 -0.1391 +vn -0.0000 0.9897 -0.1429 +vn -0.0000 0.9897 0.1429 +vn -0.0433 0.9893 0.1391 +vn -0.1146 0.9759 0.1856 +vn 0.0433 0.9893 0.1391 +vn 0.1146 0.9759 0.1856 +vn -0.1146 0.9759 -0.1856 +vn 0.1146 0.9759 -0.1856 +vn 0.0012 0.0000 -1.0000 +vn 0.0071 1.0000 0.0000 +vn -0.0072 -1.0000 0.0000 +vn 0.0012 0.0000 1.0000 +vn 0.0072 1.0000 0.0000 +vn -0.9985 -0.0554 0.0000 +vn -0.7981 0.6025 0.0000 +vn -0.3010 0.9536 0.0000 +vn -0.0522 0.9986 0.0000 +vn 0.6738 0.7389 0.0000 +vn 0.3448 0.9387 0.0000 +vn 0.9962 -0.0872 0.0000 +vn -0.7081 0.7062 0.0000 +vn -0.1730 -0.9849 0.0000 +vn 0.3184 0.9480 0.0000 +vn -0.7744 -0.6326 0.0000 +vn 0.8709 0.4915 0.0000 +vn -0.0133 -0.9999 0.0000 +vn 0.0406 0.9992 0.0000 +vn 0.9030 0.4296 0.0000 +# 183 vertex normals + +vt 0.1615 0.3345 0.0000 +vt 0.1623 0.3345 0.0000 +vt 0.1623 0.3345 0.0000 +vt 0.1615 0.3345 0.0000 +vt 0.1615 0.4039 0.0000 +vt 0.1615 0.4039 0.0000 +vt 0.1623 0.4039 0.0000 +vt 0.1623 0.4039 0.0000 +vt 0.1623 0.4027 0.0000 +vt 0.1623 0.3358 0.0000 +vt 0.1860 0.3345 0.0000 +vt 0.1860 0.3358 0.0000 +vt 0.1860 0.3358 0.0000 +vt 0.1860 0.3345 0.0000 +vt 0.1623 0.3358 0.0000 +vt 0.1623 0.4027 0.0000 +vt 0.1860 0.4027 0.0000 +vt 0.1860 0.4027 0.0000 +vt 0.1860 0.4039 0.0000 +vt 0.1860 0.4039 0.0000 +vt 0.1102 0.1509 0.0000 +vt 0.1102 0.1581 0.0000 +vt 0.1306 0.1581 0.0000 +vt 0.1306 0.1509 0.0000 +vt 0.1102 0.1130 0.0000 +vt 0.1102 0.1159 0.0000 +vt 0.1306 0.1159 0.0000 +vt 0.1306 0.1130 0.0000 +vt 0.1102 0.1321 0.0000 +vt 0.1102 0.1349 0.0000 +vt 0.1306 0.1349 0.0000 +vt 0.1306 0.1321 0.0000 +vt 0.1102 0.1282 0.0000 +vt 0.1102 0.1310 0.0000 +vt 0.1306 0.1310 0.0000 +vt 0.1306 0.1282 0.0000 +vt 0.1102 0.0900 0.0000 +vt 0.1102 0.0971 0.0000 +vt 0.1306 0.0971 0.0000 +vt 0.1306 0.0900 0.0000 +vt 0.1102 0.0988 0.0000 +vt 0.1102 0.1016 0.0000 +vt 0.1306 0.1016 0.0000 +vt 0.1306 0.0988 0.0000 +vt 0.1102 0.1036 0.0000 +vt 0.1102 0.1111 0.0000 +vt 0.1306 0.1111 0.0000 +vt 0.1306 0.1036 0.0000 +vt 0.1102 0.1170 0.0000 +vt 0.1102 0.1198 0.0000 +vt 0.1306 0.1198 0.0000 +vt 0.1306 0.1170 0.0000 +vt 0.1102 0.1209 0.0000 +vt 0.1102 0.1270 0.0000 +vt 0.1306 0.1270 0.0000 +vt 0.1306 0.1209 0.0000 +vt 0.1102 0.1368 0.0000 +vt 0.1102 0.1442 0.0000 +vt 0.1306 0.1442 0.0000 +vt 0.1306 0.1368 0.0000 +vt 0.1102 0.1462 0.0000 +vt 0.1102 0.1492 0.0000 +vt 0.1306 0.1492 0.0000 +vt 0.1306 0.1462 0.0000 +vt 0.1306 0.1581 0.0000 +vt 0.1102 0.1581 0.0000 +vt 0.1102 0.1509 0.0000 +vt 0.1306 0.1509 0.0000 +vt 0.1306 0.1159 0.0000 +vt 0.1102 0.1159 0.0000 +vt 0.1102 0.1130 0.0000 +vt 0.1306 0.1130 0.0000 +vt 0.1306 0.1349 0.0000 +vt 0.1102 0.1349 0.0000 +vt 0.1102 0.1320 0.0000 +vt 0.1306 0.1320 0.0000 +vt 0.1306 0.1310 0.0000 +vt 0.1102 0.1310 0.0000 +vt 0.1102 0.1283 0.0000 +vt 0.1306 0.1283 0.0000 +vt 0.1306 0.0971 0.0000 +vt 0.1102 0.0971 0.0000 +vt 0.1102 0.0900 0.0000 +vt 0.1306 0.0900 0.0000 +vt 0.1306 0.1016 0.0000 +vt 0.1102 0.1016 0.0000 +vt 0.1102 0.0988 0.0000 +vt 0.1306 0.0988 0.0000 +vt 0.1306 0.1111 0.0000 +vt 0.1102 0.1111 0.0000 +vt 0.1102 0.1036 0.0000 +vt 0.1306 0.1036 0.0000 +vt 0.1306 0.1198 0.0000 +vt 0.1102 0.1198 0.0000 +vt 0.1102 0.1170 0.0000 +vt 0.1306 0.1170 0.0000 +vt 0.1306 0.1271 0.0000 +vt 0.1102 0.1271 0.0000 +vt 0.1102 0.1209 0.0000 +vt 0.1306 0.1209 0.0000 +vt 0.1306 0.1442 0.0000 +vt 0.1102 0.1442 0.0000 +vt 0.1102 0.1369 0.0000 +vt 0.1306 0.1369 0.0000 +vt 0.1306 0.1492 0.0000 +vt 0.1102 0.1492 0.0000 +vt 0.1102 0.1462 0.0000 +vt 0.1306 0.1462 0.0000 +vt 0.1086 0.0905 0.0000 +vt 0.1106 0.0905 0.0000 +vt 0.1106 0.0905 0.0000 +vt 0.1086 0.0905 0.0000 +vt 0.1086 0.1576 0.0000 +vt 0.1086 0.1576 0.0000 +vt 0.1106 0.1576 0.0000 +vt 0.1106 0.1576 0.0000 +vt 0.1303 0.0905 0.0000 +vt 0.1324 0.0905 0.0000 +vt 0.1324 0.0905 0.0000 +vt 0.1303 0.0905 0.0000 +vt 0.1303 0.1576 0.0000 +vt 0.1303 0.1576 0.0000 +vt 0.1324 0.1576 0.0000 +vt 0.1324 0.1576 0.0000 +vt 0.4223 0.3879 0.0000 +vt 0.4227 0.3879 0.0000 +vt 0.4237 0.3879 0.0000 +vt 0.4241 0.3879 0.0000 +vt 0.4241 0.3879 0.0000 +vt 0.4223 0.3879 0.0000 +vt 0.4223 0.3898 0.0000 +vt 0.4223 0.3898 0.0000 +vt 0.4241 0.3898 0.0000 +vt 0.4241 0.3898 0.0000 +vt 0.4237 0.3898 0.0000 +vt 0.4227 0.3898 0.0000 +vt 0.4232 0.3879 0.0000 +vt 0.4232 0.3898 0.0000 +vt 0.4235 0.3898 0.0000 +vt 0.4235 0.3879 0.0000 +vt 0.4228 0.3879 0.0000 +vt 0.4228 0.3898 0.0000 +vt 0.4223 0.4019 0.0000 +vt 0.4227 0.4019 0.0000 +vt 0.4237 0.4019 0.0000 +vt 0.4241 0.4019 0.0000 +vt 0.4241 0.4019 0.0000 +vt 0.4223 0.4019 0.0000 +vt 0.4223 0.4057 0.0000 +vt 0.4223 0.4057 0.0000 +vt 0.4241 0.4057 0.0000 +vt 0.4241 0.4057 0.0000 +vt 0.4237 0.4057 0.0000 +vt 0.4227 0.4057 0.0000 +vt 0.4232 0.4019 0.0000 +vt 0.4232 0.4057 0.0000 +vt 0.4235 0.4057 0.0000 +vt 0.4235 0.4019 0.0000 +vt 0.4228 0.4019 0.0000 +vt 0.4228 0.4057 0.0000 +vt 0.4161 0.4019 0.0000 +vt 0.4165 0.4019 0.0000 +vt 0.4175 0.4019 0.0000 +vt 0.4179 0.4019 0.0000 +vt 0.4179 0.4019 0.0000 +vt 0.4161 0.4019 0.0000 +vt 0.4161 0.4057 0.0000 +vt 0.4161 0.4057 0.0000 +vt 0.4179 0.4057 0.0000 +vt 0.4179 0.4057 0.0000 +vt 0.4175 0.4057 0.0000 +vt 0.4165 0.4057 0.0000 +vt 0.4170 0.4019 0.0000 +vt 0.4170 0.4057 0.0000 +vt 0.4174 0.4057 0.0000 +vt 0.4174 0.4019 0.0000 +vt 0.4167 0.4019 0.0000 +vt 0.4167 0.4057 0.0000 +vt 0.4174 0.3376 0.0000 +vt 0.4174 0.4077 0.0000 +vt 0.4173 0.4077 0.0000 +vt 0.4173 0.3376 0.0000 +vt 0.4170 0.4077 0.0000 +vt 0.4170 0.3376 0.0000 +vt 0.4168 0.4077 0.0000 +vt 0.4168 0.3376 0.0000 +vt 0.4166 0.4077 0.0000 +vt 0.4166 0.3376 0.0000 +vt 0.4168 0.4077 0.0000 +vt 0.4168 0.3376 0.0000 +vt 0.4170 0.4077 0.0000 +vt 0.4170 0.3376 0.0000 +vt 0.4173 0.4077 0.0000 +vt 0.4173 0.3376 0.0000 +vt 0.4174 0.3354 0.0000 +vt 0.4175 0.3354 0.0000 +vt 0.4174 0.3354 0.0000 +vt 0.4170 0.3354 0.0000 +vt 0.4167 0.3354 0.0000 +vt 0.4166 0.3354 0.0000 +vt 0.4167 0.3354 0.0000 +vt 0.4170 0.3354 0.0000 +vt 0.4175 0.4099 0.0000 +vt 0.4174 0.4099 0.0000 +vt 0.4170 0.4099 0.0000 +vt 0.4167 0.4099 0.0000 +vt 0.4165 0.4099 0.0000 +vt 0.4167 0.4099 0.0000 +vt 0.4170 0.4099 0.0000 +vt 0.4174 0.4099 0.0000 +vt 0.4175 0.4079 0.0000 +vt 0.4174 0.4079 0.0000 +vt 0.4170 0.4079 0.0000 +vt 0.4167 0.4079 0.0000 +vt 0.4165 0.4079 0.0000 +vt 0.4167 0.4079 0.0000 +vt 0.4170 0.4079 0.0000 +vt 0.4174 0.4079 0.0000 +vt 0.4174 0.3374 0.0000 +vt 0.4175 0.3374 0.0000 +vt 0.4174 0.3374 0.0000 +vt 0.4170 0.3374 0.0000 +vt 0.4167 0.3374 0.0000 +vt 0.4166 0.3374 0.0000 +vt 0.4167 0.3374 0.0000 +vt 0.4170 0.3374 0.0000 +vt 0.4236 0.3376 0.0000 +vt 0.4236 0.4077 0.0000 +vt 0.4235 0.4077 0.0000 +vt 0.4235 0.3376 0.0000 +vt 0.4232 0.4077 0.0000 +vt 0.4232 0.3376 0.0000 +vt 0.4229 0.4077 0.0000 +vt 0.4229 0.3376 0.0000 +vt 0.4228 0.4077 0.0000 +vt 0.4228 0.3376 0.0000 +vt 0.4229 0.4077 0.0000 +vt 0.4229 0.3376 0.0000 +vt 0.4232 0.4077 0.0000 +vt 0.4232 0.3376 0.0000 +vt 0.4235 0.4077 0.0000 +vt 0.4235 0.3376 0.0000 +vt 0.4235 0.3354 0.0000 +vt 0.4236 0.3354 0.0000 +vt 0.4235 0.3354 0.0000 +vt 0.4232 0.3354 0.0000 +vt 0.4229 0.3354 0.0000 +vt 0.4227 0.3354 0.0000 +vt 0.4229 0.3354 0.0000 +vt 0.4232 0.3354 0.0000 +vt 0.4237 0.4099 0.0000 +vt 0.4235 0.4099 0.0000 +vt 0.4232 0.4099 0.0000 +vt 0.4228 0.4099 0.0000 +vt 0.4227 0.4099 0.0000 +vt 0.4228 0.4099 0.0000 +vt 0.4232 0.4099 0.0000 +vt 0.4235 0.4099 0.0000 +vt 0.4237 0.4079 0.0000 +vt 0.4235 0.4079 0.0000 +vt 0.4232 0.4079 0.0000 +vt 0.4228 0.4079 0.0000 +vt 0.4227 0.4079 0.0000 +vt 0.4228 0.4079 0.0000 +vt 0.4232 0.4079 0.0000 +vt 0.4235 0.4079 0.0000 +vt 0.4235 0.3374 0.0000 +vt 0.4236 0.3374 0.0000 +vt 0.4235 0.3374 0.0000 +vt 0.4232 0.3374 0.0000 +vt 0.4229 0.3374 0.0000 +vt 0.4227 0.3374 0.0000 +vt 0.4229 0.3374 0.0000 +vt 0.4232 0.3374 0.0000 +vt 0.4161 0.3879 0.0000 +vt 0.4165 0.3879 0.0000 +vt 0.4175 0.3879 0.0000 +vt 0.4179 0.3879 0.0000 +vt 0.4179 0.3879 0.0000 +vt 0.4161 0.3879 0.0000 +vt 0.4161 0.3898 0.0000 +vt 0.4161 0.3898 0.0000 +vt 0.4179 0.3898 0.0000 +vt 0.4179 0.3898 0.0000 +vt 0.4175 0.3898 0.0000 +vt 0.4165 0.3898 0.0000 +vt 0.4170 0.3879 0.0000 +vt 0.4170 0.3898 0.0000 +vt 0.4174 0.3898 0.0000 +vt 0.4174 0.3879 0.0000 +vt 0.4167 0.3879 0.0000 +vt 0.4167 0.3898 0.0000 +vt 0.4223 0.3556 0.0000 +vt 0.4227 0.3556 0.0000 +vt 0.4237 0.3556 0.0000 +vt 0.4241 0.3556 0.0000 +vt 0.4241 0.3556 0.0000 +vt 0.4223 0.3556 0.0000 +vt 0.4223 0.3575 0.0000 +vt 0.4223 0.3575 0.0000 +vt 0.4241 0.3575 0.0000 +vt 0.4241 0.3575 0.0000 +vt 0.4237 0.3575 0.0000 +vt 0.4227 0.3575 0.0000 +vt 0.4232 0.3556 0.0000 +vt 0.4232 0.3575 0.0000 +vt 0.4235 0.3575 0.0000 +vt 0.4235 0.3556 0.0000 +vt 0.4228 0.3556 0.0000 +vt 0.4228 0.3575 0.0000 +vt 0.4161 0.3556 0.0000 +vt 0.4165 0.3556 0.0000 +vt 0.4175 0.3556 0.0000 +vt 0.4179 0.3556 0.0000 +vt 0.4179 0.3556 0.0000 +vt 0.4161 0.3556 0.0000 +vt 0.4161 0.3575 0.0000 +vt 0.4161 0.3575 0.0000 +vt 0.4179 0.3575 0.0000 +vt 0.4179 0.3575 0.0000 +vt 0.4175 0.3575 0.0000 +vt 0.4165 0.3575 0.0000 +vt 0.4170 0.3556 0.0000 +vt 0.4170 0.3575 0.0000 +vt 0.4174 0.3575 0.0000 +vt 0.4174 0.3556 0.0000 +vt 0.4167 0.3556 0.0000 +vt 0.4167 0.3575 0.0000 +vt 0.4161 0.3396 0.0000 +vt 0.4165 0.3396 0.0000 +vt 0.4175 0.3396 0.0000 +vt 0.4179 0.3396 0.0000 +vt 0.4179 0.3396 0.0000 +vt 0.4161 0.3396 0.0000 +vt 0.4161 0.3434 0.0000 +vt 0.4161 0.3434 0.0000 +vt 0.4179 0.3434 0.0000 +vt 0.4179 0.3434 0.0000 +vt 0.4175 0.3434 0.0000 +vt 0.4165 0.3434 0.0000 +vt 0.4170 0.3396 0.0000 +vt 0.4170 0.3434 0.0000 +vt 0.4174 0.3434 0.0000 +vt 0.4174 0.3396 0.0000 +vt 0.4167 0.3396 0.0000 +vt 0.4167 0.3434 0.0000 +vt 0.4223 0.3396 0.0000 +vt 0.4227 0.3396 0.0000 +vt 0.4237 0.3396 0.0000 +vt 0.4241 0.3396 0.0000 +vt 0.4241 0.3396 0.0000 +vt 0.4223 0.3396 0.0000 +vt 0.4223 0.3434 0.0000 +vt 0.4223 0.3434 0.0000 +vt 0.4241 0.3434 0.0000 +vt 0.4241 0.3434 0.0000 +vt 0.4237 0.3434 0.0000 +vt 0.4227 0.3434 0.0000 +vt 0.4232 0.3396 0.0000 +vt 0.4232 0.3434 0.0000 +vt 0.4235 0.3434 0.0000 +vt 0.4235 0.3396 0.0000 +vt 0.4228 0.3396 0.0000 +vt 0.4228 0.3434 0.0000 +vt 0.4172 0.3773 0.0000 +vt 0.4177 0.3776 0.0000 +vt 0.4177 0.3776 0.0000 +vt 0.4172 0.3773 0.0000 +vt 0.4180 0.3776 0.0000 +vt 0.4183 0.3776 0.0000 +vt 0.4183 0.3776 0.0000 +vt 0.4180 0.3776 0.0000 +vt 0.4180 0.3785 0.0000 +vt 0.4183 0.3785 0.0000 +vt 0.4183 0.3785 0.0000 +vt 0.4180 0.3785 0.0000 +vt 0.4211 0.3784 0.0000 +vt 0.4211 0.3778 0.0000 +vt 0.4223 0.3779 0.0000 +vt 0.4223 0.3780 0.0000 +vt 0.4223 0.3781 0.0000 +vt 0.4223 0.3782 0.0000 +vt 0.4223 0.3783 0.0000 +vt 0.4211 0.3784 0.0000 +vt 0.4210 0.3784 0.0000 +vt 0.4210 0.3784 0.0000 +vt 0.4183 0.3779 0.0000 +vt 0.4194 0.3780 0.0000 +vt 0.4194 0.3778 0.0000 +vt 0.4180 0.3779 0.0000 +vt 0.4180 0.3782 0.0000 +vt 0.4183 0.3782 0.0000 +vt 0.4211 0.3778 0.0000 +vt 0.4211 0.3780 0.0000 +vt 0.4211 0.3782 0.0000 +vt 0.4223 0.3783 0.0000 +vt 0.4223 0.3782 0.0000 +vt 0.4223 0.3781 0.0000 +vt 0.4223 0.3780 0.0000 +vt 0.4223 0.3779 0.0000 +vt 0.4210 0.3782 0.0000 +vt 0.4210 0.3778 0.0000 +vt 0.4210 0.3780 0.0000 +vt 0.4210 0.3778 0.0000 +vt 0.4194 0.3784 0.0000 +vt 0.4194 0.3784 0.0000 +vt 0.4194 0.3778 0.0000 +vt 0.4194 0.3782 0.0000 +vt 0.4194 0.3782 0.0000 +vt 0.4183 0.3782 0.0000 +vt 0.4172 0.3788 0.0000 +vt 0.4177 0.3785 0.0000 +vt 0.4194 0.3780 0.0000 +vt 0.4181 0.3782 0.0000 +vt 0.4181 0.3779 0.0000 +vt 0.4172 0.3788 0.0000 +vt 0.4177 0.3785 0.0000 +vt 0.4183 0.3779 0.0000 +vt 0.4200 0.3779 0.0000 +vt 0.4204 0.3779 0.0000 +vt 0.4204 0.3775 0.0000 +vt 0.4200 0.3775 0.0000 +vt 0.4200 0.3783 0.0000 +vt 0.4200 0.3786 0.0000 +vt 0.4204 0.3786 0.0000 +vt 0.4204 0.3783 0.0000 +vt 0.4200 0.3776 0.0000 +vt 0.4200 0.3786 0.0000 +vt 0.4200 0.3786 0.0000 +vt 0.4200 0.3776 0.0000 +vt 0.4204 0.3778 0.0000 +vt 0.4200 0.3778 0.0000 +vt 0.4200 0.3783 0.0000 +vt 0.4204 0.3783 0.0000 +vt 0.4202 0.3774 0.0000 +vt 0.4202 0.3787 0.0000 +vt 0.4204 0.3786 0.0000 +vt 0.4204 0.3776 0.0000 +vt 0.4202 0.3774 0.0000 +vt 0.4202 0.3788 0.0000 +vt 0.4204 0.3786 0.0000 +vt 0.4204 0.3776 0.0000 +vt 0.4172 0.3667 0.0000 +vt 0.4177 0.3669 0.0000 +vt 0.4177 0.3669 0.0000 +vt 0.4172 0.3667 0.0000 +vt 0.4180 0.3669 0.0000 +vt 0.4183 0.3670 0.0000 +vt 0.4183 0.3670 0.0000 +vt 0.4180 0.3669 0.0000 +vt 0.4180 0.3678 0.0000 +vt 0.4183 0.3678 0.0000 +vt 0.4183 0.3678 0.0000 +vt 0.4180 0.3678 0.0000 +vt 0.4211 0.3677 0.0000 +vt 0.4211 0.3671 0.0000 +vt 0.4223 0.3672 0.0000 +vt 0.4223 0.3673 0.0000 +vt 0.4223 0.3674 0.0000 +vt 0.4223 0.3675 0.0000 +vt 0.4223 0.3676 0.0000 +vt 0.4211 0.3677 0.0000 +vt 0.4210 0.3677 0.0000 +vt 0.4210 0.3677 0.0000 +vt 0.4183 0.3672 0.0000 +vt 0.4194 0.3673 0.0000 +vt 0.4194 0.3671 0.0000 +vt 0.4180 0.3672 0.0000 +vt 0.4180 0.3675 0.0000 +vt 0.4183 0.3675 0.0000 +vt 0.4211 0.3671 0.0000 +vt 0.4211 0.3673 0.0000 +vt 0.4211 0.3675 0.0000 +vt 0.4223 0.3676 0.0000 +vt 0.4223 0.3675 0.0000 +vt 0.4223 0.3674 0.0000 +vt 0.4223 0.3673 0.0000 +vt 0.4223 0.3672 0.0000 +vt 0.4210 0.3675 0.0000 +vt 0.4210 0.3671 0.0000 +vt 0.4210 0.3673 0.0000 +vt 0.4210 0.3671 0.0000 +vt 0.4194 0.3677 0.0000 +vt 0.4194 0.3677 0.0000 +vt 0.4194 0.3671 0.0000 +vt 0.4194 0.3675 0.0000 +vt 0.4194 0.3675 0.0000 +vt 0.4183 0.3675 0.0000 +vt 0.4172 0.3681 0.0000 +vt 0.4177 0.3678 0.0000 +vt 0.4194 0.3673 0.0000 +vt 0.4181 0.3675 0.0000 +vt 0.4181 0.3672 0.0000 +vt 0.4172 0.3681 0.0000 +vt 0.4177 0.3678 0.0000 +vt 0.4183 0.3672 0.0000 +vt 0.4200 0.3672 0.0000 +vt 0.4204 0.3672 0.0000 +vt 0.4204 0.3669 0.0000 +vt 0.4200 0.3669 0.0000 +vt 0.4200 0.3676 0.0000 +vt 0.4200 0.3679 0.0000 +vt 0.4204 0.3679 0.0000 +vt 0.4204 0.3676 0.0000 +vt 0.4200 0.3669 0.0000 +vt 0.4200 0.3679 0.0000 +vt 0.4200 0.3679 0.0000 +vt 0.4200 0.3669 0.0000 +vt 0.4204 0.3672 0.0000 +vt 0.4200 0.3672 0.0000 +vt 0.4200 0.3676 0.0000 +vt 0.4204 0.3676 0.0000 +vt 0.4202 0.3667 0.0000 +vt 0.4202 0.3680 0.0000 +vt 0.4204 0.3679 0.0000 +vt 0.4204 0.3669 0.0000 +vt 0.4202 0.3667 0.0000 +vt 0.4202 0.3681 0.0000 +vt 0.4204 0.3679 0.0000 +vt 0.4204 0.3669 0.0000 +vt 0.4235 0.3773 0.0000 +vt 0.4239 0.3776 0.0000 +vt 0.4239 0.3776 0.0000 +vt 0.4235 0.3773 0.0000 +vt 0.4243 0.3776 0.0000 +vt 0.4245 0.3776 0.0000 +vt 0.4245 0.3776 0.0000 +vt 0.4243 0.3776 0.0000 +vt 0.4243 0.3785 0.0000 +vt 0.4245 0.3785 0.0000 +vt 0.4245 0.3785 0.0000 +vt 0.4243 0.3785 0.0000 +vt 0.4273 0.3784 0.0000 +vt 0.4273 0.3778 0.0000 +vt 0.4285 0.3779 0.0000 +vt 0.4285 0.3780 0.0000 +vt 0.4286 0.3781 0.0000 +vt 0.4285 0.3782 0.0000 +vt 0.4285 0.3783 0.0000 +vt 0.4273 0.3784 0.0000 +vt 0.4272 0.3784 0.0000 +vt 0.4272 0.3784 0.0000 +vt 0.4245 0.3779 0.0000 +vt 0.4256 0.3780 0.0000 +vt 0.4256 0.3778 0.0000 +vt 0.4243 0.3779 0.0000 +vt 0.4243 0.3782 0.0000 +vt 0.4245 0.3782 0.0000 +vt 0.4273 0.3778 0.0000 +vt 0.4273 0.3780 0.0000 +vt 0.4273 0.3782 0.0000 +vt 0.4285 0.3783 0.0000 +vt 0.4285 0.3782 0.0000 +vt 0.4286 0.3781 0.0000 +vt 0.4285 0.3780 0.0000 +vt 0.4285 0.3779 0.0000 +vt 0.4272 0.3782 0.0000 +vt 0.4272 0.3778 0.0000 +vt 0.4272 0.3780 0.0000 +vt 0.4272 0.3778 0.0000 +vt 0.4256 0.3784 0.0000 +vt 0.4256 0.3784 0.0000 +vt 0.4256 0.3778 0.0000 +vt 0.4256 0.3782 0.0000 +vt 0.4256 0.3782 0.0000 +vt 0.4246 0.3782 0.0000 +vt 0.4235 0.3788 0.0000 +vt 0.4239 0.3785 0.0000 +vt 0.4256 0.3780 0.0000 +vt 0.4243 0.3782 0.0000 +vt 0.4243 0.3779 0.0000 +vt 0.4235 0.3788 0.0000 +vt 0.4239 0.3785 0.0000 +vt 0.4246 0.3779 0.0000 +vt 0.4262 0.3779 0.0000 +vt 0.4266 0.3779 0.0000 +vt 0.4266 0.3775 0.0000 +vt 0.4262 0.3775 0.0000 +vt 0.4262 0.3783 0.0000 +vt 0.4262 0.3786 0.0000 +vt 0.4266 0.3786 0.0000 +vt 0.4266 0.3783 0.0000 +vt 0.4262 0.3776 0.0000 +vt 0.4262 0.3786 0.0000 +vt 0.4262 0.3786 0.0000 +vt 0.4262 0.3776 0.0000 +vt 0.4266 0.3778 0.0000 +vt 0.4262 0.3778 0.0000 +vt 0.4262 0.3783 0.0000 +vt 0.4266 0.3783 0.0000 +vt 0.4264 0.3774 0.0000 +vt 0.4264 0.3787 0.0000 +vt 0.4266 0.3786 0.0000 +vt 0.4266 0.3776 0.0000 +vt 0.4264 0.3774 0.0000 +vt 0.4264 0.3788 0.0000 +vt 0.4266 0.3786 0.0000 +vt 0.4266 0.3776 0.0000 +vt 0.4235 0.3667 0.0000 +vt 0.4239 0.3669 0.0000 +vt 0.4239 0.3669 0.0000 +vt 0.4235 0.3667 0.0000 +vt 0.4243 0.3669 0.0000 +vt 0.4245 0.3670 0.0000 +vt 0.4245 0.3670 0.0000 +vt 0.4243 0.3669 0.0000 +vt 0.4243 0.3678 0.0000 +vt 0.4245 0.3678 0.0000 +vt 0.4245 0.3678 0.0000 +vt 0.4243 0.3678 0.0000 +vt 0.4273 0.3677 0.0000 +vt 0.4273 0.3671 0.0000 +vt 0.4285 0.3672 0.0000 +vt 0.4285 0.3673 0.0000 +vt 0.4286 0.3674 0.0000 +vt 0.4285 0.3675 0.0000 +vt 0.4285 0.3676 0.0000 +vt 0.4273 0.3677 0.0000 +vt 0.4272 0.3677 0.0000 +vt 0.4272 0.3677 0.0000 +vt 0.4245 0.3672 0.0000 +vt 0.4256 0.3673 0.0000 +vt 0.4256 0.3671 0.0000 +vt 0.4243 0.3672 0.0000 +vt 0.4243 0.3675 0.0000 +vt 0.4245 0.3675 0.0000 +vt 0.4273 0.3671 0.0000 +vt 0.4273 0.3673 0.0000 +vt 0.4273 0.3675 0.0000 +vt 0.4285 0.3676 0.0000 +vt 0.4285 0.3675 0.0000 +vt 0.4286 0.3674 0.0000 +vt 0.4285 0.3673 0.0000 +vt 0.4285 0.3672 0.0000 +vt 0.4272 0.3675 0.0000 +vt 0.4272 0.3671 0.0000 +vt 0.4272 0.3673 0.0000 +vt 0.4272 0.3671 0.0000 +vt 0.4256 0.3677 0.0000 +vt 0.4256 0.3677 0.0000 +vt 0.4256 0.3671 0.0000 +vt 0.4256 0.3675 0.0000 +vt 0.4256 0.3675 0.0000 +vt 0.4246 0.3675 0.0000 +vt 0.4235 0.3681 0.0000 +vt 0.4239 0.3678 0.0000 +vt 0.4256 0.3673 0.0000 +vt 0.4243 0.3675 0.0000 +vt 0.4243 0.3672 0.0000 +vt 0.4235 0.3681 0.0000 +vt 0.4239 0.3678 0.0000 +vt 0.4246 0.3672 0.0000 +vt 0.4262 0.3672 0.0000 +vt 0.4266 0.3672 0.0000 +vt 0.4266 0.3669 0.0000 +vt 0.4262 0.3669 0.0000 +vt 0.4262 0.3676 0.0000 +vt 0.4262 0.3679 0.0000 +vt 0.4266 0.3679 0.0000 +vt 0.4266 0.3676 0.0000 +vt 0.4262 0.3669 0.0000 +vt 0.4262 0.3679 0.0000 +vt 0.4262 0.3679 0.0000 +vt 0.4262 0.3669 0.0000 +vt 0.4266 0.3672 0.0000 +vt 0.4262 0.3672 0.0000 +vt 0.4262 0.3676 0.0000 +vt 0.4266 0.3676 0.0000 +vt 0.4264 0.3667 0.0000 +vt 0.4264 0.3680 0.0000 +vt 0.4266 0.3679 0.0000 +vt 0.4266 0.3669 0.0000 +vt 0.4264 0.3667 0.0000 +vt 0.4264 0.3681 0.0000 +vt 0.4266 0.3679 0.0000 +vt 0.4266 0.3669 0.0000 +vt 0.1079 0.1473 0.0000 +vt 0.1079 0.1500 0.0000 +vt 0.1078 0.1500 0.0000 +vt 0.1078 0.1473 0.0000 +vt 0.1074 0.1500 0.0000 +vt 0.1074 0.1473 0.0000 +vt 0.1070 0.1500 0.0000 +vt 0.1070 0.1473 0.0000 +vt 0.1068 0.1500 0.0000 +vt 0.1068 0.1473 0.0000 +vt 0.1069 0.1500 0.0000 +vt 0.1069 0.1473 0.0000 +vt 0.1072 0.1500 0.0000 +vt 0.1072 0.1473 0.0000 +vt 0.1075 0.1500 0.0000 +vt 0.1075 0.1473 0.0000 +vt 0.1097 0.1473 0.0000 +vt 0.1097 0.1500 0.0000 +vt 0.1100 0.1500 0.0000 +vt 0.1100 0.1473 0.0000 +vt 0.1080 0.1473 0.0000 +vt 0.1080 0.1500 0.0000 +vt 0.1079 0.1500 0.0000 +vt 0.1079 0.1473 0.0000 +vt 0.1088 0.1473 0.0000 +vt 0.1088 0.1500 0.0000 +vt 0.1088 0.1500 0.0000 +vt 0.1088 0.1473 0.0000 +vt 0.1090 0.1473 0.0000 +vt 0.1090 0.1500 0.0000 +vt 0.1090 0.1500 0.0000 +vt 0.1090 0.1473 0.0000 +vt 0.1100 0.1473 0.0000 +vt 0.1100 0.1500 0.0000 +vt 0.1079 0.1309 0.0000 +vt 0.1079 0.1337 0.0000 +vt 0.1078 0.1337 0.0000 +vt 0.1078 0.1309 0.0000 +vt 0.1074 0.1337 0.0000 +vt 0.1074 0.1309 0.0000 +vt 0.1070 0.1337 0.0000 +vt 0.1070 0.1309 0.0000 +vt 0.1068 0.1337 0.0000 +vt 0.1068 0.1309 0.0000 +vt 0.1069 0.1337 0.0000 +vt 0.1069 0.1309 0.0000 +vt 0.1072 0.1337 0.0000 +vt 0.1072 0.1309 0.0000 +vt 0.1075 0.1337 0.0000 +vt 0.1075 0.1309 0.0000 +vt 0.1097 0.1309 0.0000 +vt 0.1097 0.1337 0.0000 +vt 0.1100 0.1337 0.0000 +vt 0.1100 0.1309 0.0000 +vt 0.1080 0.1309 0.0000 +vt 0.1080 0.1337 0.0000 +vt 0.1079 0.1337 0.0000 +vt 0.1079 0.1309 0.0000 +vt 0.1088 0.1309 0.0000 +vt 0.1088 0.1337 0.0000 +vt 0.1088 0.1337 0.0000 +vt 0.1088 0.1309 0.0000 +vt 0.1090 0.1309 0.0000 +vt 0.1090 0.1337 0.0000 +vt 0.1090 0.1337 0.0000 +vt 0.1090 0.1309 0.0000 +vt 0.1100 0.1309 0.0000 +vt 0.1100 0.1337 0.0000 +vt 0.1079 0.1146 0.0000 +vt 0.1079 0.1174 0.0000 +vt 0.1078 0.1174 0.0000 +vt 0.1078 0.1146 0.0000 +vt 0.1074 0.1174 0.0000 +vt 0.1074 0.1146 0.0000 +vt 0.1070 0.1174 0.0000 +vt 0.1070 0.1146 0.0000 +vt 0.1068 0.1174 0.0000 +vt 0.1068 0.1146 0.0000 +vt 0.1069 0.1174 0.0000 +vt 0.1069 0.1146 0.0000 +vt 0.1072 0.1174 0.0000 +vt 0.1072 0.1146 0.0000 +vt 0.1075 0.1174 0.0000 +vt 0.1075 0.1146 0.0000 +vt 0.1097 0.1146 0.0000 +vt 0.1097 0.1174 0.0000 +vt 0.1100 0.1174 0.0000 +vt 0.1100 0.1146 0.0000 +vt 0.1080 0.1146 0.0000 +vt 0.1080 0.1174 0.0000 +vt 0.1079 0.1174 0.0000 +vt 0.1079 0.1146 0.0000 +vt 0.1088 0.1146 0.0000 +vt 0.1088 0.1174 0.0000 +vt 0.1088 0.1174 0.0000 +vt 0.1088 0.1146 0.0000 +vt 0.1090 0.1146 0.0000 +vt 0.1090 0.1174 0.0000 +vt 0.1090 0.1174 0.0000 +vt 0.1090 0.1146 0.0000 +vt 0.1100 0.1146 0.0000 +vt 0.1100 0.1174 0.0000 +vt 0.1079 0.0983 0.0000 +vt 0.1079 0.1010 0.0000 +vt 0.1078 0.1010 0.0000 +vt 0.1078 0.0983 0.0000 +vt 0.1074 0.1010 0.0000 +vt 0.1074 0.0983 0.0000 +vt 0.1070 0.1010 0.0000 +vt 0.1070 0.0983 0.0000 +vt 0.1068 0.1010 0.0000 +vt 0.1068 0.0983 0.0000 +vt 0.1069 0.1010 0.0000 +vt 0.1069 0.0983 0.0000 +vt 0.1072 0.1010 0.0000 +vt 0.1072 0.0983 0.0000 +vt 0.1075 0.1010 0.0000 +vt 0.1075 0.0983 0.0000 +vt 0.1097 0.0983 0.0000 +vt 0.1097 0.1010 0.0000 +vt 0.1100 0.1010 0.0000 +vt 0.1100 0.0983 0.0000 +vt 0.1080 0.0983 0.0000 +vt 0.1080 0.1010 0.0000 +vt 0.1079 0.1010 0.0000 +vt 0.1079 0.0983 0.0000 +vt 0.1088 0.0983 0.0000 +vt 0.1088 0.1010 0.0000 +vt 0.1088 0.1010 0.0000 +vt 0.1088 0.0983 0.0000 +vt 0.1090 0.0983 0.0000 +vt 0.1090 0.1010 0.0000 +vt 0.1090 0.1010 0.0000 +vt 0.1090 0.0983 0.0000 +vt 0.1100 0.0983 0.0000 +vt 0.1100 0.1010 0.0000 +# 812 texture coords + +# g Door_Right +# usemtl ShippingContainer +# s 2 +# f 7349/7353/409 7350/7354/409 7351/7355/409 7352/7356/409 +# s 4 +# f 7353/7357/410 7354/7358/410 7355/7359/410 7356/7360/410 +# s 8 +# f 7349/7353/411 7353/7357/412 7356/7360/412 7357/7361/412 7358/7362/411 7350/7354/412 +# s 16 +# f 7359/7366/413 7360/7363/413 7361/7364/413 7362/7365/413 +# s 32 +# f 7363/7368/414 7355/7359/415 7354/7358/414 7352/7356/416 7351/7355/416 7364/7367/416 +# s 64 +# f 7352/7356/417 7354/7358/417 7353/7357/417 7349/7353/417 +# s 16 +# f 7363/7368/413 7364/7367/413 7358/7362/413 7357/7361/413 +# s off +# f 7350/7354/409 7360/7363/409 7359/7366/409 7351/7355/409 +# f 7351/7355/418 7359/7366/418 7362/7365/418 7364/7367/418 +# f 7364/7367/419 7362/7365/419 7361/7364/419 7358/7362/419 +# f 7358/7362/412 7361/7364/412 7360/7363/412 7350/7354/412 +# s 16 +# f 7365/7372/413 7366/7369/413 7367/7370/413 7368/7371/413 +# s off +# f 7355/7359/410 7365/7372/410 7368/7371/410 7356/7360/410 +# f 7356/7360/412 7368/7371/412 7367/7370/412 7357/7361/412 +# f 7357/7361/409 7367/7370/409 7366/7369/409 7363/7368/409 +# f 7363/7368/415 7366/7369/415 7365/7372/415 7355/7359/415 +# f 7369/7375/420 7370/7376/420 7371/7373/420 7372/7374/420 +# f 7373/7379/412 7374/7380/412 7375/7377/412 7376/7378/412 +# f 7377/7383/420 7378/7384/420 7379/7381/420 7380/7382/420 +# f 7381/7387/412 7382/7388/412 7383/7385/412 7384/7386/412 +# f 7385/7391/420 7386/7392/420 7387/7389/420 7388/7390/420 +# f 7389/7395/412 7390/7396/412 7391/7393/412 7392/7394/412 +# f 7393/7399/412 7394/7400/412 7395/7397/412 7396/7398/412 +# f 7397/7403/420 7398/7404/420 7399/7401/420 7400/7402/420 +# f 7401/7407/412 7402/7408/412 7403/7405/412 7404/7406/412 +# f 7405/7411/420 7406/7412/420 7407/7409/420 7408/7410/420 +# f 7409/7415/412 7410/7416/412 7411/7413/412 7412/7414/412 +# f 7374/7380/421 7393/7399/421 7396/7398/421 7375/7377/421 +# f 7376/7378/422 7399/7401/422 7398/7404/422 7373/7379/422 +# f 7378/7384/423 7381/7387/423 7384/7386/423 7379/7381/423 +# f 7380/7382/424 7407/7409/424 7406/7412/424 7377/7383/424 +# f 7390/7396/425 7385/7391/425 7388/7390/425 7391/7393/425 +# f 7392/7394/426 7395/7397/426 7394/7400/426 7389/7395/426 +# f 7402/7408/427 7397/7403/427 7400/7402/427 7403/7405/427 +# f 7404/7406/428 7383/7385/428 7382/7388/428 7401/7407/428 +# f 7410/7416/429 7405/7411/429 7408/7410/429 7411/7413/429 +# f 7412/7414/430 7371/7373/430 7370/7376/430 7409/7415/430 +# f 7413/7419/431 7414/7420/431 7415/7417/431 7416/7418/431 +# f 7417/7423/432 7418/7424/432 7419/7421/432 7420/7422/432 +# f 7421/7427/433 7422/7428/433 7423/7425/433 7424/7426/433 +# f 7425/7431/434 7426/7432/434 7427/7429/434 7428/7430/434 +# f 7429/7435/435 7430/7436/435 7431/7433/435 7432/7434/435 +# f 7433/7439/436 7434/7440/436 7435/7437/436 7436/7438/436 +# f 7437/7443/418 7438/7444/418 7439/7441/418 7440/7442/418 +# f 7441/7447/414 7442/7448/414 7443/7445/414 7444/7446/414 +# f 7445/7451/437 7446/7452/437 7447/7449/437 7448/7450/437 +# f 7449/7455/414 7450/7456/414 7451/7453/414 7452/7454/414 +# f 7453/7459/438 7454/7460/438 7455/7457/438 7456/7458/438 +# f 7440/7442/439 7439/7441/439 7418/7424/439 7417/7423/439 +# f 7442/7448/440 7441/7447/440 7420/7422/440 7419/7421/440 +# f 7428/7430/441 7427/7429/441 7422/7428/441 7421/7427/441 +# f 7450/7456/442 7449/7455/442 7424/7426/442 7423/7425/442 +# f 7432/7434/443 7431/7433/443 7434/7440/443 7433/7439/443 +# f 7438/7444/444 7437/7443/444 7436/7438/444 7435/7437/444 +# f 7444/7446/445 7443/7445/445 7446/7452/445 7445/7451/445 +# f 7426/7432/446 7425/7431/446 7448/7450/446 7447/7449/446 +# f 7452/7454/447 7451/7453/447 7454/7460/447 7453/7459/447 +# f 7414/7420/448 7413/7419/448 7456/7458/448 7455/7457/448 +# s 2 +# f 7457/7461/409 7458/7462/409 7459/7463/409 7460/7464/409 +# s 4 +# f 7461/7465/410 7462/7466/410 7463/7467/410 7464/7468/410 +# s 8 +# f 7457/7461/412 7461/7465/412 7464/7468/412 7458/7462/412 +# s 16 +# f 7458/7462/413 7464/7468/413 7463/7467/413 7459/7463/413 +# s 32 +# f 7459/7463/415 7463/7467/415 7462/7466/415 7460/7464/415 +# s 64 +# f 7460/7464/417 7462/7466/417 7461/7465/417 7457/7461/417 +# s 2 +# f 7465/7469/409 7466/7470/409 7467/7471/409 7468/7472/409 +# s 4 +# f 7469/7473/410 7470/7474/410 7471/7475/410 7472/7476/410 +# s 8 +# f 7465/7469/412 7469/7473/412 7472/7476/412 7466/7470/412 +# s 16 +# f 7466/7470/413 7472/7476/413 7471/7475/413 7467/7471/413 +# s 32 +# f 7467/7471/416 7471/7475/416 7470/7474/416 7468/7472/416 +# s 64 +# f 7468/7472/417 7470/7474/417 7469/7473/417 7465/7469/417 +# s off +# f 7473/7480/409 7474/7481/409 7475/7482/409 7476/7477/409 7477/7478/409 7478/7479/409 +# f 7479/7486/410 7480/7487/410 7481/7488/410 7482/7483/410 7483/7484/410 7484/7485/410 +# s 1 +# f 7477/7478/449 7476/7477/450 7482/7483/450 7481/7488/449 +# s off +# f 7473/7480/413 7479/7486/413 7484/7485/413 7474/7481/413 +# f 7475/7482/417 7483/7484/417 7482/7483/417 7476/7477/417 +# s 1 +# f 7485/7492/451 7486/7489/412 7487/7490/412 7488/7491/451 +# s off +# f 7485/7492/409 7489/7493/409 7486/7489/409 +# f 7490/7494/410 7488/7491/410 7487/7490/410 +# s 1 +# f 7486/7489/412 7489/7493/452 7490/7494/452 7487/7490/412 +# f 7478/7479/453 7485/7492/451 7488/7491/451 7480/7487/453 +# s off +# f 7485/7492/409 7478/7479/409 7477/7478/409 7489/7493/409 +# f 7490/7494/410 7481/7488/410 7480/7487/410 7488/7491/410 +# s 1 +# f 7489/7493/452 7477/7478/449 7481/7488/449 7490/7494/452 +# f 7473/7480/454 7478/7479/453 7480/7487/453 7479/7486/454 +# s off +# f 7491/7498/409 7492/7499/409 7493/7500/409 7494/7495/409 7495/7496/409 7496/7497/409 +# f 7497/7504/410 7498/7505/410 7499/7506/410 7500/7501/410 7501/7502/410 7502/7503/410 +# s 1 +# f 7495/7496/449 7494/7495/450 7500/7501/450 7499/7506/449 +# s off +# f 7491/7498/413 7497/7504/413 7502/7503/413 7492/7499/413 +# f 7493/7500/417 7501/7502/417 7500/7501/417 7494/7495/417 +# s 1 +# f 7503/7510/451 7504/7507/412 7505/7508/412 7506/7509/451 +# s off +# f 7503/7510/409 7507/7511/409 7504/7507/409 +# f 7508/7512/410 7506/7509/410 7505/7508/410 +# s 1 +# f 7504/7507/412 7507/7511/452 7508/7512/452 7505/7508/412 +# f 7496/7497/453 7503/7510/451 7506/7509/451 7498/7505/453 +# s off +# f 7503/7510/409 7496/7497/409 7495/7496/409 7507/7511/409 +# f 7508/7512/410 7499/7506/410 7498/7505/410 7506/7509/410 +# s 1 +# f 7507/7511/452 7495/7496/449 7499/7506/449 7508/7512/452 +# f 7491/7498/454 7496/7497/453 7498/7505/453 7497/7504/454 +# s off +# f 7509/7516/409 7510/7517/409 7511/7518/409 7512/7513/409 7513/7514/409 7514/7515/409 +# f 7515/7522/410 7516/7523/410 7517/7524/410 7518/7519/410 7519/7520/410 7520/7521/410 +# s 1 +# f 7513/7514/449 7512/7513/450 7518/7519/450 7517/7524/449 +# s off +# f 7509/7516/413 7515/7522/413 7520/7521/413 7510/7517/413 +# f 7511/7518/417 7519/7520/417 7518/7519/417 7512/7513/417 +# s 1 +# f 7521/7528/451 7522/7525/412 7523/7526/412 7524/7527/451 +# s off +# f 7521/7528/409 7525/7529/409 7522/7525/409 +# f 7526/7530/410 7524/7527/410 7523/7526/410 +# s 1 +# f 7522/7525/412 7525/7529/452 7526/7530/452 7523/7526/412 +# f 7514/7515/453 7521/7528/451 7524/7527/451 7516/7523/453 +# s off +# f 7521/7528/409 7514/7515/409 7513/7514/409 7525/7529/409 +# f 7526/7530/410 7517/7524/410 7516/7523/410 7524/7527/410 +# s 1 +# f 7525/7529/452 7513/7514/449 7517/7524/449 7526/7530/452 +# f 7509/7516/454 7514/7515/453 7516/7523/453 7515/7522/454 +# s 8 +# f 7527/7534/455 7528/7531/413 7529/7532/413 7530/7533/456 +# f 7531/7536/416 7527/7534/455 7530/7533/456 7532/7535/416 +# f 7533/7538/457 7531/7536/416 7532/7535/416 7534/7537/458 +# f 7535/7540/417 7533/7538/457 7534/7537/458 7536/7539/417 +# f 7537/7542/459 7535/7540/417 7536/7539/417 7538/7541/459 +# f 7539/7544/412 7537/7542/459 7538/7541/459 7540/7543/412 +# f 7541/7546/460 7539/7544/412 7540/7543/412 7542/7545/460 +# f 7528/7531/413 7541/7546/460 7542/7545/460 7529/7532/413 +# s 1 +# f 7543/7552/409 7544/7553/409 7545/7554/409 7546/7547/409 7547/7548/409 7548/7549/409 7549/7550/409 7550/7551/409 +# f 7551/7560/410 7552/7561/410 7553/7562/410 7554/7555/410 7555/7556/410 7556/7557/410 7557/7558/410 7558/7559/410 +# s 2048 +# f 7559/7564/461 7530/7533/461 7529/7532/462 7560/7563/462 +# f 7561/7565/463 7532/7535/463 7530/7533/461 7559/7564/461 +# f 7562/7566/464 7534/7537/465 7532/7535/463 7561/7565/463 +# f 7563/7567/466 7536/7539/467 7534/7537/465 7562/7566/464 +# f 7564/7568/468 7538/7541/468 7536/7539/467 7563/7567/466 +# f 7565/7569/469 7540/7543/469 7538/7541/468 7564/7568/468 +# f 7566/7570/470 7542/7545/470 7540/7543/469 7565/7569/469 +# f 7560/7563/462 7529/7532/462 7542/7545/470 7566/7570/470 +# s 8 +# f 7553/7562/455 7559/7564/455 7560/7563/413 7554/7555/413 +# f 7552/7561/415 7561/7565/415 7559/7564/455 7553/7562/455 +# f 7551/7560/458 7562/7566/458 7561/7565/415 7552/7561/415 +# f 7558/7559/417 7563/7567/417 7562/7566/458 7551/7560/458 +# f 7557/7558/459 7564/7568/459 7563/7567/417 7558/7559/417 +# f 7556/7557/412 7565/7569/412 7564/7568/459 7557/7558/459 +# f 7555/7556/460 7566/7570/460 7565/7569/412 7556/7557/412 +# f 7554/7555/413 7560/7563/413 7566/7570/460 7555/7556/460 +# s 2048 +# f 7528/7531/471 7527/7534/472 7567/7571/472 7568/7572/471 +# f 7541/7546/473 7528/7531/471 7568/7572/471 7569/7573/473 +# f 7539/7544/474 7541/7546/473 7569/7573/473 7570/7574/474 +# f 7537/7542/475 7539/7544/474 7570/7574/474 7571/7575/475 +# f 7535/7540/476 7537/7542/475 7571/7575/475 7572/7576/476 +# f 7533/7538/477 7535/7540/476 7572/7576/476 7573/7577/477 +# f 7531/7536/478 7533/7538/477 7573/7577/477 7574/7578/478 +# f 7527/7534/472 7531/7536/478 7574/7578/478 7567/7571/472 +# s off +# f 7547/7548/479 7568/7572/479 7567/7571/479 7548/7549/479 +# f 7546/7547/480 7569/7573/480 7568/7572/480 7547/7548/480 +# f 7545/7554/481 7570/7574/481 7569/7573/481 7546/7547/481 +# f 7544/7553/482 7571/7575/482 7570/7574/482 7545/7554/482 +# f 7543/7552/483 7572/7576/483 7571/7575/483 7544/7553/483 +# f 7550/7551/484 7573/7577/484 7572/7576/484 7543/7552/484 +# f 7549/7550/485 7574/7578/485 7573/7577/485 7550/7551/485 +# f 7548/7549/486 7567/7571/486 7574/7578/486 7549/7550/486 +# s 8 +# f 7575/7582/455 7576/7579/413 7577/7580/413 7578/7581/456 +# f 7579/7584/416 7575/7582/455 7578/7581/456 7580/7583/416 +# f 7581/7586/457 7579/7584/416 7580/7583/416 7582/7585/458 +# f 7583/7588/417 7581/7586/457 7582/7585/458 7584/7587/417 +# f 7585/7590/459 7583/7588/417 7584/7587/417 7586/7589/459 +# f 7587/7592/412 7585/7590/459 7586/7589/459 7588/7591/412 +# f 7589/7594/460 7587/7592/412 7588/7591/412 7590/7593/460 +# f 7576/7579/413 7589/7594/460 7590/7593/460 7577/7580/413 +# s 1 +# f 7591/7600/409 7592/7601/409 7593/7602/409 7594/7595/409 7595/7596/409 7596/7597/409 7597/7598/409 7598/7599/409 +# f 7599/7608/410 7600/7609/410 7601/7610/410 7602/7603/410 7603/7604/410 7604/7605/410 7605/7606/410 7606/7607/410 +# s 2048 +# f 7607/7612/461 7578/7581/461 7577/7580/462 7608/7611/462 +# f 7609/7613/463 7580/7583/463 7578/7581/461 7607/7612/461 +# f 7610/7614/464 7582/7585/465 7580/7583/463 7609/7613/463 +# f 7611/7615/466 7584/7587/467 7582/7585/465 7610/7614/464 +# f 7612/7616/468 7586/7589/468 7584/7587/467 7611/7615/466 +# f 7613/7617/469 7588/7591/469 7586/7589/468 7612/7616/468 +# f 7614/7618/470 7590/7593/470 7588/7591/469 7613/7617/469 +# f 7608/7611/462 7577/7580/462 7590/7593/470 7614/7618/470 +# s 8 +# f 7601/7610/455 7607/7612/455 7608/7611/413 7602/7603/413 +# f 7600/7609/415 7609/7613/415 7607/7612/455 7601/7610/455 +# f 7599/7608/458 7610/7614/458 7609/7613/415 7600/7609/415 +# f 7606/7607/417 7611/7615/417 7610/7614/458 7599/7608/458 +# f 7605/7606/459 7612/7616/459 7611/7615/417 7606/7607/417 +# f 7604/7605/412 7613/7617/412 7612/7616/459 7605/7606/459 +# f 7603/7604/460 7614/7618/460 7613/7617/412 7604/7605/412 +# f 7602/7603/413 7608/7611/413 7614/7618/460 7603/7604/460 +# s 2048 +# f 7576/7579/471 7575/7582/472 7615/7619/472 7616/7620/471 +# f 7589/7594/473 7576/7579/471 7616/7620/471 7617/7621/473 +# f 7587/7592/474 7589/7594/473 7617/7621/473 7618/7622/474 +# f 7585/7590/475 7587/7592/474 7618/7622/474 7619/7623/475 +# f 7583/7588/476 7585/7590/475 7619/7623/475 7620/7624/476 +# f 7581/7586/477 7583/7588/476 7620/7624/476 7621/7625/477 +# f 7579/7584/478 7581/7586/477 7621/7625/477 7622/7626/478 +# f 7575/7582/472 7579/7584/478 7622/7626/478 7615/7619/472 +# s off +# f 7595/7596/479 7616/7620/479 7615/7619/479 7596/7597/479 +# f 7594/7595/480 7617/7621/480 7616/7620/480 7595/7596/480 +# f 7593/7602/481 7618/7622/481 7617/7621/481 7594/7595/481 +# f 7592/7601/482 7619/7623/482 7618/7622/482 7593/7602/482 +# f 7591/7600/483 7620/7624/483 7619/7623/483 7592/7601/483 +# f 7598/7599/484 7621/7625/484 7620/7624/484 7591/7600/484 +# f 7597/7598/485 7622/7626/485 7621/7625/485 7598/7599/485 +# f 7596/7597/486 7615/7619/486 7622/7626/486 7597/7598/486 +# f 7623/7630/409 7624/7631/409 7625/7632/409 7626/7627/409 7627/7628/409 7628/7629/409 +# f 7629/7636/410 7630/7637/410 7631/7638/410 7632/7633/410 7633/7634/410 7634/7635/410 +# s 1 +# f 7627/7628/449 7626/7627/450 7632/7633/450 7631/7638/449 +# s off +# f 7623/7630/413 7629/7636/413 7634/7635/413 7624/7631/413 +# f 7625/7632/417 7633/7634/417 7632/7633/417 7626/7627/417 +# s 1 +# f 7635/7642/451 7636/7639/412 7637/7640/412 7638/7641/451 +# s off +# f 7635/7642/409 7639/7643/409 7636/7639/409 +# f 7640/7644/410 7638/7641/410 7637/7640/410 +# s 1 +# f 7636/7639/412 7639/7643/452 7640/7644/452 7637/7640/412 +# f 7628/7629/453 7635/7642/451 7638/7641/451 7630/7637/453 +# s off +# f 7635/7642/409 7628/7629/409 7627/7628/409 7639/7643/409 +# f 7640/7644/410 7631/7638/410 7630/7637/410 7638/7641/410 +# s 1 +# f 7639/7643/452 7627/7628/449 7631/7638/449 7640/7644/452 +# f 7623/7630/454 7628/7629/453 7630/7637/453 7629/7636/454 +# s off +# f 7641/7648/409 7642/7649/409 7643/7650/409 7644/7645/409 7645/7646/409 7646/7647/409 +# f 7647/7654/410 7648/7655/410 7649/7656/410 7650/7651/410 7651/7652/410 7652/7653/410 +# s 1 +# f 7645/7646/449 7644/7645/450 7650/7651/450 7649/7656/449 +# s off +# f 7641/7648/413 7647/7654/413 7652/7653/413 7642/7649/413 +# f 7643/7650/417 7651/7652/417 7650/7651/417 7644/7645/417 +# s 1 +# f 7653/7660/451 7654/7657/412 7655/7658/412 7656/7659/451 +# s off +# f 7653/7660/409 7657/7661/409 7654/7657/409 +# f 7658/7662/410 7656/7659/410 7655/7658/410 +# s 1 +# f 7654/7657/412 7657/7661/452 7658/7662/452 7655/7658/412 +# f 7646/7647/453 7653/7660/451 7656/7659/451 7648/7655/453 +# s off +# f 7653/7660/409 7646/7647/409 7645/7646/409 7657/7661/409 +# f 7658/7662/410 7649/7656/410 7648/7655/410 7656/7659/410 +# s 1 +# f 7657/7661/452 7645/7646/449 7649/7656/449 7658/7662/452 +# f 7641/7648/454 7646/7647/453 7648/7655/453 7647/7654/454 +# s off +# f 7659/7666/409 7660/7667/409 7661/7668/409 7662/7663/409 7663/7664/409 7664/7665/409 +# f 7665/7672/410 7666/7673/410 7667/7674/410 7668/7669/410 7669/7670/410 7670/7671/410 +# s 1 +# f 7663/7664/449 7662/7663/450 7668/7669/450 7667/7674/449 +# s off +# f 7659/7666/413 7665/7672/413 7670/7671/413 7660/7667/413 +# f 7661/7668/417 7669/7670/417 7668/7669/417 7662/7663/417 +# s 1 +# f 7671/7678/451 7672/7675/411 7673/7676/412 7674/7677/451 +# s off +# f 7671/7678/409 7675/7679/409 7672/7675/409 +# f 7676/7680/410 7674/7677/410 7673/7676/410 +# s 1 +# f 7672/7675/411 7675/7679/452 7676/7680/452 7673/7676/412 +# f 7664/7665/453 7671/7678/451 7674/7677/451 7666/7673/453 +# s off +# f 7671/7678/409 7664/7665/409 7663/7664/409 7675/7679/409 +# f 7676/7680/410 7667/7674/410 7666/7673/410 7674/7677/410 +# s 1 +# f 7675/7679/452 7663/7664/449 7667/7674/449 7676/7680/452 +# f 7659/7666/454 7664/7665/453 7666/7673/453 7665/7672/454 +# s off +# f 7677/7684/409 7678/7685/409 7679/7686/409 7680/7681/409 7681/7682/409 7682/7683/409 +# f 7683/7690/410 7684/7691/410 7685/7692/410 7686/7687/410 7687/7688/410 7688/7689/410 +# s 1 +# f 7681/7682/449 7680/7681/450 7686/7687/450 7685/7692/449 +# s off +# f 7677/7684/413 7683/7690/413 7688/7689/413 7678/7685/413 +# f 7679/7686/417 7687/7688/417 7686/7687/417 7680/7681/417 +# s 1 +# f 7689/7696/451 7690/7693/412 7691/7694/412 7692/7695/451 +# s off +# f 7689/7696/409 7693/7697/409 7690/7693/409 +# f 7694/7698/410 7692/7695/410 7691/7694/410 +# s 1 +# f 7690/7693/412 7693/7697/452 7694/7698/452 7691/7694/412 +# f 7682/7683/453 7689/7696/451 7692/7695/451 7684/7691/453 +# s off +# f 7689/7696/409 7682/7683/409 7681/7682/409 7693/7697/409 +# f 7694/7698/410 7685/7692/410 7684/7691/410 7692/7695/410 +# s 1 +# f 7693/7697/452 7681/7682/449 7685/7692/449 7694/7698/452 +# f 7677/7684/454 7682/7683/453 7684/7691/453 7683/7690/454 +# s off +# f 7695/7702/409 7696/7703/409 7697/7704/409 7698/7699/409 7699/7700/409 7700/7701/409 +# f 7701/7708/410 7702/7709/410 7703/7710/410 7704/7705/410 7705/7706/410 7706/7707/410 +# s 1 +# f 7699/7700/449 7698/7699/450 7704/7705/450 7703/7710/449 +# s off +# f 7695/7702/413 7701/7708/413 7706/7707/413 7696/7703/413 +# f 7697/7704/417 7705/7706/417 7704/7705/417 7698/7699/417 +# s 1 +# f 7707/7714/451 7708/7711/412 7709/7712/412 7710/7713/451 +# s off +# f 7707/7714/409 7711/7715/409 7708/7711/409 +# f 7712/7716/410 7710/7713/410 7709/7712/410 +# s 1 +# f 7708/7711/412 7711/7715/452 7712/7716/452 7709/7712/412 +# f 7700/7701/453 7707/7714/451 7710/7713/451 7702/7709/453 +# s off +# f 7707/7714/409 7700/7701/409 7699/7700/409 7711/7715/409 +# f 7712/7716/410 7703/7710/410 7702/7709/410 7710/7713/410 +# s 1 +# f 7711/7715/452 7699/7700/449 7703/7710/449 7712/7716/452 +# f 7695/7702/454 7700/7701/453 7702/7709/453 7701/7708/454 +# s off +# f 7713/7719/487 7714/7720/487 7715/7717/487 7716/7718/487 +# f 7717/7722/488 7718/7723/488 7719/7724/488 7720/7721/488 +# f 7721/7726/489 7722/7727/489 7723/7728/489 7724/7725/489 +# f 7725/7729/490 7726/7730/490 7727/7731/490 7728/7732/490 7729/7733/490 7730/7734/490 7731/7735/490 +# f 7725/7729/410 7732/7736/410 7733/7737/410 7734/7738/410 +# f 7717/7722/491 7735/7739/491 7736/7740/491 7737/7741/491 +# f 7720/7721/492 7738/7742/492 7735/7739/492 7717/7722/492 +# f 7739/7743/492 7723/7728/492 7722/7727/492 7740/7744/492 +# f 7741/7745/493 7742/7746/493 7743/7747/493 7732/7736/493 7744/7748/493 7745/7749/493 7746/7750/493 7747/7751/493 7748/7752/493 +# f 7749/7753/494 7733/7737/494 7732/7736/494 7743/7747/494 +# f 7731/7735/495 7744/7748/495 7732/7736/495 7725/7729/495 +# f 7750/7754/496 7751/7755/496 7742/7746/496 7741/7745/496 +# f 7741/7745/409 7726/7730/409 7752/7756/409 7750/7754/409 +# f 7737/7741/412 7736/7740/412 7751/7755/412 7750/7754/412 +# f 7734/7738/497 7733/7737/497 7753/7757/497 7754/7758/497 +# f 7752/7756/415 7734/7738/415 7754/7758/415 7755/7759/415 +# f 7756/7760/412 7753/7757/412 7733/7737/412 7749/7753/412 +# f 7750/7754/409 7752/7756/409 7755/7759/409 7737/7741/409 +# f 7748/7752/498 7727/7731/498 7726/7730/498 7741/7745/498 +# f 7726/7730/499 7725/7729/499 7734/7738/499 7752/7756/499 +# f 7740/7744/500 7756/7760/500 7757/7761/500 7758/7762/500 +# f 7715/7717/501 7759/7763/501 7760/7764/501 7716/7718/501 +# f 7742/7746/502 7761/7765/502 7757/7761/502 7743/7747/502 +# f 7762/7766/503 7763/7767/503 7738/7742/503 7739/7743/503 +# f 7764/7769/504 7765/7768/504 7714/7720/504 7713/7719/504 +# f 7719/7724/505 7718/7723/505 7721/7726/505 7724/7725/505 +# f 7760/7764/506 7759/7763/506 7765/7768/506 7764/7769/506 +# f 7763/7767/507 7766/7770/507 7735/7739/507 7738/7742/507 +# f 7742/7746/508 7751/7755/508 7736/7740/508 7761/7765/508 +# f 7739/7743/509 7740/7744/509 7758/7762/509 7762/7766/509 +# f 7743/7747/510 7757/7761/510 7756/7760/510 7749/7753/510 +# f 7757/7761/511 7761/7765/511 7766/7770/511 7758/7762/511 +# f 7766/7770/512 7761/7765/512 7736/7740/512 7735/7739/512 +# f 7737/7741/513 7755/7759/513 7718/7723/513 7717/7722/513 +# f 7755/7759/514 7754/7758/514 7721/7726/514 7718/7723/514 +# f 7754/7758/515 7753/7757/515 7722/7727/515 7721/7726/515 +# f 7740/7744/491 7722/7727/491 7753/7757/491 7756/7760/491 +# f 7762/7766/516 7758/7762/516 7766/7770/516 7763/7767/516 +# f 7728/7732/517 7727/7731/517 7748/7752/517 7747/7751/517 +# f 7729/7733/518 7728/7732/518 7747/7751/518 7746/7750/518 +# f 7730/7734/519 7729/7733/519 7746/7750/519 7745/7749/519 +# f 7731/7735/520 7730/7734/520 7745/7749/520 7744/7748/520 +# f 7767/7774/521 7768/7771/521 7769/7772/521 7770/7773/521 +# f 7771/7778/522 7772/7775/522 7773/7776/522 7774/7777/522 +# f 7768/7771/412 7772/7775/412 7771/7778/412 7769/7772/412 +# f 7770/7773/413 7769/7772/413 7771/7778/413 7774/7777/413 +# s 1 +# f 7775/7782/523 7776/7779/524 7777/7780/525 7778/7781/526 +# s off +# f 7779/7784/527 7767/7774/527 7770/7773/527 7780/7783/527 +# f 7781/7786/528 7774/7777/528 7773/7776/528 7782/7785/528 +# f 7780/7783/413 7770/7773/413 7774/7777/413 7781/7786/413 +# f 7768/7771/417 7767/7774/417 7773/7776/417 7772/7775/417 +# f 7767/7774/417 7779/7784/417 7782/7785/417 7773/7776/417 +# s 2 +# f 7779/7784/529 7780/7783/530 7783/7787/531 +# f 7784/7788/532 7782/7785/533 7778/7781/534 +# s 1 +# f 7785/7790/535 7780/7783/413 7781/7786/413 7786/7789/536 +# f 7779/7784/417 7775/7782/523 7778/7781/526 7782/7785/417 +# f 7776/7779/524 7775/7782/523 7783/7787/537 7787/7791/538 +# f 7788/7793/539 7786/7789/536 7784/7788/540 7789/7792/541 +# f 7790/7794/542 7785/7790/535 7786/7789/536 7788/7793/539 +# f 7790/7794/542 7787/7791/538 7783/7787/537 7785/7790/535 +# f 7777/7780/525 7789/7792/541 7784/7788/540 7778/7781/526 +# s 2 +# f 7781/7786/543 7784/7788/532 7786/7789/544 +# f 7784/7788/532 7781/7786/543 7782/7785/533 +# f 7779/7784/529 7783/7787/531 7775/7782/545 +# f 7783/7787/531 7780/7783/530 7785/7790/546 +# s off +# f 7791/7797/487 7792/7798/487 7793/7795/487 7794/7796/487 +# f 7795/7800/488 7796/7801/488 7797/7802/488 7798/7799/488 +# f 7799/7804/489 7800/7805/489 7801/7806/489 7802/7803/489 +# f 7803/7807/490 7804/7808/490 7805/7809/490 7806/7810/490 7807/7811/490 7808/7812/490 7809/7813/490 +# f 7803/7807/410 7810/7814/410 7811/7815/410 7812/7816/410 +# f 7795/7800/491 7813/7817/491 7814/7818/491 7815/7819/491 +# f 7798/7799/492 7816/7820/492 7813/7817/492 7795/7800/492 +# f 7817/7821/492 7801/7806/492 7800/7805/492 7818/7822/492 +# f 7819/7823/493 7820/7824/493 7821/7825/493 7810/7814/493 7822/7826/493 7823/7827/493 7824/7828/493 7825/7829/493 7826/7830/493 +# f 7827/7831/496 7811/7815/496 7810/7814/496 7821/7825/496 +# f 7809/7813/495 7822/7826/495 7810/7814/495 7803/7807/495 +# f 7828/7832/494 7829/7833/494 7820/7824/494 7819/7823/494 +# f 7819/7823/409 7804/7808/409 7830/7834/409 7828/7832/409 +# f 7815/7819/412 7814/7818/412 7829/7833/412 7828/7832/412 +# f 7812/7816/497 7811/7815/497 7831/7835/497 7832/7836/497 +# f 7830/7834/415 7812/7816/415 7832/7836/415 7833/7837/415 +# f 7834/7838/412 7831/7835/412 7811/7815/412 7827/7831/412 +# f 7828/7832/409 7830/7834/409 7833/7837/409 7815/7819/409 +# f 7826/7830/498 7805/7809/498 7804/7808/498 7819/7823/498 +# f 7804/7808/547 7803/7807/547 7812/7816/547 7830/7834/547 +# f 7818/7822/500 7834/7838/500 7835/7839/500 7836/7840/500 +# f 7793/7795/501 7837/7841/501 7838/7842/501 7794/7796/501 +# f 7820/7824/502 7839/7843/502 7835/7839/502 7821/7825/502 +# f 7840/7844/548 7841/7845/548 7816/7820/548 7817/7821/548 +# f 7842/7847/549 7843/7846/549 7792/7798/549 7791/7797/549 +# f 7797/7802/505 7796/7801/505 7799/7804/505 7802/7803/505 +# f 7838/7842/506 7837/7841/506 7843/7846/506 7842/7847/506 +# f 7841/7845/550 7844/7848/550 7813/7817/550 7816/7820/550 +# f 7820/7824/508 7829/7833/508 7814/7818/508 7839/7843/508 +# f 7817/7821/509 7818/7822/509 7836/7840/509 7840/7844/509 +# f 7821/7825/510 7835/7839/510 7834/7838/510 7827/7831/510 +# f 7835/7839/511 7839/7843/511 7844/7848/511 7836/7840/511 +# f 7844/7848/512 7839/7843/512 7814/7818/512 7813/7817/512 +# f 7815/7819/513 7833/7837/513 7796/7801/513 7795/7800/513 +# f 7833/7837/514 7832/7836/514 7799/7804/514 7796/7801/514 +# f 7832/7836/515 7831/7835/515 7800/7805/515 7799/7804/515 +# f 7818/7822/491 7800/7805/491 7831/7835/491 7834/7838/491 +# f 7840/7844/551 7836/7840/551 7844/7848/551 7841/7845/551 +# f 7806/7810/517 7805/7809/517 7826/7830/517 7825/7829/517 +# f 7807/7811/552 7806/7810/552 7825/7829/552 7824/7828/552 +# f 7808/7812/519 7807/7811/519 7824/7828/519 7823/7827/519 +# f 7809/7813/520 7808/7812/520 7823/7827/520 7822/7826/520 +# f 7845/7852/521 7846/7849/521 7847/7850/521 7848/7851/521 +# f 7849/7856/522 7850/7853/522 7851/7854/522 7852/7855/522 +# f 7846/7849/412 7850/7853/412 7849/7856/412 7847/7850/412 +# f 7848/7851/413 7847/7850/413 7849/7856/413 7852/7855/413 +# s 1 +# f 7853/7860/523 7854/7857/524 7855/7858/525 7856/7859/526 +# s off +# f 7857/7862/527 7845/7852/527 7848/7851/527 7858/7861/527 +# f 7859/7864/528 7852/7855/528 7851/7854/528 7860/7863/528 +# f 7858/7861/413 7848/7851/413 7852/7855/413 7859/7864/413 +# f 7846/7849/417 7845/7852/417 7851/7854/417 7850/7853/417 +# f 7845/7852/417 7857/7862/417 7860/7863/417 7851/7854/417 +# s 2 +# f 7857/7862/529 7858/7861/530 7861/7865/531 +# f 7862/7866/532 7860/7863/533 7856/7859/534 +# s 1 +# f 7863/7868/535 7858/7861/413 7859/7864/413 7864/7867/536 +# f 7857/7862/417 7853/7860/523 7856/7859/526 7860/7863/417 +# f 7854/7857/524 7853/7860/523 7861/7865/553 7865/7869/538 +# f 7866/7871/539 7864/7867/536 7862/7866/540 7867/7870/541 +# f 7868/7872/542 7863/7868/535 7864/7867/536 7866/7871/539 +# f 7868/7872/542 7865/7869/538 7861/7865/553 7863/7868/535 +# f 7855/7858/525 7867/7870/541 7862/7866/540 7856/7859/526 +# s 2 +# f 7859/7864/543 7862/7866/532 7864/7867/544 +# f 7862/7866/532 7859/7864/543 7860/7863/533 +# f 7857/7862/529 7861/7865/531 7853/7860/545 +# f 7861/7865/531 7858/7861/530 7863/7868/546 +# s off +# f 7869/7875/487 7870/7876/487 7871/7873/487 7872/7874/487 +# f 7873/7878/488 7874/7879/488 7875/7880/488 7876/7877/488 +# f 7877/7882/489 7878/7883/489 7879/7884/489 7880/7881/489 +# f 7881/7885/490 7882/7886/490 7883/7887/490 7884/7888/490 7885/7889/490 7886/7890/490 7887/7891/490 +# f 7881/7885/410 7888/7892/410 7889/7893/410 7890/7894/410 +# f 7873/7878/491 7891/7895/491 7892/7896/491 7893/7897/491 +# f 7876/7877/492 7894/7898/492 7891/7895/492 7873/7878/492 +# f 7895/7899/492 7879/7884/492 7878/7883/492 7896/7900/492 +# f 7897/7901/493 7898/7902/493 7899/7903/493 7888/7892/493 7900/7904/493 7901/7905/493 7902/7906/493 7903/7907/493 7904/7908/493 +# f 7905/7909/494 7889/7893/494 7888/7892/494 7899/7903/494 +# f 7887/7891/495 7900/7904/495 7888/7892/495 7881/7885/495 +# f 7906/7910/496 7907/7911/496 7898/7902/496 7897/7901/496 +# f 7897/7901/409 7882/7886/409 7908/7912/409 7906/7910/409 +# f 7893/7897/412 7892/7896/412 7907/7911/412 7906/7910/412 +# f 7890/7894/497 7889/7893/497 7909/7913/497 7910/7914/497 +# f 7908/7912/415 7890/7894/415 7910/7914/415 7911/7915/415 +# f 7912/7916/412 7909/7913/412 7889/7893/412 7905/7909/412 +# f 7906/7910/409 7908/7912/409 7911/7915/409 7893/7897/409 +# f 7904/7908/498 7883/7887/498 7882/7886/498 7897/7901/498 +# f 7882/7886/499 7881/7885/499 7890/7894/499 7908/7912/499 +# f 7896/7900/500 7912/7916/500 7913/7917/500 7914/7918/500 +# f 7871/7873/501 7915/7919/501 7916/7920/501 7872/7874/501 +# f 7898/7902/502 7917/7921/502 7913/7917/502 7899/7903/502 +# f 7918/7922/503 7919/7923/503 7894/7898/503 7895/7899/503 +# f 7920/7925/549 7921/7924/549 7870/7876/549 7869/7875/549 +# f 7875/7880/505 7874/7879/505 7877/7882/505 7880/7881/505 +# f 7916/7920/506 7915/7919/506 7921/7924/506 7920/7925/506 +# f 7919/7923/507 7922/7926/507 7891/7895/507 7894/7898/507 +# f 7898/7902/508 7907/7911/508 7892/7896/508 7917/7921/508 +# f 7895/7899/509 7896/7900/509 7914/7918/509 7918/7922/509 +# f 7899/7903/510 7913/7917/510 7912/7916/510 7905/7909/510 +# f 7913/7917/511 7917/7921/511 7922/7926/511 7914/7918/511 +# f 7922/7926/512 7917/7921/512 7892/7896/512 7891/7895/512 +# f 7893/7897/513 7911/7915/513 7874/7879/513 7873/7878/513 +# f 7911/7915/514 7910/7914/514 7877/7882/514 7874/7879/514 +# f 7910/7914/515 7909/7913/515 7878/7883/515 7877/7882/515 +# f 7896/7900/491 7878/7883/491 7909/7913/491 7912/7916/491 +# f 7918/7922/516 7914/7918/516 7922/7926/516 7919/7923/516 +# f 7884/7888/517 7883/7887/517 7904/7908/517 7903/7907/517 +# f 7885/7889/552 7884/7888/552 7903/7907/552 7902/7906/552 +# f 7886/7890/519 7885/7889/519 7902/7906/519 7901/7905/519 +# f 7887/7891/520 7886/7890/520 7901/7905/520 7900/7904/520 +# f 7923/7930/521 7924/7927/521 7925/7928/521 7926/7929/521 +# f 7927/7934/522 7928/7931/522 7929/7932/522 7930/7933/522 +# f 7924/7927/412 7928/7931/412 7927/7934/412 7925/7928/412 +# f 7926/7929/413 7925/7928/413 7927/7934/413 7930/7933/413 +# s 1 +# f 7931/7938/523 7932/7935/554 7933/7936/525 7934/7937/526 +# s off +# f 7935/7940/527 7923/7930/527 7926/7929/527 7936/7939/527 +# f 7937/7942/528 7930/7933/528 7929/7932/528 7938/7941/528 +# f 7936/7939/413 7926/7929/413 7930/7933/413 7937/7942/413 +# f 7924/7927/417 7923/7930/417 7929/7932/417 7928/7931/417 +# f 7923/7930/417 7935/7940/417 7938/7941/417 7929/7932/417 +# s 2 +# f 7935/7940/529 7936/7939/530 7939/7943/531 +# f 7940/7944/555 7938/7941/533 7934/7937/534 +# s 1 +# f 7941/7946/535 7936/7939/413 7937/7942/413 7942/7945/536 +# f 7935/7940/417 7931/7938/523 7934/7937/526 7938/7941/417 +# f 7932/7935/554 7931/7938/523 7939/7943/556 7943/7947/557 +# f 7944/7949/539 7942/7945/536 7940/7944/558 7945/7948/559 +# f 7946/7950/560 7941/7946/535 7942/7945/536 7944/7949/539 +# f 7946/7950/560 7943/7947/557 7939/7943/556 7941/7946/535 +# f 7933/7936/525 7945/7948/559 7940/7944/558 7934/7937/526 +# s 2 +# f 7937/7942/543 7940/7944/555 7942/7945/544 +# f 7940/7944/555 7937/7942/543 7938/7941/533 +# f 7935/7940/529 7939/7943/531 7931/7938/545 +# f 7939/7943/531 7936/7939/530 7941/7946/546 +# s off +# f 7947/7953/487 7948/7954/487 7949/7951/487 7950/7952/487 +# f 7951/7956/488 7952/7957/488 7953/7958/488 7954/7955/488 +# f 7955/7960/489 7956/7961/489 7957/7962/489 7958/7959/489 +# f 7959/7963/490 7960/7964/490 7961/7965/490 7962/7966/490 7963/7967/490 7964/7968/490 7965/7969/490 +# f 7959/7963/410 7966/7970/410 7967/7971/410 7968/7972/410 +# f 7951/7956/491 7969/7973/491 7970/7974/491 7971/7975/491 +# f 7954/7955/492 7972/7976/492 7969/7973/492 7951/7956/492 +# f 7973/7977/492 7957/7962/492 7956/7961/492 7974/7978/492 +# f 7975/7979/493 7976/7980/493 7977/7981/493 7966/7970/493 7978/7982/493 7979/7983/493 7980/7984/493 7981/7985/493 7982/7986/493 +# f 7983/7987/496 7967/7971/496 7966/7970/496 7977/7981/496 +# f 7965/7969/495 7978/7982/495 7966/7970/495 7959/7963/495 +# f 7984/7988/494 7985/7989/494 7976/7980/494 7975/7979/494 +# f 7975/7979/409 7960/7964/409 7986/7990/409 7984/7988/409 +# f 7971/7975/412 7970/7974/412 7985/7989/412 7984/7988/412 +# f 7968/7972/497 7967/7971/497 7987/7991/497 7988/7992/497 +# f 7986/7990/415 7968/7972/415 7988/7992/415 7989/7993/415 +# f 7990/7994/412 7987/7991/412 7967/7971/412 7983/7987/412 +# f 7984/7988/409 7986/7990/409 7989/7993/409 7971/7975/409 +# f 7982/7986/498 7961/7965/498 7960/7964/498 7975/7979/498 +# f 7960/7964/499 7959/7963/499 7968/7972/499 7986/7990/499 +# f 7974/7978/500 7990/7994/500 7991/7995/500 7992/7996/500 +# f 7949/7951/501 7993/7997/501 7994/7998/501 7950/7952/501 +# f 7976/7980/502 7995/7999/502 7991/7995/502 7977/7981/502 +# f 7996/8000/548 7997/8001/548 7972/7976/548 7973/7977/548 +# f 7998/8003/549 7999/8002/549 7948/7954/549 7947/7953/549 +# f 7953/7958/505 7952/7957/505 7955/7960/505 7958/7959/505 +# f 7994/7998/506 7993/7997/506 7999/8002/506 7998/8003/506 +# f 7997/8001/550 8000/8004/550 7969/7973/550 7972/7976/550 +# f 7976/7980/508 7985/7989/508 7970/7974/508 7995/7999/508 +# f 7973/7977/509 7974/7978/509 7992/7996/509 7996/8000/509 +# f 7977/7981/510 7991/7995/510 7990/7994/510 7983/7987/510 +# f 7991/7995/511 7995/7999/511 8000/8004/511 7992/7996/511 +# f 8000/8004/512 7995/7999/512 7970/7974/512 7969/7973/512 +# f 7971/7975/513 7989/7993/513 7952/7957/513 7951/7956/513 +# f 7989/7993/514 7988/7992/514 7955/7960/514 7952/7957/514 +# f 7988/7992/515 7987/7991/515 7956/7961/515 7955/7960/515 +# f 7974/7978/491 7956/7961/491 7987/7991/491 7990/7994/491 +# f 7996/8000/551 7992/7996/551 8000/8004/551 7997/8001/551 +# f 7962/7966/517 7961/7965/517 7982/7986/517 7981/7985/517 +# f 7963/7967/561 7962/7966/561 7981/7985/561 7980/7984/561 +# f 7964/7968/519 7963/7967/519 7980/7984/519 7979/7983/519 +# f 7965/7969/520 7964/7968/520 7979/7983/520 7978/7982/520 +# f 8001/8008/521 8002/8005/521 8003/8006/521 8004/8007/521 +# f 8005/8012/522 8006/8009/522 8007/8010/522 8008/8011/522 +# f 8002/8005/412 8006/8009/412 8005/8012/412 8003/8006/412 +# f 8004/8007/413 8003/8006/413 8005/8012/413 8008/8011/413 +# s 1 +# f 8009/8016/523 8010/8013/524 8011/8014/525 8012/8015/526 +# s off +# f 8013/8018/527 8001/8008/527 8004/8007/527 8014/8017/527 +# f 8015/8020/528 8008/8011/528 8007/8010/528 8016/8019/528 +# f 8014/8017/413 8004/8007/413 8008/8011/413 8015/8020/413 +# f 8002/8005/417 8001/8008/417 8007/8010/417 8006/8009/417 +# f 8001/8008/417 8013/8018/417 8016/8019/417 8007/8010/417 +# s 2 +# f 8013/8018/562 8014/8017/563 8017/8021/564 +# f 8018/8022/565 8016/8019/566 8012/8015/567 +# s 1 +# f 8019/8024/535 8014/8017/413 8015/8020/413 8020/8023/536 +# f 8013/8018/417 8009/8016/523 8012/8015/526 8016/8019/417 +# f 8010/8013/524 8009/8016/523 8017/8021/556 8021/8025/557 +# f 8022/8027/539 8020/8023/536 8018/8022/558 8023/8026/559 +# f 8024/8028/542 8019/8024/535 8020/8023/536 8022/8027/539 +# f 8024/8028/542 8021/8025/557 8017/8021/556 8019/8024/535 +# f 8011/8014/525 8023/8026/559 8018/8022/558 8012/8015/526 +# s 2 +# f 8015/8020/568 8018/8022/565 8020/8023/569 +# f 8018/8022/565 8015/8020/568 8016/8019/566 +# f 8013/8018/562 8017/8021/564 8009/8016/570 +# f 8017/8021/564 8014/8017/563 8019/8024/571 +# s off +# f 7720/7721/572 7719/7724/572 7713/7719/572 7716/7718/572 +# f 7716/7718/573 7760/7764/573 7723/7728/573 7739/7743/573 7738/7742/573 7720/7721/573 +# f 7724/7725/574 7764/7769/574 7713/7719/574 7719/7724/574 +# f 7724/7725/575 7723/7728/575 7760/7764/575 7764/7769/575 +# f 7798/7799/572 7797/7802/572 7791/7797/572 7794/7796/572 +# f 7794/7796/576 7838/7842/576 7801/7806/576 7817/7821/576 7816/7820/576 7798/7799/576 +# f 7802/7803/574 7842/7847/574 7791/7797/574 7797/7802/574 +# f 7802/7803/575 7801/7806/575 7838/7842/575 7842/7847/575 +# f 7876/7877/572 7875/7880/572 7869/7875/572 7872/7874/572 +# f 7872/7874/576 7916/7920/576 7879/7884/576 7895/7899/576 7894/7898/576 7876/7877/576 +# f 7880/7881/574 7920/7925/574 7869/7875/574 7875/7880/574 +# f 7880/7881/575 7879/7884/575 7916/7920/575 7920/7925/575 +# f 7954/7955/572 7953/7958/572 7947/7953/572 7950/7952/572 +# f 7950/7952/576 7994/7998/576 7957/7962/576 7973/7977/576 7972/7976/576 7954/7955/576 +# f 7958/7959/574 7998/8003/574 7947/7953/574 7953/7958/574 +# f 7958/7959/575 7957/7962/575 7994/7998/575 7998/8003/575 +# s 8 +# f 8025/8029/479 8026/8030/479 8027/8031/455 8028/8032/455 +# f 8028/8032/455 8027/8031/455 8029/8033/418 8030/8034/418 +# f 8030/8034/418 8029/8033/418 8031/8035/458 8032/8036/458 +# f 8032/8036/458 8031/8035/458 8033/8037/577 8034/8038/577 +# f 8034/8038/577 8033/8037/577 8035/8039/578 8036/8040/578 +# f 8036/8040/578 8035/8039/578 8037/8041/579 8038/8042/579 +# f 8038/8042/579 8037/8041/579 8039/8043/580 8040/8044/580 +# f 8041/8048/581 8042/8045/582 8043/8046/582 8044/8047/581 +# s 1 +# f 8034/8038/409 8036/8040/409 8038/8042/409 8040/8044/409 8025/8029/409 8028/8032/409 8030/8034/409 8032/8036/409 +# f 8031/8035/410 8029/8033/410 8027/8031/410 8026/8030/410 8039/8043/410 8037/8041/410 8035/8039/410 8033/8037/410 +# s off +# f 8025/8029/583 8045/8049/583 8046/8050/583 8026/8030/583 +# f 8026/8030/410 8046/8050/410 8047/8051/410 8039/8043/410 +# f 8039/8043/584 8047/8051/584 8048/8052/584 8040/8044/584 +# f 8040/8044/409 8048/8052/409 8045/8049/409 8025/8029/409 +# f 8045/8049/585 8049/8053/585 8050/8054/585 8046/8050/585 +# f 8046/8050/410 8050/8054/410 8051/8055/410 8047/8051/410 +# f 8047/8051/586 8051/8055/586 8052/8056/586 8048/8052/586 +# f 8048/8052/409 8052/8056/409 8049/8053/409 8045/8049/409 +# f 8049/8053/587 8053/8057/587 8054/8058/587 8050/8054/587 +# f 8050/8054/410 8054/8058/410 8055/8059/410 8051/8055/410 +# f 8051/8055/588 8055/8059/588 8056/8060/588 8052/8056/588 +# f 8052/8056/409 8056/8060/409 8053/8057/409 8049/8053/409 +# f 8053/8057/589 8057/8061/589 8058/8062/589 8054/8058/589 +# f 8054/8058/410 8058/8062/410 8044/8047/410 8043/8046/410 8055/8059/410 +# f 8055/8059/590 8043/8046/590 8042/8045/590 8056/8060/590 +# f 8056/8060/409 8042/8045/409 8041/8048/409 8057/8061/409 8053/8057/409 +# s 8 +# f 8057/8061/591 8041/8048/581 8044/8047/581 8058/8062/591 +# f 8059/8063/479 8060/8064/479 8061/8065/455 8062/8066/455 +# f 8062/8066/455 8061/8065/455 8063/8067/418 8064/8068/418 +# f 8064/8068/418 8063/8067/418 8065/8069/458 8066/8070/458 +# f 8066/8070/458 8065/8069/458 8067/8071/577 8068/8072/577 +# f 8068/8072/577 8067/8071/577 8069/8073/578 8070/8074/578 +# f 8070/8074/578 8069/8073/578 8071/8075/579 8072/8076/579 +# f 8072/8076/579 8071/8075/579 8073/8077/580 8074/8078/580 +# f 8075/8082/581 8076/8079/582 8077/8080/582 8078/8081/581 +# s 1 +# f 8068/8072/409 8070/8074/409 8072/8076/409 8074/8078/409 8059/8063/409 8062/8066/409 8064/8068/409 8066/8070/409 +# f 8065/8069/410 8063/8067/410 8061/8065/410 8060/8064/410 8073/8077/410 8071/8075/410 8069/8073/410 8067/8071/410 +# s off +# f 8059/8063/583 8079/8083/583 8080/8084/583 8060/8064/583 +# f 8060/8064/410 8080/8084/410 8081/8085/410 8073/8077/410 +# f 8073/8077/584 8081/8085/584 8082/8086/584 8074/8078/584 +# f 8074/8078/409 8082/8086/409 8079/8083/409 8059/8063/409 +# f 8079/8083/585 8083/8087/585 8084/8088/585 8080/8084/585 +# f 8080/8084/410 8084/8088/410 8085/8089/410 8081/8085/410 +# f 8081/8085/586 8085/8089/586 8086/8090/586 8082/8086/586 +# f 8082/8086/409 8086/8090/409 8083/8087/409 8079/8083/409 +# f 8083/8087/587 8087/8091/587 8088/8092/587 8084/8088/587 +# f 8084/8088/410 8088/8092/410 8089/8093/410 8085/8089/410 +# f 8085/8089/588 8089/8093/588 8090/8094/588 8086/8090/588 +# f 8086/8090/409 8090/8094/409 8087/8091/409 8083/8087/409 +# f 8087/8091/589 8091/8095/589 8092/8096/589 8088/8092/589 +# f 8088/8092/410 8092/8096/410 8078/8081/410 8077/8080/410 8089/8093/410 +# f 8089/8093/590 8077/8080/590 8076/8079/590 8090/8094/590 +# f 8090/8094/409 8076/8079/409 8075/8082/409 8091/8095/409 8087/8091/409 +# s 8 +# f 8091/8095/591 8075/8082/581 8078/8081/581 8092/8096/591 +# f 8093/8097/479 8094/8098/479 8095/8099/455 8096/8100/455 +# f 8096/8100/455 8095/8099/455 8097/8101/418 8098/8102/418 +# f 8098/8102/418 8097/8101/418 8099/8103/458 8100/8104/458 +# f 8100/8104/458 8099/8103/458 8101/8105/577 8102/8106/577 +# f 8102/8106/577 8101/8105/577 8103/8107/578 8104/8108/578 +# f 8104/8108/578 8103/8107/578 8105/8109/579 8106/8110/579 +# f 8106/8110/579 8105/8109/579 8107/8111/580 8108/8112/580 +# f 8109/8116/581 8110/8113/582 8111/8114/582 8112/8115/581 +# s 1 +# f 8102/8106/409 8104/8108/409 8106/8110/409 8108/8112/409 8093/8097/409 8096/8100/409 8098/8102/409 8100/8104/409 +# f 8099/8103/410 8097/8101/410 8095/8099/410 8094/8098/410 8107/8111/410 8105/8109/410 8103/8107/410 8101/8105/410 +# s off +# f 8093/8097/583 8113/8117/583 8114/8118/583 8094/8098/583 +# f 8094/8098/410 8114/8118/410 8115/8119/410 8107/8111/410 +# f 8107/8111/584 8115/8119/584 8116/8120/584 8108/8112/584 +# f 8108/8112/409 8116/8120/409 8113/8117/409 8093/8097/409 +# f 8113/8117/585 8117/8121/585 8118/8122/585 8114/8118/585 +# f 8114/8118/410 8118/8122/410 8119/8123/410 8115/8119/410 +# f 8115/8119/586 8119/8123/586 8120/8124/586 8116/8120/586 +# f 8116/8120/409 8120/8124/409 8117/8121/409 8113/8117/409 +# f 8117/8121/587 8121/8125/587 8122/8126/587 8118/8122/587 +# f 8118/8122/410 8122/8126/410 8123/8127/410 8119/8123/410 +# f 8119/8123/588 8123/8127/588 8124/8128/588 8120/8124/588 +# f 8120/8124/409 8124/8128/409 8121/8125/409 8117/8121/409 +# f 8121/8125/589 8125/8129/589 8126/8130/589 8122/8126/589 +# f 8122/8126/410 8126/8130/410 8112/8115/410 8111/8114/410 8123/8127/410 +# f 8123/8127/590 8111/8114/590 8110/8113/590 8124/8128/590 +# f 8124/8128/409 8110/8113/409 8109/8116/409 8125/8129/409 8121/8125/409 +# s 8 +# f 8125/8129/591 8109/8116/581 8112/8115/581 8126/8130/591 +# f 8127/8131/479 8128/8132/479 8129/8133/455 8130/8134/455 +# f 8130/8134/455 8129/8133/455 8131/8135/418 8132/8136/418 +# f 8132/8136/418 8131/8135/418 8133/8137/458 8134/8138/458 +# f 8134/8138/458 8133/8137/458 8135/8139/577 8136/8140/577 +# f 8136/8140/577 8135/8139/577 8137/8141/578 8138/8142/578 +# f 8138/8142/578 8137/8141/578 8139/8143/579 8140/8144/579 +# f 8140/8144/579 8139/8143/579 8141/8145/580 8142/8146/580 +# f 8143/8150/581 8144/8147/582 8145/8148/582 8146/8149/581 +# s 1 +# f 8136/8140/409 8138/8142/409 8140/8144/409 8142/8146/409 8127/8131/409 8130/8134/409 8132/8136/409 8134/8138/409 +# f 8133/8137/410 8131/8135/410 8129/8133/410 8128/8132/410 8141/8145/410 8139/8143/410 8137/8141/410 8135/8139/410 +# s off +# f 8127/8131/583 8147/8151/583 8148/8152/583 8128/8132/583 +# f 8128/8132/410 8148/8152/410 8149/8153/410 8141/8145/410 +# f 8141/8145/584 8149/8153/584 8150/8154/584 8142/8146/584 +# f 8142/8146/409 8150/8154/409 8147/8151/409 8127/8131/409 +# f 8147/8151/585 8151/8155/585 8152/8156/585 8148/8152/585 +# f 8148/8152/410 8152/8156/410 8153/8157/410 8149/8153/410 +# f 8149/8153/586 8153/8157/586 8154/8158/586 8150/8154/586 +# f 8150/8154/409 8154/8158/409 8151/8155/409 8147/8151/409 +# f 8151/8155/587 8155/8159/587 8156/8160/587 8152/8156/587 +# f 8152/8156/410 8156/8160/410 8157/8161/410 8153/8157/410 +# f 8153/8157/588 8157/8161/588 8158/8162/588 8154/8158/588 +# f 8154/8158/409 8158/8162/409 8155/8159/409 8151/8155/409 +# f 8155/8159/589 8159/8163/589 8160/8164/589 8156/8160/589 +# f 8156/8160/410 8160/8164/410 8146/8149/410 8145/8148/410 8157/8161/410 +# f 8157/8161/590 8145/8148/590 8144/8147/590 8158/8162/590 +# f 8158/8162/409 8144/8147/409 8143/8150/409 8159/8163/409 8155/8159/409 +# s 8 +# f 8159/8163/591 8143/8150/581 8146/8149/581 8160/8164/591 +# 610 polygons - 40 triangles + +# +# object Frame_Container +# + +v 1.0904 -3.6665 0.1793 +v 1.0449 -3.6665 0.1793 +v 1.0449 -3.5452 0.1793 +v 1.0904 -3.5452 0.1793 +v 1.0449 -3.6665 2.5913 +v 1.0904 -3.6665 2.5913 +v 1.0904 -3.5452 2.5913 +v 1.0449 -3.5452 2.5913 +v 1.0904 -3.6665 0.4892 +v 1.0449 -3.6665 0.4892 +v 1.0904 -3.6665 0.5923 +v 1.0449 -3.6665 0.5923 +v 1.0449 -3.6160 0.5923 +v 1.0904 -3.6160 0.5923 +v 1.0449 -3.6160 0.4892 +v 1.0904 -3.6160 0.4892 +v 1.0904 -3.6665 1.7257 +v 1.0449 -3.6665 1.7257 +v 1.0449 -3.6160 1.7257 +v 1.0904 -3.6160 1.7257 +v 1.0449 -3.6160 1.6226 +v 1.0904 -3.6160 1.6226 +v 1.0449 -3.6665 1.6226 +v 1.0904 -3.6665 1.6226 +v 1.0904 -3.6665 1.0563 +v 1.0449 -3.6665 1.0563 +v 1.0449 -3.6665 1.1594 +v 1.0904 -3.6665 1.1594 +v 1.0449 -3.6160 1.1594 +v 1.0904 -3.6160 1.1594 +v 1.0449 -3.6160 1.0563 +v 1.0904 -3.6160 1.0563 +v 1.0904 -3.6665 2.1890 +v 1.0449 -3.6665 2.1890 +v 1.0449 -3.6665 2.2924 +v 1.0904 -3.6665 2.2924 +v 1.0449 -3.6160 2.2924 +v 1.0904 -3.6160 2.2924 +v 1.0449 -3.6160 2.1890 +v 1.0904 -3.6160 2.1890 +v 0.9617 -3.7064 2.5890 +v 0.9617 -3.5447 2.5890 +v 1.1349 -3.5447 2.5890 +v 1.1349 -3.7064 2.5890 +v 0.9617 -3.7064 2.7506 +v 1.1349 -3.7064 2.7506 +v 1.1349 -3.5447 2.7506 +v 0.9617 -3.5447 2.7506 +v -1.2528 -3.6661 2.5904 +v -1.2528 -3.5243 2.5904 +v 0.9819 -3.5243 2.5904 +v 0.9819 -3.6661 2.5904 +v -1.2528 -3.6661 2.7319 +v 0.9819 -3.6661 2.7319 +v 0.9819 -3.5243 2.7319 +v -1.2528 -3.5243 2.7319 +v -1.4211 -3.7064 2.5890 +v -1.4211 -3.5447 2.5890 +v -1.2484 -3.5447 2.5890 +v -1.2484 -3.7064 2.5890 +v -1.4211 -3.7064 2.7506 +v -1.2484 -3.7064 2.7506 +v -1.2484 -3.5447 2.7506 +v -1.4211 -3.5447 2.7506 +v -1.3769 -3.6656 0.1793 +v -1.3769 -3.5444 0.1793 +v -1.3314 -3.5444 0.1793 +v -1.3314 -3.6656 0.1793 +v -1.3314 -3.6656 2.5913 +v -1.3314 -3.5444 2.5913 +v -1.3769 -3.5444 2.5913 +v -1.3769 -3.6656 2.5913 +v -1.3769 -3.6656 0.4892 +v -1.3314 -3.6656 0.4892 +v -1.3769 -3.6656 0.5923 +v -1.3769 -3.6152 0.5923 +v -1.3314 -3.6152 0.5923 +v -1.3314 -3.6656 0.5923 +v -1.3769 -3.6152 0.4892 +v -1.3314 -3.6152 0.4892 +v -1.3769 -3.6656 1.7257 +v -1.3769 -3.6152 1.7257 +v -1.3314 -3.6152 1.7257 +v -1.3314 -3.6656 1.7257 +v -1.3769 -3.6152 1.6226 +v -1.3314 -3.6152 1.6226 +v -1.3769 -3.6656 1.6226 +v -1.3314 -3.6656 1.6226 +v -1.3769 -3.6656 1.0563 +v -1.3314 -3.6656 1.0563 +v -1.3314 -3.6656 1.1594 +v -1.3769 -3.6656 1.1594 +v -1.3769 -3.6152 1.1594 +v -1.3314 -3.6152 1.1594 +v -1.3769 -3.6152 1.0563 +v -1.3314 -3.6152 1.0563 +v -1.3314 -3.6656 2.1890 +v -1.3769 -3.6656 2.1890 +v -1.3314 -3.6656 2.2924 +v -1.3769 -3.6656 2.2924 +v -1.3314 -3.6152 2.2924 +v -1.3769 -3.6152 2.2924 +v -1.3769 -3.6152 2.1890 +v -1.3314 -3.6152 2.1890 +v -1.3914 8.4012 2.5796 +v -1.2422 8.4012 2.5796 +v -1.2422 -3.5230 2.5796 +v -1.3914 -3.5230 2.5796 +v -1.3914 8.4012 2.7301 +v -1.3914 -3.5230 2.7301 +v -1.2422 -3.5230 2.7301 +v -1.2422 8.4012 2.7301 +v -1.3914 8.4012 0.0161 +v -1.2422 8.4012 0.0161 +v -1.2422 -3.5230 0.0161 +v -1.3914 -3.5230 0.0161 +v -1.3914 8.4012 0.1666 +v -1.3914 -3.5230 0.1666 +v -1.2422 -3.5230 0.1666 +v -1.2422 8.4012 0.1666 +v -1.4211 -3.7064 0.0254 +v -1.4211 -3.5447 0.0254 +v -1.2484 -3.5447 0.0254 +v -1.2484 -3.7064 0.0254 +v -1.4211 -3.7064 0.1871 +v -1.2484 -3.7064 0.1871 +v -1.2484 -3.5447 0.1871 +v -1.4211 -3.5447 0.1871 +v -1.2528 -3.6661 0.0269 +v -1.2528 -3.5243 0.0269 +v 0.9819 -3.5243 0.0269 +v 0.9819 -3.6661 0.0269 +v -1.2528 -3.6661 0.1683 +v 0.9819 -3.6661 0.1683 +v 0.9819 -3.5243 0.1683 +v -1.2528 -3.5243 0.1683 +v 0.9617 -3.7064 0.0254 +v 0.9617 -3.5447 0.0254 +v 1.1349 -3.5447 0.0254 +v 1.1349 -3.7064 0.0254 +v 0.9617 -3.7064 0.1871 +v 1.1349 -3.7064 0.1871 +v 1.1349 -3.5447 0.1871 +v 0.9617 -3.5447 0.1871 +v 0.9547 8.4012 0.0161 +v 1.1070 8.4012 0.0161 +v 1.1070 -3.5230 0.0161 +v 0.9547 -3.5230 0.0161 +v 0.9547 8.4012 0.1666 +v 0.9547 -3.5230 0.1666 +v 1.1070 -3.5230 0.1666 +v 1.1070 8.4012 0.1666 +v -1.2528 8.4140 0.0269 +v -1.2528 8.5575 0.0269 +v 0.9819 8.5575 0.0269 +v 0.9819 8.4140 0.0269 +v -1.2528 8.4140 0.1713 +v 0.9819 8.4140 0.1713 +v 0.9819 8.5575 0.1713 +v -1.2528 8.5575 0.1713 +v 0.9636 8.3952 0.0254 +v 0.9636 8.5568 0.0254 +v 1.1342 8.5568 0.0254 +v 1.1342 8.3952 0.0254 +v 0.9636 8.3952 0.1871 +v 1.1342 8.3952 0.1871 +v 1.1342 8.5568 0.1871 +v 0.9636 8.5568 0.1871 +v -1.4191 8.3952 0.0254 +v -1.4191 8.5568 0.0254 +v -1.2484 8.5568 0.0254 +v -1.2484 8.3952 0.0254 +v -1.4191 8.3952 0.1871 +v -1.2484 8.3952 0.1871 +v -1.2484 8.5568 0.1871 +v -1.4191 8.5568 0.1871 +v -1.3770 8.4265 0.1052 +v -1.2560 8.4265 0.1052 +v -1.2560 8.4265 2.6034 +v -1.3770 8.4265 2.6034 +v -1.2560 8.5489 0.1052 +v -1.2560 8.5489 2.6034 +v -1.3770 8.5489 0.1052 +v -1.3770 8.5489 2.6034 +v -1.2528 8.4140 2.5904 +v -1.2528 8.5575 2.5904 +v 0.9819 8.5575 2.5904 +v 0.9819 8.4140 2.5904 +v -1.2528 8.4140 2.7348 +v 0.9819 8.4140 2.7348 +v 0.9819 8.5575 2.7348 +v -1.2528 8.5575 2.7348 +v 0.9700 8.4265 0.1052 +v 1.0911 8.4265 0.1052 +v 1.0911 8.4265 2.6034 +v 0.9700 8.4265 2.6034 +v 1.0911 8.5489 0.1052 +v 1.0911 8.5489 2.6034 +v 0.9700 8.5489 0.1052 +v 0.9700 8.5489 2.6034 +v 0.9617 8.3952 2.5890 +v 0.9617 8.5568 2.5890 +v 1.1324 8.5568 2.5890 +v 1.1324 8.3952 2.5890 +v 0.9617 8.3952 2.7506 +v 1.1324 8.3952 2.7506 +v 1.1324 8.5568 2.7506 +v 0.9617 8.5568 2.7506 +v -1.4191 8.3952 2.5890 +v -1.4191 8.5568 2.5890 +v -1.2484 8.5568 2.5890 +v -1.2484 8.3952 2.5890 +v -1.4191 8.3952 2.7506 +v -1.2484 8.3952 2.7506 +v -1.2484 8.5568 2.7506 +v -1.4191 8.5568 2.7506 +v 0.9547 8.4012 2.5796 +v 1.1070 8.4012 2.5796 +v 1.1070 -3.5230 2.5796 +v 0.9547 -3.5230 2.5796 +v 0.9547 8.4012 2.7301 +v 0.9547 -3.5230 2.7301 +v 1.1070 -3.5230 2.7301 +v 1.1070 8.4012 2.7301 +# 224 vertices + +vn 0.0000 0.0000 -1.0000 +vn -0.0000 0.0000 1.0000 +vn 0.0000 1.0000 0.0000 +vn 0.0000 -1.0000 0.0000 +vn 0.0000 0.0000 1.0000 +vn -0.0000 0.0000 -1.0000 +vn -1.0000 0.0000 0.0000 +vn -1.0000 -0.0000 -0.0000 +vn -1.0000 0.0000 -0.0000 +vn 1.0000 0.0000 0.0000 +vn 1.0000 0.0000 -0.0000 +vn 0.0000 -0.0000 -1.0000 +vn 1.0000 -0.0000 0.0000 +vn -0.0000 1.0000 0.0000 +vn -0.0000 1.0000 -0.0000 +# 15 vertex normals + +vt 0.1078 0.0892 0.0000 +vt 0.1069 0.0892 0.0000 +vt 0.1069 0.0892 0.0000 +vt 0.1078 0.0892 0.0000 +vt 0.1069 0.1587 0.0000 +vt 0.1078 0.1587 0.0000 +vt 0.1078 0.1587 0.0000 +vt 0.1069 0.1587 0.0000 +vt 0.1078 0.0981 0.0000 +vt 0.1069 0.0981 0.0000 +vt 0.1078 0.1011 0.0000 +vt 0.1069 0.1011 0.0000 +vt 0.1069 0.1011 0.0000 +vt 0.1078 0.1011 0.0000 +vt 0.1069 0.0981 0.0000 +vt 0.1078 0.0981 0.0000 +vt 0.1078 0.1338 0.0000 +vt 0.1069 0.1338 0.0000 +vt 0.1069 0.1338 0.0000 +vt 0.1078 0.1338 0.0000 +vt 0.1069 0.1308 0.0000 +vt 0.1078 0.1308 0.0000 +vt 0.1069 0.1308 0.0000 +vt 0.1078 0.1308 0.0000 +vt 0.1078 0.1145 0.0000 +vt 0.1069 0.1145 0.0000 +vt 0.1069 0.1174 0.0000 +vt 0.1078 0.1174 0.0000 +vt 0.1069 0.1174 0.0000 +vt 0.1078 0.1174 0.0000 +vt 0.1069 0.1145 0.0000 +vt 0.1078 0.1145 0.0000 +vt 0.1078 0.1471 0.0000 +vt 0.1069 0.1471 0.0000 +vt 0.1069 0.1501 0.0000 +vt 0.1078 0.1501 0.0000 +vt 0.1069 0.1501 0.0000 +vt 0.1078 0.1501 0.0000 +vt 0.1069 0.1471 0.0000 +vt 0.1078 0.1471 0.0000 +vt 0.1051 0.1587 0.0000 +vt 0.1051 0.1587 0.0000 +vt 0.1087 0.1587 0.0000 +vt 0.1087 0.1587 0.0000 +vt 0.1051 0.1633 0.0000 +vt 0.1087 0.1633 0.0000 +vt 0.1087 0.1633 0.0000 +vt 0.1051 0.1633 0.0000 +vt 0.0591 0.1587 0.0000 +vt 0.0591 0.1587 0.0000 +vt 0.1056 0.1587 0.0000 +vt 0.1056 0.1587 0.0000 +vt 0.0591 0.1628 0.0000 +vt 0.1056 0.1628 0.0000 +vt 0.1056 0.1628 0.0000 +vt 0.0591 0.1628 0.0000 +vt 0.0556 0.1587 0.0000 +vt 0.0556 0.1587 0.0000 +vt 0.0592 0.1587 0.0000 +vt 0.0592 0.1587 0.0000 +vt 0.0556 0.1633 0.0000 +vt 0.0592 0.1633 0.0000 +vt 0.0592 0.1633 0.0000 +vt 0.0556 0.1633 0.0000 +vt 0.0566 0.0892 0.0000 +vt 0.0566 0.0892 0.0000 +vt 0.0575 0.0892 0.0000 +vt 0.0575 0.0892 0.0000 +vt 0.0575 0.1587 0.0000 +vt 0.0575 0.1587 0.0000 +vt 0.0566 0.1587 0.0000 +vt 0.0566 0.1587 0.0000 +vt 0.0566 0.0981 0.0000 +vt 0.0575 0.0981 0.0000 +vt 0.0566 0.1011 0.0000 +vt 0.0566 0.1011 0.0000 +vt 0.0575 0.1011 0.0000 +vt 0.0575 0.1011 0.0000 +vt 0.0566 0.0981 0.0000 +vt 0.0575 0.0981 0.0000 +vt 0.0566 0.1338 0.0000 +vt 0.0566 0.1338 0.0000 +vt 0.0575 0.1338 0.0000 +vt 0.0575 0.1338 0.0000 +vt 0.0566 0.1308 0.0000 +vt 0.0575 0.1308 0.0000 +vt 0.0566 0.1308 0.0000 +vt 0.0575 0.1308 0.0000 +vt 0.0566 0.1145 0.0000 +vt 0.0575 0.1145 0.0000 +vt 0.0575 0.1174 0.0000 +vt 0.0566 0.1174 0.0000 +vt 0.0566 0.1174 0.0000 +vt 0.0575 0.1174 0.0000 +vt 0.0566 0.1145 0.0000 +vt 0.0575 0.1145 0.0000 +vt 0.0575 0.1471 0.0000 +vt 0.0566 0.1471 0.0000 +vt 0.0575 0.1501 0.0000 +vt 0.0566 0.1501 0.0000 +vt 0.0575 0.1501 0.0000 +vt 0.0566 0.1501 0.0000 +vt 0.0566 0.1471 0.0000 +vt 0.0575 0.1471 0.0000 +vt 0.0563 0.1584 0.0000 +vt 0.0594 0.1584 0.0000 +vt 0.0594 0.1584 0.0000 +vt 0.0563 0.1584 0.0000 +vt 0.0563 0.1627 0.0000 +vt 0.0563 0.1627 0.0000 +vt 0.0594 0.1627 0.0000 +vt 0.0594 0.1627 0.0000 +vt 0.0563 0.0845 0.0000 +vt 0.0594 0.0845 0.0000 +vt 0.0594 0.0845 0.0000 +vt 0.0563 0.0845 0.0000 +vt 0.0563 0.0888 0.0000 +vt 0.0563 0.0888 0.0000 +vt 0.0594 0.0888 0.0000 +vt 0.0594 0.0888 0.0000 +vt 0.0556 0.0848 0.0000 +vt 0.0556 0.0848 0.0000 +vt 0.0592 0.0848 0.0000 +vt 0.0592 0.0848 0.0000 +vt 0.0556 0.0894 0.0000 +vt 0.0592 0.0894 0.0000 +vt 0.0592 0.0894 0.0000 +vt 0.0556 0.0894 0.0000 +vt 0.0591 0.0848 0.0000 +vt 0.0591 0.0848 0.0000 +vt 0.1056 0.0848 0.0000 +vt 0.1056 0.0848 0.0000 +vt 0.0591 0.0889 0.0000 +vt 0.1056 0.0889 0.0000 +vt 0.1056 0.0889 0.0000 +vt 0.0591 0.0889 0.0000 +vt 0.1051 0.0848 0.0000 +vt 0.1051 0.0848 0.0000 +vt 0.1087 0.0848 0.0000 +vt 0.1087 0.0848 0.0000 +vt 0.1051 0.0894 0.0000 +vt 0.1087 0.0894 0.0000 +vt 0.1087 0.0894 0.0000 +vt 0.1051 0.0894 0.0000 +vt 0.1050 0.0845 0.0000 +vt 0.1082 0.0845 0.0000 +vt 0.1082 0.0845 0.0000 +vt 0.1050 0.0845 0.0000 +vt 0.1050 0.0888 0.0000 +vt 0.1050 0.0888 0.0000 +vt 0.1082 0.0888 0.0000 +vt 0.1082 0.0888 0.0000 +vt 0.0591 0.0848 0.0000 +vt 0.0591 0.0848 0.0000 +vt 0.1056 0.0848 0.0000 +vt 0.1056 0.0848 0.0000 +vt 0.0591 0.0890 0.0000 +vt 0.1056 0.0890 0.0000 +vt 0.1056 0.0890 0.0000 +vt 0.0591 0.0890 0.0000 +vt 0.1052 0.0848 0.0000 +vt 0.1052 0.0848 0.0000 +vt 0.1087 0.0848 0.0000 +vt 0.1087 0.0848 0.0000 +vt 0.1052 0.0894 0.0000 +vt 0.1087 0.0894 0.0000 +vt 0.1087 0.0894 0.0000 +vt 0.1052 0.0894 0.0000 +vt 0.0557 0.0848 0.0000 +vt 0.0557 0.0848 0.0000 +vt 0.0592 0.0848 0.0000 +vt 0.0592 0.0848 0.0000 +vt 0.0557 0.0894 0.0000 +vt 0.0592 0.0894 0.0000 +vt 0.0592 0.0894 0.0000 +vt 0.0557 0.0894 0.0000 +vt 0.0566 0.0871 0.0000 +vt 0.0591 0.0871 0.0000 +vt 0.0591 0.1591 0.0000 +vt 0.0566 0.1591 0.0000 +vt 0.0591 0.0871 0.0000 +vt 0.0591 0.1591 0.0000 +vt 0.0566 0.0871 0.0000 +vt 0.0566 0.1591 0.0000 +vt 0.0591 0.1587 0.0000 +vt 0.0591 0.1587 0.0000 +vt 0.1056 0.1587 0.0000 +vt 0.1056 0.1587 0.0000 +vt 0.0591 0.1629 0.0000 +vt 0.1056 0.1629 0.0000 +vt 0.1056 0.1629 0.0000 +vt 0.0591 0.1629 0.0000 +vt 0.1053 0.0871 0.0000 +vt 0.1078 0.0871 0.0000 +vt 0.1078 0.1591 0.0000 +vt 0.1053 0.1591 0.0000 +vt 0.1078 0.0871 0.0000 +vt 0.1078 0.1591 0.0000 +vt 0.1053 0.0871 0.0000 +vt 0.1053 0.1591 0.0000 +vt 0.1051 0.1587 0.0000 +vt 0.1051 0.1587 0.0000 +vt 0.1087 0.1587 0.0000 +vt 0.1087 0.1587 0.0000 +vt 0.1051 0.1633 0.0000 +vt 0.1087 0.1633 0.0000 +vt 0.1087 0.1633 0.0000 +vt 0.1051 0.1633 0.0000 +vt 0.0557 0.1587 0.0000 +vt 0.0557 0.1587 0.0000 +vt 0.0592 0.1587 0.0000 +vt 0.0592 0.1587 0.0000 +vt 0.0557 0.1633 0.0000 +vt 0.0592 0.1633 0.0000 +vt 0.0592 0.1633 0.0000 +vt 0.0557 0.1633 0.0000 +vt 0.1050 0.1584 0.0000 +vt 0.1082 0.1584 0.0000 +vt 0.1082 0.1584 0.0000 +vt 0.1050 0.1584 0.0000 +vt 0.1050 0.1627 0.0000 +vt 0.1050 0.1627 0.0000 +vt 0.1082 0.1627 0.0000 +vt 0.1082 0.1627 0.0000 +# 224 texture coords + +# g Frame_Container +# usemtl ShippingContainer +# s 2 +# f 8161/8165/592 8162/8166/592 8163/8167/592 8164/8168/592 +# s 4 +# f 8165/8169/593 8166/8170/593 8167/8171/593 8168/8172/593 +# s 32 +# f 8163/8167/594 8168/8172/594 8167/8171/594 8164/8168/594 +# s 8 +# f 8169/8173/595 8170/8174/595 8162/8166/595 8161/8165/595 +# s 1 +# f 8171/8175/592 8172/8176/592 8173/8177/592 8174/8178/592 +# s 2 +# f 8174/8178/595 8173/8177/595 8175/8179/595 8176/8180/595 +# s 1 +# f 8175/8179/596 8170/8174/596 8169/8173/596 8176/8180/596 +# f 8177/8181/592 8178/8182/592 8179/8183/592 8180/8184/592 +# s 2 +# f 8180/8184/595 8179/8183/595 8181/8185/595 8182/8186/595 +# s 1 +# f 8181/8185/596 8183/8187/596 8184/8188/596 8182/8186/596 +# s 8 +# f 8185/8189/595 8186/8190/595 8172/8176/595 8171/8175/595 +# f 8187/8191/595 8188/8192/595 8184/8188/595 8183/8187/595 +# s 1 +# f 8188/8192/597 8187/8191/597 8189/8193/597 8190/8194/597 +# s 2 +# f 8190/8194/595 8189/8193/595 8191/8195/595 8192/8196/595 +# s 1 +# f 8191/8195/596 8186/8190/596 8185/8189/596 8192/8196/596 +# s 8 +# f 8177/8181/595 8193/8197/595 8194/8198/595 8178/8182/595 +# f 8195/8199/595 8196/8200/595 8166/8170/595 8165/8169/595 +# s 1 +# f 8197/8201/592 8198/8202/592 8196/8200/592 8195/8199/592 +# s 2 +# f 8197/8201/595 8199/8203/595 8200/8204/595 8198/8202/595 +# s 1 +# f 8193/8197/596 8200/8204/596 8199/8203/596 8194/8198/596 +# s 16 +# f 8162/8166/598 8170/8174/598 8175/8179/598 8173/8177/598 8172/8176/598 8186/8190/598 8191/8195/598 8189/8193/599 8187/8191/600 8183/8187/600 8181/8185/600 8179/8183/600 8178/8182/598 8194/8198/598 8199/8203/600 8197/8201/599 8195/8199/600 8165/8169/600 8168/8172/599 8163/8167/599 +# s 64 +# f 8184/8188/601 8188/8192/601 8190/8194/601 8192/8196/601 8185/8189/601 8171/8175/601 8174/8178/601 8176/8180/602 8169/8173/601 8161/8165/602 8164/8168/602 8167/8171/601 8166/8170/601 8196/8200/601 8198/8202/601 8200/8204/601 8193/8197/601 8177/8181/601 8180/8184/601 8182/8186/601 +# s 2 +# f 8201/8205/592 8202/8206/592 8203/8207/592 8204/8208/592 +# s 4 +# f 8205/8209/593 8206/8210/593 8207/8211/593 8208/8212/593 +# s 8 +# f 8201/8205/595 8204/8208/595 8206/8210/595 8205/8209/595 +# s 16 +# f 8204/8208/601 8203/8207/601 8207/8211/601 8206/8210/601 +# s 32 +# f 8203/8207/594 8202/8206/594 8208/8212/594 8207/8211/594 +# s 64 +# f 8202/8206/598 8201/8205/598 8205/8209/598 8208/8212/598 +# s 2 +# f 8209/8213/592 8210/8214/592 8211/8215/592 8212/8216/592 +# s 4 +# f 8213/8217/596 8214/8218/596 8215/8219/596 8216/8220/596 +# s 8 +# f 8209/8213/595 8212/8216/595 8214/8218/595 8213/8217/595 +# s 32 +# f 8211/8215/594 8210/8214/594 8216/8220/594 8215/8219/594 +# s 2 +# f 8217/8221/603 8218/8222/603 8219/8223/603 8220/8224/603 +# s 4 +# f 8221/8225/593 8222/8226/593 8223/8227/593 8224/8228/593 +# s 8 +# f 8217/8221/595 8220/8224/595 8222/8226/595 8221/8225/595 +# s 16 +# f 8220/8224/604 8219/8223/604 8223/8227/604 8222/8226/604 +# s 32 +# f 8219/8223/594 8218/8222/594 8224/8228/594 8223/8227/594 +# s 64 +# f 8218/8222/600 8217/8221/600 8221/8225/600 8224/8228/600 +# s 2 +# f 8225/8229/592 8226/8230/592 8227/8231/592 8228/8232/592 +# s 4 +# f 8229/8233/596 8230/8234/596 8231/8235/596 8232/8236/596 +# s 32 +# f 8227/8231/594 8226/8230/594 8231/8235/594 8230/8234/594 +# s 8 +# f 8233/8237/595 8225/8229/595 8228/8232/595 8234/8238/595 +# s 1 +# f 8235/8239/592 8236/8240/592 8237/8241/592 8238/8242/592 +# s 2 +# f 8236/8240/595 8239/8243/595 8240/8244/595 8237/8241/595 +# s 1 +# f 8240/8244/593 8239/8243/593 8233/8237/593 8234/8238/593 +# f 8241/8245/592 8242/8246/592 8243/8247/592 8244/8248/592 +# s 2 +# f 8242/8246/595 8245/8249/595 8246/8250/595 8243/8247/595 +# s 1 +# f 8246/8250/596 8245/8249/596 8247/8251/596 8248/8252/596 +# s 8 +# f 8249/8253/595 8235/8239/595 8238/8242/595 8250/8254/595 +# f 8251/8255/595 8248/8252/595 8247/8251/595 8252/8256/595 +# s 1 +# f 8252/8256/592 8253/8257/592 8254/8258/592 8251/8255/592 +# s 2 +# f 8253/8257/595 8255/8259/595 8256/8260/595 8254/8258/595 +# s 1 +# f 8256/8260/593 8255/8259/593 8249/8253/593 8250/8254/593 +# s 8 +# f 8241/8245/595 8244/8248/595 8257/8261/595 8258/8262/595 +# f 8259/8263/595 8229/8233/595 8232/8236/595 8260/8264/595 +# s 1 +# f 8261/8265/592 8259/8263/592 8260/8264/592 8262/8266/592 +# s 2 +# f 8261/8265/595 8262/8266/595 8263/8267/595 8264/8268/595 +# s 1 +# f 8258/8262/596 8257/8261/596 8264/8268/596 8263/8267/596 +# s 16 +# f 8246/8250/604 8248/8252/601 8251/8255/601 8254/8258/604 8256/8260/601 8250/8254/604 8238/8242/604 8237/8241/604 8240/8244/604 8234/8238/601 8228/8232/604 8227/8231/604 8230/8234/604 8229/8233/601 8259/8263/601 8261/8265/604 8264/8268/604 8257/8261/601 8244/8248/601 8243/8247/604 +# s 64 +# f 8225/8229/600 8233/8237/600 8239/8243/599 8236/8240/600 8235/8239/600 8249/8253/600 8255/8259/600 8253/8257/600 8252/8256/600 8247/8251/600 8245/8249/599 8242/8246/598 8241/8245/598 8258/8262/598 8263/8267/598 8262/8266/600 8260/8264/600 8232/8236/598 8231/8235/598 8226/8230/600 +# s 2 +# f 8265/8269/592 8266/8270/592 8267/8271/592 8268/8272/592 +# s 4 +# f 8269/8273/593 8270/8274/593 8271/8275/593 8272/8276/593 +# s 8 +# f 8265/8269/598 8268/8272/598 8270/8274/598 8269/8273/598 +# s 32 +# f 8267/8271/604 8266/8270/604 8272/8276/604 8271/8275/604 +# s 2 +# f 8273/8277/592 8274/8278/592 8275/8279/592 8276/8280/592 +# s 4 +# f 8277/8281/596 8278/8282/596 8279/8283/596 8280/8284/596 +# s 8 +# f 8273/8277/598 8276/8280/598 8278/8282/598 8277/8281/598 +# s 32 +# f 8275/8279/604 8274/8278/604 8280/8284/604 8279/8283/604 +# s 2 +# f 8281/8285/592 8282/8286/592 8283/8287/592 8284/8288/592 +# s 4 +# f 8285/8289/593 8286/8290/593 8287/8291/593 8288/8292/593 +# s 8 +# f 8281/8285/595 8284/8288/595 8286/8290/595 8285/8289/595 +# s 16 +# f 8284/8288/604 8283/8287/601 8287/8291/604 8286/8290/604 +# s 32 +# f 8283/8287/594 8282/8286/594 8288/8292/594 8287/8291/594 +# s 64 +# f 8282/8286/598 8281/8285/598 8285/8289/598 8288/8292/598 +# s 2 +# f 8289/8293/603 8290/8294/592 8291/8295/603 8292/8296/603 +# s 4 +# f 8293/8297/593 8294/8298/593 8295/8299/593 8296/8300/593 +# s 8 +# f 8289/8293/595 8292/8296/595 8294/8298/595 8293/8297/595 +# s 32 +# f 8291/8295/594 8290/8294/594 8296/8300/594 8295/8299/594 +# s 2 +# f 8297/8301/592 8298/8302/592 8299/8303/592 8300/8304/592 +# s 4 +# f 8301/8305/596 8302/8306/596 8303/8307/596 8304/8308/596 +# s 8 +# f 8297/8301/595 8300/8304/595 8302/8306/595 8301/8305/595 +# s 16 +# f 8300/8304/604 8299/8303/604 8303/8307/604 8302/8306/601 +# s 32 +# f 8299/8303/594 8298/8302/594 8304/8308/594 8303/8307/594 +# s 64 +# f 8298/8302/600 8297/8301/598 8301/8305/600 8304/8308/600 +# s 2 +# f 8305/8309/592 8306/8310/592 8307/8311/592 8308/8312/592 +# s 4 +# f 8309/8313/596 8310/8314/596 8311/8315/596 8312/8316/596 +# s 8 +# f 8305/8309/600 8308/8312/600 8310/8314/600 8309/8313/598 +# s 32 +# f 8307/8311/604 8306/8310/604 8312/8316/604 8311/8315/604 +# s 2 +# f 8313/8317/592 8314/8318/592 8315/8319/592 8316/8320/592 +# s 4 +# f 8317/8321/593 8318/8322/593 8319/8323/593 8320/8324/593 +# s 8 +# f 8313/8317/595 8316/8320/595 8318/8322/595 8317/8321/595 +# s 32 +# f 8315/8319/605 8314/8318/605 8320/8324/605 8319/8323/605 +# s 2 +# f 8321/8325/592 8322/8326/592 8323/8327/592 8324/8328/592 +# s 4 +# f 8325/8329/596 8326/8330/596 8327/8331/596 8328/8332/596 +# s 8 +# f 8321/8325/595 8324/8328/595 8326/8330/595 8325/8329/595 +# s 16 +# f 8324/8328/601 8323/8327/601 8327/8331/601 8326/8330/601 +# s 32 +# f 8323/8327/594 8322/8326/594 8328/8332/594 8327/8331/594 +# s 64 +# f 8322/8326/598 8321/8325/598 8325/8329/598 8328/8332/598 +# s 2 +# f 8329/8333/592 8330/8334/592 8331/8335/592 8332/8336/592 +# s 4 +# f 8333/8337/593 8334/8338/593 8335/8339/593 8336/8340/593 +# s 8 +# f 8329/8333/595 8332/8336/595 8334/8338/595 8333/8337/595 +# s 16 +# f 8332/8336/601 8331/8335/601 8335/8339/601 8334/8338/601 +# s 32 +# f 8331/8335/594 8330/8334/594 8336/8340/594 8335/8339/594 +# s 64 +# f 8330/8334/600 8329/8333/598 8333/8337/600 8336/8340/600 +# s 8 +# f 8337/8341/595 8338/8342/595 8339/8343/595 8340/8344/595 +# s 16 +# f 8338/8342/601 8341/8345/601 8342/8346/601 8339/8343/601 +# s 32 +# f 8341/8345/594 8343/8347/594 8344/8348/594 8342/8346/594 +# s 64 +# f 8343/8347/600 8337/8341/600 8340/8344/600 8344/8348/600 +# s 2 +# f 8345/8349/592 8346/8350/592 8347/8351/592 8348/8352/592 +# s 4 +# f 8349/8353/593 8350/8354/593 8351/8355/593 8352/8356/596 +# s 8 +# f 8345/8349/595 8348/8352/595 8350/8354/595 8349/8353/595 +# s 32 +# f 8347/8351/606 8346/8350/606 8352/8356/606 8351/8355/605 +# s 8 +# f 8353/8357/595 8354/8358/595 8355/8359/595 8356/8360/595 +# s 16 +# f 8354/8358/601 8357/8361/601 8358/8362/601 8355/8359/601 +# s 32 +# f 8357/8361/594 8359/8363/594 8360/8364/594 8358/8362/594 +# s 64 +# f 8359/8363/600 8353/8357/600 8356/8360/600 8360/8364/600 +# s 2 +# f 8361/8365/592 8362/8366/592 8363/8367/592 8364/8368/592 +# s 4 +# f 8365/8369/593 8366/8370/593 8367/8371/593 8368/8372/593 +# s 8 +# f 8361/8365/595 8364/8368/595 8366/8370/595 8365/8369/595 +# s 16 +# f 8364/8368/604 8363/8367/601 8367/8371/604 8366/8370/604 +# s 32 +# f 8363/8367/594 8362/8366/594 8368/8372/594 8367/8371/594 +# s 64 +# f 8362/8366/600 8361/8365/600 8365/8369/600 8368/8372/598 +# s 2 +# f 8369/8373/603 8370/8374/592 8371/8375/603 8372/8376/603 +# s 4 +# f 8373/8377/593 8374/8378/593 8375/8379/593 8376/8380/593 +# s 8 +# f 8369/8373/595 8372/8376/595 8374/8378/595 8373/8377/595 +# s 16 +# f 8372/8376/604 8371/8375/604 8375/8379/604 8374/8378/601 +# s 32 +# f 8371/8375/594 8370/8374/594 8376/8380/594 8375/8379/594 +# s 64 +# f 8370/8374/598 8369/8373/598 8373/8377/598 8376/8380/598 +# s 2 +# f 8377/8381/603 8378/8382/603 8379/8383/603 8380/8384/603 +# s 4 +# f 8381/8385/593 8382/8386/593 8383/8387/593 8384/8388/593 +# s 8 +# f 8377/8381/600 8380/8384/598 8382/8386/600 8381/8385/600 +# s 32 +# f 8379/8383/604 8378/8382/604 8384/8388/604 8383/8387/604 +# 132 polygons + diff --git a/simulators/sim_env/models/shipping_container_conveyor_ariac/model.config b/simulators/sim_env/models/shipping_container_conveyor_ariac/model.config new file mode 100755 index 0000000..2bd6dc9 --- /dev/null +++ b/simulators/sim_env/models/shipping_container_conveyor_ariac/model.config @@ -0,0 +1,22 @@ + + + + Shipping Container Conveyor + 1.0 + model.sdf + + + Cole Biesemeyer + cole.bsmr@gmail.com + + + + Nate Koenig + nate@osrfoundation.com + + + + A shipping container conveyor belt with out ramp. + + + diff --git a/simulators/sim_env/models/shipping_container_conveyor_ariac/model.sdf b/simulators/sim_env/models/shipping_container_conveyor_ariac/model.sdf new file mode 100755 index 0000000..6eea385 --- /dev/null +++ b/simulators/sim_env/models/shipping_container_conveyor_ariac/model.sdf @@ -0,0 +1,36 @@ + + + + true + + + 1.191 1.6275 0.32 0 0 0 + 10 + + + 0.137 7.98 0.3 + + + + + + 0.268 1.6275 0.32 0 0 0 + 10 + + + 0.145 7.98 0.3 + + + + + + + + 1.3 0.7 1.0 + model://shipping_container_conveyor_ariac/meshes/ShippingContainer_Textured.obj + + + + + + diff --git a/simulators/sim_env/package.xml b/simulators/sim_env/package.xml new file mode 100755 index 0000000..f549c27 --- /dev/null +++ b/simulators/sim_env/package.xml @@ -0,0 +1,40 @@ + + sim_env + 0.0.1 + + ROS motion planning simulation environment. + + Winter + Winter + BSD + catkin + roscpp + rospy + std_msgs + message_generation + gazebo_ros + rviz + + roscpp + rospy + std_msgs + controller_manager + urdf + effort_controllers + gazebo_plugins + gazebo_ros + gazebo_ros_control + joint_state_controller + joint_state_publisher + robot_state_publisher + yocs_cmd_vel_mux + message_runtime + xacro + rviz + + + + + + + \ No newline at end of file diff --git a/simulators/sim_env/rviz/cache.rviz b/simulators/sim_env/rviz/cache.rviz new file mode 100755 index 0000000..22857cb --- /dev/null +++ b/simulators/sim_env/rviz/cache.rviz @@ -0,0 +1,47 @@ +Panels: +- Class: rviz/Displays + Name: Displays +- Class: rviz/Tool Properties + Name: Tool Properties +Visualization Manager: + Displays: + - Class: rviz/Map + Enabled: true + Name: Map + Topic: /map + - Class: rviz/Grid + Enabled: true + Name: Grid + - Class: rviz/TF + Enabled: false + Name: TF + - Class: rviz/RobotModel + Enabled: true + Name: RobotModel + Robot Description: robot_description + - Class: rviz/Image + Enabled: false + Name: Image + Topic: /camera/rgb/image_raw + - Alpha: 1 + Class: rviz/LaserScan + Color: 255; 0; 0 + Color Transformer: FlatColor + Enabled: true + Name: LaserScan + Size (m): 0.03 + Style: Spheres + Topic: /scan + Global Options: + Fixed Frame: map + Tools: + - Class: rviz/Interact + - Class: rviz/MoveCamera + - Class: rviz/Select + - Class: rviz/FocusCamera + - Class: rviz/Measure + - Class: rviz/PublishPoint + - Class: rviz/SetInitialPose + Topic: /initialpose + - Class: rviz/SetGoal + Topic: /move_base_simple/goal diff --git a/simulators/sim_env/rviz/sim_env.rviz b/simulators/sim_env/rviz/sim_env.rviz new file mode 100755 index 0000000..8bf9718 --- /dev/null +++ b/simulators/sim_env/rviz/sim_env.rviz @@ -0,0 +1,414 @@ +Panels: + - Class: rviz/Displays + Help Height: 138 + Name: Displays + Property Tree Widget: + Expanded: + - /Path1 + - /TrackedPersons1 + - /Map5 + Splitter Ratio: 0.5 + Tree Height: 1520 + - Class: rviz/Selection + Name: Selection + - Class: rviz/Tool Properties + Expanded: + - /2D Pose Estimate1 + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: LaserScan +Preferences: + PromptSaveOnExit: true +Toolbars: + toolButtonStyle: 2 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Alpha: 0.699999988079071 + Class: rviz/Map + Color Scheme: map + Draw Behind: true + Enabled: true + Name: Map + Topic: /map + Unreliable: false + Use Timestamp: false + Value: true + - Alpha: 1 + Class: rviz/RobotModel + Collision Enabled: false + Enabled: true + Links: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + Link Tree Style: Links in Alphabetic Order + base_footprint: + Alpha: 1 + Show Axes: false + Show Trail: false + base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + base_scan: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + camera_depth_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + camera_depth_optical_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + camera_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + camera_rgb_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + camera_rgb_optical_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + caster_back_left_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + caster_back_right_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + imu_link: + Alpha: 1 + Show Axes: false + Show Trail: false + wheel_left_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + wheel_right_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Name: RobotModel + Robot Description: robot_description + TF Prefix: "" + Update Interval: 0 + Value: true + Visual Enabled: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/LaserScan + Color: 255; 255; 255 + Color Transformer: Intensity + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Min Color: 0; 0; 0 + Name: LaserScan + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.10000000149011612 + Style: Squares + Topic: /scan + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true + - Alpha: 1 + Buffer Length: 1 + Class: rviz/Path + Color: 32; 74; 135 + Enabled: true + Head Diameter: 0.30000001192092896 + Head Length: 0.20000000298023224 + Length: 0.30000001192092896 + Line Style: Lines + Line Width: 0.029999999329447746 + Name: Path + Offset: + X: 0 + Y: 0 + Z: 0 + Pose Color: 255; 85; 255 + Pose Style: None + Queue Size: 10 + Radius: 0.029999999329447746 + Shaft Diameter: 0.10000000149011612 + Shaft Length: 0.10000000149011612 + Topic: /move_base/GraphPlanner/plan + Unreliable: false + Value: true + - Alpha: 0.8999999761581421 + Class: rviz/Map + Color Scheme: costmap + Draw Behind: true + Enabled: false + Name: Map + Topic: /move_base/GraphPlanner/expand + Unreliable: false + Use Timestamp: false + Value: false + - Alpha: 0.20000000298023224 + Class: rviz/Map + Color Scheme: costmap + Draw Behind: false + Enabled: false + Name: Map + Topic: /move_base/local_costmap/costmap + Unreliable: false + Use Timestamp: false + Value: false + - Alpha: 0.20000000298023224 + Class: rviz/Map + Color Scheme: costmap + Draw Behind: false + Enabled: false + Name: Map + Topic: /move_base/global_costmap/costmap + Unreliable: false + Use Timestamp: false + Value: false + - Class: rviz/Marker + Enabled: true + Marker Topic: /move_base/SamplePlanner/tree + Name: Marker + Namespaces: + {} + Queue Size: 100 + Value: true + - Alpha: 1 + Axes Length: 1 + Axes Radius: 0.10000000149011612 + Class: rviz/Pose + Color: 255; 25; 0 + Enabled: true + Head Length: 0.30000001192092896 + Head Radius: 0.10000000149011612 + Name: Pose + Queue Size: 10 + Shaft Length: 0.5 + Shaft Radius: 0.05000000074505806 + Shape: Arrow + Topic: /target_pose + Unreliable: false + Value: true + - Alpha: 1 + Axes Length: 1 + Axes Radius: 0.10000000149011612 + Class: rviz/Pose + Color: 0; 255; 0 + Enabled: true + Head Length: 0.30000001192092896 + Head Radius: 0.10000000149011612 + Name: Pose + Queue Size: 10 + Shaft Length: 0.5 + Shaft Radius: 0.05000000074505806 + Shape: Arrow + Topic: /current_pose + Unreliable: false + Value: true + - Alpha: 1 + Axes Length: 1 + Axes Radius: 0.10000000149011612 + Class: rviz/Pose + Color: 32; 74; 135 + Enabled: true + Head Length: 0.30000001192092896 + Head Radius: 0.10000000149011612 + Name: Pose + Queue Size: 10 + Shaft Length: 1 + Shaft Radius: 0.05000000074505806 + Shape: Arrow + Topic: /human_1/pose + Unreliable: false + Value: true + - Alpha: 1 + Axes Length: 1 + Axes Radius: 0.10000000149011612 + Class: rviz/Pose + Color: 32; 74; 135 + Enabled: true + Head Length: 0.30000001192092896 + Head Radius: 0.10000000149011612 + Name: Pose + Queue Size: 10 + Shaft Length: 1 + Shaft Radius: 0.05000000074505806 + Shape: Arrow + Topic: /human_2/pose + Unreliable: false + Value: true + - Alpha: 1 + Class: spencer_tracking_rviz_plugin/TrackedPersons + Color: 130; 130; 130 + Color map offset: 0 + Color transform: Rainbow + Delete after no. cycles: 100 + Enabled: true + Excluded person IDs: "" + Font color: 255; 255; 255 + Font color style: Same color + Font scale: 2 + History as line: + Line width: 0.05000000074505806 + Value: true + History size: 100 + Included person IDs: "" + Min. history point distance: 0.4000000059604645 + Missed alpha: 0.5 + Name: TrackedPersons + Occlusion alpha: 0.30000001192092896 + Queue Size: 10 + Render covariances: + Line width: 0.10000000149011612 + Value: true + Render detection IDs: false + Render history: true + Render person visual: true + Render track IDs: true + Render track state: false + Render velocities: true + Show DELETED tracks: false + Show MATCHED tracks: true + Show MISSED tracks: true + Show OCCLUDED tracks: true + Style: + Line width: 0.05000000074505806 + Scaling factor: 1 + Value: Person meshes + Topic: ped_visualization + Unreliable: false + Value: true + Z offset: + Use Z position from message: false + Value: 0 + - Alpha: 0.30000001192092896 + Class: rviz/Map + Color Scheme: map + Draw Behind: true + Enabled: true + Name: Map + Topic: /move_base/global_costmap/voronoi_layer/voronoi_grid + Unreliable: false + Use Timestamp: false + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Default Light: true + Fixed Frame: map + Frame Rate: 30 + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + - Class: rviz/FocusCamera + - Class: rviz/Measure + - Class: rviz/SetInitialPose + Theta std deviation: 0.2617993950843811 + Topic: /initialpose + X std deviation: 0.5 + Y std deviation: 0.5 + - Class: rviz/SetGoal + Topic: /move_base_simple/goal + - Class: rviz/PublishPoint + Single click: true + Topic: /clicked_point + Value: true + Views: + Current: + Class: rviz/Orbit + Distance: 31.205366134643555 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Field of View: 0.7853981852531433 + Focal Point: + X: -0.006348671857267618 + Y: 0.48202550411224365 + Z: -4.073554039001465 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 1.5697963237762451 + Target Frame: + Yaw: 1.5549954175949097 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 2032 + Hide Left Dock: false + Hide Right Dock: false + QMainWindow State: 000000ff00000000fd000000040000000000000299000006e8fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b000000b000fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000b0fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000006e000006e80000018200fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000015f000006e8fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000006e000006e80000013200fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e1000001970000000300000e7000000060fc0100000002fb0000000800540069006d0065010000000000000e700000057100fffffffb0000000800540069006d0065010000000000000450000000000000000000000a60000006e800000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 3696 + X: 144 + Y: 54 diff --git a/simulators/sim_env/rviz/view_multi.rviz b/simulators/sim_env/rviz/view_multi.rviz new file mode 100755 index 0000000..b7888aa --- /dev/null +++ b/simulators/sim_env/rviz/view_multi.rviz @@ -0,0 +1,330 @@ +Panels: + - Class: rviz/Displays + Help Height: 78 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + Splitter Ratio: 0.5 + Tree Height: 843 + - Class: rviz/Selection + Name: Selection + - Class: rviz/Tool Properties + Expanded: + - /2D Pose Estimate1 + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.588679016 + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: LaserScan +Toolbars: + toolButtonStyle: 2 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.0299999993 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Class: rviz/TF + Enabled: false + Frame Timeout: 15 + Frames: + All Enabled: false + Marker Scale: 1 + Name: TF + Show Arrows: true + Show Axes: true + Show Names: false + Tree: + {} + Update Interval: 0 + Value: false + - Alpha: 1 + Class: rviz/RobotModel + Collision Enabled: false + Enabled: true + Links: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + Link Tree Style: Links in Alphabetic Order + base_footprint: + Alpha: 1 + Show Axes: false + Show Trail: false + base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + camera_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + camera_link_optical: + Alpha: 1 + Show Axes: false + Show Trail: false + imu_link: + Alpha: 1 + Show Axes: false + Show Trail: false + laser: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + laser_mount_link: + Alpha: 1 + Show Axes: false + Show Trail: false + left_wheel: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + pitch_platform: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + right_wheel: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + yaw_platform: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Name: RobotModel + Robot Description: robot1/robot_description + TF Prefix: robot1 + Update Interval: 0 + Value: true + Visual Enabled: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/LaserScan + Color: 255; 255; 255 + Color Transformer: Intensity + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 0 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: LaserScan + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.0299999993 + Style: Squares + Topic: /robot1/scan + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/PointCloud2 + Color: 255; 255; 255 + Color Transformer: RGB8 + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 4096 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: PointCloud2 + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.0199999996 + Style: Flat Squares + Topic: /robot1/camera/depth/points + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true + - Alpha: 1 + Class: rviz/RobotModel + Collision Enabled: false + Enabled: false + Links: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + Link Tree Style: Links in Alphabetic Order + Name: RobotModel + Robot Description: robot2/robot_description + TF Prefix: robot2 + Update Interval: 0 + Value: false + Visual Enabled: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/LaserScan + Color: 255; 255; 255 + Color Transformer: Intensity + Decay Time: 0 + Enabled: false + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 0 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: LaserScan + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.0299999993 + Style: Squares + Topic: /robot2/scan + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: false + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/PointCloud2 + Color: 255; 255; 255 + Color Transformer: RGB8 + Decay Time: 0 + Enabled: false + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 4096 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: PointCloud2 + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.0199999996 + Style: Flat Squares + Topic: /robot2/camera/depth/points + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: false + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Default Light: true + Fixed Frame: robot1/odom + Frame Rate: 30 + Name: root + Tools: + - Class: rviz/MoveCamera + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/Select + - Class: rviz/SetInitialPose + Topic: /initialpose + - Class: rviz/SetGoal + Topic: /move_base_simple/goal + - Class: rviz/Measure + - Class: rviz/PublishPoint + Single click: true + Topic: /clicked_point + Value: true + Views: + Current: + Class: rviz/Orbit + Distance: 14.9153643 + Enable Stereo Rendering: + Stereo Eye Separation: 0.0599999987 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: 1.28042281 + Y: -2.00316596 + Z: 1.72873592 + Focal Shape Fixed Size: true + Focal Shape Size: 0.0500000007 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.00999999978 + Pitch: 0.539797246 + Target Frame: + Value: Orbit (rviz) + Yaw: 1.57499635 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 1056 + Hide Left Dock: false + Hide Right Dock: false + QMainWindow State: 000000ff00000000fd00000004000000000000016a000003dafc0200000005fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006100fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c0061007900730100000028000003da000000d700ffffff00000001000001d5000003dafc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a005600690065007700730100000028000003da000000ad00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004a00000003efc0100000002fb0000000800540069006d00650000000000000004a00000030000fffffffb0000000800540069006d00650100000000000004500000000000000000000003f4000003da00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 1855 + X: 65 + Y: 24 diff --git a/simulators/sim_env/scripts/killpro.sh b/simulators/sim_env/scripts/killpro.sh new file mode 100755 index 0000000..9598986 --- /dev/null +++ b/simulators/sim_env/scripts/killpro.sh @@ -0,0 +1,4 @@ +killall -9 rosmaster +killall -9 roscore +killall gzserver +killall gzclient diff --git a/simulators/sim_env/scripts/main.sh b/simulators/sim_env/scripts/main.sh new file mode 100755 index 0000000..ed3cdc0 --- /dev/null +++ b/simulators/sim_env/scripts/main.sh @@ -0,0 +1,3 @@ +source ../../../devel/setup.bash +python ../../third_party/dynamic_xml_config/main_generate.py user_config.yaml +# roslaunch sim_env main.launch diff --git a/simulators/sim_env/urdf/pictures/frames/burger_frames.pdf b/simulators/sim_env/urdf/pictures/frames/burger_frames.pdf new file mode 100755 index 0000000..3193f20 Binary files /dev/null and b/simulators/sim_env/urdf/pictures/frames/burger_frames.pdf differ diff --git a/simulators/sim_env/urdf/pictures/frames/waffle_frames.pdf b/simulators/sim_env/urdf/pictures/frames/waffle_frames.pdf new file mode 100755 index 0000000..ebf5f82 Binary files /dev/null and b/simulators/sim_env/urdf/pictures/frames/waffle_frames.pdf differ diff --git a/simulators/sim_env/urdf/pictures/frames/waffle_pi_frames.pdf b/simulators/sim_env/urdf/pictures/frames/waffle_pi_frames.pdf new file mode 100755 index 0000000..ec7d0df Binary files /dev/null and b/simulators/sim_env/urdf/pictures/frames/waffle_pi_frames.pdf differ diff --git a/simulators/sim_env/urdf/pictures/frames/xbot_frames.pdf b/simulators/sim_env/urdf/pictures/frames/xbot_frames.pdf new file mode 100755 index 0000000..a4dd459 Binary files /dev/null and b/simulators/sim_env/urdf/pictures/frames/xbot_frames.pdf differ diff --git a/simulators/sim_env/urdf/pictures/turtlebot3_burger.jpg b/simulators/sim_env/urdf/pictures/turtlebot3_burger.jpg new file mode 100755 index 0000000..ccc146f Binary files /dev/null and b/simulators/sim_env/urdf/pictures/turtlebot3_burger.jpg differ diff --git a/simulators/sim_env/urdf/pictures/turtlebot3_waffle.jpg b/simulators/sim_env/urdf/pictures/turtlebot3_waffle.jpg new file mode 100755 index 0000000..200ef56 Binary files /dev/null and b/simulators/sim_env/urdf/pictures/turtlebot3_waffle.jpg differ diff --git a/simulators/sim_env/urdf/pictures/turtlebot3_waffle_pi.jpg b/simulators/sim_env/urdf/pictures/turtlebot3_waffle_pi.jpg new file mode 100755 index 0000000..f1e2340 Binary files /dev/null and b/simulators/sim_env/urdf/pictures/turtlebot3_waffle_pi.jpg differ diff --git a/simulators/sim_env/urdf/turtlebot3_burger/common_properties.xacro b/simulators/sim_env/urdf/turtlebot3_burger/common_properties.xacro new file mode 100755 index 0000000..b26a853 --- /dev/null +++ b/simulators/sim_env/urdf/turtlebot3_burger/common_properties.xacro @@ -0,0 +1,44 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/simulators/sim_env/urdf/turtlebot3_burger/turtlebot3_burger.gazebo.xacro b/simulators/sim_env/urdf/turtlebot3_burger/turtlebot3_burger.gazebo.xacro new file mode 100755 index 0000000..9211733 --- /dev/null +++ b/simulators/sim_env/urdf/turtlebot3_burger/turtlebot3_burger.gazebo.xacro @@ -0,0 +1,135 @@ + + + + + + + Gazebo/DarkGrey + + + + 0.1 + 0.1 + 500000.0 + 10.0 + 0.001 + 0.1 + 1 0 0 + Gazebo/FlatBlack + + + + 0.1 + 0.1 + 500000.0 + 10.0 + 0.001 + 0.1 + 1 0 0 + Gazebo/FlatBlack + + + + 0.1 + 0.1 + 1000000.0 + 100.0 + 0.001 + 1.0 + Gazebo/FlatBlack + + + + + true + $(arg imu_visual) + + Gazebo/FlatBlack + + + + + cmd_vel + odom + odom + world + true + base_footprint + false + true + false + false + 30 + wheel_left_joint + wheel_right_joint + 0.160 + 0.066 + 1 + 10 + na + + + + + + true + imu_link + imu_link + imu + imu_service + 0.0 + 0 + + + gaussian + + 0.0 + 2e-4 + 0.0000075 + 0.0000008 + + + 0.0 + 1.7e-2 + 0.1 + 0.001 + + + + + + + + Gazebo/FlatBlack + + 0 0 0 0 0 0 + $(arg laser_visual) + 5 + + + + 360 + 1 + 0.0 + 6.28319 + + + + 0.120 + 3.5 + 0.015 + + + gaussian + 0.0 + 0.01 + + + + scan + base_scan + + + + + diff --git a/simulators/sim_env/urdf/turtlebot3_burger/turtlebot3_burger.urdf.xacro b/simulators/sim_env/urdf/turtlebot3_burger/turtlebot3_burger.urdf.xacro new file mode 100755 index 0000000..eea9c07 --- /dev/null +++ b/simulators/sim_env/urdf/turtlebot3_burger/turtlebot3_burger.urdf.xacro @@ -0,0 +1,163 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/simulators/sim_env/urdf/turtlebot3_burger/turtlebot3_burger.xacro b/simulators/sim_env/urdf/turtlebot3_burger/turtlebot3_burger.xacro new file mode 100755 index 0000000..4fe3a6d --- /dev/null +++ b/simulators/sim_env/urdf/turtlebot3_burger/turtlebot3_burger.xacro @@ -0,0 +1,8 @@ + + + + + + + + diff --git a/simulators/sim_env/urdf/turtlebot3_waffle/common_properties.xacro b/simulators/sim_env/urdf/turtlebot3_waffle/common_properties.xacro new file mode 100755 index 0000000..b26a853 --- /dev/null +++ b/simulators/sim_env/urdf/turtlebot3_waffle/common_properties.xacro @@ -0,0 +1,44 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/simulators/sim_env/urdf/turtlebot3_waffle/turtlebot3_waffle.gazebo.xacro b/simulators/sim_env/urdf/turtlebot3_waffle/turtlebot3_waffle.gazebo.xacro new file mode 100755 index 0000000..c9e2e0b --- /dev/null +++ b/simulators/sim_env/urdf/turtlebot3_waffle/turtlebot3_waffle.gazebo.xacro @@ -0,0 +1,190 @@ + + + + + + + + Gazebo/DarkGrey + + + + 0.1 + 0.1 + 500000.0 + 10.0 + 0.001 + 0.1 + 1 0 0 + Gazebo/FlatBlack + + + + 0.1 + 0.1 + 500000.0 + 10.0 + 0.001 + 0.1 + 1 0 0 + Gazebo/FlatBlack + + + + 0.1 + 0.1 + 1000000.0 + 100.0 + 0.001 + 1.0 + Gazebo/FlatBlack + + + + 0.1 + 0.1 + 1000000.0 + 100.0 + 0.001 + 1.0 + Gazebo/FlatBlack + + + + + true + $(arg imu_visual) + + Gazebo/Grey + + + + + cmd_vel + odom + odom + world + true + base_footprint + false + true + false + false + 30 + wheel_left_joint + wheel_right_joint + 0.287 + 0.066 + 1 + 10 + na + + + + + + true + imu_link + imu_link + imu + imu_service + 0.0 + 0 + + + gaussian + + 0.0 + 2e-4 + 0.0000075 + 0.0000008 + + + 0.0 + 1.7e-2 + 0.1 + 0.001 + + + + + + + + Gazebo/FlatBlack + + 0 0 0 0 0 0 + $(arg laser_visual) + 5 + + + + 360 + 1 + 0.0 + 6.28319 + + + + 0.120 + 3.5 + 0.015 + + + gaussian + 0.0 + 0.01 + + + + scan + base_scan + + + + + + + true + $(arg camera_visual) + + 1.3439 + + 1920 + 1080 + R8G8B8 + + + + 0.03 + 100 + + + + 0.2 + true + 30.0 + camera + camera_rgb_optical_frame + rgb/image_raw + depth/image_raw + depth/points + rgb/camera_info + depth/camera_info + 0.4 + 0.07 + 0.0 + 0.0 + 0.0 + 0.0 + 0.0 + 0.0 + 0.0 + 0.0 + 0 + 0 + + + + + diff --git a/simulators/sim_env/urdf/turtlebot3_waffle/turtlebot3_waffle.urdf.xacro b/simulators/sim_env/urdf/turtlebot3_waffle/turtlebot3_waffle.urdf.xacro new file mode 100755 index 0000000..742d26c --- /dev/null +++ b/simulators/sim_env/urdf/turtlebot3_waffle/turtlebot3_waffle.urdf.xacro @@ -0,0 +1,249 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/simulators/sim_env/urdf/turtlebot3_waffle/turtlebot3_waffle.xacro b/simulators/sim_env/urdf/turtlebot3_waffle/turtlebot3_waffle.xacro new file mode 100755 index 0000000..a1ba42b --- /dev/null +++ b/simulators/sim_env/urdf/turtlebot3_waffle/turtlebot3_waffle.xacro @@ -0,0 +1,8 @@ + + + + + + + + diff --git a/simulators/sim_env/urdf/turtlebot3_waffle_pi/common_properties.xacro b/simulators/sim_env/urdf/turtlebot3_waffle_pi/common_properties.xacro new file mode 100755 index 0000000..b26a853 --- /dev/null +++ b/simulators/sim_env/urdf/turtlebot3_waffle_pi/common_properties.xacro @@ -0,0 +1,44 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/simulators/sim_env/urdf/turtlebot3_waffle_pi/turtlebot3_waffle_pi.gazebo.xacro b/simulators/sim_env/urdf/turtlebot3_waffle_pi/turtlebot3_waffle_pi.gazebo.xacro new file mode 100755 index 0000000..3ac563c --- /dev/null +++ b/simulators/sim_env/urdf/turtlebot3_waffle_pi/turtlebot3_waffle_pi.gazebo.xacro @@ -0,0 +1,180 @@ + + + + + + + + Gazebo/DarkGrey + + + + 0.1 + 0.1 + 500000.0 + 10.0 + 0.001 + 0.1 + 1 0 0 + Gazebo/FlatBlack + + + + 0.1 + 0.1 + 500000.0 + 10.0 + 0.001 + 0.1 + 1 0 0 + Gazebo/FlatBlack + + + + 0.1 + 0.1 + 1000000.0 + 100.0 + 0.001 + 1.0 + Gazebo/FlatBlack + + + + 0.1 + 0.1 + 1000000.0 + 100.0 + 0.001 + 1.0 + Gazebo/FlatBlack + + + + + true + $(arg imu_visual) + + Gazebo/Grey + + + + + cmd_vel + odom + odom + world + true + base_footprint + true + true + true + false + 30 + wheel_left_joint + wheel_right_joint + 0.287 + 0.066 + 1 + 10 + na + + + + + + true + imu_link + imu_link + imu + imu_service + 0.0 + 0 + + + gaussian + + 0.0 + 2e-4 + 0.0000075 + 0.0000008 + + + 0.0 + 1.7e-2 + 0.1 + 0.001 + + + + + + + + Gazebo/FlatBlack + + 0 0 0 0 0 0 + $(arg laser_visual) + 5 + + + + 360 + 1 + 0.0 + 6.28319 + + + + 0.120 + 3.5 + 0.015 + + + gaussian + 0.0 + 0.01 + + + + scan + base_scan + + + + + + + + true + $(arg camera_visual) + + 1.085595 + + 640 + 480 + R8G8B8 + + + 0.03 + 100 + + + + true + 30.0 + camera + camera_rgb_optical_frame + rgb/image_raw + rgb/camera_info + 0.07 + 0.0 + 0.0 + 0.0 + 0.0 + 0.0 + + + + + diff --git a/simulators/sim_env/urdf/turtlebot3_waffle_pi/turtlebot3_waffle_pi.urdf.xacro b/simulators/sim_env/urdf/turtlebot3_waffle_pi/turtlebot3_waffle_pi.urdf.xacro new file mode 100755 index 0000000..9af6793 --- /dev/null +++ b/simulators/sim_env/urdf/turtlebot3_waffle_pi/turtlebot3_waffle_pi.urdf.xacro @@ -0,0 +1,215 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/simulators/sim_env/urdf/turtlebot3_waffle_pi/turtlebot3_waffle_pi.xacro b/simulators/sim_env/urdf/turtlebot3_waffle_pi/turtlebot3_waffle_pi.xacro new file mode 100755 index 0000000..e6103bb --- /dev/null +++ b/simulators/sim_env/urdf/turtlebot3_waffle_pi/turtlebot3_waffle_pi.xacro @@ -0,0 +1,8 @@ + + + + + + + + diff --git a/simulators/sim_env/worlds/pictures/turtlebot3_house.jpg b/simulators/sim_env/worlds/pictures/turtlebot3_house.jpg new file mode 100755 index 0000000..d231c88 Binary files /dev/null and b/simulators/sim_env/worlds/pictures/turtlebot3_house.jpg differ diff --git a/simulators/sim_env/worlds/pictures/workshop.jpg b/simulators/sim_env/worlds/pictures/workshop.jpg new file mode 100755 index 0000000..77dcbd3 Binary files /dev/null and b/simulators/sim_env/worlds/pictures/workshop.jpg differ diff --git a/simulators/sim_env/worlds/turtlebot3_house.world b/simulators/sim_env/worlds/turtlebot3_house.world new file mode 100755 index 0000000..0f5d327 --- /dev/null +++ b/simulators/sim_env/worlds/turtlebot3_house.world @@ -0,0 +1,53 @@ + + + + + + model://sun + + + + + model://ground_plane + + + + 1000.0 + 0.001 + 1 + + + quick + 150 + 0 + 1.400000 + 1 + + + 0.00001 + 0.2 + 2000.000000 + 0.01000 + + + + + + + model://turtlebot3_house + + + + 0.4 0.4 0.4 1 + 0.7 0.7 0.7 1 + true + + + + + 0.0 0.0 17.0 0 1.5708 0 + orbit + + + + diff --git a/simulators/sim_env/worlds/turtlebot3_stage_1.world b/simulators/sim_env/worlds/turtlebot3_stage_1.world new file mode 100755 index 0000000..de2b241 --- /dev/null +++ b/simulators/sim_env/worlds/turtlebot3_stage_1.world @@ -0,0 +1,53 @@ + + + + + + model://sun + + + + + model://ground_plane + + + + 1000.0 + 0.001 + 1 + + + quick + 150 + 0 + 1.400000 + 1 + + + 0.00001 + 0.2 + 2000.000000 + 0.01000 + + + + + + + model://turtlebot3_square + + + + 0.4 0.4 0.4 1 + 0.7 0.7 0.7 1 + true + + + + + 0.0 0.0 17.0 0 1.5708 0 + orbit + + + + diff --git a/simulators/sim_env/worlds/turtlebot3_stage_2.world b/simulators/sim_env/worlds/turtlebot3_stage_2.world new file mode 100755 index 0000000..d931d6b --- /dev/null +++ b/simulators/sim_env/worlds/turtlebot3_stage_2.world @@ -0,0 +1,203 @@ + + + + + + model://sun + + + + + model://ground_plane + + + + 1000.0 + 0.001 + 1 + + + quick + 150 + 0 + 1.400000 + 1 + + + 0.00001 + 0.2 + 2000.000000 + 0.01000 + + + + + + + model://turtlebot3_square + + + + 0 0 0 0 -0 0 + + + -0.6 -0.6 0.25 0 0 0 + + + 0.15 + 0.5 + + + 10 + + + + + + + + + + + + + -0.6 -0.6 0.25 0 0 0 + + + 0.15 + 0.5 + + + + + + + + + -0.6 0.6 0.25 0 0 0 + + + 0.15 + 0.5 + + + 10 + + + + + + + + + + + + + -0.6 0.6 0.25 0 0 0 + + + 0.15 + 0.5 + + + + + + + + + 0.6 -0.6 0.25 0 0 0 + + + 0.15 + 0.5 + + + 10 + + + + + + + + + + + + + 0.6 -0.6 0.25 0 0 0 + + + 0.15 + 0.5 + + + + + + + + + 0.6 0.6 0.25 0 0 0 + + + 0.15 + 0.5 + + + 10 + + + + + + + + + + + + + 0.6 0.6 0.25 0 0 0 + + + 0.15 + 0.5 + + + + + + + + 1 + + + + 0.4 0.4 0.4 1 + 0.7 0.7 0.7 1 + true + + + + + 0.0 0.0 17.0 0 1.5708 0 + orbit + + + + diff --git a/simulators/sim_env/worlds/turtlebot3_stage_3.world b/simulators/sim_env/worlds/turtlebot3_stage_3.world new file mode 100755 index 0000000..6796fff --- /dev/null +++ b/simulators/sim_env/worlds/turtlebot3_stage_3.world @@ -0,0 +1,202 @@ + + + + + + model://sun + + + + + model://ground_plane + + + + 1000.0 + 0.001 + 1 + + + quick + 150 + 0 + 1.400000 + 1 + + + 0.00001 + 0.2 + 2000.000000 + 0.01000 + + + + + + + model://turtlebot3_square + + + + 0 0 0 0 -0 0 + + + -0.6 -0.6 0.25 0 0 0 + + + 0.15 + 0.5 + + + 10 + + + + + + + + + + + + + -0.6 -0.6 0.25 0 0 0 + + + 0.15 + 0.5 + + + + + + + + + -0.6 0.6 0.25 0 0 0 + + + 0.15 + 0.5 + + + 10 + + + + + + + + + + + + + -0.6 0.6 0.25 0 0 0 + + + 0.15 + 0.5 + + + + + + + + + 0.6 -0.6 0.25 0 0 0 + + + 0.15 + 0.5 + + + 10 + + + + + + + + + + + + + 0.6 -0.6 0.25 0 0 0 + + + 0.15 + 0.5 + + + + + + + + + 0.6 0.6 0.25 0 0 0 + + + 0.15 + 0.5 + + + 10 + + + + + + + + + + + + + 0.6 0.6 0.25 0 0 0 + + + 0.15 + 0.5 + + + + + + + + + + + 0.4 0.4 0.4 1 + 0.7 0.7 0.7 1 + true + + + + + 0.0 0.0 17.0 0 1.5708 0 + orbit + + + + diff --git a/simulators/sim_env/worlds/turtlebot3_stage_4.world b/simulators/sim_env/worlds/turtlebot3_stage_4.world new file mode 100755 index 0000000..7623f2e --- /dev/null +++ b/simulators/sim_env/worlds/turtlebot3_stage_4.world @@ -0,0 +1,101 @@ + + + + + + model://sun + + + + + model://ground_plane + + + + 1000.0 + 0.001 + 1 + + + quick + 150 + 0 + 1.400000 + 1 + + + 0.00001 + 0.2 + 2000.000000 + 0.01000 + + + + + + + model://turtlebot3_plaza + + + + + 2 2 0 0 0 0 + + + + + 0.12 + 0.25 + + + + + + + + 0.12 + 0.25 + + + + + + + + -2 -2 0 0 0 0 + + + + + 0.12 + 0.25 + + + + + + + + 0.12 + 0.25 + + + + + + + + + 0.4 0.4 0.4 1 + 0.7 0.7 0.7 1 + true + + + + + 0.0 0.0 17.0 0 1.5708 0 + orbit + + + + diff --git a/simulators/sim_env/worlds/turtlebot3_world.world b/simulators/sim_env/worlds/turtlebot3_world.world new file mode 100755 index 0000000..1d276b7 --- /dev/null +++ b/simulators/sim_env/worlds/turtlebot3_world.world @@ -0,0 +1,53 @@ + + + + + + model://sun + + + + + model://ground_plane + + + + 1000.0 + 0.001 + 1 + + + quick + 150 + 0 + 1.400000 + 1 + + + 0.00001 + 0.2 + 2000.000000 + 0.01000 + + + + + + + model://turtlebot3_world + + + + 0.4 0.4 0.4 1 + 0.7 0.7 0.7 1 + true + + + + + 0.8 0.0 12.0 0 1.5708 0 + orbit + + + + diff --git a/simulators/sim_env/worlds/warehouse.world b/simulators/sim_env/worlds/warehouse.world new file mode 100755 index 0000000..bdf5142 --- /dev/null +++ b/simulators/sim_env/worlds/warehouse.world @@ -0,0 +1,1997 @@ + + + + 1 + 0 0 10 0 -0 0 + 0.8 0.8 0.8 1 + 0.2 0.2 0.2 1 + + 1000 + 0.9 + 0.01 + 0.001 + + -0.5 0.1 -0.9 + + 0 + 0 + 0 + + + + 1 + + + + + 0 0 1 + 100 100 + + + + + + 100 + 50 + + + + + + + + + + + 10 + + + 0 + + + 0 0 1 + 100 100 + + + + + + + 0 + 0 + 0 + + + 0 0 -9.8 + 6e-06 2.3e-05 -4.2e-05 + + + 0.001 + 1 + 1000 + + + 0.4 0.4 0.4 1 + 0.7 0.7 0.7 1 + 1 + + + + EARTH_WGS84 + 0 + 0 + 0 + 0 + + + 1 + + + 1.191 1.6275 0.32 0 -0 0 + 10 + + + 0.137 7.98 0.3 + + + + + + + + + + + + + + + + + 0.268 1.6275 0.32 0 -0 0 + 10 + + + 0.145 7.98 0.3 + + + + + + + + + + + + + + + + + + + 1.3 0.7 1 + model://sim_env/models/shipping_container_conveyor_ariac/meshes/ShippingContainer_Textured.obj + + + + 0 + 0 + 0 + + 5.94716 0.254888 0 0 -0 0 + + + + + 2 + + 0.841 + 0 + 0 + 0.954 + 0 + 1.422 + + + + + + model://sim_env/models/aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://sim_env/models/aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 4.52823 -6.5 0 0 -0 0 + + + + + 1 + + 1.558 + 0 + 0 + 1.821 + 0 + 1.892 + + + + + + model://sim_env/models/aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://sim_env/models/aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 6.33701 -4.2 0 0 -0 0 + + + + + 2 + + 0.841 + 0 + 0 + 0.954 + 0 + 1.422 + + + + + + model://sim_env/models/aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://sim_env/models/aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 4.5893 -4.7 0 0 -0 0 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + -6 3.5 -0.7 0 -0 0 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 0 3.5 -0.7 0 -0 0 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + -6 6.63287 -0.7 0 -0 0 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 0 6.5 -0.7 0 -0 0 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + -2 -0.5 -0.7 0 -0 1.57 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + -5 -0.5 -0.7 0 -0 1.57 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + -2 -5.88998 -0.7 0 -0 1.57 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + -5 -5.9682 -0.7 0 -0 1.57 + + + 0 0 + 0 0 + 1679208078 74263312 + 0 + + 6.98561 -2.64944 0.000917 0 -2e-06 0 + 1 1 1 + + 6.98561 -2.64944 0.000917 0 -2e-06 0 + 0 0 0 0 -0 0 + -0.006033 -0 -5e-06 0 -0.280679 4e-06 + -0.006033 -0 -5e-06 0 -0 0 + + + + 4.52823 -6.5 0 0 -0 0 + 1 1 1 + + 4.52823 -6.5 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 4.5893 -4.7 0 0 -0 0 + 1 1 1 + + 4.5893 -4.7 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 6.33701 -4.2 0 0 -0 0 + 1 1 1 + + 6.33701 -4.2 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 6.2 -6.2 0 0 -0 0 + 1 1 1 + + 6.2 -6.2 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 6.49861 6.95891 0 0 -0 0 + 1 1 1 + + 6.49861 6.95891 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 5.56779 -2.61305 -0.5 0 -0 0 + 1 1 1 + + 5.56779 -2.61305 -0.5 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -6 6.63287 -0.7 0 -0 0 + 1 1 1 + + -6 6.63287 -0.7 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 0 6.5 -0.7 0 -0 0 + 1 1 1 + + 0 6.5 -0.7 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -2 -0.5 -0.7 0 -0 1.57 + 1 1 1 + + -2 -0.5 -0.7 0 -0 1.57 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -5 -0.5 -0.7 0 -0 1.57 + 1 1 1 + + -5 -0.5 -0.7 0 -0 1.57 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -2 -5.88998 -0.7 0 -0 1.57 + 1 1 1 + + -2 -5.88998 -0.7 0 -0 1.57 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -5 -5.9682 -0.7 0 -0 1.57 + 1 1 1 + + -5 -5.9682 -0.7 0 -0 1.57 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -7.95437 -5.83764 -0.7 0 -0 1.57 + 1 1 1 + + -7.95437 -5.83764 -0.7 0 -0 1.57 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -7.82227 -0.391682 -0.7 0 -0 1.57 + 1 1 1 + + -7.82227 -0.391682 -0.7 0 -0 1.57 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -6 3.5 -0.7 0 -0 0 + 1 1 1 + + -6 3.5 -0.7 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 0 3.5 -0.7 0 -0 0 + 1 1 1 + + 0 3.5 -0.7 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 0 0 0 0 -0 0 + 1 1 1 + + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 5.94716 0.254888 -0.15 0 -0 0 + 1 1 1 + + 5.94716 0.254888 -0.15 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -10 0 0 0 -0 1.57 + 1 1 1 + + -10 0 0 0 -0 1.57 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 0.7388 -5.70207 0 0 0 -1.57 + 1 1 1 + + 0.7388 -5.70207 0 0 0 -1.57 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 1.40743 -1.85107 0 0 -0 3.14 + 1 1 1 + + 1.40743 -1.85107 0 0 -0 3.14 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 5.36173 -1.85107 0 0 -0 3.14 + 1 1 1 + + 5.36173 -1.85107 0 0 -0 3.14 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 8.68743 -1.85107 0 0 -0 3.14 + 1 1 1 + + 8.68743 -1.85107 0 0 -0 3.14 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 0 10 0 0 -0 0 + 1 1 1 + + 0 10 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 0 -10 0 0 -0 3.14 + 1 1 1 + + 0 -10 0 0 -0 3.14 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 10 0 0 0 0 -1.57 + 1 1 1 + + 10 0 0 0 0 -1.57 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 0 0 10 0 -0 0 + + + + + 11.0426 21.9041 29.5178 0 0.900977 -2.0681 + orbit + perspective + + + + + + 1 + + 1.558 + 0 + 0 + 1.821 + 0 + 1.892 + + + + + + model://sim_env/models/aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://sim_env/models/aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 6.49861 6.95891 0 0 -0 0 + + + + + 1 + + 1.558 + 0 + 0 + 1.821 + 0 + 1.892 + + + + + + model://sim_env/models/aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://sim_env/models/aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 6.01431 -6.50899 0 0 -0 0 + + + + + 1 + + 1.558 + 0 + 0 + 1.821 + 0 + 1.892 + + + + + + model://sim_env/models/aws_robomaker_warehouse_ClutteringD_01/meshes/aws_robomaker_warehouse_ClutteringD_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://sim_env/models/aws_robomaker_warehouse_ClutteringD_01/meshes/aws_robomaker_warehouse_ClutteringD_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 5.5675 -2.73505 0 0 -0 0 + + + + + + + model://sim_env/models/dumpster/meshes/dumpster.dae + + + 10 + + + + + + + + + + + + + + + + + model://sim_env/models/dumpster/meshes/dumpster.dae + + + + + + + 0 + + 0 0 0 0 -0 0 + + 1 + 0 + 0 + 1 + 0 + 1 + + 1 + + 0 + 0 + + 8.07649 -2.37718 0 0 -0 0 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + -7.95437 -5.83764 -0.7 0 -0 1.57 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + -7.82227 -0.391682 -0.7 0 -0 1.57 + + + -10 0 0 0 -0 1.57 + + + + + 20 0.15 2.5 + + + 0 0 1.25 0 -0 0 + 10 + + + + + + + + + + + + + + + 0 0 1.25 0 -0 0 + + + 20 0.15 2.5 + + + + + 1 1 1 1 + + + 0 + + + 0 0 0 0 -0 0 + 0 + 0 + 0 + + 1 + + + 0 10 0 0 -0 0 + + + + + 20 0.15 2.5 + + + 0 0 1.25 0 -0 0 + 10 + + + + + + + + + + + + + + + 0 0 1.25 0 -0 0 + + + 20 0.15 2.5 + + + + + 1 1 1 1 + + + 0 + + + 0 0 0 0 -0 0 + 0 + 0 + 0 + + 1 + + + 0 -10 0 0 -0 3.14 + + + + + 20 0.15 2.5 + + + 0 0 1.25 0 -0 0 + 10 + + + + + + + + + + + + + + + 0 0 1.25 0 -0 0 + + + 20 0.15 2.5 + + + + + 1 1 1 1 + + + 0 + + + 0 0 0 0 -0 0 + 0 + 0 + 0 + + 1 + + + 10 0 0 0 0 -1.57 + + + + + 20 0.15 2.5 + + + 0 0 1.25 0 -0 0 + 10 + + + + + + + + + + + + + + + 0 0 1.25 0 -0 0 + + + 20 0.15 2.5 + + + + + 1 1 1 1 + + + 0 + + + 0 0 0 0 -0 0 + 0 + 0 + 0 + + 1 + + + 0.7388 -5.70207 0 0 0 -1.57 + + + + + 8 0.15 2.5 + + + 0 0 1.25 0 -0 0 + 10 + + + + + + + + + + + + + + + 0 0 1.25 0 -0 0 + + + 8 0.15 2.5 + + + + + 1 1 1 1 + + + 0 + + + 0 0 0 0 -0 0 + 0 + 0 + 0 + + 1 + + + + 0 0 0 0 -0 0 + 0 + 0 + 0 + + + 0 + 0 + 0 + 0 + 0 + 0 + + 0 + 0 0 0 0 -0 0 + + 1 + + 0 0 1.25 0 -0 0 + + + 1 0.15 2.5 + + + + + 1 1 1 1 + + __default__ + + 1 1 1 1 + 0.2 0.2 0.2 1 + 0 0 0 1 + + + 0 + + 0 + 1 + + + 0 + 10 + 0 0 1.25 0 -0 0 + + + 1 0.15 2.5 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 1 + 1 + 5.36173 -1.85107 0 0 -0 3.14 + + + + -0 0 0 0 -0 0 + 0 + 0 + 0 + + + 0 + 0 + 0 + 0 + 0 + 0 + + 0 + 0 0 0 0 -0 0 + + 1 + + 0 0 1.25 0 -0 0 + + + 1.5 0.15 2.5 + + + + + 1 1 1 1 + + __default__ + + 1 1 1 1 + 0.2 0.2 0.2 1 + 0 0 0 1 + + + 0 + + 0 + 1 + + + 0 + 10 + 0 0 1.25 0 -0 0 + + + 1 0.15 2.5 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 1 + 1 + 1.40743 -1.85107 0 0 -0 3.14 + + + + -0 0 0 0 -0 0 + 0 + 0 + 0 + + + 0 + 0 + 0 + 0 + 0 + 0 + + 0 + 0 0 0 0 -0 0 + + 1 + + 0 0 1.25 0 -0 0 + + + 2.25 0.15 2.5 + + + + + 1 1 1 1 + + __default__ + + 1 1 1 1 + 0.2 0.2 0.2 1 + 0 0 0 1 + + + 0 + + 0 + 1 + + + 0 + 10 + 0 0 1.25 0 -0 0 + + + 2.25 0.15 2.5 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 1 + 1 + 8.68743 -1.85107 0 0 -0 3.14 + + + diff --git a/simulators/sim_env/worlds/warehouse_with_obstacles.world b/simulators/sim_env/worlds/warehouse_with_obstacles.world new file mode 100755 index 0000000..4933162 --- /dev/null +++ b/simulators/sim_env/worlds/warehouse_with_obstacles.world @@ -0,0 +1,2292 @@ + + + + 1 + 0 0 10 0 -0 0 + 0.8 0.8 0.8 1 + 0.2 0.2 0.2 1 + + 1000 + 0.9 + 0.01 + 0.001 + + -0.5 0.1 -0.9 + + 0 + 0 + 0 + + + + 1 + + + + + 0 0 1 + 100 100 + + + + + + 100 + 50 + + + + + + + + + + + 10 + + + 0 + + + 0 0 1 + 100 100 + + + + + + + 0 + 0 + 0 + + + 0 0 -9.8 + 6e-06 2.3e-05 -4.2e-05 + + + 0.001 + 1 + 1000 + + + 0.4 0.4 0.4 1 + 0.7 0.7 0.7 1 + 1 + + + + EARTH_WGS84 + 0 + 0 + 0 + 0 + + + 1 + + + 1.191 1.6275 0.32 0 -0 0 + 10 + + + 0.137 7.98 0.3 + + + + + + + + + + + + + + + + + 0.268 1.6275 0.32 0 -0 0 + 10 + + + 0.145 7.98 0.3 + + + + + + + + + + + + + + + + + + + 1.3 0.7 1 + model://sim_env/models/shipping_container_conveyor_ariac/meshes/ShippingContainer_Textured.obj + + + + 0 + 0 + 0 + + 5.94716 0.254888 0 0 -0 0 + + + + + 2 + + 0.841 + 0 + 0 + 0.954 + 0 + 1.422 + + + + + + model://sim_env/models/aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://sim_env/models/aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 4.52823 -6.5 0 0 -0 0 + + + + + 1 + + 1.558 + 0 + 0 + 1.821 + 0 + 1.892 + + + + + + model://sim_env/models/aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://sim_env/models/aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 6.33701 -4.2 0 0 -0 0 + + + + + 2 + + 0.841 + 0 + 0 + 0.954 + 0 + 1.422 + + + + + + model://sim_env/models/aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://sim_env/models/aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 4.5893 -4.7 0 0 -0 0 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + -6 3.5 -0.7 0 -0 0 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 0 3.5 -0.7 0 -0 0 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + -6 6.63287 -0.7 0 -0 0 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 0 6.5 -0.7 0 -0 0 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + -2 -0.5 -0.7 0 -0 1.57 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + -5 -0.5 -0.7 0 -0 1.57 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + -2 -5.88998 -0.7 0 -0 1.57 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + -5 -5.9682 -0.7 0 -0 1.57 + + + 0 0 + 0 0 + 1679208078 74263312 + 0 + + 3.9 3.5 -0 0 -1e-06 0 + 1 1 1 + + 3.9 3.5 -0 0 -1e-06 0 + 0 0 0 0 -0 0 + -0 0 0.008512 2.58585 -1.13682 -3.14159 + -0 0 0.008512 0 -0 0 + + + + 2.5 3.5 0 -0 -0 -0 + 1 1 1 + + 2.5 3.5 0 -0 -0 -0 + 0 0 0 0 -0 0 + 0 0 -9.8 0 -0 0 + 0 0 -9.8 0 -0 0 + + + + 3.9 2.8 -0 0 -1e-06 0 + 1 1 1 + + 3.9 2.8 -0 0 -1e-06 0 + 0 0 0 0 -0 0 + -0 0 0.008512 2.58585 -1.13682 -3.14159 + -0 0 0.008512 0 -0 0 + + + + 3.9 2.1 -5e-06 -4e-06 1e-06 0 + 1 1 1 + + 3.9 2.1 -5e-06 -4e-06 1e-06 0 + 0 0 0 0 -0 0 + 0 0 -9.8 -0 -0 -0 + 0 0 -9.8 0 -0 0 + + + + 3.2 3.5 -0 0 -0 0 + 1 1 1 + + 3.2 3.5 -0 0 -0 0 + 0 0 0 0 -0 0 + 0 -0 -0.008512 -2.58585 1.13682 3.14159 + 0 -0 -0.008512 0 -0 0 + + + + 6.98561 -2.64944 0.000917 0 -2e-06 0 + 1 1 1 + + 6.98561 -2.64944 0.000917 0 -2e-06 0 + 0 0 0 0 -0 0 + -0.006033 -0 -5e-06 0 -0.280679 4e-06 + -0.006033 -0 -5e-06 0 -0 0 + + + + 4.52823 -6.5 0 0 -0 0 + 1 1 1 + + 4.52823 -6.5 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 4.5893 -4.7 0 0 -0 0 + 1 1 1 + + 4.5893 -4.7 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 6.33701 -4.2 0 0 -0 0 + 1 1 1 + + 6.33701 -4.2 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 6.2 -6.2 0 0 -0 0 + 1 1 1 + + 6.2 -6.2 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 6.49861 6.95891 0 0 -0 0 + 1 1 1 + + 6.49861 6.95891 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 5.56779 -2.61305 -0.5 0 -0 0 + 1 1 1 + + 5.56779 -2.61305 -0.5 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -6 6.63287 -0.7 0 -0 0 + 1 1 1 + + -6 6.63287 -0.7 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 0 6.5 -0.7 0 -0 0 + 1 1 1 + + 0 6.5 -0.7 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -2 -0.5 -0.7 0 -0 1.57 + 1 1 1 + + -2 -0.5 -0.7 0 -0 1.57 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -5 -0.5 -0.7 0 -0 1.57 + 1 1 1 + + -5 -0.5 -0.7 0 -0 1.57 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -2 -5.88998 -0.7 0 -0 1.57 + 1 1 1 + + -2 -5.88998 -0.7 0 -0 1.57 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -5 -5.9682 -0.7 0 -0 1.57 + 1 1 1 + + -5 -5.9682 -0.7 0 -0 1.57 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -7.95437 -5.83764 -0.7 0 -0 1.57 + 1 1 1 + + -7.95437 -5.83764 -0.7 0 -0 1.57 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -7.82227 -0.391682 -0.7 0 -0 1.57 + 1 1 1 + + -7.82227 -0.391682 -0.7 0 -0 1.57 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -6 3.5 -0.7 0 -0 0 + 1 1 1 + + -6 3.5 -0.7 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 0 3.5 -0.7 0 -0 0 + 1 1 1 + + 0 3.5 -0.7 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 0 0 0 0 -0 0 + 1 1 1 + + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 5.94716 0.254888 -0.15 0 -0 0 + 1 1 1 + + 5.94716 0.254888 -0.15 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -10 0 0 0 -0 1.57 + 1 1 1 + + -10 0 0 0 -0 1.57 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 0.7388 -5.70207 0 0 0 -1.57 + 1 1 1 + + 0.7388 -5.70207 0 0 0 -1.57 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 1.40743 -1.85107 0 0 -0 3.14 + 1 1 1 + + 1.40743 -1.85107 0 0 -0 3.14 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 5.36173 -1.85107 0 0 -0 3.14 + 1 1 1 + + 5.36173 -1.85107 0 0 -0 3.14 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 8.68743 -1.85107 0 0 -0 3.14 + 1 1 1 + + 8.68743 -1.85107 0 0 -0 3.14 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 0 10 0 0 -0 0 + 1 1 1 + + 0 10 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 0 -10 0 0 -0 3.14 + 1 1 1 + + 0 -10 0 0 -0 3.14 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 10 0 0 0 0 -1.57 + 1 1 1 + + 10 0 0 0 0 -1.57 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 0 0 10 0 -0 0 + + + + + 11.0426 21.9041 29.5178 0 0.900977 -2.0681 + orbit + perspective + + + + + + 1 + + 1.558 + 0 + 0 + 1.821 + 0 + 1.892 + + + + + + model://sim_env/models/aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://sim_env/models/aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 6.49861 6.95891 0 0 -0 0 + + + + + 1 + + 1.558 + 0 + 0 + 1.821 + 0 + 1.892 + + + + + + model://sim_env/models/aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://sim_env/models/aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 6.01431 -6.50899 0 0 -0 0 + + + + + 1 + + 1.558 + 0 + 0 + 1.821 + 0 + 1.892 + + + + + + model://sim_env/models/aws_robomaker_warehouse_ClutteringD_01/meshes/aws_robomaker_warehouse_ClutteringD_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://sim_env/models/aws_robomaker_warehouse_ClutteringD_01/meshes/aws_robomaker_warehouse_ClutteringD_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 5.5675 -2.73505 0 0 -0 0 + + + + + + + model://sim_env/models/dumpster/meshes/dumpster.dae + + + 10 + + + + + + + + + + + + + + + + + model://sim_env/models/dumpster/meshes/dumpster.dae + + + + + + + 0 + + 0 0 0 0 -0 0 + + 1 + 0 + 0 + 1 + 0 + 1 + + 1 + + 0 + 0 + + 8.07649 -2.37718 0 0 -0 0 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + -7.95437 -5.83764 -0.7 0 -0 1.57 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + -7.82227 -0.391682 -0.7 0 -0 1.57 + + + + + + + 10 10 10 + model://sim_env/models/construction_cone/meshes/construction_cone.dae + + + 10 + + + + + + + + + + + + + + + + + 10 10 10 + model://sim_env/models/construction_cone/meshes/construction_cone.dae + + + + 0 + + 0 0 0 0 -0 0 + + 1 + 0 + 0 + 1 + 0 + 1 + + 1 + + 0 + 0 + + 3.9 3.5 -0 0 -1e-06 0 + + + + + + + 10 10 10 + model://sim_env/models/construction_cone/meshes/construction_cone.dae + + + 10 + + + + + + + + + + + + + + + + + 10 10 10 + model://sim_env/models/construction_cone/meshes/construction_cone.dae + + + + 0 + + 0 0 0 0 -0 0 + + 1 + 0 + 0 + 1 + 0 + 1 + + 1 + + 0 + 0 + + 2.5 3.5 0 -0 -0 -0 + + + + + + + 10 10 10 + model://sim_env/models/construction_cone/meshes/construction_cone.dae + + + 10 + + + + + + + + + + + + + + + + + 10 10 10 + model://sim_env/models/construction_cone/meshes/construction_cone.dae + + + + 0 + + 0 0 0 0 -0 0 + + 1 + 0 + 0 + 1 + 0 + 1 + + 1 + + 0 + 0 + + 3.9 2.8 -0 0 -1e-06 0 + + + + + + + 10 10 10 + model://sim_env/models/construction_cone/meshes/construction_cone.dae + + + 10 + + + + + + + + + + + + + + + + + 10 10 10 + model://sim_env/models/construction_cone/meshes/construction_cone.dae + + + + 0 + + 0 0 0 0 -0 0 + + 1 + 0 + 0 + 1 + 0 + 1 + + 1 + + 0 + 0 + + 3.9 2.1 -5e-06 -4e-06 1e-06 0 + + + + + + + 10 10 10 + model://sim_env/models/construction_cone/meshes/construction_cone.dae + + + 10 + + + + + + + + + + + + + + + + + 10 10 10 + model://sim_env/models/construction_cone/meshes/construction_cone.dae + + + + 0 + + 0 0 0 0 -0 0 + + 1 + 0 + 0 + 1 + 0 + 1 + + 1 + + 0 + 0 + + 3.2 3.5 -0 0 -0 0 + + + -10 0 0 0 -0 1.57 + + + + + 20 0.15 2.5 + + + 0 0 1.25 0 -0 0 + 10 + + + + + + + + + + + + + + + 0 0 1.25 0 -0 0 + + + 20 0.15 2.5 + + + + + 1 1 1 1 + + + 0 + + + 0 0 0 0 -0 0 + 0 + 0 + 0 + + 1 + + + 0 10 0 0 -0 0 + + + + + 20 0.15 2.5 + + + 0 0 1.25 0 -0 0 + 10 + + + + + + + + + + + + + + + 0 0 1.25 0 -0 0 + + + 20 0.15 2.5 + + + + + 1 1 1 1 + + + 0 + + + 0 0 0 0 -0 0 + 0 + 0 + 0 + + 1 + + + 0 -10 0 0 -0 3.14 + + + + + 20 0.15 2.5 + + + 0 0 1.25 0 -0 0 + 10 + + + + + + + + + + + + + + + 0 0 1.25 0 -0 0 + + + 20 0.15 2.5 + + + + + 1 1 1 1 + + + 0 + + + 0 0 0 0 -0 0 + 0 + 0 + 0 + + 1 + + + 10 0 0 0 0 -1.57 + + + + + 20 0.15 2.5 + + + 0 0 1.25 0 -0 0 + 10 + + + + + + + + + + + + + + + 0 0 1.25 0 -0 0 + + + 20 0.15 2.5 + + + + + 1 1 1 1 + + + 0 + + + 0 0 0 0 -0 0 + 0 + 0 + 0 + + 1 + + + 0.7388 -5.70207 0 0 0 -1.57 + + + + + 8 0.15 2.5 + + + 0 0 1.25 0 -0 0 + 10 + + + + + + + + + + + + + + + 0 0 1.25 0 -0 0 + + + 8 0.15 2.5 + + + + + 1 1 1 1 + + + 0 + + + 0 0 0 0 -0 0 + 0 + 0 + 0 + + 1 + + + + 0 0 0 0 -0 0 + 0 + 0 + 0 + + + 0 + 0 + 0 + 0 + 0 + 0 + + 0 + 0 0 0 0 -0 0 + + 1 + + 0 0 1.25 0 -0 0 + + + 1 0.15 2.5 + + + + + 1 1 1 1 + + __default__ + + 1 1 1 1 + 0.2 0.2 0.2 1 + 0 0 0 1 + + + 0 + + 0 + 1 + + + 0 + 10 + 0 0 1.25 0 -0 0 + + + 1 0.15 2.5 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 1 + 1 + 5.36173 -1.85107 0 0 -0 3.14 + + + + -0 0 0 0 -0 0 + 0 + 0 + 0 + + + 0 + 0 + 0 + 0 + 0 + 0 + + 0 + 0 0 0 0 -0 0 + + 1 + + 0 0 1.25 0 -0 0 + + + 1.5 0.15 2.5 + + + + + 1 1 1 1 + + __default__ + + 1 1 1 1 + 0.2 0.2 0.2 1 + 0 0 0 1 + + + 0 + + 0 + 1 + + + 0 + 10 + 0 0 1.25 0 -0 0 + + + 1 0.15 2.5 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 1 + 1 + 1.40743 -1.85107 0 0 -0 3.14 + + + + -0 0 0 0 -0 0 + 0 + 0 + 0 + + + 0 + 0 + 0 + 0 + 0 + 0 + + 0 + 0 0 0 0 -0 0 + + 1 + + 0 0 1.25 0 -0 0 + + + 2.25 0.15 2.5 + + + + + 1 1 1 1 + + __default__ + + 1 1 1 1 + 0.2 0.2 0.2 1 + 0 0 0 1 + + + 0 + + 0 + 1 + + + 0 + 10 + 0 0 1.25 0 -0 0 + + + 2.25 0.15 2.5 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 1 + 1 + 8.68743 -1.85107 0 0 -0 3.14 + + + diff --git a/simulators/sim_env/worlds/warehouse_with_obstacles_with_pedestrians.world b/simulators/sim_env/worlds/warehouse_with_obstacles_with_pedestrians.world new file mode 100755 index 0000000..efed943 --- /dev/null +++ b/simulators/sim_env/worlds/warehouse_with_obstacles_with_pedestrians.world @@ -0,0 +1,2453 @@ + + + + + 1 + 0 0 10 0 -0 0 + 0.8 0.8 0.8 1 + 0.2 0.2 0.2 1 + + 1000 + 0.9 + 0.01 + 0.001 + + -0.5 0.1 -0.9 + + 0 + 0 + 0 + + + + 1 + + + + + 0 0 1 + 100 100 + + + + + + 100 + 50 + + + + + + + + + + + 10 + + + 0 + + + 0 0 1 + 100 100 + + + + + + + 0 + 0 + 0 + + + 0 0 -9.8 + 6e-06 2.3e-05 -4.2e-05 + + + 0.001 + 1 + 1000 + + + 0.4 0.4 0.4 1 + 0.7 0.7 0.7 1 + 1 + + + + EARTH_WGS84 + 0 + 0 + 0 + 0 + + + 1 + + + 1.191 1.6275 0.32 0 -0 0 + 10 + + + 0.137 7.98 0.3 + + + + + + + + + + + + + + + + + 0.268 1.6275 0.32 0 -0 0 + 10 + + + 0.145 7.98 0.3 + + + + + + + + + + + + + + + + + + + 1.3 0.7 1 + model://sim_env/models/shipping_container_conveyor_ariac/meshes/ShippingContainer_Textured.obj + + + + 0 + 0 + 0 + + 5.94716 0.254888 0 0 -0 0 + + + + + 2 + + 0.841 + 0 + 0 + 0.954 + 0 + 1.422 + + + + + + model://sim_env/models/aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://sim_env/models/aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 4.52823 -6.5 0 0 -0 0 + + + + + 1 + + 1.558 + 0 + 0 + 1.821 + 0 + 1.892 + + + + + + model://sim_env/models/aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://sim_env/models/aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 6.33701 -4.2 0 0 -0 0 + + + + + 2 + + 0.841 + 0 + 0 + 0.954 + 0 + 1.422 + + + + + + model://sim_env/models/aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://sim_env/models/aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 4.5893 -4.7 0 0 -0 0 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + -6 3.5 -0.7 0 -0 0 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 0 3.5 -0.7 0 -0 0 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + -6 6.63287 -0.7 0 -0 0 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 0 6.5 -0.7 0 -0 0 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + -2 -0.5 -0.7 0 -0 1.57 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + -5 -0.5 -0.7 0 -0 1.57 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + -2 -5.88998 -0.7 0 -0 1.57 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + -5 -5.9682 -0.7 0 -0 1.57 + + + 0 0 + 0 0 + 1679208078 74263312 + 0 + + 3.9 3.5 -0 0 -1e-06 0 + 1 1 1 + + 3.9 3.5 -0 0 -1e-06 0 + 0 0 0 0 -0 0 + -0 0 0.008512 2.58585 -1.13682 -3.14159 + -0 0 0.008512 0 -0 0 + + + + 2.5 3.5 0 -0 -0 -0 + 1 1 1 + + 2.5 3.5 0 -0 -0 -0 + 0 0 0 0 -0 0 + 0 0 -9.8 0 -0 0 + 0 0 -9.8 0 -0 0 + + + + 3.9 2.8 -0 0 -1e-06 0 + 1 1 1 + + 3.9 2.8 -0 0 -1e-06 0 + 0 0 0 0 -0 0 + -0 0 0.008512 2.58585 -1.13682 -3.14159 + -0 0 0.008512 0 -0 0 + + + + 3.9 2.1 -5e-06 -4e-06 1e-06 0 + 1 1 1 + + 3.9 2.1 -5e-06 -4e-06 1e-06 0 + 0 0 0 0 -0 0 + 0 0 -9.8 -0 -0 -0 + 0 0 -9.8 0 -0 0 + + + + 3.2 3.5 -0 0 -0 0 + 1 1 1 + + 3.2 3.5 -0 0 -0 0 + 0 0 0 0 -0 0 + 0 -0 -0.008512 -2.58585 1.13682 3.14159 + 0 -0 -0.008512 0 -0 0 + + + + 6.98561 -2.64944 0.000917 0 -2e-06 0 + 1 1 1 + + 6.98561 -2.64944 0.000917 0 -2e-06 0 + 0 0 0 0 -0 0 + -0.006033 -0 -5e-06 0 -0.280679 4e-06 + -0.006033 -0 -5e-06 0 -0 0 + + + + 4.52823 -6.5 0 0 -0 0 + 1 1 1 + + 4.52823 -6.5 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 4.5893 -4.7 0 0 -0 0 + 1 1 1 + + 4.5893 -4.7 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 6.33701 -4.2 0 0 -0 0 + 1 1 1 + + 6.33701 -4.2 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 6.2 -6.2 0 0 -0 0 + 1 1 1 + + 6.2 -6.2 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 6.49861 6.95891 0 0 -0 0 + 1 1 1 + + 6.49861 6.95891 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 5.56779 -2.61305 -0.5 0 -0 0 + 1 1 1 + + 5.56779 -2.61305 -0.5 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -6 6.63287 -0.7 0 -0 0 + 1 1 1 + + -6 6.63287 -0.7 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 0 6.5 -0.7 0 -0 0 + 1 1 1 + + 0 6.5 -0.7 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -2 -0.5 -0.7 0 -0 1.57 + 1 1 1 + + -2 -0.5 -0.7 0 -0 1.57 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -5 -0.5 -0.7 0 -0 1.57 + 1 1 1 + + -5 -0.5 -0.7 0 -0 1.57 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -2 -5.88998 -0.7 0 -0 1.57 + 1 1 1 + + -2 -5.88998 -0.7 0 -0 1.57 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -5 -5.9682 -0.7 0 -0 1.57 + 1 1 1 + + -5 -5.9682 -0.7 0 -0 1.57 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -7.95437 -5.83764 -0.7 0 -0 1.57 + 1 1 1 + + -7.95437 -5.83764 -0.7 0 -0 1.57 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -7.82227 -0.391682 -0.7 0 -0 1.57 + 1 1 1 + + -7.82227 -0.391682 -0.7 0 -0 1.57 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -6 3.5 -0.7 0 -0 0 + 1 1 1 + + -6 3.5 -0.7 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 0 3.5 -0.7 0 -0 0 + 1 1 1 + + 0 3.5 -0.7 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 0 0 0 0 -0 0 + 1 1 1 + + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 5.94716 0.254888 -0.15 0 -0 0 + 1 1 1 + + 5.94716 0.254888 -0.15 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -10 0 0 0 -0 1.57 + 1 1 1 + + -10 0 0 0 -0 1.57 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 0.7388 -5.70207 0 0 0 -1.57 + 1 1 1 + + 0.7388 -5.70207 0 0 0 -1.57 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 1.40743 -1.85107 0 0 -0 3.14 + 1 1 1 + + 1.40743 -1.85107 0 0 -0 3.14 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 5.36173 -1.85107 0 0 -0 3.14 + 1 1 1 + + 5.36173 -1.85107 0 0 -0 3.14 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 8.68743 -1.85107 0 0 -0 3.14 + 1 1 1 + + 8.68743 -1.85107 0 0 -0 3.14 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 0 10 0 0 -0 0 + 1 1 1 + + 0 10 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 0 -10 0 0 -0 3.14 + 1 1 1 + + 0 -10 0 0 -0 3.14 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 10 0 0 0 0 -1.57 + 1 1 1 + + 10 0 0 0 0 -1.57 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 0 0 10 0 -0 0 + + + + + 11.0426 21.9041 29.5178 0 0.900977 -2.0681 + orbit + perspective + + + + + + 1 + + 1.558 + 0 + 0 + 1.821 + 0 + 1.892 + + + + + + model://sim_env/models/aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://sim_env/models/aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 6.49861 6.95891 0 0 -0 0 + + + + + 1 + + 1.558 + 0 + 0 + 1.821 + 0 + 1.892 + + + + + + model://sim_env/models/aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://sim_env/models/aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 6.01431 -6.50899 0 0 -0 0 + + + + + 1 + + 1.558 + 0 + 0 + 1.821 + 0 + 1.892 + + + + + + model://sim_env/models/aws_robomaker_warehouse_ClutteringD_01/meshes/aws_robomaker_warehouse_ClutteringD_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://sim_env/models/aws_robomaker_warehouse_ClutteringD_01/meshes/aws_robomaker_warehouse_ClutteringD_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 5.5675 -2.73505 0 0 -0 0 + + + + + + + model://sim_env/models/dumpster/meshes/dumpster.dae + + + 10 + + + + + + + + + + + + + + + + + model://sim_env/models/dumpster/meshes/dumpster.dae + + + + + + + 0 + + 0 0 0 0 -0 0 + + 1 + 0 + 0 + 1 + 0 + 1 + + 1 + + 0 + 0 + + 8.07649 -2.37718 0 0 -0 0 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + -7.95437 -5.83764 -0.7 0 -0 1.57 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + -7.82227 -0.391682 -0.7 0 -0 1.57 + + + + + + + 10 10 10 + model://sim_env/models/construction_cone/meshes/construction_cone.dae + + + 10 + + + + + + + + + + + + + + + + + 10 10 10 + model://sim_env/models/construction_cone/meshes/construction_cone.dae + + + + 0 + + 0 0 0 0 -0 0 + + 1 + 0 + 0 + 1 + 0 + 1 + + 1 + + 0 + 0 + + 3.9 3.5 -0 0 -1e-06 0 + + + + + + + 10 10 10 + model://sim_env/models/construction_cone/meshes/construction_cone.dae + + + 10 + + + + + + + + + + + + + + + + + 10 10 10 + model://sim_env/models/construction_cone/meshes/construction_cone.dae + + + + 0 + + 0 0 0 0 -0 0 + + 1 + 0 + 0 + 1 + 0 + 1 + + 1 + + 0 + 0 + + 2.5 3.5 0 -0 -0 -0 + + + + + + + 10 10 10 + model://sim_env/models/construction_cone/meshes/construction_cone.dae + + + 10 + + + + + + + + + + + + + + + + + 10 10 10 + model://sim_env/models/construction_cone/meshes/construction_cone.dae + + + + 0 + + 0 0 0 0 -0 0 + + 1 + 0 + 0 + 1 + 0 + 1 + + 1 + + 0 + 0 + + 3.9 2.8 -0 0 -1e-06 0 + + + + + + + 10 10 10 + model://sim_env/models/construction_cone/meshes/construction_cone.dae + + + 10 + + + + + + + + + + + + + + + + + 10 10 10 + model://sim_env/models/construction_cone/meshes/construction_cone.dae + + + + 0 + + 0 0 0 0 -0 0 + + 1 + 0 + 0 + 1 + 0 + 1 + + 1 + + 0 + 0 + + 3.9 2.1 -5e-06 -4e-06 1e-06 0 + + + + + + + 10 10 10 + model://sim_env/models/construction_cone/meshes/construction_cone.dae + + + 10 + + + + + + + + + + + + + + + + + 10 10 10 + model://sim_env/models/construction_cone/meshes/construction_cone.dae + + + + 0 + + 0 0 0 0 -0 0 + + 1 + 0 + 0 + 1 + 0 + 1 + + 1 + + 0 + 0 + + 3.2 3.5 -0 0 -0 0 + + + -10 0 0 0 -0 1.57 + + + + + 20 0.15 2.5 + + + 0 0 1.25 0 -0 0 + 10 + + + + + + + + + + + + + + + 0 0 1.25 0 -0 0 + + + 20 0.15 2.5 + + + + + 1 1 1 1 + + + 0 + + + 0 0 0 0 -0 0 + 0 + 0 + 0 + + 1 + + + 0 10 0 0 -0 0 + + + + + 20 0.15 2.5 + + + 0 0 1.25 0 -0 0 + 10 + + + + + + + + + + + + + + + 0 0 1.25 0 -0 0 + + + 20 0.15 2.5 + + + + + 1 1 1 1 + + + 0 + + + 0 0 0 0 -0 0 + 0 + 0 + 0 + + 1 + + + 0 -10 0 0 -0 3.14 + + + + + 20 0.15 2.5 + + + 0 0 1.25 0 -0 0 + 10 + + + + + + + + + + + + + + + 0 0 1.25 0 -0 0 + + + 20 0.15 2.5 + + + + + 1 1 1 1 + + + 0 + + + 0 0 0 0 -0 0 + 0 + 0 + 0 + + 1 + + + 10 0 0 0 0 -1.57 + + + + + 20 0.15 2.5 + + + 0 0 1.25 0 -0 0 + 10 + + + + + + + + + + + + + + + 0 0 1.25 0 -0 0 + + + 20 0.15 2.5 + + + + + 1 1 1 1 + + + 0 + + + 0 0 0 0 -0 0 + 0 + 0 + 0 + + 1 + + + 0.7388 -5.70207 0 0 0 -1.57 + + + + + 8 0.15 2.5 + + + 0 0 1.25 0 -0 0 + 10 + + + + + + + + + + + + + + + 0 0 1.25 0 -0 0 + + + 8 0.15 2.5 + + + + + 1 1 1 1 + + + 0 + + + 0 0 0 0 -0 0 + 0 + 0 + 0 + + 1 + + + + 0 0 0 0 -0 0 + 0 + 0 + 0 + + + 0 + 0 + 0 + 0 + 0 + 0 + + 0 + 0 0 0 0 -0 0 + + 1 + + 0 0 1.25 0 -0 0 + + + 1 0.15 2.5 + + + + + 1 1 1 1 + + __default__ + + 1 1 1 1 + 0.2 0.2 0.2 1 + 0 0 0 1 + + + 0 + + 0 + 1 + + + 0 + 10 + 0 0 1.25 0 -0 0 + + + 1 0.15 2.5 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 1 + 1 + 5.36173 -1.85107 0 0 -0 3.14 + + + + -0 0 0 0 -0 0 + 0 + 0 + 0 + + + 0 + 0 + 0 + 0 + 0 + 0 + + 0 + 0 0 0 0 -0 0 + + 1 + + 0 0 1.25 0 -0 0 + + + 1.5 0.15 2.5 + + + + + 1 1 1 1 + + __default__ + + 1 1 1 1 + 0.2 0.2 0.2 1 + 0 0 0 1 + + + 0 + + 0 + 1 + + + 0 + 10 + 0 0 1.25 0 -0 0 + + + 1 0.15 2.5 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 1 + 1 + 1.40743 -1.85107 0 0 -0 3.14 + + + + -0 0 0 0 -0 0 + 0 + 0 + 0 + + + 0 + 0 + 0 + 0 + 0 + 0 + + 0 + 0 0 0 0 -0 0 + + 1 + + 0 0 1.25 0 -0 0 + + + 2.25 0.15 2.5 + + + + + 1 1 1 1 + + __default__ + + 1 1 1 1 + 0.2 0.2 0.2 1 + 0 0 0 1 + + + 0 + + 0 + 1 + + + 0 + 10 + 0 0 1.25 0 -0 0 + + + 2.25 0.15 2.5 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 1 + 1 + 8.68743 -1.85107 0 0 -0 3.14 + + + 3 2 1 0 0 0 + + walk.dae + 1.0 + + + walk.dae + 1.0 + true + + + LHipJoint_LeftUpLeg_collision + LeftUpLeg_LeftLeg_collision + LeftLeg_LeftFoot_collision + LeftFoot_LeftToeBase_collision + RHipJoint_RightUpLeg_collision + RightUpLeg_RightLeg_collision + RightLeg_RightFoot_collision + RightFoot_RightToeBase_collision + Spine_Spine1_collision + Neck_Neck1_collision + Neck1_Head_collision + LeftShoulder_LeftArm_collision + LeftArm_LeftForeArm_collision + LeftForeArm_LeftHand_collision + LeftFingerBase_LeftHandIndex1_collision + RightShoulder_RightArm_collision + RightArm_RightForeArm_collision + RightForeArm_RightHand_collision + RightFingerBase_RightHandIndex1_collision + LowerBack_Spine_collision + 0.9 + 0.4 + True + 5.1 + 6.0 + 2.0 + 20.0 + 15 + 3.0 + 2.0 + 1.0 + + ground_plane + turtlebot3_waffle + + + 3 2 1 0 0 0 + 3 -8 1 0 0 0 + + + + + + -0.5 -8.5 1 0 0 0 + + walk.dae + 1.0 + + + walk.dae + 1.0 + true + + + LHipJoint_LeftUpLeg_collision + LeftUpLeg_LeftLeg_collision + LeftLeg_LeftFoot_collision + LeftFoot_LeftToeBase_collision + RHipJoint_RightUpLeg_collision + RightUpLeg_RightLeg_collision + RightLeg_RightFoot_collision + RightFoot_RightToeBase_collision + Spine_Spine1_collision + Neck_Neck1_collision + Neck1_Head_collision + LeftShoulder_LeftArm_collision + LeftArm_LeftForeArm_collision + LeftForeArm_LeftHand_collision + LeftFingerBase_LeftHandIndex1_collision + RightShoulder_RightArm_collision + RightArm_RightForeArm_collision + RightForeArm_RightHand_collision + RightFingerBase_RightHandIndex1_collision + LowerBack_Spine_collision + 1.2 + 0.4 + True + 5.1 + 6.0 + 2.0 + 20.0 + 15 + 3.0 + 2.0 + 1.0 + + ground_plane + turtlebot3_waffle + + + -0.5 -8.5 1 0 0 0 + -9 2.5 1 0 0 0 + + + + + -3.5 -8.5 1 0 0 0 + + walk.dae + 1.0 + + + walk.dae + 1.0 + true + + + LHipJoint_LeftUpLeg_collision + LeftUpLeg_LeftLeg_collision + LeftLeg_LeftFoot_collision + LeftFoot_LeftToeBase_collision + RHipJoint_RightUpLeg_collision + RightUpLeg_RightLeg_collision + RightLeg_RightFoot_collision + RightFoot_RightToeBase_collision + Spine_Spine1_collision + Neck_Neck1_collision + Neck1_Head_collision + LeftShoulder_LeftArm_collision + LeftArm_LeftForeArm_collision + LeftForeArm_LeftHand_collision + LeftFingerBase_LeftHandIndex1_collision + RightShoulder_RightArm_collision + RightArm_RightForeArm_collision + RightForeArm_RightHand_collision + RightFingerBase_RightHandIndex1_collision + LowerBack_Spine_collision + 1.2 + 0.4 + True + 5.1 + 6.0 + 2.0 + 20.0 + 15 + 3.0 + 2.0 + 1.0 + + ground_plane + turtlebot3_waffle + + + -3.5 -8.5 1 0 0 0 + -3.5 8.5 1 0 0 0 + + + + + \ No newline at end of file diff --git a/simulators/sim_env/worlds/warehouse_with_pedestrians.world b/simulators/sim_env/worlds/warehouse_with_pedestrians.world new file mode 100755 index 0000000..d0684d9 --- /dev/null +++ b/simulators/sim_env/worlds/warehouse_with_pedestrians.world @@ -0,0 +1,2054 @@ + + + + + 1 + 0 0 10 0 -0 0 + 0.8 0.8 0.8 1 + 0.2 0.2 0.2 1 + + 1000 + 0.9 + 0.01 + 0.001 + + -0.5 0.1 -0.9 + + 0 + 0 + 0 + + + + 1 + + + + + 0 0 1 + 100 100 + + + + + + 100 + 50 + + + + + + + + + + + 10 + + + 0 + + + 0 0 1 + 100 100 + + + + + + + 0 + 0 + 0 + + + 0 0 -9.8 + 6e-06 2.3e-05 -4.2e-05 + + + 0.001 + 1 + 1000 + + + 0.4 0.4 0.4 1 + 0.7 0.7 0.7 1 + 1 + + + + EARTH_WGS84 + 0 + 0 + 0 + 0 + + + 1 + + + 1.191 1.6275 0.32 0 -0 0 + 10 + + + 0.137 7.98 0.3 + + + + + + + + + + + + + + + + + 0.268 1.6275 0.32 0 -0 0 + 10 + + + 0.145 7.98 0.3 + + + + + + + + + + + + + + + + + + + 1.3 0.7 1 + model://sim_env/models/shipping_container_conveyor_ariac/meshes/ShippingContainer_Textured.obj + + + + 0 + 0 + 0 + + 5.94716 0.254888 0 0 -0 0 + + + + + 2 + + 0.841 + 0 + 0 + 0.954 + 0 + 1.422 + + + + + + model://sim_env/models/aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://sim_env/models/aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 4.52823 -6.5 0 0 -0 0 + + + + + 1 + + 1.558 + 0 + 0 + 1.821 + 0 + 1.892 + + + + + + model://sim_env/models/aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://sim_env/models/aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 6.33701 -4.2 0 0 -0 0 + + + + + 2 + + 0.841 + 0 + 0 + 0.954 + 0 + 1.422 + + + + + + model://sim_env/models/aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://sim_env/models/aws_robomaker_warehouse_ClutteringA_01/meshes/aws_robomaker_warehouse_ClutteringA_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 4.5893 -4.7 0 0 -0 0 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + -6 3.5 -0.7 0 -0 0 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfE_01/meshes/aws_robomaker_warehouse_ShelfE_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 0 3.5 -0.7 0 -0 0 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + -6 6.63287 -0.7 0 -0 0 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 0 6.5 -0.7 0 -0 0 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + -2 -0.5 -0.7 0 -0 1.57 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + -5 -0.5 -0.7 0 -0 1.57 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + -2 -5.88998 -0.7 0 -0 1.57 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + -5 -5.9682 -0.7 0 -0 1.57 + + + 0 0 + 0 0 + 1679208078 74263312 + 0 + + 6.98561 -2.64944 0.000917 0 -2e-06 0 + 1 1 1 + + 6.98561 -2.64944 0.000917 0 -2e-06 0 + 0 0 0 0 -0 0 + -0.006033 -0 -5e-06 0 -0.280679 4e-06 + -0.006033 -0 -5e-06 0 -0 0 + + + + 4.52823 -6.5 0 0 -0 0 + 1 1 1 + + 4.52823 -6.5 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 4.5893 -4.7 0 0 -0 0 + 1 1 1 + + 4.5893 -4.7 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 6.33701 -4.2 0 0 -0 0 + 1 1 1 + + 6.33701 -4.2 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 6.2 -6.2 0 0 -0 0 + 1 1 1 + + 6.2 -6.2 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 6.49861 6.95891 0 0 -0 0 + 1 1 1 + + 6.49861 6.95891 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 5.56779 -2.61305 -0.5 0 -0 0 + 1 1 1 + + 5.56779 -2.61305 -0.5 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -6 6.63287 -0.7 0 -0 0 + 1 1 1 + + -6 6.63287 -0.7 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 0 6.5 -0.7 0 -0 0 + 1 1 1 + + 0 6.5 -0.7 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -2 -0.5 -0.7 0 -0 1.57 + 1 1 1 + + -2 -0.5 -0.7 0 -0 1.57 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -5 -0.5 -0.7 0 -0 1.57 + 1 1 1 + + -5 -0.5 -0.7 0 -0 1.57 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -2 -5.88998 -0.7 0 -0 1.57 + 1 1 1 + + -2 -5.88998 -0.7 0 -0 1.57 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -5 -5.9682 -0.7 0 -0 1.57 + 1 1 1 + + -5 -5.9682 -0.7 0 -0 1.57 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -7.95437 -5.83764 -0.7 0 -0 1.57 + 1 1 1 + + -7.95437 -5.83764 -0.7 0 -0 1.57 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -7.82227 -0.391682 -0.7 0 -0 1.57 + 1 1 1 + + -7.82227 -0.391682 -0.7 0 -0 1.57 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -6 3.5 -0.7 0 -0 0 + 1 1 1 + + -6 3.5 -0.7 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 0 3.5 -0.7 0 -0 0 + 1 1 1 + + 0 3.5 -0.7 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 0 0 0 0 -0 0 + 1 1 1 + + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 5.94716 0.254888 -0.15 0 -0 0 + 1 1 1 + + 5.94716 0.254888 -0.15 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -10 0 0 0 -0 1.57 + 1 1 1 + + -10 0 0 0 -0 1.57 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 0.7388 -5.70207 0 0 0 -1.57 + 1 1 1 + + 0.7388 -5.70207 0 0 0 -1.57 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 1.40743 -1.85107 0 0 -0 3.14 + 1 1 1 + + 1.40743 -1.85107 0 0 -0 3.14 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 5.36173 -1.85107 0 0 -0 3.14 + 1 1 1 + + 5.36173 -1.85107 0 0 -0 3.14 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 8.68743 -1.85107 0 0 -0 3.14 + 1 1 1 + + 8.68743 -1.85107 0 0 -0 3.14 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 0 10 0 0 -0 0 + 1 1 1 + + 0 10 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 0 -10 0 0 -0 3.14 + 1 1 1 + + 0 -10 0 0 -0 3.14 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 10 0 0 0 0 -1.57 + 1 1 1 + + 10 0 0 0 0 -1.57 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 0 0 10 0 -0 0 + + + + + 11.0426 21.9041 29.5178 0 0.900977 -2.0681 + orbit + perspective + + + + + + 1 + + 1.558 + 0 + 0 + 1.821 + 0 + 1.892 + + + + + + model://sim_env/models/aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://sim_env/models/aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 6.49861 6.95891 0 0 -0 0 + + + + + 1 + + 1.558 + 0 + 0 + 1.821 + 0 + 1.892 + + + + + + model://sim_env/models/aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://sim_env/models/aws_robomaker_warehouse_ClutteringC_01/meshes/aws_robomaker_warehouse_ClutteringC_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 6.01431 -6.50899 0 0 -0 0 + + + + + 1 + + 1.558 + 0 + 0 + 1.821 + 0 + 1.892 + + + + + + model://sim_env/models/aws_robomaker_warehouse_ClutteringD_01/meshes/aws_robomaker_warehouse_ClutteringD_01_collision.DAE + 1 1 1 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + + + + + 10 + + + + + model://sim_env/models/aws_robomaker_warehouse_ClutteringD_01/meshes/aws_robomaker_warehouse_ClutteringD_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + 5.5675 -2.73505 0 0 -0 0 + + + + + + + model://sim_env/models/dumpster/meshes/dumpster.dae + + + 10 + + + + + + + + + + + + + + + + + model://sim_env/models/dumpster/meshes/dumpster.dae + + + + + + + 0 + + 0 0 0 0 -0 0 + + 1 + 0 + 0 + 1 + 0 + 1 + + 1 + + 0 + 0 + + 8.07649 -2.37718 0 0 -0 0 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + -7.95437 -5.83764 -0.7 0 -0 1.57 + + + + + 30 + + 907.144 + 0 + 0 + 104.95 + 0 + 824.248 + + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_collision.DAE + 1 1 1 + + + + + + 0.2 + 0.2 + 0 0 0 + 0 + 0 + + + + + + + + + + + 10 + + + + + model://sim_env/models/aws_robomaker_warehouse_ShelfD_01/meshes/aws_robomaker_warehouse_ShelfD_01_visual.DAE + + + + 1 + + + 0 + 0 + 0 + + 1 + -7.82227 -0.391682 -0.7 0 -0 1.57 + + + -10 0 0 0 -0 1.57 + + + + + 20 0.15 2.5 + + + 0 0 1.25 0 -0 0 + 10 + + + + + + + + + + + + + + + 0 0 1.25 0 -0 0 + + + 20 0.15 2.5 + + + + + 1 1 1 1 + + + 0 + + + 0 0 0 0 -0 0 + 0 + 0 + 0 + + 1 + + + 0 10 0 0 -0 0 + + + + + 20 0.15 2.5 + + + 0 0 1.25 0 -0 0 + 10 + + + + + + + + + + + + + + + 0 0 1.25 0 -0 0 + + + 20 0.15 2.5 + + + + + 1 1 1 1 + + + 0 + + + 0 0 0 0 -0 0 + 0 + 0 + 0 + + 1 + + + 0 -10 0 0 -0 3.14 + + + + + 20 0.15 2.5 + + + 0 0 1.25 0 -0 0 + 10 + + + + + + + + + + + + + + + 0 0 1.25 0 -0 0 + + + 20 0.15 2.5 + + + + + 1 1 1 1 + + + 0 + + + 0 0 0 0 -0 0 + 0 + 0 + 0 + + 1 + + + 10 0 0 0 0 -1.57 + + + + + 20 0.15 2.5 + + + 0 0 1.25 0 -0 0 + 10 + + + + + + + + + + + + + + + 0 0 1.25 0 -0 0 + + + 20 0.15 2.5 + + + + + 1 1 1 1 + + + 0 + + + 0 0 0 0 -0 0 + 0 + 0 + 0 + + 1 + + + 0.7388 -5.70207 0 0 0 -1.57 + + + + + 8 0.15 2.5 + + + 0 0 1.25 0 -0 0 + 10 + + + + + + + + + + + + + + + 0 0 1.25 0 -0 0 + + + 8 0.15 2.5 + + + + + 1 1 1 1 + + + 0 + + + 0 0 0 0 -0 0 + 0 + 0 + 0 + + 1 + + + + 0 0 0 0 -0 0 + 0 + 0 + 0 + + + 0 + 0 + 0 + 0 + 0 + 0 + + 0 + 0 0 0 0 -0 0 + + 1 + + 0 0 1.25 0 -0 0 + + + 1 0.15 2.5 + + + + + 1 1 1 1 + + __default__ + + 1 1 1 1 + 0.2 0.2 0.2 1 + 0 0 0 1 + + + 0 + + 0 + 1 + + + 0 + 10 + 0 0 1.25 0 -0 0 + + + 1 0.15 2.5 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 1 + 1 + 5.36173 -1.85107 0 0 -0 3.14 + + + + -0 0 0 0 -0 0 + 0 + 0 + 0 + + + 0 + 0 + 0 + 0 + 0 + 0 + + 0 + 0 0 0 0 -0 0 + + 1 + + 0 0 1.25 0 -0 0 + + + 1.5 0.15 2.5 + + + + + 1 1 1 1 + + __default__ + + 1 1 1 1 + 0.2 0.2 0.2 1 + 0 0 0 1 + + + 0 + + 0 + 1 + + + 0 + 10 + 0 0 1.25 0 -0 0 + + + 1 0.15 2.5 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 1 + 1 + 1.40743 -1.85107 0 0 -0 3.14 + + + + -0 0 0 0 -0 0 + 0 + 0 + 0 + + + 0 + 0 + 0 + 0 + 0 + 0 + + 0 + 0 0 0 0 -0 0 + + 1 + + 0 0 1.25 0 -0 0 + + + 2.25 0.15 2.5 + + + + + 1 1 1 1 + + __default__ + + 1 1 1 1 + 0.2 0.2 0.2 1 + 0 0 0 1 + + + 0 + + 0 + 1 + + + 0 + 10 + 0 0 1.25 0 -0 0 + + + 2.25 0.15 2.5 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 1 + 1 + 8.68743 -1.85107 0 0 -0 3.14 + + + 11 25 1 0 0 0 + + walk.dae + 1.0 + + + walk.dae + 1.0 + true + + + LHipJoint_LeftUpLeg_collision + LeftUpLeg_LeftLeg_collision + LeftLeg_LeftFoot_collision + LeftFoot_LeftToeBase_collision + RHipJoint_RightUpLeg_collision + RightUpLeg_RightLeg_collision + RightLeg_RightFoot_collision + RightFoot_RightToeBase_collision + Spine_Spine1_collision + Neck_Neck1_collision + Neck1_Head_collision + LeftShoulder_LeftArm_collision + LeftArm_LeftForeArm_collision + LeftForeArm_LeftHand_collision + LeftFingerBase_LeftHandIndex1_collision + RightShoulder_RightArm_collision + RightArm_RightForeArm_collision + RightForeArm_RightHand_collision + RightFingerBase_RightHandIndex1_collision + LowerBack_Spine_collision + 0.9 + 0.4 + True + 5.1 + 6.0 + 2.0 + 20.0 + 15 + 3.0 + 2.0 + 1.0 + + ground_plane + turtlebot3_waffle_1 + + + 11 25 1 0 0 0 + 11 30 1 0 0 0 + + + + 5 + + + + \ No newline at end of file diff --git a/simulators/third_party/dynamic_rviz_config/CMakeLists.txt b/simulators/third_party/dynamic_rviz_config/CMakeLists.txt new file mode 100755 index 0000000..dd8c1a3 --- /dev/null +++ b/simulators/third_party/dynamic_rviz_config/CMakeLists.txt @@ -0,0 +1,15 @@ +cmake_minimum_required(VERSION 3.0.2) +project(dynamic_rviz_config) +find_package(catkin REQUIRED COMPONENTS + roscpp + rospy +) + +catkin_package( + CATKIN_DEPENDS urdf xacro +) + +catkin_install_python(PROGRAMS + scripts/rviz_generate.py + DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) \ No newline at end of file diff --git a/simulators/third_party/dynamic_rviz_config/package.xml b/simulators/third_party/dynamic_rviz_config/package.xml new file mode 100755 index 0000000..622c422 --- /dev/null +++ b/simulators/third_party/dynamic_rviz_config/package.xml @@ -0,0 +1,17 @@ + + dynamic_rviz_config + 0.0.1 + dynamic_rviz_config package + Winter + Yang Haodong + BSD + catkin + roscpp + rospy + + roscpp + rospy + urdf + xacro + + diff --git a/simulators/third_party/dynamic_rviz_config/scripts/config.py b/simulators/third_party/dynamic_rviz_config/scripts/config.py new file mode 100755 index 0000000..42325c4 --- /dev/null +++ b/simulators/third_party/dynamic_rviz_config/scripts/config.py @@ -0,0 +1,166 @@ +#!/usr/bin/python +#-*- coding: utf-8 -*- + +''' +****************************************************************************************** +* Copyright (C) 2023 Yang Haodong, All Rights Reserved * +* * +* @brief rviz basic pannel configure class. * +* @author Haodong Yang * +* @version 1.0.1 * +* @date 2022.07.06 * +* @license GNU General Public License (GPL) * +****************************************************************************************** +''' +import yaml + +class RVizConfig: + def __init__(self, rviz_name, path, base_file=None): + # Rviz visualization manager + self.VIZ_MAN = 'Visualization Manager' + # Rviz standard tools + self.STD_TOOLS = ['rviz/Interact', 'rviz/MoveCamera', 'rviz/Select', 'rviz/FocusCamera', 'rviz/Measure', 'rviz/PublishPoint'] + # Rviz standard panels + self.STD_PANELS = ['rviz/Displays', 'rviz/Tool Properties'] + # Rviz file name + self.file_name = rviz_name + # Rviz cache + self.cache_path = path + # Rviz pre-configure + self.data = yaml.load(base_file) if base_file else {} + + def __repr__(self): + return yaml.dump(self.data, default_flow_style=False) + + # @breif: set Rviz configure path + # + # @param[in]: path Rviz configure path + # @return: None + def setFileCache(self, path): + self.cache_path = path + + # @breif: extract all configure data of `rviz Visualization Manager` + # + # @param[in]: None + # @return: all configure data of `rviz Visualization Manager` + def getVisualization(self): + if self.VIZ_MAN not in self.data: + self.data[self.VIZ_MAN] = {} + return self.data[self.VIZ_MAN] + + # @breif: set display format + # @param[in]: displays display format + # @return: True if successful else False + def setDisplays(self, displays): + if 'Displays' not in self.getVisualization(): + self.data[self.VIZ_MAN]['Displays'] = displays + print("Displays have been set successfully!") + return True + print("Displays setting failed! please call displays delete first!") + return False + + # @breif: clear display + # @param[in]: None + # @return: True if successful else False + def delDisplays(self): + if 'Displays' in self.getVisualization(): + del self.data[self.VIZ_MAN]['Displays'] + print("Displays have been deleted successfully!") + return True + print("Displays delete failed! please call displays setting first!") + return False + + # @breif: set Rviz standard tools + # @param[in]: None + # @return: True if successful else False + def setStdTools(self): + v = self.getVisualization() + if 'Tools' not in v: + v['Tools'] = [] + for tool in self.STD_TOOLS: + v['Tools'].append({'Class': tool}) + print("standard tools have been set successfully!") + return True + print("standard tools setting failed! please call standard tools delete first!") + return False + + # @breif: clear Rviz standard tools + # @param[in]: None + # @return: True if successful else False + def delStdTools(self): + if 'Tools' in self.getVisualization(): + del self.data[self.VIZ_MAN]['Tools'] + print("standard tools have been deleted successfully!") + return True + print("standard tools delete failed! please call standard tools setting first!") + return False + + # @breif: set Rviz standard panels + # @param[in]: None + # @return: True if successful else False + def setStdPanels(self): + if 'Panels' not in self.data: + self.data['Panels'] = [] + for tool in self.STD_PANELS: + self.data['Panels'].append({'Class': tool, 'Name': tool.split('/')[-1]}) + print("standard panels have been set successfully!") + return True + print("standard panels setting failed! please call standard panels delete first!") + return False + + # @breif: clear Rviz standard panels + # @param[in]: None + # @return: True if successful else False + def delStdPanels(self): + if 'Panels' in self.data: + del self.data['Panels'] + print("standard panels have been deleted successfully!") + return True + print("standard panels delete failed! please call standard panels setting first!") + return False + + # @breif: set base coordinate + # @param[in]: frame base coordinate, default is `map` + # @return: None + def setFixedFrame(self, frame='map'): + v = self.getVisualization() + if 'Global Options' not in v: + v['Global Options'] = {'Fixed Frame':frame} + else: + v['Global Options']['Fixed Frame'] = frame + + # @breif: set the topics of Rviz standard tools + # @param[in]: name Rviz standard tools classes + # @param[in]: topic the topic of Rviz standard tools relatively + # @return: None + def setToolTopic(self, name, topic): + for m in self.data[self.VIZ_MAN]['Tools']: + if m.get('Class', '')==name: + m['Topic'] = topic + + # @breif: append navigation tools and their topics + # @param[in]: None + # @return: None + def appendToolGoal(self, topic): + v = self.getVisualization() + if 'Tools' not in v: + v['Tools'] = [] + v['Tools'].append({'Class': 'rviz/SetGoal', 'Topic': topic}) + + # @breif: append initial Pose and its topic + # @param[in]: None + # @return: None + def appendToolInit(self, topic): + v = self.getVisualization() + if 'Tools' not in v: + v['Tools'] = [] + v['Tools'].append({'Class': 'rviz/SetInitialPose', 'Topic': topic}) + + # @breif: run Rviz and apply user configure + # @param[in]: None + # @return: None + def run(self): + with open( self.cache_path + self.file_name + '.rviz', "w") as fp: + fp.write(str(self)) + import subprocess + subprocess.call(['rosrun','rviz','rviz', '-d', self.cache_path + self.file_name + '.rviz']) \ No newline at end of file diff --git a/simulators/third_party/dynamic_rviz_config/scripts/displays.py b/simulators/third_party/dynamic_rviz_config/scripts/displays.py new file mode 100755 index 0000000..8e605da --- /dev/null +++ b/simulators/third_party/dynamic_rviz_config/scripts/displays.py @@ -0,0 +1,93 @@ +#!/usr/bin/python +#-*- coding: utf-8 -*- + +''' +****************************************************************************************** +* Copyright (C) 2023 Yang Haodong, All Rights Reserved * +* * +* @brief rviz display pannel configure class. * +* @author Haodong Yang * +* @version 1.0.1 * +* @date 2022.07.06 * +* @license GNU General Public License (GPL) * +****************************************************************************************** +''' + +class Displays(list): + def __init__(self): + None + + + def addDisplay(self, name, class_name, topic=None, color=None, fields={}, enabled=True): + d = {'Name': name, 'Class': class_name, 'Enabled': enabled} + if topic: + d['Topic'] = topic + if color: + d['Color'] = '%d; %d; %d'%color + d.update(fields) + self.append(d) + + def addMap(self, topic='/map', name='Map', alpha=None, scheme=None): + fields = {} + if alpha: + fields['Alpha'] = alpha + if scheme: + fields['Color Scheme'] = scheme + self.addDisplay(name, 'rviz/Map', topic, fields=fields) + + def addGrid(self): + self.addDisplay('Grid', 'rviz/Grid') + + def addTf(self, scale=None): + fields = {} + if scale: + fields['Marker Scale'] = scale + self.addDisplay('TF', 'rviz/TF', fields=fields, enabled=False) + + def addGroup(self, name, displays): + self.addDisplay(name, 'rviz/Group', fields={'Displays': displays}) + + def addModel(self, parameter='robot_description', tf_prefix=None): + fields = {'Robot Description': parameter} + if tf_prefix: + fields['TF Prefix'] = tf_prefix + self.addDisplay('RobotModel', 'rviz/RobotModel', fields=fields) + + def addLaserscan(self, topic='/base_scan', name=None, color=(46, 255, 0), size=0.1, alpha=None): + if name is None: + name = topic + fields = {'Size (m)': size, 'Style': 'Spheres', 'Color Transformer': 'FlatColor'} + if alpha: + fields['Alpha'] = alpha + self.addDisplay(name, 'rviz/LaserScan', topic, color, fields) + + def addPoseArray(self, topic='/particlecloud', color=None): + self.addDisplay('AMCL Cloud', 'rviz/PoseArray', topic, color) + + def addFootprint(self, topic, color=(0,170,255)): + self.addDisplay('Robot Footprint', 'rviz/Polygon', topic, color) + + def addPath(self, topic, name, color=None): + self.addDisplay(name, 'rviz/Path', topic, color) + + def addPose(self, topic, name='Current Goal', color=None, arrow_shape=None): + fields = {} + if arrow_shape: + fields['Head Length'] = arrow_shape[0] + fields['Head Radius'] = arrow_shape[1] + fields['Shaft Length'] = arrow_shape[2] + fields['Shaft Radius'] = arrow_shape[3] + fields['Shape'] = 'Arrow' + self.addDisplay(name, 'rviz/Pose', topic, color, fields) + + def addImage(self, topic="/camera/rgb/image_raw", name="Image"): + self.addDisplay(name, "rviz/Image", topic, enabled=False) + + + +import yaml + +def display_representer(dumper, data): + return dumper.represent_sequence(u'tag:yaml.org,2002:seq', list(data)) + +yaml.add_representer(Displays, display_representer) diff --git a/simulators/third_party/dynamic_rviz_config/scripts/rviz_generate.py b/simulators/third_party/dynamic_rviz_config/scripts/rviz_generate.py new file mode 100755 index 0000000..1031b4b --- /dev/null +++ b/simulators/third_party/dynamic_rviz_config/scripts/rviz_generate.py @@ -0,0 +1,73 @@ +#!/usr/bin/python +#-*- coding: utf-8 -*- + +''' +****************************************************************************************** +* Copyright (C) 2023 Yang Haodong, All Rights Reserved * +* * +* @brief rviz basic pannel configure class. * +* @author Haodong Yang * +* @version 1.0.1 * +* @date 2022.07.06 * +* @license GNU General Public License (GPL) * +****************************************************************************************** +''' +import sys, os +dir_path = os.path.dirname(os.path.realpath(__file__)) +sys.path.insert(0, dir_path) + +from config import RVizConfig +from displays import Displays + +# the number of robots +robot_num = int(sys.argv[1]) + +r = RVizConfig("cache", os.path.split(os.path.realpath(__file__))[0] + "/../../../sim_env/rviz/") +# set Rviz standard tools +r.setStdTools() +# visualize Rviz models +d = Displays() +# load map and grid +d.addMap() +d.addGrid() +# set transform +d.addTf() + +# single robot +if robot_num == 1: + # append robots' model + d.addModel() + # append camera image + d.addImage() + # append laser + d.addLaserscan(topic="/scan", name="LaserScan", color=(255, 0, 0), size=0.03, alpha=1) + # append `initialpose` setting panel + r.appendToolInit('/initialpose') + # append `move_base_simple/goal` setting panel + r.appendToolGoal('/move_base_simple/goal') +else: + # multi-robot + for i in range(robot_num): + meta_robot = Displays() + # append robots' model + meta_robot.addModel(parameter="robot" + str(i + 1) + "/robot_description", tf_prefix="robot" + str(i + 1)) + # append camera image + meta_robot.addImage(topic="/robot" + str(i + 1) + "/camera/rgb/image_raw", name="Image" + str(i + 1)) + # append laser + meta_robot.addLaserscan(topic="/robot" + str(i + 1) + "/scan", name="LaserScan" + str(i + 1), color=(255, 0, 0), size=0.03, alpha=1) + # append path + meta_robot.addPath(topic=None, name="Path", color=(32, 74, 135)) + d.addGroup("Robot" + str(i + 1), meta_robot) + # append `initialpose` setting panel + r.appendToolInit('/robot' + str(i + 1) + '/initialpose') + # ppend `move_base_simple/goal` setting panel + r.appendToolGoal('/robot' + str(i + 1) +'/move_base_simple/goal') + +# 设置Rviz标准面板 +r.setStdPanels() +# 设置Rviz模型显示 +r.setDisplays(d) +# 设置Rviz基坐标系 +r.setFixedFrame() +# 启动Rviz +r.run() diff --git a/simulators/third_party/dynamic_xml_config/CMakeLists.txt b/simulators/third_party/dynamic_xml_config/CMakeLists.txt new file mode 100755 index 0000000..1480716 --- /dev/null +++ b/simulators/third_party/dynamic_xml_config/CMakeLists.txt @@ -0,0 +1,15 @@ +cmake_minimum_required(VERSION 2.8.3) +project(dynamic_xml_config) +find_package(catkin REQUIRED COMPONENTS + roscpp + rospy +) + +catkin_package( + +) + +catkin_install_python(PROGRAMS + plugins/obstacles_generate_ros.py + DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) \ No newline at end of file diff --git a/simulators/third_party/dynamic_xml_config/main_generate.py b/simulators/third_party/dynamic_xml_config/main_generate.py new file mode 100755 index 0000000..03a71c5 --- /dev/null +++ b/simulators/third_party/dynamic_xml_config/main_generate.py @@ -0,0 +1,63 @@ +#!/usr/bin/python +# -*- coding: utf-8 -*- + +""" +****************************************************************************************** +* Copyright (C) 2023 Yang Haodong, All Rights Reserved * +* * +* @brief generate launch file dynamicly based on user configure. * +* @author Haodong Yang * +* @version 1.0.3 * +* @date 2023.07.19 * +* @license GNU General Public License (GPL) * +****************************************************************************************** +""" +import xml.etree.ElementTree as ET +from plugins import XMLGenerator, PedGenerator, RobotGenerator, ObstacleGenerator + +class MainGenerator(XMLGenerator): + def __init__(self, *plugins) -> None: + super().__init__() + self.main_path = self.root_path + "pedestrian_simulation/" + self.app_list = [app for app in plugins] + + def writeMainLaunch(self, path): + """ + Create configure file of package `sim_env` dynamically. + + Parameters + ---------- + path: str + the path of file(.launch.xml) to write. + """ + # root + launch = MainGenerator.createElement("launch") + + # other applications + for app in self.app_list: + assert isinstance(app, XMLGenerator), "Expected type of app is XMLGenerator" + app_register = app.plugin() + for app_element in app_register: + launch.append(app_element) + + # include + include = MainGenerator.createElement("include", props={"file": "$(find sim_env)/launch/config.launch"}) + include.append(MainGenerator.createElement("arg", props={"name": "world", "value": "$(arg world_parameter)"})) + include.append(MainGenerator.createElement("arg", props={"name": "map", "value": self.user_cfg["map"]})) + include.append(MainGenerator.createElement("arg", props={"name": "robot_number", "value": str(len(self.user_cfg["robots_config"]))})) + include.append(MainGenerator.createElement("arg", props={"name": "rviz_file", "value": self.user_cfg["rviz_file"]})) + + launch.append(include) + MainGenerator.indent(launch) + + with open(path, "wb+") as f: + ET.ElementTree(launch).write(f, encoding="utf-8", xml_declaration=True) + + def plugin(self): + pass + +# dynamic generator +main_gen = MainGenerator(PedGenerator(), + RobotGenerator(), + ObstacleGenerator()) +main_gen.writeMainLaunch(main_gen.root_path + "sim_env/launch/main.launch") diff --git a/simulators/third_party/dynamic_xml_config/package.xml b/simulators/third_party/dynamic_xml_config/package.xml new file mode 100755 index 0000000..6f1bfc3 --- /dev/null +++ b/simulators/third_party/dynamic_xml_config/package.xml @@ -0,0 +1,17 @@ + + + dynamic_xml_config + 0.2.0 + + dynamic xml configure + + + Winter + + BSD + + Winter + + catkin + + diff --git a/simulators/third_party/dynamic_xml_config/plugins/__init__.py b/simulators/third_party/dynamic_xml_config/plugins/__init__.py new file mode 100755 index 0000000..d8a8aa8 --- /dev/null +++ b/simulators/third_party/dynamic_xml_config/plugins/__init__.py @@ -0,0 +1,6 @@ +from .xml_generate import XMLGenerator +from .pedestrians_generate import PedGenerator +from .robot_generate import RobotGenerator +from .obstacles_generate import ObstacleGenerator + +__all__ = ["XMLGenerator", "PedGenerator", "RobotGenerator", "ObstacleGenerator"] \ No newline at end of file diff --git a/simulators/third_party/dynamic_xml_config/plugins/__pycache__/__init__.cpython-38.pyc b/simulators/third_party/dynamic_xml_config/plugins/__pycache__/__init__.cpython-38.pyc new file mode 100755 index 0000000..31169e7 Binary files /dev/null and b/simulators/third_party/dynamic_xml_config/plugins/__pycache__/__init__.cpython-38.pyc differ diff --git a/simulators/third_party/dynamic_xml_config/plugins/__pycache__/obstacles_generate.cpython-38.pyc b/simulators/third_party/dynamic_xml_config/plugins/__pycache__/obstacles_generate.cpython-38.pyc new file mode 100755 index 0000000..5b1805c Binary files /dev/null and b/simulators/third_party/dynamic_xml_config/plugins/__pycache__/obstacles_generate.cpython-38.pyc differ diff --git a/simulators/third_party/dynamic_xml_config/plugins/__pycache__/pedestrians_generate.cpython-38.pyc b/simulators/third_party/dynamic_xml_config/plugins/__pycache__/pedestrians_generate.cpython-38.pyc new file mode 100755 index 0000000..819a547 Binary files /dev/null and b/simulators/third_party/dynamic_xml_config/plugins/__pycache__/pedestrians_generate.cpython-38.pyc differ diff --git a/simulators/third_party/dynamic_xml_config/plugins/__pycache__/robot_generate.cpython-38.pyc b/simulators/third_party/dynamic_xml_config/plugins/__pycache__/robot_generate.cpython-38.pyc new file mode 100755 index 0000000..c64ec5e Binary files /dev/null and b/simulators/third_party/dynamic_xml_config/plugins/__pycache__/robot_generate.cpython-38.pyc differ diff --git a/simulators/third_party/dynamic_xml_config/plugins/__pycache__/xml_generate.cpython-38.pyc b/simulators/third_party/dynamic_xml_config/plugins/__pycache__/xml_generate.cpython-38.pyc new file mode 100755 index 0000000..d530f14 Binary files /dev/null and b/simulators/third_party/dynamic_xml_config/plugins/__pycache__/xml_generate.cpython-38.pyc differ diff --git a/simulators/third_party/dynamic_xml_config/plugins/obstacles_generate.py b/simulators/third_party/dynamic_xml_config/plugins/obstacles_generate.py new file mode 100755 index 0000000..294c6e3 --- /dev/null +++ b/simulators/third_party/dynamic_xml_config/plugins/obstacles_generate.py @@ -0,0 +1,191 @@ +#!/usr/bin/python +# -*- coding: utf-8 -*- + +""" +****************************************************************************************** +* Copyright (C) 2023 Yang Haodong, All Rights Reserved * +* * +* @brief generate launch file dynamicly based on user configure. * +* @author Haodong Yang * +* @version 1.0.2 * +* @date 2023.03.15 * +* @license GNU General Public License (GPL) * +****************************************************************************************** +""" +import rospy, tf +from gazebo_msgs.srv import SpawnModel +from geometry_msgs.msg import Quaternion, Pose, Point +import xml.etree.ElementTree as ET +from .xml_generate import XMLGenerator + + +class ObstacleGenerator(XMLGenerator): + def __init__(self) -> None: + super().__init__() + if "plugins" in self.user_cfg.keys() and "obstacles" in self.user_cfg["plugins"] \ + and self.user_cfg["plugins"]["obstacles"]: + self.obs_cfg = ObstacleGenerator.yamlParser(self.root_path + "user_config/" + self.user_cfg["plugins"]["obstacles"]) + else: + self.obs_cfg = None + + self.box_obs, self.cylinder_obs, self.sphere_obs = [], [], [] + + def plugin(self): + """ + Implement of obstacles application. + """ + app_register = [] + if not self.obs_cfg is None: + '''app register''' + # obstacles generation + obs_gen = ObstacleGenerator.createElement("node", props={"pkg": "dynamic_xml_config", "type": "obstacles_generate_ros.py", + "name": "obstacles_generate", "args": "user_config.yaml","output": "screen"}) + app_register.append(obs_gen) + + return app_register + + def spawn(self) -> None: + """ + ROS service for spawning static obstacles in Gazebo world. + """ + rospy.wait_for_service("gazebo/spawn_urdf_model") + proxy = rospy.ServiceProxy("gazebo/spawn_urdf_model", SpawnModel) + + for obs in self.obs_cfg["obstacles"]: + pose = [float(i) for i in obs["pose"].split()] + x, y, z, r, p, yaw = pose + orient = tf.transformations.quaternion_from_euler(r, p, yaw) + orient = Quaternion(orient[0], orient[1], orient[2], orient[3]) + params = obs["props"] + params["c"] = obs["color"] + urdf = self.constructURDF(obs["type"], **params) + + if obs["type"] == "BOX": + z = z if z else obs["props"]["h"] / 2 + pose = Pose(Point(x=x, y=y, z=z), orient) + proxy(obs["type"] + str(len(self.box_obs)), urdf, "", pose, "world") + self.box_obs.append(obs) + elif obs["type"] == "CYLINDER": + z = z if z else obs["props"]["h"] / 2 + pose = Pose(Point(x=x, y=y, z=z), orient) + proxy(obs["type"] + str(len(self.cylinder_obs)), urdf, "", pose, "world") + self.cylinder_obs.append(obs) + elif obs["type"] == "SPHERE": + z = z if z else obs["props"]["r"] + pose = Pose(Point(x=x, y=y, z=z), orient) + proxy(obs["type"] + str(len(self.sphere_obs)), urdf, "", pose, "world") + self.sphere_obs.append(obs) + + def constructURDF(self, model_type: str, **kwargs) -> str: + """ + Construct URDF of specific type of obstacle. + + Parameters + ---------- + model_type: str + specific type of obstacle. Optional is `BOX`, `CYLINDER` and `SPHERE` + kwargs: dict + parameters of obstacle, such as mass, color, height, etc. + + Return + ---------- + urdf_str: str + URDF of obstacle + """ + # parameters checking + if model_type.upper() == "BOX": + assert "m" in kwargs and \ + "w" in kwargs and \ + "d" in kwargs and \ + "h" in kwargs and \ + "c" in kwargs, \ + "Parameters of {} are `m`, `w`, `d`, `h`, `c` which mean mass, \ + width, depth, height and color, ".format(model_type) + ixx = (kwargs["m"] / 12.0) * (pow(kwargs["d"], 2) + pow(kwargs["h"], 2)) + iyy = (kwargs["m"] / 12.0) * (pow(kwargs["w"], 2) + pow(kwargs["h"], 2)) + izz = (kwargs["m"] / 12.0) * (pow(kwargs["w"], 2) + pow(kwargs["d"], 2)) + geometry = ObstacleGenerator.createElement("geometry") + geometry.append(ObstacleGenerator.createElement(model_type.lower(), + props={"size": "{:f} {:f} {:f}".format(kwargs["w"], kwargs["d"], kwargs["h"])})) + elif model_type.upper() == "CYLINDER": + assert "m" in kwargs and \ + "r" in kwargs and \ + "h" in kwargs and \ + "c" in kwargs, \ + "Parameters of {} are `m`, `r`, `h`, `c` which mean mass, \ + radius, height and color, ".format(model_type) + ixx = (kwargs["m"] / 12.0) * (3 * pow(kwargs["r"], 2) + pow(kwargs["h"], 2)) + iyy = (kwargs["m"] / 12.0) * (3 * pow(kwargs["r"], 2) + pow(kwargs["h"], 2)) + izz = (kwargs["m"] * pow(kwargs["r"], 2)) / 2.0 + geometry = ObstacleGenerator.createElement("geometry") + geometry.append(ObstacleGenerator.createElement(model_type.lower(), + props={"length": str(kwargs["h"]), "radius": str(kwargs["r"])})) + elif model_type.upper() == "SPHERE": + assert "m" in kwargs and \ + "r" in kwargs and \ + "c" in kwargs, \ + "Parameters of {} are `m`, `r`, `h`, `c` which mean mass, \ + radius and color, ".format(model_type) + ixx = (2 * kwargs["m"] * pow(kwargs["r"], 2)) / 5.0 + iyy = (2 * kwargs["m"] * pow(kwargs["r"], 2)) / 5.0 + izz = (2 * kwargs["m"] * pow(kwargs["r"], 2)) / 5.0 + geometry = ObstacleGenerator.createElement("geometry") + geometry.append(ObstacleGenerator.createElement("sphere", props={"radius": str(kwargs["r"])})) + else: + raise NotImplementedError + + # URDF generation dynamically + static_obs = ObstacleGenerator.createElement("robot", props={"name": model_type.lower()}) + link = ObstacleGenerator.createElement("link", props={"name": model_type.lower() + "_link"}) + + inertial = ObstacleGenerator.createElement("inertial") + inertial.append(ObstacleGenerator.createElement("origin", props={"xyz": "0 0 0", "rpy": "0 0 0"})) + inertial.append(ObstacleGenerator.createElement("mass", props={"value": str(kwargs["m"])})) + inertial.append(ObstacleGenerator.createElement("inertia", props={"ixx": str(ixx), "ixy": "0.0", "ixz": "0.0", + "iyy": str(iyy), "iyz": "0.0", "izz": str(izz)})) + + collision = ObstacleGenerator.createElement("collision") + collision.append(ObstacleGenerator.createElement("origin", props={"xyz": "0 0 0", "rpy": "0 0 0"})) + + collision.append(geometry) + + visual = ObstacleGenerator.createElement("visual") + visual.append(ObstacleGenerator.createElement("origin", props={"xyz": "0 0 0", "rpy": "0 0 0"})) + visual.append(geometry) + r, g, b, a = ObstacleGenerator.color(kwargs["c"]) + visual.append(ObstacleGenerator.createElement("color", props={"rgba": "{:f} {:f} {:f} {:f}".format(r, g, b, a)})) + + link.append(inertial) + link.append(collision) + link.append(visual) + + gazebo = ObstacleGenerator.createElement("gazebo", props={"reference": model_type.lower() + "_link"}) + gazebo.append(ObstacleGenerator.createElement("kp", text=str(100000.0))) + gazebo.append(ObstacleGenerator.createElement("kd", text=str(100000.0))) + gazebo.append(ObstacleGenerator.createElement("mu1", text=str(10.0))) + gazebo.append(ObstacleGenerator.createElement("mu2", text=str(10.0))) + gazebo.append(ObstacleGenerator.createElement("material", text="Gazebo/" + kwargs["c"])) + + static_obs.append(link) + static_obs.append(gazebo) + + ObstacleGenerator.indent(static_obs) + + return ET.tostring(static_obs).decode() + + @staticmethod + def color(color_name): + if color_name == "Blue": + return (0, 0, 0.8, 1) + elif color_name == "Red": + return (0.8, 0, 0, 1) + elif color_name == "Green": + return (0, 0.8, 0, 1) + elif color_name == "Grey": + return (0.75, 0.75, 0.75, 1) + elif color_name == "White": + return (1.0, 1.0, 1.0, 1) + elif color_name == "Black": + return (0, 0, 0, 1) + else: + return (0.75, 0.75, 0.75, 1) \ No newline at end of file diff --git a/simulators/third_party/dynamic_xml_config/plugins/obstacles_generate_ros.py b/simulators/third_party/dynamic_xml_config/plugins/obstacles_generate_ros.py new file mode 100755 index 0000000..2c0ea32 --- /dev/null +++ b/simulators/third_party/dynamic_xml_config/plugins/obstacles_generate_ros.py @@ -0,0 +1,25 @@ +#!/usr/bin/python +# -*- coding: utf-8 -*- + +""" +****************************************************************************************** +* Copyright (C) 2023 Yang Haodong, All Rights Reserved * +* * +* @brief generate launch file dynamicly based on user configure. * +* @author Haodong Yang * +* @version 1.0.2 * +* @date 2023.03.15 * +* @license GNU General Public License (GPL) * +****************************************************************************************** +""" +import rospy +import sys, os +sys.path.append(os.path.abspath(os.path.join(__file__, "../../"))) + +from plugins import ObstacleGenerator + +if __name__ == "__main__": + obstacles = ObstacleGenerator() + + rospy.init_node("spawn_obstacles") + obstacles.spawn() \ No newline at end of file diff --git a/simulators/third_party/dynamic_xml_config/plugins/pedestrians_generate.py b/simulators/third_party/dynamic_xml_config/plugins/pedestrians_generate.py new file mode 100755 index 0000000..f6862d2 --- /dev/null +++ b/simulators/third_party/dynamic_xml_config/plugins/pedestrians_generate.py @@ -0,0 +1,185 @@ +#!/usr/bin/python +# -*- coding: utf-8 -*- + +""" +****************************************************************************************** +* Copyright (C) 2023 Yang Haodong, All Rights Reserved * +* * +* @brief generate launch file dynamicly based on user configure. * +* @author Haodong Yang * +* @version 1.0.2 * +* @date 2023.03.15 * +* @license GNU General Public License (GPL) * +****************************************************************************************** +""" +import xml.etree.ElementTree as ET +from .xml_generate import XMLGenerator + + +class PedGenerator(XMLGenerator): + def __init__(self) -> None: + super().__init__() + if "plugins" in self.user_cfg.keys() and "pedestrians" in self.user_cfg["plugins"] \ + and self.user_cfg["plugins"]["pedestrians"]: + self.ped_cfg = PedGenerator.yamlParser(self.root_path + "user_config/" + self.user_cfg["plugins"]["pedestrians"]) + else: + self.ped_cfg = None + + def __str__(self) -> str: + return "Pedestrians Generator" + + def plugin(self): + """ + Implement of pedestrian application. + """ + app_register = [] + if not self.ped_cfg is None: + '''dynamic confiugre''' + ped_path = self.root_path + "sim_env/worlds/" + self.user_cfg["world"] + "_with_pedestrians.world" + self.writePedestrianWorld(ped_path) + + '''app register''' + # world generation + ped_world = PedGenerator.createElement("arg", props={"name": "world_parameter", + "value": self.user_cfg["world"] + "_with_pedestrians"}) + app_register.append(ped_world) + else: + # world generation + ped_world = PedGenerator.createElement("arg", props={"name": "world_parameter", "value": self.user_cfg["world"]}) + app_register.append(ped_world) + + return app_register + + def writePedestrianWorld(self, path): + """ + Create configure file to construct pedestrians environment. + + Parameters + ---------- + path: str + the path of file(.launch.xml) to write. + """ + + def createHuman(config, index): + """ + Create human element of world file. + + Parameters + ---------- + config: dict + configure data structure. + index: int + human index + + Return + ---------- + human: ET.Element + human element ptr + """ + + def createCollision(name, scale, pose=None): + if pose: + props = {"scale": " ".join("%s" % s for s in scale), "pose": " ".join("%s" % p for p in pose)} + else: + props = {"scale": " ".join("%s" % s for s in scale)} + return PedGenerator.createElement("collision", text=name, props=props) + + # configure + sfm = config["social_force"] + human = config["pedestrians"]["ped_property"][index] + upd_rate = config["pedestrians"]["update_rate"] + + # root: actor + actor = PedGenerator.createElement("actor", props={"name": human["name"]}) + + # human initial pose + pose = PedGenerator.createElement("pose", text=human["pose"]) + + # human skin + skin = PedGenerator.createElement("skin") + skin.append(PedGenerator.createElement("filename", text="walk.dae")) + skin.append(PedGenerator.createElement("scale", text="1.0")) + + animation = PedGenerator.createElement("animation", props={"name": "walking"}) + animation.append(PedGenerator.createElement("filename", text="walk.dae")) + animation.append(PedGenerator.createElement("scale", text="1.0")) + animation.append(PedGenerator.createElement("interpolate_x", text="true")) + + # plugin + if not index: + plugin_visual = PedGenerator.createElement("plugin", props={"name": "pedestrian_visual", "filename": "libPedestrianVisualPlugin.so"}) + plugin_visual.append(PedGenerator.createElement("update_rate", text=str(upd_rate))) + else: + plugin_visual = None + + plugin = PedGenerator.createElement("plugin", props={"name": human["name"] + "_plugin", "filename": "libPedestrianSFMPlugin.so"}) + plugin.append(createCollision("LHipJoint_LeftUpLeg_collision", [0.01, 0.001, 0.001])) + plugin.append(createCollision("LeftUpLeg_LeftLeg_collision", [8.0, 8.0, 1.0])) + plugin.append(createCollision("LeftLeg_LeftFoot_collision", [10.0, 10.0, 1.5])) + plugin.append(createCollision("LeftFoot_LeftToeBase_collision", [4.0, 4.0, 1.5])) + plugin.append(createCollision("RHipJoint_RightUpLeg_collision", [0.01, 0.001, 0.001])) + plugin.append(createCollision("RightUpLeg_RightLeg_collision", [8.0, 8.0, 1.0])) + plugin.append(createCollision("RightLeg_RightFoot_collision", [10.0, 10.0, 1.5])) + plugin.append(createCollision("RightFoot_RightToeBase_collision", [4.0, 4.0, 1.5])) + plugin.append(createCollision("Spine_Spine1_collision", [0.01, 0.001, 0.001])) + plugin.append(createCollision("Neck_Neck1_collision", [0.01, 0.001, 0.001])) + plugin.append(createCollision("Neck1_Head_collision", [5.0, 5.0, 3.0])) + plugin.append(createCollision("LeftShoulder_LeftArm_collision", [0.01, 0.001, 0.001])) + plugin.append(createCollision("LeftArm_LeftForeArm_collision", [5.0, 5.0, 1.0])) + plugin.append(createCollision("LeftForeArm_LeftHand_collision", [5.0, 5.0, 1.0])) + plugin.append(createCollision("LeftFingerBase_LeftHandIndex1_collision", [4.0, 4.0, 3.0])) + plugin.append(createCollision("RightShoulder_RightArm_collision", [0.01, 0.001, 0.001])) + plugin.append(createCollision("RightArm_RightForeArm_collision", [5.0, 5.0, 1.0])) + plugin.append(createCollision("RightForeArm_RightHand_collision", [5.0, 5.0, 1.0])) + plugin.append(createCollision("RightFingerBase_RightHandIndex1_collision", [4.0, 4.0, 3.0])) + plugin.append(createCollision("LowerBack_Spine_collision", [12.0, 20.0, 5.0], [0.05, 0, 0, 0, -0.2, 0])) + + plugin.append(PedGenerator.createElement("velocity", text=str(human["velocity"]))) + plugin.append(PedGenerator.createElement("radius", text=str(human["radius"]))) + plugin.append(PedGenerator.createElement("cycle", text=str(human["cycle"]))) + plugin.append(PedGenerator.createElement("animation_factor", text=str(sfm["animation_factor"]))) + plugin.append(PedGenerator.createElement("people_distance", text=str(sfm["people_distance"]))) + plugin.append(PedGenerator.createElement("goal_weight", text=str(sfm["goal_weight"]))) + plugin.append(PedGenerator.createElement("obstacle_weight", text=str(sfm["obstacle_weight"]))) + plugin.append(PedGenerator.createElement("social_weight", text=str(sfm["social_weight"]))) + plugin.append(PedGenerator.createElement("group_gaze_weight", text=str(sfm["group_gaze_weight"]))) + plugin.append(PedGenerator.createElement("group_coh_weight", text=str(sfm["group_coh_weight"]))) + plugin.append(PedGenerator.createElement("group_rep_weight", text=str(sfm["group_rep_weight"]))) + + if "time_delay" in human.keys(): + plugin.append(PedGenerator.createElement("time_delay", text=str(human["time_delay"]))) + + ignore_obstacles = PedGenerator.createElement("ignore_obstacles") + for model in human["ignore"].values(): + ignore_obstacles.append(PedGenerator.createElement("model", text=model)) + + trajectory = PedGenerator.createElement("trajectory") + for goal in human["trajectory"].values(): + trajectory.append(PedGenerator.createElement("goalpoint", text=goal)) + + plugin.append(ignore_obstacles) + plugin.append(trajectory) + + actor.append(pose) + actor.append(skin) + actor.append(animation) + actor.append(plugin) + + if not plugin_visual is None: + actor.append(plugin_visual) + + PedGenerator.indent(actor) + + return actor + + if not self.ped_cfg is None: + world_file = self.root_path + "sim_env/worlds/" + self.user_cfg["world"] + ".world" + tree = ET.parse(world_file) + world = tree.getroot().find("world") + + human_num = len(self.ped_cfg["pedestrians"]["ped_property"]) + for i in range(human_num): + world.append(createHuman(self.ped_cfg, i)) + + with open(path, "wb+") as f: + tree.write(f, encoding="utf-8", xml_declaration=True) \ No newline at end of file diff --git a/simulators/third_party/dynamic_xml_config/plugins/robot_generate.py b/simulators/third_party/dynamic_xml_config/plugins/robot_generate.py new file mode 100755 index 0000000..a09bec9 --- /dev/null +++ b/simulators/third_party/dynamic_xml_config/plugins/robot_generate.py @@ -0,0 +1,124 @@ +#!/usr/bin/python +# -*- coding: utf-8 -*- + +""" +****************************************************************************************** +* Copyright (C) 2023 Yang Haodong, All Rights Reserved * +* * +* @brief generate launch file dynamicly based on user configure. * +* @author Haodong Yang * +* @version 1.0.2 * +* @date 2023.07.19 * +* @license GNU General Public License (GPL) * +****************************************************************************************** +""" +import xml.etree.ElementTree as ET +from .xml_generate import XMLGenerator + + +class RobotGenerator(XMLGenerator): + def __init__(self) -> None: + super().__init__() + + def __str__(self) -> str: + return "Robots Generator" + + def plugin(self): + """ + Implement of robots starting application. + """ + app_register = [] + self.writeRobotsXml(self.root_path + "sim_env/launch/include/robots/start_robots.launch.xml") + return app_register + + def writeRobotsXml(self, path): + """ + Create configure file to start robots dynamically. + + Parameters + ---------- + path: str + the path of file(.launch.xml) to write. + """ + + def getRobotArg(name: str, index: int = -1): + if index == -1: + e = RobotGenerator.createElement( + "arg", props={"name": name, "value": "$(eval arg('robot' + str(arg('robot_number')) + '_" + name + "'))"} + ) + else: + e = RobotGenerator.createElement( + "arg", + props={ + "name": "robot" + str(index + 1) + "_" + name, + "value": self.user_cfg["robots_config"][index]["robot" + str(index + 1) + "_" + name], + }, + ) + return e + + # root + launch = RobotGenerator.createElement("launch") + + # setting the number of robots + if "robots_config" in self.user_cfg.keys(): + robots_num = len(self.user_cfg["robots_config"]) + else: + robots_num = 0 + raise ValueError("There is no robot!") + + launch.append(RobotGenerator.createElement("arg", props={"name": "robot_number", "default": str(robots_num)})) + + # setting the parameters of robots + for i in range(robots_num): + # robotic type + launch.append(getRobotArg("type", i)) + # global planner + launch.append(getRobotArg("global_planner", i)) + # local planner + launch.append(getRobotArg("local_planner", i)) + # robotic pose + launch.append(getRobotArg("x_pos", i)) + launch.append(getRobotArg("y_pos", i)) + launch.append(getRobotArg("z_pos", i)) + launch.append(getRobotArg("yaw", i)) + + # create starting node + include = RobotGenerator.createElement("include", props={"file": "$(find sim_env)/launch/app/environment_single.launch.xml"}) + include.append( + RobotGenerator.createElement("arg", props={"name": "robot", "value": "$(eval arg('robot' + str(arg('robot_number')) + '_type'))"}) + ) + # planner + include.append(getRobotArg("global_planner")) + include.append(getRobotArg("local_planner")) + # namespace + include.append(RobotGenerator.createElement("arg", props={"name": "robot_namespace", "value": "robot$(arg robot_number)"})) + if robots_num > 1: + include.append(RobotGenerator.createElement("arg", props={"name": "start_ns", "value": "true"})) + else: + include.append(RobotGenerator.createElement("arg", props={"name": "start_ns", "value": "false"})) + # pose + include.append( + RobotGenerator.createElement("arg", props={"name": "robot_x", "value": "$(eval arg('robot' + str(arg('robot_number')) + '_x_pos'))"}) + ) + include.append( + RobotGenerator.createElement("arg", props={"name": "robot_y", "value": "$(eval arg('robot' + str(arg('robot_number')) + '_y_pos'))"}) + ) + include.append( + RobotGenerator.createElement("arg", props={"name": "robot_z", "value": "$(eval arg('robot' + str(arg('robot_number')) + '_z_pos'))"}) + ) + include.append( + RobotGenerator.createElement("arg", props={"name": "robot_yaw", "value": "$(eval arg('robot' + str(arg('robot_number')) + '_yaw'))"}) + ) + + # recursive start + cycle = RobotGenerator.createElement( + "include", props={"file": "$(find sim_env)/launch/include/robots/start_robots.launch.xml", "if": "$(eval arg('robot_number') > 1)"} + ) + cycle.append(RobotGenerator.createElement("arg", props={"name": "robot_number", "value": "$(eval arg('robot_number') - 1)"})) + + launch.append(include) + launch.append(cycle) + RobotGenerator.indent(launch) + + with open(path, "wb+") as f: + ET.ElementTree(launch).write(f, encoding="utf-8", xml_declaration=True) \ No newline at end of file diff --git a/simulators/third_party/dynamic_xml_config/plugins/xml_generate.py b/simulators/third_party/dynamic_xml_config/plugins/xml_generate.py new file mode 100755 index 0000000..de33159 --- /dev/null +++ b/simulators/third_party/dynamic_xml_config/plugins/xml_generate.py @@ -0,0 +1,88 @@ +#!/usr/bin/python +# -*- coding: utf-8 -*- + +""" +****************************************************************************************** +* Copyright (C) 2023 Yang Haodong, All Rights Reserved * +* * +* @brief generate launch file dynamicly based on user configure. * +* @author Haodong Yang * +* @version 1.0.2 * +* @date 2023.04.23 * +* @license GNU General Public License (GPL) * +****************************************************************************************** +""" +import yaml +import xml.etree.ElementTree as ET +import sys, os + +from abc import abstractmethod, ABC + +class XMLGenerator(ABC): + def __init__(self) -> None: + # get the root path of package(src layer) + self.root_path = os.path.split(os.path.realpath(__file__))[0] + "/../../../" + # user configure + self.user_cfg = XMLGenerator.yamlParser(self.root_path + "user_config/" + sys.argv[1]) + + @abstractmethod + def plugin(self): + """ + [interface] Implement of specific application. + + Return + ---------- + app_register: list of ET.Element to register + """ + pass + + @staticmethod + def yamlParser(path: str) -> dict: + """ + Parser user configure file(.yaml). + + Parameters + ---------- + path: str + the path of file(.yaml). + + Return + ---------- + data: dict + user configuer tree + """ + with open(path, "r") as f: + data = yaml.load(f, Loader=yaml.FullLoader) + return data + + @staticmethod + def indent(elem: ET.Element, level: int = 0) -> None: + """ + Format the generated xml document. + + Parameters + ---------- + elem: ET.Element + level: int + indent level. + """ + i = "\n" + level * "\t" + if len(elem): + if not elem.text or not elem.text.strip(): + elem.text = i + "\t" + if not elem.tail or not elem.tail.strip(): + elem.tail = i + for elem in elem: + XMLGenerator.indent(elem, level + 1) + if not elem.tail or not elem.tail.strip(): + elem.tail = i + else: + if level and (not elem.tail or not elem.tail.strip()): + elem.tail = i + + @staticmethod + def createElement(name: str, text: str = None, props: dict = {}) -> ET.Element: + e = ET.Element(name, attrib=props) + if not text is None: + e.text = text + return e \ No newline at end of file diff --git a/simulators/third_party/gazebo_plugins/pedestrian_sfm_plugin/CMakeLists.txt b/simulators/third_party/gazebo_plugins/pedestrian_sfm_plugin/CMakeLists.txt new file mode 100755 index 0000000..5aa1cd2 --- /dev/null +++ b/simulators/third_party/gazebo_plugins/pedestrian_sfm_plugin/CMakeLists.txt @@ -0,0 +1,55 @@ +cmake_minimum_required(VERSION 3.0.2) +project(gazebo_sfm_plugin) + +add_compile_options(-std=c++17) + +find_package(catkin REQUIRED COMPONENTS + gazebo_ros + roscpp + message_generation +) + +find_package(Boost REQUIRED COMPONENTS thread) +find_package(gazebo REQUIRED) + +add_service_files( + FILES + ped_state.srv +) + +generate_messages( + DEPENDENCIES +) + +include_directories(include) +include_directories(SYSTEM + /usr/local/include #to find lightsfm + ${Boost_INCLUDE_DIRS} + ${catkin_INCLUDE_DIRS} + ${GAZEBO_INCLUDE_DIRS} +) + +link_directories( + ${catkin_LIBRARY_DIRS} + ${GAZEBO_LIBRARY_DIRS} +) + + + +catkin_package( + INCLUDE_DIRS include + LIBRARIES PedestrianSFMPlugin + CATKIN_DEPENDS gazebo_ros roscpp +) + + +add_library(PedestrianSFMPlugin src/pedestrian_sfm_plugin.cpp) +add_dependencies(PedestrianSFMPlugin gazebo_sfm_plugin_generate_messages_cpp) +target_link_libraries(PedestrianSFMPlugin ${catkin_LIBRARIES} ${GAZEBO_LIBRARIES}) #${Boost_LIBRARIES + +install(TARGETS + PedestrianSFMPlugin + DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +) + diff --git a/simulators/third_party/gazebo_plugins/pedestrian_sfm_plugin/include/lightsfm/angle.hpp b/simulators/third_party/gazebo_plugins/pedestrian_sfm_plugin/include/lightsfm/angle.hpp new file mode 100755 index 0000000..778f809 --- /dev/null +++ b/simulators/third_party/gazebo_plugins/pedestrian_sfm_plugin/include/lightsfm/angle.hpp @@ -0,0 +1,203 @@ +/***********************************************************************/ +/** */ +/** angle.hpp */ +/** */ +/** Copyright (c) 2016, Service Robotics Lab. */ +/** http://robotics.upo.es */ +/** */ +/** All rights reserved. */ +/** */ +/** Authors: */ +/** Ignacio Perez-Hurtado (maintainer) */ +/** Jesus Capitan */ +/** Fernando Caballero */ +/** Luis Merino */ +/** */ +/** This software may be modified and distributed under the terms */ +/** of the BSD license. See the LICENSE file for details. */ +/** */ +/** http://www.opensource.org/licenses/BSD-3-Clause */ +/** */ +/***********************************************************************/ + +#ifndef _ANGLE_HPP_ +#define _ANGLE_HPP_ + +#include +#include + +namespace utils +{ +class Angle +{ +public: + enum AngleRange + { + // [0, 2*pi) or [0°, 360°) + PositiveOnlyRange, + // (-pi, +pi] or (-180°, 180°] + PositiveNegativeRange + }; + + Angle() : value(0) + { + } + virtual ~Angle() + { + } + + static Angle fromRadian(double value) + { + return Angle(value); + } + + static Angle fromDegree(double value) + { + return Angle(value / 180 * M_PI); + } + + double toRadian(AngleRange range = PositiveNegativeRange) const + { + if (range == PositiveNegativeRange) + { + return value; + } + else + { + return (value >= 0) ? value : (value + 2 * M_PI); + } + } + + double cos() const + { + return std::cos(value); + } + + double sin() const + { + return std::sin(value); + } + + double toDegree(AngleRange range = PositiveNegativeRange) const + { + double degreeValue = value * 180 / M_PI; + if (range == PositiveNegativeRange) + { + return degreeValue; + } + else + { + return (degreeValue >= 0) ? degreeValue : (degreeValue + 360); + } + } + + void setRadian(double value) + { + Angle::value = value; + normalize(); + } + + void setDegree(double value) + { + Angle::value = value / 180 * M_PI; + normalize(); + } + + int sign() const + { + if (value == 0) + { + return 0; + } + else if (value > 0) + { + return 1; + } + else + { + return -1; + } + } + + Angle operator+(const Angle& other) const + { + return Angle(value + other.value); + } + + Angle operator-(const Angle& other) const + { + return Angle(value - other.value); + } + + Angle& operator+=(const Angle& other) + { + value += other.value; + normalize(); + return *this; + } + + Angle& operator-=(const Angle& other) + { + value -= other.value; + normalize(); + return *this; + } + + bool operator==(const Angle& other) const + { + return value == other.value; + } + + bool operator!=(const Angle& other) const + { + return value != other.value; + } + + bool operator<(const Angle& other) const + { + return value < other.value; + } + + bool operator<=(const Angle& other) const + { + return value <= other.value; + } + + bool operator>(const Angle& other) const + { + return value > other.value; + } + + bool operator>=(const Angle& other) const + { + return value >= other.value; + } + +private: + Angle(double value) + { + Angle::value = value; + normalize(); + } + + void normalize() + { + while (value <= -M_PI) + value += 2 * M_PI; + while (value > M_PI) + value -= 2 * M_PI; + } + + double value; +}; +} // namespace utils +namespace std +{ +inline ostream& operator<<(ostream& stream, const utils::Angle& alpha) +{ + stream << alpha.toRadian(); + return stream; +} +} // namespace std + +#endif diff --git a/simulators/third_party/gazebo_plugins/pedestrian_sfm_plugin/include/lightsfm/map.hpp b/simulators/third_party/gazebo_plugins/pedestrian_sfm_plugin/include/lightsfm/map.hpp new file mode 100755 index 0000000..7c0f003 --- /dev/null +++ b/simulators/third_party/gazebo_plugins/pedestrian_sfm_plugin/include/lightsfm/map.hpp @@ -0,0 +1,53 @@ +/***********************************************************************/ +/** */ +/** map.hpp */ +/** */ +/** Copyright (c) 2016, Service Robotics Lab. */ +/** http://robotics.upo.es */ +/** */ +/** All rights reserved. */ +/** */ +/** Authors: */ +/** Ignacio Perez-Hurtado (maintainer) */ +/** Jesus Capitan */ +/** Fernando Caballero */ +/** Luis Merino */ +/** */ +/** This software may be modified and distributed under the terms */ +/** of the BSD license. See the LICENSE file for details. */ +/** */ +/** http://www.opensource.org/licenses/BSD-3-Clause */ +/** */ +/***********************************************************************/ + +#ifndef _MAP_HPP_ +#define _MAP_HPP_ + +#include "vector2d.hpp" + +namespace sfm +{ +class Map +{ +public: + struct Obstacle + { + Obstacle() : distance(-1) + { + } + double distance; + utils::Vector2d position; + }; + + Map() + { + } + virtual ~Map() + { + } + virtual const Obstacle& getNearestObstacle(const utils::Vector2d& x) = 0; + virtual bool isObstacle(const utils::Vector2d& x) const = 0; +}; +} // namespace sfm + +#endif diff --git a/simulators/third_party/gazebo_plugins/pedestrian_sfm_plugin/include/lightsfm/sfm.hpp b/simulators/third_party/gazebo_plugins/pedestrian_sfm_plugin/include/lightsfm/sfm.hpp new file mode 100755 index 0000000..395a438 --- /dev/null +++ b/simulators/third_party/gazebo_plugins/pedestrian_sfm_plugin/include/lightsfm/sfm.hpp @@ -0,0 +1,619 @@ +/***********************************************************************/ +/** */ +/** sfm.hpp */ +/** */ +/** Copyright (c) 2016, Service Robotics Lab. */ +/** http://robotics.upo.es */ +/** */ +/** All rights reserved. */ +/** */ +/** Authors: */ +/** Ignacio Perez-Hurtado (maintainer) */ +/** Jesus Capitan */ +/** Fernando Caballero */ +/** Luis Merino */ +/** */ +/** This software may be modified and distributed under the terms */ +/** of the BSD license. See the LICENSE file for details. */ +/** */ +/** http://www.opensource.org/licenses/BSD-3-Clause */ +/** */ +/***********************************************************************/ + +#ifndef _SFM_HPP_ +#define _SFM_HPP_ + +#include "map.hpp" +#include "vector2d.hpp" +#include +#include +#include + +namespace sfm +{ +struct Forces +{ + utils::Vector2d desiredForce; + utils::Vector2d obstacleForce; + utils::Vector2d socialForce; + utils::Vector2d groupGazeForce; + utils::Vector2d groupCoherenceForce; + utils::Vector2d groupRepulsionForce; + utils::Vector2d groupForce; + utils::Vector2d globalForce; + utils::Vector2d robotSocialForce; +}; + +struct Parameters +{ + Parameters() + : forceFactorDesired(2.0) + , forceFactorObstacle(10) + , forceSigmaObstacle(0.2) + , forceFactorSocial(2.1) + , forceFactorGroupGaze(3.0) + , forceFactorGroupCoherence(2.0) + , forceFactorGroupRepulsion(1.0) + , lambda(2.0) + , gamma(0.35) + , n(2.0) + , nPrime(3.0) + , relaxationTime(0.5) + { + } + + double forceFactorDesired; + double forceFactorObstacle; + double forceSigmaObstacle; + double forceFactorSocial; + double forceFactorGroupGaze; + double forceFactorGroupCoherence; + double forceFactorGroupRepulsion; + double lambda; + double gamma; + double n; + double nPrime; + double relaxationTime; +}; + +struct Goal +{ + utils::Vector2d center; + double radius; +}; + +struct Agent +{ + Agent() + : desiredVelocity(0.6) + , radius(0.35) + , cyclicGoals(false) + , teleoperated(false) + , antimove(false) + , linearVelocity(0) + , angularVelocity(0) + , groupId(-1) + { + } + + Agent(double linearVelocity, double angularVelocity) + : desiredVelocity(0.6) + , radius(0.35) + , cyclicGoals(false) + , teleoperated(true) + , antimove(false) + , linearVelocity(linearVelocity) + , angularVelocity(angularVelocity) + , groupId(-1) + { + } + + Agent(const utils::Vector2d& position, const utils::Angle& yaw, double linearVelocity, double angularVelocity) + : position(position) + , yaw(yaw) + , desiredVelocity(0.6) + , radius(0.35) + , cyclicGoals(false) + , teleoperated(true) + , antimove(false) + , linearVelocity(linearVelocity) + , angularVelocity(angularVelocity) + , groupId(-1) + { + } + + void move(double dt); // only if teleoperated + + utils::Vector2d position; + utils::Vector2d velocity; + utils::Angle yaw; + + utils::Vector2d movement; + + double desiredVelocity; + double radius; + + std::list goals; + bool cyclicGoals; + + bool teleoperated; + bool antimove; + double linearVelocity; + double angularVelocity; + + int groupId; + + int id; + + Forces forces; + Parameters params; + std::vector obstacles1; + std::vector obstacles2; +}; + +struct Group +{ + utils::Vector2d center; + std::vector agents; +}; + +class SocialForceModel +{ +public: + SocialForceModel(SocialForceModel const&) = delete; + void operator=(SocialForceModel const&) = delete; + ~SocialForceModel() + { + } + + static SocialForceModel& getInstance() + { + static SocialForceModel singleton; + return singleton; + } + +#define SFM SocialForceModel::getInstance() + + std::vector& computeForces(std::vector& agents, Map* map = NULL) const; + void computeForces(Agent& me, std::vector& agents, Map* map = NULL); + std::vector& updatePosition(std::vector& agents, double dt) const; + void updatePosition(Agent& me, double dt) const; + +private: +#define PW(x) ((x) * (x)) + SocialForceModel() + { + } + utils::Vector2d computeDesiredForce(Agent& agent) const; + void computeObstacleForce(Agent& agent, Map* map) const; + void computeSocialForce(unsigned index, std::vector& agents) const; + void computeSocialForce(Agent& agent, std::vector& agents) const; + void computeGroupForce(unsigned index, const utils::Vector2d& desiredDirection, std::vector& agents, + const std::unordered_map& groups) const; + void computeGroupForce(Agent& me, const utils::Vector2d& desiredDirection, std::vector& agents, + Group& group) const; +}; + +inline utils::Vector2d SocialForceModel::computeDesiredForce(Agent& agent) const +{ + utils::Vector2d desiredDirection; + if (!agent.goals.empty() && (agent.goals.front().center - agent.position).norm() > agent.goals.front().radius) + { + utils::Vector2d diff = agent.goals.front().center - agent.position; + desiredDirection = diff.normalized(); + agent.forces.desiredForce = agent.params.forceFactorDesired * + (desiredDirection * agent.desiredVelocity - agent.velocity) / + agent.params.relaxationTime; + agent.antimove = false; + } + else + { + agent.forces.desiredForce = -agent.velocity / agent.params.relaxationTime; + agent.antimove = true; + } + return desiredDirection; +} + +inline void SocialForceModel::computeObstacleForce(Agent& agent, Map* map) const +{ + // Initially, the obstacles were expected to be in robot local frame. We have + // replaced it to work in the same frame of the other forces. + // if (agent.obstacles1.size() > 0 || agent.obstacles2.size() > 0) { + // agent.forces.obstacleForce.set(0, 0); + // for (unsigned i = 0; i < agent.obstacles1.size(); i++) { + // double distance = agent.obstacles1[i].norm() - agent.radius; + // agent.forces.obstacleForce += + // agent.params.forceFactorObstacle * + // std::exp(-distance / agent.params.forceSigmaObstacle) * + // (-agent.obstacles1[i]).normalized(); + // } + // for (unsigned i = 0; i < agent.obstacles2.size(); i++) { + // double distance = agent.obstacles2[i].norm() - agent.radius; + // agent.forces.obstacleForce += + // agent.params.forceFactorObstacle * + // std::exp(-distance / agent.params.forceSigmaObstacle) * + // (-agent.obstacles2[i]).normalized(); + // } + // agent.forces.obstacleForce /= + // (double)(agent.obstacles1.size() + agent.obstacles2.size()); + if (agent.obstacles1.size() > 0 || agent.obstacles2.size() > 0) + { + agent.forces.obstacleForce.set(0, 0); + for (unsigned i = 0; i < agent.obstacles1.size(); i++) + { + utils::Vector2d minDiff = agent.position - agent.obstacles1[i]; + double distance = minDiff.norm() - agent.radius; + agent.forces.obstacleForce += agent.params.forceFactorObstacle * + std::exp(-distance / agent.params.forceSigmaObstacle) * minDiff.normalized(); + } + for (unsigned i = 0; i < agent.obstacles2.size(); i++) + { + utils::Vector2d minDiff = agent.position - agent.obstacles2[i]; + double distance = minDiff.norm() - agent.radius; + agent.forces.obstacleForce += agent.params.forceFactorObstacle * + std::exp(-distance / agent.params.forceSigmaObstacle) * minDiff.normalized(); + } + agent.forces.obstacleForce /= (double)(agent.obstacles1.size() + agent.obstacles2.size()); + } + else if (map != NULL) + { + const Map::Obstacle& obs = map->getNearestObstacle(agent.position); + utils::Vector2d minDiff = agent.position - obs.position; + double distance = minDiff.norm() - agent.radius; + agent.forces.obstacleForce = + agent.params.forceFactorObstacle * std::exp(-distance / agent.params.forceSigmaObstacle) * minDiff.normalized(); + } + else + { + agent.forces.obstacleForce.set(0, 0); + } +} + +inline void SocialForceModel::computeSocialForce(unsigned index, std::vector& agents) const +{ + Agent& agent = agents[index]; + agent.forces.socialForce.set(0, 0); + for (unsigned i = 0; i < agents.size(); i++) + { + if (i == index) + { + continue; + } + utils::Vector2d diff = agents[i].position - agent.position; + utils::Vector2d diffDirection = diff.normalized(); + utils::Vector2d velDiff = agent.velocity - agents[i].velocity; + utils::Vector2d interactionVector = agent.params.lambda * velDiff + diffDirection; + double interactionLength = interactionVector.norm(); + utils::Vector2d interactionDirection = interactionVector / interactionLength; + utils::Angle theta = interactionDirection.angleTo(diffDirection); + double B = agent.params.gamma * interactionLength; + double thetaRad = theta.toRadian(); + double forceVelocityAmount = -std::exp(-diff.norm() / B - PW(agent.params.nPrime * B * thetaRad)); + double forceAngleAmount = -theta.sign() * std::exp(-diff.norm() / B - PW(agent.params.n * B * thetaRad)); + utils::Vector2d forceVelocity = forceVelocityAmount * interactionDirection; + utils::Vector2d forceAngle = forceAngleAmount * interactionDirection.leftNormalVector(); + agent.forces.socialForce += agent.params.forceFactorSocial * (forceVelocity + forceAngle); + if (i == 0) + { + agent.forces.robotSocialForce = agent.params.forceFactorSocial * (forceVelocity + forceAngle); + } + } +} + +inline void SocialForceModel::computeSocialForce(Agent& me, std::vector& agents) const +{ + // Agent& agent = agents[index]; + me.forces.socialForce.set(0, 0); + for (unsigned i = 0; i < agents.size(); i++) + { + if (agents[i].id == me.id) + { + continue; + } + utils::Vector2d diff = agents[i].position - me.position; + utils::Vector2d diffDirection = diff.normalized(); + utils::Vector2d velDiff = me.velocity - agents[i].velocity; + utils::Vector2d interactionVector = me.params.lambda * velDiff + diffDirection; + double interactionLength = interactionVector.norm(); + utils::Vector2d interactionDirection = interactionVector / interactionLength; + utils::Angle theta = interactionDirection.angleTo(diffDirection); + double B = me.params.gamma * interactionLength; + double thetaRad = theta.toRadian(); + double forceVelocityAmount = -std::exp(-diff.norm() / B - PW(me.params.nPrime * B * thetaRad)); + double forceAngleAmount = -theta.sign() * std::exp(-diff.norm() / B - PW(me.params.n * B * thetaRad)); + utils::Vector2d forceVelocity = forceVelocityAmount * interactionDirection; + utils::Vector2d forceAngle = forceAngleAmount * interactionDirection.leftNormalVector(); + me.forces.socialForce += me.params.forceFactorSocial * (forceVelocity + forceAngle); + // if (i == 0) + //{ + // agent.forces.robotSocialForce = + // agent.params.forceFactorSocial * (forceVelocity + forceAngle); + //} + } +} + +inline void SocialForceModel::computeGroupForce(unsigned index, const utils::Vector2d& desiredDirection, + std::vector& agents, + const std::unordered_map& groups) const +{ + Agent& agent = agents[index]; + agent.forces.groupForce.set(0, 0); + agent.forces.groupGazeForce.set(0, 0); + agent.forces.groupCoherenceForce.set(0, 0); + agent.forces.groupRepulsionForce.set(0, 0); + if (groups.count(agent.groupId) == 0 || groups.at(agent.groupId).agents.size() < 2) + { + return; + } + const Group& group = groups.at(agent.groupId); + + // Gaze force + utils::Vector2d com = group.center; + com = (1 / (double)(group.agents.size() - 1)) * (group.agents.size() * com - agent.position); + + utils::Vector2d relativeCom = com - agent.position; + utils::Angle visionAngle = utils::Angle::fromDegree(90); + double elementProduct = desiredDirection.dot(relativeCom); + utils::Angle comAngle = + utils::Angle::fromRadian(std::acos(elementProduct / (desiredDirection.norm() * relativeCom.norm()))); + if (comAngle > visionAngle) + { +#ifdef _PAPER_VERSION_ + utils::Angle necessaryRotation = comAngle - visionAngle; + agent.forces.groupGazeForce = -necessaryRotation.toRadian() * desiredDirection; +#else + double desiredDirectionSquared = desiredDirection.squaredNorm(); + double desiredDirectionDistance = elementProduct / desiredDirectionSquared; + agent.forces.groupGazeForce = desiredDirectionDistance * desiredDirection; +#endif + agent.forces.groupGazeForce *= agent.params.forceFactorGroupGaze; + } + + // Coherence force + com = group.center; + relativeCom = com - agent.position; + double distance = relativeCom.norm(); + double maxDistance = ((double)group.agents.size() - 1) / 2; +#ifdef _PAPER_VERSION_ + if (distance >= maxDistance) + { + agent.forces.groupCoherenceForce = relativeCom.normalized(); + agent.forces.groupCoherenceForce *= agent.params.forceFactorGroupCoherence; + } +#else + agent.forces.groupCoherenceForce = relativeCom; + double softenedFactor = agent.params.forceFactorGroupCoherence * (std::tanh(distance - maxDistance) + 1) / 2; + agent.forces.groupCoherenceForce *= softenedFactor; +#endif + + // Repulsion Force + for (unsigned i = 0; i < group.agents.size(); i++) + { + if (index == group.agents[i]) + { + continue; + } + utils::Vector2d diff = agent.position - agents.at(group.agents[i]).position; + if (diff.norm() < agent.radius + agents.at(group.agents[i]).radius) + { + agent.forces.groupRepulsionForce += diff; + } + } + agent.forces.groupRepulsionForce *= agent.params.forceFactorGroupRepulsion; + + // Group Force + agent.forces.groupForce = + agent.forces.groupGazeForce + agent.forces.groupCoherenceForce + agent.forces.groupRepulsionForce; +} + +inline void SocialForceModel::computeGroupForce(Agent& me, const utils::Vector2d& desiredDirection, + std::vector& agents, Group& group) const +{ + // Agent& agent = agents[index]; + me.forces.groupForce.set(0, 0); + me.forces.groupGazeForce.set(0, 0); + me.forces.groupCoherenceForce.set(0, 0); + me.forces.groupRepulsionForce.set(0, 0); + if (group.agents.size() < 2) + { + return; + } + + // Gaze force + utils::Vector2d com = group.center; + com = (1 / (double)(group.agents.size() - 1)) * (group.agents.size() * com - me.position); + + utils::Vector2d relativeCom = com - me.position; + utils::Angle visionAngle = utils::Angle::fromDegree(90); + double elementProduct = desiredDirection.dot(relativeCom); + utils::Angle comAngle = + utils::Angle::fromRadian(std::acos(elementProduct / (desiredDirection.norm() * relativeCom.norm()))); + if (comAngle > visionAngle) + { +#ifdef _PAPER_VERSION_ + utils::Angle necessaryRotation = comAngle - visionAngle; + me.forces.groupGazeForce = -necessaryRotation.toRadian() * desiredDirection; +#else + double desiredDirectionSquared = desiredDirection.squaredNorm(); + double desiredDirectionDistance = elementProduct / desiredDirectionSquared; + me.forces.groupGazeForce = desiredDirectionDistance * desiredDirection; +#endif + me.forces.groupGazeForce *= me.params.forceFactorGroupGaze; + } + + // Coherence force + com = group.center; + relativeCom = com - me.position; + double distance = relativeCom.norm(); + double maxDistance = ((double)group.agents.size() - 1) / 2; +#ifdef _PAPER_VERSION_ + if (distance >= maxDistance) + { + me.forces.groupCoherenceForce = relativeCom.normalized(); + me.forces.groupCoherenceForce *= me.params.forceFactorGroupCoherence; + } +#else + me.forces.groupCoherenceForce = relativeCom; + double softenedFactor = me.params.forceFactorGroupCoherence * (std::tanh(distance - maxDistance) + 1) / 2; + me.forces.groupCoherenceForce *= softenedFactor; +#endif + + // Repulsion Force + // Index 0 -> me + for (unsigned i = 1; i < group.agents.size(); i++) + { + utils::Vector2d diff = me.position - agents.at(group.agents[i]).position; + if (diff.norm() < me.radius + agents.at(group.agents[i]).radius) + { + me.forces.groupRepulsionForce += diff; + } + } + me.forces.groupRepulsionForce *= me.params.forceFactorGroupRepulsion; + + // Group Force + me.forces.groupForce = me.forces.groupGazeForce + me.forces.groupCoherenceForce + me.forces.groupRepulsionForce; +} + +inline std::vector& SocialForceModel::computeForces(std::vector& agents, Map* map) const +{ + std::unordered_map groups; + for (unsigned i = 0; i < agents.size(); i++) + { + if (agents[i].groupId < 0) + { + continue; + } + groups[agents[i].groupId].agents.push_back(i); + groups[agents[i].groupId].center += agents[i].position; + } + for (auto it = groups.begin(); it != groups.end(); ++it) + { + it->second.center /= (double)(it->second.agents.size()); + } + + for (unsigned i = 0; i < agents.size(); i++) + { + utils::Vector2d desiredDirection = computeDesiredForce(agents[i]); + computeObstacleForce(agents[i], map); + computeSocialForce(i, agents); + computeGroupForce(i, desiredDirection, agents, groups); + agents[i].forces.globalForce = agents[i].forces.desiredForce + agents[i].forces.socialForce + + agents[i].forces.obstacleForce + agents[i].forces.groupForce; + } + return agents; +} + +inline void SocialForceModel::computeForces(Agent& me, std::vector& agents, Map* map) +{ + // form the group + Group mygroup; + if (me.groupId != -1) + { + mygroup.agents.push_back(me.id); + mygroup.center = me.position; + for (unsigned i = 0; i < agents.size(); i++) + { + if (agents[i].id == me.id) + { + continue; + } + if (agents[i].groupId == me.groupId) + { + mygroup.agents.push_back(i); + mygroup.center += agents[i].position; + } + } + mygroup.center /= (double)mygroup.agents.size(); + } + + // Compute agent's forces + utils::Vector2d desiredDirection = computeDesiredForce(me); + computeObstacleForce(me, map); + computeSocialForce(me, agents); + computeGroupForce(me, desiredDirection, agents, mygroup); + me.forces.globalForce = + me.forces.desiredForce + me.forces.socialForce + me.forces.obstacleForce + me.forces.groupForce; +} + +inline void Agent::move(double dt) +{ + double imd = linearVelocity * dt; + utils::Vector2d inc(imd * std::cos(yaw.toRadian() + angularVelocity * dt * 0.5), + imd * std::sin(yaw.toRadian() + angularVelocity * dt * 0.5)); + yaw += utils::Angle::fromRadian(angularVelocity * dt); + position += inc; + velocity.set(linearVelocity * yaw.cos(), linearVelocity * yaw.sin()); +} + +inline std::vector& SocialForceModel::updatePosition(std::vector& agents, double dt) const +{ + for (unsigned i = 0; i < agents.size(); i++) + { + utils::Vector2d initPos = agents[i].position; + if (agents[i].teleoperated) + { + double imd = agents[i].linearVelocity * dt; + utils::Vector2d inc(imd * std::cos(agents[i].yaw.toRadian() + agents[i].angularVelocity * dt * 0.5), + imd * std::sin(agents[i].yaw.toRadian() + agents[i].angularVelocity * dt * 0.5)); + agents[i].yaw += utils::Angle::fromRadian(agents[i].angularVelocity * dt); + agents[i].position += inc; + agents[i].velocity.set(agents[i].linearVelocity * agents[i].yaw.cos(), + agents[i].linearVelocity * agents[i].yaw.sin()); + } + else + { + agents[i].velocity += agents[i].forces.globalForce * dt; + if (agents[i].velocity.norm() > agents[i].desiredVelocity) + { + agents[i].velocity.normalize(); + agents[i].velocity *= agents[i].desiredVelocity; + } + agents[i].yaw = agents[i].velocity.angle(); + agents[i].position += agents[i].velocity * dt; + } + agents[i].movement = agents[i].position - initPos; + if (!agents[i].goals.empty() && + (agents[i].goals.front().center - agents[i].position).norm() <= agents[i].goals.front().radius) + { + Goal g = agents[i].goals.front(); + agents[i].goals.pop_front(); + if (agents[i].cyclicGoals) + { + agents[i].goals.push_back(g); + } + } + } + return agents; +} + +inline void SocialForceModel::updatePosition(Agent& agent, double dt) const +{ + utils::Vector2d initPos = agent.position; + utils::Angle initYaw = agent.yaw; + + agent.velocity += agent.forces.globalForce * dt; + if (agent.velocity.norm() > agent.desiredVelocity) + { + agent.velocity.normalize(); + agent.velocity *= agent.desiredVelocity; + } + agent.yaw = agent.velocity.angle(); + agent.position += agent.velocity * dt; + + agent.linearVelocity = agent.velocity.norm(); + agent.angularVelocity = (agent.yaw - initYaw).toRadian() / dt; + + agent.movement = agent.position - initPos; + if (!agent.goals.empty() && (agent.goals.front().center - agent.position).norm() <= agent.goals.front().radius) + { + Goal g = agent.goals.front(); + agent.goals.pop_front(); + if (agent.cyclicGoals) + { + agent.goals.push_back(g); + } + } +} + +} // namespace sfm +#endif diff --git a/simulators/third_party/gazebo_plugins/pedestrian_sfm_plugin/include/lightsfm/vector2d.hpp b/simulators/third_party/gazebo_plugins/pedestrian_sfm_plugin/include/lightsfm/vector2d.hpp new file mode 100755 index 0000000..f54e527 --- /dev/null +++ b/simulators/third_party/gazebo_plugins/pedestrian_sfm_plugin/include/lightsfm/vector2d.hpp @@ -0,0 +1,258 @@ +/***********************************************************************/ +/** */ +/** vector2d.hpp */ +/** */ +/** Copyright (c) 2016, Service Robotics Lab. */ +/** http://robotics.upo.es */ +/** */ +/** All rights reserved. */ +/** */ +/** Authors: */ +/** Ignacio Perez-Hurtado (maintainer) */ +/** Jesus Capitan */ +/** Fernando Caballero */ +/** Luis Merino */ +/** */ +/** This software may be modified and distributed under the terms */ +/** of the BSD license. See the LICENSE file for details. */ +/** */ +/** http://www.opensource.org/licenses/BSD-3-Clause */ +/** */ +/***********************************************************************/ + +#ifndef _VECTOR2D_HPP_ +#define _VECTOR2D_HPP_ + +#include +#include +// #include +#include + +#include "angle.hpp" + +namespace utils +{ +class Vector2d +{ +public: + Vector2d() : x(0), y(0) + { + } + Vector2d(double x, double y) : x(x), y(y) + { + } + virtual ~Vector2d() + { + } + double operator()(int index) const + { + return index == 0 ? x : y; + } + double operator[](int index) const + { + return index == 0 ? x : y; + } + bool operator==(const Vector2d& other) const + { + return x == other.x && y == other.y; + } + bool operator<(const Vector2d& other) const + { + return x < other.x || (x == other.x && y < other.y); + } + double getX() const + { + return x; + } + double getY() const + { + return y; + } + + /*geometry_msgs::Point toPoint() const + { + geometry_msgs::Point p; + p.x = x; + p.y = y; + p.z = 0; + return p; + }*/ + + Vector2d& set(double x, double y) + { + Vector2d::x = x; + Vector2d::y = y; + return *this; + } + Vector2d& setX(double x) + { + Vector2d::x = x; + return *this; + } + + Vector2d& setY(double y) + { + Vector2d::y = y; + return *this; + } + + Vector2d& incX(double inc_x) + { + x += inc_x; + return *this; + } + + Vector2d& incY(double inc_y) + { + y += inc_y; + return *this; + } + + Vector2d& inc(double inc_x, double inc_y) + { + x += inc_x; + y += inc_y; + return *this; + } + + const Angle angle() const + { + return Angle::fromRadian(std::atan2(y, x)); + } + + Angle angleTo(const Vector2d& other) const + { + return other.angle() - angle(); + } + + double squaredNorm() const + { + return x * x + y * y; + } + + double norm() const + { + return std::sqrt(squaredNorm()); + } + + double dot(const Vector2d& other) const + { + return x * other.x + y * other.y; + } + + Vector2d& normalize() + { + double n = norm(); + if (n > 0) + { + x /= n; + y /= n; + } + return *this; + } + + Vector2d normalized() const + { + Vector2d v(*this); + v.normalize(); + return v; + } + + Vector2d& operator*=(double scalar) + { + x *= scalar; + y *= scalar; + return *this; + } + Vector2d operator*(double scalar) const + { + return Vector2d(x * scalar, y * scalar); + } + + Vector2d& operator/=(double scalar) + { + x /= scalar; + y /= scalar; + return *this; + } + Vector2d operator/(double scalar) const + { + return Vector2d(x / scalar, y / scalar); + } + + Vector2d leftNormalVector() const + { + return Vector2d(-y, x); + } + + Vector2d rightNormalVector() const + { + return Vector2d(y, -x); + } + + Vector2d& operator+=(const Vector2d& other) + { + set(x + other.x, y + other.y); + return *this; + } + Vector2d operator+(const Vector2d& other) const + { + return Vector2d(x + other.x, y + other.y); + } + Vector2d& operator-=(const Vector2d& other) + { + set(x - other.x, y - other.y); + return *this; + } + Vector2d operator-(const Vector2d& other) const + { + return Vector2d(x - other.x, y - other.y); + } + Vector2d operator-() const + { + return Vector2d(-x, -y); + } + + static const Vector2d& Zero() + { + static Vector2d zero; + return zero; + } + +private: + double x; + double y; +}; +} // namespace utils + +inline utils::Vector2d operator*(double scalar, const utils::Vector2d& v) +{ + utils::Vector2d w(v); + w *= scalar; + return w; +} + +namespace std +{ +inline ostream& operator<<(ostream& stream, const utils::Vector2d& v) +{ + stream << "(" << v.getX() << "," << v.getY() << ")"; + return stream; +} + +template <> +struct hash +{ + size_t operator()(const utils::Vector2d& v) const + { + using boost::hash_combine; + using boost::hash_value; + std::size_t seed = 0; + hash_combine(seed, hash_value(v[0])); + hash_combine(seed, hash_value(v[1])); + return seed; + } +}; +} // namespace std + +#endif diff --git a/simulators/third_party/gazebo_plugins/pedestrian_sfm_plugin/include/pedestrian_sfm_plugin.h b/simulators/third_party/gazebo_plugins/pedestrian_sfm_plugin/include/pedestrian_sfm_plugin.h new file mode 100755 index 0000000..3715c52 --- /dev/null +++ b/simulators/third_party/gazebo_plugins/pedestrian_sfm_plugin/include/pedestrian_sfm_plugin.h @@ -0,0 +1,131 @@ +/*********************************************************** + * + * @file: pedestrian_sfm_plugin.cpp + * @breif: Gazebo plugin for pedestrians using social force model + * @author: Yang Haodong + * @update: 2023-03-15 + * @version: 1.1 + * + * Copyright (c) 2023, Yang Haodong + * All rights reserved. + * -------------------------------------------------------- + * + **********************************************************/ +#ifndef PEDESTRIANSFM_GAZEBO_PLUGIN_H +#define PEDESTRIANSFM_GAZEBO_PLUGIN_H + +// C++ +#include +#include +#include +#include +#include +#include +#include + +// Gazebo +#include +#include +#include +#include + +// Social Force Model +#include + +// message +#include + +namespace gazebo +{ +class GZ_PLUGIN_VISIBLE PedestrianSFMPlugin : public ModelPlugin +{ +public: + /** + * @brief Construct a gazebo plugin + */ + PedestrianSFMPlugin(); + + /** + * @brief De-Construct a gazebo plugin + */ + ~PedestrianSFMPlugin(); + + /** + * @brief Load the actor plugin. + * @param _model Pointer to the parent model. + * @param _sdf Pointer to the plugin's SDF elements. + */ + virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf); + + /** + * @brief Initialize the social force model. + */ + virtual void Reset(); + +private: + /** + * @brief Function that is called every update cycle. + * @param _info Timing information. + */ + void OnUpdate(const common::UpdateInfo& _info); + + bool OnStateCallBack(gazebo_sfm_plugin::ped_state::Request& req, gazebo_sfm_plugin::ped_state::Response& resp); + + /** + * @brief Helper function to detect the closest obstacles. + */ + void handleObstacles(); + + /** + * @brief Helper function to detect the nearby pedestrians (other actors). + */ + void handlePedestrians(); + +private: + // Gazebo ROS node + std::unique_ptr node_; + // topic publisher + ros::Publisher pose_pub_; + ros::Publisher vel_pub_; + // pedestrian state server + ros::ServiceServer state_server_; + // this actor as a SFM agent + sfm::Agent sfm_actor_; + // names of the other models in my walking group. + std::vector group_names_; + // vector of pedestrians detected. + std::vector other_actors_; + // time delay + double time_delay_; + bool time_init_; + // Maximum distance to detect nearby pedestrians. + double people_dist_; + // initialized + bool pose_init_; + // last pose + double last_pose_x_, last_pose_y_; + // current state + double px_, py_, pz_, vx_, vy_, theta_; + + + // Pointer to the parent actor. + physics::ActorPtr actor_; + // Pointer to the world, for convenience. + physics::WorldPtr world_; + // Pointer to the sdf element. + sdf::ElementPtr sdf_; + // Velocity of the actor + ignition::math::Vector3d velocity_; + // List of connections + std::vector connections_; + // Time scaling factor. Used to coordinate translational motion with the actor's walking animation. + double animation_factor_ = 1.0; + // Time of the last update. + common::Time last_update_; + // List of models to ignore. Used for vector field + std::vector ignore_models_; + // Custom trajectory info. + physics::TrajectoryInfoPtr trajectory_info_; +}; +} // namespace gazebo +#endif \ No newline at end of file diff --git a/simulators/third_party/gazebo_plugins/pedestrian_sfm_plugin/package.xml b/simulators/third_party/gazebo_plugins/pedestrian_sfm_plugin/package.xml new file mode 100755 index 0000000..f6e0193 --- /dev/null +++ b/simulators/third_party/gazebo_plugins/pedestrian_sfm_plugin/package.xml @@ -0,0 +1,27 @@ + + + gazebo_sfm_plugin + 1.0.0 + The gazebo_sfm_plugin package + + winter + GPL3 + + catkin + lightsfm + gazebo_ros + roscpp + message_generation + + gazebo_ros + roscpp + + lightsfm + gazebo_ros + roscpp + message_runtime + + + + + diff --git a/simulators/third_party/gazebo_plugins/pedestrian_sfm_plugin/src/pedestrian_sfm_plugin.cpp b/simulators/third_party/gazebo_plugins/pedestrian_sfm_plugin/src/pedestrian_sfm_plugin.cpp new file mode 100755 index 0000000..ba97ce9 --- /dev/null +++ b/simulators/third_party/gazebo_plugins/pedestrian_sfm_plugin/src/pedestrian_sfm_plugin.cpp @@ -0,0 +1,479 @@ +/*********************************************************** + * + * @file: pedestrian_sfm_plugin.cpp + * @breif: Gazebo plugin for pedestrians using social force model + * @author: Yang Haodong + * @update: 2023-03-22 + * @version: 2.0 + * + * Copyright (c) 2023, Yang Haodong + * All rights reserved. + * -------------------------------------------------------- + * + **********************************************************/ +#include +#include +#include + +#include + +#define WALKING_ANIMATION "walking" + +using namespace gazebo; +GZ_REGISTER_MODEL_PLUGIN(PedestrianSFMPlugin) + +/** + * @brief Construct a gazebo plugin + */ +PedestrianSFMPlugin::PedestrianSFMPlugin() : pose_init_(false), time_delay_(0.0), time_init_(false) +{ +} + +/** + * @brief De-Construct a gazebo plugin + */ +PedestrianSFMPlugin::~PedestrianSFMPlugin() +{ + pose_pub_.shutdown(); +} + +/** + * @brief Load the actor plugin. + * @param _model Pointer to the parent model. + * @param _sdf Pointer to the plugin's SDF elements. + */ +void PedestrianSFMPlugin::Load(physics::ModelPtr _model, sdf::ElementPtr _sdf) +{ + // gazebo model pointer + sdf_ = _sdf; + actor_ = boost::dynamic_pointer_cast(_model); + world_ = actor_->GetWorld(); + + // Create the ROS node + if (!ros::isInitialized()) + { + int argc = 0; + char** argv = NULL; + ros::init(argc, argv, "gazebo_client", ros::init_options::NoSigintHandler); + } + node_.reset(new ros::NodeHandle("gazebo_client")); + + // topic publisher + pose_pub_ = node_->advertise("/" + actor_->GetName() + "/pose", 10); + vel_pub_ = node_->advertise("/" + actor_->GetName() + "/twist", 10); + + // server + state_server_ = node_->advertiseService(actor_->GetName() + "_state", &PedestrianSFMPlugin::OnStateCallBack, this); + + // Collision attribute configuration of pedestrian links + std::map scales; + std::map offsets; + + // Read in the collision property + if (sdf_->HasElement("collision")) + { + auto elem = sdf_->GetElement("collision"); + while (elem) + { + auto name = elem->Get(); + + if (elem->HasAttribute("scale")) + { + auto scale = elem->Get("scale"); + scales[name] = scale; + } + if (elem->HasAttribute("pose")) + { + auto pose = elem->Get("pose"); + offsets[name] = pose; + } + elem = elem->GetNextElement("collision"); + } + } + // Configure the links + for (const auto& link : actor_->GetLinks()) + { + // Init the links, which in turn enables collisions + link->Init(); + + if (scales.empty()) + continue; + + // Process all the collisions in all the links + for (const auto& collision : link->GetCollisions()) + { + auto name = collision->GetName(); + // std::cout<(collision->GetShape()); + // Make sure we have a box shape. + if (boxShape) + boxShape->SetSize(boxShape->Size() * scales[name]); + } + + if (offsets.find(name) != offsets.end()) + { + collision->SetInitialRelativePose(offsets[name] + collision->InitialRelativePose()); + } + } + } + + if (sdf_->HasElement("time_delay")) + { + time_delay_ = sdf_->GetElement("time_delay")->Get(); + // std::unique_ptr t_time_delay(new std::thread(&PedestrianSFMPlugin::timeDelay, this)); + std::unique_ptr t_time_delay(new std::thread([this]() { + if (!time_init_) + { + sleep(time_delay_); + time_init_ = true; + } + })); + + std::unique_ptr d_time_delay = std::move(t_time_delay); + d_time_delay->detach(); + } + else + time_init_ = true; + + // Bind the update callback function + connections_.push_back( + event::Events::ConnectWorldUpdateBegin(std::bind(&PedestrianSFMPlugin::OnUpdate, this, std::placeholders::_1))); + + // Initialize the social force model. + this->Reset(); +} + +/** + * @brief Initialize the social force model. + */ +void PedestrianSFMPlugin::Reset() +{ + sfm_actor_.id = actor_->GetId(); + + // Read in the goals to reach + if (sdf_->HasElement("cycle")) + sfm_actor_.cyclicGoals = sdf_->GetElement("cycle")->Get(); + + if (sdf_->HasElement("trajectory")) + { + sdf::ElementPtr model_elem = sdf_->GetElement("trajectory")->GetElement("goalpoint"); + while (model_elem) + { + ignition::math::Pose3d g = model_elem->Get(); + sfm::Goal goal; + goal.center.set(g.Pos().X(), g.Pos().Y()); + goal.radius = 0.3; + sfm_actor_.goals.push_back(goal); + model_elem = model_elem->GetNextElement("goalpoint"); + } + } + + auto skel_anims = actor_->SkeletonAnimations(); + if (skel_anims.find(WALKING_ANIMATION) == skel_anims.end()) + { + gzerr << "Skeleton animation " << WALKING_ANIMATION << " not found.\n"; + } + else + { + // Create custom trajectory + trajectory_info_.reset(new physics::TrajectoryInfo()); + trajectory_info_->type = WALKING_ANIMATION; + trajectory_info_->duration = 1.0; + actor_->SetCustomTrajectory(trajectory_info_); + } + + // Initialize sfm actor position + ignition::math::Vector3d pos = actor_->WorldPose().Pos(); + ignition::math::Vector3d rpy = actor_->WorldPose().Rot().Euler(); + + sfm_actor_.position.set(pos.X(), pos.Y()); + sfm_actor_.yaw = utils::Angle::fromRadian(rpy.Z()); + ignition::math::Vector3d linvel = actor_->WorldLinearVel(); + sfm_actor_.velocity.set(linvel.X(), linvel.Y()); + sfm_actor_.linearVelocity = linvel.Length(); + ignition::math::Vector3d angvel = actor_->WorldAngularVel(); + sfm_actor_.angularVelocity = angvel.Z(); + + ignition::math::Pose3d actor_pose = actor_->WorldPose(); + actor_pose.Rot() = ignition::math::Quaterniond(1.5707, 0, rpy.Z()); + actor_->SetWorldPose(actor_pose); + + // Read in the maximum velocity of the pedestrian + if (sdf_->HasElement("velocity")) + sfm_actor_.desiredVelocity = sdf_->Get("velocity"); + else + sfm_actor_.desiredVelocity = 0.8; + + // Read in the algorithm weights + if (sdf_->HasElement("goal_weight")) + sfm_actor_.params.forceFactorDesired = sdf_->Get("goal_weight"); + if (sdf_->HasElement("obstacle_weight")) + sfm_actor_.params.forceFactorObstacle = sdf_->Get("obstacle_weight"); + if (sdf_->HasElement("social_weight")) + sfm_actor_.params.forceFactorSocial = sdf_->Get("social_weight"); + if (sdf_->HasElement("group_gaze_weight")) + sfm_actor_.params.forceFactorGroupGaze = sdf_->Get("group_gaze_weight"); + if (sdf_->HasElement("group_coh_weight")) + sfm_actor_.params.forceFactorGroupCoherence = sdf_->Get("group_coh_weight"); + if (sdf_->HasElement("group_rep_weight")) + sfm_actor_.params.forceFactorGroupRepulsion = sdf_->Get("group_rep_weight"); + + // Read in the animation factor (applied in the OnUpdate function). + if (sdf_->HasElement("animation_factor")) + animation_factor_ = sdf_->Get("animation_factor"); + else + animation_factor_ = 4.5; + + if (sdf_->HasElement("people_distance")) + people_dist_ = sdf_->Get("people_distance"); + else + people_dist_ = 5.0; + + // Read in the pedestrians in your walking group + if (sdf_->HasElement("group")) + { + sfm_actor_.groupId = sfm_actor_.id; + sdf::ElementPtr model_elem = sdf_->GetElement("group")->GetElement("model"); + while (model_elem) + { + group_names_.push_back(model_elem->Get()); + model_elem = model_elem->GetNextElement("model"); + } + sfm_actor_.groupId = sfm_actor_.id; + } + else + sfm_actor_.groupId = -1; + + // Read in the other obstacles to ignore + if (sdf_->HasElement("ignore_obstacles")) + { + sdf::ElementPtr model_elem = sdf_->GetElement("ignore_obstacles")->GetElement("model"); + while (model_elem) + { + ignore_models_.push_back(model_elem->Get()); + model_elem = model_elem->GetNextElement("model"); + } + } + // Add our own name to models we should ignore when avoiding obstacles. + ignore_models_.push_back(actor_->GetName()); + + // Add the other pedestrians to the ignored obstacles + for (unsigned int i = 0; i < world_->ModelCount(); ++i) + { + physics::ModelPtr model = world_->ModelByIndex(i); + + if (model->GetId() != actor_->GetId() && ((int)model->GetType() == (int)actor_->GetType())) + ignore_models_.push_back(model->GetName()); + } +} + +/** + * @brief Helper function to detect the closest obstacles. + */ +void PedestrianSFMPlugin::handleObstacles() +{ + double min_dist = 10000.0; + ignition::math::Vector3d closest_obs; + sfm_actor_.obstacles1.clear(); + + for (unsigned int i = 0; i < world_->ModelCount(); ++i) + { + physics::ModelPtr model = world_->ModelByIndex(i); + if (std::find(ignore_models_.begin(), ignore_models_.end(), model->GetName()) == ignore_models_.end()) + { + // simple method, suppose BBs are AABBs + ignition::math::Vector3d actorPos = actor_->WorldPose().Pos(); + ignition::math::Vector3d modelPos = model->WorldPose().Pos(); + + // BB border + double max_x = model->BoundingBox().Max().X(); + double min_x = model->BoundingBox().Min().X(); + double max_y = model->BoundingBox().Max().Y(); + double min_y = model->BoundingBox().Min().Y(); + double max_z = model->BoundingBox().Max().Z(); + double min_z = model->BoundingBox().Min().Z(); + + ignition::math::Vector3d closest_point; + double closest_weight = 0.8; + closest_point.X() = + ignition::math::clamp(closest_weight * actorPos.X() + (1 - closest_weight) * modelPos.X(), min_x, max_x); + closest_point.Y() = + ignition::math::clamp(closest_weight * actorPos.Y() + (1 - closest_weight) * modelPos.Y(), min_y, max_y); + closest_point.Z() = + ignition::math::clamp(closest_weight * actorPos.Z() + (1 - closest_weight) * modelPos.Z(), min_z, max_z); + ignition::math::Vector3d offset = closest_point - actorPos; + double model_dist = offset.Length(); + if (model_dist < min_dist) + { + min_dist = model_dist; + closest_obs = closest_point; + } + } + } + + // ROS_WARN("model: %s, min_dist: %.2f", closest_model->GetName().c_str(), min_dist); + utils::Vector2d ob(closest_obs.X(), closest_obs.Y()); + sfm_actor_.obstacles1.push_back(ob); +} + +/** + * @brief Helper function to detect the nearby pedestrians (other actors). + */ +void PedestrianSFMPlugin::handlePedestrians() +{ + other_actors_.clear(); + + for (unsigned int i = 0; i < world_->ModelCount(); ++i) + { + physics::ModelPtr model = world_->ModelByIndex(i); + + if (model->GetId() != actor_->GetId() && ((int)model->GetType() == (int)actor_->GetType())) + { + ignition::math::Pose3d model_pose = model->WorldPose(); + ignition::math::Vector3d pos = model_pose.Pos() - actor_->WorldPose().Pos(); + if (pos.Length() < people_dist_) + { + sfm::Agent ped; + ped.id = model->GetId(); + ped.position.set(model_pose.Pos().X(), model_pose.Pos().Y()); + ignition::math::Vector3d rpy = model_pose.Rot().Euler(); + ped.yaw = utils::Angle::fromRadian(rpy.Z()); + + ped.radius = sfm_actor_.radius; + ignition::math::Vector3d linvel = model->WorldLinearVel(); + ped.velocity.set(linvel.X(), linvel.Y()); + ped.linearVelocity = linvel.Length(); + ignition::math::Vector3d angvel = model->WorldAngularVel(); + ped.angularVelocity = angvel.Z(); + + // check if the ped belongs to my group + if (sfm_actor_.groupId != -1) + { + std::vector::iterator it; + it = find(group_names_.begin(), group_names_.end(), model->GetName()); + if (it != group_names_.end()) + ped.groupId = sfm_actor_.groupId; + else + ped.groupId = -1; + } + other_actors_.push_back(ped); + } + } + } +} + +/** + * @brief Function that is called every update cycle. + * @param _info Timing information. + */ +void PedestrianSFMPlugin::OnUpdate(const common::UpdateInfo& _info) +{ + if (time_init_) + { + if (!pose_init_) + last_update_ = _info.simTime; + + // Time delta + double dt = (_info.simTime - last_update_).Double(); + + ignition::math::Pose3d actor_pose = actor_->WorldPose(); + + // update closest obstacle + this->handleObstacles(); + // update pedestrian around + this->handlePedestrians(); + + // Compute Social Forces + sfm::SFM.computeForces(sfm_actor_, other_actors_); + // Update model + sfm::SFM.updatePosition(sfm_actor_, dt); + + utils::Angle h = this->sfm_actor_.yaw; + utils::Angle add = utils::Angle::fromRadian(1.5707); + h = h + add; + double yaw = h.toRadian(); + + ignition::math::Vector3d rpy = actor_pose.Rot().Euler(); + utils::Angle current = utils::Angle::fromRadian(rpy.Z()); + double diff = (h - current).toRadian(); + if (std::fabs(diff) > IGN_DTOR(10)) + { + current = current + utils::Angle::fromRadian(diff * 0.005); + yaw = current.toRadian(); + } + + actor_pose.Pos().X(sfm_actor_.position.getX()); + actor_pose.Pos().Y(sfm_actor_.position.getY()); + actor_pose.Pos().Z(1.0); + actor_pose.Rot() = ignition::math::Quaterniond(1.5707, 0, yaw); + + // Distance traveled is used to coordinate motion with the walking + double distance_traveled = (actor_pose.Pos() - actor_->WorldPose().Pos()).Length(); + + actor_->SetWorldPose(actor_pose); + actor_->SetScriptTime(actor_->ScriptTime() + distance_traveled * animation_factor_); + + geometry_msgs::PoseStamped current_pose; + current_pose.header.frame_id = "map"; + current_pose.header.stamp = ros::Time::now(); + current_pose.pose.position.x = sfm_actor_.position.getX(); + current_pose.pose.position.y = sfm_actor_.position.getY(); + current_pose.pose.position.z = 1.0; + tf2::Quaternion q; + q.setRPY(0, 0, sfm_actor_.yaw.toRadian()); + tf2::convert(q, current_pose.pose.orientation); + + // set model velocity + geometry_msgs::Twist current_vel; + if (!pose_init_) + { + pose_init_ = true; + last_pose_x_ = current_pose.pose.position.x; + last_pose_y_ = current_pose.pose.position.y; + current_vel.linear.x = 0; + current_vel.linear.y = 0; + } + else + { + double dt = (_info.simTime - last_update_).Double(); + double vx = (current_pose.pose.position.x - last_pose_x_) / dt; + double vy = (current_pose.pose.position.y - last_pose_y_) / dt; + last_pose_x_ = current_pose.pose.position.x; + last_pose_y_ = current_pose.pose.position.y; + + current_vel.linear.x = vx; + current_vel.linear.y = vy; + } + + pose_pub_.publish(current_pose); + vel_pub_.publish(current_vel); + + // update + px_ = current_pose.pose.position.x; + py_ = current_pose.pose.position.y; + pz_ = current_pose.pose.position.z; + vx_ = current_vel.linear.x; + vy_ = current_vel.linear.y; + theta_ = yaw; + last_update_ = _info.simTime; + } +} + +bool PedestrianSFMPlugin::OnStateCallBack(gazebo_sfm_plugin::ped_state::Request& req, + gazebo_sfm_plugin::ped_state::Response& resp) +{ + if (req.name == actor_->GetName()) + { + resp.px = px_; + resp.py = py_; + resp.pz = pz_; + resp.vx = vx_; + resp.vy = vy_; + resp.theta = theta_; + return true; + } + else + return false; +} \ No newline at end of file diff --git a/simulators/third_party/gazebo_plugins/pedestrian_sfm_plugin/srv/ped_state.srv b/simulators/third_party/gazebo_plugins/pedestrian_sfm_plugin/srv/ped_state.srv new file mode 100755 index 0000000..c731fde --- /dev/null +++ b/simulators/third_party/gazebo_plugins/pedestrian_sfm_plugin/srv/ped_state.srv @@ -0,0 +1,10 @@ +# client +string name +--- +# server +float64 px +float64 py +float64 pz +float64 vx +float64 vy +float64 theta \ No newline at end of file diff --git a/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/gazebo_ped_visualizer_plugin/CMakeLists.txt b/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/gazebo_ped_visualizer_plugin/CMakeLists.txt new file mode 100755 index 0000000..864911d --- /dev/null +++ b/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/gazebo_ped_visualizer_plugin/CMakeLists.txt @@ -0,0 +1,48 @@ +cmake_minimum_required(VERSION 2.8.3) +project(gazebo_ped_visualizer_plugin) + +add_compile_options(-std=c++11) + +find_package(catkin REQUIRED COMPONENTS + gazebo_ros + roscpp + pedsim_msgs + std_msgs +) + +find_package(Boost REQUIRED COMPONENTS thread) +find_package(gazebo REQUIRED) + + +include_directories(include) +include_directories(SYSTEM + /usr/local/include #to find lightsfm + ${Boost_INCLUDE_DIRS} + ${catkin_INCLUDE_DIRS} + ${GAZEBO_INCLUDE_DIRS} +) + +link_directories( + ${catkin_LIBRARY_DIRS} + ${GAZEBO_LIBRARY_DIRS} +) + + +catkin_package( + INCLUDE_DIRS include + LIBRARIES PedestrianVisualPlugin + CATKIN_DEPENDS gazebo_ros roscpp +) + +add_library(PedestrianVisualPlugin src/pedestrian_visual_plugin.cpp) +add_dependencies(PedestrianVisualPlugin ${catkin_EXPORTED_TARGETS}) +target_link_libraries(PedestrianVisualPlugin ${catkin_LIBRARIES} ${GAZEBO_LIBRARIES}) #${Boost_LIBRARIES + +install(TARGETS + PedestrianVisualPlugin + DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +) + + + diff --git a/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/gazebo_ped_visualizer_plugin/include/pedestrian_visual_plugin.h b/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/gazebo_ped_visualizer_plugin/include/pedestrian_visual_plugin.h new file mode 100755 index 0000000..d04f31a --- /dev/null +++ b/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/gazebo_ped_visualizer_plugin/include/pedestrian_visual_plugin.h @@ -0,0 +1,93 @@ +/*********************************************************** + * + * @file: pedestrian_sfm_plugin.cpp + * @breif: Gazebo plugin for pedestrians using social force model + * @author: Yang Haodong + * @update: 2023-03-15 + * @version: 1.1 + * + * Copyright (c) 2023, Yang Haodong + * All rights reserved. + * -------------------------------------------------------- + * + **********************************************************/ +#ifndef PEDESTRIANVISUAL_GAZEBO_PLUGIN_H +#define PEDESTRIANVISUAL_GAZEBO_PLUGIN_H + +// C++ +#include +#include +#include +#include +#include +#include +#include + +// Gazebo +#include +#include +#include +#include +#include + +// message +#include +#include +#include +#include +#include + +namespace gazebo +{ +class GZ_PLUGIN_VISIBLE PedestrianVisualPlugin : public ModelPlugin +{ +public: + /** + * @brief Construct a gazebo plugin + */ + PedestrianVisualPlugin(); + + /** + * @brief De-Construct a gazebo plugin + */ + ~PedestrianVisualPlugin(); + + /** + * @brief Load the actor plugin. + * @param _model Pointer to the parent model. + * @param _sdf Pointer to the plugin's SDF elements. + */ + virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf); + + /** + * @brief Publish pedestrians visualization information + */ + void publishPedVisuals(); + +private: + /** + * @brief Function that is called every update cycle. + * @param _info Timing information. + */ + void OnUpdate(const common::UpdateInfo& _info); + +private: + // Gazebo ROS node + std::unique_ptr node_; + // topic publisher + ros::Publisher ped_visual_pub_; + // Pointer to the parent actor. + physics::ActorPtr actor_; + // Pointer to the world, for convenience. + physics::WorldPtr world_; + // Pointer to the sdf element. + sdf::ElementPtr sdf_; + // List of connections + std::vector connections_; + // Update interval + size_t update_interval_; + // Update counter + size_t update_cnt_; +}; +} // namespace gazebo +#endif diff --git a/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/gazebo_ped_visualizer_plugin/package.xml b/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/gazebo_ped_visualizer_plugin/package.xml new file mode 100755 index 0000000..61c5b29 --- /dev/null +++ b/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/gazebo_ped_visualizer_plugin/package.xml @@ -0,0 +1,37 @@ + + + gazebo_ped_visualizer_plugin + 0.1.0 + The pedsim_visualizer package + + Billy Okal + + BSD + + catkin + + geometry_msgs + pedsim_msgs + roscpp + std_msgs + visualization_msgs + gazebo_ros + + + geometry_msgs + pedsim_msgs + roscpp + std_msgs + visualization_msgs + gazebo_ros + + + geometry_msgs + pedsim_msgs + roscpp + std_msgs + visualization_msgs + gazebo_ros + + + \ No newline at end of file diff --git a/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/gazebo_ped_visualizer_plugin/src/pedestrian_visual_plugin.cpp b/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/gazebo_ped_visualizer_plugin/src/pedestrian_visual_plugin.cpp new file mode 100755 index 0000000..7996a46 --- /dev/null +++ b/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/gazebo_ped_visualizer_plugin/src/pedestrian_visual_plugin.cpp @@ -0,0 +1,136 @@ +/*********************************************************** + * + * @file: pedestrian_sfm_plugin.cpp + * @breif: Gazebo plugin for pedestrians using social force model + * @author: Yang Haodong + * @update: 2023-03-15 + * @version: 1.1 + * + * Copyright (c) 2023, Yang Haodong + * All rights reserved. + * -------------------------------------------------------- + * + **********************************************************/ +#include +#include +#include + +#include + +using namespace gazebo; +GZ_REGISTER_MODEL_PLUGIN(PedestrianVisualPlugin) + +/** + * @brief Construct a gazebo plugin + */ +PedestrianVisualPlugin::PedestrianVisualPlugin() +{ +} + +/** + * @brief De-Construct a gazebo plugin + */ +PedestrianVisualPlugin::~PedestrianVisualPlugin() +{ + ped_visual_pub_.shutdown(); +} + +/** + * @brief Load the actor plugin. + * @param _model Pointer to the parent model. + * @param _sdf Pointer to the plugin's SDF elements. + */ +void PedestrianVisualPlugin::Load(physics::ModelPtr _model, sdf::ElementPtr _sdf) +{ + // gazebo model pointer + sdf_ = _sdf; + actor_ = boost::dynamic_pointer_cast(_model); + world_ = actor_->GetWorld(); + + // Create the ROS node + if (!ros::isInitialized()) + { + int argc = 0; + char** argv = NULL; + ros::init(argc, argv, "gazebo_client", ros::init_options::NoSigintHandler); + } + node_.reset(new ros::NodeHandle("gazebo_client")); + + // topic publisher + ped_visual_pub_ = node_->advertise("/ped_visualization", 1); + + // Bind the update callback function + connections_.push_back(event::Events::ConnectWorldUpdateBegin( + std::bind(&PedestrianVisualPlugin::OnUpdate, this, std::placeholders::_1))); + + // Update rate setting + if (sdf_->HasElement("update_rate")) + { + auto update_rate = sdf_->Get("update_rate"); + update_interval_ = std::max(size_t(1), size_t(100 / update_rate)); + } + else + update_interval_ = 10; + + update_cnt_ = 0; +} + +/** + * @brief Publish pedestrians visualization information + */ +void PedestrianVisualPlugin::publishPedVisuals() +{ + int human_id = 0; + + pedsim_msgs::TrackedPersons tracked_people; + std_msgs::Header msg_header; + msg_header.stamp = ros::Time::now(); + msg_header.frame_id = "map"; + tracked_people.header = msg_header; + + for (unsigned int i = 0; i < world_->ModelCount(); ++i) + { + physics::ModelPtr model = world_->ModelByIndex(i); + if (((int)model->GetType() == (int)actor_->GetType())) + { + human_id++; + pedsim_msgs::TrackedPerson person; + person.track_id = human_id; + person.is_occluded = false; + person.detection_id = human_id; + + ros::ServiceClient state_client = node_->serviceClient(model->GetName() + "_state"); + gazebo_sfm_plugin::ped_state model_state; + model_state.request.name = model->GetName(); + state_client.call(model_state); + + geometry_msgs::PoseWithCovariance pose_with_cov; + pose_with_cov.pose.position.x = model_state.response.px; + pose_with_cov.pose.position.y = model_state.response.py; + pose_with_cov.pose.position.z = model_state.response.pz; + tf2::Quaternion q; + q.setRPY(0, 0, model_state.response.theta - 1.57); + tf2::convert(q, pose_with_cov.pose.orientation); + person.pose = pose_with_cov; + + geometry_msgs::TwistWithCovariance twist_with_cov; + twist_with_cov.twist.linear.x = model_state.response.vx; + twist_with_cov.twist.linear.y = model_state.response.vy; + person.twist = twist_with_cov; + + tracked_people.tracks.push_back(person); + } + } + ped_visual_pub_.publish(tracked_people); +} + +/** + * @brief Function that is called every update cycle. + * @param _info Timing information. + */ +void PedestrianVisualPlugin::OnUpdate(const common::UpdateInfo& _info) +{ + update_cnt_ = update_cnt_ % update_interval_ + 1; + if (update_cnt_ == 1) + publishPedVisuals(); +} diff --git a/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/pedsim_msgs/CMakeLists.txt b/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/pedsim_msgs/CMakeLists.txt new file mode 100755 index 0000000..8f1e62e --- /dev/null +++ b/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/pedsim_msgs/CMakeLists.txt @@ -0,0 +1,45 @@ +cmake_minimum_required(VERSION 2.8.3) +project(pedsim_msgs) + +# message and service dependencies +set(MESSAGE_DEPENDENCIES + std_msgs + geometry_msgs + sensor_msgs + nav_msgs +) + +find_package(catkin REQUIRED COMPONENTS message_generation ${MESSAGE_DEPENDENCIES}) + +include_directories(${catkin_INCLUDE_DIRS}) + +## Generate messages in the 'msg' folder +add_message_files( DIRECTORY msg + FILES + AgentState.msg + AgentStates.msg + AgentGroup.msg + AgentGroups.msg + AgentForce.msg + LineObstacle.msg + LineObstacles.msg + TrackedPerson.msg + TrackedPersons.msg + TrackedGroup.msg + TrackedGroups.msg + SocialRelation.msg + SocialRelations.msg + SocialActivity.msg + SocialActivities.msg + Waypoint.msg + Waypoints.msg +) + +# generate the messages +generate_messages(DEPENDENCIES ${MESSAGE_DEPENDENCIES}) + + +#Declare package run-time dependencies +catkin_package( + CATKIN_DEPENDS roscpp rospy message_runtime ${MESSAGE_DEPENDENCIES} +) diff --git a/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/pedsim_msgs/msg/AgentForce.msg b/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/pedsim_msgs/msg/AgentForce.msg new file mode 100755 index 0000000..b9218e2 --- /dev/null +++ b/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/pedsim_msgs/msg/AgentForce.msg @@ -0,0 +1,14 @@ +# Forces acting on an agent. + +# Basic SFM forces. +geometry_msgs/Vector3 desired_force +geometry_msgs/Vector3 obstacle_force +geometry_msgs/Vector3 social_force + +# Additional Group Forces +geometry_msgs/Vector3 group_coherence_force +geometry_msgs/Vector3 group_gaze_force +geometry_msgs/Vector3 group_repulsion_force + +# Extra stabilization/custom forces. +geometry_msgs/Vector3 random_force diff --git a/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/pedsim_msgs/msg/AgentGroup.msg b/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/pedsim_msgs/msg/AgentGroup.msg new file mode 100755 index 0000000..37ed096 --- /dev/null +++ b/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/pedsim_msgs/msg/AgentGroup.msg @@ -0,0 +1,5 @@ +Header header +uint16 group_id +float64 age +uint64[] members +geometry_msgs/Pose center_of_mass diff --git a/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/pedsim_msgs/msg/AgentGroups.msg b/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/pedsim_msgs/msg/AgentGroups.msg new file mode 100755 index 0000000..de1d3ac --- /dev/null +++ b/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/pedsim_msgs/msg/AgentGroups.msg @@ -0,0 +1,2 @@ +Header header +pedsim_msgs/AgentGroup[] groups diff --git a/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/pedsim_msgs/msg/AgentState.msg b/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/pedsim_msgs/msg/AgentState.msg new file mode 100755 index 0000000..6eee4d8 --- /dev/null +++ b/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/pedsim_msgs/msg/AgentState.msg @@ -0,0 +1,21 @@ +Header header +uint64 id +uint16 type +string social_state +geometry_msgs/Pose pose +geometry_msgs/Twist twist +pedsim_msgs/AgentForce forces + +# Use sensors package to control observability + +# Social State string constants +string TYPE_STANDING = "standing" +string TYPE_INDIVIDUAL_MOVING = "individual_moving" +string TYPE_WAITING_IN_QUEUE = "waiting_in_queue" +string TYPE_GROUP_MOVING = "group_moving" + + +# Agent types +# 0, 1 -> ordinary agents +# 2 -> Robot +# 3 -> standing/elderly agents diff --git a/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/pedsim_msgs/msg/AgentStates.msg b/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/pedsim_msgs/msg/AgentStates.msg new file mode 100755 index 0000000..01b118d --- /dev/null +++ b/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/pedsim_msgs/msg/AgentStates.msg @@ -0,0 +1,2 @@ +Header header +pedsim_msgs/AgentState[] agent_states diff --git a/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/pedsim_msgs/msg/AllAgentsState.msg b/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/pedsim_msgs/msg/AllAgentsState.msg new file mode 100755 index 0000000..6c95a56 --- /dev/null +++ b/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/pedsim_msgs/msg/AllAgentsState.msg @@ -0,0 +1,2 @@ +Header header +pedsim_msgs/AgentState[] agent_states \ No newline at end of file diff --git a/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/pedsim_msgs/msg/LineObstacle.msg b/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/pedsim_msgs/msg/LineObstacle.msg new file mode 100755 index 0000000..587a251 --- /dev/null +++ b/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/pedsim_msgs/msg/LineObstacle.msg @@ -0,0 +1,4 @@ +# A line obstacle in the simulator. + +geometry_msgs/Point start +geometry_msgs/Point end diff --git a/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/pedsim_msgs/msg/LineObstacles.msg b/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/pedsim_msgs/msg/LineObstacles.msg new file mode 100755 index 0000000..7d4526e --- /dev/null +++ b/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/pedsim_msgs/msg/LineObstacles.msg @@ -0,0 +1,4 @@ +# A collection of line obstacles. +# No need to header since these are detemined at sim initiation time. +Header header +pedsim_msgs/LineObstacle[] obstacles diff --git a/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/pedsim_msgs/msg/SocialActivities.msg b/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/pedsim_msgs/msg/SocialActivities.msg new file mode 100755 index 0000000..b0b55a4 --- /dev/null +++ b/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/pedsim_msgs/msg/SocialActivities.msg @@ -0,0 +1,5 @@ +std_msgs/Header header + +# All social activities that have been detected in the current time step, +# within sensor range of the robot. +SocialActivity[] elements \ No newline at end of file diff --git a/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/pedsim_msgs/msg/SocialActivity.msg b/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/pedsim_msgs/msg/SocialActivity.msg new file mode 100755 index 0000000..58e9c29 --- /dev/null +++ b/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/pedsim_msgs/msg/SocialActivity.msg @@ -0,0 +1,22 @@ +string type # see constants below +float32 confidence # detection confidence + +uint64[] track_ids # IDs of all person tracks involved in the activity, might be one or multiple + + +# Constants for social activity type (just examples at the moment) +string TYPE_SHOPPING = shopping +string TYPE_STANDING = standing +string TYPE_INDIVIDUAL_MOVING = individual_moving +string TYPE_WAITING_IN_QUEUE = waiting_in_queue +string TYPE_LOOKING_AT_INFORMATION_SCREEN = looking_at_information_screen +string TYPE_LOOKING_AT_KIOSK = looking_at_kiosk +string TYPE_GROUP_ASSEMBLING = group_assembling +string TYPE_GROUP_MOVING = group_moving +string TYPE_FLOW_WITH_ROBOT = flow +string TYPE_ANTIFLOW_AGAINST_ROBOT = antiflow +string TYPE_WAITING_FOR_OTHERS = waiting_for_others + +#string TYPE_COMMUNICATING = communicating +#string TYPE_TAKING_PHOTOGRAPH = taking_photograph +#string TYPE_TALKING_ON_PHONE = talking_on_phone diff --git a/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/pedsim_msgs/msg/SocialRelation.msg b/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/pedsim_msgs/msg/SocialRelation.msg new file mode 100755 index 0000000..2159dc9 --- /dev/null +++ b/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/pedsim_msgs/msg/SocialRelation.msg @@ -0,0 +1,12 @@ +string type # e.g. mother-son relationship, romantic relationship, etc. +float32 strength # relationship strength between 0.0 and 1.0 + +uint32 track1_id +uint32 track2_id + + +# Constants for type (just examples at the moment) +string TYPE_SPATIAL = "spatial" +string TYPE_ROMANTIC = "romantic" +string TYPE_PARENT_CHILD = "parent_child" +string TYPE_FRIENDSHIP = "friendship" \ No newline at end of file diff --git a/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/pedsim_msgs/msg/SocialRelations.msg b/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/pedsim_msgs/msg/SocialRelations.msg new file mode 100755 index 0000000..f30cd8d --- /dev/null +++ b/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/pedsim_msgs/msg/SocialRelations.msg @@ -0,0 +1,5 @@ +std_msgs/Header header + +# All social relations of all tracks in the current time step. +# There might be multiple social relations per pair of tracks. +SocialRelation[] elements \ No newline at end of file diff --git a/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/pedsim_msgs/msg/TrackedGroup.msg b/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/pedsim_msgs/msg/TrackedGroup.msg new file mode 100755 index 0000000..29cd536 --- /dev/null +++ b/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/pedsim_msgs/msg/TrackedGroup.msg @@ -0,0 +1,10 @@ +# Message defining a tracked group +# + +uint64 group_id # unique identifier of the target, consistent over time + +duration age # age of the group + +geometry_msgs/PoseWithCovariance centerOfGravity # mean and covariance of the group (calculated from its person tracks) + +uint64[] track_ids # IDs of the tracked persons in this group. See srl_tracking_msgs/TrackedPersons \ No newline at end of file diff --git a/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/pedsim_msgs/msg/TrackedGroups.msg b/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/pedsim_msgs/msg/TrackedGroups.msg new file mode 100755 index 0000000..b22c517 --- /dev/null +++ b/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/pedsim_msgs/msg/TrackedGroups.msg @@ -0,0 +1,5 @@ +# Message with all currently tracked groups +# + +Header header # Header containing timestamp etc. of this message +pedsim_msgs/TrackedGroup[] groups # All groups that are currently being tracked diff --git a/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/pedsim_msgs/msg/TrackedPerson.msg b/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/pedsim_msgs/msg/TrackedPerson.msg new file mode 100755 index 0000000..996c6c3 --- /dev/null +++ b/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/pedsim_msgs/msg/TrackedPerson.msg @@ -0,0 +1,14 @@ +# Message defining a tracked person +# + +uint64 track_id # unique identifier of the target, consistent over time +bool is_occluded # if the track is currently not observable in a physical way +bool is_matched # if the track is currently matched by a detection +uint64 detection_id # id of the corresponding detection in the current cycle (undefined if occluded) +duration age # age of the track + +# The following fields are extracted from the Kalman state x and its covariance C + +geometry_msgs/PoseWithCovariance pose # pose of the track (z value and orientation might not be set, check if corresponding variance on diagonal is > 99999) + +geometry_msgs/TwistWithCovariance twist # velocity of the track (z value and rotational velocities might not be set, check if corresponding variance on diagonal is > 99999) diff --git a/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/pedsim_msgs/msg/TrackedPersons.msg b/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/pedsim_msgs/msg/TrackedPersons.msg new file mode 100755 index 0000000..5c5a361 --- /dev/null +++ b/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/pedsim_msgs/msg/TrackedPersons.msg @@ -0,0 +1,5 @@ +# Message with all currently tracked persons +# + +Header header # Header containing timestamp etc. of this message +TrackedPerson[] tracks # All persons that are currently being tracked \ No newline at end of file diff --git a/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/pedsim_msgs/msg/Waypoint.msg b/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/pedsim_msgs/msg/Waypoint.msg new file mode 100755 index 0000000..e85e4fc --- /dev/null +++ b/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/pedsim_msgs/msg/Waypoint.msg @@ -0,0 +1,8 @@ +int8 BHV_SIMPLE = 0 +int8 BHV_SOURCE = 1 +int8 BHV_SINK = 2 + +string name +int8 behavior +geometry_msgs/Point position +float32 radius diff --git a/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/pedsim_msgs/msg/Waypoints.msg b/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/pedsim_msgs/msg/Waypoints.msg new file mode 100755 index 0000000..e0acc3c --- /dev/null +++ b/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/pedsim_msgs/msg/Waypoints.msg @@ -0,0 +1,2 @@ +Header header +pedsim_msgs/Waypoint[] waypoints diff --git a/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/pedsim_msgs/package.xml b/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/pedsim_msgs/package.xml new file mode 100755 index 0000000..02d148d --- /dev/null +++ b/simulators/third_party/gazebo_plugins/pedestrian_visualizer_plugin/pedsim_msgs/package.xml @@ -0,0 +1,29 @@ + + + pedsim_msgs + 0.0.2 + The pedsim_msgs package: contains messages for pedsim + + Billy Okal + + BSD + + catkin + + geometry_msgs + roscpp + rospy + std_msgs + sensor_msgs + nav_msgs + message_generation + + message_runtime + geometry_msgs + roscpp + rospy + std_msgs + sensor_msgs + nav_msgs + + diff --git a/simulators/third_party/map_plugins/voronoi_layer/CMakeLists.txt b/simulators/third_party/map_plugins/voronoi_layer/CMakeLists.txt new file mode 100755 index 0000000..03b0872 --- /dev/null +++ b/simulators/third_party/map_plugins/voronoi_layer/CMakeLists.txt @@ -0,0 +1,33 @@ +cmake_minimum_required(VERSION 3.0.2) +project(voronoi_layer) + +## Compile as C++11, supported in ROS Kinetic and newer +add_compile_options(-std=c++14) + +set(CMAKE_BUILD_TYPE Release) +set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -Werror") + +## Find catkin macros and libraries +## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) +## is used, also find other catkin packages +find_package(catkin REQUIRED COMPONENTS + costmap_2d + dynamic_reconfigure + nav_msgs + roscpp +) + +catkin_package( + INCLUDE_DIRS include + LIBRARIES voronoi_layer + CATKIN_DEPENDS costmap_2d dynamic_reconfigure nav_msgs roscpp +# DEPENDS system_lib +) + +include_directories( + include + ${catkin_INCLUDE_DIRS} +) + +add_library(voronoi_layer src/dynamicvoronoi.cpp src/voronoi_layer.cpp) +target_link_libraries(voronoi_layer ${catkin_LIBRARIES}) diff --git a/simulators/third_party/map_plugins/voronoi_layer/costmap_plugins.xml b/simulators/third_party/map_plugins/voronoi_layer/costmap_plugins.xml new file mode 100755 index 0000000..1e0389f --- /dev/null +++ b/simulators/third_party/map_plugins/voronoi_layer/costmap_plugins.xml @@ -0,0 +1,7 @@ + + + + A costmap plugin for dynamic Voronoi. + + + diff --git a/simulators/third_party/map_plugins/voronoi_layer/include/bucketedqueue.h b/simulators/third_party/map_plugins/voronoi_layer/include/bucketedqueue.h new file mode 100755 index 0000000..a0769a2 --- /dev/null +++ b/simulators/third_party/map_plugins/voronoi_layer/include/bucketedqueue.h @@ -0,0 +1,60 @@ +#ifndef _PRIORITYQUEUE2_H_ +#define _PRIORITYQUEUE2_H_ + +#include +#include +#include +#include +#include "point.h" +#include + +//! Priority queue for integer coordinates with squared distances as priority. +/** A priority queue that uses buckets to group elements with the same priority. + * The individual buckets are unsorted, which increases efficiency if these groups are large. + * The elements are assumed to be integer coordinates, and the priorities are assumed + * to be squared Euclidean distances (integers). + */ + +template +class BucketPrioQueue { + +public: + //! Standard constructor + /** Standard constructor. When called for the first time it creates a look up table + * that maps square distances to bucket numbers, which might take some time... + */ + BucketPrioQueue(); + + + void clear() { + buckets.clear(); + count = 0; + nextPop = buckets.end(); + } + + //! Checks whether the Queue is empty + bool empty(); + //! push an element + void push(int prio, T t); + //! return and pop the element with the lowest squared distance */ + T pop(); + + int size() { return count; } + int getNumBuckets() { return buckets.size(); } + + int getTopPriority(){ + return nextPop->first; + } + +private: + + int count; + + typedef std::map< int, std::queue > BucketType; + BucketType buckets; + typename BucketType::iterator nextPop; +}; + +#include "bucketedqueue.hxx" + +#endif diff --git a/simulators/third_party/map_plugins/voronoi_layer/include/bucketedqueue.hxx b/simulators/third_party/map_plugins/voronoi_layer/include/bucketedqueue.hxx new file mode 100755 index 0000000..b93d8e4 --- /dev/null +++ b/simulators/third_party/map_plugins/voronoi_layer/include/bucketedqueue.hxx @@ -0,0 +1,38 @@ +#include "bucketedqueue.h" + +#include "limits.h" +#include +#include + +template +BucketPrioQueue::BucketPrioQueue() { + clear(); +} + +template +bool BucketPrioQueue::empty() { + return (count==0); +} + + +template +void BucketPrioQueue::push(int prio, T t) { + buckets[prio].push(t); + if (nextPop == buckets.end() || prio < nextPop->first) nextPop = buckets.find(prio); + count++; +} + +template +T BucketPrioQueue::pop() { + while (nextPop!=buckets.end() && nextPop->second.empty()) ++nextPop; + + T p = nextPop->second.front(); + nextPop->second.pop(); + if (nextPop->second.empty()) { + typename BucketType::iterator it = nextPop; + nextPop++; + buckets.erase(it); + } + count--; + return p; +} diff --git a/simulators/third_party/map_plugins/voronoi_layer/include/dynamicvoronoi.h b/simulators/third_party/map_plugins/voronoi_layer/include/dynamicvoronoi.h new file mode 100755 index 0000000..a2b483a --- /dev/null +++ b/simulators/third_party/map_plugins/voronoi_layer/include/dynamicvoronoi.h @@ -0,0 +1,120 @@ +#ifndef _DYNAMICVORONOI_H_ +#define _DYNAMICVORONOI_H_ + + +#include +#include +#include +#include + +#include "bucketedqueue.h" + +//! A DynamicVoronoi object computes and updates a distance map and Voronoi diagram. +class DynamicVoronoi { + +public: + + DynamicVoronoi(); + ~DynamicVoronoi(); + + //! Initialization with an empty map + void initializeEmpty(int _sizeX, int _sizeY, bool initGridMap=true); + //! Initialization with a given binary map (false==free, true==occupied) + void initializeMap(int _sizeX, int _sizeY, bool** _gridMap); + + //! add an obstacle at the specified cell coordinate + void occupyCell(int x, int y); + //! remove an obstacle at the specified cell coordinate + void clearCell(int x, int y); + //! remove old dynamic obstacles and add the new ones + void exchangeObstacles(std::vector& newObstacles); + + //! update distance map and Voronoi diagram to reflect the changes + void update(bool updateRealDist=true); + //! prune the Voronoi diagram + void prune(); + //! prune the Voronoi diagram by globally revisiting all Voronoi nodes. Takes more time but gives a more sparsely pruned Voronoi graph. You need to call this after every call to udpate() + void updateAlternativePrunedDiagram(); + //! retrieve the alternatively pruned diagram. see updateAlternativePrunedDiagram() + int** alternativePrunedDiagram() const { + return alternativeDiagram; + }; + //! retrieve the number of neighbors that are Voronoi nodes (4-connected) + int getNumVoronoiNeighborsAlternative(int x, int y) const; + //! returns whether the specified cell is part of the alternatively pruned diagram. See updateAlternativePrunedDiagram. + bool isVoronoiAlternative( int x, int y ) const; + + //! returns the obstacle distance at the specified location + float getDistance( int x, int y ) const; + //! returns whether the specified cell is part of the (pruned) Voronoi graph + bool isVoronoi( int x, int y ) const; + //! checks whether the specficied location is occupied + bool isOccupied(int x, int y) const; + //! write the current distance map and voronoi diagram as ppm file + void visualize(const char* filename="result.ppm"); + + //! returns the horizontal size of the workspace/map + unsigned int getSizeX() const {return sizeX;} + //! returns the vertical size of the workspace/map + unsigned int getSizeY() const {return sizeY;} + +private: + struct dataCell { + float dist; + char voronoi; + char queueing; + int obstX; + int obstY; + bool needsRaise; + int sqdist; + }; + + typedef enum {voronoiKeep=-4, freeQueued = -3, voronoiRetry=-2, voronoiPrune=-1, free=0, occupied=1} State; + typedef enum {fwNotQueued=1, fwQueued=2, fwProcessed=3, bwQueued=4, bwProcessed=1} QueueingState; + typedef enum {invalidObstData = SHRT_MAX/2} ObstDataState; + typedef enum {pruned, keep, retry} markerMatchResult; + + + + // methods + void setObstacle(int x, int y); + void removeObstacle(int x, int y); + inline void checkVoro(int x, int y, int nx, int ny, dataCell& c, dataCell& nc); + void recheckVoro(); + void commitAndColorize(bool updateRealDist=true); + inline void reviveVoroNeighbors(int &x, int &y); + + inline bool isOccupied(int &x, int &y, dataCell &c); + inline markerMatchResult markerMatch(int x, int y); + inline bool markerMatchAlternative(int x, int y); + inline int getVoronoiPruneValence(int x, int y); + + // queues + + BucketPrioQueue open; + std::queue pruneQueue; + BucketPrioQueue sortedPruneQueue; + + std::vector removeList; + std::vector addList; + std::vector lastObstacles; + + // maps + int sizeY; + int sizeX; + dataCell** data; + bool** gridMap; + bool allocatedGridMap; + + // parameters + int padding; + double doubleThreshold; + + double sqrt2; + + // dataCell** getData(){ return data; } + int** alternativeDiagram; +}; + + +#endif diff --git a/simulators/third_party/map_plugins/voronoi_layer/include/point.h b/simulators/third_party/map_plugins/voronoi_layer/include/point.h new file mode 100755 index 0000000..4899eac --- /dev/null +++ b/simulators/third_party/map_plugins/voronoi_layer/include/point.h @@ -0,0 +1,14 @@ +#ifndef _VOROPOINT_H_ +#define _VOROPOINT_H_ + +#define INTPOINT IntPoint + +/*! A light-weight integer point with fields x,y */ +class IntPoint { +public: + IntPoint() : x(0), y(0) {} + IntPoint(int _x, int _y) : x(_x), y(_y) {} + int x,y; +}; + +#endif diff --git a/simulators/third_party/map_plugins/voronoi_layer/include/voronoi_layer.h b/simulators/third_party/map_plugins/voronoi_layer/include/voronoi_layer.h new file mode 100755 index 0000000..8a1cec7 --- /dev/null +++ b/simulators/third_party/map_plugins/voronoi_layer/include/voronoi_layer.h @@ -0,0 +1,76 @@ +/****************************************************************************** + * Copyright (c) 2023, NKU Mobile & Flying Robotics Lab + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 'AS IS' + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *****************************************************************************/ + +#pragma once + +#include + +#include + +#include "costmap_2d/GenericPluginConfig.h" +#include "costmap_2d/cost_values.h" +#include "costmap_2d/layer.h" +#include "costmap_2d/layered_costmap.h" +#include "dynamic_reconfigure/server.h" +#include "dynamicvoronoi.h" +#include "nav_msgs/OccupancyGrid.h" +#include "ros/ros.h" + +namespace costmap_2d +{ +class VoronoiLayer : public Layer +{ +public: + VoronoiLayer() = default; + virtual ~VoronoiLayer() = default; + + void onInitialize() override; + void updateBounds(double robot_x, double robot_y, double robot_yaw, double* min_x, double* min_y, double* max_x, + double* max_y) override; + void updateCosts(costmap_2d::Costmap2D& master_grid, int min_i, int min_j, int max_i, int max_j) override; + const DynamicVoronoi& getVoronoi() const; + boost::mutex& getMutex(); + +private: + void publishVoronoiGrid(const costmap_2d::Costmap2D& master_grid); + void outlineMap(unsigned char* costarr, int nx, int ny, unsigned char value); + + void reconfigureCB(const costmap_2d::GenericPluginConfig& config, uint32_t level); + std::unique_ptr> dsrv_ = nullptr; + ros::Publisher voronoi_grid_pub_; + + DynamicVoronoi voronoi_; + unsigned int last_size_x_ = 0; + unsigned int last_size_y_ = 0; + boost::mutex mutex_; +}; + +} // namespace costmap_2d diff --git a/simulators/third_party/map_plugins/voronoi_layer/package.xml b/simulators/third_party/map_plugins/voronoi_layer/package.xml new file mode 100755 index 0000000..52f87b5 --- /dev/null +++ b/simulators/third_party/map_plugins/voronoi_layer/package.xml @@ -0,0 +1,69 @@ + + + voronoi_layer + 0.0.0 + The voronoi_layer package + + + + + jwen + + + + + + TODO + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + catkin + costmap_2d + dynamic_reconfigure + nav_msgs + roscpp + costmap_2d + dynamic_reconfigure + nav_msgs + roscpp + costmap_2d + dynamic_reconfigure + nav_msgs + roscpp + + + + + + diff --git a/simulators/third_party/map_plugins/voronoi_layer/src/dynamicvoronoi.cpp b/simulators/third_party/map_plugins/voronoi_layer/src/dynamicvoronoi.cpp new file mode 100755 index 0000000..c868229 --- /dev/null +++ b/simulators/third_party/map_plugins/voronoi_layer/src/dynamicvoronoi.cpp @@ -0,0 +1,720 @@ +#include "dynamicvoronoi.h" + +#include +#include + +DynamicVoronoi::DynamicVoronoi() { + sqrt2 = sqrt(2.0); + data = NULL; + gridMap = NULL; + alternativeDiagram = NULL; + allocatedGridMap = false; +} + +DynamicVoronoi::~DynamicVoronoi() { + if (data) { + for (int x=0; x=sizeX-1) continue; + for (int dy=-1; dy<=1; dy++) { + if (dx==0 && dy==0) continue; + int ny = y+dy; + if (ny<=0 || ny>=sizeY-1) continue; + + if (!gridMap[nx][ny]) { + isSurrounded = false; + break; + } + } + } + if (isSurrounded) { + c.obstX = x; + c.obstY = y; + c.sqdist = 0; + c.dist=0; + c.voronoi=occupied; + c.queueing = fwProcessed; + data[x][y] = c; + } else setObstacle(x,y); + } + } + } + } +} + +void DynamicVoronoi::occupyCell(int x, int y) { + gridMap[x][y] = 1; + setObstacle(x,y); +} +void DynamicVoronoi::clearCell(int x, int y) { + gridMap[x][y] = 0; + removeObstacle(x,y); +} + +void DynamicVoronoi::setObstacle(int x, int y) { + dataCell c = data[x][y]; + if(isOccupied(x,y,c)) return; + + addList.push_back(INTPOINT(x,y)); + c.obstX = x; + c.obstY = y; + data[x][y] = c; +} + +void DynamicVoronoi::removeObstacle(int x, int y) { + dataCell c = data[x][y]; + if(isOccupied(x,y,c) == false) return; + + removeList.push_back(INTPOINT(x,y)); + c.obstX = invalidObstData; + c.obstY = invalidObstData; + c.queueing = bwQueued; + data[x][y] = c; +} + +void DynamicVoronoi::exchangeObstacles(std::vector& points) { + + for (unsigned int i=0; i=sizeX-1) continue; + for (int dy=-1; dy<=1; dy++) { + if (dx==0 && dy==0) continue; + int ny = y+dy; + if (ny<=0 || ny>=sizeY-1) continue; + dataCell nc = data[nx][ny]; + if (nc.obstX!=invalidObstData && !nc.needsRaise) { + if(!isOccupied(nc.obstX,nc.obstY,data[nc.obstX][nc.obstY])) { + open.push(nc.sqdist, INTPOINT(nx,ny)); + nc.queueing = fwQueued; + nc.needsRaise = true; + nc.obstX = invalidObstData; + nc.obstY = invalidObstData; + if (updateRealDist) nc.dist = INFINITY; + nc.sqdist = INT_MAX; + data[nx][ny] = nc; + } else { + if(nc.queueing != fwQueued){ + open.push(nc.sqdist, INTPOINT(nx,ny)); + nc.queueing = fwQueued; + data[nx][ny] = nc; + } + } + } + } + } + c.needsRaise = false; + c.queueing = bwProcessed; + data[x][y] = c; + } + else if (c.obstX != invalidObstData && isOccupied(c.obstX,c.obstY,data[c.obstX][c.obstY])) { + + // LOWER + c.queueing = fwProcessed; + c.voronoi = occupied; + + for (int dx=-1; dx<=1; dx++) { + int nx = x+dx; + if (nx<=0 || nx>=sizeX-1) continue; + for (int dy=-1; dy<=1; dy++) { + if (dx==0 && dy==0) continue; + int ny = y+dy; + if (ny<=0 || ny>=sizeY-1) continue; + dataCell nc = data[nx][ny]; + if(!nc.needsRaise) { + int distx = nx-c.obstX; + int disty = ny-c.obstY; + int newSqDistance = distx*distx + disty*disty; + bool overwrite = (newSqDistance < nc.sqdist); + if(!overwrite && newSqDistance==nc.sqdist) { + if (nc.obstX == invalidObstData || isOccupied(nc.obstX,nc.obstY,data[nc.obstX][nc.obstY])==false) overwrite = true; + } + if (overwrite) { + open.push(newSqDistance, INTPOINT(nx,ny)); + nc.queueing = fwQueued; + if (updateRealDist) { + nc.dist = sqrt((double) newSqDistance); + } + nc.sqdist = newSqDistance; + nc.obstX = c.obstX; + nc.obstY = c.obstY; + } else { + checkVoro(x,y,nx,ny,c,nc); + } + data[nx][ny] = nc; + } + } + } + } + data[x][y] = c; + } +} + +float DynamicVoronoi::getDistance( int x, int y ) const { + if( (x>0) && (x0) && (y1 || nc.sqdist>1) && nc.obstX!=invalidObstData) { + if (abs(c.obstX-nc.obstX) > 1 || abs(c.obstY-nc.obstY) > 1) { + //compute dist from x,y to obstacle of nx,ny + int dxy_x = x-nc.obstX; + int dxy_y = y-nc.obstY; + int sqdxy = dxy_x*dxy_x + dxy_y*dxy_y; + int stability_xy = sqdxy - c.sqdist; + if (sqdxy - c.sqdist<0) return; + + //compute dist from nx,ny to obstacle of x,y + int dnxy_x = nx - c.obstX; + int dnxy_y = ny - c.obstY; + int sqdnxy = dnxy_x*dnxy_x + dnxy_y*dnxy_y; + int stability_nxy = sqdnxy - nc.sqdist; + if (sqdnxy - nc.sqdist <0) return; + + //which cell is added to the Voronoi diagram? + if(stability_xy <= stability_nxy && c.sqdist>2) { + if (c.voronoi != free) { + c.voronoi = free; + reviveVoroNeighbors(x,y); + pruneQueue.push(INTPOINT(x,y)); + } + } + if(stability_nxy <= stability_xy && nc.sqdist>2) { + if (nc.voronoi != free) { + nc.voronoi = free; + reviveVoroNeighbors(nx,ny); + pruneQueue.push(INTPOINT(nx,ny)); + } + } + } + } +} + + +void DynamicVoronoi::reviveVoroNeighbors(int &x, int &y) { + for (int dx=-1; dx<=1; dx++) { + int nx = x+dx; + if (nx<=0 || nx>=sizeX-1) continue; + for (int dy=-1; dy<=1; dy++) { + if (dx==0 && dy==0) continue; + int ny = y+dy; + if (ny<=0 || ny>=sizeY-1) continue; + dataCell nc = data[nx][ny]; + if (nc.sqdist != INT_MAX && !nc.needsRaise && (nc.voronoi == voronoiKeep || nc.voronoi == voronoiPrune)) { + nc.voronoi = free; + data[nx][ny] = nc; + pruneQueue.push(INTPOINT(nx,ny)); + } + } + } +} + + +bool DynamicVoronoi::isOccupied(int x, int y) const { + dataCell c = data[x][y]; + return (c.obstX==x && c.obstY==y); +} + +bool DynamicVoronoi::isOccupied(int &x, int &y, dataCell &c) { + return (c.obstX==x && c.obstY==y); +} + +void DynamicVoronoi::visualize(const char *filename) { + // write ppm files + + FILE* F = fopen(filename, "w"); + if (!F) { + std::cerr << "could not open 'result.pgm' for writing!\n"; + return; + } + fprintf(F, "P6\n#\n"); + fprintf(F, "%d %d\n255\n", sizeX, sizeY); + + for(int y = sizeY-1; y >=0; y--){ + for(int x = 0; x255) f=255; + if (f<0) f=0; + c = (unsigned char)f; + fputc( c, F ); + fputc( c, F ); + fputc( c, F ); + } + } + } + fclose(F); +} + + +void DynamicVoronoi::prune() { + // filler + while(!pruneQueue.empty()) { + INTPOINT p = pruneQueue.front(); + pruneQueue.pop(); + int x = p.x; + int y = p.y; + + if (data[x][y].voronoi==occupied) continue; + if (data[x][y].voronoi==freeQueued) continue; + + data[x][y].voronoi = freeQueued; + sortedPruneQueue.push(data[x][y].sqdist, p); + + /* tl t tr + l c r + bl b br */ + + dataCell tr,tl,br,bl; + tr = data[x+1][y+1]; + tl = data[x-1][y+1]; + br = data[x+1][y-1]; + bl = data[x-1][y-1]; + + dataCell r,b,t,l; + r = data[x+1][y]; + l = data[x-1][y]; + t = data[x][y+1]; + b = data[x][y-1]; + + if (x+2=0 && l.voronoi==occupied) { + // fill to the left + if (tl.voronoi!=occupied && bl.voronoi!=occupied && data[x-2][y].voronoi!=occupied) { + l.voronoi = freeQueued; + sortedPruneQueue.push(l.sqdist, INTPOINT(x-1,y)); + data[x-1][y] = l; + } + } + if (y+2=0 && b.voronoi==occupied) { + // fill to the bottom + if (br.voronoi!=occupied && bl.voronoi!=occupied && data[x][y-2].voronoi!=occupied) { + b.voronoi = freeQueued; + sortedPruneQueue.push(b.sqdist, INTPOINT(x,y-1)); + data[x][y-1] = b; + } + } + } + + + while(!sortedPruneQueue.empty()) { + INTPOINT p = sortedPruneQueue.pop(); + dataCell c = data[p.x][p.y]; + int v = c.voronoi; + if (v!=freeQueued && v!=voronoiRetry) { // || v>free || v==voronoiPrune || v==voronoiKeep) { + // assert(v!=retry); + continue; + } + + markerMatchResult r = markerMatch(p.x,p.y); + if (r==pruned) c.voronoi = voronoiPrune; + else if (r==keep) c.voronoi = voronoiKeep; + else { // r==retry + c.voronoi = voronoiRetry; + // printf("RETRY %d %d\n", x, sizeY-1-y); + pruneQueue.push(p); + } + data[p.x][p.y] = c; + + if (sortedPruneQueue.empty()) { + while (!pruneQueue.empty()) { + INTPOINT p = pruneQueue.front(); + pruneQueue.pop(); + sortedPruneQueue.push(data[p.x][p.y].sqdist, p); + } + } + } + // printf("match: %d\nnomat: %d\n", matchCount, noMatchCount); +} + +void DynamicVoronoi::updateAlternativePrunedDiagram() { + + if(alternativeDiagram==NULL){ + alternativeDiagram = new int*[sizeX]; + for(int x=0; x end_cells; + BucketPrioQueue sortedPruneQueue; + for(int x=1; x= 3){ + alternativeDiagram[x][y] = voronoiKeep; + sortedPruneQueue.push(data[x][y].sqdist, INTPOINT(x,y)); + end_cells.push(INTPOINT(x, y)); + } + } + } + + for(int x=1; x= 3){ + alternativeDiagram[x][y] = voronoiKeep; + sortedPruneQueue.push(data[x][y].sqdist, INTPOINT(x,y)); + end_cells.push(INTPOINT(x, y)); + } + } + } + + + while (!sortedPruneQueue.empty()) { + INTPOINT p = sortedPruneQueue.pop(); + + if (markerMatchAlternative(p.x, p.y)) { + alternativeDiagram[p.x][p.y]=voronoiPrune; + } else { + alternativeDiagram[p.x][p.y]=voronoiKeep; + } + } + + // //delete worms + while (!end_cells.empty()) { + INTPOINT p = end_cells.front(); + end_cells.pop(); + + if (isVoronoiAlternative(p.x,p.y) && getNumVoronoiNeighborsAlternative(p.x, p.y) == 1) { + alternativeDiagram[p.x][p.y] = voronoiPrune; + + for (int dx = -1; dx <= 1; ++dx) { + for (int dy = -1; dy <= 1; ++dy) { + if (!(dx || dy) || (dx && dy)) { + continue; + } + int nx = p.x + dx; + int ny = p.y + dy; + if (nx < 0 || nx >= sizeX || ny < 0 || ny >= sizeY) { + continue; + } + if (isVoronoiAlternative(nx,ny)) { + if (getNumVoronoiNeighborsAlternative(nx, ny) == 1) { + end_cells.push(INTPOINT(nx, ny)); + } + } + } + } + } + } +} + +bool DynamicVoronoi::markerMatchAlternative(int x, int y) { +// prune if this returns true + + bool f[8]; + + int nx, ny; + int dx, dy; + + int i = 0; +// int obstacleCount=0; + int voroCount = 0; + for (dy = 1; dy >= -1; dy--) { + ny = y + dy; + for (dx = -1; dx <= 1; dx++) { + if (dx || dy) { + nx = x + dx; + int v = alternativeDiagram[nx][ny]; + bool b = (v <= free && v != voronoiPrune); + // if (v==occupied) obstacleCount++; + f[i] = b; + if (v <= free && !(dx && dy)) + voroCount++; + i++; + } + } + } + + /* + * 5 6 7 + * 3 4 + * 0 1 2 + */ + + { + //connected horizontal or vertically to only one cell + if (voroCount == 1 && (f[1] || f[3] || f[4] || f[6])) { + return false; + } + + // 4-connected + if ((!f[0] && f[1] && f[3]) || (!f[2] && f[1] && f[4]) || (!f[5] && f[3] && f[6]) || (!f[7] && f[6] && f[4])) + return false; + + if ((f[3] && f[4] && !f[1] && !f[6]) || (f[1] && f[6] && !f[3] && !f[4])) + return false; + + } + return true; +} + +int DynamicVoronoi::getNumVoronoiNeighborsAlternative(int x, int y) const { + int count = 0; + for (int dx = -1; dx <= 1; dx++) { + for (int dy = -1; dy <= 1; dy++) { + if ((dx == 0 && dy == 0) || (dx != 0 && dy != 0)) { + continue; + } + + int nx = x + dx; + int ny = y + dy; + if (nx < 0 || nx >= sizeX || ny < 0 || ny >= sizeY) { + continue; + } + if (alternativeDiagram[nx][ny]==free || alternativeDiagram[nx][ny]==voronoiKeep) { + count++; + } + } + } + return count; +} + + + +DynamicVoronoi::markerMatchResult DynamicVoronoi::markerMatch(int x, int y) { + // implementation of connectivity patterns + bool f[8]; + + int nx, ny; + int dx, dy; + + int i=0; + int count=0; + // int obstacleCount=0; + int voroCount=0; + int voroCountFour=0; + + for (dy=1; dy>=-1; dy--) { + ny = y+dy; + for (dx=-1; dx<=1; dx++) { + if (dx || dy) { + nx = x+dx; + dataCell nc = data[nx][ny]; + int v = nc.voronoi; + bool b = (v<=free && v!=voronoiPrune); + // if (v==occupied) obstacleCount++; + f[i] = b; + if (b) { + voroCount++; + if (!(dx && dy)) voroCountFour++; + } + if (b && !(dx && dy) ) count++; + // if (v<=free && !(dx && dy)) voroCount++; + i++; + } + } + } + if (voroCount<3 && voroCountFour==1 && (f[1] || f[3] || f[4] || f[6])) { + // assert(voroCount<2); + // if (voroCount>=2) printf("voro>2 %d %d\n", x, y); + return keep; + } + + // 4-connected + if ((!f[0] && f[1] && f[3]) || (!f[2] && f[1] && f[4]) || (!f[5] && f[3] && f[6]) || (!f[7] && f[6] && f[4])) return keep; + if ((f[3] && f[4] && !f[1] && !f[6]) || (f[1] && f[6] && !f[3] && !f[4])) return keep; + + + + // keep voro cells inside of blocks and retry later + if (voroCount>=5 && voroCountFour>=3 && data[x][y].voronoi!=voronoiRetry) { + return retry; + } + + return pruned; +} diff --git a/simulators/third_party/map_plugins/voronoi_layer/src/voronoi_layer.cpp b/simulators/third_party/map_plugins/voronoi_layer/src/voronoi_layer.cpp new file mode 100755 index 0000000..41a6b09 --- /dev/null +++ b/simulators/third_party/map_plugins/voronoi_layer/src/voronoi_layer.cpp @@ -0,0 +1,204 @@ +/****************************************************************************** + * Copyright (c) 2023, NKU Mobile & Flying Robotics Lab + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 'AS IS' + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *****************************************************************************/ + +#include "voronoi_layer.h" + +#include // NOLINT + +#include "pluginlib/class_list_macros.h" + +PLUGINLIB_EXPORT_CLASS(costmap_2d::VoronoiLayer, costmap_2d::Layer) + +namespace costmap_2d +{ +void VoronoiLayer::onInitialize() +{ + ros::NodeHandle nh("~/" + name_); + current_ = true; + + voronoi_grid_pub_ = nh.advertise("voronoi_grid", 1); + + dsrv_ = std::make_unique>(nh); + dynamic_reconfigure::Server::CallbackType cb = + boost::bind(&VoronoiLayer::reconfigureCB, this, _1, _2); + dsrv_->setCallback(cb); +} + +void VoronoiLayer::reconfigureCB(const costmap_2d::GenericPluginConfig& config, uint32_t level) +{ + enabled_ = config.enabled; +} + +const DynamicVoronoi& VoronoiLayer::getVoronoi() const +{ + return voronoi_; +} + +boost::mutex& VoronoiLayer::getMutex() +{ + return mutex_; +} + +void VoronoiLayer::updateBounds(double robot_x, double robot_y, double robot_yaw, double* min_x, double* min_y, + double* max_x, double* max_y) +{ + if (!enabled_) + { + return; + } +} + +void VoronoiLayer::outlineMap(unsigned char* costarr, int nx, int ny, unsigned char value) +{ + unsigned char* pc = costarr; + for (int i = 0; i < nx; i++) + { + *pc++ = value; + } + pc = costarr + (ny - 1) * nx; + for (int i = 0; i < nx; i++) + { + *pc++ = value; + } + pc = costarr; + for (int i = 0; i < ny; i++, pc += nx) + { + *pc = value; + } + pc = costarr + nx - 1; + for (int i = 0; i < ny; i++, pc += nx) + { + *pc = value; + } +} + +void VoronoiLayer::updateCosts(costmap_2d::Costmap2D& master_grid, int min_i, int min_j, int max_i, int max_j) +{ + if (!enabled_) + { + return; + } + + boost::unique_lock lock(mutex_); + + unsigned int size_x = master_grid.getSizeInCellsX(); + unsigned int size_y = master_grid.getSizeInCellsY(); + outlineMap(master_grid.getCharMap(), size_x, size_y, costmap_2d::LETHAL_OBSTACLE); + + if (last_size_x_ != size_x || last_size_y_ != size_y) + { + voronoi_.initializeEmpty(size_x, size_y); + + last_size_x_ = size_x; + last_size_y_ = size_y; + } + + std::vector new_free_cells, new_occupied_cells; + for (unsigned int j = 0; j < size_y; ++j) + { + for (unsigned int i = 0; i < size_x; ++i) + { + if (voronoi_.isOccupied(i, j) && master_grid.getCost(i, j) == costmap_2d::FREE_SPACE) + { + new_free_cells.push_back(IntPoint(i, j)); + } + + if (!voronoi_.isOccupied(i, j) && master_grid.getCost(i, j) == costmap_2d::LETHAL_OBSTACLE) + { + new_occupied_cells.push_back(IntPoint(i, j)); + } + } + } + + for (size_t i = 0; i < new_free_cells.size(); ++i) + { + voronoi_.clearCell(new_free_cells[i].x, new_free_cells[i].y); + } + + for (size_t i = 0; i < new_occupied_cells.size(); ++i) + { + voronoi_.occupyCell(new_occupied_cells[i].x, new_occupied_cells[i].y); + } + + // start timing + const auto start_timestamp = std::chrono::system_clock::now(); + + voronoi_.update(); + voronoi_.prune(); + + // end timing + const auto end_timestamp = std::chrono::system_clock::now(); + const std::chrono::duration diff = end_timestamp - start_timestamp; + ROS_DEBUG("Runtime=%.3fms.", diff.count() * 1e3); + + publishVoronoiGrid(master_grid); +} + +void VoronoiLayer::publishVoronoiGrid(const costmap_2d::Costmap2D& master_grid) +{ + unsigned int nx = master_grid.getSizeInCellsX(); + unsigned int ny = master_grid.getSizeInCellsY(); + + double resolution = master_grid.getResolution(); + nav_msgs::OccupancyGrid grid; + // Publish Whole Grid + grid.header.frame_id = "map"; + grid.header.stamp = ros::Time::now(); + grid.info.resolution = resolution; + + grid.info.width = nx; + grid.info.height = ny; + + grid.info.origin.position.x = master_grid.getOriginX(); + grid.info.origin.position.y = master_grid.getOriginY(); + grid.info.origin.position.z = 0.0; + grid.info.origin.orientation.w = 1.0; + + grid.data.resize(nx * ny); + + for (unsigned int x = 0; x < nx; x++) + { + for (unsigned int y = 0; y < ny; y++) + { + if (voronoi_.isVoronoi(x, y)) + { + grid.data[x + y * nx] = 128; + } + else + { + grid.data[x + y * nx] = 0; + } + } + } + voronoi_grid_pub_.publish(grid); +} + +} // namespace costmap_2d diff --git a/simulators/third_party/rviz_plugins/spencer_messages/.gitignore b/simulators/third_party/rviz_plugins/spencer_messages/.gitignore new file mode 100755 index 0000000..4581ef2 --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_messages/.gitignore @@ -0,0 +1,29 @@ +# Compiled Object files +*.slo +*.lo +*.o +*.obj + +# Precompiled Headers +*.gch +*.pch + +# Compiled Dynamic libraries +*.so +*.dylib +*.dll + +# Fortran module files +*.mod +*.smod + +# Compiled Static libraries +*.lai +*.la +*.a +*.lib + +# Executables +*.exe +*.out +*.app diff --git a/simulators/third_party/rviz_plugins/spencer_messages/LICENSE b/simulators/third_party/rviz_plugins/spencer_messages/LICENSE new file mode 100755 index 0000000..f13c155 --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_messages/LICENSE @@ -0,0 +1,23 @@ +Copyright (c) 2016, spencer.eu +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. diff --git a/simulators/third_party/rviz_plugins/spencer_messages/README.md b/simulators/third_party/rviz_plugins/spencer_messages/README.md new file mode 100755 index 0000000..65678f0 --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_messages/README.md @@ -0,0 +1 @@ +# spencer_messages \ No newline at end of file diff --git a/simulators/third_party/rviz_plugins/spencer_messages/spencer_control_msgs/CHANGELOG.rst b/simulators/third_party/rviz_plugins/spencer_messages/spencer_control_msgs/CHANGELOG.rst new file mode 100755 index 0000000..1acffe2 --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_messages/spencer_control_msgs/CHANGELOG.rst @@ -0,0 +1,35 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package spencer_control_msgs +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +1.0.8 (2017-09-22) +------------------ +* Merge pull request `#41 `_ from LCAS/master + 1.0.7 +* Contributors: Timm Linder + +1.0.7 (2017-06-09) +------------------ + +1.0.6 (2017-06-09) +------------------ + +1.0.5 (2017-05-12) +------------------ + +1.0.4 (2017-05-12) +------------------ + +1.0.3 (2017-05-11) +------------------ + +1.0.2 (2017-05-09) +------------------ +* added missing roslib deps +* Contributors: Marc Hanheide + +1.0.1 (2017-05-09) +------------------ +* homogenised all version strings to 1.0.0 +* Adding missing spencer_control_msgs package +* Contributors: Marc Hanheide, Timm Linder diff --git a/simulators/third_party/rviz_plugins/spencer_messages/spencer_control_msgs/CMakeLists.txt b/simulators/third_party/rviz_plugins/spencer_messages/spencer_control_msgs/CMakeLists.txt new file mode 100755 index 0000000..4380db0 --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_messages/spencer_control_msgs/CMakeLists.txt @@ -0,0 +1,32 @@ +cmake_minimum_required(VERSION 2.8.3) +project(spencer_control_msgs) + +find_package(catkin REQUIRED COMPONENTS + roscpp + roslib + std_msgs + message_generation +) + +################################################ +## Declare ROS messages, services and actions ## +################################################ + +# Generate messages in the 'msg' folder +add_message_files( + FILES + ComponentStatus.msg +) + +## Generate added messages and services with any dependencies listed here +generate_messages( + DEPENDENCIES + std_msgs +) + +################################### +## catkin specific configuration ## +################################### +catkin_package( + CATKIN_DEPENDS roscpp std_msgs message_runtime +) diff --git a/simulators/third_party/rviz_plugins/spencer_messages/spencer_control_msgs/LICENSE b/simulators/third_party/rviz_plugins/spencer_messages/spencer_control_msgs/LICENSE new file mode 100755 index 0000000..98f9a8a --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_messages/spencer_control_msgs/LICENSE @@ -0,0 +1,29 @@ +Software License Agreement (BSD License) + +Copyright (c) 2013-2015 Timm Linder, Social Robotics Laboratory, University of Freiburg +Copyright (c) 2014-2015 Stefan Breuers, Lucas Beyer, Computer Vision Group, RWTH Aachen University +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name of the copyright holder nor the names of its contributors + may be used to endorse or promote products derived from this software + without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE \ No newline at end of file diff --git a/simulators/third_party/rviz_plugins/spencer_messages/spencer_control_msgs/msg/ComponentStatus.msg b/simulators/third_party/rviz_plugins/spencer_messages/spencer_control_msgs/msg/ComponentStatus.msg new file mode 100755 index 0000000..76f3cba --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_messages/spencer_control_msgs/msg/ComponentStatus.msg @@ -0,0 +1,3 @@ +string name +bool alive +string detail \ No newline at end of file diff --git a/simulators/third_party/rviz_plugins/spencer_messages/spencer_control_msgs/package.xml b/simulators/third_party/rviz_plugins/spencer_messages/spencer_control_msgs/package.xml new file mode 100755 index 0000000..6f5dae9 --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_messages/spencer_control_msgs/package.xml @@ -0,0 +1,22 @@ + + + + spencer_control_msgs + 1.0.8 + Messages used for controlling the SPENCER robot platform. + + Timm Linder + Timm Linder + + BSD + + catkin + message_generation + roscpp + std_msgs + + message_runtime + roscpp + std_msgs + +roslibroslib diff --git a/simulators/third_party/rviz_plugins/spencer_messages/spencer_human_attribute_msgs/CHANGELOG.rst b/simulators/third_party/rviz_plugins/spencer_messages/spencer_human_attribute_msgs/CHANGELOG.rst new file mode 100755 index 0000000..d49b750 --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_messages/spencer_human_attribute_msgs/CHANGELOG.rst @@ -0,0 +1,39 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package spencer_human_attribute_msgs +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +1.0.8 (2017-09-22) +------------------ +* Merge pull request `#2 `_ from spencer-project/master + Integrate multiple fixes from upstream +* Specify correct license in package.xmls +* Merge pull request `#41 `_ from LCAS/master + 1.0.7 +* Contributors: Marc Hanheide, Timm Linder + +1.0.7 (2017-06-09) +------------------ + +1.0.6 (2017-06-09) +------------------ + +1.0.5 (2017-05-12) +------------------ + +1.0.4 (2017-05-12) +------------------ + +1.0.3 (2017-05-11) +------------------ + +1.0.2 (2017-05-09) +------------------ +* added missing roslib deps +* Contributors: Marc Hanheide + +1.0.1 (2017-05-09) +------------------ +* homogenised all version strings to 1.0.0 +* Updated licenses +* Adding message definitions, RViz plugins and mock scripts +* Contributors: Marc Hanheide, Timm Linder diff --git a/simulators/third_party/rviz_plugins/spencer_messages/spencer_human_attribute_msgs/CMakeLists.txt b/simulators/third_party/rviz_plugins/spencer_messages/spencer_human_attribute_msgs/CMakeLists.txt new file mode 100755 index 0000000..2a9830c --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_messages/spencer_human_attribute_msgs/CMakeLists.txt @@ -0,0 +1,39 @@ +cmake_minimum_required(VERSION 2.8.3) +project(spencer_human_attribute_msgs) + +find_package(catkin REQUIRED COMPONENTS + roscpp + roslib + std_msgs + message_generation +) + +################################################ +## Declare ROS messages, services and actions ## +################################################ + +# Generate messages in the 'msg' folder +add_message_files( + FILES + CategoricalAttribute.msg + ScalarAttribute.msg + HumanAttributes.msg +) + +# Generate services in the 'srv' folder +#add_service_files( +# FILES +#) + +## Generate added messages and services with any dependencies listed here +generate_messages( + DEPENDENCIES + std_msgs +) + +################################### +## catkin specific configuration ## +################################### +catkin_package( + CATKIN_DEPENDS roscpp std_msgs message_runtime +) diff --git a/simulators/third_party/rviz_plugins/spencer_messages/spencer_human_attribute_msgs/LICENSE b/simulators/third_party/rviz_plugins/spencer_messages/spencer_human_attribute_msgs/LICENSE new file mode 100755 index 0000000..dddbbfb --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_messages/spencer_human_attribute_msgs/LICENSE @@ -0,0 +1,28 @@ +Software License Agreement (BSD License) + +Copyright (c) 2014-2015 Timm Linder, Social Robotics Laboratory, University of Freiburg +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name of the copyright holder nor the names of its contributors + may be used to endorse or promote products derived from this software + without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE \ No newline at end of file diff --git a/simulators/third_party/rviz_plugins/spencer_messages/spencer_human_attribute_msgs/msg/CategoricalAttribute.msg b/simulators/third_party/rviz_plugins/spencer_messages/spencer_human_attribute_msgs/msg/CategoricalAttribute.msg new file mode 100755 index 0000000..1259aa2 --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_messages/spencer_human_attribute_msgs/msg/CategoricalAttribute.msg @@ -0,0 +1,32 @@ +uint64 subject_id # either an observation ID or a track ID (if information has been integrated over time); should be encoded in topic name +string type # type of the attribute, see constants below + +string[] values # values, each value also should have a confidence, highest-confidence attribute should come first +float32[] confidences # corresponding confidences should sum up to 1.0, highest confidence comes first + + +################################################## +### Constants for categorical attribute types. ### +################################################## + +string GENDER = gender +string AGE_GROUP = age_group + +################################################### +### Constants for categorical attribute values. ### +################################################### + +string GENDER_MALE = male +string GENDER_FEMALE = female + +# Age groups are based upon the categories from the "Images Of Groups" RGB database +string AGE_GROUP_0_TO_2 = 0-2 +string AGE_GROUP_3_TO_7 = 3-7 +string AGE_GROUP_8_TO_12 = 8-12 +string AGE_GROUP_13_TO_19 = 13-19 +string AGE_GROUP_20_TO_36 = 20-36 +string AGE_GROUP_37_TO_65 = 37-65 +string AGE_GROUP_66_TO_99 = 66-99 + + + diff --git a/simulators/third_party/rviz_plugins/spencer_messages/spencer_human_attribute_msgs/msg/HumanAttributes.msg b/simulators/third_party/rviz_plugins/spencer_messages/spencer_human_attribute_msgs/msg/HumanAttributes.msg new file mode 100755 index 0000000..c60bc27 --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_messages/spencer_human_attribute_msgs/msg/HumanAttributes.msg @@ -0,0 +1,5 @@ +std_msgs/Header header + +# One entry per attribute type per person +CategoricalAttribute[] categoricalAttributes +ScalarAttribute[] scalarAttributes \ No newline at end of file diff --git a/simulators/third_party/rviz_plugins/spencer_messages/spencer_human_attribute_msgs/msg/ScalarAttribute.msg b/simulators/third_party/rviz_plugins/spencer_messages/spencer_human_attribute_msgs/msg/ScalarAttribute.msg new file mode 100755 index 0000000..eea07b7 --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_messages/spencer_human_attribute_msgs/msg/ScalarAttribute.msg @@ -0,0 +1,12 @@ +uint64 subject_id # either an observation ID or a track ID (if information has been integrated over time); should be encoded in topic name +string type # type of the attribute, see constants below + +float32[] values # values, each value also should have a confidence; highest-confidence value comes first! +float32[] confidences # corresponding confidences should sum up to 1.0 + + +########################################### +### Constants for scalar attribute types. # +########################################### + +string PERSON_HEIGHT = person_height diff --git a/simulators/third_party/rviz_plugins/spencer_messages/spencer_human_attribute_msgs/package.xml b/simulators/third_party/rviz_plugins/spencer_messages/spencer_human_attribute_msgs/package.xml new file mode 100755 index 0000000..98c6f40 --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_messages/spencer_human_attribute_msgs/package.xml @@ -0,0 +1,22 @@ + + + + spencer_human_attribute_msgs + 1.0.8 + Messages used for Human Attribute Recognition + + Timm Linder + Timm Linder + + BSD + + catkin + message_generation + roscpp + std_msgs + + message_runtime + roscpp + std_msgs + +roslibroslib diff --git a/simulators/third_party/rviz_plugins/spencer_messages/spencer_social_relation_msgs/CHANGELOG.rst b/simulators/third_party/rviz_plugins/spencer_messages/spencer_social_relation_msgs/CHANGELOG.rst new file mode 100755 index 0000000..a8ed908 --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_messages/spencer_social_relation_msgs/CHANGELOG.rst @@ -0,0 +1,40 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package spencer_social_relation_msgs +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +1.0.8 (2017-09-22) +------------------ +* Merge pull request `#2 `_ from spencer-project/master + Integrate multiple fixes from upstream +* Specify correct license in package.xmls +* Merge pull request `#41 `_ from LCAS/master + 1.0.7 +* Contributors: Marc Hanheide, Timm Linder + +1.0.7 (2017-06-09) +------------------ + +1.0.6 (2017-06-09) +------------------ + +1.0.5 (2017-05-12) +------------------ + +1.0.4 (2017-05-12) +------------------ + +1.0.3 (2017-05-11) +------------------ + +1.0.2 (2017-05-09) +------------------ +* added missing roslib deps +* Contributors: Marc Hanheide + +1.0.1 (2017-05-09) +------------------ +* homogenised all version strings to 1.0.0 +* Updating lots of utility packages to latest version from SPENCER repo. Licenses updated. +* Updated licenses +* Adding message definitions, RViz plugins and mock scripts +* Contributors: Marc Hanheide, Timm Linder diff --git a/simulators/third_party/rviz_plugins/spencer_messages/spencer_social_relation_msgs/CMakeLists.txt b/simulators/third_party/rviz_plugins/spencer_messages/spencer_social_relation_msgs/CMakeLists.txt new file mode 100755 index 0000000..7949160 --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_messages/spencer_social_relation_msgs/CMakeLists.txt @@ -0,0 +1,46 @@ +cmake_minimum_required(VERSION 2.8.3) +project(spencer_social_relation_msgs) + +find_package(catkin REQUIRED COMPONENTS + roscpp + roslib + std_msgs + sensor_msgs + nav_msgs + geometry_msgs + message_generation +) + +################################################ +## Declare ROS messages, services and actions ## +################################################ + +# Generate messages in the 'msg' folder +add_message_files( + FILES + SocialRelation.msg + SocialRelations.msg + SocialActivity.msg + SocialActivities.msg +) + +# Generate services in the 'srv' folder +#add_service_files( +# FILES +#) + +## Generate added messages and services with any dependencies listed here +generate_messages( + DEPENDENCIES + geometry_msgs + sensor_msgs + nav_msgs + std_msgs +) + +################################### +## catkin specific configuration ## +################################### +catkin_package( + CATKIN_DEPENDS roscpp std_msgs sensor_msgs nav_msgs geometry_msgs message_runtime +) diff --git a/simulators/third_party/rviz_plugins/spencer_messages/spencer_social_relation_msgs/LICENSE b/simulators/third_party/rviz_plugins/spencer_messages/spencer_social_relation_msgs/LICENSE new file mode 100755 index 0000000..7416d42 --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_messages/spencer_social_relation_msgs/LICENSE @@ -0,0 +1,28 @@ +Software License Agreement (BSD License) + +Copyright (c) 2014-2015 Timm Linder, Billy Okal, Social Robotics Laboratory, University of Freiburg +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name of the copyright holder nor the names of its contributors + may be used to endorse or promote products derived from this software + without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE \ No newline at end of file diff --git a/simulators/third_party/rviz_plugins/spencer_messages/spencer_social_relation_msgs/msg/SocialActivities.msg b/simulators/third_party/rviz_plugins/spencer_messages/spencer_social_relation_msgs/msg/SocialActivities.msg new file mode 100755 index 0000000..b0b55a4 --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_messages/spencer_social_relation_msgs/msg/SocialActivities.msg @@ -0,0 +1,5 @@ +std_msgs/Header header + +# All social activities that have been detected in the current time step, +# within sensor range of the robot. +SocialActivity[] elements \ No newline at end of file diff --git a/simulators/third_party/rviz_plugins/spencer_messages/spencer_social_relation_msgs/msg/SocialActivity.msg b/simulators/third_party/rviz_plugins/spencer_messages/spencer_social_relation_msgs/msg/SocialActivity.msg new file mode 100755 index 0000000..fc1857b --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_messages/spencer_social_relation_msgs/msg/SocialActivity.msg @@ -0,0 +1,24 @@ +string type # see constants below +float32 confidence # detection confidence + +uint64[] track_ids # IDs of all person tracks involved in the activity, might be one or multiple + + +# Constants for social activity type (just examples at the moment) +string TYPE_SHOPPING = shopping +string TYPE_STANDING = standing +string TYPE_INDIVIDUAL_MOVING = individual_moving +string TYPE_WAITING_IN_QUEUE = waiting_in_queue +string TYPE_LOOKING_AT_INFORMATION_SCREEN = looking_at_information_screen +string TYPE_LOOKING_AT_KIOSK = looking_at_kiosk +string TYPE_GROUP_ASSEMBLING = group_assembling +string TYPE_GROUP_MOVING = group_moving +string TYPE_FLOW_WITH_ROBOT = flow +string TYPE_ANTIFLOW_AGAINST_ROBOT = antiflow +string TYPE_WAITING_FOR_OTHERS = waiting_for_others +string TYPE_LOOKING_FOR_HELP = looking_for_help + + +#string TYPE_COMMUNICATING = communicating +#string TYPE_TAKING_PHOTOGRAPH = taking_photograph +#string TYPE_TALKING_ON_PHONE = talking_on_phone diff --git a/simulators/third_party/rviz_plugins/spencer_messages/spencer_social_relation_msgs/msg/SocialRelation.msg b/simulators/third_party/rviz_plugins/spencer_messages/spencer_social_relation_msgs/msg/SocialRelation.msg new file mode 100755 index 0000000..2159dc9 --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_messages/spencer_social_relation_msgs/msg/SocialRelation.msg @@ -0,0 +1,12 @@ +string type # e.g. mother-son relationship, romantic relationship, etc. +float32 strength # relationship strength between 0.0 and 1.0 + +uint32 track1_id +uint32 track2_id + + +# Constants for type (just examples at the moment) +string TYPE_SPATIAL = "spatial" +string TYPE_ROMANTIC = "romantic" +string TYPE_PARENT_CHILD = "parent_child" +string TYPE_FRIENDSHIP = "friendship" \ No newline at end of file diff --git a/simulators/third_party/rviz_plugins/spencer_messages/spencer_social_relation_msgs/msg/SocialRelations.msg b/simulators/third_party/rviz_plugins/spencer_messages/spencer_social_relation_msgs/msg/SocialRelations.msg new file mode 100755 index 0000000..f30cd8d --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_messages/spencer_social_relation_msgs/msg/SocialRelations.msg @@ -0,0 +1,5 @@ +std_msgs/Header header + +# All social relations of all tracks in the current time step. +# There might be multiple social relations per pair of tracks. +SocialRelation[] elements \ No newline at end of file diff --git a/simulators/third_party/rviz_plugins/spencer_messages/spencer_social_relation_msgs/package.xml b/simulators/third_party/rviz_plugins/spencer_messages/spencer_social_relation_msgs/package.xml new file mode 100755 index 0000000..3b653d2 --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_messages/spencer_social_relation_msgs/package.xml @@ -0,0 +1,28 @@ + + + + spencer_social_relation_msgs + 1.0.8 + Messages used for Social Activity Detection and Social Relation Analysis + + Timm Linder + BSD + + Timm Linder + + catkin + message_generation + roscpp + std_msgs + sensor_msgs + nav_msgs + geometry_msgs + + message_runtime + roscpp + std_msgs + sensor_msgs + nav_msgs + geometry_msgs + +roslibroslib diff --git a/simulators/third_party/rviz_plugins/spencer_messages/spencer_tracking_msgs/CHANGELOG.rst b/simulators/third_party/rviz_plugins/spencer_messages/spencer_tracking_msgs/CHANGELOG.rst new file mode 100755 index 0000000..e8cb240 --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_messages/spencer_tracking_msgs/CHANGELOG.rst @@ -0,0 +1,41 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package spencer_tracking_msgs +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +1.0.8 (2017-09-22) +------------------ +* Merge pull request `#2 `_ from spencer-project/master + Integrate multiple fixes from upstream +* Specify correct license in package.xmls +* Merge pull request `#41 `_ from LCAS/master + 1.0.7 +* Contributors: Marc Hanheide, Timm Linder + +1.0.7 (2017-06-09) +------------------ + +1.0.6 (2017-06-09) +------------------ + +1.0.5 (2017-05-12) +------------------ + +1.0.4 (2017-05-12) +------------------ + +1.0.3 (2017-05-11) +------------------ + +1.0.2 (2017-05-09) +------------------ +* added missing roslib deps +* Contributors: Marc Hanheide + +1.0.1 (2017-05-09) +------------------ +* homogenised all version strings to 1.0.0 +* Updating lots of utility packages to latest version from SPENCER repo. Licenses updated. +* Updated licenses +* Adding is_matched field in TrackedPerson message to distinguish between misdetections and physical occlusions +* Adding message definitions, RViz plugins and mock scripts +* Contributors: Marc Hanheide, Timm Linder diff --git a/simulators/third_party/rviz_plugins/spencer_messages/spencer_tracking_msgs/CMakeLists.txt b/simulators/third_party/rviz_plugins/spencer_messages/spencer_tracking_msgs/CMakeLists.txt new file mode 100755 index 0000000..91a25bf --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_messages/spencer_tracking_msgs/CMakeLists.txt @@ -0,0 +1,52 @@ +cmake_minimum_required(VERSION 2.8.3) +project(spencer_tracking_msgs) + +find_package(catkin REQUIRED COMPONENTS + roscpp + roslib + std_msgs + geometry_msgs + message_generation +) + +################################################ +## Declare ROS messages, services and actions ## +################################################ + +# Generate messages in the 'msg' folder +add_message_files( + FILES + DetectedPerson.msg + DetectedPersons.msg + CompositeDetectedPerson.msg + CompositeDetectedPersons.msg + TrackedPerson.msg + TrackedPersons.msg + TrackedPerson2d.msg + TrackedPersons2d.msg + TrackedGroup.msg + TrackedGroups.msg + ImmDebugInfo.msg + ImmDebugInfos.msg + TrackingTimingMetrics.msg +) + +# Generate services in the 'srv' folder +add_service_files( + FILES + GetPersonTrajectories.srv +) + +## Generate added messages and services with any dependencies listed here +generate_messages( + DEPENDENCIES + geometry_msgs + std_msgs +) + +################################### +## catkin specific configuration ## +################################### +catkin_package( + CATKIN_DEPENDS roscpp std_msgs geometry_msgs message_runtime +) diff --git a/simulators/third_party/rviz_plugins/spencer_messages/spencer_tracking_msgs/LICENSE b/simulators/third_party/rviz_plugins/spencer_messages/spencer_tracking_msgs/LICENSE new file mode 100755 index 0000000..98f9a8a --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_messages/spencer_tracking_msgs/LICENSE @@ -0,0 +1,29 @@ +Software License Agreement (BSD License) + +Copyright (c) 2013-2015 Timm Linder, Social Robotics Laboratory, University of Freiburg +Copyright (c) 2014-2015 Stefan Breuers, Lucas Beyer, Computer Vision Group, RWTH Aachen University +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name of the copyright holder nor the names of its contributors + may be used to endorse or promote products derived from this software + without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE \ No newline at end of file diff --git a/simulators/third_party/rviz_plugins/spencer_messages/spencer_tracking_msgs/msg/CompositeDetectedPerson.msg b/simulators/third_party/rviz_plugins/spencer_messages/spencer_tracking_msgs/msg/CompositeDetectedPerson.msg new file mode 100755 index 0000000..0c8d058 --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_messages/spencer_tracking_msgs/msg/CompositeDetectedPerson.msg @@ -0,0 +1,20 @@ +# Specifies which detected persons have been merged into a composite detection by the spencer_detected_person_association module. + +# TODO: Do we need a composite person-specific timestamp (or even a full message header including frame ID)? +# Having a separate timestamp per person could be useful if the timestamps of the merged DetectedPersons messages vary a lot, +# and some persons are only seen by a single sensor (so averaging over all input timestamps would have a detrimental effect). + +uint64 composite_detection_id # ID of the fused detection + +float64 mean_confidence # mean of the confidences of the original detections +float64 max_confidence # maximum confidence of original detections +float64 min_confidence # minimum confidence of original detections + + +geometry_msgs/PoseWithCovariance pose # Merged 3D pose (position + orientation) of the detection center + # check covariance to see which dimensions are actually set! + # unset dimensions shall have a covariance > 9999 + +DetectedPerson[] original_detections # The original detections from individual sensor-specific detectors that have been combined into a composite detection + # We are copying the entire DetectedPersons messages, *with poses transformed into the target frame*, such that subscribers + # do not have to subscribe to all the original DetectedPersons topics. \ No newline at end of file diff --git a/simulators/third_party/rviz_plugins/spencer_messages/spencer_tracking_msgs/msg/CompositeDetectedPersons.msg b/simulators/third_party/rviz_plugins/spencer_messages/spencer_tracking_msgs/msg/CompositeDetectedPersons.msg new file mode 100755 index 0000000..cb7cfe0 --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_messages/spencer_tracking_msgs/msg/CompositeDetectedPersons.msg @@ -0,0 +1,8 @@ +# Message specifying which original detected persons (from all kinds of sensors) have been merged into one fused detection before being processed by the person tracker, in the current time step. +# +# This information is processed by the spencer_detected_person_association module, such that other perception components can associate their results (e.g. person age, gender) +# with a particular spencer_tracking_msgs/TrackedPerson (which contains a reference to a composite person detection ID). + +Header header # Header timestamp is set to the *latest* timestamp of all fused DetectedPerson messages. + # Before fusion, all detections are transformed into a common coordinate frame (usually base_footprint). +CompositeDetectedPerson[] elements # Fused (merged) detected persons \ No newline at end of file diff --git a/simulators/third_party/rviz_plugins/spencer_messages/spencer_tracking_msgs/msg/DetectedPerson.msg b/simulators/third_party/rviz_plugins/spencer_messages/spencer_tracking_msgs/msg/DetectedPerson.msg new file mode 100755 index 0000000..7e646f2 --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_messages/spencer_tracking_msgs/msg/DetectedPerson.msg @@ -0,0 +1,23 @@ +# Message describing a detection of a person +# + +# Unique id of the detection, monotonically increasing over time +uint64 detection_id + +# (Pseudo-)probabilistic value between 0.0 and 1.0 describing the detector's confidence in the detection +float64 confidence + +# 3D pose (position + orientation) of the *center* of the detection +# check covariance to see which dimensions are actually set! unset dimensions shall have a covariance > 9999 +geometry_msgs/PoseWithCovariance pose + +# Sensor modality / detector type, see example constants below. +# used e.g. later in tracking to check which tracks have been visually confirmed +string modality + + +string MODALITY_GENERIC_LASER_2D = laser2d +string MODALITY_GENERIC_LASER_3D = laser3d +string MODALITY_GENERIC_MONOCULAR_VISION = mono +string MODALITY_GENERIC_STEREO_VISION = stereo +string MODALITY_GENERIC_RGBD = rgbd diff --git a/simulators/third_party/rviz_plugins/spencer_messages/spencer_tracking_msgs/msg/DetectedPersons.msg b/simulators/third_party/rviz_plugins/spencer_messages/spencer_tracking_msgs/msg/DetectedPersons.msg new file mode 100755 index 0000000..e8ec21c --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_messages/spencer_tracking_msgs/msg/DetectedPersons.msg @@ -0,0 +1,5 @@ +# Message with all currently detected persons +# + +Header header # Header containing timestamp etc. of this message +DetectedPerson[] detections # All persons that are currently being detected \ No newline at end of file diff --git a/simulators/third_party/rviz_plugins/spencer_messages/spencer_tracking_msgs/msg/ImmDebugInfo.msg b/simulators/third_party/rviz_plugins/spencer_messages/spencer_tracking_msgs/msg/ImmDebugInfo.msg new file mode 100755 index 0000000..57fbbb6 --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_messages/spencer_tracking_msgs/msg/ImmDebugInfo.msg @@ -0,0 +1,10 @@ +# Message for passing debug information of filter performance +# + +uint64 track_id # unique identifier of the target, consistent over time +float64 innovation # innovation of prediction and associated observation +float64 CpXX # variance of prediction acc. to x +float64 CpYY # variance of prediction acc. to y +float64 CXX # variance of state acc. to x +float64 CYY # variance of state acc. to y +float64[] modeProbabilities# array containing mode probabilities \ No newline at end of file diff --git a/simulators/third_party/rviz_plugins/spencer_messages/spencer_tracking_msgs/msg/ImmDebugInfos.msg b/simulators/third_party/rviz_plugins/spencer_messages/spencer_tracking_msgs/msg/ImmDebugInfos.msg new file mode 100755 index 0000000..10792ea --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_messages/spencer_tracking_msgs/msg/ImmDebugInfos.msg @@ -0,0 +1,5 @@ +# Message with all debug infos per frame +# + +Header header # Header containing timestamp etc. of this message +ImmDebugInfo[] infos # All persons that are currently being tracked \ No newline at end of file diff --git a/simulators/third_party/rviz_plugins/spencer_messages/spencer_tracking_msgs/msg/PersonTrajectory.msg b/simulators/third_party/rviz_plugins/spencer_messages/spencer_tracking_msgs/msg/PersonTrajectory.msg new file mode 100755 index 0000000..604bb00 --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_messages/spencer_tracking_msgs/msg/PersonTrajectory.msg @@ -0,0 +1,10 @@ +# Message defining the trajectory of a tracked person. +# +# The distinction between track and trajectory is that, depending on the +# implementation of the tracker, a single track (i.e. tracked person) might +# change the trajectory if at some point a new trajectory "fits" that track (person) +# better. +# + +uint64 track_id # Unique identifier of the tracked person. +PersonTrajectoryEntry[] trajectory # All states of the last T frames of the most likely trajectory of that tracked person. diff --git a/simulators/third_party/rviz_plugins/spencer_messages/spencer_tracking_msgs/msg/PersonTrajectoryEntry.msg b/simulators/third_party/rviz_plugins/spencer_messages/spencer_tracking_msgs/msg/PersonTrajectoryEntry.msg new file mode 100755 index 0000000..93a7da3 --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_messages/spencer_tracking_msgs/msg/PersonTrajectoryEntry.msg @@ -0,0 +1,11 @@ +# Message defining an entry of a person trajectory. +# + +time stamp # age of the track +bool is_occluded # if the track is currently not matched by a detection +uint64 detection_id # id of the corresponding detection in the current cycle (undefined if occluded) + +# The following fields are extracted from the Kalman state x and its covariance C + +geometry_msgs/PoseWithCovariance pose # pose of the track (z value and orientation might not be set, check if corresponding variance on diagonal is > 99999) +geometry_msgs/TwistWithCovariance twist # velocity of the track (z value and rotational velocities might not be set, check if corresponding variance on diagonal is > 99999) diff --git a/simulators/third_party/rviz_plugins/spencer_messages/spencer_tracking_msgs/msg/TrackedGroup.msg b/simulators/third_party/rviz_plugins/spencer_messages/spencer_tracking_msgs/msg/TrackedGroup.msg new file mode 100755 index 0000000..29cd536 --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_messages/spencer_tracking_msgs/msg/TrackedGroup.msg @@ -0,0 +1,10 @@ +# Message defining a tracked group +# + +uint64 group_id # unique identifier of the target, consistent over time + +duration age # age of the group + +geometry_msgs/PoseWithCovariance centerOfGravity # mean and covariance of the group (calculated from its person tracks) + +uint64[] track_ids # IDs of the tracked persons in this group. See srl_tracking_msgs/TrackedPersons \ No newline at end of file diff --git a/simulators/third_party/rviz_plugins/spencer_messages/spencer_tracking_msgs/msg/TrackedGroups.msg b/simulators/third_party/rviz_plugins/spencer_messages/spencer_tracking_msgs/msg/TrackedGroups.msg new file mode 100755 index 0000000..4117c12 --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_messages/spencer_tracking_msgs/msg/TrackedGroups.msg @@ -0,0 +1,5 @@ +# Message with all currently tracked groups +# + +Header header # Header containing timestamp etc. of this message +TrackedGroup[] groups # All groups that are currently being tracked \ No newline at end of file diff --git a/simulators/third_party/rviz_plugins/spencer_messages/spencer_tracking_msgs/msg/TrackedPerson.msg b/simulators/third_party/rviz_plugins/spencer_messages/spencer_tracking_msgs/msg/TrackedPerson.msg new file mode 100755 index 0000000..996c6c3 --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_messages/spencer_tracking_msgs/msg/TrackedPerson.msg @@ -0,0 +1,14 @@ +# Message defining a tracked person +# + +uint64 track_id # unique identifier of the target, consistent over time +bool is_occluded # if the track is currently not observable in a physical way +bool is_matched # if the track is currently matched by a detection +uint64 detection_id # id of the corresponding detection in the current cycle (undefined if occluded) +duration age # age of the track + +# The following fields are extracted from the Kalman state x and its covariance C + +geometry_msgs/PoseWithCovariance pose # pose of the track (z value and orientation might not be set, check if corresponding variance on diagonal is > 99999) + +geometry_msgs/TwistWithCovariance twist # velocity of the track (z value and rotational velocities might not be set, check if corresponding variance on diagonal is > 99999) diff --git a/simulators/third_party/rviz_plugins/spencer_messages/spencer_tracking_msgs/msg/TrackedPerson2d.msg b/simulators/third_party/rviz_plugins/spencer_messages/spencer_tracking_msgs/msg/TrackedPerson2d.msg new file mode 100755 index 0000000..4b370ec --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_messages/spencer_tracking_msgs/msg/TrackedPerson2d.msg @@ -0,0 +1,10 @@ +# Message defining a 2d image bbox of a tracked person +# + +uint64 track_id # unique identifier of the target, consistent over time +float32 person_height # 3d height of person in m +int32 x # top left corner x of 2d image bbox +int32 y # top left corner y of 2d image bbox +uint32 w # width of 2d image bbox +uint32 h # height of 2d image bbox +float32 depth # distance from the camera in m diff --git a/simulators/third_party/rviz_plugins/spencer_messages/spencer_tracking_msgs/msg/TrackedPersons.msg b/simulators/third_party/rviz_plugins/spencer_messages/spencer_tracking_msgs/msg/TrackedPersons.msg new file mode 100755 index 0000000..5c5a361 --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_messages/spencer_tracking_msgs/msg/TrackedPersons.msg @@ -0,0 +1,5 @@ +# Message with all currently tracked persons +# + +Header header # Header containing timestamp etc. of this message +TrackedPerson[] tracks # All persons that are currently being tracked \ No newline at end of file diff --git a/simulators/third_party/rviz_plugins/spencer_messages/spencer_tracking_msgs/msg/TrackedPersons2d.msg b/simulators/third_party/rviz_plugins/spencer_messages/spencer_tracking_msgs/msg/TrackedPersons2d.msg new file mode 100755 index 0000000..b800c0e --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_messages/spencer_tracking_msgs/msg/TrackedPersons2d.msg @@ -0,0 +1,5 @@ +# Message with all 2d bbox in image of currently tracked persons +# + +Header header # Header containing timestamp etc. of this message +TrackedPerson2d[] boxes # All persons that are currently being tracked (2d image bbox) diff --git a/simulators/third_party/rviz_plugins/spencer_messages/spencer_tracking_msgs/msg/TrackingTimingMetrics.msg b/simulators/third_party/rviz_plugins/spencer_messages/spencer_tracking_msgs/msg/TrackingTimingMetrics.msg new file mode 100755 index 0000000..ced3bbc --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_messages/spencer_tracking_msgs/msg/TrackingTimingMetrics.msg @@ -0,0 +1,13 @@ +# Message with timing values for analyzing the efficency +# + +Header header # Header containing timestamp etc. of this message +uint64 track_count # number of person currentl tracked +uint64 cycle_no # incremented number of cycles +float32 average_cycle_time # average time for one cycle of tracker +float32 cycle_time # cycle time of current cycle +float32 average_processing_rate # average frequency of processing data +float32 cpu_load # current cpu load +float32 average_cpu_load # average cpu load +float32 elapsed_time # elapsed seconds since start +float32 elapsed_cpu_time # elapsed cpu time since start \ No newline at end of file diff --git a/simulators/third_party/rviz_plugins/spencer_messages/spencer_tracking_msgs/package.xml b/simulators/third_party/rviz_plugins/spencer_messages/spencer_tracking_msgs/package.xml new file mode 100755 index 0000000..1f43de5 --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_messages/spencer_tracking_msgs/package.xml @@ -0,0 +1,29 @@ + + + + spencer_tracking_msgs + 1.0.8 + Messages used for Person Detection and Tracking + + Timm Linder + Stefan Breuers + Lucas Beyer + + BSD + + Timm Linder + Stefan Breuers + Lucas Beyer + + catkin + message_generation + roscpp + std_msgs + geometry_msgs + + message_runtime + roscpp + std_msgs + geometry_msgs + +roslibroslib diff --git a/simulators/third_party/rviz_plugins/spencer_messages/spencer_tracking_msgs/srv/GetPersonTrajectories.srv b/simulators/third_party/rviz_plugins/spencer_messages/spencer_tracking_msgs/srv/GetPersonTrajectories.srv new file mode 100755 index 0000000..fb3e767 --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_messages/spencer_tracking_msgs/srv/GetPersonTrajectories.srv @@ -0,0 +1,4 @@ +uint64[] requested_ids # The IDs of the tracks you are interested in getting the trajectories of. An empty array means all available tracks. +duration max_age # The maximum age of a trajectory you want to get. A duration of 0 means "since the beginning of times." +--- +PersonTrajectory[] trajectories # The trajectories of the tracks that have been asked for in requested_ids, in the same order. diff --git a/simulators/third_party/rviz_plugins/spencer_messages/spencer_vision_msgs/CHANGELOG.rst b/simulators/third_party/rviz_plugins/spencer_messages/spencer_vision_msgs/CHANGELOG.rst new file mode 100755 index 0000000..1777994 --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_messages/spencer_vision_msgs/CHANGELOG.rst @@ -0,0 +1,39 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package spencer_vision_msgs +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +1.0.8 (2017-09-22) +------------------ +* Merge pull request `#2 `_ from spencer-project/master + Integrate multiple fixes from upstream +* Specify correct license in package.xmls +* Merge pull request `#41 `_ from LCAS/master + 1.0.7 +* Contributors: Marc Hanheide, Timm Linder + +1.0.7 (2017-06-09) +------------------ + +1.0.6 (2017-06-09) +------------------ + +1.0.5 (2017-05-12) +------------------ + +1.0.4 (2017-05-12) +------------------ + +1.0.3 (2017-05-11) +------------------ + +1.0.2 (2017-05-09) +------------------ +* added missing roslib deps +* Contributors: Marc Hanheide + +1.0.1 (2017-05-09) +------------------ +* homogenised all version strings to 1.0.0 +* Updated licenses +* Adding message definitions, RViz plugins and mock scripts +* Contributors: Marc Hanheide, Timm Linder diff --git a/simulators/third_party/rviz_plugins/spencer_messages/spencer_vision_msgs/CMakeLists.txt b/simulators/third_party/rviz_plugins/spencer_messages/spencer_vision_msgs/CMakeLists.txt new file mode 100755 index 0000000..79a25a8 --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_messages/spencer_vision_msgs/CMakeLists.txt @@ -0,0 +1,44 @@ +cmake_minimum_required(VERSION 2.8.3) +project(spencer_vision_msgs) + +find_package(catkin REQUIRED COMPONENTS + roscpp + roslib + std_msgs + sensor_msgs + geometry_msgs + message_generation +) + +################################################ +## Declare ROS messages, services and actions ## +################################################ + +# Generate messages in the 'msg' folder +add_message_files( + FILES + PersonImage.msg + PersonImages.msg + PersonROI.msg + PersonROIs.msg +) + +# Generate services in the 'srv' folder +#add_service_files( +# FILES +#) + +## Generate added messages and services with any dependencies listed here +generate_messages( + DEPENDENCIES + geometry_msgs + sensor_msgs + std_msgs +) + +################################### +## catkin specific configuration ## +################################### +catkin_package( + CATKIN_DEPENDS roscpp std_msgs sensor_msgs geometry_msgs message_runtime +) diff --git a/simulators/third_party/rviz_plugins/spencer_messages/spencer_vision_msgs/LICENSE b/simulators/third_party/rviz_plugins/spencer_messages/spencer_vision_msgs/LICENSE new file mode 100755 index 0000000..98f9a8a --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_messages/spencer_vision_msgs/LICENSE @@ -0,0 +1,29 @@ +Software License Agreement (BSD License) + +Copyright (c) 2013-2015 Timm Linder, Social Robotics Laboratory, University of Freiburg +Copyright (c) 2014-2015 Stefan Breuers, Lucas Beyer, Computer Vision Group, RWTH Aachen University +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name of the copyright holder nor the names of its contributors + may be used to endorse or promote products derived from this software + without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE \ No newline at end of file diff --git a/simulators/third_party/rviz_plugins/spencer_messages/spencer_vision_msgs/msg/PersonImage.msg b/simulators/third_party/rviz_plugins/spencer_messages/spencer_vision_msgs/msg/PersonImage.msg new file mode 100755 index 0000000..b64a80b --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_messages/spencer_vision_msgs/msg/PersonImage.msg @@ -0,0 +1,6 @@ +# Message describing a depth or RGB image containing a part of a person (e.g. head, face, full body...), which is usually encoded in the topic title +# + +uint64 detection_id +sensor_msgs/Image image + diff --git a/simulators/third_party/rviz_plugins/spencer_messages/spencer_vision_msgs/msg/PersonImages.msg b/simulators/third_party/rviz_plugins/spencer_messages/spencer_vision_msgs/msg/PersonImages.msg new file mode 100755 index 0000000..7cb3163 --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_messages/spencer_vision_msgs/msg/PersonImages.msg @@ -0,0 +1,5 @@ +# Message describing an array of depth or RGB images containing a part of a person (e.g. head, face, full body...), which is usually encoded in the topic title +# + +std_msgs/Header header +PersonImage[] elements diff --git a/simulators/third_party/rviz_plugins/spencer_messages/spencer_vision_msgs/msg/PersonROI.msg b/simulators/third_party/rviz_plugins/spencer_messages/spencer_vision_msgs/msg/PersonROI.msg new file mode 100755 index 0000000..f48e921 --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_messages/spencer_vision_msgs/msg/PersonROI.msg @@ -0,0 +1,7 @@ +# Message describing a rectangular region of interest in a depth or RGB image containing a part of a person (e.g. head, face, full body...), which is usually encoded in the topic title +# + +uint64 detection_id + +sensor_msgs/RegionOfInterest roi + diff --git a/simulators/third_party/rviz_plugins/spencer_messages/spencer_vision_msgs/msg/PersonROIs.msg b/simulators/third_party/rviz_plugins/spencer_messages/spencer_vision_msgs/msg/PersonROIs.msg new file mode 100755 index 0000000..6b197aa --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_messages/spencer_vision_msgs/msg/PersonROIs.msg @@ -0,0 +1,9 @@ +# Message describing an array of rectangular regions of interest in a depth or RGB image containing a part of a person (e.g. head, face, full body...), which is usually encoded in the topic title +# + +std_msgs/Header header + +string rgb_topic # not necessarily the raw camera output; might be preprocessed for rectification etc. +string depth_topic # might not be set if depth is not available, otherwise it is the registered depth image + +PersonROI[] elements diff --git a/simulators/third_party/rviz_plugins/spencer_messages/spencer_vision_msgs/package.xml b/simulators/third_party/rviz_plugins/spencer_messages/spencer_vision_msgs/package.xml new file mode 100755 index 0000000..fb01455 --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_messages/spencer_vision_msgs/package.xml @@ -0,0 +1,31 @@ + + + + spencer_vision_msgs + 1.0.8 + Messages used for Vision-related tasks in SPENCER + + Lucas Beyer + Stefan Breuers + Timm Linder + + BSD + + Timm Linder + Stefan Breuers + Lucas Beyer + + catkin + message_generation + roscpp + std_msgs + geometry_msgs + sensor_msgs + + message_runtime + roscpp + std_msgs + geometry_msgs + sensor_msgs + +roslibroslib diff --git a/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/.gitignore b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/.gitignore new file mode 100755 index 0000000..259148f --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/.gitignore @@ -0,0 +1,32 @@ +# Prerequisites +*.d + +# Compiled Object files +*.slo +*.lo +*.o +*.obj + +# Precompiled Headers +*.gch +*.pch + +# Compiled Dynamic libraries +*.so +*.dylib +*.dll + +# Fortran module files +*.mod +*.smod + +# Compiled Static libraries +*.lai +*.la +*.a +*.lib + +# Executables +*.exe +*.out +*.app diff --git a/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/CMakeLists.txt b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/CMakeLists.txt new file mode 100755 index 0000000..5b259ec --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/CMakeLists.txt @@ -0,0 +1,116 @@ +# Software License Agreement (BSD License) +# +# Copyright (c) 2013-2015, Timm Linder, Social Robotics Lab, University of Freiburg +# Copyright (c) 2012, Willow Garage, Inc. +# All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions are met: +# +# * Redistributions of source code must retain the above copyright notice, this +# list of conditions and the following disclaimer. +# * Redistributions in binary form must reproduce the above copyright notice, +# this list of conditions and the following disclaimer in the documentation +# and/or other materials provided with the distribution. +# * Neither the name of the copyright holder nor the names of its contributors +# may be used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +# DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +# FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +# DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +# SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +# OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +# OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + + +cmake_minimum_required(VERSION 2.8.3) +project(spencer_tracking_rviz_plugin) + +find_package(catkin REQUIRED COMPONENTS rviz spencer_tracking_msgs spencer_human_attribute_msgs spencer_social_relation_msgs) +catkin_package() +include_directories(${catkin_INCLUDE_DIRS}) +link_directories(${catkin_LIBRARY_DIRS}) + + + +## This plugin includes Qt widgets, so we must include Qt. +## We'll use the version that rviz used so they are compatible. +if(rviz_QT_VERSION VERSION_LESS "5") + message(STATUS "Using Qt4 based on the rviz_QT_VERSION: ${rviz_QT_VERSION}") + find_package(Qt4 ${rviz_QT_VERSION} EXACT REQUIRED QtCore QtGui) + ## pull in all required include dirs, define QT_LIBRARIES, etc. + include(${QT_USE_FILE}) + qt4_wrap_cpp(MOC_FILES + src/detected_persons_display.h + src/tracked_persons_display.h + src/tracked_groups_display.h + src/social_relations_display.h + src/social_activities_display.h + src/human_attributes_display.h + src/person_display_common.h + src/additional_topic_subscriber.h +) +else() + message(STATUS "Using Qt5 based on the rviz_QT_VERSION: ${rviz_QT_VERSION}") + find_package(Qt5 ${rviz_QT_VERSION} EXACT REQUIRED Core Widgets) + ## make target_link_libraries(${QT_LIBRARIES}) pull in all required dependencies + set(QT_LIBRARIES Qt5::Widgets) + qt5_wrap_cpp(MOC_FILES + src/detected_persons_display.h + src/tracked_persons_display.h + src/tracked_groups_display.h + src/social_relations_display.h + src/social_activities_display.h + src/human_attributes_display.h + src/person_display_common.h + src/additional_topic_subscriber.h +) +endif() + +add_definitions(-DQT_NO_KEYWORDS) + + + +set(SOURCE_FILES + src/detected_persons_display.cpp + src/tracked_persons_display.cpp + src/tracked_groups_display.cpp + src/social_relations_display.cpp + src/social_activities_display.cpp + src/human_attributes_display.cpp + src/person_display_common.cpp + src/tracked_persons_cache.cpp + src/visuals/person_visual.cpp + ${MOC_FILES} +) + + +add_library(${PROJECT_NAME} ${SOURCE_FILES}) +add_dependencies(${PROJECT_NAME} ${catkin_EXPORTED_TARGETS}) # for generation of message dependencies +target_link_libraries(${PROJECT_NAME} ${QT_LIBRARIES} ${catkin_LIBRARIES}) + + +install(TARGETS + ${PROJECT_NAME} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) + +install(FILES + plugin_description.xml + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) + +install(DIRECTORY media/ + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/media) + +install(DIRECTORY icons/ + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/icons) + +install(PROGRAMS scripts/send_test_msgs.py + DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) diff --git a/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/icons/classes/DetectedPersons.png b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/icons/classes/DetectedPersons.png new file mode 100755 index 0000000..84b9ccc Binary files /dev/null and b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/icons/classes/DetectedPersons.png differ diff --git a/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/icons/classes/HumanAttributes.png b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/icons/classes/HumanAttributes.png new file mode 100755 index 0000000..b8873ea Binary files /dev/null and b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/icons/classes/HumanAttributes.png differ diff --git a/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/icons/classes/SocialActivities.png b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/icons/classes/SocialActivities.png new file mode 100755 index 0000000..66eb0b1 Binary files /dev/null and b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/icons/classes/SocialActivities.png differ diff --git a/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/icons/classes/SocialRelations.png b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/icons/classes/SocialRelations.png new file mode 100755 index 0000000..fae1feb Binary files /dev/null and b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/icons/classes/SocialRelations.png differ diff --git a/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/icons/classes/TrackedGroups.png b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/icons/classes/TrackedGroups.png new file mode 100755 index 0000000..8c32dab Binary files /dev/null and b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/icons/classes/TrackedGroups.png differ diff --git a/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/icons/classes/TrackedPersons.png b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/icons/classes/TrackedPersons.png new file mode 100755 index 0000000..6e8cb7d Binary files /dev/null and b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/icons/classes/TrackedPersons.png differ diff --git a/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/media/animated_walking_man.mesh b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/media/animated_walking_man.mesh new file mode 100755 index 0000000..a9f8ec9 Binary files /dev/null and b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/media/animated_walking_man.mesh differ diff --git a/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/media/animated_walking_man.skeleton b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/media/animated_walking_man.skeleton new file mode 100755 index 0000000..f07386f Binary files /dev/null and b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/media/animated_walking_man.skeleton differ diff --git a/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/media/female_symbol.dae b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/media/female_symbol.dae new file mode 100755 index 0000000..67ab4ed --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/media/female_symbol.dae @@ -0,0 +1,1817 @@ + + + Z_UP + + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 0.000000 1.000000 1.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + +20.843750 19.600000 0.000000 +3.714062 19.600000 0.000000 +3.714062 23.120314 0.000000 +5.246523 23.503572 0.000000 +6.699265 24.002457 0.000000 +8.072289 24.616966 0.000000 +9.365592 25.347097 0.000000 +10.579176 26.192860 0.000000 +11.713041 27.154243 0.000000 +12.767185 28.231251 0.000000 +13.743845 29.450035 0.000000 +14.570248 30.726021 0.000000 +15.246396 32.059216 0.000000 +15.772289 33.449619 0.000000 +16.147928 34.897228 0.000000 +16.373310 36.402042 0.000000 +16.448437 37.964062 0.000000 +16.350063 39.814190 0.000000 +16.054941 41.569927 0.000000 +15.563073 43.231281 0.000000 +14.874457 44.798248 0.000000 +13.989096 46.270828 0.000000 +12.906984 47.649014 0.000000 +11.628124 48.932812 0.000000 +10.256124 50.038391 0.000000 +8.801722 50.973885 0.000000 +7.264925 51.739285 0.000000 +5.645729 52.334602 0.000000 +3.944134 52.759827 0.000000 +2.160141 53.014965 0.000000 +0.293751 53.100002 0.000000 +-1.587371 53.016968 0.000000 +-3.378061 52.767853 0.000000 +-5.078317 52.352676 0.000000 +-6.688138 51.771431 0.000000 +-8.207527 51.024117 0.000000 +-9.636481 50.110722 0.000000 +-10.975000 49.031250 0.000000 +-12.245153 47.761131 0.000000 +-13.319898 46.387375 0.000000 +-14.199234 44.909985 0.000000 +-14.883162 43.328953 0.000000 +-15.371685 41.644299 0.000000 +-15.664798 39.855999 0.000000 +-15.762501 37.964062 0.000000 +-15.694038 36.455837 0.000000 +-15.488647 35.000793 0.000000 +-15.146334 33.598946 0.000000 +-14.667093 32.250286 0.000000 +-14.050928 30.954817 0.000000 +-13.297833 29.712536 0.000000 +-12.407814 28.523438 0.000000 +-11.438203 27.468559 0.000000 +-10.390083 26.517315 0.000000 +-9.263457 25.669708 0.000000 +-8.058324 24.925734 0.000000 +-6.774683 24.285398 0.000000 +-5.412533 23.748697 0.000000 +-3.971876 23.315626 0.000000 +-3.971876 19.600000 0.000000 +-20.843750 19.600000 0.000000 +-20.843750 12.900001 0.000000 +-3.971876 12.900001 0.000000 +-3.971876 -5.565625 0.000000 +3.714062 -5.565625 0.000000 +3.714062 12.900001 0.000000 +20.843750 12.900001 0.000000 +20.843750 19.600000 5.905512 +3.714062 19.600000 5.905512 +3.714062 23.120314 5.905512 +5.246523 23.503572 5.905512 +6.699265 24.002457 5.905512 +8.072289 24.616966 5.905512 +9.365592 25.347097 5.905512 +10.579176 26.192860 5.905512 +11.713041 27.154243 5.905512 +12.767185 28.231251 5.905512 +13.743845 29.450035 5.905512 +14.570248 30.726021 5.905512 +15.246396 32.059216 5.905512 +15.772289 33.449619 5.905512 +16.147928 34.897228 5.905512 +16.373310 36.402042 5.905512 +16.448437 37.964062 5.905512 +16.350063 39.814190 5.905512 +16.054941 41.569927 5.905512 +15.563073 43.231281 5.905512 +14.874457 44.798248 5.905512 +13.989096 46.270828 5.905512 +12.906984 47.649014 5.905512 +11.628124 48.932812 5.905512 +10.256124 50.038391 5.905512 +8.801722 50.973885 5.905512 +7.264925 51.739285 5.905512 +5.645729 52.334602 5.905512 +3.944134 52.759827 5.905512 +2.160141 53.014965 5.905512 +0.293751 53.100002 5.905512 +-1.587371 53.016968 5.905512 +-3.378061 52.767853 5.905512 +-5.078317 52.352676 5.905512 +-6.688138 51.771431 5.905512 +-8.207527 51.024117 5.905512 +-9.636481 50.110722 5.905512 +-10.975000 49.031250 5.905512 +-12.245153 47.761131 5.905512 +-13.319898 46.387375 5.905512 +-14.199234 44.909985 5.905512 +-14.883162 43.328953 5.905512 +-15.371685 41.644299 5.905512 +-15.664798 39.855999 5.905512 +-15.762501 37.964062 5.905512 +-15.694038 36.455837 5.905512 +-15.488647 35.000793 5.905512 +-15.146334 33.598946 5.905512 +-14.667093 32.250286 5.905512 +-14.050928 30.954817 5.905512 +-13.297833 29.712536 5.905512 +-12.407814 28.523438 5.905512 +-11.438203 27.468559 5.905512 +-10.390083 26.517315 5.905512 +-9.263457 25.669708 5.905512 +-8.058324 24.925734 5.905512 +-6.774683 24.285398 5.905512 +-5.412533 23.748697 5.905512 +-3.971876 23.315626 5.905512 +-3.971876 19.600000 5.905512 +-20.843750 19.600000 5.905512 +-20.843750 12.900001 5.905512 +-3.971876 12.900001 5.905512 +-3.971876 -5.565625 5.905512 +3.714062 -5.565625 5.905512 +3.714062 12.900001 5.905512 +20.843750 12.900001 5.905512 +8.582062 37.066360 0.000000 +8.434502 36.127934 0.000000 +8.188567 35.234726 0.000000 +7.844260 34.386734 0.000000 +7.401578 33.583965 0.000000 +6.860522 32.826401 0.000000 +6.221092 32.114063 0.000000 +5.509885 31.473598 0.000000 +4.753491 30.931664 0.000000 +3.951913 30.488266 0.000000 +3.105150 30.143400 0.000000 +2.213202 29.897070 0.000000 +1.276069 29.749269 0.000000 +0.293751 29.700001 0.000000 +-0.679527 29.749268 0.000000 +-1.608291 29.897066 0.000000 +-2.492538 30.143398 0.000000 +-3.332271 30.488270 0.000000 +-4.127489 30.931669 0.000000 +-4.878190 31.473598 0.000000 +-5.584375 32.114063 0.000000 +-6.219452 32.826405 0.000000 +-6.756824 33.583958 0.000000 +-7.196493 34.386734 0.000000 +-7.538457 35.234726 0.000000 +-7.782718 36.127937 0.000000 +-7.929275 37.066360 0.000000 +-7.978127 38.049999 0.000000 +-7.929275 39.034042 0.000000 +-7.782718 39.972767 0.000000 +-7.538457 40.866184 0.000000 +-7.196493 41.714287 0.000000 +-6.756825 42.517082 0.000000 +-6.219452 43.274555 0.000000 +-5.584375 43.986721 0.000000 +-4.878190 44.626980 0.000000 +-4.127488 45.168736 0.000000 +-3.332271 45.611992 0.000000 +-2.492539 45.956745 0.000000 +-1.608291 46.203003 0.000000 +-0.679528 46.350758 0.000000 +0.293751 46.400002 0.000000 +1.276068 46.350754 0.000000 +2.213202 46.202995 0.000000 +3.105150 45.956745 0.000000 +3.951913 45.611996 0.000000 +4.753491 45.168739 0.000000 +5.509884 44.626980 0.000000 +6.221092 43.986721 0.000000 +6.860522 43.274555 0.000000 +7.401578 42.517075 0.000000 +7.844260 41.714287 0.000000 +8.188568 40.866184 0.000000 +8.434502 39.972771 0.000000 +8.582062 39.034042 0.000000 +8.631248 38.049999 0.000000 +8.582062 37.066360 5.905512 +8.434502 36.127934 5.905512 +8.188567 35.234726 5.905512 +7.844260 34.386734 5.905512 +7.401578 33.583965 5.905512 +6.860522 32.826401 5.905512 +6.221092 32.114063 5.905512 +5.509885 31.473598 5.905512 +4.753491 30.931664 5.905512 +3.951913 30.488266 5.905512 +3.105150 30.143400 5.905512 +2.213202 29.897070 5.905512 +1.276069 29.749269 5.905512 +0.293751 29.700001 5.905512 +-0.679527 29.749268 5.905512 +-1.608291 29.897066 5.905512 +-2.492538 30.143398 5.905512 +-3.332271 30.488270 5.905512 +-4.127489 30.931669 5.905512 +-4.878190 31.473598 5.905512 +-5.584375 32.114063 5.905512 +-6.219452 32.826405 5.905512 +-6.756824 33.583958 5.905512 +-7.196493 34.386734 5.905512 +-7.538457 35.234726 5.905512 +-7.782718 36.127937 5.905512 +-7.929275 37.066360 5.905512 +-7.978127 38.049999 5.905512 +-7.929275 39.034042 5.905512 +-7.782718 39.972767 5.905512 +-7.538457 40.866184 5.905512 +-7.196493 41.714287 5.905512 +-6.756825 42.517082 5.905512 +-6.219452 43.274555 5.905512 +-5.584375 43.986721 5.905512 +-4.878190 44.626980 5.905512 +-4.127488 45.168736 5.905512 +-3.332271 45.611992 5.905512 +-2.492539 45.956745 5.905512 +-1.608291 46.203003 5.905512 +-0.679528 46.350758 5.905512 +0.293751 46.400002 5.905512 +1.276068 46.350754 5.905512 +2.213202 46.202995 5.905512 +3.105150 45.956745 5.905512 +3.951913 45.611996 5.905512 +4.753491 45.168739 5.905512 +5.509884 44.626980 5.905512 +6.221092 43.986721 5.905512 +6.860522 43.274555 5.905512 +7.401578 42.517075 5.905512 +7.844260 41.714287 5.905512 +8.188568 40.866184 5.905512 +8.434502 39.972771 5.905512 +8.582062 39.034042 5.905512 +8.631248 38.049999 5.905512 + + + + + + + + + + + +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.242621 -0.970121 0.000000 +0.283967 -0.958834 0.000000 +0.283967 -0.958834 0.000000 +0.242621 -0.970121 0.000000 +0.283967 -0.958834 0.000000 +0.242621 -0.970121 0.000000 +0.283967 -0.958834 0.000000 +0.367023 -0.930212 0.000000 +0.367023 -0.930212 0.000000 +0.283967 -0.958834 0.000000 +0.367023 -0.930212 0.000000 +0.283967 -0.958834 0.000000 +0.367023 -0.930212 0.000000 +0.450552 -0.892750 0.000000 +0.450551 -0.892750 0.000000 +0.367023 -0.930212 0.000000 +0.450551 -0.892750 0.000000 +0.367023 -0.930212 0.000000 +0.450552 -0.892750 0.000000 +0.532285 -0.846565 0.000000 +0.532285 -0.846565 0.000000 +0.450552 -0.892750 0.000000 +0.532285 -0.846565 0.000000 +0.450551 -0.892750 0.000000 +0.532285 -0.846565 0.000000 +0.609918 -0.792465 0.000000 +0.609918 -0.792465 0.000000 +0.532285 -0.846565 0.000000 +0.609918 -0.792465 0.000000 +0.532285 -0.846565 0.000000 +0.609918 -0.792465 0.000000 +0.681415 -0.731897 0.000000 +0.681415 -0.731897 0.000000 +0.609918 -0.792465 0.000000 +0.681415 -0.731897 0.000000 +0.609918 -0.792465 0.000000 +0.681415 -0.731897 0.000000 +0.748424 -0.663221 0.000000 +0.748424 -0.663220 0.000000 +0.681415 -0.731897 0.000000 +0.748424 -0.663220 0.000000 +0.681415 -0.731897 0.000000 +0.748424 -0.663221 0.000000 +0.810880 -0.585212 0.000000 +0.810880 -0.585213 0.000000 +0.748424 -0.663221 0.000000 +0.810880 -0.585213 0.000000 +0.748424 -0.663220 0.000000 +0.810880 -0.585212 0.000000 +0.866801 -0.498654 0.000000 +0.866801 -0.498654 0.000000 +0.810880 -0.585212 0.000000 +0.866801 -0.498654 0.000000 +0.810880 -0.585213 0.000000 +0.866801 -0.498654 0.000000 +0.914922 -0.403630 0.000000 +0.914922 -0.403630 0.000000 +0.866801 -0.498654 0.000000 +0.914922 -0.403630 0.000000 +0.866801 -0.498654 0.000000 +0.914922 -0.403630 0.000000 +0.953019 -0.302910 0.000000 +0.953019 -0.302910 0.000000 +0.914922 -0.403630 0.000000 +0.953019 -0.302910 0.000000 +0.914922 -0.403630 0.000000 +0.953019 -0.302910 0.000000 +0.979812 -0.199923 0.000000 +0.979812 -0.199923 0.000000 +0.953019 -0.302910 0.000000 +0.979812 -0.199923 0.000000 +0.953019 -0.302910 0.000000 +0.979812 -0.199923 0.000000 +0.995166 -0.098205 0.000000 +0.995166 -0.098205 0.000000 +0.979812 -0.199923 0.000000 +0.995166 -0.098205 0.000000 +0.979812 -0.199923 0.000000 +0.995166 -0.098205 0.000000 +0.999997 0.002531 0.000000 +0.999997 0.002531 0.000000 +0.995166 -0.098205 0.000000 +0.999997 0.002531 0.000000 +0.995166 -0.098205 0.000000 +0.999997 0.002531 0.000000 +0.993975 0.109607 0.000000 +0.993975 0.109607 0.000000 +0.999997 0.002531 0.000000 +0.993975 0.109607 0.000000 +0.999997 0.002531 0.000000 +0.993975 0.109607 0.000000 +0.974304 0.225239 0.000000 +0.974304 0.225239 0.000000 +0.993975 0.109607 0.000000 +0.974304 0.225239 0.000000 +0.993975 0.109607 0.000000 +0.974304 0.225239 0.000000 +0.939047 0.343788 0.000000 +0.939047 0.343788 0.000000 +0.974304 0.225239 0.000000 +0.939047 0.343788 0.000000 +0.974304 0.225239 0.000000 +0.939047 0.343788 0.000000 +0.888060 0.459728 0.000000 +0.888060 0.459728 0.000000 +0.939047 0.343788 0.000000 +0.888060 0.459728 0.000000 +0.939047 0.343788 0.000000 +0.888060 0.459728 0.000000 +0.823366 0.567510 0.000000 +0.823366 0.567510 0.000000 +0.888060 0.459728 0.000000 +0.823366 0.567510 0.000000 +0.888060 0.459728 0.000000 +0.823366 0.567510 0.000000 +0.748796 0.662800 0.000000 +0.748796 0.662800 0.000000 +0.823366 0.567510 0.000000 +0.748796 0.662800 0.000000 +0.823366 0.567510 0.000000 +0.748796 0.662800 0.000000 +0.668954 0.743303 0.000000 +0.668954 0.743303 0.000000 +0.748796 0.662800 0.000000 +0.668954 0.743303 0.000000 +0.748796 0.662800 0.000000 +0.668954 0.743303 0.000000 +0.585044 0.811002 0.000000 +0.585044 0.811002 0.000000 +0.668954 0.743303 0.000000 +0.585044 0.811002 0.000000 +0.668954 0.743303 0.000000 +0.585044 0.811002 0.000000 +0.494134 0.869386 0.000000 +0.494134 0.869386 0.000000 +0.585044 0.811002 0.000000 +0.494134 0.869386 0.000000 +0.585044 0.811002 0.000000 +0.494134 0.869386 0.000000 +0.396043 0.918232 0.000000 +0.396044 0.918232 0.000000 +0.494134 0.869386 0.000000 +0.396044 0.918232 0.000000 +0.494134 0.869386 0.000000 +0.396043 0.918232 0.000000 +0.294185 0.955749 0.000000 +0.294185 0.955749 0.000000 +0.396043 0.918232 0.000000 +0.294185 0.955749 0.000000 +0.396044 0.918232 0.000000 +0.294185 0.955749 0.000000 +0.192263 0.981344 0.000000 +0.192263 0.981343 0.000000 +0.294185 0.955749 0.000000 +0.192263 0.981343 0.000000 +0.294185 0.955749 0.000000 +0.192263 0.981344 0.000000 +0.093654 0.995605 0.000000 +0.093654 0.995605 0.000000 +0.192263 0.981344 0.000000 +0.093654 0.995605 0.000000 +0.192263 0.981343 0.000000 +0.093654 0.995605 0.000000 +0.000709 1.000000 0.000000 +0.000709 1.000000 0.000000 +0.093654 0.995605 0.000000 +0.000709 1.000000 0.000000 +0.093654 0.995605 0.000000 +0.000709 1.000000 0.000000 +-0.091045 0.995847 0.000000 +-0.091045 0.995847 0.000000 +0.000709 1.000000 0.000000 +-0.091045 0.995847 0.000000 +0.000709 1.000000 0.000000 +-0.091045 0.995847 0.000000 +-0.187743 0.982218 0.000000 +-0.187743 0.982218 0.000000 +-0.091045 0.995847 0.000000 +-0.187743 0.982218 0.000000 +-0.091045 0.995847 0.000000 +-0.187743 0.982218 0.000000 +-0.288823 0.957383 0.000000 +-0.288823 0.957383 0.000000 +-0.187743 0.982218 0.000000 +-0.288823 0.957383 0.000000 +-0.187743 0.982218 0.000000 +-0.288823 0.957383 0.000000 +-0.391077 0.920358 0.000000 +-0.391077 0.920358 0.000000 +-0.288823 0.957383 0.000000 +-0.391077 0.920358 0.000000 +-0.288823 0.957383 0.000000 +-0.391077 0.920358 0.000000 +-0.490731 0.871311 0.000000 +-0.490731 0.871311 0.000000 +-0.391077 0.920358 0.000000 +-0.490731 0.871311 0.000000 +-0.391077 0.920358 0.000000 +-0.490731 0.871311 0.000000 +-0.584051 0.811717 0.000000 +-0.584051 0.811717 0.000000 +-0.490731 0.871311 0.000000 +-0.584051 0.811717 0.000000 +-0.490731 0.871311 0.000000 +-0.584051 0.811717 0.000000 +-0.668380 0.743820 0.000000 +-0.668380 0.743820 0.000000 +-0.584051 0.811717 0.000000 +-0.668380 0.743820 0.000000 +-0.584051 0.811717 0.000000 +-0.668380 0.743820 0.000000 +-0.748734 0.662870 0.000000 +-0.748734 0.662870 0.000000 +-0.668380 0.743820 0.000000 +-0.748734 0.662870 0.000000 +-0.668380 0.743820 0.000000 +-0.748734 0.662870 0.000000 +-0.825121 0.564956 0.000000 +-0.825121 0.564956 0.000000 +-0.748734 0.662870 0.000000 +-0.825121 0.564956 0.000000 +-0.748734 0.662870 0.000000 +-0.825121 0.564956 0.000000 +-0.890398 0.455183 0.000000 +-0.890398 0.455183 0.000000 +-0.825121 0.564956 0.000000 +-0.890398 0.455183 0.000000 +-0.825121 0.564956 0.000000 +-0.890398 0.455183 0.000000 +-0.940988 0.338441 0.000000 +-0.940988 0.338441 0.000000 +-0.890398 0.455183 0.000000 +-0.940988 0.338441 0.000000 +-0.890398 0.455183 0.000000 +-0.940988 0.338441 0.000000 +-0.975381 0.220524 0.000000 +-0.975381 0.220524 0.000000 +-0.940988 0.338441 0.000000 +-0.975381 0.220524 0.000000 +-0.940988 0.338441 0.000000 +-0.975381 0.220524 0.000000 +-0.994278 0.106824 0.000000 +-0.994278 0.106824 0.000000 +-0.975381 0.220524 0.000000 +-0.994278 0.106824 0.000000 +-0.975381 0.220524 0.000000 +-0.994278 0.106824 0.000000 +-0.999995 0.003117 0.000000 +-0.999995 0.003117 0.000000 +-0.994278 0.106824 0.000000 +-0.999995 0.003117 0.000000 +-0.994278 0.106824 0.000000 +-0.999995 0.003117 0.000000 +-0.995698 -0.092663 0.000000 +-0.995698 -0.092663 0.000000 +-0.999995 0.003117 0.000000 +-0.995698 -0.092663 0.000000 +-0.999995 0.003117 0.000000 +-0.995698 -0.092663 0.000000 +-0.982030 -0.188727 0.000000 +-0.982030 -0.188727 0.000000 +-0.995698 -0.092663 0.000000 +-0.982030 -0.188727 0.000000 +-0.995698 -0.092663 0.000000 +-0.982030 -0.188727 0.000000 +-0.958111 -0.286398 0.000000 +-0.958111 -0.286398 0.000000 +-0.982030 -0.188727 0.000000 +-0.958111 -0.286398 0.000000 +-0.982030 -0.188727 0.000000 +-0.958111 -0.286398 0.000000 +-0.923881 -0.382681 0.000000 +-0.923881 -0.382681 0.000000 +-0.958111 -0.286398 0.000000 +-0.923881 -0.382681 0.000000 +-0.958111 -0.286398 0.000000 +-0.923881 -0.382681 0.000000 +-0.880220 -0.474566 0.000000 +-0.880220 -0.474566 0.000000 +-0.923881 -0.382681 0.000000 +-0.880220 -0.474566 0.000000 +-0.923881 -0.382681 0.000000 +-0.880220 -0.474566 0.000000 +-0.828846 -0.559477 0.000000 +-0.828846 -0.559477 0.000000 +-0.880220 -0.474566 0.000000 +-0.828846 -0.559477 0.000000 +-0.880220 -0.474566 0.000000 +-0.828846 -0.559477 0.000000 +-0.769386 -0.638784 0.000000 +-0.769386 -0.638784 0.000000 +-0.828846 -0.559477 0.000000 +-0.769386 -0.638784 0.000000 +-0.828846 -0.559477 0.000000 +-0.769386 -0.638784 0.000000 +-0.704868 -0.709338 0.000000 +-0.704868 -0.709338 0.000000 +-0.769386 -0.638784 0.000000 +-0.704868 -0.709338 0.000000 +-0.769386 -0.638784 0.000000 +-0.704868 -0.709338 0.000000 +-0.637301 -0.770615 0.000000 +-0.637301 -0.770615 0.000000 +-0.704868 -0.709338 0.000000 +-0.637301 -0.770615 0.000000 +-0.704868 -0.709338 0.000000 +-0.637301 -0.770615 0.000000 +-0.563845 -0.825881 0.000000 +-0.563845 -0.825881 0.000000 +-0.637301 -0.770615 0.000000 +-0.563845 -0.825881 0.000000 +-0.637301 -0.770615 0.000000 +-0.563845 -0.825881 0.000000 +-0.486340 -0.873770 0.000000 +-0.486340 -0.873770 0.000000 +-0.563845 -0.825881 0.000000 +-0.486340 -0.873770 0.000000 +-0.563845 -0.825881 0.000000 +-0.486340 -0.873770 0.000000 +-0.406872 -0.913485 0.000000 +-0.406872 -0.913485 0.000000 +-0.486340 -0.873770 0.000000 +-0.406872 -0.913485 0.000000 +-0.486340 -0.873770 0.000000 +-0.406872 -0.913485 0.000000 +-0.327515 -0.944846 0.000000 +-0.327515 -0.944846 0.000000 +-0.406872 -0.913485 0.000000 +-0.327515 -0.944846 0.000000 +-0.406872 -0.913485 0.000000 +-0.327515 -0.944846 0.000000 +-0.287881 -0.957666 0.000000 +-0.287881 -0.957666 0.000000 +-0.327515 -0.944846 0.000000 +-0.287881 -0.957666 0.000000 +-0.327515 -0.944846 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.994704 0.102782 0.000000 +-0.977544 0.210731 0.000000 +-0.977544 0.210731 0.000000 +-0.994704 0.102782 0.000000 +-0.977544 0.210731 0.000000 +-0.994704 0.102782 0.000000 +-0.977544 0.210731 0.000000 +-0.946951 0.321379 0.000000 +-0.946951 0.321379 0.000000 +-0.977544 0.210731 0.000000 +-0.946951 0.321379 0.000000 +-0.977544 0.210731 0.000000 +-0.946951 0.321379 0.000000 +-0.902688 0.430296 0.000000 +-0.902688 0.430296 0.000000 +-0.946951 0.321379 0.000000 +-0.902688 0.430296 0.000000 +-0.946951 0.321379 0.000000 +-0.902688 0.430296 0.000000 +-0.846152 0.532942 0.000000 +-0.846152 0.532942 0.000000 +-0.902688 0.430296 0.000000 +-0.846152 0.532942 0.000000 +-0.902688 0.430296 0.000000 +-0.846152 0.532942 0.000000 +-0.780172 0.625565 0.000000 +-0.780172 0.625565 0.000000 +-0.846152 0.532942 0.000000 +-0.780172 0.625565 0.000000 +-0.846152 0.532942 0.000000 +-0.780172 0.625565 0.000000 +-0.707670 0.706543 0.000000 +-0.707670 0.706543 0.000000 +-0.780172 0.625565 0.000000 +-0.707670 0.706543 0.000000 +-0.780172 0.625565 0.000000 +-0.707670 0.706543 0.000000 +-0.626771 0.779204 0.000000 +-0.626771 0.779203 0.000000 +-0.707670 0.706543 0.000000 +-0.626771 0.779203 0.000000 +-0.707670 0.706543 0.000000 +-0.626771 0.779204 0.000000 +-0.534131 0.845402 0.000000 +-0.534131 0.845402 0.000000 +-0.626771 0.779204 0.000000 +-0.534131 0.845402 0.000000 +-0.626771 0.779203 0.000000 +-0.534131 0.845402 0.000000 +-0.431372 0.902174 0.000000 +-0.431372 0.902174 0.000000 +-0.534131 0.845402 0.000000 +-0.431372 0.902174 0.000000 +-0.534131 0.845402 0.000000 +-0.431372 0.902174 0.000000 +-0.322253 0.946654 0.000000 +-0.322253 0.946654 0.000000 +-0.431372 0.902174 0.000000 +-0.322253 0.946654 0.000000 +-0.431372 0.902174 0.000000 +-0.322253 0.946654 0.000000 +-0.211335 0.977414 0.000000 +-0.211335 0.977414 0.000000 +-0.322253 0.946654 0.000000 +-0.211335 0.977414 0.000000 +-0.322253 0.946654 0.000000 +-0.211335 0.977414 0.000000 +-0.103087 0.994672 0.000000 +-0.103087 0.994672 0.000000 +-0.211335 0.977414 0.000000 +-0.103087 0.994672 0.000000 +-0.211335 0.977414 0.000000 +-0.103087 0.994672 0.000000 +0.000231 1.000000 0.000000 +0.000231 1.000000 0.000000 +-0.103087 0.994672 0.000000 +0.000231 1.000000 0.000000 +-0.103087 0.994672 0.000000 +0.000231 1.000000 0.000000 +0.104005 0.994577 0.000000 +0.104005 0.994577 0.000000 +0.000231 1.000000 0.000000 +0.104005 0.994577 0.000000 +0.000231 1.000000 0.000000 +0.104005 0.994577 0.000000 +0.213104 0.977030 0.000000 +0.213104 0.977030 0.000000 +0.104005 0.994577 0.000000 +0.213104 0.977030 0.000000 +0.104005 0.994577 0.000000 +0.213104 0.977030 0.000000 +0.324695 0.945819 0.000000 +0.324695 0.945819 0.000000 +0.213104 0.977030 0.000000 +0.324695 0.945819 0.000000 +0.213104 0.977030 0.000000 +0.324695 0.945819 0.000000 +0.434216 0.900809 0.000000 +0.434216 0.900809 0.000000 +0.324695 0.945819 0.000000 +0.434216 0.900809 0.000000 +0.324695 0.945819 0.000000 +0.434216 0.900809 0.000000 +0.537069 0.843538 0.000000 +0.537069 0.843538 0.000000 +0.434216 0.900809 0.000000 +0.537069 0.843538 0.000000 +0.434216 0.900809 0.000000 +0.537069 0.843538 0.000000 +0.629534 0.776973 0.000000 +0.629533 0.776973 0.000000 +0.537069 0.843538 0.000000 +0.629533 0.776973 0.000000 +0.537069 0.843538 0.000000 +0.629534 0.776973 0.000000 +0.710111 0.704090 0.000000 +0.710111 0.704090 0.000000 +0.629534 0.776973 0.000000 +0.710111 0.704090 0.000000 +0.629533 0.776973 0.000000 +0.710111 0.704090 0.000000 +0.782238 0.622980 0.000000 +0.782238 0.622980 0.000000 +0.710111 0.704090 0.000000 +0.782238 0.622980 0.000000 +0.710111 0.704090 0.000000 +0.782238 0.622980 0.000000 +0.847775 0.530355 0.000000 +0.847775 0.530355 0.000000 +0.782238 0.622980 0.000000 +0.847775 0.530355 0.000000 +0.782238 0.622980 0.000000 +0.847775 0.530355 0.000000 +0.903816 0.427920 0.000000 +0.903816 0.427920 0.000000 +0.847775 0.530355 0.000000 +0.903816 0.427920 0.000000 +0.847775 0.530355 0.000000 +0.903816 0.427920 0.000000 +0.947610 0.319429 0.000000 +0.947610 0.319429 0.000000 +0.903816 0.427920 0.000000 +0.947610 0.319429 0.000000 +0.903816 0.427920 0.000000 +0.947610 0.319429 0.000000 +0.977837 0.209369 0.000000 +0.977837 0.209369 0.000000 +0.947610 0.319429 0.000000 +0.977837 0.209369 0.000000 +0.947610 0.319429 0.000000 +0.977837 0.209369 0.000000 +0.994775 0.102095 0.000000 +0.994775 0.102095 0.000000 +0.977837 0.209369 0.000000 +0.994775 0.102095 0.000000 +0.977837 0.209369 0.000000 +0.994775 0.102095 0.000000 +1.000000 0.000010 0.000000 +1.000000 0.000010 0.000000 +0.994775 0.102095 0.000000 +1.000000 0.000010 0.000000 +0.994775 0.102095 0.000000 +1.000000 0.000010 0.000000 +0.994778 -0.102060 0.000000 +0.994778 -0.102060 0.000000 +1.000000 0.000010 0.000000 +0.994778 -0.102060 0.000000 +1.000000 0.000010 0.000000 +0.994778 -0.102060 0.000000 +0.977848 -0.209316 0.000000 +0.977848 -0.209316 0.000000 +0.994778 -0.102060 0.000000 +0.977848 -0.209316 0.000000 +0.994778 -0.102060 0.000000 +0.977848 -0.209316 0.000000 +0.947627 -0.319380 0.000000 +0.947627 -0.319380 0.000000 +0.977848 -0.209316 0.000000 +0.947627 -0.319380 0.000000 +0.977848 -0.209316 0.000000 +0.947627 -0.319380 0.000000 +0.903829 -0.427895 0.000000 +0.903829 -0.427895 0.000000 +0.947627 -0.319380 0.000000 +0.903829 -0.427895 0.000000 +0.947627 -0.319380 0.000000 +0.903829 -0.427895 0.000000 +0.847765 -0.530372 0.000000 +0.847765 -0.530372 0.000000 +0.903829 -0.427895 0.000000 +0.847765 -0.530372 0.000000 +0.903829 -0.427895 0.000000 +0.847765 -0.530372 0.000000 +0.782184 -0.623048 0.000000 +0.782184 -0.623048 0.000000 +0.847765 -0.530372 0.000000 +0.782184 -0.623048 0.000000 +0.847765 -0.530372 0.000000 +0.782184 -0.623048 0.000000 +0.710012 -0.704190 0.000000 +0.710012 -0.704190 0.000000 +0.782184 -0.623048 0.000000 +0.710012 -0.704190 0.000000 +0.782184 -0.623048 0.000000 +0.710012 -0.704190 0.000000 +0.629412 -0.777072 0.000000 +0.629412 -0.777072 0.000000 +0.710012 -0.704190 0.000000 +0.629412 -0.777072 0.000000 +0.710012 -0.704190 0.000000 +0.629412 -0.777072 0.000000 +0.536947 -0.843616 0.000000 +0.536947 -0.843616 0.000000 +0.629412 -0.777072 0.000000 +0.536947 -0.843616 0.000000 +0.629412 -0.777072 0.000000 +0.536947 -0.843616 0.000000 +0.434100 -0.900865 0.000000 +0.434100 -0.900865 0.000000 +0.536947 -0.843616 0.000000 +0.434100 -0.900865 0.000000 +0.536947 -0.843616 0.000000 +0.434100 -0.900865 0.000000 +0.324602 -0.945851 0.000000 +0.324602 -0.945851 0.000000 +0.434100 -0.900865 0.000000 +0.324602 -0.945851 0.000000 +0.434100 -0.900865 0.000000 +0.324602 -0.945851 0.000000 +0.213043 -0.977043 0.000000 +0.213043 -0.977043 0.000000 +0.324602 -0.945851 0.000000 +0.213043 -0.977043 0.000000 +0.324602 -0.945851 0.000000 +0.213043 -0.977043 0.000000 +0.103971 -0.994580 0.000000 +0.103971 -0.994580 0.000000 +0.213043 -0.977043 0.000000 +0.103971 -0.994580 0.000000 +0.213043 -0.977043 0.000000 +0.103971 -0.994580 0.000000 +0.000230 -1.000000 0.000000 +0.000230 -1.000000 0.000000 +0.103971 -0.994580 0.000000 +0.000230 -1.000000 0.000000 +0.103971 -0.994580 0.000000 +0.000230 -1.000000 0.000000 +-0.103055 -0.994676 0.000000 +-0.103055 -0.994676 0.000000 +0.000230 -1.000000 0.000000 +-0.103055 -0.994676 0.000000 +0.000230 -1.000000 0.000000 +-0.103055 -0.994676 0.000000 +-0.211273 -0.977427 0.000000 +-0.211273 -0.977427 0.000000 +-0.103055 -0.994676 0.000000 +-0.211273 -0.977427 0.000000 +-0.103055 -0.994676 0.000000 +-0.211273 -0.977427 0.000000 +-0.322158 -0.946686 0.000000 +-0.322158 -0.946686 0.000000 +-0.211273 -0.977427 0.000000 +-0.322158 -0.946686 0.000000 +-0.211273 -0.977427 0.000000 +-0.322158 -0.946686 0.000000 +-0.431258 -0.902229 0.000000 +-0.431258 -0.902229 0.000000 +-0.322158 -0.946686 0.000000 +-0.431258 -0.902229 0.000000 +-0.322158 -0.946686 0.000000 +-0.431258 -0.902229 0.000000 +-0.534009 -0.845479 0.000000 +-0.534009 -0.845479 0.000000 +-0.431258 -0.902229 0.000000 +-0.534009 -0.845479 0.000000 +-0.431258 -0.902229 0.000000 +-0.534009 -0.845479 0.000000 +-0.626649 -0.779302 0.000000 +-0.626649 -0.779302 0.000000 +-0.534009 -0.845479 0.000000 +-0.626649 -0.779302 0.000000 +-0.534009 -0.845479 0.000000 +-0.626649 -0.779302 0.000000 +-0.707571 -0.706642 0.000000 +-0.707571 -0.706642 0.000000 +-0.626649 -0.779302 0.000000 +-0.707571 -0.706642 0.000000 +-0.626649 -0.779302 0.000000 +-0.707571 -0.706642 0.000000 +-0.780118 -0.625632 0.000000 +-0.780118 -0.625632 0.000000 +-0.707571 -0.706642 0.000000 +-0.780118 -0.625632 0.000000 +-0.707571 -0.706642 0.000000 +-0.780118 -0.625632 0.000000 +-0.846141 -0.532959 0.000000 +-0.846141 -0.532960 0.000000 +-0.780118 -0.625632 0.000000 +-0.846141 -0.532960 0.000000 +-0.780118 -0.625632 0.000000 +-0.846141 -0.532959 0.000000 +-0.902699 -0.430272 0.000000 +-0.902699 -0.430272 0.000000 +-0.846141 -0.532959 0.000000 +-0.902699 -0.430272 0.000000 +-0.846141 -0.532960 0.000000 +-0.902699 -0.430272 0.000000 +-0.946967 -0.321330 0.000000 +-0.946967 -0.321330 0.000000 +-0.902699 -0.430272 0.000000 +-0.946967 -0.321330 0.000000 +-0.902699 -0.430272 0.000000 +-0.946967 -0.321330 0.000000 +-0.977556 -0.210678 0.000000 +-0.977556 -0.210678 0.000000 +-0.946967 -0.321330 0.000000 +-0.977556 -0.210678 0.000000 +-0.946967 -0.321330 0.000000 +-0.977556 -0.210678 0.000000 +-0.994707 -0.102748 0.000000 +-0.994707 -0.102748 0.000000 +-0.977556 -0.210678 0.000000 +-0.994707 -0.102748 0.000000 +-0.977556 -0.210678 0.000000 +-0.994707 -0.102748 0.000000 +-1.000000 0.000010 0.000000 +-1.000000 0.000010 0.000000 +-0.994707 -0.102748 0.000000 +-1.000000 0.000010 0.000000 +-0.994707 -0.102748 0.000000 +-1.000000 0.000010 0.000000 +-0.994704 0.102782 0.000000 +-0.994704 0.102782 0.000000 +-1.000000 0.000010 0.000000 +-0.994704 0.102782 0.000000 +-1.000000 0.000010 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 + + + + + + + + + + + + +

0 0 1 1 68 2 0 3 68 4 67 5 1 6 2 7 69 8 1 9 69 10 68 11 2 12 3 13 70 14 2 15 70 16 69 17 3 18 4 19 71 20 3 21 71 22 70 23 4 24 5 25 72 26 4 27 72 28 71 29 5 30 6 31 73 32 5 33 73 34 72 35 6 36 7 37 74 38 6 39 74 40 73 41 7 42 8 43 75 44 7 45 75 46 74 47 8 48 9 49 76 50 8 51 76 52 75 53 9 54 10 55 77 56 9 57 77 58 76 59 10 60 11 61 78 62 10 63 78 64 77 65 11 66 12 67 79 68 11 69 79 70 78 71 12 72 13 73 80 74 12 75 80 76 79 77 13 78 14 79 81 80 13 81 81 82 80 83 14 84 15 85 82 86 14 87 82 88 81 89 15 90 16 91 83 92 15 93 83 94 82 95 16 96 17 97 84 98 16 99 84 100 83 101 17 102 18 103 85 104 17 105 85 106 84 107 18 108 19 109 86 110 18 111 86 112 85 113 19 114 20 115 87 116 19 117 87 118 86 119 20 120 21 121 88 122 20 123 88 124 87 125 21 126 22 127 89 128 21 129 89 130 88 131 22 132 23 133 90 134 22 135 90 136 89 137 23 138 24 139 91 140 23 141 91 142 90 143 24 144 25 145 92 146 24 147 92 148 91 149 25 150 26 151 93 152 25 153 93 154 92 155 26 156 27 157 94 158 26 159 94 160 93 161 27 162 28 163 95 164 27 165 95 166 94 167 28 168 29 169 96 170 28 171 96 172 95 173 29 174 30 175 97 176 29 177 97 178 96 179 30 180 31 181 98 182 30 183 98 184 97 185 31 186 32 187 99 188 31 189 99 190 98 191 32 192 33 193 100 194 32 195 100 196 99 197 33 198 34 199 101 200 33 201 101 202 100 203 34 204 35 205 102 206 34 207 102 208 101 209 35 210 36 211 103 212 35 213 103 214 102 215 36 216 37 217 104 218 36 219 104 220 103 221 37 222 38 223 105 224 37 225 105 226 104 227 38 228 39 229 106 230 38 231 106 232 105 233 39 234 40 235 107 236 39 237 107 238 106 239 40 240 41 241 108 242 40 243 108 244 107 245 41 246 42 247 109 248 41 249 109 250 108 251 42 252 43 253 110 254 42 255 110 256 109 257 43 258 44 259 111 260 43 261 111 262 110 263 44 264 45 265 112 266 44 267 112 268 111 269 45 270 46 271 113 272 45 273 113 274 112 275 46 276 47 277 114 278 46 279 114 280 113 281 47 282 48 283 115 284 47 285 115 286 114 287 48 288 49 289 116 290 48 291 116 292 115 293 49 294 50 295 117 296 49 297 117 298 116 299 50 300 51 301 118 302 50 303 118 304 117 305 51 306 52 307 119 308 51 309 119 310 118 311 52 312 53 313 120 314 52 315 120 316 119 317 53 318 54 319 121 320 53 321 121 322 120 323 54 324 55 325 122 326 54 327 122 328 121 329 55 330 56 331 123 332 55 333 123 334 122 335 56 336 57 337 124 338 56 339 124 340 123 341 57 342 58 343 125 344 57 345 125 346 124 347 58 348 59 349 126 350 58 351 126 352 125 353 59 354 60 355 127 356 59 357 127 358 126 359 60 360 61 361 128 362 60 363 128 364 127 365 61 366 62 367 129 368 61 369 129 370 128 371 62 372 63 373 130 374 62 375 130 376 129 377 63 378 64 379 131 380 63 381 131 382 130 383 64 384 65 385 132 386 64 387 132 388 131 389 65 390 66 391 133 392 65 393 133 394 132 395 66 396 0 397 67 398 66 399 67 400 133 401 134 402 135 403 191 404 134 405 191 406 190 407 135 408 136 409 192 410 135 411 192 412 191 413 136 414 137 415 193 416 136 417 193 418 192 419 137 420 138 421 194 422 137 423 194 424 193 425 138 426 139 427 195 428 138 429 195 430 194 431 139 432 140 433 196 434 139 435 196 436 195 437 140 438 141 439 197 440 140 441 197 442 196 443 141 444 142 445 198 446 141 447 198 448 197 449 142 450 143 451 199 452 142 453 199 454 198 455 143 456 144 457 200 458 143 459 200 460 199 461 144 462 145 463 201 464 144 465 201 466 200 467 145 468 146 469 202 470 145 471 202 472 201 473 146 474 147 475 203 476 146 477 203 478 202 479 147 480 148 481 204 482 147 483 204 484 203 485 148 486 149 487 205 488 148 489 205 490 204 491 149 492 150 493 206 494 149 495 206 496 205 497 150 498 151 499 207 500 150 501 207 502 206 503 151 504 152 505 208 506 151 507 208 508 207 509 152 510 153 511 209 512 152 513 209 514 208 515 153 516 154 517 210 518 153 519 210 520 209 521 154 522 155 523 211 524 154 525 211 526 210 527 155 528 156 529 212 530 155 531 212 532 211 533 156 534 157 535 213 536 156 537 213 538 212 539 157 540 158 541 214 542 157 543 214 544 213 545 158 546 159 547 215 548 158 549 215 550 214 551 159 552 160 553 216 554 159 555 216 556 215 557 160 558 161 559 217 560 160 561 217 562 216 563 161 564 162 565 218 566 161 567 218 568 217 569 162 570 163 571 219 572 162 573 219 574 218 575 163 576 164 577 220 578 163 579 220 580 219 581 164 582 165 583 221 584 164 585 221 586 220 587 165 588 166 589 222 590 165 591 222 592 221 593 166 594 167 595 223 596 166 597 223 598 222 599 167 600 168 601 224 602 167 603 224 604 223 605 168 606 169 607 225 608 168 609 225 610 224 611 169 612 170 613 226 614 169 615 226 616 225 617 170 618 171 619 227 620 170 621 227 622 226 623 171 624 172 625 228 626 171 627 228 628 227 629 172 630 173 631 229 632 172 633 229 634 228 635 173 636 174 637 230 638 173 639 230 640 229 641 174 642 175 643 231 644 174 645 231 646 230 647 175 648 176 649 232 650 175 651 232 652 231 653 176 654 177 655 233 656 176 657 233 658 232 659 177 660 178 661 234 662 177 663 234 664 233 665 178 666 179 667 235 668 178 669 235 670 234 671 179 672 180 673 236 674 179 675 236 676 235 677 180 678 181 679 237 680 180 681 237 682 236 683 181 684 182 685 238 686 181 687 238 688 237 689 182 690 183 691 239 692 182 693 239 694 238 695 183 696 184 697 240 698 183 699 240 700 239 701 184 702 185 703 241 704 184 705 241 706 240 707 185 708 186 709 242 710 185 711 242 712 241 713 186 714 187 715 243 716 186 717 243 718 242 719 187 720 188 721 244 722 187 723 244 724 243 725 188 726 189 727 245 728 188 729 245 730 244 731 189 732 134 733 190 734 189 735 190 736 245 737 147 738 2 739 1 740 146 741 2 742 147 743 145 744 2 745 146 746 145 747 3 748 2 749 144 750 3 751 145 752 144 753 4 754 3 755 143 756 4 757 144 758 143 759 5 760 4 761 142 762 5 763 143 764 142 765 6 766 5 767 141 768 6 769 142 770 141 771 7 772 6 773 140 774 7 775 141 776 140 777 8 778 7 779 65 780 0 781 66 782 65 783 1 784 0 785 63 786 65 787 64 788 62 789 65 790 63 791 62 792 1 793 65 794 60 795 62 796 61 797 59 798 62 799 60 800 59 801 1 802 62 803 59 804 147 805 1 806 58 807 147 808 59 809 58 810 148 811 147 812 58 813 149 814 148 815 58 816 150 817 149 818 57 819 150 820 58 821 57 822 151 823 150 824 56 825 151 826 57 827 56 828 152 829 151 830 55 831 152 832 56 833 139 834 8 835 140 836 139 837 9 838 8 839 139 840 10 841 9 842 138 843 10 844 139 845 138 846 11 847 10 848 137 849 11 850 138 851 137 852 12 853 11 854 136 855 12 856 137 857 136 858 13 859 12 860 135 861 13 862 136 863 135 864 14 865 13 866 135 867 15 868 14 869 134 870 15 871 135 872 134 873 16 874 15 875 189 876 16 877 134 878 189 879 17 880 16 881 188 882 17 883 189 884 188 885 18 886 17 887 187 888 18 889 188 890 187 891 19 892 18 893 186 894 19 895 187 896 186 897 20 898 19 899 185 900 20 901 186 902 185 903 21 904 20 905 184 906 21 907 185 908 184 909 22 910 21 911 183 912 22 913 184 914 183 915 23 916 22 917 182 918 23 919 183 920 182 921 24 922 23 923 181 924 24 925 182 926 181 927 25 928 24 929 180 930 25 931 181 932 180 933 26 934 25 935 179 936 26 937 180 938 179 939 27 940 26 941 178 942 27 943 179 944 178 945 28 946 27 947 177 948 28 949 178 950 177 951 29 952 28 953 176 954 29 955 177 956 176 957 30 958 29 959 175 960 30 961 176 962 175 963 31 964 30 965 174 966 31 967 175 968 174 969 32 970 31 971 173 972 32 973 174 974 172 975 32 976 173 977 172 978 33 979 32 980 171 981 33 982 172 983 171 984 34 985 33 986 170 987 34 988 171 989 170 990 35 991 34 992 169 993 35 994 170 995 169 996 36 997 35 998 168 999 36 1000 169 1001 168 1002 37 1003 36 1004 167 1005 37 1006 168 1007 167 1008 38 1009 37 1010 166 1011 38 1012 167 1013 166 1014 39 1015 38 1016 166 1017 40 1018 39 1019 165 1020 40 1021 166 1022 165 1023 41 1024 40 1025 164 1026 41 1027 165 1028 164 1029 42 1030 41 1031 163 1032 42 1033 164 1034 163 1035 43 1036 42 1037 162 1038 43 1039 163 1040 162 1041 44 1042 43 1043 161 1044 44 1045 162 1046 161 1047 45 1048 44 1049 160 1050 45 1051 161 1052 160 1053 46 1054 45 1055 159 1056 46 1057 160 1058 159 1059 47 1060 46 1061 158 1062 47 1063 159 1064 158 1065 48 1066 47 1067 158 1068 49 1069 48 1070 157 1071 49 1072 158 1073 157 1074 50 1075 49 1076 156 1077 50 1078 157 1079 156 1080 51 1081 50 1082 155 1083 51 1084 156 1085 155 1086 52 1087 51 1088 154 1089 52 1090 155 1091 154 1092 53 1093 52 1094 154 1095 54 1096 53 1097 153 1098 54 1099 154 1100 153 1101 55 1102 54 1103 153 1104 152 1105 55 1106 203 1107 68 1108 69 1109 202 1110 203 1111 69 1112 201 1113 202 1114 69 1115 201 1116 69 1117 70 1118 200 1119 201 1120 70 1121 200 1122 70 1123 71 1124 199 1125 200 1126 71 1127 199 1128 71 1129 72 1130 198 1131 199 1132 72 1133 198 1134 72 1135 73 1136 197 1137 198 1138 73 1139 197 1140 73 1141 74 1142 196 1143 197 1144 74 1145 196 1146 74 1147 75 1148 132 1149 133 1150 67 1151 132 1152 67 1153 68 1154 130 1155 131 1156 132 1157 129 1158 130 1159 132 1160 129 1161 132 1162 68 1163 127 1164 128 1165 129 1166 126 1167 127 1168 129 1169 126 1170 129 1171 68 1172 126 1173 68 1174 203 1175 125 1176 126 1177 203 1178 125 1179 203 1180 204 1181 125 1182 204 1183 205 1184 125 1185 205 1186 206 1187 124 1188 125 1189 206 1190 124 1191 206 1192 207 1193 123 1194 124 1195 207 1196 123 1197 207 1198 208 1199 122 1200 123 1201 208 1202 195 1203 196 1204 75 1205 195 1206 75 1207 76 1208 195 1209 76 1210 77 1211 194 1212 195 1213 77 1214 194 1215 77 1216 78 1217 193 1218 194 1219 78 1220 193 1221 78 1222 79 1223 192 1224 193 1225 79 1226 192 1227 79 1228 80 1229 191 1230 192 1231 80 1232 191 1233 80 1234 81 1235 191 1236 81 1237 82 1238 190 1239 191 1240 82 1241 190 1242 82 1243 83 1244 245 1245 190 1246 83 1247 245 1248 83 1249 84 1250 244 1251 245 1252 84 1253 244 1254 84 1255 85 1256 243 1257 244 1258 85 1259 243 1260 85 1261 86 1262 242 1263 243 1264 86 1265 242 1266 86 1267 87 1268 241 1269 242 1270 87 1271 241 1272 87 1273 88 1274 240 1275 241 1276 88 1277 240 1278 88 1279 89 1280 239 1281 240 1282 89 1283 239 1284 89 1285 90 1286 238 1287 239 1288 90 1289 238 1290 90 1291 91 1292 237 1293 238 1294 91 1295 237 1296 91 1297 92 1298 236 1299 237 1300 92 1301 236 1302 92 1303 93 1304 235 1305 236 1306 93 1307 235 1308 93 1309 94 1310 234 1311 235 1312 94 1313 234 1314 94 1315 95 1316 233 1317 234 1318 95 1319 233 1320 95 1321 96 1322 232 1323 233 1324 96 1325 232 1326 96 1327 97 1328 231 1329 232 1330 97 1331 231 1332 97 1333 98 1334 230 1335 231 1336 98 1337 230 1338 98 1339 99 1340 229 1341 230 1342 99 1343 228 1344 229 1345 99 1346 228 1347 99 1348 100 1349 227 1350 228 1351 100 1352 227 1353 100 1354 101 1355 226 1356 227 1357 101 1358 226 1359 101 1360 102 1361 225 1362 226 1363 102 1364 225 1365 102 1366 103 1367 224 1368 225 1369 103 1370 224 1371 103 1372 104 1373 223 1374 224 1375 104 1376 223 1377 104 1378 105 1379 222 1380 223 1381 105 1382 222 1383 105 1384 106 1385 222 1386 106 1387 107 1388 221 1389 222 1390 107 1391 221 1392 107 1393 108 1394 220 1395 221 1396 108 1397 220 1398 108 1399 109 1400 219 1401 220 1402 109 1403 219 1404 109 1405 110 1406 218 1407 219 1408 110 1409 218 1410 110 1411 111 1412 217 1413 218 1414 111 1415 217 1416 111 1417 112 1418 216 1419 217 1420 112 1421 216 1422 112 1423 113 1424 215 1425 216 1426 113 1427 215 1428 113 1429 114 1430 214 1431 215 1432 114 1433 214 1434 114 1435 115 1436 214 1437 115 1438 116 1439 213 1440 214 1441 116 1442 213 1443 116 1444 117 1445 212 1446 213 1447 117 1448 212 1449 117 1450 118 1451 211 1452 212 1453 118 1454 211 1455 118 1456 119 1457 210 1458 211 1459 119 1460 210 1461 119 1462 120 1463 210 1464 120 1465 121 1466 209 1467 210 1468 121 1469 209 1470 121 1471 122 1472 209 1473 122 1474 208 1475

+
+
+
+ + + + + 1.000000 1.000000 1.000000 + + + + + + + 1.000000 0.000000 0.000000 0.992424 0.000000 1.000000 0.000000 -23.446840 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 + + + + + + + + +
diff --git a/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/media/male_symbol.dae b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/media/male_symbol.dae new file mode 100755 index 0000000..adc9d6b --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/media/male_symbol.dae @@ -0,0 +1,1778 @@ + + + Z_UP + + + + + + + + + + + + 0.000000 0.000000 0.000000 1.000000 + + + 0.000000 1.000000 1.000000 1.000000 + + + 0.000000 1.000000 1.000000 1.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 2.000000 + + + 0.000000 0.000000 0.000000 1.000000 + + + 1.000000 + + + 1.000000 1.000000 1.000000 1.000000 + + + 0.000000 + + + + + + + + + + + +26.607811 48.799999 0.000000 +1.921875 48.799999 0.000000 +1.921875 42.100002 0.000000 +14.070313 42.100002 0.000000 +-2.507813 25.515625 0.000000 +-3.563105 26.095154 0.000000 +-4.645057 26.585522 0.000000 +-5.753666 26.986734 0.000000 +-6.888935 27.298786 0.000000 +-8.050860 27.521687 0.000000 +-9.239446 27.655424 0.000000 +-10.454687 27.700001 0.000000 +-12.314348 27.602936 0.000000 +-14.096906 27.311735 0.000000 +-15.802360 26.826405 0.000000 +-17.430708 26.146940 0.000000 +-18.981955 25.273344 0.000000 +-20.456093 24.205614 0.000000 +-21.853127 22.943750 0.000000 +-23.114574 21.545570 0.000000 +-24.181952 20.068876 0.000000 +-25.055260 18.513681 0.000000 +-25.734503 16.879974 0.000000 +-26.219677 15.167763 0.000000 +-26.510777 13.377041 0.000000 +-26.607813 11.507813 0.000000 +-26.515434 9.704163 0.000000 +-26.238297 7.978922 0.000000 +-25.776403 6.332096 0.000000 +-25.129751 4.763681 0.000000 +-24.298346 3.273677 0.000000 +-23.282175 1.862086 0.000000 +-22.081249 0.528906 0.000000 +-20.748726 -0.672640 0.000000 +-19.337753 -1.689333 0.000000 +-17.848341 -2.521173 0.000000 +-16.280485 -3.168160 0.000000 +-14.634187 -3.630294 0.000000 +-12.909439 -3.907574 0.000000 +-11.106251 -4.000000 0.000000 +-9.237867 -3.902934 0.000000 +-7.447895 -3.611735 0.000000 +-5.736336 -3.126403 0.000000 +-4.103189 -2.446939 0.000000 +-2.548453 -1.573342 0.000000 +-1.072129 -0.505612 0.000000 +0.325783 0.756250 0.000000 +1.587437 2.153762 0.000000 +2.654991 3.628444 0.000000 +3.528444 5.180294 0.000000 +4.207796 6.809311 0.000000 +4.693048 8.515498 0.000000 +4.984200 10.298853 0.000000 +5.081249 12.159375 0.000000 +5.036702 13.384025 0.000000 +4.903060 14.582079 0.000000 +4.680325 15.753540 0.000000 +4.368495 16.898407 0.000000 +3.967570 18.016678 0.000000 +3.477551 19.108355 0.000000 +2.898438 20.173437 0.000000 +19.345314 36.654690 0.000000 +19.345314 24.600000 0.000000 +26.607811 24.600000 0.000000 +26.607811 48.799999 5.905512 +1.921875 48.799999 5.905512 +1.921875 42.100002 5.905512 +14.070313 42.100002 5.905512 +-2.507813 25.515625 5.905512 +-3.563105 26.095154 5.905512 +-4.645057 26.585522 5.905512 +-5.753666 26.986734 5.905512 +-6.888935 27.298786 5.905512 +-8.050860 27.521687 5.905512 +-9.239446 27.655424 5.905512 +-10.454687 27.700001 5.905512 +-12.314348 27.602936 5.905512 +-14.096906 27.311735 5.905512 +-15.802360 26.826405 5.905512 +-17.430708 26.146940 5.905512 +-18.981955 25.273344 5.905512 +-20.456093 24.205614 5.905512 +-21.853127 22.943750 5.905512 +-23.114574 21.545570 5.905512 +-24.181952 20.068876 5.905512 +-25.055260 18.513681 5.905512 +-25.734503 16.879974 5.905512 +-26.219677 15.167763 5.905512 +-26.510777 13.377041 5.905512 +-26.607813 11.507813 5.905512 +-26.515434 9.704163 5.905512 +-26.238297 7.978922 5.905512 +-25.776403 6.332096 5.905512 +-25.129751 4.763681 5.905512 +-24.298346 3.273677 5.905512 +-23.282175 1.862086 5.905512 +-22.081249 0.528906 5.905512 +-20.748726 -0.672640 5.905512 +-19.337753 -1.689333 5.905512 +-17.848341 -2.521173 5.905512 +-16.280485 -3.168160 5.905512 +-14.634187 -3.630294 5.905512 +-12.909439 -3.907574 5.905512 +-11.106251 -4.000000 5.905512 +-9.237867 -3.902934 5.905512 +-7.447895 -3.611735 5.905512 +-5.736336 -3.126403 5.905512 +-4.103189 -2.446939 5.905512 +-2.548453 -1.573342 5.905512 +-1.072129 -0.505612 5.905512 +0.325783 0.756250 5.905512 +1.587437 2.153762 5.905512 +2.654991 3.628444 5.905512 +3.528444 5.180294 5.905512 +4.207796 6.809311 5.905512 +4.693048 8.515498 5.905512 +4.984200 10.298853 5.905512 +5.081249 12.159375 5.905512 +5.036702 13.384025 5.905512 +4.903060 14.582079 5.905512 +4.680325 15.753540 5.905512 +4.368495 16.898407 5.905512 +3.967570 18.016678 5.905512 +3.477551 19.108355 5.905512 +2.898438 20.173437 5.905512 +19.345314 36.654690 5.905512 +19.345314 24.600000 5.905512 +26.607811 24.600000 5.905512 +-2.523852 10.888011 0.000000 +-2.670408 9.982843 0.000000 +-2.914669 9.118878 0.000000 +-3.256633 8.296111 0.000000 +-3.696301 7.514542 0.000000 +-4.233674 6.774171 0.000000 +-4.868750 6.075000 0.000000 +-5.572959 5.444899 0.000000 +-6.317729 4.911735 0.000000 +-7.103061 4.475511 0.000000 +-7.928954 4.136225 0.000000 +-8.795409 3.893878 0.000000 +-9.702424 3.748470 0.000000 +-10.650000 3.700000 0.000000 +-11.588871 3.748470 0.000000 +-12.488519 3.893878 0.000000 +-13.348947 4.136224 0.000000 +-14.170153 4.475510 0.000000 +-14.952137 4.911736 0.000000 +-15.694899 5.444899 0.000000 +-16.398438 6.075000 0.000000 +-17.033514 6.774171 0.000000 +-17.570885 7.514541 0.000000 +-18.010553 8.296110 0.000000 +-18.352520 9.118877 0.000000 +-18.596783 9.982845 0.000000 +-18.743338 10.888012 0.000000 +-18.792187 11.834375 0.000000 +-18.743336 12.780661 0.000000 +-18.596779 13.686480 0.000000 +-18.352520 14.551833 0.000000 +-18.010555 15.376724 0.000000 +-17.570887 16.161146 0.000000 +-17.033514 16.905104 0.000000 +-16.398438 17.608595 0.000000 +-15.694899 18.243050 0.000000 +-14.952135 18.779896 0.000000 +-14.170153 19.219135 0.000000 +-13.348948 19.560760 0.000000 +-12.488521 19.804787 0.000000 +-11.588871 19.951197 0.000000 +-10.650000 20.000000 0.000000 +-9.702424 19.951197 0.000000 +-8.795407 19.804781 0.000000 +-7.928954 19.560762 0.000000 +-7.103061 19.219133 0.000000 +-6.317729 18.779898 0.000000 +-5.572959 18.243050 0.000000 +-4.868750 17.608595 0.000000 +-4.233674 16.905104 0.000000 +-3.696301 16.161146 0.000000 +-3.256633 15.376723 0.000000 +-2.914669 14.551836 0.000000 +-2.670409 13.686481 0.000000 +-2.523852 12.780662 0.000000 +-2.475000 11.834375 0.000000 +-2.523852 10.888011 5.905512 +-2.670408 9.982843 5.905512 +-2.914669 9.118878 5.905512 +-3.256633 8.296111 5.905512 +-3.696301 7.514542 5.905512 +-4.233674 6.774171 5.905512 +-4.868750 6.075000 5.905512 +-5.572959 5.444899 5.905512 +-6.317729 4.911735 5.905512 +-7.103061 4.475511 5.905512 +-7.928954 4.136225 5.905512 +-8.795409 3.893878 5.905512 +-9.702424 3.748470 5.905512 +-10.650000 3.700000 5.905512 +-11.588871 3.748470 5.905512 +-12.488519 3.893878 5.905512 +-13.348947 4.136224 5.905512 +-14.170153 4.475510 5.905512 +-14.952137 4.911736 5.905512 +-15.694899 5.444899 5.905512 +-16.398438 6.075000 5.905512 +-17.033514 6.774171 5.905512 +-17.570885 7.514541 5.905512 +-18.010553 8.296110 5.905512 +-18.352520 9.118877 5.905512 +-18.596783 9.982845 5.905512 +-18.743338 10.888012 5.905512 +-18.792187 11.834375 5.905512 +-18.743336 12.780661 5.905512 +-18.596779 13.686480 5.905512 +-18.352520 14.551833 5.905512 +-18.010555 15.376724 5.905512 +-17.570887 16.161146 5.905512 +-17.033514 16.905104 5.905512 +-16.398438 17.608595 5.905512 +-15.694899 18.243050 5.905512 +-14.952135 18.779896 5.905512 +-14.170153 19.219135 5.905512 +-13.348948 19.560760 5.905512 +-12.488521 19.804787 5.905512 +-11.588871 19.951197 5.905512 +-10.650000 20.000000 5.905512 +-9.702424 19.951197 5.905512 +-8.795407 19.804781 5.905512 +-7.928954 19.560762 5.905512 +-7.103061 19.219133 5.905512 +-6.317729 18.779898 5.905512 +-5.572959 18.243050 5.905512 +-4.868750 17.608595 5.905512 +-4.233674 16.905104 5.905512 +-3.696301 16.161146 5.905512 +-3.256633 15.376723 5.905512 +-2.914669 14.551836 5.905512 +-2.670409 13.686481 5.905512 +-2.523852 12.780662 5.905512 +-2.475000 11.834375 5.905512 + + + + + + + + + + + +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +0.000000 1.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +-0.707240 0.706973 0.000000 +-0.707240 0.706973 0.000000 +-0.707240 0.706973 0.000000 +-0.707240 0.706973 0.000000 +-0.707240 0.706973 0.000000 +-0.707240 0.706973 0.000000 +0.481356 0.876525 0.000000 +0.447410 0.894329 0.000000 +0.447410 0.894329 0.000000 +0.481356 0.876525 0.000000 +0.447410 0.894329 0.000000 +0.481356 0.876525 0.000000 +0.447410 0.894329 0.000000 +0.376845 0.926276 0.000000 +0.376845 0.926276 0.000000 +0.447410 0.894329 0.000000 +0.376845 0.926276 0.000000 +0.447410 0.894329 0.000000 +0.376845 0.926276 0.000000 +0.302909 0.953019 0.000000 +0.302909 0.953019 0.000000 +0.376845 0.926276 0.000000 +0.302909 0.953019 0.000000 +0.376845 0.926276 0.000000 +0.302909 0.953019 0.000000 +0.226897 0.973919 0.000000 +0.226897 0.973919 0.000000 +0.302909 0.953019 0.000000 +0.226897 0.973919 0.000000 +0.302909 0.953019 0.000000 +0.226897 0.973919 0.000000 +0.150220 0.988653 0.000000 +0.150220 0.988653 0.000000 +0.226897 0.973919 0.000000 +0.150220 0.988653 0.000000 +0.226897 0.973919 0.000000 +0.150220 0.988653 0.000000 +0.074287 0.997237 0.000000 +0.074287 0.997237 0.000000 +0.150220 0.988653 0.000000 +0.074287 0.997237 0.000000 +0.150220 0.988653 0.000000 +0.074287 0.997237 0.000000 +-0.007741 0.999970 0.000000 +-0.007741 0.999970 0.000000 +0.074287 0.997237 0.000000 +-0.007741 0.999970 0.000000 +0.074287 0.997237 0.000000 +-0.007741 0.999970 0.000000 +-0.106835 0.994277 0.000000 +-0.106835 0.994277 0.000000 +-0.007741 0.999970 0.000000 +-0.106835 0.994277 0.000000 +-0.007741 0.999970 0.000000 +-0.106835 0.994277 0.000000 +-0.217828 0.975987 0.000000 +-0.217828 0.975987 0.000000 +-0.106835 0.994277 0.000000 +-0.217828 0.975987 0.000000 +-0.106835 0.994277 0.000000 +-0.217828 0.975987 0.000000 +-0.329975 0.943990 0.000000 +-0.329975 0.943990 0.000000 +-0.217828 0.975987 0.000000 +-0.329975 0.943990 0.000000 +-0.217828 0.975987 0.000000 +-0.329975 0.943990 0.000000 +-0.438652 0.898657 0.000000 +-0.438652 0.898657 0.000000 +-0.329975 0.943990 0.000000 +-0.438652 0.898657 0.000000 +-0.329975 0.943990 0.000000 +-0.438652 0.898657 0.000000 +-0.539524 0.841970 0.000000 +-0.539524 0.841970 0.000000 +-0.438652 0.898657 0.000000 +-0.539524 0.841970 0.000000 +-0.438652 0.898657 0.000000 +-0.539524 0.841970 0.000000 +-0.629360 0.777114 0.000000 +-0.629360 0.777114 0.000000 +-0.539524 0.841970 0.000000 +-0.629360 0.777114 0.000000 +-0.539524 0.841970 0.000000 +-0.629360 0.777114 0.000000 +-0.707309 0.706905 0.000000 +-0.707309 0.706905 0.000000 +-0.629360 0.777114 0.000000 +-0.707309 0.706905 0.000000 +-0.629360 0.777114 0.000000 +-0.707309 0.706905 0.000000 +-0.777602 0.628757 0.000000 +-0.777602 0.628757 0.000000 +-0.707309 0.706905 0.000000 +-0.777602 0.628757 0.000000 +-0.707309 0.706905 0.000000 +-0.777602 0.628757 0.000000 +-0.842565 0.538595 0.000000 +-0.842565 0.538595 0.000000 +-0.777602 0.628757 0.000000 +-0.842565 0.538595 0.000000 +-0.777602 0.628757 0.000000 +-0.842565 0.538595 0.000000 +-0.899207 0.437524 0.000000 +-0.899207 0.437524 0.000000 +-0.842565 0.538595 0.000000 +-0.899207 0.437524 0.000000 +-0.842565 0.538595 0.000000 +-0.899207 0.437524 0.000000 +-0.944386 0.328839 0.000000 +-0.944386 0.328839 0.000000 +-0.899207 0.437524 0.000000 +-0.944386 0.328839 0.000000 +-0.899207 0.437524 0.000000 +-0.944386 0.328839 0.000000 +-0.976194 0.216899 0.000000 +-0.976194 0.216899 0.000000 +-0.944386 0.328839 0.000000 +-0.976194 0.216899 0.000000 +-0.944386 0.328839 0.000000 +-0.976194 0.216899 0.000000 +-0.994333 0.106307 0.000000 +-0.994333 0.106307 0.000000 +-0.976194 0.216899 0.000000 +-0.994333 0.106307 0.000000 +-0.976194 0.216899 0.000000 +-0.994333 0.106307 0.000000 +-1.000000 0.000347 0.000000 +-1.000000 0.000347 0.000000 +-0.994333 0.106307 0.000000 +-1.000000 0.000347 0.000000 +-0.994333 0.106307 0.000000 +-1.000000 0.000347 0.000000 +-0.994469 -0.105031 0.000000 +-0.994469 -0.105031 0.000000 +-1.000000 0.000347 0.000000 +-0.994469 -0.105031 0.000000 +-1.000000 0.000347 0.000000 +-0.994469 -0.105031 0.000000 +-0.976685 -0.214678 0.000000 +-0.976685 -0.214678 0.000000 +-0.994469 -0.105031 0.000000 +-0.976685 -0.214678 0.000000 +-0.994469 -0.105031 0.000000 +-0.976685 -0.214678 0.000000 +-0.945309 -0.326176 0.000000 +-0.945309 -0.326176 0.000000 +-0.976685 -0.214678 0.000000 +-0.945309 -0.326176 0.000000 +-0.976685 -0.214678 0.000000 +-0.945309 -0.326176 0.000000 +-0.900443 -0.434974 0.000000 +-0.900443 -0.434974 0.000000 +-0.945309 -0.326176 0.000000 +-0.900443 -0.434974 0.000000 +-0.945309 -0.326176 0.000000 +-0.900443 -0.434974 0.000000 +-0.843812 -0.536639 0.000000 +-0.843812 -0.536639 0.000000 +-0.900443 -0.434974 0.000000 +-0.843812 -0.536639 0.000000 +-0.900443 -0.434974 0.000000 +-0.843812 -0.536639 0.000000 +-0.778453 -0.627703 0.000000 +-0.778453 -0.627703 0.000000 +-0.843812 -0.536639 0.000000 +-0.778453 -0.627703 0.000000 +-0.843812 -0.536639 0.000000 +-0.778453 -0.627703 0.000000 +-0.707284 -0.706929 0.000000 +-0.707284 -0.706929 0.000000 +-0.778453 -0.627703 0.000000 +-0.707284 -0.706929 0.000000 +-0.778453 -0.627703 0.000000 +-0.707284 -0.706929 0.000000 +-0.628074 -0.778154 0.000000 +-0.628074 -0.778154 0.000000 +-0.707284 -0.706929 0.000000 +-0.628074 -0.778154 0.000000 +-0.707284 -0.706929 0.000000 +-0.628074 -0.778154 0.000000 +-0.536995 -0.843586 0.000000 +-0.536994 -0.843586 0.000000 +-0.628074 -0.778154 0.000000 +-0.536994 -0.843586 0.000000 +-0.628074 -0.778154 0.000000 +-0.536995 -0.843586 0.000000 +-0.435288 -0.900291 0.000000 +-0.435288 -0.900291 0.000000 +-0.536995 -0.843586 0.000000 +-0.435288 -0.900291 0.000000 +-0.536994 -0.843586 0.000000 +-0.435288 -0.900291 0.000000 +-0.326425 -0.945223 0.000000 +-0.326425 -0.945223 0.000000 +-0.435288 -0.900291 0.000000 +-0.326425 -0.945223 0.000000 +-0.435288 -0.900291 0.000000 +-0.326425 -0.945223 0.000000 +-0.214847 -0.976648 0.000000 +-0.214846 -0.976648 0.000000 +-0.326425 -0.945223 0.000000 +-0.214846 -0.976648 0.000000 +-0.326425 -0.945223 0.000000 +-0.214847 -0.976648 0.000000 +-0.105112 -0.994460 0.000000 +-0.105112 -0.994460 0.000000 +-0.214847 -0.976648 0.000000 +-0.105112 -0.994460 0.000000 +-0.214846 -0.976648 0.000000 +-0.105112 -0.994460 0.000000 +0.000346 -1.000000 0.000000 +0.000346 -1.000000 0.000000 +-0.105112 -0.994460 0.000000 +0.000346 -1.000000 0.000000 +-0.105112 -0.994460 0.000000 +0.000346 -1.000000 0.000000 +0.106386 -0.994325 0.000000 +0.106386 -0.994325 0.000000 +0.000346 -1.000000 0.000000 +0.106386 -0.994325 0.000000 +0.000346 -1.000000 0.000000 +0.106386 -0.994325 0.000000 +0.217048 -0.976161 0.000000 +0.217048 -0.976161 0.000000 +0.106386 -0.994325 0.000000 +0.217048 -0.976161 0.000000 +0.106386 -0.994325 0.000000 +0.217048 -0.976161 0.000000 +0.329038 -0.944317 0.000000 +0.329038 -0.944317 0.000000 +0.217048 -0.976161 0.000000 +0.329038 -0.944317 0.000000 +0.217048 -0.976161 0.000000 +0.329038 -0.944317 0.000000 +0.437751 -0.899096 0.000000 +0.437751 -0.899096 0.000000 +0.329038 -0.944317 0.000000 +0.437751 -0.899096 0.000000 +0.329038 -0.944317 0.000000 +0.437751 -0.899096 0.000000 +0.538823 -0.842419 0.000000 +0.538823 -0.842419 0.000000 +0.437751 -0.899096 0.000000 +0.538823 -0.842419 0.000000 +0.437751 -0.899096 0.000000 +0.538823 -0.842419 0.000000 +0.628965 -0.777434 0.000000 +0.628965 -0.777434 0.000000 +0.538823 -0.842419 0.000000 +0.628965 -0.777434 0.000000 +0.538823 -0.842419 0.000000 +0.628965 -0.777434 0.000000 +0.707085 -0.707128 0.000000 +0.707086 -0.707128 0.000000 +0.628965 -0.777434 0.000000 +0.707086 -0.707128 0.000000 +0.628965 -0.777434 0.000000 +0.707085 -0.707128 0.000000 +0.777273 -0.629163 0.000000 +0.777273 -0.629163 0.000000 +0.707085 -0.707128 0.000000 +0.777273 -0.629163 0.000000 +0.707086 -0.707128 0.000000 +0.777273 -0.629163 0.000000 +0.842102 -0.539318 0.000000 +0.842102 -0.539318 0.000000 +0.777273 -0.629163 0.000000 +0.842102 -0.539318 0.000000 +0.777273 -0.629163 0.000000 +0.842102 -0.539318 0.000000 +0.898754 -0.438454 0.000000 +0.898754 -0.438454 0.000000 +0.842102 -0.539318 0.000000 +0.898754 -0.438454 0.000000 +0.842102 -0.539318 0.000000 +0.898754 -0.438454 0.000000 +0.944049 -0.329805 0.000000 +0.944049 -0.329805 0.000000 +0.898754 -0.438454 0.000000 +0.944049 -0.329805 0.000000 +0.898754 -0.438454 0.000000 +0.944049 -0.329805 0.000000 +0.976015 -0.217704 0.000000 +0.976015 -0.217704 0.000000 +0.944049 -0.329805 0.000000 +0.976015 -0.217704 0.000000 +0.944049 -0.329805 0.000000 +0.976015 -0.217704 0.000000 +0.994284 -0.106770 0.000000 +0.994284 -0.106770 0.000000 +0.976015 -0.217704 0.000000 +0.994284 -0.106770 0.000000 +0.976015 -0.217704 0.000000 +0.994284 -0.106770 0.000000 +0.999969 -0.007878 0.000000 +0.999969 -0.007878 0.000000 +0.994284 -0.106770 0.000000 +0.999969 -0.007878 0.000000 +0.994284 -0.106770 0.000000 +0.999969 -0.007878 0.000000 +0.997284 0.073658 0.000000 +0.997284 0.073658 0.000000 +0.999969 -0.007878 0.000000 +0.997284 0.073658 0.000000 +0.999969 -0.007878 0.000000 +0.997284 0.073658 0.000000 +0.988847 0.148935 0.000000 +0.988847 0.148935 0.000000 +0.997284 0.073658 0.000000 +0.988847 0.148935 0.000000 +0.997284 0.073658 0.000000 +0.988847 0.148935 0.000000 +0.974367 0.224965 0.000000 +0.974367 0.224965 0.000000 +0.988847 0.148935 0.000000 +0.974367 0.224965 0.000000 +0.988847 0.148935 0.000000 +0.974367 0.224965 0.000000 +0.953822 0.300373 0.000000 +0.953822 0.300373 0.000000 +0.974367 0.224965 0.000000 +0.953822 0.300373 0.000000 +0.974367 0.224965 0.000000 +0.953822 0.300373 0.000000 +0.927518 0.373778 0.000000 +0.927518 0.373778 0.000000 +0.953822 0.300373 0.000000 +0.927518 0.373778 0.000000 +0.953822 0.300373 0.000000 +0.927518 0.373778 0.000000 +0.896069 0.443915 0.000000 +0.896069 0.443915 0.000000 +0.927518 0.373778 0.000000 +0.896069 0.443915 0.000000 +0.927518 0.373778 0.000000 +0.896069 0.443915 0.000000 +0.878533 0.477682 0.000000 +0.878533 0.477682 0.000000 +0.896069 0.443915 0.000000 +0.878533 0.477682 0.000000 +0.896069 0.443915 0.000000 +0.707845 -0.706368 0.000000 +0.707845 -0.706368 0.000000 +0.707845 -0.706368 0.000000 +0.707845 -0.706368 0.000000 +0.707845 -0.706368 0.000000 +0.707845 -0.706368 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +-1.000000 0.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +0.000000 -1.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +1.000000 0.000000 0.000000 +-0.994382 0.105847 0.000000 +-0.976327 0.216300 0.000000 +-0.976327 0.216300 0.000000 +-0.994382 0.105847 0.000000 +-0.976327 0.216300 0.000000 +-0.994382 0.105847 0.000000 +-0.976327 0.216300 0.000000 +-0.944503 0.328502 0.000000 +-0.944503 0.328502 0.000000 +-0.976327 0.216300 0.000000 +-0.944503 0.328502 0.000000 +-0.976327 0.216300 0.000000 +-0.944503 0.328502 0.000000 +-0.899066 0.437813 0.000000 +-0.899066 0.437813 0.000000 +-0.944503 0.328502 0.000000 +-0.899066 0.437813 0.000000 +-0.944503 0.328502 0.000000 +-0.899066 0.437813 0.000000 +-0.841829 0.539744 0.000000 +-0.841829 0.539744 0.000000 +-0.899066 0.437813 0.000000 +-0.841829 0.539744 0.000000 +-0.899066 0.437813 0.000000 +-0.841829 0.539744 0.000000 +-0.775923 0.630828 0.000000 +-0.775923 0.630828 0.000000 +-0.841829 0.539744 0.000000 +-0.775923 0.630828 0.000000 +-0.841829 0.539744 0.000000 +-0.775923 0.630828 0.000000 +-0.704457 0.709747 0.000000 +-0.704457 0.709747 0.000000 +-0.775923 0.630828 0.000000 +-0.704457 0.709747 0.000000 +-0.775923 0.630828 0.000000 +-0.704457 0.709747 0.000000 +-0.625373 0.780326 0.000000 +-0.625373 0.780326 0.000000 +-0.704457 0.709747 0.000000 +-0.625373 0.780326 0.000000 +-0.704457 0.709747 0.000000 +-0.625373 0.780326 0.000000 +-0.534711 0.845035 0.000000 +-0.534711 0.845035 0.000000 +-0.625373 0.780326 0.000000 +-0.534711 0.845035 0.000000 +-0.625373 0.780326 0.000000 +-0.534711 0.845035 0.000000 +-0.433533 0.901138 0.000000 +-0.433533 0.901138 0.000000 +-0.534711 0.845035 0.000000 +-0.433533 0.901138 0.000000 +-0.534711 0.845035 0.000000 +-0.433533 0.901138 0.000000 +-0.325235 0.945633 0.000000 +-0.325235 0.945633 0.000000 +-0.433533 0.901138 0.000000 +-0.325235 0.945633 0.000000 +-0.433533 0.901138 0.000000 +-0.325235 0.945633 0.000000 +-0.214174 0.976796 0.000000 +-0.214174 0.976795 0.000000 +-0.325235 0.945633 0.000000 +-0.214174 0.976795 0.000000 +-0.325235 0.945633 0.000000 +-0.214174 0.976796 0.000000 +-0.104842 0.994489 0.000000 +-0.104842 0.994489 0.000000 +-0.214174 0.976796 0.000000 +-0.104842 0.994489 0.000000 +-0.214174 0.976795 0.000000 +-0.104842 0.994489 0.000000 +0.000236 1.000000 0.000000 +0.000236 1.000000 0.000000 +-0.104842 0.994489 0.000000 +0.000236 1.000000 0.000000 +-0.104842 0.994489 0.000000 +0.000236 1.000000 0.000000 +0.105713 0.994397 0.000000 +0.105713 0.994397 0.000000 +0.000236 1.000000 0.000000 +0.105713 0.994397 0.000000 +0.000236 1.000000 0.000000 +0.105713 0.994397 0.000000 +0.215685 0.976463 0.000000 +0.215685 0.976463 0.000000 +0.105713 0.994397 0.000000 +0.215685 0.976463 0.000000 +0.105713 0.994397 0.000000 +0.215685 0.976463 0.000000 +0.327041 0.945010 0.000000 +0.327041 0.945010 0.000000 +0.215685 0.976463 0.000000 +0.327041 0.945010 0.000000 +0.215685 0.976463 0.000000 +0.327041 0.945010 0.000000 +0.435254 0.900308 0.000000 +0.435254 0.900308 0.000000 +0.327041 0.945010 0.000000 +0.435254 0.900308 0.000000 +0.327041 0.945010 0.000000 +0.435254 0.900308 0.000000 +0.536018 0.844207 0.000000 +0.536018 0.844207 0.000000 +0.435254 0.900308 0.000000 +0.536018 0.844207 0.000000 +0.435254 0.900308 0.000000 +0.536018 0.844207 0.000000 +0.626056 0.779778 0.000000 +0.626056 0.779778 0.000000 +0.536018 0.844207 0.000000 +0.626056 0.779778 0.000000 +0.536018 0.844207 0.000000 +0.626056 0.779778 0.000000 +0.704624 0.709580 0.000000 +0.704624 0.709580 0.000000 +0.626056 0.779778 0.000000 +0.704624 0.709580 0.000000 +0.626056 0.779778 0.000000 +0.704624 0.709580 0.000000 +0.775923 0.630828 0.000000 +0.775923 0.630828 0.000000 +0.704624 0.709580 0.000000 +0.775923 0.630828 0.000000 +0.704624 0.709580 0.000000 +0.775923 0.630828 0.000000 +0.841829 0.539744 0.000000 +0.841829 0.539744 0.000000 +0.775923 0.630828 0.000000 +0.841829 0.539744 0.000000 +0.775923 0.630828 0.000000 +0.841829 0.539744 0.000000 +0.899066 0.437814 0.000000 +0.899066 0.437814 0.000000 +0.841829 0.539744 0.000000 +0.899066 0.437814 0.000000 +0.841829 0.539744 0.000000 +0.899066 0.437814 0.000000 +0.944503 0.328504 0.000000 +0.944503 0.328504 0.000000 +0.899066 0.437814 0.000000 +0.944503 0.328504 0.000000 +0.899066 0.437814 0.000000 +0.944503 0.328504 0.000000 +0.976327 0.216301 0.000000 +0.976327 0.216301 0.000000 +0.944503 0.328504 0.000000 +0.976327 0.216301 0.000000 +0.944503 0.328504 0.000000 +0.976327 0.216301 0.000000 +0.994383 0.105846 0.000000 +0.994383 0.105846 0.000000 +0.976327 0.216301 0.000000 +0.994383 0.105846 0.000000 +0.976327 0.216301 0.000000 +0.994383 0.105846 0.000000 +1.000000 -0.000003 0.000000 +1.000000 -0.000003 0.000000 +0.994383 0.105846 0.000000 +1.000000 -0.000003 0.000000 +0.994383 0.105846 0.000000 +1.000000 -0.000003 0.000000 +0.994388 -0.105793 0.000000 +0.994388 -0.105793 0.000000 +1.000000 -0.000003 0.000000 +0.994388 -0.105793 0.000000 +1.000000 -0.000003 0.000000 +0.994388 -0.105793 0.000000 +0.976385 -0.216039 0.000000 +0.976385 -0.216039 0.000000 +0.994388 -0.105793 0.000000 +0.976385 -0.216039 0.000000 +0.994388 -0.105793 0.000000 +0.976385 -0.216039 0.000000 +0.944722 -0.327872 0.000000 +0.944722 -0.327872 0.000000 +0.976385 -0.216039 0.000000 +0.944722 -0.327872 0.000000 +0.976385 -0.216039 0.000000 +0.944722 -0.327872 0.000000 +0.899606 -0.436703 0.000000 +0.899606 -0.436703 0.000000 +0.944722 -0.327872 0.000000 +0.899606 -0.436703 0.000000 +0.944722 -0.327872 0.000000 +0.899606 -0.436703 0.000000 +0.842867 -0.538122 0.000000 +0.842867 -0.538122 0.000000 +0.899606 -0.436703 0.000000 +0.842867 -0.538122 0.000000 +0.899606 -0.436703 0.000000 +0.842867 -0.538122 0.000000 +0.777611 -0.628746 0.000000 +0.777611 -0.628746 0.000000 +0.842867 -0.538122 0.000000 +0.777611 -0.628746 0.000000 +0.842867 -0.538122 0.000000 +0.777611 -0.628746 0.000000 +0.706923 -0.707291 0.000000 +0.706923 -0.707291 0.000000 +0.777611 -0.628746 0.000000 +0.706923 -0.707291 0.000000 +0.777611 -0.628746 0.000000 +0.706923 -0.707291 0.000000 +0.628659 -0.777681 0.000000 +0.628659 -0.777681 0.000000 +0.706923 -0.707291 0.000000 +0.628659 -0.777681 0.000000 +0.706923 -0.707291 0.000000 +0.628659 -0.777681 0.000000 +0.538632 -0.842541 0.000000 +0.538632 -0.842541 0.000000 +0.628659 -0.777681 0.000000 +0.538632 -0.842541 0.000000 +0.628659 -0.777681 0.000000 +0.538632 -0.842541 0.000000 +0.437669 -0.899136 0.000000 +0.437669 -0.899136 0.000000 +0.538632 -0.842541 0.000000 +0.437669 -0.899136 0.000000 +0.538632 -0.842541 0.000000 +0.437669 -0.899136 0.000000 +0.329043 -0.944315 0.000000 +0.329043 -0.944315 0.000000 +0.437669 -0.899136 0.000000 +0.329043 -0.944315 0.000000 +0.437669 -0.899136 0.000000 +0.329043 -0.944315 0.000000 +0.217098 -0.976150 0.000000 +0.217098 -0.976150 0.000000 +0.329043 -0.944315 0.000000 +0.217098 -0.976150 0.000000 +0.329043 -0.944315 0.000000 +0.217098 -0.976150 0.000000 +0.106429 -0.994320 0.000000 +0.106429 -0.994320 0.000000 +0.217098 -0.976150 0.000000 +0.106429 -0.994320 0.000000 +0.217098 -0.976150 0.000000 +0.106429 -0.994320 0.000000 +0.000238 -1.000000 0.000000 +0.000238 -1.000000 0.000000 +0.106429 -0.994320 0.000000 +0.000238 -1.000000 0.000000 +0.106429 -0.994320 0.000000 +0.000238 -1.000000 0.000000 +-0.105554 -0.994414 0.000000 +-0.105554 -0.994413 0.000000 +0.000238 -1.000000 0.000000 +-0.105554 -0.994413 0.000000 +0.000238 -1.000000 0.000000 +-0.105554 -0.994414 0.000000 +-0.215576 -0.976487 0.000000 +-0.215576 -0.976487 0.000000 +-0.105554 -0.994414 0.000000 +-0.215576 -0.976487 0.000000 +-0.105554 -0.994413 0.000000 +-0.215576 -0.976487 0.000000 +-0.327227 -0.944946 0.000000 +-0.327227 -0.944946 0.000000 +-0.215576 -0.976487 0.000000 +-0.327227 -0.944946 0.000000 +-0.215576 -0.976487 0.000000 +-0.327227 -0.944946 0.000000 +-0.435943 -0.899974 0.000000 +-0.435943 -0.899974 0.000000 +-0.327227 -0.944946 0.000000 +-0.435943 -0.899974 0.000000 +-0.327227 -0.944946 0.000000 +-0.435943 -0.899974 0.000000 +-0.537323 -0.843376 0.000000 +-0.537323 -0.843376 0.000000 +-0.435943 -0.899974 0.000000 +-0.537323 -0.843376 0.000000 +-0.435943 -0.899974 0.000000 +-0.537323 -0.843376 0.000000 +-0.627977 -0.778232 0.000000 +-0.627977 -0.778232 0.000000 +-0.537323 -0.843376 0.000000 +-0.627977 -0.778232 0.000000 +-0.537323 -0.843376 0.000000 +-0.627977 -0.778232 0.000000 +-0.706755 -0.707458 0.000000 +-0.706755 -0.707458 0.000000 +-0.627977 -0.778232 0.000000 +-0.706755 -0.707458 0.000000 +-0.627977 -0.778232 0.000000 +-0.706755 -0.707458 0.000000 +-0.777611 -0.628746 0.000000 +-0.777611 -0.628746 0.000000 +-0.706755 -0.707458 0.000000 +-0.777611 -0.628746 0.000000 +-0.706755 -0.707458 0.000000 +-0.777611 -0.628746 0.000000 +-0.842867 -0.538122 0.000000 +-0.842867 -0.538122 0.000000 +-0.777611 -0.628746 0.000000 +-0.842867 -0.538122 0.000000 +-0.777611 -0.628746 0.000000 +-0.842867 -0.538122 0.000000 +-0.899606 -0.436703 0.000000 +-0.899606 -0.436703 0.000000 +-0.842867 -0.538122 0.000000 +-0.899606 -0.436703 0.000000 +-0.842867 -0.538122 0.000000 +-0.899606 -0.436703 0.000000 +-0.944722 -0.327873 0.000000 +-0.944722 -0.327873 0.000000 +-0.899606 -0.436703 0.000000 +-0.944722 -0.327873 0.000000 +-0.899606 -0.436703 0.000000 +-0.944722 -0.327873 0.000000 +-0.976385 -0.216040 0.000000 +-0.976385 -0.216040 0.000000 +-0.944722 -0.327873 0.000000 +-0.976385 -0.216040 0.000000 +-0.944722 -0.327873 0.000000 +-0.976385 -0.216040 0.000000 +-0.994388 -0.105793 0.000000 +-0.994388 -0.105793 0.000000 +-0.976385 -0.216040 0.000000 +-0.994388 -0.105793 0.000000 +-0.976385 -0.216040 0.000000 +-0.994388 -0.105793 0.000000 +-1.000000 -0.000002 0.000000 +-1.000000 -0.000002 0.000000 +-0.994388 -0.105793 0.000000 +-1.000000 -0.000002 0.000000 +-0.994388 -0.105793 0.000000 +-1.000000 -0.000002 0.000000 +-0.994382 0.105847 0.000000 +-0.994382 0.105847 0.000000 +-1.000000 -0.000002 0.000000 +-0.994382 0.105847 0.000000 +-1.000000 -0.000002 0.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 -1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 +0.000000 0.000000 1.000000 + + + + + + + + + + + + +

0 0 1 1 65 2 0 3 65 4 64 5 1 6 2 7 66 8 1 9 66 10 65 11 2 12 3 13 67 14 2 15 67 16 66 17 3 18 4 19 68 20 3 21 68 22 67 23 4 24 5 25 69 26 4 27 69 28 68 29 5 30 6 31 70 32 5 33 70 34 69 35 6 36 7 37 71 38 6 39 71 40 70 41 7 42 8 43 72 44 7 45 72 46 71 47 8 48 9 49 73 50 8 51 73 52 72 53 9 54 10 55 74 56 9 57 74 58 73 59 10 60 11 61 75 62 10 63 75 64 74 65 11 66 12 67 76 68 11 69 76 70 75 71 12 72 13 73 77 74 12 75 77 76 76 77 13 78 14 79 78 80 13 81 78 82 77 83 14 84 15 85 79 86 14 87 79 88 78 89 15 90 16 91 80 92 15 93 80 94 79 95 16 96 17 97 81 98 16 99 81 100 80 101 17 102 18 103 82 104 17 105 82 106 81 107 18 108 19 109 83 110 18 111 83 112 82 113 19 114 20 115 84 116 19 117 84 118 83 119 20 120 21 121 85 122 20 123 85 124 84 125 21 126 22 127 86 128 21 129 86 130 85 131 22 132 23 133 87 134 22 135 87 136 86 137 23 138 24 139 88 140 23 141 88 142 87 143 24 144 25 145 89 146 24 147 89 148 88 149 25 150 26 151 90 152 25 153 90 154 89 155 26 156 27 157 91 158 26 159 91 160 90 161 27 162 28 163 92 164 27 165 92 166 91 167 28 168 29 169 93 170 28 171 93 172 92 173 29 174 30 175 94 176 29 177 94 178 93 179 30 180 31 181 95 182 30 183 95 184 94 185 31 186 32 187 96 188 31 189 96 190 95 191 32 192 33 193 97 194 32 195 97 196 96 197 33 198 34 199 98 200 33 201 98 202 97 203 34 204 35 205 99 206 34 207 99 208 98 209 35 210 36 211 100 212 35 213 100 214 99 215 36 216 37 217 101 218 36 219 101 220 100 221 37 222 38 223 102 224 37 225 102 226 101 227 38 228 39 229 103 230 38 231 103 232 102 233 39 234 40 235 104 236 39 237 104 238 103 239 40 240 41 241 105 242 40 243 105 244 104 245 41 246 42 247 106 248 41 249 106 250 105 251 42 252 43 253 107 254 42 255 107 256 106 257 43 258 44 259 108 260 43 261 108 262 107 263 44 264 45 265 109 266 44 267 109 268 108 269 45 270 46 271 110 272 45 273 110 274 109 275 46 276 47 277 111 278 46 279 111 280 110 281 47 282 48 283 112 284 47 285 112 286 111 287 48 288 49 289 113 290 48 291 113 292 112 293 49 294 50 295 114 296 49 297 114 298 113 299 50 300 51 301 115 302 50 303 115 304 114 305 51 306 52 307 116 308 51 309 116 310 115 311 52 312 53 313 117 314 52 315 117 316 116 317 53 318 54 319 118 320 53 321 118 322 117 323 54 324 55 325 119 326 54 327 119 328 118 329 55 330 56 331 120 332 55 333 120 334 119 335 56 336 57 337 121 338 56 339 121 340 120 341 57 342 58 343 122 344 57 345 122 346 121 347 58 348 59 349 123 350 58 351 123 352 122 353 59 354 60 355 124 356 59 357 124 358 123 359 60 360 61 361 125 362 60 363 125 364 124 365 61 366 62 367 126 368 61 369 126 370 125 371 62 372 63 373 127 374 62 375 127 376 126 377 63 378 0 379 64 380 63 381 64 382 127 383 128 384 129 385 185 386 128 387 185 388 184 389 129 390 130 391 186 392 129 393 186 394 185 395 130 396 131 397 187 398 130 399 187 400 186 401 131 402 132 403 188 404 131 405 188 406 187 407 132 408 133 409 189 410 132 411 189 412 188 413 133 414 134 415 190 416 133 417 190 418 189 419 134 420 135 421 191 422 134 423 191 424 190 425 135 426 136 427 192 428 135 429 192 430 191 431 136 432 137 433 193 434 136 435 193 436 192 437 137 438 138 439 194 440 137 441 194 442 193 443 138 444 139 445 195 446 138 447 195 448 194 449 139 450 140 451 196 452 139 453 196 454 195 455 140 456 141 457 197 458 140 459 197 460 196 461 141 462 142 463 198 464 141 465 198 466 197 467 142 468 143 469 199 470 142 471 199 472 198 473 143 474 144 475 200 476 143 477 200 478 199 479 144 480 145 481 201 482 144 483 201 484 200 485 145 486 146 487 202 488 145 489 202 490 201 491 146 492 147 493 203 494 146 495 203 496 202 497 147 498 148 499 204 500 147 501 204 502 203 503 148 504 149 505 205 506 148 507 205 508 204 509 149 510 150 511 206 512 149 513 206 514 205 515 150 516 151 517 207 518 150 519 207 520 206 521 151 522 152 523 208 524 151 525 208 526 207 527 152 528 153 529 209 530 152 531 209 532 208 533 153 534 154 535 210 536 153 537 210 538 209 539 154 540 155 541 211 542 154 543 211 544 210 545 155 546 156 547 212 548 155 549 212 550 211 551 156 552 157 553 213 554 156 555 213 556 212 557 157 558 158 559 214 560 157 561 214 562 213 563 158 564 159 565 215 566 158 567 215 568 214 569 159 570 160 571 216 572 159 573 216 574 215 575 160 576 161 577 217 578 160 579 217 580 216 581 161 582 162 583 218 584 161 585 218 586 217 587 162 588 163 589 219 590 162 591 219 592 218 593 163 594 164 595 220 596 163 597 220 598 219 599 164 600 165 601 221 602 164 603 221 604 220 605 165 606 166 607 222 608 165 609 222 610 221 611 166 612 167 613 223 614 166 615 223 616 222 617 167 618 168 619 224 620 167 621 224 622 223 623 168 624 169 625 225 626 168 627 225 628 224 629 169 630 170 631 226 632 169 633 226 634 225 635 170 636 171 637 227 638 170 639 227 640 226 641 171 642 172 643 228 644 171 645 228 646 227 647 172 648 173 649 229 650 172 651 229 652 228 653 173 654 174 655 230 656 173 657 230 658 229 659 174 660 175 661 231 662 174 663 231 664 230 665 175 666 176 667 232 668 175 669 232 670 231 671 176 672 177 673 233 674 176 675 233 676 232 677 177 678 178 679 234 680 177 681 234 682 233 683 178 684 179 685 235 686 178 687 235 688 234 689 179 690 180 691 236 692 179 693 236 694 235 695 180 696 181 697 237 698 180 699 237 700 236 701 181 702 182 703 238 704 181 705 238 706 237 707 182 708 183 709 239 710 182 711 239 712 238 713 183 714 128 715 184 716 183 717 184 718 239 719 62 720 0 721 63 722 61 723 0 724 62 725 61 726 176 727 0 728 60 729 176 730 61 731 60 732 177 733 176 734 60 735 178 736 177 737 59 738 178 739 60 740 59 741 179 742 178 743 58 744 179 745 59 746 58 747 180 748 179 749 57 750 180 751 58 752 56 753 180 754 57 755 56 756 181 757 180 758 55 759 181 760 56 761 55 762 182 763 181 764 54 765 182 766 55 767 53 768 182 769 54 770 53 771 183 772 182 773 52 774 183 775 53 776 52 777 128 778 183 779 51 780 128 781 52 782 51 783 129 784 128 785 50 786 129 787 51 788 50 789 130 790 129 791 49 792 130 793 50 794 49 795 131 796 130 797 48 798 131 799 49 800 48 801 132 802 131 803 47 804 132 805 48 806 47 807 133 808 132 809 46 810 133 811 47 812 46 813 134 814 133 815 45 816 134 817 46 818 45 819 135 820 134 821 44 822 135 823 45 824 44 825 136 826 135 827 43 828 136 829 44 830 43 831 137 832 136 833 42 834 137 835 43 836 42 837 138 838 137 839 41 840 138 841 42 842 41 843 139 844 138 845 40 846 139 847 41 848 40 849 140 850 139 851 39 852 140 853 40 854 39 855 141 856 140 857 39 858 142 859 141 860 38 861 142 862 39 863 38 864 143 865 142 866 37 867 143 868 38 869 37 870 144 871 143 872 36 873 144 874 37 875 35 876 144 877 36 878 35 879 145 880 144 881 34 882 145 883 35 884 34 885 146 886 145 887 33 888 146 889 34 890 33 891 147 892 146 893 32 894 147 895 33 896 32 897 148 898 147 899 31 900 148 901 32 902 31 903 149 904 148 905 30 906 149 907 31 908 30 909 150 910 149 911 29 912 150 913 30 914 29 915 151 916 150 917 28 918 151 919 29 920 28 921 152 922 151 923 27 924 152 925 28 926 27 927 153 928 152 929 26 930 153 931 27 932 26 933 154 934 153 935 25 936 154 937 26 938 25 939 155 940 154 941 24 942 155 943 25 944 24 945 156 946 155 947 23 948 156 949 24 950 23 951 157 952 156 953 22 954 157 955 23 956 22 957 158 958 157 959 21 960 158 961 22 962 21 963 159 964 158 965 20 966 159 967 21 968 20 969 160 970 159 971 19 972 160 973 20 974 19 975 161 976 160 977 18 978 161 979 19 980 18 981 162 982 161 983 17 984 162 985 18 986 17 987 163 988 162 989 16 990 163 991 17 992 16 993 164 994 163 995 15 996 164 997 16 998 15 999 165 1000 164 1001 14 1002 165 1003 15 1004 14 1005 166 1006 165 1007 13 1008 166 1009 14 1010 13 1011 167 1012 166 1013 12 1014 167 1015 13 1016 12 1017 168 1018 167 1019 11 1020 168 1021 12 1022 11 1023 169 1024 168 1025 10 1026 169 1027 11 1028 10 1029 170 1030 169 1031 9 1032 170 1033 10 1034 9 1035 171 1036 170 1037 8 1038 171 1039 9 1040 7 1041 171 1042 8 1043 7 1044 172 1045 171 1046 6 1047 172 1048 7 1049 6 1050 173 1051 172 1052 5 1053 173 1054 6 1055 4 1056 173 1057 5 1058 4 1059 174 1060 173 1061 1 1062 3 1063 2 1064 0 1065 3 1066 1 1067 176 1068 3 1069 0 1070 176 1071 4 1072 3 1073 175 1074 4 1075 176 1076 175 1077 174 1078 4 1079 126 1080 127 1081 64 1082 125 1083 126 1084 64 1085 125 1086 64 1087 232 1088 124 1089 125 1090 232 1091 124 1092 232 1093 233 1094 124 1095 233 1096 234 1097 123 1098 124 1099 234 1100 123 1101 234 1102 235 1103 122 1104 123 1105 235 1106 122 1107 235 1108 236 1109 121 1110 122 1111 236 1112 120 1113 121 1114 236 1115 120 1116 236 1117 237 1118 119 1119 120 1120 237 1121 119 1122 237 1123 238 1124 118 1125 119 1126 238 1127 117 1128 118 1129 238 1130 117 1131 238 1132 239 1133 116 1134 117 1135 239 1136 116 1137 239 1138 184 1139 115 1140 116 1141 184 1142 115 1143 184 1144 185 1145 114 1146 115 1147 185 1148 114 1149 185 1150 186 1151 113 1152 114 1153 186 1154 113 1155 186 1156 187 1157 112 1158 113 1159 187 1160 112 1161 187 1162 188 1163 111 1164 112 1165 188 1166 111 1167 188 1168 189 1169 110 1170 111 1171 189 1172 110 1173 189 1174 190 1175 109 1176 110 1177 190 1178 109 1179 190 1180 191 1181 108 1182 109 1183 191 1184 108 1185 191 1186 192 1187 107 1188 108 1189 192 1190 107 1191 192 1192 193 1193 106 1194 107 1195 193 1196 106 1197 193 1198 194 1199 105 1200 106 1201 194 1202 105 1203 194 1204 195 1205 104 1206 105 1207 195 1208 104 1209 195 1210 196 1211 103 1212 104 1213 196 1214 103 1215 196 1216 197 1217 103 1218 197 1219 198 1220 102 1221 103 1222 198 1223 102 1224 198 1225 199 1226 101 1227 102 1228 199 1229 101 1230 199 1231 200 1232 100 1233 101 1234 200 1235 99 1236 100 1237 200 1238 99 1239 200 1240 201 1241 98 1242 99 1243 201 1244 98 1245 201 1246 202 1247 97 1248 98 1249 202 1250 97 1251 202 1252 203 1253 96 1254 97 1255 203 1256 96 1257 203 1258 204 1259 95 1260 96 1261 204 1262 95 1263 204 1264 205 1265 94 1266 95 1267 205 1268 94 1269 205 1270 206 1271 93 1272 94 1273 206 1274 93 1275 206 1276 207 1277 92 1278 93 1279 207 1280 92 1281 207 1282 208 1283 91 1284 92 1285 208 1286 91 1287 208 1288 209 1289 90 1290 91 1291 209 1292 90 1293 209 1294 210 1295 89 1296 90 1297 210 1298 89 1299 210 1300 211 1301 88 1302 89 1303 211 1304 88 1305 211 1306 212 1307 87 1308 88 1309 212 1310 87 1311 212 1312 213 1313 86 1314 87 1315 213 1316 86 1317 213 1318 214 1319 85 1320 86 1321 214 1322 85 1323 214 1324 215 1325 84 1326 85 1327 215 1328 84 1329 215 1330 216 1331 83 1332 84 1333 216 1334 83 1335 216 1336 217 1337 82 1338 83 1339 217 1340 82 1341 217 1342 218 1343 81 1344 82 1345 218 1346 81 1347 218 1348 219 1349 80 1350 81 1351 219 1352 80 1353 219 1354 220 1355 79 1356 80 1357 220 1358 79 1359 220 1360 221 1361 78 1362 79 1363 221 1364 78 1365 221 1366 222 1367 77 1368 78 1369 222 1370 77 1371 222 1372 223 1373 76 1374 77 1375 223 1376 76 1377 223 1378 224 1379 75 1380 76 1381 224 1382 75 1383 224 1384 225 1385 74 1386 75 1387 225 1388 74 1389 225 1390 226 1391 73 1392 74 1393 226 1394 73 1395 226 1396 227 1397 72 1398 73 1399 227 1400 71 1401 72 1402 227 1403 71 1404 227 1405 228 1406 70 1407 71 1408 228 1409 70 1410 228 1411 229 1412 69 1413 70 1414 229 1415 68 1416 69 1417 229 1418 68 1419 229 1420 230 1421 65 1422 66 1423 67 1424 64 1425 65 1426 67 1427 232 1428 64 1429 67 1430 232 1431 67 1432 68 1433 231 1434 232 1435 68 1436 231 1437 68 1438 230 1439

+
+
+
+ + + + + 1.000000 1.000000 1.000000 + + + + + + + 1.000000 0.000000 0.000000 0.992424 0.000000 1.000000 0.000000 -23.446840 0.000000 0.000000 1.000000 0.000000 0.000000 0.000000 0.000000 1.000000 + + + + + + + + +
diff --git a/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/package.xml b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/package.xml new file mode 100755 index 0000000..1810f29 --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/package.xml @@ -0,0 +1,30 @@ + + spencer_tracking_rviz_plugin + 1.0.8 + + + RViz plugin for visualizing tracked and detected persons and groups + + + Timm Linder + Timm Linder + + BSD; CC BY 3.0 (Fugue Icons by Yusuke Kamiyamane) + + catkin + + rviz + spencer_tracking_msgs + spencer_social_relation_msgs + spencer_human_attribute_msgs + + rviz + spencer_tracking_msgs + spencer_social_relation_msgs + spencer_human_attribute_msgs + + + + + +roslibroslib diff --git a/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/plugin_description.xml b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/plugin_description.xml new file mode 100755 index 0000000..78b9c56 --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/plugin_description.xml @@ -0,0 +1,45 @@ + + + + + Displays detected persons from spencer_tracking_msgs/DetectedPersons messages. + + spencer_tracking_msgs/DetectedPersons + + + + + Displays tracked persons from spencer_tracking_msgs/TrackedPersons messages. + + spencer_tracking_msgs/TrackedPersons + + + + + Displays tracked groups from spencer_tracking_msgs/TrackedGroups messages. + + spencer_tracking_msgs/TrackedGroups + + + + + Displays social relations from spencer_social_relation_msgs/SocialRelations messages. + + spencer_social_relation_msgs/SocialRelations + + + + + Displays social activities from spencer_social_relation_msgs/SocialActivities messages. + + spencer_social_relation_msgs/SocialActivities + + + + + Displays human attributes from spencer_human_attribute_msgs/HumanAttributes messages. + + spencer_human_attribute_msgs/HumanAttributes + + + diff --git a/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/scripts/send_test_msgs.py b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/scripts/send_test_msgs.py new file mode 100755 index 0000000..2da62e4 --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/scripts/send_test_msgs.py @@ -0,0 +1,125 @@ +#!/usr/bin/env python + +import roslib; roslib.load_manifest( 'spencer_tracking_rviz_plugin' ) +from spencer_tracking_msgs.msg import TrackedPersons, TrackedPerson, DetectedPersons, DetectedPerson +import rospy +from math import cos, sin, tan, pi +import tf +import random +import copy + +def setPoseAndTwistFromAngle( pose, twist, angle, radius ) : + currentx = radius * cos(angle) + currenty = radius * sin(angle) + + nextx = radius * cos(angle + angleStep) + nexty = radius * sin(angle + angleStep) + + pose.pose.position.x = currentx + pose.pose.position.y = currenty + pose.pose.position.z = 0.0 + + quaternion = tf.transformations.quaternion_from_euler(0, 0, angle + pi/2.0) + pose.pose.orientation.x = quaternion[0] + pose.pose.orientation.y = quaternion[1] + pose.pose.orientation.z = quaternion[2] + pose.pose.orientation.w = quaternion[3] + + pose.covariance[0 + 0 * 6] = 0.4 # x + pose.covariance[1 + 1 * 6] = 0.2 # y + pose.covariance[2 + 2 * 6] = 999999 # z + pose.covariance[3 + 3 * 6] = 0.0 # x rotation + pose.covariance[4 + 5 * 6] = 0.0 # y rotation + pose.covariance[4 + 5 * 6] = 0.1 # z rotation + + twist.twist.linear.x = nextx - currentx + twist.twist.linear.y = nexty - currenty + twist.twist.linear.z = 0 + + for i in range(0, 3): + twist.covariance[i + i * 6] = 1.0 # linear velocity + for i in range(3, 6): + twist.covariance[i + i * 6] = float("inf") # rotational velocity + +def createTrackAndDetection( tracks, detections, track_id, detection_id, angle, radius ) : + trackedPerson = TrackedPerson() + trackedPerson.track_id = track_id + + if detection_id >= 0 : + trackedPerson.detection_id = detection_id + trackedPerson.is_occluded = False + else : + trackedPerson.is_occluded = True + + trackedPerson.age = rospy.Time.now() - startTime + + setPoseAndTwistFromAngle(trackedPerson.pose, trackedPerson.twist, angle, radius) + tracks.append(trackedPerson) + + if detection_id >= 0: + detectedPerson = DetectedPerson() + detectedPerson.detection_id = detection_id + detectedPerson.confidence = random.random() + + detectedPerson.pose = copy.deepcopy(trackedPerson.pose) + detectedPerson.pose.pose.position.x += random.random() * 0.5 - 0.25 # introduce some noise on observation position + detectedPerson.pose.pose.position.y += random.random() * 0.5 - 0.25 + + detections.append(detectedPerson) + + return + +# Main code +trackTopic = '/spencer/tracked_persons' +trackPublisher = rospy.Publisher( trackTopic, TrackedPersons ) + +observationTopic = '/spencer/detected_persons' +observationPublisher = rospy.Publisher( observationTopic, DetectedPersons ) + +rospy.init_node( 'publish_test_tracks_and_detections' ) +br = tf.TransformBroadcaster() + +# State variables +startTime = rospy.Time.now() +currentCycle = 0 +currentAngle = 0.0 +angleStep = 4.5 * pi / 180. +idShift = 0 +updateRateHz = 10 + +# Test coordinate frame for checking if mapping into the fixed frame works correctly +frameOffset = (0, 0, 0) +frameOrientation = tf.transformations.quaternion_from_euler(0, 0, 0) # 90.0 / 180.0 * pi + +print("Sending test messages on " + observationTopic + " and " + trackTopic) +rate = rospy.Rate(updateRateHz) +while not rospy.is_shutdown(): + br.sendTransform(frameOffset, frameOrientation, rospy.Time.now(), "test_tf_frame", "odom") + + trackedPersons = TrackedPersons() + trackedPersons.header.frame_id = "/test_tf_frame" + trackedPersons.header.stamp = rospy.Time.now() + + detectedPersons = DetectedPersons() + detectedPersons.header = trackedPersons.header + + tracks = trackedPersons.tracks; + detections = detectedPersons.detections; + + createTrackAndDetection(tracks, detections, idShift+0, 3, currentAngle, 2.0) + createTrackAndDetection(tracks, detections, idShift+1, 7, currentAngle + pi / 2, 2.5) + createTrackAndDetection(tracks, detections, idShift+2, -1, currentAngle + pi / 1, 3.0) + createTrackAndDetection(tracks, detections, idShift+3, -1, currentAngle + pi * 1.5, cos(currentAngle) * 3.5 + 7.0) + createTrackAndDetection(tracks, detections, idShift+4, 88, 0.0, 0.0) + + trackPublisher.publish( trackedPersons ) + observationPublisher.publish( detectedPersons ) + + currentAngle += angleStep + currentCycle += 1 + + # Periodically shift the IDs to simulate tracks being removed and new tracks being added + if(currentCycle % (updateRateHz * 15) == 0) : + idShift += len(tracks) + + rate.sleep() \ No newline at end of file diff --git a/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/src/additional_topic_subscriber.h b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/src/additional_topic_subscriber.h new file mode 100755 index 0000000..2cbe41a --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/src/additional_topic_subscriber.h @@ -0,0 +1,221 @@ +/* +* Software License Agreement (BSD License) +* +* Copyright (c) 2013-2015, Timm Linder, Social Robotics Lab, University of Freiburg +* Copyright (c) 2012, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* * Redistributions of source code must retain the above copyright notice, this +* list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above copyright notice, +* this list of conditions and the following disclaimer in the documentation +* and/or other materials provided with the distribution. +* * Neither the name of the copyright holder nor the names of its contributors +* may be used to endorse or promote products derived from this software +* without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*/ +#ifndef ADDITIONAL_TOPIC_SUBSCRIBER_H +#define ADDITIONAL_TOPIC_SUBSCRIBER_H + +#ifndef Q_MOC_RUN +#include +#if ROS_VERSION_MINIMUM(1, 14, 0) +#include +#else +#include +#endif + +#include +#include +#include +#include +#include +#endif + +#include +#include +#include +#include + + +using namespace boost; + +namespace rviz +{ + +/** @brief Helper superclass for AdditionalTopicSubscriber, needed because + * Qt's moc and c++ templates don't work nicely together. Not + * intended to be used directly. */ +class _AdditionalTopicSubscriber : public QObject +{ +Q_OBJECT +public: + void initialize(Display* display, FrameManager* frameManager) + { + QObject::connect(display, SIGNAL(changed()), this, SLOT(displayEnableChanged())); + QObject::connect(frameManager, SIGNAL(fixedFrameChanged()), this, SLOT(fixedFrameChanged())); + additional_topic_property_ = new RosTopicProperty("Additional topic", "", "", "", display, SLOT(updateTopic()), this); + } + +protected Q_SLOTS: + virtual void updateTopic() = 0; + virtual void displayEnableChanged() = 0; + virtual void fixedFrameChanged() = 0; + +protected: + RosTopicProperty* additional_topic_property_; +}; + +/** @brief Display subclass using a tf::MessageFilter, templated on the ROS message type. + * + * This class brings together some common things used in many Display + * types. It has a tf::MessageFilter to filter incoming messages, and + * it handles subscribing and unsubscribing when the display is + * enabled or disabled. It also has an Ogre::SceneNode which */ +template +class AdditionalTopicSubscriber: public _AdditionalTopicSubscriber +{ +// No Q_OBJECT macro here, moc does not support Q_OBJECT in a templated class. +public: + /** @brief Convenience typedef so subclasses don't have to use + * the long templated class name to refer to their super class. */ + typedef AdditionalTopicSubscriber ATSClass; + + AdditionalTopicSubscriber(const QString& propertyName, Display* display, DisplayContext* context, ros::NodeHandle& update_nh, const boost::function)>& messageCallback) + : tf_filter(NULL), m_messagesReceived(0), m_display(display), m_context(context), m_updateNodeHandle(update_nh), m_enabled(false), m_messageCallback(messageCallback) + { + _AdditionalTopicSubscriber::initialize(display, context->getFrameManager()); + + additional_topic_property_->setName(propertyName); + QString message_type = QString::fromStdString(ros::message_traits::datatype()); + additional_topic_property_->setMessageType(message_type); + additional_topic_property_->setDescription(message_type + " topic to subscribe to."); + +#if ROS_VERSION_MINIMUM(1, 14, 0) + tf_filter = new tf2_ros::MessageFilter(*m_context->getTF2BufferPtr(), "map", 10, m_updateNodeHandle); +#else + tf_filter = new tf::MessageFilter(*m_context->getTFClient(), "map", 10, m_updateNodeHandle); +#endif + + tf_filter->connectInput(m_subscriber); + tf_filter->registerCallback(boost::bind(&AdditionalTopicSubscriber::incomingMessage, this, _1)); + m_context->getFrameManager()->registerFilterForTransformStatusCheck(tf_filter, display); + + setEnabled(m_display->isEnabled()); + updateTopic(); + fixedFrameChanged(); + } + + virtual ~AdditionalTopicSubscriber() + { + unsubscribe(); + delete tf_filter; + } + + virtual void reset() + { + tf_filter->clear(); + m_messagesReceived = 0; + } + + void setEnabled(bool enabled) + { + m_enabled = enabled; + if (enabled) subscribe(); + } + +protected: + virtual void updateTopic() + { + ROS_DEBUG_STREAM_NAMED("AdditionalTopicSubscriber", "AdditionalTopicSubscriber: Topic was changed to " << additional_topic_property_->getTopicStd()); + unsubscribe(); + reset(); + subscribe(); + m_context->queueRender(); + } + + virtual void displayEnableChanged() + { + ROS_DEBUG_STREAM_NAMED("AdditionalTopicSubscriber", "AdditionalTopicSubscriber: Display enabled = " << m_display->getBool()); + setEnabled(m_display->getBool()); + } + + virtual void fixedFrameChanged() + { + ROS_DEBUG_STREAM_NAMED("AdditionalTopicSubscriber", "AdditionalTopicSubscriber: Fixed frame has changed for topic " << additional_topic_property_->getTopicStd()); + tf_filter->setTargetFrame(m_context->getFixedFrame().toStdString()); + reset(); + } + + virtual void subscribe() + { + if (!m_display->isEnabled()) { + return; + } + + try { + ROS_DEBUG_STREAM_NAMED("AdditionalTopicSubscriber", "AdditionalTopicSubscriber: Subscribing to topic " << additional_topic_property_->getTopicStd()); + m_subscriber.subscribe(m_updateNodeHandle, additional_topic_property_->getTopicStd(), 10); + m_display->setStatus(StatusProperty::Ok, additional_topic_property_->getName(), "OK"); + } + catch (ros::Exception& e) { + m_display->setStatus(StatusProperty::Error, additional_topic_property_->getName(), QString("Error subscribing: ") + e.what()); + } + } + + virtual void unsubscribe() + { + m_subscriber.unsubscribe(); + } + + /** @brief Incoming message callback. Checks if the message pointer + * is valid, increments m_messagesReceived, then calls + * processMessage(). */ + void incomingMessage(const typename MessageType::ConstPtr& msg) + { + if (!msg) { + return; + } + + ++m_messagesReceived; + m_display->setStatus(StatusProperty::Ok, additional_topic_property_->getName(), QString::number(m_messagesReceived) + " messages received"); + + // Callback for further processing + m_messageCallback(msg); + } + +#if ROS_VERSION_MINIMUM(1, 14, 0) + tf2_ros::MessageFilter* tf_filter; +#else + tf::MessageFilter* tf_filter; +#endif + +private: + std::string m_topic; + bool m_enabled; + Display* m_display; + DisplayContext* m_context; + ros::NodeHandle m_updateNodeHandle; + message_filters::Subscriber m_subscriber; + uint32_t m_messagesReceived; + + const boost::function)> m_messageCallback; +}; + +} // end namespace rviz + +#endif // ADDITIONAL_TOPIC_SUBSCRIBER_H diff --git a/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/src/detected_persons_display.cpp b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/src/detected_persons_display.cpp new file mode 100755 index 0000000..766f4fa --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/src/detected_persons_display.cpp @@ -0,0 +1,279 @@ +/* +* Software License Agreement (BSD License) +* +* Copyright (c) 2013-2015, Timm Linder, Social Robotics Lab, University of Freiburg +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* * Redistributions of source code must retain the above copyright notice, this +* list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above copyright notice, +* this list of conditions and the following disclaimer in the documentation +* and/or other materials provided with the distribution. +* * Neither the name of the copyright holder nor the names of its contributors +* may be used to endorse or promote products derived from this software +* without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*/ + +#include +#include +#include "rviz/selection/selection_manager.h" + +#include "detected_persons_display.h" +#ifndef Q_MOC_RUN +#include +#endif +#define foreach BOOST_FOREACH + +namespace spencer_tracking_rviz_plugin +{ + +// The constructor must have no arguments, so we can't give the +// constructor the parameters it needs to fully initialize. +void DetectedPersonsDisplay::onInitialize() +{ + PersonDisplayCommon::onInitialize(); + + QObject::connect(m_commonProperties->style, SIGNAL(changed()), this, SLOT(personVisualTypeChanged()) ); + + m_render_covariances_property = new rviz::BoolProperty( "Render covariances", true, "Render track covariance ellipses", this, SLOT(stylesChanged()) ); + m_render_detection_ids_property = new rviz::BoolProperty( "Render detection IDs", true, "Render IDs of the detection that a track was matched against, if any", this, SLOT(stylesChanged())); + m_render_confidences_property = new rviz::BoolProperty( "Render confidences", false, "Render detection confidences", this, SLOT(stylesChanged())); + m_render_orientations_property = new rviz::BoolProperty( "Render orientation arrows", true, "Render orientation arrows (only if orientation covariances are finite!)", this, SLOT(stylesChanged())); + m_render_modality_text_property = new rviz::BoolProperty( "Render modality text", false, "Render detection modality as text below detected person", this, SLOT(stylesChanged())); + + m_text_spacing_property = new rviz::FloatProperty( "Text spacing", 1.0, "Factor for vertical spacing betweent texts", this, SLOT(stylesChanged()), this ); + + m_low_confidence_threshold_property = new rviz::FloatProperty( "Low-confidence threshold", 0.5, "Detection confidence below which alpha will be reduced", this, SLOT(stylesChanged())); + m_low_confidence_alpha_property = new rviz::FloatProperty( "Low-confidence alpha", 0.5, "Alpha multiplier for detections with confidence below low-confidence threshold", this, SLOT(stylesChanged())); + + m_covariance_line_width_property = new rviz::FloatProperty( "Line width", 0.1, "Line width of covariance ellipses", m_render_covariances_property, SLOT(stylesChanged()), this ); +} + +DetectedPersonsDisplay::~DetectedPersonsDisplay() +{ + m_previousDetections.clear(); +} + +// Clear the visuals by deleting their objects. +void DetectedPersonsDisplay::reset() +{ + PersonDisplayCommon::reset(); + m_previousDetections.clear(); +} + +// Set the rendering style (cylinders, meshes, ...) of detected persons +void DetectedPersonsDisplay::personVisualTypeChanged() +{ + foreach(boost::shared_ptr& detectedPersonVisual, m_previousDetections) + { + detectedPersonVisual->personVisual.reset(); + createPersonVisualIfRequired(detectedPersonVisual->sceneNode.get(), detectedPersonVisual->personVisual); + } + stylesChanged(); +} + +// Update dynamically adjustable properties of all existing detections +void DetectedPersonsDisplay::stylesChanged() +{ + foreach(boost::shared_ptr detectedPersonVisual, m_previousDetections) + { + bool personHidden = isPersonHidden(detectedPersonVisual->detectionId); + + // Update common styles to person visual, such as line width + applyCommonStyles(detectedPersonVisual->personVisual); + + // Get current detection color + Ogre::ColourValue detectionColor = getColorFromId(detectedPersonVisual->detectionId); + detectionColor.a *= m_commonProperties->alpha->getFloat(); // general alpha + if(personHidden) detectionColor.a = 0.0; + if(detectedPersonVisual->confidence < m_low_confidence_threshold_property->getFloat()) detectionColor.a *= m_low_confidence_alpha_property->getFloat(); + + if(detectedPersonVisual->personVisual) { + detectedPersonVisual->personVisual->setColor(detectionColor); + } + + // Update texts + Ogre::ColourValue fontColor = m_commonProperties->font_color_style->getOptionInt() == FONT_COLOR_CONSTANT ? m_commonProperties->constant_font_color->getOgreColor() : detectionColor; + fontColor.a = m_commonProperties->alpha->getFloat(); + if(personHidden) fontColor.a = 0.0; + + float textOffset = 0.0f; + detectedPersonVisual->detectionIdText->setCharacterHeight(0.18 * m_commonProperties->font_scale->getFloat()); + detectedPersonVisual->detectionIdText->setPosition(Ogre::Vector3(0,0, -0.5*detectedPersonVisual->detectionIdText->getCharacterHeight() - textOffset)); + detectedPersonVisual->detectionIdText->setVisible(m_render_detection_ids_property->getBool()); + detectedPersonVisual->detectionIdText->setColor(fontColor); + if(m_render_detection_ids_property->getBool()) textOffset += m_text_spacing_property->getFloat() * detectedPersonVisual->detectionIdText->getCharacterHeight(); + + detectedPersonVisual->modalityText->setCharacterHeight(0.18 * m_commonProperties->font_scale->getFloat()); + detectedPersonVisual->modalityText->setPosition(Ogre::Vector3(textOffset, 0, -0.5*detectedPersonVisual->modalityText->getCharacterHeight() - textOffset)); + detectedPersonVisual->modalityText->setVisible(m_render_modality_text_property->getBool()); + detectedPersonVisual->modalityText->setColor(fontColor); + if(m_render_modality_text_property->getBool()) textOffset += m_text_spacing_property->getFloat() * detectedPersonVisual->modalityText->getCharacterHeight(); + + detectedPersonVisual->confidenceText->setCharacterHeight(0.13 * m_commonProperties->font_scale->getFloat()); + detectedPersonVisual->confidenceText->setPosition(Ogre::Vector3(textOffset, 0, -0.5*detectedPersonVisual->confidenceText->getCharacterHeight() - textOffset)); + detectedPersonVisual->confidenceText->setVisible(m_render_confidences_property->getBool()); + detectedPersonVisual->confidenceText->setColor(fontColor); + if(m_render_confidences_property->getBool()) textOffset += m_text_spacing_property->getFloat() * detectedPersonVisual->confidenceText->getCharacterHeight(); + + // Set color of covariance visualization + Ogre::ColourValue covarianceColor = detectionColor; + if(!m_render_covariances_property->getBool()) covarianceColor.a = 0.0; + detectedPersonVisual->covarianceVisual->setColor(covarianceColor); + detectedPersonVisual->covarianceVisual->setLineWidth(m_covariance_line_width_property->getFloat()); + + // Update orientation arrow + double arrowAlpha = m_render_orientations_property->getBool() && detectedPersonVisual->hasValidOrientation ? detectionColor.a : 0.0; + detectedPersonVisual->orientationArrow->setColor(Ogre::ColourValue(detectionColor.r, detectionColor.g, detectionColor.b, arrowAlpha)); + const double shaftLength = 0.5, shaftDiameter = 0.05, headLength = 0.2, headDiameter = 0.2; + detectedPersonVisual->orientationArrow->set(shaftLength, shaftDiameter, headLength, headDiameter); + } +} + +// This is our callback to handle an incoming message. +void DetectedPersonsDisplay::processMessage(const spencer_tracking_msgs::DetectedPersons::ConstPtr& msg) +{ + // Get transforms into fixed frame etc. + if(!preprocessMessage(msg)) return; + + const Ogre::Quaternion shapeQuaternion( Ogre::Degree(90), Ogre::Vector3(1,0,0) ); // required to fix orientation of any Cylinder shapes + stringstream ss; + + // Clear previous detections, this will also delete them from the scene graph + m_previousDetections.clear(); + + // + // Iterate over all detections in this message and create a visual representation + // + for (vector::const_iterator detectedPersonIt = msg->detections.begin(); detectedPersonIt != msg->detections.end(); ++detectedPersonIt) + { + boost::shared_ptr detectedPersonVisual; + + // Create a new visual representation of the detected person + detectedPersonVisual = boost::shared_ptr(new DetectedPersonVisual); + m_previousDetections.push_back(detectedPersonVisual); + + // This scene node is the parent of all visualization elements for the detected person + detectedPersonVisual->sceneNode = boost::shared_ptr(scene_node_->createChildSceneNode()); + detectedPersonVisual->detectionId = detectedPersonIt->detection_id; + detectedPersonVisual->confidence = detectedPersonIt->confidence; + Ogre::SceneNode* currentSceneNode = detectedPersonVisual->sceneNode.get(); + + + // + // Person visualization + // + + // Create new visual for the person itself, if needed + boost::shared_ptr &personVisual = detectedPersonVisual->personVisual; + createPersonVisualIfRequired(currentSceneNode, personVisual); + + const double personHeight = personVisual ? personVisual->getHeight() : 0; + const double halfPersonHeight = personHeight / 2.0; + + + // + // Position & visibility of entire detection + // + + const Ogre::Matrix3 covXYZinTargetFrame = covarianceXYZIntoTargetFrame(detectedPersonIt->pose); + setPoseOrientation(currentSceneNode, detectedPersonIt->pose, covXYZinTargetFrame, personHeight); + + // + // Texts + // + { + // Detection ID + if (!detectedPersonVisual->detectionIdText) { + detectedPersonVisual->detectionIdText.reset(new TextNode(context_->getSceneManager(), currentSceneNode)); + detectedPersonVisual->detectionIdText->showOnTop(); + } + + ss.str(""); ss << "det " << detectedPersonIt->detection_id; + detectedPersonVisual->detectionIdText->setCaption(ss.str()); + + // Confidence value + if (!detectedPersonVisual->confidenceText) { + detectedPersonVisual->confidenceText.reset(new TextNode(context_->getSceneManager(), currentSceneNode)); + } + + ss.str(""); ss << fixed << setprecision(2) << detectedPersonIt->confidence; + detectedPersonVisual->confidenceText->setCaption(ss.str()); + detectedPersonVisual->confidenceText->showOnTop(); + + // Modality text + if (!detectedPersonVisual->modalityText) { + detectedPersonVisual->modalityText.reset(new TextNode(context_->getSceneManager(), currentSceneNode)); + } + + ss.str(""); ss << detectedPersonIt->modality; + detectedPersonVisual->modalityText->setCaption(ss.str()); + detectedPersonVisual->modalityText->showOnTop(); + } + + // + // Covariance visualization + // + if(!detectedPersonVisual->covarianceVisual) { + detectedPersonVisual->covarianceVisual.reset(new ProbabilityEllipseCovarianceVisual(context_->getSceneManager(), currentSceneNode)); + } + + // Update covariance ellipse + { + Ogre::Vector3 covarianceMean(0,0,0); // zero mean because parent node is already centered at pose mean + detectedPersonVisual->covarianceVisual->setOrientation(currentSceneNode->getOrientation().Inverse()); + detectedPersonVisual->covarianceVisual->setMeanCovariance(covarianceMean, covXYZinTargetFrame); + } + + + // + // Orientation arrows + // + if (!detectedPersonVisual->orientationArrow) { + detectedPersonVisual->orientationArrow.reset(new rviz::Arrow(context_->getSceneManager(), currentSceneNode)); + } + + // Update orientation arrow + { + const Ogre::Vector3 forwardVector(1,0,0); + + const double personRadius = 0.2; + const Ogre::Vector3 arrowAttachPoint(personRadius, 0, halfPersonHeight); // relative to tracked person's scene node + detectedPersonVisual->orientationArrow->setPosition(arrowAttachPoint); + detectedPersonVisual->orientationArrow->setOrientation(Ogre::Vector3::NEGATIVE_UNIT_Z.getRotationTo(forwardVector)); + detectedPersonVisual->hasValidOrientation = hasValidOrientation(detectedPersonIt->pose); + } + + } // end for loop over all detected persons + + // Set all properties that can dynamically be adjusted in the GUI + stylesChanged(); + + // + // Update status (shown in property pane) + // + ss.str(""); + ss << msg->detections.size() << " detections received"; + setStatusStd(rviz::StatusProperty::Ok, "Tracks", ss.str()); +} + +} // end namespace spencer_tracking_rviz_plugin + +// Tell pluginlib about this class. It is important to do this in +// global scope, outside our package's namespace. +#include +PLUGINLIB_EXPORT_CLASS(spencer_tracking_rviz_plugin::DetectedPersonsDisplay, rviz::Display) diff --git a/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/src/detected_persons_display.h b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/src/detected_persons_display.h new file mode 100755 index 0000000..d210b59 --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/src/detected_persons_display.h @@ -0,0 +1,114 @@ +/* +* Software License Agreement (BSD License) +* +* Copyright (c) 2013-2015, Timm Linder, Social Robotics Lab, University of Freiburg +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* * Redistributions of source code must retain the above copyright notice, this +* list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above copyright notice, +* this list of conditions and the following disclaimer in the documentation +* and/or other materials provided with the distribution. +* * Neither the name of the copyright holder nor the names of its contributors +* may be used to endorse or promote products derived from this software +* without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*/ + +#ifndef DETECTED_PERSONS_DISPLAY_H +#define DETECTED_PERSONS_DISPLAY_H + +#ifndef Q_MOC_RUN +#include +#include +#include +#include "person_display_common.h" +#endif + +namespace spencer_tracking_rviz_plugin +{ + /// The visual of a tracked person. + struct DetectedPersonVisual + { + boost::shared_ptr sceneNode; + + boost::shared_ptr personVisual; + boost::shared_ptr detectionIdText, confidenceText, modalityText; + boost::shared_ptr orientationArrow; + boost::shared_ptr covarianceVisual; + + float confidence; + bool hasValidOrientation; + unsigned int detectionId; + }; + + // The DetectedPersonsDisplay class itself just implements a circular buffer, + // editable parameters, and Display subclass machinery. + class DetectedPersonsDisplay: public PersonDisplayCommon + { + Q_OBJECT + public: + // Constructor. pluginlib::ClassLoader creates instances by calling + // the default constructor, so make sure you have one. + DetectedPersonsDisplay() {}; + virtual ~DetectedPersonsDisplay(); + + // Overrides of protected virtual functions from Display. As much + // as possible, when Displays are not enabled, they should not be + // subscribed to incoming data and should not show anything in the + // 3D view. These functions are where these connections are made + // and broken. + + virtual void onInitialize(); + + protected: + // A helper to clear this display back to the initial state. + virtual void reset(); + + // Must be implemented by derived classes because MOC doesn't work in templates + virtual rviz::DisplayContext* getContext() { + return context_; + } + + private Q_SLOTS: + void personVisualTypeChanged(); + + // Called whenever one of the properties in PersonDisplayCommonProperties has been changed + virtual void stylesChanged(); + + private: + // Function to handle an incoming ROS message. + void processMessage(const spencer_tracking_msgs::DetectedPersons::ConstPtr& msg); + + // All currently active tracks, with unique track ID as map key + vector > m_previousDetections; + + // Properties + rviz::BoolProperty* m_render_covariances_property; + rviz::BoolProperty* m_render_detection_ids_property; + rviz::BoolProperty* m_render_confidences_property; + rviz::FloatProperty* m_low_confidence_threshold_property; + rviz::FloatProperty* m_low_confidence_alpha_property; + rviz::BoolProperty* m_render_orientations_property; + rviz::BoolProperty* m_render_modality_text_property; + + rviz::FloatProperty* m_text_spacing_property; + rviz::FloatProperty* m_covariance_line_width_property; + }; + +} // end namespace spencer_tracking_rviz_plugin + +#endif // DETECTED_PERSONS_DISPLAY_H diff --git a/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/src/human_attributes_display.cpp b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/src/human_attributes_display.cpp new file mode 100755 index 0000000..db71e15 --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/src/human_attributes_display.cpp @@ -0,0 +1,289 @@ +/* +* Software License Agreement (BSD License) +* +* Copyright (c) 2013-2015, Timm Linder, Social Robotics Lab, University of Freiburg +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* * Redistributions of source code must retain the above copyright notice, this +* list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above copyright notice, +* this list of conditions and the following disclaimer in the documentation +* and/or other materials provided with the distribution. +* * Neither the name of the copyright holder nor the names of its contributors +* may be used to endorse or promote products derived from this software +* without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*/ + +#include +#include + +#ifndef Q_MOC_RUN +#include "human_attributes_display.h" +#include +#include +#include +#include +#endif +#define foreach BOOST_FOREACH + +namespace spencer_tracking_rviz_plugin +{ + +void HumanAttributesDisplay::onInitialize() +{ + m_trackedPersonsCache.initialize(this, context_, update_nh_); + PersonDisplayCommon::onInitialize(); + + m_render_gender_property = new rviz::BoolProperty( "Render gender", true, "Render gender visual", this, SLOT(stylesChanged())); + m_render_age_group_property = new rviz::BoolProperty( "Render age group", true, "Render age group visual", this, SLOT(stylesChanged())); + m_render_person_height_property = new rviz::BoolProperty( "Render person height", true, "Render person height", this, SLOT(stylesChanged())); + + m_occlusion_alpha_property = new rviz::FloatProperty( "Occlusion alpha", 0.5, "Alpha multiplier for occluded tracks", this, SLOT(stylesChanged()) ); + m_occlusion_alpha_property->setMin( 0.0 ); + + m_commonProperties->z_offset->setFloat(2.7f); + m_commonProperties->style->setHidden(true); +} + +HumanAttributesDisplay::~HumanAttributesDisplay() +{ +} + +// Clear the visuals by deleting their objects. +void HumanAttributesDisplay::reset() +{ + PersonDisplayCommon::reset(); + m_trackedPersonsCache.reset(); + m_humanAttributeVisuals.clear(); + scene_node_->removeAndDestroyAllChildren(); // not sure if required? +} + +void HumanAttributesDisplay::update(float wall_dt, float ros_dt) +{} + +void HumanAttributesDisplay::stylesChanged() +{ + foreach(boost::shared_ptr humanAttributeVisual, m_humanAttributeVisuals | boost::adaptors::map_values) { + updateVisualStyles(humanAttributeVisual); + } +} + +void HumanAttributesDisplay::updateVisualStyles(boost::shared_ptr& humanAttributeVisual) +{ + track_id trackId = humanAttributeVisual->trackId; + bool personHidden = isPersonHidden(trackId); + + boost::shared_ptr trackedPerson = m_trackedPersonsCache.lookup(trackId); + float occlusionAlpha = trackedPerson->isOccluded ? m_occlusion_alpha_property->getFloat() : 1.0; + + // Update text colors, size and visibility + Ogre::ColourValue fontColor = m_commonProperties->font_color_style->getOptionInt() == FONT_COLOR_CONSTANT ? m_commonProperties->constant_font_color->getOgreColor() : getColorFromId(trackId); + fontColor.a = m_commonProperties->alpha->getFloat() * occlusionAlpha; + if(personHidden) fontColor.a = 0; + + humanAttributeVisual->ageGroupText->setVisible(m_render_age_group_property->getBool()); + humanAttributeVisual->ageGroupText->setCharacterHeight(0.17 * m_commonProperties->font_scale->getFloat()); + humanAttributeVisual->ageGroupText->setColor(fontColor); + humanAttributeVisual->ageGroupText->setPosition(Ogre::Vector3(0, 0, 0.17 * m_commonProperties->font_scale->getFloat()) ); + + humanAttributeVisual->personHeightText->setVisible(m_render_person_height_property->getBool()); + humanAttributeVisual->personHeightText->setCharacterHeight(0.17 * m_commonProperties->font_scale->getFloat()); + humanAttributeVisual->personHeightText->setColor(fontColor); + humanAttributeVisual->personHeightText->setPosition(Ogre::Vector3(0, 0, 0) ); + + if(humanAttributeVisual->genderMesh) { + humanAttributeVisual->genderMesh->setPosition(Ogre::Vector3(0, 0, 0.17 * 2 * m_commonProperties->font_scale->getFloat() + 0.3)); + humanAttributeVisual->genderMesh->setVisible(m_render_gender_property->getBool()); + } +} + +boost::shared_ptr HumanAttributesDisplay::createVisualIfNotExists(track_id trackId) +{ + if(m_humanAttributeVisuals.find(trackId) == m_humanAttributeVisuals.end()) { + boost::shared_ptr humanAttributeVisual = boost::shared_ptr(new HumanAttributeVisual); + + humanAttributeVisual->sceneNode = boost::shared_ptr(scene_node_->createChildSceneNode()); + + humanAttributeVisual->ageGroupText = boost::shared_ptr(new TextNode(context_->getSceneManager(), humanAttributeVisual->sceneNode.get())); + humanAttributeVisual->ageGroupText->showOnTop(); + humanAttributeVisual->ageGroupText->setCaption(" "); + + humanAttributeVisual->personHeightText = boost::shared_ptr(new TextNode(context_->getSceneManager(), humanAttributeVisual->sceneNode.get())); + humanAttributeVisual->personHeightText->showOnTop(); + humanAttributeVisual->personHeightText->setCaption(" "); + + humanAttributeVisual->trackId = trackId; + + m_humanAttributeVisuals[trackId] = humanAttributeVisual; + } + + + return m_humanAttributeVisuals[trackId]; +} + +// This is our callback to handle an incoming group message. +void HumanAttributesDisplay::processMessage(const spencer_human_attribute_msgs::HumanAttributes::ConstPtr& msg) +{ + // Get transforms into fixed frame etc. + if(!preprocessMessage(msg)) return; + + // Transform into Rviz fixed frame + m_frameTransform = Ogre::Matrix4(m_frameOrientation); + m_frameTransform.setTrans(m_framePosition); + + const Ogre::Quaternion shapeQuaternion( Ogre::Degree(90), Ogre::Vector3(1,0,0) ); // required to fix orientation of any Cylinder shapes + stringstream ss; + + // + // Iterate over all categorical attributes in this message + // + foreach (const spencer_human_attribute_msgs::CategoricalAttribute& categoricalAttribute, msg->categoricalAttributes) + { + // Check if there is already a visual for this particular track + track_id trackId = categoricalAttribute.subject_id; // assumes subject_id is a track_id (not detection_id) + boost::shared_ptr humanAttributeVisual = createVisualIfNotExists(trackId); + + if(categoricalAttribute.values.empty()) { + ROS_ERROR_STREAM("categoricalAttribute.values.empty() for track ID " << trackId << ", attribute " << categoricalAttribute.type); + continue; + } + if(categoricalAttribute.confidences.size() != categoricalAttribute.values.size()) { + ROS_WARN_STREAM("categoricalAttribute.confidences.size() != categoricalAttribute.values.size() for track ID " << trackId << ", attribute " << categoricalAttribute.type); + } + + // Find highest-ranking attribute + size_t highestRankingIndex = 0; float highestConfidence = -999999; + for(size_t i = 0; i < categoricalAttribute.confidences.size(); i++) { + if(categoricalAttribute.confidences[i] > highestConfidence) { + highestConfidence = categoricalAttribute.confidences[i]; + highestRankingIndex = i; + } + } + + std::string valueWithHighestConfidence = categoricalAttribute.values[highestRankingIndex]; + + // Age group + if(categoricalAttribute.type == spencer_human_attribute_msgs::CategoricalAttribute::AGE_GROUP) { + ss.str(""); ss << valueWithHighestConfidence << "yrs"; + humanAttributeVisual->ageGroupText->setCaption(ss.str()); + } + + // Gender + else if(categoricalAttribute.type == spencer_human_attribute_msgs::CategoricalAttribute::GENDER) { + ss.str(""); ss << "package://" ROS_PACKAGE_NAME "/media/" << valueWithHighestConfidence << "_symbol.dae"; + std::string meshResource = ss.str(); + + humanAttributeVisual->genderMesh = boost::shared_ptr(new MeshNode(context_, humanAttributeVisual->sceneNode.get(), meshResource)); + + Ogre::ColourValue meshColor(1, 1, 1, 1); + if(valueWithHighestConfidence == spencer_human_attribute_msgs::CategoricalAttribute::GENDER_MALE) meshColor = Ogre::ColourValue(0, 1, 1, 1); + if(valueWithHighestConfidence == spencer_human_attribute_msgs::CategoricalAttribute::GENDER_FEMALE) meshColor = Ogre::ColourValue(1, 0, 1, 1); + humanAttributeVisual->genderMesh->setColor(meshColor); + + humanAttributeVisual->genderMesh->setScale(0.5); + humanAttributeVisual->genderMesh->setCameraFacing(true); + } + } + + + // + // Iterate over all scalar attributes in this message + // + foreach (const spencer_human_attribute_msgs::ScalarAttribute& scalarAttribute, msg->scalarAttributes) + { + // Check if there is already a visual for this particular track + track_id trackId = scalarAttribute.subject_id; // assumes subject_id is a track_id (not detection_id) + boost::shared_ptr humanAttributeVisual = createVisualIfNotExists(trackId); + + if(scalarAttribute.values.empty()) { + ROS_ERROR_STREAM("scalarAttribute.values.empty() for track ID " << trackId << ", attribute " << scalarAttribute.type); + continue; + } + if(scalarAttribute.confidences.size() != scalarAttribute.values.size()) { + ROS_WARN_STREAM("scalarAttribute.confidences.size() != scalarAttribute.values.size() for track ID " << trackId << ", attribute " << scalarAttribute.type); + } + + // Find highest-ranking attribute + size_t highestRankingIndex = 0; float highestConfidence = -999999; + for(size_t i = 0; i < scalarAttribute.confidences.size(); i++) { + if(scalarAttribute.confidences[i] > highestConfidence) { + highestConfidence = scalarAttribute.confidences[i]; + highestRankingIndex = i; + } + } + + float valueWithHighestConfidence = scalarAttribute.values[highestRankingIndex]; + + // Person height + if(scalarAttribute.type == spencer_human_attribute_msgs::ScalarAttribute::PERSON_HEIGHT) { + ss.str(""); ss << std::fixed << std::setprecision(2) << valueWithHighestConfidence << "m"; + humanAttributeVisual->personHeightText->setCaption(ss.str()); + } + } + + + // + // Update position and style of all existing person visuals + // + set tracksWithUnknownPosition; + foreach(boost::shared_ptr humanAttributeVisual, m_humanAttributeVisuals | boost::adaptors::map_values) + { + boost::shared_ptr trackedPerson = m_trackedPersonsCache.lookup(humanAttributeVisual->trackId); + + // Get current track position + if(!trackedPerson) { + tracksWithUnknownPosition.insert(humanAttributeVisual->trackId); + } + else + { // Track position is known + humanAttributeVisual->sceneNode->setPosition(trackedPerson->center + Ogre::Vector3(0, 0, m_commonProperties->z_offset->getFloat())); + + // Update styles + updateVisualStyles(humanAttributeVisual); + } + } + + + // Remove visuals for tracks with unknown position + foreach(track_id trackId, tracksWithUnknownPosition) { + m_humanAttributeVisuals.erase(trackId); + } + + + // + // Update display status (shown in property pane) + // + + ss.str(""); + ss << msg->categoricalAttributes.size() << " categorical attribute(s)"; + setStatusStd(rviz::StatusProperty::Ok, "Categorical attributes", ss.str()); + + ss.str(""); + ss << msg->scalarAttributes.size() << " scalar attribute(s)"; + setStatusStd(rviz::StatusProperty::Ok, "Scalar attributes", ss.str()); + + ss.str(""); + ss << tracksWithUnknownPosition.size() << " track(s) with unknown position"; + setStatusStd(0 == tracksWithUnknownPosition.size() ? rviz::StatusProperty::Ok : rviz::StatusProperty::Warn, "Attribute-to-track assignment", ss.str()); +} + +} // end namespace spencer_tracking_rviz_plugin + +// Tell pluginlib about this class. It is important to do this in +// global scope, outside our package's namespace. +#include +PLUGINLIB_EXPORT_CLASS(spencer_tracking_rviz_plugin::HumanAttributesDisplay, rviz::Display) diff --git a/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/src/human_attributes_display.h b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/src/human_attributes_display.h new file mode 100755 index 0000000..344afde --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/src/human_attributes_display.h @@ -0,0 +1,112 @@ +/* +* Software License Agreement (BSD License) +* +* Copyright (c) 2013-2015, Timm Linder, Social Robotics Lab, University of Freiburg +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* * Redistributions of source code must retain the above copyright notice, this +* list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above copyright notice, +* this list of conditions and the following disclaimer in the documentation +* and/or other materials provided with the distribution. +* * Neither the name of the copyright holder nor the names of its contributors +* may be used to endorse or promote products derived from this software +* without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*/ + +#ifndef HUMAN_ATTRIBUTES_DISPLAY_H +#define HUMAN_ATTRIBUTES_DISPLAY_H + +#ifndef Q_MOC_RUN +#include +#include +#include + +#include "person_display_common.h" +#include "tracked_persons_cache.h" +#include "visuals/mesh_node.h" +#endif + +namespace spencer_tracking_rviz_plugin +{ + /// The display which can be added in RViz to display human attributes. + class HumanAttributesDisplay: public PersonDisplayCommon + { + Q_OBJECT + public: + // Constructor. pluginlib::ClassLoader creates instances by calling + // the default constructor, so make sure you have one. + HumanAttributesDisplay() {}; + virtual ~HumanAttributesDisplay(); + + // Overrides of protected virtual functions from Display. As much + // as possible, when Displays are not enabled, they should not be + // subscribed to incoming data and should not show anything in the + // 3D view. These functions are where these connections are made + // and broken. + + // Called after the constructors have run + virtual void onInitialize(); + + // Called periodically by the visualization manager + virtual void update(float wall_dt, float ros_dt); + + protected: + // A helper to clear this display back to the initial state. + virtual void reset(); + + // Must be implemented by derived classes because MOC doesn't work in templates + virtual rviz::DisplayContext* getContext() { + return context_; + } + + private: + struct HumanAttributeVisual { + boost::shared_ptr sceneNode; + boost::shared_ptr genderMesh; + unsigned int trackId; + boost::shared_ptr ageGroupText; + boost::shared_ptr personHeightText; + }; + + // Functions to handle an incoming ROS message. + void processMessage(const spencer_human_attribute_msgs::HumanAttributes::ConstPtr& msg); + + // Helper functions + void updateVisualStyles(boost::shared_ptr& humanAttributeVisual); + boost::shared_ptr createVisualIfNotExists(track_id trackId); + + // User-editable property variables. + rviz::BoolProperty* m_render_gender_property; + rviz::BoolProperty* m_render_person_height_property; + rviz::BoolProperty* m_render_age_group_property; + + rviz::FloatProperty* m_occlusion_alpha_property; + + // State variables + map > m_humanAttributeVisuals; + + Ogre::Matrix4 m_frameTransform; + TrackedPersonsCache m_trackedPersonsCache; + + private Q_SLOTS: + virtual void stylesChanged(); + }; + +} // end namespace spencer_tracking_rviz_plugin + +#endif // HUMAN_ATTRIBUTES_DISPLAY_H diff --git a/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/src/person_display_common.cpp b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/src/person_display_common.cpp new file mode 100755 index 0000000..0333dea --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/src/person_display_common.cpp @@ -0,0 +1,140 @@ +/* +* Software License Agreement (BSD License) +* +* Copyright (c) 2013-2015, Timm Linder, Social Robotics Lab, University of Freiburg +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* * Redistributions of source code must retain the above copyright notice, this +* list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above copyright notice, +* this list of conditions and the following disclaimer in the documentation +* and/or other materials provided with the distribution. +* * Neither the name of the copyright holder nor the names of its contributors +* may be used to endorse or promote products derived from this software +* without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*/ + +#ifndef Q_MOC_RUN +#include "person_display_common.h" +#include +#include +#include +#endif +#define foreach BOOST_FOREACH + + +namespace spencer_tracking_rviz_plugin +{ +// The constructor must have no arguments, so we can't give the +// constructor the parameters it needs to fully initialize. +PersonDisplayCommonProperties::PersonDisplayCommonProperties(rviz::Display* display, StylesChangedSubscriber* stylesChangedSubscriber) + : m_display(display), m_stylesChangedSubscriber(stylesChangedSubscriber) +{ + style = new rviz::EnumProperty( "Style", "Cylinders", "Rendering mode to use, in order of computational complexity.", m_display, SLOT(stylesChanged()), this ); + style->addOption( "Simple", STYLE_SIMPLE ); + style->addOption( "Cylinders", STYLE_CYLINDER ); + style->addOption( "Person meshes", STYLE_PERSON_MESHES ); + style->addOption( "Bounding boxes", STYLE_BOUNDING_BOXES ); + style->addOption( "Crosshairs", STYLE_CROSSHAIRS ); + + color_transform = new rviz::EnumProperty( "Color transform", "Rainbow", "How to color the tracked persons", m_display, SLOT(stylesChanged()), this ); + color_transform->addOption( "SRL Tracking Colors", COLORS_SRL ); + color_transform->addOption( "Alternative SRL colors", COLORS_SRL_ALTERNATIVE ); + color_transform->addOption( "Rainbow", COLORS_RAINBOW ); + color_transform->addOption( "Rainbow + B/W", COLORS_RAINBOW_BW ); + color_transform->addOption( "Flat", COLORS_FLAT ); + color_transform->addOption( "Vintage", COLORS_VINTAGE ); + color_transform->addOption( "Constant color", COLORS_CONSTANT ); + + constant_color = new rviz::ColorProperty("Color", QColor( 130, 130, 130 ), "Color for tracked persons if using constant color transform.", m_display, SLOT(stylesChanged()), this ); + + color_map_offset = new rviz::IntProperty( "Color map offset", 0, "By how many indices to shift the offset in the color map (useful if not happy with the current colors)", m_display, SLOT(stylesChanged()), this); + color_map_offset->setMin( 0 ); + + alpha = new rviz::FloatProperty( "Alpha", 1.0, "0 is fully transparent, 1.0 is fully opaque.", m_display, SLOT(stylesChanged()), this); + alpha->setMin( 0.0 ); + alpha->setMax( 1.0 ); + + line_width = new rviz::FloatProperty( "Line width", 0.05, "Line width for person visual", style, SLOT(stylesChanged()), this); + line_width->setMin( 0.0 ); + line_width->setMax( 1.0 ); + + scaling_factor = new rviz::FloatProperty( "Scaling factor", 1.0, "Scaling factor for person visual", style); + scaling_factor->setMin( 0.0 ); + scaling_factor->setMax( 100.0 ); + + font_color_style = new rviz::EnumProperty( "Font color style", "Same color", "Which type of font coloring to use", m_display, SLOT(stylesChanged()), this ); + font_color_style->addOption( "Same color", FONT_COLOR_FROM_PERSON ); + font_color_style->addOption( "Constant color", FONT_COLOR_CONSTANT ); + + constant_font_color = new rviz::ColorProperty("Font color", QColor( 255, 255, 255 ), "Font color if using a constant color", m_display, SLOT(stylesChanged()), this ); + + font_scale = new rviz::FloatProperty( "Font scale", 2.0, "Larger values mean bigger font", m_display); + font_scale->setMin( 0.0 ); + + z_offset = new rviz::FloatProperty( "Z offset", 0.0, "Offset of all visualizations on the z (height) axis", m_display, SLOT(stylesChanged()), this); + + use_actual_z_position = new rviz::BoolProperty( "Use Z position from message", false, "Use Z position from message (otherwise place above ground plane)", z_offset, SLOT(stylesChanged()), this); + + m_excluded_person_ids_property = new rviz::StringProperty( "Excluded person IDs", "", "Comma-separated list of person IDs whose visualization should be hidden", m_display, SLOT(stylesChanged()), this ); + m_included_person_ids_property = new rviz::StringProperty( "Included person IDs", "", "Comma-separated list of person IDs whose visualization should be visible. Overrides excluded IDs.", m_display, SLOT(stylesChanged()), this ); + + hideIrrelevantProperties(); +} + +void PersonDisplayCommonProperties::hideIrrelevantProperties() +{ + constant_color->setHidden(color_transform->getOptionInt() != COLORS_CONSTANT); + color_map_offset->setHidden(color_transform->getOptionInt() == COLORS_CONSTANT); + constant_font_color->setHidden(font_color_style->getOptionInt() != FONT_COLOR_CONSTANT); + + line_width->setHidden(style->getOptionInt() != STYLE_BOUNDING_BOXES && style->getOptionInt() != STYLE_CROSSHAIRS); +} + +// Callback for any changed style +void PersonDisplayCommonProperties::stylesChanged() +{ + hideIrrelevantProperties(); + + // Update list of person IDs that shall be hidden or visible + m_excludedPersonIDs.clear(); + { + string personIDString = m_excluded_person_ids_property->getStdString(); + char_separator separator(","); + tokenizer< char_separator > tokens(personIDString, separator); + foreach(const string& token, tokens) { + try { m_excludedPersonIDs.insert(lexical_cast(token)); } + catch(bad_lexical_cast &) {} + } + } + m_includedPersonIDs.clear(); + { + string personIDString = m_included_person_ids_property->getStdString(); + char_separator separator(","); + tokenizer< char_separator > tokens(personIDString, separator); + foreach(const string& token, tokens) { + try { m_includedPersonIDs.insert(lexical_cast(token)); } + catch(bad_lexical_cast &) {} + } + } + + // Relay change to other subscribers + m_stylesChangedSubscriber->stylesChanged(); +} + + +} // end namespace spencer_tracking_rviz_plugin diff --git a/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/src/person_display_common.h b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/src/person_display_common.h new file mode 100755 index 0000000..9a49763 --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/src/person_display_common.h @@ -0,0 +1,383 @@ +/* +* Software License Agreement (BSD License) +* +* Copyright (c) 2013-2015, Timm Linder, Social Robotics Lab, University of Freiburg +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* * Redistributions of source code must retain the above copyright notice, this +* list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above copyright notice, +* this list of conditions and the following disclaimer in the documentation +* and/or other materials provided with the distribution. +* * Neither the name of the copyright holder nor the names of its contributors +* may be used to endorse or promote products derived from this software +* without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*/ + +#ifndef PERSON_DISPLAY_COMMON_H +#define PERSON_DISPLAY_COMMON_H + +#ifndef Q_MOC_RUN +#include +#include +#include +#include +#include +#include + +#include +#include +#include "visuals/person_visual.h" +#include "visuals/text_node.h" +#include "visuals/covariance_visual.h" +#include +#include +#include +#include +#include +#include +#include +#include +#include +#endif + + + + + + + +using namespace std; +using namespace boost; + +namespace spencer_tracking_rviz_plugin +{ + typedef unsigned int person_id; + + /// Visualization style for a person + enum Styles { + STYLE_SIMPLE, + STYLE_CYLINDER, + STYLE_PERSON_MESHES, + STYLE_BOUNDING_BOXES, + STYLE_CROSSHAIRS + }; + + /// How to color persons + enum ColorTransforms { + COLORS_SRL, + COLORS_SRL_ALTERNATIVE, + COLORS_RAINBOW, + COLORS_RAINBOW_BW, + COLORS_FLAT, + COLORS_VINTAGE, + COLORS_CONSTANT, + }; + + /// Which font colors to use + enum FontColorStyle { + FONT_COLOR_FROM_PERSON, + FONT_COLOR_CONSTANT + }; + + /// Subclasses of PersonDisplayCommon can override stylesChanged() to get notified when one of the properties in PersonDisplayCommonProperties has changed. + class StylesChangedSubscriber { + public: + virtual ~StylesChangedSubscriber() {} + virtual void stylesChanged() {} + }; + + /// Common properties shared by multiple displays. + class PersonDisplayCommonProperties : public QObject { + Q_OBJECT + public: + PersonDisplayCommonProperties(rviz::Display* display, StylesChangedSubscriber* stylesChangedSubscriber); + + // User-editable property variables. + rviz::EnumProperty* style; + rviz::EnumProperty* color_transform; + rviz::IntProperty* color_map_offset; + + rviz::ColorProperty* constant_color; + rviz::FloatProperty* alpha; + + rviz::FloatProperty* line_width; + rviz::FloatProperty* z_offset; + rviz::FloatProperty* scaling_factor; + + rviz::BoolProperty* use_actual_z_position; + + rviz::EnumProperty* font_color_style; + rviz::ColorProperty* constant_font_color; + rviz::FloatProperty* font_scale; + + rviz::StringProperty* m_excluded_person_ids_property; + rviz::StringProperty* m_included_person_ids_property; + + /// These sets get updated automatically whenever the corresponding properties are updated. + set m_excludedPersonIDs, m_includedPersonIDs; + + private: + rviz::Display* m_display; + StylesChangedSubscriber* m_stylesChangedSubscriber; + + void hideIrrelevantProperties(); + + private Q_SLOTS: + void stylesChanged(); + }; + + /// A display with common properties that are shared by multiple specializations. + template + class PersonDisplayCommon: public rviz::MessageFilterDisplay, public StylesChangedSubscriber + { + public: + /// Constructor. pluginlib::ClassLoader creates instances by calling + /// the default constructor, so make sure you have one. + PersonDisplayCommon() : m_commonProperties(0), m_veryLargeVariance(99999) {} + virtual ~PersonDisplayCommon() {} + + /// Overrides base class method + virtual void onInitialize() + { + rviz::MessageFilterDisplay::onInitialize(); + m_commonProperties = new PersonDisplayCommonProperties(this, this); + } + + protected: + /// Common message processing. This method needs to be called by derived classes + bool preprocessMessage(const typename MessageType::ConstPtr& msg) + { + // Here we call the rviz::FrameManager to get the transform from the + // fixed frame to the frame in the header of this Imu message. If + // it fails, we can't do anything else so we return. + if (!getContext()->getFrameManager()->getTransform(msg->header, m_framePosition, m_frameOrientation)) { + ROS_ERROR_THROTTLE(5.0, "Error transforming from frame '%s' into fixed frame!", msg->header.frame_id.c_str()); + return false; + } + + m_frameOrientation.ToRotationMatrix(m_frameRotationMatrix); + return true; + } + + /// Create a visual representation of the person itself, if not set yet + void createPersonVisualIfRequired(Ogre::SceneNode* sceneNode, boost::shared_ptr &personVisual) + { + if (!personVisual) { + PersonVisualDefaultArgs defaultArgs(getContext()->getSceneManager(), sceneNode); + PersonVisual* newPersonVisual = 0; + + if (m_commonProperties->style->getOptionInt() == STYLE_CYLINDER) newPersonVisual = new CylinderPersonVisual(defaultArgs); + if (m_commonProperties->style->getOptionInt() == STYLE_PERSON_MESHES) newPersonVisual = new MeshPersonVisual(defaultArgs); + if (m_commonProperties->style->getOptionInt() == STYLE_BOUNDING_BOXES) newPersonVisual = new BoundingBoxPersonVisual(defaultArgs); + if (m_commonProperties->style->getOptionInt() == STYLE_CROSSHAIRS) newPersonVisual = new CrosshairPersonVisual(defaultArgs); + personVisual.reset(newPersonVisual); + } + + // Update position of the person visual + if (personVisual) { + personVisual->setPosition(Ogre::Vector3(0,0, personVisual->getHeight() * 0.5)); + } + } + + /// Applies common styles which apply to person visuals, such as line width etc. + void applyCommonStyles(boost::shared_ptr &personVisual) { + if(!personVisual) return; + + // Set line width of wireframe visualization + HasLineWidth* hasLineWidth = dynamic_cast(personVisual.get()); + if(hasLineWidth) { + hasLineWidth->setLineWidth(m_commonProperties->line_width->getFloat()); + } + + // Set scaling factor + personVisual->setScalingFactor(m_commonProperties->scaling_factor->getFloat()); + } + + // Builds velocity vector for a person from a twist message + Ogre::Vector3 getVelocityVector(const geometry_msgs::TwistWithCovariance& twist) { + const double zVelocityVariance = twist.covariance[2 * 6 + 2]; + const double zVelocity = (isnan(zVelocityVariance) || isinf(zVelocityVariance)) ? 0.0 : twist.twist.linear.z; + return Ogre::Vector3(twist.twist.linear.x, twist.twist.linear.y, zVelocity); + } + + /// Returns true if all xyz rotation variances are finite + bool hasValidOrientation(const geometry_msgs::PoseWithCovariance& pose) + { + // Check if quaternion has not been initialized, then it's invalid (all-zero elements) + if(pose.pose.orientation.x == 0 && pose.pose.orientation.y == 0 && pose.pose.orientation.z == 0 && pose.pose.orientation.w == 0) return false; + + // According to ROS conventions, orientation covariance is always fixed-frame + // so no transform necessary! + const double xRotVariance = pose.covariance[3 * 6 + 3]; + const double yRotVariance = pose.covariance[4 * 6 + 4]; + const double zRotVariance = pose.covariance[5 * 6 + 5]; + // Using logical OR instead of AND here because the orientation is given as a quaternion, instead of independent + // RPY angles. We assume if at least one RPY angle is valid (according to its covariance), the other angles are set to a + // reasonable default (as part of the quaternion) if their variance is non-finite. + return xRotVariance < m_veryLargeVariance || yRotVariance < m_veryLargeVariance || zRotVariance < m_veryLargeVariance; + } + + /// Rotate the position (xyz) part of a pose covariance matrix into the fixed frame used for visualization + /// The covariance matrix needs to be transformed from the source (e.g. sensor) into the target (e.g. odometry) frame + /// This is mainly be a problem if the sensor is rotated vertically compared to the odometry frame, so that axes get swapped + Ogre::Matrix3 covarianceXYZIntoTargetFrame(const geometry_msgs::PoseWithCovariance& pose) { + Ogre::Matrix3 xyzcov; + for(int row = 0; row < 3; row++) for(int col = 0; col < 3; col++) xyzcov[row][col] = pose.covariance[row*6 + col]; // 6 = dimension of ROS covariance matrix + if(!isfinite(xyzcov.Determinant())) ROS_WARN_STREAM("Covariance matrix supplied to covarianceXYZIntoTargetFrame() contains non-finite elements: " << xyzcov); + return m_frameRotationMatrix * xyzcov * m_frameRotationMatrix.Transpose(); // cov(AX + a) = A cov(X) A^T + } + + /// Set pose and orientation of person visual + void setPoseOrientation(Ogre::SceneNode* sceneNode, const geometry_msgs::PoseWithCovariance& pose, const Ogre::Matrix3& covXYZinTargetFrame, double personVisualHeight) + { + const geometry_msgs::Point& position = pose.pose.position; + const geometry_msgs::Quaternion& orientation = pose.pose.orientation; + + Ogre::Matrix4 transform(m_frameOrientation); + transform.setTrans(m_framePosition); + + Ogre::Vector3 originalPosition(position.x, position.y, position.z); + if(!isfinite(originalPosition.x) || !isfinite(originalPosition.y) || !isfinite(originalPosition.z)) { + ROS_WARN("Detected or tracked person has non-finite position! Something is wrong!"); + return; + } + + Ogre::Vector3 positionInTargetFrame = transform * originalPosition; + + if(hasValidOrientation(pose)) { + Ogre::Quaternion detectionOrientation(orientation.w, orientation.x, orientation.y, orientation.z); + detectionOrientation.FromAngleAxis(detectionOrientation.getRoll(), Ogre::Vector3(0,0,1)); // only use yaw angle, ignore roll and pitch + sceneNode->setOrientation(m_frameOrientation * detectionOrientation); + } + else { + Ogre::Quaternion rotateTowardsCamera; + rotateTowardsCamera.FromAngleAxis(Ogre::Degree(180), Ogre::Vector3(0,0,1)); + sceneNode->setOrientation(rotateTowardsCamera); + } + + const double zVariance = covXYZinTargetFrame[2][2]; + bool useActualZPosition = m_commonProperties->use_actual_z_position->getBool() && isfinite(zVariance) && zVariance >= 0 && zVariance < m_veryLargeVariance; + + positionInTargetFrame.z = useActualZPosition ? positionInTargetFrame.z - personVisualHeight/2.0: 0.0; + positionInTargetFrame.z += m_commonProperties->z_offset->getFloat(); + + sceneNode->setPosition(positionInTargetFrame); + } + + /// Get a color based upon track / detection ID. + Ogre::ColourValue getColorFromId(unsigned int object_id) + { + Ogre::ColourValue color; + const int colorScheme = m_commonProperties->color_transform->getOptionInt(); + object_id += max(0, m_commonProperties->color_map_offset->getInt()); + + if(colorScheme == COLORS_SRL || colorScheme == COLORS_SRL_ALTERNATIVE) + { + // SRL People Tracker colors + const size_t NUM_SRL_COLORS = 6, NUM_SRL_COLOR_SHADES = 4, NUM_SRL_TOTAL_COLORS = NUM_SRL_COLORS * NUM_SRL_COLOR_SHADES; + const unsigned int spencer_colors[NUM_SRL_TOTAL_COLORS] = { + 0xC00000, 0xFF0000, 0xFF5050, 0xFFA0A0, // red + 0x00C000, 0x00FF00, 0x50FF50, 0xA0FFA0, // green + 0x0000C0, 0x0000FF, 0x5050FF, 0xA0A0FF, // blue + 0xF20A86, 0xFF00FF, 0xFF50FF, 0xFFA0FF, // magenta + 0x00C0C0, 0x00FFFF, 0x50FFFF, 0xA0FFFF, // cyan + 0xF5A316, 0xFFFF00, 0xFFFF50, 0xFFFFA0 // yellow + }; + + unsigned int rgb = 0; + const unsigned int tableId = object_id % NUM_SRL_TOTAL_COLORS; + if(m_commonProperties->color_transform->getOptionInt() == COLORS_SRL) { + // Colors in original order (first vary shade, then vary color) + rgb = spencer_colors[tableId]; + } + else if(m_commonProperties->color_transform->getOptionInt() == COLORS_SRL_ALTERNATIVE) { + // Colors in alternative order (first vary color, then vary shade) + unsigned int shadeIndex = tableId / NUM_SRL_COLORS; + unsigned int colorIndex = tableId % NUM_SRL_COLORS; + rgb = spencer_colors[colorIndex * NUM_SRL_COLOR_SHADES + shadeIndex]; + } + + float r = ((rgb >> 16) & 0xff) / 255.0f, + g = ((rgb >> 8) & 0xff) / 255.0f, + b = ((rgb >> 0) & 0xff) / 255.0f; + + color = Ogre::ColourValue(r, g, b, 1.0); + } + else if(colorScheme == COLORS_RAINBOW || colorScheme == COLORS_RAINBOW_BW) + { + const size_t NUM_COLOR = 10, NUM_BW = 4; + const unsigned int rainbow_colors[NUM_COLOR + NUM_BW] = { + 0xaf1f90, 0x000846, 0x00468a, 0x00953d, 0xb2c908, 0xfcd22a, 0xffa800, 0xff4500, 0xe0000b, 0xb22222, + 0xffffff, 0xb8b8b8, 0x555555, 0x000000 + }; + + color.setAsARGB(rainbow_colors[object_id % (colorScheme == COLORS_RAINBOW ? NUM_COLOR : (NUM_COLOR+NUM_BW))]); + } + else if(colorScheme == COLORS_FLAT) + { + const size_t NUM_COLOR = 10; + const unsigned int flat_colors[NUM_COLOR] = { + 0x990033, 0xa477c4, 0x3498db, 0x1abc9c, 0x55e08f, 0xfff054, 0xef5523, 0xfe374a, 0xbaa891, 0xad5f43 + }; + + color.setAsARGB(flat_colors[object_id % NUM_COLOR]); + } + else if(colorScheme == COLORS_VINTAGE) + { + const size_t NUM_COLOR = 10; + const unsigned int vintage_colors[NUM_COLOR] = { + 0xd05e56, 0x797d88, 0x448d7a, 0xa5d1cd, 0x88a764, 0xebe18c, 0xd8a027, 0xffcc66, 0xdc3f1c, 0xff9966 + }; + + color.setAsARGB(vintage_colors[object_id % NUM_COLOR]); + } + else + { + // Constant color for all tracks + color = m_commonProperties->constant_color->getOgreColor(); + } + + color.a = 1.0f; // force full opacity + return color; + } + + /// Checks if a person shall be hidden (can be set using include/exclude person ID properties in GUI) + bool isPersonHidden(person_id personId) + { + bool isIncluded = m_commonProperties->m_includedPersonIDs.find(personId) != m_commonProperties->m_includedPersonIDs.end(); + if(isIncluded) return false; + if(!m_commonProperties->m_includedPersonIDs.empty()) return true; + return m_commonProperties->m_excludedPersonIDs.find(personId) != m_commonProperties->m_excludedPersonIDs.end(); + } + + /// Must be implemented by derived classes because MOC doesn't work in templates + virtual rviz::DisplayContext* getContext() = 0; + + /// Common properties for the displays in this plugin + PersonDisplayCommonProperties* m_commonProperties; + + protected: + Ogre::Quaternion m_frameOrientation; + Ogre::Matrix3 m_frameRotationMatrix; + Ogre::Vector3 m_framePosition; + const double m_veryLargeVariance; + }; +} // end namespace spencer_tracking_rviz_plugin + + +#endif // PERSON_DISPLAY_COMMON_H diff --git a/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/src/social_activities_display.cpp b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/src/social_activities_display.cpp new file mode 100755 index 0000000..17e7927 --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/src/social_activities_display.cpp @@ -0,0 +1,566 @@ +/* +* Software License Agreement (BSD License) +* +* Copyright (c) 2013-2015, Timm Linder, Social Robotics Lab, University of Freiburg +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* * Redistributions of source code must retain the above copyright notice, this +* list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above copyright notice, +* this list of conditions and the following disclaimer in the documentation +* and/or other materials provided with the distribution. +* * Neither the name of the copyright holder nor the names of its contributors +* may be used to endorse or promote products derived from this software +* without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*/ + +#include +#include +#include "rviz/selection/selection_manager.h" + +#ifndef Q_MOC_RUN +#include "social_activities_display.h" + +#include +#include +#include +#include +#include +#endif +#define foreach BOOST_FOREACH + +// required to fix orientation of any Cylinder shapes +const Ogre::Quaternion shapeQuaternion( Ogre::Degree(90), Ogre::Vector3(1,0,0) ); + + +namespace sr = spencer_social_relation_msgs; +namespace spencer_tracking_rviz_plugin +{ + +void SocialActivitiesDisplay::onInitialize() +{ + m_trackedPersonsCache.initialize(this, context_, update_nh_); + PersonDisplayCommon::onInitialize(); + + QObject::connect(m_commonProperties->style, SIGNAL(changed()), this, SLOT(personVisualTypeChanged()) ); + + m_excluded_activity_types_property = new rviz::StringProperty( "Excluded activity types", "", "Comma-separated list of activity types whose visualization should be hidden", this, SLOT(stylesChanged()) ); + m_included_activity_types_property = new rviz::StringProperty( "Included activity types", "", "Comma-separated list of activity types whose visualization should be visible, overrides excluded", this, SLOT(stylesChanged()) ); + + m_min_confidence_property = new rviz::FloatProperty( "Min. confidence", 0.0, "Minimum confidence for a social activity to be shown", this, SLOT(stylesChanged()) ); + m_min_confidence_property->setMin( 0.0 ); + + m_hide_with_no_activity_property = new rviz::BoolProperty( "Hide tracks with no activity", false, "Hide all tracks which do not have at least one social activity assigned", this, SLOT(stylesChanged())); + + m_render_intraactivity_connections_property = new rviz::BoolProperty( "Connect tracks sharing the same activity", true, "Connect all tracks that share the same activity", this, SLOT(stylesChanged())); + m_line_width_property = new rviz::FloatProperty( "Line width", 0.05, "Line width of connecting lines", m_render_intraactivity_connections_property, SLOT(stylesChanged()), this ); + m_line_width_property->setMin( 0.0 ); + + m_render_activity_types_property = new rviz::BoolProperty( "Render activity type texts", true, "Render activity types as text", this, SLOT(stylesChanged())); + m_activity_type_per_track_property = new rviz::BoolProperty( "Activity type per track", false, "Show activity type for each individual track", this, SLOT(stylesChanged())); + m_render_confidences_property = new rviz::BoolProperty( "Render confidences", true, "Render confidence values next to activity type", this, SLOT(stylesChanged())); + + m_render_circles_property = new rviz::BoolProperty( "Render circles below person", true, "Render circles below person", this, SLOT(stylesChanged())); + m_circle_radius_property = new rviz::FloatProperty( "Radius", 0.45, "Radius of circles below person in meters", m_render_circles_property, SLOT(stylesChanged()), this ); + m_circle_radius_property->setMin( 0.0 ); + + m_circle_alpha_property = new rviz::FloatProperty( "Alpha", 1.0, "Alpha value (opacity) of circles below person", m_render_circles_property, SLOT(stylesChanged()), this ); + m_circle_alpha_property->setMin( 0.0 ); + m_circle_alpha_property->setMax( 1.0 ); + + m_occlusion_alpha_property = new rviz::FloatProperty( "Occlusion alpha", 0.5, "Alpha multiplier for history of occluded tracks", this, SLOT(stylesChanged()) ); + m_occlusion_alpha_property->setMin( 0.0 ); + + m_activity_type_offset = new rviz::FloatProperty( "Activity type Z offset", 2.0, "Offset in z position (height) of the activity type text", this, SLOT(stylesChanged()) ); + + m_activity_colors = new rviz::Property( "Activity colors", "", "Colors of different social activity types", this ); + + // Add colors for new activity types here, also adjust header file! + m_activity_color_unknown = new rviz::ColorProperty( "(Unknown activity)", QColor(255,255,255), "", m_activity_colors, SLOT(stylesChanged()), this); + m_activity_color_none = new rviz::ColorProperty( "(No activity)", QColor(200,200,200), "", m_activity_colors, SLOT(stylesChanged()), this); + m_activity_color_shopping = new rviz::ColorProperty( sr::SocialActivity::TYPE_SHOPPING.c_str(), QColor(0,0,255), "", m_activity_colors, SLOT(stylesChanged()), this); + m_activity_color_standing = new rviz::ColorProperty( sr::SocialActivity::TYPE_STANDING.c_str(), QColor(0,0,0), "", m_activity_colors, SLOT(stylesChanged()), this); + m_activity_color_individual_moving = new rviz::ColorProperty( sr::SocialActivity::TYPE_INDIVIDUAL_MOVING.c_str(), QColor(128,128,128), "", m_activity_colors, SLOT(stylesChanged()), this); + m_activity_color_waiting_in_queue = new rviz::ColorProperty( sr::SocialActivity::TYPE_WAITING_IN_QUEUE.c_str(), QColor(255,0,255), "", m_activity_colors, SLOT(stylesChanged()), this); + m_activity_color_looking_at_information_screen = new rviz::ColorProperty( sr::SocialActivity::TYPE_LOOKING_AT_INFORMATION_SCREEN.c_str(), QColor(255,255,0), "", m_activity_colors, SLOT(stylesChanged()), this); + m_activity_color_looking_at_kiosk = new rviz::ColorProperty( sr::SocialActivity::TYPE_LOOKING_AT_KIOSK.c_str(), QColor(255,128,0), "", m_activity_colors, SLOT(stylesChanged()), this); + m_activity_color_group_assembling = new rviz::ColorProperty( sr::SocialActivity::TYPE_GROUP_ASSEMBLING.c_str(), QColor(0,128,255), "", m_activity_colors, SLOT(stylesChanged()), this); + m_activity_color_group_moving = new rviz::ColorProperty( sr::SocialActivity::TYPE_GROUP_MOVING.c_str(), QColor(0,255,255), "", m_activity_colors, SLOT(stylesChanged()), this); + m_activity_color_flow = new rviz::ColorProperty( sr::SocialActivity::TYPE_FLOW_WITH_ROBOT.c_str(), QColor(0,255,0), "", m_activity_colors, SLOT(stylesChanged()), this); + m_activity_color_antiflow = new rviz::ColorProperty( sr::SocialActivity::TYPE_ANTIFLOW_AGAINST_ROBOT.c_str(), QColor(255,0,0), "", m_activity_colors, SLOT(stylesChanged()), this); + m_activity_color_waiting_for_others = new rviz::ColorProperty( sr::SocialActivity::TYPE_WAITING_FOR_OTHERS.c_str(), QColor(255,170,255), "", m_activity_colors, SLOT(stylesChanged()), this); + m_activity_color_looking_for_help = new rviz::ColorProperty( sr::SocialActivity::TYPE_LOOKING_FOR_HELP.c_str(), QColor(155,170,255), "", m_activity_colors, SLOT(stylesChanged()), this); + + m_commonProperties->color_transform->setHidden(true); + m_commonProperties->color_map_offset->setHidden(true); + + // Create a scene node for visualizing group affiliation history + m_socialActivitiesSceneNode = boost::shared_ptr(scene_node_->createChildSceneNode()); +} + +SocialActivitiesDisplay::~SocialActivitiesDisplay() +{ +} + +// Clear the visuals by deleting their objects. +void SocialActivitiesDisplay::reset() +{ + PersonDisplayCommon::reset(); + m_trackedPersonsCache.reset(); + m_socialActivityVisuals.clear(); + m_personVisualMap.clear(); + m_highestConfidenceActivityPerTrack.clear(); +} + +void SocialActivitiesDisplay::update(float wall_dt, float ros_dt) +{ + // Update animations + foreach(PersonVisualContainer& personVisualContainer, m_personVisualMap | boost::adaptors::map_values) { + if(personVisualContainer.personVisual) { + personVisualContainer.personVisual->update(ros_dt); + } + } +} + +void SocialActivitiesDisplay::stylesChanged() +{ + m_commonProperties->color_map_offset->setHidden(true); + + // Get list of group IDs belonging to tracks that shall be hidden or visible + m_excludedActivityTypes.clear(); + { + string inputString = m_excluded_activity_types_property->getStdString(); + char_separator separator(","); + tokenizer< char_separator > tokens(inputString, separator); + foreach(const string& token, tokens) { + string tmp = token; + boost::algorithm::to_lower(tmp); + m_excludedActivityTypes.insert(tmp); + } + } + m_includedActivityTypes.clear(); + { + string inputString = m_included_activity_types_property->getStdString(); + char_separator separator(","); + tokenizer< char_separator > tokens(inputString, separator); + foreach(const string& token, tokens) { + string tmp = token; + boost::algorithm::to_lower(tmp); + m_includedActivityTypes.insert(tmp); + } + } + + foreach(boost::shared_ptr socialActivityVisual, m_socialActivityVisuals) { + updateSocialActivityVisualStyles(socialActivityVisual); + } + + foreach(PersonVisualContainer& personVisualContainer, m_personVisualMap | boost::adaptors::map_values) { + if(personVisualContainer.personVisual) { + // Update common styles to person visual, such as line width + applyCommonStyles(personVisualContainer.personVisual); + + // Update color according to highest-ranking social activity for this person + Ogre::ColourValue activityColor; + + activity_type activityType = ""; + float confidence = 1.0f; + if(m_highestConfidenceActivityPerTrack.find(personVisualContainer.trackId) != m_highestConfidenceActivityPerTrack.end()) { + activityType = m_highestConfidenceActivityPerTrack[personVisualContainer.trackId].type; + confidence = m_highestConfidenceActivityPerTrack[personVisualContainer.trackId].confidence; + } + else { + if(m_hide_with_no_activity_property->getBool()) confidence = -999; + } + activityColor = getActivityColor(activityType, confidence); + + personVisualContainer.personVisual->setColor(activityColor); + } + } +} + +bool SocialActivitiesDisplay::isActivityTypeHidden(activity_type activityType) { + boost::algorithm::to_lower(activityType); + + bool isIncluded = m_includedActivityTypes.find(activityType) != m_includedActivityTypes.end(); + if(isIncluded) return false; + if(!m_includedActivityTypes.empty()) return true; + + return m_excludedActivityTypes.find(activityType) != m_excludedActivityTypes.end(); +} + +Ogre::ColourValue SocialActivitiesDisplay::getActivityColor(activity_type activityType, float confidence) { + bool hideActivityType = isActivityTypeHidden(activityType); + + // Determine color + rviz::ColorProperty* colorProperty = NULL; + + // Add new social activity types here, and also add a property in constructor at top of file! + if(activityType.empty()) + colorProperty = m_activity_color_none; + else if(activityType == sr::SocialActivity::TYPE_SHOPPING) + colorProperty = m_activity_color_shopping; + else if(activityType == sr::SocialActivity::TYPE_STANDING) + colorProperty = m_activity_color_standing; + else if(activityType == sr::SocialActivity::TYPE_INDIVIDUAL_MOVING) + colorProperty = m_activity_color_individual_moving; + else if(activityType == sr::SocialActivity::TYPE_WAITING_IN_QUEUE) + colorProperty = m_activity_color_waiting_in_queue; + else if(activityType == sr::SocialActivity::TYPE_LOOKING_AT_INFORMATION_SCREEN) + colorProperty = m_activity_color_looking_at_information_screen; + else if(activityType == sr::SocialActivity::TYPE_LOOKING_AT_KIOSK) + colorProperty = m_activity_color_looking_at_kiosk; + else if(activityType == sr::SocialActivity::TYPE_GROUP_ASSEMBLING) + colorProperty = m_activity_color_group_assembling; + else if(activityType == sr::SocialActivity::TYPE_GROUP_MOVING) + colorProperty = m_activity_color_group_moving; + else if(activityType == sr::SocialActivity::TYPE_FLOW_WITH_ROBOT) + colorProperty = m_activity_color_flow; + else if(activityType == sr::SocialActivity::TYPE_ANTIFLOW_AGAINST_ROBOT) + colorProperty = m_activity_color_antiflow; + else if(activityType == sr::SocialActivity::TYPE_WAITING_FOR_OTHERS) + colorProperty = m_activity_color_waiting_for_others; + else if(activityType == sr::SocialActivity::TYPE_LOOKING_FOR_HELP) + colorProperty = m_activity_color_looking_for_help; + else + colorProperty = m_activity_color_unknown; + + Ogre::ColourValue activityColor = colorProperty->getOgreColor(); + activityColor.a = 1.0f; + + activityColor.a *= m_commonProperties->alpha->getFloat(); // general alpha + if(hideActivityType) activityColor.a = 0; + + if(confidence < m_min_confidence_property->getFloat()) activityColor.a = 0; + + return activityColor; +} + +// Set the rendering style (cylinders, meshes, ...) of tracked persons +void SocialActivitiesDisplay::personVisualTypeChanged() +{ + m_personVisualMap.clear(); + foreach(PersonVisualContainer& personVisualContainer, m_personVisualMap | boost::adaptors::map_values) { + personVisualContainer.personVisual.reset(); + createPersonVisualIfRequired(personVisualContainer.sceneNode.get(), personVisualContainer.personVisual); + } + stylesChanged(); +} + +void SocialActivitiesDisplay::updateSocialActivityVisualStyles(boost::shared_ptr& socialActivityVisual) +{ + std::stringstream ss; + + Ogre::ColourValue activityColor = getActivityColor(socialActivityVisual->activityType, socialActivityVisual->confidence); + bool hideActivity = isActivityTypeHidden(socialActivityVisual->activityType) || socialActivityVisual->confidence < m_min_confidence_property->getFloat(); + bool showCircles = m_render_circles_property->getBool(); + + foreach(boost::shared_ptr circle, socialActivityVisual->socialActivityAssignmentCircles) { + circle->setColor(activityColor.r, activityColor.g, activityColor.b, activityColor.a * m_circle_alpha_property->getFloat() * (showCircles ? 1.0f : 0.0f)); + const double circleDiameter = m_circle_radius_property->getFloat() * 2, circleHeight = 0; + circle->setScale(shapeQuaternion * Ogre::Vector3(circleDiameter, circleDiameter, circleHeight)); + } + + double connectionLineVisibilityAlpha = m_render_intraactivity_connections_property->getBool() ? 1.0 : 0.0; + foreach(boost::shared_ptr connectionLine, socialActivityVisual->connectionLines) { + connectionLine->setColor(activityColor.r, activityColor.g, activityColor.b, activityColor.a * connectionLineVisibilityAlpha); + connectionLine->setLineWidth(m_line_width_property->getFloat()); + } + + // Update text colors, size and visibility + ss.str(""); ss << socialActivityVisual->activityType; + if(m_render_confidences_property->getBool()) ss << fixed << setprecision(1) << " (" << 100*socialActivityVisual->confidence << "%)"; + + for(int i = 0; i < socialActivityVisual->typeTexts.size(); i++) { + boost::shared_ptr& typeText = socialActivityVisual->typeTexts[i]; + + if(typeText) { // might be not set if center of activity could not be determined + typeText->setCaption(ss.str()); + + Ogre::Vector3 centerAt; + if(m_activity_type_per_track_property->getBool()) { + boost::shared_ptr trackedPerson = m_trackedPersonsCache.lookup(socialActivityVisual->trackIds[i]); + if(!trackedPerson) continue; + centerAt = Ogre::Vector3(trackedPerson->center.x, trackedPerson->center.y, m_commonProperties->z_offset->getFloat()); + } + else centerAt = Ogre::Vector3(socialActivityVisual->socialActivityCenter.x, socialActivityVisual->socialActivityCenter.y, socialActivityVisual->socialActivityCenter.z); + + Ogre::ColourValue fontColor = m_commonProperties->font_color_style->getOptionInt() == FONT_COLOR_CONSTANT ? m_commonProperties->constant_font_color->getOgreColor() : activityColor; + fontColor.a = m_commonProperties->alpha->getFloat(); + if(hideActivity) fontColor.a = 0; + float characterHeight = 0.23 * m_commonProperties->font_scale->getFloat(); + typeText->setVisible(m_render_activity_types_property->getBool()); + typeText->setCharacterHeight(characterHeight); + typeText->setColor(fontColor); + typeText->setPosition(m_frameTransform * Ogre::Vector3( + centerAt.x, + centerAt.y, + centerAt.z + m_activity_type_offset->getFloat() + m_commonProperties->z_offset->getFloat() + + socialActivityVisual->declutteringOffset * characterHeight /* this is for decluttering of overlapping labels */)); + } + } +} + +// Helper function for guaranteeing consistent ordering of activity labels +bool CompareActivityByType (const SocialActivitiesDisplay::ActivityWithConfidence& first, const SocialActivitiesDisplay::ActivityWithConfidence& second) { + return first.type < second.type; +} + +// This is our callback to handle an incoming group message. +void SocialActivitiesDisplay::processMessage(const spencer_social_relation_msgs::SocialActivities::ConstPtr& msg) +{ + // Get transforms into fixed frame etc. + if(!preprocessMessage(msg)) return; + + // Transform into Rviz fixed frame + m_frameTransform = Ogre::Matrix4(m_frameOrientation); + m_frameTransform.setTrans(m_framePosition); + stringstream ss; + + // Clear previous visualization (not very efficient, but easier to implement) + // Note that person visuals are not cleared to allow walking animations to function properly + m_socialActivityVisuals.clear(); + m_socialActivitiesSceneNode->removeAndDestroyAllChildren(); + + m_highestConfidenceActivityPerTrack.clear(); // used later on to determine color of person visuals + m_allActivitiesPerTrack.clear(); + + unsigned int numTracksWithUnknownPosition = 0; + + + // + // Iterate over all social activities in this message + // + foreach (const spencer_social_relation_msgs::SocialActivity& socialActivity, msg->elements) + { + // Create a new visual representation of the social activity + boost::shared_ptr socialActivityVisual = boost::shared_ptr(new SocialActivityVisual); + socialActivityVisual->activityType = socialActivity.type; + socialActivityVisual->confidence = socialActivity.confidence; + socialActivityVisual->personCount = socialActivity.track_ids.size(); + m_socialActivityVisuals.push_back(socialActivityVisual); + + geometry_msgs::Point socialActivityCenter; + size_t numGoodTracksInActivity = 0; + + // + // Assignment circles, person visuals (if enabled) + connections between social activity members + // + + for(size_t trackIndex = 0; trackIndex < socialActivity.track_ids.size(); trackIndex++) + { + const track_id trackId = socialActivity.track_ids[trackIndex]; + boost::shared_ptr trackedPerson = m_trackedPersonsCache.lookup(trackId); + + ActivityWithConfidence activityWithConfidence; + activityWithConfidence.type = socialActivity.type; + activityWithConfidence.confidence = socialActivity.confidence; + + // Update map of highest-confidence activity per person + if(m_highestConfidenceActivityPerTrack.find(trackId) == m_highestConfidenceActivityPerTrack.end() + || socialActivity.confidence > m_highestConfidenceActivityPerTrack[trackId].confidence) { + m_highestConfidenceActivityPerTrack[trackId] = activityWithConfidence; + } + + // Update map of all activities per person + if(m_allActivitiesPerTrack.find(trackId) == m_allActivitiesPerTrack.end()) { + m_allActivitiesPerTrack[trackId] = vector(); + } + m_allActivitiesPerTrack[trackId].push_back(activityWithConfidence); + + + // Get current track position + if(!trackedPerson) { + numTracksWithUnknownPosition++; + } + else + { + socialActivityVisual->trackIds.push_back(trackId); + numGoodTracksInActivity++; + + Ogre::Vector3 trackCenterAtGroundPlane(trackedPerson->center.x, trackedPerson->center.y, m_commonProperties->z_offset->getFloat()); + socialActivityCenter.x += trackCenterAtGroundPlane.x; + socialActivityCenter.y += trackCenterAtGroundPlane.y; + socialActivityCenter.z += trackCenterAtGroundPlane.z; + + + // + // Social activity assignment circles (below tracks) + // + + if(m_render_circles_property->getBool()) // only create circles if they are enabled, for better performance + { + boost::shared_ptr circle = boost::shared_ptr(new rviz::Shape(rviz::Shape::Cylinder, context_->getSceneManager(), m_socialActivitiesSceneNode.get())); + + const double circleHeight = 0; + circle->setOrientation(shapeQuaternion); + + Ogre::Vector3 circlePos = trackCenterAtGroundPlane + Ogre::Vector3(0, 0, -0.5*circleHeight - 0.01); + circle->setPosition(circlePos); + + socialActivityVisual->socialActivityAssignmentCircles.push_back(circle); + } + + // + // Intra-activity connections + // + + if(m_render_intraactivity_connections_property->getBool()) // only create circles if they are enabled, for better performance + { + // Iterate over all tracks sharing the same activity to render intra-activity connections + for(size_t otherTrackIndex = trackIndex + 1; otherTrackIndex < socialActivity.track_ids.size(); otherTrackIndex++) + { + const track_id otherTrackId = socialActivity.track_ids[otherTrackIndex]; + boost::shared_ptr otherTrackedPerson = m_trackedPersonsCache.lookup(otherTrackId); + + // Get other track's position + if(otherTrackedPerson) { + // Get positions. These are already in fixed frame coordinates! + const Ogre::Vector3 verticalShift(0,0, 0.5 + m_commonProperties->z_offset->getFloat()); + const Ogre::Vector3& position1 = verticalShift + trackedPerson->center; + const Ogre::Vector3& position2 = verticalShift + otherTrackedPerson->center; + + // Add line connecting the two tracks + boost::shared_ptr connectionLine(new rviz::BillboardLine(context_->getSceneManager(), m_socialActivitiesSceneNode.get())); + connectionLine->setMaxPointsPerLine(2); + connectionLine->addPoint(position1); + connectionLine->addPoint(position2); + socialActivityVisual->connectionLines.push_back(connectionLine); + } + } // end loop over other tracks sharing same activity + } + + } // end if track found + } // end for loop over tracks + + // + // Texts + // + socialActivityCenter.x /= (double) numGoodTracksInActivity; + socialActivityCenter.y /= (double) numGoodTracksInActivity; + socialActivityCenter.z /= (double) numGoodTracksInActivity; + socialActivityVisual->socialActivityCenter = socialActivityCenter; + + // Social activity type + if(numGoodTracksInActivity > 0) { + for(int i = 0; i < (m_activity_type_per_track_property->getBool() ? socialActivityVisual->trackIds.size() : 1); i++) { + boost::shared_ptr typeText(new TextNode(context_->getSceneManager(), m_socialActivitiesSceneNode.get())); + typeText->showOnTop(); + socialActivityVisual->typeTexts.push_back(typeText); + } + } + } // end for loop over all social activities in msg + + + // + // Second iteration over all social activities and member tracks, required for decluttering + // + ROS_ASSERT(msg->elements.size() == m_socialActivityVisuals.size()); + for(size_t i = 0; i < msg->elements.size(); i++) + { + const spencer_social_relation_msgs::SocialActivity& socialActivity = msg->elements[i]; + boost::shared_ptr socialActivityVisual = m_socialActivityVisuals[i]; + size_t maxIndexOfThisActivity = 0; + + for(size_t trackIndex = 0; trackIndex < socialActivity.track_ids.size(); trackIndex++) + { + const track_id trackId = socialActivity.track_ids[trackIndex]; + vector activitiesOfTrack(m_allActivitiesPerTrack[trackId]); + + // Sort to ensure consistency across multiple runs, even if msg->elements order changes + std::sort(activitiesOfTrack.begin(), activitiesOfTrack.end(), CompareActivityByType); + + for(size_t j = 0; j < activitiesOfTrack.size(); j++) { + if(activitiesOfTrack[j].type == socialActivityVisual->activityType) { + maxIndexOfThisActivity = std::max(maxIndexOfThisActivity, j); + break; + } + } + } + + socialActivityVisual->declutteringOffset = maxIndexOfThisActivity; // got it + } + + + // + // Create person visuals for all tracked persons (colored in color of activity with highest confidence) + // + set seenTrackIds; + foreach(const TrackedPersonsCache::CachedTrackedPersonsMap::value_type& entry, m_trackedPersonsCache.getMap()) { + const track_id trackId = entry.first; + const boost::shared_ptr trackedPerson = entry.second; + + PersonVisualContainer personVisualContainer; + if(m_personVisualMap.find(trackId) != m_personVisualMap.end()) { + personVisualContainer = m_personVisualMap[trackId]; + } + else { + personVisualContainer.trackId = trackId; + personVisualContainer.sceneNode = boost::shared_ptr(scene_node_->createChildSceneNode()); // This scene node is the parent of all visualization elements for the tracked person + } + + // Create new visual for the person itself, if needed + createPersonVisualIfRequired(personVisualContainer.sceneNode.get(), personVisualContainer.personVisual); + + const double personHeight = personVisualContainer.personVisual ? personVisualContainer.personVisual->getHeight() : 0; + const Ogre::Matrix3 covXYZinTargetFrame = covarianceXYZIntoTargetFrame(trackedPerson->pose); + setPoseOrientation(personVisualContainer.sceneNode.get(), trackedPerson->pose, covXYZinTargetFrame, personHeight); + + // Update walking animation if required + const Ogre::Vector3 velocityVector = getVelocityVector(trackedPerson->twist); + boost::shared_ptr meshPersonVisual = boost::dynamic_pointer_cast(personVisualContainer.personVisual); + if(meshPersonVisual) { + meshPersonVisual->setWalkingSpeed(velocityVector.length()); + } + + m_personVisualMap[trackId] = personVisualContainer; // to keep visuals alive across multiple frames, for walking animation + seenTrackIds.insert(trackId); + } + + // Delete obsolete track visuals of tracks that have disappeared + set trackIdsToDelete; + foreach(track_id trackId, m_personVisualMap | boost::adaptors::map_keys) { + if(seenTrackIds.find(trackId) == seenTrackIds.end()) trackIdsToDelete.insert(trackId); + } + foreach(track_id trackIdToDelete, trackIdsToDelete) { + m_personVisualMap.erase(trackIdToDelete); + } + + // + // Update all styles (colors etc. which can also be reconfigured at runtime, even if no new messages are received) + // + stylesChanged(); + + + // + // Update status (shown in property pane) + // + + ss.str(""); + ss << msg->elements.size() << " activities(s)"; + setStatusStd(rviz::StatusProperty::Ok, "Social activities", ss.str()); + + ss.str(""); + ss << numTracksWithUnknownPosition << " track(s) with unknown position"; + setStatusStd(0 == numTracksWithUnknownPosition ? rviz::StatusProperty::Ok : rviz::StatusProperty::Warn, "Track-to-activity assignment", ss.str()); +} + +} // end namespace spencer_tracking_rviz_plugin + +// Tell pluginlib about this class. It is important to do this in +// global scope, outside our package's namespace. +#include +PLUGINLIB_EXPORT_CLASS(spencer_tracking_rviz_plugin::SocialActivitiesDisplay, rviz::Display) diff --git a/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/src/social_activities_display.h b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/src/social_activities_display.h new file mode 100755 index 0000000..9414e83 --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/src/social_activities_display.h @@ -0,0 +1,167 @@ +/* +* Software License Agreement (BSD License) +* +* Copyright (c) 2013-2015, Timm Linder, Social Robotics Lab, University of Freiburg +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* * Redistributions of source code must retain the above copyright notice, this +* list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above copyright notice, +* this list of conditions and the following disclaimer in the documentation +* and/or other materials provided with the distribution. +* * Neither the name of the copyright holder nor the names of its contributors +* may be used to endorse or promote products derived from this software +* without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*/ + +#ifndef SOCIAL_ACTIVITIES_DISPLAY_H +#define SOCIAL_ACTIVITIES_DISPLAY_H +#ifndef Q_MOC_RUN +#include +#include +#include +#include +#endif +#include "person_display_common.h" +#include "tracked_persons_cache.h" + +namespace spencer_tracking_rviz_plugin +{ + typedef std::string activity_type; + + /// The display which can be added in RViz to display social activities. + class SocialActivitiesDisplay: public PersonDisplayCommon + { + Q_OBJECT + public: + // To determine, for persons involved in multiple social activities, their most likely one. + struct ActivityWithConfidence { + activity_type type; + float confidence; + }; + + // Constructor. pluginlib::ClassLoader creates instances by calling + // the default constructor, so make sure you have one. + SocialActivitiesDisplay() {}; + virtual ~SocialActivitiesDisplay(); + + // Overrides of protected virtual functions from Display. As much + // as possible, when Displays are not enabled, they should not be + // subscribed to incoming data and should not show anything in the + // 3D view. These functions are where these connections are made + // and broken. + + // Called after the constructors have run + virtual void onInitialize(); + + // Called periodically by the visualization manager + virtual void update(float wall_dt, float ros_dt); + + protected: + // A helper to clear this display back to the initial state. + virtual void reset(); + + // Must be implemented by derived classes because MOC doesn't work in templates + virtual rviz::DisplayContext* getContext() { + return context_; + } + + private: + struct SocialActivityVisual { + vector > socialActivityAssignmentCircles; + vector > connectionLines; + vector< boost::shared_ptr > typeTexts; + vector trackIds; + activity_type activityType; + float confidence; + geometry_msgs::Point socialActivityCenter; + size_t personCount; + size_t declutteringOffset; // for decluttering of labels etc. in case of multiple activities per track, e.g. 1 = shift label by 1 row + }; + + // Functions to handle an incoming ROS message. + void processMessage(const spencer_social_relation_msgs::SocialActivities::ConstPtr& msg); + + // Helper functions + void updateSocialActivityVisualStyles(boost::shared_ptr& groupVisual); + bool isActivityTypeHidden(activity_type activityType); + Ogre::ColourValue getActivityColor(activity_type activityType, float confidence); + + // Scene nodes + boost::shared_ptr m_socialActivitiesSceneNode; + + // User-editable property variables. + rviz::StringProperty* m_excluded_activity_types_property; + rviz::StringProperty* m_included_activity_types_property; + + rviz::BoolProperty* m_render_intraactivity_connections_property; + rviz::BoolProperty* m_render_activity_types_property; + rviz::BoolProperty* m_activity_type_per_track_property; + rviz::BoolProperty* m_render_confidences_property; + rviz::BoolProperty* m_render_circles_property; + rviz::BoolProperty* m_hide_with_no_activity_property; + + rviz::FloatProperty* m_occlusion_alpha_property; + rviz::FloatProperty* m_min_confidence_property; + rviz::FloatProperty* m_circle_radius_property; + rviz::FloatProperty* m_circle_alpha_property; + rviz::FloatProperty* m_line_width_property; + rviz::FloatProperty* m_activity_type_offset; // z offset of the group ID text + + rviz::Property* m_activity_colors; + rviz::ColorProperty* m_activity_color_none; + rviz::ColorProperty* m_activity_color_unknown; + rviz::ColorProperty* m_activity_color_shopping; + rviz::ColorProperty* m_activity_color_standing; + rviz::ColorProperty* m_activity_color_individual_moving; + rviz::ColorProperty* m_activity_color_waiting_in_queue; + rviz::ColorProperty* m_activity_color_looking_at_information_screen; + rviz::ColorProperty* m_activity_color_looking_at_kiosk; + rviz::ColorProperty* m_activity_color_group_assembling; + rviz::ColorProperty* m_activity_color_group_moving; + rviz::ColorProperty* m_activity_color_flow; + rviz::ColorProperty* m_activity_color_antiflow; + rviz::ColorProperty* m_activity_color_waiting_for_others; + rviz::ColorProperty* m_activity_color_looking_for_help; + + + // State variables + struct PersonVisualContainer { + boost::shared_ptr personVisual; + boost::shared_ptr sceneNode; + track_id trackId; + }; + + vector > m_socialActivityVisuals; + map m_personVisualMap; // to keep person visuals alive across multiple frames, for walking animation + + map m_highestConfidenceActivityPerTrack; // only highest-confidence activity per person + map > m_allActivitiesPerTrack; // all activities that a track is involved in + + set m_excludedActivityTypes, m_includedActivityTypes; + + Ogre::Matrix4 m_frameTransform; + TrackedPersonsCache m_trackedPersonsCache; + + private Q_SLOTS: + void personVisualTypeChanged(); + virtual void stylesChanged(); + }; + +} // end namespace spencer_tracking_rviz_plugin + +#endif // SOCIAL_ACTIVITIES_DISPLAY_H diff --git a/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/src/social_relations_display.cpp b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/src/social_relations_display.cpp new file mode 100755 index 0000000..f38e44f --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/src/social_relations_display.cpp @@ -0,0 +1,167 @@ +/* +* Software License Agreement (BSD License) +* +* Copyright (c) 2013-2015, Timm Linder, Social Robotics Lab, University of Freiburg +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* * Redistributions of source code must retain the above copyright notice, this +* list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above copyright notice, +* this list of conditions and the following disclaimer in the documentation +* and/or other materials provided with the distribution. +* * Neither the name of the copyright holder nor the names of its contributors +* may be used to endorse or promote products derived from this software +* without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*/ + +#include +#include +#include "rviz/selection/selection_manager.h" + +#ifndef Q_MOC_RUN +#include "social_relations_display.h" +#include +#endif +#define foreach BOOST_FOREACH + +namespace spencer_tracking_rviz_plugin +{ + +void SocialRelationsDisplay::onInitialize() +{ + m_trackedPersonsCache.initialize(this, context_, update_nh_); + PersonDisplayCommon::onInitialize(); + + m_relation_type_filter_property = new rviz::StringProperty( "Relation type filter", "", "Type of social relations to display (see \"type\" field in message). No wildcards allowed. Leave empty to allow any type of relation.", this, SLOT(stylesChanged())); + + m_positive_person_relation_threshold = new rviz::FloatProperty( "Positive relation threshold", 0.5, "Above which probability threshold a social relation between tracks is considered as positive", this, SLOT(stylesChanged())); + + m_positive_person_relations_color = new rviz::ColorProperty( "Positive relation color", QColor(0,255,0), "Color for positive track relations", this, SLOT(stylesChanged())); + m_negative_person_relations_color = new rviz::ColorProperty( "Negative relation color", QColor(255,0,0), "Color for negative track relations", this, SLOT(stylesChanged())); + + m_render_positive_person_relations_property = new rviz::BoolProperty( "Render positive relations", true, "Render positive person relations", this, SLOT(stylesChanged())); + m_render_negative_person_relations_property = new rviz::BoolProperty( "Render negative relations", false, "Render negative person relations", this, SLOT(stylesChanged())); + + // Create a scene node for visualizing social relations + m_socialRelationsSceneNode = boost::shared_ptr(scene_node_->createChildSceneNode()); +} + +SocialRelationsDisplay::~SocialRelationsDisplay() +{ +} + +// Clear the visuals by deleting their objects. +void SocialRelationsDisplay::reset() +{ + PersonDisplayCommon::reset(); + m_trackedPersonsCache.reset(); + m_relationVisuals.clear(); +} + +void SocialRelationsDisplay::processMessage(const spencer_social_relation_msgs::SocialRelations::ConstPtr& msg) +{ + // Get transforms into fixed frame etc. + if(!preprocessMessage(msg)) return; + + // Loop over all social relations between tracks + m_relationVisuals.clear(); + m_socialRelationsSceneNode->removeAndDestroyAllChildren(); + + foreach(const spencer_social_relation_msgs::SocialRelation& socialRelation, msg->elements) + { + boost::shared_ptr personTrack1 = m_trackedPersonsCache.lookup(socialRelation.track1_id); + boost::shared_ptr personTrack2 = m_trackedPersonsCache.lookup(socialRelation.track2_id); + + // Cannot draw relations for tracks with unknown position + if(!personTrack1 || !personTrack2) continue; + + // Create a new visual representation of the tracked person + boost::shared_ptr relationVisual = boost::shared_ptr(new RelationVisual); + relationVisual->type = socialRelation.type; + relationVisual->relationStrength = socialRelation.strength; + m_relationVisuals.push_back(relationVisual); + + // Get positions. These are already in fixed frame coordinates! + const Ogre::Vector3 verticalShift(0,0, 1.0 + m_commonProperties->z_offset->getFloat()), textShift(0,0, 0.3); + const Ogre::Vector3& position1 = verticalShift + personTrack1->center; + const Ogre::Vector3& position2 = verticalShift + personTrack2->center; + const Ogre::Vector3& centerPosition = (position1 + position2) / 2.0; + + // Add line connecting the two tracks + boost::shared_ptr relationLine(new rviz::BillboardLine(context_->getSceneManager(), m_socialRelationsSceneNode.get())); + relationLine->setMaxPointsPerLine(2); + relationLine->addPoint(position1); + relationLine->addPoint(position2); + relationVisual->relationLine = relationLine; + + // Add relationship strength text + stringstream ss; + boost::shared_ptr relationText(new TextNode(context_->getSceneManager(), m_socialRelationsSceneNode.get())); + ss.str(""); ss << std::fixed << std::setprecision(0) << socialRelation.strength * 100 << "%"; + relationText->setCaption(ss.str()); + relationText->setPosition(centerPosition + textShift); + relationText->showOnTop(); + relationVisual->relationText = relationText; + + // Remember to which groups the tracks belong, to be able to hide certain groups and their track-to-track relations + relationVisual->trackId1 = socialRelation.track1_id; + relationVisual->trackId2 = socialRelation.track2_id; + + // Update adjustable styles + updateRelationVisualStyles(relationVisual); + } +} + +void SocialRelationsDisplay::stylesChanged() +{ + foreach(boost::shared_ptr relationVisual, m_relationVisuals) { + updateRelationVisualStyles(relationVisual); + } +} + +void SocialRelationsDisplay::updateRelationVisualStyles(boost::shared_ptr& relationVisual) +{ + std::string typeFilter = m_relation_type_filter_property->getStdString(); + bool validRelationType = relationVisual->type.find(typeFilter) != std::string::npos; + bool hideRelation = !validRelationType || isPersonHidden(relationVisual->trackId1) || isPersonHidden(relationVisual->trackId2); + + // Determine type of the relationship + bool isPositiveRelation = relationVisual->relationStrength > m_positive_person_relation_threshold->getFloat(); + + // Get color + Ogre::ColourValue relationColor = isPositiveRelation ? m_positive_person_relations_color->getOgreColor() : m_negative_person_relations_color->getOgreColor(); + relationColor.a *= m_commonProperties->alpha->getFloat(); // general alpha + if(hideRelation) relationColor.a = 0; + + if(isPositiveRelation && !m_render_positive_person_relations_property->getBool()) relationColor.a = 0; + if(!isPositiveRelation && !m_render_negative_person_relations_property->getBool()) relationColor.a = 0; + + + relationVisual->relationLine->setLineWidth(0.03 * (isPositiveRelation ? 1.0 : 0.3)); + relationVisual->relationLine->setColor(relationColor.r, relationColor.g, relationColor.b, relationColor.a); + + relationVisual->relationText->setCharacterHeight(0.15 * m_commonProperties->font_scale->getFloat()); + relationVisual->relationText->setColor(relationColor); +} + + +} // end namespace spencer_tracking_rviz_plugin + +// Tell pluginlib about this class. It is important to do this in +// global scope, outside our package's namespace. +#include +PLUGINLIB_EXPORT_CLASS(spencer_tracking_rviz_plugin::SocialRelationsDisplay, rviz::Display) diff --git a/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/src/social_relations_display.h b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/src/social_relations_display.h new file mode 100755 index 0000000..48e53cc --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/src/social_relations_display.h @@ -0,0 +1,108 @@ +/* +* Software License Agreement (BSD License) +* +* Copyright (c) 2013-2015, Timm Linder, Social Robotics Lab, University of Freiburg +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* * Redistributions of source code must retain the above copyright notice, this +* list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above copyright notice, +* this list of conditions and the following disclaimer in the documentation +* and/or other materials provided with the distribution. +* * Neither the name of the copyright holder nor the names of its contributors +* may be used to endorse or promote products derived from this software +* without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*/ + +#ifndef SOCIAL_RELATIONS_DISPLAY_H +#define SOCIAL_RELATIONS_DISPLAY_H + +#ifndef Q_MOC_RUN +#include +#include "person_display_common.h" +#include "tracked_persons_cache.h" +#endif + +namespace spencer_tracking_rviz_plugin +{ + /// The display which can be added in RViz to display social relations. + class SocialRelationsDisplay: public PersonDisplayCommon + { + Q_OBJECT + public: + // Constructor. pluginlib::ClassLoader creates instances by calling + // the default constructor, so make sure you have one. + SocialRelationsDisplay() {}; + virtual ~SocialRelationsDisplay(); + + // Overrides of protected virtual functions from Display. As much + // as possible, when Displays are not enabled, they should not be + // subscribed to incoming data and should not show anything in the + // 3D view. These functions are where these connections are made + // and broken. + + // Called after the constructors have run + virtual void onInitialize(); + + protected: + // A helper to clear this display back to the initial state. + virtual void reset(); + + // Must be implemented by derived classes because MOC doesn't work in templates + virtual rviz::DisplayContext* getContext() { + return context_; + } + + private: + struct RelationVisual { + std::string type; + double relationStrength; + boost::shared_ptr relationLine; + boost::shared_ptr relationText; + track_id trackId1, trackId2; // required to hide certain tracks + }; + + // Functions to handle an incoming ROS message. + void processMessage(const spencer_social_relation_msgs::SocialRelations::ConstPtr& msg); + + // Helper functions + void updateRelationVisualStyles(boost::shared_ptr& relationVisual); + + // Scene node for group affiliation history visualization + boost::shared_ptr m_socialRelationsSceneNode; + + // User-editable property variables. + rviz::StringProperty* m_relation_type_filter_property; + + rviz::BoolProperty* m_render_positive_person_relations_property; + rviz::BoolProperty* m_render_negative_person_relations_property; + + rviz::FloatProperty* m_positive_person_relation_threshold; + rviz::ColorProperty* m_positive_person_relations_color; + rviz::ColorProperty* m_negative_person_relations_color; + + // State variables + vector > m_relationVisuals; + TrackedPersonsCache m_trackedPersonsCache; + + private Q_SLOTS: + virtual void stylesChanged(); + }; + +} // end namespace spencer_tracking_rviz_plugin + +#endif // SOCIAL_RELATIONS_DISPLAY_H diff --git a/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/src/tracked_groups_display.cpp b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/src/tracked_groups_display.cpp new file mode 100755 index 0000000..160c54f --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/src/tracked_groups_display.cpp @@ -0,0 +1,405 @@ +/* +* Software License Agreement (BSD License) +* +* Copyright (c) 2013-2015, Timm Linder, Social Robotics Lab, University of Freiburg +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* * Redistributions of source code must retain the above copyright notice, this +* list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above copyright notice, +* this list of conditions and the following disclaimer in the documentation +* and/or other materials provided with the distribution. +* * Neither the name of the copyright holder nor the names of its contributors +* may be used to endorse or promote products derived from this software +* without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*/ + +#include +#include +#include "rviz/selection/selection_manager.h" + +#include "tracked_groups_display.h" +#ifndef Q_MOC_RUN +#include +#include +#include +#endif +#define foreach BOOST_FOREACH + +namespace spencer_tracking_rviz_plugin +{ + +void TrackedGroupsDisplay::onInitialize() +{ + m_realFixedFrame = "map"; + + m_trackedPersonsCache.initialize(this, context_, update_nh_); + PersonDisplayCommon::onInitialize(); + + QObject::connect(m_commonProperties->style, SIGNAL(changed()), this, SLOT(personVisualTypeChanged()) ); + + m_excluded_group_ids_property = new rviz::StringProperty( "Excluded group IDs", "", "Comma-separated list of group IDs whose group visualization should be hidden", this, SLOT(stylesChanged()) ); + m_included_group_ids_property = new rviz::StringProperty( "Included group IDs", "", "Comma-separated list of group IDs whose group visualization should be visible, overrides excluded", this, SLOT(stylesChanged()) ); + + m_render_intragroup_connections_property = new rviz::BoolProperty( "Connect group members", true, "Connect all members of a group by lines", this, SLOT(stylesChanged())); + m_render_ids_property = new rviz::BoolProperty( "Render group IDs", true, "Render group IDs as text", this, SLOT(stylesChanged())); + m_render_history_property = new rviz::BoolProperty( "Render history", false, "Render group affiliation history", this, SLOT(stylesChanged())); + + m_single_person_groups_in_constant_color_property = new rviz::BoolProperty( "Single-person groups in constant color", true, "Render single-person groups in constant color", this, SLOT(stylesChanged())); + m_hide_ids_of_single_person_groups_property = new rviz::BoolProperty( "Hide IDs of single-person groups", false, "Hide IDs of single-person groups", m_render_ids_property, SLOT(stylesChanged()), this); + + m_history_length_property = new rviz::IntProperty( "Global history size", 1000, "Global number of group affiliation history entries to display.", this, SLOT(stylesChanged())); + m_history_length_property->setMin( 1 ); + m_history_length_property->setMax( 10000000 ); + + m_occlusion_alpha_property = new rviz::FloatProperty( "Occlusion alpha", 0.5, "Alpha multiplier for history of occluded tracks", this, SLOT(stylesChanged()) ); + m_occlusion_alpha_property->setMin( 0.0 ); + + m_group_id_offset = new rviz::FloatProperty( "Group ID Z offset", 2.0, "Offset in z position (height) of the group ID text", this, SLOT(stylesChanged()) ); + + // Create a scene node for visualizing group affiliation history + m_groupAffiliationHistorySceneNode = boost::shared_ptr(scene_node_->createChildSceneNode()); + m_groupsSceneNode = boost::shared_ptr(scene_node_->createChildSceneNode()); +} + +TrackedGroupsDisplay::~TrackedGroupsDisplay() +{ +} + +// Clear the visuals by deleting their objects. +void TrackedGroupsDisplay::reset() +{ + PersonDisplayCommon::reset(); + m_trackedPersonsCache.reset(); + m_groupVisuals.clear(); + m_groupAffiliationHistory.clear(); + m_groupAffiliations.clear(); +} + +void TrackedGroupsDisplay::update(float wall_dt, float ros_dt) +{ + // Move map scene node + Ogre::Vector3 mapFramePosition; Ogre::Quaternion mapFrameOrientation; + getContext()->getFrameManager()->getTransform(m_realFixedFrame, ros::Time(0), mapFramePosition, mapFrameOrientation); + Ogre::Matrix4 mapFrameTransform(mapFrameOrientation); mapFrameTransform.setTrans(mapFramePosition); + m_groupAffiliationHistorySceneNode->setPosition(mapFramePosition); + m_groupAffiliationHistorySceneNode->setOrientation(mapFrameOrientation); +} + +bool TrackedGroupsDisplay::isGroupHidden(group_id groupId) { + bool isIncluded = m_includedGroupIDs.find(groupId) != m_includedGroupIDs.end(); + if(isIncluded) return false; + if(!m_includedGroupIDs.empty()) return true; + + return m_excludedGroupIDs.find(groupId) != m_excludedGroupIDs.end(); +} + +void TrackedGroupsDisplay::stylesChanged() +{ + // Get list of group IDs belonging to tracks that shall be hidden or visible + m_excludedGroupIDs.clear(); + { + string groupIDString = m_excluded_group_ids_property->getStdString(); + char_separator separator(","); + tokenizer< char_separator > tokens(groupIDString, separator); + foreach(const string& token, tokens) { + try { m_excludedGroupIDs.insert(lexical_cast(token)); } + catch(bad_lexical_cast &) {} + } + } + m_includedGroupIDs.clear(); + { + string groupIDString = m_included_group_ids_property->getStdString(); + char_separator separator(","); + tokenizer< char_separator > tokens(groupIDString, separator); + foreach(const string& token, tokens) { + try { m_includedGroupIDs.insert(lexical_cast(token)); } + catch(bad_lexical_cast &) {} + } + } + + foreach(boost::shared_ptr groupVisual, m_groupVisuals) { + updateGroupVisualStyles(groupVisual); + } + + // Update history size + m_groupAffiliationHistory.rset_capacity(m_history_length_property->getInt()); + + // Update history color etc. + updateHistoryStyles(); +} + + +// Set the rendering style (cylinders, meshes, ...) of tracked persons +void TrackedGroupsDisplay::personVisualTypeChanged() +{ + foreach(boost::shared_ptr groupVisual, m_groupVisuals) { + foreach(boost::shared_ptr& personVisual, groupVisual->personVisuals) { + Ogre::SceneNode* parentSceneNode = personVisual->getParentSceneNode(); + personVisual.reset(); + createPersonVisualIfRequired(parentSceneNode, personVisual); + } + } + stylesChanged(); +} + +void TrackedGroupsDisplay::updateGroupVisualStyles(boost::shared_ptr& groupVisual) +{ + bool hideGroup = isGroupHidden(groupVisual->groupId); + + // Apply current group color + Ogre::ColourValue groupColor = m_commonProperties->constant_color->getOgreColor(); + + if(groupVisual->personCount > 1 || !m_single_person_groups_in_constant_color_property->getBool()) { + groupColor = getColorFromId(groupVisual->groupId); + } + + groupColor.a *= m_commonProperties->alpha->getFloat(); // general alpha + if(hideGroup) groupColor.a = 0; + + foreach(boost::shared_ptr groupAssignmentCircle, groupVisual->groupAssignmentCircles) { + groupAssignmentCircle->setColor(groupColor.r, groupColor.g, groupColor.b, groupColor.a); + } + + foreach(boost::shared_ptr& personVisual, groupVisual->personVisuals) { + if(personVisual) { + // Update common styles to person visual, such as line width + applyCommonStyles(personVisual); + + personVisual->setColor(groupColor); + } + } + + double connectionLineVisibilityAlpha = m_render_intragroup_connections_property->getBool() ? 1.0 : 0.0; + foreach(boost::shared_ptr connectionLine, groupVisual->connectionLines) { + connectionLine->setColor(groupColor.r, groupColor.g, groupColor.b, groupColor.a * connectionLineVisibilityAlpha); + connectionLine->setLineWidth(0.05); + } + + // Update text colors, size and visibility + Ogre::ColourValue fontColor = m_commonProperties->font_color_style->getOptionInt() == FONT_COLOR_CONSTANT ? m_commonProperties->constant_font_color->getOgreColor() : groupColor; + fontColor.a = m_commonProperties->alpha->getFloat(); + if(hideGroup) fontColor.a = 0; + bool groupIdVisible = groupVisual->personCount > 1 ? true : !m_hide_ids_of_single_person_groups_property->getBool(); + groupVisual->idText->setVisible(m_render_ids_property->getBool() && groupIdVisible); + groupVisual->idText->setCharacterHeight(0.23 * m_commonProperties->font_scale->getFloat()); + groupVisual->idText->setColor(fontColor); + groupVisual->idText->setPosition(m_frameTransform * Ogre::Vector3( + groupVisual->groupCenter.x, + groupVisual->groupCenter.y, + groupVisual->groupCenter.z + m_group_id_offset->getFloat() + m_commonProperties->z_offset->getFloat())); +} + +void TrackedGroupsDisplay::updateHistoryStyles() +{ + const Ogre::Quaternion shapeQuaternion( Ogre::Degree(90), Ogre::Vector3(1,0,0) ); + foreach(boost::shared_ptr groupAffiliationHistoryEntry, m_groupAffiliationHistory) { + bool hideGroup = isGroupHidden(groupAffiliationHistoryEntry->groupId); + const double historyShapeDiameter = 0.1; + + Ogre::ColourValue historyColor = m_commonProperties->constant_color->getOgreColor(); + + if(!groupAffiliationHistoryEntry->wasSinglePersonGroup || !m_single_person_groups_in_constant_color_property->getBool()) { + historyColor = getColorFromId(groupAffiliationHistoryEntry->groupId); + } + + + historyColor.a = m_commonProperties->alpha->getFloat(); + + if(groupAffiliationHistoryEntry->wasOccluded) historyColor.a *= m_occlusion_alpha_property->getFloat(); + if(hideGroup) historyColor.a = 0; + if(!m_render_history_property->getBool()) historyColor.a = 0; + + groupAffiliationHistoryEntry->shape->setColor(historyColor); + groupAffiliationHistoryEntry->shape->setScale(shapeQuaternion * Ogre::Vector3(historyShapeDiameter, historyShapeDiameter, 0.05)); + } +} + +// This is our callback to handle an incoming group message. +void TrackedGroupsDisplay::processMessage(const spencer_tracking_msgs::TrackedGroups::ConstPtr& msg) +{ + // Get transforms into fixed frame etc. + if(!preprocessMessage(msg)) return; + + // Transform from map/odometry frame into fixed frame, required to display track history if the fixed frame is not really "fixed" (e.g. base_link) + Ogre::Vector3 mapFramePosition; Ogre::Quaternion mapFrameOrientation; + getContext()->getFrameManager()->getTransform(m_realFixedFrame, msg->header.stamp, mapFramePosition, mapFrameOrientation); + Ogre::Matrix4 mapFrameTransform(mapFrameOrientation); mapFrameTransform.setTrans(mapFramePosition); + + // Transform into Rviz fixed frame + m_frameTransform = Ogre::Matrix4(m_frameOrientation); + m_frameTransform.setTrans(m_framePosition); + + const Ogre::Quaternion shapeQuaternion( Ogre::Degree(90), Ogre::Vector3(1,0,0) ); // required to fix orientation of any Cylinder shapes + stringstream ss; + + // Clear previous visualization + m_groupVisuals.clear(); + m_groupsSceneNode->removeAndDestroyAllChildren(); + + unsigned int numTracksWithUnknownPosition = 0; + m_groupAffiliations.clear(); + + // + // Iterate over all groups in this message + // + foreach (const spencer_tracking_msgs::TrackedGroup& trackedGroup, msg->groups) + { + // Create a new visual representation of the tracked group + boost::shared_ptr groupVisual = boost::shared_ptr(new GroupVisual); + groupVisual->groupId = trackedGroup.group_id; + groupVisual->personCount = trackedGroup.track_ids.size(); + m_groupVisuals.push_back(groupVisual); + + // + // Group visualization circles, person visuals (if enabled) + connections between group members + // + + for(size_t trackIndex = 0; trackIndex < trackedGroup.track_ids.size(); trackIndex++) + { + const track_id trackId = trackedGroup.track_ids[trackIndex]; + boost::shared_ptr trackedPerson = m_trackedPersonsCache.lookup(trackId); + + // Get current track position + if(!trackedPerson) { + numTracksWithUnknownPosition++; + } + else + { + Ogre::Vector3 trackCenterAtGroundPlane(trackedPerson->center.x, trackedPerson->center.y, m_commonProperties->z_offset->getFloat()); + + m_groupAffiliations[trackId] = trackedGroup.group_id; // required to hide certain groups later on + + + // + // Group visualization circles (below tracks) + // + + const double groupAssignmentCircleHeight = 0; + const double groupAssignmentCircleDiameter = 0.9; + boost::shared_ptr groupAssignmentCircle = boost::shared_ptr(new rviz::Shape(rviz::Shape::Cylinder, context_->getSceneManager(), m_groupsSceneNode.get())); + + groupAssignmentCircle->setScale(shapeQuaternion * Ogre::Vector3(groupAssignmentCircleDiameter, groupAssignmentCircleDiameter, groupAssignmentCircleHeight)); + groupAssignmentCircle->setOrientation(shapeQuaternion); + + Ogre::Vector3 groupAssignmentCirclePos = trackCenterAtGroundPlane + Ogre::Vector3(0, 0, -0.5*groupAssignmentCircleHeight - 0.01); + groupAssignmentCircle->setPosition(groupAssignmentCirclePos); + + groupVisual->groupAssignmentCircles.push_back(groupAssignmentCircle); + + + // + // Person visuals (colored in group color) + // + + // This scene node is the parent of all visualization elements for the tracked person + boost::shared_ptr sceneNode = boost::shared_ptr(scene_node_->createChildSceneNode()); + groupVisual->personVisualSceneNodes.push_back(sceneNode); + + // Create new visual for the person itself, if needed + boost::shared_ptr personVisual; + createPersonVisualIfRequired(sceneNode.get(), personVisual); + groupVisual->personVisuals.push_back(personVisual); + + const double personHeight = personVisual ? personVisual->getHeight() : 0; + const Ogre::Matrix3 covXYZinTargetFrame = covarianceXYZIntoTargetFrame(trackedPerson->pose); + setPoseOrientation(sceneNode.get(), trackedPerson->pose, covXYZinTargetFrame, personHeight); + + + // + // Intra-group connections + // + + // Iterate over all neighbouring group tracks to render intra-group connections + for(size_t otherTrackIndex = trackIndex + 1; otherTrackIndex < trackedGroup.track_ids.size(); otherTrackIndex++) + { + const track_id otherTrackId = trackedGroup.track_ids[otherTrackIndex]; + boost::shared_ptr otherTrackedPerson = m_trackedPersonsCache.lookup(otherTrackId); + + // Get other track's position + if(otherTrackedPerson) { + // Get positions. These are already in fixed frame coordinates! + const Ogre::Vector3 verticalShift(0,0, 0.5 + m_commonProperties->z_offset->getFloat()); + const Ogre::Vector3& position1 = verticalShift + trackedPerson->center; + const Ogre::Vector3& position2 = verticalShift + otherTrackedPerson->center; + + // Add line connecting the two tracks + boost::shared_ptr connectionLine(new rviz::BillboardLine(context_->getSceneManager(), m_groupsSceneNode.get())); + connectionLine->setMaxPointsPerLine(2); + connectionLine->addPoint(position1); + connectionLine->addPoint(position2); + groupVisual->connectionLines.push_back(connectionLine); + } + } // end loop over neighbouring group tracks + + + // + // Group affiliation history + // + + boost::shared_ptr newHistoryEntry(new GroupAffiliationHistoryEntry); + newHistoryEntry->shape = boost::shared_ptr(new rviz::Shape(rviz::Shape::Cylinder, context_->getSceneManager(), m_groupAffiliationHistorySceneNode.get())); + newHistoryEntry->shape->setPosition(mapFrameTransform.inverse() * trackCenterAtGroundPlane); + newHistoryEntry->shape->setOrientation(shapeQuaternion); + newHistoryEntry->wasOccluded = trackedPerson->isOccluded; + newHistoryEntry->wasSinglePersonGroup = trackedGroup.track_ids.size() <= 1; + newHistoryEntry->groupId = trackedGroup.group_id; + m_groupAffiliationHistory.push_back(newHistoryEntry); + + + } // end if track found + } // end for loop over tracks + + + // + // Texts + // + const geometry_msgs::Point& groupCenter = trackedGroup.centerOfGravity.pose.position; + groupVisual->groupCenter = groupCenter; + + // Group ID + boost::shared_ptr idText(new TextNode(context_->getSceneManager(), m_groupsSceneNode.get())); + ss.str(""); ss << "group " << trackedGroup.group_id; + idText->setCaption(ss.str()); + idText->showOnTop(); + groupVisual->idText = idText; + + // Set adjustable styles such as color etc. + updateGroupVisualStyles(groupVisual); + updateHistoryStyles(); + } // end for loop over all tracked groups + + + // + // Update status (shown in property pane) + // + + ss.str(""); + ss << msg->groups.size() << " group(s)"; + setStatusStd(rviz::StatusProperty::Ok, "Groups", ss.str()); + + ss.str(""); + ss << numTracksWithUnknownPosition << " track(s) with unknown position"; + setStatusStd(0 == numTracksWithUnknownPosition ? rviz::StatusProperty::Ok : rviz::StatusProperty::Warn, "Track-to-group assignment", ss.str()); +} + +} // end namespace spencer_tracking_rviz_plugin + +// Tell pluginlib about this class. It is important to do this in +// global scope, outside our package's namespace. +#include +PLUGINLIB_EXPORT_CLASS(spencer_tracking_rviz_plugin::TrackedGroupsDisplay, rviz::Display) diff --git a/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/src/tracked_groups_display.h b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/src/tracked_groups_display.h new file mode 100755 index 0000000..88c606d --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/src/tracked_groups_display.h @@ -0,0 +1,146 @@ +/* +* Software License Agreement (BSD License) +* +* Copyright (c) 2013-2015, Timm Linder, Social Robotics Lab, University of Freiburg +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* * Redistributions of source code must retain the above copyright notice, this +* list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above copyright notice, +* this list of conditions and the following disclaimer in the documentation +* and/or other materials provided with the distribution. +* * Neither the name of the copyright holder nor the names of its contributors +* may be used to endorse or promote products derived from this software +* without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*/ + +#ifndef TRACKED_GROUPS_DISPLAY_H +#define TRACKED_GROUPS_DISPLAY_H + +#ifndef Q_MOC_RUN +#include +#include +#endif +#include + +#include "person_display_common.h" +#include "tracked_persons_cache.h" + +namespace spencer_tracking_rviz_plugin +{ + typedef unsigned int group_id; + + /// A single entry in the history of a tracked person, to show group affiliation. + struct GroupAffiliationHistoryEntry + { + group_id groupId; + boost::shared_ptr shape; + bool wasOccluded, wasSinglePersonGroup; + }; + + /// History of a tracked person. + typedef circular_buffer > GroupAffiliationHistory; + + /// The display which can be added in RViz to display tracked groups. + class TrackedGroupsDisplay: public PersonDisplayCommon + { + Q_OBJECT + public: + // Constructor. pluginlib::ClassLoader creates instances by calling + // the default constructor, so make sure you have one. + TrackedGroupsDisplay() {}; + virtual ~TrackedGroupsDisplay(); + + // Overrides of protected virtual functions from Display. As much + // as possible, when Displays are not enabled, they should not be + // subscribed to incoming data and should not show anything in the + // 3D view. These functions are where these connections are made + // and broken. + + // Called after the constructors have run + virtual void onInitialize(); + + // Called periodically by the visualization manager + virtual void update(float wall_dt, float ros_dt); + + protected: + // A helper to clear this display back to the initial state. + virtual void reset(); + + // Must be implemented by derived classes because MOC doesn't work in templates + virtual rviz::DisplayContext* getContext() { + return context_; + } + + private: + struct GroupVisual { + vector > groupAssignmentCircles; + vector > personVisuals; + vector > personVisualSceneNodes; + vector > connectionLines; + boost::shared_ptr idText; + group_id groupId; + geometry_msgs::Point groupCenter; + size_t personCount; + }; + + // Functions to handle an incoming ROS message. + void processMessage(const spencer_tracking_msgs::TrackedGroups::ConstPtr& msg); + + // Helper functions + void updateGroupVisualStyles(boost::shared_ptr& groupVisual); + void updateHistoryStyles(); + bool isGroupHidden(group_id groupId); + + // Scene node for group affiliation history visualization + boost::shared_ptr m_groupAffiliationHistorySceneNode, m_groupsSceneNode; + + std::string m_realFixedFrame; + + // User-editable property variables. + rviz::StringProperty* m_excluded_group_ids_property; + rviz::StringProperty* m_included_group_ids_property; + + rviz::BoolProperty* m_render_intragroup_connections_property; + rviz::BoolProperty* m_render_ids_property; + rviz::BoolProperty* m_render_history_property; + rviz::BoolProperty* m_single_person_groups_in_constant_color_property; + rviz::BoolProperty* m_hide_ids_of_single_person_groups_property; + + rviz::IntProperty* m_history_length_property; + + rviz::FloatProperty* m_occlusion_alpha_property; + rviz::FloatProperty* m_group_id_offset; // z offset of the group ID text + + // State variables + vector > m_groupVisuals; + + map m_groupAffiliations; + GroupAffiliationHistory m_groupAffiliationHistory; + set m_excludedGroupIDs, m_includedGroupIDs; + + Ogre::Matrix4 m_frameTransform; + TrackedPersonsCache m_trackedPersonsCache; + + private Q_SLOTS: + void personVisualTypeChanged(); + virtual void stylesChanged(); + }; + +} // end namespace spencer_tracking_rviz_plugin + +#endif // TRACKED_GROUPS_DISPLAY_H diff --git a/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/src/tracked_persons_cache.cpp b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/src/tracked_persons_cache.cpp new file mode 100755 index 0000000..df8d734 --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/src/tracked_persons_cache.cpp @@ -0,0 +1,98 @@ +/* +* Software License Agreement (BSD License) +* +* Copyright (c) 2013-2015, Timm Linder, Social Robotics Lab, University of Freiburg +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* * Redistributions of source code must retain the above copyright notice, this +* list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above copyright notice, +* this list of conditions and the following disclaimer in the documentation +* and/or other materials provided with the distribution. +* * Neither the name of the copyright holder nor the names of its contributors +* may be used to endorse or promote products derived from this software +* without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*/ + +#include "tracked_persons_cache.h" + +#ifndef Q_MOC_RUN +#include +#include +#endif +#define foreach BOOST_FOREACH + + +namespace spencer_tracking_rviz_plugin +{ + +TrackedPersonsCache::~TrackedPersonsCache() +{ + m_cachedTrackedPersons.clear(); + delete m_tracked_person_subscriber; +} + +void TrackedPersonsCache::initialize(rviz::Display* display, rviz::DisplayContext* context, ros::NodeHandle update_nh) +{ + m_display = display; + m_context = context; + + m_tracked_person_subscriber = new rviz::AdditionalTopicSubscriber("Tracked persons topic", display, context, update_nh, + boost::bind(&TrackedPersonsCache::processTrackedPersonsMessage, this, _1)); +} + +void TrackedPersonsCache::reset() +{ + m_cachedTrackedPersons.clear(); +} + +const boost::shared_ptr TrackedPersonsCache::lookup(track_id trackId) +{ + CachedTrackedPersonsMap::const_iterator entry = m_cachedTrackedPersons.find(trackId); + if(entry == m_cachedTrackedPersons.end()) return boost::shared_ptr(); + else return entry->second; +} + +void TrackedPersonsCache::processTrackedPersonsMessage(const spencer_tracking_msgs::TrackedPersons::ConstPtr& msg) +{ + // Get transform of person tracks into fixed frame + Ogre::Vector3 frameOrigin; Ogre::Quaternion frameOrientation; + m_context->getFrameManager()->getTransform(msg->header, frameOrigin, frameOrientation); + Ogre::Matrix4 transform(frameOrientation); + transform.setTrans(frameOrigin); + + // Now iterate over all tracks and store their positions + m_cachedTrackedPersons.clear(); + foreach(spencer_tracking_msgs::TrackedPerson trackedPerson, msg->tracks) + { + m_cachedTrackedPersons[trackedPerson.track_id] = boost::shared_ptr(new CachedTrackedPerson); + CachedTrackedPerson& cachedTrackedPerson = *m_cachedTrackedPersons[trackedPerson.track_id]; + + const geometry_msgs::Point& position = trackedPerson.pose.pose.position; + cachedTrackedPerson.center = transform * Ogre::Vector3(position.x, position.y, position.z); + cachedTrackedPerson.pose = trackedPerson.pose; + cachedTrackedPerson.twist = trackedPerson.twist; + cachedTrackedPerson.isOccluded = trackedPerson.is_occluded; + } + + std::stringstream ss; + ss << msg->tracks.size() << " track(s)"; + m_display->setStatusStd(rviz::StatusProperty::Ok, "Tracks", ss.str()); +} + + +} // end namespace spencer_tracking_rviz_plugin diff --git a/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/src/tracked_persons_cache.h b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/src/tracked_persons_cache.h new file mode 100755 index 0000000..55f641c --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/src/tracked_persons_cache.h @@ -0,0 +1,93 @@ +/* +* Software License Agreement (BSD License) +* +* Copyright (c) 2013-2015, Timm Linder, Social Robotics Lab, University of Freiburg +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* * Redistributions of source code must retain the above copyright notice, this +* list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above copyright notice, +* this list of conditions and the following disclaimer in the documentation +* and/or other materials provided with the distribution. +* * Neither the name of the copyright holder nor the names of its contributors +* may be used to endorse or promote products derived from this software +* without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*/ + +#ifndef TRACKED_PERSONS_CACHE_H +#define TRACKED_PERSONS_CACHE_H + +#ifndef Q_MOC_RUN +#include +#include +#include +#include +#endif +#include "additional_topic_subscriber.h" + +namespace spencer_tracking_rviz_plugin +{ + typedef unsigned int track_id; + + /// Data structure for storing information about individual person tracks + struct CachedTrackedPerson + { + Ogre::Vector3 center; + geometry_msgs::PoseWithCovariance pose; + geometry_msgs::TwistWithCovariance twist; + bool isOccluded; + }; + + /// Subscribes to a TrackedPersons topic and caches all TrackedPersons of the current cycle, so that + /// the owning rviz::Display can look up track positions etc for visualization. + class TrackedPersonsCache { + public: + typedef std::map > CachedTrackedPersonsMap; + + // Destructor + ~TrackedPersonsCache(); + + /// Create TrackedPersons subscriber and setup RViz properties. + void initialize(rviz::Display* display, rviz::DisplayContext* context, ros::NodeHandle update_nh); + + /// Clear internal state, including all cached track positions. + void reset(); + + /// Lookup information for the given tracked person ID. Returns a null pointer if no information is available. + const boost::shared_ptr lookup(track_id trackId); + + /// Return internal map + const CachedTrackedPersonsMap& getMap() { + return m_cachedTrackedPersons; + } + + private: + // Callback when a new TrackedPersons message has arrived + void processTrackedPersonsMessage(const spencer_tracking_msgs::TrackedPersons::ConstPtr& msg); + + rviz::AdditionalTopicSubscriber* m_tracked_person_subscriber; + rviz::Display* m_display; + rviz::DisplayContext* m_context; + + // Our TrackedPerson memory + CachedTrackedPersonsMap m_cachedTrackedPersons; + }; + + +} + +#endif // TRACKED_PERSONS_CACHE_H diff --git a/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/src/tracked_persons_display.cpp b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/src/tracked_persons_display.cpp new file mode 100755 index 0000000..711bbf6 --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/src/tracked_persons_display.cpp @@ -0,0 +1,608 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2013-2015, Timm Linder, Social Robotics Lab, University of Freiburg + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * * Neither the name of the copyright holder nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef Q_MOC_RUN +#include +#include +#include "rviz/selection/selection_manager.h" +#include "tracked_persons_display.h" +#include +#include +#include +#endif +#define foreach BOOST_FOREACH + +namespace spencer_tracking_rviz_plugin +{ +// The constructor must have no arguments, so we can't give the +// constructor the parameters it needs to fully initialize. +void TrackedPersonsDisplay::onInitialize() +{ + PersonDisplayCommon::onInitialize(); + + m_realFixedFrame = "odom"; + QObject::connect(m_commonProperties->style, SIGNAL(changed()), this, SLOT(personVisualTypeChanged())); + + m_occlusion_alpha_property = new rviz::FloatProperty("Occlusion alpha", 0.3, "Alpha multiplier for occluded tracks", + this, SLOT(stylesChanged())); + m_occlusion_alpha_property->setMin(0.0); + + m_missed_alpha_property = + new rviz::FloatProperty("Missed alpha", 0.5, "Alpha multiplier for missed tracks", this, SLOT(stylesChanged())); + m_missed_alpha_property->setMin(0.0); + + m_history_length_property = new rviz::IntProperty("History size", 100, "Number of prior track positions to display.", + this, SLOT(stylesChanged())); + m_history_length_property->setMin(1); + m_history_length_property->setMax(10000000); + + m_delete_after_ncycles_property = new rviz::IntProperty("Delete after no. cycles", 100, + "After how many time steps to delete an old track that has " + "not been seen again, including its history", + this, SLOT(stylesChanged())); + m_delete_after_ncycles_property->setMin(0); + m_delete_after_ncycles_property->setMax(10000000); + + m_show_deleted_property = new rviz::BoolProperty( + "Show DELETED tracks", false, "Show tracks which have been marked as deleted", this, SLOT(stylesChanged())); + m_show_occluded_property = new rviz::BoolProperty("Show OCCLUDED tracks", true, + "Show tracks which could not be matched to an detection due to " + "sensor occlusion", + this, SLOT(stylesChanged())); + m_show_missed_property = new rviz::BoolProperty("Show MISSED tracks", true, + "Show tracks which could not be matched to an detection but should " + "be observable by the sensor", + this, SLOT(stylesChanged())); + m_show_matched_property = new rviz::BoolProperty( + "Show MATCHED tracks", true, "Show tracks which could be matched to an detection", this, SLOT(stylesChanged())); + + m_render_history_property = + new rviz::BoolProperty("Render history", true, "Render prior track positions", this, SLOT(stylesChanged())); + m_render_history_as_line_property = new rviz::BoolProperty( + "History as line", true, "Display history as line instead of dots", this, SLOT(stylesChanged())); + m_render_person_property = + new rviz::BoolProperty("Render person visual", true, "Render person visualization", this, SLOT(stylesChanged())); + m_render_covariances_property = new rviz::BoolProperty("Render covariances", true, "Render track covariance ellipses", + this, SLOT(stylesChanged())); + m_render_velocities_property = + new rviz::BoolProperty("Render velocities", true, "Render track velocity arrows", this, SLOT(stylesChanged())); + m_render_ids_property = + new rviz::BoolProperty("Render track IDs", true, "Render track IDs as text", this, SLOT(stylesChanged())); + m_render_detection_ids_property = new rviz::BoolProperty("Render detection IDs", true, + "Render IDs of the detection that a track was matched " + "against, if any", + this, SLOT(stylesChanged())); + m_render_track_state_property = + new rviz::BoolProperty("Render track state", true, "Render track state text", this, SLOT(stylesChanged())); + + m_history_min_point_distance_property = new rviz::FloatProperty("Min. history point distance", 0.4, + "Minimum distance between history points before a " + "new one is placed", + this, SLOT(stylesChanged())); + m_history_line_width_property = new rviz::FloatProperty( + "Line width", 0.05, "Line width of history", m_render_history_as_line_property, SLOT(stylesChanged()), this); + m_covariance_line_width_property = + new rviz::FloatProperty("Line width", 0.1, "Line width of covariance ellipses", m_render_covariances_property, + SLOT(stylesChanged()), this); + + // TODO: Implement functionality + // m_render_state_prediction_property = new rviz::BoolProperty( "Render state prediction", true, "Render state + // prediction from Kalman filter", this, SLOT( updateRenderFlags() )); + + // Create a scene node for visualizing track history + m_trackHistorySceneNode = boost::shared_ptr(scene_node_->createChildSceneNode()); +} + +TrackedPersonsDisplay::~TrackedPersonsDisplay() +{ + m_cachedTracks.clear(); +} + +// Clear the visuals by deleting their objects. +void TrackedPersonsDisplay::reset() +{ + PersonDisplayCommon::reset(); + m_cachedTracks.clear(); +} + +void TrackedPersonsDisplay::update(float wall_dt, float ros_dt) +{ + // Move map scene node + Ogre::Vector3 mapFramePosition; + Ogre::Quaternion mapFrameOrientation; + getContext()->getFrameManager()->getTransform(m_realFixedFrame, ros::Time(0), mapFramePosition, mapFrameOrientation); + Ogre::Matrix4 mapFrameTransform(mapFrameOrientation); + mapFrameTransform.setTrans(mapFramePosition); + m_trackHistorySceneNode->setPosition(mapFramePosition); + m_trackHistorySceneNode->setOrientation(mapFrameOrientation); + + // Update position of deleted tracks (because they are not being updated by ROS messages any more) + foreach (const track_map::value_type& entry, m_cachedTracks) + { + const boost::shared_ptr& trackedPersonVisual = entry.second; + if (trackedPersonVisual->isDeleted) + { + Ogre::Matrix4 poseInCurrentFrame = mapFrameTransform * trackedPersonVisual->lastObservedPose; + Ogre::Vector3 position = poseInCurrentFrame.getTrans(); + Ogre::Quaternion orientation = poseInCurrentFrame.extractQuaternion(); + if (!position.isNaN() && !orientation.isNaN()) + { + trackedPersonVisual->sceneNode->setPosition(position); + trackedPersonVisual->sceneNode->setOrientation(orientation); + } + } + else + { + // Update animation etc. + if (trackedPersonVisual->personVisual) + trackedPersonVisual->personVisual->update(ros_dt); + } + } +} + +/// Update all dynamically adjusted visualization properties (colors, font sizes etc.) of all currently tracked persons +void TrackedPersonsDisplay::stylesChanged() +{ + const Ogre::Quaternion shapeQuaternion(Ogre::Degree(90), Ogre::Vector3(1, 0, 0)); + + // Update each track + foreach (const track_map::value_type& entry, m_cachedTracks) + { + const track_id trackId = entry.first; + const boost::shared_ptr& trackedPersonVisual = entry.second; + + // Update common styles to person visual, such as line width + applyCommonStyles(trackedPersonVisual->personVisual); + + // Update track visibility + bool trackVisible = !isPersonHidden(trackId); + + if (trackedPersonVisual->isDeleted) + trackVisible &= m_show_deleted_property->getBool(); + else if (trackedPersonVisual->isOccluded) + trackVisible &= m_show_occluded_property->getBool(); + else if (trackedPersonVisual->isMissed) + trackVisible &= m_show_missed_property->getBool(); + else + trackVisible &= m_show_matched_property->getBool(); + + trackedPersonVisual->sceneNode->setVisible(trackVisible); + trackedPersonVisual->historySceneNode->setVisible(trackVisible && !m_render_history_as_line_property->getBool()); + trackedPersonVisual->historyLineSceneNode->setVisible(trackVisible && m_render_history_as_line_property->getBool()); + + // Get current track color + Ogre::ColourValue trackColorWithFullAlpha = getColorFromId(trackId); + Ogre::ColourValue trackColor = getColorFromId(trackId); + trackColor.a *= m_commonProperties->alpha->getFloat(); // general alpha + if (trackedPersonVisual->isOccluded) + trackColor.a *= m_occlusion_alpha_property->getFloat(); // occlusion alpha + if (trackedPersonVisual->isMissed) + trackColor.a *= m_missed_alpha_property->getFloat(); // occlusion alpha + + // Update person color + Ogre::ColourValue personColor = trackColor; + if (!m_render_person_property->getBool()) + personColor.a = 0.0; + + if (trackedPersonVisual->personVisual) + { + trackedPersonVisual->personVisual->setColor(personColor); + } + + // Update history size + trackedPersonVisual->history.rset_capacity(m_history_length_property->getInt()); + + // Update history color + foreach (boost::shared_ptr historyEntry, trackedPersonVisual->history) + { + const double historyShapeDiameter = 0.1; + Ogre::ColourValue historyColor = trackColorWithFullAlpha; + historyColor.a *= m_commonProperties->alpha->getFloat(); // general alpha + if (historyEntry->wasOccluded) + historyColor.a *= m_occlusion_alpha_property->getFloat(); + if (isPersonHidden(trackId) || m_render_history_as_line_property->getBool()) + historyColor.a = 0; + + if (historyEntry->shape) + { + historyEntry->shape->setColor(historyColor); + historyEntry->shape->setScale(shapeQuaternion * + Ogre::Vector3(historyShapeDiameter, historyShapeDiameter, 0.05)); + } + } + + if (trackedPersonVisual->historyLine) + { // history-as-line mode (as opposed to history-as-dots) + Ogre::ColourValue historyColor = trackColorWithFullAlpha; + historyColor.a *= m_commonProperties->alpha->getFloat(); // general alpha + if (isPersonHidden(trackId)) + historyColor.a = 0; + trackedPersonVisual->historyLine->setColor(historyColor.r, historyColor.g, historyColor.b, historyColor.a); + } + + // Update text colors, font size and visibility + const double personHeight = trackedPersonVisual->personVisual ? trackedPersonVisual->personVisual->getHeight() : 0; + Ogre::ColourValue fontColor = m_commonProperties->font_color_style->getOptionInt() == FONT_COLOR_CONSTANT ? + m_commonProperties->constant_font_color->getOgreColor() : + trackColor; + fontColor.a = m_commonProperties->alpha->getFloat(); + + trackedPersonVisual->detectionIdText->setCharacterHeight(0.18 * m_commonProperties->font_scale->getFloat()); + trackedPersonVisual->detectionIdText->setVisible(!trackedPersonVisual->isOccluded && + m_render_detection_ids_property->getBool() && trackVisible); + trackedPersonVisual->detectionIdText->setColor(fontColor); + trackedPersonVisual->detectionIdText->setPosition( + Ogre::Vector3(0, 0, -trackedPersonVisual->detectionIdText->getCharacterHeight())); + + trackedPersonVisual->stateText->setCharacterHeight(0.18 * m_commonProperties->font_scale->getFloat()); + trackedPersonVisual->stateText->setVisible(m_render_track_state_property->getBool() && trackVisible); + trackedPersonVisual->stateText->setColor(fontColor); + trackedPersonVisual->stateText->setPosition( + Ogre::Vector3(0, 0, personHeight + trackedPersonVisual->stateText->getCharacterHeight())); + + const double stateTextOffset = + m_render_track_state_property->getBool() ? 1.2 * trackedPersonVisual->stateText->getCharacterHeight() : 0; + trackedPersonVisual->idText->setCharacterHeight(0.25 * m_commonProperties->font_scale->getFloat()); + trackedPersonVisual->idText->setVisible(m_render_ids_property->getBool() && trackVisible); + trackedPersonVisual->idText->setColor(fontColor); + trackedPersonVisual->idText->setPosition( + Ogre::Vector3(0, 0, personHeight + trackedPersonVisual->idText->getCharacterHeight() + stateTextOffset)); + + // Update velocity arrow color + double arrowAlpha = m_render_velocities_property->getBool() ? trackColor.a : 0.0; + if (trackedPersonVisual->hasZeroVelocity) + arrowAlpha = 0.0; + trackedPersonVisual->velocityArrow->setColor( + Ogre::ColourValue(trackColor.r, trackColor.g, trackColor.b, arrowAlpha)); + + // Set color of covariance visualization + Ogre::ColourValue covarianceColor = trackColor; + if (!m_render_covariances_property->getBool()) + covarianceColor.a = 0.0; + trackedPersonVisual->covarianceVisual->setColor(covarianceColor); + trackedPersonVisual->covarianceVisual->setLineWidth(m_covariance_line_width_property->getFloat()); + } + + // Update global history visibility + m_trackHistorySceneNode->setVisible(m_render_history_property->getBool()); +} + +// Set the rendering style (cylinders, meshes, ...) of tracked persons +void TrackedPersonsDisplay::personVisualTypeChanged() +{ + foreach (const track_map::value_type& entry, m_cachedTracks) + { + const boost::shared_ptr& trackedPersonVisual = entry.second; + trackedPersonVisual->personVisual.reset(); + createPersonVisualIfRequired(trackedPersonVisual->sceneNode.get(), trackedPersonVisual->personVisual); + } + stylesChanged(); +} + +// This is our callback to handle an incoming message. +void TrackedPersonsDisplay::processMessage(const spencer_tracking_msgs::TrackedPersons::ConstPtr& msg) +{ + // Get transforms into fixed frame etc. + if (!preprocessMessage(msg)) + return; + + // Transform from map/odometry frame into fixed frame, required to display track history if the fixed frame is not + // really "fixed" (e.g. base_link) + Ogre::Vector3 mapFramePosition; + Ogre::Quaternion mapFrameOrientation; + getContext()->getFrameManager()->getTransform(m_realFixedFrame, msg->header.stamp, mapFramePosition, + mapFrameOrientation); + Ogre::Matrix4 mapFrameTransform(mapFrameOrientation); + mapFrameTransform.setTrans(mapFramePosition); + + // Transform required to fix orientation of any Cylinder shapes + const Ogre::Quaternion shapeQuaternion(Ogre::Degree(90), Ogre::Vector3(1, 0, 0)); + stringstream ss; + + // + // Iterate over all tracks in this message, see if we have a cached visual (then update it) or create a new one. + // + set encounteredTrackIds; + for (vector::const_iterator trackedPersonIt = msg->tracks.begin(); + trackedPersonIt != msg->tracks.end(); ++trackedPersonIt) + { + boost::shared_ptr trackedPersonVisual; + + // See if we encountered this track ID before in this loop (means duplicate track ID) + if (encounteredTrackIds.find(trackedPersonIt->track_id) != encounteredTrackIds.end()) + { + ROS_ERROR_STREAM("spencer_tracking_msgs::TrackedPersons contains duplicate track ID " + << trackedPersonIt->track_id << "! Skipping duplicate track."); + continue; + } + else + { + encounteredTrackIds.insert(trackedPersonIt->track_id); + } + + // See if we have cached a track with this ID + if (m_cachedTracks.find(trackedPersonIt->track_id) != m_cachedTracks.end()) + { + trackedPersonVisual = m_cachedTracks[trackedPersonIt->track_id]; + } + else + { + // Create a new visual representation of the tracked person + trackedPersonVisual = boost::shared_ptr(new TrackedPersonVisual); + m_cachedTracks[trackedPersonIt->track_id] = trackedPersonVisual; + + // This scene node is the parent of all visualization elements for the tracked person + trackedPersonVisual->sceneNode = boost::shared_ptr(scene_node_->createChildSceneNode()); + trackedPersonVisual->historySceneNode = + boost::shared_ptr(m_trackHistorySceneNode->createChildSceneNode()); + trackedPersonVisual->historyLineSceneNode = + boost::shared_ptr(m_trackHistorySceneNode->createChildSceneNode()); + } + + // These values need to be remembered for later use in stylesChanged() + if (trackedPersonIt->is_occluded && !trackedPersonIt->is_matched) + { + trackedPersonVisual->isOccluded = true; + trackedPersonVisual->isMissed = false; + } + else if (!trackedPersonIt->is_occluded && !trackedPersonIt->is_matched) + { + trackedPersonVisual->isOccluded = false; + trackedPersonVisual->isMissed = true; + } + else + { + trackedPersonVisual->isOccluded = false; + trackedPersonVisual->isMissed = false; + } + + trackedPersonVisual->isDeleted = false; + trackedPersonVisual->numCyclesNotSeen = 0; + + Ogre::SceneNode* currentSceneNode = trackedPersonVisual->sceneNode.get(); + + // + // Person visualization + // + + // Create new visual for the person itself, if needed + boost::shared_ptr& personVisual = trackedPersonVisual->personVisual; + createPersonVisualIfRequired(currentSceneNode, personVisual); + + const double personHeight = personVisual ? personVisual->getHeight() : 0; + const double halfPersonHeight = personHeight / 2.0; + + // + // Position of entire track + // + + const Ogre::Matrix3 covXYZinTargetFrame = covarianceXYZIntoTargetFrame(trackedPersonIt->pose); + setPoseOrientation(currentSceneNode, trackedPersonIt->pose, covXYZinTargetFrame, personHeight); + + // + // Track history + // + + Ogre::Vector3 newHistoryEntryPosition = mapFrameTransform.inverse() * currentSceneNode->getPosition(); + + const float MIN_HISTORY_ENTRY_DISTANCE = m_history_min_point_distance_property->getFloat(); // in meters + if ((trackedPersonVisual->positionOfLastHistoryEntry - newHistoryEntryPosition).length() > + MIN_HISTORY_ENTRY_DISTANCE) + { + // General history + boost::shared_ptr newHistoryEntry(new TrackedPersonHistoryEntry); + newHistoryEntry->trackId = trackedPersonIt->track_id; + newHistoryEntry->position = newHistoryEntryPosition; // used by history lines (below) even if no shape is set + newHistoryEntry->wasOccluded = trackedPersonIt->is_occluded; + trackedPersonVisual->history.push_back(newHistoryEntry); + + // Always need to reset history line since history is like a queue, oldest element has to be removed but + // BillboardLine doesn't offer that functionality + trackedPersonVisual->historyLine.reset( + new rviz::BillboardLine(context_->getSceneManager(), trackedPersonVisual->historyLineSceneNode.get())); + + if (m_render_history_as_line_property->getBool()) + { + // History lines + if (trackedPersonVisual->history.size() >= 2) + { + trackedPersonVisual->historyLine->setLineWidth(m_history_line_width_property->getFloat()); + trackedPersonVisual->historyLine->setMaxPointsPerLine(trackedPersonVisual->history.size()); + + foreach (const boost::shared_ptr& historyEntry, trackedPersonVisual->history) + { + historyEntry->shape.reset(); // remove existing dot shapes, if any, for better performance + trackedPersonVisual->historyLine->addPoint(historyEntry->position); + } + } + } + else + { + // History dots + newHistoryEntry->shape = boost::shared_ptr(new rviz::Shape( + rviz::Shape::Cylinder, context_->getSceneManager(), trackedPersonVisual->historySceneNode.get())); + newHistoryEntry->shape->setPosition(newHistoryEntryPosition); + newHistoryEntry->shape->setOrientation(shapeQuaternion); + } + + trackedPersonVisual->positionOfLastHistoryEntry = newHistoryEntryPosition; + } + + // + // Texts + // + { + if (!trackedPersonVisual->idText) + { + trackedPersonVisual->idText.reset(new TextNode(context_->getSceneManager(), currentSceneNode)); + trackedPersonVisual->stateText.reset(new TextNode(context_->getSceneManager(), currentSceneNode)); + trackedPersonVisual->detectionIdText.reset(new TextNode(context_->getSceneManager(), currentSceneNode)); + } + + // Detection ID + ss.str(""); + ss << "det " << trackedPersonIt->detection_id; + trackedPersonVisual->detectionIdText->setCaption(ss.str()); + + // Track state + ss.str(""); + + if (trackedPersonIt->is_occluded && !trackedPersonIt->is_matched) + ss << "OCCLUDED"; + else if (!trackedPersonIt->is_occluded && !trackedPersonIt->is_matched) + ss << "MISSED"; + else + ss << "MATCHED"; + + trackedPersonVisual->stateText->setCaption(ss.str()); + + // Track ID + ss.str(""); + ss << "Human " << trackedPersonIt->track_id; + trackedPersonVisual->idText->setCaption(ss.str()); + } + + // + // Velocity arrows + // + if (!trackedPersonVisual->velocityArrow) + { + trackedPersonVisual->velocityArrow.reset(new rviz::Arrow(context_->getSceneManager(), currentSceneNode)); + } + + // Update velocity arrow + { + const Ogre::Vector3 velocityVector = getVelocityVector(trackedPersonIt->twist); + + if (velocityVector.isZeroLength() || velocityVector.length() > 100 || velocityVector.isNaN()) + { + if (!velocityVector.isZeroLength()) + { // do not show warning for zero velocity + ROS_WARN("Track %lu has suspicious velocity (%.1f m/s), not showing velocity vector!", + trackedPersonIt->track_id, velocityVector.length()); + } + } + else + { + const double personRadius = 0.2; + const Ogre::Vector3 velocityArrowAttachPoint(personRadius, 0, + halfPersonHeight); // relative to tracked person's scene node + trackedPersonVisual->velocityArrow->setPosition(velocityArrowAttachPoint); + trackedPersonVisual->velocityArrow->setOrientation( + m_frameOrientation * currentSceneNode->getOrientation().Inverse() * + Ogre::Vector3::NEGATIVE_UNIT_Z.getRotationTo(velocityVector)); + + const double shaftLength = velocityVector.length(), shaftDiameter = 0.05, headLength = 0.2, headDiameter = 0.2; + trackedPersonVisual->velocityArrow->set(shaftLength, shaftDiameter, headLength, headDiameter); + trackedPersonVisual->hasZeroVelocity = velocityVector.length() < 0.05; + } + + boost::shared_ptr meshPersonVisual = + boost::dynamic_pointer_cast(personVisual); + if (meshPersonVisual) + { + meshPersonVisual->setWalkingSpeed(velocityVector.length()); + } + } + + // + // Covariance visualization + // + if (!trackedPersonVisual->covarianceVisual) + { + trackedPersonVisual->covarianceVisual.reset( + new ProbabilityEllipseCovarianceVisual(context_->getSceneManager(), currentSceneNode)); + } + + // Update covariance ellipse + { + Ogre::Vector3 covarianceMean(0, 0, 0); // zero mean because parent node is already centered at pose mean + trackedPersonVisual->covarianceVisual->setOrientation(currentSceneNode->getOrientation().Inverse()); + trackedPersonVisual->covarianceVisual->setMeanCovariance(covarianceMean, covXYZinTargetFrame); + } + + } // end for loop over all tracked persons + + // Set all properties which can be dynamically in the GUI. This iterates over all tracks. + stylesChanged(); + + // + // First hide, then delete old cached tracks which have not been seen for a while + // + set trackIdsToDelete; + for (map >::const_iterator cachedTrackIt = + m_cachedTracks.begin(); + cachedTrackIt != m_cachedTracks.end(); ++cachedTrackIt) + { + if (encounteredTrackIds.end() == encounteredTrackIds.find(cachedTrackIt->first)) + { + const boost::shared_ptr& trackedPersonVisual = cachedTrackIt->second; + + // Update state and visibility + if (!trackedPersonVisual->isDeleted) + { + trackedPersonVisual->stateText->setCaption("DELETED"); + trackedPersonVisual->isDeleted = true; + + Ogre::Matrix4 lastObservedPose(trackedPersonVisual->sceneNode->getOrientation()); + lastObservedPose.setTrans(trackedPersonVisual->sceneNode->getPosition()); + trackedPersonVisual->lastObservedPose = mapFrameTransform.inverse() * lastObservedPose; + } + + if (!m_show_deleted_property->getBool()) + trackedPersonVisual->sceneNode->setVisible(false); + + // Delete if too old + if (++trackedPersonVisual->numCyclesNotSeen > m_delete_after_ncycles_property->getInt()) + { + trackIdsToDelete.insert(cachedTrackIt->first); + } + } + } + + for (set::const_iterator setIt = trackIdsToDelete.begin(); setIt != trackIdsToDelete.end(); ++setIt) + { + m_cachedTracks.erase(*setIt); + } + + // + // Update status (shown in property pane) + // + ss.str(""); + ss << msg->tracks.size() << " tracks received"; + setStatusStd(rviz::StatusProperty::Ok, "Tracks", ss.str()); +} + +} // end namespace spencer_tracking_rviz_plugin + +// Tell pluginlib about this class. It is important to do this in +// global scope, outside our package's namespace. +#include +PLUGINLIB_EXPORT_CLASS(spencer_tracking_rviz_plugin::TrackedPersonsDisplay, rviz::Display) diff --git a/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/src/tracked_persons_display.h b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/src/tracked_persons_display.h new file mode 100755 index 0000000..0c70469 --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/src/tracked_persons_display.h @@ -0,0 +1,155 @@ +/* +* Software License Agreement (BSD License) +* +* Copyright (c) 2013-2015, Timm Linder, Social Robotics Lab, University of Freiburg +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* * Redistributions of source code must retain the above copyright notice, this +* list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above copyright notice, +* this list of conditions and the following disclaimer in the documentation +* and/or other materials provided with the distribution. +* * Neither the name of the copyright holder nor the names of its contributors +* may be used to endorse or promote products derived from this software +* without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*/ + +#ifndef TRACKED_PERSONS_DISPLAY_H +#define TRACKED_PERSONS_DISPLAY_H + +#ifndef Q_MOC_RUN +#include +#include +#include +#include "person_display_common.h" +#endif + +namespace spencer_tracking_rviz_plugin +{ + typedef unsigned int track_id; + + /// A single entry in the history of a tracked person. + struct TrackedPersonHistoryEntry + { + Ogre::Vector3 position; + boost::shared_ptr shape; + bool wasOccluded; + track_id trackId; + }; + + /// History of a tracked person. + typedef circular_buffer > TrackedPersonHistory; + + /// The visual of a tracked person. + struct TrackedPersonVisual + { + TrackedPersonHistory history; + boost::shared_ptr historyLine; + Ogre::Vector3 positionOfLastHistoryEntry; + + boost::shared_ptr sceneNode, historySceneNode, historyLineSceneNode; + + boost::shared_ptr personVisual; + boost::shared_ptr idText, detectionIdText, stateText; + boost::shared_ptr velocityArrow; + boost::shared_ptr covarianceVisual; + + Ogre::Matrix4 lastObservedPose; + + bool isOccluded, isDeleted, isMissed, hasZeroVelocity; + int numCyclesNotSeen; + }; + + // The TrackedPersonsDisplay class itself just implements a circular buffer, + // editable parameters, and Display subclass machinery. + class TrackedPersonsDisplay: public PersonDisplayCommon + { + Q_OBJECT + public: + // Constructor. pluginlib::ClassLoader creates instances by calling + // the default constructor, so make sure you have one. + TrackedPersonsDisplay() {}; + virtual ~TrackedPersonsDisplay(); + + // Overrides of protected virtual functions from Display. As much + // as possible, when Displays are not enabled, they should not be + // subscribed to incoming data and should not show anything in the + // 3D view. These functions are where these connections are made + // and broken. + + // Called after the constructors have run + virtual void onInitialize(); + + // Called periodically by the visualization manager + virtual void update(float wall_dt, float ros_dt); + + protected: + // A helper to clear this display back to the initial state. + virtual void reset(); + + // Must be implemented by derived classes because MOC doesn't work in templates + virtual rviz::DisplayContext* getContext() { + return context_; + } + + private Q_SLOTS: + void personVisualTypeChanged(); + + // Called whenever one of the properties in PersonDisplayCommonProperties has been changed + virtual void stylesChanged(); + + private: + // Function to handle an incoming ROS message. + void processMessage(const spencer_tracking_msgs::TrackedPersons::ConstPtr& msg); + + // All currently active tracks, with unique track ID as map key + typedef map > track_map; + track_map m_cachedTracks; + + // Scene node for track history visualization + boost::shared_ptr m_trackHistorySceneNode; + std::string m_realFixedFrame; + + // User-editable property variables. + rviz::FloatProperty* m_occlusion_alpha_property; + rviz::FloatProperty* m_missed_alpha_property; + rviz::IntProperty* m_history_length_property; + rviz::IntProperty* m_delete_after_ncycles_property; + + rviz::BoolProperty* m_show_deleted_property; + rviz::BoolProperty* m_show_occluded_property; + rviz::BoolProperty* m_show_missed_property; + rviz::BoolProperty* m_show_matched_property; + + rviz::BoolProperty* m_render_person_property; + rviz::BoolProperty* m_render_history_property; + rviz::BoolProperty* m_render_history_as_line_property; + rviz::BoolProperty* m_render_covariances_property; + rviz::BoolProperty* m_render_state_prediction_property; + rviz::BoolProperty* m_render_velocities_property; + rviz::BoolProperty* m_render_ids_property; + rviz::BoolProperty* m_render_detection_ids_property; + rviz::BoolProperty* m_render_track_state_property; + + rviz::FloatProperty* m_history_line_width_property; + rviz::FloatProperty* m_history_min_point_distance_property; + rviz::FloatProperty* m_covariance_line_width_property; + }; + +} // end namespace spencer_tracking_rviz_plugin + +#endif // TRACKED_PERSONS_DISPLAY_H diff --git a/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/src/visuals/covariance_visual.h b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/src/visuals/covariance_visual.h new file mode 100755 index 0000000..3fda09c --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/src/visuals/covariance_visual.h @@ -0,0 +1,236 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2013-2015, Timm Linder, Social Robotics Lab, University of Freiburg + * Copyright (c) 2006, Kai O. Arras, Autonomous Intelligent Systems Lab, University of Freiburg + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * * Neither the name of the copyright holder nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef COVARIANCE_VISUAL_H +#define COVARIANCE_VISUAL_H + +#include +#include +#include + +namespace spencer_tracking_rviz_plugin +{ +// Visualization of a covariance matrix +class CovarianceVisual +{ +public: + CovarianceVisual(Ogre::SceneManager* sceneManager, Ogre::SceneNode* parentNode) : m_sceneManager(sceneManager) + { + m_sceneNode = parentNode->createChildSceneNode(); + } + + virtual ~CovarianceVisual() + { + m_sceneManager->destroySceneNode(m_sceneNode->getName()); + }; + + void setPosition(const Ogre::Vector3& position) + { + m_sceneNode->setPosition(position); + } + + void setOrientation(const Ogre::Quaternion& orientation) + { + m_sceneNode->setOrientation(orientation); + } + + void setVisible(bool visible) + { + m_sceneNode->setVisible(visible, true); + } + + virtual void setColor(const Ogre::ColourValue& c) = 0; + + virtual void setLineWidth(float lineWidth) = 0; + + /// NOTE: It is assumed that the covariance matrix is already rotated into the target frame of the sceneNode! + virtual void setMeanCovariance(const Ogre::Vector3& mean, const Ogre::Matrix3& cov) = 0; + +protected: + Ogre::SceneManager* m_sceneManager; + Ogre::SceneNode* m_sceneNode; +}; + +// 2D ellipse visualization of a covariance matrix +class ProbabilityEllipseCovarianceVisual : public CovarianceVisual +{ +public: + ProbabilityEllipseCovarianceVisual(Ogre::SceneManager* sceneManager, Ogre::SceneNode* parentNode) + : CovarianceVisual(sceneManager, parentNode) + { + m_line = new rviz::BillboardLine(m_sceneManager, m_sceneNode); + } + + virtual ~ProbabilityEllipseCovarianceVisual() + { + delete m_line; + } + + virtual void setLineWidth(float lineWidth) + { + m_line->setLineWidth(lineWidth); + } + + virtual void setColor(const Ogre::ColourValue& c) + { + m_line->setColor(c.r, c.g, c.b, c.a); + } + + virtual void setMeanCovariance(const Ogre::Vector3& mean, const Ogre::Matrix3& cov) + { + int numberOfPoints; + double *xs, *ys; + double determinant = cov[0][0] * cov[1][1] - cov[1][0] * cov[0][1]; + + m_line->clear(); + + if (!std::isfinite(determinant)) + { + ROS_WARN_STREAM_THROTTLE( + 5.0, "Covariance matrix has non-finite values in ProbabilityEllipseCovarianceVisual::setMeanCovariance(): " + << cov); + return; + } + + if (std::abs(cov[0][1] - cov[1][0]) > 0.00001) + { + ROS_WARN_STREAM_THROTTLE( + 5.0, + "Covariance matrix is not symmetric in ProbabilityEllipseCovarianceVisual::setMeanCovariance(): " << cov); + return; + } + + if (determinant > 0 && cov[0][0] > 0 /* positive definite? */ || + std::abs(determinant - 0.00001) == 0.0 && (cov[0][0] > 0 || cov[1][1] > 0) /* positive semidefinite? */) + { + calc_prob_elli_99(mean.x, mean.y, cov[0][0], cov[1][1], cov[0][1], numberOfPoints, xs, ys); + + m_line->setMaxPointsPerLine(numberOfPoints); + + for (int i = 0; i < numberOfPoints; i++) + { + Ogre::Vector3 vertex(xs[i], ys[i], mean.z); + m_line->addPoint(vertex); + } + } + else + { + if (cov[0][0] != 0 || cov[0][1] != 0 || cov[0][2] != 0 || cov[1][0] != 0 || cov[1][1] != 0 || cov[1][2] != 0 || + cov[2][0] != 0 || cov[2][1] != 0 || cov[2][2] != 0) + ROS_WARN_STREAM_THROTTLE(5.0, + "Covariance matrix is not positive (semi-)definite in " + "ProbabilityEllipseCovarianceVisual::setMeanCovariance(): " + << cov); + } + } + +private: + rviz::BillboardLine* m_line; + + // Puts angle alpha into the interval [min..min+2*pi[ + double set_angle_to_range(double alpha, double min) + { + while (alpha >= min + 2.0 * M_PI) + { + alpha -= 2.0 * M_PI; + } + while (alpha < min) + { + alpha += 2.0 * M_PI; + } + return alpha; + } + + // Calculates the points on a rotated ellipse given by center xc, yc, half axes a, b and angle phi. + // Returns number of points np and points in Cart. coordinates + void calc_ellipse(double xc, double yc, double a, double b, double phi, int& np, double*& xvec, double*& yvec) + { + const int N_ELLI_POINTS = 40; + int i, offset; + double t, cr, sr, ca, sa, xi, yi, reso; + static double x[N_ELLI_POINTS + 1]; + static double y[N_ELLI_POINTS + 1]; + reso = 2 * M_PI / N_ELLI_POINTS; + offset = N_ELLI_POINTS / 2; + ca = cos(phi); + sa = sin(phi); + i = 0; + t = 0; + while (t < M_PI) + { + cr = cos(t); + sr = sin(t); + xi = a * cr * ca - b * sr * sa; + yi = a * cr * sa + b * sr * ca; + x[i] = xi + xc; + y[i] = yi + yc; + x[offset + i] = -xi + xc; + y[offset + i] = -yi + yc; + t = t + reso; + i++; + } + x[N_ELLI_POINTS] = x[0]; // Close contour + y[N_ELLI_POINTS] = y[0]; // Close contour + np = N_ELLI_POINTS + 1; + xvec = x; + yvec = y; + } + + // Calculates the points on a 95%-iso-probability ellipse given by the bivarate RV with mean xc, yc + // and covariance matrix sxx, syy, sxy. Returns number of points np and points in Cart. coordinates + void calc_prob_elli_95(double xc, double yc, double sxx, double syy, double sxy, int& np, double*& x, double*& y) + { + double la, lb, a, b, phi; + la = (sxx + syy + sqrt((sxx - syy) * (sxx - syy) + 4 * sxy * sxy)) / 2; + lb = (sxx + syy - sqrt((sxx - syy) * (sxx - syy) + 4 * sxy * sxy)) / 2; + a = sqrt(5.991464 * la); + b = sqrt(5.991464 * lb); + phi = set_angle_to_range(atan2(2 * sxy, sxx - syy) / 2, 0); + calc_ellipse(xc, yc, a, b, phi, np, x, y); + } + + // Calculates the points on a 99%-iso-probability ellipse given by the bivarate RV with mean xc, yc + // and covariance matrix sxx, syy, sxy. Returns number of points np and points in Cart. coordinates + void calc_prob_elli_99(double xc, double yc, double sxx, double syy, double sxy, int& np, double*& x, double*& y) + { + double la, lb, a, b, phi; + la = (sxx + syy + sqrt((sxx - syy) * (sxx - syy) + 4 * sxy * sxy)) / 2; + lb = (sxx + syy - sqrt((sxx - syy) * (sxx - syy) + 4 * sxy * sxy)) / 2; + a = sqrt(9.210340 * la); + b = sqrt(9.210340 * lb); + phi = set_angle_to_range(atan2(2 * sxy, sxx - syy) / 2, 0); + calc_ellipse(xc, yc, a, b, phi, np, x, y); + } +}; + +} // namespace spencer_tracking_rviz_plugin + +#endif // COVARIANCE_VISUAL_H diff --git a/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/src/visuals/mesh_node.h b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/src/visuals/mesh_node.h new file mode 100755 index 0000000..6b7aa04 --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/src/visuals/mesh_node.h @@ -0,0 +1,191 @@ +/* +* Software License Agreement (BSD License) +* +* Copyright (c) 2013-2015, Timm Linder, Social Robotics Lab, University of Freiburg +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* * Redistributions of source code must retain the above copyright notice, this +* list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above copyright notice, +* this list of conditions and the following disclaimer in the documentation +* and/or other materials provided with the distribution. +* * Neither the name of the copyright holder nor the names of its contributors +* may be used to endorse or promote products derived from this software +* without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*/ + +#ifndef MESH_NODE_H +#define MESH_NODE_H + +#include +#ifndef Q_MOC_RUN +#include +#endif +#include +#include // hack to get camera position + +#include +#include +#include +#include +#include +#include +#include + + +namespace spencer_tracking_rviz_plugin { + class MeshNode : public Ogre::FrameListener { + public: + MeshNode(rviz::DisplayContext* displayContext, Ogre::SceneNode* parentNode, const std::string& meshResource, Ogre::Vector3 position = Ogre::Vector3::ZERO) + : m_sceneManager(displayContext->getSceneManager()), m_displayContext(displayContext), m_meshResource(meshResource) + { + m_cameraFacing = false; + m_sceneNode = parentNode->createChildSceneNode(); + m_sceneNode->setVisible(false); + + // Load mesh + assert(!rviz::loadMeshFromResource(meshResource).isNull()); + + // Create scene entity + std::stringstream ss; + static int counter = 0; + ss << "gender_symbol_" << counter++; + std::string id = ss.str(); + + m_entity = m_sceneManager->createEntity(id, meshResource); + m_sceneNode->attachObject(m_entity); + + // set up material + ss << "Material"; + // Ogre::MaterialPtr default_material = Ogre::MaterialManager::getSingleton().create( ss.str(), "rviz" ); + Ogre::MaterialPtr default_material = Ogre::MaterialManager::getSingleton().create(ss.str(), Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME); + default_material->setReceiveShadows(false); + default_material->getTechnique(0)->setLightingEnabled(true); + default_material->getTechnique(0)->setAmbient( 0.5, 0.5, 0.5 ); + m_materials.insert( default_material ); + m_entity->setMaterial( default_material ); + + setPosition(position); + setVisible(true); + + // For camera-facing meshes + Ogre::Root::getSingleton().addFrameListener(this); + } + + virtual ~MeshNode() { + Ogre::Root::getSingleton().removeFrameListener(this); + m_sceneManager->destroyEntity(m_entity); + + // destroy all the materials we've created + std::set::iterator it; + for(it = m_materials.begin(); it != m_materials.end(); it++ ) + { + Ogre::MaterialPtr material = *it; + if (!material.isNull()) + { + material->unload(); + Ogre::MaterialManager::getSingleton().remove(material->getName()); + } + } + m_materials.clear(); + m_sceneManager->destroySceneNode(m_sceneNode->getName()); + } + + void setOrientation(const Ogre::Quaternion& orientation) { + m_orientation = orientation; + } + + void setPosition(const Ogre::Vector3& position) { + m_sceneNode->setPosition(position); + } + + void setScale(const float scaleFactor) { + m_sceneNode->setScale(Ogre::Vector3(scaleFactor, scaleFactor, scaleFactor)); + } + + void setVisible(bool visible) { + m_sceneNode->setVisible(visible, true); + } + + void setCameraFacing(bool cameraFacing) { + m_cameraFacing = cameraFacing; + } + + void setColor(const Ogre::ColourValue& c) { + Ogre::SceneBlendType blending; + bool depth_write; + + if ( c.a < 0.9998 ) + { + blending = Ogre::SBT_TRANSPARENT_ALPHA; + depth_write = false; + } + else + { + blending = Ogre::SBT_REPLACE; + depth_write = true; + } + + std::set::iterator it; + for(it = m_materials.begin(); it != m_materials.end(); it++) + { + Ogre::Technique* technique = (*it)->getTechnique( 0 ); + + technique->setAmbient( c.r*0.5, c.g*0.5, c.b*0.5 ); + technique->setDiffuse( c.r, c.g, c.b, c.a ); + technique->setSceneBlending( blending ); + technique->setDepthWriteEnabled( depth_write ); + technique->setLightingEnabled( true ); + } + } + + const std::string& getMeshResource() const { + return m_meshResource; + } + + // We are using this FrameListener callback to orient the mesh towards the camera. + // Using a SceneManager::Listener and its preUpdateSceneGraph(SceneManager, Camera) method doesn't work because + // it is apparently never invoked by the Rviz render system. + virtual bool frameStarted(const Ogre::FrameEvent &evt) + { + Ogre::Quaternion cameraQuat; + if(m_cameraFacing) { + // Align with camera view direction + // FIXME: The following way of retrieving the camera and its position is a bit hacky, don't try this at home! + rviz::VisualizationManager* visualizationManager = dynamic_cast(m_displayContext); + assert(visualizationManager != NULL); + cameraQuat = visualizationManager->getRenderPanel()->getCamera()->getOrientation(); + } + m_sceneNode->setOrientation(cameraQuat * m_orientation); + return true; + } + + private: + Ogre::SceneManager* m_sceneManager; + Ogre::SceneNode* m_sceneNode; + rviz::DisplayContext* m_displayContext; + + Ogre::Quaternion m_orientation; + Ogre::Entity* m_entity; + std::set m_materials; + std::string m_meshResource; + bool m_cameraFacing; + }; + +} + +#endif // MESH_NODE_H diff --git a/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/src/visuals/person_visual.cpp b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/src/visuals/person_visual.cpp new file mode 100755 index 0000000..2671eeb --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/src/visuals/person_visual.cpp @@ -0,0 +1,232 @@ +/* +* Software License Agreement (BSD License) +* +* Copyright (c) 2013-2015, Timm Linder, Social Robotics Lab, University of Freiburg +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* * Redistributions of source code must retain the above copyright notice, this +* list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above copyright notice, +* this list of conditions and the following disclaimer in the documentation +* and/or other materials provided with the distribution. +* * Neither the name of the copyright holder nor the names of its contributors +* may be used to endorse or promote products derived from this software +* without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*/ + + +#include +#ifndef Q_MOC_RUN +#include +#include +#include + +#include +#include +#endif +#include +#include +#include +#include +#include +#include + +#include "person_visual.h" + + +namespace fs = boost::filesystem; + +namespace spencer_tracking_rviz_plugin { + +/** This helper class ensures that skeletons can be loaded from a package:// path **/ +class RosPackagePathResourceLoadingListener : public Ogre::ResourceLoadingListener +{ +public: + RosPackagePathResourceLoadingListener(const fs::path& parentPath) : _parentPath(parentPath) { + } + + /** This event is called when a resource beings loading. */ + virtual Ogre::DataStreamPtr resourceLoading(const Ogre::String &name, const Ogre::String &group, Ogre::Resource *resource) { + fs::path absolutePath = _parentPath / name; + ROS_INFO_STREAM("RosPackagePathResourceLoadingListener loading resource: " << absolutePath.string()); + + try + { + resource_retriever::Retriever retriever; + _lastResource = retriever.get(absolutePath.string()); // not thread-safe! + return Ogre::DataStreamPtr(new Ogre::MemoryDataStream(_lastResource.data.get(), _lastResource.size)); + } + catch (resource_retriever::Exception& e) + { + ROS_ERROR("In RosPackagePathResourceLoadingListener: %s", e.what()); + return Ogre::DataStreamPtr(); + } + } + + virtual void resourceStreamOpened(const Ogre::String &name, const Ogre::String &group, Ogre::Resource *resource, Ogre::DataStreamPtr& dataStream) { + } + + virtual bool resourceCollision(Ogre::Resource *resource, Ogre::ResourceManager *resourceManager) { + return false; + } + +private: + const fs::path& _parentPath; + resource_retriever::MemoryResource _lastResource; +}; + + + +MeshPersonVisual::MeshPersonVisual(const PersonVisualDefaultArgs& args) : PersonVisual(args), m_animationState(NULL), m_walkingSpeed(1.0), entity_(NULL) +{ + m_childSceneNode = m_sceneNode->createChildSceneNode(); + m_childSceneNode->setVisible(false); + + std::string meshResource = "package://" ROS_PACKAGE_NAME "/media/animated_walking_man.mesh"; + + std::cout<createEntity(id, meshResource); + m_childSceneNode->attachObject(entity_); + + // set up animation + setAnimationState(""); + + // set up material + ss << "Material"; + // Ogre::MaterialPtr default_material = Ogre::MaterialManager::getSingleton().create( ss.str(), "rviz" ); + Ogre::MaterialPtr default_material = Ogre::MaterialManager::getSingleton().create(ss.str(), Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME); + default_material->setReceiveShadows(false); + default_material->getTechnique(0)->setLightingEnabled(true); + default_material->getTechnique(0)->setAmbient( 0.5, 0.5, 0.5 ); + materials_.insert( default_material ); + entity_->setMaterial( default_material ); + + // set position + Ogre::Quaternion quat1; quat1.FromAngleAxis(Ogre::Degree(90), Ogre::Vector3(0,1,0)); + Ogre::Quaternion quat2; quat2.FromAngleAxis(Ogre::Degree(-90), Ogre::Vector3(0,0,1)); + m_childSceneNode->setOrientation(quat1 * quat2); + + double scaleFactor = 0.243 * 1.75; + m_childSceneNode->setScale(Ogre::Vector3(scaleFactor, scaleFactor, scaleFactor)); + m_childSceneNode->setPosition(Ogre::Vector3(0, 0, -1)); + + m_childSceneNode->setVisible(true); +} + +MeshPersonVisual::~MeshPersonVisual() { + m_sceneManager->destroyEntity( entity_ ); + + // destroy all the materials we've created + std::set::iterator it; + for ( it = materials_.begin(); it!=materials_.end(); it++ ) + { + Ogre::MaterialPtr material = *it; + if (!material.isNull()) + { + material->unload(); + Ogre::MaterialManager::getSingleton().remove(material->getName()); + } + } + materials_.clear(); + + m_sceneManager->destroySceneNode(m_childSceneNode->getName()); +} + +void MeshPersonVisual::setColor(const Ogre::ColourValue& c) { + Ogre::SceneBlendType blending; + bool depth_write; + + if ( c.a < 0.9998 ) + { + blending = Ogre::SBT_TRANSPARENT_ALPHA; + depth_write = false; + } + else + { + blending = Ogre::SBT_REPLACE; + depth_write = true; + } + + std::set::iterator it; + for( it = materials_.begin(); it != materials_.end(); it++ ) + { + Ogre::Technique* technique = (*it)->getTechnique( 0 ); + + technique->setAmbient( c.r*0.5, c.g*0.5, c.b*0.5 ); + technique->setDiffuse( c.r, c.g, c.b, c.a ); + technique->setSceneBlending( blending ); + technique->setDepthWriteEnabled( depth_write ); + technique->setLightingEnabled( true ); + } +} + +void MeshPersonVisual::setAnimationState(const std::string& nameOfAnimationState) { + Ogre::AnimationStateSet *animationStates = entity_->getAllAnimationStates(); + if(animationStates != NULL) + { + Ogre::AnimationStateIterator animationsIterator = animationStates->getAnimationStateIterator(); + while (animationsIterator.hasMoreElements()) + { + Ogre::AnimationState *animationState = animationsIterator.getNext(); + if(animationState->getAnimationName() == nameOfAnimationState || nameOfAnimationState.empty()) { + animationState->setLoop(true); + animationState->setEnabled(true); + m_animationState = animationState; + return; + } + } + + // Not found. Set first animation state then. + ROS_WARN_STREAM_ONCE("Person mesh animation state " << nameOfAnimationState << " does not exist in mesh!"); + setAnimationState(""); + } +} + +void MeshPersonVisual::setWalkingSpeed(float walkingSpeed) { + m_walkingSpeed = walkingSpeed; +} + + +void MeshPersonVisual::update(float deltaTime) { + if(m_animationState) { + m_animationState->addTime(0.7 * deltaTime * m_walkingSpeed); + } +} + + +} // end of namespace spencer_tracking_rviz_plugin diff --git a/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/src/visuals/person_visual.h b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/src/visuals/person_visual.h new file mode 100755 index 0000000..f57fe67 --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/src/visuals/person_visual.h @@ -0,0 +1,319 @@ +/* +* Software License Agreement (BSD License) +* +* Copyright (c) 2013-2015, Timm Linder, Social Robotics Lab, University of Freiburg +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* * Redistributions of source code must retain the above copyright notice, this +* list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above copyright notice, +* this list of conditions and the following disclaimer in the documentation +* and/or other materials provided with the distribution. +* * Neither the name of the copyright holder nor the names of its contributors +* may be used to endorse or promote products derived from this software +* without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*/ + +#ifndef PERSON_VISUAL_H +#define PERSON_VISUAL_H + +#include +#include + +#include +#include +#include +#include + + +namespace spencer_tracking_rviz_plugin { + // Abstract class for visuals which have got an adjustable line width + class HasLineWidth { + public: + virtual void setLineWidth(double lineWidth) = 0; + }; + + // Default arguments that need to be supplied to all types of PersonVisual + struct PersonVisualDefaultArgs { + PersonVisualDefaultArgs(Ogre::SceneManager* sceneManager, Ogre::SceneNode* parentNode) : sceneManager(sceneManager), parentNode(parentNode) {} + Ogre::SceneManager* sceneManager; + Ogre::SceneNode* parentNode; + }; + + /// Base class for all person visualization types + class PersonVisual { + public: + PersonVisual(const PersonVisualDefaultArgs& args) : + m_sceneManager(args.sceneManager), + m_correctOrientation( Ogre::Degree(90), Ogre::Vector3(1,0,0) ) + { + m_parentSceneNode = args.parentNode; + m_sceneNode = args.parentNode->createChildSceneNode(); + + Ogre::Vector3 scale(1,1,1); + m_sceneNode->setScale(m_correctOrientation * scale); + } + + virtual ~PersonVisual() { + m_sceneManager->destroySceneNode(m_sceneNode->getName()); + }; + + void setPosition(const Ogre::Vector3& position) { + m_sceneNode->setPosition(position); + } + + const Ogre::Vector3& getPosition() const { + return m_sceneNode->getPosition(); + } + + void setOrientation(const Ogre::Quaternion& orientation) { + m_sceneNode->setOrientation(orientation * m_correctOrientation); + } + + const Ogre::Quaternion& getOrientation() const { + return m_sceneNode->getOrientation(); + } + + virtual void setScalingFactor(double scalingFactor) { + m_sceneNode->setScale(scalingFactor, scalingFactor, scalingFactor); + } + + void setVisible(bool visible) { + m_sceneNode->setVisible(visible, true); + } + + Ogre::SceneNode* getParentSceneNode() { + return m_parentSceneNode; + } + + virtual void update(float deltaTime) {} + virtual void setColor(const Ogre::ColourValue& c) = 0; + virtual double getHeight() = 0; + + protected: + Ogre::SceneManager* m_sceneManager; + Ogre::SceneNode *m_sceneNode, *m_parentSceneNode; + Ogre::Quaternion m_correctOrientation; + }; + + + /// Visualization of a person as cylinder (body) + sphere (head) + class CylinderPersonVisual : public PersonVisual { + public: + CylinderPersonVisual(const PersonVisualDefaultArgs& args) : PersonVisual(args) + { + m_bodyShape = new rviz::Shape(rviz::Shape::Cylinder, args.sceneManager, m_sceneNode); + m_headShape = new rviz::Shape(rviz::Shape::Sphere, args.sceneManager, m_sceneNode); + + const float headDiameter = 0.4; + const float totalHeight = getHeight(); + const float cylinderHeight = totalHeight - headDiameter; + + m_bodyShape->setScale(Ogre::Vector3(headDiameter, headDiameter, cylinderHeight)); + m_headShape->setScale(Ogre::Vector3(headDiameter, headDiameter, headDiameter)); + + m_bodyShape->setPosition(Ogre::Vector3(0, 0, cylinderHeight / 2 - totalHeight / 2)); + m_headShape->setPosition(Ogre::Vector3(0, 0, totalHeight / 2 - headDiameter / 2 )); + } + + virtual ~CylinderPersonVisual() { + delete m_bodyShape; + delete m_headShape; + } + + virtual void setColor(const Ogre::ColourValue& c) { + m_bodyShape->setColor(c); + m_headShape->setColor(c); + } + + virtual double getHeight() { + return 1.75; + } + + private: + rviz::Shape *m_bodyShape, *m_headShape; + }; + + + /// Visualization of a person as a wireframe bounding box + class BoundingBoxPersonVisual : public PersonVisual, public HasLineWidth { + public: + BoundingBoxPersonVisual(const PersonVisualDefaultArgs& args, double height = 1.75, double width = 0.6, double scalingFactor = 1.0) : PersonVisual(args) + { + m_width = width; m_height = height; m_scalingFactor = scalingFactor; m_lineWidth = 0.03; + m_wireframe = NULL; + generateWireframe(); + } + + virtual ~BoundingBoxPersonVisual() { + delete m_wireframe; + } + + virtual void setColor(const Ogre::ColourValue& c) { + m_wireframe->setColor(c.r, c.g, c.b, c.a); + } + + virtual double getHeight() { + return m_height; + } + + virtual void setLineWidth(double lineWidth) { + m_wireframe->setLineWidth(lineWidth); + } + + /* + virtual void setScalingFactor(double scalingFactor) { + if(scalingFactor != m_scalingFactor) { + m_scalingFactor = scalingFactor; + generateWireframe(); + } + } + */ + + protected: + virtual void generateWireframe() { + delete m_wireframe; + m_wireframe = new rviz::BillboardLine(m_sceneManager, m_sceneNode); + + m_wireframe->setLineWidth(m_lineWidth); + m_wireframe->setMaxPointsPerLine(2); + m_wireframe->setNumLines(12); + + double w = m_width * m_scalingFactor, h = m_height * m_scalingFactor; + Ogre::Vector3 bottomLeft(0, -w, 0), bottomRight(0, 0, 0), topLeft(0, -w, h), topRight(0, 0, h); + Ogre::Vector3 rear(w, 0, 0); + + // Front quad + m_wireframe->addPoint(bottomLeft); m_wireframe->addPoint(bottomRight); + m_wireframe->newLine(); m_wireframe->addPoint(bottomRight); m_wireframe->addPoint(topRight); + m_wireframe->newLine(); m_wireframe->addPoint(topRight); m_wireframe->addPoint(topLeft); + m_wireframe->newLine(); m_wireframe->addPoint(topLeft); m_wireframe->addPoint(bottomLeft); + + // Rear quad + m_wireframe->newLine(); m_wireframe->addPoint(bottomLeft + rear); m_wireframe->addPoint(bottomRight + rear); + m_wireframe->newLine(); m_wireframe->addPoint(bottomRight + rear); m_wireframe->addPoint(topRight + rear); + m_wireframe->newLine(); m_wireframe->addPoint(topRight + rear); m_wireframe->addPoint(topLeft + rear); + m_wireframe->newLine(); m_wireframe->addPoint(topLeft + rear); m_wireframe->addPoint(bottomLeft + rear); + + // Four connecting lines between front and rear + m_wireframe->newLine(); m_wireframe->addPoint(bottomLeft); m_wireframe->addPoint(bottomLeft + rear); + m_wireframe->newLine(); m_wireframe->addPoint(bottomRight); m_wireframe->addPoint(bottomRight + rear); + m_wireframe->newLine(); m_wireframe->addPoint(topRight); m_wireframe->addPoint(topRight + rear); + m_wireframe->newLine(); m_wireframe->addPoint(topLeft); m_wireframe->addPoint(topLeft + rear); + + m_wireframe->setPosition(Ogre::Vector3(-w/2, w/2, -h/2)); + } + + private: + rviz::BillboardLine *m_wireframe; + double m_width, m_height, m_scalingFactor, m_lineWidth; + }; + + + /// Visualization of a person as a crosshair + class CrosshairPersonVisual : public PersonVisual, public HasLineWidth { + public: + CrosshairPersonVisual(const PersonVisualDefaultArgs& args, double height = 1.0, double width = 1.0) : PersonVisual(args) + { + m_width = width; m_height = height; m_lineWidth = 0.03; + m_crosshair = NULL; + generateCrosshair(); + } + + virtual ~CrosshairPersonVisual() { + delete m_crosshair; + } + + virtual void setColor(const Ogre::ColourValue& c) { + m_crosshair->setColor(c.r, c.g, c.b, c.a); + } + + virtual double getHeight() { + return m_height; + } + + virtual void setLineWidth(double lineWidth) { + m_crosshair->setLineWidth(lineWidth); + } + + + protected: + virtual void generateCrosshair() { + delete m_crosshair; + m_crosshair = new rviz::BillboardLine(m_sceneManager, m_sceneNode); + + m_crosshair->setLineWidth(m_lineWidth); + m_crosshair->setMaxPointsPerLine(2); + m_crosshair->setNumLines(5); + + double w = m_width / 2.0; + Ogre::Vector3 p1a(-w, 0, 0), p1b(+w, 0, 0); + Ogre::Vector3 p2a(0, -w, 0), p2b(0, +w, 0); + Ogre::Vector3 p3a(0, 0, -w), p3b(0, 0, +w); + + Ogre::Vector3 arrow_a(0.7*w, -0.2*w, 0), arrow_m(w, 0, 0), arrow_b(0.7*w, +0.2*w, 0); + + m_crosshair->addPoint(p1a); m_crosshair->addPoint(p1b); + m_crosshair->newLine(); m_crosshair->addPoint(p2a); m_crosshair->addPoint(p2b); + m_crosshair->newLine(); m_crosshair->addPoint(p3a); m_crosshair->addPoint(p3b); + + m_crosshair->newLine(); m_crosshair->addPoint(arrow_m); m_crosshair->addPoint(arrow_a); + m_crosshair->newLine(); m_crosshair->addPoint(arrow_m); m_crosshair->addPoint(arrow_b); + + m_crosshair->setPosition(Ogre::Vector3(0, 0, 0)); + } + + private: + rviz::BillboardLine *m_crosshair; + double m_width, m_height, m_lineWidth; + }; + + + /// Visualization of a person as a mesh (walking human) + class MeshPersonVisual : public PersonVisual { + public: + MeshPersonVisual(const PersonVisualDefaultArgs& args); + + virtual ~MeshPersonVisual(); + + virtual void update(float deltaTime); + + virtual void setColor(const Ogre::ColourValue& c); + + void setAnimationState(const std::string& nameOfAnimationState); + + void setWalkingSpeed(float walkingSpeed); + + virtual double getHeight() { + return 1.75; + } + + virtual void setScalingFactor(double scalingFactor) { + // Not supported (for some reason causes the mesh to be mirrored vertically). + } + + private: + Ogre::SceneNode *m_childSceneNode; + Ogre::Entity* entity_; + Ogre::AnimationState* m_animationState; + std::set materials_; + float m_walkingSpeed; + }; + +} + +#endif // PERSON_VISUAL_H diff --git a/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/src/visuals/text_node.h b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/src/visuals/text_node.h new file mode 100755 index 0000000..1389a33 --- /dev/null +++ b/simulators/third_party/rviz_plugins/spencer_tracking_rviz_plugin/src/visuals/text_node.h @@ -0,0 +1,95 @@ +/* +* Software License Agreement (BSD License) +* +* Copyright (c) 2013-2015, Timm Linder, Social Robotics Lab, University of Freiburg +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* * Redistributions of source code must retain the above copyright notice, this +* list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above copyright notice, +* this list of conditions and the following disclaimer in the documentation +* and/or other materials provided with the distribution. +* * Neither the name of the copyright holder nor the names of its contributors +* may be used to endorse or promote products derived from this software +* without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*/ + +#ifndef TEXT_NODE_H +#define TEXT_NODE_H + +#include +#include + +namespace spencer_tracking_rviz_plugin { + class TextNode { + public: + TextNode(Ogre::SceneManager* sceneManager, Ogre::SceneNode* parentNode, Ogre::Vector3 position = Ogre::Vector3::ZERO) : m_sceneManager(sceneManager) + { + m_sceneNode = parentNode->createChildSceneNode(); + + m_text = new rviz::MovableText("text"); + m_text->setTextAlignment(rviz::MovableText::H_CENTER, rviz::MovableText::V_BELOW); + m_sceneNode->attachObject(m_text); + + setCharacterHeight(1.0); + setPosition(position); + setVisible(true); + } + + virtual ~TextNode() { + m_sceneManager->destroySceneNode(m_sceneNode->getName()); + delete m_text; + }; + + void setCharacterHeight(double characterHeight) { + m_text->setCharacterHeight(characterHeight); + m_text->setSpaceWidth(0.3 * characterHeight); + } + + double getCharacterHeight() { + return m_text->getCharacterHeight(); + } + + void setCaption(const std::string& caption) { + m_text->setCaption(caption); + } + + void setPosition(const Ogre::Vector3& position) { + m_sceneNode->setPosition(position); + } + + void setVisible(bool visible) { + m_sceneNode->setVisible(visible, true); + } + + void setColor(const Ogre::ColourValue& c) { + m_text->setColor(c); + } + + void showOnTop(bool onTop = true) { + m_text->showOnTop(onTop); + } + + private: + Ogre::SceneManager* m_sceneManager; + Ogre::SceneNode* m_sceneNode; + rviz::MovableText* m_text; + }; + +} + +#endif // TEXT_NODE_H diff --git a/simulators/user_config/obstacles_config.yaml b/simulators/user_config/obstacles_config.yaml new file mode 100755 index 0000000..f99c2c6 --- /dev/null +++ b/simulators/user_config/obstacles_config.yaml @@ -0,0 +1,18 @@ +# static obstacles +obstacles: + - type: BOX + pose: 4 2 0 0 0 0 + color: Grey + props: + m: 1.00 + w: 0.50 + d: 1.00 + h: 0.80 + - type: BOX + pose: 3 3 0 0 0 0 + color: Grey + props: + m: 1.00 + w: 1.00 + d: 0.50 + h: 1.00 \ No newline at end of file diff --git a/simulators/user_config/pedestrian_config.yaml b/simulators/user_config/pedestrian_config.yaml new file mode 100755 index 0000000..e0cb0df --- /dev/null +++ b/simulators/user_config/pedestrian_config.yaml @@ -0,0 +1,50 @@ +# sfm algorithm configure +social_force: + animation_factor: 5.1 + # only handle pedestrians within `people_distance` + people_distance: 6.0 + # weights of social force model + goal_weight: 2.0 + obstacle_weight: 20.0 + social_weight: 15 + group_gaze_weight: 3.0 + group_coh_weight: 2.0 + group_rep_weight: 1.0 + +# pedestrians setting +pedestrians: + update_rate: 5 + ped_property: + - name: human_1 + pose: 11 25 1 0 0 0 + velocity: 0.9 + radius: 0.4 + cycle: true + ignore: + model_1: ground_plane + model_2: turtlebot3_waffle_1 + trajectory: + goal_point_1: 11 25 1 0 0 0 + goal_point_2: 11 30 1 0 0 0 + # - name: human_2 + # pose: -0.5 -8.5 1 0 0 0 + # velocity: 1.2 + # radius: 0.4 + # cycle: true + # ignore: + # model_1: ground_plane + # model_2: turtlebot3_waffle + # trajectory: + # goal_point_1: -0.5 -8.5 1 0 0 0 + # goal_point_2: -9 2.5 1 0 0 0 + # - name: human_3 + # pose: -3.5 -8.5 1 0 0 0 + # velocity: 1.2 + # radius: 0.4 + # cycle: true + # ignore: + # model_1: ground_plane + # model_2: turtlebot3_waffle + # trajectory: + # goal_point_1: -3.5 -8.5 1 0 0 0 + # goal_point_2: -3.5 8.5 1 0 0 0 diff --git a/simulators/user_config/user_config.yaml b/simulators/user_config/user_config.yaml new file mode 100755 index 0000000..12d7067 --- /dev/null +++ b/simulators/user_config/user_config.yaml @@ -0,0 +1,17 @@ +map: "warehouse" +world: "warehouse" +rviz_file: "sim_env.rviz" + +robots_config: + - robot1_type: "turtlebot3_waffle" + robot1_global_planner: "d_star" + robot1_local_planner: "dwa" + robot1_x_pos: "0.0" + robot1_y_pos: "0.0" + robot1_z_pos: "0.0" + robot1_yaw: "0.0" + +plugins: + pedestrians: "pedestrian_config.yaml" + obstacles: "obstacles_config.yaml" + map_layers: "maps_config.yaml"